diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 5a62dc471..874c68bc2 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -23,7 +23,7 @@ jobs: uses: ros-tooling/setup-ros@v0.2 with: use-ros2-testing: true - required-ros-distributions: galactic + required-ros-distributions: humble - name: Install Custom Dependencies run: | # Webots (temporary disabled) @@ -34,4 +34,4 @@ jobs: - name: Build packages and run and tests uses: ros-tooling/action-ros-ci@v0.2 with: - target-ros2-distro: galactic + target-ros2-distro: humble diff --git a/.github/workflows/linter_cpp.yml b/.github/workflows/linter_cpp.yml index 027200ec2..271ee819e 100644 --- a/.github/workflows/linter_cpp.yml +++ b/.github/workflows/linter_cpp.yml @@ -10,7 +10,7 @@ jobs: fail-fast: false matrix: linters: [cpplint, xmllint, lint_cmake] - packages: [mep3_driver, mep3_behavior_tree, mep3_navigation] + packages: [mep3_hardware, mep3_behavior, mep3_navigation] steps: - name: Checkout repository uses: actions/checkout@v2 @@ -22,6 +22,6 @@ jobs: - name: Run linter ${{ matrix.linters }} for package ${{ matrix.packages }} uses: ros-tooling/action-ros-lint@v0.1 with: - distribution: galactic + distribution: humble linter: ${{ matrix.linters }} package-name: ${{ matrix.packages }} diff --git a/.github/workflows/linter_python.yml b/.github/workflows/linter_python.yml index 948e0de15..75e568edd 100644 --- a/.github/workflows/linter_python.yml +++ b/.github/workflows/linter_python.yml @@ -22,6 +22,6 @@ jobs: - name: Run linter ${{ matrix.linters }} for package ${{ matrix.packages }} uses: ros-tooling/action-ros-lint@v0.1 with: - distribution: galactic + distribution: humble linter: ${{ matrix.linters }} package-name: ${{ matrix.packages }} diff --git a/.gitignore b/.gitignore index 98fbcd30d..fba065966 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,4 @@ -.vscode/ +.vscode/settings.json .idea/ build/ install/ diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100644 index 000000000..20867a4a2 --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,64 @@ +{ + "configurations": [ + { + "name": "ROS2 Humble", + "browse": { + "databaseFilename": "", + "limitSymbolsToIncludedHeaders": true + }, + "includePath": [ + "${env:HOME}/webots/include/controller/cpp", + "/usr/include/python3.10", + "/usr/include", + "${workspaceFolder}/mep3_behavior/include", + "${workspaceFolder}/../../install/mep3_msgs/include/mep3_msgs", + "${workspaceFolder}/mep3_hardware/include", + "${workspaceFolder}/mep3_navigation/include", + "${workspaceFolder}/mep3_behavior/include", + "${workspaceFolder}/../dynamixel-workbench/dynamixel_workbench_toolbox/include", + "/opt/ros/humble/include", + "/opt/ros/humble/include/rclcpp", + "/opt/ros/humble/include/rclcpp_action", + "/opt/ros/humble/include/action_msgs", + "/opt/ros/humble/include/rcl_action", + "/opt/ros/humble/include/unique_identifier_msgs", + "/opt/ros/humble/include/can_msgs", + "/opt/ros/humble/include/pluginlib", + "/opt/ros/humble/include/geometry_msgs", + "/opt/ros/humble/include/nav_msgs", + "/opt/ros/humble/include/std_msgs", + "/opt/ros/humble/include/diagnostic_msgs", + "/opt/ros/humble/include/tf2_geometry_msgs", + "/opt/ros/humble/include/class_loader", + "/opt/ros/humble/include/rosidl_runtime_cpp", + "/opt/ros/humble/include/rosidl_runtime_c", + "/opt/ros/humble/include/rosidl_typesupport_interface", + "/opt/ros/humble/include/builtin_interfaces", + "/opt/ros/humble/include/rclcpp_lifecycle", + "/opt/ros/humble/include/rcutils", + "/opt/ros/humble/include/rcl", + "/opt/ros/humble/include/rmw", + "/opt/ros/humble/include/rcl_yaml_param_parser", + "/opt/ros/humble/include/rcl_interfaces", + "/opt/ros/humble/include/rcpputils", + "/opt/ros/humble/include/tracetools", + "/opt/ros/humble/include/libstatistics_collector", + "/opt/ros/humble/include/statistics_msgs", + "/opt/ros/humble/include/lifecycle_msgs", + "/opt/ros/humble/include/rcl_lifecycle", + "/opt/ros/humble/include/map_msgs", + "/opt/ros/humble/include/nav2_msgs", + "/opt/ros/humble/include/tf2", + "/opt/ros/humble/include/bond", + "/opt/ros/humble/include/tf2_ros", + "/opt/ros/humble/include/tf2_msgs", + "/opt/ros/humble/include/ament_index_cpp", + ], + "intelliSenseMode": "gcc-x64", + "compilerPath": "/usr/bin/g++", + "cStandard": "c99", + "cppStandard": "c++17" + } + ], + "version": 4 +} diff --git a/README.md b/README.md index a435db830..a7d42d68e 100644 --- a/README.md +++ b/README.md @@ -18,15 +18,15 @@ Memristor Eurobot Platform based on ROS 2 ## Getting started ```sh -# Make sure you have ROS 2 Galactic installed. -# https://docs.ros.org/en/galactic/Installation/Ubuntu-Install-Debians.html +# Make sure you have ROS 2 Humble installed. +# https://docs.ros.org/en/humble/Installation/Ubuntu-Install-Debians.html # Source ROS 2 -source /opt/ros/galactic/local_setup.bash +source /opt/ros/humble/local_setup.bash # Create a workspace -mkdir -p ~/galactic_ws/src -cd ~/galactic_ws +mkdir -p ~/ros2_ws/src +cd ~/ros2_ws git clone git@github.com:memristor/mep3.git src/mep3 # On embedded device: touch src/mep3/mep3_simulation/COLCON_IGNORE @@ -80,7 +80,7 @@ ros2 launch mep3_bringup simulation_launch.py bt:=false ``` - Control the robot from another terminal window ```sh -source /opt/ros/galactic/local_setup.bash +source /opt/ros/humble/local_setup.bash ros2 run teleop_twist_keyboard teleop_twist_keyboard --ros-args -r cmd_vel:=big/cmd_vel ``` - Run the simulation with the behavior tree: @@ -105,17 +105,17 @@ ros2 launch mep3_bringup rviz_launch.py - Change working directory to `~/ros2_ws` - Run the following command: ```sh - source /opt/ros/galactic/local_setup.bash + source /opt/ros/humble/local_setup.bash colcon test --event-handlers console_cohesion+ --return-code-on-test-failure ``` ### BehaviorTree strategies -Robot strategies are located inside [mep3_behavior_tree/assets](./mep3_behavior_tree/assets) +Robot strategies are located inside [mep3_behavior/assets](./mep3_behavior/assets) directory with the following hierarchy: ```ini -mep3_behavior_tree/assets +mep3_behavior/assets - skills/ - big_retract_hands.xml # skill for Big robot - small_replace_statuette.xml # skill for Small robot diff --git a/docker/Dockerfile b/docker/Dockerfile deleted file mode 100644 index 6ad12e64a..000000000 --- a/docker/Dockerfile +++ /dev/null @@ -1,92 +0,0 @@ -FROM ros:humble - -ARG DEBIAN_FRONTEND=noninteractive -ARG UID=1000 - -# User -RUN useradd -d /memristor -m \ - -u $UID -U \ - -s /usr/bin/bash \ - -c "Memristor Robotics" memristor && \ - echo "memristor ALL=(ALL) NOPASSWD: ALL" >> /etc/sudoers - -# System utilities -RUN apt-get update -RUN apt-get install -y \ - git \ - git-lfs \ - curl \ - wget \ - vim \ - rsync \ - dialog - -# ROS packages -RUN apt-get install -y \ - ros-humble-navigation2 \ - ros-humble-nav2-bringup \ - ros-humble-rviz2 \ - ros-humble-teleop-twist-keyboard \ - ros-humble-webots-ros2 -RUN echo 'source /opt/ros/humble/local_setup.bash' >> /memristor/.bashrc - -# VS Code -RUN curl -L -o /tmp/vscode.deb \ - 'https://code.visualstudio.com/sha/download?build=stable&os=linux-deb-x64' && \ - apt-get install -y /tmp/vscode.deb && \ - rm -f /tmp/vscode.deb -RUN apt-get install -y alsa libxshmfence1 libgtk-3-dev -RUN su memristor -c 'code --install-extension eamodio.gitlens' && \ - su memristor -c 'code --install-extension ms-python.python' && \ - su memristor -c 'code --install-extension ms-vscode.cpptools-extension-pack' && \ - su memristor -c 'code --install-extension usernamehw.errorlens' && \ - su memristor -c 'code --install-extension ms-iot.vscode-ros' - -# Webots -RUN curl -L -o /tmp/webots.deb \ - '/~https://github.com/cyberbotics/webots/releases/download/R2022b/webots_2022b_amd64.deb' && \ - apt-get install -y /tmp/webots.deb && \ - rm -f /tmp/webots.deb && \ - mkdir -p /memristor/.config/Cyberbotics - -# TurboVNC -RUN curl -L -o /tmp/turbovnc.deb \ - 'https://downloads.sourceforge.net/project/turbovnc/3.0.1/turbovnc_3.0.1_amd64.deb?use_mirror=autoselect' && \ - apt-get install -y /tmp/turbovnc.deb && \ - rm -f /tmp/turbovnc.deb && \ - echo 'PATH="$PATH:/opt/TurboVNC/bin"' >> /memristor/.bashrc - -# VirtualGL -RUN curl -L -o /tmp/virtualgl.deb \ - 'https://downloads.sourceforge.net/project/virtualgl/3.0.2/virtualgl_3.0.2_amd64.deb?use_mirror=autoselect' && \ - apt-get install -y /tmp/virtualgl.deb && \ - rm -f /tmp/virtualgl.deb && \ - echo 'PATH="$PATH:/opt/VirtualGL/bin"' >> /memristor/.bashrc && \ - printf "1\n\n\n\nX" | /opt/VirtualGL/bin/vglserver_config && \ - sudo usermod -a -G vglusers memristor - -# NoVNC -RUN apt-get install -y novnc && \ - ln -sf /usr/share/novnc/vnc.html /usr/share/novnc/index.html && \ - mkdir -p /memristor/.host - -# XFCE -RUN apt-get install -y --no-install-recommends \ - xorg \ - dbus-x11 \ - xfce4 \ - xfce4-terminal && \ - echo '/usr/sbin/lightdm' > /etc/X11/default-display-manager - -# User config -RUN echo 'export PS1="$(tput setaf 4)\w$(tput sgr0) [$(tput setaf 5)\$?$(tput sgr0)] $(tput setaf 3)\$(git branch --show-current 2>/dev/null | xargs -I{} echo \"({})\")$(tput sgr0)\n$(tput setaf 2)\\$ \\[$(tput sgr0)\\]"' >> /memristor/.bashrc -RUN echo 'cp -p /memristor/.host/.Xauthority /memristor/.Xauthority' >> /memristor/.bashrc -COPY ./config/vscode/. /memristor/ros2_ws/.vscode/ -COPY ./config/Cyberobotics/. /memristor/.config/Cyberbotics/ -COPY ./config/setup.sh /usr/bin/ -COPY ./config/vnc.sh /usr/bin/ - -RUN chown -R memristor:memristor /memristor - -USER memristor -WORKDIR /memristor/ros2_ws diff --git a/docker/Dockerfile.base b/docker/Dockerfile.base new file mode 100644 index 000000000..98b4091d7 --- /dev/null +++ b/docker/Dockerfile.base @@ -0,0 +1,68 @@ +FROM ros:humble + +ARG DEBIAN_FRONTEND=noninteractive +ARG UID=1000 + +# User +RUN useradd -d /memristor -m \ + -u $UID -U \ + -s /usr/bin/bash \ + -c "Memristor Robotics" memristor && \ + echo "memristor ALL=(ALL) NOPASSWD: ALL" >> /etc/sudoers + +# Essentials +RUN apt-get update && apt-get install -y \ + ros-humble-navigation2 \ + ros-humble-nav2-bringup \ + ros-humble-rviz2 \ + ros-humble-teleop-twist-keyboard \ + ros-humble-webots-ros2 \ + ros-humble-dynamixel-sdk \ + ros-humble-can-msgs \ + ros-humble-ruckig \ + ros-humble-laser-filters \ + ros-humble-domain-bridge \ + ros-humble-rmw-cyclonedds-cpp \ + python3-pil \ + alsa \ + libxshmfence1 \ + libgtk-3-dev \ + git \ + git-lfs \ + curl \ + wget \ + vim \ + rsync \ + dialog + +# VS Code +RUN curl -L -o /tmp/vscode.deb \ + 'https://code.visualstudio.com/sha/download?build=stable&os=linux-deb-x64' && \ + apt-get install -y /tmp/vscode.deb && \ + rm -f /tmp/vscode.deb + +RUN su memristor -c 'code --install-extension eamodio.gitlens' && \ + su memristor -c 'code --install-extension ms-python.python' && \ + su memristor -c 'code --install-extension ms-vscode.cpptools-extension-pack' && \ + su memristor -c 'code --install-extension usernamehw.errorlens' && \ + su memristor -c 'code --install-extension ms-iot.vscode-ros' + +# Webots +RUN curl -L -o /tmp/webots.deb \ + '/~https://github.com/cyberbotics/webots/releases/download/R2022b/webots_2022b_amd64.deb' && \ + apt-get install -y /tmp/webots.deb && \ + rm -f /tmp/webots.deb && \ + mkdir -p /memristor/.config/Cyberbotics + +# User config +COPY config/bashrc /tmp/bashrc +COPY ./config/vscode/. /memristor/ros2_ws/.vscode/ +COPY ./config/Cyberobotics/. /memristor/.config/Cyberbotics/ +COPY ./config/setup.sh /usr/bin/ + +RUN cat /tmp/bashrc >> /memristor/.bashrc && \ + rm -f /tmp/bashrc && \ + chown -R memristor:memristor /memristor + +USER memristor +WORKDIR /memristor/ros2_ws diff --git a/docker/Dockerfile.vnc b/docker/Dockerfile.vnc new file mode 100644 index 000000000..4767f90be --- /dev/null +++ b/docker/Dockerfile.vnc @@ -0,0 +1,38 @@ +FROM mep3 + +USER root + +# TurboVNC +RUN curl -L -o /tmp/turbovnc.deb \ + 'https://downloads.sourceforge.net/project/turbovnc/3.0.1/turbovnc_3.0.1_amd64.deb?use_mirror=autoselect' && \ + apt-get install -y /tmp/turbovnc.deb && \ + rm -f /tmp/turbovnc.deb && \ + echo 'PATH="$PATH:/opt/TurboVNC/bin"' >> /memristor/.bashrc + +# VirtualGL +RUN curl -L -o /tmp/virtualgl.deb \ + 'https://downloads.sourceforge.net/project/virtualgl/3.0.2/virtualgl_3.0.2_amd64.deb?use_mirror=autoselect' && \ + apt-get install -y /tmp/virtualgl.deb && \ + rm -f /tmp/virtualgl.deb && \ + echo 'PATH="$PATH:/opt/VirtualGL/bin"' >> /memristor/.bashrc && \ + printf "1\n\n\n\nX" | /opt/VirtualGL/bin/vglserver_config && \ + sudo usermod -a -G vglusers memristor + +# NoVNC +RUN apt-get install -y novnc && \ + ln -sf /usr/share/novnc/vnc.html /usr/share/novnc/index.html && \ + mkdir -p /memristor/.host + +# XFCE +RUN apt-get install -y --no-install-recommends \ + xorg \ + dbus-x11 \ + xfce4 \ + xfce4-terminal && \ + echo '/usr/sbin/lightdm' > /etc/X11/default-display-manager + +# User config +COPY ./config/vnc.sh /usr/bin/ + +USER memristor +WORKDIR /memristor/ros2_ws diff --git a/docker/Makefile b/docker/Makefile index 367dc6444..8c14b1775 100644 --- a/docker/Makefile +++ b/docker/Makefile @@ -5,7 +5,11 @@ NVIDIA_GPU:=$(shell docker info | grep Runtimes | grep nvidia 1> /dev/null && ec .PHONY: destroy build run setup build: - @docker build ${ROOT_DIR} -t mep3 --build-arg UID=${UID} + @docker build ${ROOT_DIR} -f ${ROOT_DIR}/Dockerfile.base -t mep3 --build-arg UID=${UID} + +build-vnc: build +# TODO (parag): Handle the `mep3-vnc` container in other commands + @docker build ${ROOT_DIR} -f ${ROOT_DIR}/Dockerfile.vnc -t mep3-vnc run: @docker run \ diff --git a/docker/config/Cyberobotics/Webots-R2022b.conf b/docker/config/Cyberobotics/Webots-R2022b.conf index ab4849b4b..b3eba5e5f 100644 --- a/docker/config/Cyberobotics/Webots-R2022b.conf +++ b/docker/config/Cyberobotics/Webots-R2022b.conf @@ -6,5 +6,12 @@ startupMode=Real-time telemetry=false theme=webots_night.qss +[OpenGL] +GTAO=0 +disableAntiAliasing=true +disableShadows=true +textureFiltering=1 +textureQuality=0 + [Internal] firstLaunch=false diff --git a/docker/config/bashrc b/docker/config/bashrc new file mode 100644 index 000000000..4f510426f --- /dev/null +++ b/docker/config/bashrc @@ -0,0 +1,5 @@ +source /opt/ros/humble/local_setup.bash +source /memristor/ros2_ws/install/local_setup.bash +export RMW_IMPLEMENTATION=rmw_cyclonedds_cpp +export PS1="$(tput setaf 4)\w$(tput sgr0) [$(tput setaf 5)\$?$(tput sgr0)] $(tput setaf 3)\$(git branch --show-current 2>/dev/null | xargs -I{} echo \"({})\")$(tput sgr0)\n$(tput setaf 2)\\$ \\[$(tput sgr0)\\]" +cp -p /memristor/.host/.Xauthority /memristor/.Xauthority \ No newline at end of file diff --git a/docker/config/setup.sh b/docker/config/setup.sh index 48c3b360d..1529b98df 100755 --- a/docker/config/setup.sh +++ b/docker/config/setup.sh @@ -2,7 +2,6 @@ if dialog --title 'mep3 config' --yesno 'Run first time ROS setup' 5 30; then clear - touch /memristor/ros2_ws/src/mep3/mep3_simulation/COLCON_IGNORE sudo -E rosdep init sudo -E apt-get install -y python3-vcstool cd /memristor/ros2_ws && vcs import src < /memristor/ros2_ws/src/mep3/mep3.repos diff --git a/docker/config/shortcuts.sh b/docker/config/shortcuts.sh index 98f963df9..313b884fc 100755 --- a/docker/config/shortcuts.sh +++ b/docker/config/shortcuts.sh @@ -87,9 +87,6 @@ shortcut_scratchpad_print() { $1 == "navigate_to_pose" { printf "\n", $2, $3, $4; } - $1 == "precise_navigate_to_pose" { - printf "\n", $2, $3, $4; - } $1 == "dynamixel" { printf "\n", $2, $3, $4, $5, $6; } @@ -387,20 +384,3 @@ shortcut_scoreboard_task() { eval "ros2 topic pub --once /scoreboard mep3_msgs/msg/Scoreboard '${message}'" } alias sc="shortcut_scoreboard_task" - -## Launch ResistanceMeterAction action -# Arguments: -# - namespace [optional] -# - side [right/left] [optional] -shortcut_resistance_meter() { - if echo "$2" | grep -qv '^[0-9\.-]*$'; then - namespace="${1:-big}" - shift - else - namespace='big' - fi - side="${1:-right}" - last_action="resistance_meter ${task} ${points}" - eval "ros2 action send_goal /${namespace}/resistance_meter/${side} mep3_msgs/action/ResistanceMeter {}" -} -alias re="shortcut_resistance_meter" diff --git a/install.bash b/install.bash deleted file mode 100755 index b1fb6af8e..000000000 --- a/install.bash +++ /dev/null @@ -1,61 +0,0 @@ -#!/usr/bin/env bash - -# Usage: ./script [rpi|pc] -# Example: ./script pc - -# Configure the script -set -e - -# If there is a ROS environment already sourced it might cause installation issues. -if [ "$(env | grep ROS)" ] && [ ! "$(env | grep 'ROS_DISTRO=galactic')" ]; then - echo "ERROR: You already have a ROS environment sourced (please check your ~/.bashrc)." - exit 2 -fi - -# Export arguments -TARGET_HARDWARE="$1" -if [ "${TARGET_HARDWARE}" != "rpi" ] && [ "${TARGET_HARDWARE}" != "pc" ]; then - echo "Usage: ./script [rpi|pc]" - exit 1 -fi - -# Install ROS 2 -# Referece: https://docs.ros.org/en/galactic/Installation/Ubuntu-Install-Debians.html -sudo apt update -sudo apt install -y locales -sudo locale-gen en_US en_US.UTF-8 -sudo update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 -export LANG=en_US.UTF-8 - -sudo apt install -y curl gnupg2 lsb-release -sudo curl -sSL 'https://raw.githubusercontent.com/ros/rosdistro/master/ros.key' -o /usr/share/keyrings/ros-archive-keyring.gpg -echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2-testing/ubuntu $(source /etc/os-release && echo "$UBUNTU_CODENAME") main" | sudo tee /etc/apt/sources.list.d/ros2.list >/dev/null -sudo apt update - -case "${TARGET_HARDWARE}" in - 'pc') sudo apt install -y ros-galactic-desktop python3-rosdep;; - 'rpi') sudo apt install -y ros-galactic-ros-base python3-rosdep;; -esac - -# Install apt dependencies -sudo apt install -y git build-essential python3-argcomplete python3-colcon-common-extensions - -# Clone mep3 -mkdir -p ~/galactic_ws/src -git clone /~https://github.com/memristor/mep3.git ~/galactic_ws/src/mep3 -if [ "${TARGET_HARDWARE}" = "rpi" ]; then - touch ~/galactic_ws/src/mep3/mep3_simulation/COLCON_IGNORE -fi - -# Build mep3 -pushd ~/galactic_ws -source /opt/ros/galactic/local_setup.bash -if [ ! -f /etc/ros/rosdep/sources.list.d/20-default.list ]; then - # rosdep can be initialized only once so we have to check whether it has already been initialized. - sudo rosdep init -fi -rosdep update -yes | rosdep install --from-paths src --ignore-src -colcon build -source ./install/local_setup.bash -popd diff --git a/mep3_behavior_tree/CMakeLists.txt b/mep3_behavior/CMakeLists.txt similarity index 90% rename from mep3_behavior_tree/CMakeLists.txt rename to mep3_behavior/CMakeLists.txt index 99ca9c292..ffa552b23 100644 --- a/mep3_behavior_tree/CMakeLists.txt +++ b/mep3_behavior/CMakeLists.txt @@ -1,16 +1,14 @@ cmake_minimum_required(VERSION 3.5) -project(mep3_behavior_tree) +project(mep3_behavior) -# Default to C17 +# Default to C99 if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 17) - set(CMAKE_C_STANDARD_REQUIRED ON) + set(CMAKE_C_STANDARD 99) endif() -# Default to C++20 +# Default to C++17 if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 20) - set(CMAKE_CXX_STANDARD_REQUIRED ON) + set(CMAKE_CXX_STANDARD 17) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") diff --git a/mep3_behavior_tree/CPPLINT.cfg b/mep3_behavior/CPPLINT.cfg similarity index 100% rename from mep3_behavior_tree/CPPLINT.cfg rename to mep3_behavior/CPPLINT.cfg diff --git a/mep3_behavior_tree/assets/skills/big_retract_hands.xml b/mep3_behavior/assets/skills/big_retract_hands.xml similarity index 100% rename from mep3_behavior_tree/assets/skills/big_retract_hands.xml rename to mep3_behavior/assets/skills/big_retract_hands.xml diff --git a/mep3_behavior_tree/assets/skills/common_swap.xml b/mep3_behavior/assets/skills/common_swap.xml similarity index 100% rename from mep3_behavior_tree/assets/skills/common_swap.xml rename to mep3_behavior/assets/skills/common_swap.xml diff --git a/mep3_behavior_tree/assets/skills/example.xml b/mep3_behavior/assets/skills/example.xml similarity index 100% rename from mep3_behavior_tree/assets/skills/example.xml rename to mep3_behavior/assets/skills/example.xml diff --git a/mep3_behavior_tree/assets/strategies/big/purple_strategy.xml b/mep3_behavior/assets/strategies/big/purple_strategy.xml similarity index 74% rename from mep3_behavior_tree/assets/strategies/big/purple_strategy.xml rename to mep3_behavior/assets/strategies/big/purple_strategy.xml index 65a1dd805..26a895f9a 100644 --- a/mep3_behavior_tree/assets/strategies/big/purple_strategy.xml +++ b/mep3_behavior/assets/strategies/big/purple_strategy.xml @@ -2,10 +2,12 @@ + + - - + + diff --git a/mep3_behavior_tree/assets/strategies/homologation_forward_backward.xml b/mep3_behavior/assets/strategies/homologation_forward_backward.xml similarity index 100% rename from mep3_behavior_tree/assets/strategies/homologation_forward_backward.xml rename to mep3_behavior/assets/strategies/homologation_forward_backward.xml diff --git a/mep3_behavior_tree/assets/strategies/homologation_resistance.xml b/mep3_behavior/assets/strategies/homologation_resistance.xml similarity index 100% rename from mep3_behavior_tree/assets/strategies/homologation_resistance.xml rename to mep3_behavior/assets/strategies/homologation_resistance.xml diff --git a/mep3_behavior_tree/assets/strategies/mep3_tree_nodes.xml b/mep3_behavior/assets/strategies/mep3_tree_nodes.xml similarity index 100% rename from mep3_behavior_tree/assets/strategies/mep3_tree_nodes.xml rename to mep3_behavior/assets/strategies/mep3_tree_nodes.xml diff --git a/mep3_behavior_tree/assets/strategies/small/purple_strategy.xml b/mep3_behavior/assets/strategies/small/purple_strategy.xml similarity index 100% rename from mep3_behavior_tree/assets/strategies/small/purple_strategy.xml rename to mep3_behavior/assets/strategies/small/purple_strategy.xml diff --git a/mep3_behavior_tree/assets/strategies/statuette.xml b/mep3_behavior/assets/strategies/statuette.xml similarity index 100% rename from mep3_behavior_tree/assets/strategies/statuette.xml rename to mep3_behavior/assets/strategies/statuette.xml diff --git a/mep3_behavior_tree/assets/strategies/strategy.xml b/mep3_behavior/assets/strategies/strategy.xml similarity index 100% rename from mep3_behavior_tree/assets/strategies/strategy.xml rename to mep3_behavior/assets/strategies/strategy.xml diff --git a/mep3_behavior_tree/assets/strategies/testing.xml b/mep3_behavior/assets/strategies/testing.xml similarity index 100% rename from mep3_behavior_tree/assets/strategies/testing.xml rename to mep3_behavior/assets/strategies/testing.xml diff --git a/mep3_behavior_tree/assets/skills/.gitkeep b/mep3_behavior/assets/tasks/.gitkeep similarity index 100% rename from mep3_behavior_tree/assets/skills/.gitkeep rename to mep3_behavior/assets/tasks/.gitkeep diff --git a/mep3_behavior_tree/assets/tasks/big_replica_and_statuette.xml b/mep3_behavior/assets/tasks/big_replica_and_statuette.xml similarity index 100% rename from mep3_behavior_tree/assets/tasks/big_replica_and_statuette.xml rename to mep3_behavior/assets/tasks/big_replica_and_statuette.xml diff --git a/mep3_behavior_tree/assets/tasks/example_moving.xml b/mep3_behavior/assets/tasks/example_moving.xml similarity index 100% rename from mep3_behavior_tree/assets/tasks/example_moving.xml rename to mep3_behavior/assets/tasks/example_moving.xml diff --git a/mep3_behavior_tree/assets/tasks/example_scoreboard.xml b/mep3_behavior/assets/tasks/example_scoreboard.xml similarity index 100% rename from mep3_behavior_tree/assets/tasks/example_scoreboard.xml rename to mep3_behavior/assets/tasks/example_scoreboard.xml diff --git a/mep3_behavior_tree/assets/tasks/small_excavation_squares.xml b/mep3_behavior/assets/tasks/small_excavation_squares.xml similarity index 100% rename from mep3_behavior_tree/assets/tasks/small_excavation_squares.xml rename to mep3_behavior/assets/tasks/small_excavation_squares.xml diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/add_obstacle_action.hpp b/mep3_behavior/include/mep3_behavior/add_obstacle_action.hpp similarity index 95% rename from mep3_behavior_tree/include/mep3_behavior_tree/add_obstacle_action.hpp rename to mep3_behavior/include/mep3_behavior/add_obstacle_action.hpp index c500259a9..5b426e5e0 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/add_obstacle_action.hpp +++ b/mep3_behavior/include/mep3_behavior/add_obstacle_action.hpp @@ -18,7 +18,7 @@ #include #include -#include "mep3_behavior_tree/pose_2d.hpp" +#include "mep3_behavior/pose_2d.hpp" #include "mep3_msgs/msg/temporal_obstacle.hpp" #include "behaviortree_cpp_v3/behavior_tree.h" @@ -27,7 +27,7 @@ #include "rclcpp/rclcpp.hpp" #include "geometry_msgs/msg/point.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class AddObstacleAction : public BT::AsyncActionNode { @@ -73,6 +73,6 @@ namespace mep3_behavior_tree return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__ADD_OBSTACLE_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/blackboard_control_flow.hpp b/mep3_behavior/include/mep3_behavior/blackboard_control_flow.hpp similarity index 99% rename from mep3_behavior_tree/include/mep3_behavior_tree/blackboard_control_flow.hpp rename to mep3_behavior/include/mep3_behavior/blackboard_control_flow.hpp index c25f7a62f..04060edfe 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/blackboard_control_flow.hpp +++ b/mep3_behavior/include/mep3_behavior/blackboard_control_flow.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp_v3/control_node.h" #include "rclcpp/rclcpp.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class CompareBlackboardControl : public BT::ControlNode @@ -368,6 +368,6 @@ class PassAction : public BT::SyncActionNode } }; -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__BLACKBOARD_CONTROL_FLOW_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/bt_action_node.hpp b/mep3_behavior/include/mep3_behavior/bt_action_node.hpp similarity index 61% rename from mep3_behavior_tree/include/mep3_behavior_tree/bt_action_node.hpp rename to mep3_behavior/include/mep3_behavior/bt_action_node.hpp index e5ad9b062..7223e723a 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/bt_action_node.hpp +++ b/mep3_behavior/include/mep3_behavior/bt_action_node.hpp @@ -12,77 +12,64 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MEP3_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_ -#define MEP3_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_ +#ifndef NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_ +#define NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_ #include #include -#include +#include #include "behaviortree_cpp_v3/action_node.h" -#include "rclcpp/executors/single_threaded_executor.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" +#include "nav2_util/node_utils.hpp" #include "rclcpp_action/rclcpp_action.hpp" +#include "nav2_behavior_tree/bt_conversions.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { + +using namespace std::chrono_literals; // NOLINT + /** - * @brief Abstract class representing an action based BT node - * @tparam ActionT Type of action - */ + * @brief Abstract class representing an action based BT node + * @tparam ActionT Type of action + */ template class BtActionNode : public BT::ActionNodeBase { public: /** - * @brief A nav2_behavior_tree::BtActionNode constructor - * @param xml_tag_name Name for the XML tag for this node - * @param action_name Action name this node creates a client for - * @param conf BT node configuration - */ + * @brief A nav2_behavior_tree::BtActionNode constructor + * @param xml_tag_name Name for the XML tag for this node + * @param action_name Action name this node creates a client for + * @param conf BT node configuration + */ BtActionNode( - const std::string & xml_tag_name, const std::string & action_name, + const std::string & xml_tag_name, + const std::string & action_name, const BT::NodeConfiguration & conf) : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name) { node_ = config().blackboard->template get("node"); - callback_group_ = - node_->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); + callback_group_ = node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, + false); callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); - bt_loop_duration_ = std::chrono::milliseconds(10); - server_timeout_ = std::chrono::milliseconds(1000); + // Get the required items from the blackboard + bt_loop_duration_ = + config().blackboard->template get("bt_loop_duration"); + server_timeout_ = + config().blackboard->template get("server_timeout"); + getInput("server_timeout", server_timeout_); // Initialize the input and output messages goal_ = typename ActionT::Goal(); result_ = typename rclcpp_action::ClientGoalHandle::WrappedResult(); - std::string raw_action_name; - std::string raw_name; - if (getInput("server_name", raw_action_name)) { - action_name_ = raw_action_name; - } - if (raw_action_name == "" && getInput("label", raw_name)) { - // Unfortunately, `name` is a reserved property, so we have to use `label`. - action_name_ = action_name + "/" + raw_name; + std::string remapped_action_name; + if (getInput("server_name", remapped_action_name)) { + action_name_ = remapped_action_name; } - - std::string raw_mirror; - if (!getInput("mirror", raw_mirror)) - raw_mirror = "default"; - mirror_ = StrategyMirror::string_to_mirror_enum(raw_mirror); - - original_action_name_ = action_name_; - if (g_StrategyMirror.server_name_requires_mirroring(action_name_, mirror_)) { - g_StrategyMirror.remap_server_name(action_name_); - RCLCPP_INFO( - node_->get_logger(), - "Remapping \"%s\" action server to \"%s\"", - original_action_name_.c_str(), - action_name_.c_str() - ); - } - createActionClient(action_name_); // Give the derive class a chance to do any initialization @@ -91,44 +78,39 @@ class BtActionNode : public BT::ActionNodeBase BtActionNode() = delete; - virtual ~BtActionNode() {} + virtual ~BtActionNode() + { + } /** - * @brief Create instance of an action client - * @param action_name Action name to create client for - */ + * @brief Create instance of an action client + * @param action_name Action name to create client for + */ void createActionClient(const std::string & action_name) { - if (BtActionNode::action_client_list_.find(action_name) != action_client_list_.end()) { - action_client_ = BtActionNode::action_client_list_[action_name]; - RCLCPP_INFO(node_->get_logger(), "Reusing an existing \"%s\" action server", action_name.c_str()); - return; - } - // Now that we have the ROS node to use, create the action client for this BT action action_client_ = rclcpp_action::create_client(node_, action_name, callback_group_); // Make sure the server is actually there before continuing - RCLCPP_INFO(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str()); - if (!action_client_->wait_for_action_server(std::chrono::seconds(35))) { - RCLCPP_FATAL(node_->get_logger(), "Action server \"%s\" is not found", action_name.c_str()); - exit(1); + RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str()); + if (!action_client_->wait_for_action_server(1s)) { + RCLCPP_ERROR( + node_->get_logger(), "\"%s\" action server not available after waiting for 1 s", + action_name.c_str()); + throw std::runtime_error(std::string("Action server %s not available", action_name.c_str())); } - BtActionNode::action_client_list_[action_name] = action_client_; } /** - * @brief Any subclass of BtActionNode that accepts parameters must provide a - * providedPorts method and call providedBasicPorts in it. - * @param addition Additional ports to add to BT port list - * @return BT::PortsList Containing basic ports along with node-specific ports - */ + * @brief Any subclass of BtActionNode that accepts parameters must provide a + * providedPorts method and call providedBasicPorts in it. + * @param addition Additional ports to add to BT port list + * @return BT::PortsList Containing basic ports along with node-specific ports + */ static BT::PortsList providedBasicPorts(BT::PortsList addition) { BT::PortsList basic = { BT::InputPort("server_name", "Action server name"), - BT::InputPort("label", "Action name suffix"), - BT::InputPort("mirror", "Action mirroring flag"), BT::InputPort("server_timeout") }; basic.insert(addition.begin(), addition.end()); @@ -137,49 +119,68 @@ class BtActionNode : public BT::ActionNodeBase } /** - * @brief Creates list of BT ports - * @return BT::PortsList Containing basic ports along with node-specific ports - */ - static BT::PortsList providedPorts() {return providedBasicPorts({});} + * @brief Creates list of BT ports + * @return BT::PortsList Containing basic ports along with node-specific ports + */ + static BT::PortsList providedPorts() + { + return providedBasicPorts({}); + } // Derived classes can override any of the following methods to hook into the // processing for the action: on_tick, on_wait_for_result, and on_success /** - * @brief Function to perform some user-defined operation on tick - * Could do dynamic checks, such as getting updates to values on the blackboard - */ - virtual void on_tick() {} + * @brief Function to perform some user-defined operation on tick + * Could do dynamic checks, such as getting updates to values on the blackboard + */ + virtual void on_tick() + { + } /** - * @brief Function to perform some user-defined operation after a timeout - * waiting for a result that hasn't been received yet - */ - virtual void on_wait_for_result() {} + * @brief Function to perform some user-defined operation after a timeout + * waiting for a result that hasn't been received yet. Also provides access to + * the latest feedback message from the action server. Feedback will be nullptr + * in subsequent calls to this function if no new feedback is received while waiting for a result. + * @param feedback shared_ptr to latest feedback message, nullptr if no new feedback was received + */ + virtual void on_wait_for_result(std::shared_ptr/*feedback*/) + { + } /** - * @brief Function to perform some user-defined operation upon successful - * completion of the action. Could put a value on the blackboard. - * @return BT::NodeStatus Returns SUCCESS by default, user may override return another value - */ - virtual BT::NodeStatus on_success() {return BT::NodeStatus::SUCCESS;} + * @brief Function to perform some user-defined operation upon successful + * completion of the action. Could put a value on the blackboard. + * @return BT::NodeStatus Returns SUCCESS by default, user may override return another value + */ + virtual BT::NodeStatus on_success() + { + return BT::NodeStatus::SUCCESS; + } /** - * @brief Function to perform some user-defined operation whe the action is aborted. - * @return BT::NodeStatus Returns FAILURE by default, user may override return another value - */ - virtual BT::NodeStatus on_aborted() {return BT::NodeStatus::FAILURE;} + * @brief Function to perform some user-defined operation whe the action is aborted. + * @return BT::NodeStatus Returns FAILURE by default, user may override return another value + */ + virtual BT::NodeStatus on_aborted() + { + return BT::NodeStatus::FAILURE; + } /** - * @brief Function to perform some user-defined operation when the action is cancelled. - * @return BT::NodeStatus Returns SUCCESS by default, user may override return another value - */ - virtual BT::NodeStatus on_cancelled() {return BT::NodeStatus::SUCCESS;} + * @brief Function to perform some user-defined operation when the action is cancelled. + * @return BT::NodeStatus Returns SUCCESS by default, user may override return another value + */ + virtual BT::NodeStatus on_cancelled() + { + return BT::NodeStatus::SUCCESS; + } /** - * @brief The main override required by a BT action - * @return BT::NodeStatus Status of tick execution - */ + * @brief The main override required by a BT action + * @return BT::NodeStatus Status of tick execution + */ BT::NodeStatus tick() override { // first step to be done only at the beginning of the Action @@ -216,11 +217,13 @@ class BtActionNode : public BT::ActionNodeBase // The following code corresponds to the "RUNNING" loop if (rclcpp::ok() && !goal_result_available_) { // user defined callback. May modify the value of "goal_updated_" - on_wait_for_result(); + on_wait_for_result(feedback_); + + // reset feedback to avoid stale information + feedback_.reset(); auto goal_status = goal_handle_->get_status(); - if ( - goal_updated_ && (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING || + if (goal_updated_ && (goal_status == action_msgs::msg::GoalStatus::STATUS_EXECUTING || goal_status == action_msgs::msg::GoalStatus::STATUS_ACCEPTED)) { goal_updated_ = false; @@ -248,8 +251,7 @@ class BtActionNode : public BT::ActionNodeBase } } } catch (const std::runtime_error & e) { - if ( - e.what() == std::string("send_goal failed") || + if (e.what() == std::string("send_goal failed") || e.what() == std::string("Goal was rejected by the action server")) { // Action related failure that should not fail the tree, but the node @@ -283,19 +285,19 @@ class BtActionNode : public BT::ActionNodeBase } /** - * @brief The other (optional) override required by a BT action. In this case, we - * make sure to cancel the ROS2 action if it is still running. - */ + * @brief The other (optional) override required by a BT action. In this case, we + * make sure to cancel the ROS2 action if it is still running. + */ void halt() override { if (should_cancel_goal()) { auto future_cancel = action_client_->async_cancel_goal(goal_handle_); - if ( - callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) != + if (callback_group_executor_.spin_until_future_complete(future_cancel, server_timeout_) != rclcpp::FutureReturnCode::SUCCESS) { RCLCPP_ERROR( - node_->get_logger(), "Failed to cancel action server for %s", action_name_.c_str()); + node_->get_logger(), + "Failed to cancel action server for %s", action_name_.c_str()); } } @@ -304,9 +306,9 @@ class BtActionNode : public BT::ActionNodeBase protected: /** - * @brief Function to check if current goal should be cancelled - * @return bool True if current goal should be cancelled, false otherwise - */ + * @brief Function to check if current goal should be cancelled + * @return bool True if current goal should be cancelled, false otherwise + */ bool should_cancel_goal() { // Shut the node down if it is currently running @@ -328,8 +330,8 @@ class BtActionNode : public BT::ActionNodeBase } /** - * @brief Function to send new goal to action server - */ + * @brief Function to send new goal to action server + */ void send_new_goal() { goal_result_available_ = false; @@ -340,8 +342,7 @@ class BtActionNode : public BT::ActionNodeBase RCLCPP_DEBUG( node_->get_logger(), "Goal result for %s available, but it hasn't received the goal response yet. " - "It's probably a goal result for the last goal request", - action_name_.c_str()); + "It's probably a goal result for the last goal request", action_name_.c_str()); return; } @@ -353,6 +354,11 @@ class BtActionNode : public BT::ActionNodeBase result_ = result; } }; + send_goal_options.feedback_callback = + [this](typename rclcpp_action::ClientGoalHandle::SharedPtr, + const std::shared_ptr feedback) { + feedback_ = feedback; + }; future_goal_handle_ = std::make_shared< std::shared_future::SharedPtr>>( @@ -361,11 +367,11 @@ class BtActionNode : public BT::ActionNodeBase } /** - * @brief Function to check if the action server acknowledged a new goal - * @param elapsed Duration since the last goal was sent and future goal handle has not completed. - * After waiting for the future to complete, this value is incremented with the timeout value. - * @return boolean True if future_goal_handle_ returns SUCCESS, False otherwise - */ + * @brief Function to check if the action server acknowledged a new goal + * @param elapsed Duration since the last goal was sent and future goal handle has not completed. + * After waiting for the future to complete, this value is incremented with the timeout value. + * @return boolean True if future_goal_handle_ returns SUCCESS, False otherwise + */ bool is_future_goal_handle_complete(std::chrono::milliseconds & elapsed) { auto remaining = server_timeout_ - elapsed; @@ -399,8 +405,8 @@ class BtActionNode : public BT::ActionNodeBase } /** - * @brief Function to increment recovery count on blackboard if this node wraps a recovery - */ + * @brief Function to increment recovery count on blackboard if this node wraps a recovery + */ void increment_recovery_count() { int recovery_count = 0; @@ -409,10 +415,8 @@ class BtActionNode : public BT::ActionNodeBase config().blackboard->template set("number_recoveries", recovery_count); // NOLINT } - std::string action_name_, original_action_name_; - MirrorParam mirror_; + std::string action_name_; typename std::shared_ptr> action_client_; - static std::unordered_map>> action_client_list_; // All ROS2 actions have a goal and a result typename ActionT::Goal goal_; @@ -421,6 +425,9 @@ class BtActionNode : public BT::ActionNodeBase typename rclcpp_action::ClientGoalHandle::SharedPtr goal_handle_; typename rclcpp_action::ClientGoalHandle::WrappedResult result_; + // To handle feedback from action server + std::shared_ptr feedback_; + // The node that will be used for any ROS operations rclcpp::Node::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; @@ -439,9 +446,6 @@ class BtActionNode : public BT::ActionNodeBase rclcpp::Time time_goal_sent_; }; -template -std::unordered_map>> BtActionNode::action_client_list_; - -} // namespace mep3_behavior_tree +} // namespace nav2_behavior_tree -#endif // MEP3_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_ +#endif // NAV2_BEHAVIOR_TREE__BT_ACTION_NODE_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/canbus_send_action.hpp b/mep3_behavior/include/mep3_behavior/canbus_send_action.hpp similarity index 97% rename from mep3_behavior_tree/include/mep3_behavior_tree/canbus_send_action.hpp rename to mep3_behavior/include/mep3_behavior/canbus_send_action.hpp index 14913fc53..dfc396d82 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/canbus_send_action.hpp +++ b/mep3_behavior/include/mep3_behavior/canbus_send_action.hpp @@ -25,7 +25,7 @@ #include "behaviortree_cpp_v3/action_node.h" #include "rclcpp/rclcpp.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class CanbusSendAction : public BT::AsyncActionNode { @@ -81,6 +81,6 @@ BT::NodeStatus CanbusSendAction::tick() return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__CANBUS_SEND_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/delay_action.hpp b/mep3_behavior/include/mep3_behavior/delay_action.hpp similarity index 97% rename from mep3_behavior_tree/include/mep3_behavior_tree/delay_action.hpp rename to mep3_behavior/include/mep3_behavior/delay_action.hpp index facfb3560..67761afbb 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/delay_action.hpp +++ b/mep3_behavior/include/mep3_behavior/delay_action.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp_v3/action_node.h" #include "rclcpp/rclcpp.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class DelayAction : public BT::ActionNodeBase { @@ -91,6 +91,6 @@ namespace mep3_behavior_tree return BT::NodeStatus::RUNNING; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__DELAY_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/dynamixel_command_action.hpp b/mep3_behavior/include/mep3_behavior/dynamixel_command_action.hpp similarity index 85% rename from mep3_behavior_tree/include/mep3_behavior_tree/dynamixel_command_action.hpp rename to mep3_behavior/include/mep3_behavior/dynamixel_command_action.hpp index 8535950d4..58fa92c8b 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/dynamixel_command_action.hpp +++ b/mep3_behavior/include/mep3_behavior/dynamixel_command_action.hpp @@ -20,20 +20,20 @@ #include "behaviortree_cpp_v3/behavior_tree.h" #include "behaviortree_cpp_v3/bt_factory.h" -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_behavior_tree/table_specific_ports.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" +#include "mep3_behavior/bt_action_node.hpp" +#include "mep3_behavior/table_specific_ports.hpp" +#include "mep3_behavior/team_color_strategy_mirror.hpp" #include "mep3_msgs/action/dynamixel_command.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class DynamixelCommandAction - : public mep3_behavior_tree::BtActionNode + : public mep3_behavior::BtActionNode { public: explicit DynamixelCommandAction( const std::string & xml_tag_name, const BT::NodeConfiguration & config) - : mep3_behavior_tree::BtActionNode( + : mep3_behavior::BtActionNode( xml_tag_name, "dynamixel_command", config) { if (!getInput("position", this->position)) @@ -52,11 +52,6 @@ class DynamixelCommandAction if (table.length() > 0 && getInput("position_" + table, position_offset)) { position += position_offset; } - - if (g_StrategyMirror.angle_requires_mirroring(original_action_name_, mirror_)) { - g_StrategyMirror.invert_angle(position); - } - } void on_tick() override; @@ -116,6 +111,6 @@ BT::NodeStatus DynamixelCommandAction::on_cancelled() return BT::NodeStatus::FAILURE; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__DYNAMIXEL_COMMAND_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/motion_command_action.hpp b/mep3_behavior/include/mep3_behavior/motion_command_action.hpp similarity index 88% rename from mep3_behavior_tree/include/mep3_behavior_tree/motion_command_action.hpp rename to mep3_behavior/include/mep3_behavior/motion_command_action.hpp index 421e4f592..e59c2547b 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/motion_command_action.hpp +++ b/mep3_behavior/include/mep3_behavior/motion_command_action.hpp @@ -20,20 +20,20 @@ #include "behaviortree_cpp_v3/behavior_tree.h" #include "behaviortree_cpp_v3/bt_factory.h" -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_behavior_tree/table_specific_ports.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" +#include "mep3_behavior/bt_action_node.hpp" +#include "mep3_behavior/table_specific_ports.hpp" +#include "mep3_behavior/team_color_strategy_mirror.hpp" #include "mep3_msgs/action/motion_command.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class MotionCommandAction - : public mep3_behavior_tree::BtActionNode + : public mep3_behavior::BtActionNode { public: explicit MotionCommandAction( const std::string & xml_tag_name, const BT::NodeConfiguration & config) - : mep3_behavior_tree::BtActionNode( + : mep3_behavior::BtActionNode( xml_tag_name, "motion_command", config) { if (!getInput("command", this->command)) @@ -60,12 +60,12 @@ class MotionCommandAction } if ( - g_StrategyMirror.requires_mirroring(mirror_) && \ + g_StrategyMirror.requires_mirroring() && \ command == "rotate_relative" ) { g_StrategyMirror.invert_angle(value); } else if ( - g_StrategyMirror.requires_mirroring(mirror_) && \ + g_StrategyMirror.requires_mirroring() && \ command == "rotate_absolute" ) { g_StrategyMirror.mirror_angle(value); @@ -125,6 +125,6 @@ BT::NodeStatus MotionCommandAction::on_success() return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__MOTION_COMMAND_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/navigate_through_action.hpp b/mep3_behavior/include/mep3_behavior/navigate_through_action.hpp similarity index 87% rename from mep3_behavior_tree/include/mep3_behavior_tree/navigate_through_action.hpp rename to mep3_behavior/include/mep3_behavior/navigate_through_action.hpp index 24e34dad8..f84a1ebd6 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/navigate_through_action.hpp +++ b/mep3_behavior/include/mep3_behavior/navigate_through_action.hpp @@ -22,20 +22,20 @@ #include "behaviortree_cpp_v3/behavior_tree.h" #include "behaviortree_cpp_v3/bt_factory.h" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_behavior_tree/pose_2d.hpp" -#include "mep3_behavior_tree/table_specific_ports.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" +#include "mep3_behavior/bt_action_node.hpp" +#include "mep3_behavior/pose_2d.hpp" +#include "mep3_behavior/table_specific_ports.hpp" +#include "mep3_behavior/team_color_strategy_mirror.hpp" #include "nav2_msgs/action/navigate_through_poses.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class NavigateThroughAction - : public mep3_behavior_tree::BtActionNode + : public mep3_behavior::BtActionNode { public: explicit NavigateThroughAction(const std::string &xml_tag_name, const BT::NodeConfiguration &config) - : mep3_behavior_tree::BtActionNode( + : mep3_behavior::BtActionNode( xml_tag_name, "navigate_through_poses", config) { } @@ -77,7 +77,7 @@ namespace mep3_behavior_tree << table << "' detected" << std::endl; } - bool requires_mirroring = g_StrategyMirror.requires_mirroring(mirror_); + bool requires_mirroring = g_StrategyMirror.requires_mirroring(); goal_.behavior_tree = behavior_tree; for (auto &pose : poses) @@ -112,6 +112,6 @@ namespace mep3_behavior_tree return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__NAVIGATE_THROUGH_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/navigate_to_action.hpp b/mep3_behavior/include/mep3_behavior/navigate_to_action.hpp similarity index 86% rename from mep3_behavior_tree/include/mep3_behavior_tree/navigate_to_action.hpp rename to mep3_behavior/include/mep3_behavior/navigate_to_action.hpp index 41c36970b..496e1e270 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/navigate_to_action.hpp +++ b/mep3_behavior/include/mep3_behavior/navigate_to_action.hpp @@ -21,20 +21,20 @@ #include "behaviortree_cpp_v3/behavior_tree.h" #include "behaviortree_cpp_v3/bt_factory.h" -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_behavior_tree/pose_2d.hpp" -#include "mep3_behavior_tree/table_specific_ports.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" +#include "mep3_behavior/bt_action_node.hpp" +#include "mep3_behavior/pose_2d.hpp" +#include "mep3_behavior/table_specific_ports.hpp" +#include "mep3_behavior/team_color_strategy_mirror.hpp" #include "nav2_msgs/action/navigate_to_pose.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class NavigateToAction - : public mep3_behavior_tree::BtActionNode + : public mep3_behavior::BtActionNode { public: explicit NavigateToAction(const std::string &xml_tag_name, const BT::NodeConfiguration &config) - : mep3_behavior_tree::BtActionNode( + : mep3_behavior::BtActionNode( xml_tag_name, "navigate_to_pose", config) { if (!getInput("goal", this->goal)) @@ -49,7 +49,7 @@ namespace mep3_behavior_tree goal += goal_offset; } - if (g_StrategyMirror.requires_mirroring(mirror_)) { + if (g_StrategyMirror.requires_mirroring()) { g_StrategyMirror.mirror_pose(goal); } } @@ -109,6 +109,6 @@ namespace mep3_behavior_tree return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__NAVIGATE_TO_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/pose_2d.hpp b/mep3_behavior/include/mep3_behavior/pose_2d.hpp similarity index 100% rename from mep3_behavior_tree/include/mep3_behavior_tree/pose_2d.hpp rename to mep3_behavior/include/mep3_behavior/pose_2d.hpp diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/remove_obstacle_action.hpp b/mep3_behavior/include/mep3_behavior/remove_obstacle_action.hpp similarity index 96% rename from mep3_behavior_tree/include/mep3_behavior_tree/remove_obstacle_action.hpp rename to mep3_behavior/include/mep3_behavior/remove_obstacle_action.hpp index 64da344fe..37b7b6b9d 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/remove_obstacle_action.hpp +++ b/mep3_behavior/include/mep3_behavior/remove_obstacle_action.hpp @@ -24,7 +24,7 @@ #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class RemoveObstacleAction : public BT::AsyncActionNode { @@ -66,6 +66,6 @@ namespace mep3_behavior_tree return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__REMOVE_OBSTACLE_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/scoreboard_task_action.hpp b/mep3_behavior/include/mep3_behavior/scoreboard_task_action.hpp similarity index 96% rename from mep3_behavior_tree/include/mep3_behavior_tree/scoreboard_task_action.hpp rename to mep3_behavior/include/mep3_behavior/scoreboard_task_action.hpp index d1648352b..810dd3888 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/scoreboard_task_action.hpp +++ b/mep3_behavior/include/mep3_behavior/scoreboard_task_action.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp_v3/action_node.h" #include "rclcpp/rclcpp.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class ScoreboardTaskAction : public BT::AsyncActionNode { @@ -70,6 +70,6 @@ BT::NodeStatus ScoreboardTaskAction::tick() return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__SCOREBOARD_TASK_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/set_shared_blackboard_action.hpp b/mep3_behavior/include/mep3_behavior/set_shared_blackboard_action.hpp similarity index 97% rename from mep3_behavior_tree/include/mep3_behavior_tree/set_shared_blackboard_action.hpp rename to mep3_behavior/include/mep3_behavior/set_shared_blackboard_action.hpp index 334af2648..08dd9cecd 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/set_shared_blackboard_action.hpp +++ b/mep3_behavior/include/mep3_behavior/set_shared_blackboard_action.hpp @@ -25,7 +25,7 @@ #include "behaviortree_cpp_v3/action_node.h" #include "rclcpp/rclcpp.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { using KeyValueT = diagnostic_msgs::msg::KeyValue; @@ -73,6 +73,6 @@ namespace mep3_behavior_tree return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__SET_SHARED_BLACKBOARD_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/table_specific_ports.hpp b/mep3_behavior/include/mep3_behavior/table_specific_ports.hpp similarity index 95% rename from mep3_behavior_tree/include/mep3_behavior_tree/table_specific_ports.hpp rename to mep3_behavior/include/mep3_behavior/table_specific_ports.hpp index 668a9ce9f..019d9c802 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/table_specific_ports.hpp +++ b/mep3_behavior/include/mep3_behavior/table_specific_ports.hpp @@ -18,7 +18,7 @@ #include #include -namespace mep3_behavior_tree +namespace mep3_behavior { class InputPortNameFactory { @@ -42,6 +42,6 @@ class InputPortNameFactory { // Globally shared singleton InputPortNameFactory g_InputPortNameFactory; -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__TABLE_SPECIFIC_PORTS_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/task_sequence_control.hpp b/mep3_behavior/include/mep3_behavior/task_sequence_control.hpp similarity index 98% rename from mep3_behavior_tree/include/mep3_behavior_tree/task_sequence_control.hpp rename to mep3_behavior/include/mep3_behavior/task_sequence_control.hpp index b322f8d77..ac886b7c5 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/task_sequence_control.hpp +++ b/mep3_behavior/include/mep3_behavior/task_sequence_control.hpp @@ -20,7 +20,7 @@ #include "behaviortree_cpp_v3/control_node.h" -namespace mep3_behavior_tree +namespace mep3_behavior { class TaskSequenceControl : public BT::ControlNode { @@ -106,5 +106,5 @@ namespace mep3_behavior_tree // DO NOT reset current_child_idx_ on halt BT::ControlNode::halt(); } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__TASK_SEQUENCE_CONTROL_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/team_color_strategy_mirror.hpp b/mep3_behavior/include/mep3_behavior/team_color_strategy_mirror.hpp similarity index 53% rename from mep3_behavior_tree/include/mep3_behavior_tree/team_color_strategy_mirror.hpp rename to mep3_behavior/include/mep3_behavior/team_color_strategy_mirror.hpp index 3110e2471..03d794994 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/team_color_strategy_mirror.hpp +++ b/mep3_behavior/include/mep3_behavior/team_color_strategy_mirror.hpp @@ -24,21 +24,15 @@ #include #include "behaviortree_cpp_v3/action_node.h" -#include "mep3_behavior_tree/pose_2d.hpp" +#include "mep3_behavior/pose_2d.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { enum TeamColor { Purple, Yellow }; -enum MirrorParam { - True, - False, - Default -}; - class StrategyMirror { public: StrategyMirror() { @@ -51,14 +45,6 @@ class StrategyMirror { this->color = StrategyMirror::string_to_color_enum(color); } - void set_angle_blacklist(const std::vector& list) { - this->mirror_angle_blacklist = list; - } - - void set_name_blacklist(const std::vector& list) { - this->mirror_name_blacklist = list; - } - void set_default_color(const std::string& color) { this->default_color = StrategyMirror::string_to_color_enum(color); } @@ -78,73 +64,11 @@ class StrategyMirror { } } - void remap_server_name(std::string& server_name) { - if (this->color == this->default_color) - return; - const auto re_left = std::regex("left"); - const auto re_right = std::regex("right"); - const auto re_placeholder = std::regex("PLACEHOLDER"); - server_name = std::regex_replace(server_name, re_right, "PLACEHOLDER"); - server_name = std::regex_replace(server_name, re_left, "right"); - server_name = std::regex_replace(server_name, re_placeholder, "left"); - } - - bool requires_mirroring( - const MirrorParam mirror - ) { - switch (mirror) { - case MirrorParam::True: - return true; - case MirrorParam::False: - return false; - default: - if (this->color == this->default_color) - return false; - else - return true; - } - } - - bool server_name_requires_mirroring( - const std::string& server_name, - const MirrorParam mirror - ) { - switch (mirror) { - case MirrorParam::True: - return true; - case MirrorParam::False: + bool requires_mirroring() { + if (this->color == this->default_color) return false; - default: - if (this->color == this->default_color) - return false; - // Return true if not found in blacklist array - return std::find( - this->mirror_name_blacklist.begin(), - this->mirror_name_blacklist.end(), - StrategyMirror::strip_server_name(server_name) - ) == this->mirror_name_blacklist.end(); - } - } - - bool angle_requires_mirroring( - const std::string& server_name, - const MirrorParam mirror - ) { - switch (mirror) { - case MirrorParam::True: + else return true; - case MirrorParam::False: - return false; - default: - if (this->color == this->default_color) - return false; - // Return true if not found in blacklist array - return std::find( - this->mirror_angle_blacklist.begin(), - this->mirror_angle_blacklist.end(), - StrategyMirror::strip_server_name(server_name) - ) == this->mirror_angle_blacklist.end(); - } } template @@ -162,28 +86,6 @@ class StrategyMirror { } } - template - void mirror_resistance(Number& resistance) { - switch (resistance) { - case RESISTANCE_VALUE_YELLOW: - resistance = RESISTANCE_VALUE_PURPLE; - return; - case RESISTANCE_VALUE_PURPLE: - resistance = RESISTANCE_VALUE_YELLOW; - return; - } - } - - static MirrorParam string_to_mirror_enum(const std::string& mirror) { - if (mirror == "false") { - return MirrorParam::False; - } else if (mirror == "true") { - return MirrorParam::True; - } else { - return MirrorParam::Default; - } - } - private: static TeamColor string_to_color_enum(const std::string& color) { if (color == "purple") { @@ -206,8 +108,6 @@ class StrategyMirror { } TeamColor color, default_color; - std::vector mirror_angle_blacklist, mirror_name_blacklist; - }; // Globally shared singleton @@ -241,6 +141,6 @@ class DefaultTeamColorCondition : public BT::ConditionNode } }; -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__TEAM_COLOR_STRATEGY_MIRROR_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/vacuum_pump_command_action.hpp b/mep3_behavior/include/mep3_behavior/vacuum_pump_command_action.hpp similarity index 87% rename from mep3_behavior_tree/include/mep3_behavior_tree/vacuum_pump_command_action.hpp rename to mep3_behavior/include/mep3_behavior/vacuum_pump_command_action.hpp index 19bf0be28..7fc29253d 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/vacuum_pump_command_action.hpp +++ b/mep3_behavior/include/mep3_behavior/vacuum_pump_command_action.hpp @@ -19,19 +19,19 @@ #include "behaviortree_cpp_v3/behavior_tree.h" #include "behaviortree_cpp_v3/bt_factory.h" -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" +#include "mep3_behavior/bt_action_node.hpp" +#include "mep3_behavior/team_color_strategy_mirror.hpp" #include "mep3_msgs/action/vacuum_pump_command.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class VacuumPumpCommandAction - : public mep3_behavior_tree::BtActionNode + : public mep3_behavior::BtActionNode { public: explicit VacuumPumpCommandAction( const std::string & xml_tag_name, const BT::NodeConfiguration & config) - : mep3_behavior_tree::BtActionNode( + : mep3_behavior::BtActionNode( xml_tag_name, "vacuum_pump_command", config) { if (!getInput("connect", this->connect)) @@ -82,6 +82,6 @@ BT::NodeStatus VacuumPumpCommandAction::on_cancelled() return BT::NodeStatus::FAILURE; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__VACUUM_PUMP_COMMAND_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/wait_match_start_action.hpp b/mep3_behavior/include/mep3_behavior/wait_match_start_action.hpp similarity index 97% rename from mep3_behavior_tree/include/mep3_behavior_tree/wait_match_start_action.hpp rename to mep3_behavior/include/mep3_behavior/wait_match_start_action.hpp index 5fc5fee33..6b92e8afe 100644 --- a/mep3_behavior_tree/include/mep3_behavior_tree/wait_match_start_action.hpp +++ b/mep3_behavior/include/mep3_behavior/wait_match_start_action.hpp @@ -22,7 +22,7 @@ #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/int8.hpp" -namespace mep3_behavior_tree +namespace mep3_behavior { class WaitMatchStartAction : public BT::SyncActionNode { @@ -77,6 +77,6 @@ BT::NodeStatus WaitMatchStartAction::tick() return BT::NodeStatus::SUCCESS; } -} // namespace mep3_behavior_tree +} // namespace mep3_behavior #endif // MEP3_BEHAVIOR_TREE__WAIT_MATCH_START_ACTION_HPP_ diff --git a/mep3_behavior_tree/package.xml b/mep3_behavior/package.xml similarity index 97% rename from mep3_behavior_tree/package.xml rename to mep3_behavior/package.xml index 68f34a650..58bc380d7 100644 --- a/mep3_behavior_tree/package.xml +++ b/mep3_behavior/package.xml @@ -1,7 +1,7 @@ - mep3_behavior_tree + mep3_behavior 0.1.0 Memristor Eurobot Platform Strategy Planner memristor diff --git a/mep3_behavior_tree/src/mep3_behavior_tree.cpp b/mep3_behavior/src/mep3_behavior_tree.cpp similarity index 54% rename from mep3_behavior_tree/src/mep3_behavior_tree.cpp rename to mep3_behavior/src/mep3_behavior_tree.cpp index 9cf01436a..63e5adc95 100644 --- a/mep3_behavior_tree/src/mep3_behavior_tree.cpp +++ b/mep3_behavior/src/mep3_behavior_tree.cpp @@ -13,7 +13,7 @@ // limitations under the License. #ifndef ASSETS_DIRECTORY -#define ASSETS_DIRECTORY "mep3_behavior_tree/assets" +#define ASSETS_DIRECTORY "mep3_behavior/assets" #endif #include @@ -26,25 +26,22 @@ #include "behaviortree_cpp_v3/bt_factory.h" #include "behaviortree_cpp_v3/utils/shared_library.h" #include "behaviortree_cpp_v3/loggers/bt_cout_logger.h" -#include "mep3_behavior_tree/dynamixel_command_action.hpp" -#include "mep3_behavior_tree/lift_command_action.hpp" -#include "mep3_behavior_tree/motion_command_action.hpp" -#include "mep3_behavior_tree/navigate_to_action.hpp" -#include "mep3_behavior_tree/precise_navigate_to_action.hpp" -#include "mep3_behavior_tree/resistance_meter_action.hpp" -#include "mep3_behavior_tree/table_specific_ports.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" -#include "mep3_behavior_tree/scoreboard_task_action.hpp" -#include "mep3_behavior_tree/task_sequence_control.hpp" -#include "mep3_behavior_tree/vacuum_pump_command_action.hpp" -#include "mep3_behavior_tree/wait_match_start_action.hpp" -#include "mep3_behavior_tree/delay_action.hpp" -#include "mep3_behavior_tree/canbus_send_action.hpp" -#include "mep3_behavior_tree/set_shared_blackboard_action.hpp" -#include "mep3_behavior_tree/blackboard_control_flow.hpp" -#include "mep3_behavior_tree/navigate_through_action.hpp" -#include "mep3_behavior_tree/add_obstacle_action.hpp" -#include "mep3_behavior_tree/remove_obstacle_action.hpp" +#include "mep3_behavior/dynamixel_command_action.hpp" +#include "mep3_behavior/motion_command_action.hpp" +#include "mep3_behavior/navigate_to_action.hpp" +#include "mep3_behavior/table_specific_ports.hpp" +#include "mep3_behavior/team_color_strategy_mirror.hpp" +#include "mep3_behavior/scoreboard_task_action.hpp" +#include "mep3_behavior/task_sequence_control.hpp" +#include "mep3_behavior/vacuum_pump_command_action.hpp" +#include "mep3_behavior/wait_match_start_action.hpp" +#include "mep3_behavior/delay_action.hpp" +#include "mep3_behavior/canbus_send_action.hpp" +#include "mep3_behavior/set_shared_blackboard_action.hpp" +#include "mep3_behavior/blackboard_control_flow.hpp" +#include "mep3_behavior/navigate_through_action.hpp" +#include "mep3_behavior/add_obstacle_action.hpp" +#include "mep3_behavior/remove_obstacle_action.hpp" #include "rclcpp/rclcpp.hpp" using KeyValueT = diagnostic_msgs::msg::KeyValue; @@ -59,7 +56,7 @@ int main(int argc, char **argv) // Initialize ROS node rclcpp::init(argc, argv); - auto node = rclcpp::Node::make_shared("mep3_behavior_tree"); + auto node = rclcpp::Node::make_shared("mep3_behavior"); // Initialize blackboard auto blackboard = BT::Blackboard::create(); @@ -105,36 +102,16 @@ int main(int argc, char **argv) std::vector({}) ); node->get_parameter("predefined_tables", predefined_tables); - mep3_behavior_tree::g_InputPortNameFactory.set_names( + mep3_behavior::g_InputPortNameFactory.set_names( predefined_tables.as_string_array() ); // Set color node->declare_parameter("color", "purple"); auto color = node->get_parameter("color"); - mep3_behavior_tree::g_StrategyMirror.set_color(color.as_string()); + mep3_behavior::g_StrategyMirror.set_color(color.as_string()); blackboard->set("color", color.as_string()); - // Get mirroring blacklists - node->declare_parameter>("mirror_angle_blacklist", std::vector({})); - node->declare_parameter>("mirror_name_blacklist", std::vector({})); - rclcpp::Parameter mirror_angle_blacklist( - "mirror_angle_blacklist", - std::vector({}) - ); - rclcpp::Parameter mirror_name_blacklist( - "mirror_name_blacklist", - std::vector({}) - ); - node->get_parameter("mirror_angle_blacklist", mirror_angle_blacklist); - node->get_parameter("mirror_name_blacklist", mirror_name_blacklist); - mep3_behavior_tree::g_StrategyMirror.set_angle_blacklist( - mirror_angle_blacklist.as_string_array() - ); - mep3_behavior_tree::g_StrategyMirror.set_name_blacklist( - mirror_name_blacklist.as_string_array() - ); - blackboard->set( "bt_loop_duration", std::chrono::milliseconds(10)); @@ -152,64 +129,55 @@ int main(int argc, char **argv) loader.getOSName("nav2_recovery_node_bt_node") ); - factory.registerNodeType( + factory.registerNodeType( "CanbusSend" ); - factory.registerNodeType( + factory.registerNodeType( "SetSharedBlackboard" ); - factory.registerNodeType( + factory.registerNodeType( "CompareBlackboard" ); - factory.registerNodeType( + factory.registerNodeType( "Blackboard" ); - factory.registerNodeType( + factory.registerNodeType( "Pass" ); - factory.registerNodeType( + factory.registerNodeType( "Wait" ); - factory.registerNodeType( + factory.registerNodeType( "Dynamixel" ); - factory.registerNodeType( + factory.registerNodeType( "Motion" ); - factory.registerNodeType( + factory.registerNodeType( "Navigate" ); - factory.registerNodeType( - "PreciseNavigate" - ); - factory.registerNodeType( + factory.registerNodeType( "VacuumPump" ); - factory.registerNodeType( - "ResistanceMeter" - ); - factory.registerNodeType( + factory.registerNodeType( "ScoreboardTask" ); - factory.registerNodeType( + factory.registerNodeType( "WaitMatchStart" ); - factory.registerNodeType( - "Lift" - ); - factory.registerNodeType( + factory.registerNodeType( "DefaultTeamColor" ); - factory.registerNodeType( + factory.registerNodeType( "TaskSequence" ); - factory.registerNodeType( + factory.registerNodeType( "NavigateThrough" ); - factory.registerNodeType( + factory.registerNodeType( "AddObstacle" ); - factory.registerNodeType( + factory.registerNodeType( "RemoveObstacle" ); diff --git a/mep3_behavior_tree/assets/strategies/big/.gitkeep b/mep3_behavior_tree/assets/strategies/big/.gitkeep deleted file mode 100644 index e69de29bb..000000000 diff --git a/mep3_behavior_tree/assets/strategies/big/florian.xml b/mep3_behavior_tree/assets/strategies/big/florian.xml deleted file mode 100644 index 125bc92ba..000000000 --- a/mep3_behavior_tree/assets/strategies/big/florian.xml +++ /dev/null @@ -1,318 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - purple, yellow - - - [deg] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [deg] - [deg/s] - - - purple, yellow - - - [cm] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [cm] - [cm/s] - - - [rad/s^2] - [m/s^2] - [forward/rotate_relative/rotate_absolute] - [success/drift] - value to pass to motion function, in meters or radians - [rad/s] - [m/s] - - - - - - - Behavior tree - A target pose in format "x;y;theta". - - - [Ohms] - Action server name - [%] - - - points scored, can be negative - unique task name - - - - 0 - disconnect, 1 - connected - 0 - disconnected, 1 - connected, 2 - couldn't disconnect, 3 - couldn't connect, 4 - other - Action server name - - - 0 = unarmed; 1 = armed; 2 = started - - - - - - - - - - - - - - - - diff --git a/mep3_behavior_tree/assets/strategies/big/florian_homologation.xml b/mep3_behavior_tree/assets/strategies/big/florian_homologation.xml deleted file mode 100644 index 90bfd7d3a..000000000 --- a/mep3_behavior_tree/assets/strategies/big/florian_homologation.xml +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/mep3_behavior_tree/assets/strategies/big/test_stuck.xml b/mep3_behavior_tree/assets/strategies/big/test_stuck.xml deleted file mode 100644 index 68d68f001..000000000 --- a/mep3_behavior_tree/assets/strategies/big/test_stuck.xml +++ /dev/null @@ -1,42 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/mep3_behavior_tree/assets/strategies/resistance.xml b/mep3_behavior_tree/assets/strategies/resistance.xml deleted file mode 100644 index 2c145dd98..000000000 --- a/mep3_behavior_tree/assets/strategies/resistance.xml +++ /dev/null @@ -1,317 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -<<<<<<< HEAD - -======= - ->>>>>>> main - - - - - - - - - - - - - - - - - -<<<<<<< HEAD -<<<<<<< HEAD:mep3_behavior_tree/assets/strategies/resistance.xml -======= ->>>>>>> main - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -<<<<<<< HEAD -======= ->>>>>>> main:mep3_behavior_tree/assets/strategies/homologation_resistance.xml -======= ->>>>>>> main - - - - -<<<<<<< HEAD - - - - - - - - - - - - - - - - - - - - - -======= - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - ->>>>>>> main - - - - -<<<<<<< HEAD -======= - - - ->>>>>>> main - - - - - - - - - - - - - - - - - - - - - purple, yellow - - - [deg] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [deg] - [deg/s] - - - purple, yellow - - - [cm] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [cm] - [cm/s] - - - [rad/s^2] - [m/s^2] - [forward/rotate_relative/rotate_absolute] - [success/drift] - value to pass to motion function, in meters or radians - [rad/s] - [m/s] - - - - - - - Behavior tree - A target pose in format "x;y;theta". - - - [Ohms] - Action server name - [%] - - - points scored, can be negative - unique task name - - - - 0 - disconnect, 1 - connected - 0 - disconnected, 1 - connected, 2 - couldn't disconnect, 3 - couldn't connect, 4 - other - Action server name - - - 0 = unarmed; 1 = armed; 2 = started - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/mep3_behavior_tree/assets/strategies/small/.gitkeep b/mep3_behavior_tree/assets/strategies/small/.gitkeep deleted file mode 100644 index e69de29bb..000000000 diff --git a/mep3_behavior_tree/assets/strategies/small/kosta.xml b/mep3_behavior_tree/assets/strategies/small/kosta.xml deleted file mode 100644 index 518559523..000000000 --- a/mep3_behavior_tree/assets/strategies/small/kosta.xml +++ /dev/null @@ -1,680 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - purple, yellow - - - [deg] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [deg] - [deg/s] - - - purple, yellow - - - [cm] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [cm] - [cm/s] - - - [rad/s^2] - [m/s^2] - [forward/rotate_relative/rotate_absolute] - [success/drift] - value to pass to motion function, in meters or radians - [rad/s] - [m/s] - - - - - - - Behavior tree - A target pose in format "x;y;theta". - - - [Ohms] - Action server name - [%] - - - points scored, can be negative - unique task name - - - - 0 - disconnect, 1 - connected - 0 - disconnected, 1 - connected, 2 - couldn't disconnect, 3 - couldn't connect, 4 - other - Action server name - - - 0 = unarmed; 1 = armed; 2 = started - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/mep3_behavior_tree/assets/strategies/small/kosta_homologation.xml b/mep3_behavior_tree/assets/strategies/small/kosta_homologation.xml deleted file mode 100644 index 7286038aa..000000000 --- a/mep3_behavior_tree/assets/strategies/small/kosta_homologation.xml +++ /dev/null @@ -1,53 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/mep3_behavior_tree/assets/strategies/small/kosta_yellow.xml b/mep3_behavior_tree/assets/strategies/small/kosta_yellow.xml deleted file mode 100644 index dc8fa0190..000000000 --- a/mep3_behavior_tree/assets/strategies/small/kosta_yellow.xml +++ /dev/null @@ -1,757 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - purple, yellow - - - [deg] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [deg] - [deg/s] - - - purple, yellow - - - [cm] - 0 - success, 1 - timeout, 2 - other error - Action server name - [s] - [cm] - [cm/s] - - - [rad/s^2] - [m/s^2] - [forward/rotate_relative/rotate_absolute] - [success/drift] - value to pass to motion function, in meters or radians - [rad/s] - [m/s] - - - - - - - Behavior tree - A target pose in format "x;y;theta". - - - [Ohms] - Action server name - [%] - - - points scored, can be negative - unique task name - - - - 0 - disconnect, 1 - connected - 0 - disconnected, 1 - connected, 2 - couldn't disconnect, 3 - couldn't connect, 4 - other - Action server name - - - 0 = unarmed; 1 = armed; 2 = started - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/mep3_behavior_tree/assets/tasks/.gitkeep b/mep3_behavior_tree/assets/tasks/.gitkeep deleted file mode 100644 index e69de29bb..000000000 diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/lift_command_action.hpp b/mep3_behavior_tree/include/mep3_behavior_tree/lift_command_action.hpp deleted file mode 100644 index 0ae9dfe89..000000000 --- a/mep3_behavior_tree/include/mep3_behavior_tree/lift_command_action.hpp +++ /dev/null @@ -1,94 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#ifndef MEP3_BEHAVIOR_TREE__LIFT_COMMAND_ACTION_HPP_ -#define MEP3_BEHAVIOR_TREE__LIFT_COMMAND_ACTION_HPP_ - -#include - -#include "behaviortree_cpp_v3/behavior_tree.h" -#include "behaviortree_cpp_v3/bt_factory.h" -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_msgs/action/dynamixel_command.hpp" - -#define GEAR_RADIUS_CM 15.75 -#define RAD_TO_DEG 180 / 3.14159 - -namespace mep3_behavior_tree -{ -class LiftCommandAction - : public mep3_behavior_tree::BtActionNode -{ -public: - explicit LiftCommandAction( - const std::string & xml_tag_name, const BT::NodeConfiguration & config) - : mep3_behavior_tree::BtActionNode( - xml_tag_name, "lift_command", config) - { - } - - void on_tick() override; - BT::NodeStatus on_success() override; - BT::NodeStatus on_aborted() override; - BT::NodeStatus on_cancelled() override; - - static BT::PortsList providedPorts() - { - return providedBasicPorts( - { - BT::InputPort<_Float64>("height"), - BT::InputPort<_Float64>("velocity"), - BT::InputPort<_Float64>("tolerance"), - BT::InputPort<_Float64>("timeout"), - BT::OutputPort("result") - }); - } -}; - -void LiftCommandAction::on_tick() -{ - _Float64 height, velocity, tolerance, timeout; - - getInput("height", height); - getInput("velocity", velocity); - getInput("tolerance", tolerance); - getInput("timeout", timeout); - - goal_.position = height / GEAR_RADIUS_CM * RAD_TO_DEG; - goal_.velocity = velocity / GEAR_RADIUS_CM * RAD_TO_DEG; - goal_.tolerance = tolerance / GEAR_RADIUS_CM * RAD_TO_DEG; - goal_.timeout = timeout; -} - -BT::NodeStatus LiftCommandAction::on_success() -{ - setOutput("result", 0); - return BT::NodeStatus::SUCCESS; -} - -BT::NodeStatus LiftCommandAction::on_aborted() -{ - setOutput("result", 2); - return BT::NodeStatus::FAILURE; -} - -BT::NodeStatus LiftCommandAction::on_cancelled() -{ - setOutput("result", 2); - return BT::NodeStatus::FAILURE; -} - -} // namespace mep3_behavior_tree - -#endif // MEP3_BEHAVIOR_TREE__LIFT_COMMAND_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/precise_navigate_to_action.hpp b/mep3_behavior_tree/include/mep3_behavior_tree/precise_navigate_to_action.hpp deleted file mode 100644 index 96a5f47eb..000000000 --- a/mep3_behavior_tree/include/mep3_behavior_tree/precise_navigate_to_action.hpp +++ /dev/null @@ -1,114 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#ifndef MEP3_BEHAVIOR_TREE__PRECISE_NAVIGATE_TO_ACTION_HPP_ -#define MEP3_BEHAVIOR_TREE__PRECISE_NAVIGATE_TO_ACTION_HPP_ - -#include -#include -#include - -#include "behaviortree_cpp_v3/behavior_tree.h" -#include "behaviortree_cpp_v3/bt_factory.h" -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_behavior_tree/pose_2d.hpp" -#include "nav2_msgs/action/navigate_to_pose.hpp" - -namespace mep3_behavior_tree -{ - class PreciseNavigateToAction - : public mep3_behavior_tree::BtActionNode - { - public: - explicit PreciseNavigateToAction( - const std::string &xml_tag_name, const BT::NodeConfiguration &config) - : mep3_behavior_tree::BtActionNode( - xml_tag_name, "precise_navigate_to_pose", config) - { - if (!getInput("goal", this->goal)) - throw BT::RuntimeError( - "PreciseNavigate action requires 'goal' argument" - ); - getInput("behavior_tree", this->behavior_tree); - - // Warning: might break for a still undetermined reason - std::string table = this->config().blackboard->get("table"); - BT::Pose2D goal_offset; - if (table.length() > 0 && getInput("goal_" + table, goal_offset)) { - goal += goal_offset; - } - - if (g_StrategyMirror.requires_mirroring(mirror_)) { - g_StrategyMirror.mirror_pose(goal); - } - } - - void on_tick() override; - BT::NodeStatus on_success() override; - - static BT::PortsList providedPorts() - { - // Static parameters - BT::PortsList port_list = providedBasicPorts({ - BT::InputPort("goal"), - BT::InputPort("behavior_tree") - }); - - // Dynamic parameters - for (std::string table : g_InputPortNameFactory.get_names()) { - port_list.insert( - BT::InputPort("goal_" + table) - ); - } - - return port_list; - } - - private: - BT::Pose2D goal; - std::string behavior_tree; - }; - - void PreciseNavigateToAction::on_tick() - { - std::cout << "Precise navigating to x=" << goal.x \ - << " y=" << goal.y \ - << " θ=" << goal.theta << "°" << std::endl; - - goal_.pose.header.frame_id = "map"; - goal_.pose.header.stamp = node_->get_clock()->now(); - - // Position - goal_.pose.pose.position.x = goal.x; - goal_.pose.pose.position.y = goal.y; - goal_.behavior_tree = behavior_tree; - - // Orientation (yaw) - // Convert deg to rad - double theta = goal.theta * M_PI / 180.0; - // https://math.stackexchange.com/a/1972382 - goal_.pose.pose.orientation.w = std::cos(theta / 2.0); - goal_.pose.pose.orientation.z = std::sin(theta / 2.0); - } - - BT::NodeStatus PreciseNavigateToAction::on_success() - { - std::cout << "Navigation succesful " << std::endl; - - return BT::NodeStatus::SUCCESS; - } - -} // namespace mep3_behavior_tree - -#endif // MEP3_BEHAVIOR_TREE__PRECISE_NAVIGATE_TO_ACTION_HPP_ diff --git a/mep3_behavior_tree/include/mep3_behavior_tree/resistance_meter_action.hpp b/mep3_behavior_tree/include/mep3_behavior_tree/resistance_meter_action.hpp deleted file mode 100644 index 22cd28244..000000000 --- a/mep3_behavior_tree/include/mep3_behavior_tree/resistance_meter_action.hpp +++ /dev/null @@ -1,127 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#ifndef MEP3_BEHAVIOR_TREE__RESISTANCE_METER_ACTION_HPP_ -#define MEP3_BEHAVIOR_TREE__RESISTANCE_METER_ACTION_HPP_ - -#include -#include - -#include "mep3_behavior_tree/bt_action_node.hpp" -#include "mep3_behavior_tree/table_specific_ports.hpp" -#include "mep3_behavior_tree/team_color_strategy_mirror.hpp" -#include "mep3_msgs/action/resistance_meter.hpp" - -#include "behaviortree_cpp_v3/behavior_tree.h" -#include "behaviortree_cpp_v3/bt_factory.h" - -namespace mep3_behavior_tree -{ - - class ResistanceMeterAction - : public mep3_behavior_tree::BtActionNode - { - public: - explicit ResistanceMeterAction( - const std::string &name, - const BT::NodeConfiguration &config) : - mep3_behavior_tree::BtActionNode( - name, "resistance_meter", config - ) - { - if (!getInput("resistance", this->expected)) - throw BT::RuntimeError( - "ResistanceMeter action requires 'resistance' argument" - ); - if (!getInput("tolerance", this->tolerance)) - throw BT::RuntimeError( - "ResistanceMeter action requires 'tolerance' argument" - ); - - tolerance /= 100.0; - - std::string table = this->config().blackboard->get("table"); - int32_t resistance_offset; - if (table.length() > 0 && getInput("resistance_" + table, resistance_offset)) { - expected += resistance_offset; - } - - if (g_StrategyMirror.requires_mirroring(mirror_)) { - g_StrategyMirror.mirror_resistance(expected); - } - } - - void on_tick() override; - BT::NodeStatus on_success() override; - BT::NodeStatus on_aborted() override; - BT::NodeStatus on_cancelled() override; - - static BT::PortsList providedPorts() - { - // Static parameters - BT::PortsList port_list = providedBasicPorts({ - BT::InputPort("resistance"), - BT::InputPort<_Float32>("tolerance"), - }); - - // Dynamic parameters - for (std::string table : g_InputPortNameFactory.get_names()) { - port_list.insert( - BT::InputPort("resistance_" + table) - ); - } - - return port_list; - } - - private: - int32_t measured, expected; - _Float32 tolerance; - }; - - void ResistanceMeterAction::on_tick() - { - std::cout << "Measuring resistance on '" \ - << this->action_name_ << "'" << std::endl; - } - - BT::NodeStatus ResistanceMeterAction::on_success() - { - int32_t measured = result_.result->resistance; - std::cout << "Expected " << expected << "±" \ - << tolerance * expected << "Ω, " \ - << "measured " << 0 << "Ω" << std::endl; - if ( - measured >= expected * (1.0 - tolerance) && \ - measured <= expected * (1.0 + tolerance) - ) { - return BT::NodeStatus::SUCCESS; - } else { - return BT::NodeStatus::FAILURE; - } - } - - BT::NodeStatus ResistanceMeterAction::on_aborted() - { - return BT::NodeStatus::FAILURE; - } - - BT::NodeStatus ResistanceMeterAction::on_cancelled() - { - return BT::NodeStatus::FAILURE; - } - -} // namespace mep3_behavior_tree - -#endif // MEP3_BEHAVIOR_TREE__RESISTANCE_METER_ACTION_HPP_ diff --git a/mep3_bringup/launch/robot_launch.py b/mep3_bringup/launch/robot_launch.py index ea5e85843..78d219bcc 100644 --- a/mep3_bringup/launch/robot_launch.py +++ b/mep3_bringup/launch/robot_launch.py @@ -1,4 +1,9 @@ -"""Brings up a single robot.""" +# Brings up a single robot. +# +# Example usage: +# +# ros2 launch mep3_bringup robot_launch.py sim:=true color:=yellow namespace:=big strategy:=purple_strategy +# from math import pi import os @@ -27,30 +32,6 @@ 'table2' ] -ANGLE_MIRRORING_BLACKLIST = [ - # Florian (big) - 'box', - 'flipper_left', - 'flipper_right', - # Kosta (small) - 'base', - 'mid', - 'gripper', - 'rail' -] - -SERVER_NAME_MIRRORING_BLACKLIST = [ - # Florian (big) - 'box', - # Kosta (small) - 'base', - 'mid', - 'gripper', - 'rail', - 'fork_left', - 'fork_right' -] - def verify_color(context, *args, **kwargs): if LaunchConfiguration('color').perform(context) \ @@ -91,9 +72,11 @@ def get_initial_pose_transform(namespace, color): executable='static_transform_publisher', output='screen', arguments=[ - str(row_pose[0]), - str(row_pose[1]), '0', - str(row_pose[2]), '0', '0', 'map', 'odom' + '--x', str(row_pose[0]), + '--y', str(row_pose[1]), + '--yaw', str(row_pose[2]), + '--frame-id', 'map', + '--child-frame-id', 'odom' ], namespace=namespace, remappings=[('/tf_static', 'tf_static')], @@ -103,11 +86,8 @@ def get_initial_pose_transform(namespace, color): def generate_launch_description(): - package_dir = get_package_share_directory('mep3_bringup') - use_nav = LaunchConfiguration('nav', default=True) use_behavior_tree = LaunchConfiguration('bt', default=True) - use_regulator = LaunchConfiguration('regulator', default=True) use_simulation = LaunchConfiguration('sim', default=False) # Implementation wise, it would probably be easier to use @@ -122,13 +102,11 @@ def generate_launch_description(): color = LaunchConfiguration('color') table = LaunchConfiguration('table', default='') - nav2_map = os.path.join(package_dir, 'resource', 'map.yml') - set_colorized_output = SetEnvironmentVariable('RCUTILS_COLORIZED_OUTPUT', '1') diffdrive_controller_spawner = Node( package='controller_manager', - executable='spawner.py', + executable='spawner', output='screen', arguments=[ 'diffdrive_controller', @@ -142,8 +120,8 @@ def generate_launch_description(): }]) behavior_tree = Node( - package='mep3_behavior_tree', - executable='mep3_behavior_tree', + package='mep3_behavior', + executable='mep3_behavior', name=['behavior', namespace], output='screen', parameters=[{ @@ -151,9 +129,7 @@ def generate_launch_description(): 'color': color, 'table': table, 'strategy': strategy, - 'predefined_tables': PREDEFINED_TABLE_NAMES, - 'mirror_angle_blacklist': ANGLE_MIRRORING_BLACKLIST, - 'mirror_name_blacklist': SERVER_NAME_MIRRORING_BLACKLIST + 'predefined_tables': PREDEFINED_TABLE_NAMES }], namespace=namespace, condition=launch.conditions.IfCondition(use_behavior_tree)) @@ -163,7 +139,6 @@ def generate_launch_description(): os.path.join(get_package_share_directory('mep3_navigation'), 'launch', 'navigation_launch.py')), launch_arguments=[ - ('map', nav2_map), ('use_sim_time', use_simulation), ('namespace', namespace), ('use_namespace', 'true'), @@ -175,24 +150,9 @@ def generate_launch_description(): ], condition=launch.conditions.IfCondition(use_nav)) - regulator = Node(package='mep3_navigation', - executable='distance_angle_regulator', - output='screen', - parameters=[{ - 'use_sim_time': use_simulation, - }, - [ - get_package_share_directory('mep3_navigation'), - '/params', - '/config_regulator_', namespace, '.yaml' - ]], - namespace=namespace, - remappings=[('/tf_static', 'tf_static'), ('/tf', 'tf')], - condition=launch.conditions.IfCondition(use_regulator)) - driver = IncludeLaunchDescription( PythonLaunchDescriptionSource( - os.path.join(get_package_share_directory('mep3_driver'), 'launch', + os.path.join(get_package_share_directory('mep3_hardware'), 'launch', 'driver_launch.py')), launch_arguments=[('namespace', namespace)], condition=launch.conditions.UnlessCondition(use_simulation)) @@ -202,38 +162,28 @@ def generate_launch_description(): executable='static_transform_publisher', output='screen', arguments=[ - '0', '0', '0.3', - str(pi), '0', '0', 'base_link', 'laser' + '--z', '0.3', + '--yaw', str(-pi/2), + '--frame-id', 'base_link', + '--child-frame-id', 'laser' ], namespace=namespace, remappings=[('/tf_static', 'tf_static')], ) - laser_inflator = Node(package='mep3_navigation', - executable='laser_inflator', - parameters=[{ - 'inflation_radius': 0.05, - 'inflation_angular_step': 0.09 - }], - remappings=[('/tf_static', 'tf_static'), - ('/tf', 'tf'), - ('scan', 'scan_filtered')], - output='screen', - namespace=namespace) - laser_filters = Node(package='laser_filters', - executable='scan_to_scan_filter_chain', - parameters=[ - PathJoinSubstitution([ - get_package_share_directory('mep3_navigation'), - 'params', 'laser_filters.yaml', - ]) - ], - remappings=[('/tf_static', 'tf_static'), - ('/tf', 'tf') - ], - output='screen', - namespace=namespace) + executable='scan_to_scan_filter_chain', + parameters=[ + PathJoinSubstitution([ + get_package_share_directory('mep3_navigation'), + 'params', 'laser_filters.yaml', + ]) + ], + remappings=[('/tf_static', 'tf_static'), + ('/tf', 'tf') + ], + output='screen', + namespace=namespace) domain_bridge_node = Node( package='domain_bridge', @@ -253,7 +203,6 @@ def generate_launch_description(): on_exit_events = [] critical_nodes = [ behavior_tree, - regulator, ] for node in critical_nodes: on_exit_event = RegisterEventHandler( @@ -274,15 +223,11 @@ def generate_launch_description(): # Wheel controller diffdrive_controller_spawner, - # Lidar inflation - laser_inflator, - # Lidar filtering laser_filters, # Navigation 2 nav2, - regulator, tf_base_link_laser, driver, ] + on_exit_events + get_initial_pose_transform(namespace, color)) diff --git a/mep3_bringup/package.xml b/mep3_bringup/package.xml index f717d3660..4dcccb119 100644 --- a/mep3_bringup/package.xml +++ b/mep3_bringup/package.xml @@ -8,6 +8,7 @@ TODO: License declaration domain_bridge + rmw_cyclonedds_cpp ament_copyright ament_flake8 diff --git a/mep3_bringup/setup.cfg b/mep3_bringup/setup.cfg index 0c059d972..56629a1e4 100644 --- a/mep3_bringup/setup.cfg +++ b/mep3_bringup/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/mep3_bringup +script_dir=$base/lib/mep3_bringup [install] -install-scripts=$base/lib/mep3_bringup +install_scripts=$base/lib/mep3_bringup diff --git a/mep3_driver/mep3_driver/lynx_driver.py b/mep3_driver/mep3_driver/lynx_driver.py deleted file mode 100755 index cb84c82d7..000000000 --- a/mep3_driver/mep3_driver/lynx_driver.py +++ /dev/null @@ -1,223 +0,0 @@ -#!/usr/bin/env python3 - -from distutils import command -from functools import partial -from traceback import print_tb - -from mep3_msgs.action import DynamixelCommand -from rclpy.executors import MultiThreadedExecutor - -import rclpy -from rclpy.node import Node - -from rclpy.action import ActionServer, CancelResponse, GoalResponse -from rclpy.callback_groups import ReentrantCallbackGroup - - -DEFAULT_POSITION = 0 # deg -MAX_POSITION = 155 # deg -MIN_POSITION = 0 # deg -DEFAULT_VELOCITY = 10 # deg/s -DEFAULT_TOLERANCE = 5 # deg -DEFAULT_TIMEOUT = 5 # s -""" -Test: -ros2 action send_goal /big/dynamixel_command/lift_motor mep3_msgs/action/DynamixelCommand "position: 22" -""" - -from threading import current_thread, Lock - -import can -import struct -from math import isclose - -SERVOS = [ - {'id': 0, 'name': 'lift_motor', 'model': 'lynx'}, -] - -SERVO_CAN_ID = 0x00006C20 -POLL_PERIOD = 0.2 - - -def scale(val, src, dst): - return ((val - src[0]) / (src[1] - src[0])) * (dst[1] - dst[0]) + dst[0] - - -class LynxServo: - def __init__(self, servo_id, name, model): - self.id = servo_id - self.name = name - self.model = model - - # Values we need to keep track of while Node is active - self.present_position = 0 - self.present_velocity = 0 - - def get_command_data(self, position): - - if position > MAX_POSITION: position = MAX_POSITION - if position < MIN_POSITION: position = MIN_POSITION - position = int(position*10) # Scaling to Lynx protocol - - fmt = '>BHH' - speed = int(37*10) # Scaling to Lynx protocol - - data = [self.id, position, speed] - - binary_data = struct.pack(fmt, *data) - - return binary_data - - -class LynxDriver(Node): - def __init__(self, can_mutex, can_bus): - super().__init__('lynx_driver') - self.__actions = [] - self.servo_list = [] - - self.can_mutex = can_mutex - self.bus = can_bus - - self.rate = self.create_rate(1 / POLL_PERIOD) - - callback_group = ReentrantCallbackGroup() - for servo_config in SERVOS: - new_servo = LynxServo( - servo_id=servo_config['id'], name=servo_config['name'], model=servo_config['model'] - ) - self.servo_list.append(new_servo) - self.__actions.append( - ActionServer( - self, - DynamixelCommand, - f"dynamixel_command/{servo_config['name']}", - execute_callback=partial(self.__handle_dynamixel_command, servo=new_servo), - callback_group=callback_group, - goal_callback=self.__goal_callback, - cancel_callback=self.__cancel_callback - ) - ) - - def __goal_callback(self, _): - return GoalResponse.ACCEPT - - def __cancel_callback(self, _): - return CancelResponse.ACCEPT - - def process_single_command(self, bin_data): - - self.can_mutex.acquire() - - msg = can.Message(arbitration_id=SERVO_CAN_ID, - data=bin_data, - is_extended_id=True) - - try: - self.bus.send(msg) - except can.CanError: - self.get_logger().info("CAN ERROR: Cannot send message over CAN bus. Check if can0 is active.") - - message = self.bus.recv(0.1) # Wait until a message is received or 0.1s - - self.can_mutex.release() - - if message: - ret_val = message - else: - self.get_logger().info("Timeout error for servo response. Check servo connections.") - ret_val = False - - return ret_val - - def __handle_dynamixel_command(self, goal_handle, - servo: LynxServo = None): - self.get_logger().info(str(goal_handle.request)) - self.get_logger().info("Servo ID: " + str(servo.id)) - self.get_logger().info("Thread: " + str(current_thread().name)) - - position = goal_handle.request.position # deg - position += 6 # For some reason Servo doesn't go to 5 or lower - - if not position: - position = 0.1 - - tolerance = goal_handle.request.tolerance # deg - timeout = goal_handle.request.timeout - - if not tolerance: - tolerance = DEFAULT_TOLERANCE - if not timeout: - timeout = DEFAULT_TIMEOUT - - result = DynamixelCommand.Result() - - result.result = 2 # Other error - - if not isclose(position, servo.present_position, - abs_tol=tolerance): - # Send GoalPosition and Poll - if not self.go_to_position(servo, position, - timeout, tolerance): - result.result = 1 # Set to Timeout error - self.get_logger().info("Timeout!!!") - - goal_handle.abort() - return result - - result.result = 0 # There are no errors, return 0 - goal_handle.succeed() - return result - - - def go_to_position(self, servo, position, timeout, tolerance): - status = self.process_single_command( - bin_data=servo.get_command_data(position)) - if not status: - return 0 - - number_of_tries = 0 - - while not isclose(position, servo.present_position, - abs_tol=tolerance): - - self.rate.sleep() - status = self.process_single_command( - bin_data=servo.get_command_data(position)) - - if status: - - fmt = '>BHH' - if len(status.data) == 5: - servo.present_position = float( struct.unpack(fmt, status.data)[1])/10 - servo.present_velocity = float( struct.unpack(fmt, status.data)[2])/10 - self.get_logger().info("Servo responded pos: {}".format(servo.present_position)) - else: - self.get_logger().info("Servo response is not OK") - - - if number_of_tries > (timeout / POLL_PERIOD): - return 0 - - number_of_tries += 1 - - return 1 - - -def main(args=None): - rclpy.init(args=args) - - can_mutex = Lock() - bus = can.ThreadSafeBus(bustype='socketcan', channel='can0', bitrate=500000) - - # Set filters for receiving data - bus.set_filters(filters=[{"can_id": SERVO_CAN_ID, "can_mask": 0x1FFFFFFE, "extended": True}]) - - executor = MultiThreadedExecutor(num_threads=6) - driver = LynxDriver(can_mutex, bus) - executor.add_node(driver) - executor.spin() - rclpy.shutdown() - - -if __name__ == '__main__': - main() diff --git a/mep3_driver/mep3_driver/resistance_meter_driver.py b/mep3_driver/mep3_driver/resistance_meter_driver.py deleted file mode 100755 index 11145275b..000000000 --- a/mep3_driver/mep3_driver/resistance_meter_driver.py +++ /dev/null @@ -1,115 +0,0 @@ -#!/usr/bin/env python3 - -import struct -import can -import math -from functools import partial -from rclpy.action import ActionServer, CancelResponse, GoalResponse -from threading import Lock, current_thread -from mep3_msgs.action import ResistanceMeter -import rclpy -from rclpy.node import Node - - -RESISANCE_METER_CAN_ID = 0x00008D73 -RESISANCE_METER_CAN_MASK = 0x1FFFFFFF -RESISTANCE_METERS = [ - {'name': 'left'}, - {'name': 'right'}, -] - - -def readout_to_resistance(value): - return int(1.2*value - 250) - - -class ResistanceMeterDriver(Node): - def __init__(self, can_mutex, can_bus): - super().__init__('resistance_meter_driver') - self.__actions = [] - self.meter_list = [] - - self.can_mutex = can_mutex - self.bus = can_bus - - for meter in RESISTANCE_METERS: - self.__actions.append( - ActionServer( - self, - ResistanceMeter, - f'resistance_meter/{meter["name"]}', - execute_callback=partial(self.__handle_resistance_meter), - goal_callback=self.__goal_callback, - cancel_callback=self.__cancel_callback - ) - ) - - def __goal_callback(self, _): - return GoalResponse.ACCEPT - - def __cancel_callback(self, _): - return CancelResponse.ACCEPT - - def __handle_resistance_meter(self, goal_handle): - self.get_logger().info(str(goal_handle.request)) - self.get_logger().info("Resistance meter ID: " + str(RESISANCE_METER_CAN_ID)) - self.get_logger().info("Thread: " + str(current_thread().name)) - - result = ResistanceMeter.Result() - resistance = None - - msg = can.Message( - arbitration_id=RESISANCE_METER_CAN_ID, - data=[], # Send an empty message - is_extended_id=True - ) - - self.can_mutex.acquire() - - try: - self.bus.send(msg) - except can.CanError: - self.get_logger().info( - "CAN ERROR: Cannot send message over CAN bus. Check if can0 is active.") - - recv = self.bus.recv(timeout=1) - print(recv) - if recv is not None: - readout = struct.unpack('>>>>>>>VALUE FROM CAN: " + str(readout)) - resistance = readout_to_resistance(readout) - self.get_logger().info("Resistance: " + str(resistance)) - self.get_logger().info("can data resist: " + str(recv)) - - self.can_mutex.release() - - if resistance is None: - result.resistance = 0 - goal_handle.abort() - else: - goal_handle.succeed() - result.resistance = resistance - - return result - - -def main(args=None): - rclpy.init(args=args) - - can_mutex = Lock() - bus = can.ThreadSafeBus(bustype='socketcan', - channel='can0', bitrate=500000) - - # Set filters for receiving data - bus.set_filters(filters=[{ - 'can_id': RESISANCE_METER_CAN_ID, - 'can_mask': RESISANCE_METER_CAN_MASK, - 'extended': True - }]) - driver = ResistanceMeterDriver(can_mutex, bus) - rclpy.spin(driver) - rclpy.shutdown() - - -if __name__ == '__main__': - main() diff --git a/mep3_driver/mep3_driver_ros2_control.xml b/mep3_driver/mep3_driver_ros2_control.xml deleted file mode 100644 index 4d7aee361..000000000 --- a/mep3_driver/mep3_driver_ros2_control.xml +++ /dev/null @@ -1,3 +0,0 @@ - - - diff --git a/mep3_driver/CMakeLists.txt b/mep3_hardware/CMakeLists.txt similarity index 89% rename from mep3_driver/CMakeLists.txt rename to mep3_hardware/CMakeLists.txt index efab91052..9ca22ef8a 100644 --- a/mep3_driver/CMakeLists.txt +++ b/mep3_hardware/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.5) -project(mep3_driver) +project(mep3_hardware) # Default to C99 if(NOT CMAKE_C_STANDARD) @@ -8,7 +8,7 @@ endif() # Default to C++14 if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD 17) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") @@ -46,7 +46,7 @@ ament_target_dependencies( rclcpp_lifecycle ) -pluginlib_export_plugin_description_file(hardware_interface mep3_driver_ros2_control.xml) +pluginlib_export_plugin_description_file(hardware_interface mep3_hardware_ros2_control.xml) add_executable(socketcan_bridge src/socketcan_bridge.cpp) target_include_directories( @@ -101,11 +101,9 @@ install( # Python install(PROGRAMS - mep3_driver/lynx_driver.py - mep3_driver/vacuum_pump_driver.py - mep3_driver/cinch_driver.py - mep3_driver/lcd_driver.py - mep3_driver/resistance_meter_driver.py + mep3_hardware/vacuum_pump_driver.py + mep3_hardware/cinch_driver.py + mep3_hardware/lcd_driver.py DESTINATION lib/${PROJECT_NAME} ) ament_python_install_package(${PROJECT_NAME} diff --git a/mep3_driver/README.md b/mep3_hardware/README.md similarity index 76% rename from mep3_driver/README.md rename to mep3_hardware/README.md index 21856dda4..b405f60d6 100644 --- a/mep3_driver/README.md +++ b/mep3_hardware/README.md @@ -4,5 +4,5 @@ Creates ROS 2 interface on top of the physical robot. It includes the `ros2_cont Run the driver: ```bash -ros2 launch mep3_driver driver_launch.py +ros2 launch mep3_hardware driver_launch.py ``` diff --git a/mep3_driver/include/mep3_driver/dynamixel_driver.hpp b/mep3_hardware/include/mep3_hardware/dynamixel_driver.hpp similarity index 89% rename from mep3_driver/include/mep3_driver/dynamixel_driver.hpp rename to mep3_hardware/include/mep3_hardware/dynamixel_driver.hpp index 92e5d3521..796eddd62 100644 --- a/mep3_driver/include/mep3_driver/dynamixel_driver.hpp +++ b/mep3_hardware/include/mep3_hardware/dynamixel_driver.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MEP3_DRIVER__DYNAMIXEL_DRIVER_HPP_ -#define MEP3_DRIVER__DYNAMIXEL_DRIVER_HPP_ +#ifndef MEP3_HARDWARE__DYNAMIXEL_DRIVER_HPP_ +#define MEP3_HARDWARE__DYNAMIXEL_DRIVER_HPP_ #include #include @@ -27,11 +27,11 @@ #define DEG2RAD(x) (x * M_PI / 180.0) -#include "mep3_driver/simple_action_server.hpp" +#include "mep3_hardware/simple_action_server.hpp" #include "mep3_msgs/action/dynamixel_command.hpp" #include "rclcpp/rclcpp.hpp" -namespace mep3_driver +namespace mep3_hardware { class DynamixelDriver : public rclcpp::Node { @@ -67,6 +67,6 @@ class DynamixelDriver : public rclcpp::Node int32_t velocity_to_value(uint8_t id, float velocity); }; -} // namespace mep3_driver +} // namespace mep3_hardware -#endif // MEP3_DRIVER__DYNAMIXEL_DRIVER_HPP_ +#endif // MEP3_HARDWARE__DYNAMIXEL_DRIVER_HPP_ diff --git a/mep3_driver/include/mep3_driver/motion_board_driver.hpp b/mep3_hardware/include/mep3_hardware/motion_board_driver.hpp similarity index 93% rename from mep3_driver/include/mep3_driver/motion_board_driver.hpp rename to mep3_hardware/include/mep3_hardware/motion_board_driver.hpp index fbd48417a..07a7b7354 100644 --- a/mep3_driver/include/mep3_driver/motion_board_driver.hpp +++ b/mep3_hardware/include/mep3_hardware/motion_board_driver.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MEP3_DRIVER__MOTION_BOARD_DRIVER_HPP_ -#define MEP3_DRIVER__MOTION_BOARD_DRIVER_HPP_ +#ifndef MEP3_HARDWARE__MOTION_BOARD_DRIVER_HPP_ +#define MEP3_HARDWARE__MOTION_BOARD_DRIVER_HPP_ extern "C" { #include // CAN network layer definitions @@ -28,7 +28,7 @@ extern "C" { #include #include -namespace mep3_driver +namespace mep3_hardware { class MotionBoardDriver { @@ -90,6 +90,6 @@ class MotionBoardDriver void set_ki_angular(float val); void set_kd_angular(float val); }; -} // namespace mep3_driver +} // namespace mep3_hardware -#endif // MEP3_DRIVER__MOTION_BOARD_DRIVER_HPP_ +#endif // MEP3_HARDWARE__MOTION_BOARD_DRIVER_HPP_ diff --git a/mep3_driver/include/mep3_driver/robot_hardware_interface.hpp b/mep3_hardware/include/mep3_hardware/robot_hardware_interface.hpp similarity index 67% rename from mep3_driver/include/mep3_driver/robot_hardware_interface.hpp rename to mep3_hardware/include/mep3_hardware/robot_hardware_interface.hpp index 1020a0aeb..84d49f7f8 100644 --- a/mep3_driver/include/mep3_driver/robot_hardware_interface.hpp +++ b/mep3_hardware/include/mep3_hardware/robot_hardware_interface.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MEP3_DRIVER__ROBOT_HARDWARE_INTERFACE_HPP_ -#define MEP3_DRIVER__ROBOT_HARDWARE_INTERFACE_HPP_ +#ifndef MEP3_HARDWARE__ROBOT_HARDWARE_INTERFACE_HPP_ +#define MEP3_HARDWARE__ROBOT_HARDWARE_INTERFACE_HPP_ #include @@ -25,18 +25,18 @@ #define POW2(N) (1UL << (N)) -namespace mep3_driver +namespace mep3_hardware { class RobotHardwareInterface : public hardware_interface::SystemInterface { public: - CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; - CallbackReturn on_activate(const rclcpp_lifecycle::State &) override; - CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) override; + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_init(const hardware_interface::HardwareInfo & info) override; + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override; + rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) override; std::vector export_state_interfaces() override; std::vector export_command_interfaces() override; - hardware_interface::return_type read() override; - hardware_interface::return_type write() override; + hardware_interface::return_type read(const rclcpp::Time &/*time*/, const rclcpp::Duration &/*period*/) override; + hardware_interface::return_type write(const rclcpp::Time &/*time*/, const rclcpp::Duration &/*period*/) override; private: double left_wheel_velocity_command_; @@ -60,6 +60,6 @@ class RobotHardwareInterface : public hardware_interface::SystemInterface MotionBoardDriver motion_board_; }; -} // namespace mep3_driver +} // namespace mep3_hardware -#endif // MEP3_DRIVER__ROBOT_HARDWARE_INTERFACE_HPP_ +#endif // MEP3_HARDWARE__ROBOT_HARDWARE_INTERFACE_HPP_ diff --git a/mep3_driver/include/mep3_driver/simple_action_server.hpp b/mep3_hardware/include/mep3_hardware/simple_action_server.hpp similarity index 100% rename from mep3_driver/include/mep3_driver/simple_action_server.hpp rename to mep3_hardware/include/mep3_hardware/simple_action_server.hpp diff --git a/mep3_driver/include/mep3_driver/socketcan_bridge.hpp b/mep3_hardware/include/mep3_hardware/socketcan_bridge.hpp similarity index 90% rename from mep3_driver/include/mep3_driver/socketcan_bridge.hpp rename to mep3_hardware/include/mep3_hardware/socketcan_bridge.hpp index 1b3ac449a..aef990bfe 100644 --- a/mep3_driver/include/mep3_driver/socketcan_bridge.hpp +++ b/mep3_hardware/include/mep3_hardware/socketcan_bridge.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MEP3_DRIVER__SOCKETCAN_BRIDGE_HPP_ -#define MEP3_DRIVER__SOCKETCAN_BRIDGE_HPP_ +#ifndef MEP3_HARDWARE__SOCKETCAN_BRIDGE_HPP_ +#define MEP3_HARDWARE__SOCKETCAN_BRIDGE_HPP_ extern "C" { #include // CAN network layer definitions @@ -32,7 +32,7 @@ extern "C" { #include "can_msgs/msg/frame.hpp" #include "rclcpp/rclcpp.hpp" -namespace mep3_driver +namespace mep3_hardware { class Bridge : public rclcpp::Node { @@ -58,6 +58,6 @@ class Bridge : public rclcpp::Node std::thread canbus_receive_thread_; }; -} // namespace mep3_driver +} // namespace mep3_hardware -#endif // MEP3_DRIVER__SOCKETCAN_BRIDGE_HPP_ +#endif // MEP3_HARDWARE__SOCKETCAN_BRIDGE_HPP_ diff --git a/mep3_driver/launch/driver_launch.py b/mep3_hardware/launch/hardware_launch.py similarity index 77% rename from mep3_driver/launch/driver_launch.py rename to mep3_hardware/launch/hardware_launch.py index 6c0b3554d..8fe0c353a 100644 --- a/mep3_driver/launch/driver_launch.py +++ b/mep3_hardware/launch/hardware_launch.py @@ -4,13 +4,12 @@ from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, OpaqueFunction +from launch.actions import OpaqueFunction from launch.substitutions import LaunchConfiguration, PythonExpression from launch_ros.actions import Node from launch.conditions import IfCondition - def enable_can_interface(): is_can_up = False if os.path.isfile('/sys/class/net/can0/operstate'): @@ -27,13 +26,13 @@ def enable_can_interface(): def launch_setup(context, *args, **kwargs): - package_dir = get_package_share_directory('mep3_driver') - bringup_dir = os.path.join(get_package_share_directory('mep3_bringup')) + package_dir = get_package_share_directory('mep3_hardware') namespace = LaunchConfiguration('namespace', default='big') performed_namespace = namespace.perform(context) - controller_params_file = os.path.join(get_package_share_directory('mep3_bringup'), 'resource', f'ros2_control_{performed_namespace}.yaml') + controller_params_file = os.path.join(get_package_share_directory( + 'mep3_bringup'), 'resource', f'ros2_control_{performed_namespace}.yaml') robot_description = pathlib.Path(os.path.join(package_dir, 'resource', f'config_{performed_namespace}.urdf')).read_text() dynamixel_config = os.path.join(package_dir, 'resource', f'dynamixel_config_{performed_namespace}.yaml') @@ -56,32 +55,25 @@ def launch_setup(context, *args, **kwargs): ) socketcan_bridge = Node( - package='mep3_driver', + package='mep3_hardware', executable='socketcan_bridge', output='screen', namespace=namespace ) cinch_driver = Node( - package='mep3_driver', + package='mep3_hardware', executable='cinch_driver.py', output='screen' ) pumps_driver = Node( - package='mep3_driver', + package='mep3_hardware', executable='vacuum_pump_driver.py', output='screen', namespace=namespace ) - resistance_driver = Node( - package='mep3_driver', - executable='resistance_meter_driver.py', - output='screen', - namespace=namespace - ) - lidar_rplidar = Node( package='rplidar_ros', executable='rplidar_composition', @@ -92,11 +84,10 @@ def launch_setup(context, *args, **kwargs): }], output='screen', namespace=namespace, - # condition=IfCondition(PythonExpression(["'", namespace, "' == 'small'"])) ) dynamixel_driver = Node( - package='mep3_driver', + package='mep3_hardware', executable='dynamixel_driver', parameters=[dynamixel_config], output='screen', @@ -104,29 +95,20 @@ def launch_setup(context, *args, **kwargs): ) lcd_driver = Node( - package='mep3_driver', + package='mep3_hardware', executable='lcd_driver.py', output='screen', condition=IfCondition(PythonExpression(["'", namespace, "' == 'small'"])) ) - lynxs_driver = Node( - package='mep3_driver', - executable='lynx_driver.py', - output='screen', - namespace=namespace - ) - return [ controller_manager_node, socketcan_bridge, cinch_driver, lidar_rplidar, pumps_driver, - resistance_driver, dynamixel_driver, - lcd_driver, - lynxs_driver, + lcd_driver ] diff --git a/mep3_driver/mep3_driver/__init__.py b/mep3_hardware/mep3_hardware/__init__.py similarity index 100% rename from mep3_driver/mep3_driver/__init__.py rename to mep3_hardware/mep3_hardware/__init__.py diff --git a/mep3_driver/mep3_driver/cinch_driver.py b/mep3_hardware/mep3_hardware/cinch_driver.py similarity index 99% rename from mep3_driver/mep3_driver/cinch_driver.py rename to mep3_hardware/mep3_hardware/cinch_driver.py index 226eafc70..ee2174527 100755 --- a/mep3_driver/mep3_driver/cinch_driver.py +++ b/mep3_hardware/mep3_hardware/cinch_driver.py @@ -22,7 +22,6 @@ def process_cinch_state(self): self.__start_cinch.wait_for_press() self.__publisher.publish(Int8(data=1)) rclpy.spin_once(self, timeout_sec=0) - self.__start_cinch.wait_for_release() self.__publisher.publish(Int8(data=2)) diff --git a/mep3_driver/mep3_driver/lcd_driver.py b/mep3_hardware/mep3_hardware/lcd_driver.py similarity index 93% rename from mep3_driver/mep3_driver/lcd_driver.py rename to mep3_hardware/mep3_hardware/lcd_driver.py index 89ffda29a..755ce2fc0 100755 --- a/mep3_driver/mep3_driver/lcd_driver.py +++ b/mep3_hardware/mep3_hardware/lcd_driver.py @@ -30,8 +30,8 @@ def display_pts(self, p): def listener_callback(self, msg): - #if msg.task not in self.__completed_tasks: - if True: # add always + # if msg.task not in self.__completed_tasks: + if True: # add always self.__score += msg.points self.__completed_tasks.add(msg.task) self.get_logger().info( @@ -48,6 +48,8 @@ def listener_callback(self, msg): self.display_pts(self.__score) self.get_logger().info( 'Current score: %i points' % self.__score) + + def main(args=None): rclpy.init(args=args) diff --git a/mep3_driver/mep3_driver/vacuum_pump_driver.py b/mep3_hardware/mep3_hardware/vacuum_pump_driver.py similarity index 100% rename from mep3_driver/mep3_driver/vacuum_pump_driver.py rename to mep3_hardware/mep3_hardware/vacuum_pump_driver.py diff --git a/mep3_hardware/mep3_hardware_ros2_control.xml b/mep3_hardware/mep3_hardware_ros2_control.xml new file mode 100644 index 000000000..3f72d597a --- /dev/null +++ b/mep3_hardware/mep3_hardware_ros2_control.xml @@ -0,0 +1,3 @@ + + + diff --git a/mep3_driver/package.xml b/mep3_hardware/package.xml similarity index 97% rename from mep3_driver/package.xml rename to mep3_hardware/package.xml index 9fe57cbbe..52786bd49 100644 --- a/mep3_driver/package.xml +++ b/mep3_hardware/package.xml @@ -1,7 +1,7 @@ - mep3_driver + mep3_hardware 0.0.0 TODO: Package description lukic diff --git a/mep3_driver/resource/config_big.urdf b/mep3_hardware/resource/config_big.urdf similarity index 92% rename from mep3_driver/resource/config_big.urdf rename to mep3_hardware/resource/config_big.urdf index ad8f8f5b5..fa0b506e4 100644 --- a/mep3_driver/resource/config_big.urdf +++ b/mep3_hardware/resource/config_big.urdf @@ -2,7 +2,7 @@ - mep3_driver::RobotHardwareInterface + mep3_hardware::RobotHardwareInterface 90.0 1.0 2.0 diff --git a/mep3_driver/resource/config_small.urdf b/mep3_hardware/resource/config_small.urdf similarity index 92% rename from mep3_driver/resource/config_small.urdf rename to mep3_hardware/resource/config_small.urdf index 11ffb2a97..92f35ddc9 100644 --- a/mep3_driver/resource/config_small.urdf +++ b/mep3_hardware/resource/config_small.urdf @@ -2,7 +2,7 @@ - mep3_driver::RobotHardwareInterface + mep3_hardware::RobotHardwareInterface 170.0 2.0 80.0 diff --git a/mep3_driver/resource/dynamixel_config_big.yaml b/mep3_hardware/resource/dynamixel_config_big.yaml similarity index 100% rename from mep3_driver/resource/dynamixel_config_big.yaml rename to mep3_hardware/resource/dynamixel_config_big.yaml diff --git a/mep3_driver/resource/dynamixel_config_small.yaml b/mep3_hardware/resource/dynamixel_config_small.yaml similarity index 100% rename from mep3_driver/resource/dynamixel_config_small.yaml rename to mep3_hardware/resource/dynamixel_config_small.yaml diff --git a/mep3_driver/src/dynamixel_driver.cpp b/mep3_hardware/src/dynamixel_driver.cpp similarity index 98% rename from mep3_driver/src/dynamixel_driver.cpp rename to mep3_hardware/src/dynamixel_driver.cpp index 83b529991..5b7569280 100644 --- a/mep3_driver/src/dynamixel_driver.cpp +++ b/mep3_hardware/src/dynamixel_driver.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mep3_driver/dynamixel_driver.hpp" +#include "mep3_hardware/dynamixel_driver.hpp" #include #include @@ -24,7 +24,7 @@ using std::placeholders::_1; using namespace std::chrono_literals; -namespace mep3_driver +namespace mep3_hardware { DynamixelDriver::DynamixelDriver(const rclcpp::NodeOptions & options) : Node("dynamixel_driver", options) @@ -302,7 +302,7 @@ void DynamixelDriver::control_loop() prev_torque_enabled = torque_enabled; } -} // namespace mep3_driver +} // namespace mep3_hardware int main(int argc, char * argv[]) { @@ -310,7 +310,7 @@ int main(int argc, char * argv[]) rclcpp::ExecutorOptions options; rclcpp::executors::MultiThreadedExecutor executor( options, (size_t)12, false, std::chrono::nanoseconds(-1)); - auto node = std::make_shared(); + auto node = std::make_shared(); executor.add_node(node); executor.spin(); diff --git a/mep3_driver/src/motion_board_driver.cpp b/mep3_hardware/src/motion_board_driver.cpp similarity index 98% rename from mep3_driver/src/motion_board_driver.cpp rename to mep3_hardware/src/motion_board_driver.cpp index c33ce3d0c..34139056f 100644 --- a/mep3_driver/src/motion_board_driver.cpp +++ b/mep3_hardware/src/motion_board_driver.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mep3_driver/motion_board_driver.hpp" +#include "mep3_hardware/motion_board_driver.hpp" #include #include #include #include -namespace mep3_driver +namespace mep3_hardware { MotionBoardDriver::MotionBoardDriver() { @@ -259,4 +259,4 @@ void MotionBoardDriver::set_kd_angular(float val) write(canbus_socket_, &frame, sizeof(struct can_frame)); } -} // namespace mep3_driver +} // namespace mep3_hardware diff --git a/mep3_driver/src/robot_hardware_interface.cpp b/mep3_hardware/src/robot_hardware_interface.cpp similarity index 86% rename from mep3_driver/src/robot_hardware_interface.cpp rename to mep3_hardware/src/robot_hardware_interface.cpp index 1b1076e75..706dee0ff 100644 --- a/mep3_driver/src/robot_hardware_interface.cpp +++ b/mep3_hardware/src/robot_hardware_interface.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mep3_driver/robot_hardware_interface.hpp" +#include "mep3_hardware/robot_hardware_interface.hpp" #include #include @@ -22,9 +22,9 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "rclcpp/rclcpp.hpp" -namespace mep3_driver +namespace mep3_hardware { -CallbackReturn RobotHardwareInterface::on_init(const hardware_interface::HardwareInfo & info) +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotHardwareInterface::on_init(const hardware_interface::HardwareInfo & info) { if (hardware_interface::SystemInterface::on_init(info) != CallbackReturn::SUCCESS) { return CallbackReturn::ERROR; @@ -48,7 +48,7 @@ CallbackReturn RobotHardwareInterface::on_init(const hardware_interface::Hardwar return CallbackReturn::SUCCESS; } -CallbackReturn RobotHardwareInterface::on_activate(const rclcpp_lifecycle::State &) +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotHardwareInterface::on_activate(const rclcpp_lifecycle::State &) { // init variables left_wheel_velocity_command_ = 0; @@ -64,7 +64,7 @@ CallbackReturn RobotHardwareInterface::on_activate(const rclcpp_lifecycle::State int board_init_status = motion_board_.init(); if (board_init_status != 0) { RCLCPP_FATAL( - rclcpp::get_logger("mep3_driver"), + rclcpp::get_logger("mep3_hardware"), "Motion board low lever driver init failed! Is 'can0' up?\n"); return CallbackReturn::ERROR; } @@ -81,7 +81,7 @@ CallbackReturn RobotHardwareInterface::on_activate(const rclcpp_lifecycle::State return CallbackReturn::SUCCESS; } -CallbackReturn RobotHardwareInterface::on_deactivate(const rclcpp_lifecycle::State &) +rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn RobotHardwareInterface::on_deactivate(const rclcpp_lifecycle::State &) { motion_board_.halt(); @@ -113,7 +113,7 @@ RobotHardwareInterface::export_command_interfaces() return interfaces; } -hardware_interface::return_type RobotHardwareInterface::read() +hardware_interface::return_type RobotHardwareInterface::read(const rclcpp::Time &/*time*/, const rclcpp::Duration &/*period*/) { // Read encoder data from the robot int32_t tmp_left, tmp_right; @@ -159,7 +159,7 @@ hardware_interface::return_type RobotHardwareInterface::read() return hardware_interface::return_type::OK; } -hardware_interface::return_type RobotHardwareInterface::write() +hardware_interface::return_type RobotHardwareInterface::write(const rclcpp::Time &/*time*/, const rclcpp::Duration &/*period*/) { // Send left and right wheel velocity commands to the robot @@ -172,9 +172,9 @@ hardware_interface::return_type RobotHardwareInterface::write() // TODO(angstrem98): Publish setpoints on topic. /*RCLCPP_INFO( - rclcpp::get_logger("mep3_driver"), "Setpoint left rad/s: %lf", left_wheel_velocity_command_); + rclcpp::get_logger("mep3_hardware"), "Setpoint left rad/s: %lf", left_wheel_velocity_command_); RCLCPP_INFO( - rclcpp::get_logger("mep3_driver"), "Setpoint right rad/s: %lf\n", + rclcpp::get_logger("mep3_hardware"), "Setpoint right rad/s: %lf\n", right_wheel_velocity_command_);*/ // const int16_t speed_increments_left = (int16_t)round(speed_double_left); @@ -189,7 +189,7 @@ hardware_interface::return_type RobotHardwareInterface::write() return hardware_interface::return_type::OK; } -} // namespace mep3_driver +} // namespace mep3_hardware #include "pluginlib/class_list_macros.hpp" -PLUGINLIB_EXPORT_CLASS(mep3_driver::RobotHardwareInterface, hardware_interface::SystemInterface) +PLUGINLIB_EXPORT_CLASS(mep3_hardware::RobotHardwareInterface, hardware_interface::SystemInterface) diff --git a/mep3_driver/src/socketcan_bridge.cpp b/mep3_hardware/src/socketcan_bridge.cpp similarity index 96% rename from mep3_driver/src/socketcan_bridge.cpp rename to mep3_hardware/src/socketcan_bridge.cpp index ec3f1b9dd..8a12968c6 100644 --- a/mep3_driver/src/socketcan_bridge.cpp +++ b/mep3_hardware/src/socketcan_bridge.cpp @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "mep3_driver/socketcan_bridge.hpp" +#include "mep3_hardware/socketcan_bridge.hpp" #include #include using std::placeholders::_1; -namespace mep3_driver +namespace mep3_hardware { Bridge::Bridge(const rclcpp::NodeOptions & options) : Node("socketcan_bridge", options) { @@ -140,12 +140,12 @@ int Bridge::init(std::string interface_name) return 0; } -} // namespace mep3_driver +} // namespace mep3_hardware int main(int argc, char * argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; diff --git a/mep3_msgs/CMakeLists.txt b/mep3_msgs/CMakeLists.txt index 8f664dd7a..b27cf79c0 100644 --- a/mep3_msgs/CMakeLists.txt +++ b/mep3_msgs/CMakeLists.txt @@ -6,9 +6,9 @@ if(NOT CMAKE_C_STANDARD) set(CMAKE_C_STANDARD 99) endif() -# Default to C++14 +# Default to C++17 if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD 17) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") @@ -23,7 +23,6 @@ find_package(geometry_msgs REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "action/DynamixelCommand.action" "action/MotionCommand.action" - "action/ResistanceMeter.action" "msgs/Scoreboard.msg" "action/VacuumPumpCommand.action" "msgs/TemporalObstacle.msg" diff --git a/mep3_msgs/action/ResistanceMeter.action b/mep3_msgs/action/ResistanceMeter.action deleted file mode 100644 index d8238a22f..000000000 --- a/mep3_msgs/action/ResistanceMeter.action +++ /dev/null @@ -1,3 +0,0 @@ ---- -int32 resistance # Ohms ---- diff --git a/mep3_navigation/CMakeLists.txt b/mep3_navigation/CMakeLists.txt index d73cf4de9..1975bd94a 100644 --- a/mep3_navigation/CMakeLists.txt +++ b/mep3_navigation/CMakeLists.txt @@ -44,52 +44,6 @@ find_package(laser_filters REQUIRED) find_package(diagnostic_msgs REQUIRED) include_directories(include) - -# Distance angle regulator -add_executable(distance_angle_regulator - src/distance_angle/distance_angle_regulator.cpp - src/distance_angle/pid_regulator.c - src/distance_angle/motion_profile.cpp -) - -target_link_libraries(distance_angle_regulator ruckig::ruckig) - -ament_target_dependencies(distance_angle_regulator - rclcpp - rclcpp_action - rclcpp_components - nav_msgs - nav2_msgs - nav2_util - nav2_core - nav_2d_utils - nav_2d_msgs - geometry_msgs - mep3_msgs - std_msgs - ruckig - tf2 - tf2_ros - can_msgs -) -### - -# Laser inflator with scan constraining -add_executable(laser_inflator src/laser_inflator/laser_inflator.cpp) -target_include_directories( - laser_inflator - PRIVATE - include -) - -ament_target_dependencies( - laser_inflator - rclcpp - sensor_msgs - geometry_msgs - tf2 - tf2_ros -) ### set(dependencies @@ -113,16 +67,6 @@ ament_target_dependencies(regulated_pure_pursuit_controller ${dependencies} ) -# BT condition -add_library(nav2_globally_updated_goal_condition_bt_node SHARED src/plugins/condition/globally_updated_goal_condition.cpp) -ament_target_dependencies(nav2_globally_updated_goal_condition_bt_node ${dependencies}) -target_compile_definitions(nav2_globally_updated_goal_condition_bt_node PRIVATE BT_PLUGIN_EXPORT) -install(TARGETS nav2_globally_updated_goal_condition_bt_node - ARCHIVE DESTINATION lib - LIBRARY DESTINATION lib - RUNTIME DESTINATION bin -) - # temporal_obstacle_layer add_library( temporal_obstacle_layer @@ -153,16 +97,6 @@ install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) install(DIRECTORY params DESTINATION share/${PROJECT_NAME}) install(DIRECTORY behavior_trees DESTINATION share/${PROJECT_NAME}) -install(TARGETS - distance_angle_regulator - DESTINATION lib/${PROJECT_NAME} -) - -install( - TARGETS laser_inflator - DESTINATION lib/${PROJECT_NAME} -) - install(TARGETS regulated_pure_pursuit_controller DESTINATION lib/${PROJECT_NAME} diff --git a/mep3_navigation/include/mep3_navigation/distance_angle/distance_angle_regulator.hpp b/mep3_navigation/include/mep3_navigation/distance_angle/distance_angle_regulator.hpp deleted file mode 100644 index e46ccac06..000000000 --- a/mep3_navigation/include/mep3_navigation/distance_angle/distance_angle_regulator.hpp +++ /dev/null @@ -1,160 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#ifndef MEP3_NAVIGATION__DISTANCE_ANGLE__DISTANCE_ANGLE_REGULATOR_HPP_ -#define MEP3_NAVIGATION__DISTANCE_ANGLE__DISTANCE_ANGLE_REGULATOR_HPP_ - -#define RUN_EACH_NTH_CYCLES(counter_type, nth, run) \ - { \ - static counter_type _cycle_ = 0; \ - if (nth > 0 && ++_cycle_ >= nth) { \ - _cycle_ = 0; \ - run; \ - } \ - } - -#include -#include -#include -#include -#include -#include - -extern "C" { -#include "mep3_navigation/distance_angle/pid_regulator.h" -} - -#include "geometry_msgs/msg/pose2_d.hpp" -#include "geometry_msgs/msg/twist.hpp" -#include "mep3_msgs/action/motion_command.hpp" -#include "std_msgs/msg/float64.hpp" -#include "mep3_navigation/distance_angle/motion_profile.hpp" -#include "nav2_costmap_2d/costmap_topic_collision_checker.hpp" -#include "nav2_msgs/action/navigate_to_pose.hpp" -#include "mep3_navigation/simple_action_server/simple_action_server.hpp" -#include "nav_msgs/msg/odometry.hpp" -#include "rcl_interfaces/msg/set_parameters_result.hpp" -#include "rclcpp/rclcpp.hpp" -#include "ruckig/ruckig.hpp" -#include "std_msgs/msg/string.hpp" -#include "tf2/exceptions.h" -#include "tf2/utils.h" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" -#include "can_msgs/msg/frame.hpp" - -using std::placeholders::_1; - -template -int sgn(T val) -{ - return val >= T(0) ? T(1) : T(-1); -} - -class DistanceAngleRegulator : public rclcpp::Node -{ -public: - explicit DistanceAngleRegulator(const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); - rcl_interfaces::msg::SetParametersResult parameters_callback( - const std::vector & parameters); - void init(); - ~DistanceAngleRegulator(); - using NavigatoToPoseT = nav2_msgs::action::NavigateToPose; - using NavigateToPoseServer = nav2_util::SimpleActionServer; - using MotionCommandT = mep3_msgs::action::MotionCommand; - using MotionCommandServer = nav2_util::SimpleActionServer; - -private: - rclcpp::Subscription::SharedPtr odometry_subscription_; - rclcpp::Publisher::SharedPtr twist_publisher_; - pid_regulator_t regulator_distance_; - pid_regulator_t regulator_angle_; - double odom_robot_x_; - double odom_robot_y_; - double map_robot_x_; - double map_robot_y_; - double odom_robot_distance_; - double odom_robot_angle_; - double odom_robot_speed_linear_; - double odom_robot_speed_angular_; - double map_robot_angle_; - double prev_odom_robot_x_; - double prev_odom_robot_y_; - double distance_goal_tolerance_; - double angle_goal_tolerance_; - bool position_initialized_; - bool debug_; - bool action_running_; - bool output_enabled_; - std::atomic_bool run_process_frame_thread_; - std::thread process_frame_thread_; - std::shared_ptr transform_listener_{nullptr}; - std::unique_ptr tf_buffer_; - rclcpp::TimerBase::SharedPtr timer_; - int64_t system_time_; // ms - - ruckig::Ruckig<2> * motion_profile_; - ruckig::InputParameter<2> motion_profile_input_; - ruckig::OutputParameter<2> motion_profile_output_; - ruckig::Result motion_profile_result_; - - double goal_distance_; - OnSetParametersCallbackHandle::SharedPtr parameters_callback_handle_; - - std::unique_ptr navigate_to_pose_server_; - std::unique_ptr motion_command_server_; - - std::mutex data_mutex_; - - void odometry_callback(const nav_msgs::msg::Odometry::SharedPtr msg); - void process_robot_frame(); - void control_loop(); - - double angle_normalize(double angle); - void forward(double distance); - void rotate_relative(double angle); - void rotate_absolute(double angle); - void softstop(); - - bool distance_regulator_finished(); - bool angle_regulator_finished(); - bool motion_profile_finished(); - void reset_regulation(); - - void navigate_to_pose(); - void motion_command(); - - geometry_msgs::msg::Pose2D projectPose( - geometry_msgs::msg::Pose2D pose, geometry_msgs::msg::Twist twist, double projection_time); - std::shared_ptr costmap_sub_; - std::shared_ptr footprint_sub_; - std::shared_ptr collision_checker_; - std::string robot_base_frame_ = "base_link"; - double transform_tolerance_ = 0.8; - bool check_collision_; - - bool stuck_enabled_ = true; - bool robot_stuck_ = false; - int distance_fail_count_ = 0; - int angle_fail_count_ = 0; - rclcpp::Publisher::SharedPtr can_publisher_; - void reset_stuck(); - // Publishers for regulator tuning and visualization - rclcpp::Publisher::SharedPtr distance_setpoint_publisher_; - rclcpp::Publisher::SharedPtr distance_publisher_; - rclcpp::Publisher::SharedPtr angle_setpoint_publisher_; - rclcpp::Publisher::SharedPtr angle_publisher_; -}; - -#endif // MEP3_NAVIGATION__DISTANCE_ANGLE__DISTANCE_ANGLE_REGULATOR_HPP_ diff --git a/mep3_navigation/include/mep3_navigation/distance_angle/motion_profile.hpp b/mep3_navigation/include/mep3_navigation/distance_angle/motion_profile.hpp deleted file mode 100644 index 5e332de74..000000000 --- a/mep3_navigation/include/mep3_navigation/distance_angle/motion_profile.hpp +++ /dev/null @@ -1,63 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#ifndef MEP3_NAVIGATION__DISTANCE_ANGLE__MOTION_PROFILE_HPP_ -#define MEP3_NAVIGATION__DISTANCE_ANGLE__MOTION_PROFILE_HPP_ - -#include "rclcpp/time.hpp" - -class MotionProfile -{ -public: - MotionProfile(); - MotionProfile(double position_initial, double velocity_max, double acceleration_max); - void plan( - double position_initial, double setpoint, double velocity_initial, double velocity_final, - rclcpp::Time time); - double update(rclcpp::Time time); - double get_position(); - double get_velocity(); - double get_setpoint(); - double get_velocity_max(); - void set_velocity_max(double velocity_max); - double get_acceleration_max(); - void set_acceleration_max(double acceleration_max); - bool finished(); - enum class ProfileState { ACCELERATION, CRUISING, DECELERATION, FINISHED }; - ProfileState get_state(); - -private: - double position_; - double position_initial_; - double setpoint_; - double velocity_max_; - double acceleration_max_; - double velocity_initial_; - double velocity_cruising_; - double velocity_final_; - double velocity_current_; - double acceleration_; - double deceleration_; - double acceleration_current_; - - double t0_, t1_, t2_, t3_; - double y1_, y2_; - - rclcpp::Time time_initial_; - - ProfileState state_; - bool finished_; -}; - -#endif // MEP3_NAVIGATION__DISTANCE_ANGLE__MOTION_PROFILE_HPP_ diff --git a/mep3_navigation/include/mep3_navigation/distance_angle/pid_regulator.h b/mep3_navigation/include/mep3_navigation/distance_angle/pid_regulator.h deleted file mode 100644 index 0a16bb30b..000000000 --- a/mep3_navigation/include/mep3_navigation/distance_angle/pid_regulator.h +++ /dev/null @@ -1,46 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#ifndef MEP3_NAVIGATION__DISTANCE_ANGLE__PID_REGULATOR_H_ -#define MEP3_NAVIGATION__DISTANCE_ANGLE__PID_REGULATOR_H_ - -#include -#include - -typedef struct -{ - double reference; - double feedback; - double feedback_old; - double error; - double integrator; - double integrator_min; - double integrator_max; - double d_term_filtered; - double d_term_filter_coefficient; - double kp; - double ki; - double kd; - double clamp_min; - double clamp_max; - double command; - - bool angle_mode; -} pid_regulator_t; // pid positional form - -void pid_regulator_update(pid_regulator_t * reg); -void pid_regulator_reset(pid_regulator_t * reg); -void pid_regulator_set_gains(pid_regulator_t * reg, double kp, double ki, double kd); - -#endif // MEP3_NAVIGATION__DISTANCE_ANGLE__PID_REGULATOR_H_ diff --git a/mep3_navigation/include/mep3_navigation/plugins/condition/globally_updated_goal_condition.hpp b/mep3_navigation/include/mep3_navigation/plugins/condition/globally_updated_goal_condition.hpp deleted file mode 100644 index 27803eae6..000000000 --- a/mep3_navigation/include/mep3_navigation/plugins/condition/globally_updated_goal_condition.hpp +++ /dev/null @@ -1,73 +0,0 @@ -// Copyright (c) 2021 Joshua Wallace -// -// 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. - -#ifndef MEP3_NAVIGATION__PLUGINS__CONDITION__GLOBALLY_UPDATED_GOAL_CONDITION_HPP_ -#define MEP3_NAVIGATION__PLUGINS__CONDITION__GLOBALLY_UPDATED_GOAL_CONDITION_HPP_ - -#include -#include - -#include "rclcpp/rclcpp.hpp" - -#include "behaviortree_cpp_v3/condition_node.h" -#include "geometry_msgs/msg/pose_stamped.hpp" - - -namespace mep3_navigation -{ -/** - * @brief A BT::ConditionNode that returns SUCCESS when goal is - * updated on the blackboard and FAILURE otherwise - */ -class GloballyUpdatedGoalCondition : public BT::ConditionNode -{ -public: - /** - * @brief A constructor for mep3_navigation::GloballyUpdatedGoalCondition - * @param condition_name Name for the XML tag for this node - * @param conf BT node configuration - */ - GloballyUpdatedGoalCondition( - const std::string & condition_name, - const BT::NodeConfiguration & conf); - - GloballyUpdatedGoalCondition() = delete; - - /** - * @brief The main override required by a BT action - * @return BT::NodeStatus Status of tick execution - */ - BT::NodeStatus tick() override; - - - /** - * @brief Creates list of BT ports - * @return BT::PortsList Containing node-specific ports - */ - static BT::PortsList providedPorts() - { - return {}; - } - -private: - bool first_time; - rclcpp::Node::SharedPtr node_; - geometry_msgs::msg::PoseStamped goal_; - std::vector goals_; -}; - -} // namespace mep3_navigation - - -#endif // MEP3_NAVIGATION__PLUGINS__CONDITION__GLOBALLY_UPDATED_GOAL_CONDITION_HPP_ diff --git a/mep3_navigation/include/mep3_navigation/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp b/mep3_navigation/include/mep3_navigation/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp index c72d8bfbc..479c7b142 100644 --- a/mep3_navigation/include/mep3_navigation/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp +++ b/mep3_navigation/include/mep3_navigation/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp @@ -59,8 +59,8 @@ class RegulatedPurePursuitController : public nav2_core::Controller */ void configure( const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, - std::string name, const std::shared_ptr & tf, - const std::shared_ptr & costmap_ros) override; + std::string name, std::shared_ptr tf, + std::shared_ptr costmap_ros) override; /** * @brief Cleanup controller state machine diff --git a/mep3_navigation/include/mep3_navigation/simple_action_server/simple_action_server.hpp b/mep3_navigation/include/mep3_navigation/simple_action_server/simple_action_server.hpp deleted file mode 100644 index 680bd0c8b..000000000 --- a/mep3_navigation/include/mep3_navigation/simple_action_server/simple_action_server.hpp +++ /dev/null @@ -1,587 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// -// 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. - -#ifndef NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_ -#define NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_ - -#include -#include -#include -#include -#include -#include - -#include "nav2_util/node_thread.hpp" -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_action/rclcpp_action.hpp" - -namespace nav2_util -{ -/** - * @class nav2_util::SimpleActionServer - * @brief An action server wrapper to make applications simpler using Actions - */ -template -class SimpleActionServer -{ -public: - // Callback function to complete main work. This should itself deal with its - // own exceptions, but if for some reason one is thrown, it will be caught - // in SimpleActionServer and terminate the action itself. - typedef std::function ExecuteCallback; - - // Callback function to notify the user that an exception was thrown that - // the simple action server caught (or another failure) and the action was - // terminated. To avoid using, catch exceptions in your application such that - // the SimpleActionServer will never need to terminate based on failed action - // ExecuteCallback. - typedef std::function CompletionCallback; - - /** - * @brief An constructor for SimpleActionServer - * @param node Ptr to node to make actions - * @param action_name Name of the action to call - * @param execute_callback Execution callback function of Action - * @param server_timeout Timeout to to react to stop or preemption requests - * @param spin_thread Whether to spin with a dedicated thread internally - * @param options Options to pass to the underlying rcl_action_server_t - */ - template - explicit SimpleActionServer( - NodeT node, const std::string & action_name, ExecuteCallback execute_callback, - CompletionCallback completion_callback = nullptr, - std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500), - bool spin_thread = false, - const rcl_action_server_options_t & options = rcl_action_server_get_default_options()) - : SimpleActionServer( - node->get_node_base_interface(), node->get_node_clock_interface(), - node->get_node_logging_interface(), node->get_node_waitables_interface(), action_name, - execute_callback, completion_callback, server_timeout, spin_thread, options) - { - } - - /** - * @brief An constructor for SimpleActionServer - * @param Abstract node interfaces to make actions - * @param action_name Name of the action to call - * @param execute_callback Execution callback function of Action - * @param server_timeout Timeout to to react to stop or preemption requests - * @param spin_thread Whether to spin with a dedicated thread internally - * @param options Options to pass to the underlying rcl_action_server_t - */ - explicit SimpleActionServer( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, - rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, - rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, - const std::string & action_name, ExecuteCallback execute_callback, - CompletionCallback completion_callback = nullptr, - std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500), - bool spin_thread = false, - const rcl_action_server_options_t & options = rcl_action_server_get_default_options()) - : node_base_interface_(node_base_interface), - node_clock_interface_(node_clock_interface), - node_logging_interface_(node_logging_interface), - node_waitables_interface_(node_waitables_interface), - action_name_(action_name), - execute_callback_(execute_callback), - completion_callback_(completion_callback), - server_timeout_(server_timeout), - spin_thread_(spin_thread) - { - using namespace std::placeholders; // NOLINT - if (spin_thread_) { - callback_group_ = node_base_interface->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive, false); - } - action_server_ = rclcpp_action::create_server( - node_base_interface_, node_clock_interface_, node_logging_interface_, - node_waitables_interface_, action_name_, - std::bind(&SimpleActionServer::handle_goal, this, _1, _2), - std::bind(&SimpleActionServer::handle_cancel, this, _1), - std::bind(&SimpleActionServer::handle_accepted, this, _1), options, callback_group_); - if (spin_thread_) { - executor_ = std::make_shared(); - executor_->add_callback_group(callback_group_, node_base_interface_); - executor_thread_ = std::make_unique(executor_); - } - } - - /** - * @brief handle the goal requested: accept or reject. This implementation always accepts. - * @param uuid Goal ID - * @param Goal A shared pointer to the specific goal - * @return GoalResponse response of the goal processed - */ - rclcpp_action::GoalResponse handle_goal( - const rclcpp_action::GoalUUID & /*uuid*/, - std::shared_ptr /*goal*/) - { - std::lock_guard lock(update_mutex_); - - if (!server_active_) { - return rclcpp_action::GoalResponse::REJECT; - } - - debug_msg("Received request for goal acceptance"); - return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; - } - - /** - * @brief Accepts cancellation requests of action server. - * @param uuid Goal ID - * @param Goal A server goal handle to cancel - * @return CancelResponse response of the goal cancelled - */ - rclcpp_action::CancelResponse handle_cancel( - const std::shared_ptr> handle) - { - std::lock_guard lock(update_mutex_); - - if (!handle->is_active()) { - warn_msg( - "Received request for goal cancellation," - "but the handle is inactive, so reject the request"); - return rclcpp_action::CancelResponse::REJECT; - } - - debug_msg("Received request for goal cancellation"); - return rclcpp_action::CancelResponse::ACCEPT; - } - - /** - * @brief Handles accepted goals and adds to preempted queue to switch to - * @param Goal A server goal handle to cancel - */ - void handle_accepted(const std::shared_ptr> handle) - { - std::lock_guard lock(update_mutex_); - debug_msg("Receiving a new goal"); - - if (is_active(current_handle_) || is_running()) { - debug_msg("An older goal is active, moving the new goal to a pending slot."); - - if (is_active(pending_handle_)) { - debug_msg( - "The pending slot is occupied." - " The previous pending goal will be terminated and replaced."); - terminate(pending_handle_); - } - pending_handle_ = handle; - preempt_requested_ = true; - } else { - if (is_active(pending_handle_)) { - // Shouldn't reach a state with a pending goal but no current one. - error_msg("Forgot to handle a preemption. Terminating the pending goal."); - terminate(pending_handle_); - preempt_requested_ = false; - } - - current_handle_ = handle; - - // Return quickly to avoid blocking the executor, so spin up a new thread - debug_msg("Executing goal asynchronously."); - execution_future_ = std::async(std::launch::async, [this]() { work(); }); - } - } - - /** - * @brief Computed background work and processes stop requests - */ - void work() - { - while (rclcpp::ok() && !stop_execution_ && is_active(current_handle_)) { - debug_msg("Executing the goal..."); - try { - execute_callback_(); - } catch (std::exception & ex) { - RCLCPP_ERROR( - node_logging_interface_->get_logger(), - "Action server failed while executing action callback: \"%s\"", ex.what()); - terminate_all(); - completion_callback_(); - return; - } - - debug_msg("Blocking processing of new goal handles."); - std::lock_guard lock(update_mutex_); - - if (stop_execution_) { - warn_msg("Stopping the thread per request."); - terminate_all(); - completion_callback_(); - break; - } - - if (is_active(current_handle_)) { - warn_msg("Current goal was not completed successfully."); - terminate(current_handle_); - completion_callback_(); - } - - if (is_active(pending_handle_)) { - debug_msg("Executing a pending handle on the existing thread."); - accept_pending_goal(); - } else { - debug_msg("Done processing available goals."); - break; - } - } - debug_msg("Worker thread done."); - } - - /** - * @brief Active action server - */ - void activate() - { - std::lock_guard lock(update_mutex_); - server_active_ = true; - stop_execution_ = false; - } - - /** - * @brief Deactive action server - */ - void deactivate() - { - debug_msg("Deactivating..."); - - { - std::lock_guard lock(update_mutex_); - server_active_ = false; - stop_execution_ = true; - } - - if (!execution_future_.valid()) { - return; - } - - if (is_running()) { - warn_msg( - "Requested to deactivate server but goal is still executing." - " Should check if action server is running before deactivating."); - } - - using namespace std::chrono; //NOLINT - auto start_time = steady_clock::now(); - while (execution_future_.wait_for(milliseconds(100)) != std::future_status::ready) { - info_msg("Waiting for async process to finish."); - if (steady_clock::now() - start_time >= server_timeout_) { - terminate_all(); - completion_callback_(); - throw std::runtime_error("Action callback is still running and missed deadline to stop"); - } - } - - debug_msg("Deactivation completed."); - } - - /** - * @brief Whether the action server is munching on a goal - * @return bool If its running or not - */ - bool is_running() - { - return execution_future_.valid() && (execution_future_.wait_for(std::chrono::milliseconds(0)) == - std::future_status::timeout); - } - - /** - * @brief Whether the action server is active or not - * @return bool If its active or not - */ - bool is_server_active() - { - std::lock_guard lock(update_mutex_); - return server_active_; - } - - /** - * @brief Whether the action server has been asked to be preempted with a new goal - * @return bool If there's a preemption request or not - */ - bool is_preempt_requested() const - { - std::lock_guard lock(update_mutex_); - return preempt_requested_; - } - - /** - * @brief Accept pending goals - * @return Goal Ptr to the goal that's going to be accepted - */ - const std::shared_ptr accept_pending_goal() - { - std::lock_guard lock(update_mutex_); - - if (!pending_handle_ || !pending_handle_->is_active()) { - error_msg("Attempting to get pending goal when not available"); - return std::shared_ptr(); - } - - if (is_active(current_handle_) && current_handle_ != pending_handle_) { - debug_msg("Cancelling the previous goal"); - current_handle_->abort(empty_result()); - } - - current_handle_ = pending_handle_; - pending_handle_.reset(); - preempt_requested_ = false; - - debug_msg("Preempted goal"); - - return current_handle_->get_goal(); - } - - /** - * @brief Terminate pending goals - */ - void terminate_pending_goal() - { - std::lock_guard lock(update_mutex_); - - if (!pending_handle_ || !pending_handle_->is_active()) { - error_msg("Attempting to terminate pending goal when not available"); - return; - } - - terminate(pending_handle_); - preempt_requested_ = false; - - debug_msg("Pending goal terminated"); - } - - /** - * @brief Get the current goal object - * @return Goal Ptr to the goal that's being processed currently - */ - const std::shared_ptr get_current_goal() const - { - std::lock_guard lock(update_mutex_); - - if (!is_active(current_handle_)) { - error_msg("A goal is not available or has reached a final state"); - return std::shared_ptr(); - } - - return current_handle_->get_goal(); - } - - /** - * @brief Get the pending goal object - * @return Goal Ptr to the goal that's pending - */ - const std::shared_ptr get_pending_goal() const - { - std::lock_guard lock(update_mutex_); - - if (!pending_handle_ || !pending_handle_->is_active()) { - error_msg("Attempting to get pending goal when not available"); - return std::shared_ptr(); - } - - return pending_handle_->get_goal(); - } - - /** - * @brief Whether or not a cancel command has come in - * @return bool Whether a cancel command has been requested or not - */ - bool is_cancel_requested() const - { - std::lock_guard lock(update_mutex_); - - // A cancel request is assumed if either handle is canceled by the client. - - if (current_handle_ == nullptr) { - error_msg("Checking for cancel but current goal is not available"); - return false; - } - - if (pending_handle_ != nullptr) { - return pending_handle_->is_canceling(); - } - - return current_handle_->is_canceling(); - } - - /** - * @brief Terminate all pending and active actions - * @param result A result object to send to the terminated actions - */ - void terminate_all( - typename std::shared_ptr result = - std::make_shared()) - { - std::lock_guard lock(update_mutex_); - terminate(current_handle_, result); - terminate(pending_handle_, result); - preempt_requested_ = false; - } - - /** - * @brief Terminate the active action - * @param result A result object to send to the terminated action - */ - void terminate_current( - typename std::shared_ptr result = - std::make_shared()) - { - std::lock_guard lock(update_mutex_); - terminate(current_handle_, result); - } - - /** - * @brief Return success of the active action - * @param result A result object to send to the terminated actions - */ - void succeeded_current( - typename std::shared_ptr result = - std::make_shared()) - { - std::lock_guard lock(update_mutex_); - - if (is_active(current_handle_)) { - debug_msg("Setting succeed on current goal."); - current_handle_->succeed(result); - current_handle_.reset(); - } - } - - /** - * @brief Publish feedback to the action server clients - * @param feedback A feedback object to send to the clients - */ - void publish_feedback(typename std::shared_ptr feedback) - { - if (!is_active(current_handle_)) { - error_msg("Trying to publish feedback when the current goal handle is not active"); - return; - } - - current_handle_->publish_feedback(feedback); - } - -protected: - // The SimpleActionServer isn't itself a node, so it needs interfaces to one - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_; - rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface_; - rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface_; - rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface_; - std::string action_name_; - - ExecuteCallback execute_callback_; - CompletionCallback completion_callback_; - std::future execution_future_; - bool stop_execution_{false}; - - mutable std::recursive_mutex update_mutex_; - bool server_active_{false}; - bool preempt_requested_{false}; - std::chrono::milliseconds server_timeout_; - - std::shared_ptr> current_handle_; - std::shared_ptr> pending_handle_; - - typename rclcpp_action::Server::SharedPtr action_server_; - bool spin_thread_; - rclcpp::CallbackGroup::SharedPtr callback_group_{nullptr}; - rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; - std::unique_ptr executor_thread_; - - /** - * @brief Generate an empty result object for an action type - */ - constexpr auto empty_result() const { return std::make_shared(); } - - /** - * @brief Whether a given goal handle is currently active - * @param handle Goal handle to check - * @return Whether this goal handle is active - */ - constexpr bool is_active( - const std::shared_ptr> handle) const - { - return handle != nullptr && handle->is_active(); - } - - /** - * @brief Terminate a particular action with a result - * @param handle goal handle to terminate - * @param the Results object to terminate the action with - */ - void terminate( - std::shared_ptr> handle, - typename std::shared_ptr result = - std::make_shared()) - { - std::lock_guard lock(update_mutex_); - - if (is_active(handle)) { - if (handle->is_canceling()) { - warn_msg("Client requested to cancel the goal. Cancelling."); - handle->canceled(result); - } else { - warn_msg("Aborting handle."); - handle->abort(result); - } - handle.reset(); - } - } - - /** - * @brief Info logging - */ - void info_msg(const std::string & msg) const - { - RCLCPP_INFO( - node_logging_interface_->get_logger(), "[%s] [ActionServer] %s", action_name_.c_str(), - msg.c_str()); - } - - /** - * @brief Debug logging - */ - void debug_msg(const std::string & msg) const - { - RCLCPP_DEBUG( - node_logging_interface_->get_logger(), "[%s] [ActionServer] %s", action_name_.c_str(), - msg.c_str()); - } - - /** - * @brief Error logging - */ - void error_msg(const std::string & msg) const - { - RCLCPP_ERROR( - node_logging_interface_->get_logger(), "[%s] [ActionServer] %s", action_name_.c_str(), - msg.c_str()); - } - - /** - * @brief Warn logging - */ - void warn_msg(const std::string & msg) const - { - RCLCPP_WARN( - node_logging_interface_->get_logger(), "[%s] [ActionServer] %s", action_name_.c_str(), - msg.c_str()); - } -}; - -} // namespace nav2_util - -#endif // NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_ diff --git a/mep3_navigation/launch/navigation_launch.py b/mep3_navigation/launch/navigation_launch.py index 707dac245..bf02c6ce8 100644 --- a/mep3_navigation/launch/navigation_launch.py +++ b/mep3_navigation/launch/navigation_launch.py @@ -17,12 +17,10 @@ from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription -from launch.actions import (DeclareLaunchArgument, GroupAction, SetEnvironmentVariable) -from launch.conditions import IfCondition +from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable from launch.substitutions import LaunchConfiguration -from launch_ros.actions import Node -from launch_ros.actions import PushRosNamespace -from nav2_common.launch import RewrittenYaml +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode def generate_launch_description(): @@ -31,39 +29,17 @@ def generate_launch_description(): # Create the launch configuration variables namespace = LaunchConfiguration('namespace') - use_namespace = LaunchConfiguration('use_namespace') - map_yaml_file = LaunchConfiguration('map') use_sim_time = LaunchConfiguration('use_sim_time') params_file = LaunchConfiguration('params_file') - autostart = LaunchConfiguration('autostart') nav2_bt_xml_file = LaunchConfiguration('nav2_bt_xml_file') + log_level = LaunchConfiguration('log_level') lifecycle_nodes = ['controller_server', 'planner_server', - 'recoveries_server', - 'bt_navigator', - 'map_server'] - - # Map fully qualified names to relative ones so the node's namespace can be prepended. - # In case of the transforms (tf), currently, there doesn't seem to be a better alternative - # /~https://github.com/ros/geometry2/issues/32 - # /~https://github.com/ros/robot_state_publisher/pull/30 - # TODO(orduno) Substitute with `PushNodeRemapping` - # /~https://github.com/ros2/launch_ros/issues/56 - remappings = [('/tf', 'tf'), - ('/tf_static', 'tf_static')] - - # Create our own temporary YAML files that include substitutions - param_substitutions = { - 'default_nav_to_pose_bt_xml': nav2_bt_xml_file, - 'use_sim_time': use_sim_time, - 'yaml_filename': map_yaml_file} - - configured_params = RewrittenYaml( - source_file=params_file, - root_key=namespace, - param_rewrites=param_substitutions, - convert_types=True) + 'behavior_server', + 'bt_navigator'] + remappings = [('/tf', ['tf']), + ('/tf_static', ['tf_static'])] stdout_linebuf_envvar = SetEnvironmentVariable( 'RCUTILS_LOGGING_BUFFERED_STREAM', '1') @@ -75,28 +51,14 @@ def generate_launch_description(): 'behavior_trees', 'navigate_w_recovery_and_replanning_only_if_path_becomes_invalid.xml', ), - description='Full path to the parameter YAML file to use for configuring the behavior tree' + description='Full path to the YAML file used with navigation behavior' ) declare_namespace_cmd = DeclareLaunchArgument( 'namespace', - default_value='', + default_value='big', description='Top-level namespace') - declare_use_namespace_cmd = DeclareLaunchArgument( - 'use_namespace', - default_value='false', - description='Whether to apply a namespace to the navigation stack') - - declare_slam_cmd = DeclareLaunchArgument( - 'slam', - default_value='False', - description='Whether run a SLAM') - - declare_map_yaml_cmd = DeclareLaunchArgument( - 'map', - description='Full path to map yaml file to load') - declare_use_sim_time_cmd = DeclareLaunchArgument( 'use_sim_time', default_value='false', @@ -108,82 +70,74 @@ def generate_launch_description(): mep3_navigation_dir, 'params', 'nav2_params_big.yaml'), description='Full path to the ROS2 parameters file to use for all launched nodes') - declare_autostart_cmd = DeclareLaunchArgument( - 'autostart', default_value='true', - description='Automatically startup the nav2 stack') - - # Specify the actions - bringup_cmd_group = GroupAction([ - PushRosNamespace( - condition=IfCondition(use_namespace), - namespace=namespace), - Node( - package='nav2_map_server', - executable='map_server', - name='map_server', - output='screen', - parameters=[configured_params], - remappings=remappings), - Node( - package='nav2_controller', - executable='controller_server', - output='screen', - parameters=[configured_params], - remappings=remappings), - - Node( - package='nav2_planner', - executable='planner_server', - name='planner_server', - output='screen', - parameters=[configured_params], - remappings=remappings), - - Node( - package='nav2_recoveries', - executable='recoveries_server', - name='recoveries_server', - output='screen', - parameters=[configured_params], - remappings=remappings), + # TODO: Switch to warn later + declare_log_level_cmd = DeclareLaunchArgument( + 'log_level', default_value='warn', + description='log level') + + load_composable_nodes = ComposableNodeContainer( + namespace=namespace, + remappings=remappings, + parameters=[params_file], + name='nav2_container', + package='rclcpp_components', + executable='component_container', + arguments=['--ros-args', '--log-level', log_level], + composable_node_descriptions=[ + ComposableNode( + package='nav2_controller', + plugin='nav2_controller::ControllerServer', + name='controller_server', + namespace=namespace, + parameters=[ + params_file + ], + remappings=remappings), + ComposableNode( + package='nav2_planner', + plugin='nav2_planner::PlannerServer', + name='planner_server', + namespace=namespace, + parameters=[ + params_file + ], + remappings=remappings), + ComposableNode( + package='nav2_behaviors', + plugin='behavior_server::BehaviorServer', + name='behavior_server', + namespace=namespace, + parameters=[ + params_file + ], + remappings=remappings), + ComposableNode( + package='nav2_bt_navigator', + plugin='nav2_bt_navigator::BtNavigator', + name='bt_navigator', + namespace=namespace, + parameters=[ + params_file, + {'default_nav_to_pose_bt_xml': nav2_bt_xml_file} + ], + remappings=remappings), + ComposableNode( + package='nav2_lifecycle_manager', + plugin='nav2_lifecycle_manager::LifecycleManager', + name='lifecycle_manager_navigation', + namespace=namespace, + parameters=[{'use_sim_time': use_sim_time, + 'autostart': True, + 'node_names': lifecycle_nodes}]), + ], + ) - Node( - package='nav2_bt_navigator', - executable='bt_navigator', - name='bt_navigator', - output='screen', - parameters=[configured_params], - remappings=remappings), - Node( - package='nav2_lifecycle_manager', - executable='lifecycle_manager', - name='lifecycle_manager_navigation', - output='screen', - parameters=[ - {'use_sim_time': use_sim_time}, - {'autostart': autostart}, - {'node_names': lifecycle_nodes}, - {'bond_timeout': 8.0} - ]), + return LaunchDescription([ + stdout_linebuf_envvar, + declare_namespace_cmd, + declare_use_sim_time_cmd, + declare_params_file_cmd, + nav2_bt_xml_file_cmd, + declare_log_level_cmd, + load_composable_nodes ]) - - # Create the launch description and populate - ld = LaunchDescription() - - # Set environment variables - ld.add_action(stdout_linebuf_envvar) - - # Declare the launch options - ld.add_action(declare_namespace_cmd) - ld.add_action(declare_use_namespace_cmd) - ld.add_action(declare_slam_cmd) - ld.add_action(declare_map_yaml_cmd) - ld.add_action(declare_use_sim_time_cmd) - ld.add_action(declare_params_file_cmd) - ld.add_action(declare_autostart_cmd) - ld.add_action(nav2_bt_xml_file_cmd) - - # Add the actions to launch all of the navigation nodes - ld.add_action(bringup_cmd_group) - - return ld diff --git a/mep3_navigation/params/config_regulator_big.yaml b/mep3_navigation/params/config_regulator_big.yaml deleted file mode 100644 index 05de29e9a..000000000 --- a/mep3_navigation/params/config_regulator_big.yaml +++ /dev/null @@ -1,17 +0,0 @@ -big: - distance_angle_regulator: - ros__parameters: - kp_distance: 5.0 - ki_distance: 0.0 - kd_distance: 3.0 - d_term_filter_distance: 0.1 - - kp_angle: 8.0 - ki_angle: 0.0 - kd_angle: 4.0 - d_term_filter_angle: 0.1 - - distance_goal_tolerance: 0.002 - angle_goal_tolerance: 0.018 - - control_frequency: 100.0 \ No newline at end of file diff --git a/mep3_navigation/params/config_regulator_small.yaml b/mep3_navigation/params/config_regulator_small.yaml deleted file mode 100644 index 4778c6415..000000000 --- a/mep3_navigation/params/config_regulator_small.yaml +++ /dev/null @@ -1,17 +0,0 @@ -small: - distance_angle_regulator: - ros__parameters: - kp_distance: 11.0 - ki_distance: 0.0 - kd_distance: 3.0 - d_term_filter_distance: 0.1 - - kp_angle: 9.0 - ki_angle: 0.0 - kd_angle: 2.0 - d_term_filter_angle: 0.1 - - distance_goal_tolerance: 0.002 - angle_goal_tolerance: 0.018 - - control_frequency: 100.0 diff --git a/mep3_navigation/params/nav2_params_big.yaml b/mep3_navigation/params/nav2_params_big.yaml index 88ae7d19f..e806e616e 100644 --- a/mep3_navigation/params/nav2_params_big.yaml +++ b/mep3_navigation/params/nav2_params_big.yaml @@ -1,79 +1,77 @@ -bt_navigator: +/big/bt_navigator: ros__parameters: use_sim_time: True global_frame: map robot_base_frame: base_link - odom_topic: /odom - bt_loop_duration: 5 - default_server_timeout: 100 - enable_groot_monitoring: False - # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: - # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml - # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml - # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. + odom_topic: /big/odom + bt_loop_duration: 10 + default_server_timeout: 20 default_nav_to_pose_bt_xml: navigate_to_pose_w_replanning_and_recovery.xml plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_compute_path_through_poses_action_bt_node + - nav2_smooth_path_action_bt_node - nav2_follow_path_action_bt_node - - nav2_back_up_action_bt_node - nav2_spin_action_bt_node - nav2_wait_action_bt_node + - nav2_back_up_action_bt_node + - nav2_drive_on_heading_bt_node - nav2_clear_costmap_service_bt_node - nav2_is_stuck_condition_bt_node - nav2_goal_reached_condition_bt_node - nav2_goal_updated_condition_bt_node + - nav2_globally_updated_goal_condition_bt_node + - nav2_is_path_valid_condition_bt_node - nav2_initial_pose_received_condition_bt_node - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node - nav2_distance_controller_bt_node - nav2_speed_controller_bt_node - nav2_truncate_path_action_bt_node + - nav2_truncate_path_local_action_bt_node - nav2_goal_updater_node_bt_node - nav2_recovery_node_bt_node - nav2_pipeline_sequence_bt_node - nav2_round_robin_node_bt_node - nav2_transform_available_condition_bt_node - nav2_time_expired_condition_bt_node + - nav2_path_expiring_timer_condition - nav2_distance_traveled_condition_bt_node - nav2_single_trigger_bt_node - - nav2_is_battery_low_condition_bt_node + - nav2_goal_updated_controller_bt_node - nav2_navigate_through_poses_action_bt_node - nav2_navigate_to_pose_action_bt_node - nav2_remove_passed_goals_action_bt_node - nav2_planner_selector_bt_node - nav2_controller_selector_bt_node - nav2_goal_checker_selector_bt_node - - nav2_globally_updated_goal_condition_bt_node + - nav2_controller_cancel_bt_node + - nav2_path_longer_on_approach_bt_node + - nav2_wait_cancel_bt_node + - nav2_spin_cancel_bt_node + - nav2_back_up_cancel_bt_node + - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: +/big/controller_server: ros__parameters: use_sim_time: True - -controller_server: - ros__parameters: - use_sim_time: True - controller_frequency: 40.0 + controller_frequency: 20.0 min_x_velocity_threshold: 0.001 - min_y_velocity_threshold: 0.001 + min_y_velocity_threshold: 0.5 min_theta_velocity_threshold: 0.001 + failure_tolerance: 0.3 progress_checker_plugin: "progress_checker" - goal_checker_plugin: "goal_checker" + goal_checker_plugins: ["general_goal_checker"] controller_plugins: ["FollowPath"] - - # Progress checker parameters progress_checker: plugin: "nav2_controller::SimpleProgressChecker" required_movement_radius: 0.6 movement_time_allowance: 10.0 - # Goal checker parameters - goal_checker: + general_goal_checker: + stateful: True plugin: "nav2_controller::SimpleGoalChecker" xy_goal_tolerance: 0.08 yaw_goal_tolerance: 0.05 - stateful: true - # Controller parameters - # RPP Custom controller for Memristor FollowPath: plugin: "mep3_navigation::RegulatedPurePursuitController" desired_linear_vel: 0.8 @@ -104,40 +102,8 @@ controller_server: cost_scaling_dist: 0.7 cost_scaling_gain: 1.0 inflation_cost_scaling_factor: 5.0 - # RPP Controller from Navigation2 Package - NAV2RPPFollowPath: - plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" - desired_linear_vel: 0.4 - # acceleration limiting is not implemented yet - max_linear_accel: 0.0001 - max_linear_decel: 0.0001 - lookahead_dist: 0.2 - min_lookahead_dist: 0.05 - max_lookahead_dist: 0.4 - lookahead_time: 1.0 - rotate_to_heading_angular_vel: 2.5 - transform_tolerance: 0.1 - use_velocity_scaled_lookahead_dist: true - min_approach_linear_velocity: 0.05 - use_approach_linear_velocity_scaling: true - max_allowed_time_to_collision: 0.6 - use_regulated_linear_velocity_scaling: true - use_cost_regulated_linear_velocity_scaling: false - regulated_linear_scaling_min_radius: 0.2 - regulated_linear_scaling_min_speed: 0.1 - allow_reversing: false - use_rotate_to_heading: true - rotate_to_heading_min_angle: 0.785 - max_angular_accel: 3.5 - cost_scaling_dist: 0.7 - cost_scaling_gain: 1.0 - inflation_cost_scaling_factor: 5.0 - -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True -local_costmap: +/big/local_costmap: local_costmap: ros__parameters: update_frequency: 10.0 @@ -146,36 +112,34 @@ local_costmap: robot_base_frame: base_link use_sim_time: True rolling_window: True - width: 3 - height: 3 - resolution: 0.01 + width: 1 + height: 1 + resolution: 0.07 robot_radius: 0.17 - # footprint: "[ [0.1, 0.15], [0.1, -0.15], [-0.1, -0.15], [-0.1, 0.15] ]" + use_maximum: true plugins: ["obstacle_layer", "inflation_layer"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True observation_sources: scan scan: - topic: /big/scan_inflated + topic: /big/scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" inf_is_valid: True + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 4.0 inflation_radius: 1.0 always_send_full_costmap: True - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True -global_costmap: +/big/global_costmap: global_costmap: ros__parameters: update_frequency: 10.0 @@ -183,24 +147,26 @@ global_costmap: global_frame: map robot_base_frame: base_link use_sim_time: True + rolling_window: True robot_radius: 0.2 - resolution: 0.01 - track_unknown_space: true - plugins: ["static_layer", "obstacle_layer", "inflation_layer", "temporal_obstacle_layer"] + resolution: 0.07 + use_maximum: true + plugins: ["obstacle_layer", "inflation_layer", "temporal_obstacle_layer"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True observation_sources: scan scan: - topic: /big/scan_inflated + topic: /big/scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" inf_is_valid: True - static_layer: - plugin: "nav2_costmap_2d::StaticLayer" - map_subscribe_transient_local: True + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 4.0 @@ -210,27 +176,8 @@ global_costmap: add_obstacle_topic: /big/add_obstacle remove_obstacle_topic: /big/remove_obstacle always_send_full_costmap: True - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True -map_server: - ros__parameters: - use_sim_time: True - yaml_filename: "map.yaml" - -map_saver: - ros__parameters: - use_sim_time: True - save_map_timeout: 5.0 - free_thresh_default: 0.25 - occupied_thresh_default: 0.65 - map_subscribe_transient_local: True - -planner_server: +/big/planner_server: ros__parameters: use_sim_time: True planner_plugins: ["GridBased"] @@ -238,58 +185,29 @@ planner_server: GridBased: plugin: 'nav2_navfn_planner/NavfnPlanner' use_astar: True - allow_unknown: false + allow_unknown: true use_final_approach_orientation: False tolerance: 0.025 - _GridBased: - plugin: "nav2_smac_planner/SmacPlanner2D" - tolerance: 0.02 - downsample_costmap: false # whether or not to downsample the map - downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) - allow_unknown: true # allow traveling in unknown space - max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable - max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance - max_planning_time: 0.2 # max time in s for planner to plan, smooth - motion_model_for_search: "MOORE" # 2D Moore, Von Neumann - cost_travel_multiplier: 5.0 # Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*. - use_final_approach_orientation: false # Whether to set the final path pose at the goal's orientation to the requested orientation (false) or in line with the approach angle so the robot doesn't rotate to heading (true) - smoother: - max_iterations: 1000 - w_smooth: 0.4 - w_data: 0.2 - tolerance: 1e-10 -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - -recoveries_server: +/big/behavior_server: ros__parameters: costmap_topic: local_costmap/costmap_raw footprint_topic: local_costmap/published_footprint cycle_frequency: 10.0 - recovery_plugins: ["spin", "backup", "wait"] + behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] spin: - plugin: "nav2_recoveries/Spin" + plugin: "nav2_behaviors/Spin" backup: - plugin: "nav2_recoveries/BackUp" + plugin: "nav2_behaviors/BackUp" + drive_on_heading: + plugin: "nav2_behaviors/DriveOnHeading" wait: - plugin: "nav2_recoveries/Wait" + plugin: "nav2_behaviors/Wait" global_frame: odom robot_base_frame: base_link - transform_timeout: 0.1 + transform_tolerance: 0.1 use_sim_time: true simulate_ahead_time: 2.0 max_rotational_vel: 1.0 min_rotational_vel: 0.4 rotational_acc_lim: 3.2 - -waypoint_follower: - ros__parameters: - loop_rate: 20 - stop_on_failure: false - waypoint_task_executor_plugin: "wait_at_waypoint" - wait_at_waypoint: - plugin: "nav2_waypoint_follower::WaitAtWaypoint" - enabled: True - waypoint_pause_duration: 200 diff --git a/mep3_navigation/params/nav2_params_small.yaml b/mep3_navigation/params/nav2_params_small.yaml index 32dee7621..0b14b2d3b 100644 --- a/mep3_navigation/params/nav2_params_small.yaml +++ b/mep3_navigation/params/nav2_params_small.yaml @@ -1,79 +1,77 @@ -bt_navigator: +/small/bt_navigator: ros__parameters: use_sim_time: True global_frame: map robot_base_frame: base_link - odom_topic: /odom - bt_loop_duration: 5 - default_server_timeout: 100 - enable_groot_monitoring: False - # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: - # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml - # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml - # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. + odom_topic: /small/odom + bt_loop_duration: 10 + default_server_timeout: 20 default_nav_to_pose_bt_xml: navigate_to_pose_w_replanning_and_recovery.xml plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_compute_path_through_poses_action_bt_node + - nav2_smooth_path_action_bt_node - nav2_follow_path_action_bt_node - - nav2_back_up_action_bt_node - nav2_spin_action_bt_node - nav2_wait_action_bt_node + - nav2_back_up_action_bt_node + - nav2_drive_on_heading_bt_node - nav2_clear_costmap_service_bt_node - nav2_is_stuck_condition_bt_node - nav2_goal_reached_condition_bt_node - nav2_goal_updated_condition_bt_node + - nav2_globally_updated_goal_condition_bt_node + - nav2_is_path_valid_condition_bt_node - nav2_initial_pose_received_condition_bt_node - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node - nav2_distance_controller_bt_node - nav2_speed_controller_bt_node - nav2_truncate_path_action_bt_node + - nav2_truncate_path_local_action_bt_node - nav2_goal_updater_node_bt_node - nav2_recovery_node_bt_node - nav2_pipeline_sequence_bt_node - nav2_round_robin_node_bt_node - nav2_transform_available_condition_bt_node - nav2_time_expired_condition_bt_node + - nav2_path_expiring_timer_condition - nav2_distance_traveled_condition_bt_node - nav2_single_trigger_bt_node - - nav2_is_battery_low_condition_bt_node + - nav2_goal_updated_controller_bt_node - nav2_navigate_through_poses_action_bt_node - nav2_navigate_to_pose_action_bt_node - nav2_remove_passed_goals_action_bt_node - nav2_planner_selector_bt_node - nav2_controller_selector_bt_node - nav2_goal_checker_selector_bt_node - - nav2_globally_updated_goal_condition_bt_node + - nav2_controller_cancel_bt_node + - nav2_path_longer_on_approach_bt_node + - nav2_wait_cancel_bt_node + - nav2_spin_cancel_bt_node + - nav2_back_up_cancel_bt_node + - nav2_drive_on_heading_cancel_bt_node -bt_navigator_rclcpp_node: - ros__parameters: - use_sim_time: True - -controller_server: +/small/controller_server: ros__parameters: use_sim_time: True controller_frequency: 20.0 min_x_velocity_threshold: 0.001 - min_y_velocity_threshold: 0.001 + min_y_velocity_threshold: 0.5 min_theta_velocity_threshold: 0.001 + failure_tolerance: 0.3 progress_checker_plugin: "progress_checker" - goal_checker_plugin: "goal_checker" - controller_plugins: ["FollowPath", "FollowPathFast"] - - # Progress checker parameters + goal_checker_plugins: ["general_goal_checker"] + controller_plugins: ["FollowPath"] progress_checker: plugin: "nav2_controller::SimpleProgressChecker" - required_movement_radius: 0.5 + required_movement_radius: 0.6 movement_time_allowance: 10.0 - # Goal checker parameters - goal_checker: + general_goal_checker: + stateful: True plugin: "nav2_controller::SimpleGoalChecker" xy_goal_tolerance: 0.08 yaw_goal_tolerance: 0.05 - stateful: true - # Controller parameters - # RPP Custom controller for Memristor FollowPath: plugin: "mep3_navigation::RegulatedPurePursuitController" desired_linear_vel: 0.8 @@ -83,8 +81,8 @@ controller_server: max_angular_jerk: 99999.0 lookahead_dist: 0.2 min_lookahead_dist: 0.15 - max_lookahead_dist: 0.6 - lookahead_time: 0.75 + max_lookahead_dist: 0.5 + lookahead_time: 0.625 rotate_to_heading_angular_vel: 15.0 transform_tolerance: 0.1 use_velocity_scaled_lookahead_dist: true @@ -98,165 +96,88 @@ controller_server: allow_reversing: true use_rotate_to_heading: false use_rotate_to_goal: true - rotate_to_heading_min_angle: 0.785 - max_angular_accel: 15.0 - cost_scaling_dist: 0.7 - cost_scaling_gain: 1.0 - inflation_cost_scaling_factor: 5.0 - # RPP Custom controller for Memristor - VERY FAST - FollowPathFast: - plugin: "mep3_navigation::RegulatedPurePursuitController" - desired_linear_vel: 2.0 - max_linear_accel: 2.4 - max_linear_decel: 2.4 - max_linear_jerk: 99999999.0 - max_angular_jerk: 99999999.0 - lookahead_dist: 0.9 - min_lookahead_dist: 0.15 - max_lookahead_dist: 0.9 - lookahead_time: 0.45 - rotate_to_heading_angular_vel: 14.0 - transform_tolerance: 0.1 - use_velocity_scaled_lookahead_dist: false - min_approach_linear_velocity: 0.05 - use_approach_linear_velocity_scaling: true - max_allowed_time_to_collision: 0.6 - use_regulated_linear_velocity_scaling: false - use_cost_regulated_linear_velocity_scaling: false - regulated_linear_scaling_min_radius: 0.2 - regulated_linear_scaling_min_speed: 0.0 - allow_reversing: true - use_rotate_to_heading: false - use_rotate_to_goal: true kp_angle: 6.0 rotate_to_heading_min_angle: 0.785 max_angular_accel: 15.0 cost_scaling_dist: 0.7 cost_scaling_gain: 1.0 inflation_cost_scaling_factor: 5.0 - # RPP Controller from Navigation2 Package - NAV2RPPFollowPath: - plugin: "nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController" - desired_linear_vel: 0.4 - # acceleration limiting is not implemented yet - max_linear_accel: 0.0001 - max_linear_decel: 0.0001 - lookahead_dist: 0.2 - min_lookahead_dist: 0.05 - max_lookahead_dist: 0.4 - lookahead_time: 1.0 - rotate_to_heading_angular_vel: 2.5 - transform_tolerance: 0.1 - use_velocity_scaled_lookahead_dist: true - min_approach_linear_velocity: 0.05 - use_approach_linear_velocity_scaling: true - max_allowed_time_to_collision: 0.6 - use_regulated_linear_velocity_scaling: true - use_cost_regulated_linear_velocity_scaling: false - regulated_linear_scaling_min_radius: 0.2 - regulated_linear_scaling_min_speed: 0.1 - allow_reversing: false - use_rotate_to_heading: true - rotate_to_heading_min_angle: 0.785 - max_angular_accel: 3.5 - cost_scaling_dist: 0.7 - cost_scaling_gain: 1.0 - inflation_cost_scaling_factor: 5.0 - -controller_server_rclcpp_node: - ros__parameters: - use_sim_time: True -local_costmap: +/small/local_costmap: local_costmap: ros__parameters: - update_frequency: 5.0 + update_frequency: 10.0 publish_frequency: 5.0 global_frame: map robot_base_frame: base_link use_sim_time: True rolling_window: True - width: 3 - height: 3 - resolution: 0.01 + width: 1 + height: 1 + resolution: 0.07 robot_radius: 0.17 - # footprint: "[ [0.1, 0.15], [0.1, -0.15], [-0.1, -0.15], [-0.1, 0.15] ]" + use_maximum: true plugins: ["obstacle_layer", "inflation_layer"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True observation_sources: scan scan: - topic: /small/scan_inflated + topic: /small/scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" inf_is_valid: True + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 4.0 inflation_radius: 1.0 always_send_full_costmap: True - local_costmap_client: - ros__parameters: - use_sim_time: True - local_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True -global_costmap: +/small/global_costmap: global_costmap: ros__parameters: - update_frequency: 2.0 + update_frequency: 10.0 publish_frequency: 2.0 global_frame: map robot_base_frame: base_link use_sim_time: True + rolling_window: True robot_radius: 0.2 - resolution: 0.02 - track_unknown_space: true - plugins: ["static_layer", "obstacle_layer", "inflation_layer"] + resolution: 0.07 + use_maximum: true + plugins: ["obstacle_layer", "inflation_layer", "temporal_obstacle_layer"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True observation_sources: scan scan: - topic: /small/scan_inflated + topic: /small/scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" inf_is_valid: True - static_layer: - plugin: "nav2_costmap_2d::StaticLayer" - map_subscribe_transient_local: True + raytrace_max_range: 3.0 + raytrace_min_range: 0.0 + obstacle_max_range: 2.5 + obstacle_min_range: 0.0 inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 4.0 inflation_radius: 1.0 + temporal_obstacle_layer: + plugin: "mep3_navigation::TemporalObstacleLayer" + add_obstacle_topic: /small/add_obstacle + remove_obstacle_topic: /small/remove_obstacle always_send_full_costmap: True - global_costmap_client: - ros__parameters: - use_sim_time: True - global_costmap_rclcpp_node: - ros__parameters: - use_sim_time: True -map_server: - ros__parameters: - use_sim_time: True - yaml_filename: "map.yaml" - -map_saver: - ros__parameters: - use_sim_time: True - save_map_timeout: 5.0 - free_thresh_default: 0.25 - occupied_thresh_default: 0.65 - map_subscribe_transient_local: True - -planner_server: +/small/planner_server: ros__parameters: use_sim_time: True planner_plugins: ["GridBased"] @@ -264,58 +185,29 @@ planner_server: GridBased: plugin: 'nav2_navfn_planner/NavfnPlanner' use_astar: True - allow_unknown: false + allow_unknown: true use_final_approach_orientation: False - tolerance: 0.005 - _GridBased: - plugin: "nav2_smac_planner/SmacPlanner2D" - tolerance: 0.02 - downsample_costmap: false # whether or not to downsample the map - downsampling_factor: 1 # multiplier for the resolution of the costmap layer (e.g. 2 on a 5cm costmap would be 10cm) - allow_unknown: true # allow traveling in unknown space - max_iterations: 1000000 # maximum total iterations to search for before failing (in case unreachable), set to -1 to disable - max_on_approach_iterations: 1000 # maximum number of iterations to attempt to reach goal once in tolerance - max_planning_time: 0.2 # max time in s for planner to plan, smooth - motion_model_for_search: "MOORE" # 2D Moore, Von Neumann - cost_travel_multiplier: 5.0 # Cost multiplier to apply to search to steer away from high cost areas. Larger values will place in the center of aisles more exactly (if non-`FREE` cost potential field exists) but take slightly longer to compute. To optimize for speed, a value of 1.0 is reasonable. A reasonable tradeoff value is 2.0. A value of 0.0 effective disables steering away from obstacles and acts like a naive binary search A*. - use_final_approach_orientation: false # Whether to set the final path pose at the goal's orientation to the requested orientation (false) or in line with the approach angle so the robot doesn't rotate to heading (true) - smoother: - max_iterations: 1000 - w_smooth: 0.4 - w_data: 0.2 - tolerance: 1e-10 + tolerance: 0.025 -planner_server_rclcpp_node: - ros__parameters: - use_sim_time: True - -recoveries_server: +/small/behavior_server: ros__parameters: costmap_topic: local_costmap/costmap_raw footprint_topic: local_costmap/published_footprint cycle_frequency: 10.0 - recovery_plugins: ["spin", "backup", "wait"] + behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"] spin: - plugin: "nav2_recoveries/Spin" + plugin: "nav2_behaviors/Spin" backup: - plugin: "nav2_recoveries/BackUp" + plugin: "nav2_behaviors/BackUp" + drive_on_heading: + plugin: "nav2_behaviors/DriveOnHeading" wait: - plugin: "nav2_recoveries/Wait" + plugin: "nav2_behaviors/Wait" global_frame: odom robot_base_frame: base_link - transform_timeout: 0.1 + transform_tolerance: 0.1 use_sim_time: true simulate_ahead_time: 2.0 max_rotational_vel: 1.0 min_rotational_vel: 0.4 rotational_acc_lim: 3.2 - -waypoint_follower: - ros__parameters: - loop_rate: 20 - stop_on_failure: false - waypoint_task_executor_plugin: "wait_at_waypoint" - wait_at_waypoint: - plugin: "nav2_waypoint_follower::WaitAtWaypoint" - enabled: True - waypoint_pause_duration: 200 diff --git a/mep3_navigation/src/distance_angle/.clang-format b/mep3_navigation/src/distance_angle/.clang-format deleted file mode 100644 index 33bf2a3b9..000000000 --- a/mep3_navigation/src/distance_angle/.clang-format +++ /dev/null @@ -1,137 +0,0 @@ ---- -Language: Cpp -# BasedOnStyle: LLVM -AccessModifierOffset: -2 -AlignAfterOpenBracket: Align -AlignConsecutiveMacros: false -AlignConsecutiveAssignments: false -AlignConsecutiveDeclarations: false -AlignEscapedNewlines: Right -AlignOperands: true -AlignTrailingComments: true -AllowAllArgumentsOnNextLine: true -AllowAllConstructorInitializersOnNextLine: true -AllowAllParametersOfDeclarationOnNextLine: true -AllowShortBlocksOnASingleLine: Never -AllowShortCaseLabelsOnASingleLine: false -AllowShortFunctionsOnASingleLine: All -AllowShortLambdasOnASingleLine: All -AllowShortIfStatementsOnASingleLine: Never -AllowShortLoopsOnASingleLine: false -AlwaysBreakAfterDefinitionReturnType: None -AlwaysBreakAfterReturnType: None -AlwaysBreakBeforeMultilineStrings: false -AlwaysBreakTemplateDeclarations: MultiLine -BinPackArguments: true -BinPackParameters: true -BraceWrapping: - AfterCaseLabel: false - AfterClass: false - AfterControlStatement: false - AfterEnum: false - AfterFunction: false - AfterNamespace: false - AfterObjCDeclaration: false - AfterStruct: false - AfterUnion: false - AfterExternBlock: false - BeforeCatch: false - BeforeElse: false - IndentBraces: false - SplitEmptyFunction: true - SplitEmptyRecord: true - SplitEmptyNamespace: true -BreakBeforeBinaryOperators: None -BreakBeforeBraces: Attach -BreakBeforeInheritanceComma: false -BreakInheritanceList: BeforeColon -BreakBeforeTernaryOperators: true -BreakConstructorInitializersBeforeComma: false -BreakConstructorInitializers: BeforeColon -BreakAfterJavaFieldAnnotations: false -BreakStringLiterals: true -ColumnLimit: 80 -CommentPragmas: '^ IWYU pragma:' -CompactNamespaces: false -ConstructorInitializerAllOnOneLineOrOnePerLine: false -ConstructorInitializerIndentWidth: 4 -ContinuationIndentWidth: 4 -Cpp11BracedListStyle: true -DeriveLineEnding: true -DerivePointerAlignment: false -DisableFormat: false -ExperimentalAutoDetectBinPacking: false -FixNamespaceComments: true -ForEachMacros: - - foreach - - Q_FOREACH - - BOOST_FOREACH -IncludeBlocks: Preserve -IncludeCategories: - - Regex: '^"(llvm|llvm-c|clang|clang-c)/' - Priority: 2 - SortPriority: 0 - - Regex: '^(<|"(gtest|gmock|isl|json)/)' - Priority: 3 - SortPriority: 0 - - Regex: '.*' - Priority: 1 - SortPriority: 0 -IncludeIsMainRegex: '(Test)?$' -IncludeIsMainSourceRegex: '' -IndentCaseLabels: false -IndentGotoLabels: true -IndentPPDirectives: None -IndentWidth: 2 -IndentWrappedFunctionNames: false -JavaScriptQuotes: Leave -JavaScriptWrapImports: true -KeepEmptyLinesAtTheStartOfBlocks: true -MacroBlockBegin: '' -MacroBlockEnd: '' -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCBinPackProtocolList: Auto -ObjCBlockIndentWidth: 2 -ObjCSpaceAfterProperty: false -ObjCSpaceBeforeProtocolList: true -PenaltyBreakAssignment: 2 -PenaltyBreakBeforeFirstCallParameter: 19 -PenaltyBreakComment: 300 -PenaltyBreakFirstLessLess: 120 -PenaltyBreakString: 1000 -PenaltyBreakTemplateDeclaration: 10 -PenaltyExcessCharacter: 1000000 -PenaltyReturnTypeOnItsOwnLine: 60 -PointerAlignment: Right -ReflowComments: true -SortIncludes: true -SortUsingDeclarations: true -SpaceAfterCStyleCast: false -SpaceAfterLogicalNot: false -SpaceAfterTemplateKeyword: true -SpaceBeforeAssignmentOperators: true -SpaceBeforeCpp11BracedList: false -SpaceBeforeCtorInitializerColon: true -SpaceBeforeInheritanceColon: true -SpaceBeforeParens: ControlStatements -SpaceBeforeRangeBasedForLoopColon: true -SpaceInEmptyBlock: false -SpaceInEmptyParentheses: false -SpacesBeforeTrailingComments: 1 -SpacesInAngles: false -SpacesInConditionalStatement: false -SpacesInContainerLiterals: true -SpacesInCStyleCastParentheses: false -SpacesInParentheses: false -SpacesInSquareBrackets: false -SpaceBeforeSquareBrackets: false -Standard: Latest -StatementMacros: - - Q_UNUSED - - QT_REQUIRE_VERSION -TabWidth: 8 -UseCRLF: false -UseTab: Never -... - diff --git a/mep3_navigation/src/distance_angle/distance_angle_regulator.cpp b/mep3_navigation/src/distance_angle/distance_angle_regulator.cpp deleted file mode 100644 index d0335fe30..000000000 --- a/mep3_navigation/src/distance_angle/distance_angle_regulator.cpp +++ /dev/null @@ -1,989 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#include "mep3_navigation/distance_angle/distance_angle_regulator.hpp" - -#include -#include -#include -#include -#include -#include -#include - -#include "tf2/utils.h" - -using std::placeholders::_1; -using std::placeholders::_2; -using namespace std::chrono_literals; - -DistanceAngleRegulator::DistanceAngleRegulator(const rclcpp::NodeOptions & options) -: Node("distance_angle_regulator", options) -{ - odometry_subscription_ = this->create_subscription( - "odom", 10, std::bind(&DistanceAngleRegulator::odometry_callback, this, _1)); - twist_publisher_ = this->create_publisher("cmd_vel", 10); - - /* PARAMETER DECLARATION */ - this->declare_parameter("kp_distance", 4.0); - this->declare_parameter("ki_distance", 0.0); - this->declare_parameter("kd_distance", 0.0); // na pravom robotu 5.0 - this->declare_parameter("d_term_filter_distance", 0.1); - - this->declare_parameter("kp_angle", 4.0); - this->declare_parameter("ki_angle", 0.0); - this->declare_parameter("kd_angle", 0.0); // na pravom robotu 3.5 - this->declare_parameter("d_term_filter_angle", 0.1); - - this->declare_parameter("distance_goal_tolerance", 0.002); - this->declare_parameter("angle_goal_tolerance", 0.018); - - this->declare_parameter("control_frequency", 100.0); - - debug_ = this->declare_parameter("debug", false); - parameters_callback_handle_ = this->add_on_set_parameters_callback( - std::bind(&DistanceAngleRegulator::parameters_callback, this, std::placeholders::_1)); - /**********************************************/ - - /* DISTANCE REGULATOR PARAMETERS */ - this->get_parameter("kp_distance", regulator_distance_.kp); - this->get_parameter("ki_distance", regulator_distance_.ki); - this->get_parameter("kd_distance", regulator_distance_.kd); - regulator_distance_.clamp_min = -2.5; - regulator_distance_.clamp_max = 2.5; - regulator_distance_.integrator_min = -0.08; - regulator_distance_.integrator_max = 0.08; - this->get_parameter("d_term_filter_distance", regulator_distance_.d_term_filter_coefficient); - regulator_distance_.angle_mode = false; - - this->get_parameter("distance_goal_tolerance", distance_goal_tolerance_); - /*****************************************************/ - - /* ANGLE REGULATOR PARAMETERS */ - this->get_parameter("kp_angle", regulator_angle_.kp); - this->get_parameter("ki_angle", regulator_angle_.ki); - this->get_parameter("kd_angle", regulator_angle_.kd); - regulator_angle_.clamp_min = -20.0; - regulator_angle_.clamp_max = 20.0; - regulator_angle_.integrator_min = -1.0; - regulator_angle_.integrator_max = 1.0; - this->get_parameter("d_term_filter_angle", regulator_angle_.d_term_filter_coefficient); - regulator_angle_.angle_mode = true; - - this->get_parameter("angle_goal_tolerance", angle_goal_tolerance_); - /*****************************************************/ - - odom_robot_distance_ = 0; - position_initialized_ = false; - - action_running_ = false; - output_enabled_ = false; - - run_process_frame_thread_ = true; - - check_collision_ = false; - - tf_buffer_ = std::make_unique(this->get_clock()); - transform_listener_ = std::make_shared(*tf_buffer_); - - // This thread converts robot pose to polar coords using tf2 listener - process_frame_thread_ = std::thread(&DistanceAngleRegulator::process_robot_frame, this); - - double control_frequency; - this->get_parameter("control_frequency", control_frequency); - const double control_period = 1.0 / control_frequency; - motion_profile_ = new ruckig::Ruckig<2>{control_period}; - std::chrono::duration chrono_control_period(control_period); - timer_ = rclcpp::create_timer( - this, this->get_clock(), chrono_control_period, - std::bind(&DistanceAngleRegulator::control_loop, this)); - - // Disabling Synchronization is important. We want independent control for distance and angle. - motion_profile_input_.synchronization = ruckig::Synchronization::None; - motion_profile_input_.max_velocity = {0.2, 2.0}; - motion_profile_input_.max_acceleration = {0.8, 1.5}; - motion_profile_input_.max_jerk = { - 999999999999.0, 999999999999.0}; // force trapezoidal velocity profile - motion_profile_result_ = ruckig::Result::Finished; - - can_publisher_ = this->create_publisher("can_send", 100); - - navigate_to_pose_server_ = std::make_unique( - this, "precise_navigate_to_pose", - std::bind(&DistanceAngleRegulator::navigate_to_pose, this), nullptr, - std::chrono::milliseconds(1500), true, rcl_action_server_get_default_options() - ); - - motion_command_server_ = std::make_unique( - this, "motion_command", - std::bind(&DistanceAngleRegulator::motion_command, this), nullptr, - std::chrono::milliseconds(1500), true, rcl_action_server_get_default_options() - ); - - distance_setpoint_publisher_ = this->create_publisher("distance_setpoint", 10); - distance_publisher_ = this->create_publisher("robot_distance", 10); - angle_setpoint_publisher_ = this->create_publisher("angle_setpoint", 10); - angle_publisher_ = this->create_publisher("robot_angle", 10); - - navigate_to_pose_server_->activate(); - motion_command_server_->activate(); -} - -void DistanceAngleRegulator::init() -{ - // setup collision checker - std::string costmap_topic, footprint_topic; - costmap_topic = "local_costmap/costmap_raw"; - footprint_topic = "local_costmap/published_footprint"; - - costmap_sub_ = - std::make_shared(shared_from_this(), costmap_topic); - footprint_sub_ = std::make_shared( - shared_from_this(), footprint_topic, transform_tolerance_); - collision_checker_ = std::make_shared( - *costmap_sub_, *footprint_sub_, *tf_buffer_, "collision_checker", "map", "base_link", - transform_tolerance_); -} - -DistanceAngleRegulator::~DistanceAngleRegulator() -{ - run_process_frame_thread_ = false; - process_frame_thread_.join(); -} - -void DistanceAngleRegulator::odometry_callback(const nav_msgs::msg::Odometry::SharedPtr msg) -{ - rclcpp::Time time = this->get_clock()->now(); - - std::unique_lock lock(data_mutex_); - - odom_robot_x_ = msg->pose.pose.position.x; - odom_robot_y_ = msg->pose.pose.position.y; - - if (!position_initialized_) { - prev_odom_robot_x_ = odom_robot_x_; - prev_odom_robot_y_ = odom_robot_y_; - position_initialized_ = true; - - odom_robot_speed_linear_ = 0.0; - odom_robot_speed_angular_ = 0.0; - - odom_robot_angle_ = tf2::getYaw(msg->pose.pose.orientation); - - motion_profile_input_.current_position = {0.0, odom_robot_angle_}; - motion_profile_input_.target_position = {0.0, odom_robot_angle_}; - } - - odom_robot_angle_ = tf2::getYaw(msg->pose.pose.orientation); - - const double delta_x = odom_robot_x_ - prev_odom_robot_x_; - const double delta_y = odom_robot_y_ - prev_odom_robot_y_; - const double distance_increment = std::hypot(delta_x, delta_y); - const double distance_increment_angle = std::atan2(delta_y, delta_x); - - int sign = 1; - if (std::abs(angle_normalize(odom_robot_angle_ - distance_increment_angle)) > 0.1) { - sign = -1; - } - - odom_robot_distance_ += sign * distance_increment; - - odom_robot_speed_linear_ = msg->twist.twist.linear.x; - odom_robot_speed_angular_ = msg->twist.twist.angular.z; - - prev_odom_robot_x_ = odom_robot_x_; - prev_odom_robot_y_ = odom_robot_y_; - - lock.unlock(); -} - -void DistanceAngleRegulator::process_robot_frame() -{ - rclcpp::Rate r(200); - - while (run_process_frame_thread_) { - std::string to_frame = "map"; - std::string from_frame = "base_link"; - geometry_msgs::msg::TransformStamped transform_stamped; - - try { - transform_stamped = tf_buffer_->lookupTransform(to_frame, from_frame, tf2::TimePointZero); - } catch (tf2::TransformException & ex) { - // no transform available, sleep and rerun the loop - r.sleep(); - continue; - } - - std::unique_lock lock(data_mutex_); - - map_robot_x_ = transform_stamped.transform.translation.x; - map_robot_y_ = transform_stamped.transform.translation.y; - map_robot_angle_ = tf2::getYaw(transform_stamped.transform.rotation); - - lock.unlock(); - - r.sleep(); - } -} - -void DistanceAngleRegulator::reset_stuck() -{ - distance_fail_count_ = 0; - angle_fail_count_ = 0; - robot_stuck_ = false; - reset_regulation(); - - can_msgs::msg::Frame msg; - msg.id = 0x00002000; - msg.dlc = 1; - msg.data[0] = 0x11; // CMD_RESET_REGULATORS - can_publisher_->publish(msg); - msg.data[0] = 0x15; // CMD_SETPOINTS_ENABLE - can_publisher_->publish(msg); -} - -void DistanceAngleRegulator::control_loop() -{ - std::unique_lock lock(data_mutex_); - - regulator_distance_.feedback = odom_robot_distance_; - regulator_angle_.feedback = odom_robot_angle_; - - /* RUCKIG */ - motion_profile_result_ = motion_profile_->update(motion_profile_input_, motion_profile_output_); - - if (motion_profile_result_ == ruckig::Result::Working) { - regulator_distance_.reference = motion_profile_output_.new_position[0]; - regulator_angle_.reference = angle_normalize(motion_profile_output_.new_position[1]); - motion_profile_output_.pass_to_input(motion_profile_input_); - } - /**********/ - - const double prev_distance_error = regulator_distance_.error; - const double prev_angle_error = regulator_angle_.error; - - pid_regulator_update(®ulator_distance_); - pid_regulator_update(®ulator_angle_); - - if (debug_) { - RCLCPP_INFO(this->get_logger(), "Robot distance: %lf", odom_robot_distance_); - RCLCPP_INFO( - this->get_logger(), "Regulator distance reference: %lf", regulator_distance_.reference); - RCLCPP_INFO(this->get_logger(), "Regulator distance error: %lf\n", regulator_distance_.error); - - RCLCPP_INFO(this->get_logger(), "Robot angle: %lf", odom_robot_angle_); - RCLCPP_INFO(this->get_logger(), "Robot angle deg: %lf", odom_robot_angle_ * 180.0 / M_PI); - RCLCPP_INFO( - this->get_logger(), "Robot angle reference deg: %lf", - regulator_angle_.reference * 180.0 / M_PI); - RCLCPP_INFO( - this->get_logger(), "Regulator angle error deg: %lf\n", - regulator_angle_.error * 180.0 / M_PI); - } - - geometry_msgs::msg::Twist motor_command; - motor_command.linear.x = regulator_distance_.command; - motor_command.angular.z = regulator_angle_.command; - - const bool distance_finished = distance_regulator_finished(); - const bool angle_finished = angle_regulator_finished(); - - if (action_running_) { - output_enabled_ = true; - } - if (output_enabled_) { - if (distance_finished && angle_finished) { - output_enabled_ = false; - motor_command.linear.x = 0.0; - motor_command.angular.z = 0.0; - } - - /*** STUCK DETECTION ***/ - if (stuck_enabled_ && !robot_stuck_) { - const double stuck_distance_jump = 0.25; // meters - const double stuck_angle_jump = 2.8; - const int distance_max_fail_count = 50; - const int angle_max_fail_count = 50; - - const bool prev_stuck_state = robot_stuck_; - - // DISTANCE STUCK - if (std::abs(regulator_distance_.error - prev_distance_error) > stuck_distance_jump) { - robot_stuck_ = true; - RCLCPP_WARN(this->get_logger(), "Distance Stuck 1!"); - } - - if ( - (sgn(regulator_distance_.error) != sgn(odom_robot_speed_linear_) && - std::abs(odom_robot_speed_linear_) > 0.25) || - (std::abs(regulator_distance_.command) > regulator_distance_.clamp_max / 4.0 && - std::abs(odom_robot_speed_linear_) < 0.15)) { - distance_fail_count_++; - if (distance_fail_count_ > distance_max_fail_count) { - robot_stuck_ = true; - distance_fail_count_ = 0; - RCLCPP_WARN(this->get_logger(), "Distance Stuck 2!"); - } - } else { - distance_fail_count_ = 0; - } - - // ANGLE STUCK - if (std::abs(regulator_angle_.error - prev_angle_error) > stuck_angle_jump) { - robot_stuck_ = true; - RCLCPP_WARN(this->get_logger(), "Angle Stuck 1!"); - } - - if ( - std::abs(regulator_angle_.error) > 0.1 && - (sgn(regulator_angle_.error) != sgn(odom_robot_speed_angular_) || - std::abs(odom_robot_speed_angular_) < 0.004)) { - angle_fail_count_++; - if (angle_fail_count_ > angle_max_fail_count) { - robot_stuck_ = true; - angle_fail_count_ = 0; - RCLCPP_WARN(this->get_logger(), "Angle Stuck 2!"); - } - - } else { - angle_fail_count_ = 0; - } - - // Display warn only once - if (robot_stuck_ && prev_stuck_state != true) { - RCLCPP_INFO(this->get_logger(), "STUCK DETECTED!"); - } - - // If robot is stuck, reset regulation - if (robot_stuck_) { - motor_command.linear.x = 0.0; - motor_command.angular.z = 0.0; - // Reset regulators on motion board - can_msgs::msg::Frame msg; - msg.id = 0x00002000; - msg.dlc = 1; - msg.data[0] = 0x11; // CMD_RESET_REGULATORS - can_publisher_->publish(msg); - msg.data[0] = 0x16; // CMD_SETPOINTS_DISABLE - can_publisher_->publish(msg); - reset_regulation(); - } - } - /***********************/ - - /*** COLLISION DETECTION ***/ - if (check_collision_) { - geometry_msgs::msg::Pose2D current_pose_2d; - current_pose_2d.x = map_robot_x_; - current_pose_2d.y = map_robot_y_; - current_pose_2d.theta = map_robot_angle_; - - geometry_msgs::msg::Twist project_command = motor_command; - if (project_command.linear.x < 0.05) { - project_command.linear.x = 0.2; - } - - bool is_collision_ahead = false; - - const double projection_time = 0.02 / project_command.linear.x; - - int project_cnt = 1; - while (true) { - if (project_cnt * projection_time >= 0.5) { - break; - } - - project_cnt++; - - geometry_msgs::msg::Pose2D projected_pose = - projectPose(current_pose_2d, project_command, project_cnt * projection_time); - - is_collision_ahead = !collision_checker_->isCollisionFree(projected_pose); - - if (is_collision_ahead) { - break; - } - - } - - if (is_collision_ahead && check_collision_) { - RCLCPP_INFO(this->get_logger(), "COLLISION AHEAD!"); - motor_command.linear.x = 0.0; - motor_command.angular.z = 0.0; - - // stop pnp action - navigate_to_pose_server_->terminate_all(); - action_running_ = false; - output_enabled_ = false; - - reset_regulation(); - } - } - /*******************************************/ - auto tuning_msg = std_msgs::msg::Float64(); - tuning_msg.data = regulator_distance_.reference; - distance_setpoint_publisher_->publish(tuning_msg); - - tuning_msg.data = regulator_distance_.feedback; - distance_publisher_->publish(tuning_msg); - - tuning_msg.data = regulator_angle_.reference; - angle_setpoint_publisher_->publish(tuning_msg); - - tuning_msg.data = regulator_angle_.feedback; - angle_publisher_->publish(tuning_msg); - - twist_publisher_->publish(motor_command); - } - - system_time_ += 10; // + 10 ms - - lock.unlock(); -} - -rcl_interfaces::msg::SetParametersResult DistanceAngleRegulator::parameters_callback( - const std::vector & parameters) -{ - rcl_interfaces::msg::SetParametersResult result; - result.successful = true; - result.reason = "success"; - - for (const auto & param : parameters) { - if (param.get_name() == "kp_distance") { - regulator_distance_.kp = param.as_double(); - } else if (param.get_name() == "ki_distance") { - regulator_distance_.ki = param.as_double(); - } else if (param.get_name() == "kd_distance") { - regulator_distance_.kd = param.as_double(); - } else if (param.get_name() == "d_term_filter_distance") { - regulator_distance_.d_term_filter_coefficient = param.as_double(); - } else if (param.get_name() == "kp_angle") { - regulator_angle_.kp = param.as_double(); - } else if (param.get_name() == "ki_angle") { - regulator_angle_.ki = param.as_double(); - } else if (param.get_name() == "kd_angle") { - regulator_angle_.kd = param.as_double(); - } else if (param.get_name() == "d_term_filter_angle") { - regulator_angle_.d_term_filter_coefficient = param.as_double(); - } else if (param.get_name() == "distance_goal_tolerance") { - distance_goal_tolerance_ = param.as_double(); - } else if (param.get_name() == "angle_goal_tolerance") { - angle_goal_tolerance_ = param.as_double(); - } else if (param.get_name() == "debug") { - debug_ = param.as_bool(); - } - } - - return result; -} - -void DistanceAngleRegulator::motion_command() -{ - auto result = std::make_shared(); - auto goal = motion_command_server_->get_current_goal(); - - std::unique_lock lock(data_mutex_); - - rclcpp::Rate r(50); - - if (action_running_) { - RCLCPP_WARN( - this->get_logger(), "Tried calling motion command action while other action is running!"); - motion_command_server_->terminate_current(); - return; - } else { - reset_stuck(); - reset_regulation(); - action_running_ = true; - check_collision_ = false; - - lock.unlock(); - - r.sleep(); - - lock.lock(); - } - - if (goal->velocity_linear != 0) { - motion_profile_input_.max_velocity[0] = goal->velocity_linear; - } - - if (goal->acceleration_linear != 0) { - motion_profile_input_.max_acceleration[0] = goal->acceleration_linear; - } - - if (goal->velocity_angular != 0) { - motion_profile_input_.max_velocity[1] = goal->velocity_angular; - } - - if (goal->acceleration_angular != 0) { - motion_profile_input_.max_acceleration[1] = goal->acceleration_angular; - } - lock.unlock(); - - enum class MotionState { START, RUNNING_COMMAND, RUNNING_COMMAND_STUCK, FINISHED }; - MotionState state = MotionState::START; - - - const int timeout = 40; - int timeout_counter = 0; - - while (rclcpp::ok()) { - lock.lock(); - - if (motion_command_server_->is_cancel_requested()) { - softstop(); - action_running_ = false; - result->set__result("drift"); - motion_command_server_->terminate_current(result); - return; - } - - if (motion_command_server_->is_preempt_requested()) { - // preempting this action does not make much sense - motion_command_server_->terminate_pending_goal(); - } - - if (robot_stuck_) { - action_running_ = false; - RCLCPP_WARN(this->get_logger(), "Motion Command FAILED with stuck"); - motion_command_server_->terminate_current(); - return; - } - - switch (state) { - case MotionState::START: - if (goal->command == "forward") { - forward(goal->value); - state = MotionState::RUNNING_COMMAND; - } else if (goal->command == "forward_stuck") { - forward(goal->value); - state = MotionState::RUNNING_COMMAND_STUCK; - } else if (goal->command == "rotate_absolute") { - rotate_absolute(goal->value); - state = MotionState::RUNNING_COMMAND; - } else if (goal->command == "rotate_relative") { - rotate_relative(goal->value); - state = MotionState::RUNNING_COMMAND; - } - timeout_counter = timeout; - - break; - - case MotionState::RUNNING_COMMAND: - if (motion_profile_finished()) { - timeout_counter--; - } - if (timeout_counter <= 0) { - state = MotionState::FINISHED; - } - if (distance_regulator_finished() && angle_regulator_finished()) { - state = MotionState::FINISHED; - } - break; - - case MotionState::RUNNING_COMMAND_STUCK: - if (motion_profile_finished()) { - result->set__result("success"); - action_running_ = false; - reset_regulation(); - reset_stuck(); - - motion_command_server_->succeeded_current(result); - return; - } - break; - - case MotionState::FINISHED: - if (distance_regulator_finished() && angle_regulator_finished()) { - result->set__result("success"); - } else { - result->set__result("drift"); - } - - action_running_ = false; - - motion_command_server_->succeeded_current(result); - return; - break; - - default: - break; - } - int64_t curr_t = system_time_; - lock.unlock(); - while (1) { - lock.lock(); - const int64_t delta_sys_t = system_time_ - curr_t; - lock.unlock(); - if (delta_sys_t >= 20) { - break; - } else { - r.sleep(); - } - } - } -} - -double DistanceAngleRegulator::angle_normalize(double angle) -{ - while (angle > M_PI) { - angle -= 2.0 * M_PI; - } - while (angle < -M_PI) { - angle += 2.0 * M_PI; - } - - return angle; -} -void DistanceAngleRegulator::forward(double distance) -{ - motion_profile_result_ = ruckig::Working; - motion_profile_input_.target_position[0] = motion_profile_input_.current_position[0] + distance; -} - -void DistanceAngleRegulator::rotate_absolute(double angle) -{ - motion_profile_result_ = ruckig::Working; - // absolute rotate based on map angle - rotate_relative(angle_normalize(angle - map_robot_angle_)); -} - -void DistanceAngleRegulator::rotate_relative(double angle) -{ - motion_profile_result_ = ruckig::Working; - motion_profile_input_.target_position[1] = motion_profile_input_.current_position[1] + angle; -} - -void DistanceAngleRegulator::softstop() -{ - const double robot_velocity_linear = motion_profile_output_.new_velocity[0]; - const double robot_velocity_angular = motion_profile_output_.new_velocity[1]; - double linear_stop_distance = - std::pow(robot_velocity_linear, 2) / (2.0 * motion_profile_input_.max_acceleration[0]); - double angular_stop_distance = - std::pow(robot_velocity_angular, 2) / (2.0 * motion_profile_input_.max_acceleration[1]); - - linear_stop_distance = std::copysign(linear_stop_distance, robot_velocity_linear); - angular_stop_distance = std::copysign(angular_stop_distance, robot_velocity_angular); - forward(linear_stop_distance); - rotate_relative(angular_stop_distance); -} - -bool DistanceAngleRegulator::distance_regulator_finished() -{ - return motion_profile_finished() && - (std::abs(regulator_distance_.error) < distance_goal_tolerance_); -} - -bool DistanceAngleRegulator::angle_regulator_finished() -{ - return motion_profile_finished() && (std::abs(regulator_angle_.error) < angle_goal_tolerance_); -} - -bool DistanceAngleRegulator::motion_profile_finished() -{ - return motion_profile_result_ != ruckig::Result::Working; -} - -void DistanceAngleRegulator::reset_regulation() -{ - motion_profile_input_.current_position[0] = odom_robot_distance_; - motion_profile_input_.current_position[1] = odom_robot_angle_; - - motion_profile_input_.target_position[0] = odom_robot_distance_; - motion_profile_input_.target_position[1] = odom_robot_angle_; - - pid_regulator_reset(®ulator_distance_); - pid_regulator_reset(®ulator_angle_); -} - -void DistanceAngleRegulator::navigate_to_pose() -{ - auto result = std::make_shared(); - auto goal = navigate_to_pose_server_->get_current_goal(); - - const double goal_x = goal->pose.pose.position.x; - const double goal_y = goal->pose.pose.position.y; - const double goal_angle = tf2::getYaw(goal->pose.pose.orientation); - - enum class MotionState { - START, - ROTATING_TO_GOAL, - MOVING_TO_GOAL, - ROTATING_IN_GOAL, - FINISHED, - SOFTSTOPPING - }; - MotionState state = MotionState::START; - - std::unique_lock lock(data_mutex_); - - reset_stuck(); - - int8_t direction = 1; - bool use_stuck = false; - - if (action_running_) { - RCLCPP_WARN( - this->get_logger(), "Tried calling navigate to goal action while other action is running!"); - navigate_to_pose_server_->terminate_current(); - return; - } else { - reset_regulation(); - action_running_ = true; - - check_collision_ = false; - - std::string input = goal->behavior_tree; - std::vector options; - std::stringstream ss (input); - std::string item; - - while (std::getline(ss, item, ';')) { - options.push_back(item); - } - - for (auto arg : options) { - if (arg == "backward") { - direction = -1; - } else if (arg == "backward_safe") { - direction = -1; - check_collision_ = true; - } else if (arg == "safe") { - check_collision_ = true; - } else if (arg == "stuck") { - use_stuck = true; - } - } - - } - - // coordinate frame conversions - - double delta_x = goal_x - map_robot_x_; - double delta_y = goal_y - map_robot_y_; - double distance_to_goal = std::hypot(delta_x, delta_y); - double angle_to_goal = std::atan2(delta_y, delta_x); - - // Don't execute movement if in tolerance - if ( - distance_to_goal <= distance_goal_tolerance_ && - std::abs(angle_normalize(goal_angle - map_robot_angle_)) <= angle_goal_tolerance_) { - action_running_ = false; - navigate_to_pose_server_->succeeded_current(result); - return; - } - - lock.unlock(); - - rclcpp::Rate r(50); - - const int timeout = 55; - int timeout_counter = 0; - - while (rclcpp::ok() && action_running_) { - lock.lock(); - - if (navigate_to_pose_server_->is_cancel_requested() && state != MotionState::SOFTSTOPPING) { - softstop(); - state = MotionState::SOFTSTOPPING; - timeout_counter = timeout; - RCLCPP_WARN(this->get_logger(), "Cancel requested, softstopping!"); - } - - if (navigate_to_pose_server_->is_preempt_requested() && state != MotionState::SOFTSTOPPING) { - softstop(); - state = MotionState::SOFTSTOPPING; - timeout_counter = timeout; - RCLCPP_WARN(this->get_logger(), "Preempt requested, softstopping!"); - } - - if (robot_stuck_) { - if (use_stuck) { - action_running_ = false; - navigate_to_pose_server_->succeeded_current(result); - RCLCPP_WARN(this->get_logger(), "PNP finished with stuck"); - return; - } else { - action_running_ = false; - RCLCPP_WARN(this->get_logger(), "PNP FAILED with stuck"); - navigate_to_pose_server_->terminate_current(); - return; - } - } - - switch (state) { - case MotionState::START: - rotate_absolute(angle_to_goal + (direction < 0 ? M_PI : 0.0)); - timeout_counter = timeout; - state = MotionState::ROTATING_TO_GOAL; - RCLCPP_WARN(this->get_logger(), "Start rotating to goal!"); - break; - - case MotionState::ROTATING_TO_GOAL: - if (motion_profile_finished()) { - timeout_counter--; - } - if (timeout_counter <= 0) { - softstop(); - state = MotionState::SOFTSTOPPING; - timeout_counter = timeout; - } - if (angle_regulator_finished()) { - delta_x = goal_x - map_robot_x_; - delta_y = goal_y - map_robot_y_; - distance_to_goal = std::hypot(delta_x, delta_y); - forward(direction * distance_to_goal); - timeout_counter = timeout; - state = MotionState::MOVING_TO_GOAL; - RCLCPP_WARN(this->get_logger(), "Moving to goal"); - } - - break; - - case MotionState::MOVING_TO_GOAL: - // RUN_EACH_NTH_CYCLES( - // uint8_t, 5, { - // delta_x = goal_x - map_robot_x_; - // delta_y = goal_y - map_robot_y_; - // distance_to_goal = std::hypot(delta_x, delta_y); - // angle_to_goal = std::atan2(delta_y, delta_x); - // // refresh only for longer moves - // if (distance_to_goal > 0.1) { - // // refresh both distance and angle - // motion_profile_input_.target_position[0] = - // odom_robot_distance_ + direction * distance_to_goal; - // rotate_absolute(angle_to_goal + (direction < 0 ? M_PI : 0.0)); - // } - // }) - - RUN_EACH_NTH_CYCLES( - uint8_t, 15, { - delta_x = goal_x - map_robot_x_; - delta_y = goal_y - map_robot_y_; - distance_to_goal = std::hypot(delta_x, delta_y); - angle_to_goal = std::atan2(delta_y, delta_x); - // refresh only for longer moves - if (distance_to_goal > 0.1) { - // refresh both distance and angle - motion_profile_input_.target_position[0] = - odom_robot_distance_ + direction * distance_to_goal; - rotate_absolute(angle_to_goal + (direction < 0 ? M_PI : 0.0)); - } - }) - - if (motion_profile_finished()) { - timeout_counter--; - } - if (timeout_counter <= 0) { - softstop(); - state = MotionState::SOFTSTOPPING; - timeout_counter = timeout; - } - if (distance_regulator_finished()) { - rotate_absolute(goal_angle); - timeout_counter = timeout; - state = MotionState::ROTATING_IN_GOAL; - RCLCPP_WARN(this->get_logger(), "Rotating in goal"); - } - break; - - case MotionState::ROTATING_IN_GOAL: - if (motion_profile_finished()) { - timeout_counter--; - } - if (timeout_counter <= 0) { - softstop(); - state = MotionState::SOFTSTOPPING; - timeout_counter = timeout; - } - if (angle_regulator_finished()) { - state = MotionState::FINISHED; - } - break; - - case MotionState::FINISHED: - action_running_ = false; - navigate_to_pose_server_->succeeded_current(result); - RCLCPP_WARN(this->get_logger(), "PNP finished"); - return; - break; - - case MotionState::SOFTSTOPPING: - if (motion_profile_finished()) { - timeout_counter--; - } - if (timeout_counter <= 0 || (distance_regulator_finished() && angle_regulator_finished())) { - action_running_ = false; - RCLCPP_WARN(this->get_logger(), "Terminated pnp after softstopping!"); - navigate_to_pose_server_->terminate_current(); - return; - } - break; - - default: - RCLCPP_WARN(this->get_logger(), "PNP default in switch-case, WTF?"); - softstop(); - state = MotionState::SOFTSTOPPING; - timeout_counter = timeout; - break; - } - int64_t curr_t = system_time_; - lock.unlock(); - while (1) { - lock.lock(); - const int64_t delta_sys_t = system_time_ - curr_t; - lock.unlock(); - if (delta_sys_t >= 20) { - break; - } else { - r.sleep(); - } - } - } - RCLCPP_WARN(this->get_logger(), "PNP while loop condition returned false, terminating action!"); - navigate_to_pose_server_->terminate_current(result); -} - -geometry_msgs::msg::Pose2D DistanceAngleRegulator::projectPose( - geometry_msgs::msg::Pose2D pose, geometry_msgs::msg::Twist twist, double projection_time) -{ - geometry_msgs::msg::Pose2D projected_pose = pose; - - projected_pose.x += - projection_time * (twist.linear.x * cos(pose.theta) + twist.linear.y * sin(pose.theta)); - - projected_pose.y += - projection_time * (twist.linear.x * sin(pose.theta) - twist.linear.y * cos(pose.theta)); - - projected_pose.theta += projection_time * twist.angular.z; - - return projected_pose; -} - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - rclcpp::ExecutorOptions options; - rclcpp::executors::MultiThreadedExecutor executor( - options, (size_t)4, false, std::chrono::nanoseconds(-1)); - auto node = std::make_shared(); - node->init(); - executor.add_node(node); - executor.spin(); - rclcpp::shutdown(); - - return 0; -} diff --git a/mep3_navigation/src/distance_angle/motion_profile.cpp b/mep3_navigation/src/distance_angle/motion_profile.cpp deleted file mode 100644 index 78bd7804d..000000000 --- a/mep3_navigation/src/distance_angle/motion_profile.cpp +++ /dev/null @@ -1,142 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#include "mep3_navigation/distance_angle/motion_profile.hpp" - -#include -#include - -#include "rclcpp/duration.hpp" - -MotionProfile::MotionProfile() -{ - position_ = 0; - position_initial_ = 0; - setpoint_ = 0; - velocity_max_ = 0.1; - acceleration_max_ = 0.01; - - state_ = ProfileState::FINISHED; -} - -MotionProfile::MotionProfile(double position_initial, double velocity_max, double acceleration_max) -{ - position_ = position_initial; - position_initial_ = position_initial; - setpoint_ = position_initial; - velocity_max_ = velocity_max; - acceleration_max_ = acceleration_max; - - state_ = ProfileState::FINISHED; -} - -void MotionProfile::plan( - double position_initial, double setpoint, double velocity_initial, double velocity_final, - rclcpp::Time time) -{ - state_ = ProfileState::ACCELERATION; - time_initial_ = time; - position_initial_ = position_initial; - setpoint_ = setpoint; - velocity_initial_ = velocity_initial; - velocity_final_ = velocity_final; - - const double x_stop = - position_initial_ + - (std::pow(velocity_final_, 2) - std::pow(velocity_initial_, 2)) / (2.0 * acceleration_max_); - const double s = std::signbit(setpoint_ - x_stop) ? -1.0 : 1.0; - - acceleration_ = s * acceleration_max_; - deceleration_ = -s * acceleration_max_; - velocity_cruising_ = s * velocity_max_; - - double delta_t1 = std::abs((velocity_cruising_ - velocity_initial_) / acceleration_); - double delta_t3 = -velocity_cruising_ / deceleration_; - const double delta_x1 = velocity_initial_ * delta_t1 + acceleration_ * pow(delta_t1, 2) / 2.0; - const double delta_x3 = velocity_cruising_ * delta_t3 + deceleration_ * pow(delta_t3, 2) / 2.0; - - double delta_t2 = (setpoint_ - (position_initial_ + delta_x1 + delta_x3)) / velocity_cruising_; - - if (std::signbit(delta_t2)) { - // trapezoidal profile not possible - velocity_cruising_ = s * sqrt( - s * acceleration_max_ * (setpoint_ - position_initial_) + - pow(velocity_initial_, 2) / 2.0); - delta_t2 = 0; - delta_t1 = std::abs((velocity_cruising_ - velocity_initial_) / acceleration_); - delta_t3 = -velocity_cruising_ / deceleration_; - } - - t0_ = 0; - t1_ = t0_ + delta_t1; - t2_ = t1_ + delta_t2; - t3_ = t2_ + delta_t3; - - y1_ = - position_initial_ + velocity_initial_ * delta_t1 + acceleration_ * delta_t1 * delta_t1 / 2.0; - y2_ = y1_ + velocity_cruising_ * delta_t2; -} - -double MotionProfile::update(rclcpp::Time time) -{ - rclcpp::Duration delta_t = time - time_initial_; - double t = delta_t.nanoseconds() / 1000000000.0; - - if (t <= t1_) { - position_ = position_initial_ + velocity_initial_ * (t - t0_) + - acceleration_ * (t - t0_) * (t - t0_) / 2.0; - velocity_current_ = velocity_initial_ + acceleration_ * (t - t0_); - acceleration_current_ = acceleration_; - state_ = ProfileState::ACCELERATION; - } else if (t <= t2_) { - position_ = y1_ + velocity_cruising_ * (t - t1_); - velocity_current_ = velocity_cruising_; - acceleration_current_ = 0; - state_ = ProfileState::CRUISING; - } else if (t < t3_) { - position_ = y2_ + velocity_cruising_ * (t - t2_) + deceleration_ * (t - t2_) * (t - t2_) / 2.0; - velocity_current_ = velocity_cruising_ + deceleration_ * (t - t2_); - acceleration_current_ = deceleration_; - state_ = ProfileState::DECELERATION; - } else { - position_ = setpoint_ + velocity_final_ * - (t - t3_); // Continue integrating in case of non-zero final velocity - velocity_current_ = velocity_final_; - acceleration_current_ = 0; - state_ = ProfileState::FINISHED; - } - - return position_; -} - -double MotionProfile::get_position() { return position_; } - -double MotionProfile::get_velocity() { return velocity_current_; } - -double MotionProfile::get_setpoint() { return setpoint_; } - -double MotionProfile::get_velocity_max() { return velocity_max_; } - -void MotionProfile::set_velocity_max(double velocity_max) { velocity_max_ = velocity_max; } - -double MotionProfile::get_acceleration_max() { return acceleration_max_; } - -void MotionProfile::set_acceleration_max(double acceleration_max) -{ - acceleration_max_ = acceleration_max; -} - -bool MotionProfile::finished() { return state_ == ProfileState::FINISHED; } - -MotionProfile::ProfileState MotionProfile::get_state() { return state_; } diff --git a/mep3_navigation/src/distance_angle/pid_regulator.c b/mep3_navigation/src/distance_angle/pid_regulator.c deleted file mode 100644 index fd3f44bbb..000000000 --- a/mep3_navigation/src/distance_angle/pid_regulator.c +++ /dev/null @@ -1,108 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#include "mep3_navigation/distance_angle/pid_regulator.h" - -#include - -void pid_regulator_update(pid_regulator_t * reg) -{ - if (reg->angle_mode) { - while (reg->reference > M_PI) { - reg->reference -= 2.0 * M_PI; - } - - while (reg->reference < -M_PI) { - reg->reference += 2.0 * M_PI; - } - } - // P, I, D, terms discretized with Backward Euler (s = (z - 1) / zT) - reg->error = reg->reference - reg->feedback; // error = reference - feedback - - if (reg->angle_mode) { - while (reg->error > M_PI) { - reg->error -= 2.0 * M_PI; - } - - while (reg->error < -M_PI) { - reg->error += 2.0 * M_PI; - } - } - const double p_term = reg->kp * reg->error; // proportional action - double new_integrator = reg->integrator + reg->ki * reg->error; // integrator - double feedback_difference = reg->feedback - reg->feedback_old; - - if (reg->angle_mode) { - while (feedback_difference > M_PI) { - feedback_difference -= 2.0 * M_PI; - } - - while (feedback_difference < -M_PI) { - feedback_difference += 2.0 * M_PI; - } - } - const double d_term_raw = - -reg->kd * feedback_difference; // differential action in local feedback - reg->d_term_filtered = - reg->d_term_filter_coefficient * reg->d_term_filtered + - (1 - reg->d_term_filter_coefficient) * d_term_raw; // apply first order low pass filter - bool integrator_ok = 1; // flag - - if (new_integrator > reg->integrator_max) { - new_integrator = reg->integrator_max; - } else if (new_integrator < reg->integrator_min) { - new_integrator = reg->integrator_min; - } - - double u = p_term + new_integrator + reg->d_term_filtered; - - /* ANTI WINDUP and output clamping*/ - if (u > reg->clamp_max) { - u = reg->clamp_max; - if (reg->error > 0) { - integrator_ok = 0; // integrator windup, stop it - } - } else if (u < reg->clamp_min) { - u = reg->clamp_min; - if (reg->error < 0) { - integrator_ok = 0; // integrator windup, stop it - } - } - - if (integrator_ok) { - reg->integrator = new_integrator; // no windup, continue - } - /********************************/ - - reg->command = u; // set output - - reg->feedback_old = reg->feedback; -} - -void pid_regulator_reset(pid_regulator_t * reg) -{ - reg->reference = reg->feedback; - reg->feedback_old = reg->feedback; - reg->error = 0; - reg->command = 0; - reg->integrator = 0; - reg->d_term_filtered = 0.0; -} - -void pid_regulator_set_gains(pid_regulator_t * reg, double kp, double ki, double kd) -{ - reg->kp = kp; - reg->ki = ki; - reg->kd = kd; -} diff --git a/mep3_navigation/src/laser_inflator/laser_inflator.cpp b/mep3_navigation/src/laser_inflator/laser_inflator.cpp deleted file mode 100644 index 79c51192b..000000000 --- a/mep3_navigation/src/laser_inflator/laser_inflator.cpp +++ /dev/null @@ -1,188 +0,0 @@ -// Copyright 2021 Memristor Robotics -// -// 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. - -#include -#include -#include -#include -#include - -#include "geometry_msgs/msg/transform_stamped.hpp" -#include "rclcpp/rclcpp.hpp" -#include "sensor_msgs/msg/laser_scan.hpp" -#include "tf2/exceptions.h" -#include "tf2/utils.h" -#include "tf2_ros/buffer.h" -#include "tf2_ros/transform_listener.h" - -using std::placeholders::_1; - -namespace mep3_driver -{ -class LaserInflator : public rclcpp::Node -{ -public: - LaserInflator() - : Node("laser_inflator") - { - this->declare_parameter("inflation_radius", 0.2); - this->declare_parameter("inflation_angular_step", 0.09); - this->get_parameter("inflation_radius", inflation_radius_); - this->get_parameter("inflation_angular_step", inflation_angular_step_); - tf_buffer_ = std::make_unique(this->get_clock()); - transform_listener_ = std::make_shared(*tf_buffer_); - subscriber_ = this->create_subscription( - "scan", rclcpp::QoS(rclcpp::SensorDataQoS()), - std::bind(&LaserInflator::scan_callback, this, _1)); - publisher_ = this->create_publisher( - "scan_inflated", rclcpp::QoS(rclcpp::SensorDataQoS())); - } - -private: - rclcpp::Subscription::SharedPtr subscriber_; - rclcpp::Publisher::SharedPtr publisher_; - float inflation_radius_; - float inflation_angular_step_; - std::shared_ptr transform_listener_{nullptr}; - std::unique_ptr tf_buffer_; - - void inflate_scan(sensor_msgs::msg::LaserScan & scan) - { - sensor_msgs::msg::LaserScan scan_out; - scan_out.header = scan.header; - scan_out.angle_min = -M_PI; - scan_out.angle_max = M_PI; - scan_out.angle_increment = M_PI / 180.0; - scan_out.range_max = std::numeric_limits::infinity(); - - size_t ranges_size = static_cast( - std::ceil((scan_out.angle_max - scan_out.angle_min) / scan_out.angle_increment)); - scan_out.ranges.assign(ranges_size, std::numeric_limits::infinity()); - - float point_angle = scan.angle_min; // angle of current point from incoming laser data - // iterate through received laser points - for (auto it = scan.ranges.begin(); it != scan.ranges.end(); - it++, point_angle += scan.angle_increment) - { - if (*it == std::numeric_limits::infinity()) { - continue; - } - - // create new points around current laser point - // new points lay on a semicircle facing the laser frame - float curr_angle = point_angle - 3.0 * M_PI_2; - const float end_angle = point_angle - M_PI_2; - - // TODO(angstrem98): ovaj step treba otpimalno odabrati kako se ne bi trosio previse CPU - // ili naci mozda neki drugi nacin - for (; curr_angle <= end_angle; curr_angle += inflation_angular_step_) { - const float point_range = *it; - const float new_x = point_range * cosf(point_angle) + inflation_radius_ * cosf(curr_angle); - const float new_y = point_range * sinf(point_angle) + inflation_radius_ * sinf(curr_angle); - const float new_range = std::hypot(new_x, new_y); - const float new_angle = atan2f(new_y, new_x); - - int index = - static_cast((new_angle - scan_out.angle_min) / scan_out.angle_increment); - // TODO(angstrem98) OVO PROVERI - if (index >= 359) { - index = 359; - } - if (new_range < scan_out.ranges.at(index)) { - scan_out.ranges.at(index) = new_range; - } - } - } - - scan = scan_out; - } - - bool constrain_scan(sensor_msgs::msg::LaserScan & scan) - { - std::string to_frame = "map"; - std::string from_frame = "laser"; - geometry_msgs::msg::TransformStamped transform_stamped; - - try { - transform_stamped = tf_buffer_->lookupTransform(to_frame, from_frame, tf2::TimePointZero); - } catch (tf2::TransformException & ex) { - RCLCPP_INFO( - this->get_logger(), "Could not transform %s to %s: %s", to_frame.c_str(), - from_frame.c_str(), ex.what()); - return false; - } - - float transform_angle = static_cast(tf2::getYaw(transform_stamped.transform.rotation)); - const double x_offset = transform_stamped.transform.translation.x; - const double y_offset = transform_stamped.transform.translation.y; - - // iterate through points and check if xy coords are valid - - float point_angle = scan.angle_min + transform_angle; // apply rotation - for (auto it = scan.ranges.begin(); it != scan.ranges.end(); - it++, point_angle += scan.angle_increment) - { - if (*it == std::numeric_limits::infinity()) { - continue; - } - const float point_range = *it; - const double x = point_range * cosf(point_angle) + x_offset; - const double y = point_range * sinf(point_angle) + y_offset; - - // Remove total stop button that out lidar can see - if (point_range < 0.12) { - *it = std::numeric_limits::infinity(); - continue; - } - - // Is (x, y) valid? - // Currently, just check if the point is inside a rectangle - // a bit smaller than the playing area. - const double shrink = 0.17; - if ( - (x >= -1.5 + shrink) && (x <= 1.5 - shrink) && (y >= -1.0 + shrink) && - (y <= 1.0 - shrink)) - { - // point is valid, don't touch it, continue - continue; - } else { - // point outside area, delete it by making the range equal to infinity - *it = std::numeric_limits::infinity(); - } - } - return true; - } - - void scan_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg) - { - sensor_msgs::msg::LaserScan scan = *msg; - if (constrain_scan(scan)) { - inflate_scan(scan); - if (constrain_scan(scan)) { - publisher_->publish(scan); - } - } - } -}; - -} // namespace mep3_driver - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - - return 0; -} diff --git a/mep3_navigation/src/plugins/condition/globally_updated_goal_condition.cpp b/mep3_navigation/src/plugins/condition/globally_updated_goal_condition.cpp deleted file mode 100644 index 05b34f1a6..000000000 --- a/mep3_navigation/src/plugins/condition/globally_updated_goal_condition.cpp +++ /dev/null @@ -1,61 +0,0 @@ -// Copyright (c) 2021 Joshua Wallace -// -// 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. - -#include -#include - -#include "mep3_navigation/plugins/condition/globally_updated_goal_condition.hpp" - -namespace mep3_navigation -{ - -GloballyUpdatedGoalCondition::GloballyUpdatedGoalCondition( - const std::string & condition_name, - const BT::NodeConfiguration & conf) -: BT::ConditionNode(condition_name, conf), - first_time(true) -{ - node_ = config().blackboard->get("node"); -} - -BT::NodeStatus GloballyUpdatedGoalCondition::tick() -{ - if (first_time) { - first_time = false; - config().blackboard->get>("goals", goals_); - config().blackboard->get("goal", goal_); - return BT::NodeStatus::FAILURE; - } - - std::vector current_goals; - config().blackboard->get>("goals", current_goals); - geometry_msgs::msg::PoseStamped current_goal; - config().blackboard->get("goal", current_goal); - - if (goal_ != current_goal || goals_ != current_goals) { - goal_ = current_goal; - goals_ = current_goals; - return BT::NodeStatus::SUCCESS; - } - - return BT::NodeStatus::FAILURE; -} - -} // namespace mep3_navigation - -#include "behaviortree_cpp_v3/bt_factory.h" -BT_REGISTER_NODES(factory) -{ - factory.registerNodeType("GlobalUpdatedGoal"); -} diff --git a/mep3_navigation/src/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.cpp b/mep3_navigation/src/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.cpp index 09e8d1e30..e989639ca 100644 --- a/mep3_navigation/src/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.cpp +++ b/mep3_navigation/src/regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.cpp @@ -38,8 +38,8 @@ namespace mep3_navigation void RegulatedPurePursuitController::configure( const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, - std::string name, const std::shared_ptr & tf, - const std::shared_ptr & costmap_ros) + std::string name, std::shared_ptr tf, + std::shared_ptr costmap_ros) { auto node = parent.lock(); if (!node) { diff --git a/mep3_simulation/launch/simulation_launch.py b/mep3_simulation/launch/simulation_launch.py index b457b5641..3213f1083 100644 --- a/mep3_simulation/launch/simulation_launch.py +++ b/mep3_simulation/launch/simulation_launch.py @@ -5,7 +5,7 @@ import launch from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node -from webots_ros2_driver.webots_launcher import WebotsLauncher +from webots_ros2_driver.webots_launcher import WebotsLauncher, Ros2SupervisorLauncher def generate_launch_description(): @@ -55,7 +55,7 @@ def generate_launch_description(): ('/scan', 'scan'), ('/scan/point_cloud', 'scan/point_cloud'), ], - additional_env={'WEBOTS_ROBOT_NAME': 'robot_big'}, + additional_env={'WEBOTS_CONTROLLER_URL': 'robot_big'}, namespace='big') webots_robot_driver_small = Node( @@ -79,8 +79,10 @@ def generate_launch_description(): ('/scan', 'scan'), ('/scan/point_cloud', 'scan/point_cloud'), ], - additional_env={'WEBOTS_ROBOT_NAME': 'robot_small'}, + additional_env={'WEBOTS_CONTROLLER_URL': 'robot_small'}, namespace='small') + + ros2_supervisor = Ros2SupervisorLauncher() # Standard ROS 2 launch description return launch.LaunchDescription([ @@ -91,6 +93,8 @@ def generate_launch_description(): webots_robot_driver_big, webots_robot_driver_small, + ros2_supervisor, + # This action will kill all nodes once the Webots simulation has exited launch.actions. RegisterEventHandler(event_handler=launch.event_handlers.OnProcessExit( diff --git a/mep3_simulation/mep3_simulation/resistance_meter_driver.py b/mep3_simulation/mep3_simulation/resistance_meter_driver.py deleted file mode 100644 index cb4342b70..000000000 --- a/mep3_simulation/mep3_simulation/resistance_meter_driver.py +++ /dev/null @@ -1,187 +0,0 @@ -from functools import reduce -from math import copysign, degrees -from random import randrange - -from mep3_msgs.action import ResistanceMeter -from mep3_simulation import WebotsUserDriver - -from rclpy.action import ActionServer, CancelResponse, GoalResponse - - -FORCE_TRESHOLD = 0.01 -EXCAVATION_SQUARES = { - 'x_center': [ - -0.8325, -0.6475, -0.4625, -0.2775, -0.0925, - 0.0925, 0.2775, 0.4625, 0.6475, 0.8325 - ], - 'resistances': [ - 1000, 1000, 4700, 470, 1000, - 1000, 470, 4700, 470, 470 - ], - 'x_correction_left': 0.0285, - 'x_correction_right': -0.0285, - 'x_tolerance': 0.015, - 'y_start': -0.77, - 'y_end': -0.83, - 'yaw_tolerance': 4.6 -} -MEASUREMENT_NOISE = 3.0 # percent -MEASUREMENT_INACCURACY = 5.0 # percent - - -def value_in_range(value, left, right): - if left > right: - left, right = right, left - return value >= left and value <= right - - -def vector_to_average_scalar(vector): - return reduce(lambda e, s: e + s, vector) / len(vector) - - -def axangle_to_yaw(axis_angle): - assert len(axis_angle) == 4 - x, y, z, theta = axis_angle - - # Assertion is disabled because rotation 0 0 1 0 - # is represented as 0 1 0 0 in Webots - - # Axis vector is approximately z-axis unit vector - # assert abs(x) < 0.1 - # assert abs(y) < 0.1 - # assert value_in_range(abs(z), 0.9, 1.1) - - return theta * copysign(1.0, z) # radians - - -class ResistanceMeterDriver: - - def init(self, webots_node, properties): - namespace = properties['namespace'] - self.measuring_side = properties['measuringSide'] - - assert self.measuring_side in ['left', 'right'] - - self.__supervisor = webots_node.robot - self.__robot = self.__supervisor.getSelf() - - self.__touch_sensor_front = self.__supervisor.getDevice( - f'hand_{self.measuring_side}_Dz_touch_sensor_front' - ) - self.__touch_sensor_back = self.__supervisor.getDevice( - f'hand_{self.measuring_side}_Dz_touch_sensor_back' - ) - - timestep = int(self.__supervisor.getBasicTimeStep()) - - self.__touch_sensor_front.enable(timestep) - self.__touch_sensor_back.enable(timestep) - - self.__arm = self.__supervisor.getDevice( - f'hand_{self.measuring_side}_Dz' - ) - - self.__action = ActionServer( - WebotsUserDriver.get().node, - ResistanceMeter, - f'{namespace}/resistance_meter/{self.measuring_side}', - execute_callback=self.__execute_callback, - callback_group=WebotsUserDriver.get().callback_group, - goal_callback=self.__goal_callback, - cancel_callback=self.__cancel_callback - ) - - def __goal_callback(self, _): - return GoalResponse.ACCEPT - - def __cancel_callback(self, _): - return CancelResponse.ACCEPT - - def __execute_callback(self, goal_handle): - result = ResistanceMeter.Result() - resistance = 0 - - if goal_handle.is_cancel_requested: - goal_handle.cancelled() - - position = self.discretize_robot_position() - force = self.measure_touch_force() - - if position is not None: - if force >= FORCE_TRESHOLD: - resistance = EXCAVATION_SQUARES['resistances'][position] - noise = randrange( - resistance * MEASUREMENT_NOISE * -1, - resistance * MEASUREMENT_NOISE - ) / 100.0 - inaccuracy = randrange( - resistance * MEASUREMENT_INACCURACY * -1, - resistance * MEASUREMENT_INACCURACY - ) / 100.0 - resistance = int(resistance + noise + inaccuracy) - - result.resistance = resistance - goal_handle.succeed() - - return result - - def measure_touch_force(self): - - fork_front = self.__touch_sensor_front.getValues() - fork_back = self.__touch_sensor_back.getValues() - - return vector_to_average_scalar(fork_front) + \ - vector_to_average_scalar(fork_back) - - def discretize_robot_position(self): - - trn = self.__robot.getField('translation').getSFVec3f() - rot = self.__robot.getField('rotation').getSFRotation() - - if value_in_range( - trn[1], - EXCAVATION_SQUARES['y_start'], EXCAVATION_SQUARES['y_end'] - ): - - # Robot's yaw in degrees - yaw = degrees(axangle_to_yaw(rot)) - - # Robot's orientation - o = None - if value_in_range( - yaw, - 0 - EXCAVATION_SQUARES['yaw_tolerance'], - 0 + EXCAVATION_SQUARES['yaw_tolerance'] - ): - o = 'right' - elif value_in_range( - abs(yaw), - 180 - EXCAVATION_SQUARES['yaw_tolerance'], - 180 + EXCAVATION_SQUARES['yaw_tolerance'] - ): - o = 'left' - else: - # Outside yaw range - return None - - # Robot's Џ hand x-axis center in meters - x = trn[0] + EXCAVATION_SQUARES[f'x_correction_{o}'] - for i, c in enumerate(EXCAVATION_SQUARES['x_center']): - # Inside x-axis center range - if value_in_range( - x, - c - EXCAVATION_SQUARES['x_tolerance'], - c + EXCAVATION_SQUARES['x_tolerance'] - ): - return i - - # Outside x-axis center ranges - return None - - else: - - # Outside y-axis range - return None - - def step(self): - pass diff --git a/mep3_simulation/mep3_simulation/webots_dynamixel_driver.py b/mep3_simulation/mep3_simulation/webots_dynamixel_driver.py deleted file mode 100644 index 9f89d0ad8..000000000 --- a/mep3_simulation/mep3_simulation/webots_dynamixel_driver.py +++ /dev/null @@ -1,99 +0,0 @@ -from math import radians -import time - -from mep3_msgs.action import DynamixelCommand -from mep3_simulation import WebotsUserDriver -from rclpy.action import ActionServer, CancelResponse, GoalResponse - -DEFAULT_POSITION = radians(0) # deg -DEFAULT_VELOCITY = radians(45) # deg/s -DEFAULT_TOLERANCE = radians(1) # deg -DEFAULT_TIMEOUT = 5 # s -""" -# Test: -ros2 action send_goal /big/dynamixel_command/arm_right_motor_base mep3_msgs/action/DynamixelCommand "position: 2.2" # noqa: E501 -""" - - -class WebotsDynamixelDriver: - - def init(self, webots_node, properties): - namespace = properties['namespace'] - motor_name = properties['motorName'] - - if 'gearRatio' in properties: - self.__gear_ratio = float( - properties['gearRatio'] - ) - else: - self.__gear_ratio = 1.0 - - self.__robot = webots_node.robot - timestep = int(self.__robot.getBasicTimeStep()) - - self.__motor = self.__robot.getDevice(motor_name) - self.__encoder = self.__motor.getPositionSensor() - self.__encoder.enable(timestep) - self.__motor_action = ActionServer( - WebotsUserDriver.get().node, - DynamixelCommand, - f'{namespace}/dynamixel_command/{motor_name}', - execute_callback=self.__execute_callback, - callback_group=WebotsUserDriver.get().callback_group, - goal_callback=self.__goal_callback, - cancel_callback=self.__cancel_callback) - - def __timeout_overflow(self, timeout): - if self.__robot.getTime() - self.__start_time > timeout: - return True - else: - return False - - def __goal_callback(self, _): - return GoalResponse.ACCEPT - - def __cancel_callback(self, _): - return CancelResponse.ACCEPT - - async def __execute_callback(self, goal_handle): - position = radians(goal_handle.request.position) * \ - self.__gear_ratio - velocity = radians(goal_handle.request.velocity) * \ - self.__gear_ratio - tolerance = radians(goal_handle.request.tolerance) * \ - self.__gear_ratio - timeout = goal_handle.request.timeout - - self.__motor.setPosition(position) - self.__motor.setVelocity(velocity if velocity else DEFAULT_VELOCITY) - if not tolerance: - tolerance = DEFAULT_TOLERANCE - if not timeout: - timeout = DEFAULT_TIMEOUT - - self.__start_time = self.__robot.getTime() - result = DynamixelCommand.Result() - - while abs(self.__encoder.getValue() - position) > tolerance: - if self.__timeout_overflow(timeout): - # Return failure - result.result = 1 - goal_handle.abort() - return result - - if goal_handle.is_cancel_requested: - # Return failure - result.result = 2 - goal_handle.canceled() - return result - - time.sleep(0.1) - - # Return sucesss - goal_handle.succeed() - result.result = 0 - - return result - - def step(self): - pass diff --git a/mep3_simulation/mep3_simulation/webots_replica_driver.py b/mep3_simulation/mep3_simulation/webots_replica_driver.py deleted file mode 100644 index 3e48af7d9..000000000 --- a/mep3_simulation/mep3_simulation/webots_replica_driver.py +++ /dev/null @@ -1,30 +0,0 @@ -from math import radians - - -REPLICA_DECOUPLING_ANGLE = 80 # degrees - - -class WebotsReplicaDriver: - - def init(self, webots_node, properties): - self.__robot = webots_node.robot - timestep = int(self.__robot.getBasicTimeStep()) - self.__connector = self.__robot.getDevice('hand_L_replica_connector') - self.__motor = self.__robot.getDevice('hand_mid_L') - self.__encoder = self.__motor.getPositionSensor() - self.__encoder.enable(timestep) - self.__finished = False - - def step(self): - """ - Check in every time step if replica should be decoupled. - - If the angle of the motor is above a threshold, - decouple the replica. - The threshold is currently set at 80 degrees. - """ - if self.__finished: - return - if self.__encoder.getValue() > radians(REPLICA_DECOUPLING_ANGLE): - self.__connector.unlock() - self.__finished = True diff --git a/mep3_simulation/mep3_simulation/webots_statuette_driver.py b/mep3_simulation/mep3_simulation/webots_statuette_driver.py deleted file mode 100644 index 2da325513..000000000 --- a/mep3_simulation/mep3_simulation/webots_statuette_driver.py +++ /dev/null @@ -1,40 +0,0 @@ -from math import radians - - -REPLICA_DECOUPLING_ANGLE = radians(80) -STATUETTE_DECOUPLING_ANGLE = radians(5) - - -class WebotsStatuetteDriver: - - def init(self, webots_node, properties): - self.__robot = webots_node.robot - timestep = int(self.__robot.getBasicTimeStep()) - self.__connector = self.__robot.getDevice('hand_L_statuette_connector') - self.__connector.enablePresence(timestep) - self.__motor = self.__robot.getDevice('hand_mid_L') - self.__encoder = self.__motor.getPositionSensor() - self.__encoder.enable(timestep) - self.__finished = False - self.__enable_statuette_decoupling = False - - def step(self): - """ - Check in every time step if statuette should be decoupled. - - In order to decouple the statuette, we first need to decouple the - replica. We have a three state FSM: - coupled_statuette -> decoupled_replica -> decoupled_statuette. - """ - if self.__finished: - return - if self.__connector.getPresence() and not self.__connector.isLocked(): - # state: coupled_statuette - self.__connector.lock() - elif self.__encoder.getValue() > REPLICA_DECOUPLING_ANGLE: - self.__enable_statuette_decoupling = True - elif self.__encoder.getValue( - ) <= STATUETTE_DECOUPLING_ANGLE and self.__connector.isLocked( - ) and self.__enable_statuette_decoupling: - self.__connector.unlock() - self.__finished = True diff --git a/mep3_simulation/mep3_simulation/webots_vacuum_pump_driver.py b/mep3_simulation/mep3_simulation/webots_vacuum_pump_driver.py deleted file mode 100644 index 65dc1c5b7..000000000 --- a/mep3_simulation/mep3_simulation/webots_vacuum_pump_driver.py +++ /dev/null @@ -1,114 +0,0 @@ -import time - -from mep3_msgs.action import VacuumPumpCommand -from mep3_simulation import WebotsUserDriver -import rclpy -from rclpy.action import ActionServer, CancelResponse, GoalResponse - -""" -# Move RIGHT arm to position: -ros2 action send_goal /big/dynamixel_command/arm_right_motor_base mep3_msgs/action/DynamixelCommand "position: -90" # noqa: E501 -ros2 action send_goal /big/dynamixel_command/arm_right_motor_mid mep3_msgs/action/DynamixelCommand "position: 90" # noqa: E501 -ros2 action send_goal /big/dynamixel_command/arm_right_motor_gripper mep3_msgs/action/DynamixelCommand "position: 90" # noqa: E501 - -# Test RIGHT pump connect: -ros2 action send_goal /big/vacuum_pump_command/arm_right_connector mep3_msgs/action/VacuumPumpCommand "connect: 1" # noqa: E501 - -# Move RIGHT arm back: -ros2 action send_goal /big/dynamixel_command/arm_right_motor_mid mep3_msgs/action/DynamixelCommand "position: 0" # noqa: E501 - -# Test RIGHT pump disconnect: -ros2 action send_goal /big/vacuum_pump_command/arm_right_connector mep3_msgs/action/VacuumPumpCommand "connect: 0" # noqa: E501 -""" -""" -# Move LEFT arm to position: -ros2 action send_goal /big/dynamixel_command/arm_left_motor_base mep3_msgs/action/DynamixelCommand "position: 90" # noqa: E501 -ros2 action send_goal /big/dynamixel_command/arm_left_motor_mid mep3_msgs/action/DynamixelCommand "position: 90" # noqa: E501 -ros2 action send_goal /big/dynamixel_command/arm_left_motor_gripper mep3_msgs/action/DynamixelCommand "position: 90" # noqa: E501 - -# Test LEFT pump connect: -ros2 action send_goal /big/vacuum_pump_command/arm_left_connector mep3_msgs/action/VacuumPumpCommand "connect: 1" # noqa: E501 - -# Move LEFT arm back: -ros2 action send_goal /big/dynamixel_command/arm_left_motor_mid mep3_msgs/action/DynamixelCommand "position: 0" # noqa: E501 - -# Test LEFT pump disconnect: -ros2 action send_goal /big/vacuum_pump_command/arm_left_connector mep3_msgs/action/VacuumPumpCommand "connect: 0" # noqa: E501 -""" - -DISTANCE_TRESHOLD = 3.5e-3 # meters - - -class WebotsVacuumPumpDriver: - - def init(self, webots_node, properties): - namespace = properties['namespace'] - connector_name = properties['connectorName'] - - self.__node = rclpy.create_node( - f'webots_vacuum_pump_driver_{connector_name}') - self.__robot = webots_node.robot - self.__connector = self.__robot.getDevice(f'{connector_name}') - self.__distance_sensor = self.__robot.getDevice( - f'{connector_name}_distance_sensor' - ) - timestep = int(self.__robot.getBasicTimeStep()) - self.__connector.enablePresence(timestep) - self.__distance_sensor.enable(timestep) - - self.__motor_action = ActionServer( - WebotsUserDriver.get().node, - VacuumPumpCommand, - f'{namespace}/vacuum_pump_command/{connector_name}', - execute_callback=self.__execute_callback, - callback_group=WebotsUserDriver.get().callback_group, - goal_callback=self.__goal_callback, - cancel_callback=self.__cancel_callback) - - def __goal_callback(self, _): - return GoalResponse.ACCEPT - - def __cancel_callback(self, _): - return CancelResponse.ACCEPT - - async def __execute_callback(self, goal_handle): - connect = goal_handle.request.connect - result = VacuumPumpCommand.Result() - - if goal_handle.is_cancel_requested: - result.result = 4 # other - goal_handle.cancelled() - - for _ in range(6): - # Give it some time to connect - distance = self.__distance_sensor.getValue() - distance = distance <= DISTANCE_TRESHOLD - if distance: - break - time.sleep(0.05) - - if connect: - if self.__connector.isLocked(): - result.result = 3 # connected - goal_handle.succeed() - else: - if self.__connector.getPresence() and distance: - self.__connector.lock() - result.result = 1 # connected - goal_handle.succeed() - else: - result.result = 3 # couldn't connect - goal_handle.abort() - else: - if self.__connector.isLocked(): - self.__connector.unlock() - result.result = 0 # disconnected - goal_handle.succeed() - else: - result.result = 0 # disconnected - goal_handle.succeed() - - return result - - def step(self): - pass diff --git a/mep3_simulation/resource/config_big.urdf b/mep3_simulation/resource/config_big.urdf index 034dc36ef..5ea7ab5e4 100644 --- a/mep3_simulation/resource/config_big.urdf +++ b/mep3_simulation/resource/config_big.urdf @@ -3,98 +3,7 @@ - - big - lift_motor - 0.1575 - - - - big - arm_right_motor_base - - - - big - arm_left_motor_base - - - - big - arm_right_motor_mid - - - - big - arm_left_motor_mid - - - - big - arm_right_motor_gripper - - - - big - arm_left_motor_gripper - - - - big - arm_right_connector - - - - big - arm_left_connector - - - - big - arm_mid_connector - - - - big - hand_right_Dz - - - - big - hand_right_G - - - - big - hand_left_Dz - - - - big - hand_left_G - - - - big - hand_mid_L - - - - big - hand_mid_S - - - - - big - left - - - - big - right - diff --git a/mep3_simulation/resource/config_small.urdf b/mep3_simulation/resource/config_small.urdf index 0f1737f8b..0654e262b 100644 --- a/mep3_simulation/resource/config_small.urdf +++ b/mep3_simulation/resource/config_small.urdf @@ -3,99 +3,8 @@ - - small - lift_motor - 0.1575 - - - - small - arm_right_motor_base - - - - small - arm_left_motor_base - - - - small - arm_right_motor_mid - - - - small - arm_left_motor_mid - - - - small - arm_right_motor_gripper - - - - small - arm_left_motor_gripper - - - - small - arm_right_connector - - - - small - arm_left_connector - - - - small - arm_mid_connector - - - - small - hand_right_Dz - - - - small - hand_right_G - - - - small - hand_left_Dz - - - - small - hand_left_G - - - - small - hand_mid_L - - - - small - hand_mid_S - - - - small - left - - - - small - right - - true diff --git a/mep3_simulation/setup.cfg b/mep3_simulation/setup.cfg index c4e55aae0..400dfc451 100644 --- a/mep3_simulation/setup.cfg +++ b/mep3_simulation/setup.cfg @@ -1,4 +1,4 @@ [develop] -script-dir=$base/lib/mep3_simulation +script_dir=$base/lib/mep3_simulation [install] -install-scripts=$base/lib/mep3_simulation +install_scripts=$base/lib/mep3_simulation diff --git a/mep3_simulation/webots_data/controllers/judge/judge.py b/mep3_simulation/webots_data/controllers/judge/judge.py index 2779d15ef..22fb53d1e 100644 --- a/mep3_simulation/webots_data/controllers/judge/judge.py +++ b/mep3_simulation/webots_data/controllers/judge/judge.py @@ -10,6 +10,14 @@ from controller import Supervisor +INITIAL_POSE_MATRIX = [ + ('big', 'purple', [1.249, 0.102, pi/2]), + ('small', 'purple', [1.2755, 0.443, pi]), + ('big', 'yellow', [-1.249, 0.102, pi/2]), + ('small', 'yellow', [-1.2755, 0.443, 0]), +] + + class ObjectManipulator: def __init__(self, supervisor, def_value): @@ -44,20 +52,16 @@ def main(): 'ROBOT_OPPONENT_SMALL') # Set initial poses - if color == 'yellow': - robot_big.set_position(x=-1.2491, y=0.12, theta=-pi / 2) - robot_small.set_position(x=-1.249, y=0.47, theta=pi / 2) - robot_opponent_big.set_position(x=0.775, y=0.375, theta=pi) - robot_opponent_small.set_position(x=0.775, y=-1.275, theta=pi) - - supervisor.step(timestep) - else: - robot_big.set_position(x=1.249, y=0.47, theta=pi / 2) - robot_small.set_position(x=1.2491, y=0.12, theta=-pi / 2) - robot_opponent_big.set_position(x=-0.775, y=0.375, theta=0) - robot_opponent_small.set_position(x=-0.775, y=-1.275, theta=0) - - supervisor.step(timestep) + pose_big = next(pose[2] for pose in INITIAL_POSE_MATRIX if pose[0] == 'big' and pose[1] == color) + robot_big.set_position(x=pose_big[0], y=pose_big[1], theta=pose_big[2]) + + pose_small = next(pose[2] for pose in INITIAL_POSE_MATRIX if pose[0] == 'small' and pose[1] == color) + robot_small.set_position(x=pose_small[0], y=pose_small[1], theta=pose_small[2]) + + robot_opponent_big.set_position(x=-pose_big[0], y=pose_big[1], theta=pose_big[2]) + robot_opponent_small.set_position(x=-pose_small[0], y=pose_small[1], theta=pose_small[2]) + + supervisor.step(timestep) # Do something while supervisor.step(timestep) != -1: diff --git a/mep3_simulation/webots_data/controllers/test_robot/.gitignore b/mep3_simulation/webots_data/controllers/test_robot/.gitignore deleted file mode 100644 index 5817a94bd..000000000 --- a/mep3_simulation/webots_data/controllers/test_robot/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -test_robot -build/* diff --git a/mep3_simulation/webots_data/controllers/test_robot/Makefile b/mep3_simulation/webots_data/controllers/test_robot/Makefile deleted file mode 100644 index 920928c35..000000000 --- a/mep3_simulation/webots_data/controllers/test_robot/Makefile +++ /dev/null @@ -1,72 +0,0 @@ -# Copyright 1996-2021 Cyberbotics Ltd. -# -# 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. - -### Generic Makefile.include for Webots controllers, physics plugins, robot -### window libraries, remote control libraries and other libraries -### to be used with GNU make -### -### Platforms: Windows, macOS, Linux -### Languages: C, C++ -### -### Authors: Olivier Michel, Yvan Bourquin, Fabien Rohrer -### Edmund Ronald, Sergei Poskriakov -### -###----------------------------------------------------------------------------- -### -### This file is meant to be included from the Makefile files located in the -### Webots projects subdirectories. It is possible to set a number of variables -### to customize the build process, i.e., add source files, compilation flags, -### include paths, libraries, etc. These variables should be set in your local -### Makefile just before including this Makefile.include. This Makefile.include -### should never be modified. -### -### Here is a description of the variables you may set in your local Makefile: -### -### ---- C Sources ---- -### if your program uses several C source files: -### C_SOURCES = my_plugin.c my_clever_algo.c my_graphics.c -### -### ---- C++ Sources ---- -### if your program uses several C++ source files: -### CXX_SOURCES = my_plugin.cc my_clever_algo.cpp my_graphics.c++ -### -### ---- Compilation options ---- -### if special compilation flags are necessary: -### CFLAGS = -Wno-unused-result -### -### ---- Linked libraries ---- -### if your program needs additional libraries: -### INCLUDE = -I"/my_library_path/include" -### LIBRARIES = -L"/path/to/my/library" -lmy_library -lmy_other_library -### -### ---- Linking options ---- -### if special linking flags are needed: -### LFLAGS = -s -### -### ---- Webots included libraries ---- -### if you want to use the Webots C API in your C++ controller program: -### USE_C_API = true -### -### ---- Debug mode ---- -### if you want to display the gcc command line for compilation and link, as -### well as the rm command details used for cleaning: -### VERBOSE = 1 -### -###----------------------------------------------------------------------------- - -### Do not modify: this includes Webots global Makefile.include -null := -space := $(null) $(null) -WEBOTS_HOME_PATH=$(subst $(space),\ ,$(strip $(subst \,/,$(WEBOTS_HOME)))) -include $(WEBOTS_HOME_PATH)/resources/Makefile.include diff --git a/mep3_simulation/webots_data/controllers/test_robot/test_robot.cpp b/mep3_simulation/webots_data/controllers/test_robot/test_robot.cpp deleted file mode 100644 index 286d4c463..000000000 --- a/mep3_simulation/webots_data/controllers/test_robot/test_robot.cpp +++ /dev/null @@ -1,109 +0,0 @@ -// You may need to add webots include files such as -// , , etc. -// and/or to add some other includes -#include -#include -#include -#include -#include -#include - -using namespace webots; - -/* - ABBREVIATIONS: - lam - Left Arm Motor - ram - Right Arm Motor - laps - Left Arm Position Sensor - raps - Right Arm Position Sensor - lwm - Left Wheel Motor - rwm - Right Wheel Motor - leps - Left Encoder Position Sensor - reps - Right Encoder Position Sensor -*/ - -int main(int argc, char **argv) { - Robot *robot = new Robot(); - int timeStep = (int)robot->getBasicTimeStep(); - - // Motors - Motor *lwm = robot->getMotor("left_motor"); - Motor *rwm = robot->getMotor("right_motor"); - PositionSensor *leps = robot->getPositionSensor("encoder_left"); - PositionSensor *reps = robot->getPositionSensor("encoder_right"); - leps->enable(timeStep); - reps->enable(timeStep); - - // Left Arm - Motor *lam0 = robot->getMotor("arm_left_motor_base"); - Motor *lam1 = robot->getMotor("arm_left_motor_mid"); - Motor *lam2 = robot->getMotor("arm_left_motor_gripper"); - PositionSensor *laps0 = robot->getPositionSensor("arm_left_sensor_base"); - PositionSensor *laps1 = robot->getPositionSensor("arm_left_sensor_mid"); - PositionSensor *laps2 = robot->getPositionSensor("arm_left_sensor_gripper"); - laps0->enable(timeStep); - laps1->enable(timeStep); - laps2->enable(timeStep); - Connector *c_arm = robot->getConnector("arm_left_connector"); - c_arm->enablePresence(timeStep); - - // pause - for (int i = 0; i < 20; i++) - robot->step(timeStep); - - // states - enum States {translate, rotate, translate_back, grab, raise}; - States state = translate; - while (robot->step(timeStep) != -1) { - switch (state){ - case translate: - lwm->setPosition(-20); - rwm->setPosition(-20); - //std::cout << leps->getValue() << std::endl; - //std::cout << reps->getValue() << std::endl; - if (leps->getValue() < -9.9) - state = rotate; - break; - case rotate: - //lwm->setPosition(-10); - //rwm->setPosition(+10); - state = translate_back; - break; - case translate_back: - lwm->setPosition(20); - rwm->setPosition(20); - // std::cout << leps->getValue() << std::endl; - // std::cout << reps->getValue() << std::endl; - if (leps->getValue() >= 0) - state = grab; - break; - case grab: - if (!(c_arm->getPresence())) { - lam0->setVelocity(0.2); - lam0->setPosition(1.5708); - lam1->setVelocity(0.2); - lam1->setPosition(1.5708); - lam2->setPosition(1.5708); - } - else { - state = raise; - } - break; - case raise: - c_arm->lock(); - lam0->setPosition(0.5); - lam1->setPosition(0.5); - // lam2->setPosition(0); - break; - default: - break; - } - // Read the sensors: - - // Enter here functions to send actuator commands, like: - - }; - - delete robot; - return 0; -} \ No newline at end of file diff --git a/mep3_simulation/webots_data/controllers/test_robot_arm_memristor/Makefile b/mep3_simulation/webots_data/controllers/test_robot_arm_memristor/Makefile deleted file mode 100644 index 920928c35..000000000 --- a/mep3_simulation/webots_data/controllers/test_robot_arm_memristor/Makefile +++ /dev/null @@ -1,72 +0,0 @@ -# Copyright 1996-2021 Cyberbotics Ltd. -# -# 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. - -### Generic Makefile.include for Webots controllers, physics plugins, robot -### window libraries, remote control libraries and other libraries -### to be used with GNU make -### -### Platforms: Windows, macOS, Linux -### Languages: C, C++ -### -### Authors: Olivier Michel, Yvan Bourquin, Fabien Rohrer -### Edmund Ronald, Sergei Poskriakov -### -###----------------------------------------------------------------------------- -### -### This file is meant to be included from the Makefile files located in the -### Webots projects subdirectories. It is possible to set a number of variables -### to customize the build process, i.e., add source files, compilation flags, -### include paths, libraries, etc. These variables should be set in your local -### Makefile just before including this Makefile.include. This Makefile.include -### should never be modified. -### -### Here is a description of the variables you may set in your local Makefile: -### -### ---- C Sources ---- -### if your program uses several C source files: -### C_SOURCES = my_plugin.c my_clever_algo.c my_graphics.c -### -### ---- C++ Sources ---- -### if your program uses several C++ source files: -### CXX_SOURCES = my_plugin.cc my_clever_algo.cpp my_graphics.c++ -### -### ---- Compilation options ---- -### if special compilation flags are necessary: -### CFLAGS = -Wno-unused-result -### -### ---- Linked libraries ---- -### if your program needs additional libraries: -### INCLUDE = -I"/my_library_path/include" -### LIBRARIES = -L"/path/to/my/library" -lmy_library -lmy_other_library -### -### ---- Linking options ---- -### if special linking flags are needed: -### LFLAGS = -s -### -### ---- Webots included libraries ---- -### if you want to use the Webots C API in your C++ controller program: -### USE_C_API = true -### -### ---- Debug mode ---- -### if you want to display the gcc command line for compilation and link, as -### well as the rm command details used for cleaning: -### VERBOSE = 1 -### -###----------------------------------------------------------------------------- - -### Do not modify: this includes Webots global Makefile.include -null := -space := $(null) $(null) -WEBOTS_HOME_PATH=$(subst $(space),\ ,$(strip $(subst \,/,$(WEBOTS_HOME)))) -include $(WEBOTS_HOME_PATH)/resources/Makefile.include diff --git a/mep3_simulation/webots_data/controllers/test_robot_arm_memristor/test_robot_arm_memristor.cpp b/mep3_simulation/webots_data/controllers/test_robot_arm_memristor/test_robot_arm_memristor.cpp deleted file mode 100644 index 3338f35a3..000000000 --- a/mep3_simulation/webots_data/controllers/test_robot_arm_memristor/test_robot_arm_memristor.cpp +++ /dev/null @@ -1,74 +0,0 @@ -// You may need to add webots include files such as -// , , etc. -// and/or to add some other includes -#include -#include -#include -#include -#include -#include - -using namespace webots; - -int main(int argc, char **argv) { - Robot *robot = new Robot(); - int timeStep = (int)robot->getBasicTimeStep(); - - Motor *m0 = robot->getMotor("test_arm_motor_base"); - Motor *m1 = robot->getMotor("test_arm_motor_mid"); - Motor *m2 = robot->getMotor("test_arm_motor_gripper"); - PositionSensor *ps0 = robot->getPositionSensor("test_arm_sensor_base"); - PositionSensor *ps1 = robot->getPositionSensor("test_arm_sensor_mid"); - PositionSensor *ps2 = robot->getPositionSensor("test_arm_sensor_gripper"); - ps0->enable(timeStep); - ps1->enable(timeStep); - ps2->enable(timeStep); - Connector *c_arm = robot->getConnector("test_arm_connector"); - c_arm->enablePresence(timeStep); - m0->enableTorqueFeedback(timeStep); - m1->enableTorqueFeedback(timeStep); - m2->enableTorqueFeedback(timeStep); - int printv = 0; - double max_torque0, max_torque1, max_torque2; - max_torque0 = max_torque1 = max_torque2 = 0; - bool measure = false; - while (robot->step(timeStep) != -1) { - // Read the sensors: - - std::cout << "max torque0 = " << max_torque0 << ", curr torque0 = " << m0->getTorqueFeedback() << std::endl; - std::cout << "max torque1 = " << max_torque1 << ", curr torque1 = " << m1->getTorqueFeedback() << std::endl; - std::cout << "max torque2 = " << max_torque2 << ", curr torque2 = " << m2->getTorqueFeedback() << std::endl; - - //std::cout << "presence: " << c_arm->getPresence() << std::endl; - if (!printv) { - std::cout << "PS: " << ps0->getValue() << " " << ps1->getValue() << " " << ps2->getValue() << std::endl; - } - else - std::cout << "CONNECTED" << std::endl; - // Process sensor data here. - if (measure) { - max_torque0 = std::max(max_torque0, std::abs(m0->getTorqueFeedback())); - max_torque1 = std::max(max_torque1, std::abs(m1->getTorqueFeedback())); - max_torque2 = std::max(max_torque2, std::abs(m2->getTorqueFeedback())); - } - // Enter here functions to send actuator commands, like: - if (!(c_arm->getPresence())) { - m0->setPosition(-1.5708); - m1->setPosition(1.5708); - m2->setPosition(1.5708); - } - else { - c_arm->lock(); - m0->setPosition(0); - m1->setPosition(0); - m2->setPosition(0); - if (printv) - measure = true; - printv=1; - - } - }; - - delete robot; - return 0; -} \ No newline at end of file diff --git a/mep3_simulation/webots_data/protos/ArucoTag.proto b/mep3_simulation/webots_data/protos/ArucoTag.proto index 067b69bbb..06806c4b6 100644 --- a/mep3_simulation/webots_data/protos/ArucoTag.proto +++ b/mep3_simulation/webots_data/protos/ArucoTag.proto @@ -5,10 +5,10 @@ PROTO ArucoTag [ ] { %< - let url = '"assets/aruco/4x4_1000-' + fields.arucoNumber.value.toString() + '.png"'; + let url = '"../worlds/assets/aruco/4x4_1000-' + fields.arucoNumber.value.toString() + '.png"'; >% Transform { - translation -0.025 0 0.500 + translation 0 0 0.500 children [ Transform { translation 0 0 0.01002 diff --git a/mep3_simulation/webots_data/protos/DispenserOuter.proto b/mep3_simulation/webots_data/protos/DispenserOuter.proto deleted file mode 100644 index eac9d0d36..000000000 --- a/mep3_simulation/webots_data/protos/DispenserOuter.proto +++ /dev/null @@ -1,67 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript -PROTO DispenserOuter [ - field SFString{"yellow", "purple"} teamColor "yellow" - hiddenField SFColor yellowColor 0.972549 0.694118 0.0666667 - hiddenField SFColor purpleColor 0.360784 0.282353 0.541176 - hiddenField SFVec3f yellowTranslation -1.522 0.7 0 - hiddenField SFVec3f purpleTranslation 1.522 0.7 0 - hiddenField SFFloat yellowRotation 0 - hiddenField SFFloat purpleRotation 3.141592653589793 -] -{ - %< - var color; - var translation; - var rotation; - if (fields.teamColor.value == "purple") { - color = fields.purpleColor.value; - translation = fields.purpleTranslation.value; - rotation = fields.purpleRotation.value; - } - else { - color = fields.yellowColor.value; - translation = fields.yellowTranslation.value; - rotation = fields.yellowRotation.value; - } - >% - Solid { - name %<= '"dispenser_outer_' + fields.teamColor.value + '"' >% - translation %<= translation.x >% %<= translation.y >% %<= translation.z >% - rotation 0 0 1 %<= rotation >% - children [ - DEF dispenser_outer Transform { - translation -0.1075 -0.075 0.048 - scale 0.001 0.001 0.001 - children [ - Shape { - appearance PBRAppearance { - baseColor %<= color.r >% %<= color.g >% %<= color.b >% - roughness 1 - metalness 0 - } - geometry IndexedFaceSet { - coord DEF o6 Coordinate { - point [ - 1e-15 37.5 22, 1e-15 112.5 22, 1e-15 37.5 0, 1e-15 112.5 0, 1e-15 37.5 22, 1e-15 112.5 22, 64.949997 -2e-15 22, 107.9 0 22, 107.9 150 22, 64.949997 150 22, 64.949997 150 0, 64.949997 150 22, 1e-15 112.5 22, 1e-15 112.5 0, 1e-15 37.5 0, 1e-15 112.5 0, 64.949997 -2e-15 0, 107.9 0 0, 107.9 150 0, 64.949997 150 0, 64.949997 -2e-15 0, 64.949997 -2e-15 22, 1e-15 37.5 22, 1e-15 37.5 0, 64.949997 150 0, 107.9 150 0, 64.949997 150 22, 107.9 150 22, 107.9 0 0, 107.9 0 22, 107.9 150 0, 107.9 150 22, 64.949997 -2e-15 0, 107.9 0 0, 64.949997 -2e-15 22, 107.9 0 22, 1e-15 37.5 22, 1e-15 112.5 22, 1e-15 112.5 0, 1e-15 37.5 0, 64.949997 150 22, 107.9 150 22, 107.9 0 22, 64.949997 -2e-15 22, 64.949997 150 0, 107.9 150 0, 107.9 0 0, 64.949997 -2e-15 0 - ] - } - coordIndex [ - 2, 0, 3, -1, 3, 0, 1, -1, 9, 5, 4, -1, 9, 4, 6, -1, 9, 6, 7, -1, 8, 9, 7, -1, 10, 12, 11, -1, 10, 13, 12, -1, 15, 19, 14, -1, 14, 19, 16, -1, 16, 19, 17, -1, 19, 18, 17, -1, 23, 20, 21, -1, 23, 21, 22, -1, 27, 25, 24, -1, 27, 24, 26, -1, 28, 30, 31, -1, 29, 28, 31, -1, 33, 35, 32, -1, 32, 35, 34, -1 - ] - } - } - ] - } - ] - boundingObject Transform { - translation -0.053952 0 0.059 - children [ - Box { - size 0.107902 0.15 0.022 - } - ] - } - locked TRUE - } -} diff --git a/mep3_simulation/webots_data/protos/DispenserVertical.proto b/mep3_simulation/webots_data/protos/DispenserVertical.proto deleted file mode 100644 index 093245c8b..000000000 --- a/mep3_simulation/webots_data/protos/DispenserVertical.proto +++ /dev/null @@ -1,64 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript -PROTO DispenserVertical [ - field SFString name "vertical_dispenser" - field SFVec3f translation 0 0 0 - field SFRotation rotation 0 1 0 0 - field SFNode teamColor NULL - field SFBool locked TRUE -] -{ - Solid { - translation IS translation - rotation IS rotation - locked IS locked - children [ - DEF DISPENSER_VERTICAL_BOX Group { - children [ - Transform { - translation 0 -0.011 0.011 - children [ - Shape { - appearance IS teamColor - geometry DEF DISPENSER_SIDE_LONG Box { - size 0.106 0.022 0.022 - } - } - ] - } - Transform { - translation 0 -0.091 0.011 - children [ - Shape { - appearance IS teamColor - geometry USE DISPENSER_SIDE_LONG - } - ] - } - Transform { - translation -0.064 -0.051 0.011 - children [ - Shape { - appearance IS teamColor - geometry DEF DISPENSER_SIDE_SHORT Box { - size 0.022 0.102 0.022 - } - } - ] - } - Transform { - translation 0.064 -0.051 0.011 - children [ - Shape { - appearance IS teamColor - geometry USE DISPENSER_SIDE_SHORT - } - ] - } - ] - } - ] - name IS name - boundingObject USE DISPENSER_VERTICAL_BOX - } -} diff --git a/mep3_simulation/webots_data/protos/ExcavationSquare.proto b/mep3_simulation/webots_data/protos/ExcavationSquare.proto deleted file mode 100644 index b3dfb713d..000000000 --- a/mep3_simulation/webots_data/protos/ExcavationSquare.proto +++ /dev/null @@ -1,170 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript -PROTO ExcavationSquare [ - field SFString name "excavation_square" - field SFVec3f translation 0 0 0 - field SFRotation rotation 0 1 0 0 - field SFBool flipped FALSE - field SFFloat POSITION -0.4 - field SFFloat MIN_STOP -0.401426 - field SFFloat MAX_STOP 2 - field SFString{"yellow1", "yellow2", "purple1", "purple2", "red"} frontTexture "yellow1" -] -{ -Solid { - translation IS translation - rotation IS rotation - children [ - Group { - children [ - DEF EXCAVATION_SQUARE_BOUNDING Transform { - translation 0 -0.0075 0.035 - children [ - Shape { - appearance DEF WALL_APPEARANCE PBRAppearance { - baseColor 0.631 0.612 0.537 - roughness 1 - metalness 0 - } - geometry Box { - size 0.185 0.015 0.07 - } - } - ] - } - Transform { - translation -0.085 -0.0425 0.0075 - children [ - DEF EXCAVATION_SQUARE_BOTTOM_BOX Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.015 0.055 0.015 - } - } - ] - } - Transform { - translation 0.085 -0.0425 0.0075 - children [ - USE EXCAVATION_SQUARE_BOTTOM_BOX - ] - } - Transform { - translation -0.085 -0.02925 0.0425 - children [ - DEF EXCAVATION_SQUARE_FIRST_BOX Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.015 0.0285 0.055 - } - } - ] - } - Transform { - translation 0.085 -0.02925 0.0425 - children [ - USE EXCAVATION_SQUARE_FIRST_BOX - ] - } - Transform { - translation -0.085 -0.06175 0.0425 - children [ - DEF EXCAVATION_SQUARE_SECOND_BOX Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.015 0.0165 0.055 - } - } - ] - } - Transform { - translation 0.085 -0.06175 0.0425 - children [ - USE EXCAVATION_SQUARE_SECOND_BOX - ] - } - ] - } - HingeJoint { - jointParameters HingeJointParameters { - position IS POSITION - anchor 0 -0.0485 0.02 - minStop IS MIN_STOP - maxStop IS MAX_STOP - } - endPoint Solid { - translation 0 -0.0485 0.02 - rotation 1 0 0 %<= (fields.flipped.value) ? 3.2 : -0.4 >% - children [ - Transform { - translation 0 0 0.064 - children [ - Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.15 0.021 0.15 - } - } - ] - } - Transform { - translation 0 0.0105 0.064 - children [ - Shape { - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ %<= '"assets/excavation_squares/excSq_' + fields.frontTexture.value + '.png"' >% ] - repeatS FALSE - repeatT FALSE - } - roughness 1 - metalness 0 - } - geometry Box { - size 0.15 0.001 0.15 - } - } - ] - } - Transform { - translation 0 0 0.139785 - children [ - Shape { - appearance PBRAppearance { - baseColor 0.768627 0.627451 0 - baseColorMap ImageTexture { - url ["assets/pcb.png"] - repeatS FALSE - repeatT FALSE - } - roughness 1 - metalness 0 - } - geometry Box { - size 0.1 0.02 0.00157 - } - } - ] - } - ] - boundingObject Transform { - translation 0 0 0.064 - children [ - Shape { - appearance PBRAppearance { - } - geometry Box { - size 0.15 0.022 0.15 - } - } - ] - } - physics Physics { - } - } - } - ] - name IS name - boundingObject USE EXCAVATION_SQUARE_BOUNDING - locked TRUE -}} diff --git a/mep3_simulation/webots_data/protos/GalleryPanel.proto b/mep3_simulation/webots_data/protos/GalleryPanel.proto deleted file mode 100644 index cbde45d0e..000000000 --- a/mep3_simulation/webots_data/protos/GalleryPanel.proto +++ /dev/null @@ -1,87 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript -PROTO GalleryPanel [ - field SFString{"yellow", "purple"} teamColor "yellow" - hiddenField SFColor yellowColor 0.972549 0.694118 0.0666667 - hiddenField SFColor purpleColor 0.360784 0.282353 0.541176 - hiddenField SFVec3f yellowTranslation -0.69 1.0251 0 - hiddenField SFVec3f purpleTranslation 0.69 1.0251 0 -] -{ - %< - var color; - var translation; - if (fields.teamColor.value == "purple") { - color = fields.purpleColor.value; - translation = fields.purpleTranslation.value; - } - else { - color = fields.yellowColor.value; - translation = fields.yellowTranslation.value; - } - >% - Solid { - name %<= '"gallery_panel_' + fields.teamColor.value + '"' >% - translation %<= translation.x >% %<= translation.y >% %<= translation.z >% - rotation 0 1 0 0 - children [ - DEF gallery_panel Group { - children [ - Transform { - translation 0 -0.00914 0.14059 - rotation 1 0 0 -0.523598 - children [ - Shape { - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ %<= '"assets/gallery/' + fields.teamColor.value + '.png"' >% ] - repeatS FALSE - repeatT FALSE - filtering 1 - } - roughness 1 - metalness 0 - textureTransform TextureTransform { - scale 0.6 1 - } - } - geometry Box { - size 0.72 0.001 0.3 - } - } - ] - } - Transform { - translation 0 0.0004 0.1351 - rotation 1 0 0 -0.523598 - children [ - Shape { - appearance DEF gallery_panel_color PBRAppearance { - baseColor %<= color.r >% %<= color.g >% %<= color.b >% - roughness 1 - metalness 0 - } - geometry Box { - size 0.72 0.021 0.3 - } - } - ] - } - Transform { - translation 0 -0.0894 0.0246 - rotation 1 0 0 -0.523598 - children [ - Shape { - appearance USE gallery_panel_color - geometry Box { - size 0.72 0.022 0.044 - } - } - ] - } - ] - } - ] - boundingObject USE gallery_panel - } -} diff --git a/mep3_simulation/webots_data/protos/GenericRobot.proto b/mep3_simulation/webots_data/protos/GenericRobot.proto new file mode 100644 index 000000000..8338cfb4e --- /dev/null +++ b/mep3_simulation/webots_data/protos/GenericRobot.proto @@ -0,0 +1,81 @@ +#VRML_SIM R2022b utf8 +# template language: javascript + +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/BrushedAluminium.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/Plastic.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/CorrodedMetal.proto" +EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/devices/robotis/protos/RobotisLds01.proto" +EXTERNPROTO "OmniWheel.proto" +EXTERNPROTO "Wheel.proto" +EXTERNPROTO "ArucoTag.proto" + +PROTO GenericRobot [ + field SFString name "robot_memristor" + field SFVec3f translation 0.5 0 0 + field SFRotation rotation 0 1 0 0 + field SFString controller "" + field SFBool supervisor FALSE + field SFInt32 arucoNumber 1 + hiddenField SFFloat mass_robot 15 + hiddenField SFFloat robot_x_size 0.2 + hiddenField SFFloat robot_y_size 0.3 + hiddenField SFFloat robot_z_size 0.337 + hiddenField SFFloat cap_cylinder_height 0.15 +] +{ +Robot { + translation IS translation + rotation IS rotation + name IS name + supervisor IS supervisor + controller IS controller + children [ + RobotisLds01 { + translation 0 0 0.349 + rotation 0 0 1 -1.5708 + } + Wheel {} + Wheel {position "right"} + Wheel {type "motor" } + Wheel {type "motor" position "right"} + OmniWheel {} + ArucoTag { + arucoNumber IS arucoNumber + } + DEF BODY_SHAPE Transform { + translation 0 0 %<= fields.robot_z_size.value / 2 >% + children [ + Shape { + geometry Box { + size %<= fields.robot_x_size.value >% %<= fields.robot_y_size.value >% %<= fields.robot_z_size.value >% + } + appearance PBRAppearance { + transparency 0.1 + metalness 0 + } + } + ] + } + Transform { + translation 0 0 %<= fields.robot_z_size.value + fields.cap_cylinder_height.value/2 + 0.02 >% + children [ + DEF cap_cylinder Shape { + appearance PBRAppearance { + transparency 0.1 + metalness 0 + } + geometry Cylinder { + height IS cap_cylinder_height + radius 0.03 + } + } + ] + } + ] + boundingObject USE BODY_SHAPE + physics Physics { + density -1 + mass IS mass_robot + } +} +} \ No newline at end of file diff --git a/mep3_simulation/webots_data/protos/Hand.proto b/mep3_simulation/webots_data/protos/Hand.proto deleted file mode 100644 index 50045b66a..000000000 --- a/mep3_simulation/webots_data/protos/Hand.proto +++ /dev/null @@ -1,298 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript -PROTO Hand [ - field SFString {"left", "right", "mid"} position "left" - field SFString {"Dz", "G", "L", "S"} shape "Dz" - hiddenField SFVec3f anchor_Dz_left -0.03530 0.1295 0.1172 - hiddenField SFVec3f anchor_Dz_right -0.03530 -0.1295 0.1172 - hiddenField SFVec3f anchor_G_left -0.02095 0.1295 0.1397 - hiddenField SFVec3f anchor_G_right -0.02095 -0.1295 0.1397 - hiddenField SFVec3f anchor_L_mid -0.07655 0.0248 0.20104 - hiddenField SFVec3f anchor_S_mid 0.0825 -0.0009 0.0333 - hiddenField SFVec3f anchor_connector 0.0667 -0.0009 0.1525 - hiddenField SFVec3f anchor_gripper 0.0667 -0.0009 0.1425 - hiddenField SFRotation rotation_positive 1 0 0 1.57079 - hiddenField SFRotation rotation_negative 1 0 0 -1.57079 - hiddenField SFRotation rotation_zero 1 0 0 0 - hiddenField SFVec3f x_axis 1 0 0 - hiddenField SFVec3f y_axis 0 1 0 - hiddenField SFFloat hand_mass 0.05 - hiddenField SFVec3f gripper_inset 0 0 0.003 - hiddenField SFFloat resistance_position 0.015 -] -{ -%< - var anchor_gripper_inset; - var anchor_connector_inset; - anchor_gripper_inset = fields.anchor_gripper.value; - anchor_gripper_inset.x -= fields.gripper_inset.value.x; - anchor_gripper_inset.y -= fields.gripper_inset.value.y; - anchor_gripper_inset.z -= fields.gripper_inset.value.z; - anchor_connector_inset = fields.anchor_gripper.value; - anchor_connector_inset.x -= fields.gripper_inset.value.x; - anchor_connector_inset.y -= fields.gripper_inset.value.y; - anchor_connector_inset.z -= fields.gripper_inset.value.z; - - var anchor; - var axis; - var rotation; - var position; - var min_position; - var max_position; - if (fields.shape.value == "Dz") { - if (fields.position.value == "left") { - max_position = 1.570796; - min_position = -0.488692; - position = 1.57079; - anchor = fields.anchor_Dz_left.value; - axis = fields.x_axis.value; - rotation = fields.rotation_negative.value; - } - else { - min_position = -1.570796; - max_position = 0.488692; - position = -1.57079; - anchor = fields.anchor_Dz_right.value; - axis = fields.x_axis.value; - rotation = fields.rotation_positive.value; - } - } - else if (fields.shape.value == "G") { - if (fields.position.value == "left") { - max_position = 1.047198; - min_position = -1.570796; - position = -1.57079; - anchor = fields.anchor_G_left.value; - axis = fields.x_axis.value; - axis.x = -axis.x; - axis.y = -axis.y; - axis.z = -axis.z; - rotation = fields.rotation_positive.value; - } - else { - min_position = -1.047198; - max_position = 1.570796; - position = 1.57079; - anchor = fields.anchor_G_right.value; - axis = fields.x_axis.value; - axis.x = -axis.x; - axis.y = -axis.y; - axis.z = -axis.z; - rotation = fields.rotation_negative.value; - } - } - else if (fields.shape.value == "L") { - min_position = -1.57079; - max_position = 0.349066; - position = 0; - anchor = fields.anchor_L_mid.value; - axis = fields.y_axis.value; - axis.x = -axis.x; - axis.y = -axis.y; - axis.z = -axis.z; - rotation = fields.rotation_zero.value; - } - else { - min_position = -1.57079; - max_position = 0.349066; - position = -1.57079; - anchor = fields.anchor_S_mid.value; - axis = fields.y_axis.value; - rotation = fields.rotation_zero.value; - } ->% -Transform { - children [ - HingeJoint { - jointParameters HingeJointParameters { - axis %<= axis.x >% %<= axis.y >% %<= axis.z >% - anchor %<= anchor.x >% %<= anchor.y >% %<= anchor.z >% - position %<= position >% - } - device [ - RotationalMotor { - name %<= '"hand_' + fields.position.value + "_" + fields.shape.value + '"' >% - minPosition %<= min_position >% - maxPosition %<= max_position >% - } - PositionSensor { - name %<= '"hand_' + fields.position.value + "_" + fields.shape.value + '_sensor' + '"' >% - } - ] - endPoint Solid { - name %<= '"hand_' + fields.position.value + "_" + fields.shape.value + '"' >% - children [ - Shape { - appearance PBRAppearance { - %< if (fields.shape.value != "S") {>% - baseColor 0.4 0.4 0.4 - %< } else {>% - baseColor 1 0 0 - %< } >% - metalness 0 - roughness 1 - } - geometry Mesh { - url [%<= '"assets/meshes/RobotMemristor2/hand_' + fields.shape.value +'_' + fields.position.value + '.obj"' >%] - } - } - %< if (fields.shape.value == "L") { >% - Connector { - translation -0.09 0 0.123 - rotation 0 0 1 3.14159 - name "hand_L_statuette_connector" - type "active" - numberOfRotations 0 - distanceTolerance 0.02 - axisTolerance 0.5 - } - Connector { - translation -0.0821 0 0.1474 - rotation 0 0 1 0 - name "hand_L_replica_connector" - type "active" - isLocked TRUE - numberOfRotations 0 - } - %< } >% - %< if (fields.shape.value == "Dz") { >% - TouchSensor { - name %<= '"hand_' + fields.position.value + "_" + fields.shape.value + '_touch_sensor_front"' >% - contactMaterial "resistance_measurement" - boundingObject Group { - children [ - Transform { - translation -0.0104 %<= (fields.position.value == "left") ? 0.1333 + fields.resistance_position.value : -0.1333 - fields.resistance_position.value>% 0.206 - rotation 1 0 0 %<= (fields.position.value == "left") ? 0.07 : -0.07 >% - children [ - DEF resistance_pad Capsule { - height 0.018 - radius 0.004 - subdivision 16 - } - ] - } - ] - } - physics Physics { - } - type "force-3d" - } - TouchSensor { - name %<= '"hand_' + fields.position.value + "_" + fields.shape.value + '_touch_sensor_back"' >% - contactMaterial "resistance_measurement" - boundingObject Group { - children [ - Transform { - translation -0.0603 %<= (fields.position.value == "left") ? 0.1333 + fields.resistance_position.value : -0.1333 - fields.resistance_position.value >% 0.206 - rotation 1 0 0 %<= (fields.position.value == "left") ? 0.07 : -0.07 >% - children [ - USE resistance_pad - ] - } - ] - } - physics Physics { - } - type "force-3d" - } - %< } >% - %< if (fields.shape.value == "S") { >% - Connector { - translation %<= anchor_connector_inset.x >% %<= anchor_connector_inset.y >% %<= anchor_connector_inset.z >% - rotation 0 -1 0 1.57079 - name "arm_mid_connector" - type "active" - numberOfRotations 0 - distanceTolerance 0.02 - axisTolerance 0.5 - } - DistanceSensor { - name "arm_mid_connector_distance_sensor" - translation %<= anchor_connector_inset.x >% %<= anchor_connector_inset.y >% %<= anchor_connector_inset.z >% - rotation 0 -1 0 -1.5708 - lookupTable [ - 0 0 0, - 1000 1000 0 - ] - type "generic" - } - Shape { - appearance PBRAppearance { - baseColor 1 1 1 - metalness 0 - roughness 1 - } - geometry Mesh { - url [%<= '"assets/meshes/RobotMemristor2/sablja_sisaljka.obj"' >%] - } - } - %< } >% - ] - - %< if (fields.shape.value != "S") { >% - boundingObject Transform { - %< if (fields.shape.value == "Dz") { >% - %< if (fields.position.value == "left") { >% - translation %<= fields.anchor_Dz_left.value.x >% %<= fields.anchor_Dz_left.value.y >% %<= fields.anchor_Dz_left.value.z+0.046 >% - %< } else { >% - translation %<= fields.anchor_Dz_left.value.x >% %<= fields.anchor_Dz_right.value.y >% %<= fields.anchor_Dz_left.value.z+0.046 >% - %< } >% - children [ - Box { - size 0.058 0.011 0.11 - } - ] - %< } else if (fields.shape.value == "G") { >% - %< if (fields.position.value == "left") { >% - translation -0.0075 0.1295 0.186 - %< } else { >% - translation -0.0075 -0.1295 0.186 - %< } >% - children [ - Box { - size 0.035 0.02 0.117 - } - ] - %< } else if (fields.shape.value == "L") { >% - translation %<= fields.anchor_L_mid.value.x-0.008 >% 0 %<= fields.anchor_L_mid.value.z-0.052 >% - children [ - Box { - size 0.013 0.073 0.09 - } - ] - %< } >% - } - %< } else { >% - boundingObject Group { - children [ - Transform { - translation 0.067 -0.0008 0.121 - children [ - Box { - size 0.022 0.0506 0.027 - } - ] - } - Transform { - translation %<= anchor_gripper_inset.x >% %<= anchor_gripper_inset.y >% %<= anchor_gripper_inset.z >% - - children [ - Cylinder { - height 0.02 - radius 0.01 - } - ] - } - ] - } - %< } >% - physics Physics { - density -1 - mass IS hand_mass - } - } - } - ] -} -} diff --git a/mep3_simulation/webots_data/protos/Lift.proto b/mep3_simulation/webots_data/protos/Lift.proto deleted file mode 100644 index 46b768523..000000000 --- a/mep3_simulation/webots_data/protos/Lift.proto +++ /dev/null @@ -1,158 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/PerforatedMetal.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/BrushedAluminium.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/Plastic.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/CorrodedMetal.proto" -EXTERNPROTO "RobotArmMemristor2.proto" -EXTERNPROTO "Hand.proto" - -PROTO Lift [ - field SFString name "lift" - field SFVec3f translation 0 0 0 - field SFRotation rotation 0 1 0 0 - field SFString {"simple", "complex"} complexity "simple" - field SFFloat mass_base 0.1 - field SFVec3f com_base 0.07500 0 0.013 - field SFVec3f com_letva 0.05764 0 0.066 - field SFVec3f size_letva 0.0075 0.015 0.09 - hiddenField SFFloat robot_x_size 0.05 - hiddenField SFFloat plate_y_size 0.3 - hiddenField SFFloat plate_z_size 0.003 -] -{ -Solid { - translation IS translation - rotation IS rotation - name IS name - physics Physics { - density -1 - mass 0.05 - } - boundingObject Group{ children[ - Transform { - translation 0.01 0 0.01 - children [ - Box { size 0.001 0.001 0.001 } - ] - } - ]} - children [ - SliderJoint { - jointParameters JointParameters { - axis 0 0 1 - } - device [ - LinearMotor { - name %<= '"' + fields.name.value + '_motor' + '"' >% - maxForce 100 - minPosition 0 - maxPosition 0.08 - } - PositionSensor { - name %<= '"' + fields.name.value + '_sensor' + '"' >% - } - ] - endPoint Solid { - physics Physics { - density -1 - mass IS mass_base - } - children [ - Shape { - appearance Plastic { - colorOverride 0.6 0.6 0.6 - } - geometry Mesh { - url ["assets/meshes/RobotMemristor2/lift_plate.obj"] - } - } - Hand {shape "S" position "mid"} - Shape { - appearance Plastic { - colorOverride 1 0 0 - } - geometry Mesh { - url ["assets/meshes/RobotMemristor2/sablja_base.obj"] - } - } - RobotArmMemristor2 { - name "arm_left" - translation 0 0 0.009 - complexity IS complexity - } - RobotArmMemristor2 { - name "arm_right" - translation 0.15 0 0.009 - rotation 0 0 1 3.14159 - complexity IS complexity - MIN_POSITION -2.617994 - MAX_POSITION 0 - } - Shape { - appearance CorrodedMetal {IBLStrength 6} - geometry Mesh { - url ["assets/meshes/RobotMemristor2/lift_letva.obj"] - } - } - %< if (fields.complexity.value == "complex") { >% - Shape { - appearance CorrodedMetal {} - geometry Mesh { - url ["assets/meshes/RobotMemristor2/lift_sine_drzaci.obj"] - } - } - %< } >% - ] - boundingObject Group{ children[ - Transform { - translation IS com_base - children [ - Box { - size %<= fields.robot_x_size.value >% %<= fields.plate_y_size.value >% %<= fields.plate_z_size.value >% - } - - ] - } - Transform { - translation IS com_letva - children [ - Box { - size IS size_letva - } - - ] - } - ]} - } - } - %< if (fields.complexity.value == "complex") { >% - Shape { - appearance PerforatedMetal {IBLStrength 10} - geometry Mesh { - url ["assets/meshes/RobotMemristor2/lift_sine.obj"] - } - } - Shape { - appearance BrushedAluminium {IBLStrength 10} - geometry Mesh { - url ["assets/meshes/RobotMemristor2/lift_zupcanik.obj"] - } - } - Shape { - appearance CorrodedMetal {} - geometry Mesh { - url ["assets/meshes/RobotMemristor2/lift_motor.obj"] - } - } - Shape { - appearance Plastic {colorOverride 0 0 0.5} - geometry Mesh { - url ["assets/meshes/RobotMemristor2/lift_motor_kuciste.obj"] - } - } - %< } >% - ] -} -} diff --git a/mep3_simulation/webots_data/protos/Replica.proto b/mep3_simulation/webots_data/protos/Replica.proto deleted file mode 100644 index 311420d10..000000000 --- a/mep3_simulation/webots_data/protos/Replica.proto +++ /dev/null @@ -1,38 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/RoughOak.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/trees/protos/Oak.proto" - -PROTO Replica [ - field SFString name "replica" - field SFVec3f translation 1.2491 0.1521 0.1579 - field SFRotation rotation 0 0 1 1.5708 -] -{ - Solid { - translation IS translation - rotation IS rotation - name IS name - children [ - DEF STATUETTE_SHAPE Shape { - appearance RoughOak {} - geometry Box { - size 0.06 0.06 0.06 - } - } - Connector { - name "connector_replica" - translation 0.03 0 0 - rotation 0 1 0 0 - type "passive" - numberOfRotations 0 - } - ] - boundingObject USE STATUETTE_SHAPE - physics Physics { - density -1 - mass 0.2 - } - } -} diff --git a/mep3_simulation/webots_data/protos/RobotArmMemristor2.proto b/mep3_simulation/webots_data/protos/RobotArmMemristor2.proto deleted file mode 100644 index bb36c164c..000000000 --- a/mep3_simulation/webots_data/protos/RobotArmMemristor2.proto +++ /dev/null @@ -1,326 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/BrushedAluminium.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/Plastic.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/CorrodedMetal.proto" - -PROTO RobotArmMemristor2 [ - field SFString name "robot_arm" - field SFVec3f translation 0 0 0 - field SFRotation rotation 0 1 0 0 - field SFString {"simple", "complex"} complexity "simple" - field SFFloat mass_base 0.1 - field SFVec3f com_base 0.07500 0.10820 0.02809 - field SFVec3f anchor_base 0.075 0.09075 0.0517 - field SFFloat mass_mid_l 0.05041 - field SFVec3f com_mid_l 0.07532 0.09079 0.08283 - field SFVec3f anchor_mid_l 0.0986 0.09075 0.096 - field SFFloat mass_mid_u 0.3 - field SFVec3f com_mid_ul 0.07560 0.09075 0.11668 - field SFVec3f com_mid_uu 0.07439 0.07595 0.16839 - field SFVec3f anchor_mid_u 0.098 0.06965 0.17931 - field SFFloat mass_gripper 0.1 - field SFVec3f com_gripper_l 0.07460 0.0677 0.194 - field SFVec3f com_gripper_m 0.07460 0.0549 0.235 - field SFVec3f com_gripper_u 0.07645 0.0317 0.25463 - field SFVec3f size_gripper_l 0.049 0.02 0.051 - field SFVec3f size_gripper_m 0.049 0.016 0.053 - field SFVec3f anchor_gripper 0.07645 0.0217 0.25463 - field SFVec3f gripper_inset 0 -0.004 0 - field SFFloat MIN_POSITION 0 - field SFFloat MAX_POSITION 2.617994 -] -{ - %< - var anchor_gripper_inset; - var com_gripper_u_inset; - anchor_gripper_inset = fields.anchor_gripper.value; - com_gripper_u_inset = fields.com_gripper_u.value; - anchor_gripper_inset.x -= fields.gripper_inset.value.x; - anchor_gripper_inset.y -= fields.gripper_inset.value.y; - anchor_gripper_inset.z -= fields.gripper_inset.value.z; - com_gripper_u_inset.x -= fields.gripper_inset.value.x; - com_gripper_u_inset.y -= fields.gripper_inset.value.y; - com_gripper_u_inset.z -= fields.gripper_inset.value.z; - >% -Solid { - translation IS translation - rotation IS rotation - name IS name - boundingObject Transform { - translation IS com_base - children [ - Box { - size 0.05 0.07 0.045 - } - ] - } - physics Physics { - density -1 - mass IS mass_base - } - children [ - Shape { - appearance DEF ROBOT_ARM_APPEARANCE PBRAppearance { - baseColor 1 0 0 - roughness 1 - metalness 0 - } - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/base.obj"] - } - } - HingeJoint { - jointParameters HingeJointParameters { - anchor IS anchor_base - axis 0 0 1 - } - device [ - RotationalMotor { - name %<= '"' + fields.name.value + '_motor_base' + '"' >% - maxTorque 100 - minPosition IS MIN_POSITION - maxPosition IS MAX_POSITION - } - PositionSensor { - name %<= '"' + fields.name.value + '_sensor_base' + '"' >% - } - ] - endPoint Solid { - boundingObject Transform { - translation IS com_mid_l - children [ - Box { - size 0.05 0.036 0.061 - } - ] - } - physics Physics { - density -1 - mass IS mass_mid_l - } - children [ - Shape { - appearance USE ROBOT_ARM_APPEARANCE - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/mid_lower.obj"] - } - } - Transform { - translation 0 0 0 - children [ - HingeJoint { - jointParameters HingeJointParameters { - axis 1 0 0 - anchor IS anchor_mid_l - } - device [ - RotationalMotor { - name %<= '"' + fields.name.value + '_motor_mid' + '"' >% - maxTorque 100 - minPosition 0 - maxPosition 2.617994 - } - PositionSensor { - name %<= '"' + fields.name.value + '_sensor_mid' + '"' >% - } - ] - endPoint Solid { - boundingObject Group { - children [ - Transform { - translation IS com_mid_uu - rotation 1 0 0 0.523599 - children [ - Box { - size 0.042 0.037 0.062 - } - ] - } - Transform { - translation IS com_mid_ul - children [ - Box { - size 0.046 0.03 0.07 - } - ] - } - ] - } - physics Physics { - density -1 - mass IS mass_mid_u - } - children [ - Shape { - appearance USE ROBOT_ARM_APPEARANCE - geometry Mesh { - url [ - "assets/meshes/RobotArmMemristor2/mid_upper.obj" - ] - } - } - Transform { - translation 0 0 0 - children [ - HingeJoint { - jointParameters HingeJointParameters { - axis 1 0 0 - anchor IS anchor_mid_u - position -0.523599 - } - device [ - RotationalMotor { - name %<= '"' + fields.name.value + '_motor_gripper' + '"' >% - maxTorque 100 - minPosition -1.570796 - maxPosition 1.047198 - } - PositionSensor { - name %<= '"' + fields.name.value + '_sensor_gripper' + '"' >% - } - ] - endPoint Solid { - boundingObject Group { - children [ - Transform { - translation IS com_gripper_l - children [ - Box { - size IS size_gripper_l - } - ] - } - Transform { - translation IS com_gripper_m - rotation 1 0 0 0.523599 - children [ - Box { - size IS size_gripper_m - } - ] - } - Transform { - translation %<= com_gripper_u_inset.x >% %<= com_gripper_u_inset.y >% %<= com_gripper_u_inset.z >% - rotation 1 0 0 1.5708 - children [ - Cylinder { - height 0.02 - radius 0.01 - } - ] - } - ] - } - physics Physics { - density -1 - mass IS mass_gripper - } - children [ - Shape { - appearance PBRAppearance { - baseColor 1 1 1 - metalness 0 - roughness 1 - } - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/connector2.obj"] - } - } - Shape { - appearance USE ROBOT_ARM_APPEARANCE - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/gripper2.obj"] - } - } - Connector { - name %<= '"' + fields.name.value + '_connector' + '"' >% - translation %<= anchor_gripper_inset.x >% %<= anchor_gripper_inset.y >% %<= anchor_gripper_inset.z >% - rotation 0 0 1 -1.5708 - type "active" - distanceTolerance 0.075 - axisTolerance 0.1 - numberOfRotations 0 - snap FALSE - } - DistanceSensor { - name %<= '"' + fields.name.value + '_connector_distance_sensor' + '"' >% - translation %<= anchor_gripper_inset.x >% %<= anchor_gripper_inset.y >% %<= anchor_gripper_inset.z >% - rotation 0 1 0 -1.5708 - lookupTable [ - 0 0 0, - 1000 1000 0 - ] - type "generic" - } - %< if (fields.complexity.value == "complex") { >% - Shape { - appearance Plastic { - colorOverride 0 0 0 - } - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/gripper_dodatno.obj"] - } - } - %< } >% - ] - } - } - ] - } - %< if (fields.complexity.value == "complex") { >% - Shape { - appearance CorrodedMetal {} - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/mid_upper_motor.obj"] - } - } - Shape { - appearance Plastic { - colorOverride 0.5 0.5 0.5 - } - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/mid_upper_grey.obj"] - } - } - Shape { - appearance BrushedAluminium {} - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/mid_upper_screws.obj"] - } - } - %< } >% - ] - } - } - ] - } - %< if (fields.complexity.value == "complex") { >% - Shape { - appearance CorrodedMetal {} - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/mid_lower_motor.obj"] - } - } - Shape { - appearance BrushedAluminium {} - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/mid_lower_white.obj"] - } - } - %< } >% - ] - } - } - %< if (fields.complexity.value == "complex") { >% - Shape { - appearance CorrodedMetal {} - geometry Mesh { - url ["assets/meshes/RobotArmMemristor2/base_motor.obj"] - } - } - %< } >% - ] -} -} diff --git a/mep3_simulation/webots_data/protos/RobotMemristor2.proto b/mep3_simulation/webots_data/protos/RobotMemristor2.proto deleted file mode 100644 index 799413410..000000000 --- a/mep3_simulation/webots_data/protos/RobotMemristor2.proto +++ /dev/null @@ -1,267 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/BrushedAluminium.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/Plastic.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/appearances/protos/CorrodedMetal.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/devices/robotis/protos/RobotisLds01.proto" -EXTERNPROTO "OmniWheel.proto" -EXTERNPROTO "Lift.proto" -EXTERNPROTO "Wheel.proto" -EXTERNPROTO "Hand.proto" -EXTERNPROTO "ArucoTag.proto" - -PROTO RobotMemristor2 [ - field SFString name "robot_memristor" - field SFVec3f translation 0.5 0 0 - field SFRotation rotation 0 1 0 0 - field SFString controller "void" - field SFBool supervisor FALSE - field SFInt32 arucoNumber 1 - field SFString {"simple", "complex"} complexity "simple" - hiddenField SFFloat mass_robot 15 - hiddenField SFFloat mass_motor_wheel 0.05 - hiddenField SFFloat mass_encoder_wheel 0.05 - hiddenField SFFloat mass_arm_base 0.2 - hiddenField SFFloat mass_arm_mid1 0.15 - hiddenField SFFloat mass_arm_mid2 0.3 - hiddenField SFFloat mass_arm_gripper 0.1 - hiddenField SFFloat body_offset 0.0105 - hiddenField SFFloat arm_x 0.075 - hiddenField SFFloat arm_y 0.132 - hiddenField SFFloat arm_z 0.063 - hiddenField SFFloat robot_x_size 0.2 - hiddenField SFFloat robot_x_inner_size 0.132 - hiddenField SFFloat robot_x_edge_size 0.034 - hiddenField SFFloat robot_y_edge_size 0.095 - hiddenField SFFloat robot_y_size 0.3 - hiddenField SFFloat robot_z_size 0.337 - hiddenField SFFloat robot_height 0.013 - hiddenField SFFloat robot_plate_width 0.02 - hiddenField SFFloat cap_cylinder_height 0.025 -] -{ -Robot { - translation IS translation - rotation IS rotation - name IS name - supervisor IS supervisor - controller IS controller - children [ - Transform { - translation 0 0 %<= fields.body_offset.value >% - children [ - Shape { - appearance Plastic { - colorOverride 0.6 0.6 0.6 - } - geometry Mesh { - url ["assets/meshes/RobotMemristor2/robot_osnovno.obj"] - } - } - Shape { - appearance Plastic { - colorOverride 1 0 0 - } - geometry Mesh { - url ["assets/meshes/RobotMemristor2/robot_crveno.obj"] - } - } - Shape { - appearance Plastic { - colorOverride 0 0 0 - } - geometry Mesh { - url ["assets/meshes/RobotMemristor2/kapa.obj"] - } - } - Shape { - appearance Plastic { - colorOverride 1 1 1 - } - geometry Mesh { - url ["assets/meshes/RobotMemristor2/sisaljke_osnovno.obj"] - } - } - DEF leva_sisaljka Connector { - translation 0.0465 0.08383 0.16865 - name "robot_left_connector" - type "active" - numberOfRotations 0 - } - DEF desna_sisaljka Connector { - translation 0.0465 -0.08383 0.16865 - name "robot_right_connector" - type "active" - numberOfRotations 0 - } - RobotisLds01 { - translation -0.0262 -0.0008 0.349 - rotation 0 0 1 -1.5708 - } - Hand {} - Hand {position "right"} - Hand {shape "G"} - Hand {shape "G" position "right"} - Hand {shape "L" position "mid"} - Lift { - name "lift" - complexity IS complexity - } - Solid { - # translation 0.0056 0.022 %<= fields.robot_z_size.value + fields.cap_cylinder_height.value/2 >% - translation -0.0254 0.038 %<= fields.robot_z_size.value + fields.cap_cylinder_height.value/2 >% - children [ - DEF cap_cylinder Shape { - appearance Plastic { - colorOverride 0 0 0 - } - geometry Cylinder { - height IS cap_cylinder_height - radius 0.0015 - } - } - ] - boundingObject USE cap_cylinder - physics DEF physics_cylinder Physics { - density -1 - mass 0.001 - } - name "front_left_cap_cylinder" - } - Solid { - translation 0.0074 -0.019 %<= fields.robot_z_size.value + fields.cap_cylinder_height.value/2 >% - children [USE cap_cylinder] - boundingObject USE cap_cylinder - physics USE physics_cylinder - name "front_right_cap_cylinder" - } - Solid { - translation -0.0583 -0.019 %<= fields.robot_z_size.value + fields.cap_cylinder_height.value/2 >% - children [USE cap_cylinder] - boundingObject USE cap_cylinder - physics USE physics_cylinder - name "back_right_cap_cylinder" - } - %< if (fields.complexity.value == "complex") { >% - Shape { - appearance Plastic {colorOverride 0 0 0} - geometry Mesh {url ["assets/meshes/RobotMemristor2/pogon_zatezaci.obj"]} - } - Shape { - appearance BrushedAluminium {} - geometry Mesh {url ["assets/meshes/RobotMemristor2/robot_bosch.obj"]} - } - Shape { - appearance CorrodedMetal {} - geometry Mesh {url ["assets/meshes/RobotMemristor2/robot_motori.obj"]} - } - Shape { - appearance Plastic {colorOverride 0 0 0.5} - geometry Mesh {url ["assets/meshes/RobotMemristor2/robot_motori_drzaci.obj"]} - } - Shape { - appearance Plastic {colorOverride 0.5 0.5 0.5} - geometry Mesh {url ["assets/meshes/RobotMemristor2/robot_vakuum_pumpe.obj"]} - } - Shape { - appearance Plastic {colorOverride 0 0 0} - geometry Mesh {url ["assets/meshes/RobotMemristor2/sisaljke_kolena.obj"]} - } - Shape { - appearance Plastic {colorOverride 0 1 0} - geometry Mesh {url ["assets/meshes/RobotMemristor2/sisaljke_baza.obj"]} - } - Shape { - appearance Plastic {colorOverride 0.7 0.7 0.7} - geometry Mesh {url ["assets/meshes/RobotMemristor2/zamenjivac_dodatno.obj"]} - } - Transform { - translation 0.001 -0.125 0.348 - children [ - Shape { - appearance Plastic {colorOverride 1 0 0} - geometry Mesh {url ["assets/meshes/RobotMemristor2/mushroom.obj"]} - } - ] - } - Transform { - translation -0.0125 0.116 0.331 - children [ - Shape { - appearance Plastic {colorOverride 0 1 0} - geometry Mesh {url ["assets/meshes/RobotMemristor2/switch.obj"]} - } - ] - } - Transform { - translation 0.0075 0.116 0.331 - children [ - Shape { - appearance Plastic {colorOverride 0 1 0} - geometry Mesh {url ["assets/meshes/RobotMemristor2/switch.obj"]} - } - ] - } - %< } >% - ] - } - Wheel {} - Wheel {position "right"} - Wheel {type "motor" } - Wheel {type "motor" position "right"} - OmniWheel {} - ArucoTag { - arucoNumber IS arucoNumber - } - ] - boundingObject Group { - children [ - Transform { - translation %<= -(fields.robot_x_size.value - fields.robot_x_inner_size.value)/2 +0.008>% 0 %<= fields.robot_z_size.value/8 + fields.robot_height.value + fields.robot_plate_width.value/4 >% - children [ - Box { - size %<= fields.robot_x_inner_size.value >% %<= fields.robot_y_size.value >% %<= fields.robot_z_size.value/4 - fields.robot_plate_width.value/2 >% - } - ] - } - Transform { - translation %<= -(fields.robot_x_size.value - fields.robot_x_inner_size.value)/2 +0.008>% 0 %<= fields.robot_z_size.value*7/8-0.013 + fields.robot_height.value + fields.robot_plate_width.value/4 >% - children [ - Box { - size %<= fields.robot_x_inner_size.value >% %<= fields.robot_y_size.value >% %<= fields.robot_z_size.value/4 - fields.robot_plate_width.value/2 + 0.026 >% - } - ] - } - Transform { - translation 0.004 0 %<= fields.robot_height.value >% - children [ - Box { - size %<= fields.robot_x_size.value - 0.008>% %<= fields.robot_y_size.value >% %<= fields.robot_plate_width.value >% - } - ] - } - Transform { - translation %<= -(fields.robot_x_size.value - fields.robot_x_inner_size.value)/2 + 0.008 >% %<= (fields.robot_y_size.value - fields.robot_y_edge_size.value)/2 >% %<= fields.robot_z_size.value/2 + fields.robot_height.value + fields.robot_plate_width.value/4 >% - children [ - Box { - size %<= fields.robot_x_inner_size.value >% %<= fields.robot_y_edge_size.value >% %<= fields.robot_z_size.value - fields.robot_plate_width.value/2 >% - } - ] - } - Transform { - translation %<= -(fields.robot_x_size.value - fields.robot_x_inner_size.value)/2 + 0.008 >% %<= -(fields.robot_y_size.value - fields.robot_y_edge_size.value)/2 >% %<= fields.robot_z_size.value/2 + fields.robot_height.value + fields.robot_plate_width.value/4 >% - children [ - Box { - size %<= fields.robot_x_inner_size.value >% %<= fields.robot_y_edge_size.value >% %<= fields.robot_z_size.value - fields.robot_plate_width.value/2 >% - } - ] - } - ] - } - physics Physics { - density -1 - mass IS mass_robot - } -} -} diff --git a/mep3_simulation/webots_data/protos/Sample.proto b/mep3_simulation/webots_data/protos/Sample.proto deleted file mode 100644 index f16da7f18..000000000 --- a/mep3_simulation/webots_data/protos/Sample.proto +++ /dev/null @@ -1,112 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript -PROTO Sample [ - field SFString name "sample" - field SFVec3f translation 0 0 0 - field SFRotation rotation 0 1 0 0 - field SFString{"empty", "red", "green", "blue", "bottom"} frontTexture "empty" -] -{ - Solid { - translation IS translation - rotation IS rotation - children [ - Transform { - children [ - Connector { - name "top" - translation 0 0 0.0075 - rotation 0 1 0 -1.5708 - type "passive" - numberOfRotations 0 - } - Shape { - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ %<= '"assets/samples/' + fields.frontTexture.value + '.png"' >% ] - repeatS FALSE - repeatT FALSE - filtering 1 - } - roughness 1 - metalness 0 - textureTransform DEF MAERKER_TEXTURE_SCALE TextureTransform { - translation 0 0.14 - } - } - geometry DEF MARKER_SHAPE_HALF IndexedFaceSet { - coord Coordinate { - point [ - 0.075 -1.66533e-16 0, 0.0375 -0.0649519 0, 0.0375 0.0649519 0, -0.0375 -0.0649519 0, -0.0375 0.0649519 0, -0.075 2.77556e-17 0, -0.0375 0.0649519 0.0075, -0.075 2.77556e-17 0.0075, 0.0375 0.0649519 0.0075, -0.0375 -0.0649519 0.0075, 0.075 -1.66533e-16 0.0075, 0.0375 -0.0649519 0.0075, -0.0375 0.0649519 0.0075, 0.0375 0.0649519 0.0075, -0.0375 0.0649519 0, 0.0375 0.0649519 0, 0.0375 0.0649519 0.0075, 0.075 -1.66533e-16 0.0075, 0.0375 0.0649519 0, 0.075 -1.66533e-16 0, -0.075 2.77556e-17 0.0075, -0.0375 0.0649519 0.0075, -0.075 2.77556e-17 0, -0.0375 0.0649519 0, -0.0375 -0.0649519 0.0075, -0.075 2.77556e-17 0.0075, -0.0375 -0.0649519 0, -0.075 2.77556e-17 0, 0.0375 -0.0649519 0.0075, -0.0375 -0.0649519 0.0075, 0.0375 -0.0649519 0, -0.0375 -0.0649519 0, 0.075 -1.66533e-16 0.0075, 0.0375 -0.0649519 0.0075, 0.075 -1.66533e-16 0, 0.0375 -0.0649519 0 - ] - } - normal Normal { - vector [ - 0 0 -1, 0 0 -1, 0 0 -1, 0 0 -1, 0 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 0, 0 1 0, 0 1 0, 0 1 0, 0.866025 0.5 0, 0.866025 0.5 0, 0.866025 0.5 0, 0.866025 0.5 0, -0.866025 0.5 0, -0.866025 0.5 0, -0.866025 0.5 0, -0.866025 0.5 0, -0.866025 -0.5 0, -0.866025 -0.5 0, -0.866025 -0.5 0, -0.866025 -0.5 0, 0 -1 0, 0 -1 0, 0 -1 0, 0 -1 0, 0.866025 -0.5 0, 0.866025 -0.5 0, 0.866025 -0.5 0, 0.866025 -0.5 0 - ] - } - coordIndex [ - 0, 1, 2, -1, 1, 3, 2, -1, 2, 3, 4, -1, 3, 5, 4, -1, 6, 7, 8, -1, 7, 9, 8, -1, 8, 9, 10, -1, 9, 11, 10, -1, 12, 13, 14, -1, 13, 15, 14, -1, 16, 17, 18, -1, 17, 19, 18, -1, 20, 21, 22, -1, 21, 23, 22, -1, 24, 25, 26, -1, 25, 27, 26, -1, 28, 29, 30, -1, 29, 31, 30, -1, 32, 33, 34, -1, 33, 35, 34, -1 - ] - } - } - ] - } - Transform { - translation 0 0 -0.0075 - children [ - Connector { - rotation 0 1 0 1.5708 - name "bottom" - type "passive" - numberOfRotations 0 - } - Shape { - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ - "assets/samples/bottom.png" - ] - repeatS FALSE - repeatT FALSE - filtering 1 - } - roughness 1 - metalness 0 - textureTransform USE MAERKER_TEXTURE_SCALE - name "DefaultMaterial" - } - geometry USE MARKER_SHAPE_HALF - } - ] - } - ] - name IS name - boundingObject Group { - children [ - DEF MARKER_BOUNDING_BOX Shape { - geometry Box { - size 0.075 0.129904 0.015 - } - } - Transform { - translation 0 0 0.0001 - rotation 0 0 1 1.0472 - children [ - USE MARKER_BOUNDING_BOX - ] - } - Transform { - rotation 0 0 1 -1.047195307179586 - children [ - USE MARKER_BOUNDING_BOX - ] - } - ] - } - physics Physics { - density -1 - mass 0.15 - } - } -} diff --git a/mep3_simulation/webots_data/protos/Statuette.proto b/mep3_simulation/webots_data/protos/Statuette.proto deleted file mode 100644 index 79c664764..000000000 --- a/mep3_simulation/webots_data/protos/Statuette.proto +++ /dev/null @@ -1,42 +0,0 @@ -#VRML_SIM R2022b utf8 -# template language: javascript -PROTO Statuette [ - field SFString name "statuette" - field SFVec3f translation 1.26798097 -0.7679809704 0.1245 - field SFRotation rotation 0 0 1 2.35619 -] -{ - Solid { - translation IS translation - rotation IS rotation - name IS name - children [ - DEF STATUETTE_SHAPE Shape { - appearance PBRAppearance { - baseColor 0 0 0 - roughness 1 - metalness 0 - } - geometry Mesh { - url ["assets/meshes/statuette.obj"] - } - } - Connector { - name "connector_statuette" - translation 0.0325 0 0.009 - rotation 0 1 0 0 - type "passive" - numberOfRotations 0 - distanceTolerance 0.02 - axisTolerance 0.5 - } - ] - boundingObject Box { - size 0.065 0.065 0.065 - } - physics Physics { - density -1 - mass 0.6 - } - } -} diff --git a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_purple1.png b/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_purple1.png deleted file mode 100644 index 02f51c07c..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_purple1.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_purple2.png b/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_purple2.png deleted file mode 100644 index d2a7ea56f..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_purple2.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_red.png b/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_red.png deleted file mode 100644 index d72d64374..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_red.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_yellow1.png b/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_yellow1.png deleted file mode 100644 index 4a6a288e0..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_yellow1.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_yellow2.png b/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_yellow2.png deleted file mode 100644 index ac19b28fa..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/excavation_squares/excSq_yellow2.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/gallery/purple.png b/mep3_simulation/webots_data/worlds/assets/gallery/purple.png deleted file mode 100644 index ca6b9b1dc..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/gallery/purple.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/gallery/yellow.png b/mep3_simulation/webots_data/worlds/assets/gallery/yellow.png deleted file mode 100644 index 835aea7c8..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/gallery/yellow.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/base.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/base.obj deleted file mode 100644 index e1ef239e6..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/base.obj +++ /dev/null @@ -1,2808 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object base_osnovno.obj -# -# Vertices: 686 -# Faces: 1420 -# -#### -vn -0.637729 -0.000001 0.770261 -v 0.059036 0.080000 0.008000 -vn -0.637729 -0.000001 -0.770261 -v 0.059036 0.080000 0.005000 -vn -0.552288 0.318863 0.770263 -v 0.058822 0.079200 0.008000 -vn -0.552288 0.318863 -0.770263 -v 0.058822 0.079200 0.005000 -vn -0.318864 0.552289 0.770261 -v 0.058236 0.078614 0.008000 -vn -0.318864 0.552289 -0.770261 -v 0.058236 0.078614 0.005000 -vn 0.000000 0.637727 0.770262 -v 0.057436 0.078400 0.008000 -vn 0.000000 0.637727 -0.770262 -v 0.057436 0.078400 0.005000 -vn 0.318864 0.552289 0.770261 -v 0.056636 0.078614 0.008000 -vn 0.318864 0.552289 -0.770261 -v 0.056636 0.078614 0.005000 -vn 0.552288 0.318863 0.770263 -v 0.056050 0.079200 0.008000 -vn 0.552288 0.318863 -0.770263 -v 0.056050 0.079200 0.005000 -vn 0.637729 -0.000001 0.770261 -v 0.055836 0.080000 0.008000 -vn 0.637729 -0.000001 -0.770261 -v 0.055836 0.080000 0.005000 -vn 0.552288 -0.318864 0.770263 -v 0.056050 0.080800 0.008000 -vn 0.552288 -0.318864 -0.770263 -v 0.056050 0.080800 0.005000 -vn 0.318864 -0.552289 0.770261 -v 0.056636 0.081386 0.008000 -vn 0.318864 -0.552289 -0.770261 -v 0.056636 0.081386 0.005000 -vn 0.000000 -0.637727 0.770262 -v 0.057436 0.081600 0.008000 -vn 0.000000 -0.637727 -0.770262 -v 0.057436 0.081600 0.005000 -vn -0.318864 -0.552289 0.770261 -v 0.058236 0.081386 0.008000 -vn -0.318864 -0.552289 -0.770261 -v 0.058236 0.081386 0.005000 -vn -0.552288 -0.318864 0.770262 -v 0.058822 0.080800 0.008000 -vn -0.552288 -0.318864 -0.770263 -v 0.058822 0.080800 0.005000 -vn -0.637730 -0.000000 0.770260 -v 0.094170 0.135500 0.008000 -vn -0.637730 -0.000000 -0.770260 -v 0.094170 0.135500 0.005000 -vn -0.552289 0.318861 0.770263 -v 0.093956 0.134700 0.008000 -vn -0.552289 0.318861 -0.770263 -v 0.093956 0.134700 0.005000 -vn -0.318862 0.552289 0.770263 -v 0.093370 0.134114 0.008000 -vn -0.318862 0.552289 -0.770263 -v 0.093370 0.134114 0.005000 -vn -0.000000 0.637730 0.770260 -v 0.092570 0.133900 0.008000 -vn 0.000000 0.637730 -0.770260 -v 0.092570 0.133900 0.005000 -vn 0.318862 0.552289 0.770263 -v 0.091770 0.134114 0.008000 -vn 0.318862 0.552289 -0.770263 -v 0.091770 0.134114 0.005000 -vn 0.552289 0.318862 0.770263 -v 0.091184 0.134700 0.008000 -vn 0.552289 0.318862 -0.770263 -v 0.091184 0.134700 0.005000 -vn 0.637730 0.000000 0.770260 -v 0.090970 0.135500 0.008000 -vn 0.637730 0.000000 -0.770260 -v 0.090970 0.135500 0.005000 -vn 0.552289 -0.318862 0.770263 -v 0.091184 0.136300 0.008000 -vn 0.552289 -0.318862 -0.770263 -v 0.091184 0.136300 0.005000 -vn 0.318862 -0.552289 0.770263 -v 0.091770 0.136886 0.008000 -vn 0.318862 -0.552289 -0.770263 -v 0.091770 0.136886 0.005000 -vn -0.000000 -0.637730 0.770260 -v 0.092570 0.137100 0.008000 -vn 0.000000 -0.637730 -0.770260 -v 0.092570 0.137100 0.005000 -vn -0.318862 -0.552289 0.770263 -v 0.093370 0.136886 0.008000 -vn -0.318861 -0.552289 -0.770263 -v 0.093370 0.136886 0.005000 -vn -0.552289 -0.318862 0.770263 -v 0.093956 0.136300 0.008000 -vn -0.552289 -0.318861 -0.770263 -v 0.093956 0.136300 0.005000 -vn -0.724383 -0.071346 0.685696 -v 0.097003 0.135750 0.011000 -vn -0.724383 -0.071346 -0.685696 -v 0.097003 0.135750 0.047000 -vn -0.689401 -0.285560 0.665719 -v 0.096699 0.137281 0.011000 -vn -0.689401 -0.285560 -0.665719 -v 0.096699 0.137281 0.047000 -vn -0.527646 -0.527643 0.665719 -v 0.095831 0.138578 0.011000 -vn -0.527646 -0.527643 -0.665719 -v 0.095831 0.138578 0.047000 -vn -0.285560 -0.689402 0.665718 -v 0.094534 0.139445 0.011000 -vn -0.285560 -0.689402 -0.665718 -v 0.094534 0.139445 0.047000 -vn -0.071344 -0.724382 0.685697 -v 0.093003 0.139750 0.011000 -vn -0.071344 -0.724382 -0.685697 -v 0.093003 0.139750 0.047000 -vn 0.724383 0.071346 0.685696 -v 0.053003 0.079750 0.011000 -vn 0.724383 0.071346 -0.685696 -v 0.053003 0.079750 0.047000 -vn 0.689401 0.285559 0.665719 -v 0.053308 0.078219 0.011000 -vn 0.689401 0.285559 -0.665719 -v 0.053308 0.078219 0.047000 -vn 0.527645 0.527645 0.665719 -v 0.054175 0.076922 0.011000 -vn 0.527646 0.527645 -0.665719 -v 0.054175 0.076922 0.047000 -vn 0.285560 0.689401 0.665719 -v 0.055472 0.076054 0.011000 -vn 0.285560 0.689401 -0.665719 -v 0.055472 0.076054 0.047000 -vn 0.071346 0.724383 0.685696 -v 0.057003 0.075750 0.011000 -vn 0.071346 0.724383 -0.685696 -v 0.057003 0.075750 0.047000 -vn 0.285560 0.689400 -0.665720 -v 0.097534 0.142445 0.005000 -vn 0.527645 0.527645 -0.665719 -v 0.098831 0.141578 0.005000 -vn 0.689401 0.285559 -0.665719 -v 0.099699 0.140281 0.005000 -vn -0.552289 -0.318862 -0.770262 -v 0.058822 0.136300 0.005000 -vn -0.318862 -0.552288 -0.770263 -v 0.058236 0.136886 0.005000 -vn 0.637728 0.000000 -0.770262 -v 0.061643 0.137750 0.005000 -vn 0.071347 0.724382 -0.685697 -v 0.096003 0.142750 0.005000 -vn 0.724383 0.071346 -0.685696 -v 0.100003 0.138750 0.005000 -vn -0.637729 -0.000000 -0.770261 -v 0.059036 0.135500 0.005000 -vn -0.637727 -0.000000 -0.770262 -v 0.088363 0.137750 0.005000 -vn -0.623737 0.258362 -0.737700 -v 0.088095 0.136750 0.005000 -vn -0.792406 0.000001 -0.609994 -v 0.087374 0.135500 0.005000 -vn -0.396203 -0.686244 -0.609994 -v 0.089972 0.131000 0.005000 -vn -0.109576 -0.656765 -0.746092 -v 0.095168 0.131000 0.005000 -vn -0.689401 0.285559 -0.665719 -v 0.050308 0.140281 0.005000 -vn 0.552290 -0.318862 -0.770262 -v 0.056050 0.136300 0.005000 -vn -0.724382 0.071345 -0.685697 -v 0.050003 0.138750 0.005000 -vn 0.637729 0.000000 -0.770261 -v 0.055836 0.135500 0.005000 -vn 0.552289 0.318862 -0.770262 -v 0.056050 0.134700 0.005000 -vn -0.351081 -0.537420 -0.766761 -v 0.096097 0.130681 0.005000 -vn -0.564557 -0.305538 -0.766760 -v 0.096762 0.129959 0.005000 -vn 0.678875 -0.095839 -0.727973 -v 0.053003 0.115353 0.005000 -vn -0.678874 -0.095839 -0.727973 -v 0.050003 0.115353 0.005000 -vn 0.671741 -0.083737 -0.736038 -v 0.053003 0.129007 0.005000 -vn 0.564558 -0.305538 -0.766760 -v 0.053244 0.129959 0.005000 -vn 0.351081 -0.537419 -0.766761 -v 0.053909 0.130681 0.005000 -vn 0.109575 -0.656765 -0.746092 -v 0.054838 0.131000 0.005000 -vn 0.318862 0.552288 -0.770263 -v 0.056636 0.134114 0.005000 -vn 0.000000 0.637730 -0.770260 -v 0.057436 0.133900 0.005000 -vn 0.396203 -0.686244 -0.609994 -v 0.060034 0.131000 0.005000 -vn 0.623737 0.258361 -0.737701 -v 0.061911 0.136750 0.005000 -vn 0.792406 0.000001 -0.609994 -v 0.062632 0.135500 0.005000 -vn -0.552289 0.318862 -0.770262 -v 0.058822 0.134700 0.005000 -vn -0.318862 0.552288 -0.770263 -v 0.058236 0.134114 0.005000 -vn -0.671742 -0.083736 -0.736038 -v 0.097003 0.129007 0.005000 -vn 0.678875 -0.095839 -0.727973 -v 0.100003 0.115353 0.005000 -vn -0.678874 -0.095839 -0.727973 -v 0.097003 0.115353 0.005000 -vn -0.527645 0.527646 -0.665719 -v 0.051175 0.141578 0.005000 -vn -0.285560 0.689400 -0.665720 -v 0.052472 0.142445 0.005000 -vn 0.318862 -0.552288 -0.770263 -v 0.056636 0.136886 0.005000 -vn -0.071347 0.724383 -0.685696 -v 0.054003 0.142750 0.005000 -vn 0.000000 -0.637730 -0.770260 -v 0.057436 0.137100 0.005000 -vn 0.318865 -0.552288 -0.770261 -v 0.062643 0.139482 0.005000 -vn 0.552289 -0.318864 -0.770262 -v 0.061911 0.138750 0.005000 -vn -0.552288 -0.318865 -0.770261 -v 0.088095 0.138750 0.005000 -vn -0.318865 -0.552288 -0.770261 -v 0.087363 0.139482 0.005000 -vn -0.088123 -0.669352 -0.737701 -v 0.086363 0.139750 0.005000 -vn 0.088123 -0.669352 -0.737701 -v 0.063643 0.139750 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.087128 0.087375 0.050000 -vn -0.000000 -0.707106 0.707107 -v 0.087128 0.072750 0.050000 -vn -0.000000 -0.707107 0.707107 -v 0.094878 0.072750 0.050000 -vn -0.671187 -0.053977 0.739320 -v 0.086964 0.091712 0.050000 -vn -0.660602 0.130425 0.739320 -v 0.086776 0.088426 0.050000 -vn -0.689401 -0.285559 0.665719 -v 0.050308 0.075219 0.050000 -vn -0.527646 -0.527644 0.665719 -v 0.051175 0.073922 0.050000 -vn -0.724382 -0.071346 0.685697 -v 0.050003 0.076750 0.050000 -vn -0.285560 -0.689401 0.665719 -v 0.052472 0.073054 0.050000 -vn -0.527645 0.527645 0.665719 -v 0.051175 0.141578 0.050000 -vn -0.689401 0.285559 0.665719 -v 0.050308 0.140281 0.050000 -vn -0.285560 0.689400 0.665720 -v 0.052472 0.142445 0.050000 -vn -0.724383 0.071346 0.685696 -v 0.050003 0.138750 0.050000 -vn -0.071347 0.724383 0.685696 -v 0.054003 0.142750 0.050000 -vn -0.707107 -0.000000 0.707107 -v 0.050003 0.123023 0.050000 -vn -0.000000 0.707107 0.707107 -v 0.062878 0.142750 0.050000 -vn 0.527645 0.527645 0.665719 -v 0.098831 0.141578 0.050000 -vn 0.285560 0.689400 0.665720 -v 0.097534 0.142445 0.050000 -vn 0.689401 0.285559 0.665719 -v 0.099699 0.140281 0.050000 -vn 0.071347 0.724383 0.685696 -v 0.096003 0.142750 0.050000 -vn 0.724383 0.071346 0.685696 -v 0.100003 0.138750 0.050000 -vn -0.000000 0.707107 0.707107 -v 0.094878 0.142750 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.100003 0.123023 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.094878 0.087375 0.050000 -vn 0.071346 -0.724383 0.685697 -v 0.096003 0.072750 0.050000 -vn 0.285560 -0.689401 0.665719 -v 0.097534 0.073054 0.050000 -vn 0.527646 -0.527644 0.665719 -v 0.098831 0.073922 0.050000 -vn -0.723161 -0.064427 0.687668 -v 0.086003 0.096318 0.050000 -vn -0.697695 -0.139813 0.702620 -v 0.086253 0.094926 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.087128 0.101250 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.087128 0.123023 0.050000 -vn -0.707107 -0.000000 0.707107 -v 0.086003 0.123023 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.087128 0.117250 0.050000 -vn -0.707107 -0.000000 0.707107 -v 0.086003 0.117250 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.087128 0.109250 0.050000 -vn -0.707107 -0.000000 0.707107 -v 0.086003 0.109250 0.050000 -vn -0.707107 -0.000000 0.707107 -v 0.086003 0.101250 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.062878 0.123023 0.050000 -vn 0.301511 -0.301511 0.904534 -v 0.064003 0.123546 0.050000 -vn -0.000000 0.707107 0.707107 -v 0.087128 0.142750 0.050000 -vn -0.301511 -0.301511 0.904534 -v 0.086003 0.123546 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.062878 0.087375 0.050000 -vn 0.671187 -0.053977 0.739320 -v 0.063042 0.091712 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.062878 0.101250 0.050000 -vn 0.697695 -0.139812 0.702619 -v 0.063753 0.094926 0.050000 -vn 0.723160 -0.064425 0.687669 -v 0.064003 0.096318 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.064003 0.101250 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.062878 0.109250 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.064003 0.109250 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.062878 0.117250 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.064003 0.117250 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.064003 0.123023 0.050000 -vn -0.494849 0.456651 0.739320 -v 0.083822 0.082612 0.050000 -vn -0.352154 0.573928 0.739320 -v 0.081279 0.080522 0.050000 -vn -0.600311 0.305013 0.739320 -v 0.085701 0.085314 0.050000 -vn -0.182960 0.648021 0.739321 -v 0.078264 0.079201 0.050000 -vn 0.000000 0.673354 0.739320 -v 0.075003 0.078750 0.050000 -vn -0.000000 -0.707107 0.707107 -v 0.062878 0.072750 0.050000 -vn 0.182960 0.648021 0.739321 -v 0.071742 0.079201 0.050000 -vn 0.352153 0.573929 0.739320 -v 0.068727 0.080522 0.050000 -vn 0.494848 0.456651 0.739321 -v 0.066184 0.082612 0.050000 -vn 0.600311 0.305013 0.739320 -v 0.064305 0.085314 0.050000 -vn 0.660602 0.130424 0.739320 -v 0.063230 0.088426 0.050000 -vn -0.318863 0.552289 0.770262 -v 0.062128 0.096167 0.050000 -vn -0.000000 0.637729 0.770261 -v 0.061503 0.096000 0.050000 -vn -0.707107 -0.000000 0.707106 -v 0.050003 0.087375 0.050000 -vn -0.071346 -0.724383 0.685696 -v 0.054003 0.072750 0.050000 -vn 0.637727 0.000000 0.770263 -v 0.060253 0.097250 0.050000 -vn -0.707107 -0.000000 0.707107 -v 0.050003 0.101250 0.050000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.096625 0.050000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.096167 0.050000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.097875 0.050000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.098332 0.050000 -vn -0.000000 -0.637728 0.770261 -v 0.061503 0.098500 0.050000 -vn -0.318863 -0.552289 0.770262 -v 0.062128 0.098332 0.050000 -vn -0.552289 -0.318863 0.770262 -v 0.062586 0.097875 0.050000 -vn -0.637728 -0.000000 0.770261 -v 0.062753 0.097250 0.050000 -vn -0.552289 0.318863 0.770262 -v 0.062586 0.096625 0.050000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.096000 0.050000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.096167 0.050000 -vn 0.552291 0.318866 0.770260 -v 0.087421 0.096625 0.050000 -vn 0.637725 0.000000 0.770264 -v 0.087253 0.097250 0.050000 -vn 0.552291 -0.318865 0.770260 -v 0.087421 0.097875 0.050000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.096167 0.050000 -vn 0.318864 -0.552286 0.770263 -v 0.087878 0.098332 0.050000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.098500 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.094878 0.101250 0.050000 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.098332 0.050000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.097875 0.050000 -vn -0.637725 -0.000000 0.770264 -v 0.089753 0.097250 0.050000 -vn -0.552291 0.318865 0.770260 -v 0.089586 0.096625 0.050000 -vn 0.637727 -0.000001 0.770262 -v 0.060253 0.105250 0.050000 -vn -0.707106 -0.000000 0.707107 -v 0.050003 0.109250 0.050000 -vn 0.552286 0.318866 0.770263 -v 0.060421 0.104625 0.050000 -vn 0.552286 -0.318867 0.770262 -v 0.060421 0.105875 0.050000 -vn 0.318866 -0.552291 0.770260 -v 0.060878 0.106332 0.050000 -vn -0.000000 -0.637725 0.770264 -v 0.061503 0.106500 0.050000 -vn -0.318866 -0.552291 0.770260 -v 0.062128 0.106332 0.050000 -vn -0.552286 0.318864 0.770263 -v 0.062586 0.104625 0.050000 -vn -0.637729 -0.000001 0.770261 -v 0.062753 0.105250 0.050000 -vn -0.552286 -0.318865 0.770263 -v 0.062586 0.105875 0.050000 -vn -0.318866 0.552291 0.770260 -v 0.062128 0.104167 0.050000 -vn -0.000000 0.637725 0.770264 -v 0.061503 0.104000 0.050000 -vn 0.318865 0.552291 0.770260 -v 0.060878 0.104167 0.050000 -vn 0.318866 -0.552288 0.770261 -v 0.087878 0.106332 0.050000 -vn -0.000001 -0.637726 0.770264 -v 0.088503 0.106500 0.050000 -vn 0.318866 0.552288 0.770261 -v 0.087878 0.104167 0.050000 -vn 0.552288 0.318866 0.770261 -v 0.087421 0.104625 0.050000 -vn 0.637725 -0.000001 0.770264 -v 0.087253 0.105250 0.050000 -vn 0.552288 -0.318867 0.770261 -v 0.087421 0.105875 0.050000 -vn -0.318867 -0.552288 0.770261 -v 0.089128 0.106332 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.094878 0.109250 0.050000 -vn -0.552288 -0.318867 0.770261 -v 0.089586 0.105875 0.050000 -vn -0.637726 -0.000001 0.770264 -v 0.089753 0.105250 0.050000 -vn -0.552288 0.318866 0.770261 -v 0.089586 0.104625 0.050000 -vn -0.318867 0.552288 0.770261 -v 0.089128 0.104167 0.050000 -vn -0.000001 0.637726 0.770264 -v 0.088503 0.104000 0.050000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.112625 0.050000 -vn -0.707107 -0.000000 0.707107 -v 0.050003 0.117250 0.050000 -vn 0.637727 0.000000 0.770263 -v 0.060253 0.113250 0.050000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.113875 0.050000 -vn 0.318867 -0.552288 0.770261 -v 0.060878 0.114332 0.050000 -vn -0.000000 -0.637725 0.770264 -v 0.061503 0.114500 0.050000 -vn -0.318867 -0.552288 0.770261 -v 0.062128 0.114332 0.050000 -vn -0.552289 0.318863 0.770262 -v 0.062586 0.112625 0.050000 -vn -0.637728 -0.000000 0.770261 -v 0.062753 0.113250 0.050000 -vn -0.552289 -0.318863 0.770262 -v 0.062586 0.113875 0.050000 -vn -0.318863 0.552289 0.770262 -v 0.062128 0.112167 0.050000 -vn -0.000000 0.637728 0.770261 -v 0.061503 0.112000 0.050000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.112167 0.050000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.112000 0.050000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.112167 0.050000 -vn 0.552291 0.318866 0.770260 -v 0.087421 0.112625 0.050000 -vn 0.637725 0.000000 0.770264 -v 0.087253 0.113250 0.050000 -vn 0.552291 -0.318865 0.770260 -v 0.087421 0.113875 0.050000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.112167 0.050000 -vn 0.318868 -0.552286 0.770262 -v 0.087878 0.114332 0.050000 -vn -0.000001 -0.637726 0.770264 -v 0.088503 0.114500 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.094878 0.117250 0.050000 -vn -0.318869 -0.552286 0.770262 -v 0.089128 0.114332 0.050000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.113875 0.050000 -vn -0.637725 -0.000000 0.770264 -v 0.089753 0.113250 0.050000 -vn -0.552291 0.318865 0.770260 -v 0.089586 0.112625 0.050000 -vn -0.318863 0.552289 0.770262 -v 0.062128 0.120167 0.050000 -vn -0.000000 0.637728 0.770261 -v 0.061503 0.120000 0.050000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.121875 0.050000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.122332 0.050000 -vn -0.000000 -0.637728 0.770261 -v 0.061503 0.122500 0.050000 -vn -0.318863 -0.552289 0.770262 -v 0.062128 0.122332 0.050000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.120167 0.050000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.120625 0.050000 -vn 0.637727 0.000000 0.770263 -v 0.060253 0.121250 0.050000 -vn -0.552289 -0.318863 0.770262 -v 0.062586 0.121875 0.050000 -vn -0.637729 -0.000000 0.770261 -v 0.062753 0.121250 0.050000 -vn -0.552289 0.318863 0.770262 -v 0.062586 0.120625 0.050000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.120167 0.050000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.120000 0.050000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.120167 0.050000 -vn 0.552291 0.318866 0.770260 -v 0.087421 0.120625 0.050000 -vn 0.637725 0.000000 0.770264 -v 0.087253 0.121250 0.050000 -vn 0.552291 -0.318865 0.770260 -v 0.087421 0.121875 0.050000 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.122332 0.050000 -vn -0.000000 -0.000000 1.000000 -v 0.094878 0.123023 0.050000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.122500 0.050000 -vn 0.318864 -0.552286 0.770263 -v 0.087878 0.122332 0.050000 -vn -0.552291 -0.318866 0.770260 -v 0.089586 0.121875 0.050000 -vn -0.637725 -0.000000 0.770264 -v 0.089753 0.121250 0.050000 -vn -0.552291 0.318865 0.770260 -v 0.089586 0.120625 0.050000 -vn 0.689401 -0.285559 0.665719 -v 0.099699 0.075219 0.050000 -vn 0.724382 -0.071346 0.685697 -v 0.100003 0.076750 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.100003 0.087375 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.100003 0.101250 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.100003 0.109250 0.050000 -vn 0.707107 0.000000 0.707107 -v 0.100003 0.117250 0.050000 -vn -0.678874 0.095840 -0.727973 -v 0.097003 0.100147 0.005000 -vn 0.678874 0.095840 -0.727973 -v 0.100003 0.100147 0.005000 -vn -0.671742 0.083736 -0.736038 -v 0.097003 0.086493 0.005000 -vn 0.724382 -0.071346 -0.685697 -v 0.100003 0.076750 0.005000 -vn -0.564556 0.305539 -0.766761 -v 0.096762 0.085541 0.005000 -vn -0.552287 -0.318863 -0.770263 -v 0.093956 0.080800 0.005000 -vn 0.000000 -0.637727 -0.770262 -v 0.092570 0.081600 0.005000 -vn -0.396203 0.686243 -0.609995 -v 0.089972 0.084500 0.005000 -vn -0.318863 -0.552290 -0.770261 -v 0.093370 0.081386 0.005000 -vn -0.109578 0.656763 -0.746093 -v 0.095168 0.084500 0.005000 -vn -0.351082 0.537421 -0.766759 -v 0.096097 0.084819 0.005000 -vn -0.623738 -0.258361 -0.737700 -v 0.088096 0.078750 0.005000 -vn -0.792406 0.000001 -0.609994 -v 0.087374 0.080000 0.005000 -vn 0.552287 -0.318863 -0.770263 -v 0.091184 0.080800 0.005000 -vn 0.318863 -0.552290 -0.770261 -v 0.091770 0.081386 0.005000 -vn 0.109577 0.656763 -0.746093 -v 0.054838 0.084500 0.005000 -vn 0.351082 0.537420 -0.766760 -v 0.053909 0.084819 0.005000 -vn 0.564557 0.305540 -0.766760 -v 0.053244 0.085541 0.005000 -vn 0.637730 -0.000001 -0.770260 -v 0.090970 0.080000 0.005000 -vn -0.552288 0.318865 -0.770261 -v 0.088096 0.076750 0.005000 -vn -0.637727 -0.000000 -0.770263 -v 0.088363 0.077750 0.005000 -vn -0.689401 -0.285559 -0.665719 -v 0.050308 0.075219 0.005000 -vn -0.724382 -0.071346 -0.685697 -v 0.050003 0.076750 0.005000 -vn -0.527646 -0.527644 -0.665719 -v 0.051175 0.073922 0.005000 -vn -0.285560 -0.689401 -0.665719 -v 0.052472 0.073054 0.005000 -vn -0.071345 -0.724382 -0.685697 -v 0.054003 0.072750 0.005000 -vn 0.671741 0.083737 -0.736038 -v 0.053003 0.086493 0.005000 -vn -0.678874 0.095840 -0.727973 -v 0.050003 0.100147 0.005000 -vn 0.678874 0.095840 -0.727973 -v 0.053003 0.100147 0.005000 -vn 0.689401 -0.285559 -0.665719 -v 0.099699 0.075219 0.005000 -vn -0.552287 0.318862 -0.770264 -v 0.093956 0.079200 0.005000 -vn -0.637730 -0.000001 -0.770260 -v 0.094170 0.080000 0.005000 -vn 0.552289 0.318864 -0.770262 -v 0.061911 0.076750 0.005000 -vn 0.318865 0.552288 -0.770261 -v 0.062643 0.076018 0.005000 -vn 0.637728 0.000000 -0.770262 -v 0.061643 0.077750 0.005000 -vn 0.623738 -0.258360 -0.737700 -v 0.061911 0.078750 0.005000 -vn 0.792406 0.000001 -0.609994 -v 0.062632 0.080000 0.005000 -vn 0.396203 0.686244 -0.609994 -v 0.060034 0.084500 0.005000 -vn 0.318863 0.552290 -0.770261 -v 0.091770 0.078614 0.005000 -vn -0.000000 0.637727 -0.770262 -v 0.092570 0.078400 0.005000 -vn 0.071346 -0.724382 -0.685697 -v 0.096003 0.072750 0.005000 -vn -0.318863 0.552290 -0.770261 -v 0.093370 0.078614 0.005000 -vn 0.285560 -0.689401 -0.665719 -v 0.097534 0.073054 0.005000 -vn 0.527646 -0.527644 -0.665719 -v 0.098831 0.073922 0.005000 -vn 0.088123 0.669352 -0.737701 -v 0.063643 0.075750 0.005000 -vn -0.088123 0.669352 -0.737701 -v 0.086363 0.075750 0.005000 -vn -0.318865 0.552288 -0.770261 -v 0.087363 0.076018 0.005000 -vn 0.552287 0.318862 -0.770264 -v 0.091184 0.079200 0.005000 -vn -0.753768 0.251477 -0.607119 -v 0.050003 0.105606 0.022368 -vn -0.753767 0.464669 -0.464669 -v 0.050003 0.103788 0.021154 -vn -0.753767 0.607119 -0.251477 -v 0.050003 0.102573 0.019336 -vn -0.753767 -0.464669 -0.464669 -v 0.050003 0.111712 0.021154 -vn -0.753767 -0.251477 -0.607120 -v 0.050003 0.109894 0.022368 -vn -0.753767 -0.000000 -0.657142 -v 0.050003 0.107750 0.022795 -vn -0.678874 0.727973 -0.095841 -v 0.050003 0.102147 0.007000 -vn -0.653227 0.655721 -0.378582 -v 0.050003 0.101879 0.006000 -vn -0.653227 0.378582 -0.655721 -v 0.050003 0.101147 0.005268 -vn -0.729849 0.680317 -0.067006 -v 0.050003 0.102147 0.017192 -vn -0.653227 -0.378581 -0.655722 -v 0.050003 0.114353 0.005268 -vn -0.653226 -0.655723 -0.378580 -v 0.050003 0.113621 0.006000 -vn -0.678875 -0.727973 -0.095838 -v 0.050003 0.113353 0.007000 -vn -0.729849 -0.680317 -0.067006 -v 0.050003 0.113353 0.017192 -vn -0.753767 -0.607119 -0.251477 -v 0.050003 0.112926 0.019336 -vn 0.753767 0.464670 -0.464669 -v 0.100003 0.103788 0.021154 -vn 0.753768 0.251477 -0.607119 -v 0.100003 0.105606 0.022368 -vn 0.753767 -0.000000 -0.657141 -v 0.100003 0.107750 0.022795 -vn 0.653227 0.378582 -0.655721 -v 0.100003 0.101147 0.005268 -vn 0.653227 0.655721 -0.378582 -v 0.100003 0.101879 0.006000 -vn 0.678874 0.727973 -0.095841 -v 0.100003 0.102147 0.007000 -vn 0.729849 0.680317 -0.067006 -v 0.100003 0.102147 0.017192 -vn 0.753767 0.607119 -0.251477 -v 0.100003 0.102573 0.019336 -vn 0.753767 -0.251477 -0.607119 -v 0.100003 0.109894 0.022368 -vn 0.653227 -0.655723 -0.378580 -v 0.100003 0.113621 0.006000 -vn 0.653227 -0.378581 -0.655722 -v 0.100003 0.114353 0.005268 -vn 0.678875 -0.727973 -0.095838 -v 0.100003 0.113353 0.007000 -vn 0.729849 -0.680317 -0.067006 -v 0.100003 0.113353 0.017192 -vn 0.753767 -0.607119 -0.251477 -v 0.100003 0.112926 0.019336 -vn 0.753767 -0.464669 -0.464669 -v 0.100003 0.111712 0.021154 -vn 0.065066 0.997001 0.041898 -v 0.063643 0.075750 0.011000 -vn -0.065066 0.997001 0.041898 -v 0.086363 0.075750 0.011000 -vn -0.071346 0.724383 -0.685696 -v 0.093003 0.075750 0.047000 -vn -0.071346 0.724383 0.685696 -v 0.093003 0.075750 0.011000 -vn 0.000000 0.707107 -0.707107 -v 0.087128 0.075750 0.047000 -vn 0.000000 0.707107 -0.707107 -v 0.062878 0.075750 0.047000 -vn -0.707107 -0.000000 -0.707107 -v 0.097003 0.087375 0.047000 -vn -0.707106 -0.000000 -0.707107 -v 0.097003 0.101250 0.047000 -vn -0.997307 -0.061680 0.039672 -v 0.097003 0.129007 0.011000 -vn -0.707106 -0.000000 -0.707108 -v 0.097003 0.109250 0.047000 -vn -0.997307 0.061680 0.039672 -v 0.097003 0.086493 0.011000 -vn -0.753768 0.251477 -0.607119 -v 0.097003 0.105606 0.022368 -vn -0.753767 0.464669 -0.464669 -v 0.097003 0.103788 0.021154 -vn -0.753767 -0.251477 -0.607120 -v 0.097003 0.109894 0.022368 -vn -0.753767 -0.464669 -0.464669 -v 0.097003 0.111712 0.021154 -vn -0.753767 -0.607119 -0.251477 -v 0.097003 0.112926 0.019336 -vn -0.729849 -0.680317 -0.067006 -v 0.097003 0.113353 0.017192 -vn -0.707107 -0.000000 -0.707107 -v 0.097003 0.123023 0.047000 -vn -0.707106 -0.000000 -0.707107 -v 0.097003 0.117250 0.047000 -vn -0.753767 0.607119 -0.251477 -v 0.097003 0.102573 0.019336 -vn -0.729849 0.680317 -0.067006 -v 0.097003 0.102147 0.017192 -vn -0.678874 0.727973 -0.095841 -v 0.097003 0.102147 0.007000 -vn -0.753767 -0.000000 -0.657142 -v 0.097003 0.107750 0.022795 -vn -0.724383 0.071346 -0.685696 -v 0.097003 0.079750 0.047000 -vn -0.724383 0.071346 0.685696 -v 0.097003 0.079750 0.011000 -vn -0.653227 0.378582 -0.655721 -v 0.097003 0.101147 0.005268 -vn -0.653227 0.655721 -0.378582 -v 0.097003 0.101879 0.006000 -vn -0.653227 -0.378581 -0.655722 -v 0.097003 0.114353 0.005268 -vn -0.653226 -0.655723 -0.378580 -v 0.097003 0.113621 0.006000 -vn -0.678875 -0.727973 -0.095838 -v 0.097003 0.113353 0.007000 -vn 0.065066 -0.997001 0.041899 -v 0.063643 0.139750 0.011000 -vn -0.065066 -0.997001 0.041899 -v 0.086363 0.139750 0.011000 -vn 0.000000 -0.707107 -0.707107 -v 0.087128 0.139750 0.047000 -vn 0.071344 -0.724382 0.685697 -v 0.057003 0.139750 0.011000 -vn 0.071344 -0.724382 -0.685697 -v 0.057003 0.139750 0.047000 -vn 0.000000 -0.707107 -0.707107 -v 0.062878 0.139750 0.047000 -vn 0.724383 -0.071346 0.685696 -v 0.053003 0.135750 0.011000 -vn 0.724383 -0.071346 -0.685696 -v 0.053003 0.135750 0.047000 -vn 0.997307 -0.061681 0.039673 -v 0.053003 0.129007 0.011000 -vn 0.707107 0.000000 -0.707107 -v 0.053003 0.123023 0.047000 -vn 0.707107 0.000000 -0.707107 -v 0.053003 0.117250 0.047000 -vn 0.678874 0.727973 -0.095841 -v 0.053003 0.102147 0.007000 -vn 0.729849 0.680317 -0.067006 -v 0.053003 0.102147 0.017192 -vn 0.997307 0.061681 0.039673 -v 0.053003 0.086493 0.011000 -vn 0.753767 0.607119 -0.251477 -v 0.053003 0.102573 0.019336 -vn 0.753767 0.464670 -0.464669 -v 0.053003 0.103788 0.021154 -vn 0.753768 0.251477 -0.607119 -v 0.053003 0.105606 0.022368 -vn 0.729849 -0.680317 -0.067006 -v 0.053003 0.113353 0.017192 -vn 0.678875 -0.727973 -0.095838 -v 0.053003 0.113353 0.007000 -vn 0.707107 0.000000 -0.707107 -v 0.053003 0.109250 0.047000 -vn 0.707107 0.000000 -0.707107 -v 0.053003 0.101250 0.047000 -vn 0.707107 0.000000 -0.707107 -v 0.053003 0.087375 0.047000 -vn 0.753767 -0.000000 -0.657141 -v 0.053003 0.107750 0.022795 -vn 0.753767 -0.251477 -0.607119 -v 0.053003 0.109894 0.022368 -vn 0.753767 -0.464669 -0.464669 -v 0.053003 0.111712 0.021154 -vn 0.753767 -0.607119 -0.251477 -v 0.053003 0.112926 0.019336 -vn 0.653227 -0.378581 -0.655722 -v 0.053003 0.114353 0.005268 -vn 0.653227 -0.655723 -0.378580 -v 0.053003 0.113621 0.006000 -vn 0.653227 0.378582 -0.655721 -v 0.053003 0.101147 0.005268 -vn 0.653227 0.655721 -0.378582 -v 0.053003 0.101879 0.006000 -vn -0.552291 0.318865 -0.770260 -v 0.089586 0.112625 0.047000 -vn -0.637725 -0.000000 -0.770264 -v 0.089753 0.113250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.087128 0.087375 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.062878 0.123023 0.047000 -vn 0.689401 -0.285560 -0.665719 -v 0.053308 0.137281 0.047000 -vn 0.527646 -0.527643 -0.665719 -v 0.054175 0.138578 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.056628 0.087375 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.062878 0.087375 0.047000 -vn -0.689401 0.285559 -0.665719 -v 0.096699 0.078219 0.047000 -vn -0.527646 0.527644 -0.665719 -v 0.095831 0.076922 0.047000 -vn -0.285560 0.689401 -0.665719 -v 0.094534 0.076054 0.047000 -vn -0.671187 -0.053977 -0.739320 -v 0.086964 0.091712 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.087128 0.101250 0.047000 -vn -0.697695 -0.139813 -0.702620 -v 0.086253 0.094926 0.047000 -vn -0.723161 -0.064427 -0.687668 -v 0.086003 0.096318 0.047000 -vn -0.707107 -0.000000 -0.707107 -v 0.086003 0.101250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.087128 0.109250 0.047000 -vn -0.707107 -0.000000 -0.707107 -v 0.086003 0.109250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.087128 0.117250 0.047000 -vn -0.707107 -0.000000 -0.707107 -v 0.086003 0.117250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.087128 0.123023 0.047000 -vn -0.707107 -0.000000 -0.707107 -v 0.086003 0.123023 0.047000 -vn -0.301511 -0.301511 -0.904534 -v 0.086003 0.123546 0.047000 -vn 0.494849 0.456651 -0.739320 -v 0.066184 0.082612 0.047000 -vn 0.352153 0.573929 -0.739320 -v 0.068727 0.080522 0.047000 -vn 0.182960 0.648021 -0.739321 -v 0.071742 0.079201 0.047000 -vn 0.000000 0.673354 -0.739320 -v 0.075003 0.078750 0.047000 -vn -0.182960 0.648021 -0.739321 -v 0.078264 0.079201 0.047000 -vn -0.352154 0.573928 -0.739320 -v 0.081279 0.080522 0.047000 -vn -0.494849 0.456651 -0.739320 -v 0.083822 0.082612 0.047000 -vn -0.600311 0.305013 -0.739320 -v 0.085701 0.085314 0.047000 -vn -0.660602 0.130425 -0.739320 -v 0.086776 0.088426 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.062878 0.101250 0.047000 -vn 0.671188 -0.053977 -0.739320 -v 0.063042 0.091712 0.047000 -vn 0.660602 0.130424 -0.739320 -v 0.063230 0.088426 0.047000 -vn 0.600311 0.305013 -0.739320 -v 0.064305 0.085314 0.047000 -vn 0.707107 0.000000 -0.707107 -v 0.064003 0.101250 0.047000 -vn 0.723161 -0.064425 -0.687669 -v 0.064003 0.096318 0.047000 -vn 0.697696 -0.139812 -0.702619 -v 0.063753 0.094926 0.047000 -vn 0.707107 0.000000 -0.707107 -v 0.064003 0.109250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.062878 0.109250 0.047000 -vn 0.707107 0.000000 -0.707107 -v 0.064003 0.117250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.062878 0.117250 0.047000 -vn 0.707107 0.000000 -0.707107 -v 0.064003 0.123023 0.047000 -vn 0.301511 -0.301511 -0.904534 -v 0.064003 0.123546 0.047000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.096167 0.047000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.096000 0.047000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.098500 0.047000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.098332 0.047000 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.098332 0.047000 -vn -0.552291 -0.318865 -0.770260 -v 0.089586 0.097875 0.047000 -vn 0.552291 -0.318865 -0.770260 -v 0.087421 0.097875 0.047000 -vn 0.637725 0.000000 -0.770264 -v 0.087253 0.097250 0.047000 -vn 0.552291 0.318865 -0.770260 -v 0.087421 0.096625 0.047000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.096167 0.047000 -vn -0.552291 0.318865 -0.770260 -v 0.089586 0.096625 0.047000 -vn -0.637725 -0.000000 -0.770264 -v 0.089753 0.097250 0.047000 -vn 0.552289 -0.318865 -0.770261 -v 0.060421 0.097875 0.047000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.097250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.056628 0.101250 0.047000 -vn -0.318863 -0.552289 -0.770262 -v 0.062128 0.098332 0.047000 -vn 0.000000 -0.637728 -0.770261 -v 0.061503 0.098500 0.047000 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.098332 0.047000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.096625 0.047000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.096167 0.047000 -vn 0.000000 0.637728 -0.770261 -v 0.061503 0.096000 0.047000 -vn -0.318863 0.552289 -0.770262 -v 0.062128 0.096167 0.047000 -vn -0.552289 0.318863 -0.770262 -v 0.062586 0.096625 0.047000 -vn -0.637728 -0.000000 -0.770261 -v 0.062753 0.097250 0.047000 -vn -0.552289 -0.318863 -0.770262 -v 0.062586 0.097875 0.047000 -vn -0.637726 -0.000001 -0.770264 -v 0.089753 0.105250 0.047000 -vn -0.552288 0.318866 -0.770261 -v 0.089586 0.104625 0.047000 -vn -0.552288 -0.318867 -0.770261 -v 0.089586 0.105875 0.047000 -vn -0.318867 -0.552288 -0.770261 -v 0.089128 0.106332 0.047000 -vn -0.000001 -0.637726 -0.770264 -v 0.088503 0.106500 0.047000 -vn 0.318866 -0.552288 -0.770261 -v 0.087878 0.106332 0.047000 -vn 0.552288 0.318866 -0.770261 -v 0.087421 0.104625 0.047000 -vn 0.637725 -0.000001 -0.770264 -v 0.087253 0.105250 0.047000 -vn 0.552288 -0.318867 -0.770261 -v 0.087421 0.105875 0.047000 -vn 0.318866 0.552288 -0.770261 -v 0.087878 0.104167 0.047000 -vn -0.000001 0.637725 -0.770264 -v 0.088503 0.104000 0.047000 -vn -0.318867 0.552288 -0.770261 -v 0.089128 0.104167 0.047000 -vn -0.318865 0.552291 -0.770260 -v 0.062128 0.104167 0.047000 -vn -0.552286 0.318864 -0.770264 -v 0.062586 0.104625 0.047000 -vn -0.637729 -0.000001 -0.770261 -v 0.062753 0.105250 0.047000 -vn -0.552286 -0.318865 -0.770263 -v 0.062586 0.105875 0.047000 -vn 0.552286 -0.318867 -0.770262 -v 0.060421 0.105875 0.047000 -vn 0.637727 -0.000001 -0.770262 -v 0.060253 0.105250 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.056628 0.109250 0.047000 -vn -0.318865 -0.552291 -0.770260 -v 0.062128 0.106332 0.047000 -vn 0.000000 -0.637725 -0.770264 -v 0.061503 0.106500 0.047000 -vn 0.318866 -0.552291 -0.770260 -v 0.060878 0.106332 0.047000 -vn 0.552286 0.318866 -0.770263 -v 0.060421 0.104625 0.047000 -vn 0.318866 0.552291 -0.770260 -v 0.060878 0.104167 0.047000 -vn -0.000000 0.637725 -0.770264 -v 0.061503 0.104000 0.047000 -vn -0.552291 -0.318865 -0.770260 -v 0.089586 0.113875 0.047000 -vn -0.318869 -0.552286 -0.770262 -v 0.089128 0.114332 0.047000 -vn -0.000001 -0.637726 -0.770264 -v 0.088503 0.114500 0.047000 -vn 0.318868 -0.552286 -0.770262 -v 0.087878 0.114332 0.047000 -vn 0.552291 0.318865 -0.770260 -v 0.087421 0.112625 0.047000 -vn 0.637725 0.000000 -0.770264 -v 0.087253 0.113250 0.047000 -vn 0.552291 -0.318865 -0.770260 -v 0.087421 0.113875 0.047000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.112167 0.047000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.112000 0.047000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.112167 0.047000 -vn -0.552289 -0.318863 -0.770262 -v 0.062586 0.113875 0.047000 -vn -0.637728 -0.000000 -0.770261 -v 0.062753 0.113250 0.047000 -vn -0.552289 0.318863 -0.770262 -v 0.062586 0.112625 0.047000 -vn -0.318863 0.552289 -0.770262 -v 0.062128 0.112167 0.047000 -vn -0.318867 -0.552288 -0.770261 -v 0.062128 0.114332 0.047000 -vn 0.000000 -0.637725 -0.770264 -v 0.061503 0.114500 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.056628 0.117250 0.047000 -vn 0.318867 -0.552288 -0.770261 -v 0.060878 0.114332 0.047000 -vn 0.552289 -0.318865 -0.770261 -v 0.060421 0.113875 0.047000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.113250 0.047000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.112625 0.047000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.112167 0.047000 -vn 0.000000 0.637728 -0.770261 -v 0.061503 0.112000 0.047000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.122500 0.047000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.122332 0.047000 -vn -0.552291 0.318865 -0.770260 -v 0.089586 0.120625 0.047000 -vn -0.637725 -0.000000 -0.770264 -v 0.089753 0.121250 0.047000 -vn -0.552291 -0.318865 -0.770260 -v 0.089586 0.121875 0.047000 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.122332 0.047000 -vn 0.552291 0.318865 -0.770260 -v 0.087421 0.120625 0.047000 -vn 0.637725 0.000000 -0.770264 -v 0.087253 0.121250 0.047000 -vn 0.552291 -0.318865 -0.770260 -v 0.087421 0.121875 0.047000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.120167 0.047000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.120000 0.047000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.120167 0.047000 -vn -0.318863 -0.552289 -0.770262 -v 0.062128 0.122332 0.047000 -vn 0.000000 -0.637729 -0.770261 -v 0.061503 0.122500 0.047000 -vn 0.000000 0.000000 -1.000000 -v 0.056628 0.123023 0.047000 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.122332 0.047000 -vn -0.318863 0.552289 -0.770262 -v 0.062128 0.120167 0.047000 -vn -0.552289 0.318863 -0.770262 -v 0.062586 0.120625 0.047000 -vn -0.637729 -0.000000 -0.770261 -v 0.062753 0.121250 0.047000 -vn -0.552289 -0.318863 -0.770262 -v 0.062586 0.121875 0.047000 -vn 0.552289 -0.318865 -0.770261 -v 0.060421 0.121875 0.047000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.121250 0.047000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.120625 0.047000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.120167 0.047000 -vn 0.000000 0.637728 -0.770261 -v 0.061503 0.120000 0.047000 -vn 0.285560 -0.689402 -0.665718 -v 0.055472 0.139445 0.047000 -vn 0.285560 -0.689402 0.665718 -v 0.055472 0.139445 0.011000 -vn 0.527646 -0.527643 0.665719 -v 0.054175 0.138578 0.011000 -vn 0.689401 -0.285559 0.665719 -v 0.053308 0.137281 0.011000 -vn -0.285560 0.689401 0.665719 -v 0.094534 0.076054 0.011000 -vn -0.527646 0.527644 0.665719 -v 0.095831 0.076922 0.011000 -vn -0.689401 0.285559 0.665719 -v 0.096699 0.078219 0.011000 -vn 0.623738 -0.258360 0.737700 -v 0.061911 0.078750 0.011000 -vn 0.792406 0.000001 0.609994 -v 0.062632 0.080000 0.011000 -vn 0.396203 0.686244 0.609994 -v 0.060034 0.084500 0.011000 -vn 0.109577 0.656764 0.746093 -v 0.054838 0.084500 0.011000 -vn 0.564557 0.305540 0.766760 -v 0.053244 0.085541 0.011000 -vn 0.272352 -0.471728 0.838628 -v 0.055617 0.083150 0.011000 -vn 0.544705 -0.000000 0.838628 -v 0.053799 0.080000 0.011000 -vn 0.272352 0.471728 0.838628 -v 0.055617 0.076850 0.011000 -vn -0.272353 0.471729 0.838627 -v 0.059255 0.076850 0.011000 -vn 0.318865 0.552288 0.770261 -v 0.062643 0.076018 0.011000 -vn 0.552289 0.318864 0.770262 -v 0.061911 0.076750 0.011000 -vn 0.637728 0.000000 0.770262 -v 0.061643 0.077750 0.011000 -vn -0.544705 -0.000000 0.838628 -v 0.061073 0.080000 0.011000 -vn -0.272352 -0.471728 0.838628 -v 0.059255 0.083150 0.011000 -vn 0.351082 0.537420 0.766760 -v 0.053909 0.084819 0.011000 -vn 0.396203 -0.686244 0.609994 -v 0.060034 0.131000 0.011000 -vn 0.109575 -0.656765 0.746092 -v 0.054838 0.131000 0.011000 -vn 0.792406 0.000001 0.609994 -v 0.062632 0.135500 0.011000 -vn 0.623737 0.258361 0.737701 -v 0.061911 0.136750 0.011000 -vn 0.272352 -0.471728 0.838628 -v 0.055617 0.138650 0.011000 -vn -0.272353 -0.471729 0.838628 -v 0.059255 0.138650 0.011000 -vn 0.564558 -0.305539 0.766760 -v 0.053244 0.129959 0.011000 -vn 0.544705 0.000000 0.838628 -v 0.053799 0.135500 0.011000 -vn 0.552288 -0.318864 0.770262 -v 0.061911 0.138750 0.011000 -vn 0.318865 -0.552288 0.770262 -v 0.062643 0.139482 0.011000 -vn 0.272352 0.471728 0.838628 -v 0.055617 0.132350 0.011000 -vn -0.272353 0.471728 0.838628 -v 0.059255 0.132350 0.011000 -vn -0.544705 -0.000000 0.838628 -v 0.061073 0.135500 0.011000 -vn 0.351081 -0.537419 0.766761 -v 0.053909 0.130681 0.011000 -vn 0.637728 0.000000 0.770262 -v 0.061643 0.137750 0.011000 -vn -0.637729 -0.000000 0.770261 -v 0.059036 0.135500 0.008000 -vn -0.552290 0.318862 0.770262 -v 0.058822 0.134700 0.008000 -vn -0.318862 0.552288 0.770263 -v 0.058236 0.134114 0.008000 -vn 0.000000 0.637730 0.770260 -v 0.057436 0.133900 0.008000 -vn 0.318862 0.552288 0.770263 -v 0.056636 0.134114 0.008000 -vn 0.552289 0.318862 0.770262 -v 0.056050 0.134700 0.008000 -vn 0.637729 0.000000 0.770261 -v 0.055836 0.135500 0.008000 -vn 0.552289 -0.318862 0.770262 -v 0.056050 0.136300 0.008000 -vn 0.318862 -0.552288 0.770263 -v 0.056636 0.136886 0.008000 -vn 0.000000 -0.637730 0.770260 -v 0.057436 0.137100 0.008000 -vn -0.318862 -0.552288 0.770263 -v 0.058236 0.136886 0.008000 -vn -0.552290 -0.318862 0.770262 -v 0.058822 0.136300 0.008000 -vn -0.623737 0.258362 0.737700 -v 0.088095 0.136750 0.011000 -vn -0.792406 0.000001 0.609994 -v 0.087374 0.135500 0.011000 -vn -0.396203 -0.686244 0.609994 -v 0.089972 0.131000 0.011000 -vn -0.109576 -0.656765 0.746092 -v 0.095168 0.131000 0.011000 -vn -0.564558 -0.305538 0.766760 -v 0.096762 0.129959 0.011000 -vn -0.272353 -0.471728 0.838628 -v 0.094389 0.138650 0.011000 -vn -0.318865 -0.552288 0.770262 -v 0.087363 0.139482 0.011000 -vn -0.552288 -0.318865 0.770261 -v 0.088095 0.138750 0.011000 -vn 0.272353 -0.471728 0.838628 -v 0.090751 0.138650 0.011000 -vn -0.637727 -0.000000 0.770262 -v 0.088363 0.137750 0.011000 -vn 0.544705 0.000000 0.838628 -v 0.088933 0.135500 0.011000 -vn -0.272353 0.471728 0.838628 -v 0.094389 0.132350 0.011000 -vn -0.544705 -0.000000 0.838628 -v 0.096207 0.135500 0.011000 -vn 0.272352 0.471728 0.838628 -v 0.090751 0.132350 0.011000 -vn -0.351081 -0.537420 0.766761 -v 0.096097 0.130681 0.011000 -vn -0.396203 0.686244 0.609994 -v 0.089972 0.084500 0.011000 -vn -0.109578 0.656763 0.746093 -v 0.095168 0.084500 0.011000 -vn -0.792406 0.000001 0.609994 -v 0.087374 0.080000 0.011000 -vn -0.623738 -0.258361 0.737700 -v 0.088096 0.078750 0.011000 -vn -0.552289 0.318865 0.770261 -v 0.088096 0.076750 0.011000 -vn -0.318865 0.552288 0.770261 -v 0.087363 0.076018 0.011000 -vn 0.272353 0.471728 0.838628 -v 0.090751 0.076850 0.011000 -vn -0.272352 -0.471728 0.838628 -v 0.094389 0.083150 0.011000 -vn 0.272352 -0.471728 0.838628 -v 0.090751 0.083150 0.011000 -vn 0.544705 -0.000000 0.838628 -v 0.088933 0.080000 0.011000 -vn -0.564556 0.305539 0.766761 -v 0.096762 0.085541 0.011000 -vn -0.637727 -0.000000 0.770262 -v 0.088363 0.077750 0.011000 -vn -0.544705 -0.000000 0.838628 -v 0.096207 0.080000 0.011000 -vn -0.351082 0.537421 0.766759 -v 0.096097 0.084819 0.011000 -vn -0.272353 0.471728 0.838628 -v 0.094389 0.076850 0.011000 -vn -0.637730 -0.000001 0.770260 -v 0.094170 0.080000 0.008000 -vn -0.552287 0.318862 0.770264 -v 0.093956 0.079200 0.008000 -vn -0.318863 0.552290 0.770261 -v 0.093370 0.078614 0.008000 -vn -0.000000 0.637727 0.770262 -v 0.092570 0.078400 0.008000 -vn 0.318863 0.552290 0.770261 -v 0.091770 0.078614 0.008000 -vn 0.552287 0.318862 0.770264 -v 0.091184 0.079200 0.008000 -vn 0.637730 -0.000001 0.770260 -v 0.090970 0.080000 0.008000 -vn 0.552287 -0.318863 0.770263 -v 0.091184 0.080800 0.008000 -vn 0.318863 -0.552290 0.770261 -v 0.091770 0.081386 0.008000 -vn -0.000000 -0.637727 0.770262 -v 0.092570 0.081600 0.008000 -vn -0.318863 -0.552290 0.770261 -v 0.093370 0.081386 0.008000 -vn -0.552287 -0.318863 0.770263 -v 0.093956 0.080800 0.008000 -vn 0.396203 -0.686244 0.609994 -v 0.090751 0.083150 0.008000 -vn 0.792406 -0.000000 0.609994 -v 0.088933 0.080000 0.008000 -vn -0.396203 -0.686244 0.609994 -v 0.094389 0.083150 0.008000 -vn -0.396203 0.686243 0.609994 -v 0.094389 0.076850 0.008000 -vn -0.792406 -0.000000 0.609994 -v 0.096207 0.080000 0.008000 -vn 0.396203 0.686243 0.609994 -v 0.090751 0.076850 0.008000 -vn 0.396203 -0.686243 0.609994 -v 0.090751 0.138650 0.008000 -vn 0.792406 -0.000000 0.609995 -v 0.088933 0.135500 0.008000 -vn -0.396203 -0.686243 0.609994 -v 0.094389 0.138650 0.008000 -vn -0.792406 0.000000 0.609995 -v 0.096207 0.135500 0.008000 -vn -0.396203 0.686244 0.609994 -v 0.094389 0.132350 0.008000 -vn 0.396203 0.686243 0.609994 -v 0.090751 0.132350 0.008000 -vn 0.396203 -0.686244 0.609994 -v 0.055617 0.138650 0.008000 -vn 0.792406 0.000000 0.609994 -v 0.053799 0.135500 0.008000 -vn -0.396203 -0.686244 0.609994 -v 0.059255 0.138650 0.008000 -vn -0.792406 -0.000000 0.609994 -v 0.061073 0.135500 0.008000 -vn -0.396203 0.686244 0.609994 -v 0.059255 0.132350 0.008000 -vn 0.396203 0.686244 0.609994 -v 0.055617 0.132350 0.008000 -vn 0.792406 -0.000000 0.609994 -v 0.053799 0.080000 0.008000 -vn 0.396203 -0.686244 0.609994 -v 0.055617 0.083150 0.008000 -vn -0.396203 -0.686244 0.609994 -v 0.059255 0.083150 0.008000 -vn -0.792406 -0.000000 0.609994 -v 0.061073 0.080000 0.008000 -vn -0.396203 0.686244 0.609994 -v 0.059255 0.076850 0.008000 -vn 0.396203 0.686244 0.609994 -v 0.055617 0.076850 0.008000 -# 686 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 1//1 -f 1//1 24//24 2//2 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 25//25 -f 25//25 48//48 26//26 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 69//69 70//70 71//71 -f 72//72 73//73 74//74 -f 75//75 69//69 48//48 -f 48//48 69//69 71//71 -f 48//48 71//71 26//26 -f 26//26 71//71 76//76 -f 72//72 74//74 77//77 -f 42//42 40//40 78//78 -f 78//78 40//40 79//79 -f 79//79 40//40 38//38 -f 79//79 38//38 80//80 -f 80//80 38//38 36//36 -f 80//80 36//36 81//81 -f 81//81 36//36 34//34 -f 81//81 34//34 82//82 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 34//34 32//32 82//82 -f 82//82 32//32 30//30 -f 82//82 30//30 88//88 -f 88//88 30//30 28//28 -f 88//88 28//28 89//89 -f 48//48 46//46 75//75 -f 75//75 46//46 44//44 -f 75//75 44//44 42//42 -f 90//90 91//91 92//92 -f 92//92 91//91 85//85 -f 92//92 85//85 93//93 -f 93//93 85//85 87//87 -f 93//93 87//87 94//94 -f 94//94 87//87 95//95 -f 87//87 96//96 95//95 -f 95//95 96//96 97//97 -f 95//95 97//97 98//98 -f 74//74 99//99 77//77 -f 77//77 99//99 100//100 -f 77//77 100//100 101//101 -f 101//101 100//100 98//98 -f 101//101 98//98 102//102 -f 102//102 98//98 97//97 -f 28//28 26//26 89//89 -f 89//89 26//26 76//76 -f 89//89 76//76 103//103 -f 103//103 76//76 104//104 -f 103//103 104//104 105//105 -f 83//83 106//106 84//84 -f 84//84 106//106 107//107 -f 84//84 107//107 108//108 -f 108//108 107//107 109//109 -f 108//108 109//109 110//110 -f 110//110 109//109 111//111 -f 110//110 111//111 73//73 -f 73//73 111//111 112//112 -f 73//73 112//112 74//74 -f 78//78 113//113 42//42 -f 42//42 113//113 114//114 -f 42//42 114//114 75//75 -f 75//75 114//114 115//115 -f 75//75 115//115 109//109 -f 109//109 115//115 116//116 -f 109//109 116//116 111//111 -f 117//117 118//118 119//119 -f 120//120 121//121 117//117 -f 122//122 123//123 124//124 -f 124//124 123//123 125//125 -f 126//126 127//127 128//128 -f 128//128 127//127 129//129 -f 128//128 129//129 130//130 -f 130//130 129//129 131//131 -f 130//130 131//131 132//132 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 140//140 119//119 141//141 -f 141//141 142//142 143//143 -f 144//144 145//145 146//146 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 151//151 -f 151//151 150//150 152//152 -f 151//151 152//152 146//146 -f 146//146 152//152 153//153 -f 146//146 153//153 144//144 -f 131//131 154//154 132//132 -f 132//132 154//154 155//155 -f 132//132 155//155 156//156 -f 156//156 155//155 157//157 -f 158//158 159//159 160//160 -f 160//160 159//159 161//161 -f 161//161 162//162 160//160 -f 160//160 162//162 163//163 -f 160//160 163//163 164//164 -f 164//164 163//163 165//165 -f 164//164 165//165 166//166 -f 166//166 165//165 167//167 -f 166//166 167//167 154//154 -f 154//154 167//167 168//168 -f 154//154 168//168 155//155 -f 169//169 170//170 118//118 -f 117//117 121//121 118//118 -f 118//118 121//121 171//171 -f 118//118 171//171 169//169 -f 170//170 172//172 118//118 -f 118//118 172//172 173//173 -f 118//118 173//173 174//174 -f 174//174 173//173 175//175 -f 174//174 175//175 176//176 -f 176//176 177//177 174//174 -f 174//174 177//177 178//178 -f 174//174 178//178 158//158 -f 158//158 178//178 179//179 -f 158//158 179//179 159//159 -f 180//180 181//181 158//158 -f 158//158 181//181 182//182 -f 158//158 182//182 174//174 -f 174//174 182//182 124//124 -f 174//174 124//124 183//183 -f 183//183 124//124 125//125 -f 184//184 185//185 186//186 -f 186//186 185//185 182//182 -f 186//186 182//182 187//187 -f 187//187 182//182 181//181 -f 184//184 188//188 185//185 -f 185//185 188//188 189//189 -f 185//185 189//189 160//160 -f 160//160 189//189 190//190 -f 160//160 190//190 191//191 -f 191//191 192//192 160//160 -f 160//160 192//192 193//193 -f 160//160 193//193 158//158 -f 158//158 193//193 194//194 -f 158//158 194//194 180//180 -f 195//195 196//196 117//117 -f 117//117 196//196 197//197 -f 146//146 198//198 199//199 -f 145//145 120//120 146//146 -f 146//146 120//120 117//117 -f 146//146 117//117 198//198 -f 198//198 117//117 197//197 -f 119//119 140//140 117//117 -f 117//117 140//140 200//200 -f 117//117 200//200 195//195 -f 199//199 201//201 146//146 -f 146//146 201//201 202//202 -f 146//146 202//202 203//203 -f 203//203 202//202 204//204 -f 204//204 205//205 203//203 -f 203//203 205//205 206//206 -f 203//203 206//206 140//140 -f 140//140 206//206 207//207 -f 140//140 207//207 200//200 -f 208//208 209//209 210//210 -f 210//210 209//209 185//185 -f 208//208 211//211 209//209 -f 209//209 211//211 212//212 -f 209//209 212//212 164//164 -f 164//164 212//212 213//213 -f 164//164 213//213 214//214 -f 215//215 160//160 216//216 -f 216//216 160//160 164//164 -f 216//216 164//164 217//217 -f 217//217 164//164 214//214 -f 215//215 218//218 160//160 -f 160//160 218//218 219//219 -f 160//160 219//219 185//185 -f 185//185 219//219 220//220 -f 185//185 220//220 210//210 -f 221//221 222//222 151//151 -f 223//223 224//224 146//146 -f 146//146 224//224 225//225 -f 146//146 225//225 151//151 -f 151//151 225//225 226//226 -f 151//151 226//226 221//221 -f 222//222 227//227 228//228 -f 227//227 229//229 228//228 -f 228//228 229//229 230//230 -f 228//228 230//230 203//203 -f 230//230 231//231 203//203 -f 203//203 231//231 232//232 -f 203//203 232//232 146//146 -f 146//146 232//232 233//233 -f 146//146 233//233 223//223 -f 209//209 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 237//237 -f 238//238 239//239 166//166 -f 166//166 239//239 240//240 -f 241//241 164//164 242//242 -f 242//242 164//164 166//166 -f 242//242 166//166 243//243 -f 243//243 166//166 240//240 -f 241//241 244//244 164//164 -f 164//164 244//244 245//245 -f 164//164 245//245 209//209 -f 209//209 245//245 246//246 -f 209//209 246//246 234//234 -f 151//151 247//247 248//248 -f 248//248 249//249 151//151 -f 151//151 249//249 250//250 -f 151//151 250//250 149//149 -f 149//149 250//250 251//251 -f 222//222 228//228 151//151 -f 151//151 228//228 252//252 -f 151//151 252//252 247//247 -f 251//251 253//253 149//149 -f 149//149 253//253 254//254 -f 149//149 254//254 255//255 -f 255//255 254//254 256//256 -f 256//256 257//257 255//255 -f 255//255 257//257 258//258 -f 255//255 258//258 228//228 -f 228//228 258//258 259//259 -f 228//228 259//259 252//252 -f 260//260 261//261 166//166 -f 166//166 261//261 235//235 -f 166//166 235//235 238//238 -f 238//238 235//235 237//237 -f 262//262 263//263 131//131 -f 131//131 263//263 264//264 -f 131//131 264//264 154//154 -f 154//154 264//264 265//265 -f 261//261 266//266 235//235 -f 235//235 266//266 267//267 -f 235//235 267//267 131//131 -f 131//131 267//267 268//268 -f 131//131 268//268 262//262 -f 265//265 269//269 154//154 -f 154//154 269//269 270//270 -f 154//154 270//270 166//166 -f 166//166 270//270 271//271 -f 166//166 271//271 260//260 -f 255//255 272//272 149//149 -f 149//149 272//272 273//273 -f 149//149 273//273 274//274 -f 274//274 275//275 149//149 -f 149//149 275//275 276//276 -f 149//149 276//276 147//147 -f 147//147 276//276 277//277 -f 278//278 279//279 280//280 -f 280//280 279//279 147//147 -f 280//280 147//147 281//281 -f 281//281 147//147 277//277 -f 278//278 282//282 279//279 -f 279//279 282//282 283//283 -f 279//279 283//283 255//255 -f 255//255 283//283 284//284 -f 255//255 284//284 272//272 -f 143//143 285//285 141//141 -f 141//141 285//285 286//286 -f 141//141 286//286 140//140 -f 140//140 286//286 287//287 -f 140//140 287//287 203//203 -f 203//203 287//287 288//288 -f 203//203 288//288 228//228 -f 228//228 288//288 289//289 -f 228//228 289//289 255//255 -f 255//255 289//289 290//290 -f 255//255 290//290 279//279 -f 279//279 290//290 139//139 -f 139//139 138//138 279//279 -f 279//279 138//138 156//156 -f 279//279 156//156 147//147 -f 147//147 156//156 157//157 -f 147//147 157//157 148//148 -f 291//291 292//292 293//293 -f 293//293 292//292 294//294 -f 293//293 294//294 295//295 -f 295//295 294//294 296//296 -f 297//297 298//298 299//299 -f 299//299 298//298 300//300 -f 299//299 300//300 296//296 -f 296//296 300//300 301//301 -f 296//296 301//301 295//295 -f 302//302 303//303 304//304 -f 304//304 303//303 298//298 -f 304//304 298//298 305//305 -f 305//305 298//298 297//297 -f 306//306 18//18 307//307 -f 307//307 18//18 16//16 -f 307//307 16//16 308//308 -f 309//309 310//310 304//304 -f 304//304 310//310 311//311 -f 304//304 311//311 302//302 -f 12//12 312//312 14//14 -f 14//14 312//312 313//313 -f 314//314 312//312 315//315 -f 315//315 312//312 12//12 -f 315//315 12//12 316//316 -f 316//316 12//12 10//10 -f 16//16 14//14 308//308 -f 308//308 14//14 313//313 -f 308//308 313//313 317//317 -f 317//317 313//313 318//318 -f 317//317 318//318 319//319 -f 320//320 321//321 294//294 -f 294//294 321//321 322//322 -f 294//294 322//322 296//296 -f 323//323 324//324 6//6 -f 6//6 324//324 316//316 -f 6//6 316//316 8//8 -f 8//8 316//316 10//10 -f 323//323 6//6 325//325 -f 325//325 6//6 4//4 -f 325//325 4//4 326//326 -f 326//326 4//4 2//2 -f 326//326 2//2 327//327 -f 327//327 2//2 24//24 -f 327//327 24//24 328//328 -f 328//328 24//24 22//22 -f 328//328 22//22 306//306 -f 306//306 22//22 20//20 -f 306//306 20//20 18//18 -f 329//329 330//330 331//331 -f 331//331 330//330 332//332 -f 331//331 332//332 333//333 -f 333//333 332//332 321//321 -f 333//333 321//321 334//334 -f 334//334 321//321 320//320 -f 324//324 335//335 316//316 -f 316//316 335//335 336//336 -f 316//316 336//336 331//331 -f 331//331 336//336 337//337 -f 331//331 337//337 329//329 -f 329//329 337//337 310//310 -f 329//329 310//310 338//338 -f 338//338 310//310 309//309 -f 339//339 340//340 124//124 -f 124//124 340//340 341//341 -f 124//124 341//341 313//313 -f 129//129 342//342 131//131 -f 131//131 342//342 343//343 -f 131//131 343//343 235//235 -f 235//235 343//343 344//344 -f 345//345 346//346 347//347 -f 124//124 182//182 339//339 -f 339//339 182//182 185//185 -f 339//339 185//185 344//344 -f 344//344 185//185 209//209 -f 344//344 209//209 235//235 -f 341//341 348//348 313//313 -f 313//313 348//348 345//345 -f 313//313 345//345 318//318 -f 318//318 345//345 347//347 -f 349//349 350//350 91//91 -f 91//91 350//350 351//351 -f 91//91 351//351 85//85 -f 85//85 351//351 352//352 -f 85//85 352//352 129//129 -f 129//129 352//352 353//353 -f 129//129 353//353 342//342 -f 331//331 141//141 119//119 -f 183//183 316//316 174//174 -f 174//174 316//316 331//331 -f 174//174 331//331 118//118 -f 118//118 331//331 119//119 -f 286//286 354//354 287//287 -f 287//287 354//354 355//355 -f 287//287 355//355 288//288 -f 288//288 355//355 356//356 -f 357//357 358//358 292//292 -f 292//292 358//358 359//359 -f 292//292 359//359 294//294 -f 294//294 359//359 360//360 -f 294//294 360//360 286//286 -f 286//286 360//360 361//361 -f 286//286 361//361 354//354 -f 137//137 139//139 362//362 -f 362//362 139//139 290//290 -f 362//362 290//290 356//356 -f 356//356 290//290 289//289 -f 356//356 289//289 288//288 -f 363//363 364//364 365//365 -f 365//365 364//364 104//104 -f 365//365 104//104 366//366 -f 366//366 104//104 76//76 -f 366//366 76//76 367//367 -f 367//367 76//76 137//137 -f 367//367 137//137 368//368 -f 368//368 137//137 362//362 -f 138//138 136//136 75//75 -f 109//109 130//130 132//132 -f 109//109 132//132 75//75 -f 75//75 132//132 156//156 -f 75//75 156//156 138//138 -f 67//67 68//68 369//369 -f 369//369 68//68 370//370 -f 369//369 370//370 335//335 -f 335//335 370//370 336//336 -f 371//371 372//372 373//373 -f 373//373 372//372 370//370 -f 373//373 370//370 374//374 -f 374//374 370//370 68//68 -f 375//375 376//376 377//377 -f 377//377 376//376 378//378 -f 379//379 380//380 381//381 -f 382//382 375//375 383//383 -f 383//383 375//375 377//377 -f 383//383 377//377 384//384 -f 384//384 377//377 385//385 -f 50//50 49//49 386//386 -f 386//386 49//49 377//377 -f 386//386 377//377 387//387 -f 387//387 377//377 378//378 -f 381//381 388//388 379//379 -f 379//379 388//388 389//389 -f 379//379 389//389 390//390 -f 382//382 391//391 375//375 -f 375//375 391//391 380//380 -f 375//375 380//380 392//392 -f 392//392 380//380 379//379 -f 392//392 379//379 393//393 -f 293//293 379//379 291//291 -f 291//291 379//379 390//390 -f 291//291 390//390 394//394 -f 394//394 390//390 395//395 -f 105//105 396//396 397//397 -f 377//377 103//103 385//385 -f 385//385 103//103 105//105 -f 385//385 105//105 398//398 -f 398//398 105//105 397//397 -f 116//116 115//115 399//399 -f 399//399 115//115 400//400 -f 57//57 58//58 400//400 -f 400//400 58//58 401//401 -f 402//402 399//399 403//403 -f 403//403 399//399 400//400 -f 403//403 400//400 404//404 -f 404//404 400//400 401//401 -f 405//405 406//406 407//407 -f 407//407 406//406 408//408 -f 407//407 408//408 409//409 -f 410//410 411//411 412//412 -f 411//411 413//413 412//412 -f 412//412 413//413 414//414 -f 412//412 414//414 415//415 -f 407//407 416//416 417//417 -f 409//409 418//418 407//407 -f 407//407 418//418 419//419 -f 407//407 419//419 420//420 -f 415//415 421//421 420//420 -f 421//421 422//422 420//420 -f 420//420 422//422 423//423 -f 420//420 423//423 407//407 -f 407//407 423//423 424//424 -f 407//407 424//424 416//416 -f 92//92 407//407 90//90 -f 90//90 407//407 417//417 -f 90//90 417//417 425//425 -f 425//425 417//417 426//426 -f 427//427 428//428 319//319 -f 319//319 428//428 410//410 -f 319//319 410//410 317//317 -f 317//317 410//410 412//412 -f 415//415 420//420 412//412 -f 412//412 420//420 60//60 -f 412//412 60//60 59//59 -f 429//429 430//430 378//378 -f 371//371 373//373 431//431 -f 403//403 404//404 432//432 -f 406//406 433//433 434//434 -f 64//64 62//62 66//66 -f 66//66 62//62 60//60 -f 435//435 436//436 68//68 -f 68//68 436//436 374//374 -f 437//437 438//438 431//431 -f 431//431 438//438 439//439 -f 431//431 439//439 371//371 -f 54//54 52//52 56//56 -f 56//56 52//52 50//50 -f 56//56 50//50 58//58 -f 431//431 440//440 441//441 -f 441//441 440//440 442//442 -f 442//442 443//443 441//441 -f 441//441 443//443 444//444 -f 441//441 444//444 445//445 -f 445//445 444//444 446//446 -f 445//445 446//446 447//447 -f 447//447 446//446 448//448 -f 447//447 448//448 449//449 -f 449//449 448//448 450//450 -f 449//449 450//450 451//451 -f 452//452 453//453 374//374 -f 453//453 454//454 374//374 -f 374//374 454//454 455//455 -f 374//374 455//455 373//373 -f 373//373 455//455 456//456 -f 373//373 456//456 457//457 -f 457//457 458//458 373//373 -f 373//373 458//458 459//459 -f 373//373 459//459 431//431 -f 431//431 459//459 460//460 -f 431//431 460//460 440//440 -f 461//461 462//462 436//436 -f 436//436 462//462 463//463 -f 436//436 463//463 374//374 -f 374//374 463//463 464//464 -f 374//374 464//464 452//452 -f 465//465 466//466 461//461 -f 461//461 466//466 467//467 -f 461//461 467//467 462//462 -f 465//465 461//461 468//468 -f 468//468 461//461 469//469 -f 468//468 469//469 470//470 -f 470//470 469//469 471//471 -f 470//470 471//471 472//472 -f 472//472 471//471 432//432 -f 472//472 432//432 473//473 -f 473//473 432//432 404//404 -f 473//473 404//404 451//451 -f 451//451 404//404 401//401 -f 451//451 401//401 449//449 -f 474//474 475//475 431//431 -f 441//441 476//476 477//477 -f 475//475 375//375 431//431 -f 431//431 375//375 392//392 -f 431//431 392//392 437//437 -f 476//476 441//441 478//478 -f 478//478 441//441 376//376 -f 478//478 376//376 479//479 -f 477//477 480//480 441//441 -f 441//441 480//480 481//481 -f 441//441 481//481 431//431 -f 431//431 481//481 482//482 -f 431//431 482//482 474//474 -f 475//475 483//483 375//375 -f 375//375 483//483 484//484 -f 375//375 484//484 376//376 -f 376//376 484//484 485//485 -f 376//376 485//485 479//479 -f 486//486 487//487 488//488 -f 489//489 490//490 461//461 -f 488//488 487//487 435//435 -f 461//461 490//490 488//488 -f 488//488 490//490 491//491 -f 488//488 491//491 486//486 -f 487//487 492//492 435//435 -f 435//435 492//492 493//493 -f 435//435 493//493 436//436 -f 436//436 493//493 494//494 -f 436//436 494//494 495//495 -f 495//495 496//496 436//436 -f 436//436 496//496 497//497 -f 436//436 497//497 461//461 -f 461//461 497//497 498//498 -f 461//461 498//498 489//489 -f 499//499 378//378 500//500 -f 500//500 378//378 376//376 -f 499//499 501//501 378//378 -f 378//378 501//501 502//502 -f 378//378 502//502 445//445 -f 445//445 502//502 503//503 -f 445//445 503//503 504//504 -f 505//505 441//441 506//506 -f 506//506 441//441 445//445 -f 506//506 445//445 507//507 -f 507//507 445//445 504//504 -f 505//505 508//508 441//441 -f 441//441 508//508 509//509 -f 441//441 509//509 376//376 -f 376//376 509//509 510//510 -f 376//376 510//510 500//500 -f 511//511 512//512 461//461 -f 461//461 512//512 513//513 -f 461//461 513//513 469//469 -f 469//469 513//513 514//514 -f 515//515 516//516 517//517 -f 517//517 516//516 488//488 -f 514//514 518//518 469//469 -f 469//469 518//518 519//519 -f 469//469 519//519 517//517 -f 517//517 519//519 520//520 -f 517//517 520//520 515//515 -f 516//516 521//521 488//488 -f 488//488 521//521 522//522 -f 488//488 522//522 461//461 -f 461//461 522//522 523//523 -f 461//461 523//523 511//511 -f 378//378 430//430 387//387 -f 430//430 524//524 387//387 -f 387//387 524//524 525//525 -f 387//387 525//525 447//447 -f 447//447 525//525 526//526 -f 447//447 526//526 527//527 -f 528//528 445//445 529//529 -f 529//529 445//445 447//447 -f 529//529 447//447 530//530 -f 530//530 447//447 527//527 -f 528//528 531//531 445//445 -f 445//445 531//531 532//532 -f 445//445 532//532 378//378 -f 378//378 532//532 533//533 -f 378//378 533//533 429//429 -f 534//534 471//471 535//535 -f 535//535 471//471 469//469 -f 535//535 469//469 536//536 -f 536//536 469//469 537//537 -f 534//534 538//538 471//471 -f 471//471 538//538 539//539 -f 471//471 539//539 540//540 -f 540//540 539//539 541//541 -f 541//541 542//542 540//540 -f 540//540 542//542 543//543 -f 540//540 543//543 517//517 -f 543//543 544//544 517//517 -f 517//517 544//544 545//545 -f 517//517 545//545 469//469 -f 469//469 545//545 546//546 -f 469//469 546//546 537//537 -f 547//547 548//548 449//449 -f 386//386 387//387 549//549 -f 549//549 550//550 386//386 -f 386//386 550//550 551//551 -f 386//386 551//551 552//552 -f 552//552 547//547 386//386 -f 386//386 547//547 449//449 -f 386//386 449//449 50//50 -f 50//50 449//449 401//401 -f 50//50 401//401 58//58 -f 553//553 447//447 554//554 -f 554//554 447//447 449//449 -f 554//554 449//449 555//555 -f 555//555 449//449 548//548 -f 553//553 556//556 447//447 -f 447//447 556//556 557//557 -f 447//447 557//557 387//387 -f 387//387 557//557 558//558 -f 387//387 558//558 549//549 -f 559//559 560//560 432//432 -f 403//403 432//432 561//561 -f 561//561 432//432 560//560 -f 561//561 560//560 562//562 -f 563//563 564//564 471//471 -f 471//471 564//564 565//565 -f 471//471 565//565 432//432 -f 432//432 565//565 566//566 -f 432//432 566//566 559//559 -f 562//562 567//567 561//561 -f 561//561 567//567 568//568 -f 561//561 568//568 540//540 -f 568//568 569//569 540//540 -f 540//540 569//569 570//570 -f 540//540 570//570 471//471 -f 471//471 570//570 571//571 -f 471//471 571//571 563//563 -f 434//434 572//572 406//406 -f 406//406 572//572 403//403 -f 406//406 403//403 408//408 -f 408//408 403//403 561//561 -f 408//408 561//561 409//409 -f 409//409 561//561 540//540 -f 409//409 540//540 418//418 -f 418//418 540//540 517//517 -f 418//418 517//517 419//419 -f 419//419 517//517 488//488 -f 419//419 488//488 420//420 -f 420//420 488//488 435//435 -f 420//420 435//435 60//60 -f 60//60 435//435 68//68 -f 60//60 68//68 66//66 -f 402//402 403//403 573//573 -f 573//573 403//403 572//572 -f 573//573 572//572 574//574 -f 574//574 572//572 434//434 -f 574//574 434//434 575//575 -f 575//575 434//434 433//433 -f 575//575 433//433 405//405 -f 405//405 433//433 406//406 -f 372//372 371//371 576//576 -f 576//576 371//371 439//439 -f 576//576 439//439 577//577 -f 577//577 439//439 438//438 -f 577//577 438//438 578//578 -f 578//578 438//438 437//437 -f 578//578 437//437 393//393 -f 393//393 437//437 392//392 -f 141//141 331//331 333//333 -f 141//141 333//333 142//142 -f 142//142 333//333 334//334 -f 142//142 334//334 143//143 -f 143//143 334//334 320//320 -f 143//143 320//320 285//285 -f 285//285 320//320 294//294 -f 285//285 294//294 286//286 -f 124//124 313//313 312//312 -f 124//124 312//312 122//122 -f 122//122 312//312 314//314 -f 122//122 314//314 123//123 -f 123//123 314//314 315//315 -f 123//123 315//315 125//125 -f 125//125 315//315 316//316 -f 125//125 316//316 183//183 -f 137//137 76//76 71//71 -f 137//137 71//71 135//135 -f 135//135 71//71 70//70 -f 135//135 70//70 133//133 -f 133//133 70//70 69//69 -f 133//133 69//69 134//134 -f 134//134 69//69 75//75 -f 134//134 75//75 136//136 -f 130//130 109//109 107//107 -f 130//130 107//107 128//128 -f 128//128 107//107 106//106 -f 128//128 106//106 126//126 -f 126//126 106//106 83//83 -f 126//126 83//83 127//127 -f 127//127 83//83 85//85 -f 127//127 85//85 129//129 -f 162//162 466//466 163//163 -f 163//163 466//466 465//465 -f 163//163 465//465 165//165 -f 165//165 465//465 468//468 -f 165//165 468//468 167//167 -f 167//167 468//468 470//470 -f 167//167 470//470 168//168 -f 168//168 470//470 472//472 -f 168//168 472//472 155//155 -f 155//155 472//472 473//473 -f 473//473 451//451 155//155 -f 155//155 451//451 157//157 -f 443//443 144//144 444//444 -f 444//444 144//144 153//153 -f 444//444 153//153 446//446 -f 446//446 153//153 152//152 -f 446//446 152//152 448//448 -f 448//448 152//152 150//150 -f 448//448 150//150 450//450 -f 450//450 150//150 148//148 -f 450//450 148//148 451//451 -f 451//451 148//148 157//157 -f 467//467 161//161 462//462 -f 462//462 161//161 159//159 -f 462//462 159//159 463//463 -f 463//463 159//159 179//179 -f 463//463 179//179 464//464 -f 464//464 179//179 178//178 -f 464//464 178//178 452//452 -f 452//452 178//178 177//177 -f 452//452 177//177 453//453 -f 453//453 177//177 176//176 -f 453//453 176//176 454//454 -f 454//454 176//176 175//175 -f 454//454 175//175 455//455 -f 455//455 175//175 173//173 -f 455//455 173//173 456//456 -f 456//456 173//173 172//172 -f 456//456 172//172 457//457 -f 457//457 172//172 170//170 -f 457//457 170//170 458//458 -f 458//458 170//170 169//169 -f 458//458 169//169 459//459 -f 459//459 169//169 171//171 -f 459//459 171//171 460//460 -f 460//460 171//171 121//121 -f 460//460 121//121 440//440 -f 440//440 121//121 120//120 -f 440//440 120//120 442//442 -f 442//442 120//120 145//145 -f 162//162 161//161 466//466 -f 466//466 161//161 467//467 -f 145//145 144//144 442//442 -f 442//442 144//144 443//443 -f 481//481 198//198 482//482 -f 482//482 198//198 197//197 -f 482//482 197//197 474//474 -f 474//474 197//197 196//196 -f 474//474 196//196 475//475 -f 475//475 196//196 195//195 -f 475//475 195//195 483//483 -f 483//483 195//195 200//200 -f 483//483 200//200 484//484 -f 484//484 200//200 207//207 -f 484//484 207//207 485//485 -f 485//485 207//207 206//206 -f 485//485 206//206 479//479 -f 479//479 206//206 205//205 -f 479//479 205//205 478//478 -f 478//478 205//205 204//204 -f 478//478 204//204 476//476 -f 476//476 204//204 202//202 -f 476//476 202//202 477//477 -f 477//477 202//202 201//201 -f 477//477 201//201 480//480 -f 480//480 201//201 199//199 -f 480//480 199//199 481//481 -f 481//481 199//199 198//198 -f 487//487 184//184 492//492 -f 492//492 184//184 186//186 -f 492//492 186//186 493//493 -f 493//493 186//186 187//187 -f 493//493 187//187 494//494 -f 494//494 187//187 181//181 -f 494//494 181//181 495//495 -f 495//495 181//181 180//180 -f 495//495 180//180 496//496 -f 496//496 180//180 194//194 -f 496//496 194//194 497//497 -f 497//497 194//194 193//193 -f 497//497 193//193 498//498 -f 498//498 193//193 192//192 -f 498//498 192//192 489//489 -f 489//489 192//192 191//191 -f 489//489 191//191 490//490 -f 490//490 191//191 190//190 -f 490//490 190//190 491//491 -f 491//491 190//190 189//189 -f 491//491 189//189 486//486 -f 486//486 189//189 188//188 -f 486//486 188//188 487//487 -f 487//487 188//188 184//184 -f 516//516 208//208 521//521 -f 521//521 208//208 210//210 -f 521//521 210//210 522//522 -f 522//522 210//210 220//220 -f 522//522 220//220 523//523 -f 523//523 220//220 219//219 -f 523//523 219//219 511//511 -f 511//511 219//219 218//218 -f 511//511 218//218 512//512 -f 512//512 218//218 215//215 -f 512//512 215//215 513//513 -f 513//513 215//215 216//216 -f 513//513 216//216 514//514 -f 514//514 216//216 217//217 -f 514//514 217//217 518//518 -f 518//518 217//217 214//214 -f 518//518 214//214 519//519 -f 519//519 214//214 213//213 -f 519//519 213//213 520//520 -f 520//520 213//213 212//212 -f 520//520 212//212 515//515 -f 515//515 212//212 211//211 -f 515//515 211//211 516//516 -f 516//516 211//211 208//208 -f 543//543 236//236 544//544 -f 544//544 236//236 234//234 -f 544//544 234//234 545//545 -f 545//545 234//234 246//246 -f 545//545 246//246 546//546 -f 546//546 246//246 245//245 -f 546//546 245//245 537//537 -f 537//537 245//245 244//244 -f 537//537 244//244 536//536 -f 536//536 244//244 241//241 -f 536//536 241//241 535//535 -f 535//535 241//241 242//242 -f 535//535 242//242 534//534 -f 534//534 242//242 243//243 -f 534//534 243//243 538//538 -f 538//538 243//243 240//240 -f 538//538 240//240 539//539 -f 539//539 240//240 239//239 -f 539//539 239//239 541//541 -f 541//541 239//239 238//238 -f 541//541 238//238 542//542 -f 542//542 238//238 237//237 -f 542//542 237//237 543//543 -f 543//543 237//237 236//236 -f 568//568 268//268 569//569 -f 569//569 268//268 267//267 -f 569//569 267//267 570//570 -f 570//570 267//267 266//266 -f 570//570 266//266 571//571 -f 571//571 266//266 261//261 -f 571//571 261//261 563//563 -f 563//563 261//261 260//260 -f 563//563 260//260 564//564 -f 564//564 260//260 271//271 -f 564//564 271//271 565//565 -f 565//565 271//271 270//270 -f 565//565 270//270 566//566 -f 566//566 270//270 269//269 -f 566//566 269//269 559//559 -f 559//559 269//269 265//265 -f 559//559 265//265 560//560 -f 560//560 265//265 264//264 -f 560//560 264//264 562//562 -f 562//562 264//264 263//263 -f 562//562 263//263 567//567 -f 567//567 263//263 262//262 -f 567//567 262//262 568//568 -f 568//568 262//262 268//268 -f 554//554 276//276 553//553 -f 553//553 276//276 275//275 -f 553//553 275//275 556//556 -f 556//556 275//275 274//274 -f 556//556 274//274 557//557 -f 557//557 274//274 273//273 -f 557//557 273//273 558//558 -f 558//558 273//273 272//272 -f 558//558 272//272 549//549 -f 549//549 272//272 284//284 -f 549//549 284//284 550//550 -f 550//550 284//284 283//283 -f 550//550 283//283 551//551 -f 551//551 283//283 282//282 -f 551//551 282//282 552//552 -f 552//552 282//282 278//278 -f 552//552 278//278 547//547 -f 547//547 278//278 280//280 -f 547//547 280//280 548//548 -f 548//548 280//280 281//281 -f 548//548 281//281 555//555 -f 555//555 281//281 277//277 -f 555//555 277//277 554//554 -f 554//554 277//277 276//276 -f 529//529 250//250 528//528 -f 528//528 250//250 249//249 -f 528//528 249//249 531//531 -f 531//531 249//249 248//248 -f 531//531 248//248 532//532 -f 532//532 248//248 247//247 -f 532//532 247//247 533//533 -f 533//533 247//247 252//252 -f 533//533 252//252 429//429 -f 429//429 252//252 259//259 -f 429//429 259//259 430//430 -f 430//430 259//259 258//258 -f 430//430 258//258 524//524 -f 524//524 258//258 257//257 -f 524//524 257//257 525//525 -f 525//525 257//257 256//256 -f 525//525 256//256 526//526 -f 526//526 256//256 254//254 -f 526//526 254//254 527//527 -f 527//527 254//254 253//253 -f 527//527 253//253 530//530 -f 530//530 253//253 251//251 -f 530//530 251//251 529//529 -f 529//529 251//251 250//250 -f 506//506 225//225 505//505 -f 505//505 225//225 224//224 -f 505//505 224//224 508//508 -f 508//508 224//224 223//223 -f 508//508 223//223 509//509 -f 509//509 223//223 233//233 -f 509//509 233//233 510//510 -f 510//510 233//233 232//232 -f 510//510 232//232 500//500 -f 500//500 232//232 231//231 -f 500//500 231//231 499//499 -f 499//499 231//231 230//230 -f 499//499 230//230 501//501 -f 501//501 230//230 229//229 -f 501//501 229//229 502//502 -f 502//502 229//229 227//227 -f 502//502 227//227 503//503 -f 503//503 227//227 222//222 -f 503//503 222//222 504//504 -f 504//504 222//222 221//221 -f 504//504 221//221 507//507 -f 507//507 221//221 226//226 -f 507//507 226//226 506//506 -f 506//506 226//226 225//225 -f 345//345 348//348 410//410 -f 410//410 348//348 411//411 -f 417//417 416//416 351//351 -f 351//351 416//416 352//352 -f 352//352 416//416 353//353 -f 353//353 416//416 424//424 -f 353//353 424//424 342//342 -f 342//342 424//424 423//423 -f 342//342 423//423 343//343 -f 343//343 423//423 422//422 -f 343//343 422//422 344//344 -f 344//344 422//422 421//421 -f 344//344 421//421 339//339 -f 339//339 421//421 415//415 -f 339//339 415//415 340//340 -f 340//340 415//415 414//414 -f 340//340 414//414 341//341 -f 341//341 414//414 413//413 -f 341//341 413//413 348//348 -f 348//348 413//413 411//411 -f 385//385 366//366 384//384 -f 384//384 366//366 367//367 -f 384//384 367//367 383//383 -f 383//383 367//367 368//368 -f 383//383 368//368 382//382 -f 382//382 368//368 362//362 -f 382//382 362//362 391//391 -f 391//391 362//362 356//356 -f 391//391 356//356 380//380 -f 380//380 356//356 355//355 -f 380//380 355//355 381//381 -f 381//381 355//355 354//354 -f 381//381 354//354 388//388 -f 388//388 354//354 361//361 -f 388//388 361//361 389//389 -f 389//389 361//361 360//360 -f 365//365 366//366 398//398 -f 398//398 366//366 385//385 -f 390//390 389//389 359//359 -f 359//359 389//389 360//360 -f 105//105 104//104 364//364 -f 105//105 364//364 396//396 -f 396//396 364//364 363//363 -f 396//396 363//363 397//397 -f 397//397 363//363 365//365 -f 397//397 365//365 398//398 -f 91//91 90//90 425//425 -f 91//91 425//425 349//349 -f 349//349 425//425 426//426 -f 349//349 426//426 350//350 -f 350//350 426//426 417//417 -f 350//350 417//417 351//351 -f 345//345 410//410 428//428 -f 345//345 428//428 346//346 -f 346//346 428//428 427//427 -f 346//346 427//427 347//347 -f 347//347 427//427 319//319 -f 347//347 319//319 318//318 -f 390//390 359//359 358//358 -f 390//390 358//358 395//395 -f 395//395 358//358 357//357 -f 395//395 357//357 394//394 -f 394//394 357//357 292//292 -f 394//394 292//292 291//291 -f 326//326 327//327 579//579 -f 579//579 327//327 580//580 -f 581//581 580//580 328//328 -f 328//328 580//580 327//327 -f 582//582 581//581 306//306 -f 306//306 581//581 328//328 -f 583//583 412//412 59//59 -f 584//584 59//59 585//585 -f 585//585 59//59 61//61 -f 585//585 61//61 586//586 -f 586//586 61//61 63//63 -f 63//63 65//65 586//586 -f 586//586 65//65 67//67 -f 586//586 67//67 587//587 -f 587//587 67//67 369//369 -f 587//587 369//369 588//588 -f 588//588 589//589 587//587 -f 587//587 589//589 590//590 -f 587//587 590//590 591//591 -f 590//590 579//579 591//591 -f 591//591 579//579 580//580 -f 591//591 580//580 592//592 -f 592//592 580//580 581//581 -f 592//592 581//581 584//584 -f 584//584 581//581 582//582 -f 584//584 582//582 59//59 -f 59//59 582//582 593//593 -f 59//59 593//593 583//583 -f 594//594 595//595 98//98 -f 98//98 595//595 95//95 -f 596//596 594//594 100//100 -f 100//100 594//594 98//98 -f 597//597 596//596 99//99 -f 99//99 596//596 100//100 -f 402//402 598//598 599//599 -f 405//405 407//407 600//600 -f 402//402 573//573 598//598 -f 598//598 573//573 574//574 -f 598//598 574//574 601//601 -f 601//601 574//574 575//575 -f 601//601 575//575 405//405 -f 602//602 603//603 599//599 -f 599//599 603//603 399//399 -f 599//599 399//399 402//402 -f 604//604 595//595 605//605 -f 605//605 595//595 594//594 -f 605//605 594//594 606//606 -f 604//604 601//601 595//595 -f 595//595 601//601 405//405 -f 595//595 405//405 607//607 -f 607//607 405//405 600//600 -f 594//594 596//596 606//606 -f 606//606 596//596 597//597 -f 606//606 597//597 599//599 -f 599//599 597//597 608//608 -f 599//599 608//608 602//602 -f 609//609 77//77 610//610 -f 610//610 77//77 101//101 -f 610//610 101//101 611//611 -f 611//611 101//101 102//102 -f 611//611 102//102 612//612 -f 612//612 102//102 97//97 -f 612//612 97//97 613//613 -f 613//613 97//97 96//96 -f 613//613 96//96 614//614 -f 614//614 96//96 87//87 -f 614//614 87//87 615//615 -f 615//615 87//87 86//86 -f 615//615 86//86 616//616 -f 616//616 86//86 84//84 -f 616//616 84//84 617//617 -f 617//617 84//84 108//108 -f 617//617 108//108 618//618 -f 618//618 108//108 110//110 -f 618//618 110//110 619//619 -f 619//619 110//110 73//73 -f 619//619 73//73 620//620 -f 620//620 73//73 72//72 -f 620//620 72//72 609//609 -f 609//609 72//72 77//77 -f 79//79 80//80 621//621 -f 621//621 80//80 622//622 -f 623//623 622//622 81//81 -f 81//81 622//622 80//80 -f 624//624 623//623 82//82 -f 82//82 623//623 81//81 -f 625//625 377//377 49//49 -f 626//626 55//55 57//57 -f 627//627 628//628 629//629 -f 629//629 628//628 630//630 -f 629//629 630//630 631//631 -f 626//626 57//57 629//629 -f 629//629 57//57 400//400 -f 629//629 400//400 627//627 -f 632//632 49//49 633//633 -f 633//633 49//49 51//51 -f 633//633 51//51 626//626 -f 626//626 51//51 53//53 -f 626//626 53//53 55//55 -f 630//630 621//621 631//631 -f 631//631 621//621 622//622 -f 631//631 622//622 634//634 -f 634//634 622//622 623//623 -f 634//634 623//623 632//632 -f 632//632 623//623 624//624 -f 632//632 624//624 49//49 -f 49//49 624//624 635//635 -f 49//49 635//635 625//625 -f 636//636 637//637 298//298 -f 298//298 637//637 300//300 -f 638//638 636//636 303//303 -f 303//303 636//636 298//298 -f 639//639 638//638 302//302 -f 302//302 638//638 303//303 -f 640//640 641//641 642//642 -f 643//643 637//637 644//644 -f 644//644 637//637 636//636 -f 644//644 636//636 645//645 -f 393//393 379//379 646//646 -f 636//636 638//638 645//645 -f 645//645 638//638 639//639 -f 645//645 639//639 642//642 -f 642//642 639//639 647//647 -f 642//642 647//647 640//640 -f 643//643 648//648 637//637 -f 637//637 648//648 393//393 -f 637//637 393//393 649//649 -f 649//649 393//393 646//646 -f 641//641 370//370 642//642 -f 642//642 370//370 372//372 -f 642//642 372//372 650//650 -f 372//372 576//576 650//650 -f 650//650 576//576 577//577 -f 650//650 577//577 648//648 -f 648//648 577//577 578//578 -f 648//648 578//578 393//393 -f 651//651 322//322 652//652 -f 652//652 322//322 321//321 -f 652//652 321//321 653//653 -f 653//653 321//321 332//332 -f 653//653 332//332 654//654 -f 654//654 332//332 330//330 -f 654//654 330//330 655//655 -f 655//655 330//330 329//329 -f 655//655 329//329 656//656 -f 656//656 329//329 338//338 -f 656//656 338//338 657//657 -f 657//657 338//338 309//309 -f 657//657 309//309 658//658 -f 658//658 309//309 304//304 -f 658//658 304//304 659//659 -f 659//659 304//304 305//305 -f 659//659 305//305 660//660 -f 660//660 305//305 297//297 -f 660//660 297//297 661//661 -f 661//661 297//297 299//299 -f 661//661 299//299 662//662 -f 662//662 299//299 296//296 -f 662//662 296//296 651//651 -f 651//651 296//296 322//322 -f 624//624 82//82 635//635 -f 635//635 82//82 88//88 -f 635//635 88//88 625//625 -f 625//625 88//88 89//89 -f 625//625 89//89 377//377 -f 377//377 89//89 103//103 -f 79//79 621//621 78//78 -f 78//78 621//621 630//630 -f 78//78 630//630 113//113 -f 113//113 630//630 628//628 -f 113//113 628//628 114//114 -f 114//114 628//628 627//627 -f 114//114 627//627 115//115 -f 115//115 627//627 400//400 -f 95//95 595//595 94//94 -f 94//94 595//595 607//607 -f 94//94 607//607 93//93 -f 93//93 607//607 600//600 -f 93//93 600//600 92//92 -f 92//92 600//600 407//407 -f 597//597 99//99 608//608 -f 608//608 99//99 74//74 -f 608//608 74//74 602//602 -f 602//602 74//74 112//112 -f 602//602 112//112 603//603 -f 603//603 112//112 111//111 -f 603//603 111//111 399//399 -f 399//399 111//111 116//116 -f 300//300 637//637 301//301 -f 301//301 637//637 649//649 -f 301//301 649//649 295//295 -f 295//295 649//649 646//646 -f 295//295 646//646 293//293 -f 293//293 646//646 379//379 -f 639//639 302//302 647//647 -f 647//647 302//302 311//311 -f 647//647 311//311 640//640 -f 640//640 311//311 310//310 -f 640//640 310//310 641//641 -f 641//641 310//310 337//337 -f 641//641 337//337 370//370 -f 370//370 337//337 336//336 -f 582//582 306//306 593//593 -f 593//593 306//306 307//307 -f 593//593 307//307 583//583 -f 583//583 307//307 308//308 -f 583//583 308//308 412//412 -f 412//412 308//308 317//317 -f 326//326 579//579 325//325 -f 325//325 579//579 590//590 -f 325//325 590//590 323//323 -f 323//323 590//590 589//589 -f 323//323 589//589 324//324 -f 324//324 589//589 588//588 -f 324//324 588//588 335//335 -f 335//335 588//588 369//369 -f 663//663 664//664 658//658 -f 658//658 659//659 663//663 -f 663//663 659//659 660//660 -f 663//663 660//660 665//665 -f 666//666 667//667 652//652 -f 660//660 661//661 665//665 -f 665//665 661//661 662//662 -f 665//665 662//662 667//667 -f 667//667 662//662 651//651 -f 667//667 651//651 652//652 -f 652//652 653//653 666//666 -f 666//666 653//653 654//654 -f 666//666 654//654 668//668 -f 654//654 655//655 668//668 -f 668//668 655//655 656//656 -f 668//668 656//656 664//664 -f 664//664 656//656 657//657 -f 664//664 657//657 658//658 -f 666//666 668//668 650//650 -f 650//650 668//668 642//642 -f 668//668 664//664 642//642 -f 642//642 664//664 645//645 -f 664//664 663//663 645//645 -f 645//645 663//663 644//644 -f 663//663 665//665 644//644 -f 644//644 665//665 643//643 -f 665//665 667//667 643//643 -f 643//643 667//667 648//648 -f 667//667 666//666 648//648 -f 648//648 666//666 650//650 -f 669//669 670//670 39//39 -f 39//39 41//41 669//669 -f 669//669 41//41 43//43 -f 669//669 43//43 671//671 -f 671//671 43//43 45//45 -f 671//671 45//45 672//672 -f 27//27 673//673 25//25 -f 25//25 673//673 672//672 -f 25//25 672//672 47//47 -f 47//47 672//672 45//45 -f 27//27 29//29 673//673 -f 673//673 29//29 31//31 -f 673//673 31//31 674//674 -f 31//31 33//33 674//674 -f 674//674 33//33 35//35 -f 674//674 35//35 670//670 -f 670//670 35//35 37//37 -f 670//670 37//37 39//39 -f 673//673 674//674 632//632 -f 632//632 674//674 634//634 -f 674//674 670//670 634//634 -f 634//634 670//670 631//631 -f 670//670 669//669 631//631 -f 631//631 669//669 629//629 -f 669//669 671//671 629//629 -f 629//629 671//671 626//626 -f 671//671 672//672 626//626 -f 626//626 672//672 633//633 -f 672//672 673//673 633//633 -f 633//633 673//673 632//632 -f 675//675 676//676 616//616 -f 616//616 617//617 675//675 -f 675//675 617//617 618//618 -f 675//675 618//618 677//677 -f 618//618 619//619 677//677 -f 677//677 619//619 620//620 -f 677//677 620//620 678//678 -f 678//678 620//620 609//609 -f 678//678 609//609 679//679 -f 609//609 610//610 679//679 -f 679//679 610//610 611//611 -f 679//679 611//611 680//680 -f 680//680 611//611 612//612 -f 612//612 613//613 680//680 -f 680//680 613//613 614//614 -f 680//680 614//614 676//676 -f 676//676 614//614 615//615 -f 676//676 615//615 616//616 -f 680//680 676//676 604//604 -f 604//604 676//676 601//601 -f 676//676 675//675 601//601 -f 601//601 675//675 598//598 -f 675//675 677//677 598//598 -f 598//598 677//677 599//599 -f 677//677 678//678 599//599 -f 599//599 678//678 606//606 -f 678//678 679//679 606//606 -f 606//606 679//679 605//605 -f 679//679 680//680 605//605 -f 605//605 680//680 604//604 -f 681//681 13//13 15//15 -f 681//681 15//15 682//682 -f 15//15 17//17 682//682 -f 682//682 17//17 19//19 -f 682//682 19//19 683//683 -f 19//19 21//21 683//683 -f 683//683 21//21 23//23 -f 683//683 23//23 684//684 -f 684//684 23//23 1//1 -f 684//684 1//1 685//685 -f 1//1 3//3 685//685 -f 685//685 3//3 5//5 -f 685//685 5//5 686//686 -f 5//5 7//7 686//686 -f 686//686 7//7 9//9 -f 686//686 9//9 681//681 -f 681//681 9//9 11//11 -f 681//681 11//11 13//13 -f 684//684 685//685 591//591 -f 591//591 685//685 587//587 -f 685//685 686//686 587//587 -f 587//587 686//686 586//586 -f 686//686 681//681 586//586 -f 586//586 681//681 585//585 -f 681//681 682//682 585//585 -f 585//585 682//682 584//584 -f 682//682 683//683 584//584 -f 584//584 683//683 592//592 -f 683//683 684//684 592//592 -f 592//592 684//684 591//591 -# 1420 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/base_motor.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/base_motor.obj deleted file mode 100644 index 7f570dc3f..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/base_motor.obj +++ /dev/null @@ -1,14328 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object base_motor.obj -# -# Vertices: 3504 -# Faces: 7304 -# -#### -vn 0.577350 0.577350 0.577350 -v 0.080753 0.127750 0.042000 -vn -0.577350 0.577350 0.577350 -v 0.069253 0.127750 0.042000 -vn 0.301511 0.301511 0.904534 -v 0.080753 0.126250 0.042000 -vn -0.301511 0.301511 0.904534 -v 0.069253 0.126250 0.042000 -vn -0.095842 0.727973 0.678874 -v 0.063003 0.126250 0.042000 -vn -0.000000 -1.000000 -0.000000 -v 0.064603 0.124750 0.042000 -vn -0.499995 0.866028 0.000000 -v 0.065103 0.122884 0.042000 -vn 1.000000 -0.000000 -0.000002 -v 0.064753 0.081750 0.042000 -vn -0.866025 0.500001 0.000004 -v 0.065469 0.123250 0.042000 -vn 0.866025 -0.500001 0.000002 -v 0.064887 0.082250 0.042000 -vn -1.000000 0.000000 -0.000002 -v 0.065603 0.123750 0.042000 -vn -1.000000 -0.000004 -0.000000 -v 0.085253 0.081750 0.042000 -vn -0.000009 1.000000 -0.000001 -v 0.085403 0.122750 0.042000 -vn -0.866024 -0.500003 0.000001 -v 0.085119 0.082250 0.042000 -vn -0.500001 -0.866025 0.000000 -v 0.084753 0.082616 0.042000 -vn -0.500001 -0.866025 0.000000 -v 0.065103 0.124616 0.042000 -vn -0.866025 -0.500001 0.000000 -v 0.065469 0.124250 0.042000 -vn -0.000000 -1.000000 0.000002 -v 0.084253 0.082750 0.042000 -vn 0.499989 0.866032 0.000000 -v 0.084903 0.122884 0.042000 -vn 0.866025 0.500001 0.000000 -v 0.084537 0.123250 0.042000 -vn 0.095840 0.727973 0.678874 -v 0.087003 0.126250 0.042000 -vn -0.499998 -0.866026 -0.000000 -v 0.085903 0.124616 0.042000 -vn 0.378578 0.655722 0.653228 -v 0.087503 0.126116 0.042000 -vn -0.866026 -0.500000 -0.000000 -v 0.086269 0.124250 0.042000 -vn 0.655721 0.378585 0.653226 -v 0.087869 0.125750 0.042000 -vn 0.727973 0.095839 0.678875 -v 0.088003 0.125250 0.042000 -vn -1.000000 0.000000 0.000000 -v 0.086403 0.123750 0.042000 -vn -0.866026 0.500000 -0.000000 -v 0.086269 0.123250 0.042000 -vn 0.997120 -0.075739 -0.003866 -v 0.088003 0.084250 0.042000 -vn -0.499992 0.866030 0.000000 -v 0.085903 0.122884 0.042000 -vn 0.587418 -0.809272 -0.004460 -v 0.085942 0.080205 0.042000 -vn -0.500001 0.866025 -0.000000 -v 0.084753 0.080884 0.042000 -vn 0.307849 -0.951434 -0.001695 -v 0.084548 0.079495 0.042000 -vn 0.000000 1.000000 -0.000000 -v 0.084253 0.080750 0.042000 -vn 0.078458 -0.996917 0.000000 -v 0.083003 0.079250 0.042000 -vn 0.500001 0.866025 0.000000 -v 0.083753 0.080884 0.042000 -vn -0.077786 -0.996970 -0.000829 -v 0.067003 0.079250 0.042000 -vn 0.866025 0.500001 0.000000 -v 0.083387 0.081250 0.042000 -vn 0.808802 -0.588052 -0.005792 -v 0.087048 0.081311 0.042000 -vn -0.866026 0.500000 0.000000 -v 0.085119 0.081250 0.042000 -vn 0.950926 -0.309341 -0.006980 -v 0.087758 0.082705 0.042000 -vn -0.655721 0.378585 0.653226 -v 0.062137 0.125750 0.042000 -vn -0.727973 0.095839 0.678874 -v 0.062003 0.125250 0.042000 -vn -0.378579 0.655721 0.653228 -v 0.062503 0.126116 0.042000 -vn 0.866025 -0.500001 -0.000001 -v 0.063737 0.124250 0.042000 -vn 0.500001 -0.866025 0.000000 -v 0.064103 0.124616 0.042000 -vn 0.500001 -0.866025 0.000000 -v 0.065253 0.082616 0.042000 -vn -0.000000 -1.000000 0.000000 -v 0.065753 0.082750 0.042000 -vn -0.500001 -0.866025 -0.000000 -v 0.066253 0.082616 0.042000 -vn 0.866025 -0.500001 0.000002 -v 0.083387 0.082250 0.042000 -vn -0.866025 -0.500001 0.000000 -v 0.066619 0.082250 0.042000 -vn 1.000000 -0.000000 0.000000 -v 0.083253 0.081750 0.042000 -vn -1.000000 0.000000 0.000000 -v 0.066753 0.081750 0.042000 -vn -0.866025 0.500001 -0.000000 -v 0.066619 0.081250 0.042000 -vn -0.500001 0.866025 0.000000 -v 0.066253 0.080884 0.042000 -vn -0.308524 -0.951213 -0.002423 -v 0.065458 0.079495 0.042000 -vn 0.000000 1.000000 0.000000 -v 0.065753 0.080750 0.042000 -vn -0.587425 -0.809268 -0.004299 -v 0.064064 0.080205 0.042000 -vn 1.000000 -0.000000 -0.000000 -v 0.084403 0.123750 0.042000 -vn 0.500001 -0.866025 0.000000 -v 0.083753 0.082616 0.042000 -vn 0.866025 -0.500001 0.000001 -v 0.084537 0.124250 0.042000 -vn 0.500007 -0.866021 0.000000 -v 0.084903 0.124616 0.042000 -vn 0.000005 -1.000000 0.000001 -v 0.085403 0.124750 0.042000 -vn 0.000000 1.000000 0.000001 -v 0.064603 0.122750 0.042000 -vn 0.499995 0.866028 0.000000 -v 0.064103 0.122884 0.042000 -vn -0.996935 -0.078222 -0.001162 -v 0.062003 0.084250 0.042000 -vn 0.866025 0.500001 -0.000000 -v 0.063737 0.123250 0.042000 -vn 1.000000 -0.000000 0.000000 -v 0.063603 0.123750 0.042000 -vn 0.500001 0.866025 0.000000 -v 0.065253 0.080884 0.042000 -vn 0.866025 0.500001 0.000000 -v 0.064887 0.081250 0.042000 -vn -0.808805 -0.588051 -0.005610 -v 0.062958 0.081311 0.042000 -vn -0.951748 -0.306861 -0.003336 -v 0.062248 0.082705 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.080753 0.126250 0.020000 -vn 0.095840 0.727973 -0.678874 -v 0.087003 0.126250 0.020000 -vn 0.000003 -0.637724 -0.770265 -v 0.085403 0.124750 0.020000 -vn -0.577350 0.577350 -0.577350 -v 0.069253 0.127750 0.020000 -vn 0.577350 0.577350 -0.577350 -v 0.080753 0.127750 0.020000 -vn -0.301511 0.301511 -0.904534 -v 0.069253 0.126250 0.020000 -vn -0.637731 -0.000000 -0.770259 -v 0.086403 0.123750 0.020000 -vn -0.552286 -0.318862 -0.770265 -v 0.086269 0.124250 0.020000 -vn 0.727973 0.095839 -0.678875 -v 0.088003 0.125250 0.020000 -vn 0.552289 -0.318864 -0.770262 -v 0.063737 0.124250 0.020000 -vn 0.637727 0.000000 -0.770263 -v 0.063603 0.123750 0.020000 -vn -0.727973 0.095839 -0.678874 -v 0.062003 0.125250 0.020000 -vn 0.552289 0.318864 -0.770262 -v 0.063737 0.123250 0.020000 -vn -0.997099 -0.076046 0.003384 -v 0.062003 0.084250 0.020000 -vn 0.318862 0.552289 -0.770262 -v 0.064103 0.122884 0.020000 -vn 0.000000 0.637730 -0.770260 -v 0.064603 0.122750 0.020000 -vn -0.000006 0.637731 -0.770259 -v 0.085403 0.122750 0.020000 -vn -0.318865 -0.552288 -0.770261 -v 0.084753 0.082616 0.020000 -vn 0.000000 -0.637727 -0.770263 -v 0.084253 0.082750 0.020000 -vn 0.552288 -0.318865 -0.770262 -v 0.084537 0.124250 0.020000 -vn 0.637727 0.000000 -0.770263 -v 0.084403 0.123750 0.020000 -vn -0.552288 -0.318865 -0.770262 -v 0.065469 0.124250 0.020000 -vn -0.318865 -0.552289 -0.770261 -v 0.065103 0.124616 0.020000 -vn 0.655721 0.378585 -0.653226 -v 0.087869 0.125750 0.020000 -vn 0.378578 0.655722 -0.653228 -v 0.087503 0.126116 0.020000 -vn -0.318864 -0.552291 -0.770260 -v 0.085903 0.124616 0.020000 -vn 0.318865 -0.552288 -0.770262 -v 0.083753 0.082616 0.020000 -vn 0.552289 -0.318865 -0.770261 -v 0.083387 0.082250 0.020000 -vn -0.318865 -0.552289 -0.770261 -v 0.066253 0.082616 0.020000 -vn 0.000000 -0.637727 -0.770262 -v 0.065753 0.082750 0.020000 -vn 0.318865 -0.552288 -0.770261 -v 0.065253 0.082616 0.020000 -vn -0.095842 0.727973 -0.678874 -v 0.063003 0.126250 0.020000 -vn -0.000000 -0.637728 -0.770262 -v 0.064603 0.124750 0.020000 -vn 0.318866 -0.552288 -0.770261 -v 0.064103 0.124616 0.020000 -vn -0.378579 0.655721 -0.653228 -v 0.062503 0.126116 0.020000 -vn -0.655721 0.378585 -0.653226 -v 0.062137 0.125750 0.020000 -vn -0.587771 -0.808999 0.006827 -v 0.064064 0.080205 0.020000 -vn -0.808998 -0.587772 0.006827 -v 0.062958 0.081311 0.020000 -vn 0.637727 -0.000000 -0.770262 -v 0.064753 0.081750 0.020000 -vn -0.951034 -0.309011 0.006827 -v 0.062248 0.082705 0.020000 -vn 0.552288 -0.318865 -0.770262 -v 0.064887 0.082250 0.020000 -vn -0.076045 -0.997099 0.003384 -v 0.067003 0.079250 0.020000 -vn 0.552289 0.318865 -0.770261 -v 0.083387 0.081250 0.020000 -vn 0.076045 -0.997099 0.003384 -v 0.083003 0.079250 0.020000 -vn 0.318865 0.552288 -0.770261 -v 0.083753 0.080884 0.020000 -vn 0.309011 -0.951034 0.006827 -v 0.084548 0.079495 0.020000 -vn -0.000000 0.637727 -0.770263 -v 0.084253 0.080750 0.020000 -vn 0.587773 -0.808997 0.006827 -v 0.085942 0.080205 0.020000 -vn 0.318870 -0.552288 -0.770260 -v 0.084903 0.124616 0.020000 -vn -0.637727 -0.000000 -0.770263 -v 0.065603 0.123750 0.020000 -vn -0.552288 0.318865 -0.770262 -v 0.065469 0.123250 0.020000 -vn 0.552290 0.318866 -0.770260 -v 0.084537 0.123250 0.020000 -vn -0.318860 0.552289 -0.770263 -v 0.065103 0.122884 0.020000 -vn 0.318855 0.552290 -0.770264 -v 0.084903 0.122884 0.020000 -vn -0.552286 0.318862 -0.770265 -v 0.086269 0.123250 0.020000 -vn 0.997099 -0.076046 0.003385 -v 0.088003 0.084250 0.020000 -vn -0.318859 0.552292 -0.770261 -v 0.085903 0.122884 0.020000 -vn -0.637727 -0.000002 -0.770263 -v 0.085253 0.081750 0.020000 -vn -0.552288 -0.318866 -0.770261 -v 0.085119 0.082250 0.020000 -vn -0.318865 0.552288 -0.770262 -v 0.084753 0.080884 0.020000 -vn -0.552289 0.318864 -0.770262 -v 0.085119 0.081250 0.020000 -vn 0.808998 -0.587772 0.006827 -v 0.087048 0.081311 0.020000 -vn 0.951034 -0.309011 0.006827 -v 0.087758 0.082705 0.020000 -vn 0.552288 0.318865 -0.770262 -v 0.064887 0.081250 0.020000 -vn 0.318865 0.552288 -0.770261 -v 0.065253 0.080884 0.020000 -vn -0.309008 -0.951035 0.006827 -v 0.065458 0.079495 0.020000 -vn -0.000000 0.637727 -0.770263 -v 0.065753 0.080750 0.020000 -vn -0.318865 0.552288 -0.770261 -v 0.066253 0.080884 0.020000 -vn -0.552288 0.318865 -0.770262 -v 0.066619 0.081250 0.020000 -vn 0.637727 0.000000 -0.770263 -v 0.083253 0.081750 0.020000 -vn -0.637727 -0.000000 -0.770263 -v 0.066753 0.081750 0.020000 -vn -0.552288 -0.318865 -0.770262 -v 0.066619 0.082250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.064253 0.128125 0.047000 -vn 0.000000 0.382683 0.923880 -v 0.064253 0.128250 0.047000 -vn -0.630263 0.297108 0.717284 -v 0.063753 0.128250 0.047000 -vn -0.090326 -0.003465 0.995906 -v 0.063503 0.084250 0.047000 -vn -0.077894 -0.400395 0.913026 -v 0.063542 0.083728 0.047000 -vn 0.000000 -0.406420 0.913686 -v 0.064253 0.083728 0.047000 -vn -0.608676 0.173332 0.774254 -v 0.065003 0.121778 0.047000 -vn -0.615305 0.619634 0.487292 -v 0.065049 0.121852 0.047000 -vn 0.052066 0.336739 0.940157 -v 0.064373 0.121814 0.047000 -vn -0.000001 -0.637726 0.770264 -v 0.088503 0.122750 0.047000 -vn -0.318869 -0.552286 0.770262 -v 0.089128 0.122582 0.047000 -vn 0.000000 0.000000 1.000000 -v 0.089878 0.124125 0.047000 -vn 0.000000 -0.707107 0.707107 -v 0.089878 0.118250 0.047000 -vn -0.318867 0.552288 0.770261 -v 0.089128 0.120417 0.047000 -vn 0.185743 -0.131340 0.973781 -v 0.088003 0.118250 0.047000 -vn -0.000001 0.637725 0.770264 -v 0.088503 0.120250 0.047000 -vn 0.318866 0.552288 0.770261 -v 0.087878 0.120417 0.047000 -vn 0.552288 0.318866 0.770261 -v 0.087421 0.120875 0.047000 -vn 0.809971 0.229381 0.539751 -v 0.085003 0.121841 0.047000 -vn 0.637725 -0.000002 0.770264 -v 0.087253 0.121500 0.047000 -vn -0.552291 -0.318867 0.770259 -v 0.089586 0.122125 0.047000 -vn -0.637725 -0.000002 0.770264 -v 0.089753 0.121500 0.047000 -vn -0.552288 0.318866 0.770261 -v 0.089586 0.120875 0.047000 -vn -0.322853 -0.085435 0.942585 -v 0.087313 0.124141 0.047000 -vn -0.357003 0.003457 0.934097 -v 0.087350 0.123857 0.047000 -vn 0.318868 -0.552286 0.770262 -v 0.087878 0.122582 0.047000 -vn -0.305755 0.147418 0.940628 -v 0.087148 0.122879 0.047000 -vn 0.552291 -0.318867 0.770259 -v 0.087421 0.122125 0.047000 -vn -0.193451 0.279981 0.940312 -v 0.086488 0.122130 0.047000 -vn -0.039746 0.340987 0.939228 -v 0.085545 0.121805 0.047000 -vn 0.000000 0.707107 0.707107 -v 0.089878 0.124750 0.047000 -vn 0.185743 0.131340 0.973781 -v 0.088003 0.124750 0.047000 -vn -0.280917 -0.197233 0.939247 -v 0.087042 0.124806 0.047000 -vn 0.408249 0.408247 0.816497 -v 0.088003 0.126250 0.047000 -vn -0.152299 -0.299944 0.941721 -v 0.086304 0.125479 0.047000 -vn 0.131339 0.185742 0.973781 -v 0.086253 0.126250 0.047000 -vn -0.000000 -0.637725 0.770264 -v 0.083003 0.128000 0.047000 -vn -0.318865 -0.552291 0.770260 -v 0.083628 0.127832 0.047000 -vn 0.707107 0.000000 0.707107 -v 0.086253 0.128125 0.047000 -vn -0.552286 -0.318865 0.770263 -v 0.084086 0.127375 0.047000 -vn -0.637729 -0.000000 0.770261 -v 0.084253 0.126750 0.047000 -vn -0.552291 0.318862 0.770261 -v 0.084086 0.126125 0.047000 -vn -0.318861 0.552286 0.770265 -v 0.083628 0.125667 0.047000 -vn -0.000000 0.637732 0.770258 -v 0.083003 0.125500 0.047000 -vn 0.286743 -0.156016 0.945218 -v 0.083690 0.124682 0.047000 -vn 0.342077 -0.015343 0.939547 -v 0.083453 0.123712 0.047000 -vn 0.318861 0.552287 0.770265 -v 0.082378 0.125667 0.047000 -vn 0.552291 0.318862 0.770261 -v 0.081921 0.126125 0.047000 -vn -0.131339 0.185742 0.973781 -v 0.079753 0.126250 0.047000 -vn 0.637728 0.000000 0.770261 -v 0.081753 0.126750 0.047000 -vn -0.707107 0.000000 0.707107 -v 0.079753 0.128125 0.047000 -vn 0.552286 -0.318865 0.770263 -v 0.081921 0.127375 0.047000 -vn 0.318865 -0.552291 0.770260 -v 0.082378 0.127832 0.047000 -vn 0.178875 -0.280569 0.943019 -v 0.084376 0.125407 0.047000 -vn 0.015660 -0.334883 0.942130 -v 0.085331 0.125699 0.047000 -vn 0.232771 0.818505 0.525230 -v 0.083518 0.123250 0.047000 -vn 0.000000 0.707107 0.707107 -v 0.075003 0.123250 0.047000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.124125 0.047000 -vn -0.157466 0.622391 0.766703 -v 0.066577 0.123250 0.047000 -vn -0.343554 -0.035311 0.938469 -v 0.066550 0.123865 0.047000 -vn -0.588698 0.661093 0.465178 -v 0.066472 0.123193 0.047000 -vn 0.000000 0.382682 0.923880 -v 0.075003 0.126250 0.047000 -vn 0.131339 0.185742 0.973781 -v 0.070253 0.126250 0.047000 -vn 0.637729 0.000000 0.770261 -v 0.065753 0.126750 0.047000 -vn 0.552286 -0.318865 0.770263 -v 0.065921 0.127375 0.047000 -vn 0.318865 -0.552291 0.770260 -v 0.066378 0.127832 0.047000 -vn -0.637725 0.000000 0.770264 -v 0.068253 0.126750 0.047000 -vn -0.552286 -0.318869 0.770262 -v 0.068086 0.127375 0.047000 -vn 0.707107 0.000000 0.707107 -v 0.070253 0.128125 0.047000 -vn -0.318865 -0.552291 0.770260 -v 0.067628 0.127832 0.047000 -vn -0.000000 -0.637725 0.770264 -v 0.067003 0.128000 0.047000 -vn -0.297108 0.630263 0.717284 -v 0.060003 0.124750 0.047000 -vn -0.382683 0.000000 0.923880 -v 0.060003 0.124125 0.047000 -vn -0.185743 0.131340 0.973781 -v 0.062003 0.124750 0.047000 -vn 0.299507 -0.094216 0.949431 -v 0.062692 0.124140 0.047000 -vn -0.408249 0.408247 0.816497 -v 0.062003 0.126250 0.047000 -vn 0.279929 -0.183411 0.942338 -v 0.062954 0.124791 0.047000 -vn 0.176213 -0.289299 0.940880 -v 0.063662 0.125458 0.047000 -vn -0.131339 0.185742 0.973781 -v 0.063753 0.126250 0.047000 -vn 0.073530 -0.316745 0.945656 -v 0.064239 0.125666 0.047000 -vn -0.707107 0.000000 0.707107 -v 0.063753 0.128125 0.047000 -vn 0.318865 0.552291 0.770260 -v 0.060878 0.120417 0.047000 -vn -0.297108 -0.630263 0.717284 -v 0.060003 0.118250 0.047000 -vn 0.000000 0.637725 0.770264 -v 0.061503 0.120250 0.047000 -vn -0.185742 -0.131340 0.973781 -v 0.062003 0.118250 0.047000 -vn -0.318865 0.552291 0.770260 -v 0.062128 0.120417 0.047000 -vn -0.552286 0.318864 0.770264 -v 0.062586 0.120875 0.047000 -vn 0.552286 0.318866 0.770263 -v 0.060421 0.120875 0.047000 -vn 0.637727 -0.000002 0.770263 -v 0.060253 0.121500 0.047000 -vn -0.637728 -0.000002 0.770261 -v 0.062753 0.121500 0.047000 -vn -0.552288 -0.318864 0.770262 -v 0.062586 0.122125 0.047000 -vn 0.203069 0.270853 0.940958 -v 0.063466 0.122165 0.047000 -vn -0.318867 -0.552288 0.770261 -v 0.062128 0.122582 0.047000 -vn 0.552288 -0.318866 0.770261 -v 0.060421 0.122125 0.047000 -vn 0.318867 -0.552288 0.770261 -v 0.060878 0.122582 0.047000 -vn -0.000000 -0.637725 0.770264 -v 0.061503 0.122750 0.047000 -vn 0.356521 0.003689 0.934280 -v 0.062656 0.123865 0.047000 -vn 0.307206 0.139688 0.941335 -v 0.062843 0.122911 0.047000 -vn -0.707107 0.000000 0.707107 -v 0.065003 0.117500 0.047000 -vn 0.000000 0.000000 1.000000 -v 0.064253 0.117500 0.047000 -vn -0.707107 0.000000 0.707107 -v 0.065003 0.109500 0.047000 -vn 0.000000 0.000000 1.000000 -v 0.064253 0.109500 0.047000 -vn -0.707107 -0.000000 0.707107 -v 0.065003 0.101500 0.047000 -vn 0.000000 0.000000 1.000000 -v 0.064253 0.101500 0.047000 -vn -0.810973 -0.237789 0.534583 -v 0.065003 0.083728 0.047000 -vn -0.064243 -0.040621 0.997107 -v 0.063503 0.092750 0.047000 -vn -0.185742 0.131340 0.973781 -v 0.062003 0.100750 0.047000 -vn -0.318863 -0.552289 0.770262 -v 0.062128 0.098582 0.047000 -vn -0.552289 -0.318863 0.770262 -v 0.062586 0.098125 0.047000 -vn -0.637729 -0.000000 0.770261 -v 0.062753 0.097500 0.047000 -vn -0.297109 -0.630263 0.717284 -v 0.062003 0.092750 0.047000 -vn -0.185742 -0.131340 0.973781 -v 0.062003 0.094250 0.047000 -vn -0.552289 0.318863 0.770262 -v 0.062586 0.096875 0.047000 -vn -0.297108 0.630263 0.717284 -v 0.060003 0.100750 0.047000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.098582 0.047000 -vn 0.000000 -0.637729 0.770261 -v 0.061503 0.098750 0.047000 -vn -0.318863 0.552289 0.770262 -v 0.062128 0.096417 0.047000 -vn -0.000000 0.637728 0.770261 -v 0.061503 0.096250 0.047000 -vn -0.297108 -0.630262 0.717284 -v 0.060003 0.094250 0.047000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.096417 0.047000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.096875 0.047000 -vn 0.637727 -0.000000 0.770263 -v 0.060253 0.097500 0.047000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.098125 0.047000 -vn -0.185742 0.131340 0.973781 -v 0.062003 0.108750 0.047000 -vn -0.297108 0.630262 0.717284 -v 0.060003 0.108750 0.047000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.106582 0.047000 -vn 0.000000 -0.637728 0.770261 -v 0.061503 0.106750 0.047000 -vn -0.318863 -0.552289 0.770262 -v 0.062128 0.106582 0.047000 -vn -0.552289 -0.318863 0.770262 -v 0.062586 0.106125 0.047000 -vn -0.637729 -0.000000 0.770261 -v 0.062753 0.105500 0.047000 -vn -0.552289 0.318863 0.770262 -v 0.062586 0.104875 0.047000 -vn -0.185742 -0.131340 0.973781 -v 0.062003 0.102250 0.047000 -vn -0.382683 0.000000 0.923880 -v 0.062003 0.101500 0.047000 -vn -0.318863 0.552289 0.770262 -v 0.062128 0.104417 0.047000 -vn -0.000000 0.637728 0.770261 -v 0.061503 0.104250 0.047000 -vn -0.297108 -0.630263 0.717284 -v 0.060003 0.102250 0.047000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.104417 0.047000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.104875 0.047000 -vn 0.637727 -0.000000 0.770263 -v 0.060253 0.105500 0.047000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.106125 0.047000 -vn -0.185742 0.131340 0.973781 -v 0.062003 0.116750 0.047000 -vn -0.297108 0.630262 0.717284 -v 0.060003 0.116750 0.047000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.114582 0.047000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.112417 0.047000 -vn -0.297108 -0.630263 0.717284 -v 0.060003 0.110250 0.047000 -vn -0.000000 0.637728 0.770261 -v 0.061503 0.112250 0.047000 -vn -0.185742 -0.131340 0.973781 -v 0.062003 0.110250 0.047000 -vn -0.318863 0.552289 0.770262 -v 0.062128 0.112417 0.047000 -vn -0.552289 0.318863 0.770262 -v 0.062586 0.112875 0.047000 -vn -0.382683 0.000000 0.923880 -v 0.062003 0.117500 0.047000 -vn 0.000000 -0.637728 0.770261 -v 0.061503 0.114750 0.047000 -vn -0.318863 -0.552289 0.770262 -v 0.062128 0.114582 0.047000 -vn -0.552289 -0.318863 0.770262 -v 0.062586 0.114125 0.047000 -vn -0.637729 -0.000000 0.770261 -v 0.062753 0.113500 0.047000 -vn -0.382683 0.000000 0.923880 -v 0.062003 0.109500 0.047000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.112875 0.047000 -vn 0.637727 -0.000000 0.770263 -v 0.060253 0.113500 0.047000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.114125 0.047000 -vn -0.552291 0.318865 0.770260 -v 0.068086 0.126125 0.047000 -vn -0.318861 0.552286 0.770265 -v 0.067628 0.125667 0.047000 -vn -0.000000 0.637732 0.770258 -v 0.067003 0.125500 0.047000 -vn -0.280809 -0.183371 0.942084 -v 0.066252 0.124791 0.047000 -vn 0.318861 0.552286 0.770265 -v 0.066378 0.125667 0.047000 -vn -0.158357 -0.287249 0.944675 -v 0.065544 0.125458 0.047000 -vn 0.552291 0.318862 0.770261 -v 0.065921 0.126125 0.047000 -vn -0.025414 -0.345284 0.938154 -v 0.064603 0.125700 0.047000 -vn 0.630263 0.297108 0.717284 -v 0.070253 0.128250 0.047000 -vn 0.630263 0.297108 0.717284 -v 0.086253 0.128250 0.047000 -vn -0.630263 0.297108 0.717284 -v 0.079753 0.128250 0.047000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.124750 0.047000 -vn 0.382683 0.000000 0.923880 -v 0.090003 0.124125 0.047000 -vn 0.297108 -0.630263 0.717284 -v 0.090003 0.118250 0.047000 -vn 0.318864 -0.552286 0.770264 -v 0.087878 0.114582 0.047000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.114750 0.047000 -vn 0.707107 0.000000 0.707107 -v 0.085003 0.117500 0.047000 -vn 0.000000 0.707107 0.707107 -v 0.089878 0.116750 0.047000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.114125 0.047000 -vn -0.637725 0.000000 0.770264 -v 0.089753 0.113500 0.047000 -vn 0.185743 -0.131340 0.973781 -v 0.088003 0.110250 0.047000 -vn 0.000000 -0.707107 0.707107 -v 0.089878 0.110250 0.047000 -vn -0.552291 0.318865 0.770260 -v 0.089586 0.112875 0.047000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.112417 0.047000 -vn 0.707107 0.000000 0.707107 -v 0.085003 0.109500 0.047000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.112250 0.047000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.112417 0.047000 -vn 0.382684 0.000000 0.923879 -v 0.088003 0.117500 0.047000 -vn 0.185743 0.131340 0.973781 -v 0.088003 0.116750 0.047000 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.114582 0.047000 -vn 0.552291 0.318865 0.770260 -v 0.087421 0.112875 0.047000 -vn 0.637725 -0.000000 0.770264 -v 0.087253 0.113500 0.047000 -vn 0.552291 -0.318865 0.770260 -v 0.087421 0.114125 0.047000 -vn 0.297108 -0.630262 0.717284 -v 0.090003 0.110250 0.047000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.116750 0.047000 -vn 0.318864 -0.552286 0.770264 -v 0.087878 0.106582 0.047000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.106750 0.047000 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.106582 0.047000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.106125 0.047000 -vn 0.000000 0.707107 0.707107 -v 0.089878 0.108750 0.047000 -vn -0.637725 0.000000 0.770264 -v 0.089753 0.105500 0.047000 -vn 0.185743 -0.131340 0.973781 -v 0.088003 0.102250 0.047000 -vn 0.000000 -0.707107 0.707107 -v 0.089878 0.102250 0.047000 -vn -0.552291 0.318865 0.770260 -v 0.089586 0.104875 0.047000 -vn 0.185743 0.131340 0.973781 -v 0.088003 0.108750 0.047000 -vn 0.382684 0.000000 0.923879 -v 0.088003 0.109500 0.047000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.104417 0.047000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.104250 0.047000 -vn 0.707107 0.000000 0.707107 -v 0.085003 0.101500 0.047000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.104417 0.047000 -vn 0.552291 0.318865 0.770260 -v 0.087421 0.104875 0.047000 -vn 0.637725 -0.000000 0.770264 -v 0.087253 0.105500 0.047000 -vn 0.552291 -0.318865 0.770260 -v 0.087421 0.106125 0.047000 -vn 0.297108 -0.630262 0.717284 -v 0.090003 0.102250 0.047000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.108750 0.047000 -vn 0.318864 -0.552286 0.770264 -v 0.087878 0.098582 0.047000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.098750 0.047000 -vn 0.064243 -0.040621 0.997107 -v 0.086503 0.092750 0.047000 -vn 0.297109 -0.630262 0.717283 -v 0.088003 0.092750 0.047000 -vn 0.185743 -0.131340 0.973781 -v 0.088003 0.094250 0.047000 -vn 0.018718 -0.379337 0.925069 -v 0.086460 0.083700 0.047000 -vn 0.084938 0.004468 0.996376 -v 0.086503 0.084250 0.047000 -vn 0.804188 -0.227460 0.549130 -v 0.085003 0.083700 0.047000 -vn -0.552291 0.318865 0.770260 -v 0.089586 0.096875 0.047000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.096417 0.047000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.096250 0.047000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.096417 0.047000 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.098582 0.047000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.098125 0.047000 -vn 0.000000 0.707107 0.707107 -v 0.089878 0.100750 0.047000 -vn -0.637725 0.000000 0.770264 -v 0.089753 0.097500 0.047000 -vn 0.000000 -0.707107 0.707107 -v 0.089878 0.094250 0.047000 -vn 0.552291 0.318865 0.770260 -v 0.087421 0.096875 0.047000 -vn 0.637725 -0.000000 0.770264 -v 0.087253 0.097500 0.047000 -vn 0.552291 -0.318865 0.770260 -v 0.087421 0.098125 0.047000 -vn 0.185743 0.131340 0.973781 -v 0.088003 0.100750 0.047000 -vn 0.382684 0.000000 0.923879 -v 0.088003 0.101500 0.047000 -vn 0.297108 -0.630262 0.717284 -v 0.090003 0.094250 0.047000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.100750 0.047000 -vn 0.458748 0.726534 0.511565 -v 0.085003 0.121846 0.046995 -vn 0.884569 0.331545 0.328047 -v 0.085003 0.121846 0.049800 -vn 0.630263 -0.717284 0.297105 -v 0.085003 0.083500 0.047050 -vn 0.131341 -0.973782 0.185739 -v 0.085003 0.083500 0.046800 -vn 0.630262 -0.297112 0.717282 -v 0.085003 0.083700 0.047250 -vn 0.973781 -0.185742 0.131341 -v 0.085003 0.099700 0.047250 -vn 0.875580 -0.341587 0.341582 -v 0.085003 0.099700 0.049800 -vn 0.329651 0.886093 0.325836 -v 0.083526 0.123250 0.049800 -vn 0.700477 0.484972 0.523578 -v 0.083526 0.123250 0.046993 -vn -0.197161 0.921917 0.333461 -v 0.066577 0.123250 0.049800 -vn -0.229246 0.253757 0.939709 -v 0.065944 0.122334 0.050000 -vn -0.449474 0.276500 0.849424 -v 0.065203 0.121895 0.050000 -vn -0.341589 -0.341589 0.875576 -v 0.065203 0.099700 0.050000 -vn 0.170272 -0.319830 0.932049 -v 0.069601 0.100846 0.050000 -vn 0.105140 -0.346276 0.932222 -v 0.071676 0.101706 0.050000 -vn 0.243753 0.242884 0.938931 -v 0.084062 0.122334 0.050000 -vn 0.035502 -0.360145 0.932221 -v 0.073880 0.102145 0.050000 -vn -0.035503 -0.360144 0.932221 -v 0.076126 0.102145 0.050000 -vn 0.438784 0.296916 0.848121 -v 0.084803 0.121895 0.050000 -vn 0.290139 0.453575 0.842668 -v 0.083583 0.123050 0.050000 -vn -0.268927 0.463104 0.844520 -v 0.066423 0.123050 0.050000 -vn 0.118991 -0.408565 0.904940 -v 0.067862 0.099700 0.050000 -vn -0.119734 -0.408625 0.904814 -v 0.082144 0.099700 0.050000 -vn 0.341589 -0.341589 0.875576 -v 0.084803 0.099700 0.050000 -vn -0.169991 -0.320347 0.931923 -v 0.080405 0.100846 0.050000 -vn -0.105140 -0.346276 0.932222 -v 0.078330 0.101706 0.050000 -vn 0.110049 -0.987815 0.110050 -v 0.082303 0.079250 0.045300 -vn 0.067779 -0.924496 0.375119 -v 0.083003 0.079250 0.045300 -vn -0.067148 -0.924212 0.375929 -v 0.067003 0.079250 0.045300 -vn -0.110048 -0.987815 0.110048 -v 0.067703 0.079250 0.045300 -vn -0.370185 -0.921352 0.118633 -v 0.067703 0.079250 0.045750 -vn 0.370194 -0.921348 0.118633 -v 0.082303 0.079250 0.045750 -vn 0.227458 -0.549133 0.804186 -v 0.084803 0.099500 0.047250 -vn 0.044033 -0.353787 0.934289 -v 0.084253 0.083700 0.047250 -vn -0.162202 0.658078 0.735271 -v 0.077181 0.081914 0.047250 -vn 0.000000 0.677774 0.735271 -v 0.075003 0.081650 0.047250 -vn 0.353788 -0.044032 0.934289 -v 0.082303 0.081750 0.047250 -vn 0.180496 -0.602022 0.777812 -v 0.067932 0.099500 0.047250 -vn 0.449447 -0.507321 0.735271 -v 0.068969 0.097561 0.047250 -vn 0.339063 -0.644140 0.685653 -v 0.069753 0.100700 0.047250 -vn 0.314977 -0.600139 0.735271 -v 0.070774 0.098808 0.047250 -vn 0.209153 -0.697355 0.685529 -v 0.071772 0.101526 0.047250 -vn 0.162202 -0.658079 0.735271 -v 0.072825 0.099586 0.047250 -vn 0.070713 -0.724414 0.685729 -v 0.073912 0.101947 0.047250 -vn 0.000000 -0.677774 0.735271 -v 0.075003 0.099850 0.047250 -vn -0.070313 -0.724270 0.685922 -v 0.076094 0.101947 0.047250 -vn -0.208638 -0.696941 0.686108 -v 0.078234 0.101526 0.047250 -vn 0.162202 0.658079 0.735271 -v 0.072825 0.081914 0.047250 -vn 0.314977 0.600139 0.735271 -v 0.070774 0.082692 0.047250 -vn -0.282131 -0.162889 0.945447 -v 0.067442 0.082725 0.047250 -vn 0.449446 0.507322 0.735271 -v 0.068969 0.083938 0.047250 -vn -0.162889 -0.282134 0.945446 -v 0.066728 0.083439 0.047250 -vn 0.557796 0.385019 0.735271 -v 0.067514 0.085581 0.047250 -vn -0.044032 -0.353788 0.934289 -v 0.065753 0.083700 0.047250 -vn 0.633729 0.240342 0.735271 -v 0.066494 0.087523 0.047250 -vn 0.672832 0.081697 0.735271 -v 0.065969 0.089653 0.047250 -vn -0.227458 -0.549133 0.804186 -v 0.065203 0.099500 0.047250 -vn -0.630262 -0.297113 0.717282 -v 0.065003 0.083700 0.047250 -vn -0.973781 -0.185743 0.131338 -v 0.065003 0.099700 0.047250 -vn 0.672832 -0.081697 0.735271 -v 0.065969 0.091847 0.047250 -vn 0.633729 -0.240342 0.735271 -v 0.066494 0.093977 0.047250 -vn 0.557797 -0.385019 0.735271 -v 0.067514 0.095919 0.047250 -vn -0.353779 -0.044032 0.934292 -v 0.067703 0.081750 0.047250 -vn -0.370189 -0.118635 0.921350 -v 0.067703 0.080750 0.047250 -vn 0.370197 -0.118635 0.921347 -v 0.082303 0.080750 0.047250 -vn -0.672832 0.081696 0.735271 -v 0.084037 0.089653 0.047250 -vn -0.633729 0.240342 0.735271 -v 0.083512 0.087523 0.047250 -vn 0.162888 -0.282130 0.945447 -v 0.083278 0.083439 0.047250 -vn -0.557798 0.385019 0.735270 -v 0.082492 0.085581 0.047250 -vn 0.282130 -0.162888 0.945447 -v 0.082564 0.082725 0.047250 -vn -0.449447 0.507319 0.735272 -v 0.081037 0.083938 0.047250 -vn -0.314977 0.600139 0.735270 -v 0.079232 0.082692 0.047250 -vn -0.162202 -0.658078 0.735271 -v 0.077181 0.099586 0.047250 -vn -0.180799 -0.601629 0.778045 -v 0.082074 0.099500 0.047250 -vn -0.339068 -0.643461 0.686287 -v 0.080253 0.100700 0.047250 -vn -0.314977 -0.600139 0.735270 -v 0.079232 0.098808 0.047250 -vn -0.449447 -0.507320 0.735271 -v 0.081037 0.097561 0.047250 -vn -0.557797 -0.385019 0.735270 -v 0.082492 0.095919 0.047250 -vn -0.633729 -0.240342 0.735271 -v 0.083512 0.093977 0.047250 -vn -0.672832 -0.081696 0.735271 -v 0.084037 0.091847 0.047250 -vn 0.266628 -0.889762 0.370451 -v 0.084447 0.079463 0.045300 -vn 0.464446 -0.802097 0.375408 -v 0.085768 0.080084 0.045300 -vn 0.582389 -0.711808 0.392622 -v 0.085942 0.080205 0.045300 -vn 0.685727 -0.623803 0.375031 -v 0.086853 0.081060 0.045300 -vn 0.765886 -0.503029 0.400476 -v 0.087048 0.081311 0.045300 -vn 0.840819 -0.390449 0.374930 -v 0.087610 0.082307 0.045300 -vn 0.880317 -0.258902 0.397507 -v 0.087758 0.082705 0.045300 -vn 0.995705 -0.028548 0.088068 -v 0.088003 0.084250 0.045500 -vn 0.900884 -0.426411 0.081123 -v 0.087970 0.083677 0.045500 -vn 0.969823 -0.226905 0.089208 -v 0.087970 0.083677 0.045300 -vn 0.904534 0.301511 -0.301511 -v 0.091003 0.095500 0.045000 -vn -0.552291 0.318865 -0.770260 -v 0.089586 0.096875 0.045000 -vn -0.637725 -0.000000 -0.770264 -v 0.089753 0.097500 0.045000 -vn 0.792406 0.000001 -0.609994 -v 0.086194 0.097500 0.045000 -vn 0.637725 0.000000 -0.770264 -v 0.087253 0.097500 0.045000 -vn 0.552291 0.318865 -0.770260 -v 0.087421 0.096875 0.045000 -vn 0.904534 -0.301511 -0.301511 -v 0.091003 0.099500 0.045000 -vn -0.552291 -0.318866 -0.770260 -v 0.089586 0.098125 0.045000 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.098582 0.045000 -vn 0.396204 -0.686243 -0.609994 -v 0.087348 0.099500 0.045000 -vn 0.396203 0.686244 -0.609994 -v 0.087348 0.095500 0.045000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.096417 0.045000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.096250 0.045000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.096417 0.045000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.098750 0.045000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.098582 0.045000 -vn 0.552291 -0.318865 -0.770260 -v 0.087421 0.098125 0.045000 -vn 0.396203 -0.686243 -0.609995 -v 0.087348 0.107500 0.045000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.106582 0.045000 -vn 0.792406 -0.000001 -0.609994 -v 0.086194 0.105500 0.045000 -vn 0.552291 -0.318865 -0.770260 -v 0.087421 0.106125 0.045000 -vn 0.396204 0.686243 -0.609994 -v 0.087348 0.103500 0.045000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.104250 0.045000 -vn 0.904534 0.301511 -0.301511 -v 0.091003 0.103500 0.045000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.104417 0.045000 -vn -0.552291 0.318865 -0.770260 -v 0.089586 0.104875 0.045000 -vn -0.637725 -0.000000 -0.770264 -v 0.089753 0.105500 0.045000 -vn 0.904534 -0.301511 -0.301511 -v 0.091003 0.107500 0.045000 -vn -0.552291 -0.318865 -0.770260 -v 0.089586 0.106125 0.045000 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.106582 0.045000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.106750 0.045000 -vn 0.637725 0.000000 -0.770264 -v 0.087253 0.105500 0.045000 -vn 0.552291 0.318865 -0.770260 -v 0.087421 0.104875 0.045000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.104417 0.045000 -vn 0.396204 0.686243 -0.609994 -v 0.087348 0.111500 0.045000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.112250 0.045000 -vn 0.904534 0.301511 -0.301511 -v 0.091003 0.111500 0.045000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.112417 0.045000 -vn 0.792406 -0.000001 -0.609994 -v 0.086194 0.113500 0.045000 -vn 0.552291 0.318865 -0.770260 -v 0.087421 0.112875 0.045000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.112417 0.045000 -vn -0.552291 0.318865 -0.770260 -v 0.089586 0.112875 0.045000 -vn -0.637725 -0.000000 -0.770264 -v 0.089753 0.113500 0.045000 -vn 0.904534 -0.301511 -0.301511 -v 0.091003 0.115500 0.045000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.114750 0.045000 -vn 0.396203 -0.686243 -0.609995 -v 0.087348 0.115500 0.045000 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.114582 0.045000 -vn -0.552291 -0.318865 -0.770260 -v 0.089586 0.114125 0.045000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.114582 0.045000 -vn 0.552291 -0.318865 -0.770260 -v 0.087421 0.114125 0.045000 -vn 0.637725 0.000000 -0.770264 -v 0.087253 0.113500 0.045000 -vn -0.630262 0.297109 -0.717284 -v 0.063753 0.128250 0.042000 -vn 0.516597 0.427644 -0.741787 -v 0.065003 0.128250 0.042000 -vn -0.301511 0.301511 -0.904534 -v 0.063753 0.127750 0.042000 -vn 0.279911 0.452906 -0.846478 -v 0.066003 0.126250 0.042000 -vn 0.452906 0.279911 -0.846479 -v 0.088003 0.096500 0.042000 -vn 0.427644 0.516597 -0.741787 -v 0.090003 0.095500 0.042000 -vn 0.297109 -0.630262 -0.717284 -v 0.090003 0.094250 0.042000 -vn -0.297108 -0.630263 -0.717284 -v 0.060003 0.094250 0.042000 -vn -0.427643 0.516597 -0.741788 -v 0.060003 0.095500 0.042000 -vn -0.301511 -0.301511 -0.904534 -v 0.060503 0.094250 0.042000 -vn -0.452905 0.279911 -0.846479 -v 0.062003 0.096500 0.042000 -vn -0.297108 -0.630263 -0.717284 -v 0.060003 0.102250 0.042000 -vn -0.427644 0.516596 -0.741788 -v 0.060003 0.103500 0.042000 -vn -0.301511 -0.301511 -0.904534 -v 0.060503 0.102250 0.042000 -vn -0.452906 0.279911 -0.846479 -v 0.062003 0.104500 0.042000 -vn -0.297108 -0.630263 -0.717284 -v 0.060003 0.110250 0.042000 -vn -0.427644 0.516596 -0.741788 -v 0.060003 0.111500 0.042000 -vn -0.301511 -0.301511 -0.904534 -v 0.060503 0.110250 0.042000 -vn -0.452906 0.279911 -0.846479 -v 0.062003 0.112500 0.042000 -vn -0.301511 0.301511 -0.904534 -v 0.060503 0.108750 0.042000 -vn -0.301511 0.301511 -0.904534 -v 0.060503 0.124750 0.042000 -vn -0.577350 0.577350 -0.577351 -v 0.060503 0.126250 0.042000 -vn -0.301512 0.301511 -0.904534 -v 0.062003 0.126250 0.042000 -vn -0.427644 -0.516596 -0.741788 -v 0.060003 0.099500 0.042000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.100750 0.042000 -vn -0.452906 -0.279911 -0.846479 -v 0.062003 0.098500 0.042000 -vn -0.301511 0.301511 -0.904534 -v 0.060503 0.100750 0.042000 -vn -0.452905 -0.279911 -0.846479 -v 0.062003 0.106500 0.042000 -vn -0.427643 -0.516597 -0.741788 -v 0.060003 0.107500 0.042000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.108750 0.042000 -vn -0.301511 -0.301511 -0.904534 -v 0.062003 0.092750 0.042000 -vn 0.427644 0.516596 -0.741787 -v 0.090003 0.119500 0.042000 -vn 0.297109 -0.630262 -0.717284 -v 0.090003 0.118250 0.042000 -vn 0.452907 0.279911 -0.846478 -v 0.088003 0.120500 0.042000 -vn 0.301511 -0.301511 -0.904534 -v 0.089503 0.118250 0.042000 -vn -0.427644 -0.516596 -0.741788 -v 0.060003 0.115500 0.042000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.116750 0.042000 -vn -0.452906 -0.279911 -0.846479 -v 0.062003 0.114500 0.042000 -vn -0.301511 0.301511 -0.904534 -v 0.060503 0.116750 0.042000 -vn -0.452906 0.279911 -0.846479 -v 0.062003 0.120500 0.042000 -vn -0.452906 -0.279911 -0.846479 -v 0.062003 0.122500 0.042000 -vn 0.297109 0.630262 -0.717284 -v 0.090003 0.116750 0.042000 -vn 0.427644 -0.516596 -0.741787 -v 0.090003 0.115500 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.089503 0.116750 0.042000 -vn 0.452906 -0.279911 -0.846478 -v 0.088003 0.114500 0.042000 -vn 0.427644 0.516596 -0.741787 -v 0.090003 0.111500 0.042000 -vn 0.297109 -0.630262 -0.717284 -v 0.090003 0.110250 0.042000 -vn 0.452907 0.279911 -0.846478 -v 0.088003 0.112500 0.042000 -vn 0.301511 -0.301511 -0.904534 -v 0.089503 0.110250 0.042000 -vn 0.297109 0.630262 -0.717284 -v 0.090003 0.108750 0.042000 -vn 0.427644 -0.516597 -0.741787 -v 0.090003 0.107500 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.089503 0.108750 0.042000 -vn 0.452906 -0.279912 -0.846479 -v 0.088003 0.106500 0.042000 -vn -0.577350 -0.577350 -0.577351 -v 0.060503 0.092750 0.042000 -vn -0.297108 -0.630263 -0.717284 -v 0.060003 0.118250 0.042000 -vn -0.427644 0.516596 -0.741788 -v 0.060003 0.119500 0.042000 -vn -0.301511 -0.301511 -0.904534 -v 0.060503 0.118250 0.042000 -vn -0.427644 -0.516596 -0.741788 -v 0.060003 0.123500 0.042000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.124750 0.042000 -vn 0.297109 0.630262 -0.717284 -v 0.090003 0.124750 0.042000 -vn 0.427644 -0.516596 -0.741787 -v 0.090003 0.123500 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.089503 0.124750 0.042000 -vn 0.452907 -0.279911 -0.846478 -v 0.088003 0.122500 0.042000 -vn 0.427644 0.516596 -0.741787 -v 0.090003 0.103500 0.042000 -vn 0.297109 -0.630262 -0.717284 -v 0.090003 0.102250 0.042000 -vn 0.452906 0.279911 -0.846478 -v 0.088003 0.104500 0.042000 -vn 0.301511 -0.301511 -0.904534 -v 0.089503 0.102250 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.089503 0.100750 0.042000 -vn 0.301511 -0.301511 -0.904534 -v 0.089503 0.094250 0.042000 -vn 0.577350 -0.577350 -0.577350 -v 0.089503 0.092750 0.042000 -vn 0.301511 -0.301511 -0.904534 -v 0.088003 0.092750 0.042000 -vn 0.279912 0.452905 -0.846479 -v 0.082003 0.126250 0.042000 -vn -0.279912 0.452905 -0.846479 -v 0.084003 0.126250 0.042000 -vn -0.516597 0.427644 -0.741787 -v 0.069003 0.128250 0.042000 -vn 0.630262 0.297109 -0.717284 -v 0.070253 0.128250 0.042000 -vn -0.279911 0.452906 -0.846478 -v 0.068003 0.126250 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.070253 0.127750 0.042000 -vn -0.301511 0.301511 -0.904534 -v 0.079753 0.127750 0.042000 -vn -0.630262 0.297109 -0.717284 -v 0.079753 0.128250 0.042000 -vn 0.516598 0.427643 -0.741787 -v 0.081003 0.128250 0.042000 -vn -0.577350 0.577350 -0.577350 -v 0.062003 0.127750 0.042000 -vn -0.516598 0.427643 -0.741787 -v 0.085003 0.128250 0.042000 -vn 0.630262 0.297109 -0.717284 -v 0.086253 0.128250 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.086253 0.127750 0.042000 -vn 0.577350 0.577350 -0.577350 -v 0.088003 0.127750 0.042000 -vn 0.577350 0.577350 -0.577350 -v 0.089503 0.126250 0.042000 -vn 0.301511 0.301511 -0.904534 -v 0.088003 0.126250 0.042000 -vn 0.452907 -0.279911 -0.846478 -v 0.088003 0.098500 0.042000 -vn 0.427644 -0.516596 -0.741787 -v 0.090003 0.099500 0.042000 -vn 0.297109 0.630262 -0.717284 -v 0.090003 0.100750 0.042000 -vn 0.113763 -0.990667 0.075085 -v 0.090003 0.099500 0.043500 -vn 0.396204 -0.686243 0.609994 -v 0.087348 0.099500 0.043500 -vn 0.452906 -0.279911 0.846478 -v 0.088003 0.098500 0.043500 -vn 0.792406 0.000001 0.609994 -v 0.086194 0.097500 0.043500 -vn 0.452906 0.279912 0.846479 -v 0.088003 0.096500 0.043500 -vn 0.396203 0.686244 0.609994 -v 0.087348 0.095500 0.043500 -vn 0.113762 0.990667 0.075085 -v 0.090003 0.095500 0.043500 -vn 0.113762 -0.990667 0.075085 -v 0.090003 0.107500 0.043500 -vn 0.396203 -0.686243 0.609994 -v 0.087348 0.107500 0.043500 -vn 0.452906 -0.279911 0.846479 -v 0.088003 0.106500 0.043500 -vn 0.792406 -0.000001 0.609994 -v 0.086194 0.105500 0.043500 -vn 0.452907 0.279911 0.846478 -v 0.088003 0.104500 0.043500 -vn 0.396204 0.686243 0.609994 -v 0.087348 0.103500 0.043500 -vn 0.113763 0.990667 0.075085 -v 0.090003 0.103500 0.043500 -vn 0.113763 -0.990667 0.075085 -v 0.090003 0.115500 0.043500 -vn 0.396203 -0.686243 0.609994 -v 0.087348 0.115500 0.043500 -vn 0.452907 -0.279911 0.846478 -v 0.088003 0.114500 0.043500 -vn 0.792406 -0.000001 0.609994 -v 0.086194 0.113500 0.043500 -vn 0.452907 0.279911 0.846478 -v 0.088003 0.112500 0.043500 -vn 0.396204 0.686243 0.609994 -v 0.087348 0.111500 0.043500 -vn 0.113763 0.990667 0.075085 -v 0.090003 0.111500 0.043500 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.099500 0.043000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.100750 0.043000 -vn 0.717283 0.630262 0.297109 -v 0.091003 0.100750 0.046000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.094250 0.046000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.095500 0.043000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.094250 0.043000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.107500 0.043000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.108750 0.043000 -vn 0.717283 0.630262 0.297109 -v 0.091003 0.108750 0.046000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.102250 0.046000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.103500 0.043000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.102250 0.043000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.115500 0.043000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.116750 0.043000 -vn 0.717283 0.630262 0.297109 -v 0.091003 0.116750 0.046000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.110250 0.046000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.111500 0.043000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.110250 0.043000 -vn 0.396204 0.686243 -0.609994 -v 0.087348 0.119500 0.045000 -vn -0.000001 0.637725 -0.770264 -v 0.088503 0.120250 0.045000 -vn 0.904534 0.301511 -0.301511 -v 0.091003 0.119500 0.045000 -vn -0.318867 0.552288 -0.770261 -v 0.089128 0.120417 0.045000 -vn 0.396203 -0.686244 -0.609994 -v 0.087348 0.123500 0.045000 -vn 0.904534 -0.301511 -0.301511 -v 0.091003 0.123500 0.045000 -vn -0.318869 -0.552286 -0.770262 -v 0.089128 0.122582 0.045000 -vn 0.552291 -0.318867 -0.770259 -v 0.087421 0.122125 0.045000 -vn 0.792406 -0.000001 -0.609994 -v 0.086194 0.121500 0.045000 -vn 0.318868 -0.552286 -0.770262 -v 0.087878 0.122582 0.045000 -vn -0.000001 -0.637726 -0.770264 -v 0.088503 0.122750 0.045000 -vn 0.637725 -0.000002 -0.770264 -v 0.087253 0.121500 0.045000 -vn 0.552288 0.318866 -0.770261 -v 0.087421 0.120875 0.045000 -vn 0.318866 0.552288 -0.770261 -v 0.087878 0.120417 0.045000 -vn -0.552288 0.318866 -0.770261 -v 0.089586 0.120875 0.045000 -vn -0.637725 -0.000002 -0.770264 -v 0.089753 0.121500 0.045000 -vn -0.552291 -0.318867 -0.770259 -v 0.089586 0.122125 0.045000 -vn 0.301511 0.904534 -0.301511 -v 0.081003 0.129250 0.045000 -vn -0.301511 0.904534 -0.301511 -v 0.085003 0.129250 0.045000 -vn 0.000000 -0.637725 -0.770264 -v 0.083003 0.128000 0.045000 -vn -0.318865 -0.552291 -0.770260 -v 0.083628 0.127832 0.045000 -vn -0.318861 0.552286 -0.770265 -v 0.083628 0.125667 0.045000 -vn -0.686243 0.396204 -0.609994 -v 0.085003 0.125595 0.045000 -vn 0.000000 0.637732 -0.770258 -v 0.083003 0.125500 0.045000 -vn -0.000000 0.792406 -0.609995 -v 0.083003 0.124441 0.045000 -vn 0.318861 0.552286 -0.770265 -v 0.082378 0.125667 0.045000 -vn 0.686243 0.396204 -0.609994 -v 0.081003 0.125595 0.045000 -vn 0.552291 0.318862 -0.770261 -v 0.081921 0.126125 0.045000 -vn 0.318865 -0.552291 -0.770260 -v 0.082378 0.127832 0.045000 -vn 0.552286 -0.318865 -0.770263 -v 0.081921 0.127375 0.045000 -vn 0.637729 -0.000000 -0.770261 -v 0.081753 0.126750 0.045000 -vn -0.552291 0.318862 -0.770261 -v 0.084086 0.126125 0.045000 -vn -0.637728 0.000000 -0.770261 -v 0.084253 0.126750 0.045000 -vn -0.552286 -0.318865 -0.770263 -v 0.084086 0.127375 0.045000 -vn 0.113763 -0.990667 0.075085 -v 0.090003 0.123500 0.043500 -vn 0.396203 -0.686243 0.609994 -v 0.087348 0.123500 0.043500 -vn 0.452907 -0.279911 0.846478 -v 0.088003 0.122500 0.043500 -vn 0.792406 -0.000001 0.609994 -v 0.086194 0.121500 0.043500 -vn 0.452907 0.279911 0.846478 -v 0.088003 0.120500 0.043500 -vn 0.396204 0.686243 0.609994 -v 0.087348 0.119500 0.043500 -vn 0.113763 0.990667 0.075085 -v 0.090003 0.119500 0.043500 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.123500 0.043000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.124750 0.043000 -vn 0.717283 0.630262 0.297109 -v 0.091003 0.124750 0.046000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.118250 0.046000 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.119500 0.043000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.118250 0.043000 -vn 0.279912 0.452905 0.846479 -v 0.082003 0.126250 0.043500 -vn 0.990667 0.113762 0.075084 -v 0.081003 0.128250 0.043500 -vn 0.686243 0.396204 0.609994 -v 0.081003 0.125595 0.043500 -vn -0.686243 0.396204 0.609994 -v 0.085003 0.125595 0.043500 -vn -0.990667 0.113762 0.075084 -v 0.085003 0.128250 0.043500 -vn -0.279912 0.452905 0.846479 -v 0.084003 0.126250 0.043500 -vn 0.000000 0.792406 0.609995 -v 0.083003 0.124441 0.043500 -vn 0.630262 0.717284 -0.297109 -v 0.081003 0.129250 0.043000 -vn -0.630262 0.717284 -0.297109 -v 0.079753 0.129250 0.043000 -vn -0.630262 0.717283 0.297109 -v 0.079753 0.129250 0.046000 -vn 0.630262 0.717283 0.297109 -v 0.086253 0.129250 0.046000 -vn -0.630262 0.717284 -0.297109 -v 0.085003 0.129250 0.043000 -vn 0.630262 0.717284 -0.297109 -v 0.086253 0.129250 0.043000 -vn -0.670430 -0.736841 0.087121 -v 0.062003 0.092750 0.045500 -vn -0.996447 -0.019683 0.081891 -v 0.062003 0.084250 0.045500 -vn 0.670430 -0.736840 0.087121 -v 0.088003 0.092750 0.045500 -vn 0.717284 -0.630263 0.297108 -v 0.089503 0.092750 0.045500 -vn 0.554222 -0.768479 0.319809 -v 0.087802 0.092750 0.046250 -vn 0.319806 -0.768479 0.554224 -v 0.087253 0.092750 0.046799 -vn 0.549133 -0.804186 0.227458 -v 0.089503 0.094250 0.045500 -vn 0.549133 0.804186 0.227458 -v 0.089503 0.100750 0.045500 -vn 0.549133 -0.804186 0.227458 -v 0.089503 0.102250 0.045500 -vn 0.549133 0.804186 0.227458 -v 0.089503 0.108750 0.045500 -vn 0.549133 -0.804186 0.227458 -v 0.089503 0.110250 0.045500 -vn 0.549133 0.804186 0.227458 -v 0.089503 0.116750 0.045500 -vn 0.549133 -0.804186 0.227458 -v 0.089503 0.118250 0.045500 -vn 0.549133 0.804186 0.227458 -v 0.089503 0.124750 0.045500 -vn 0.717284 0.630263 0.297108 -v 0.089503 0.126250 0.045500 -vn 0.630262 0.717283 0.297110 -v 0.088003 0.127750 0.045500 -vn 0.804187 0.549132 0.227459 -v 0.086253 0.127750 0.045500 -vn -0.804187 0.549132 0.227459 -v 0.079753 0.127750 0.045500 -vn 0.804187 0.549132 0.227459 -v 0.070253 0.127750 0.045500 -vn 0.630262 0.717283 0.297109 -v 0.070253 0.129250 0.046000 -vn 0.630262 0.717284 -0.297109 -v 0.070253 0.129250 0.043000 -vn 0.630262 0.717284 -0.297109 -v 0.065003 0.129250 0.043000 -vn -0.630262 0.717284 -0.297109 -v 0.063753 0.129250 0.043000 -vn 0.301511 0.904534 -0.301511 -v 0.065003 0.129250 0.045000 -vn -0.630262 0.717283 0.297109 -v 0.063753 0.129250 0.046000 -vn -0.301511 0.904534 -0.301511 -v 0.069003 0.129250 0.045000 -vn -0.630262 0.717284 -0.297109 -v 0.069003 0.129250 0.043000 -vn -0.804187 0.549132 0.227459 -v 0.063753 0.127750 0.045500 -vn -0.630263 0.717283 0.297110 -v 0.062003 0.127750 0.045500 -vn -0.717284 0.630262 0.297108 -v 0.060503 0.126250 0.045500 -vn -0.549133 0.804187 0.227458 -v 0.060503 0.124750 0.045500 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.124750 0.043000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.124750 0.046000 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.119500 0.043000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.118250 0.043000 -vn -0.904534 0.301511 -0.301511 -v 0.059003 0.119500 0.045000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.118250 0.046000 -vn -0.904534 -0.301511 -0.301511 -v 0.059003 0.123500 0.045000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.123500 0.043000 -vn -0.549133 -0.804187 0.227458 -v 0.060503 0.118250 0.045500 -vn -0.549133 0.804187 0.227458 -v 0.060503 0.116750 0.045500 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.116750 0.043000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.116750 0.046000 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.111500 0.043000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.110250 0.043000 -vn -0.904534 0.301511 -0.301511 -v 0.059003 0.111500 0.045000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.110250 0.046000 -vn -0.904534 -0.301511 -0.301511 -v 0.059003 0.115500 0.045000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.115500 0.043000 -vn -0.549133 -0.804187 0.227458 -v 0.060503 0.110250 0.045500 -vn -0.549133 0.804187 0.227458 -v 0.060503 0.108750 0.045500 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.108750 0.043000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.108750 0.046000 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.103500 0.043000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.102250 0.043000 -vn -0.904534 0.301511 -0.301511 -v 0.059003 0.103500 0.045000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.102250 0.046000 -vn -0.904534 -0.301511 -0.301511 -v 0.059003 0.107500 0.045000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.107500 0.043000 -vn -0.549133 -0.804187 0.227458 -v 0.060503 0.102250 0.045500 -vn -0.549133 0.804187 0.227458 -v 0.060503 0.100750 0.045500 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.100750 0.043000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.100750 0.046000 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.095500 0.043000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.094250 0.043000 -vn -0.904534 0.301511 -0.301511 -v 0.059003 0.095500 0.045000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.094250 0.046000 -vn -0.904534 -0.301511 -0.301511 -v 0.059003 0.099500 0.045000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.099500 0.043000 -vn -0.549133 -0.804187 0.227458 -v 0.060503 0.094250 0.045500 -vn -0.717284 -0.630262 0.297108 -v 0.060503 0.092750 0.045500 -vn -0.319807 -0.768479 0.554223 -v 0.062753 0.092750 0.046799 -vn -0.554223 -0.768479 0.319808 -v 0.062204 0.092750 0.046250 -vn -0.121938 -0.977022 0.174810 -v 0.065003 0.083500 0.046747 -vn -0.630263 -0.717284 0.297105 -v 0.065003 0.083500 0.047050 -vn -0.915535 0.226220 0.332596 -v 0.065003 0.121778 0.049800 -vn -0.875580 -0.341586 0.341582 -v 0.065003 0.099700 0.049800 -vn -0.341587 -0.875580 0.341582 -v 0.065203 0.099500 0.049800 -vn 0.268839 -0.888586 0.371672 -v 0.067932 0.099500 0.049800 -vn 0.432637 -0.812014 0.391739 -v 0.069696 0.100669 0.049800 -vn 0.267545 -0.880347 0.391674 -v 0.071735 0.101515 0.049800 -vn 0.090445 -0.915764 0.391402 -v 0.073899 0.101946 0.049800 -vn -0.090178 -0.915900 0.391145 -v 0.076107 0.101946 0.049800 -vn -0.267368 -0.880746 0.390898 -v 0.078272 0.101515 0.049800 -vn -0.432392 -0.812381 0.391247 -v 0.080311 0.100669 0.049800 -vn -0.269619 -0.888353 0.371665 -v 0.082074 0.099500 0.049800 -vn 0.341586 -0.875580 0.341582 -v 0.084803 0.099500 0.049800 -vn -0.686243 0.396205 0.609994 -v 0.069003 0.125595 0.043500 -vn -0.686243 0.396204 -0.609994 -v 0.069003 0.125595 0.045000 -vn -0.990667 0.113762 0.075085 -v 0.069003 0.128250 0.043500 -vn 0.000000 -0.637725 -0.770264 -v 0.067003 0.128000 0.045000 -vn -0.318865 -0.552291 -0.770260 -v 0.067628 0.127832 0.045000 -vn 0.637729 -0.000000 -0.770261 -v 0.065753 0.126750 0.045000 -vn 0.686243 0.396204 -0.609994 -v 0.065003 0.125595 0.045000 -vn 0.552286 -0.318865 -0.770263 -v 0.065921 0.127375 0.045000 -vn 0.318865 -0.552291 -0.770260 -v 0.066378 0.127832 0.045000 -vn 0.552291 0.318862 -0.770261 -v 0.065921 0.126125 0.045000 -vn 0.318861 0.552286 -0.770265 -v 0.066378 0.125667 0.045000 -vn 0.000001 0.792405 -0.609995 -v 0.067003 0.124441 0.045000 -vn 0.000000 0.637732 -0.770258 -v 0.067003 0.125500 0.045000 -vn -0.318861 0.552287 -0.770265 -v 0.067628 0.125667 0.045000 -vn -0.552291 0.318865 -0.770260 -v 0.068086 0.126125 0.045000 -vn -0.637725 -0.000000 -0.770264 -v 0.068253 0.126750 0.045000 -vn -0.552286 -0.318869 -0.770262 -v 0.068086 0.127375 0.045000 -vn 0.990667 0.113762 0.075085 -v 0.065003 0.128250 0.043500 -vn 0.686243 0.396204 0.609994 -v 0.065003 0.125595 0.043500 -vn 0.000001 0.792405 0.609995 -v 0.067003 0.124441 0.043500 -vn 0.279911 0.452906 0.846478 -v 0.066003 0.126250 0.043500 -vn -0.279911 0.452906 0.846478 -v 0.068003 0.126250 0.043500 -vn -0.396203 -0.686244 0.609994 -v 0.062658 0.123500 0.043500 -vn -0.396203 -0.686244 -0.609994 -v 0.062658 0.123500 0.045000 -vn -0.113763 -0.990667 0.075085 -v 0.060003 0.123500 0.043500 -vn -0.396204 0.686243 -0.609994 -v 0.062658 0.119500 0.045000 -vn 0.318865 0.552291 -0.770260 -v 0.060878 0.120417 0.045000 -vn -0.000000 0.637725 -0.770264 -v 0.061503 0.120250 0.045000 -vn -0.318865 0.552291 -0.770260 -v 0.062128 0.120417 0.045000 -vn -0.792406 -0.000001 -0.609995 -v 0.063812 0.121500 0.045000 -vn -0.552286 0.318864 -0.770263 -v 0.062586 0.120875 0.045000 -vn 0.000000 -0.637725 -0.770264 -v 0.061503 0.122750 0.045000 -vn 0.318867 -0.552288 -0.770261 -v 0.060878 0.122582 0.045000 -vn 0.552288 -0.318866 -0.770261 -v 0.060421 0.122125 0.045000 -vn 0.637727 -0.000002 -0.770263 -v 0.060253 0.121500 0.045000 -vn 0.552286 0.318866 -0.770263 -v 0.060421 0.120875 0.045000 -vn -0.637728 -0.000002 -0.770261 -v 0.062753 0.121500 0.045000 -vn -0.552288 -0.318864 -0.770262 -v 0.062586 0.122125 0.045000 -vn -0.318867 -0.552288 -0.770261 -v 0.062128 0.122582 0.045000 -vn -0.113763 0.990667 0.075085 -v 0.060003 0.119500 0.043500 -vn -0.396204 0.686243 0.609994 -v 0.062658 0.119500 0.043500 -vn -0.792406 -0.000001 0.609994 -v 0.063812 0.121500 0.043500 -vn -0.452907 0.279912 0.846478 -v 0.062003 0.120500 0.043500 -vn -0.452907 -0.279912 0.846478 -v 0.062003 0.122500 0.043500 -vn -0.396203 -0.686244 0.609994 -v 0.062658 0.115500 0.043500 -vn -0.396203 -0.686244 -0.609994 -v 0.062658 0.115500 0.045000 -vn -0.113763 -0.990667 0.075085 -v 0.060003 0.115500 0.043500 -vn -0.396203 0.686243 -0.609994 -v 0.062658 0.111500 0.045000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.112417 0.045000 -vn 0.000000 0.637729 -0.770261 -v 0.061503 0.112250 0.045000 -vn -0.318863 0.552289 -0.770262 -v 0.062128 0.112417 0.045000 -vn -0.792406 -0.000001 -0.609995 -v 0.063812 0.113500 0.045000 -vn -0.552288 0.318863 -0.770262 -v 0.062586 0.112875 0.045000 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.114582 0.045000 -vn -0.000000 -0.637729 -0.770261 -v 0.061503 0.114750 0.045000 -vn -0.637728 0.000000 -0.770261 -v 0.062753 0.113500 0.045000 -vn -0.552289 -0.318863 -0.770262 -v 0.062586 0.114125 0.045000 -vn -0.318863 -0.552289 -0.770262 -v 0.062128 0.114582 0.045000 -vn 0.552288 -0.318865 -0.770261 -v 0.060421 0.114125 0.045000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.113500 0.045000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.112875 0.045000 -vn -0.113763 0.990667 0.075085 -v 0.060003 0.111500 0.043500 -vn -0.396204 0.686243 0.609994 -v 0.062658 0.111500 0.043500 -vn -0.396203 -0.686244 0.609994 -v 0.062658 0.107500 0.043500 -vn -0.396203 -0.686244 -0.609994 -v 0.062658 0.107500 0.045000 -vn -0.113762 -0.990667 0.075084 -v 0.060003 0.107500 0.043500 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.106582 0.045000 -vn -0.000000 -0.637729 -0.770261 -v 0.061503 0.106750 0.045000 -vn 0.552288 -0.318865 -0.770261 -v 0.060421 0.106125 0.045000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.105500 0.045000 -vn -0.552288 0.318863 -0.770262 -v 0.062586 0.104875 0.045000 -vn -0.792406 -0.000001 -0.609995 -v 0.063812 0.105500 0.045000 -vn -0.318863 0.552289 -0.770262 -v 0.062128 0.104417 0.045000 -vn -0.396203 0.686243 -0.609994 -v 0.062658 0.103500 0.045000 -vn -0.637728 0.000000 -0.770261 -v 0.062753 0.105500 0.045000 -vn -0.552289 -0.318863 -0.770262 -v 0.062586 0.106125 0.045000 -vn -0.318863 -0.552289 -0.770262 -v 0.062128 0.106582 0.045000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.104875 0.045000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.104417 0.045000 -vn 0.000000 0.637729 -0.770261 -v 0.061503 0.104250 0.045000 -vn -0.113763 0.990667 0.075085 -v 0.060003 0.103500 0.043500 -vn -0.396203 0.686243 0.609994 -v 0.062658 0.103500 0.043500 -vn -0.396204 -0.686243 0.609994 -v 0.062658 0.099500 0.043500 -vn -0.396204 -0.686243 -0.609994 -v 0.062658 0.099500 0.045000 -vn -0.113763 -0.990667 0.075085 -v 0.060003 0.099500 0.043500 -vn -0.637728 0.000000 -0.770261 -v 0.062753 0.097500 0.045000 -vn -0.552289 -0.318863 -0.770262 -v 0.062586 0.098125 0.045000 -vn -0.792406 0.000001 -0.609994 -v 0.063812 0.097500 0.045000 -vn -0.396203 0.686244 -0.609994 -v 0.062658 0.095500 0.045000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.096417 0.045000 -vn 0.000000 0.637728 -0.770261 -v 0.061503 0.096250 0.045000 -vn -0.318863 0.552289 -0.770262 -v 0.062128 0.096417 0.045000 -vn -0.552288 0.318863 -0.770262 -v 0.062586 0.096875 0.045000 -vn -0.318863 -0.552289 -0.770262 -v 0.062128 0.098582 0.045000 -vn -0.000000 -0.637729 -0.770261 -v 0.061503 0.098750 0.045000 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.098582 0.045000 -vn 0.552288 -0.318865 -0.770261 -v 0.060421 0.098125 0.045000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.097500 0.045000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.096875 0.045000 -vn -0.113762 0.990667 0.075084 -v 0.060003 0.095500 0.043500 -vn -0.396203 0.686244 0.609994 -v 0.062658 0.095500 0.043500 -vn -0.792406 -0.000001 0.609994 -v 0.063812 0.113500 0.043500 -vn -0.452907 0.279912 0.846478 -v 0.062003 0.112500 0.043500 -vn -0.452907 -0.279912 0.846478 -v 0.062003 0.114500 0.043500 -vn -0.792406 -0.000001 0.609994 -v 0.063812 0.105500 0.043500 -vn -0.452907 0.279912 0.846478 -v 0.062003 0.104500 0.043500 -vn -0.452906 -0.279912 0.846478 -v 0.062003 0.106500 0.043500 -vn -0.792406 0.000001 0.609994 -v 0.063812 0.097500 0.043500 -vn -0.452906 0.279912 0.846478 -v 0.062003 0.096500 0.043500 -vn -0.452907 -0.279912 0.846478 -v 0.062003 0.098500 0.043500 -vn -0.890021 -0.454638 0.034161 -v 0.062033 0.083700 0.045500 -vn -0.966963 -0.237884 0.091613 -v 0.062033 0.083700 0.045300 -vn -0.878390 -0.237228 0.414914 -v 0.062248 0.082705 0.045300 -vn -0.838511 -0.392577 0.377866 -v 0.062389 0.082324 0.045300 -vn -0.767491 -0.494293 0.408206 -v 0.062958 0.081311 0.045300 -vn -0.686608 -0.622827 0.375041 -v 0.063144 0.081070 0.045300 -vn -0.583344 -0.711416 0.391915 -v 0.064064 0.080205 0.045300 -vn -0.465356 -0.801566 0.375414 -v 0.064231 0.080089 0.045300 -vn -0.268201 -0.888949 0.371266 -v 0.065555 0.079464 0.045300 -vn -0.911374 -0.057149 0.407593 -v 0.067503 0.080750 0.047050 -vn -0.911638 -0.123375 0.392039 -v 0.067503 0.081750 0.047050 -vn -0.727973 -0.095840 0.678874 -v 0.067503 0.081750 0.045500 -vn -0.900734 -0.217184 0.376177 -v 0.067503 0.080100 0.046876 -vn -0.900734 -0.376178 0.217186 -v 0.067503 0.079624 0.046400 -vn -0.911372 -0.407597 0.057148 -v 0.067503 0.079450 0.045750 -vn -0.578879 -0.574276 0.578884 -v 0.067503 0.079450 0.045500 -vn -0.207845 -0.566899 0.797136 -v 0.062285 0.083500 0.045500 -vn -0.702014 -0.593606 0.393457 -v 0.062259 0.083521 0.045500 -vn -0.366933 -0.166934 0.915146 -v 0.062573 0.082401 0.045500 -vn 0.637727 0.000000 0.770262 -v 0.064753 0.081750 0.045500 -vn 0.552288 -0.318865 0.770261 -v 0.064887 0.082250 0.045500 -vn 0.318865 -0.552288 0.770261 -v 0.065253 0.082616 0.045500 -vn -0.095839 -0.727973 0.678875 -v 0.065753 0.083500 0.045500 -vn 0.000000 -0.637727 0.770262 -v 0.065753 0.082750 0.045500 -vn -0.378583 -0.655722 0.653226 -v 0.066628 0.083265 0.045500 -vn -0.318865 -0.552288 0.770261 -v 0.066253 0.082616 0.045500 -vn -0.655722 -0.378579 0.653227 -v 0.067269 0.082625 0.045500 -vn -0.552288 -0.318865 0.770261 -v 0.066619 0.082250 0.045500 -vn -0.637727 -0.000000 0.770262 -v 0.066753 0.081750 0.045500 -vn -0.552288 0.318865 0.770261 -v 0.066619 0.081250 0.045500 -vn -0.030259 -0.397290 0.917194 -v 0.067003 0.079450 0.045500 -vn -0.318865 0.552288 0.770261 -v 0.066253 0.080884 0.045500 -vn -0.119454 -0.394715 0.911005 -v 0.065613 0.079656 0.045500 -vn -0.000000 0.637727 0.770262 -v 0.065753 0.080750 0.045500 -vn -0.214458 -0.341592 0.915054 -v 0.064342 0.080255 0.045500 -vn 0.318865 0.552288 0.770261 -v 0.065253 0.080884 0.045500 -vn -0.304882 -0.260380 0.916105 -v 0.063299 0.081198 0.045500 -vn 0.552288 0.318865 0.770261 -v 0.064887 0.081250 0.045500 -vn -0.123374 -0.911642 0.392029 -v 0.065753 0.083500 0.047050 -vn -0.036324 -0.925872 0.376088 -v 0.063542 0.083500 0.046747 -vn -0.347094 -0.934778 0.075601 -v 0.062299 0.083500 0.045690 -vn -0.135462 -0.923537 0.358790 -v 0.063085 0.083500 0.046662 -vn -0.243489 -0.928827 0.279274 -v 0.062687 0.083500 0.046415 -vn -0.318433 -0.931062 0.178110 -v 0.062452 0.083500 0.046122 -vn -0.791066 -0.456719 0.406968 -v 0.067269 0.082625 0.047050 -vn -0.456724 -0.791065 0.406964 -v 0.066628 0.083265 0.047050 -vn 0.911376 -0.407588 0.057148 -v 0.082503 0.079450 0.045750 -vn 0.578886 -0.574270 0.578882 -v 0.082503 0.079450 0.045500 -vn 0.727973 -0.095840 0.678874 -v 0.082503 0.081750 0.045500 -vn 0.900738 -0.376170 0.217181 -v 0.082503 0.079624 0.046400 -vn 0.900738 -0.217179 0.376170 -v 0.082503 0.080100 0.046876 -vn 0.911378 -0.057148 0.407584 -v 0.082503 0.080750 0.047050 -vn 0.911642 -0.123375 0.392030 -v 0.082503 0.081750 0.047050 -vn 0.000000 -0.637727 0.770262 -v 0.084253 0.082750 0.045500 -vn -0.318865 -0.552288 0.770261 -v 0.084753 0.082616 0.045500 -vn 0.236673 -0.830924 0.503538 -v 0.087744 0.083500 0.045500 -vn -0.552288 -0.318866 0.770261 -v 0.085119 0.082250 0.045500 -vn 0.364051 -0.164414 0.916752 -v 0.087426 0.082385 0.045500 -vn -0.637727 -0.000002 0.770263 -v 0.085253 0.081750 0.045500 -vn 0.302274 -0.262566 0.916346 -v 0.086699 0.081187 0.045500 -vn -0.552289 0.318864 0.770262 -v 0.085119 0.081250 0.045500 -vn 0.213524 -0.341970 0.915131 -v 0.085657 0.080250 0.045500 -vn -0.318865 0.552288 0.770261 -v 0.084753 0.080884 0.045500 -vn 0.119059 -0.394733 0.911049 -v 0.084389 0.079654 0.045500 -vn -0.000000 0.637727 0.770262 -v 0.084253 0.080750 0.045500 -vn 0.030155 -0.397246 0.917217 -v 0.083003 0.079450 0.045500 -vn 0.318865 0.552288 0.770261 -v 0.083753 0.080884 0.045500 -vn 0.552288 0.318865 0.770261 -v 0.083387 0.081250 0.045500 -vn 0.637727 0.000000 0.770262 -v 0.083253 0.081750 0.045500 -vn 0.655722 -0.378581 0.653227 -v 0.082737 0.082625 0.045500 -vn 0.552288 -0.318865 0.770261 -v 0.083387 0.082250 0.045500 -vn 0.378581 -0.655722 0.653227 -v 0.083378 0.083265 0.045500 -vn 0.318865 -0.552288 0.770261 -v 0.083753 0.082616 0.045500 -vn 0.095840 -0.727973 0.678875 -v 0.084253 0.083500 0.045500 -vn 0.123375 -0.911642 0.392029 -v 0.084253 0.083500 0.047050 -vn 0.456721 -0.791065 0.406967 -v 0.083378 0.083265 0.047050 -vn 0.791065 -0.456721 0.406968 -v 0.082737 0.082625 0.047050 -vn 0.366133 -0.919678 0.141910 -v 0.087685 0.083500 0.045965 -vn 0.373330 -0.926997 0.036082 -v 0.087771 0.083500 0.045500 -vn 0.719566 -0.528017 0.451025 -v 0.087771 0.083500 0.045473 -vn 0.008526 -0.922214 0.386587 -v 0.086460 0.083500 0.046800 -vn 0.065702 -0.915770 0.396294 -v 0.086592 0.083500 0.046793 -vn 0.292842 -0.918048 0.267268 -v 0.087433 0.083500 0.046372 -vn 0.179874 -0.915021 0.361085 -v 0.087056 0.083500 0.046658 -vn -0.398271 0.907512 0.133426 -v 0.065207 0.122108 0.046800 -vn -0.374712 0.652396 0.658764 -v 0.065478 0.122234 0.045500 -vn -0.088429 0.934450 0.344939 -v 0.064603 0.122000 0.046800 -vn -0.007637 0.752369 0.658698 -v 0.064603 0.122000 0.045500 -vn 0.185142 0.901666 0.390794 -v 0.064396 0.122012 0.046800 -vn 0.375048 0.648877 0.662041 -v 0.063728 0.122234 0.045500 -vn 0.650284 0.374858 0.660766 -v 0.063087 0.122875 0.045500 -vn 0.603008 0.695162 0.391320 -v 0.063583 0.122328 0.046800 -vn 0.383986 0.856586 0.344696 -v 0.063728 0.122234 0.046800 -vn 0.751859 -0.000677 0.659324 -v 0.062853 0.123750 0.045500 -vn 0.866054 0.310549 0.391804 -v 0.063023 0.122997 0.046800 -vn 0.753958 0.551766 0.356512 -v 0.063087 0.122875 0.046800 -vn 0.651908 -0.377401 0.657712 -v 0.063087 0.124625 0.045500 -vn 0.902556 -0.138338 0.407743 -v 0.062856 0.123853 0.046800 -vn 0.924136 0.105640 0.367169 -v 0.062853 0.123750 0.046800 -vn -0.375907 -0.655784 0.654707 -v 0.065478 0.125265 0.045500 -vn -0.021916 -0.906204 0.422272 -v 0.064603 0.125500 0.046800 -vn -0.001406 -0.756523 0.653966 -v 0.064603 0.125500 0.045500 -vn 0.451995 -0.789490 0.415219 -v 0.063758 0.125282 0.046800 -vn 0.376807 -0.654565 0.655409 -v 0.063728 0.125265 0.045500 -vn 0.713954 -0.579377 0.393183 -v 0.063123 0.124684 0.046800 -vn 0.851631 -0.364530 0.376620 -v 0.063087 0.124625 0.046800 -vn -0.651904 -0.377400 0.657716 -v 0.066119 0.124625 0.045500 -vn -0.713919 -0.579421 0.393180 -v 0.066083 0.124684 0.046800 -vn -0.439297 -0.801281 0.406160 -v 0.065448 0.125282 0.046800 -vn -0.750976 -0.002348 0.660326 -v 0.066353 0.123750 0.045500 -vn -0.906554 -0.149701 0.394650 -v 0.066350 0.123854 0.046800 -vn -0.848406 -0.368054 0.380453 -v 0.066119 0.124625 0.046800 -vn -0.647900 0.378742 0.660894 -v 0.066119 0.122875 0.045500 -vn -0.886711 0.444734 0.126316 -v 0.066207 0.123050 0.046800 -vn -0.918168 0.076501 0.388736 -v 0.066353 0.123750 0.046800 -vn -0.701676 0.635244 0.322669 -v 0.066207 0.123050 0.049800 -vn -0.787547 0.505466 0.352525 -v 0.066119 0.122875 0.049800 -vn -0.630834 0.674650 0.383268 -v 0.065806 0.122479 0.049800 -vn -0.520472 0.808499 0.274659 -v 0.065478 0.122234 0.049800 -vn -0.605235 0.727339 0.323525 -v 0.065207 0.122108 0.049800 -vn 0.318860 0.552289 0.770263 -v 0.064103 0.122884 0.045500 -vn -0.000000 0.637731 0.770259 -v 0.064603 0.122750 0.045500 -vn -0.318860 0.552289 0.770263 -v 0.065103 0.122884 0.045500 -vn -0.552288 0.318865 0.770261 -v 0.065469 0.123250 0.045500 -vn -0.637727 -0.000000 0.770262 -v 0.065603 0.123750 0.045500 -vn -0.552288 -0.318865 0.770261 -v 0.065469 0.124250 0.045500 -vn -0.318865 -0.552288 0.770261 -v 0.065103 0.124616 0.045500 -vn 0.000000 -0.637727 0.770262 -v 0.064603 0.124750 0.045500 -vn 0.318865 -0.552288 0.770261 -v 0.064103 0.124616 0.045500 -vn 0.552288 -0.318865 0.770261 -v 0.063737 0.124250 0.045500 -vn 0.637727 0.000000 0.770262 -v 0.063603 0.123750 0.045500 -vn 0.552288 0.318865 0.770261 -v 0.063737 0.123250 0.045500 -vn -0.001539 0.750456 0.660919 -v 0.085403 0.122000 0.045500 -vn 0.378733 0.647850 0.660948 -v 0.084528 0.122234 0.045500 -vn 0.424027 0.901119 0.090478 -v 0.084703 0.122146 0.046800 -vn 0.881675 0.464698 0.081888 -v 0.083870 0.122906 0.046800 -vn 0.653826 0.375510 0.656889 -v 0.083887 0.122875 0.045500 -vn 0.907199 -0.009040 0.420605 -v 0.083653 0.123716 0.046800 -vn 0.757274 -0.003253 0.653089 -v 0.083653 0.123750 0.045500 -vn 0.656941 -0.375682 0.653676 -v 0.083887 0.124625 0.045500 -vn 0.377252 -0.653208 0.656506 -v 0.084528 0.125265 0.045500 -vn 0.577534 -0.715764 0.392603 -v 0.084481 0.125237 0.046800 -vn 0.803706 -0.434097 0.406960 -v 0.083866 0.124586 0.046800 -vn 0.000053 -0.753859 0.657037 -v 0.085403 0.125500 0.045500 -vn 0.139926 -0.908513 0.393733 -v 0.085338 0.125499 0.046800 -vn 0.361631 -0.850109 0.382801 -v 0.084528 0.125265 0.046800 -vn -0.376695 -0.652477 0.657552 -v 0.086278 0.125265 0.045500 -vn -0.330517 -0.857628 0.393996 -v 0.086212 0.125302 0.046800 -vn -0.109891 -0.918055 0.380918 -v 0.085403 0.125500 0.046800 -vn -0.652111 -0.376458 0.658051 -v 0.086919 0.124625 0.045500 -vn -0.713317 -0.579440 0.394244 -v 0.086874 0.124698 0.046800 -vn -0.552871 -0.742076 0.379022 -v 0.086278 0.125265 0.046800 -vn -0.752552 0.000079 0.658533 -v 0.087153 0.123750 0.045500 -vn -0.902976 -0.129597 0.409681 -v 0.087150 0.123846 0.046800 -vn -0.837942 -0.379801 0.391924 -v 0.086919 0.124625 0.046800 -vn -0.651313 0.376172 0.659004 -v 0.086919 0.122875 0.045500 -vn -0.860168 0.322968 0.394719 -v 0.086969 0.122969 0.046800 -vn -0.921190 0.103446 0.375110 -v 0.087153 0.123750 0.046800 -vn -0.375744 0.651103 0.659455 -v 0.086278 0.122234 0.045500 -vn -0.585458 0.707991 0.394954 -v 0.086377 0.122296 0.046800 -vn -0.748088 0.548757 0.373135 -v 0.086919 0.122875 0.046800 -vn 0.046128 0.939539 0.339320 -v 0.085403 0.122000 0.046800 -vn -0.141023 0.911942 0.385325 -v 0.085530 0.122005 0.046800 -vn -0.376039 0.849024 0.371151 -v 0.086278 0.122234 0.046800 -vn 0.532247 0.782881 0.322196 -v 0.084703 0.122146 0.049800 -vn 0.489365 0.801454 0.343793 -v 0.084528 0.122234 0.049800 -vn 0.653559 0.651024 0.386042 -v 0.084200 0.122479 0.049800 -vn 0.779289 0.546599 0.306492 -v 0.083887 0.122875 0.049800 -vn 0.770000 0.549397 0.324444 -v 0.083870 0.122906 0.049800 -vn 0.318855 0.552289 0.770265 -v 0.084903 0.122884 0.045500 -vn -0.000006 0.637733 0.770258 -v 0.085403 0.122750 0.045500 -vn -0.318859 0.552292 0.770261 -v 0.085903 0.122884 0.045500 -vn -0.552286 0.318862 0.770265 -v 0.086269 0.123250 0.045500 -vn -0.637731 -0.000000 0.770259 -v 0.086403 0.123750 0.045500 -vn -0.552286 -0.318862 0.770265 -v 0.086269 0.124250 0.045500 -vn -0.318864 -0.552291 0.770260 -v 0.085903 0.124616 0.045500 -vn 0.000003 -0.637724 0.770265 -v 0.085403 0.124750 0.045500 -vn 0.318870 -0.552288 0.770260 -v 0.084903 0.124616 0.045500 -vn 0.552288 -0.318865 0.770261 -v 0.084537 0.124250 0.045500 -vn 0.637727 0.000000 0.770262 -v 0.084403 0.123750 0.045500 -vn 0.552288 0.318865 0.770261 -v 0.084537 0.123250 0.045500 -vn 0.953043 -0.027690 0.301565 -v 0.087910 0.084250 0.046019 -vn 0.854942 -0.028992 0.517913 -v 0.087802 0.084250 0.046250 -vn 0.704306 -0.023714 0.709500 -v 0.087564 0.084250 0.046561 -vn 0.524696 -0.021420 0.851020 -v 0.087253 0.084250 0.046799 -vn 0.307441 -0.009598 0.951519 -v 0.087022 0.084250 0.046907 -vn 0.139205 -0.381660 0.913760 -v 0.086612 0.083697 0.046992 -vn 0.408361 -0.405544 0.817787 -v 0.087146 0.083688 0.046836 -vn 0.668172 -0.417646 0.615726 -v 0.087581 0.083682 0.046506 -vn 0.846071 -0.424814 0.322019 -v 0.087870 0.083678 0.046037 -vn -0.951047 -0.026107 0.307942 -v 0.062096 0.084250 0.046019 -vn -0.853310 -0.026787 0.520716 -v 0.062204 0.084250 0.046250 -vn -0.711169 -0.023046 0.702644 -v 0.062442 0.084250 0.046561 -vn -0.304154 -0.010427 0.952566 -v 0.062984 0.084250 0.046907 -vn -0.519835 -0.020965 0.854010 -v 0.062753 0.084250 0.046799 -vn -0.876851 -0.446633 0.177908 -v 0.062051 0.083700 0.045729 -vn -0.776815 -0.444998 0.445574 -v 0.062234 0.083703 0.046248 -vn -0.598245 -0.437025 0.671649 -v 0.062516 0.083707 0.046600 -vn -0.313565 -0.422546 0.850371 -v 0.062994 0.083716 0.046898 -vn -0.362023 -0.466083 0.807283 -v 0.067703 0.080000 0.047049 -vn 0.362031 -0.466082 0.807280 -v 0.082303 0.080000 0.047049 -vn -0.362023 -0.807283 0.466084 -v 0.067703 0.079451 0.046500 -vn 0.362031 -0.807280 0.466082 -v 0.082303 0.079451 0.046500 -vn 0.000000 -0.732324 0.680956 -v 0.075003 0.099850 0.046500 -vn 0.175257 -0.711044 0.680956 -v 0.072825 0.099586 0.046500 -vn 0.340328 -0.648441 0.680956 -v 0.070774 0.098808 0.046500 -vn 0.485621 -0.548153 0.680956 -v 0.068969 0.097561 0.046500 -vn 0.602691 -0.416007 0.680956 -v 0.067514 0.095919 0.046500 -vn 0.684735 -0.259686 0.680957 -v 0.066494 0.093977 0.046500 -vn 0.726985 -0.088272 0.680956 -v 0.065969 0.091847 0.046500 -vn 0.726985 0.088272 0.680956 -v 0.065969 0.089653 0.046500 -vn 0.684735 0.259686 0.680957 -v 0.066494 0.087523 0.046500 -vn 0.602691 0.416008 0.680956 -v 0.067514 0.085581 0.046500 -vn 0.485620 0.548153 0.680957 -v 0.068969 0.083938 0.046500 -vn 0.340328 0.648441 0.680956 -v 0.070774 0.082692 0.046500 -vn 0.175257 0.711044 0.680956 -v 0.072825 0.081914 0.046500 -vn 0.000000 0.732324 0.680956 -v 0.075003 0.081650 0.046500 -vn -0.175257 0.711044 0.680956 -v 0.077181 0.081914 0.046500 -vn -0.340328 0.648441 0.680957 -v 0.079232 0.082692 0.046500 -vn -0.485622 0.548152 0.680956 -v 0.081037 0.083938 0.046500 -vn -0.602691 0.416006 0.680957 -v 0.082492 0.085581 0.046500 -vn -0.684735 0.259686 0.680956 -v 0.083512 0.087523 0.046500 -vn -0.726985 0.088271 0.680957 -v 0.084037 0.089653 0.046500 -vn -0.726985 -0.088271 0.680956 -v 0.084037 0.091847 0.046500 -vn -0.684735 -0.259686 0.680956 -v 0.083512 0.093977 0.046500 -vn -0.602691 -0.416007 0.680957 -v 0.082492 0.095919 0.046500 -vn -0.485621 -0.548153 0.680956 -v 0.081037 0.097561 0.046500 -vn -0.340328 -0.648441 0.680957 -v 0.079232 0.098808 0.046500 -vn -0.175257 -0.711044 0.680956 -v 0.077181 0.099586 0.046500 -vn 0.507834 0.440041 0.740587 -v 0.080067 0.095138 0.046500 -vn 0.363290 0.565290 0.740586 -v 0.078625 0.096386 0.046500 -vn 0.189313 0.644742 0.740587 -v 0.076891 0.097179 0.046500 -vn -0.000000 0.671961 0.740586 -v 0.075003 0.097450 0.046500 -vn -0.189313 0.644742 0.740587 -v 0.073115 0.097179 0.046500 -vn -0.363289 0.565290 0.740587 -v 0.071381 0.096386 0.046500 -vn 0.363290 -0.565289 0.740586 -v 0.078625 0.085114 0.046500 -vn 0.507834 -0.440041 0.740587 -v 0.080067 0.086362 0.046500 -vn 0.611238 -0.279142 0.740586 -v 0.081098 0.087967 0.046500 -vn 0.665122 -0.095630 0.740586 -v 0.081635 0.089796 0.046500 -vn 0.665122 0.095630 0.740586 -v 0.081635 0.091703 0.046500 -vn 0.611238 0.279142 0.740586 -v 0.081098 0.093533 0.046500 -vn -0.507834 0.440040 0.740587 -v 0.069940 0.095138 0.046500 -vn -0.611238 0.279142 0.740586 -v 0.068909 0.093533 0.046500 -vn -0.665122 0.095630 0.740586 -v 0.068371 0.091703 0.046500 -vn -0.665122 -0.095630 0.740586 -v 0.068371 0.089796 0.046500 -vn -0.611238 -0.279142 0.740586 -v 0.068909 0.087967 0.046500 -vn -0.507834 -0.440041 0.740587 -v 0.069940 0.086362 0.046500 -vn -0.363289 -0.565290 0.740586 -v 0.071381 0.085114 0.046500 -vn -0.189313 -0.644742 0.740587 -v 0.073115 0.084321 0.046500 -vn -0.000000 -0.671961 0.740586 -v 0.075003 0.084050 0.046500 -vn 0.189313 -0.644742 0.740587 -v 0.076891 0.084321 0.046500 -vn -0.000000 0.736503 0.676434 -v 0.075003 0.097450 0.047250 -vn -0.207497 0.706670 0.676434 -v 0.073115 0.097179 0.047250 -vn -0.398184 0.619586 0.676434 -v 0.071381 0.096386 0.047250 -vn -0.556613 0.482307 0.676434 -v 0.069940 0.095138 0.047250 -vn -0.669947 0.305954 0.676434 -v 0.068909 0.093533 0.047250 -vn -0.729007 0.104815 0.676434 -v 0.068371 0.091703 0.047250 -vn -0.729007 -0.104815 0.676434 -v 0.068371 0.089796 0.047250 -vn -0.669947 -0.305954 0.676434 -v 0.068909 0.087967 0.047250 -vn -0.556612 -0.482308 0.676433 -v 0.069940 0.086362 0.047250 -vn -0.398183 -0.619587 0.676434 -v 0.071381 0.085114 0.047250 -vn -0.207497 -0.706670 0.676434 -v 0.073115 0.084321 0.047250 -vn -0.000000 -0.736503 0.676434 -v 0.075003 0.084050 0.047250 -vn 0.207497 -0.706670 0.676433 -v 0.076891 0.084321 0.047250 -vn 0.398184 -0.619586 0.676434 -v 0.078625 0.085114 0.047250 -vn 0.556613 -0.482307 0.676434 -v 0.080067 0.086362 0.047250 -vn 0.669947 -0.305954 0.676434 -v 0.081098 0.087967 0.047250 -vn 0.729007 -0.104815 0.676434 -v 0.081635 0.089796 0.047250 -vn 0.729007 0.104815 0.676434 -v 0.081635 0.091703 0.047250 -vn 0.669947 0.305954 0.676434 -v 0.081098 0.093533 0.047250 -vn 0.556612 0.482308 0.676433 -v 0.080067 0.095138 0.047250 -vn 0.398183 0.619586 0.676434 -v 0.078625 0.096386 0.047250 -vn 0.207497 0.706670 0.676433 -v 0.076891 0.097179 0.047250 -vn -0.645460 -0.163453 0.746099 -v 0.079608 0.091916 0.047250 -vn -0.557416 -0.364177 0.746098 -v 0.078980 0.093348 0.047250 -vn -0.408963 -0.525437 0.746100 -v 0.077921 0.094498 0.047250 -vn -0.216196 -0.629759 0.746098 -v 0.076545 0.095243 0.047250 -vn -0.000000 -0.665834 0.746100 -v 0.075003 0.095500 0.047250 -vn 0.216197 -0.629759 0.746098 -v 0.073461 0.095243 0.047250 -vn 0.408964 -0.525438 0.746099 -v 0.072086 0.094498 0.047250 -vn 0.557415 -0.364178 0.746099 -v 0.071026 0.093348 0.047250 -vn -0.109594 0.656754 0.746099 -v 0.075785 0.086065 0.047250 -vn -0.316903 0.585585 0.746099 -v 0.077264 0.086572 0.047250 -vn -0.489871 0.450958 0.746099 -v 0.078498 0.087533 0.047250 -vn -0.609754 0.267463 0.746099 -v 0.079353 0.088842 0.047250 -vn -0.663561 0.054984 0.746099 -v 0.079737 0.090358 0.047250 -vn 0.645460 -0.163452 0.746100 -v 0.070398 0.091916 0.047250 -vn 0.663562 0.054985 0.746098 -v 0.070269 0.090358 0.047250 -vn 0.609754 0.267462 0.746099 -v 0.070653 0.088842 0.047250 -vn 0.489871 0.450958 0.746099 -v 0.071508 0.087533 0.047250 -vn 0.316903 0.585585 0.746099 -v 0.072742 0.086572 0.047250 -vn 0.109593 0.656754 0.746099 -v 0.074221 0.086065 0.047250 -vn 0.000000 -0.740671 0.671868 -v 0.075003 0.095500 0.044750 -vn 0.240496 -0.700538 0.671869 -v 0.073461 0.095243 0.044750 -vn 0.454928 -0.584494 0.671868 -v 0.072086 0.094498 0.044750 -vn 0.620064 -0.405109 0.671869 -v 0.071026 0.093348 0.044750 -vn 0.718007 -0.181823 0.671868 -v 0.070398 0.091916 0.044750 -vn 0.738140 0.061164 0.671869 -v 0.070269 0.090358 0.044750 -vn 0.678287 0.297523 0.671868 -v 0.070653 0.088842 0.044750 -vn 0.544929 0.501643 0.671869 -v 0.071508 0.087533 0.044750 -vn 0.352520 0.651400 0.671869 -v 0.072742 0.086572 0.044750 -vn 0.121911 0.730569 0.671868 -v 0.074221 0.086065 0.044750 -vn -0.121911 0.730569 0.671868 -v 0.075785 0.086065 0.044750 -vn -0.352521 0.651400 0.671869 -v 0.077264 0.086572 0.044750 -vn -0.544929 0.501643 0.671869 -v 0.078498 0.087533 0.044750 -vn -0.678286 0.297524 0.671869 -v 0.079353 0.088842 0.044750 -vn -0.738141 0.061164 0.671868 -v 0.079737 0.090358 0.044750 -vn -0.718006 -0.181825 0.671868 -v 0.079608 0.091916 0.044750 -vn -0.620064 -0.405108 0.671869 -v 0.078980 0.093348 0.044750 -vn -0.454929 -0.584494 0.671868 -v 0.077921 0.094498 0.044750 -vn -0.240495 -0.700538 0.671869 -v 0.076545 0.095243 0.044750 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.090750 0.044750 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.106582 0.015000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.106750 0.015000 -vn 0.382683 0.000000 -0.923880 -v 0.090003 0.108000 0.015000 -vn 0.110050 0.110050 -0.987815 -v 0.065203 0.102750 0.015000 -vn 0.000000 0.382686 -0.923879 -v 0.065878 0.102750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065878 0.098250 0.015000 -vn -0.133727 -0.005386 -0.991004 -v 0.063003 0.084250 0.015000 -vn -0.065066 -0.041899 -0.997001 -v 0.063003 0.092750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.090550 0.015000 -vn -0.185742 -0.131340 -0.973781 -v 0.062003 0.094250 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.060128 0.094250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.060128 0.096200 0.015000 -vn 0.185743 0.131340 -0.973781 -v 0.088003 0.124750 0.015000 -vn 0.297108 0.630263 -0.717284 -v 0.090003 0.124750 0.015000 -vn 0.382683 0.000000 -0.923880 -v 0.090003 0.124375 0.015000 -vn -0.282125 -0.162886 -0.945449 -v 0.069869 0.083750 0.015000 -vn -0.208922 -0.642995 -0.736824 -v 0.073334 0.085614 0.015000 -vn -0.325771 -0.000001 -0.945449 -v 0.070003 0.083250 0.015000 -vn 0.000000 -0.676085 -0.736824 -v 0.075003 0.085350 0.015000 -vn -0.282132 0.162887 -0.945447 -v 0.069869 0.082750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065878 0.090550 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.068928 0.090550 0.015000 -vn 0.000001 -0.325772 -0.945448 -v 0.069003 0.084250 0.015000 -vn 0.162891 -0.282135 -0.945445 -v 0.068503 0.084116 0.015000 -vn 0.282135 -0.162893 -0.945445 -v 0.068137 0.083750 0.015000 -vn -0.042314 -0.130227 -0.990581 -v 0.065767 0.080446 0.015000 -vn 0.325772 0.000001 -0.945448 -v 0.068003 0.083250 0.015000 -vn 0.282142 0.162892 -0.945443 -v 0.068137 0.082750 0.015000 -vn -0.162891 0.282135 -0.945445 -v 0.069503 0.082384 0.015000 -vn 0.000000 -0.130525 -0.991445 -v 0.075003 0.080250 0.015000 -vn -0.000001 0.325772 -0.945448 -v 0.069003 0.082250 0.015000 -vn 0.000000 -0.130526 -0.991445 -v 0.068928 0.080250 0.015000 -vn 0.162892 0.282137 -0.945444 -v 0.068503 0.082384 0.015000 -vn -0.005386 -0.133725 -0.991004 -v 0.067003 0.080250 0.015000 -vn -0.021421 -0.135244 -0.990581 -v 0.066377 0.080299 0.015000 -vn -0.552290 -0.318862 -0.770262 -v 0.062586 0.098125 0.015000 -vn -0.318864 -0.552287 -0.770263 -v 0.062128 0.098582 0.015000 -vn -0.185742 0.131340 -0.973781 -v 0.062003 0.100750 0.015000 -vn 0.000000 -0.637728 -0.770261 -v 0.061503 0.098750 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.060128 0.100750 0.015000 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.098582 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.060128 0.098250 0.015000 -vn 0.552288 -0.318865 -0.770261 -v 0.060421 0.098125 0.015000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.097500 0.015000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.096875 0.015000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.096417 0.015000 -vn -0.637728 -0.000000 -0.770261 -v 0.062753 0.097500 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.098250 0.015000 -vn -0.552290 0.318862 -0.770262 -v 0.062586 0.096875 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.096200 0.015000 -vn -0.318864 0.552287 -0.770263 -v 0.062128 0.096417 0.015000 -vn -0.000000 0.637728 -0.770261 -v 0.061503 0.096250 0.015000 -vn -0.552290 -0.318862 -0.770262 -v 0.062586 0.114125 0.015000 -vn -0.185742 0.131340 -0.973781 -v 0.062003 0.116750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.114000 0.015000 -vn -0.552279 -0.318861 -0.770270 -v 0.065043 0.116400 0.015000 -vn -0.318868 -0.552298 -0.770254 -v 0.065153 0.116290 0.015000 -vn -0.318864 -0.552287 -0.770263 -v 0.062128 0.114582 0.015000 -vn 0.000000 -0.637728 -0.770261 -v 0.061503 0.114750 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.060128 0.116750 0.015000 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.114582 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.060128 0.114000 0.015000 -vn -0.185742 -0.131340 -0.973781 -v 0.062003 0.110250 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.060128 0.110250 0.015000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.112417 0.015000 -vn -0.000000 0.637728 -0.770261 -v 0.061503 0.112250 0.015000 -vn -0.318864 0.552287 -0.770263 -v 0.062128 0.112417 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.110250 0.015000 -vn -0.552290 0.318862 -0.770262 -v 0.062586 0.112875 0.015000 -vn -0.637728 -0.000000 -0.770261 -v 0.062753 0.113500 0.015000 -vn 0.552288 -0.318865 -0.770261 -v 0.060421 0.114125 0.015000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.113500 0.015000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.112875 0.015000 -vn 0.000000 0.637732 -0.770258 -v 0.067003 0.125500 0.015000 -vn -0.318861 0.552286 -0.770265 -v 0.067628 0.125667 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.068928 0.124375 0.015000 -vn -0.552291 0.318865 -0.770260 -v 0.068086 0.126125 0.015000 -vn -0.637725 0.000000 -0.770264 -v 0.068253 0.126750 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.068928 0.128250 0.015000 -vn -0.552286 -0.318869 -0.770262 -v 0.068086 0.127375 0.015000 -vn -0.318866 -0.552291 -0.770260 -v 0.067628 0.127832 0.015000 -vn 0.000000 -0.637725 -0.770264 -v 0.067003 0.128000 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.065878 0.128250 0.015000 -vn 0.318866 -0.552291 -0.770260 -v 0.066378 0.127832 0.015000 -vn 0.552286 -0.318865 -0.770263 -v 0.065921 0.127375 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.065103 0.128250 0.015000 -vn 0.637728 0.000000 -0.770261 -v 0.065753 0.126750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.124375 0.015000 -vn 0.552291 0.318862 -0.770261 -v 0.065921 0.126125 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065878 0.124375 0.015000 -vn 0.318861 0.552286 -0.770265 -v 0.066378 0.125667 0.015000 -vn 0.382683 0.000000 -0.923880 -v 0.090003 0.103500 0.015000 -vn 0.297108 -0.630262 -0.717284 -v 0.090003 0.102250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.103500 0.015000 -vn 0.185743 -0.131340 -0.973781 -v 0.088003 0.102250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.098250 0.015000 -vn 0.185743 0.131340 -0.973781 -v 0.088003 0.100750 0.015000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.098582 0.015000 -vn 0.552291 -0.318866 -0.770260 -v 0.087421 0.098125 0.015000 -vn 0.637725 -0.000000 -0.770264 -v 0.087253 0.097500 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.096200 0.015000 -vn 0.382683 0.000000 -0.923880 -v 0.090003 0.096200 0.015000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.096250 0.015000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.096417 0.015000 -vn 0.552291 0.318866 -0.770260 -v 0.087421 0.096875 0.015000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.096417 0.015000 -vn -0.552291 0.318866 -0.770260 -v 0.089586 0.096875 0.015000 -vn -0.637725 0.000000 -0.770264 -v 0.089753 0.097500 0.015000 -vn 0.382683 0.000000 -0.923880 -v 0.090003 0.098250 0.015000 -vn -0.552291 -0.318866 -0.770260 -v 0.089586 0.098125 0.015000 -vn 0.297108 0.630262 -0.717284 -v 0.090003 0.100750 0.015000 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.098582 0.015000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.098750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.118250 0.015000 -vn 0.185743 -0.131340 -0.973781 -v 0.088003 0.118250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.114000 0.015000 -vn 0.185743 0.131340 -0.973781 -v 0.088003 0.116750 0.015000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.114582 0.015000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.112417 0.015000 -vn 0.297108 -0.630262 -0.717284 -v 0.090003 0.110250 0.015000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.112250 0.015000 -vn 0.185743 -0.131340 -0.973781 -v 0.088003 0.110250 0.015000 -vn 0.318864 0.552286 -0.770263 -v 0.087878 0.112417 0.015000 -vn -0.552291 0.318866 -0.770260 -v 0.089586 0.112875 0.015000 -vn -0.637725 0.000000 -0.770264 -v 0.089753 0.113500 0.015000 -vn 0.382683 0.000000 -0.923880 -v 0.090003 0.114000 0.015000 -vn -0.552291 -0.318866 -0.770260 -v 0.089586 0.114125 0.015000 -vn 0.297108 0.630262 -0.717284 -v 0.090003 0.116750 0.015000 -vn -0.318865 -0.552286 -0.770263 -v 0.089128 0.114582 0.015000 -vn -0.000001 -0.637729 -0.770261 -v 0.088503 0.114750 0.015000 -vn 0.552291 0.318866 -0.770260 -v 0.087421 0.112875 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.110250 0.015000 -vn 0.637725 -0.000000 -0.770264 -v 0.087253 0.113500 0.015000 -vn 0.552291 -0.318865 -0.770260 -v 0.087421 0.114125 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.124375 0.015000 -vn 0.318854 0.552289 -0.770266 -v 0.084853 0.123210 0.015000 -vn 0.088113 0.669358 -0.737697 -v 0.084703 0.123250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.081078 0.124375 0.015000 -vn 0.318870 -0.552288 -0.770260 -v 0.084853 0.116290 0.015000 -vn 0.552289 -0.318854 -0.770266 -v 0.084963 0.116400 0.015000 -vn 0.669358 -0.088113 -0.737697 -v 0.085003 0.116550 0.015000 -vn 0.707107 0.000000 -0.707107 -v 0.085003 0.118250 0.015000 -vn 0.669358 0.088113 -0.737697 -v 0.085003 0.122950 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.081078 0.116250 0.015000 -vn 0.088128 -0.669350 -0.737702 -v 0.084703 0.116250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.114000 0.015000 -vn -0.707107 0.000000 -0.707107 -v 0.079003 0.118250 0.015000 -vn -0.669350 -0.088128 -0.737702 -v 0.079003 0.116550 0.015000 -vn 0.000000 -0.000000 -1.000000 -v 0.075003 0.114000 0.015000 -vn -0.552288 -0.318870 -0.770260 -v 0.079043 0.116400 0.015000 -vn -0.318875 -0.552288 -0.770258 -v 0.079153 0.116290 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.079503 0.114000 0.015000 -vn -0.088131 -0.669347 -0.737704 -v 0.079303 0.116250 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.081078 0.123250 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.079503 0.123250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.079503 0.124375 0.015000 -vn -0.088117 0.669356 -0.737698 -v 0.079303 0.123250 0.015000 -vn 0.297108 0.630263 -0.717284 -v 0.090003 0.108750 0.015000 -vn 0.185743 0.131340 -0.973781 -v 0.088003 0.108750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.108000 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.086128 0.128250 0.015000 -vn 0.630263 0.297108 -0.717284 -v 0.086253 0.128250 0.015000 -vn 0.131339 0.185742 -0.973781 -v 0.086253 0.126250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.124375 0.015000 -vn 0.408249 0.408247 -0.816497 -v 0.088003 0.126250 0.015000 -vn -0.630263 0.297108 -0.717284 -v 0.079753 0.128250 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.081078 0.128250 0.015000 -vn -0.131339 0.185742 -0.973781 -v 0.079753 0.126250 0.015000 -vn 0.000000 0.382682 -0.923880 -v 0.079503 0.126250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.075003 0.124375 0.015000 -vn -0.318858 0.552289 -0.770264 -v 0.079153 0.123210 0.015000 -vn 0.630262 0.297108 -0.717284 -v 0.070253 0.128250 0.015000 -vn 0.131339 0.185742 -0.973781 -v 0.070253 0.126250 0.015000 -vn 0.000000 0.382682 -0.923880 -v 0.075003 0.126250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.060128 0.124375 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.060128 0.124750 0.015000 -vn -0.185742 0.131340 -0.973781 -v 0.062003 0.124750 0.015000 -vn -0.630263 0.297108 -0.717284 -v 0.063753 0.128250 0.015000 -vn -0.131339 0.185742 -0.973781 -v 0.063753 0.126250 0.015000 -vn -0.408249 0.408247 -0.816497 -v 0.062003 0.126250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.060128 0.108000 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.060128 0.108750 0.015000 -vn -0.185742 0.131340 -0.973781 -v 0.062003 0.108750 0.015000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.108750 0.015000 -vn -0.382683 0.000000 -0.923880 -v 0.060003 0.108000 0.015000 -vn -0.382683 0.000000 -0.923880 -v 0.060003 0.103500 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.103500 0.015000 -vn -0.185742 -0.131340 -0.973781 -v 0.062003 0.102250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.060128 0.103500 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.060128 0.102250 0.015000 -vn -0.297108 -0.630263 -0.717284 -v 0.060003 0.102250 0.015000 -vn -0.297108 -0.630262 -0.717284 -v 0.062003 0.092750 0.015000 -vn -0.062165 -0.122005 -0.990581 -v 0.065187 0.080686 0.015000 -vn -0.080485 -0.110777 -0.990581 -v 0.064652 0.081014 0.015000 -vn -0.135246 -0.021421 -0.990580 -v 0.063052 0.083624 0.015000 -vn -0.130227 -0.042313 -0.990581 -v 0.063199 0.083014 0.015000 -vn -0.096824 -0.096825 -0.990581 -v 0.064175 0.081422 0.015000 -vn -0.110778 -0.080485 -0.990581 -v 0.063767 0.081899 0.015000 -vn -0.122005 -0.062164 -0.990581 -v 0.063439 0.082434 0.015000 -vn 0.000001 -0.325772 -0.945448 -v 0.081003 0.084250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.081078 0.090550 0.015000 -vn -0.162895 -0.282142 -0.945442 -v 0.081503 0.084116 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.090550 0.015000 -vn -0.282123 -0.162886 -0.945450 -v 0.081869 0.083750 0.015000 -vn -0.325788 0.000001 -0.945443 -v 0.082003 0.083250 0.015000 -vn 0.110780 -0.080486 -0.990580 -v 0.086239 0.081899 0.015000 -vn 0.096824 -0.096825 -0.990581 -v 0.085831 0.081422 0.015000 -vn -0.282131 0.162884 -0.945447 -v 0.081869 0.082750 0.015000 -vn 0.062165 -0.122005 -0.990581 -v 0.084819 0.080686 0.015000 -vn 0.080485 -0.110778 -0.990581 -v 0.085354 0.081014 0.015000 -vn 0.133725 -0.005386 -0.991004 -v 0.087003 0.084250 0.015000 -vn 0.135244 -0.021421 -0.990581 -v 0.086954 0.083624 0.015000 -vn 0.130229 -0.042314 -0.990581 -v 0.086807 0.083014 0.015000 -vn 0.297108 -0.630263 -0.717284 -v 0.090003 0.094250 0.015000 -vn 0.185743 -0.131340 -0.973781 -v 0.088003 0.094250 0.015000 -vn 0.297109 -0.630262 -0.717283 -v 0.088003 0.092750 0.015000 -vn 0.065065 -0.041898 -0.997001 -v 0.087003 0.092750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.090550 0.015000 -vn -0.185742 -0.131340 -0.973781 -v 0.062003 0.118250 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.060128 0.118250 0.015000 -vn 0.318865 0.552291 -0.770260 -v 0.060878 0.120417 0.015000 -vn 0.000000 0.637725 -0.770264 -v 0.061503 0.120250 0.015000 -vn -0.707107 0.000000 -0.707107 -v 0.065003 0.118250 0.015000 -vn -0.669358 -0.088113 -0.737697 -v 0.065003 0.116550 0.015000 -vn -0.318866 0.552289 -0.770260 -v 0.062128 0.120417 0.015000 -vn -0.552287 0.318863 -0.770263 -v 0.062586 0.120875 0.015000 -vn -0.669358 0.088113 -0.737697 -v 0.065003 0.122950 0.015000 -vn -0.637728 -0.000002 -0.770261 -v 0.062753 0.121500 0.015000 -vn -0.552279 0.318861 -0.770270 -v 0.065043 0.123100 0.015000 -vn -0.552290 -0.318863 -0.770261 -v 0.062586 0.122125 0.015000 -vn -0.318868 -0.552287 -0.770261 -v 0.062128 0.122582 0.015000 -vn 0.000000 -0.637725 -0.770264 -v 0.061503 0.122750 0.015000 -vn 0.318867 -0.552288 -0.770261 -v 0.060878 0.122582 0.015000 -vn 0.552288 -0.318866 -0.770261 -v 0.060421 0.122125 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.060128 0.123000 0.015000 -vn 0.637727 -0.000002 -0.770263 -v 0.060253 0.121500 0.015000 -vn 0.552286 0.318866 -0.770263 -v 0.060421 0.120875 0.015000 -vn -0.318851 0.552299 -0.770260 -v 0.065153 0.123210 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.065878 0.123250 0.015000 -vn -0.088117 0.669356 -0.737698 -v 0.065303 0.123250 0.015000 -vn 0.669358 0.088113 -0.737697 -v 0.071003 0.122950 0.015000 -vn 0.552289 0.318854 -0.770265 -v 0.070963 0.123100 0.015000 -vn 0.318854 0.552289 -0.770265 -v 0.070853 0.123210 0.015000 -vn 0.088113 0.669358 -0.737697 -v 0.070703 0.123250 0.015000 -vn 0.000000 0.707107 -0.707107 -v 0.068928 0.123250 0.015000 -vn 0.669358 -0.088113 -0.737697 -v 0.071003 0.116550 0.015000 -vn 0.707107 0.000000 -0.707107 -v 0.071003 0.118250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.075003 0.118250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.075003 0.123000 0.015000 -vn -0.552288 0.318870 -0.770259 -v 0.079043 0.123100 0.015000 -vn 0.552289 -0.318854 -0.770265 -v 0.070963 0.116400 0.015000 -vn -0.669350 0.088128 -0.737702 -v 0.079003 0.122950 0.015000 -vn -0.088131 -0.669347 -0.737704 -v 0.065303 0.116250 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.065878 0.116250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065878 0.114000 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.068928 0.116250 0.015000 -vn 0.000000 -0.000000 -1.000000 -v 0.068928 0.114000 0.015000 -vn 0.088128 -0.669350 -0.737702 -v 0.070703 0.116250 0.015000 -vn 0.318870 -0.552288 -0.770260 -v 0.070853 0.116290 0.015000 -vn 0.131340 0.185742 -0.973781 -v 0.075503 0.102750 0.015000 -vn 0.000000 -0.000000 -1.000000 -v 0.075003 0.098250 0.015000 -vn 0.000001 0.000000 -1.000000 -v 0.075003 0.103500 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.079503 0.098250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.081078 0.110250 0.015000 -vn 0.000000 -0.382685 -0.923879 -v 0.081078 0.109250 0.015000 -vn 0.000000 -0.382685 -0.923879 -v 0.079503 0.109250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.108000 0.015000 -vn -0.382686 0.000000 -0.923879 -v 0.084803 0.108000 0.015000 -vn -0.110051 -0.110051 -0.987815 -v 0.084803 0.109250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.110250 0.015000 -vn -0.382686 0.000000 -0.923879 -v 0.084803 0.103500 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.103500 0.015000 -vn -0.110051 0.110051 -0.987815 -v 0.084803 0.102750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.068928 0.098250 0.015000 -vn -0.000000 0.382683 -0.923880 -v 0.068928 0.102750 0.015000 -vn -0.131339 0.185742 -0.973781 -v 0.074503 0.102750 0.015000 -vn -0.707106 0.000000 -0.707107 -v 0.074503 0.103500 0.015000 -vn 0.000001 0.000000 -1.000000 -v 0.075003 0.108000 0.015000 -vn -0.707106 0.000000 -0.707108 -v 0.074503 0.108000 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.075003 0.110250 0.015000 -vn -0.131340 -0.185743 -0.973781 -v 0.074503 0.109250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.068928 0.110250 0.015000 -vn -0.000000 -0.382685 -0.923879 -v 0.068928 0.109250 0.015000 -vn 0.000000 -0.382686 -0.923879 -v 0.065878 0.109250 0.015000 -vn -0.397392 0.546965 -0.736823 -v 0.071829 0.095119 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.068928 0.096200 0.015000 -vn -0.208922 0.642995 -0.736823 -v 0.073334 0.095886 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.075003 0.096200 0.015000 -vn -0.546963 0.397392 -0.736825 -v 0.070634 0.093924 0.015000 -vn -0.642996 0.208921 -0.736823 -v 0.069867 0.092419 0.015000 -vn -0.676083 -0.000000 -0.736825 -v 0.069603 0.090750 0.015000 -vn -0.642995 -0.208922 -0.736823 -v 0.069867 0.089081 0.015000 -vn -0.162893 -0.282134 -0.945445 -v 0.069503 0.084116 0.015000 -vn -0.546963 -0.397393 -0.736825 -v 0.070634 0.087576 0.015000 -vn -0.397392 -0.546965 -0.736823 -v 0.071829 0.086381 0.015000 -vn 0.546964 0.397393 -0.736824 -v 0.079372 0.093924 0.015000 -vn 0.397392 0.546964 -0.736824 -v 0.078177 0.095119 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.079503 0.096200 0.015000 -vn 0.208922 0.642995 -0.736824 -v 0.076672 0.095886 0.015000 -vn 0.000000 0.676085 -0.736824 -v 0.075003 0.096150 0.015000 -vn 0.282135 -0.162893 -0.945445 -v 0.080137 0.083750 0.015000 -vn 0.325772 0.000001 -0.945448 -v 0.080003 0.083250 0.015000 -vn 0.546964 -0.397393 -0.736824 -v 0.079372 0.087576 0.015000 -vn 0.000000 -0.130526 -0.991445 -v 0.079503 0.080250 0.015000 -vn 0.397392 -0.546964 -0.736824 -v 0.078177 0.086381 0.015000 -vn 0.642995 0.208922 -0.736824 -v 0.080139 0.092419 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.081078 0.096200 0.015000 -vn 0.676085 -0.000000 -0.736824 -v 0.080403 0.090750 0.015000 -vn 0.642994 -0.208922 -0.736824 -v 0.080139 0.089081 0.015000 -vn 0.162891 -0.282135 -0.945445 -v 0.080503 0.084116 0.015000 -vn 0.042313 -0.130227 -0.990581 -v 0.084239 0.080446 0.015000 -vn 0.021421 -0.135244 -0.990581 -v 0.083629 0.080299 0.015000 -vn -0.162892 0.282144 -0.945442 -v 0.081503 0.082384 0.015000 -vn 0.005386 -0.133725 -0.991004 -v 0.083003 0.080250 0.015000 -vn -0.000002 0.325772 -0.945448 -v 0.081003 0.082250 0.015000 -vn 0.000000 -0.130526 -0.991445 -v 0.081078 0.080250 0.015000 -vn 0.162892 0.282137 -0.945444 -v 0.080503 0.082384 0.015000 -vn 0.282142 0.162892 -0.945443 -v 0.080137 0.082750 0.015000 -vn 0.208922 -0.642995 -0.736824 -v 0.076672 0.085614 0.015000 -vn -0.000000 -0.325771 -0.945449 -v 0.067003 0.097750 0.015000 -vn 0.162885 -0.282125 -0.945449 -v 0.066503 0.097616 0.015000 -vn -0.282135 -0.162891 -0.945445 -v 0.067869 0.097250 0.015000 -vn -0.162884 -0.282126 -0.945449 -v 0.067503 0.097616 0.015000 -vn -0.000001 0.325772 -0.945448 -v 0.067003 0.095750 0.015000 -vn -0.162891 0.282135 -0.945445 -v 0.067503 0.095884 0.015000 -vn -0.282135 0.162892 -0.945445 -v 0.067869 0.096250 0.015000 -vn -0.325772 -0.000001 -0.945448 -v 0.068003 0.096750 0.015000 -vn 0.282124 -0.162882 -0.945450 -v 0.066137 0.097250 0.015000 -vn 0.325788 -0.000002 -0.945443 -v 0.066003 0.096750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065878 0.096200 0.015000 -vn 0.282125 0.162885 -0.945449 -v 0.066137 0.096250 0.015000 -vn 0.162893 0.282134 -0.945445 -v 0.066503 0.095884 0.015000 -vn 0.162885 -0.282124 -0.945449 -v 0.082503 0.097616 0.015000 -vn 0.282124 -0.162885 -0.945449 -v 0.082137 0.097250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.081078 0.098250 0.015000 -vn -0.000000 -0.325771 -0.945449 -v 0.083003 0.097750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.096200 0.015000 -vn -0.325771 0.000000 -0.945449 -v 0.084003 0.096750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.084903 0.098250 0.015000 -vn -0.282124 -0.162885 -0.945449 -v 0.083869 0.097250 0.015000 -vn -0.162885 -0.282124 -0.945449 -v 0.083503 0.097616 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.081078 0.102750 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.079503 0.102750 0.015000 -vn -0.162891 0.282135 -0.945445 -v 0.083503 0.095884 0.015000 -vn -0.282126 0.162884 -0.945449 -v 0.083869 0.096250 0.015000 -vn 0.325771 -0.000000 -0.945449 -v 0.082003 0.096750 0.015000 -vn 0.282125 0.162885 -0.945449 -v 0.082137 0.096250 0.015000 -vn 0.162893 0.282134 -0.945445 -v 0.082503 0.095884 0.015000 -vn -0.000001 0.325772 -0.945448 -v 0.083003 0.095750 0.015000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.100750 0.015000 -vn -0.382683 0.000000 -0.923880 -v 0.060003 0.098250 0.015000 -vn -0.382683 0.000000 -0.923880 -v 0.060003 0.096200 0.015000 -vn -0.297108 -0.630263 -0.717284 -v 0.060003 0.094250 0.015000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.116750 0.015000 -vn -0.382683 0.000000 -0.923880 -v 0.060003 0.114000 0.015000 -vn -0.297108 -0.630262 -0.717284 -v 0.060003 0.110250 0.015000 -vn -0.297108 0.630263 -0.717284 -v 0.060003 0.124750 0.015000 -vn -0.382683 0.000000 -0.923880 -v 0.060003 0.124375 0.015000 -vn -0.382683 0.000000 -0.923880 -v 0.060003 0.123000 0.015000 -vn -0.297108 -0.630263 -0.717284 -v 0.060003 0.118250 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065103 0.108000 0.015000 -vn -0.318864 -0.552287 -0.770263 -v 0.062128 0.106582 0.015000 -vn 0.000000 -0.637728 -0.770261 -v 0.061503 0.106750 0.015000 -vn 0.318863 -0.552289 -0.770262 -v 0.060878 0.106582 0.015000 -vn 0.552288 -0.318865 -0.770261 -v 0.060421 0.106125 0.015000 -vn 0.637727 0.000000 -0.770263 -v 0.060253 0.105500 0.015000 -vn 0.552288 0.318865 -0.770261 -v 0.060421 0.104875 0.015000 -vn -0.318864 0.552287 -0.770263 -v 0.062128 0.104417 0.015000 -vn -0.000000 0.637728 -0.770261 -v 0.061503 0.104250 0.015000 -vn 0.318863 0.552289 -0.770262 -v 0.060878 0.104417 0.015000 -vn -0.552290 0.318862 -0.770262 -v 0.062586 0.104875 0.015000 -vn -0.637728 -0.000000 -0.770261 -v 0.062753 0.105500 0.015000 -vn -0.552290 -0.318862 -0.770262 -v 0.062586 0.106125 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.065878 0.110250 0.015000 -vn 0.000001 -0.325772 -0.945448 -v 0.067003 0.113250 0.015000 -vn 0.162891 -0.282135 -0.945445 -v 0.066503 0.113116 0.015000 -vn 0.162893 0.282134 -0.945445 -v 0.066503 0.111384 0.015000 -vn -0.000001 0.325772 -0.945448 -v 0.067003 0.111250 0.015000 -vn 0.282132 -0.162885 -0.945447 -v 0.066137 0.112750 0.015000 -vn 0.325788 -0.000002 -0.945443 -v 0.066003 0.112250 0.015000 -vn 0.282125 0.162885 -0.945449 -v 0.066137 0.111750 0.015000 -vn 0.110050 -0.110050 -0.987815 -v 0.065203 0.109250 0.015000 -vn 0.382680 0.000000 -0.923881 -v 0.065203 0.108000 0.015000 -vn 0.382680 0.000000 -0.923881 -v 0.065203 0.103500 0.015000 -vn -0.162891 0.282135 -0.945445 -v 0.067503 0.111384 0.015000 -vn -0.282135 0.162892 -0.945445 -v 0.067869 0.111750 0.015000 -vn -0.325772 -0.000002 -0.945448 -v 0.068003 0.112250 0.015000 -vn -0.162892 -0.282137 -0.945444 -v 0.067503 0.113116 0.015000 -vn -0.282143 -0.162893 -0.945443 -v 0.067869 0.112750 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.081078 0.114000 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.079503 0.110250 0.015000 -vn 0.131340 -0.185743 -0.973781 -v 0.075503 0.109250 0.015000 -vn 0.707107 0.000000 -0.707107 -v 0.075503 0.108000 0.015000 -vn 0.707107 0.000000 -0.707107 -v 0.075503 0.103500 0.015000 -vn 0.000001 -0.325772 -0.945448 -v 0.083003 0.113250 0.015000 -vn 0.162891 -0.282135 -0.945445 -v 0.082503 0.113116 0.015000 -vn -0.162892 -0.282135 -0.945445 -v 0.083503 0.113116 0.015000 -vn 0.000000 -0.707107 -0.707107 -v 0.079503 0.116250 0.015000 -vn 0.282124 0.162885 -0.945449 -v 0.082137 0.111750 0.015000 -vn 0.325771 -0.000001 -0.945449 -v 0.082003 0.112250 0.015000 -vn 0.282132 -0.162887 -0.945447 -v 0.082137 0.112750 0.015000 -vn 0.162893 0.282134 -0.945445 -v 0.082503 0.111384 0.015000 -vn -0.000001 0.325772 -0.945448 -v 0.083003 0.111250 0.015000 -vn -0.162891 0.282135 -0.945445 -v 0.083503 0.111384 0.015000 -vn -0.282126 0.162884 -0.945449 -v 0.083869 0.111750 0.015000 -vn -0.325770 -0.000000 -0.945449 -v 0.084003 0.112250 0.015000 -vn -0.282132 -0.162887 -0.945447 -v 0.083869 0.112750 0.015000 -vn 0.318866 -0.552291 -0.770260 -v 0.082378 0.127832 0.015000 -vn -0.000000 -0.637725 -0.770264 -v 0.083003 0.128000 0.015000 -vn 0.000000 0.382683 -0.923880 -v 0.084903 0.128250 0.015000 -vn -0.318866 -0.552291 -0.770260 -v 0.083628 0.127832 0.015000 -vn -0.552286 -0.318865 -0.770263 -v 0.084086 0.127375 0.015000 -vn 0.552291 0.318862 -0.770261 -v 0.081921 0.126125 0.015000 -vn 0.637728 0.000000 -0.770261 -v 0.081753 0.126750 0.015000 -vn 0.552286 -0.318865 -0.770263 -v 0.081921 0.127375 0.015000 -vn -0.552291 0.318862 -0.770261 -v 0.084086 0.126125 0.015000 -vn -0.637728 -0.000000 -0.770261 -v 0.084253 0.126750 0.015000 -vn 0.318861 0.552286 -0.770265 -v 0.082378 0.125667 0.015000 -vn 0.000000 0.637732 -0.770258 -v 0.083003 0.125500 0.015000 -vn -0.318861 0.552286 -0.770265 -v 0.083628 0.125667 0.015000 -vn 0.122004 -0.062165 -0.990581 -v 0.086567 0.082434 0.015000 -vn 0.637725 -0.000000 -0.770264 -v 0.087253 0.105500 0.015000 -vn 0.552291 0.318866 -0.770260 -v 0.087421 0.104875 0.015000 -vn 0.318864 -0.552286 -0.770263 -v 0.087878 0.106582 0.015000 -vn 0.552291 -0.318866 -0.770260 -v 0.087421 0.106125 0.015000 -vn 0.318864 0.552286 -0.770264 -v 0.087878 0.104417 0.015000 -vn -0.000001 0.637729 -0.770261 -v 0.088503 0.104250 0.015000 -vn -0.318865 0.552286 -0.770263 -v 0.089128 0.104417 0.015000 -vn -0.552291 0.318866 -0.770260 -v 0.089586 0.104875 0.015000 -vn -0.637725 0.000000 -0.770264 -v 0.089753 0.105500 0.015000 -vn -0.552291 -0.318866 -0.770260 -v 0.089586 0.106125 0.015000 -vn -0.318867 0.552288 -0.770261 -v 0.089128 0.120417 0.015000 -vn 0.297108 -0.630263 -0.717284 -v 0.090003 0.118250 0.015000 -vn -0.000001 0.637726 -0.770264 -v 0.088503 0.120250 0.015000 -vn 0.318866 0.552288 -0.770261 -v 0.087878 0.120417 0.015000 -vn 0.552288 0.318866 -0.770261 -v 0.087421 0.120875 0.015000 -vn -0.552288 0.318866 -0.770261 -v 0.089586 0.120875 0.015000 -vn -0.637725 -0.000002 -0.770264 -v 0.089753 0.121500 0.015000 -vn 0.382683 0.000000 -0.923880 -v 0.090003 0.123000 0.015000 -vn -0.552291 -0.318867 -0.770259 -v 0.089586 0.122125 0.015000 -vn -0.318869 -0.552286 -0.770262 -v 0.089128 0.122582 0.015000 -vn -0.000001 -0.637726 -0.770264 -v 0.088503 0.122750 0.015000 -vn 0.318868 -0.552286 -0.770262 -v 0.087878 0.122582 0.015000 -vn 0.000000 0.000000 -1.000000 -v 0.086128 0.123000 0.015000 -vn 0.552291 -0.318867 -0.770259 -v 0.087421 0.122125 0.015000 -vn 0.637725 -0.000002 -0.770264 -v 0.087253 0.121500 0.015000 -vn 0.552289 0.318854 -0.770266 -v 0.084963 0.123100 0.015000 -vn -0.904534 0.301511 0.301511 -v 0.059003 0.095500 0.017000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.096875 0.017000 -vn 0.637727 -0.000000 0.770263 -v 0.060253 0.097500 0.017000 -vn -0.792406 0.000001 0.609994 -v 0.063812 0.097500 0.017000 -vn -0.637728 0.000000 0.770261 -v 0.062753 0.097500 0.017000 -vn -0.552290 0.318862 0.770262 -v 0.062586 0.096875 0.017000 -vn -0.904534 -0.301511 0.301511 -v 0.059003 0.099500 0.017000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.098125 0.017000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.098582 0.017000 -vn -0.396204 -0.686243 0.609994 -v 0.062658 0.099500 0.017000 -vn -0.396203 0.686244 0.609994 -v 0.062658 0.095500 0.017000 -vn -0.318864 0.552287 0.770263 -v 0.062128 0.096417 0.017000 -vn 0.000000 0.637728 0.770261 -v 0.061503 0.096250 0.017000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.096417 0.017000 -vn -0.000000 -0.637729 0.770261 -v 0.061503 0.098750 0.017000 -vn -0.318864 -0.552287 0.770263 -v 0.062128 0.098582 0.017000 -vn -0.552290 -0.318862 0.770262 -v 0.062586 0.098125 0.017000 -vn -0.396203 -0.686244 0.609994 -v 0.062658 0.107500 0.017000 -vn -0.318864 -0.552287 0.770263 -v 0.062128 0.106582 0.017000 -vn -0.792406 -0.000001 0.609994 -v 0.063812 0.105500 0.017000 -vn -0.552290 -0.318862 0.770262 -v 0.062586 0.106125 0.017000 -vn -0.396204 0.686243 0.609994 -v 0.062658 0.103500 0.017000 -vn 0.000000 0.637728 0.770261 -v 0.061503 0.104250 0.017000 -vn -0.904534 0.301511 0.301511 -v 0.059003 0.103500 0.017000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.104417 0.017000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.104875 0.017000 -vn 0.637727 -0.000000 0.770263 -v 0.060253 0.105500 0.017000 -vn -0.904534 -0.301511 0.301511 -v 0.059003 0.107500 0.017000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.106125 0.017000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.106582 0.017000 -vn -0.000000 -0.637728 0.770261 -v 0.061503 0.106750 0.017000 -vn -0.637728 0.000000 0.770261 -v 0.062753 0.105500 0.017000 -vn -0.552290 0.318862 0.770262 -v 0.062586 0.104875 0.017000 -vn -0.318864 0.552287 0.770263 -v 0.062128 0.104417 0.017000 -vn -0.396204 0.686243 0.609994 -v 0.062658 0.111500 0.017000 -vn 0.000000 0.637728 0.770261 -v 0.061503 0.112250 0.017000 -vn -0.904534 0.301511 0.301511 -v 0.059003 0.111500 0.017000 -vn 0.318863 0.552289 0.770262 -v 0.060878 0.112417 0.017000 -vn -0.792406 -0.000001 0.609994 -v 0.063812 0.113500 0.017000 -vn -0.552290 0.318862 0.770262 -v 0.062586 0.112875 0.017000 -vn -0.318864 0.552287 0.770263 -v 0.062128 0.112417 0.017000 -vn 0.552288 0.318865 0.770261 -v 0.060421 0.112875 0.017000 -vn 0.637727 -0.000000 0.770263 -v 0.060253 0.113500 0.017000 -vn -0.904534 -0.301511 0.301511 -v 0.059003 0.115500 0.017000 -vn -0.000000 -0.637728 0.770261 -v 0.061503 0.114750 0.017000 -vn -0.396203 -0.686244 0.609994 -v 0.062658 0.115500 0.017000 -vn 0.318863 -0.552289 0.770262 -v 0.060878 0.114582 0.017000 -vn 0.552288 -0.318865 0.770261 -v 0.060421 0.114125 0.017000 -vn -0.318864 -0.552287 0.770263 -v 0.062128 0.114582 0.017000 -vn -0.552290 -0.318862 0.770262 -v 0.062586 0.114125 0.017000 -vn -0.637728 0.000000 0.770261 -v 0.062753 0.113500 0.017000 -vn -0.000000 -0.000000 1.000000 -v 0.064278 0.083400 0.020000 -vn 0.301511 -0.301511 0.904534 -v 0.089503 0.118250 0.020000 -vn 0.297108 -0.630263 0.717284 -v 0.090003 0.118250 0.020000 -vn 0.427644 0.516597 0.741787 -v 0.090003 0.119500 0.020000 -vn -0.301512 0.301511 0.904534 -v 0.060503 0.108750 0.020000 -vn -0.297108 0.630263 0.717284 -v 0.060003 0.108750 0.020000 -vn -0.427643 -0.516597 0.741787 -v 0.060003 0.107500 0.020000 -vn -0.427643 0.516597 0.741787 -v 0.060003 0.095500 0.020000 -vn -0.297108 -0.630263 0.717284 -v 0.060003 0.094250 0.020000 -vn -0.452906 0.279911 0.846478 -v 0.062003 0.096500 0.020000 -vn -0.301511 -0.301511 0.904534 -v 0.060503 0.094250 0.020000 -vn -0.707107 0.000000 0.707107 -v 0.060503 0.093925 0.020000 -vn -0.000000 -0.000000 1.000000 -v 0.064278 0.093925 0.020000 -vn -0.452907 -0.279911 0.846478 -v 0.062003 0.098500 0.020000 -vn -0.000000 -0.000000 1.000000 -v 0.064278 0.100700 0.020000 -vn -0.427644 -0.516597 0.741787 -v 0.060003 0.099500 0.020000 -vn -0.301511 0.301514 0.904533 -v 0.060503 0.100750 0.020000 -vn -0.297108 0.630263 0.717284 -v 0.060003 0.100750 0.020000 -vn -0.382683 0.000000 0.923880 -v 0.060003 0.100700 0.020000 -vn -0.452907 0.279911 0.846478 -v 0.062003 0.104500 0.020000 -vn -0.427644 0.516597 0.741787 -v 0.060003 0.103500 0.020000 -vn -0.297108 -0.630263 0.717284 -v 0.060003 0.102250 0.020000 -vn -0.000000 0.000000 1.000000 -v 0.064278 0.109800 0.020000 -vn -0.452906 -0.279911 0.846478 -v 0.062003 0.106500 0.020000 -vn -0.301511 -0.301511 0.904534 -v 0.060503 0.102250 0.020000 -vn -0.452907 0.279911 0.846478 -v 0.062003 0.112500 0.020000 -vn -0.427644 0.516597 0.741787 -v 0.060003 0.111500 0.020000 -vn -0.297108 -0.630263 0.717284 -v 0.060003 0.110250 0.020000 -vn -0.000000 -0.000000 1.000000 -v 0.064278 0.118000 0.020000 -vn -0.707107 0.000000 0.707107 -v 0.060503 0.118000 0.020000 -vn -0.301512 0.301511 0.904534 -v 0.060503 0.116750 0.020000 -vn -0.452907 -0.279911 0.846478 -v 0.062003 0.114500 0.020000 -vn -0.707107 0.000000 0.707107 -v 0.060503 0.109800 0.020000 -vn -0.301511 -0.301511 0.904534 -v 0.060503 0.110250 0.020000 -vn -0.301512 -0.301511 0.904534 -v 0.060503 0.118250 0.020000 -vn -0.452907 -0.279911 0.846478 -v 0.062003 0.122500 0.020000 -vn -0.452908 0.279912 0.846477 -v 0.062003 0.120500 0.020000 -vn 0.108876 0.188583 0.976003 -v 0.064153 0.122971 0.020000 -vn -0.301512 0.301511 0.904534 -v 0.062003 0.126250 0.020000 -vn -0.577350 0.577350 0.577350 -v 0.060503 0.126250 0.020000 -vn -0.301511 0.301511 0.904534 -v 0.060503 0.124750 0.020000 -vn 0.188578 0.108878 0.976004 -v 0.063824 0.123300 0.020000 -vn -0.427644 -0.516597 0.741787 -v 0.060003 0.123500 0.020000 -vn -0.297108 0.630263 0.717284 -v 0.060003 0.124750 0.020000 -vn 0.108874 -0.188581 0.976004 -v 0.064153 0.124529 0.020000 -vn 0.188579 -0.108877 0.976004 -v 0.063824 0.124200 0.020000 -vn 0.217757 0.000000 0.976003 -v 0.063703 0.123750 0.020000 -vn -0.577350 0.577350 0.577350 -v 0.062003 0.127750 0.020000 -vn -0.707107 0.000000 0.707107 -v 0.062003 0.126450 0.020000 -vn -0.301513 0.301511 0.904533 -v 0.063753 0.127750 0.020000 -vn -0.000001 0.000000 1.000000 -v 0.064278 0.126450 0.020000 -vn -0.630264 0.297108 0.717283 -v 0.063753 0.128250 0.020000 -vn -0.000002 0.382683 0.923880 -v 0.064278 0.128250 0.020000 -vn 0.630263 0.297108 0.717284 -v 0.070253 0.128250 0.020000 -vn -0.516597 0.427644 0.741787 -v 0.069003 0.128250 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.070253 0.127750 0.020000 -vn -0.279911 0.452906 0.846478 -v 0.068003 0.126250 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.071828 0.127750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.071828 0.126450 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.075003 0.127750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.126450 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.078178 0.127750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.078178 0.126450 0.020000 -vn -0.301511 0.301511 0.904534 -v 0.079753 0.127750 0.020000 -vn 0.279912 0.452905 0.846479 -v 0.082003 0.126250 0.020000 -vn -0.630263 0.297108 0.717284 -v 0.079753 0.128250 0.020000 -vn 0.516598 0.427643 0.741787 -v 0.081003 0.128250 0.020000 -vn -0.279912 0.452905 0.846479 -v 0.084003 0.126250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.084203 0.126450 0.020000 -vn -0.516598 0.427643 0.741787 -v 0.085003 0.128250 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.086253 0.127750 0.020000 -vn 0.630263 0.297108 0.717284 -v 0.086253 0.128250 0.020000 -vn 0.452906 0.279911 0.846478 -v 0.088003 0.120500 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.084203 0.118000 0.020000 -vn 0.707107 0.000000 0.707107 -v 0.089503 0.118000 0.020000 -vn 0.000001 -0.217756 0.976003 -v 0.085403 0.124650 0.020000 -vn -0.108876 -0.188579 0.976004 -v 0.085853 0.124529 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.089503 0.124750 0.020000 -vn -0.188582 -0.108877 0.976003 -v 0.086182 0.124200 0.020000 -vn -0.217755 -0.000000 0.976004 -v 0.086303 0.123750 0.020000 -vn 0.108877 0.188588 0.976002 -v 0.084953 0.122971 0.020000 -vn 0.188580 0.108876 0.976004 -v 0.084624 0.123300 0.020000 -vn 0.217769 0.000002 0.976000 -v 0.084503 0.123750 0.020000 -vn 0.188581 -0.108878 0.976004 -v 0.084624 0.124200 0.020000 -vn 0.108880 -0.188586 0.976002 -v 0.084953 0.124529 0.020000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.124750 0.020000 -vn 0.427644 -0.516596 0.741788 -v 0.090003 0.123500 0.020000 -vn 0.452906 -0.279911 0.846478 -v 0.088003 0.122500 0.020000 -vn -0.188581 0.108878 0.976004 -v 0.086182 0.123300 0.020000 -vn -0.108877 0.188580 0.976004 -v 0.085853 0.122971 0.020000 -vn -0.000002 0.217756 0.976003 -v 0.085403 0.122850 0.020000 -vn 0.577350 0.577350 0.577350 -v 0.089503 0.126250 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.088003 0.126250 0.020000 -vn 0.707107 0.000000 0.707107 -v 0.088003 0.126450 0.020000 -vn 0.577350 0.577350 0.577350 -v 0.088003 0.127750 0.020000 -vn 0.707107 0.000000 0.707107 -v 0.089503 0.109800 0.020000 -vn 0.301511 -0.301511 0.904534 -v 0.089503 0.110250 0.020000 -vn 0.427644 -0.516597 0.741788 -v 0.090003 0.115500 0.020000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.116750 0.020000 -vn 0.452906 -0.279911 0.846478 -v 0.088003 0.114500 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.089503 0.116750 0.020000 -vn 0.452906 0.279911 0.846479 -v 0.088003 0.112500 0.020000 -vn 0.427644 0.516597 0.741787 -v 0.090003 0.111500 0.020000 -vn 0.297108 -0.630263 0.717284 -v 0.090003 0.110250 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.082728 0.108250 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.084203 0.108250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.084203 0.109800 0.020000 -vn -0.301511 -0.301511 0.904534 -v 0.084503 0.108250 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.089503 0.100750 0.020000 -vn 0.301511 -0.301511 0.904534 -v 0.089503 0.102250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.084203 0.100700 0.020000 -vn 0.382683 0.000000 0.923880 -v 0.090003 0.100700 0.020000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.100750 0.020000 -vn 0.427643 -0.516597 0.741787 -v 0.090003 0.107500 0.020000 -vn 0.297108 0.630263 0.717284 -v 0.090003 0.108750 0.020000 -vn 0.452906 -0.279912 0.846479 -v 0.088003 0.106500 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.089503 0.108750 0.020000 -vn 0.297108 -0.630263 0.717284 -v 0.090003 0.102250 0.020000 -vn 0.427644 0.516597 0.741787 -v 0.090003 0.103500 0.020000 -vn 0.452907 0.279911 0.846478 -v 0.088003 0.104500 0.020000 -vn 0.707107 0.000000 0.707107 -v 0.089503 0.093925 0.020000 -vn 0.301511 -0.301511 0.904534 -v 0.089503 0.094250 0.020000 -vn 0.427644 -0.516597 0.741788 -v 0.090003 0.099500 0.020000 -vn 0.452906 -0.279911 0.846478 -v 0.088003 0.098500 0.020000 -vn 0.452906 0.279912 0.846479 -v 0.088003 0.096500 0.020000 -vn 0.427643 0.516597 0.741787 -v 0.090003 0.095500 0.020000 -vn 0.297108 -0.630263 0.717284 -v 0.090003 0.094250 0.020000 -vn 0.707106 0.000001 0.707108 -v 0.088003 0.086825 0.020000 -vn 0.301511 -0.301511 0.904534 -v 0.088003 0.092750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.084203 0.093925 0.020000 -vn -0.188580 -0.108876 0.976004 -v 0.085032 0.082200 0.020000 -vn -0.217757 -0.000000 0.976003 -v 0.085153 0.081750 0.020000 -vn -0.188579 0.108876 0.976004 -v 0.085032 0.081300 0.020000 -vn -0.108884 0.188590 0.976001 -v 0.084703 0.080971 0.020000 -vn 0.000001 0.217756 0.976003 -v 0.084253 0.080850 0.020000 -vn 0.108883 0.188590 0.976001 -v 0.083803 0.080971 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.082728 0.079250 0.020000 -vn 0.188590 0.108884 0.976001 -v 0.083474 0.081300 0.020000 -vn 0.217756 -0.000001 0.976003 -v 0.083353 0.081750 0.020000 -vn 0.188590 -0.108883 0.976001 -v 0.083474 0.082200 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082728 0.083400 0.020000 -vn 0.108884 -0.188590 0.976001 -v 0.083803 0.082529 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.084203 0.083400 0.020000 -vn -0.000001 -0.217756 0.976003 -v 0.084253 0.082650 0.020000 -vn -0.108882 -0.188591 0.976001 -v 0.084703 0.082529 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.065803 0.083400 0.020000 -vn -0.000001 -0.217756 0.976003 -v 0.065753 0.082650 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.067278 0.083400 0.020000 -vn -0.108882 -0.188591 0.976001 -v 0.066203 0.082529 0.020000 -vn -0.188580 -0.108876 0.976004 -v 0.066532 0.082200 0.020000 -vn -0.217757 -0.000000 0.976003 -v 0.066653 0.081750 0.020000 -vn -0.188579 0.108876 0.976004 -v 0.066532 0.081300 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.067278 0.079250 0.020000 -vn -0.108884 0.188590 0.976001 -v 0.066203 0.080971 0.020000 -vn 0.000001 0.217756 0.976003 -v 0.065753 0.080850 0.020000 -vn 0.108883 0.188590 0.976001 -v 0.065303 0.080971 0.020000 -vn 0.188590 0.108884 0.976001 -v 0.064974 0.081300 0.020000 -vn 0.217756 -0.000001 0.976003 -v 0.064853 0.081750 0.020000 -vn 0.188590 -0.108883 0.976001 -v 0.064974 0.082200 0.020000 -vn 0.108884 -0.188590 0.976001 -v 0.065303 0.082529 0.020000 -vn -0.000000 -0.000000 1.000000 -v 0.064278 0.086825 0.020000 -vn -0.577350 -0.577350 0.577350 -v 0.060503 0.092750 0.020000 -vn -0.301512 -0.301512 0.904534 -v 0.062003 0.092750 0.020000 -vn -0.707107 0.000000 0.707107 -v 0.062003 0.086825 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.075503 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.100700 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.078178 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.078178 0.100700 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.082003 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082003 0.100700 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.082728 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082728 0.100700 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.084203 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.109800 0.020000 -vn 0.301511 -0.301511 0.904534 -v 0.075503 0.108250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.078178 0.109800 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.078178 0.108250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082003 0.109800 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.082003 0.108250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082728 0.109800 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.065803 0.108250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.065803 0.109800 0.020000 -vn 0.301511 -0.301511 0.904534 -v 0.065503 0.108250 0.020000 -vn 0.301511 0.301511 0.904534 -v 0.065503 0.103750 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.065803 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.071828 0.109800 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.071828 0.108250 0.020000 -vn -0.301511 -0.301511 0.904534 -v 0.074503 0.108250 0.020000 -vn -0.301511 0.301511 0.904534 -v 0.074503 0.103750 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.067278 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.067278 0.100700 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.068003 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.068003 0.100700 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.071828 0.103750 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.071828 0.100700 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.068003 0.108250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.068003 0.109800 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.067278 0.108250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.067278 0.109800 0.020000 -vn -0.108876 -0.188579 0.976004 -v 0.065053 0.124529 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.065803 0.126450 0.020000 -vn 0.000000 -0.217757 0.976003 -v 0.064603 0.124650 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.065803 0.118000 0.020000 -vn -0.108877 0.188582 0.976003 -v 0.065053 0.122971 0.020000 -vn -0.427644 0.516597 0.741787 -v 0.060003 0.119500 0.020000 -vn -0.297108 -0.630263 0.717284 -v 0.060003 0.118250 0.020000 -vn -0.000000 0.217755 0.976004 -v 0.064603 0.122850 0.020000 -vn -0.188590 -0.108884 0.976001 -v 0.065382 0.124200 0.020000 -vn -0.217756 0.000001 0.976003 -v 0.065503 0.123750 0.020000 -vn -0.188590 0.108883 0.976001 -v 0.065382 0.123300 0.020000 -vn 0.637729 0.000001 0.770261 -v 0.073753 0.090750 0.020000 -vn 0.552286 -0.318864 0.770263 -v 0.073921 0.091375 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.071828 0.093925 0.020000 -vn 0.318866 -0.552291 0.770260 -v 0.074378 0.091832 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.093925 0.020000 -vn 0.000000 -0.637725 0.770264 -v 0.075003 0.092000 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.078178 0.093925 0.020000 -vn -0.318866 -0.552291 0.770260 -v 0.075628 0.091832 0.020000 -vn -0.552286 -0.318864 0.770263 -v 0.076086 0.091375 0.020000 -vn -0.637729 0.000001 0.770261 -v 0.076253 0.090750 0.020000 -vn -0.552286 0.318865 0.770263 -v 0.076086 0.090125 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.078178 0.086825 0.020000 -vn -0.318865 0.552291 0.770260 -v 0.075628 0.089667 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.086825 0.020000 -vn -0.000000 0.637725 0.770264 -v 0.075003 0.089500 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.071828 0.086825 0.020000 -vn 0.318865 0.552291 0.770260 -v 0.074378 0.089667 0.020000 -vn 0.552286 0.318865 0.770263 -v 0.073921 0.090125 0.020000 -vn 0.637731 -0.000003 0.770259 -v 0.068103 0.083250 0.020000 -vn 0.552289 -0.318862 0.770262 -v 0.068224 0.083700 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.068003 0.086825 0.020000 -vn 0.318861 -0.552289 0.770263 -v 0.068553 0.084029 0.020000 -vn 0.000000 -0.637731 0.770259 -v 0.069003 0.084150 0.020000 -vn -0.318863 -0.552285 0.770264 -v 0.069453 0.084029 0.020000 -vn -0.637726 -0.000003 0.770263 -v 0.069903 0.083250 0.020000 -vn -0.552289 0.318865 0.770262 -v 0.069782 0.082800 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.071828 0.079250 0.020000 -vn -0.318861 0.552289 0.770263 -v 0.069453 0.082471 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.068003 0.079250 0.020000 -vn -0.000000 0.637731 0.770259 -v 0.069003 0.082350 0.020000 -vn 0.318858 0.552292 0.770262 -v 0.068553 0.082471 0.020000 -vn 0.318863 0.552285 0.770264 -v 0.066553 0.095971 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.065803 0.093925 0.020000 -vn -0.000000 0.637731 0.770259 -v 0.067003 0.095850 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.067278 0.093925 0.020000 -vn -0.318861 0.552289 0.770263 -v 0.067453 0.095971 0.020000 -vn 0.318866 -0.552288 0.770261 -v 0.066553 0.097529 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.065803 0.100700 0.020000 -vn 0.552292 0.318864 0.770260 -v 0.066224 0.096300 0.020000 -vn 0.637726 -0.000000 0.770263 -v 0.066103 0.096750 0.020000 -vn 0.552288 -0.318866 0.770261 -v 0.066224 0.097200 0.020000 -vn -0.000000 -0.637726 0.770263 -v 0.067003 0.097650 0.020000 -vn -0.318864 -0.552292 0.770260 -v 0.067453 0.097529 0.020000 -vn -0.552285 -0.318863 0.770264 -v 0.067782 0.097200 0.020000 -vn -0.552289 0.318861 0.770263 -v 0.067782 0.096300 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.068003 0.093925 0.020000 -vn -0.637731 -0.000000 0.770259 -v 0.067903 0.096750 0.020000 -vn 0.318863 0.552285 0.770264 -v 0.066553 0.111471 0.020000 -vn 0.552292 0.318864 0.770260 -v 0.066224 0.111800 0.020000 -vn 0.637726 -0.000000 0.770263 -v 0.066103 0.112250 0.020000 -vn 0.552288 -0.318866 0.770261 -v 0.066224 0.112700 0.020000 -vn 0.318861 -0.552289 0.770263 -v 0.066553 0.113029 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.067278 0.118000 0.020000 -vn -0.000000 0.637731 0.770259 -v 0.067003 0.111350 0.020000 -vn 0.000000 -0.637731 0.770259 -v 0.067003 0.113150 0.020000 -vn -0.318858 -0.552292 0.770262 -v 0.067453 0.113029 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.068003 0.118000 0.020000 -vn -0.552285 -0.318863 0.770264 -v 0.067782 0.112700 0.020000 -vn -0.637731 -0.000000 0.770259 -v 0.067903 0.112250 0.020000 -vn -0.552289 0.318861 0.770263 -v 0.067782 0.111800 0.020000 -vn -0.318861 0.552289 0.770263 -v 0.067453 0.111471 0.020000 -vn 0.637731 -0.000003 0.770259 -v 0.080103 0.083250 0.020000 -vn 0.552289 -0.318862 0.770262 -v 0.080224 0.083700 0.020000 -vn 0.318861 -0.552289 0.770263 -v 0.080553 0.084029 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082003 0.086825 0.020000 -vn 0.000000 -0.637731 0.770259 -v 0.081003 0.084150 0.020000 -vn -0.318863 -0.552285 0.770264 -v 0.081453 0.084029 0.020000 -vn -0.637726 -0.000003 0.770263 -v 0.081903 0.083250 0.020000 -vn -0.552288 0.318865 0.770262 -v 0.081782 0.082800 0.020000 -vn 0.000000 -0.707106 0.707107 -v 0.082003 0.079250 0.020000 -vn -0.318861 0.552289 0.770263 -v 0.081453 0.082471 0.020000 -vn -0.000000 0.637731 0.770259 -v 0.081003 0.082350 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.078178 0.079250 0.020000 -vn 0.318858 0.552292 0.770262 -v 0.080553 0.082471 0.020000 -vn -0.318861 -0.552289 0.770263 -v 0.083453 0.113029 0.020000 -vn -0.552288 -0.318866 0.770261 -v 0.083782 0.112700 0.020000 -vn -0.637726 0.000000 0.770263 -v 0.083903 0.112250 0.020000 -vn -0.552292 0.318864 0.770259 -v 0.083782 0.111800 0.020000 -vn -0.318863 0.552285 0.770264 -v 0.083453 0.111471 0.020000 -vn 0.000000 -0.637731 0.770259 -v 0.083003 0.113150 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082728 0.118000 0.020000 -vn 0.318861 -0.552289 0.770263 -v 0.082553 0.113029 0.020000 -vn -0.000000 0.637731 0.770259 -v 0.083003 0.111350 0.020000 -vn 0.318863 0.552285 0.770264 -v 0.082553 0.111471 0.020000 -vn 0.552292 0.318864 0.770260 -v 0.082224 0.111800 0.020000 -vn 0.552288 -0.318866 0.770261 -v 0.082224 0.112700 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082003 0.118000 0.020000 -vn 0.637726 0.000000 0.770263 -v 0.082103 0.112250 0.020000 -vn 0.000000 -0.637726 0.770263 -v 0.083003 0.097650 0.020000 -vn -0.318866 -0.552288 0.770261 -v 0.083453 0.097529 0.020000 -vn -0.552288 -0.318866 0.770261 -v 0.083782 0.097200 0.020000 -vn 0.318866 -0.552288 0.770261 -v 0.082553 0.097529 0.020000 -vn -0.301511 0.301511 0.904534 -v 0.084503 0.103750 0.020000 -vn -0.637726 0.000000 0.770263 -v 0.083903 0.096750 0.020000 -vn -0.552292 0.318864 0.770260 -v 0.083782 0.096300 0.020000 -vn -0.318863 0.552285 0.770264 -v 0.083453 0.095971 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082728 0.093925 0.020000 -vn 0.577350 -0.577350 0.577350 -v 0.089503 0.092750 0.020000 -vn 0.552288 -0.318866 0.770261 -v 0.082224 0.097200 0.020000 -vn 0.637726 0.000000 0.770263 -v 0.082103 0.096750 0.020000 -vn -0.000000 0.637731 0.770259 -v 0.083003 0.095850 0.020000 -vn 0.318863 0.552285 0.770264 -v 0.082553 0.095971 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082003 0.093925 0.020000 -vn 0.552292 0.318864 0.770260 -v 0.082224 0.096300 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082003 0.083400 0.020000 -vn -0.552292 -0.318865 0.770259 -v 0.081782 0.083700 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.084203 0.086825 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.082728 0.086825 0.020000 -vn 0.552286 0.318861 0.770265 -v 0.080224 0.082800 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.078178 0.083400 0.020000 -vn 0.000000 -0.707107 0.707107 -v 0.075003 0.079250 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.083400 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.071828 0.083400 0.020000 -vn -0.552292 -0.318865 0.770259 -v 0.069782 0.083700 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.078178 0.118000 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.075003 0.118000 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.071828 0.118000 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.082728 0.126250 0.020000 -vn 0.516597 0.427644 0.741787 -v 0.065003 0.128250 0.020000 -vn 0.279911 0.452906 0.846478 -v 0.066003 0.126250 0.020000 -vn 0.000000 0.707107 0.707107 -v 0.067278 0.126250 0.020000 -vn 0.552285 0.318861 0.770265 -v 0.068224 0.082800 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.068003 0.083400 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.067278 0.086825 0.020000 -vn 0.000000 0.000000 1.000000 -v 0.065803 0.086825 0.020000 -vn -0.427644 -0.516597 0.741787 -v 0.060003 0.115500 0.020000 -vn -0.297108 0.630263 0.717284 -v 0.060003 0.116750 0.020000 -vn -0.113763 -0.990667 -0.075085 -v 0.060003 0.099500 0.018500 -vn -0.396204 -0.686243 -0.609994 -v 0.062658 0.099500 0.018500 -vn -0.452906 -0.279911 -0.846478 -v 0.062003 0.098500 0.018500 -vn -0.792406 0.000001 -0.609994 -v 0.063812 0.097500 0.018500 -vn -0.452906 0.279912 -0.846479 -v 0.062003 0.096500 0.018500 -vn -0.396203 0.686244 -0.609994 -v 0.062658 0.095500 0.018500 -vn -0.113762 0.990667 -0.075085 -v 0.060003 0.095500 0.018500 -vn -0.113762 -0.990667 -0.075085 -v 0.060003 0.107500 0.018500 -vn -0.396203 -0.686244 -0.609994 -v 0.062658 0.107500 0.018500 -vn -0.452906 -0.279911 -0.846479 -v 0.062003 0.106500 0.018500 -vn -0.792406 -0.000001 -0.609994 -v 0.063812 0.105500 0.018500 -vn -0.452907 0.279911 -0.846478 -v 0.062003 0.104500 0.018500 -vn -0.396204 0.686243 -0.609994 -v 0.062658 0.103500 0.018500 -vn -0.113763 0.990667 -0.075085 -v 0.060003 0.103500 0.018500 -vn -0.113763 -0.990667 -0.075085 -v 0.060003 0.115500 0.018500 -vn -0.396203 -0.686244 -0.609994 -v 0.062658 0.115500 0.018500 -vn -0.452906 -0.279911 -0.846478 -v 0.062003 0.114500 0.018500 -vn -0.792406 -0.000001 -0.609994 -v 0.063812 0.113500 0.018500 -vn -0.452906 0.279911 -0.846478 -v 0.062003 0.112500 0.018500 -vn -0.396204 0.686243 -0.609994 -v 0.062658 0.111500 0.018500 -vn -0.113763 0.990667 -0.075085 -v 0.060003 0.111500 0.018500 -vn -0.717284 -0.630262 0.297109 -v 0.059003 0.099500 0.019000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.100750 0.019000 -vn -0.717284 0.630262 -0.297109 -v 0.059003 0.100750 0.016000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.094250 0.016000 -vn -0.717284 0.630262 0.297109 -v 0.059003 0.095500 0.019000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.094250 0.019000 -vn -0.717284 -0.630262 0.297109 -v 0.059003 0.107500 0.019000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.108750 0.019000 -vn -0.717284 0.630262 -0.297109 -v 0.059003 0.108750 0.016000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.102250 0.016000 -vn -0.717284 0.630262 0.297109 -v 0.059003 0.103500 0.019000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.102250 0.019000 -vn -0.717284 -0.630262 0.297109 -v 0.059003 0.115500 0.019000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.116750 0.019000 -vn -0.717284 0.630262 -0.297109 -v 0.059003 0.116750 0.016000 -vn -0.717284 -0.630262 -0.297109 -v 0.059003 0.110250 0.016000 -vn -0.717284 0.630262 0.297109 -v 0.059003 0.111500 0.019000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.110250 0.019000 -vn -0.396204 0.686243 0.609994 -v 0.062658 0.119500 0.017000 -vn 0.000000 0.637725 0.770264 -v 0.061503 0.120250 0.017000 -vn -0.904534 0.301511 0.301511 -v 0.059003 0.119500 0.017000 -vn 0.318866 0.552291 0.770260 -v 0.060878 0.120417 0.017000 -vn -0.396203 -0.686244 0.609994 -v 0.062658 0.123500 0.017000 -vn -0.904534 -0.301511 0.301511 -v 0.059003 0.123500 0.017000 -vn 0.318867 -0.552288 0.770261 -v 0.060878 0.122582 0.017000 -vn -0.552290 -0.318863 0.770261 -v 0.062586 0.122125 0.017000 -vn -0.792406 -0.000001 0.609994 -v 0.063812 0.121500 0.017000 -vn -0.318868 -0.552287 0.770261 -v 0.062128 0.122582 0.017000 -vn 0.000000 -0.637725 0.770264 -v 0.061503 0.122750 0.017000 -vn -0.637728 -0.000002 0.770261 -v 0.062753 0.121500 0.017000 -vn -0.552287 0.318863 0.770263 -v 0.062586 0.120875 0.017000 -vn -0.318866 0.552289 0.770260 -v 0.062128 0.120417 0.017000 -vn 0.552286 0.318866 0.770263 -v 0.060421 0.120875 0.017000 -vn 0.637727 -0.000002 0.770263 -v 0.060253 0.121500 0.017000 -vn 0.552288 -0.318866 0.770261 -v 0.060421 0.122125 0.017000 -vn -0.301511 0.904534 0.301511 -v 0.069003 0.129250 0.017000 -vn 0.301511 0.904534 0.301511 -v 0.065003 0.129250 0.017000 -vn 0.000000 -0.637725 0.770264 -v 0.067003 0.128000 0.017000 -vn 0.318866 -0.552291 0.770260 -v 0.066378 0.127832 0.017000 -vn 0.318861 0.552286 0.770265 -v 0.066378 0.125667 0.017000 -vn 0.686243 0.396204 0.609994 -v 0.065003 0.125595 0.017000 -vn 0.000000 0.637732 0.770258 -v 0.067003 0.125500 0.017000 -vn 0.000001 0.792405 0.609995 -v 0.067003 0.124441 0.017000 -vn -0.318861 0.552286 0.770265 -v 0.067628 0.125667 0.017000 -vn -0.686243 0.396205 0.609994 -v 0.069003 0.125595 0.017000 -vn -0.552291 0.318865 0.770260 -v 0.068086 0.126125 0.017000 -vn -0.318866 -0.552291 0.770260 -v 0.067628 0.127832 0.017000 -vn -0.552286 -0.318869 0.770262 -v 0.068086 0.127375 0.017000 -vn -0.637725 0.000000 0.770264 -v 0.068253 0.126750 0.017000 -vn 0.552291 0.318862 0.770261 -v 0.065921 0.126125 0.017000 -vn 0.637728 -0.000000 0.770261 -v 0.065753 0.126750 0.017000 -vn 0.552286 -0.318865 0.770263 -v 0.065921 0.127375 0.017000 -vn -0.113763 -0.990667 -0.075085 -v 0.060003 0.123500 0.018500 -vn -0.396203 -0.686244 -0.609994 -v 0.062658 0.123500 0.018500 -vn -0.452906 -0.279911 -0.846478 -v 0.062003 0.122500 0.018500 -vn -0.792406 -0.000001 -0.609994 -v 0.063812 0.121500 0.018500 -vn -0.452906 0.279911 -0.846478 -v 0.062003 0.120500 0.018500 -vn -0.396204 0.686243 -0.609994 -v 0.062658 0.119500 0.018500 -vn -0.113763 0.990667 -0.075085 -v 0.060003 0.119500 0.018500 -vn -0.717284 -0.630262 0.297109 -v 0.059003 0.123500 0.019000 -vn -0.717283 0.630262 0.297109 -v 0.059003 0.124750 0.019000 -vn -0.717283 0.630262 -0.297109 -v 0.059003 0.124750 0.016000 -vn -0.717283 -0.630262 -0.297109 -v 0.059003 0.118250 0.016000 -vn -0.717284 0.630262 0.297109 -v 0.059003 0.119500 0.019000 -vn -0.717283 -0.630262 0.297109 -v 0.059003 0.118250 0.019000 -vn -0.279911 0.452906 -0.846478 -v 0.068003 0.126250 0.018500 -vn -0.990667 0.113762 -0.075085 -v 0.069003 0.128250 0.018500 -vn -0.686243 0.396205 -0.609994 -v 0.069003 0.125595 0.018500 -vn 0.686243 0.396204 -0.609994 -v 0.065003 0.125595 0.018500 -vn 0.990667 0.113762 -0.075085 -v 0.065003 0.128250 0.018500 -vn 0.279911 0.452906 -0.846478 -v 0.066003 0.126250 0.018500 -vn 0.000001 0.792405 -0.609995 -v 0.067003 0.124441 0.018500 -vn -0.630262 0.717284 0.297109 -v 0.069003 0.129250 0.019000 -vn 0.630262 0.717283 0.297109 -v 0.070253 0.129250 0.019000 -vn 0.630262 0.717284 -0.297109 -v 0.070253 0.129250 0.016000 -vn -0.630262 0.717283 -0.297109 -v 0.063753 0.129250 0.016000 -vn 0.630262 0.717284 0.297109 -v 0.065003 0.129250 0.019000 -vn -0.630263 0.717283 0.297108 -v 0.063753 0.129250 0.019000 -vn 0.669352 -0.737700 -0.088123 -v 0.088003 0.092750 0.016000 -vn 0.990752 -0.038808 -0.130014 -v 0.088003 0.084250 0.016000 -vn 0.038804 -0.990753 -0.130008 -v 0.083003 0.079250 0.016000 -vn -0.038804 -0.990754 -0.130007 -v 0.067003 0.079250 0.016000 -vn -0.669352 -0.737701 -0.088123 -v 0.062003 0.092750 0.016000 -vn -0.990752 -0.038806 -0.130014 -v 0.062003 0.084250 0.016000 -vn -0.717283 -0.630263 -0.297109 -v 0.060503 0.092750 0.016500 -vn -0.552289 -0.770261 -0.318865 -v 0.062137 0.092750 0.015500 -vn -0.318865 -0.770262 -0.552288 -v 0.062503 0.092750 0.015134 -vn -0.549133 -0.804187 -0.227458 -v 0.060503 0.094250 0.016500 -vn -0.549133 0.804187 -0.227458 -v 0.060503 0.100750 0.016500 -vn -0.549133 -0.804187 -0.227458 -v 0.060503 0.102250 0.016500 -vn -0.549133 0.804187 -0.227458 -v 0.060503 0.108750 0.016500 -vn -0.549133 -0.804187 -0.227458 -v 0.060503 0.110250 0.016500 -vn -0.549133 0.804187 -0.227458 -v 0.060503 0.116750 0.016500 -vn -0.549133 -0.804187 -0.227458 -v 0.060503 0.118250 0.016500 -vn -0.549133 0.804187 -0.227458 -v 0.060503 0.124750 0.016500 -vn -0.717284 0.630262 -0.297109 -v 0.060503 0.126250 0.016500 -vn -0.630262 0.717283 -0.297110 -v 0.062003 0.127750 0.016500 -vn -0.804187 0.549132 -0.227459 -v 0.063753 0.127750 0.016500 -vn 0.804187 0.549132 -0.227459 -v 0.070253 0.127750 0.016500 -vn -0.804187 0.549132 -0.227459 -v 0.079753 0.127750 0.016500 -vn -0.630262 0.717284 -0.297109 -v 0.079753 0.129250 0.016000 -vn -0.630262 0.717284 0.297109 -v 0.079753 0.129250 0.019000 -vn -0.630262 0.717284 0.297109 -v 0.085003 0.129250 0.019000 -vn 0.630262 0.717284 0.297109 -v 0.086253 0.129250 0.019000 -vn -0.301511 0.904534 0.301511 -v 0.085003 0.129250 0.017000 -vn 0.630262 0.717284 -0.297109 -v 0.086253 0.129250 0.016000 -vn 0.301511 0.904534 0.301511 -v 0.081003 0.129250 0.017000 -vn 0.630262 0.717284 0.297109 -v 0.081003 0.129250 0.019000 -vn 0.804187 0.549132 -0.227459 -v 0.086253 0.127750 0.016500 -vn 0.630262 0.717283 -0.297110 -v 0.088003 0.127750 0.016500 -vn 0.717284 0.630263 -0.297108 -v 0.089503 0.126250 0.016500 -vn 0.549133 0.804186 -0.227458 -v 0.089503 0.124750 0.016500 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.124750 0.016000 -vn 0.717284 0.630262 0.297109 -v 0.091003 0.124750 0.019000 -vn 0.717284 0.630262 0.297109 -v 0.091003 0.119500 0.019000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.118250 0.019000 -vn 0.904534 0.301511 0.301511 -v 0.091003 0.119500 0.017000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.118250 0.016000 -vn 0.904534 -0.301511 0.301511 -v 0.091003 0.123500 0.017000 -vn 0.717284 -0.630262 0.297109 -v 0.091003 0.123500 0.019000 -vn 0.549133 -0.804186 -0.227458 -v 0.089503 0.118250 0.016500 -vn 0.549133 0.804186 -0.227458 -v 0.089503 0.116750 0.016500 -vn 0.717283 0.630262 -0.297109 -v 0.091003 0.116750 0.016000 -vn 0.717284 0.630262 0.297109 -v 0.091003 0.116750 0.019000 -vn 0.717284 0.630262 0.297109 -v 0.091003 0.111500 0.019000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.110250 0.019000 -vn 0.904534 0.301511 0.301511 -v 0.091003 0.111500 0.017000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.110250 0.016000 -vn 0.904534 -0.301511 0.301511 -v 0.091003 0.115500 0.017000 -vn 0.717284 -0.630262 0.297109 -v 0.091003 0.115500 0.019000 -vn 0.549133 -0.804186 -0.227458 -v 0.089503 0.110250 0.016500 -vn 0.549133 0.804186 -0.227458 -v 0.089503 0.108750 0.016500 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.108750 0.016000 -vn 0.717284 0.630262 0.297109 -v 0.091003 0.108750 0.019000 -vn 0.717284 0.630262 0.297109 -v 0.091003 0.103500 0.019000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.102250 0.019000 -vn 0.904534 0.301511 0.301511 -v 0.091003 0.103500 0.017000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.102250 0.016000 -vn 0.904534 -0.301511 0.301511 -v 0.091003 0.107500 0.017000 -vn 0.717284 -0.630262 0.297109 -v 0.091003 0.107500 0.019000 -vn 0.549133 -0.804186 -0.227458 -v 0.089503 0.102250 0.016500 -vn 0.549133 0.804186 -0.227458 -v 0.089503 0.100750 0.016500 -vn 0.717284 0.630262 -0.297109 -v 0.091003 0.100750 0.016000 -vn 0.717283 0.630262 0.297109 -v 0.091003 0.100750 0.019000 -vn 0.717284 0.630262 0.297109 -v 0.091003 0.095500 0.019000 -vn 0.717283 -0.630262 0.297109 -v 0.091003 0.094250 0.019000 -vn 0.904534 0.301511 0.301511 -v 0.091003 0.095500 0.017000 -vn 0.717284 -0.630262 -0.297109 -v 0.091003 0.094250 0.016000 -vn 0.904534 -0.301511 0.301511 -v 0.091003 0.099500 0.017000 -vn 0.717284 -0.630262 0.297109 -v 0.091003 0.099500 0.019000 -vn 0.549133 -0.804186 -0.227458 -v 0.089503 0.094250 0.016500 -vn 0.717284 -0.630263 -0.297108 -v 0.089503 0.092750 0.016500 -vn 0.318864 -0.770262 -0.552288 -v 0.087503 0.092750 0.015134 -vn 0.552289 -0.770261 -0.318865 -v 0.087869 0.092750 0.015500 -vn 0.128135 0.983444 -0.128137 -v 0.084703 0.123250 0.012300 -vn -0.128144 0.983443 -0.128140 -v 0.079303 0.123250 0.012300 -vn 0.983443 0.128139 -0.128142 -v 0.085003 0.122950 0.012300 -vn 0.983444 -0.128135 -0.128137 -v 0.085003 0.116550 0.012300 -vn -0.128162 -0.983438 -0.128159 -v 0.079303 0.116250 0.012300 -vn 0.128155 -0.983439 -0.128157 -v 0.084703 0.116250 0.012300 -vn -0.983438 0.128156 -0.128159 -v 0.079003 0.122950 0.012300 -vn -0.983440 -0.128149 -0.128151 -v 0.079003 0.116550 0.012300 -vn -0.108734 0.108728 -0.988107 -v 0.079303 0.122950 0.012000 -vn 0.108728 0.108729 -0.988108 -v 0.084703 0.122950 0.012000 -vn -0.108732 -0.108726 -0.988107 -v 0.079303 0.116550 0.012000 -vn 0.108726 -0.108727 -0.988108 -v 0.084703 0.116550 0.012000 -vn -0.983444 0.128135 -0.128137 -v 0.065003 0.122950 0.012300 -vn -0.983443 -0.128138 -0.128140 -v 0.065003 0.116550 0.012300 -vn -0.128144 0.983443 -0.128140 -v 0.065303 0.123250 0.012300 -vn 0.128135 0.983444 -0.128137 -v 0.070703 0.123250 0.012300 -vn 0.983443 0.128139 -0.128142 -v 0.071003 0.122950 0.012300 -vn 0.983444 -0.128135 -0.128137 -v 0.071003 0.116550 0.012300 -vn 0.128156 -0.983438 -0.128159 -v 0.070703 0.116250 0.012300 -vn -0.128162 -0.983438 -0.128159 -v 0.065303 0.116250 0.012300 -vn -0.108732 -0.108726 -0.988107 -v 0.065303 0.116550 0.012000 -vn -0.108734 0.108728 -0.988107 -v 0.065303 0.122950 0.012000 -vn 0.108728 -0.108727 -0.988108 -v 0.070703 0.116550 0.012000 -vn 0.108729 0.108729 -0.988107 -v 0.070703 0.122950 0.012000 -vn 0.686243 0.396204 -0.609994 -v 0.081003 0.125595 0.018500 -vn 0.686243 0.396204 0.609994 -v 0.081003 0.125595 0.017000 -vn 0.990667 0.113762 -0.075084 -v 0.081003 0.128250 0.018500 -vn 0.000000 -0.637725 0.770264 -v 0.083003 0.128000 0.017000 -vn 0.318865 -0.552291 0.770260 -v 0.082378 0.127832 0.017000 -vn -0.637729 0.000000 0.770261 -v 0.084253 0.126750 0.017000 -vn -0.686243 0.396204 0.609994 -v 0.085003 0.125595 0.017000 -vn -0.552286 -0.318865 0.770263 -v 0.084086 0.127375 0.017000 -vn -0.318866 -0.552291 0.770260 -v 0.083628 0.127832 0.017000 -vn -0.552291 0.318862 0.770261 -v 0.084086 0.126125 0.017000 -vn -0.318861 0.552286 0.770265 -v 0.083628 0.125667 0.017000 -vn 0.000000 0.792406 0.609995 -v 0.083003 0.124441 0.017000 -vn -0.000000 0.637732 0.770258 -v 0.083003 0.125500 0.017000 -vn 0.318861 0.552286 0.770265 -v 0.082378 0.125667 0.017000 -vn 0.552291 0.318862 0.770261 -v 0.081921 0.126125 0.017000 -vn 0.637728 -0.000000 0.770261 -v 0.081753 0.126750 0.017000 -vn 0.552286 -0.318865 0.770263 -v 0.081921 0.127375 0.017000 -vn -0.990667 0.113762 -0.075084 -v 0.085003 0.128250 0.018500 -vn -0.686243 0.396204 -0.609994 -v 0.085003 0.125595 0.018500 -vn 0.000000 0.792405 -0.609995 -v 0.083003 0.124441 0.018500 -vn -0.279912 0.452905 -0.846479 -v 0.084003 0.126250 0.018500 -vn 0.279912 0.452905 -0.846479 -v 0.082003 0.126250 0.018500 -vn 0.396203 -0.686244 -0.609994 -v 0.087348 0.123500 0.018500 -vn 0.396203 -0.686244 0.609994 -v 0.087348 0.123500 0.017000 -vn 0.113763 -0.990667 -0.075085 -v 0.090003 0.123500 0.018500 -vn 0.396204 0.686243 0.609994 -v 0.087348 0.119500 0.017000 -vn -0.318867 0.552288 0.770261 -v 0.089128 0.120417 0.017000 -vn -0.000001 0.637726 0.770264 -v 0.088503 0.120250 0.017000 -vn 0.318866 0.552288 0.770261 -v 0.087878 0.120417 0.017000 -vn 0.792406 -0.000001 0.609995 -v 0.086194 0.121500 0.017000 -vn 0.552288 0.318866 0.770261 -v 0.087421 0.120875 0.017000 -vn -0.000001 -0.637726 0.770264 -v 0.088503 0.122750 0.017000 -vn -0.318869 -0.552286 0.770262 -v 0.089128 0.122582 0.017000 -vn -0.552291 -0.318867 0.770259 -v 0.089586 0.122125 0.017000 -vn -0.637725 -0.000002 0.770264 -v 0.089753 0.121500 0.017000 -vn -0.552288 0.318866 0.770261 -v 0.089586 0.120875 0.017000 -vn 0.637725 -0.000002 0.770264 -v 0.087253 0.121500 0.017000 -vn 0.552290 -0.318867 0.770259 -v 0.087421 0.122125 0.017000 -vn 0.318868 -0.552286 0.770262 -v 0.087878 0.122582 0.017000 -vn 0.113763 0.990667 -0.075085 -v 0.090003 0.119500 0.018500 -vn 0.396204 0.686243 -0.609994 -v 0.087348 0.119500 0.018500 -vn 0.792406 -0.000001 -0.609994 -v 0.086194 0.121500 0.018500 -vn 0.452906 0.279911 -0.846478 -v 0.088003 0.120500 0.018500 -vn 0.452906 -0.279911 -0.846478 -v 0.088003 0.122500 0.018500 -vn 0.396203 -0.686244 -0.609994 -v 0.087348 0.115500 0.018500 -vn 0.396203 -0.686243 0.609994 -v 0.087348 0.115500 0.017000 -vn 0.113763 -0.990667 -0.075085 -v 0.090003 0.115500 0.018500 -vn 0.396204 0.686243 0.609994 -v 0.087348 0.111500 0.017000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.112417 0.017000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.112250 0.017000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.112417 0.017000 -vn 0.792406 -0.000001 0.609994 -v 0.086194 0.113500 0.017000 -vn 0.552291 0.318865 0.770260 -v 0.087421 0.112875 0.017000 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.114582 0.017000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.114750 0.017000 -vn 0.637725 0.000000 0.770264 -v 0.087253 0.113500 0.017000 -vn 0.552291 -0.318866 0.770260 -v 0.087421 0.114125 0.017000 -vn 0.318864 -0.552286 0.770263 -v 0.087878 0.114582 0.017000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.114125 0.017000 -vn -0.637725 -0.000000 0.770264 -v 0.089753 0.113500 0.017000 -vn -0.552291 0.318866 0.770260 -v 0.089586 0.112875 0.017000 -vn 0.113763 0.990667 -0.075085 -v 0.090003 0.111500 0.018500 -vn 0.396204 0.686243 -0.609994 -v 0.087348 0.111500 0.018500 -vn 0.396203 -0.686244 -0.609994 -v 0.087348 0.107500 0.018500 -vn 0.396203 -0.686243 0.609994 -v 0.087348 0.107500 0.017000 -vn 0.113762 -0.990667 -0.075085 -v 0.090003 0.107500 0.018500 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.106582 0.017000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.106750 0.017000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.106125 0.017000 -vn -0.637725 -0.000000 0.770264 -v 0.089753 0.105500 0.017000 -vn 0.552291 0.318865 0.770260 -v 0.087421 0.104875 0.017000 -vn 0.792406 -0.000001 0.609994 -v 0.086194 0.105500 0.017000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.104417 0.017000 -vn 0.396204 0.686243 0.609994 -v 0.087348 0.103500 0.017000 -vn 0.637725 0.000000 0.770264 -v 0.087253 0.105500 0.017000 -vn 0.552291 -0.318866 0.770260 -v 0.087421 0.106125 0.017000 -vn 0.318864 -0.552286 0.770263 -v 0.087878 0.106582 0.017000 -vn -0.552291 0.318866 0.770260 -v 0.089586 0.104875 0.017000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.104417 0.017000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.104250 0.017000 -vn 0.113763 0.990667 -0.075085 -v 0.090003 0.103500 0.018500 -vn 0.396204 0.686243 -0.609994 -v 0.087348 0.103500 0.018500 -vn 0.396204 -0.686243 -0.609994 -v 0.087348 0.099500 0.018500 -vn 0.396204 -0.686243 0.609994 -v 0.087348 0.099500 0.017000 -vn 0.113763 -0.990667 -0.075085 -v 0.090003 0.099500 0.018500 -vn 0.637725 0.000000 0.770264 -v 0.087253 0.097500 0.017000 -vn 0.552291 -0.318866 0.770260 -v 0.087421 0.098125 0.017000 -vn 0.792406 0.000001 0.609994 -v 0.086194 0.097500 0.017000 -vn 0.396203 0.686243 0.609995 -v 0.087348 0.095500 0.017000 -vn -0.318865 0.552286 0.770263 -v 0.089128 0.096417 0.017000 -vn -0.000001 0.637729 0.770261 -v 0.088503 0.096250 0.017000 -vn 0.318864 0.552286 0.770263 -v 0.087878 0.096417 0.017000 -vn 0.552291 0.318865 0.770260 -v 0.087421 0.096875 0.017000 -vn 0.318864 -0.552286 0.770263 -v 0.087878 0.098582 0.017000 -vn -0.000001 -0.637729 0.770261 -v 0.088503 0.098750 0.017000 -vn -0.318865 -0.552286 0.770263 -v 0.089128 0.098582 0.017000 -vn -0.552291 -0.318865 0.770260 -v 0.089586 0.098125 0.017000 -vn -0.637725 -0.000000 0.770264 -v 0.089753 0.097500 0.017000 -vn -0.552291 0.318866 0.770260 -v 0.089586 0.096875 0.017000 -vn 0.113762 0.990667 -0.075085 -v 0.090003 0.095500 0.018500 -vn 0.396203 0.686244 -0.609994 -v 0.087348 0.095500 0.018500 -vn 0.792406 -0.000001 -0.609994 -v 0.086194 0.113500 0.018500 -vn 0.452906 0.279911 -0.846478 -v 0.088003 0.112500 0.018500 -vn 0.452906 -0.279911 -0.846478 -v 0.088003 0.114500 0.018500 -vn 0.792406 -0.000001 -0.609994 -v 0.086194 0.105500 0.018500 -vn 0.452907 0.279911 -0.846478 -v 0.088003 0.104500 0.018500 -vn 0.452906 -0.279911 -0.846479 -v 0.088003 0.106500 0.018500 -vn 0.792406 0.000001 -0.609994 -v 0.086194 0.097500 0.018500 -vn 0.452906 0.279912 -0.846479 -v 0.088003 0.096500 0.018500 -vn 0.452906 -0.279911 -0.846478 -v 0.088003 0.098500 0.018500 -vn -0.155132 -0.979469 -0.128741 -v 0.066221 0.079311 0.016000 -vn -0.306406 -0.943025 -0.129690 -v 0.065458 0.079495 0.016000 -vn -0.450211 -0.883592 -0.128746 -v 0.064733 0.079795 0.016000 -vn -0.582822 -0.802183 -0.129694 -v 0.064064 0.080205 0.016000 -vn -0.701221 -0.701223 -0.128746 -v 0.063468 0.080714 0.016000 -vn -0.802184 -0.582821 -0.129694 -v 0.062958 0.081311 0.016000 -vn -0.883590 -0.450215 -0.128748 -v 0.062548 0.081980 0.016000 -vn -0.943024 -0.306408 -0.129693 -v 0.062248 0.082705 0.016000 -vn -0.979468 -0.155133 -0.128746 -v 0.062065 0.083468 0.016000 -vn 0.979469 -0.155134 -0.128743 -v 0.087941 0.083468 0.016000 -vn 0.943025 -0.306406 -0.129687 -v 0.087758 0.082705 0.016000 -vn 0.883591 -0.450213 -0.128746 -v 0.087458 0.081980 0.016000 -vn 0.802184 -0.582822 -0.129690 -v 0.087048 0.081311 0.016000 -vn 0.701222 -0.701222 -0.128744 -v 0.086539 0.080714 0.016000 -vn 0.582822 -0.802184 -0.129691 -v 0.085942 0.080205 0.016000 -vn 0.450218 -0.883589 -0.128742 -v 0.085273 0.079795 0.016000 -vn 0.306409 -0.943024 -0.129692 -v 0.084548 0.079495 0.016000 -vn 0.155131 -0.979469 -0.128743 -v 0.083785 0.079311 0.016000 -vn -0.804186 -0.549134 -0.227458 -v 0.084503 0.108250 0.016000 -vn 0.804186 -0.549134 -0.227458 -v 0.075503 0.108250 0.016000 -vn 0.804187 0.549133 -0.227459 -v 0.075503 0.103750 0.016000 -vn -0.804187 0.549132 -0.227459 -v 0.084503 0.103750 0.016000 -vn -0.424550 -0.483793 -0.765311 -v 0.084503 0.108950 0.015300 -vn -0.424549 0.483792 -0.765313 -v 0.084503 0.103050 0.015300 -vn 0.424544 0.483793 -0.765315 -v 0.065503 0.103050 0.015300 -vn 0.424545 -0.483794 -0.765314 -v 0.065503 0.108950 0.015300 -vn 0.804186 -0.549134 -0.227458 -v 0.065503 0.108250 0.016000 -vn 0.804187 0.549132 -0.227459 -v 0.065503 0.103750 0.016000 -vn -0.804187 0.549133 -0.227458 -v 0.074503 0.103750 0.016000 -vn -0.804186 -0.549134 -0.227458 -v 0.074503 0.108250 0.016000 -vn -0.155170 -0.979699 -0.126932 -v 0.074158 0.085416 0.012500 -vn -0.450321 -0.883800 -0.126923 -v 0.072551 0.085939 0.012500 -vn -0.306409 -0.943025 -0.129679 -v 0.073334 0.085614 0.012500 -vn -0.701386 -0.701388 -0.126935 -v 0.071185 0.086932 0.012500 -vn -0.582821 -0.802185 -0.129687 -v 0.071829 0.086381 0.012500 -vn -0.883799 -0.450316 -0.126944 -v 0.070192 0.088298 0.012500 -vn -0.802183 -0.582820 -0.129705 -v 0.070634 0.087576 0.012500 -vn -0.979699 -0.155171 -0.126929 -v 0.069670 0.089905 0.012500 -vn -0.943026 -0.306406 -0.129680 -v 0.069867 0.089081 0.012500 -vn -0.979699 0.155172 -0.126934 -v 0.069670 0.091595 0.012500 -vn -0.991553 0.000001 -0.129700 -v 0.069603 0.090750 0.012500 -vn -0.883800 0.450315 -0.126942 -v 0.070192 0.093201 0.012500 -vn -0.943027 0.306404 -0.129680 -v 0.069867 0.092419 0.012500 -vn -0.701386 0.701388 -0.126936 -v 0.071185 0.094568 0.012500 -vn -0.802182 0.582821 -0.129705 -v 0.070634 0.093924 0.012500 -vn -0.450321 0.883799 -0.126924 -v 0.072551 0.095561 0.012500 -vn -0.582820 0.802186 -0.129687 -v 0.071829 0.095119 0.012500 -vn -0.155168 0.979699 -0.126932 -v 0.074158 0.096083 0.012500 -vn -0.306410 0.943025 -0.129679 -v 0.073334 0.095886 0.012500 -vn 0.155170 0.979699 -0.126932 -v 0.075848 0.096083 0.012500 -vn -0.000001 0.991556 -0.129678 -v 0.075003 0.096150 0.012500 -vn 0.450318 0.883801 -0.126923 -v 0.077455 0.095561 0.012500 -vn 0.306409 0.943025 -0.129679 -v 0.076672 0.095886 0.012500 -vn 0.701388 0.701389 -0.126920 -v 0.078821 0.094568 0.012500 -vn 0.582821 0.802185 -0.129687 -v 0.078177 0.095119 0.012500 -vn 0.883800 0.450320 -0.126924 -v 0.079814 0.093201 0.012500 -vn 0.802185 0.582822 -0.129686 -v 0.079372 0.093924 0.012500 -vn 0.979699 0.155170 -0.126934 -v 0.080337 0.091595 0.012500 -vn 0.943024 0.306405 -0.129699 -v 0.080139 0.092419 0.012500 -vn 0.979700 -0.155166 -0.126930 -v 0.080337 0.089905 0.012500 -vn 0.991553 -0.000001 -0.129700 -v 0.080403 0.090750 0.012500 -vn 0.883800 -0.450319 -0.126924 -v 0.079814 0.088298 0.012500 -vn 0.943023 -0.306409 -0.129699 -v 0.080139 0.089081 0.012500 -vn 0.701389 -0.701388 -0.126920 -v 0.078821 0.086932 0.012500 -vn 0.802184 -0.582823 -0.129687 -v 0.079372 0.087576 0.012500 -vn 0.450319 -0.883800 -0.126924 -v 0.077455 0.085939 0.012500 -vn 0.582820 -0.802186 -0.129686 -v 0.078177 0.086381 0.012500 -vn 0.000001 -0.991556 -0.129678 -v 0.075003 0.085350 0.012500 -vn 0.155168 -0.979699 -0.126932 -v 0.075848 0.085416 0.012500 -vn 0.306410 -0.943025 -0.129679 -v 0.076672 0.085614 0.012500 -vn -0.042314 0.130230 -0.990580 -v 0.073427 0.095600 0.012200 -vn -0.021420 0.135242 -0.990581 -v 0.074205 0.095787 0.012200 -vn 0.238570 -0.615820 -0.750899 -v 0.073558 0.094480 0.012200 -vn 0.000000 -0.660418 -0.750898 -v 0.075003 0.094750 0.012200 -vn 0.096824 0.096823 -0.990581 -v 0.078609 0.094356 0.012200 -vn 0.110783 0.080490 -0.990580 -v 0.079129 0.093748 0.012200 -vn -0.444921 -0.488053 -0.750899 -v 0.077698 0.093706 0.012200 -vn -0.591182 -0.294373 -0.750898 -v 0.078584 0.092533 0.012200 -vn 0.635206 0.180730 -0.750899 -v 0.071156 0.089655 0.012200 -vn 0.527024 0.397990 -0.750899 -v 0.071811 0.088339 0.012200 -vn -0.122007 -0.062166 -0.990580 -v 0.070459 0.088435 0.012200 -vn 0.347665 0.561499 -0.750898 -v 0.072897 0.087349 0.012200 -vn -0.096826 -0.096827 -0.990580 -v 0.071397 0.087144 0.012200 -vn -0.110779 -0.080485 -0.990581 -v 0.070877 0.087752 0.012200 -vn -0.021420 -0.135242 -0.990581 -v 0.074205 0.085713 0.012200 -vn 0.121352 0.649172 -0.750899 -v 0.074268 0.086818 0.012200 -vn 0.000000 -0.136928 -0.990581 -v 0.075003 0.085650 0.012200 -vn -0.121352 0.649172 -0.750899 -v 0.075738 0.086818 0.012200 -vn 0.021420 -0.135241 -0.990581 -v 0.075801 0.085713 0.012200 -vn 0.130224 -0.042313 -0.990581 -v 0.079853 0.089174 0.012200 -vn 0.122002 -0.062164 -0.990581 -v 0.079547 0.088435 0.012200 -vn -0.635207 0.180732 -0.750898 -v 0.078850 0.089655 0.012200 -vn -0.527024 0.397990 -0.750899 -v 0.078195 0.088339 0.012200 -vn 0.122002 0.062163 -0.990581 -v 0.079547 0.093065 0.012200 -vn 0.130224 0.042313 -0.990581 -v 0.079853 0.092326 0.012200 -vn -0.657599 -0.060936 -0.750900 -v 0.078986 0.091119 0.012200 -vn 0.000001 0.136928 -0.990581 -v 0.075003 0.095850 0.012200 -vn 0.021420 0.135242 -0.990581 -v 0.075801 0.095787 0.012200 -vn -0.238569 -0.615821 -0.750899 -v 0.076448 0.094480 0.012200 -vn 0.444921 -0.488054 -0.750899 -v 0.072308 0.093706 0.012200 -vn -0.080483 0.110776 -0.990581 -v 0.072005 0.094876 0.012200 -vn -0.062166 0.122007 -0.990580 -v 0.072688 0.095294 0.012200 -vn -0.135242 0.021420 -0.990581 -v 0.069966 0.091548 0.012200 -vn -0.130230 0.042314 -0.990580 -v 0.070153 0.092326 0.012200 -vn 0.657601 -0.060936 -0.750898 -v 0.071020 0.091119 0.012200 -vn 0.591181 -0.294373 -0.750899 -v 0.071422 0.092533 0.012200 -vn -0.042314 -0.130230 -0.990580 -v 0.073427 0.085900 0.012200 -vn -0.062165 -0.122007 -0.990581 -v 0.072688 0.086206 0.012200 -vn -0.080484 -0.110776 -0.990581 -v 0.072005 0.086624 0.012200 -vn 0.042315 -0.130230 -0.990580 -v 0.076579 0.085900 0.012200 -vn -0.347665 0.561499 -0.750898 -v 0.077109 0.087349 0.012200 -vn 0.062166 -0.122007 -0.990581 -v 0.077318 0.086206 0.012200 -vn 0.110784 -0.080488 -0.990580 -v 0.079129 0.087752 0.012200 -vn 0.096826 -0.096826 -0.990580 -v 0.078609 0.087144 0.012200 -vn 0.080483 -0.110776 -0.990581 -v 0.078001 0.086624 0.012200 -vn 0.135242 0.021420 -0.990581 -v 0.080040 0.091548 0.012200 -vn 0.136934 0.000000 -0.990580 -v 0.080103 0.090750 0.012200 -vn 0.135242 -0.021421 -0.990581 -v 0.080040 0.089952 0.012200 -vn 0.042314 0.130231 -0.990580 -v 0.076579 0.095600 0.012200 -vn 0.062165 0.122007 -0.990581 -v 0.077318 0.095294 0.012200 -vn 0.080484 0.110776 -0.990581 -v 0.078001 0.094876 0.012200 -vn -0.122007 0.062166 -0.990580 -v 0.070459 0.093065 0.012200 -vn -0.110779 0.080486 -0.990581 -v 0.070877 0.093748 0.012200 -vn -0.096823 0.096823 -0.990581 -v 0.071397 0.094356 0.012200 -vn -0.130230 -0.042315 -0.990580 -v 0.070153 0.089174 0.012200 -vn -0.135243 -0.021420 -0.990581 -v 0.069966 0.089952 0.012200 -vn -0.136927 0.000000 -0.990581 -v 0.069903 0.090750 0.012200 -vn 0.000000 -0.744167 -0.667993 -v 0.075003 0.094750 0.012800 -vn -0.268823 -0.693917 -0.667992 -v 0.076448 0.094480 0.012800 -vn -0.501344 -0.549946 -0.667992 -v 0.077698 0.093706 0.012800 -vn -0.666151 -0.331704 -0.667993 -v 0.078584 0.092533 0.012800 -vn -0.740994 -0.068663 -0.667992 -v 0.078986 0.091119 0.012800 -vn -0.715759 0.203652 -0.667993 -v 0.078850 0.089655 0.012800 -vn -0.593859 0.448462 -0.667992 -v 0.078195 0.088339 0.012800 -vn -0.391753 0.632704 -0.667993 -v 0.077109 0.087349 0.012800 -vn -0.136741 0.731497 -0.667992 -v 0.075738 0.086818 0.012800 -vn 0.136741 0.731497 -0.667992 -v 0.074268 0.086818 0.012800 -vn 0.391753 0.632704 -0.667993 -v 0.072897 0.087349 0.012800 -vn 0.593859 0.448462 -0.667992 -v 0.071811 0.088339 0.012800 -vn 0.715760 0.203650 -0.667993 -v 0.071156 0.089655 0.012800 -vn 0.740993 -0.068663 -0.667993 -v 0.071020 0.091119 0.012800 -vn 0.666152 -0.331704 -0.667992 -v 0.071422 0.092533 0.012800 -vn 0.501343 -0.549946 -0.667993 -v 0.072308 0.093706 0.012800 -vn 0.268824 -0.693917 -0.667992 -v 0.073558 0.094480 0.012800 -vn 0.188588 -0.108881 -0.976002 -v 0.073682 0.091512 0.012800 -vn 0.108882 -0.188586 -0.976002 -v 0.074241 0.092071 0.012800 -vn -0.000000 -0.217765 -0.976001 -v 0.075003 0.092275 0.012800 -vn -0.108880 -0.188587 -0.976002 -v 0.075766 0.092071 0.012800 -vn 0.188585 0.108880 -0.976002 -v 0.073682 0.089987 0.012800 -vn 0.217761 0.000000 -0.976002 -v 0.073478 0.090750 0.012800 -vn -0.108881 0.188587 -0.976002 -v 0.075766 0.089429 0.012800 -vn 0.000001 0.217759 -0.976003 -v 0.075003 0.089225 0.012800 -vn 0.108881 0.188587 -0.976002 -v 0.074241 0.089429 0.012800 -vn -0.217761 -0.000000 -0.976002 -v 0.076528 0.090750 0.012800 -vn -0.188585 0.108880 -0.976002 -v 0.076324 0.089987 0.012800 -vn -0.188589 -0.108880 -0.976002 -v 0.076324 0.091512 0.012800 -vn -0.000000 0.000000 1.000000 -v 0.065753 0.081750 0.015019 -vn -0.443815 0.768715 0.460549 -v 0.066153 0.081057 0.015500 -vn -0.768715 0.443815 0.460549 -v 0.066446 0.081350 0.015500 -vn 0.000000 0.887634 0.460550 -v 0.065753 0.080950 0.015500 -vn -0.768715 -0.443815 0.460549 -v 0.066446 0.082150 0.015500 -vn -0.443815 -0.768715 0.460549 -v 0.066153 0.082443 0.015500 -vn -0.887634 0.000000 0.460550 -v 0.066553 0.081750 0.015500 -vn 0.443815 -0.768715 0.460549 -v 0.065353 0.082443 0.015500 -vn 0.768715 -0.443815 0.460549 -v 0.065060 0.082150 0.015500 -vn -0.000000 -0.887634 0.460550 -v 0.065753 0.082550 0.015500 -vn 0.768715 0.443815 0.460549 -v 0.065060 0.081350 0.015500 -vn 0.443815 0.768715 0.460549 -v 0.065353 0.081057 0.015500 -vn 0.887634 -0.000000 0.460550 -v 0.064953 0.081750 0.015500 -vn 0.000002 0.842049 0.539401 -v 0.065753 0.080950 0.019942 -vn -0.421025 0.729241 0.539394 -v 0.066153 0.081057 0.019942 -vn -0.729233 0.421022 0.539406 -v 0.066446 0.081350 0.019942 -vn -0.842048 -0.000000 0.539403 -v 0.066553 0.081750 0.019942 -vn -0.729234 -0.421020 0.539407 -v 0.066446 0.082150 0.019942 -vn -0.421021 -0.729243 0.539394 -v 0.066153 0.082443 0.019942 -vn -0.000002 -0.842049 0.539401 -v 0.065753 0.082550 0.019942 -vn 0.421025 -0.729241 0.539394 -v 0.065353 0.082443 0.019942 -vn 0.729243 -0.421023 0.539393 -v 0.065060 0.082150 0.019942 -vn 0.842049 -0.000002 0.539401 -v 0.064953 0.081750 0.019942 -vn 0.729241 0.421025 0.539394 -v 0.065060 0.081350 0.019942 -vn 0.421023 0.729243 0.539393 -v 0.065353 0.081057 0.019942 -vn -0.000000 0.000000 1.000000 -v 0.084253 0.081750 0.015019 -vn -0.443815 0.768715 0.460549 -v 0.084653 0.081057 0.015500 -vn -0.768715 0.443815 0.460549 -v 0.084946 0.081350 0.015500 -vn 0.000000 0.887634 0.460550 -v 0.084253 0.080950 0.015500 -vn -0.768715 -0.443815 0.460549 -v 0.084946 0.082150 0.015500 -vn -0.443815 -0.768715 0.460549 -v 0.084653 0.082443 0.015500 -vn -0.887634 0.000000 0.460550 -v 0.085053 0.081750 0.015500 -vn 0.443815 -0.768715 0.460549 -v 0.083853 0.082443 0.015500 -vn 0.768715 -0.443815 0.460549 -v 0.083560 0.082150 0.015500 -vn -0.000000 -0.887634 0.460550 -v 0.084253 0.082550 0.015500 -vn 0.768715 0.443815 0.460549 -v 0.083560 0.081350 0.015500 -vn 0.443815 0.768715 0.460549 -v 0.083853 0.081057 0.015500 -vn 0.887634 -0.000000 0.460550 -v 0.083453 0.081750 0.015500 -vn 0.000002 0.842049 0.539401 -v 0.084253 0.080950 0.019942 -vn -0.421024 0.729241 0.539394 -v 0.084653 0.081057 0.019942 -vn -0.729233 0.421022 0.539406 -v 0.084946 0.081350 0.019942 -vn -0.842048 -0.000000 0.539403 -v 0.085053 0.081750 0.019942 -vn -0.729234 -0.421020 0.539407 -v 0.084946 0.082150 0.019942 -vn -0.421021 -0.729243 0.539394 -v 0.084653 0.082443 0.019942 -vn -0.000002 -0.842049 0.539401 -v 0.084253 0.082550 0.019942 -vn 0.421024 -0.729241 0.539394 -v 0.083853 0.082443 0.019942 -vn 0.729243 -0.421023 0.539393 -v 0.083560 0.082150 0.019942 -vn 0.842049 -0.000002 0.539401 -v 0.083453 0.081750 0.019942 -vn 0.729241 0.421024 0.539394 -v 0.083560 0.081350 0.019942 -vn 0.421023 0.729243 0.539393 -v 0.083853 0.081057 0.019942 -vn 0.000000 0.000001 1.000000 -v 0.064603 0.123750 0.015019 -vn -0.443816 0.768714 0.460549 -v 0.065003 0.123057 0.015500 -vn -0.768713 0.443819 0.460548 -v 0.065296 0.123350 0.015500 -vn 0.000000 0.887635 0.460548 -v 0.064603 0.122950 0.015500 -vn -0.768715 -0.443815 0.460549 -v 0.065296 0.124150 0.015500 -vn -0.443815 -0.768715 0.460549 -v 0.065003 0.124443 0.015500 -vn -0.887634 0.000000 0.460550 -v 0.065403 0.123750 0.015500 -vn 0.443815 -0.768715 0.460549 -v 0.064203 0.124443 0.015500 -vn 0.768715 -0.443815 0.460549 -v 0.063910 0.124150 0.015500 -vn -0.000000 -0.887634 0.460550 -v 0.064603 0.124550 0.015500 -vn 0.768713 0.443819 0.460548 -v 0.063910 0.123350 0.015500 -vn 0.443816 0.768714 0.460549 -v 0.064203 0.123057 0.015500 -vn 0.887634 -0.000000 0.460550 -v 0.063803 0.123750 0.015500 -vn -0.000001 0.842046 0.539406 -v 0.064603 0.122950 0.019942 -vn -0.421022 0.729235 0.539404 -v 0.065003 0.123057 0.019942 -vn -0.729240 0.421025 0.539395 -v 0.065296 0.123350 0.019942 -vn -0.842049 0.000002 0.539401 -v 0.065403 0.123750 0.019942 -vn -0.729241 -0.421025 0.539394 -v 0.065296 0.124150 0.019942 -vn -0.421022 -0.729233 0.539406 -v 0.065003 0.124443 0.019942 -vn 0.000000 -0.842048 0.539403 -v 0.064603 0.124550 0.019942 -vn 0.421019 -0.729235 0.539407 -v 0.064203 0.124443 0.019942 -vn 0.729234 -0.421022 0.539406 -v 0.063910 0.124150 0.019942 -vn 0.842048 0.000000 0.539403 -v 0.063803 0.123750 0.019942 -vn 0.729230 0.421026 0.539407 -v 0.063910 0.123350 0.019942 -vn 0.421022 0.729234 0.539405 -v 0.064203 0.123057 0.019942 -vn -0.000002 -0.000000 1.000000 -v 0.085403 0.123750 0.015019 -vn -0.443821 0.768712 0.460549 -v 0.085803 0.123057 0.015500 -vn -0.768712 0.443821 0.460549 -v 0.086096 0.123350 0.015500 -vn -0.000009 0.887634 0.460549 -v 0.085403 0.122950 0.015500 -vn -0.768714 -0.443816 0.460549 -v 0.086096 0.124150 0.015500 -vn -0.443819 -0.768713 0.460548 -v 0.085803 0.124443 0.015500 -vn -0.887635 0.000000 0.460548 -v 0.086203 0.123750 0.015500 -vn 0.443825 -0.768710 0.460549 -v 0.085003 0.124443 0.015500 -vn 0.768714 -0.443816 0.460550 -v 0.084710 0.124150 0.015500 -vn 0.000005 -0.887634 0.460549 -v 0.085403 0.124550 0.015500 -vn 0.768711 0.443821 0.460551 -v 0.084710 0.123350 0.015500 -vn 0.443813 0.768716 0.460550 -v 0.085003 0.123057 0.015500 -vn 0.887634 0.000000 0.460549 -v 0.084603 0.123750 0.015500 -vn -0.000010 0.842048 0.539403 -v 0.085403 0.122950 0.019942 -vn -0.421027 0.729231 0.539405 -v 0.085803 0.123057 0.019942 -vn -0.729231 0.421028 0.539405 -v 0.086096 0.123350 0.019942 -vn -0.842046 -0.000001 0.539406 -v 0.086203 0.123750 0.019942 -vn -0.729235 -0.421023 0.539404 -v 0.086096 0.124150 0.019942 -vn -0.421025 -0.729231 0.539408 -v 0.085803 0.124443 0.019942 -vn 0.000006 -0.842047 0.539404 -v 0.085403 0.124550 0.019942 -vn 0.421036 -0.729231 0.539399 -v 0.085003 0.124443 0.019942 -vn 0.729234 -0.421025 0.539403 -v 0.084710 0.124150 0.019942 -vn 0.842056 0.000003 0.539391 -v 0.084603 0.123750 0.019942 -vn 0.729233 0.421025 0.539404 -v 0.084710 0.123350 0.019942 -vn 0.421022 0.729238 0.539400 -v 0.085003 0.123057 0.019942 -vn -0.000001 -0.842053 -0.539395 -v 0.075003 0.092000 0.012959 -vn -0.421025 -0.729239 -0.539396 -v 0.075628 0.091832 0.012959 -vn -0.729237 -0.421027 -0.539397 -v 0.076086 0.091375 0.012959 -vn -0.842051 0.000001 -0.539397 -v 0.076253 0.090750 0.012959 -vn -0.729236 0.421028 -0.539399 -v 0.076086 0.090125 0.012959 -vn -0.421026 0.729238 -0.539397 -v 0.075628 0.089667 0.012959 -vn 0.000001 0.842050 -0.539400 -v 0.075003 0.089500 0.012959 -vn 0.421026 0.729238 -0.539397 -v 0.074378 0.089667 0.012959 -vn 0.729236 0.421027 -0.539399 -v 0.073921 0.090125 0.012959 -vn 0.842051 0.000001 -0.539397 -v 0.073753 0.090750 0.012959 -vn 0.729237 -0.421029 -0.539397 -v 0.073921 0.091375 0.012959 -vn 0.421028 -0.729237 -0.539396 -v 0.074378 0.091832 0.012959 -vn 0.000002 -0.913442 -0.406970 -v 0.069003 0.084150 0.015100 -vn -0.456724 -0.791066 -0.406962 -v 0.069453 0.084029 0.015100 -vn -0.791061 -0.456722 -0.406974 -v 0.069782 0.083700 0.015100 -vn -0.913440 -0.000003 -0.406973 -v 0.069903 0.083250 0.015100 -vn -0.791062 0.456726 -0.406966 -v 0.069782 0.082800 0.015100 -vn -0.456718 0.791071 -0.406960 -v 0.069453 0.082471 0.015100 -vn -0.000002 0.913442 -0.406970 -v 0.069003 0.082350 0.015100 -vn 0.456715 0.791072 -0.406960 -v 0.068553 0.082471 0.015100 -vn 0.791071 0.456724 -0.406952 -v 0.068224 0.082800 0.015100 -vn 0.913442 -0.000001 -0.406970 -v 0.068103 0.083250 0.015100 -vn 0.791068 -0.456721 -0.406961 -v 0.068224 0.083700 0.015100 -vn 0.456718 -0.791071 -0.406960 -v 0.068553 0.084029 0.015100 -vn -0.000001 -0.913440 -0.406974 -v 0.067003 0.097650 0.015100 -vn -0.456717 -0.791063 -0.406975 -v 0.067453 0.097529 0.015100 -vn -0.791068 -0.456720 -0.406962 -v 0.067782 0.097200 0.015100 -vn -0.913442 -0.000002 -0.406970 -v 0.067903 0.096750 0.015100 -vn -0.791069 0.456719 -0.406961 -v 0.067782 0.096300 0.015100 -vn -0.456718 0.791071 -0.406960 -v 0.067453 0.095971 0.015100 -vn -0.000002 0.913442 -0.406970 -v 0.067003 0.095850 0.015100 -vn 0.456724 0.791066 -0.406962 -v 0.066553 0.095971 0.015100 -vn 0.791062 0.456720 -0.406974 -v 0.066224 0.096300 0.015100 -vn 0.913448 -0.000003 -0.406956 -v 0.066103 0.096750 0.015100 -vn 0.791062 -0.456720 -0.406974 -v 0.066224 0.097200 0.015100 -vn 0.456723 -0.791060 -0.406976 -v 0.066553 0.097529 0.015100 -vn 0.000002 -0.913442 -0.406970 -v 0.067003 0.113150 0.015100 -vn -0.456715 -0.791072 -0.406960 -v 0.067453 0.113029 0.015100 -vn -0.791070 -0.456725 -0.406952 -v 0.067782 0.112700 0.015100 -vn -0.913442 -0.000003 -0.406970 -v 0.067903 0.112250 0.015100 -vn -0.791069 0.456719 -0.406961 -v 0.067782 0.111800 0.015100 -vn -0.456718 0.791071 -0.406960 -v 0.067453 0.111471 0.015100 -vn -0.000002 0.913442 -0.406970 -v 0.067003 0.111350 0.015100 -vn 0.456724 0.791066 -0.406962 -v 0.066553 0.111471 0.015100 -vn 0.791062 0.456720 -0.406974 -v 0.066224 0.111800 0.015100 -vn 0.913448 -0.000003 -0.406956 -v 0.066103 0.112250 0.015100 -vn 0.791064 -0.456726 -0.406964 -v 0.066224 0.112700 0.015100 -vn 0.456718 -0.791071 -0.406960 -v 0.066553 0.113029 0.015100 -vn 0.000002 -0.913442 -0.406970 -v 0.081003 0.084150 0.015100 -vn -0.456730 -0.791067 -0.406952 -v 0.081453 0.084029 0.015100 -vn -0.791061 -0.456724 -0.406972 -v 0.081782 0.083700 0.015100 -vn -0.913448 -0.000000 -0.406956 -v 0.081903 0.083250 0.015100 -vn -0.791064 0.456724 -0.406965 -v 0.081782 0.082800 0.015100 -vn -0.456721 0.791073 -0.406951 -v 0.081453 0.082471 0.015100 -vn -0.000003 0.913442 -0.406970 -v 0.081003 0.082350 0.015100 -vn 0.456715 0.791072 -0.406960 -v 0.080553 0.082471 0.015100 -vn 0.791071 0.456724 -0.406952 -v 0.080224 0.082800 0.015100 -vn 0.913442 -0.000001 -0.406970 -v 0.080103 0.083250 0.015100 -vn 0.791068 -0.456721 -0.406961 -v 0.080224 0.083700 0.015100 -vn 0.456718 -0.791071 -0.406960 -v 0.080553 0.084029 0.015100 -vn 0.000002 -0.913442 -0.406970 -v 0.083003 0.113150 0.015100 -vn -0.456719 -0.791069 -0.406961 -v 0.083453 0.113029 0.015100 -vn -0.791062 -0.456728 -0.406966 -v 0.083782 0.112700 0.015100 -vn -0.913440 -0.000000 -0.406973 -v 0.083903 0.112250 0.015100 -vn -0.791063 0.456717 -0.406975 -v 0.083782 0.111800 0.015100 -vn -0.456720 0.791068 -0.406962 -v 0.083453 0.111471 0.015100 -vn -0.000002 0.913442 -0.406970 -v 0.083003 0.111350 0.015100 -vn 0.456724 0.791066 -0.406962 -v 0.082553 0.111471 0.015100 -vn 0.791062 0.456720 -0.406974 -v 0.082224 0.111800 0.015100 -vn 0.913440 -0.000001 -0.406974 -v 0.082103 0.112250 0.015100 -vn 0.791062 -0.456728 -0.406966 -v 0.082224 0.112700 0.015100 -vn 0.456718 -0.791071 -0.406960 -v 0.082553 0.113029 0.015100 -vn -0.000001 -0.913440 -0.406974 -v 0.083003 0.097650 0.015100 -vn -0.456722 -0.791060 -0.406975 -v 0.083453 0.097529 0.015100 -vn -0.791060 -0.456723 -0.406976 -v 0.083782 0.097200 0.015100 -vn -0.913440 0.000001 -0.406974 -v 0.083903 0.096750 0.015100 -vn -0.791063 0.456717 -0.406975 -v 0.083782 0.096300 0.015100 -vn -0.456720 0.791068 -0.406962 -v 0.083453 0.095971 0.015100 -vn -0.000002 0.913442 -0.406970 -v 0.083003 0.095850 0.015100 -vn 0.456724 0.791066 -0.406962 -v 0.082553 0.095971 0.015100 -vn 0.791062 0.456720 -0.406974 -v 0.082224 0.096300 0.015100 -vn 0.913440 -0.000001 -0.406974 -v 0.082103 0.096750 0.015100 -vn 0.791060 -0.456722 -0.406975 -v 0.082224 0.097200 0.015100 -vn 0.456723 -0.791060 -0.406976 -v 0.082553 0.097529 0.015100 -vn -0.867097 -0.033954 -0.496980 -v 0.062137 0.084250 0.015500 -vn -0.504677 -0.019975 -0.863077 -v 0.062503 0.084250 0.015134 -vn -0.019975 -0.504680 -0.863075 -v 0.067003 0.079750 0.015134 -vn -0.079717 -0.503307 -0.860423 -v 0.066299 0.079805 0.015134 -vn -0.033954 -0.867103 -0.496970 -v 0.067003 0.079384 0.015500 -vn -0.135973 -0.858489 -0.494478 -v 0.066242 0.079444 0.015500 -vn -0.268596 -0.826648 -0.494480 -v 0.065499 0.079622 0.015500 -vn -0.394604 -0.774453 -0.494481 -v 0.064794 0.079914 0.015500 -vn -0.510896 -0.703188 -0.494482 -v 0.064143 0.080313 0.015500 -vn -0.614609 -0.614610 -0.494481 -v 0.063562 0.080809 0.015500 -vn -0.703188 -0.510895 -0.494483 -v 0.063066 0.081390 0.015500 -vn -0.774451 -0.394606 -0.494481 -v 0.062667 0.082041 0.015500 -vn -0.826646 -0.268595 -0.494482 -v 0.062375 0.082746 0.015500 -vn -0.858485 -0.135970 -0.494485 -v 0.062197 0.083489 0.015500 -vn -0.157470 -0.484641 -0.860422 -v 0.065612 0.079970 0.015134 -vn -0.231346 -0.454041 -0.860422 -v 0.064960 0.080240 0.015134 -vn -0.299524 -0.412260 -0.860423 -v 0.064358 0.080609 0.015134 -vn -0.360328 -0.360328 -0.860423 -v 0.063821 0.081068 0.015134 -vn -0.412261 -0.299525 -0.860422 -v 0.063362 0.081605 0.015134 -vn -0.454040 -0.231346 -0.860422 -v 0.062994 0.082207 0.015134 -vn -0.484639 -0.157468 -0.860424 -v 0.062723 0.082859 0.015134 -vn -0.503303 -0.079714 -0.860425 -v 0.062558 0.083546 0.015134 -vn 0.019975 -0.504680 -0.863076 -v 0.083003 0.079750 0.015134 -vn 0.033954 -0.867103 -0.496970 -v 0.083003 0.079384 0.015500 -vn 0.504680 -0.019975 -0.863075 -v 0.087503 0.084250 0.015134 -vn 0.503307 -0.079716 -0.860423 -v 0.087448 0.083546 0.015134 -vn 0.867100 -0.033955 -0.496975 -v 0.087869 0.084250 0.015500 -vn 0.858489 -0.135970 -0.494478 -v 0.087809 0.083489 0.015500 -vn 0.826648 -0.268595 -0.494479 -v 0.087631 0.082746 0.015500 -vn 0.774452 -0.394604 -0.494481 -v 0.087339 0.082041 0.015500 -vn 0.703189 -0.510896 -0.494480 -v 0.086940 0.081390 0.015500 -vn 0.614609 -0.614609 -0.494481 -v 0.086444 0.080809 0.015500 -vn 0.510898 -0.703187 -0.494481 -v 0.085863 0.080313 0.015500 -vn 0.394608 -0.774453 -0.494477 -v 0.085212 0.079914 0.015500 -vn 0.268595 -0.826648 -0.494480 -v 0.084507 0.079622 0.015500 -vn 0.135973 -0.858489 -0.494477 -v 0.083764 0.079444 0.015500 -vn 0.484639 -0.157470 -0.860424 -v 0.087283 0.082859 0.015134 -vn 0.454041 -0.231345 -0.860422 -v 0.087013 0.082207 0.015134 -vn 0.412258 -0.299524 -0.860423 -v 0.086644 0.081605 0.015134 -vn 0.360328 -0.360328 -0.860423 -v 0.086185 0.081068 0.015134 -vn 0.299525 -0.412258 -0.860423 -v 0.085648 0.080609 0.015134 -vn 0.231348 -0.454040 -0.860422 -v 0.085046 0.080240 0.015134 -vn 0.157470 -0.484641 -0.860422 -v 0.084394 0.079970 0.015134 -vn 0.079717 -0.503307 -0.860423 -v 0.083707 0.079805 0.015134 -vn 0.858927 -0.495888 -0.127824 -v 0.084963 0.116400 0.012300 -vn 0.495905 -0.858917 -0.127828 -v 0.084853 0.116290 0.012300 -vn 0.514024 0.069807 -0.854930 -v 0.084853 0.122950 0.012040 -vn 0.514026 -0.069805 -0.854929 -v 0.084853 0.116550 0.012040 -vn 0.865328 0.112928 -0.488317 -v 0.084963 0.122950 0.012150 -vn 0.865326 -0.112919 -0.488323 -v 0.084963 0.116550 0.012150 -vn 0.495888 0.858927 -0.127824 -v 0.084853 0.123210 0.012300 -vn 0.858928 0.495884 -0.127834 -v 0.084963 0.123100 0.012300 -vn 0.112921 -0.865317 -0.488339 -v 0.084703 0.116290 0.012150 -vn 0.437996 -0.758622 -0.482341 -v 0.084833 0.116325 0.012150 -vn 0.459778 -0.265452 -0.847431 -v 0.084833 0.116475 0.012040 -vn 0.265424 -0.459781 -0.847438 -v 0.084778 0.116420 0.012040 -vn 0.758625 -0.437994 -0.482338 -v 0.084928 0.116420 0.012150 -vn 0.069807 -0.514024 -0.854930 -v 0.084703 0.116400 0.012040 -vn 0.758628 0.437978 -0.482348 -v 0.084928 0.123080 0.012150 -vn 0.069825 0.514023 -0.854930 -v 0.084703 0.123100 0.012040 -vn 0.265455 0.459757 -0.847441 -v 0.084778 0.123080 0.012040 -vn 0.459772 0.265469 -0.847429 -v 0.084833 0.123025 0.012040 -vn 0.438004 0.758609 -0.482353 -v 0.084833 0.123175 0.012150 -vn 0.112919 0.865326 -0.488323 -v 0.084703 0.123210 0.012150 -vn -0.495908 -0.858915 -0.127829 -v 0.079153 0.116290 0.012300 -vn -0.858916 -0.495910 -0.127813 -v 0.079043 0.116400 0.012300 -vn -0.069811 -0.514027 -0.854929 -v 0.079303 0.116400 0.012040 -vn -0.112930 -0.865317 -0.488338 -v 0.079303 0.116290 0.012150 -vn -0.069834 0.514028 -0.854926 -v 0.079303 0.123100 0.012040 -vn -0.112932 0.865326 -0.488322 -v 0.079303 0.123210 0.012150 -vn -0.858918 0.495904 -0.127826 -v 0.079043 0.123100 0.012300 -vn -0.495890 0.858925 -0.127827 -v 0.079153 0.123210 0.012300 -vn -0.865318 -0.112899 -0.488343 -v 0.079043 0.116550 0.012150 -vn -0.758628 -0.437996 -0.482332 -v 0.079078 0.116420 0.012150 -vn -0.265443 -0.459782 -0.847432 -v 0.079228 0.116420 0.012040 -vn -0.459776 -0.265439 -0.847436 -v 0.079173 0.116475 0.012040 -vn -0.437990 -0.758629 -0.482335 -v 0.079173 0.116325 0.012150 -vn -0.514028 -0.069801 -0.854929 -v 0.079153 0.116550 0.012040 -vn -0.437994 0.758621 -0.482344 -v 0.079173 0.123175 0.012150 -vn -0.514028 0.069805 -0.854929 -v 0.079153 0.122950 0.012040 -vn -0.459773 0.265445 -0.847436 -v 0.079173 0.123025 0.012040 -vn -0.265462 0.459762 -0.847436 -v 0.079228 0.123080 0.012040 -vn -0.758636 0.437975 -0.482337 -v 0.079078 0.123080 0.012150 -vn -0.865320 0.112913 -0.488336 -v 0.079043 0.122950 0.012150 -vn 0.495891 0.858924 -0.127833 -v 0.070853 0.123210 0.012300 -vn 0.858926 0.495887 -0.127838 -v 0.070963 0.123100 0.012300 -vn 0.112923 0.865325 -0.488324 -v 0.070703 0.123210 0.012150 -vn -0.112932 0.865326 -0.488322 -v 0.065303 0.123210 0.012150 -vn 0.069827 0.514024 -0.854929 -v 0.070703 0.123100 0.012040 -vn -0.069834 0.514028 -0.854926 -v 0.065303 0.123100 0.012040 -vn -0.858916 0.495906 -0.127833 -v 0.065043 0.123100 0.012300 -vn -0.495879 0.858932 -0.127831 -v 0.065153 0.123210 0.012300 -vn 0.865326 0.112932 -0.488322 -v 0.070963 0.122950 0.012150 -vn 0.758620 0.437986 -0.482353 -v 0.070928 0.123080 0.012150 -vn 0.265466 0.459755 -0.847439 -v 0.070778 0.123080 0.012040 -vn 0.459762 0.265462 -0.847436 -v 0.070833 0.123025 0.012040 -vn 0.437994 0.758614 -0.482355 -v 0.070833 0.123175 0.012150 -vn 0.514029 0.069834 -0.854926 -v 0.070853 0.122950 0.012040 -vn -0.437994 0.758621 -0.482344 -v 0.065173 0.123175 0.012150 -vn -0.514016 0.069809 -0.854935 -v 0.065153 0.122950 0.012040 -vn -0.459773 0.265445 -0.847436 -v 0.065173 0.123025 0.012040 -vn -0.265462 0.459762 -0.847436 -v 0.065228 0.123080 0.012040 -vn -0.758613 0.437994 -0.482356 -v 0.065078 0.123080 0.012150 -vn -0.865318 0.112922 -0.488338 -v 0.065043 0.122950 0.012150 -vn 0.858927 -0.495888 -0.127824 -v 0.070963 0.116400 0.012300 -vn 0.495903 -0.858917 -0.127834 -v 0.070853 0.116290 0.012300 -vn 0.865326 -0.112919 -0.488323 -v 0.070963 0.116550 0.012150 -vn 0.514024 -0.069821 -0.854930 -v 0.070853 0.116550 0.012040 -vn -0.865322 -0.112920 -0.488332 -v 0.065043 0.116550 0.012150 -vn -0.514013 -0.069799 -0.854938 -v 0.065153 0.116550 0.012040 -vn -0.495894 -0.858923 -0.127829 -v 0.065153 0.116290 0.012300 -vn -0.858920 -0.495900 -0.127828 -v 0.065043 0.116400 0.012300 -vn 0.112927 -0.865317 -0.488338 -v 0.070703 0.116290 0.012150 -vn 0.437981 -0.758625 -0.482350 -v 0.070833 0.116325 0.012150 -vn 0.459758 -0.265465 -0.847438 -v 0.070833 0.116475 0.012040 -vn 0.265450 -0.459778 -0.847432 -v 0.070778 0.116420 0.012040 -vn 0.758613 -0.438003 -0.482348 -v 0.070928 0.116420 0.012150 -vn 0.069807 -0.514024 -0.854930 -v 0.070703 0.116400 0.012040 -vn -0.758618 -0.438003 -0.482341 -v 0.065078 0.116420 0.012150 -vn -0.069811 -0.514027 -0.854929 -v 0.065303 0.116400 0.012040 -vn -0.265443 -0.459782 -0.847432 -v 0.065228 0.116420 0.012040 -vn -0.459770 -0.265442 -0.847439 -v 0.065173 0.116475 0.012040 -vn -0.437985 -0.758630 -0.482338 -v 0.065173 0.116325 0.012150 -vn -0.112930 -0.865317 -0.488338 -v 0.065303 0.116290 0.012150 -vn 0.079716 0.503300 -0.860427 -v 0.075824 0.095935 0.012240 -vn 0.157469 0.484639 -0.860423 -v 0.076625 0.095743 0.012240 -vn 0.231344 0.454037 -0.860425 -v 0.077386 0.095428 0.012240 -vn 0.299523 0.412260 -0.860423 -v 0.078089 0.094997 0.012240 -vn 0.360320 0.360317 -0.860431 -v 0.078715 0.094462 0.012240 -vn 0.412254 0.299522 -0.860426 -v 0.079250 0.093836 0.012240 -vn 0.454035 0.231342 -0.860426 -v 0.079681 0.093133 0.012240 -vn 0.484647 0.157472 -0.860418 -v 0.079996 0.092372 0.012240 -vn 0.503301 0.079714 -0.860426 -v 0.080188 0.091571 0.012240 -vn 0.509584 0.000001 -0.860421 -v 0.080253 0.090750 0.012240 -vn 0.503300 -0.079715 -0.860427 -v 0.080188 0.089929 0.012240 -vn 0.484645 -0.157468 -0.860421 -v 0.079996 0.089128 0.012240 -vn 0.454033 -0.231343 -0.860427 -v 0.079681 0.088366 0.012240 -vn 0.412254 -0.299521 -0.860427 -v 0.079250 0.087664 0.012240 -vn 0.360321 -0.360321 -0.860429 -v 0.078715 0.087038 0.012240 -vn 0.299524 -0.412260 -0.860423 -v 0.078089 0.086503 0.012240 -vn 0.231343 -0.454037 -0.860425 -v 0.077386 0.086072 0.012240 -vn 0.157470 -0.484639 -0.860423 -v 0.076625 0.085757 0.012240 -vn 0.079716 -0.503301 -0.860427 -v 0.075824 0.085565 0.012240 -vn 0.000001 -0.509580 -0.860423 -v 0.075003 0.085500 0.012240 -vn -0.079715 -0.503299 -0.860428 -v 0.074182 0.085565 0.012240 -vn -0.157466 -0.484635 -0.860426 -v 0.073381 0.085757 0.012240 -vn -0.231344 -0.454037 -0.860424 -v 0.072620 0.086072 0.012240 -vn -0.299529 -0.412267 -0.860418 -v 0.071917 0.086503 0.012240 -vn -0.360330 -0.360326 -0.860423 -v 0.071291 0.087038 0.012240 -vn -0.412262 -0.299525 -0.860421 -v 0.070756 0.087664 0.012240 -vn -0.454037 -0.231344 -0.860425 -v 0.070325 0.088366 0.012240 -vn -0.484635 -0.157467 -0.860426 -v 0.070010 0.089128 0.012240 -vn -0.503314 -0.079718 -0.860419 -v 0.069818 0.089929 0.012240 -vn -0.509580 0.000001 -0.860423 -v 0.069753 0.090750 0.012240 -vn -0.503315 0.079717 -0.860418 -v 0.069818 0.091571 0.012240 -vn -0.484638 0.157470 -0.860424 -v 0.070010 0.092372 0.012240 -vn -0.454037 0.231344 -0.860424 -v 0.070325 0.093133 0.012240 -vn -0.412262 0.299525 -0.860421 -v 0.070756 0.093836 0.012240 -vn -0.360327 0.360326 -0.860424 -v 0.071291 0.094462 0.012240 -vn -0.299531 0.412265 -0.860418 -v 0.071917 0.094997 0.012240 -vn -0.231343 0.454037 -0.860425 -v 0.072620 0.095428 0.012240 -vn -0.157466 0.484635 -0.860426 -v 0.073381 0.095743 0.012240 -vn -0.079714 0.503299 -0.860428 -v 0.074182 0.095935 0.012240 -vn -0.000000 0.509580 -0.860423 -v 0.075003 0.096000 0.012240 -vn 0.135972 0.858487 -0.494482 -v 0.075841 0.096044 0.012350 -vn 0.268595 0.826652 -0.494472 -v 0.076659 0.095847 0.012350 -vn 0.394605 0.774456 -0.494474 -v 0.077436 0.095526 0.012350 -vn 0.510897 0.703192 -0.494475 -v 0.078153 0.095086 0.012350 -vn 0.614611 0.614610 -0.494477 -v 0.078793 0.094540 0.012350 -vn 0.703186 0.510894 -0.494487 -v 0.079339 0.093900 0.012350 -vn 0.774456 0.394605 -0.494474 -v 0.079779 0.093183 0.012350 -vn 0.826649 0.268593 -0.494479 -v 0.080101 0.092406 0.012350 -vn 0.858487 0.135970 -0.494482 -v 0.080297 0.091588 0.012350 -vn 0.869184 -0.000001 -0.494489 -v 0.080363 0.090750 0.012350 -vn 0.858487 -0.135971 -0.494481 -v 0.080297 0.089911 0.012350 -vn 0.826646 -0.268595 -0.494483 -v 0.080101 0.089094 0.012350 -vn 0.774457 -0.394605 -0.494473 -v 0.079779 0.088317 0.012350 -vn 0.703185 -0.510896 -0.494486 -v 0.079339 0.087600 0.012350 -vn 0.614611 -0.614610 -0.494478 -v 0.078793 0.086960 0.012350 -vn 0.510897 -0.703192 -0.494476 -v 0.078153 0.086414 0.012350 -vn 0.394605 -0.774457 -0.494473 -v 0.077436 0.085974 0.012350 -vn 0.268596 -0.826652 -0.494473 -v 0.076659 0.085652 0.012350 -vn 0.135969 -0.858487 -0.494482 -v 0.075841 0.085456 0.012350 -vn 0.000002 -0.869195 -0.494469 -v 0.075003 0.085390 0.012350 -vn -0.135972 -0.858486 -0.494484 -v 0.074165 0.085456 0.012350 -vn -0.268595 -0.826650 -0.494477 -v 0.073347 0.085652 0.012350 -vn -0.394606 -0.774456 -0.494474 -v 0.072570 0.085974 0.012350 -vn -0.510899 -0.703195 -0.494468 -v 0.071853 0.086414 0.012350 -vn -0.614608 -0.614610 -0.494482 -v 0.071213 0.086960 0.012350 -vn -0.703183 -0.510893 -0.494492 -v 0.070667 0.087600 0.012350 -vn -0.774448 -0.394602 -0.494490 -v 0.070227 0.088317 0.012350 -vn -0.826650 -0.268595 -0.494477 -v 0.069906 0.089094 0.012350 -vn -0.858493 -0.135976 -0.494469 -v 0.069709 0.089911 0.012350 -vn -0.869185 0.000002 -0.494487 -v 0.069643 0.090750 0.012350 -vn -0.858495 0.135972 -0.494468 -v 0.069709 0.091588 0.012350 -vn -0.826653 0.268593 -0.494473 -v 0.069906 0.092406 0.012350 -vn -0.774447 0.394601 -0.494491 -v 0.070227 0.093183 0.012350 -vn -0.703183 0.510894 -0.494492 -v 0.070667 0.093900 0.012350 -vn -0.614608 0.614610 -0.494482 -v 0.071213 0.094540 0.012350 -vn -0.510901 0.703194 -0.494468 -v 0.071853 0.095086 0.012350 -vn -0.394607 0.774456 -0.494472 -v 0.072570 0.095526 0.012350 -vn -0.268595 0.826649 -0.494477 -v 0.073347 0.095847 0.012350 -vn -0.135970 0.858486 -0.494484 -v 0.074165 0.096044 0.012350 -vn -0.000001 0.869195 -0.494469 -v 0.075003 0.096110 0.012350 -vn 0.531962 0.513708 0.673142 -v 0.073025 0.088840 0.050500 -vn 0.668687 0.313586 0.674183 -v 0.072512 0.089585 0.050500 -vn 0.794737 0.465210 0.389837 -v 0.072531 0.089544 0.051700 -vn 0.732963 0.079094 0.675655 -v 0.072269 0.090457 0.050500 -vn 0.900920 0.189322 0.390513 -v 0.072280 0.090367 0.051700 -vn 0.861629 0.329017 0.386450 -v 0.072512 0.089585 0.051700 -vn 0.717748 -0.163113 0.676929 -v 0.072322 0.091361 0.050500 -vn 0.910397 -0.113075 0.397983 -v 0.072295 0.091227 0.051700 -vn 0.918734 0.046133 0.392172 -v 0.072269 0.090457 0.051700 -vn 0.624969 -0.386933 0.678009 -v 0.072666 0.092199 0.050500 -vn 0.833277 -0.390186 0.391669 -v 0.072575 0.092041 0.051700 -vn 0.888033 -0.256523 0.381567 -v 0.072322 0.091361 0.051700 -vn 0.464859 -0.568332 0.678900 -v 0.073263 0.092879 0.050500 -vn 0.666466 -0.634075 0.392138 -v 0.073093 0.092728 0.051700 -vn 0.761716 -0.525313 0.379256 -v 0.072666 0.092199 0.051700 -vn 0.254830 -0.687894 0.679605 -v 0.074048 0.093329 0.050500 -vn 0.431001 -0.812502 0.392529 -v 0.073798 0.093222 0.051700 -vn 0.556660 -0.740184 0.377171 -v 0.073263 0.092879 0.051700 -vn 0.017591 -0.732877 0.680134 -v 0.074937 0.093499 0.050500 -vn 0.151131 -0.907102 0.392843 -v 0.074620 0.093473 0.051700 -vn 0.294069 -0.878976 0.375399 -v 0.074048 0.093329 0.051700 -vn -0.221269 -0.698558 0.680483 -v 0.075834 0.093372 0.050500 -vn -0.144267 -0.908125 0.393060 -v 0.075481 0.093458 0.051700 -vn 0.000993 -0.927426 0.374005 -v 0.074937 0.093499 0.051700 -vn -0.436029 -0.588715 0.680657 -v 0.076640 0.092960 0.050500 -vn -0.424742 -0.815467 0.393203 -v 0.076294 0.093178 0.051700 -vn -0.292353 -0.880549 0.373046 -v 0.075834 0.093372 0.051700 -vn -0.603572 -0.415218 0.680658 -v 0.077269 0.092309 0.050500 -vn -0.671775 -0.632561 0.385467 -v 0.076981 0.092660 0.051700 -vn -0.555761 -0.743187 0.372562 -v 0.076640 0.092960 0.051700 -vn -0.705855 -0.196754 0.680483 -v 0.077652 0.091488 0.050500 -vn -0.836855 -0.387938 0.386234 -v 0.077475 0.091955 0.051700 -vn -0.761736 -0.551234 0.340440 -v 0.077269 0.092309 0.051700 -vn -0.731816 0.043158 0.680135 -v 0.077748 0.090588 0.050500 -vn -0.910712 -0.116056 0.396403 -v 0.077726 0.091133 0.051700 -vn -0.895121 -0.279384 0.347425 -v 0.077652 0.091488 0.051700 -vn -0.678580 0.278677 0.679608 -v 0.077547 0.089706 0.050500 -vn -0.901901 0.190746 0.387545 -v 0.077711 0.090272 0.051700 -vn -0.920504 0.039217 0.388760 -v 0.077748 0.090588 0.051700 -vn -0.551764 0.484410 0.678898 -v 0.077070 0.088936 0.050500 -vn -0.795350 0.465625 0.388086 -v 0.077431 0.089459 0.051700 -vn -0.877631 0.316066 0.360370 -v 0.077547 0.089706 0.051700 -vn -0.364887 0.638092 0.678009 -v 0.076369 0.088363 0.050500 -vn -0.607535 0.692765 0.388559 -v 0.076913 0.088772 0.051700 -vn -0.729340 0.577850 0.366269 -v 0.077070 0.088936 0.051700 -vn -0.137965 0.723005 0.676927 -v 0.075520 0.088049 0.050500 -vn -0.357730 0.848962 0.388964 -v 0.076209 0.088278 0.051700 -vn -0.505840 0.778414 0.371750 -v 0.076369 0.088363 0.051700 -vn 0.104625 0.729755 0.675656 -v 0.074615 0.088027 0.050500 -vn -0.080629 0.913962 0.397709 -v 0.075386 0.088027 0.051700 -vn -0.230581 0.897146 0.376777 -v 0.075520 0.088049 0.051700 -vn 0.336731 0.657335 0.674183 -v 0.073752 0.088301 0.050500 -vn 0.221976 0.893835 0.389596 -v 0.074526 0.088042 0.051700 -vn 0.078796 0.915196 0.395231 -v 0.074615 0.088027 0.051700 -vn 0.660271 0.637613 0.396853 -v 0.073025 0.088840 0.051700 -vn 0.492627 0.778039 0.389837 -v 0.073712 0.088322 0.051700 -vn 0.357729 0.850622 0.385322 -v 0.073752 0.088301 0.051700 -vn 0.138742 -0.374750 0.916686 -v 0.078718 0.080716 0.052000 -vn 0.198533 -0.346806 0.916685 -v 0.080319 0.081464 0.052000 -vn -0.004719 0.356304 0.934358 -v 0.075081 0.087701 0.052000 -vn 0.156645 0.151272 0.976002 -v 0.068708 0.095793 0.052000 -vn 0.211292 0.052681 0.976002 -v 0.068451 0.096257 0.052000 -vn -0.331779 0.242087 0.911766 -v 0.066237 0.096886 0.052000 -vn 0.209328 -0.060023 0.976002 -v 0.068460 0.096787 0.052000 -vn -0.365997 -0.005096 0.930602 -v 0.078052 0.090828 0.052000 -vn 0.344420 0.206177 0.915896 -v 0.083977 0.096577 0.052000 -vn -0.151272 0.156647 0.976001 -v 0.081470 0.095570 0.052000 -vn 0.358504 -0.014961 0.933408 -v 0.071959 0.090934 0.052000 -vn -0.052682 0.211294 0.976002 -v 0.069694 0.095510 0.052000 -vn 0.060021 0.209321 0.976003 -v 0.069163 0.095519 0.052000 -vn -0.060023 -0.209328 0.976002 -v 0.069728 0.097490 0.052000 -vn -0.198534 0.346809 0.916683 -v 0.069687 0.100036 0.052000 -vn 0.052681 -0.211292 0.976002 -v 0.069198 0.097499 0.052000 -vn -0.252906 0.309395 0.916686 -v 0.068231 0.099034 0.052000 -vn 0.151272 -0.156647 0.976001 -v 0.068734 0.097242 0.052000 -vn -0.156642 -0.151268 0.976003 -v 0.070183 0.097217 0.052000 -vn -0.075169 0.392475 0.916686 -v 0.072990 0.101259 0.052000 -vn -0.138743 0.374755 0.916684 -v 0.071288 0.100784 0.052000 -vn -0.052681 0.211292 0.976002 -v 0.081006 0.095313 0.052000 -vn 0.060023 0.209328 0.976002 -v 0.080475 0.095322 0.052000 -vn -0.359793 -0.064049 0.930831 -v 0.078023 0.091174 0.052000 -vn -0.294470 0.265981 0.917901 -v 0.066960 0.097807 0.052000 -vn 0.181747 0.355888 0.916685 -v 0.079869 0.100279 0.052000 -vn 0.120690 0.380951 0.916685 -v 0.078235 0.100950 0.052000 -vn -0.211292 -0.052681 0.976002 -v 0.070440 0.096753 0.052000 -vn 0.056341 0.395619 0.916685 -v 0.076512 0.101343 0.052000 -vn -0.009542 0.399502 0.916683 -v 0.074748 0.101447 0.052000 -vn -0.209326 0.060024 0.976002 -v 0.070431 0.096222 0.052000 -vn 0.211294 0.052681 0.976002 -v 0.079763 0.096059 0.052000 -vn 0.209326 -0.060024 0.976002 -v 0.079772 0.096590 0.052000 -vn 0.051966 -0.356716 0.932766 -v 0.074579 0.093770 0.052000 -vn 0.159739 -0.322414 0.933023 -v 0.073666 0.093491 0.052000 -vn 0.251092 -0.256419 0.933382 -v 0.072884 0.092944 0.052000 -vn -0.151267 0.156644 0.976003 -v 0.070158 0.095767 0.052000 -vn 0.316981 -0.165621 0.933859 -v 0.072310 0.092182 0.052000 -vn 0.357425 -0.076190 0.930829 -v 0.071999 0.091280 0.052000 -vn -0.061418 -0.355676 0.932589 -v 0.075533 0.093754 0.052000 -vn -0.168987 -0.319223 0.932491 -v 0.076435 0.093443 0.052000 -vn 0.156644 0.151271 0.976002 -v 0.080020 0.095595 0.052000 -vn -0.259894 -0.242173 0.934777 -v 0.077197 0.092869 0.052000 -vn -0.320078 -0.151819 0.935148 -v 0.077744 0.092087 0.052000 -vn 0.151267 -0.156644 0.976003 -v 0.080046 0.097045 0.052000 -vn 0.052682 -0.211294 0.976002 -v 0.080510 0.097302 0.052000 -vn 0.237842 0.321118 0.916686 -v 0.081372 0.099348 0.052000 -vn -0.060021 -0.209321 0.976003 -v 0.081040 0.097293 0.052000 -vn 0.287459 0.277596 0.916683 -v 0.082700 0.098183 0.052000 -vn -0.156643 -0.151268 0.976003 -v 0.081495 0.097019 0.052000 -vn 0.315469 0.233917 0.919653 -v 0.083818 0.096815 0.052000 -vn -0.211291 -0.052682 0.976002 -v 0.081752 0.096555 0.052000 -vn -0.209326 0.060024 0.976002 -v 0.081743 0.096025 0.052000 -vn -0.156646 -0.151272 0.976002 -v 0.081298 0.085707 0.052000 -vn -0.211298 -0.052685 0.976001 -v 0.081555 0.085243 0.052000 -vn 0.369681 -0.151735 0.916686 -v 0.084902 0.086687 0.052000 -vn 0.252908 -0.309400 0.916684 -v 0.081775 0.082465 0.052000 -vn 0.300383 -0.263550 0.916685 -v 0.083046 0.083693 0.052000 -vn -0.209329 0.060022 0.976001 -v 0.081546 0.084713 0.052000 -vn -0.065521 0.358168 0.931355 -v 0.075428 0.087730 0.052000 -vn 0.209322 -0.060021 0.976003 -v 0.079575 0.085278 0.052000 -vn 0.339666 -0.210514 0.916685 -v 0.084098 0.085113 0.052000 -vn 0.156645 0.151271 0.976002 -v 0.079823 0.084283 0.052000 -vn 0.211295 0.052682 0.976002 -v 0.079566 0.084747 0.052000 -vn 0.052682 -0.211294 0.976002 -v 0.080312 0.085990 0.052000 -vn -0.060022 -0.209320 0.976003 -v 0.080843 0.085981 0.052000 -vn 0.361957 0.166147 0.917269 -v 0.084696 0.095281 0.052000 -vn 0.384930 0.107323 0.916685 -v 0.085310 0.093624 0.052000 -vn -0.151271 0.156645 0.976002 -v 0.081272 0.084258 0.052000 -vn -0.052681 0.211294 0.976002 -v 0.080808 0.084001 0.052000 -vn 0.060023 0.209327 0.976002 -v 0.080278 0.084010 0.052000 -vn -0.350629 0.074590 0.933540 -v 0.078007 0.090220 0.052000 -vn -0.311293 0.169552 0.935066 -v 0.077696 0.089318 0.052000 -vn 0.151267 -0.156641 0.976003 -v 0.079848 0.085733 0.052000 -vn -0.243738 0.257039 0.935159 -v 0.077122 0.088556 0.052000 -vn -0.152598 0.319168 0.935332 -v 0.076340 0.088009 0.052000 -vn 0.389615 -0.088820 0.916685 -v 0.085435 0.088372 0.052000 -vn 0.398920 -0.023479 0.916685 -v 0.085685 0.090121 0.052000 -vn 0.397344 0.042501 0.916685 -v 0.085642 0.091888 0.052000 -vn 0.016493 0.360731 0.932524 -v 0.074819 0.087706 0.052000 -vn -0.181746 -0.355888 0.916685 -v 0.070137 0.081221 0.052000 -vn -0.120691 -0.380950 0.916685 -v 0.071771 0.080550 0.052000 -vn -0.056340 -0.395614 0.916687 -v 0.073494 0.080157 0.052000 -vn 0.009543 -0.399502 0.916683 -v 0.075259 0.080053 0.052000 -vn 0.075168 -0.392475 0.916686 -v 0.077016 0.080241 0.052000 -vn 0.315144 0.155503 0.936217 -v 0.072262 0.089413 0.052000 -vn 0.353559 0.060412 0.933460 -v 0.071983 0.090325 0.052000 -vn -0.060023 -0.209327 0.976002 -v 0.069531 0.086178 0.052000 -vn 0.052681 -0.211293 0.976002 -v 0.069000 0.086187 0.052000 -vn 0.251130 0.242514 0.937081 -v 0.072809 0.088631 0.052000 -vn -0.156645 -0.151271 0.976002 -v 0.069986 0.085905 0.052000 -vn 0.165342 0.309336 0.936468 -v 0.073571 0.088057 0.052000 -vn -0.211294 -0.052682 0.976002 -v 0.070243 0.085441 0.052000 -vn 0.080601 0.352392 0.932375 -v 0.074473 0.087746 0.052000 -vn -0.209327 0.060021 0.976002 -v 0.070234 0.084910 0.052000 -vn -0.151267 0.156642 0.976003 -v 0.069960 0.084455 0.052000 -vn -0.052682 0.211294 0.976002 -v 0.069496 0.084198 0.052000 -vn -0.237845 -0.321121 0.916685 -v 0.068634 0.082152 0.052000 -vn 0.060022 0.209325 0.976002 -v 0.068966 0.084207 0.052000 -vn -0.287455 -0.277594 0.916685 -v 0.067306 0.083317 0.052000 -vn 0.156647 0.151272 0.976001 -v 0.068511 0.084481 0.052000 -vn -0.329228 -0.226496 0.916683 -v 0.066188 0.084685 0.052000 -vn 0.211293 0.052683 0.976002 -v 0.068254 0.084945 0.052000 -vn -0.362014 -0.169216 0.916685 -v 0.065310 0.086219 0.052000 -vn 0.209328 -0.060021 0.976002 -v 0.068263 0.085475 0.052000 -vn -0.384930 -0.107322 0.916685 -v 0.064696 0.087876 0.052000 -vn 0.151272 -0.156645 0.976002 -v 0.068536 0.085930 0.052000 -vn -0.340724 0.198158 0.919043 -v 0.065908 0.096387 0.052000 -vn -0.369681 0.151736 0.916685 -v 0.065104 0.094813 0.052000 -vn -0.389616 0.088819 0.916685 -v 0.064571 0.093128 0.052000 -vn -0.398919 0.023479 0.916686 -v 0.064322 0.091379 0.052000 -vn -0.397345 -0.042501 0.916685 -v 0.064364 0.089612 0.052000 -vn -0.666628 -0.643756 -0.375747 -v 0.067090 0.083109 0.047800 -vn -0.763495 -0.525254 0.375744 -v 0.065941 0.084515 0.051700 -vn -0.763494 -0.525255 -0.375744 -v 0.065941 0.084515 0.047800 -vn -0.839534 -0.392424 0.375747 -v 0.065038 0.086092 0.051700 -vn -0.839534 -0.392424 -0.375747 -v 0.065038 0.086092 0.047800 -vn -0.892676 -0.248887 0.375747 -v 0.064407 0.087796 0.051700 -vn -0.892676 -0.248887 -0.375747 -v 0.064407 0.087796 0.047800 -vn -0.921466 -0.098561 0.375747 -v 0.064065 0.089580 0.051700 -vn -0.921466 -0.098561 -0.375747 -v 0.064065 0.089580 0.047800 -vn -0.925121 0.054450 0.375748 -v 0.064022 0.091396 0.051700 -vn -0.925121 0.054450 -0.375748 -v 0.064022 0.091396 0.047800 -vn -0.903542 0.205977 0.375747 -v 0.064278 0.093195 0.051700 -vn -0.903542 0.205977 -0.375747 -v 0.064278 0.093195 0.047800 -vn -0.857315 0.351886 0.375748 -v 0.064827 0.094927 0.051700 -vn -0.857315 0.351886 -0.375748 -v 0.064827 0.094927 0.047800 -vn -0.792540 0.484071 0.370885 -v 0.065653 0.096545 0.051700 -vn -0.787703 0.488196 -0.375751 -v 0.065653 0.096545 0.047800 -vn -0.694829 0.614877 0.373012 -v 0.066734 0.098005 0.051700 -vn -0.696606 0.611190 -0.375748 -v 0.066734 0.098005 0.047800 -vn -0.586507 0.717512 0.375748 -v 0.068041 0.099267 0.051700 -vn -0.586506 0.717512 -0.375749 -v 0.068041 0.099267 0.047800 -vn -0.460409 0.804264 0.375743 -v 0.069538 0.100296 0.051700 -vn -0.462778 0.804238 -0.372878 -v 0.069538 0.100296 0.047800 -vn -0.321754 0.869074 0.375745 -v 0.071184 0.101066 0.051700 -vn -0.321755 0.869074 -0.375744 -v 0.071184 0.101066 0.047800 -vn -0.174321 0.910179 0.375748 -v 0.072934 0.101554 0.051700 -vn -0.174319 0.910179 -0.375749 -v 0.072934 0.101554 0.047800 -vn -0.022130 0.926460 0.375743 -v 0.074740 0.101747 0.051700 -vn -0.022131 0.926460 -0.375743 -v 0.074740 0.101747 0.047800 -vn 0.130658 0.917466 0.375746 -v 0.076554 0.101640 0.051700 -vn 0.130659 0.917466 -0.375746 -v 0.076554 0.101640 0.047800 -vn 0.279887 0.883446 0.375747 -v 0.078325 0.101236 0.051700 -vn 0.279887 0.883447 -0.375747 -v 0.078325 0.101236 0.047800 -vn 0.421482 0.825328 0.375748 -v 0.080006 0.100546 0.051700 -vn 0.421481 0.825329 -0.375748 -v 0.080006 0.100546 0.047800 -vn 0.551576 0.744699 0.375749 -v 0.081550 0.099589 0.051700 -vn 0.551577 0.744698 -0.375750 -v 0.081550 0.099589 0.047800 -vn 0.666630 0.643756 0.375743 -v 0.082916 0.098391 0.051700 -vn 0.666629 0.643757 -0.375743 -v 0.082916 0.098391 0.047800 -vn 0.762338 0.530225 0.371083 -v 0.084066 0.096985 0.051700 -vn 0.763496 0.525253 -0.375743 -v 0.084066 0.096985 0.047800 -vn 0.840857 0.390854 0.374424 -v 0.084968 0.095408 0.051700 -vn 0.839535 0.392423 -0.375747 -v 0.084968 0.095408 0.047800 -vn 0.892676 0.248887 0.375747 -v 0.085599 0.093704 0.051700 -vn 0.892675 0.248887 -0.375747 -v 0.085599 0.093704 0.047800 -vn 0.921466 0.098563 0.375747 -v 0.085941 0.091920 0.051700 -vn 0.921466 0.098563 -0.375747 -v 0.085941 0.091920 0.047800 -vn 0.925121 -0.054450 0.375748 -v 0.085984 0.090104 0.051700 -vn 0.925121 -0.054450 -0.375748 -v 0.085984 0.090104 0.047800 -vn 0.903542 -0.205978 0.375747 -v 0.085728 0.088305 0.051700 -vn 0.903542 -0.205978 -0.375747 -v 0.085728 0.088305 0.047800 -vn 0.857316 -0.351883 0.375748 -v 0.085179 0.086573 0.051700 -vn 0.857316 -0.351884 -0.375748 -v 0.085179 0.086573 0.047800 -vn 0.787706 -0.488194 0.375747 -v 0.084353 0.084955 0.051700 -vn 0.787706 -0.488194 -0.375747 -v 0.084353 0.084955 0.047800 -vn 0.696607 -0.611190 0.375747 -v 0.083272 0.083495 0.051700 -vn 0.696606 -0.611190 -0.375748 -v 0.083272 0.083495 0.047800 -vn 0.586507 -0.717513 0.375745 -v 0.081965 0.082233 0.051700 -vn 0.586507 -0.717513 -0.375745 -v 0.081965 0.082233 0.047800 -vn 0.460411 -0.804262 0.375746 -v 0.080468 0.081204 0.051700 -vn 0.460411 -0.804262 -0.375746 -v 0.080468 0.081204 0.047800 -vn 0.321754 -0.869073 0.375749 -v 0.078822 0.080434 0.051700 -vn 0.321754 -0.869073 -0.375749 -v 0.078822 0.080434 0.047800 -vn 0.174319 -0.910179 0.375748 -v 0.077072 0.079946 0.051700 -vn 0.174318 -0.910179 -0.375749 -v 0.077072 0.079946 0.047800 -vn 0.022131 -0.926460 0.375743 -v 0.075266 0.079753 0.051700 -vn 0.022133 -0.926460 -0.375743 -v 0.075266 0.079753 0.047800 -vn -0.130658 -0.917464 0.375751 -v 0.073452 0.079860 0.051700 -vn -0.130659 -0.917464 -0.375751 -v 0.073452 0.079860 0.047800 -vn -0.279889 -0.883446 0.375747 -v 0.071681 0.080264 0.051700 -vn -0.279889 -0.883446 -0.375747 -v 0.071681 0.080264 0.047800 -vn -0.421481 -0.825329 0.375748 -v 0.070000 0.080953 0.051700 -vn -0.418067 -0.828955 -0.371556 -v 0.070000 0.080953 0.047800 -vn -0.551576 -0.744700 0.375747 -v 0.068456 0.081911 0.051700 -vn -0.551577 -0.744700 -0.375747 -v 0.068456 0.081911 0.047800 -vn -0.666628 -0.643756 0.375746 -v 0.067090 0.083109 0.051700 -vn 0.151271 -0.156644 -0.976002 -v 0.068536 0.085930 0.047500 -vn 0.209328 -0.060021 -0.976002 -v 0.068263 0.085475 0.047500 -vn -0.362014 -0.169216 -0.916685 -v 0.065310 0.086219 0.047500 -vn -0.329228 -0.226497 -0.916683 -v 0.066188 0.084685 0.047500 -vn 0.211293 0.052684 -0.976002 -v 0.068254 0.084945 0.047500 -vn -0.287456 -0.277594 -0.916685 -v 0.067306 0.083317 0.047500 -vn 0.156647 0.151271 -0.976002 -v 0.068511 0.084481 0.047500 -vn -0.238630 -0.320532 -0.916687 -v 0.068634 0.082152 0.047500 -vn 0.060023 0.209325 -0.976002 -v 0.068966 0.084207 0.047500 -vn -0.237991 -0.365689 -0.899795 -v 0.069494 0.081577 0.047500 -vn -0.052683 0.211294 -0.976002 -v 0.069496 0.084198 0.047500 -vn -0.151267 0.156642 -0.976003 -v 0.069960 0.084455 0.047500 -vn -0.209327 0.060022 -0.976002 -v 0.070234 0.084910 0.047500 -vn -0.105829 -0.683402 -0.722331 -v 0.074391 0.086292 0.047500 -vn -0.211294 -0.052683 -0.976002 -v 0.070243 0.085441 0.047500 -vn -0.213091 -0.651016 -0.728540 -v 0.073672 0.086451 0.047500 -vn -0.060024 -0.209327 -0.976002 -v 0.069531 0.086178 0.047500 -vn -0.663064 0.160413 -0.731173 -v 0.070629 0.091808 0.047500 -vn -0.682126 -0.009526 -0.731172 -v 0.070503 0.090687 0.047500 -vn -0.384930 -0.107322 -0.916685 -v 0.064696 0.087876 0.047500 -vn -0.397344 -0.042501 -0.916685 -v 0.064364 0.089612 0.047500 -vn -0.398919 0.023479 -0.916686 -v 0.064322 0.091379 0.047500 -vn 0.052682 -0.211292 -0.976002 -v 0.069000 0.086187 0.047500 -vn 0.060020 0.209321 -0.976003 -v 0.069163 0.095519 0.047500 -vn -0.052681 0.211293 -0.976002 -v 0.069694 0.095510 0.047500 -vn -0.658328 -0.178865 -0.731171 -v 0.070660 0.089570 0.047500 -vn -0.593162 -0.336965 -0.731173 -v 0.071090 0.088527 0.047500 -vn -0.156645 -0.151270 -0.976002 -v 0.069986 0.085905 0.047500 -vn -0.490729 -0.473892 -0.731171 -v 0.071766 0.087624 0.047500 -vn -0.357458 -0.581042 -0.731173 -v 0.072645 0.086917 0.047500 -vn -0.103183 0.686827 -0.719460 -v 0.074532 0.095225 0.047500 -vn -0.223929 0.645649 -0.730064 -v 0.073553 0.095010 0.047500 -vn -0.209326 0.060024 -0.976002 -v 0.070431 0.096222 0.047500 -vn -0.373544 0.570835 -0.731172 -v 0.072539 0.094515 0.047500 -vn -0.151267 0.156643 -0.976003 -v 0.070158 0.095767 0.047500 -vn -0.503770 0.460004 -0.731172 -v 0.071680 0.093784 0.047500 -vn -0.602342 0.320272 -0.731170 -v 0.071030 0.092863 0.047500 -vn -0.211293 -0.052681 -0.976002 -v 0.070440 0.096753 0.047500 -vn -0.156642 -0.151268 -0.976003 -v 0.070183 0.097217 0.047500 -vn -0.177187 0.355740 -0.917635 -v 0.069813 0.100107 0.047500 -vn -0.060023 -0.209327 -0.976002 -v 0.069728 0.097490 0.047500 -vn 0.156646 0.151271 -0.976002 -v 0.068708 0.095793 0.047500 -vn -0.389616 0.088819 -0.916685 -v 0.064571 0.093128 0.047500 -vn 0.211292 0.052682 -0.976002 -v 0.068451 0.096257 0.047500 -vn -0.300382 0.263550 -0.916685 -v 0.066960 0.097807 0.047500 -vn -0.252906 0.309396 -0.916686 -v 0.068231 0.099034 0.047500 -vn 0.052682 -0.211292 -0.976002 -v 0.069198 0.097499 0.047500 -vn -0.207831 0.332470 -0.919929 -v 0.069687 0.100036 0.047500 -vn 0.151271 -0.156646 -0.976002 -v 0.068734 0.097242 0.047500 -vn 0.209328 -0.060024 -0.976002 -v 0.068460 0.096787 0.047500 -vn -0.339660 0.210512 -0.916687 -v 0.065908 0.096387 0.047500 -vn -0.369681 0.151736 -0.916686 -v 0.065104 0.094813 0.047500 -vn 0.060023 0.209328 -0.976002 -v 0.080475 0.095322 0.047500 -vn -0.052682 0.211292 -0.976002 -v 0.081006 0.095313 0.047500 -vn 0.675554 0.094943 -0.731172 -v 0.079459 0.091376 0.047500 -vn 0.677942 -0.076043 -0.731172 -v 0.079475 0.090248 0.047500 -vn -0.151271 0.156647 -0.976002 -v 0.081470 0.095570 0.047500 -vn 0.362014 0.169215 -0.916685 -v 0.084696 0.095281 0.047500 -vn -0.209326 0.060025 -0.976002 -v 0.081743 0.096025 0.047500 -vn 0.329228 0.226496 -0.916683 -v 0.083818 0.096815 0.047500 -vn -0.211292 -0.052682 -0.976002 -v 0.081752 0.096555 0.047500 -vn 0.287459 0.277597 -0.916683 -v 0.082700 0.098183 0.047500 -vn -0.156643 -0.151269 -0.976002 -v 0.081495 0.097019 0.047500 -vn 0.237843 0.321118 -0.916686 -v 0.081372 0.099348 0.047500 -vn -0.060020 -0.209321 -0.976003 -v 0.081040 0.097293 0.047500 -vn 0.181746 0.355888 -0.916685 -v 0.079869 0.100279 0.047500 -vn 0.052681 -0.211293 -0.976002 -v 0.080510 0.097302 0.047500 -vn 0.120690 0.380950 -0.916685 -v 0.078235 0.100950 0.047500 -vn 0.151267 -0.156643 -0.976003 -v 0.080046 0.097045 0.047500 -vn 0.056342 0.395619 -0.916685 -v 0.076512 0.101343 0.047500 -vn -0.018544 0.693208 -0.720499 -v 0.074658 0.095237 0.047500 -vn 0.118461 0.671828 -0.731174 -v 0.075784 0.095182 0.047500 -vn -0.009544 0.399502 -0.916683 -v 0.074748 0.101447 0.047500 -vn 0.209326 -0.060024 -0.976002 -v 0.079772 0.096590 0.047500 -vn -0.075167 0.392475 -0.916686 -v 0.072990 0.101259 0.047500 -vn 0.630719 0.259964 -0.731172 -v 0.079163 0.092465 0.047500 -vn 0.546252 0.408649 -0.731173 -v 0.078606 0.093446 0.047500 -vn 0.156644 0.151271 -0.976002 -v 0.080020 0.095595 0.047500 -vn 0.427464 0.531660 -0.731172 -v 0.077823 0.094257 0.047500 -vn 0.211294 0.052681 -0.976002 -v 0.079763 0.096059 0.047500 -vn 0.281818 0.621262 -0.731172 -v 0.076862 0.094848 0.047500 -vn -0.138564 0.374821 -0.916684 -v 0.071288 0.100784 0.047500 -vn 0.384930 0.107323 -0.916685 -v 0.085310 0.093624 0.047500 -vn 0.397344 0.042502 -0.916685 -v 0.085642 0.091888 0.047500 -vn 0.398920 -0.023479 -0.916685 -v 0.085685 0.090121 0.047500 -vn 0.389615 -0.088819 -0.916685 -v 0.085435 0.088372 0.047500 -vn 0.369681 -0.151735 -0.916686 -v 0.084902 0.086687 0.047500 -vn 0.156645 0.151271 -0.976002 -v 0.079823 0.084283 0.047500 -vn 0.060024 0.209327 -0.976002 -v 0.080278 0.084010 0.047500 -vn 0.138742 -0.374750 -0.916686 -v 0.078718 0.080716 0.047500 -vn 0.300382 -0.263550 -0.916685 -v 0.083046 0.083693 0.047500 -vn 0.252909 -0.309399 -0.916684 -v 0.081775 0.082465 0.047500 -vn -0.052681 0.211294 -0.976002 -v 0.080808 0.084001 0.047500 -vn 0.637732 -0.242251 -0.731172 -v 0.079210 0.089152 0.047500 -vn 0.052681 -0.211293 -0.976002 -v 0.080312 0.085990 0.047500 -vn -0.120690 -0.380950 -0.916685 -v 0.071771 0.080550 0.047500 -vn -0.170773 -0.355945 -0.918771 -v 0.070137 0.081221 0.047500 -vn 0.211294 0.052681 -0.976002 -v 0.079566 0.084747 0.047500 -vn 0.198533 -0.346805 -0.916685 -v 0.080319 0.081464 0.047500 -vn -0.010664 -0.688851 -0.724824 -v 0.074783 0.086255 0.047500 -vn 0.137174 -0.668259 -0.731172 -v 0.075908 0.086342 0.047500 -vn -0.151271 0.156644 -0.976002 -v 0.081272 0.084258 0.047500 -vn -0.209328 0.060021 -0.976002 -v 0.081546 0.084713 0.047500 -vn 0.339666 -0.210513 -0.916685 -v 0.084098 0.085113 0.047500 -vn -0.211298 -0.052684 -0.976001 -v 0.081555 0.085243 0.047500 -vn -0.156647 -0.151272 -0.976001 -v 0.081298 0.085707 0.047500 -vn -0.060021 -0.209321 -0.976003 -v 0.080843 0.085981 0.047500 -vn 0.209322 -0.060019 -0.976003 -v 0.079575 0.085278 0.047500 -vn 0.299054 -0.613151 -0.731173 -v 0.076976 0.086705 0.047500 -vn 0.151267 -0.156642 -0.976003 -v 0.079848 0.085733 0.047500 -vn 0.442144 -0.519515 -0.731172 -v 0.077920 0.087323 0.047500 -vn 0.557451 -0.393239 -0.731171 -v 0.078680 0.088156 0.047500 -vn 0.075167 -0.392476 -0.916686 -v 0.077016 0.080241 0.047500 -vn 0.009545 -0.399502 -0.916683 -v 0.075259 0.080053 0.047500 -vn -0.056342 -0.395614 -0.916687 -v 0.073494 0.080157 0.047500 -vn -0.580685 -0.722223 -0.375766 -v 0.072183 0.087243 0.045600 -vn -0.467419 -0.782167 -0.411988 -v 0.072645 0.086917 0.045600 -vn -0.389437 -0.838228 -0.381723 -v 0.073144 0.086652 0.045600 -vn -0.257190 -0.874745 -0.410700 -v 0.073672 0.086451 0.045600 -vn -0.170039 -0.908514 -0.381693 -v 0.074222 0.086318 0.045600 -vn -0.032791 -0.910600 -0.411986 -v 0.074783 0.086255 0.045600 -vn 0.062547 -0.922160 -0.381719 -v 0.075348 0.086263 0.045600 -vn 0.194695 -0.890147 -0.411985 -v 0.075908 0.086342 0.045600 -vn 0.289915 -0.877631 -0.381723 -v 0.076453 0.086490 0.045600 -vn 0.403519 -0.827340 -0.390744 -v 0.076976 0.086705 0.045600 -vn 0.507436 -0.775440 -0.375769 -v 0.077467 0.086985 0.045600 -vn 0.596595 -0.700995 -0.390744 -v 0.077920 0.087323 0.045600 -vn 0.684338 -0.624883 -0.375770 -v 0.078326 0.087716 0.045600 -vn 0.751271 -0.515614 -0.411987 -v 0.078680 0.088156 0.045600 -vn 0.812119 -0.441306 -0.381722 -v 0.078976 0.088637 0.045600 -vn 0.855899 -0.312578 -0.411986 -v 0.079210 0.089152 0.045600 -vn 0.896354 -0.225475 -0.381721 -v 0.079377 0.089692 0.045600 -vn 0.906744 -0.089906 -0.411985 -v 0.079475 0.090248 0.045600 -vn 0.924267 0.004523 -0.381720 -v 0.079503 0.090813 0.045600 -vn 0.900617 0.138413 -0.411983 -v 0.079459 0.091376 0.045600 -vn 0.894103 0.234238 -0.381722 -v 0.079346 0.091930 0.045600 -vn 0.837897 0.358045 -0.411986 -v 0.079163 0.092465 0.045600 -vn 0.807763 0.449230 -0.381721 -v 0.078916 0.092973 0.045600 -vn 0.737074 0.551401 -0.390742 -v 0.078606 0.093446 0.045600 -vn 0.666621 0.643752 -0.375767 -v 0.078240 0.093876 0.045600 -vn 0.561767 0.717416 -0.411986 -v 0.077823 0.094257 0.045600 -vn 0.491428 0.782806 -0.381724 -v 0.077361 0.094583 0.045600 -vn 0.380264 0.838284 -0.390742 -v 0.076862 0.094848 0.045600 -vn 0.274040 0.885270 -0.375765 -v 0.076334 0.095049 0.045600 -vn 0.159843 0.906516 -0.390741 -v 0.075784 0.095182 0.045600 -vn 0.045265 0.925609 -0.375766 -v 0.075223 0.095245 0.045600 -vn -0.080990 0.907261 -0.412696 -v 0.074658 0.095237 0.045600 -vn -0.178120 0.906474 -0.382856 -v 0.074098 0.095158 0.045600 -vn -0.304722 0.858728 -0.411984 -v 0.073553 0.095010 0.045600 -vn -0.397625 0.834377 -0.381720 -v 0.073030 0.094795 0.045600 -vn -0.508708 0.755966 -0.411985 -v 0.072539 0.094515 0.045600 -vn -0.592635 0.709276 -0.381721 -v 0.072086 0.094177 0.045600 -vn -0.680724 0.605709 -0.411984 -v 0.071680 0.093784 0.045600 -vn -0.750407 0.539607 -0.381724 -v 0.071326 0.093344 0.045600 -vn -0.809972 0.417391 -0.411984 -v 0.071030 0.092863 0.045600 -vn -0.861025 0.336044 -0.381721 -v 0.070796 0.092348 0.045600 -vn -0.894690 0.216447 -0.390743 -v 0.070629 0.091808 0.045600 -vn -0.920938 0.103299 -0.375770 -v 0.070531 0.091252 0.045600 -vn -0.910861 -0.024448 -0.411988 -v 0.070503 0.090687 0.045600 -vn -0.916410 -0.120331 -0.381725 -v 0.070547 0.090124 0.045600 -vn -0.876166 -0.250202 -0.411986 -v 0.070660 0.089570 0.045600 -vn -0.857697 -0.344450 -0.381721 -v 0.070843 0.089035 0.045600 -vn -0.800368 -0.454677 -0.390742 -v 0.071090 0.088527 0.045600 -vn -0.742046 -0.555127 -0.375768 -v 0.071400 0.088054 0.045600 -vn -0.666154 -0.643294 -0.377375 -v 0.071766 0.087624 0.045600 -vn -0.242683 -0.313917 -0.917911 -v 0.072371 0.087477 0.045300 -vn 0.478962 0.462528 -0.746099 -v 0.073025 0.088840 0.045300 -vn 0.302827 0.592985 -0.746099 -v 0.073752 0.088301 0.045300 -vn -0.330798 0.577851 -0.746098 -v 0.076369 0.088363 0.045300 -vn 0.122126 -0.383609 -0.915385 -v 0.076357 0.086774 0.045300 -vn -0.125246 0.653948 -0.746100 -v 0.075520 0.088049 0.045300 -vn 0.025317 -0.402261 -0.915175 -v 0.075325 0.086562 0.045300 -vn 0.093879 0.659185 -0.746098 -v 0.074615 0.088027 0.045300 -vn -0.075514 -0.395914 -0.915177 -v 0.074274 0.086614 0.045300 -vn -0.171602 -0.364697 -0.915177 -v 0.073268 0.086925 0.045300 -vn -0.664685 0.039124 -0.746098 -v 0.077748 0.090588 0.045300 -vn 0.390394 -0.100226 -0.915176 -v 0.079085 0.089762 0.045300 -vn -0.615970 0.252823 -0.746098 -v 0.077547 0.089706 0.045300 -vn 0.353203 -0.194164 -0.915177 -v 0.078711 0.088778 0.045300 -vn -0.500500 0.439129 -0.746100 -v 0.077070 0.088936 0.045300 -vn 0.295037 -0.266167 -0.917664 -v 0.078105 0.087918 0.045300 -vn 0.217300 -0.332068 -0.917884 -v 0.077303 0.087236 0.045300 -vn -0.396300 -0.535054 -0.746099 -v 0.076640 0.092960 0.045300 -vn 0.284169 0.277745 -0.917663 -v 0.078024 0.093668 0.045300 -vn -0.548559 -0.377386 -0.746098 -v 0.077269 0.092309 0.045300 -vn 0.353933 0.191845 -0.915384 -v 0.078655 0.092824 0.045300 -vn -0.641372 -0.178820 -0.746100 -v 0.077652 0.091488 0.045300 -vn 0.390387 0.100246 -0.915177 -v 0.079056 0.091851 0.045300 -vn 0.403055 0.000009 -0.915176 -v 0.079203 0.090809 0.045300 -vn -0.284574 -0.274807 -0.918422 -v 0.071982 0.087832 0.045300 -vn -0.320363 -0.233199 -0.918142 -v 0.071640 0.088234 0.045300 -vn 0.603193 0.281949 -0.746099 -v 0.072512 0.089585 0.045300 -vn -0.375186 -0.145974 -0.915384 -v 0.071120 0.089149 0.045300 -vn 0.662058 0.070816 -0.746099 -v 0.072269 0.090457 0.045300 -vn -0.399871 -0.050526 -0.915178 -v 0.070844 0.090165 0.045300 -vn 0.649180 -0.147992 -0.746099 -v 0.072322 0.091361 0.045300 -vn 0.231175 -0.624415 -0.746100 -v 0.074048 0.093329 0.045300 -vn -0.075535 0.395912 -0.915177 -v 0.074159 0.094864 0.045300 -vn 0.015901 -0.665645 -0.746099 -v 0.074937 0.093499 0.045300 -vn 0.017021 0.396995 -0.917663 -v 0.075208 0.094945 0.045300 -vn -0.201095 -0.634742 -0.746099 -v 0.075834 0.093372 0.045300 -vn 0.117353 0.379104 -0.917882 -v 0.076245 0.094762 0.045300 -vn 0.217729 0.338621 -0.915385 -v 0.077204 0.094327 0.045300 -vn -0.395140 0.041916 -0.917664 -v 0.070829 0.091218 0.045300 -vn -0.373423 0.150422 -0.915384 -v 0.071077 0.092241 0.045300 -vn 0.565953 -0.350762 -0.746099 -v 0.072666 0.092199 0.045300 -vn -0.326080 0.236897 -0.915179 -v 0.071571 0.093171 0.045300 -vn 0.421398 -0.515521 -0.746098 -v 0.073263 0.092879 0.045300 -vn -0.256924 0.310551 -0.915176 -v 0.072281 0.093948 0.045300 -vn -0.171621 0.364691 -0.915176 -v 0.073162 0.094525 0.045300 -vn 0.532794 0.514512 -0.671869 -v 0.073025 0.088840 0.049000 -vn 0.670987 0.313638 -0.671869 -v 0.072512 0.089585 0.049000 -vn 0.736469 0.078775 -0.671869 -v 0.072269 0.090457 0.049000 -vn 0.722144 -0.164625 -0.671869 -v 0.072322 0.091361 0.049000 -vn 0.629562 -0.390185 -0.671869 -v 0.072666 0.092199 0.049000 -vn 0.468759 -0.573461 -0.671869 -v 0.073263 0.092879 0.049000 -vn 0.257158 -0.694596 -0.671868 -v 0.074048 0.093329 0.049000 -vn 0.017688 -0.740459 -0.671869 -v 0.074937 0.093499 0.049000 -vn -0.223697 -0.706083 -0.671868 -v 0.075834 0.093372 0.049000 -vn -0.440841 -0.595190 -0.671869 -v 0.076640 0.092960 0.049000 -vn -0.610212 -0.419801 -0.671869 -v 0.077269 0.092309 0.049000 -vn -0.713460 -0.198919 -0.671868 -v 0.077652 0.091488 0.049000 -vn -0.739390 0.043521 -0.671869 -v 0.077748 0.090588 0.049000 -vn -0.685198 0.281238 -0.671869 -v 0.077547 0.089706 0.049000 -vn -0.556755 0.488486 -0.671867 -v 0.077070 0.088936 0.049000 -vn -0.367976 0.642795 -0.671870 -v 0.076369 0.088363 0.049000 -vn -0.139323 0.727450 -0.671867 -v 0.075520 0.088049 0.049000 -vn 0.104430 0.733271 -0.671869 -v 0.074615 0.088027 0.049000 -vn 0.336863 0.659633 -0.671868 -v 0.073752 0.088301 0.049000 -vn -0.104988 0.635242 -0.765144 -v 0.075207 0.089517 0.049000 -vn 0.202246 0.611267 -0.765147 -v 0.074610 0.089563 0.049000 -vn 0.463152 0.447260 -0.765146 -v 0.074104 0.089882 0.049000 -vn 0.617954 0.180792 -0.765145 -v 0.073803 0.090399 0.049000 -vn -0.556733 -0.323427 -0.765143 -v 0.076084 0.091378 0.049000 -vn -0.643261 -0.027656 -0.765147 -v 0.076252 0.090804 0.049000 -vn -0.582432 0.274454 -0.765146 -v 0.076134 0.090217 0.049000 -vn -0.388170 0.513687 -0.765147 -v 0.075757 0.089753 0.049000 -vn -0.050084 -0.641907 -0.765145 -v 0.075100 0.091996 0.049000 -vn -0.342658 -0.545101 -0.765148 -v 0.075668 0.091808 0.049000 -vn 0.499825 -0.405866 -0.765145 -v 0.074033 0.091538 0.049000 -vn 0.253960 -0.591656 -0.765145 -v 0.074510 0.091899 0.049000 -vn 0.631187 -0.127095 -0.765147 -v 0.073778 0.090997 0.049000 -vn 0.463152 0.447260 0.765146 -v 0.074104 0.089882 0.050500 -vn 0.617954 0.180792 0.765145 -v 0.073803 0.090399 0.050500 -vn 0.631187 -0.127095 0.765147 -v 0.073778 0.090997 0.050500 -vn 0.499825 -0.405866 0.765145 -v 0.074033 0.091538 0.050500 -vn 0.253960 -0.591656 0.765145 -v 0.074510 0.091899 0.050500 -vn -0.050084 -0.641907 0.765145 -v 0.075100 0.091996 0.050500 -vn -0.342658 -0.545101 0.765148 -v 0.075668 0.091808 0.050500 -vn -0.556733 -0.323427 0.765143 -v 0.076084 0.091378 0.050500 -vn -0.643261 -0.027656 0.765147 -v 0.076252 0.090804 0.050500 -vn -0.582432 0.274454 0.765146 -v 0.076134 0.090217 0.050500 -vn -0.388170 0.513687 0.765147 -v 0.075757 0.089753 0.050500 -vn -0.104988 0.635242 0.765144 -v 0.075207 0.089517 0.050500 -vn 0.202246 0.611267 0.765147 -v 0.074610 0.089563 0.050500 -vn 0.817038 0.203719 -0.539396 -v 0.068472 0.084999 0.047630 -vn 0.809435 -0.232094 -0.539396 -v 0.068479 0.085413 0.047630 -vn 0.584940 -0.605721 -0.539395 -v 0.068693 0.085768 0.047630 -vn 0.203711 -0.817039 -0.539397 -v 0.069055 0.085969 0.047630 -vn -0.232100 -0.809433 -0.539396 -v 0.069469 0.085962 0.047630 -vn -0.605724 -0.584936 -0.539397 -v 0.069824 0.085748 0.047630 -vn -0.817039 -0.203716 -0.539395 -v 0.070025 0.085386 0.047630 -vn -0.809434 0.232092 -0.539398 -v 0.070017 0.084972 0.047630 -vn -0.584939 0.605718 -0.539400 -v 0.069804 0.084617 0.047630 -vn -0.203717 0.817038 -0.539396 -v 0.069442 0.084416 0.047630 -vn 0.232099 0.809431 -0.539399 -v 0.069028 0.084424 0.047630 -vn 0.605727 0.584935 -0.539394 -v 0.068673 0.084637 0.047630 -vn -0.605723 -0.584936 0.539397 -v 0.069824 0.085748 0.051870 -vn -0.232100 -0.809433 0.539396 -v 0.069469 0.085962 0.051870 -vn 0.203710 -0.817039 0.539397 -v 0.069055 0.085969 0.051870 -vn 0.584939 -0.605721 0.539396 -v 0.068693 0.085768 0.051870 -vn 0.809435 -0.232093 0.539396 -v 0.068479 0.085413 0.051870 -vn 0.817038 0.203717 0.539395 -v 0.068472 0.084999 0.051870 -vn 0.605726 0.584935 0.539395 -v 0.068673 0.084637 0.051870 -vn 0.232098 0.809432 0.539399 -v 0.069028 0.084424 0.051870 -vn -0.203717 0.817038 0.539396 -v 0.069442 0.084416 0.051870 -vn -0.584937 0.605719 0.539400 -v 0.069804 0.084617 0.051870 -vn -0.809434 0.232091 0.539398 -v 0.070017 0.084972 0.051870 -vn -0.817040 -0.203713 0.539395 -v 0.070025 0.085386 0.051870 -vn 0.817040 0.203712 -0.539396 -v 0.079784 0.084802 0.047630 -vn 0.809432 -0.232091 -0.539401 -v 0.079791 0.085216 0.047630 -vn 0.584941 -0.605714 -0.539403 -v 0.080005 0.085571 0.047630 -vn 0.203709 -0.817039 -0.539398 -v 0.080367 0.085771 0.047630 -vn -0.232097 -0.809430 -0.539402 -v 0.080781 0.085764 0.047630 -vn -0.605718 -0.584943 -0.539395 -v 0.081136 0.085551 0.047630 -vn -0.817041 -0.203716 -0.539393 -v 0.081337 0.085189 0.047630 -vn -0.809435 0.232100 -0.539393 -v 0.081329 0.084775 0.047630 -vn -0.584940 0.605721 -0.539395 -v 0.081116 0.084420 0.047630 -vn -0.203712 0.817040 -0.539396 -v 0.080754 0.084219 0.047630 -vn 0.232100 0.809433 -0.539396 -v 0.080340 0.084226 0.047630 -vn 0.605722 0.584939 -0.539396 -v 0.079985 0.084439 0.047630 -vn -0.605718 -0.584944 0.539394 -v 0.081136 0.085551 0.051870 -vn -0.232101 -0.809429 0.539402 -v 0.080781 0.085764 0.051870 -vn 0.203711 -0.817038 0.539398 -v 0.080367 0.085771 0.051870 -vn 0.584942 -0.605714 0.539402 -v 0.080005 0.085571 0.051870 -vn 0.809431 -0.232094 0.539401 -v 0.079791 0.085216 0.051870 -vn 0.817039 0.203713 0.539397 -v 0.079784 0.084802 0.051870 -vn 0.605722 0.584939 0.539396 -v 0.079985 0.084439 0.051870 -vn 0.232100 0.809433 0.539396 -v 0.080340 0.084226 0.051870 -vn -0.203712 0.817040 0.539396 -v 0.080754 0.084219 0.051870 -vn -0.584939 0.605722 0.539396 -v 0.081116 0.084420 0.051870 -vn -0.809434 0.232101 0.539394 -v 0.081329 0.084775 0.051870 -vn -0.817040 -0.203719 0.539393 -v 0.081337 0.085189 0.051870 -vn 0.817040 0.203712 -0.539396 -v 0.079982 0.096114 0.047630 -vn 0.809430 -0.232106 -0.539397 -v 0.079989 0.096528 0.047630 -vn 0.584935 -0.605723 -0.539399 -v 0.080202 0.096883 0.047630 -vn 0.203709 -0.817039 -0.539398 -v 0.080564 0.097083 0.047630 -vn -0.232097 -0.809430 -0.539402 -v 0.080978 0.097076 0.047630 -vn -0.605714 -0.584943 -0.539400 -v 0.081333 0.096863 0.047630 -vn -0.817036 -0.203715 -0.539399 -v 0.081534 0.096501 0.047630 -vn -0.809430 0.232106 -0.539397 -v 0.081527 0.096087 0.047630 -vn -0.584935 0.605727 -0.539394 -v 0.081313 0.095732 0.047630 -vn -0.203711 0.817039 -0.539397 -v 0.080951 0.095531 0.047630 -vn 0.232096 0.809434 -0.539395 -v 0.080537 0.095538 0.047630 -vn 0.605719 0.584941 -0.539397 -v 0.080182 0.095751 0.047630 -vn -0.605715 -0.584943 0.539399 -v 0.081333 0.096863 0.051870 -vn -0.232100 -0.809429 0.539402 -v 0.080978 0.097076 0.051870 -vn 0.203711 -0.817038 0.539398 -v 0.080564 0.097083 0.051870 -vn 0.584933 -0.605725 0.539399 -v 0.080202 0.096883 0.051870 -vn 0.809430 -0.232104 0.539398 -v 0.079989 0.096528 0.051870 -vn 0.817040 0.203712 0.539396 -v 0.079982 0.096114 0.051870 -vn 0.605718 0.584942 0.539396 -v 0.080182 0.095751 0.051870 -vn 0.232096 0.809435 0.539395 -v 0.080537 0.095538 0.051870 -vn -0.203710 0.817039 0.539397 -v 0.080951 0.095531 0.051870 -vn -0.584935 0.605726 0.539395 -v 0.081313 0.095732 0.051870 -vn -0.809430 0.232106 0.539397 -v 0.081527 0.096087 0.051870 -vn -0.817037 -0.203716 0.539398 -v 0.081534 0.096501 0.051870 -vn 0.817039 0.203711 -0.539397 -v 0.068670 0.096311 0.047630 -vn 0.809431 -0.232108 -0.539395 -v 0.068677 0.096725 0.047630 -vn 0.584936 -0.605726 -0.539394 -v 0.068890 0.097080 0.047630 -vn 0.203711 -0.817039 -0.539397 -v 0.069252 0.097281 0.047630 -vn -0.232100 -0.809433 -0.539396 -v 0.069666 0.097274 0.047630 -vn -0.605716 -0.584941 -0.539400 -v 0.070021 0.097060 0.047630 -vn -0.817038 -0.203712 -0.539399 -v 0.070222 0.096698 0.047630 -vn -0.809430 0.232106 -0.539397 -v 0.070215 0.096284 0.047630 -vn -0.584935 0.605723 -0.539399 -v 0.070001 0.095929 0.047630 -vn -0.203709 0.817039 -0.539398 -v 0.069639 0.095728 0.047630 -vn 0.232094 0.809431 -0.539401 -v 0.069225 0.095736 0.047630 -vn 0.605719 0.584940 -0.539398 -v 0.068870 0.095949 0.047630 -vn -0.605717 -0.584940 0.539400 -v 0.070021 0.097060 0.051870 -vn -0.232099 -0.809433 0.539396 -v 0.069666 0.097274 0.051870 -vn 0.203710 -0.817039 0.539397 -v 0.069252 0.097281 0.051870 -vn 0.584935 -0.605726 0.539395 -v 0.068890 0.097080 0.051870 -vn 0.809431 -0.232107 0.539396 -v 0.068677 0.096725 0.051870 -vn 0.817039 0.203710 0.539397 -v 0.068670 0.096311 0.051870 -vn 0.605718 0.584942 0.539397 -v 0.068870 0.095949 0.051870 -vn 0.232097 0.809431 0.539401 -v 0.069225 0.095736 0.051870 -vn -0.203711 0.817038 0.539398 -v 0.069639 0.095728 0.051870 -vn -0.584933 0.605725 0.539399 -v 0.070001 0.095929 0.051870 -vn -0.809430 0.232105 0.539398 -v 0.070215 0.096284 0.051870 -vn -0.817038 -0.203713 0.539398 -v 0.070222 0.096698 0.051870 -# 3504 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 6//6 16//16 4//4 -f 4//4 16//16 17//17 -f 4//4 17//17 3//3 -f 3//3 17//17 11//11 -f 15//15 13//13 18//18 -f 18//18 13//13 19//19 -f 18//18 19//19 20//20 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 24//24 27//27 26//26 -f 26//26 27//27 28//28 -f 26//26 28//28 29//29 -f 29//29 28//28 30//30 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 39//39 12//12 31//31 -f 31//31 12//12 40//40 -f 31//31 40//40 32//32 -f 30//30 13//13 29//29 -f 29//29 13//13 12//12 -f 29//29 12//12 41//41 -f 41//41 12//12 39//39 -f 42//42 43//43 44//44 -f 44//44 43//43 45//45 -f 44//44 45//45 5//5 -f 5//5 45//45 46//46 -f 5//5 46//46 6//6 -f 10//10 47//47 11//11 -f 11//11 47//47 48//48 -f 11//11 48//48 3//3 -f 3//3 48//48 49//49 -f 3//3 49//49 50//50 -f 50//50 49//49 51//51 -f 50//50 51//51 52//52 -f 52//52 51//51 53//53 -f 52//52 53//53 38//38 -f 38//38 53//53 54//54 -f 38//38 54//54 37//37 -f 37//37 54//54 55//55 -f 37//37 55//55 56//56 -f 56//56 55//55 57//57 -f 56//56 57//57 58//58 -f 20//20 59//59 18//18 -f 18//18 59//59 3//3 -f 18//18 3//3 60//60 -f 60//60 3//3 50//50 -f 59//59 61//61 3//3 -f 3//3 61//61 62//62 -f 3//3 62//62 21//21 -f 21//21 62//62 63//63 -f 21//21 63//63 22//22 -f 7//7 64//64 8//8 -f 8//8 64//64 65//65 -f 8//8 65//65 66//66 -f 66//66 65//65 67//67 -f 66//66 67//67 43//43 -f 43//43 67//67 68//68 -f 43//43 68//68 45//45 -f 57//57 69//69 58//58 -f 58//58 69//69 70//70 -f 58//58 70//70 71//71 -f 71//71 70//70 8//8 -f 71//71 8//8 72//72 -f 72//72 8//8 66//66 -f 73//73 74//74 75//75 -f 76//76 77//77 78//78 -f 78//78 77//77 73//73 -f 79//79 80//80 81//81 -f 82//82 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 86//86 87//87 88//88 -f 89//89 90//90 91//91 -f 78//78 92//92 93//93 -f 78//78 94//94 95//95 -f 96//96 81//81 97//97 -f 97//97 81//81 80//80 -f 97//97 80//80 74//74 -f 74//74 80//80 98//98 -f 74//74 98//98 75//75 -f 99//99 100//100 101//101 -f 102//102 103//103 88//88 -f 78//78 95//95 104//104 -f 95//95 105//105 104//104 -f 104//104 105//105 106//106 -f 104//104 106//106 107//107 -f 107//107 106//106 82//82 -f 107//107 82//82 108//108 -f 108//108 82//82 84//84 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 112//112 86//86 111//111 -f 111//111 86//86 88//88 -f 111//111 88//88 113//113 -f 113//113 88//88 103//103 -f 114//114 115//115 116//116 -f 116//116 115//115 117//117 -f 116//116 117//117 118//118 -f 118//118 117//117 119//119 -f 118//118 119//119 120//120 -f 73//73 75//75 78//78 -f 78//78 75//75 121//121 -f 78//78 121//121 92//92 -f 94//94 78//78 122//122 -f 122//122 78//78 93//93 -f 122//122 93//93 123//123 -f 123//123 93//93 124//124 -f 123//123 124//124 125//125 -f 91//91 99//99 89//89 -f 89//89 99//99 101//101 -f 89//89 101//101 126//126 -f 126//126 101//101 102//102 -f 126//126 102//102 124//124 -f 124//124 102//102 88//88 -f 124//124 88//88 125//125 -f 79//79 81//81 127//127 -f 127//127 81//81 128//128 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 89//89 -f 89//89 130//130 131//131 -f 89//89 131//131 90//90 -f 119//119 132//132 120//120 -f 120//120 132//132 133//133 -f 120//120 133//133 134//134 -f 134//134 133//133 130//130 -f 134//134 130//130 135//135 -f 135//135 130//130 128//128 -f 111//111 136//136 109//109 -f 109//109 136//136 137//137 -f 109//109 137//137 138//138 -f 138//138 137//137 139//139 -f 138//138 139//139 114//114 -f 114//114 139//139 140//140 -f 114//114 140//140 115//115 -f 115//115 140//140 141//141 -f 115//115 141//141 142//142 -f 142//142 141//141 143//143 -f 142//142 143//143 100//100 -f 100//100 143//143 144//144 -f 100//100 144//144 101//101 -f 114//114 116//116 37//37 -f 37//37 116//116 35//35 -f 26//26 29//29 81//81 -f 81//81 29//29 128//128 -f 74//74 73//73 21//21 -f 21//21 73//73 3//3 -f 1//1 3//3 77//77 -f 77//77 3//3 73//73 -f 2//2 1//1 76//76 -f 76//76 1//1 77//77 -f 4//4 2//2 78//78 -f 78//78 2//2 76//76 -f 5//5 4//4 104//104 -f 104//104 4//4 78//78 -f 84//84 86//86 43//43 -f 43//43 86//86 66//66 -f 57//57 139//139 69//69 -f 69//69 139//139 137//137 -f 69//69 137//137 70//70 -f 70//70 137//137 136//136 -f 70//70 136//136 8//8 -f 8//8 136//136 111//111 -f 8//8 111//111 10//10 -f 10//10 111//111 113//113 -f 10//10 113//113 47//47 -f 47//47 113//113 103//103 -f 47//47 103//103 48//48 -f 48//48 103//103 102//102 -f 48//48 102//102 49//49 -f 49//49 102//102 101//101 -f 49//49 101//101 51//51 -f 51//51 101//101 144//144 -f 51//51 144//144 53//53 -f 53//53 144//144 143//143 -f 53//53 143//143 54//54 -f 54//54 143//143 141//141 -f 54//54 141//141 55//55 -f 55//55 141//141 140//140 -f 55//55 140//140 57//57 -f 57//57 140//140 139//139 -f 64//64 88//88 65//65 -f 65//65 88//88 87//87 -f 65//65 87//87 67//67 -f 67//67 87//87 85//85 -f 67//67 85//85 68//68 -f 68//68 85//85 83//83 -f 68//68 83//83 45//45 -f 45//45 83//83 82//82 -f 45//45 82//82 46//46 -f 46//46 82//82 106//106 -f 46//46 106//106 6//6 -f 6//6 106//106 105//105 -f 6//6 105//105 16//16 -f 16//16 105//105 95//95 -f 16//16 95//95 17//17 -f 17//17 95//95 94//94 -f 17//17 94//94 11//11 -f 11//11 94//94 122//122 -f 11//11 122//122 9//9 -f 9//9 122//122 123//123 -f 9//9 123//123 7//7 -f 7//7 123//123 125//125 -f 7//7 125//125 64//64 -f 64//64 125//125 88//88 -f 13//13 89//89 19//19 -f 19//19 89//89 126//126 -f 19//19 126//126 20//20 -f 20//20 126//126 124//124 -f 20//20 124//124 59//59 -f 59//59 124//124 93//93 -f 59//59 93//93 61//61 -f 61//61 93//93 92//92 -f 61//61 92//92 62//62 -f 62//62 92//92 121//121 -f 62//62 121//121 63//63 -f 63//63 121//121 75//75 -f 63//63 75//75 22//22 -f 22//22 75//75 98//98 -f 22//22 98//98 24//24 -f 24//24 98//98 80//80 -f 24//24 80//80 27//27 -f 27//27 80//80 79//79 -f 27//27 79//79 28//28 -f 28//28 79//79 127//127 -f 28//28 127//127 30//30 -f 30//30 127//127 129//129 -f 30//30 129//129 13//13 -f 13//13 129//129 89//89 -f 34//34 119//119 36//36 -f 36//36 119//119 117//117 -f 36//36 117//117 38//38 -f 38//38 117//117 115//115 -f 38//38 115//115 52//52 -f 52//52 115//115 142//142 -f 52//52 142//142 50//50 -f 50//50 142//142 100//100 -f 50//50 100//100 60//60 -f 60//60 100//100 99//99 -f 60//60 99//99 18//18 -f 18//18 99//99 91//91 -f 18//18 91//91 15//15 -f 15//15 91//91 90//90 -f 15//15 90//90 14//14 -f 14//14 90//90 131//131 -f 14//14 131//131 12//12 -f 12//12 131//131 130//130 -f 12//12 130//130 40//40 -f 40//40 130//130 133//133 -f 40//40 133//133 32//32 -f 32//32 133//133 132//132 -f 32//32 132//132 34//34 -f 34//34 132//132 119//119 -f 66//66 86//86 112//112 -f 66//66 112//112 72//72 -f 72//72 112//112 110//110 -f 72//72 110//110 71//71 -f 71//71 110//110 109//109 -f 71//71 109//109 58//58 -f 58//58 109//109 138//138 -f 58//58 138//138 56//56 -f 56//56 138//138 114//114 -f 56//56 114//114 37//37 -f 35//35 116//116 118//118 -f 35//35 118//118 33//33 -f 33//33 118//118 120//120 -f 33//33 120//120 31//31 -f 31//31 120//120 134//134 -f 31//31 134//134 39//39 -f 39//39 134//134 135//135 -f 39//39 135//135 41//41 -f 41//41 135//135 128//128 -f 41//41 128//128 29//29 -f 5//5 104//104 107//107 -f 5//5 107//107 44//44 -f 44//44 107//107 108//108 -f 44//44 108//108 42//42 -f 42//42 108//108 84//84 -f 42//42 84//84 43//43 -f 26//26 81//81 96//96 -f 26//26 96//96 25//25 -f 25//25 96//96 97//97 -f 25//25 97//97 23//23 -f 23//23 97//97 74//74 -f 23//23 74//74 21//21 -f 145//145 146//146 147//147 -f 148//148 149//149 150//150 -f 151//151 152//152 153//153 -f 154//154 155//155 156//156 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 155//155 165//165 156//156 -f 156//156 165//165 166//166 -f 156//156 166//166 157//157 -f 157//157 166//166 167//167 -f 157//157 167//167 158//158 -f 156//156 168//168 154//154 -f 154//154 168//168 169//169 -f 154//154 169//169 170//170 -f 170//170 169//169 171//171 -f 170//170 171//171 172//172 -f 172//172 171//171 173//173 -f 172//172 173//173 164//164 -f 164//164 173//173 174//174 -f 164//164 174//174 163//163 -f 156//156 175//175 168//168 -f 168//168 175//175 176//176 -f 168//168 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 180//180 -f 180//180 184//184 185//185 -f 180//180 185//185 186//186 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 187//187 189//189 186//186 -f 186//186 189//189 198//198 -f 186//186 198//198 180//180 -f 180//180 198//198 199//199 -f 180//180 199//199 179//179 -f 200//200 190//190 201//201 -f 201//201 190//190 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 188//188 191//191 190//190 -f 190//190 191//191 193//193 -f 190//190 193//193 202//202 -f 202//202 193//193 206//206 -f 202//202 206//206 204//204 -f 204//204 206//206 207//207 -f 208//208 209//209 145//145 -f 145//145 209//209 210//210 -f 211//211 207//207 212//212 -f 212//212 207//207 213//213 -f 212//212 213//213 214//214 -f 214//214 213//213 215//215 -f 216//216 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 219//219 221//221 220//220 -f 220//220 221//221 222//222 -f 220//220 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 230//230 -f 230//230 229//229 231//231 -f 226//226 232//232 227//227 -f 227//227 232//232 233//233 -f 227//227 233//233 217//217 -f 234//234 153//153 235//235 -f 235//235 153//153 236//236 -f 235//235 236//236 237//237 -f 233//233 238//238 217//217 -f 217//217 238//238 239//239 -f 217//217 239//239 219//219 -f 219//219 239//239 240//240 -f 219//219 240//240 241//241 -f 241//241 240//240 237//237 -f 241//241 237//237 242//242 -f 242//242 237//237 236//236 -f 151//151 153//153 243//243 -f 243//243 153//153 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 249//249 -f 249//249 248//248 150//150 -f 150//150 248//248 250//250 -f 150//150 250//250 148//148 -f 251//251 252//252 248//248 -f 248//248 252//252 253//253 -f 248//248 253//253 254//254 -f 255//255 250//250 256//256 -f 256//256 250//250 248//248 -f 256//256 248//248 257//257 -f 257//257 248//248 254//254 -f 258//258 259//259 251//251 -f 251//251 259//259 260//260 -f 251//251 260//260 252//252 -f 257//257 261//261 256//256 -f 256//256 261//261 262//262 -f 256//256 262//262 263//263 -f 263//263 262//262 264//264 -f 264//264 265//265 263//263 -f 263//263 265//265 266//266 -f 263//263 266//266 258//258 -f 258//258 266//266 267//267 -f 258//258 267//267 259//259 -f 268//268 269//269 270//270 -f 270//270 271//271 268//268 -f 268//268 271//271 272//272 -f 268//268 272//272 246//246 -f 246//246 272//272 273//273 -f 246//246 273//273 274//274 -f 274//274 275//275 246//246 -f 246//246 275//275 276//276 -f 246//246 276//276 248//248 -f 248//248 276//276 277//277 -f 248//248 277//277 251//251 -f 275//275 278//278 276//276 -f 276//276 278//278 279//279 -f 276//276 279//279 280//280 -f 280//280 279//279 281//281 -f 281//281 282//282 280//280 -f 280//280 282//282 283//283 -f 280//280 283//283 269//269 -f 269//269 283//283 284//284 -f 269//269 284//284 270//270 -f 285//285 286//286 287//287 -f 288//288 289//289 290//290 -f 290//290 289//289 291//291 -f 290//290 291//291 292//292 -f 292//292 291//291 293//293 -f 234//234 231//231 153//153 -f 153//153 231//231 229//229 -f 153//153 229//229 244//244 -f 244//244 229//229 294//294 -f 244//244 294//294 285//285 -f 287//287 295//295 285//285 -f 285//285 295//295 296//296 -f 285//285 296//296 244//244 -f 244//244 296//296 297//297 -f 244//244 297//297 298//298 -f 298//298 293//293 244//244 -f 244//244 293//293 291//291 -f 244//244 291//291 246//246 -f 246//246 291//291 299//299 -f 246//246 299//299 268//268 -f 288//288 300//300 289//289 -f 289//289 300//300 301//301 -f 289//289 301//301 286//286 -f 286//286 301//301 302//302 -f 286//286 302//302 287//287 -f 211//211 303//303 207//207 -f 207//207 303//303 304//304 -f 207//207 304//304 204//204 -f 204//204 304//304 305//305 -f 204//204 305//305 306//306 -f 306//306 305//305 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 309//309 -f 308//308 309//309 310//310 -f 310//310 309//309 208//208 -f 310//310 208//208 224//224 -f 224//224 208//208 145//145 -f 224//224 145//145 225//225 -f 225//225 145//145 147//147 -f 311//311 146//146 213//213 -f 213//213 146//146 145//145 -f 213//213 145//145 215//215 -f 215//215 145//145 210//210 -f 312//312 313//313 183//183 -f 183//183 313//313 195//195 -f 183//183 195//195 181//181 -f 181//181 195//195 197//197 -f 314//314 175//175 315//315 -f 315//315 175//175 156//156 -f 315//315 156//156 316//316 -f 316//316 156//156 157//157 -f 317//317 318//318 319//319 -f 320//320 321//321 322//322 -f 323//323 324//324 325//325 -f 325//325 324//324 322//322 -f 326//326 327//327 328//328 -f 328//328 327//327 323//323 -f 328//328 323//323 329//329 -f 329//329 323//323 325//325 -f 160//160 161//161 159//159 -f 159//159 161//161 163//163 -f 159//159 163//163 330//330 -f 330//330 163//163 319//319 -f 330//330 319//319 331//331 -f 331//331 319//319 318//318 -f 331//331 318//318 320//320 -f 320//320 318//318 332//332 -f 320//320 332//332 321//321 -f 326//326 333//333 327//327 -f 327//327 333//333 334//334 -f 327//327 334//334 319//319 -f 319//319 334//334 335//335 -f 319//319 335//335 317//317 -f 322//322 324//324 320//320 -f 320//320 324//324 336//336 -f 320//320 336//336 337//337 -f 338//338 339//339 327//327 -f 340//340 341//341 342//342 -f 342//342 341//341 343//343 -f 344//344 345//345 346//346 -f 346//346 345//345 343//343 -f 340//340 342//342 339//339 -f 339//339 342//342 347//347 -f 339//339 347//347 327//327 -f 327//327 347//347 348//348 -f 327//327 348//348 323//323 -f 346//346 349//349 344//344 -f 344//344 349//349 350//350 -f 344//344 350//350 351//351 -f 351//351 350//350 352//352 -f 352//352 353//353 351//351 -f 351//351 353//353 354//354 -f 351//351 354//354 327//327 -f 327//327 354//354 355//355 -f 327//327 355//355 338//338 -f 343//343 345//345 342//342 -f 342//342 345//345 356//356 -f 342//342 356//356 357//357 -f 358//358 359//359 351//351 -f 360//360 361//361 362//362 -f 363//363 364//364 365//365 -f 365//365 364//364 360//360 -f 365//365 360//360 351//351 -f 366//366 367//367 360//360 -f 360//360 367//367 368//368 -f 360//360 368//368 369//369 -f 370//370 371//371 372//372 -f 372//372 371//371 373//373 -f 360//360 362//362 366//366 -f 366//366 362//362 374//374 -f 366//366 374//374 373//373 -f 369//369 375//375 360//360 -f 360//360 375//375 376//376 -f 360//360 376//376 351//351 -f 351//351 376//376 377//377 -f 351//351 377//377 358//358 -f 370//370 372//372 359//359 -f 359//359 372//372 378//378 -f 359//359 378//378 351//351 -f 351//351 378//378 379//379 -f 351//351 379//379 344//344 -f 373//373 374//374 372//372 -f 372//372 374//374 380//380 -f 372//372 380//380 381//381 -f 163//163 382//382 383//383 -f 384//384 385//385 386//386 -f 386//386 385//385 365//365 -f 386//386 365//365 387//387 -f 387//387 365//365 351//351 -f 387//387 351//351 388//388 -f 388//388 351//351 327//327 -f 388//388 327//327 383//383 -f 383//383 327//327 319//319 -f 383//383 319//319 163//163 -f 389//389 390//390 200//200 -f 389//389 200//200 391//391 -f 391//391 200//200 201//201 -f 391//391 201//201 203//203 -f 392//392 393//393 394//394 -f 395//395 396//396 397//397 -f 396//396 398//398 397//397 -f 397//397 398//398 399//399 -f 397//397 399//399 400//400 -f 401//401 402//402 397//397 -f 397//397 402//402 392//392 -f 392//392 394//394 397//397 -f 397//397 394//394 403//403 -f 397//397 403//403 395//395 -f 404//404 405//405 406//406 -f 406//406 405//405 400//400 -f 406//406 400//400 407//407 -f 407//407 400//400 399//399 -f 37//37 35//35 408//408 -f 408//408 35//35 409//409 -f 410//410 37//37 411//411 -f 411//411 37//37 408//408 -f 411//411 408//408 412//412 -f 412//412 408//408 413//413 -f 386//386 387//387 414//414 -f 386//386 414//414 415//415 -f 416//416 417//417 418//418 -f 419//419 420//420 421//421 -f 421//421 420//420 422//422 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 423//423 424//424 425//425 -f 425//425 424//424 426//426 -f 425//425 426//426 427//427 -f 427//427 426//426 428//428 -f 429//429 430//430 431//431 -f 431//431 430//430 432//432 -f 431//431 432//432 433//433 -f 433//433 432//432 434//434 -f 433//433 434//434 435//435 -f 435//435 434//434 436//436 -f 436//436 437//437 435//435 -f 435//435 437//437 438//438 -f 435//435 438//438 439//439 -f 439//439 438//438 440//440 -f 437//437 441//441 438//438 -f 438//438 441//441 442//442 -f 438//438 442//442 419//419 -f 419//419 442//442 443//443 -f 419//419 443//443 420//420 -f 431//431 444//444 429//429 -f 429//429 444//444 445//445 -f 429//429 445//445 417//417 -f 417//417 445//445 446//446 -f 417//417 446//446 418//418 -f 447//447 448//448 449//449 -f 449//449 448//448 450//450 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 418//418 -f 418//418 452//452 453//453 -f 418//418 453//453 416//416 -f 454//454 455//455 426//426 -f 426//426 455//455 456//456 -f 426//426 456//456 428//428 -f 454//454 457//457 455//455 -f 455//455 457//457 458//458 -f 455//455 458//458 414//414 -f 414//414 458//458 459//459 -f 414//414 459//459 460//460 -f 460//460 461//461 414//414 -f 414//414 461//461 447//447 -f 414//414 447//447 415//415 -f 415//415 447//447 449//449 -f 35//35 33//33 409//409 -f 409//409 33//33 462//462 -f 462//462 33//33 463//463 -f 463//463 33//33 31//31 -f 463//463 31//31 464//464 -f 464//464 31//31 465//465 -f 465//465 31//31 39//39 -f 465//465 39//39 466//466 -f 466//466 39//39 467//467 -f 467//467 39//39 41//41 -f 467//467 41//41 468//468 -f 469//469 470//470 471//471 -f 468//468 41//41 471//471 -f 471//471 41//41 29//29 -f 471//471 29//29 469//469 -f 472//472 473//473 474//474 -f 475//475 476//476 477//477 -f 472//472 474//474 478//478 -f 474//474 479//479 478//478 -f 478//478 479//479 480//480 -f 478//478 480//480 481//481 -f 475//475 477//477 482//482 -f 477//477 483//483 482//482 -f 482//482 483//483 484//484 -f 482//482 484//484 472//472 -f 472//472 484//484 485//485 -f 472//472 485//485 473//473 -f 480//480 486//486 481//481 -f 481//481 486//486 487//487 -f 481//481 487//487 475//475 -f 475//475 487//487 488//488 -f 475//475 488//488 476//476 -f 489//489 490//490 491//491 -f 491//491 490//490 492//492 -f 493//493 494//494 495//495 -f 495//495 494//494 496//496 -f 496//496 497//497 495//495 -f 495//495 497//497 498//498 -f 495//495 498//498 499//499 -f 498//498 500//500 499//499 -f 499//499 500//500 501//501 -f 499//499 501//501 489//489 -f 489//489 501//501 502//502 -f 489//489 502//502 490//490 -f 492//492 503//503 491//491 -f 491//491 503//503 504//504 -f 491//491 504//504 493//493 -f 493//493 504//504 505//505 -f 493//493 505//505 494//494 -f 506//506 507//507 508//508 -f 508//508 507//507 509//509 -f 510//510 511//511 506//506 -f 506//506 511//511 512//512 -f 506//506 512//512 507//507 -f 509//509 513//513 508//508 -f 508//508 513//513 514//514 -f 508//508 514//514 515//515 -f 516//516 517//517 518//518 -f 518//518 517//517 515//515 -f 518//518 515//515 519//519 -f 519//519 515//515 514//514 -f 516//516 520//520 517//517 -f 517//517 520//520 521//521 -f 517//517 521//521 510//510 -f 510//510 521//521 522//522 -f 510//510 522//522 511//511 -f 523//523 524//524 525//525 -f 525//525 524//524 526//526 -f 527//527 528//528 529//529 -f 32//32 40//40 31//31 -f 530//530 531//531 532//532 -f 532//532 531//531 533//533 -f 31//31 40//40 39//39 -f 39//39 40//40 12//12 -f 39//39 12//12 41//41 -f 534//534 535//535 536//536 -f 536//536 535//535 537//537 -f 538//538 539//539 540//540 -f 540//540 539//539 541//541 -f 540//540 541//541 542//542 -f 543//543 544//544 545//545 -f 546//546 547//547 548//548 -f 548//548 547//547 549//549 -f 550//550 551//551 552//552 -f 553//553 64//64 8//8 -f 554//554 555//555 556//556 -f 556//556 555//555 557//557 -f 58//58 71//71 8//8 -f 558//558 559//559 560//560 -f 560//560 559//559 561//561 -f 45//45 562//562 563//563 -f 564//564 565//565 566//566 -f 566//566 565//565 567//567 -f 568//568 569//569 570//570 -f 570//570 569//569 571//571 -f 71//71 72//72 8//8 -f 8//8 72//72 66//66 -f 8//8 66//66 553//553 -f 537//537 550//550 64//64 -f 572//572 573//573 574//574 -f 574//574 573//573 575//575 -f 61//61 545//545 62//62 -f 62//62 545//545 63//63 -f 576//576 532//532 553//553 -f 553//553 532//532 533//533 -f 553//553 533//533 64//64 -f 64//64 533//533 548//548 -f 64//64 548//548 537//537 -f 537//537 548//548 549//549 -f 537//537 549//549 536//536 -f 577//577 578//578 579//579 -f 579//579 578//578 562//562 -f 579//579 562//562 561//561 -f 561//561 562//562 45//45 -f 561//561 45//45 68//68 -f 580//580 581//581 563//563 -f 563//563 581//581 543//543 -f 563//563 543//543 45//45 -f 45//45 543//543 545//545 -f 45//45 545//545 46//46 -f 582//582 583//583 584//584 -f 584//584 583//583 585//585 -f 14//14 7//7 9//9 -f 552//552 542//542 550//550 -f 550//550 542//542 541//541 -f 550//550 541//541 64//64 -f 64//64 541//541 560//560 -f 64//64 560//560 65//65 -f 65//65 560//560 561//561 -f 65//65 561//561 67//67 -f 67//67 561//561 68//68 -f 20//20 9//9 59//59 -f 59//59 9//9 11//11 -f 59//59 11//11 61//61 -f 12//12 14//14 13//13 -f 13//13 14//14 9//9 -f 13//13 9//9 19//19 -f 19//19 9//9 20//20 -f 7//7 14//14 64//64 -f 64//64 14//14 15//15 -f 64//64 15//15 18//18 -f 586//586 587//587 588//588 -f 588//588 587//587 589//589 -f 588//588 589//589 590//590 -f 11//11 17//17 61//61 -f 61//61 17//17 16//16 -f 61//61 16//16 545//545 -f 545//545 16//16 6//6 -f 545//545 6//6 46//46 -f 48//48 47//47 64//64 -f 64//64 47//47 10//10 -f 64//64 10//10 8//8 -f 54//54 35//35 55//55 -f 55//55 35//35 37//37 -f 55//55 37//37 57//57 -f 57//57 37//37 56//56 -f 57//57 56//56 69//69 -f 69//69 56//56 58//58 -f 69//69 58//58 70//70 -f 70//70 58//58 8//8 -f 529//529 591//591 527//527 -f 527//527 591//591 592//592 -f 527//527 592//592 593//593 -f 594//594 595//595 63//63 -f 49//49 48//48 50//50 -f 50//50 48//48 64//64 -f 50//50 64//64 60//60 -f 60//60 64//64 18//18 -f 32//32 31//31 34//34 -f 34//34 31//31 33//33 -f 34//34 33//33 36//36 -f 36//36 33//33 35//35 -f 36//36 35//35 38//38 -f 38//38 35//35 54//54 -f 38//38 54//54 52//52 -f 52//52 54//54 53//53 -f 52//52 53//53 50//50 -f 50//50 53//53 51//51 -f 50//50 51//51 49//49 -f 596//596 597//597 598//598 -f 598//598 597//597 599//599 -f 598//598 599//599 600//600 -f 601//601 602//602 600//600 -f 600//600 602//602 594//594 -f 600//600 594//594 598//598 -f 598//598 594//594 63//63 -f 598//598 63//63 526//526 -f 526//526 63//63 545//545 -f 526//526 545//545 525//525 -f 525//525 545//545 603//603 -f 585//585 28//28 584//584 -f 584//584 28//28 27//27 -f 584//584 27//27 24//24 -f 556//556 13//13 585//585 -f 585//585 13//13 30//30 -f 585//585 30//30 28//28 -f 604//604 605//605 595//595 -f 595//595 605//605 606//606 -f 595//595 606//606 63//63 -f 63//63 606//606 607//607 -f 608//608 584//584 609//609 -f 609//609 584//584 24//24 -f 609//609 24//24 607//607 -f 607//607 24//24 22//22 -f 607//607 22//22 63//63 -f 557//557 566//566 556//556 -f 556//556 566//566 567//567 -f 556//556 567//567 13//13 -f 13//13 567//567 570//570 -f 610//610 527//527 13//13 -f 13//13 527//527 593//593 -f 13//13 593//593 12//12 -f 12//12 593//593 29//29 -f 12//12 29//29 41//41 -f 571//571 574//574 570//570 -f 570//570 574//574 575//575 -f 570//570 575//575 13//13 -f 13//13 575//575 588//588 -f 13//13 588//588 610//610 -f 610//610 588//588 590//590 -f 610//610 590//590 611//611 -f 611//611 590//590 612//612 -f 613//613 614//614 615//615 -f 615//615 614//614 616//616 -f 615//615 616//616 617//617 -f 617//617 616//616 618//618 -f 617//617 618//618 619//619 -f 620//620 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 624//624 623//623 625//625 -f 624//624 625//625 626//626 -f 627//627 628//628 629//629 -f 629//629 628//628 630//630 -f 629//629 630//630 631//631 -f 631//631 630//630 632//632 -f 631//631 632//632 633//633 -f 634//634 635//635 478//478 -f 478//478 635//635 636//636 -f 478//478 636//636 472//472 -f 472//472 636//636 637//637 -f 472//472 637//637 638//638 -f 638//638 637//637 639//639 -f 640//640 641//641 499//499 -f 499//499 641//641 642//642 -f 499//499 642//642 495//495 -f 495//495 642//642 643//643 -f 495//495 643//643 644//644 -f 644//644 643//643 645//645 -f 646//646 647//647 515//515 -f 515//515 647//647 648//648 -f 515//515 648//648 508//508 -f 508//508 648//648 649//649 -f 508//508 649//649 650//650 -f 650//650 649//649 651//651 -f 652//652 653//653 654//654 -f 654//654 653//653 655//655 -f 656//656 657//657 658//658 -f 659//659 660//660 661//661 -f 661//661 660//660 656//656 -f 661//661 656//656 662//662 -f 662//662 656//656 658//658 -f 659//659 663//663 660//660 -f 660//660 663//663 664//664 -f 660//660 664//664 652//652 -f 652//652 664//664 665//665 -f 652//652 665//665 653//653 -f 655//655 666//666 654//654 -f 654//654 666//666 667//667 -f 654//654 667//667 657//657 -f 657//657 667//667 668//668 -f 657//657 668//668 658//658 -f 669//669 670//670 671//671 -f 671//671 670//670 672//672 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 677//677 -f 677//677 676//676 678//678 -f 677//677 678//678 679//679 -f 671//671 680//680 669//669 -f 669//669 680//680 681//681 -f 669//669 681//681 678//678 -f 678//678 681//681 682//682 -f 678//678 682//682 679//679 -f 673//673 683//683 674//674 -f 674//674 683//683 684//684 -f 674//674 684//684 670//670 -f 670//670 684//684 685//685 -f 670//670 685//685 672//672 -f 686//686 687//687 688//688 -f 688//688 687//687 689//689 -f 688//688 689//689 690//690 -f 690//690 689//689 691//691 -f 690//690 691//691 692//692 -f 693//693 694//694 657//657 -f 657//657 694//694 695//695 -f 657//657 695//695 654//654 -f 654//654 695//695 696//696 -f 654//654 696//696 697//697 -f 697//697 696//696 698//698 -f 699//699 700//700 701//701 -f 702//702 703//703 704//704 -f 699//699 701//701 704//704 -f 704//704 701//701 705//705 -f 704//704 705//705 702//702 -f 706//706 707//707 669//669 -f 669//669 707//707 708//708 -f 669//669 708//708 670//670 -f 670//670 708//708 709//709 -f 670//670 709//709 710//710 -f 710//710 709//709 711//711 -f 712//712 553//553 713//713 -f 713//713 553//553 66//66 -f 469//469 29//29 714//714 -f 714//714 29//29 593//593 -f 593//593 592//592 714//714 -f 714//714 592//592 715//715 -f 714//714 715//715 716//716 -f 716//716 715//715 361//361 -f 716//716 361//361 717//717 -f 717//717 361//361 360//360 -f 715//715 592//592 718//718 -f 718//718 592//592 591//591 -f 374//374 362//362 718//718 -f 718//718 591//591 529//529 -f 374//374 718//718 380//380 -f 380//380 718//718 637//637 -f 637//637 718//718 529//529 -f 637//637 529//529 639//639 -f 612//612 590//590 719//719 -f 719//719 378//378 372//372 -f 612//612 719//719 635//635 -f 635//635 719//719 636//636 -f 636//636 719//719 372//372 -f 636//636 372//372 381//381 -f 719//719 590//590 720//720 -f 720//720 590//590 589//589 -f 345//345 344//344 720//720 -f 720//720 589//589 587//587 -f 345//345 720//720 356//356 -f 356//356 720//720 643//643 -f 643//643 720//720 587//587 -f 643//643 587//587 645//645 -f 572//572 574//574 721//721 -f 721//721 347//347 342//342 -f 572//572 721//721 641//641 -f 641//641 721//721 642//642 -f 642//642 721//721 342//342 -f 642//642 342//342 357//357 -f 721//721 574//574 722//722 -f 722//722 574//574 571//571 -f 324//324 323//323 722//722 -f 722//722 571//571 569//569 -f 324//324 722//722 336//336 -f 336//336 722//722 649//649 -f 649//649 722//722 569//569 -f 649//649 569//569 651//651 -f 564//564 566//566 723//723 -f 723//723 331//331 320//320 -f 564//564 723//723 647//647 -f 647//647 723//723 648//648 -f 648//648 723//723 320//320 -f 648//648 320//320 337//337 -f 723//723 566//566 724//724 -f 724//724 566//566 557//557 -f 157//157 159//159 724//724 -f 724//724 557//557 555//555 -f 157//157 724//724 316//316 -f 316//316 724//724 696//696 -f 696//696 724//724 555//555 -f 696//696 555//555 698//698 -f 582//582 584//584 725//725 -f 725//725 176//176 175//175 -f 582//582 725//725 694//694 -f 694//694 725//725 695//695 -f 695//695 725//725 175//175 -f 695//695 175//175 314//314 -f 725//725 584//584 726//726 -f 726//726 584//584 608//608 -f 726//726 608//608 178//178 -f 178//178 608//608 609//609 -f 178//178 609//609 727//727 -f 727//727 609//609 607//607 -f 727//727 607//607 728//728 -f 728//728 607//607 606//606 -f 183//183 180//180 728//728 -f 728//728 606//606 605//605 -f 183//183 728//728 312//312 -f 312//312 728//728 709//709 -f 709//709 728//728 605//605 -f 709//709 605//605 711//711 -f 601//601 600//600 729//729 -f 729//729 193//193 195//195 -f 601//601 729//729 707//707 -f 707//707 729//729 708//708 -f 708//708 729//729 195//195 -f 708//708 195//195 313//313 -f 729//729 600//600 730//730 -f 730//730 600//600 599//599 -f 213//213 207//207 730//730 -f 730//730 599//599 597//597 -f 213//213 730//730 311//311 -f 311//311 730//730 731//731 -f 731//731 730//730 597//597 -f 731//731 597//597 732//732 -f 733//733 734//734 735//735 -f 735//735 734//734 736//736 -f 735//735 736//736 737//737 -f 737//737 736//736 731//731 -f 737//737 731//731 738//738 -f 738//738 731//731 732//732 -f 523//523 525//525 739//739 -f 739//739 223//223 225//225 -f 523//523 739//739 734//734 -f 734//734 739//739 736//736 -f 736//736 739//739 225//225 -f 736//736 225//225 147//147 -f 739//739 525//525 740//740 -f 740//740 525//525 603//603 -f 740//740 603//603 220//220 -f 220//220 603//603 545//545 -f 220//220 545//545 741//741 -f 741//741 545//545 544//544 -f 741//741 544//544 742//742 -f 742//742 544//544 543//543 -f 581//581 743//743 744//744 -f 543//543 581//581 742//742 -f 742//742 581//581 744//744 -f 742//742 744//744 218//218 -f 218//218 744//744 216//216 -f 745//745 746//746 747//747 -f 747//747 746//746 748//748 -f 747//747 748//748 749//749 -f 749//749 748//748 744//744 -f 749//749 744//744 750//750 -f 750//750 744//744 743//743 -f 229//229 227//227 751//751 -f 751//751 227//227 748//748 -f 748//748 746//746 751//751 -f 751//751 746//746 577//577 -f 751//751 577//577 579//579 -f 751//751 579//579 752//752 -f 752//752 579//579 561//561 -f 559//559 753//753 754//754 -f 561//561 559//559 752//752 -f 752//752 559//559 754//754 -f 752//752 754//754 285//285 -f 285//285 754//754 286//286 -f 755//755 756//756 757//757 -f 757//757 756//756 758//758 -f 757//757 758//758 759//759 -f 759//759 758//758 754//754 -f 759//759 754//754 760//760 -f 760//760 754//754 753//753 -f 291//291 289//289 761//761 -f 761//761 289//289 758//758 -f 758//758 756//756 761//761 -f 761//761 756//756 538//538 -f 761//761 538//538 540//540 -f 761//761 540//540 762//762 -f 762//762 540//540 542//542 -f 552//552 763//763 764//764 -f 542//542 552//552 762//762 -f 762//762 552//552 764//764 -f 762//762 764//764 268//268 -f 268//268 764//764 269//269 -f 765//765 766//766 767//767 -f 767//767 766//766 768//768 -f 767//767 768//768 769//769 -f 769//769 768//768 764//764 -f 769//769 764//764 770//770 -f 770//770 764//764 763//763 -f 276//276 280//280 771//771 -f 771//771 280//280 768//768 -f 768//768 766//766 771//771 -f 771//771 766//766 534//534 -f 771//771 534//534 536//536 -f 771//771 536//536 772//772 -f 772//772 536//536 549//549 -f 547//547 773//773 774//774 -f 549//549 547//547 772//772 -f 772//772 547//547 774//774 -f 772//772 774//774 251//251 -f 251//251 774//774 258//258 -f 775//775 776//776 777//777 -f 777//777 776//776 778//778 -f 777//777 778//778 779//779 -f 779//779 778//778 774//774 -f 779//779 774//774 780//780 -f 780//780 774//774 773//773 -f 256//256 263//263 781//781 -f 781//781 263//263 778//778 -f 778//778 776//776 781//781 -f 781//781 776//776 530//530 -f 781//781 530//530 532//532 -f 781//781 532//532 782//782 -f 782//782 532//532 576//576 -f 783//783 250//250 255//255 -f 576//576 553//553 782//782 -f 782//782 553//553 712//712 -f 782//782 712//712 255//255 -f 255//255 712//712 784//784 -f 255//255 784//784 783//783 -f 249//249 785//785 786//786 -f 151//151 243//243 787//787 -f 787//787 243//243 245//245 -f 787//787 245//245 788//788 -f 788//788 245//245 247//247 -f 788//788 247//247 440//440 -f 440//440 247//247 249//249 -f 440//440 249//249 439//439 -f 439//439 249//249 786//786 -f 438//438 419//419 789//789 -f 789//789 419//419 790//790 -f 790//790 419//419 421//421 -f 790//790 421//421 791//791 -f 791//791 421//421 423//423 -f 791//791 423//423 792//792 -f 792//792 423//423 425//425 -f 792//792 425//425 793//793 -f 793//793 425//425 427//427 -f 793//793 427//427 794//794 -f 794//794 427//427 428//428 -f 794//794 428//428 795//795 -f 795//795 428//428 456//456 -f 795//795 456//456 796//796 -f 796//796 456//456 455//455 -f 796//796 455//455 797//797 -f 797//797 455//455 798//798 -f 798//798 455//455 414//414 -f 799//799 800//800 801//801 -f 801//801 800//800 737//737 -f 801//801 737//737 596//596 -f 596//596 737//737 738//738 -f 735//735 737//737 802//802 -f 802//802 737//737 803//803 -f 804//804 805//805 806//806 -f 806//806 805//805 735//735 -f 806//806 735//735 807//807 -f 807//807 735//735 802//802 -f 804//804 808//808 805//805 -f 805//805 808//808 809//809 -f 805//805 809//809 810//810 -f 810//810 809//809 811//811 -f 810//810 811//811 800//800 -f 800//800 811//811 812//812 -f 812//812 813//813 800//800 -f 800//800 813//813 814//814 -f 800//800 814//814 737//737 -f 737//737 814//814 815//815 -f 737//737 815//815 803//803 -f 524//524 733//733 816//816 -f 816//816 733//733 735//735 -f 816//816 735//735 817//817 -f 817//817 735//735 805//805 -f 799//799 818//818 800//800 -f 800//800 818//818 810//810 -f 818//818 817//817 810//810 -f 810//810 817//817 805//805 -f 816//816 817//817 819//819 -f 819//819 817//817 818//818 -f 819//819 818//818 820//820 -f 820//820 818//818 799//799 -f 820//820 799//799 801//801 -f 596//596 598//598 801//801 -f 801//801 598//598 820//820 -f 598//598 526//526 820//820 -f 820//820 526//526 819//819 -f 526//526 524//524 819//819 -f 819//819 524//524 816//816 -f 821//821 822//822 823//823 -f 823//823 822//822 749//749 -f 823//823 749//749 580//580 -f 580//580 749//749 750//750 -f 824//824 747//747 825//825 -f 825//825 826//826 824//824 -f 824//824 826//826 827//827 -f 824//824 827//827 828//828 -f 828//828 827//827 829//829 -f 822//822 830//830 749//749 -f 749//749 830//830 831//831 -f 831//831 832//832 749//749 -f 749//749 832//832 833//833 -f 749//749 833//833 747//747 -f 747//747 833//833 834//834 -f 747//747 834//834 825//825 -f 829//829 835//835 828//828 -f 828//828 835//835 836//836 -f 828//828 836//836 822//822 -f 822//822 836//836 837//837 -f 822//822 837//837 830//830 -f 578//578 745//745 838//838 -f 838//838 745//745 747//747 -f 838//838 747//747 839//839 -f 839//839 747//747 824//824 -f 821//821 840//840 822//822 -f 822//822 840//840 828//828 -f 840//840 839//839 828//828 -f 828//828 839//839 824//824 -f 841//841 838//838 839//839 -f 821//821 823//823 842//842 -f 841//841 839//839 842//842 -f 842//842 839//839 840//840 -f 842//842 840//840 821//821 -f 563//563 842//842 580//580 -f 580//580 842//842 823//823 -f 562//562 841//841 563//563 -f 563//563 841//841 842//842 -f 578//578 838//838 562//562 -f 562//562 838//838 841//841 -f 802//802 215//215 807//807 -f 807//807 215//215 210//210 -f 807//807 210//210 806//806 -f 806//806 210//210 209//209 -f 806//806 209//209 804//804 -f 804//804 209//209 208//208 -f 804//804 208//208 808//808 -f 808//808 208//208 309//309 -f 808//808 309//309 809//809 -f 809//809 309//309 307//307 -f 809//809 307//307 811//811 -f 811//811 307//307 305//305 -f 811//811 305//305 812//812 -f 812//812 305//305 304//304 -f 812//812 304//304 813//813 -f 813//813 304//304 303//303 -f 813//813 303//303 814//814 -f 814//814 303//303 211//211 -f 814//814 211//211 815//815 -f 815//815 211//211 212//212 -f 815//815 212//212 803//803 -f 803//803 212//212 214//214 -f 803//803 214//214 802//802 -f 802//802 214//214 215//215 -f 830//830 240//240 831//831 -f 831//831 240//240 239//239 -f 831//831 239//239 832//832 -f 832//832 239//239 238//238 -f 832//832 238//238 833//833 -f 833//833 238//238 233//233 -f 833//833 233//233 834//834 -f 834//834 233//233 232//232 -f 834//834 232//232 825//825 -f 825//825 232//232 226//226 -f 825//825 226//226 826//826 -f 826//826 226//226 228//228 -f 826//826 228//228 827//827 -f 827//827 228//228 230//230 -f 827//827 230//230 829//829 -f 829//829 230//230 231//231 -f 829//829 231//231 835//835 -f 835//835 231//231 234//234 -f 835//835 234//234 836//836 -f 836//836 234//234 235//235 -f 836//836 235//235 837//837 -f 837//837 235//235 237//237 -f 837//837 237//237 830//830 -f 830//830 237//237 240//240 -f 843//843 844//844 845//845 -f 845//845 844//844 759//759 -f 845//845 759//759 558//558 -f 558//558 759//759 760//760 -f 846//846 757//757 847//847 -f 847//847 848//848 846//846 -f 846//846 848//848 849//849 -f 846//846 849//849 850//850 -f 850//850 849//849 851//851 -f 852//852 759//759 853//853 -f 853//853 759//759 844//844 -f 851//851 854//854 850//850 -f 850//850 854//854 855//855 -f 850//850 855//855 844//844 -f 844//844 855//855 856//856 -f 844//844 856//856 853//853 -f 852//852 857//857 759//759 -f 759//759 857//857 858//858 -f 759//759 858//858 757//757 -f 757//757 858//858 859//859 -f 757//757 859//859 847//847 -f 539//539 755//755 860//860 -f 860//860 755//755 757//757 -f 860//860 757//757 861//861 -f 861//861 757//757 846//846 -f 862//862 863//863 864//864 -f 864//864 863//863 769//769 -f 864//864 769//769 551//551 -f 551//551 769//769 770//770 -f 865//865 769//769 866//866 -f 866//866 769//769 863//863 -f 865//865 867//867 769//769 -f 769//769 867//867 868//868 -f 769//769 868//868 767//767 -f 869//869 870//870 871//871 -f 871//871 870//870 872//872 -f 869//869 873//873 870//870 -f 870//870 873//873 874//874 -f 870//870 874//874 863//863 -f 863//863 874//874 875//875 -f 863//863 875//875 866//866 -f 868//868 876//876 767//767 -f 767//767 876//876 877//877 -f 767//767 877//877 872//872 -f 872//872 877//877 878//878 -f 872//872 878//878 871//871 -f 535//535 765//765 879//879 -f 879//879 765//765 767//767 -f 879//879 767//767 880//880 -f 880//880 767//767 872//872 -f 881//881 882//882 883//883 -f 883//883 882//882 779//779 -f 883//883 779//779 546//546 -f 546//546 779//779 780//780 -f 884//884 885//885 886//886 -f 886//886 885//885 882//882 -f 887//887 777//777 888//888 -f 888//888 889//889 887//887 -f 887//887 889//889 890//890 -f 887//887 890//890 886//886 -f 886//886 890//890 891//891 -f 886//886 891//891 884//884 -f 885//885 892//892 882//882 -f 882//882 892//892 893//893 -f 882//882 893//893 779//779 -f 779//779 893//893 894//894 -f 894//894 895//895 779//779 -f 779//779 895//895 896//896 -f 779//779 896//896 777//777 -f 777//777 896//896 897//897 -f 777//777 897//897 888//888 -f 531//531 775//775 898//898 -f 898//898 775//775 777//777 -f 898//898 777//777 899//899 -f 899//899 777//777 887//887 -f 843//843 900//900 844//844 -f 844//844 900//900 850//850 -f 900//900 861//861 850//850 -f 850//850 861//861 846//846 -f 901//901 860//860 861//861 -f 843//843 845//845 902//902 -f 901//901 861//861 902//902 -f 902//902 861//861 900//900 -f 902//902 900//900 843//843 -f 862//862 903//903 863//863 -f 863//863 903//903 870//870 -f 903//903 880//880 870//870 -f 870//870 880//880 872//872 -f 904//904 879//879 880//880 -f 862//862 864//864 905//905 -f 904//904 880//880 905//905 -f 905//905 880//880 903//903 -f 905//905 903//903 862//862 -f 881//881 906//906 882//882 -f 882//882 906//906 886//886 -f 906//906 899//899 886//886 -f 886//886 899//899 887//887 -f 907//907 898//898 899//899 -f 881//881 883//883 908//908 -f 907//907 899//899 908//908 -f 908//908 899//899 906//906 -f 908//908 906//906 881//881 -f 560//560 902//902 558//558 -f 558//558 902//902 845//845 -f 541//541 901//901 560//560 -f 560//560 901//901 902//902 -f 539//539 860//860 541//541 -f 541//541 860//860 901//901 -f 550//550 905//905 551//551 -f 551//551 905//905 864//864 -f 537//537 904//904 550//550 -f 550//550 904//904 905//905 -f 535//535 879//879 537//537 -f 537//537 879//879 904//904 -f 548//548 908//908 546//546 -f 546//546 908//908 883//883 -f 533//533 907//907 548//548 -f 548//548 907//907 908//908 -f 531//531 898//898 533//533 -f 533//533 898//898 907//907 -f 853//853 295//295 852//852 -f 852//852 295//295 287//287 -f 852//852 287//287 857//857 -f 857//857 287//287 302//302 -f 857//857 302//302 858//858 -f 858//858 302//302 301//301 -f 858//858 301//301 859//859 -f 859//859 301//301 300//300 -f 859//859 300//300 847//847 -f 847//847 300//300 288//288 -f 847//847 288//288 848//848 -f 848//848 288//288 290//290 -f 848//848 290//290 849//849 -f 849//849 290//290 292//292 -f 849//849 292//292 851//851 -f 851//851 292//292 293//293 -f 851//851 293//293 854//854 -f 854//854 293//293 298//298 -f 854//854 298//298 855//855 -f 855//855 298//298 297//297 -f 855//855 297//297 856//856 -f 856//856 297//297 296//296 -f 856//856 296//296 853//853 -f 853//853 296//296 295//295 -f 866//866 271//271 865//865 -f 865//865 271//271 270//270 -f 865//865 270//270 867//867 -f 867//867 270//270 284//284 -f 867//867 284//284 868//868 -f 868//868 284//284 283//283 -f 868//868 283//283 876//876 -f 876//876 283//283 282//282 -f 876//876 282//282 877//877 -f 877//877 282//282 281//281 -f 877//877 281//281 878//878 -f 878//878 281//281 279//279 -f 878//878 279//279 871//871 -f 871//871 279//279 278//278 -f 871//871 278//278 869//869 -f 869//869 278//278 275//275 -f 869//869 275//275 873//873 -f 873//873 275//275 274//274 -f 873//873 274//274 874//874 -f 874//874 274//274 273//273 -f 874//874 273//273 875//875 -f 875//875 273//273 272//272 -f 875//875 272//272 866//866 -f 866//866 272//272 271//271 -f 893//893 260//260 894//894 -f 894//894 260//260 259//259 -f 894//894 259//259 895//895 -f 895//895 259//259 267//267 -f 895//895 267//267 896//896 -f 896//896 267//267 266//266 -f 896//896 266//266 897//897 -f 897//897 266//266 265//265 -f 897//897 265//265 888//888 -f 888//888 265//265 264//264 -f 888//888 264//264 889//889 -f 889//889 264//264 262//262 -f 889//889 262//262 890//890 -f 890//890 262//262 261//261 -f 890//890 261//261 891//891 -f 891//891 261//261 257//257 -f 891//891 257//257 884//884 -f 884//884 257//257 254//254 -f 884//884 254//254 885//885 -f 885//885 254//254 253//253 -f 885//885 253//253 892//892 -f 892//892 253//253 252//252 -f 892//892 252//252 893//893 -f 893//893 252//252 260//260 -f 702//702 674//674 703//703 -f 703//703 674//674 670//670 -f 703//703 670//670 604//604 -f 604//604 670//670 710//710 -f 602//602 706//706 700//700 -f 700//700 706//706 669//669 -f 700//700 669//669 701//701 -f 701//701 669//669 678//678 -f 702//702 705//705 674//674 -f 674//674 705//705 676//676 -f 705//705 701//701 676//676 -f 676//676 701//701 678//678 -f 595//595 704//704 604//604 -f 604//604 704//704 703//703 -f 594//594 699//699 595//595 -f 595//595 699//699 704//704 -f 602//602 700//700 594//594 -f 594//594 700//700 699//699 -f 691//691 652//652 692//692 -f 692//692 652//652 654//654 -f 692//692 654//654 554//554 -f 554//554 654//654 697//697 -f 583//583 693//693 686//686 -f 686//686 693//693 657//657 -f 686//686 657//657 687//687 -f 687//687 657//657 656//656 -f 691//691 689//689 652//652 -f 652//652 689//689 660//660 -f 689//689 687//687 660//660 -f 660//660 687//687 656//656 -f 554//554 556//556 692//692 -f 692//692 556//556 690//690 -f 556//556 585//585 690//690 -f 690//690 585//585 688//688 -f 585//585 583//583 688//688 -f 688//688 583//583 686//686 -f 671//671 181//181 680//680 -f 680//680 181//181 197//197 -f 680//680 197//197 681//681 -f 681//681 197//197 196//196 -f 681//681 196//196 682//682 -f 682//682 196//196 194//194 -f 682//682 194//194 679//679 -f 679//679 194//194 192//192 -f 679//679 192//192 677//677 -f 677//677 192//192 191//191 -f 677//677 191//191 675//675 -f 675//675 191//191 188//188 -f 675//675 188//188 673//673 -f 673//673 188//188 187//187 -f 673//673 187//187 683//683 -f 683//683 187//187 186//186 -f 683//683 186//186 684//684 -f 684//684 186//186 185//185 -f 684//684 185//185 685//685 -f 685//685 185//185 184//184 -f 685//685 184//184 672//672 -f 672//672 184//184 182//182 -f 672//672 182//182 671//671 -f 671//671 182//182 181//181 -f 662//662 154//154 661//661 -f 661//661 154//154 170//170 -f 661//661 170//170 659//659 -f 659//659 170//170 172//172 -f 659//659 172//172 663//663 -f 663//663 172//172 164//164 -f 663//663 164//164 664//664 -f 664//664 164//164 162//162 -f 664//664 162//162 665//665 -f 665//665 162//162 161//161 -f 665//665 161//161 653//653 -f 653//653 161//161 160//160 -f 653//653 160//160 655//655 -f 655//655 160//160 158//158 -f 655//655 158//158 666//666 -f 666//666 158//158 167//167 -f 666//666 167//167 667//667 -f 667//667 167//167 166//166 -f 667//667 166//166 668//668 -f 668//668 166//166 165//165 -f 668//668 165//165 658//658 -f 658//658 165//165 155//155 -f 658//658 155//155 662//662 -f 662//662 155//155 154//154 -f 632//632 506//506 633//633 -f 633//633 506//506 508//508 -f 633//633 508//508 568//568 -f 568//568 508//508 650//650 -f 565//565 646//646 627//627 -f 627//627 646//646 515//515 -f 627//627 515//515 628//628 -f 628//628 515//515 517//517 -f 625//625 493//493 626//626 -f 626//626 493//493 495//495 -f 626//626 495//495 586//586 -f 586//586 495//495 644//644 -f 573//573 640//640 620//620 -f 620//620 640//640 499//499 -f 620//620 499//499 621//621 -f 621//621 499//499 489//489 -f 618//618 482//482 619//619 -f 619//619 482//482 472//472 -f 619//619 472//472 528//528 -f 528//528 472//472 638//638 -f 611//611 634//634 613//613 -f 613//613 634//634 478//478 -f 613//613 478//478 614//614 -f 614//614 478//478 481//481 -f 632//632 630//630 506//506 -f 506//506 630//630 510//510 -f 630//630 628//628 510//510 -f 510//510 628//628 517//517 -f 625//625 623//623 493//493 -f 493//493 623//623 491//491 -f 623//623 621//621 491//491 -f 491//491 621//621 489//489 -f 618//618 616//616 482//482 -f 482//482 616//616 475//475 -f 616//616 614//614 475//475 -f 475//475 614//614 481//481 -f 568//568 570//570 633//633 -f 633//633 570//570 631//631 -f 570//570 567//567 631//631 -f 631//631 567//567 629//629 -f 567//567 565//565 629//629 -f 629//629 565//565 627//627 -f 586//586 588//588 626//626 -f 626//626 588//588 624//624 -f 588//588 575//575 624//624 -f 624//624 575//575 622//622 -f 575//575 573//573 622//622 -f 622//622 573//573 620//620 -f 528//528 527//527 619//619 -f 619//619 527//527 617//617 -f 527//527 610//610 617//617 -f 617//617 610//610 615//615 -f 610//610 611//611 615//615 -f 615//615 611//611 613//613 -f 516//516 318//318 520//520 -f 520//520 318//318 317//317 -f 520//520 317//317 521//521 -f 521//521 317//317 335//335 -f 521//521 335//335 522//522 -f 522//522 335//335 334//334 -f 522//522 334//334 511//511 -f 511//511 334//334 333//333 -f 511//511 333//333 512//512 -f 512//512 333//333 326//326 -f 512//512 326//326 507//507 -f 507//507 326//326 328//328 -f 507//507 328//328 509//509 -f 509//509 328//328 329//329 -f 509//509 329//329 513//513 -f 513//513 329//329 325//325 -f 513//513 325//325 514//514 -f 514//514 325//325 322//322 -f 514//514 322//322 519//519 -f 519//519 322//322 321//321 -f 519//519 321//321 518//518 -f 518//518 321//321 332//332 -f 518//518 332//332 516//516 -f 516//516 332//332 318//318 -f 502//502 339//339 490//490 -f 490//490 339//339 338//338 -f 490//490 338//338 492//492 -f 492//492 338//338 355//355 -f 492//492 355//355 503//503 -f 503//503 355//355 354//354 -f 503//503 354//354 504//504 -f 504//504 354//354 353//353 -f 504//504 353//353 505//505 -f 505//505 353//353 352//352 -f 505//505 352//352 494//494 -f 494//494 352//352 350//350 -f 494//494 350//350 496//496 -f 496//496 350//350 349//349 -f 496//496 349//349 497//497 -f 497//497 349//349 346//346 -f 497//497 346//346 498//498 -f 498//498 346//346 343//343 -f 498//498 343//343 500//500 -f 500//500 343//343 341//341 -f 500//500 341//341 501//501 -f 501//501 341//341 340//340 -f 501//501 340//340 502//502 -f 502//502 340//340 339//339 -f 486//486 359//359 487//487 -f 487//487 359//359 358//358 -f 487//487 358//358 488//488 -f 488//488 358//358 377//377 -f 488//488 377//377 476//476 -f 476//476 377//377 376//376 -f 476//476 376//376 477//477 -f 477//477 376//376 375//375 -f 477//477 375//375 483//483 -f 483//483 375//375 369//369 -f 483//483 369//369 484//484 -f 484//484 369//369 368//368 -f 484//484 368//368 485//485 -f 485//485 368//368 367//367 -f 485//485 367//367 473//473 -f 473//473 367//367 366//366 -f 473//473 366//366 474//474 -f 474//474 366//366 373//373 -f 474//474 373//373 479//479 -f 479//479 373//373 371//371 -f 479//479 371//371 480//480 -f 480//480 371//371 370//370 -f 480//480 370//370 486//486 -f 486//486 370//370 359//359 -f 909//909 713//713 910//910 -f 910//910 713//713 66//66 -f 910//910 66//66 911//911 -f 911//911 66//66 72//72 -f 911//911 72//72 912//912 -f 912//912 72//72 71//71 -f 912//912 71//71 913//913 -f 913//913 71//71 914//914 -f 914//914 71//71 58//58 -f 914//914 58//58 915//915 -f 915//915 58//58 916//916 -f 916//916 58//58 56//56 -f 916//916 56//56 917//917 -f 917//917 56//56 37//37 -f 917//917 37//37 410//410 -f 918//918 919//919 920//920 -f 921//921 918//918 922//922 -f 922//922 918//918 920//920 -f 922//922 920//920 923//923 -f 923//923 920//920 924//924 -f 925//925 926//926 927//927 -f 928//928 929//929 925//925 -f 925//925 929//929 930//930 -f 925//925 930//930 931//931 -f 931//931 930//930 932//932 -f 931//931 932//932 933//933 -f 933//933 932//932 934//934 -f 933//933 934//934 935//935 -f 935//935 934//934 936//936 -f 935//935 936//936 920//920 -f 920//920 936//936 937//937 -f 920//920 937//937 924//924 -f 924//924 937//937 938//938 -f 924//924 938//938 939//939 -f 939//939 938//938 940//940 -f 939//939 940//940 941//941 -f 941//941 940//940 942//942 -f 941//941 942//942 943//943 -f 943//943 942//942 944//944 -f 943//943 944//944 945//945 -f 945//945 944//944 946//946 -f 945//945 946//946 927//927 -f 927//927 946//946 928//928 -f 927//927 928//928 925//925 -f 947//947 786//786 931//931 -f 931//931 786//786 785//785 -f 931//931 785//785 925//925 -f 925//925 785//785 948//948 -f 925//925 948//948 949//949 -f 950//950 951//951 948//948 -f 948//948 951//951 952//952 -f 948//948 952//952 949//949 -f 920//920 919//919 935//935 -f 935//935 919//919 953//953 -f 935//935 953//953 933//933 -f 933//933 953//953 954//954 -f 933//933 954//954 931//931 -f 931//931 954//954 947//947 -f 955//955 956//956 957//957 -f 958//958 955//955 959//959 -f 959//959 955//955 957//957 -f 959//959 957//957 960//960 -f 960//960 957//957 961//961 -f 962//962 963//963 964//964 -f 964//964 963//963 965//965 -f 964//964 965//965 966//966 -f 966//966 965//965 967//967 -f 966//966 967//967 968//968 -f 968//968 967//967 969//969 -f 968//968 969//969 970//970 -f 970//970 969//969 971//971 -f 970//970 971//971 972//972 -f 972//972 971//971 973//973 -f 972//972 973//973 974//974 -f 974//974 973//973 975//975 -f 974//974 975//975 956//956 -f 956//956 975//975 976//976 -f 956//956 976//976 957//957 -f 957//957 976//976 977//977 -f 957//957 977//977 978//978 -f 978//978 977//977 979//979 -f 978//978 979//979 980//980 -f 980//980 979//979 981//981 -f 980//980 981//981 982//982 -f 982//982 981//981 962//962 -f 982//982 962//962 964//964 -f 982//982 983//983 980//980 -f 980//980 983//983 984//984 -f 980//980 984//984 978//978 -f 978//978 984//984 985//985 -f 978//978 985//985 957//957 -f 957//957 985//985 961//961 -f 986//986 964//964 987//987 -f 987//987 964//964 988//988 -f 384//384 983//983 385//385 -f 385//385 983//983 982//982 -f 385//385 982//982 989//989 -f 989//989 982//982 964//964 -f 989//989 964//964 990//990 -f 986//986 991//991 964//964 -f 964//964 991//991 992//992 -f 964//964 992//992 990//990 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 997//997 996//996 998//998 -f 999//999 1000//1000 998//998 -f 998//998 1000//1000 1001//1001 -f 998//998 1001//1001 997//997 -f 1002//1002 1003//1003 999//999 -f 999//999 1003//1003 1004//1004 -f 999//999 1004//1004 1000//1000 -f 1005//1005 1006//1006 1002//1002 -f 1002//1002 1006//1006 1007//1007 -f 1002//1002 1007//1007 1003//1003 -f 1008//1008 1009//1009 1010//1010 -f 1010//1010 1009//1009 1011//1011 -f 1010//1010 1011//1011 1012//1012 -f 1012//1012 1011//1011 1013//1013 -f 1012//1012 1013//1013 1005//1005 -f 1005//1005 1013//1013 1014//1014 -f 1005//1005 1014//1014 1006//1006 -f 1015//1015 1016//1016 1008//1008 -f 1008//1008 1016//1016 1017//1017 -f 1008//1008 1017//1017 1009//1009 -f 1018//1018 1019//1019 1015//1015 -f 1015//1015 1019//1019 1020//1020 -f 1015//1015 1020//1020 1016//1016 -f 1021//1021 1022//1022 1018//1018 -f 1018//1018 1022//1022 1023//1023 -f 1018//1018 1023//1023 1019//1019 -f 1024//1024 1022//1022 1025//1025 -f 1025//1025 1022//1022 1021//1021 -f 1025//1025 1021//1021 1026//1026 -f 1026//1026 1021//1021 994//994 -f 1026//1026 994//994 1027//1027 -f 1027//1027 994//994 993//993 -f 1027//1027 993//993 1028//1028 -f 1029//1029 998//998 1030//1030 -f 1030//1030 998//998 996//996 -f 1030//1030 996//996 1031//1031 -f 1031//1031 996//996 994//994 -f 1031//1031 994//994 1032//1032 -f 1032//1032 994//994 1021//1021 -f 1032//1032 1021//1021 1033//1033 -f 1033//1033 1021//1021 1018//1018 -f 1033//1033 1018//1018 1034//1034 -f 1034//1034 1018//1018 1015//1015 -f 1034//1034 1015//1015 1035//1035 -f 1035//1035 1015//1015 1008//1008 -f 1035//1035 1008//1008 1036//1036 -f 1036//1036 1008//1008 1010//1010 -f 1036//1036 1010//1010 1037//1037 -f 1037//1037 1010//1010 1012//1012 -f 1037//1037 1012//1012 1038//1038 -f 1038//1038 1012//1012 1005//1005 -f 1038//1038 1005//1005 1039//1039 -f 1039//1039 1005//1005 1002//1002 -f 1039//1039 1002//1002 1040//1040 -f 1040//1040 1002//1002 999//999 -f 1040//1040 999//999 1029//1029 -f 1029//1029 999//999 998//998 -f 1041//1041 1042//1042 1043//1043 -f 1044//1044 1045//1045 1046//1046 -f 1046//1046 1045//1045 1047//1047 -f 1046//1046 1047//1047 1048//1048 -f 1049//1049 1050//1050 1048//1048 -f 1048//1048 1050//1050 1051//1051 -f 1048//1048 1051//1051 1046//1046 -f 1052//1052 1053//1053 1049//1049 -f 1049//1049 1053//1053 1054//1054 -f 1049//1049 1054//1054 1050//1050 -f 1055//1055 1056//1056 1052//1052 -f 1052//1052 1056//1056 1057//1057 -f 1052//1052 1057//1057 1053//1053 -f 1058//1058 1059//1059 1055//1055 -f 1055//1055 1059//1059 1060//1060 -f 1055//1055 1060//1060 1056//1056 -f 1061//1061 1062//1062 1058//1058 -f 1058//1058 1062//1062 1063//1063 -f 1058//1058 1063//1063 1059//1059 -f 1064//1064 1065//1065 1061//1061 -f 1061//1061 1065//1065 1066//1066 -f 1061//1061 1066//1066 1062//1062 -f 1067//1067 1068//1068 1064//1064 -f 1064//1064 1068//1068 1069//1069 -f 1064//1064 1069//1069 1065//1065 -f 1043//1043 1070//1070 1041//1041 -f 1041//1041 1070//1070 1071//1071 -f 1041//1041 1071//1071 1067//1067 -f 1067//1067 1071//1071 1072//1072 -f 1067//1067 1072//1072 1068//1068 -f 1073//1073 1043//1043 1074//1074 -f 1074//1074 1043//1043 1042//1042 -f 1074//1074 1042//1042 1075//1075 -f 1075//1075 1042//1042 1045//1045 -f 1075//1075 1045//1045 1076//1076 -f 1076//1076 1045//1045 1044//1044 -f 1076//1076 1044//1044 1077//1077 -f 1078//1078 1042//1042 1079//1079 -f 1079//1079 1042//1042 1041//1041 -f 1079//1079 1041//1041 1080//1080 -f 1080//1080 1041//1041 1067//1067 -f 1080//1080 1067//1067 1081//1081 -f 1081//1081 1067//1067 1064//1064 -f 1081//1081 1064//1064 1082//1082 -f 1082//1082 1064//1064 1061//1061 -f 1082//1082 1061//1061 1083//1083 -f 1083//1083 1061//1061 1058//1058 -f 1083//1083 1058//1058 1084//1084 -f 1084//1084 1058//1058 1055//1055 -f 1084//1084 1055//1055 1085//1085 -f 1085//1085 1055//1055 1052//1052 -f 1085//1085 1052//1052 1086//1086 -f 1086//1086 1052//1052 1049//1049 -f 1086//1086 1049//1049 1087//1087 -f 1087//1087 1049//1049 1048//1048 -f 1087//1087 1048//1048 1088//1088 -f 1088//1088 1048//1048 1047//1047 -f 1088//1088 1047//1047 1089//1089 -f 1089//1089 1047//1047 1045//1045 -f 1089//1089 1045//1045 1078//1078 -f 1078//1078 1045//1045 1042//1042 -f 48//48 932//932 47//47 -f 47//47 932//932 930//930 -f 47//47 930//930 10//10 -f 10//10 930//930 929//929 -f 10//10 929//929 8//8 -f 8//8 929//929 928//928 -f 8//8 928//928 70//70 -f 70//70 928//928 946//946 -f 70//70 946//946 69//69 -f 69//69 946//946 944//944 -f 69//69 944//944 57//57 -f 57//57 944//944 942//942 -f 57//57 942//942 55//55 -f 55//55 942//942 940//940 -f 55//55 940//940 54//54 -f 54//54 940//940 938//938 -f 54//54 938//938 53//53 -f 53//53 938//938 937//937 -f 53//53 937//937 51//51 -f 51//51 937//937 936//936 -f 51//51 936//936 49//49 -f 49//49 936//936 934//934 -f 49//49 934//934 48//48 -f 48//48 934//934 932//932 -f 18//18 962//962 60//60 -f 60//60 962//962 981//981 -f 60//60 981//981 50//50 -f 50//50 981//981 979//979 -f 50//50 979//979 52//52 -f 52//52 979//979 977//977 -f 52//52 977//977 38//38 -f 38//38 977//977 976//976 -f 38//38 976//976 36//36 -f 36//36 976//976 975//975 -f 36//36 975//975 34//34 -f 34//34 975//975 973//973 -f 34//34 973//973 32//32 -f 32//32 973//973 971//971 -f 32//32 971//971 40//40 -f 40//40 971//971 969//969 -f 40//40 969//969 12//12 -f 12//12 969//969 967//967 -f 12//12 967//967 14//14 -f 14//14 967//967 965//965 -f 14//14 965//965 15//15 -f 15//15 965//965 963//963 -f 15//15 963//963 18//18 -f 18//18 963//963 962//962 -f 63//63 1085//1085 62//62 -f 62//62 1085//1085 1086//1086 -f 62//62 1086//1086 61//61 -f 61//61 1086//1086 1087//1087 -f 61//61 1087//1087 59//59 -f 59//59 1087//1087 1088//1088 -f 59//59 1088//1088 20//20 -f 20//20 1088//1088 1089//1089 -f 20//20 1089//1089 19//19 -f 19//19 1089//1089 1078//1078 -f 19//19 1078//1078 13//13 -f 13//13 1078//1078 1079//1079 -f 13//13 1079//1079 30//30 -f 30//30 1079//1079 1080//1080 -f 30//30 1080//1080 28//28 -f 28//28 1080//1080 1081//1081 -f 28//28 1081//1081 27//27 -f 27//27 1081//1081 1082//1082 -f 27//27 1082//1082 24//24 -f 24//24 1082//1082 1083//1083 -f 24//24 1083//1083 22//22 -f 22//22 1083//1083 1084//1084 -f 22//22 1084//1084 63//63 -f 63//63 1084//1084 1085//1085 -f 6//6 1036//1036 46//46 -f 46//46 1036//1036 1037//1037 -f 46//46 1037//1037 45//45 -f 45//45 1037//1037 1038//1038 -f 45//45 1038//1038 68//68 -f 68//68 1038//1038 1039//1039 -f 68//68 1039//1039 67//67 -f 67//67 1039//1039 1040//1040 -f 67//67 1040//1040 65//65 -f 65//65 1040//1040 1029//1029 -f 65//65 1029//1029 64//64 -f 64//64 1029//1029 1030//1030 -f 64//64 1030//1030 7//7 -f 7//7 1030//1030 1031//1031 -f 7//7 1031//1031 9//9 -f 9//9 1031//1031 1032//1032 -f 9//9 1032//1032 11//11 -f 11//11 1032//1032 1033//1033 -f 11//11 1033//1033 17//17 -f 17//17 1033//1033 1034//1034 -f 17//17 1034//1034 16//16 -f 16//16 1034//1034 1035//1035 -f 16//16 1035//1035 6//6 -f 6//6 1035//1035 1036//1036 -f 469//469 714//714 1090//1090 -f 1090//1090 714//714 716//716 -f 1090//1090 716//716 1091//1091 -f 1091//1091 716//716 1092//1092 -f 1092//1092 716//716 717//717 -f 1092//1092 717//717 1093//1093 -f 1093//1093 717//717 1094//1094 -f 1094//1094 717//717 360//360 -f 1094//1094 360//360 364//364 -f 364//364 363//363 1095//1095 -f 364//364 1095//1095 1094//1094 -f 1094//1094 1095//1095 1096//1096 -f 1094//1094 1096//1096 1093//1093 -f 1093//1093 1096//1096 1097//1097 -f 1093//1093 1097//1097 1092//1092 -f 1092//1092 1097//1097 1091//1091 -f 1091//1091 1097//1097 1098//1098 -f 1091//1091 1098//1098 1090//1090 -f 1090//1090 1098//1098 470//470 -f 1090//1090 470//470 469//469 -f 713//713 1099//1099 712//712 -f 712//712 1099//1099 784//784 -f 1099//1099 1100//1100 784//784 -f 784//784 1100//1100 1101//1101 -f 784//784 1101//1101 783//783 -f 148//148 250//250 1102//1102 -f 1102//1102 250//250 783//783 -f 1102//1102 783//783 1103//1103 -f 1103//1103 783//783 1101//1101 -f 713//713 909//909 1104//1104 -f 713//713 1104//1104 1099//1099 -f 1099//1099 1104//1104 1105//1105 -f 1099//1099 1105//1105 1100//1100 -f 1100//1100 1105//1105 1106//1106 -f 1100//1100 1106//1106 1101//1101 -f 1101//1101 1106//1106 1103//1103 -f 1103//1103 1106//1106 1107//1107 -f 1103//1103 1107//1107 1102//1102 -f 1102//1102 1107//1107 149//149 -f 1102//1102 149//149 148//148 -f 446//446 445//445 1108//1108 -f 446//446 1108//1108 1109//1109 -f 1109//1109 1108//1108 1110//1110 -f 1109//1109 1110//1110 1111//1111 -f 1111//1111 1110//1110 412//412 -f 1111//1111 412//412 413//413 -f 1112//1112 426//426 1113//1113 -f 1113//1113 426//426 424//424 -f 1113//1113 424//424 1114//1114 -f 1114//1114 424//424 422//422 -f 1114//1114 422//422 1115//1115 -f 1115//1115 422//422 420//420 -f 1115//1115 420//420 1116//1116 -f 1116//1116 420//420 443//443 -f 1116//1116 443//443 1117//1117 -f 1117//1117 443//443 442//442 -f 1117//1117 442//442 1118//1118 -f 1118//1118 442//442 441//441 -f 1118//1118 441//441 1119//1119 -f 1119//1119 441//441 437//437 -f 1119//1119 437//437 1120//1120 -f 1120//1120 437//437 436//436 -f 1120//1120 436//436 1121//1121 -f 1121//1121 436//436 434//434 -f 1121//1121 434//434 1122//1122 -f 1122//1122 434//434 432//432 -f 1122//1122 432//432 1123//1123 -f 1123//1123 432//432 430//430 -f 1123//1123 430//430 1124//1124 -f 1124//1124 430//430 429//429 -f 1124//1124 429//429 1125//1125 -f 1125//1125 429//429 417//417 -f 1125//1125 417//417 1126//1126 -f 1126//1126 417//417 416//416 -f 1126//1126 416//416 1127//1127 -f 1127//1127 416//416 453//453 -f 1127//1127 453//453 1128//1128 -f 1128//1128 453//453 452//452 -f 1128//1128 452//452 1129//1129 -f 1129//1129 452//452 450//450 -f 1129//1129 450//450 1130//1130 -f 1130//1130 450//450 448//448 -f 1130//1130 448//448 1131//1131 -f 1131//1131 448//448 447//447 -f 1131//1131 447//447 1132//1132 -f 1132//1132 447//447 461//461 -f 1132//1132 461//461 1133//1133 -f 1133//1133 461//461 460//460 -f 1133//1133 460//460 1134//1134 -f 1134//1134 460//460 459//459 -f 1134//1134 459//459 1135//1135 -f 1135//1135 459//459 458//458 -f 1135//1135 458//458 1136//1136 -f 1136//1136 458//458 457//457 -f 1136//1136 457//457 1137//1137 -f 1137//1137 457//457 454//454 -f 1137//1137 454//454 1112//1112 -f 1112//1112 454//454 426//426 -f 1138//1138 1135//1135 1139//1139 -f 1139//1139 1135//1135 1136//1136 -f 1139//1139 1136//1136 1140//1140 -f 1140//1140 1136//1136 1137//1137 -f 1140//1140 1137//1137 1141//1141 -f 1141//1141 1137//1137 1112//1112 -f 1141//1141 1112//1112 1142//1142 -f 1142//1142 1112//1112 1113//1113 -f 1142//1142 1113//1113 1143//1143 -f 1144//1144 1128//1128 1145//1145 -f 1145//1145 1128//1128 1129//1129 -f 1145//1145 1129//1129 1146//1146 -f 1146//1146 1129//1129 1130//1130 -f 1146//1146 1130//1130 1147//1147 -f 1147//1147 1130//1130 1131//1131 -f 1147//1147 1131//1131 1148//1148 -f 1148//1148 1131//1131 1132//1132 -f 1148//1148 1132//1132 1149//1149 -f 1149//1149 1132//1132 1133//1133 -f 1149//1149 1133//1133 1138//1138 -f 1138//1138 1133//1133 1134//1134 -f 1138//1138 1134//1134 1135//1135 -f 1113//1113 1114//1114 1143//1143 -f 1143//1143 1114//1114 1115//1115 -f 1143//1143 1115//1115 1150//1150 -f 1150//1150 1115//1115 1116//1116 -f 1150//1150 1116//1116 1151//1151 -f 1151//1151 1116//1116 1117//1117 -f 1151//1151 1117//1117 1152//1152 -f 1152//1152 1117//1117 1118//1118 -f 1152//1152 1118//1118 1153//1153 -f 1153//1153 1118//1118 1119//1119 -f 1153//1153 1119//1119 1154//1154 -f 1154//1154 1119//1119 1120//1120 -f 1154//1154 1120//1120 1155//1155 -f 1120//1120 1121//1121 1155//1155 -f 1155//1155 1121//1121 1122//1122 -f 1155//1155 1122//1122 1156//1156 -f 1156//1156 1122//1122 1123//1123 -f 1156//1156 1123//1123 1157//1157 -f 1157//1157 1123//1123 1124//1124 -f 1157//1157 1124//1124 1158//1158 -f 1158//1158 1124//1124 1125//1125 -f 1158//1158 1125//1125 1159//1159 -f 1159//1159 1125//1125 1126//1126 -f 1159//1159 1126//1126 1144//1144 -f 1144//1144 1126//1126 1127//1127 -f 1144//1144 1127//1127 1128//1128 -f 1160//1160 1142//1142 1161//1161 -f 1161//1161 1142//1142 1143//1143 -f 1161//1161 1143//1143 1162//1162 -f 1162//1162 1143//1143 1150//1150 -f 1162//1162 1150//1150 1163//1163 -f 1163//1163 1150//1150 1151//1151 -f 1163//1163 1151//1151 1164//1164 -f 1164//1164 1151//1151 1152//1152 -f 1164//1164 1152//1152 1165//1165 -f 1165//1165 1152//1152 1153//1153 -f 1165//1165 1153//1153 1166//1166 -f 1166//1166 1153//1153 1154//1154 -f 1166//1166 1154//1154 1167//1167 -f 1167//1167 1154//1154 1155//1155 -f 1167//1167 1155//1155 1168//1168 -f 1168//1168 1155//1155 1156//1156 -f 1168//1168 1156//1156 1169//1169 -f 1169//1169 1156//1156 1157//1157 -f 1169//1169 1157//1157 1170//1170 -f 1170//1170 1157//1157 1158//1158 -f 1170//1170 1158//1158 1171//1171 -f 1171//1171 1158//1158 1159//1159 -f 1171//1171 1159//1159 1172//1172 -f 1172//1172 1159//1159 1144//1144 -f 1172//1172 1144//1144 1173//1173 -f 1173//1173 1144//1144 1145//1145 -f 1173//1173 1145//1145 1174//1174 -f 1174//1174 1145//1145 1146//1146 -f 1174//1174 1146//1146 1175//1175 -f 1175//1175 1146//1146 1147//1147 -f 1175//1175 1147//1147 1176//1176 -f 1176//1176 1147//1147 1148//1148 -f 1176//1176 1148//1148 1177//1177 -f 1177//1177 1148//1148 1149//1149 -f 1177//1177 1149//1149 1178//1178 -f 1178//1178 1149//1149 1138//1138 -f 1178//1178 1138//1138 1179//1179 -f 1179//1179 1138//1138 1139//1139 -f 1179//1179 1139//1139 1180//1180 -f 1180//1180 1139//1139 1140//1140 -f 1180//1180 1140//1140 1181//1181 -f 1181//1181 1140//1140 1141//1141 -f 1181//1181 1141//1141 1160//1160 -f 1160//1160 1141//1141 1142//1142 -f 1182//1182 1178//1178 1183//1183 -f 1183//1183 1178//1178 1179//1179 -f 1183//1183 1179//1179 1184//1184 -f 1184//1184 1179//1179 1180//1180 -f 1184//1184 1180//1180 1185//1185 -f 1185//1185 1180//1180 1181//1181 -f 1185//1185 1181//1181 1186//1186 -f 1186//1186 1181//1181 1160//1160 -f 1186//1186 1160//1160 1187//1187 -f 1187//1187 1160//1160 1161//1161 -f 1187//1187 1161//1161 1188//1188 -f 1188//1188 1161//1161 1162//1162 -f 1188//1188 1162//1162 1189//1189 -f 1190//1190 1172//1172 1191//1191 -f 1191//1191 1172//1172 1173//1173 -f 1191//1191 1173//1173 1192//1192 -f 1192//1192 1173//1173 1174//1174 -f 1192//1192 1174//1174 1193//1193 -f 1193//1193 1174//1174 1175//1175 -f 1193//1193 1175//1175 1194//1194 -f 1194//1194 1175//1175 1176//1176 -f 1194//1194 1176//1176 1182//1182 -f 1182//1182 1176//1176 1177//1177 -f 1182//1182 1177//1177 1178//1178 -f 1162//1162 1163//1163 1189//1189 -f 1189//1189 1163//1163 1164//1164 -f 1189//1189 1164//1164 1195//1195 -f 1195//1195 1164//1164 1165//1165 -f 1195//1195 1165//1165 1196//1196 -f 1196//1196 1165//1165 1166//1166 -f 1196//1196 1166//1166 1197//1197 -f 1197//1197 1166//1166 1167//1167 -f 1197//1197 1167//1167 1198//1198 -f 1198//1198 1167//1167 1168//1168 -f 1198//1198 1168//1168 1199//1199 -f 1199//1199 1168//1168 1169//1169 -f 1199//1199 1169//1169 1200//1200 -f 1200//1200 1169//1169 1170//1170 -f 1200//1200 1170//1170 1190//1190 -f 1190//1190 1170//1170 1171//1171 -f 1190//1190 1171//1171 1172//1172 -f 1201//1201 1186//1186 1202//1202 -f 1202//1202 1186//1186 1187//1187 -f 1202//1202 1187//1187 1203//1203 -f 1203//1203 1187//1187 1188//1188 -f 1203//1203 1188//1188 1204//1204 -f 1204//1204 1188//1188 1189//1189 -f 1204//1204 1189//1189 1205//1205 -f 1205//1205 1189//1189 1195//1195 -f 1205//1205 1195//1195 1206//1206 -f 1206//1206 1195//1195 1196//1196 -f 1206//1206 1196//1196 1207//1207 -f 1207//1207 1196//1196 1197//1197 -f 1207//1207 1197//1197 1208//1208 -f 1208//1208 1197//1197 1198//1198 -f 1208//1208 1198//1198 1209//1209 -f 1209//1209 1198//1198 1199//1199 -f 1209//1209 1199//1199 1210//1210 -f 1210//1210 1199//1199 1200//1200 -f 1210//1210 1200//1200 1211//1211 -f 1211//1211 1200//1200 1190//1190 -f 1211//1211 1190//1190 1212//1212 -f 1212//1212 1190//1190 1191//1191 -f 1212//1212 1191//1191 1213//1213 -f 1213//1213 1191//1191 1192//1192 -f 1213//1213 1192//1192 1214//1214 -f 1214//1214 1192//1192 1193//1193 -f 1214//1214 1193//1193 1215//1215 -f 1215//1215 1193//1193 1194//1194 -f 1215//1215 1194//1194 1216//1216 -f 1216//1216 1194//1194 1182//1182 -f 1216//1216 1182//1182 1217//1217 -f 1217//1217 1182//1182 1183//1183 -f 1217//1217 1183//1183 1218//1218 -f 1218//1218 1183//1183 1184//1184 -f 1218//1218 1184//1184 1219//1219 -f 1219//1219 1184//1184 1185//1185 -f 1219//1219 1185//1185 1201//1201 -f 1201//1201 1185//1185 1186//1186 -f 1201//1201 1202//1202 1220//1220 -f 1217//1217 1218//1218 1220//1220 -f 1220//1220 1218//1218 1219//1219 -f 1220//1220 1219//1219 1201//1201 -f 1214//1214 1215//1215 1220//1220 -f 1220//1220 1215//1215 1216//1216 -f 1220//1220 1216//1216 1217//1217 -f 1211//1211 1212//1212 1220//1220 -f 1220//1220 1212//1212 1213//1213 -f 1220//1220 1213//1213 1214//1214 -f 1208//1208 1209//1209 1220//1220 -f 1220//1220 1209//1209 1210//1210 -f 1220//1220 1210//1210 1211//1211 -f 1205//1205 1206//1206 1220//1220 -f 1220//1220 1206//1206 1207//1207 -f 1220//1220 1207//1207 1208//1208 -f 1202//1202 1203//1203 1220//1220 -f 1220//1220 1203//1203 1204//1204 -f 1220//1220 1204//1204 1205//1205 -f 778//778 263//263 774//774 -f 774//774 263//263 258//258 -f 768//768 280//280 764//764 -f 764//764 280//280 269//269 -f 758//758 289//289 754//754 -f 754//754 289//289 286//286 -f 216//216 744//744 217//217 -f 217//217 744//744 748//748 -f 217//217 748//748 227//227 -f 311//311 731//731 146//146 -f 146//146 731//731 736//736 -f 146//146 736//736 147//147 -f 708//708 313//313 709//709 -f 709//709 313//313 312//312 -f 316//316 696//696 315//315 -f 315//315 696//696 695//695 -f 315//315 695//695 314//314 -f 648//648 337//337 649//649 -f 649//649 337//337 336//336 -f 642//642 357//357 643//643 -f 643//643 357//357 356//356 -f 636//636 381//381 637//637 -f 637//637 381//381 380//380 -f 528//528 638//638 529//529 -f 529//529 638//638 639//639 -f 612//612 635//635 611//611 -f 611//611 635//635 634//634 -f 586//586 644//644 587//587 -f 587//587 644//644 645//645 -f 572//572 641//641 573//573 -f 573//573 641//641 640//640 -f 568//568 650//650 569//569 -f 569//569 650//650 651//651 -f 564//564 647//647 565//565 -f 565//565 647//647 646//646 -f 554//554 697//697 555//555 -f 555//555 697//697 698//698 -f 582//582 694//694 583//583 -f 583//583 694//694 693//693 -f 530//530 776//776 531//531 -f 531//531 776//776 775//775 -f 546//546 780//780 547//547 -f 547//547 780//780 773//773 -f 534//534 766//766 535//535 -f 535//535 766//766 765//765 -f 551//551 770//770 552//552 -f 552//552 770//770 763//763 -f 538//538 756//756 539//539 -f 539//539 756//756 755//755 -f 558//558 760//760 559//559 -f 559//559 760//760 753//753 -f 577//577 746//746 578//578 -f 578//578 746//746 745//745 -f 580//580 750//750 581//581 -f 581//581 750//750 743//743 -f 604//604 710//710 605//605 -f 605//605 710//710 711//711 -f 601//601 707//707 602//602 -f 602//602 707//707 706//706 -f 596//596 738//738 597//597 -f 597//597 738//738 732//732 -f 523//523 734//734 524//524 -f 524//524 734//734 733//733 -f 782//782 255//255 781//781 -f 781//781 255//255 256//256 -f 276//276 771//771 277//277 -f 277//277 771//771 772//772 -f 277//277 772//772 251//251 -f 291//291 761//761 299//299 -f 299//299 761//761 762//762 -f 299//299 762//762 268//268 -f 229//229 751//751 294//294 -f 294//294 751//751 752//752 -f 294//294 752//752 285//285 -f 742//742 218//218 741//741 -f 741//741 218//218 220//220 -f 740//740 220//220 739//739 -f 739//739 220//220 223//223 -f 718//718 362//362 715//715 -f 715//715 362//362 361//361 -f 378//378 719//719 379//379 -f 379//379 719//719 720//720 -f 379//379 720//720 344//344 -f 347//347 721//721 348//348 -f 348//348 721//721 722//722 -f 348//348 722//722 323//323 -f 331//331 723//723 330//330 -f 330//330 723//723 724//724 -f 330//330 724//724 159//159 -f 728//728 180//180 727//727 -f 727//727 180//180 178//178 -f 726//726 178//178 725//725 -f 725//725 178//178 176//176 -f 730//730 207//207 729//729 -f 729//729 207//207 206//206 -f 729//729 206//206 193//193 -f 415//415 983//983 386//386 -f 386//386 983//983 384//384 -f 983//983 415//415 984//984 -f 984//984 415//415 449//449 -f 984//984 449//449 985//985 -f 985//985 449//449 451//451 -f 985//985 451//451 961//961 -f 961//961 451//451 418//418 -f 989//989 363//363 385//385 -f 385//385 363//363 365//365 -f 446//446 960//960 418//418 -f 418//418 960//960 961//961 -f 987//987 470//470 986//986 -f 986//986 470//470 1098//1098 -f 986//986 1098//1098 991//991 -f 991//991 1098//1098 1097//1097 -f 991//991 1097//1097 992//992 -f 992//992 1097//1097 1096//1096 -f 992//992 1096//1096 990//990 -f 990//990 1096//1096 1095//1095 -f 990//990 1095//1095 989//989 -f 989//989 1095//1095 363//363 -f 960//960 446//446 1109//1109 -f 960//960 1109//1109 959//959 -f 959//959 1109//1109 1111//1111 -f 959//959 1111//1111 958//958 -f 958//958 1111//1111 413//413 -f 958//958 413//413 955//955 -f 988//988 471//471 987//987 -f 987//987 471//471 470//470 -f 408//408 956//956 413//413 -f 413//413 956//956 955//955 -f 974//974 409//409 462//462 -f 471//471 988//988 468//468 -f 468//468 988//988 964//964 -f 468//468 964//964 966//966 -f 974//974 462//462 972//972 -f 972//972 462//462 463//463 -f 972//972 463//463 970//970 -f 970//970 463//463 464//464 -f 970//970 464//464 968//968 -f 464//464 465//465 968//968 -f 968//968 465//465 466//466 -f 968//968 466//466 966//966 -f 966//966 466//466 467//467 -f 966//966 467//467 468//468 -f 409//409 974//974 408//408 -f 408//408 974//974 956//956 -f 947//947 435//435 786//786 -f 786//786 435//435 439//439 -f 785//785 249//249 948//948 -f 948//948 249//249 150//150 -f 948//948 150//150 149//149 -f 919//919 444//444 953//953 -f 953//953 444//444 431//431 -f 953//953 431//431 954//954 -f 954//954 431//431 433//433 -f 954//954 433//433 947//947 -f 947//947 433//433 435//435 -f 926//926 925//925 949//949 -f 926//926 949//949 909//909 -f 948//948 149//149 950//950 -f 950//950 149//149 1107//1107 -f 950//950 1107//1107 951//951 -f 951//951 1107//1107 1106//1106 -f 951//951 1106//1106 952//952 -f 952//952 1106//1106 1105//1105 -f 952//952 1105//1105 949//949 -f 949//949 1105//1105 1104//1104 -f 949//949 1104//1104 909//909 -f 918//918 445//445 919//919 -f 919//919 445//445 444//444 -f 909//909 910//910 926//926 -f 923//923 412//412 1110//1110 -f 923//923 1110//1110 922//922 -f 922//922 1110//1110 1108//1108 -f 922//922 1108//1108 921//921 -f 921//921 1108//1108 445//445 -f 921//921 445//445 918//918 -f 927//927 926//926 910//910 -f 910//910 911//911 927//927 -f 927//927 911//911 912//912 -f 927//927 912//912 945//945 -f 945//945 912//912 913//913 -f 913//913 914//914 945//945 -f 945//945 914//914 915//915 -f 945//945 915//915 943//943 -f 915//915 916//916 943//943 -f 943//943 916//916 917//917 -f 943//943 917//917 941//941 -f 941//941 917//917 410//410 -f 941//941 410//410 939//939 -f 924//924 411//411 923//923 -f 923//923 411//411 412//412 -f 411//411 924//924 410//410 -f 410//410 924//924 939//939 -f 414//414 387//387 798//798 -f 798//798 387//387 388//388 -f 405//405 798//798 388//388 -f 404//404 797//797 405//405 -f 405//405 797//797 798//798 -f 1043//1043 1073//1073 382//382 -f 382//382 1073//1073 383//383 -f 383//383 400//400 388//388 -f 388//388 400//400 405//405 -f 797//797 404//404 796//796 -f 796//796 404//404 406//406 -f 796//796 406//406 795//795 -f 795//795 406//406 407//407 -f 795//795 407//407 794//794 -f 794//794 407//407 399//399 -f 794//794 399//399 793//793 -f 793//793 399//399 398//398 -f 793//793 398//398 792//792 -f 792//792 398//398 396//396 -f 792//792 396//396 791//791 -f 791//791 396//396 395//395 -f 791//791 395//395 790//790 -f 790//790 395//395 403//403 -f 382//382 163//163 174//174 -f 190//190 200//200 1046//1046 -f 1046//1046 200//200 390//390 -f 1046//1046 390//390 1044//1044 -f 190//190 1046//1046 189//189 -f 189//189 1046//1046 1051//1051 -f 189//189 1051//1051 198//198 -f 1051//1051 1050//1050 198//198 -f 198//198 1050//1050 1054//1054 -f 198//198 1054//1054 199//199 -f 1054//1054 1053//1053 199//199 -f 199//199 1053//1053 1057//1057 -f 199//199 1057//1057 179//179 -f 1057//1057 1056//1056 179//179 -f 179//179 1056//1056 1060//1060 -f 179//179 1060//1060 177//177 -f 1060//1060 1059//1059 177//177 -f 177//177 1059//1059 1063//1063 -f 177//177 1063//1063 168//168 -f 168//168 1063//1063 1062//1062 -f 168//168 1062//1062 169//169 -f 169//169 1062//1062 1066//1066 -f 169//169 1066//1066 171//171 -f 1066//1066 1065//1065 171//171 -f 171//171 1065//1065 1069//1069 -f 171//171 1069//1069 173//173 -f 1069//1069 1068//1068 173//173 -f 173//173 1068//1068 1072//1072 -f 173//173 1072//1072 174//174 -f 174//174 1072//1072 1071//1071 -f 174//174 1071//1071 382//382 -f 382//382 1071//1071 1070//1070 -f 382//382 1070//1070 1043//1043 -f 383//383 1073//1073 400//400 -f 394//394 789//789 403//403 -f 403//403 789//789 790//790 -f 789//789 788//788 438//438 -f 438//438 788//788 440//440 -f 389//389 1077//1077 390//390 -f 390//390 1077//1077 1044//1044 -f 1076//1076 1077//1077 401//401 -f 1076//1076 401//401 1075//1075 -f 1075//1075 401//401 397//397 -f 1075//1075 397//397 1074//1074 -f 1074//1074 397//397 400//400 -f 1074//1074 400//400 1073//1073 -f 789//789 394//394 788//788 -f 1077//1077 389//389 401//401 -f 393//393 787//787 394//394 -f 394//394 787//787 788//788 -f 391//391 402//402 389//389 -f 389//389 402//402 401//401 -f 402//402 1024//1024 1025//1025 -f 402//402 1025//1025 392//392 -f 392//392 1025//1025 1026//1026 -f 392//392 1026//1026 393//393 -f 393//393 1026//1026 1027//1027 -f 393//393 1027//1027 1028//1028 -f 393//393 1028//1028 787//787 -f 402//402 391//391 1024//1024 -f 151//151 787//787 152//152 -f 152//152 787//787 1028//1028 -f 152//152 1028//1028 993//993 -f 391//391 203//203 1024//1024 -f 1024//1024 203//203 205//205 -f 1024//1024 205//205 1022//1022 -f 1022//1022 205//205 1023//1023 -f 1023//1023 205//205 204//204 -f 153//153 152//152 993//993 -f 993//993 995//995 153//153 -f 153//153 995//995 997//997 -f 153//153 997//997 236//236 -f 997//997 1001//1001 236//236 -f 236//236 1001//1001 1000//1000 -f 236//236 1000//1000 242//242 -f 1000//1000 1004//1004 242//242 -f 242//242 1004//1004 1003//1003 -f 242//242 1003//1003 241//241 -f 1003//1003 1007//1007 241//241 -f 241//241 1007//1007 1006//1006 -f 241//241 1006//1006 219//219 -f 219//219 1006//1006 221//221 -f 1006//1006 1014//1014 221//221 -f 221//221 1014//1014 1013//1013 -f 221//221 1013//1013 222//222 -f 222//222 1013//1013 1011//1011 -f 222//222 1011//1011 224//224 -f 224//224 1011//1011 1009//1009 -f 224//224 1009//1009 310//310 -f 310//310 1009//1009 308//308 -f 308//308 1009//1009 1017//1017 -f 308//308 1017//1017 306//306 -f 1017//1017 1016//1016 306//306 -f 306//306 1016//1016 1020//1020 -f 306//306 1020//1020 204//204 -f 204//204 1020//1020 1019//1019 -f 204//204 1019//1019 1023//1023 -f 1221//1221 1222//1222 1223//1223 -f 1224//1224 1225//1225 1226//1226 -f 1227//1227 1228//1228 1229//1229 -f 1230//1230 1231//1231 1232//1232 -f 1233//1233 1234//1234 1235//1235 -f 1236//1236 1237//1237 1238//1238 -f 1238//1238 1237//1237 1239//1239 -f 1238//1238 1239//1239 1240//1240 -f 1241//1241 1242//1242 1243//1243 -f 1243//1243 1244//1244 1241//1241 -f 1241//1241 1244//1244 1245//1245 -f 1241//1241 1245//1245 1246//1246 -f 1246//1246 1245//1245 1247//1247 -f 1246//1246 1247//1247 1248//1248 -f 1249//1249 1250//1250 1251//1251 -f 1251//1251 1250//1250 1252//1252 -f 1251//1251 1252//1252 1253//1253 -f 1253//1253 1252//1252 1254//1254 -f 1253//1253 1254//1254 1248//1248 -f 1248//1248 1254//1254 1255//1255 -f 1248//1248 1255//1255 1246//1246 -f 1256//1256 1257//1257 1258//1258 -f 1258//1258 1257//1257 1259//1259 -f 1258//1258 1259//1259 1260//1260 -f 1260//1260 1259//1259 1261//1261 -f 1260//1260 1261//1261 1262//1262 -f 1261//1261 1263//1263 1262//1262 -f 1262//1262 1263//1263 1264//1264 -f 1262//1262 1264//1264 1232//1232 -f 1232//1232 1264//1264 1265//1265 -f 1232//1232 1265//1265 1266//1266 -f 1267//1267 1268//1268 1269//1269 -f 1269//1269 1268//1268 1270//1270 -f 1269//1269 1270//1270 1271//1271 -f 1271//1271 1270//1270 1272//1272 -f 1273//1273 1274//1274 1275//1275 -f 1275//1275 1274//1274 1276//1276 -f 1275//1275 1276//1276 1277//1277 -f 1273//1273 1278//1278 1274//1274 -f 1274//1274 1278//1278 1279//1279 -f 1274//1274 1279//1279 1280//1280 -f 1280//1280 1279//1279 1281//1281 -f 1280//1280 1281//1281 1282//1282 -f 1283//1283 1284//1284 1285//1285 -f 1286//1286 1287//1287 1288//1288 -f 1288//1288 1287//1287 1289//1289 -f 1288//1288 1289//1289 1275//1275 -f 1275//1275 1289//1289 1290//1290 -f 1275//1275 1290//1290 1273//1273 -f 1281//1281 1291//1291 1282//1282 -f 1282//1282 1291//1291 1292//1292 -f 1282//1282 1292//1292 1284//1284 -f 1284//1284 1292//1292 1293//1293 -f 1284//1284 1293//1293 1285//1285 -f 1294//1294 1295//1295 1296//1296 -f 1295//1295 1297//1297 1296//1296 -f 1296//1296 1297//1297 1298//1298 -f 1296//1296 1298//1298 1299//1299 -f 1299//1299 1298//1298 1300//1300 -f 1300//1300 1301//1301 1299//1299 -f 1299//1299 1301//1301 1302//1302 -f 1299//1299 1302//1302 1303//1303 -f 1302//1302 1304//1304 1303//1303 -f 1303//1303 1304//1304 1305//1305 -f 1303//1303 1305//1305 1306//1306 -f 1306//1306 1305//1305 1307//1307 -f 1306//1306 1307//1307 1308//1308 -f 1308//1308 1307//1307 1309//1309 -f 1308//1308 1309//1309 1310//1310 -f 1310//1310 1309//1309 1311//1311 -f 1310//1310 1311//1311 1294//1294 -f 1312//1312 1313//1313 1314//1314 -f 1314//1314 1313//1313 1315//1315 -f 1314//1314 1315//1315 1316//1316 -f 1316//1316 1315//1315 1317//1317 -f 1316//1316 1317//1317 1318//1318 -f 1318//1318 1319//1319 1316//1316 -f 1316//1316 1319//1319 1320//1320 -f 1316//1316 1320//1320 1321//1321 -f 1322//1322 1323//1323 1324//1324 -f 1320//1320 1325//1325 1321//1321 -f 1321//1321 1325//1325 1326//1326 -f 1321//1321 1326//1326 1323//1323 -f 1324//1324 1327//1327 1322//1322 -f 1322//1322 1327//1327 1328//1328 -f 1322//1322 1328//1328 1329//1329 -f 1329//1329 1328//1328 1330//1330 -f 1329//1329 1330//1330 1331//1331 -f 1331//1331 1330//1330 1332//1332 -f 1331//1331 1332//1332 1317//1317 -f 1317//1317 1332//1332 1333//1333 -f 1317//1317 1333//1333 1318//1318 -f 1334//1334 1335//1335 1336//1336 -f 1336//1336 1335//1335 1337//1337 -f 1336//1336 1337//1337 1338//1338 -f 1339//1339 1340//1340 1341//1341 -f 1341//1341 1340//1340 1342//1342 -f 1341//1341 1342//1342 1343//1343 -f 1339//1339 1344//1344 1340//1340 -f 1340//1340 1344//1344 1345//1345 -f 1340//1340 1345//1345 1346//1346 -f 1346//1346 1345//1345 1347//1347 -f 1346//1346 1347//1347 1348//1348 -f 1348//1348 1347//1347 1349//1349 -f 1348//1348 1349//1349 1337//1337 -f 1337//1337 1349//1349 1350//1350 -f 1337//1337 1350//1350 1338//1338 -f 1351//1351 1352//1352 1353//1353 -f 1353//1353 1352//1352 1336//1336 -f 1353//1353 1336//1336 1354//1354 -f 1354//1354 1336//1336 1338//1338 -f 1355//1355 1356//1356 1357//1357 -f 1355//1355 1357//1357 1358//1358 -f 1359//1359 1360//1360 1336//1336 -f 1336//1336 1360//1360 1361//1361 -f 1336//1336 1361//1361 1334//1334 -f 1334//1334 1361//1361 1362//1362 -f 1334//1334 1362//1362 1363//1363 -f 1364//1364 1365//1365 1366//1366 -f 1367//1367 1368//1368 1369//1369 -f 1368//1368 1370//1370 1369//1369 -f 1369//1369 1370//1370 1371//1371 -f 1369//1369 1371//1371 1372//1372 -f 1372//1372 1371//1371 1373//1373 -f 1357//1357 1374//1374 1358//1358 -f 1358//1358 1374//1374 1375//1375 -f 1358//1358 1375//1375 1376//1376 -f 1376//1376 1375//1375 1377//1377 -f 1378//1378 1223//1223 1379//1379 -f 1379//1379 1223//1223 1380//1380 -f 1379//1379 1380//1380 1342//1342 -f 1342//1342 1380//1380 1352//1352 -f 1342//1342 1352//1352 1343//1343 -f 1343//1343 1352//1352 1351//1351 -f 1381//1381 1382//1382 1383//1383 -f 1384//1384 1383//1383 1385//1385 -f 1386//1386 1387//1387 1388//1388 -f 1388//1388 1387//1387 1358//1358 -f 1388//1388 1358//1358 1389//1389 -f 1389//1389 1358//1358 1376//1376 -f 1389//1389 1376//1376 1390//1390 -f 1390//1390 1376//1376 1377//1377 -f 1390//1390 1377//1377 1391//1391 -f 1299//1299 1392//1392 1296//1296 -f 1296//1296 1392//1392 1393//1393 -f 1296//1296 1393//1393 1390//1390 -f 1390//1390 1393//1393 1394//1394 -f 1390//1390 1394//1394 1389//1389 -f 1395//1395 1396//1396 1397//1397 -f 1398//1398 1306//1306 1399//1399 -f 1399//1399 1306//1306 1308//1308 -f 1399//1399 1308//1308 1400//1400 -f 1400//1400 1308//1308 1397//1397 -f 1401//1401 1402//1402 1403//1403 -f 1404//1404 1402//1402 1405//1405 -f 1405//1405 1402//1402 1401//1401 -f 1405//1405 1401//1401 1406//1406 -f 1267//1267 1256//1256 1268//1268 -f 1268//1268 1256//1256 1258//1258 -f 1268//1268 1258//1258 1407//1407 -f 1407//1407 1258//1258 1408//1408 -f 1407//1407 1408//1408 1409//1409 -f 1409//1409 1408//1408 1410//1410 -f 1409//1409 1410//1410 1411//1411 -f 1229//1229 1228//1228 1270//1270 -f 1266//1266 1272//1272 1232//1232 -f 1232//1232 1272//1272 1270//1270 -f 1232//1232 1270//1270 1230//1230 -f 1230//1230 1270//1270 1228//1228 -f 1230//1230 1228//1228 1412//1412 -f 1229//1229 1413//1413 1227//1227 -f 1227//1227 1413//1413 1414//1414 -f 1227//1227 1414//1414 1415//1415 -f 1415//1415 1414//1414 1416//1416 -f 1417//1417 1418//1418 1414//1414 -f 1414//1414 1418//1418 1419//1419 -f 1414//1414 1419//1419 1416//1416 -f 1420//1420 1421//1421 1422//1422 -f 1422//1422 1421//1421 1423//1423 -f 1422//1422 1423//1423 1424//1424 -f 1424//1424 1423//1423 1425//1425 -f 1426//1426 1427//1427 1423//1423 -f 1428//1428 1425//1425 1429//1429 -f 1429//1429 1425//1425 1423//1423 -f 1429//1429 1423//1423 1430//1430 -f 1430//1430 1423//1423 1427//1427 -f 1431//1431 1432//1432 1433//1433 -f 1323//1323 1322//1322 1321//1321 -f 1321//1321 1322//1322 1434//1434 -f 1321//1321 1434//1434 1435//1435 -f 1435//1435 1436//1436 1321//1321 -f 1321//1321 1436//1436 1437//1437 -f 1321//1321 1437//1437 1438//1438 -f 1438//1438 1437//1437 1431//1431 -f 1439//1439 1440//1440 1441//1441 -f 1441//1441 1442//1442 1439//1439 -f 1439//1439 1442//1442 1443//1443 -f 1439//1439 1443//1443 1274//1274 -f 1274//1274 1443//1443 1444//1444 -f 1274//1274 1444//1444 1276//1276 -f 1442//1442 1445//1445 1443//1443 -f 1443//1443 1445//1445 1446//1446 -f 1443//1443 1446//1446 1447//1447 -f 1447//1447 1446//1446 1448//1448 -f 1447//1447 1448//1448 1449//1449 -f 1448//1448 1450//1450 1449//1449 -f 1449//1449 1450//1450 1451//1451 -f 1449//1449 1451//1451 1452//1452 -f 1453//1453 1454//1454 1455//1455 -f 1455//1455 1454//1454 1456//1456 -f 1455//1455 1456//1456 1440//1440 -f 1440//1440 1456//1456 1457//1457 -f 1440//1440 1457//1457 1441//1441 -f 1308//1308 1458//1458 1449//1449 -f 1397//1397 1308//1308 1395//1395 -f 1395//1395 1308//1308 1449//1449 -f 1395//1395 1449//1449 1455//1455 -f 1455//1455 1449//1449 1452//1452 -f 1455//1455 1452//1452 1453//1453 -f 1294//1294 1296//1296 1310//1310 -f 1310//1310 1296//1296 1459//1459 -f 1310//1310 1459//1459 1308//1308 -f 1308//1308 1459//1459 1460//1460 -f 1308//1308 1460//1460 1458//1458 -f 1461//1461 1462//1462 1390//1390 -f 1462//1462 1463//1463 1390//1390 -f 1390//1390 1463//1463 1464//1464 -f 1390//1390 1464//1464 1296//1296 -f 1296//1296 1464//1464 1465//1465 -f 1296//1296 1465//1465 1459//1459 -f 1466//1466 1467//1467 1468//1468 -f 1468//1468 1467//1467 1461//1461 -f 1468//1468 1461//1461 1469//1469 -f 1469//1469 1461//1461 1390//1390 -f 1469//1469 1390//1390 1470//1470 -f 1470//1470 1390//1390 1391//1391 -f 1471//1471 1466//1466 1369//1369 -f 1369//1369 1466//1466 1468//1468 -f 1369//1369 1468//1468 1367//1367 -f 1367//1367 1468//1468 1469//1469 -f 1367//1367 1469//1469 1472//1472 -f 1472//1472 1469//1469 1470//1470 -f 1473//1473 1474//1474 1475//1475 -f 1475//1475 1474//1474 1476//1476 -f 1475//1475 1476//1476 1477//1477 -f 1477//1477 1476//1476 1478//1478 -f 1477//1477 1478//1478 1369//1369 -f 1369//1369 1478//1478 1479//1479 -f 1369//1369 1479//1479 1471//1471 -f 1480//1480 1481//1481 1482//1482 -f 1481//1481 1480//1480 1483//1483 -f 1484//1484 1485//1485 1486//1486 -f 1487//1487 1488//1488 1489//1489 -f 1485//1485 1484//1484 1489//1489 -f 1489//1489 1484//1484 1490//1490 -f 1489//1489 1490//1490 1487//1487 -f 1488//1488 1487//1487 1491//1491 -f 1491//1491 1487//1487 1492//1492 -f 1491//1491 1492//1492 1493//1493 -f 1494//1494 1495//1495 1481//1481 -f 1481//1481 1495//1495 1496//1496 -f 1481//1481 1496//1496 1482//1482 -f 1482//1482 1496//1496 1497//1497 -f 1482//1482 1497//1497 1498//1498 -f 1498//1498 1497//1497 1499//1499 -f 1498//1498 1499//1499 1500//1500 -f 1500//1500 1499//1499 1501//1501 -f 1500//1500 1501//1501 1502//1502 -f 1502//1502 1501//1501 1503//1503 -f 1502//1502 1503//1503 1504//1504 -f 1505//1505 1506//1506 1507//1507 -f 1507//1507 1506//1506 1508//1508 -f 1505//1505 1509//1509 1506//1506 -f 1506//1506 1509//1509 1510//1510 -f 1506//1506 1510//1510 1242//1242 -f 1242//1242 1510//1510 1511//1511 -f 1242//1242 1511//1511 1243//1243 -f 1243//1243 1511//1511 1512//1512 -f 1243//1243 1512//1512 1513//1513 -f 1513//1513 1512//1512 1514//1514 -f 1513//1513 1514//1514 1236//1236 -f 1236//1236 1514//1514 1515//1515 -f 1236//1236 1515//1515 1237//1237 -f 1516//1516 1517//1517 1518//1518 -f 1518//1518 1517//1517 1519//1519 -f 1518//1518 1519//1519 1508//1508 -f 1508//1508 1519//1519 1520//1520 -f 1508//1508 1520//1520 1507//1507 -f 1521//1521 1522//1522 1523//1523 -f 1523//1523 1522//1522 1524//1524 -f 1523//1523 1524//1524 1525//1525 -f 1516//1516 1518//1518 1526//1526 -f 1526//1526 1518//1518 1527//1527 -f 1526//1526 1527//1527 1528//1528 -f 1528//1528 1527//1527 1421//1421 -f 1528//1528 1421//1421 1529//1529 -f 1529//1529 1421//1421 1420//1420 -f 1529//1529 1420//1420 1523//1523 -f 1523//1523 1420//1420 1530//1530 -f 1523//1523 1530//1530 1521//1521 -f 1429//1429 1531//1531 1428//1428 -f 1428//1428 1531//1531 1532//1532 -f 1428//1428 1532//1532 1533//1533 -f 1533//1533 1532//1532 1534//1534 -f 1533//1533 1534//1534 1535//1535 -f 1535//1535 1534//1534 1536//1536 -f 1535//1535 1536//1536 1537//1537 -f 1537//1537 1536//1536 1524//1524 -f 1537//1537 1524//1524 1538//1538 -f 1538//1538 1524//1524 1522//1522 -f 1249//1249 1240//1240 1250//1250 -f 1250//1250 1240//1240 1239//1239 -f 1250//1250 1239//1239 1524//1524 -f 1524//1524 1239//1239 1539//1539 -f 1524//1524 1539//1539 1525//1525 -f 1226//1226 1540//1540 1541//1541 -f 1494//1494 1542//1542 1543//1543 -f 1225//1225 1495//1495 1226//1226 -f 1226//1226 1495//1495 1494//1494 -f 1226//1226 1494//1494 1540//1540 -f 1540//1540 1494//1494 1543//1543 -f 1241//1241 1544//1544 1242//1242 -f 1242//1242 1544//1544 1545//1545 -f 1242//1242 1545//1545 1506//1506 -f 1506//1506 1545//1545 1546//1546 -f 1506//1506 1546//1546 1547//1547 -f 1541//1541 1548//1548 1226//1226 -f 1226//1226 1548//1548 1549//1549 -f 1226//1226 1549//1549 1550//1550 -f 1550//1550 1549//1549 1551//1551 -f 1550//1550 1551//1551 1241//1241 -f 1241//1241 1551//1551 1552//1552 -f 1241//1241 1552//1552 1544//1544 -f 1553//1553 1554//1554 1555//1555 -f 1553//1553 1555//1555 1556//1556 -f 1557//1557 1558//1558 1559//1559 -f 1559//1559 1558//1558 1560//1560 -f 1559//1559 1560//1560 1561//1561 -f 1561//1561 1556//1556 1559//1559 -f 1559//1559 1556//1556 1555//1555 -f 1559//1559 1555//1555 1562//1562 -f 1562//1562 1555//1555 1483//1483 -f 1562//1562 1483//1483 1563//1563 -f 1563//1563 1483//1483 1480//1480 -f 1423//1423 1564//1564 1557//1557 -f 1557//1557 1564//1564 1565//1565 -f 1557//1557 1565//1565 1558//1558 -f 1554//1554 1566//1566 1527//1527 -f 1527//1527 1566//1566 1567//1567 -f 1527//1527 1567//1567 1421//1421 -f 1421//1421 1567//1567 1568//1568 -f 1421//1421 1568//1568 1423//1423 -f 1423//1423 1568//1568 1569//1569 -f 1423//1423 1569//1569 1564//1564 -f 1570//1570 1260//1260 1571//1571 -f 1571//1571 1260//1260 1262//1262 -f 1571//1571 1262//1262 1572//1572 -f 1572//1572 1262//1262 1232//1232 -f 1572//1572 1232//1232 1573//1573 -f 1573//1573 1232//1232 1231//1231 -f 1574//1574 1280//1280 1575//1575 -f 1575//1575 1280//1280 1282//1282 -f 1575//1575 1282//1282 1576//1576 -f 1576//1576 1282//1282 1284//1284 -f 1577//1577 1396//1396 1578//1578 -f 1578//1578 1396//1396 1395//1395 -f 1578//1578 1395//1395 1579//1579 -f 1579//1579 1395//1395 1455//1455 -f 1579//1579 1455//1455 1580//1580 -f 1580//1580 1455//1455 1440//1440 -f 1285//1285 1286//1286 1283//1283 -f 1283//1283 1286//1286 1288//1288 -f 1283//1283 1288//1288 1403//1403 -f 1403//1403 1288//1288 1581//1581 -f 1403//1403 1581//1581 1401//1401 -f 1401//1401 1581//1581 1582//1582 -f 1582//1582 1583//1583 1401//1401 -f 1401//1401 1583//1583 1584//1584 -f 1401//1401 1584//1584 1585//1585 -f 1586//1586 1587//1587 1409//1409 -f 1411//1411 1406//1406 1409//1409 -f 1409//1409 1406//1406 1401//1401 -f 1409//1409 1401//1401 1586//1586 -f 1586//1586 1401//1401 1585//1585 -f 1588//1588 1407//1407 1589//1589 -f 1589//1589 1407//1407 1409//1409 -f 1589//1589 1409//1409 1590//1590 -f 1590//1590 1409//1409 1587//1587 -f 1588//1588 1591//1591 1407//1407 -f 1407//1407 1591//1591 1592//1592 -f 1407//1407 1592//1592 1581//1581 -f 1581//1581 1592//1592 1593//1593 -f 1581//1581 1593//1593 1582//1582 -f 1407//1407 1224//1224 1268//1268 -f 1268//1268 1224//1224 1226//1226 -f 1268//1268 1226//1226 1270//1270 -f 1270//1270 1226//1226 1550//1550 -f 1270//1270 1550//1550 1229//1229 -f 1229//1229 1550//1550 1241//1241 -f 1229//1229 1241//1241 1413//1413 -f 1413//1413 1241//1241 1246//1246 -f 1277//1277 1473//1473 1275//1275 -f 1275//1275 1473//1473 1475//1475 -f 1275//1275 1475//1475 1288//1288 -f 1288//1288 1475//1475 1594//1594 -f 1475//1475 1595//1595 1596//1596 -f 1597//1597 1598//1598 1594//1594 -f 1596//1596 1599//1599 1475//1475 -f 1475//1475 1599//1599 1600//1600 -f 1475//1475 1600//1600 1594//1594 -f 1594//1594 1600//1600 1601//1601 -f 1594//1594 1601//1601 1597//1597 -f 1598//1598 1502//1502 1594//1594 -f 1594//1594 1502//1502 1504//1504 -f 1594//1594 1504//1504 1288//1288 -f 1288//1288 1504//1504 1602//1602 -f 1288//1288 1602//1602 1581//1581 -f 1581//1581 1602//1602 1603//1603 -f 1581//1581 1603//1603 1407//1407 -f 1407//1407 1603//1603 1604//1604 -f 1407//1407 1604//1604 1224//1224 -f 1598//1598 1605//1605 1502//1502 -f 1502//1502 1605//1605 1606//1606 -f 1502//1502 1606//1606 1607//1607 -f 1595//1595 1475//1475 1608//1608 -f 1608//1608 1475//1475 1477//1477 -f 1608//1608 1477//1477 1609//1609 -f 1610//1610 1611//1611 1372//1372 -f 1372//1372 1611//1611 1500//1500 -f 1372//1372 1500//1500 1369//1369 -f 1369//1369 1500//1500 1502//1502 -f 1369//1369 1502//1502 1477//1477 -f 1477//1477 1502//1502 1607//1607 -f 1477//1477 1607//1607 1609//1609 -f 1554//1554 1527//1527 1555//1555 -f 1555//1555 1527//1527 1518//1518 -f 1555//1555 1518//1518 1483//1483 -f 1483//1483 1518//1518 1508//1508 -f 1483//1483 1508//1508 1481//1481 -f 1481//1481 1508//1508 1506//1506 -f 1481//1481 1506//1506 1494//1494 -f 1494//1494 1506//1506 1547//1547 -f 1494//1494 1547//1547 1542//1542 -f 1610//1610 1484//1484 1611//1611 -f 1611//1611 1484//1484 1486//1486 -f 1611//1611 1486//1486 1500//1500 -f 1500//1500 1486//1486 1612//1612 -f 1500//1500 1612//1612 1498//1498 -f 1498//1498 1612//1612 1613//1613 -f 1498//1498 1613//1613 1482//1482 -f 1482//1482 1613//1613 1614//1614 -f 1482//1482 1614//1614 1480//1480 -f 1615//1615 1616//1616 1610//1610 -f 1617//1617 1615//1615 1366//1366 -f 1366//1366 1615//1615 1610//1610 -f 1366//1366 1610//1610 1364//1364 -f 1364//1364 1610//1610 1372//1372 -f 1364//1364 1372//1372 1618//1618 -f 1618//1618 1372//1372 1373//1373 -f 1619//1619 1484//1484 1620//1620 -f 1620//1620 1484//1484 1610//1610 -f 1620//1620 1610//1610 1621//1621 -f 1621//1621 1610//1610 1616//1616 -f 1619//1619 1622//1622 1484//1484 -f 1484//1484 1622//1622 1623//1623 -f 1484//1484 1623//1623 1490//1490 -f 1490//1490 1623//1623 1624//1624 -f 1624//1624 1625//1625 1490//1490 -f 1490//1490 1625//1625 1626//1626 -f 1490//1490 1626//1626 1366//1366 -f 1366//1366 1626//1626 1627//1627 -f 1366//1366 1627//1627 1617//1617 -f 1628//1628 1387//1387 1629//1629 -f 1629//1629 1387//1387 1630//1630 -f 1629//1629 1630//1630 1631//1631 -f 1631//1631 1630//1630 1632//1632 -f 1633//1633 1358//1358 1634//1634 -f 1634//1634 1358//1358 1387//1387 -f 1634//1634 1387//1387 1635//1635 -f 1635//1635 1387//1387 1628//1628 -f 1355//1355 1636//1636 1637//1637 -f 1633//1633 1638//1638 1358//1358 -f 1358//1358 1638//1638 1639//1639 -f 1358//1358 1639//1639 1355//1355 -f 1355//1355 1639//1639 1640//1640 -f 1355//1355 1640//1640 1636//1636 -f 1433//1433 1641//1641 1431//1431 -f 1431//1431 1641//1641 1426//1426 -f 1431//1431 1426//1426 1438//1438 -f 1438//1438 1426//1426 1423//1423 -f 1438//1438 1423//1423 1321//1321 -f 1321//1321 1423//1423 1557//1557 -f 1321//1321 1557//1557 1316//1316 -f 1316//1316 1557//1557 1559//1559 -f 1316//1316 1559//1559 1314//1314 -f 1365//1365 1359//1359 1366//1366 -f 1366//1366 1359//1359 1336//1336 -f 1366//1366 1336//1336 1490//1490 -f 1490//1490 1336//1336 1352//1352 -f 1490//1490 1352//1352 1487//1487 -f 1487//1487 1352//1352 1380//1380 -f 1487//1487 1380//1380 1492//1492 -f 1383//1383 1384//1384 1381//1381 -f 1381//1381 1384//1384 1355//1355 -f 1381//1381 1355//1355 1630//1630 -f 1630//1630 1355//1355 1637//1637 -f 1630//1630 1637//1637 1632//1632 -f 1642//1642 1643//1643 1314//1314 -f 1223//1223 1222//1222 1380//1380 -f 1380//1380 1222//1222 1644//1644 -f 1380//1380 1644//1644 1645//1645 -f 1562//1562 1493//1493 1559//1559 -f 1559//1559 1493//1493 1492//1492 -f 1559//1559 1492//1492 1314//1314 -f 1314//1314 1492//1492 1380//1380 -f 1314//1314 1380//1380 1642//1642 -f 1642//1642 1380//1380 1645//1645 -f 1643//1643 1646//1646 1314//1314 -f 1314//1314 1646//1646 1647//1647 -f 1314//1314 1647//1647 1312//1312 -f 1312//1312 1647//1647 1648//1648 -f 1648//1648 1649//1649 1312//1312 -f 1312//1312 1649//1649 1650//1650 -f 1312//1312 1650//1650 1223//1223 -f 1223//1223 1650//1650 1651//1651 -f 1223//1223 1651//1651 1221//1221 -f 1652//1652 1653//1653 1654//1654 -f 1654//1654 1653//1653 1335//1335 -f 1654//1654 1335//1335 1655//1655 -f 1655//1655 1335//1335 1334//1334 -f 1655//1655 1334//1334 1656//1656 -f 1652//1652 1657//1657 1653//1653 -f 1653//1653 1657//1657 1658//1658 -f 1653//1653 1658//1658 1659//1659 -f 1659//1659 1658//1658 1660//1660 -f 1659//1659 1660//1660 1661//1661 -f 1662//1662 1663//1663 1664//1664 -f 1664//1664 1663//1663 1665//1665 -f 1664//1664 1665//1665 1666//1666 -f 1356//1356 1355//1355 1667//1667 -f 1667//1667 1355//1355 1384//1384 -f 1667//1667 1384//1384 1363//1363 -f 1363//1363 1384//1384 1664//1664 -f 1363//1363 1664//1664 1334//1334 -f 1334//1334 1664//1664 1666//1666 -f 1334//1334 1666//1666 1656//1656 -f 1385//1385 1233//1233 1384//1384 -f 1384//1384 1233//1233 1235//1235 -f 1384//1384 1235//1235 1664//1664 -f 1664//1664 1235//1235 1659//1659 -f 1664//1664 1659//1659 1662//1662 -f 1662//1662 1659//1659 1661//1661 -f 1668//1668 1669//1669 1670//1670 -f 1671//1671 1672//1672 1673//1673 -f 1668//1668 1670//1670 1674//1674 -f 1670//1670 1675//1675 1674//1674 -f 1674//1674 1675//1675 1676//1676 -f 1674//1674 1676//1676 1677//1677 -f 1671//1671 1673//1673 1678//1678 -f 1673//1673 1679//1679 1678//1678 -f 1678//1678 1679//1679 1680//1680 -f 1678//1678 1680//1680 1668//1668 -f 1668//1668 1680//1680 1681//1681 -f 1668//1668 1681//1681 1669//1669 -f 1676//1676 1682//1682 1677//1677 -f 1677//1677 1682//1682 1683//1683 -f 1677//1677 1683//1683 1671//1671 -f 1671//1671 1683//1683 1684//1684 -f 1671//1671 1684//1684 1672//1672 -f 1685//1685 1686//1686 1687//1687 -f 1687//1687 1686//1686 1688//1688 -f 1689//1689 1690//1690 1691//1691 -f 1691//1691 1690//1690 1692//1692 -f 1692//1692 1693//1693 1691//1691 -f 1691//1691 1693//1693 1694//1694 -f 1691//1691 1694//1694 1695//1695 -f 1694//1694 1696//1696 1695//1695 -f 1695//1695 1696//1696 1697//1697 -f 1695//1695 1697//1697 1685//1685 -f 1685//1685 1697//1697 1698//1698 -f 1685//1685 1698//1698 1686//1686 -f 1688//1688 1699//1699 1687//1687 -f 1687//1687 1699//1699 1700//1700 -f 1687//1687 1700//1700 1689//1689 -f 1689//1689 1700//1700 1701//1701 -f 1689//1689 1701//1701 1690//1690 -f 1702//1702 1703//1703 1704//1704 -f 1704//1704 1703//1703 1705//1705 -f 1706//1706 1707//1707 1702//1702 -f 1702//1702 1707//1707 1708//1708 -f 1702//1702 1708//1708 1703//1703 -f 1705//1705 1709//1709 1704//1704 -f 1704//1704 1709//1709 1710//1710 -f 1704//1704 1710//1710 1711//1711 -f 1712//1712 1713//1713 1714//1714 -f 1714//1714 1713//1713 1711//1711 -f 1714//1714 1711//1711 1715//1715 -f 1715//1715 1711//1711 1710//1710 -f 1712//1712 1716//1716 1713//1713 -f 1713//1713 1716//1716 1717//1717 -f 1713//1713 1717//1717 1706//1706 -f 1706//1706 1717//1717 1718//1718 -f 1706//1706 1718//1718 1707//1707 -f 110//110 109//109 1719//1719 -f 1720//1720 1721//1721 1722//1722 -f 1723//1723 1724//1724 1725//1725 -f 1726//1726 1727//1727 1728//1728 -f 1728//1728 1727//1727 1729//1729 -f 1729//1729 1730//1730 1728//1728 -f 1728//1728 1730//1730 1731//1731 -f 1728//1728 1731//1731 1732//1732 -f 1732//1732 1731//1731 1733//1733 -f 1732//1732 1733//1733 1734//1734 -f 1735//1735 1736//1736 1737//1737 -f 1738//1738 1739//1739 1740//1740 -f 1741//1741 1742//1742 1733//1733 -f 1733//1733 1742//1742 1738//1738 -f 1740//1740 1743//1743 1738//1738 -f 1738//1738 1743//1743 1735//1735 -f 1738//1738 1735//1735 1733//1733 -f 1733//1733 1735//1735 1737//1737 -f 1733//1733 1737//1737 1734//1734 -f 1744//1744 1745//1745 1746//1746 -f 1747//1747 1748//1748 1749//1749 -f 1750//1750 1744//1744 1741//1741 -f 1725//1725 1742//1742 1723//1723 -f 1723//1723 1742//1742 1741//1741 -f 1723//1723 1741//1741 1751//1751 -f 1751//1751 1741//1741 1744//1744 -f 1751//1751 1744//1744 1752//1752 -f 1752//1752 1744//1744 1746//1746 -f 1748//1748 1747//1747 1753//1753 -f 1754//1754 1755//1755 1756//1756 -f 1757//1757 1758//1758 1759//1759 -f 1756//1756 1760//1760 1754//1754 -f 1754//1754 1760//1760 1759//1759 -f 1754//1754 1759//1759 1761//1761 -f 1761//1761 1759//1759 1762//1762 -f 1763//1763 1757//1757 1764//1764 -f 1764//1764 1757//1757 1759//1759 -f 1764//1764 1759//1759 1765//1765 -f 1765//1765 1759//1759 1760//1760 -f 1766//1766 1767//1767 1768//1768 -f 1768//1768 1767//1767 1769//1769 -f 1768//1768 1769//1769 1770//1770 -f 1770//1770 1769//1769 1771//1771 -f 1772//1772 1773//1773 1774//1774 -f 1774//1774 1773//1773 1775//1775 -f 1776//1776 1777//1777 1778//1778 -f 1778//1778 1777//1777 1779//1779 -f 1778//1778 1779//1779 1780//1780 -f 1780//1780 1779//1779 1781//1781 -f 1780//1780 1781//1781 1782//1782 -f 1782//1782 1781//1781 1783//1783 -f 1782//1782 1783//1783 1784//1784 -f 1784//1784 1783//1783 1785//1785 -f 1786//1786 1787//1787 1788//1788 -f 1788//1788 1787//1787 1789//1789 -f 1788//1788 1789//1789 1790//1790 -f 1722//1722 1791//1791 1720//1720 -f 1720//1720 1791//1791 1792//1792 -f 1720//1720 1792//1792 1793//1793 -f 1794//1794 1795//1795 1796//1796 -f 1796//1796 1795//1795 1797//1797 -f 1796//1796 1797//1797 1798//1798 -f 1799//1799 1800//1800 1792//1792 -f 1792//1792 1800//1800 1801//1801 -f 1801//1801 1802//1802 1787//1787 -f 1787//1787 1802//1802 1803//1803 -f 1804//1804 1796//1796 1805//1805 -f 1805//1805 1796//1796 1798//1798 -f 1805//1805 1798//1798 1806//1806 -f 1806//1806 1798//1798 1807//1807 -f 1806//1806 1807//1807 1791//1791 -f 1791//1791 1807//1807 1808//1808 -f 1791//1791 1808//1808 1792//1792 -f 1792//1792 1808//1808 1809//1809 -f 1792//1792 1809//1809 1799//1799 -f 1796//1796 1810//1810 1794//1794 -f 1794//1794 1810//1810 1811//1811 -f 1794//1794 1811//1811 1803//1803 -f 1803//1803 1811//1811 1812//1812 -f 1803//1803 1812//1812 1787//1787 -f 1787//1787 1812//1812 1813//1813 -f 1787//1787 1813//1813 1789//1789 -f 1814//1814 1815//1815 1792//1792 -f 1816//1816 1817//1817 1818//1818 -f 1818//1818 1817//1817 1819//1819 -f 1819//1819 1793//1793 1818//1818 -f 1818//1818 1793//1793 1792//1792 -f 1818//1818 1792//1792 1820//1820 -f 1820//1820 1792//1792 1815//1815 -f 1820//1820 1815//1815 1821//1821 -f 1821//1821 1815//1815 1822//1822 -f 1823//1823 1824//1824 1825//1825 -f 1825//1825 1824//1824 1826//1826 -f 1827//1827 1828//1828 1826//1826 -f 1829//1829 1830//1830 1827//1827 -f 1827//1827 1830//1830 1831//1831 -f 1832//1832 1833//1833 1834//1834 -f 1834//1834 1833//1833 1835//1835 -f 1834//1834 1835//1835 1814//1814 -f 1836//1836 1837//1837 1828//1828 -f 1828//1828 1837//1837 1838//1838 -f 1828//1828 1838//1838 1826//1826 -f 1839//1839 1840//1840 1829//1829 -f 1841//1841 1830//1830 1842//1842 -f 1842//1842 1830//1830 1829//1829 -f 1842//1842 1829//1829 1843//1843 -f 1843//1843 1829//1829 1840//1840 -f 1843//1843 1840//1840 1844//1844 -f 1844//1844 1840//1840 1845//1845 -f 1846//1846 1847//1847 1848//1848 -f 135//135 1849//1849 134//134 -f 134//134 1849//1849 1850//1850 -f 134//134 1850//1850 120//120 -f 1850//1850 1851//1851 120//120 -f 120//120 1851//1851 1852//1852 -f 120//120 1852//1852 118//118 -f 118//118 1852//1852 1853//1853 -f 118//118 1853//1853 116//116 -f 116//116 1853//1853 1854//1854 -f 116//116 1854//1854 1855//1855 -f 1855//1855 1854//1854 1856//1856 -f 1857//1857 1858//1858 1859//1859 -f 1859//1859 1858//1858 1860//1860 -f 1859//1859 1860//1860 1861//1861 -f 1861//1861 1860//1860 1862//1862 -f 1861//1861 1862//1862 135//135 -f 135//135 1862//1862 1863//1863 -f 135//135 1863//1863 1849//1849 -f 1864//1864 1865//1865 1866//1866 -f 1866//1866 1865//1865 1867//1867 -f 1866//1866 1867//1867 1868//1868 -f 1869//1869 1870//1870 1871//1871 -f 1871//1871 1870//1870 1872//1872 -f 1871//1871 1872//1872 114//114 -f 114//114 1872//1872 1873//1873 -f 1874//1874 109//109 1873//1873 -f 1873//1873 109//109 138//138 -f 1873//1873 138//138 114//114 -f 1874//1874 1875//1875 109//109 -f 109//109 1875//1875 1876//1876 -f 109//109 1876//1876 1719//1719 -f 1719//1719 1876//1876 1877//1877 -f 1719//1719 1877//1877 1878//1878 -f 1879//1879 86//86 1719//1719 -f 1719//1719 86//86 112//112 -f 1719//1719 112//112 110//110 -f 1730//1730 1880//1880 1731//1731 -f 1731//1731 1880//1880 1881//1881 -f 1731//1731 1881//1881 1879//1879 -f 1879//1879 1881//1881 1882//1882 -f 1879//1879 1882//1882 86//86 -f 1883//1883 1884//1884 1885//1885 -f 1885//1885 1884//1884 1886//1886 -f 1885//1885 1886//1886 1887//1887 -f 1887//1887 1886//1886 1888//1888 -f 1887//1887 1888//1888 1889//1889 -f 1889//1889 1888//1888 1890//1890 -f 1889//1889 1890//1890 1891//1891 -f 1892//1892 1893//1893 1894//1894 -f 1894//1894 1893//1893 1895//1895 -f 1894//1894 1895//1895 1896//1896 -f 1896//1896 1895//1895 1897//1897 -f 1896//1896 1897//1897 1898//1898 -f 1899//1899 1900//1900 1901//1901 -f 1901//1901 1900//1900 1741//1741 -f 1901//1901 1741//1741 1902//1902 -f 1902//1902 1741//1741 1733//1733 -f 1902//1902 1733//1733 1903//1903 -f 1904//1904 1905//1905 1892//1892 -f 1892//1892 1905//1905 1906//1906 -f 1892//1892 1906//1906 1907//1907 -f 1908//1908 1909//1909 1910//1910 -f 1910//1910 1909//1909 1911//1911 -f 1910//1910 1911//1911 1912//1912 -f 1912//1912 1911//1911 1913//1913 -f 1912//1912 1913//1913 1907//1907 -f 1907//1907 1913//1913 1884//1884 -f 1907//1907 1884//1884 1892//1892 -f 1892//1892 1884//1884 1883//1883 -f 1892//1892 1883//1883 1893//1893 -f 1914//1914 1915//1915 1916//1916 -f 1916//1916 1915//1915 1917//1917 -f 1916//1916 1917//1917 1899//1899 -f 1918//1918 1919//1919 1920//1920 -f 1920//1920 1919//1919 1769//1769 -f 1920//1920 1769//1769 1763//1763 -f 1763//1763 1769//1769 1767//1767 -f 1763//1763 1767//1767 1757//1757 -f 1747//1747 1921//1921 1922//1922 -f 1923//1923 1924//1924 1755//1755 -f 1755//1755 1924//1924 1753//1753 -f 1755//1755 1753//1753 1756//1756 -f 1756//1756 1753//1753 1747//1747 -f 1756//1756 1747//1747 1925//1925 -f 1925//1925 1747//1747 1922//1922 -f 1918//1918 1926//1926 1919//1919 -f 1919//1919 1926//1926 1927//1927 -f 1919//1919 1927//1927 1921//1921 -f 1921//1921 1927//1927 1928//1928 -f 1921//1921 1928//1928 1922//1922 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1935//1935 -f 1935//1935 1934//1934 1936//1936 -f 1935//1935 1936//1936 1937//1937 -f 1938//1938 1939//1939 1940//1940 -f 1940//1940 1939//1939 1941//1941 -f 1940//1940 1941//1941 1942//1942 -f 1942//1942 1941//1941 1943//1943 -f 1942//1942 1943//1943 1944//1944 -f 1944//1944 1943//1943 1945//1945 -f 1944//1944 1945//1945 1946//1946 -f 1947//1947 1948//1948 1949//1949 -f 1948//1948 1950//1950 1949//1949 -f 1949//1949 1950//1950 1951//1951 -f 1949//1949 1951//1951 1944//1944 -f 1944//1944 1951//1951 1952//1952 -f 1953//1953 1954//1954 1955//1955 -f 1955//1955 1954//1954 1956//1956 -f 1955//1955 1956//1956 1957//1957 -f 1957//1957 1956//1956 1958//1958 -f 1957//1957 1958//1958 1959//1959 -f 1960//1960 1961//1961 1962//1962 -f 1962//1962 1961//1961 1963//1963 -f 1962//1962 1963//1963 1964//1964 -f 1965//1965 1909//1909 1966//1966 -f 1966//1966 1909//1909 1908//1908 -f 1966//1966 1908//1908 1903//1903 -f 1960//1960 1967//1967 1961//1961 -f 1961//1961 1967//1967 1968//1968 -f 1961//1961 1968//1968 1966//1966 -f 1966//1966 1968//1968 1969//1969 -f 1966//1966 1969//1969 1965//1965 -f 1965//1965 1970//1970 1909//1909 -f 1909//1909 1970//1970 1971//1971 -f 1909//1909 1971//1971 1911//1911 -f 1911//1911 1971//1971 1972//1972 -f 1964//1964 1963//1963 1973//1973 -f 1973//1973 1963//1963 1974//1974 -f 1973//1973 1974//1974 1975//1975 -f 1976//1976 1977//1977 1900//1900 -f 1978//1978 1979//1979 1921//1921 -f 1921//1921 1979//1979 1980//1980 -f 1921//1921 1980//1980 1981//1981 -f 1899//1899 1917//1917 1900//1900 -f 1900//1900 1917//1917 1982//1982 -f 1900//1900 1982//1982 1976//1976 -f 1980//1980 1983//1983 1981//1981 -f 1981//1981 1983//1983 1984//1984 -f 1981//1981 1984//1984 1985//1985 -f 1984//1984 1986//1986 1985//1985 -f 1985//1985 1986//1986 1987//1987 -f 1985//1985 1987//1987 1915//1915 -f 1915//1915 1987//1987 1988//1988 -f 1915//1915 1988//1988 1917//1917 -f 1917//1917 1988//1988 1989//1989 -f 1917//1917 1989//1989 1982//1982 -f 1990//1990 1991//1991 1940//1940 -f 1940//1940 1991//1991 1992//1992 -f 1940//1940 1992//1992 1993//1993 -f 1993//1993 1992//1992 1994//1994 -f 1993//1993 1994//1994 1995//1995 -f 1996//1996 1997//1997 1998//1998 -f 1997//1997 1999//1999 1998//1998 -f 1998//1998 1999//1999 2000//2000 -f 1998//1998 2000//2000 2001//2001 -f 2001//2001 2000//2000 2002//2002 -f 2003//2003 2004//2004 1792//1792 -f 2005//2005 2006//2006 1825//1825 -f 2006//2006 2007//2007 1825//1825 -f 1825//1825 2007//2007 1898//1898 -f 1825//1825 1898//1898 1823//1823 -f 1823//1823 1898//1898 1897//1897 -f 2003//2003 1792//1792 2008//2008 -f 2008//2008 1792//1792 2009//2009 -f 2008//2008 2009//2009 2010//2010 -f 1838//1838 1834//1834 1826//1826 -f 1826//1826 1834//1834 1814//1814 -f 1826//1826 1814//1814 1825//1825 -f 1825//1825 1814//1814 1792//1792 -f 1825//1825 1792//1792 2005//2005 -f 2005//2005 1792//1792 2004//2004 -f 2007//2007 2011//2011 1898//1898 -f 1898//1898 2011//2011 2012//2012 -f 1898//1898 2012//2012 1896//1896 -f 1896//1896 2012//2012 2013//2013 -f 2010//2010 2009//2009 2014//2014 -f 2014//2014 2009//2009 2015//2015 -f 2014//2014 2015//2015 2016//2016 -f 2017//2017 2018//2018 1829//1829 -f 1829//1829 2018//2018 2019//2019 -f 2020//2020 2017//2017 1890//1890 -f 1890//1890 2017//2017 1829//1829 -f 1890//1890 1829//1829 1891//1891 -f 1891//1891 1829//1829 1827//1827 -f 1891//1891 1827//1827 2021//2021 -f 2021//2021 1827//1827 1826//1826 -f 2022//2022 2023//2023 1848//1848 -f 1848//1848 2023//2023 2024//2024 -f 1848//1848 2024//2024 2025//2025 -f 2019//2019 2022//2022 1829//1829 -f 1829//1829 2022//2022 1848//1848 -f 1829//1829 1848//1848 1839//1839 -f 1839//1839 1848//1848 1847//1847 -f 1839//1839 1847//1847 2026//2026 -f 2020//2020 1890//1890 2027//2027 -f 2027//2027 1890//1890 1888//1888 -f 2027//2027 1888//1888 2028//2028 -f 2024//2024 2029//2029 2025//2025 -f 2025//2025 2029//2029 2030//2030 -f 2025//2025 2030//2030 2031//2031 -f 2031//2031 2030//2030 2032//2032 -f 1856//1856 1857//1857 1855//1855 -f 1855//1855 1857//1857 1859//1859 -f 1855//1855 1859//1859 1998//1998 -f 1998//1998 1859//1859 2033//2033 -f 1998//1998 2033//2033 1996//1996 -f 1996//1996 2033//2033 2034//2034 -f 135//135 128//128 1861//1861 -f 1861//1861 128//128 2035//2035 -f 1861//1861 2035//2035 1859//1859 -f 1859//1859 2035//2035 2036//2036 -f 1859//1859 2036//2036 2033//2033 -f 2033//2033 2036//2036 1993//1993 -f 2033//2033 1993//1993 2034//2034 -f 2034//2034 1993//1993 1995//1995 -f 128//128 1846//1846 2035//2035 -f 2035//2035 1846//1846 1848//1848 -f 2035//2035 1848//1848 2036//2036 -f 2036//2036 1848//1848 2025//2025 -f 2036//2036 2025//2025 1993//1993 -f 1993//1993 2025//2025 2031//2031 -f 1993//1993 2031//2031 1940//1940 -f 1940//1940 2031//2031 1935//1935 -f 1940//1940 1935//1935 1938//1938 -f 1938//1938 1935//1935 1937//1937 -f 2002//2002 2037//2037 2001//2001 -f 2001//2001 2037//2037 2038//2038 -f 2001//2001 2038//2038 2039//2039 -f 2039//2039 2038//2038 2040//2040 -f 2039//2039 2040//2040 1955//1955 -f 1955//1955 2040//2040 2041//2041 -f 1955//1955 2041//2041 1953//1953 -f 1953//1953 2041//2041 2042//2042 -f 2037//2037 1990//1990 2038//2038 -f 2038//2038 1990//1990 1940//1940 -f 2038//2038 1940//1940 2040//2040 -f 2040//2040 1940//1940 1942//1942 -f 2040//2040 1942//1942 2041//2041 -f 2041//2041 1942//1942 1944//1944 -f 2041//2041 1944//1944 2042//2042 -f 2042//2042 1944//1944 1952//1952 -f 2013//2013 2016//2016 1896//1896 -f 1896//1896 2016//2016 2015//2015 -f 1896//1896 2015//2015 1894//1894 -f 1894//1894 2015//2015 2043//2043 -f 1894//1894 2043//2043 1892//1892 -f 1892//1892 2043//2043 2044//2044 -f 1892//1892 2044//2044 1904//1904 -f 1904//1904 2044//2044 2045//2045 -f 1801//1801 1787//1787 1792//1792 -f 1792//1792 1787//1787 1786//1786 -f 1792//1792 1786//1786 2009//2009 -f 2009//2009 1786//1786 2046//2046 -f 2009//2009 2046//2046 2015//2015 -f 2015//2015 2046//2046 1783//1783 -f 2015//2015 1783//1783 2043//2043 -f 2043//2043 1783//1783 1781//1781 -f 2043//2043 1781//1781 2044//2044 -f 2044//2044 1781//1781 1779//1779 -f 2044//2044 1779//1779 2045//2045 -f 2045//2045 1779//1779 1777//1777 -f 2045//2045 1777//1777 1775//1775 -f 1775//1775 1777//1777 1776//1776 -f 1775//1775 1776//1776 1774//1774 -f 2032//2032 2028//2028 2031//2031 -f 2031//2031 2028//2028 1888//1888 -f 2031//2031 1888//1888 1935//1935 -f 1935//1935 1888//1888 1886//1886 -f 1935//1935 1886//1886 1933//1933 -f 1933//1933 1886//1886 1884//1884 -f 1933//1933 1884//1884 1931//1931 -f 1931//1931 1884//1884 1913//1913 -f 1931//1931 1913//1913 1974//1974 -f 1974//1974 1913//1913 1911//1911 -f 1974//1974 1911//1911 1975//1975 -f 1975//1975 1911//1911 1972//1972 -f 1771//1771 1769//1769 2047//2047 -f 2047//2047 1769//1769 1919//1919 -f 2047//2047 1919//1919 2048//2048 -f 2048//2048 1919//1919 1921//1921 -f 2048//2048 1921//1921 2049//2049 -f 2049//2049 1921//1921 1981//1981 -f 2049//2049 1981//1981 1775//1775 -f 1775//1775 1981//1981 1985//1985 -f 1775//1775 1985//1985 2045//2045 -f 2045//2045 1985//1985 1915//1915 -f 2045//2045 1915//1915 1904//1904 -f 1904//1904 1915//1915 1914//1914 -f 1904//1904 1914//1914 1905//1905 -f 1959//1959 2050//2050 1957//1957 -f 1957//1957 2050//2050 2051//2051 -f 1957//1957 2051//2051 1871//1871 -f 1871//1871 2051//2051 1866//1866 -f 1871//1871 1866//1866 1869//1869 -f 1869//1869 1866//1866 1868//1868 -f 2050//2050 1947//1947 2051//2051 -f 2051//2051 1947//1947 1949//1949 -f 2051//2051 1949//1949 1866//1866 -f 1866//1866 1949//1949 2052//2052 -f 1866//1866 2052//2052 1864//1864 -f 1864//1864 2052//2052 2053//2053 -f 1946//1946 1929//1929 1944//1944 -f 1944//1944 1929//1929 1931//1931 -f 1944//1944 1931//1931 1949//1949 -f 1949//1949 1931//1931 1974//1974 -f 1949//1949 1974//1974 2052//2052 -f 2052//2052 1974//1974 1963//1963 -f 2052//2052 1963//1963 2053//2053 -f 2053//2053 1963//1963 1961//1961 -f 1903//1903 1733//1733 1966//1966 -f 1966//1966 1733//1733 1731//1731 -f 1966//1966 1731//1731 1961//1961 -f 1961//1961 1731//1731 1879//1879 -f 1961//1961 1879//1879 2053//2053 -f 2053//2053 1879//1879 1719//1719 -f 2053//2053 1719//1719 1864//1864 -f 1864//1864 1719//1719 1878//1878 -f 1864//1864 1878//1878 1865//1865 -f 1977//1977 1978//1978 1900//1900 -f 1900//1900 1978//1978 1921//1921 -f 1900//1900 1921//1921 1741//1741 -f 1741//1741 1921//1921 1747//1747 -f 1741//1741 1747//1747 1750//1750 -f 1750//1750 1747//1747 1749//1749 -f 1750//1750 1749//1749 2054//2054 -f 2054//2054 1749//1749 2055//2055 -f 2056//2056 2057//2057 2058//2058 -f 2058//2058 2057//2057 2059//2059 -f 2058//2058 2059//2059 2060//2060 -f 2060//2060 2059//2059 2061//2061 -f 2060//2060 2061//2061 2062//2062 -f 2063//2063 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2065//2065 2066//2066 2067//2067 -f 2067//2067 2066//2066 2068//2068 -f 2067//2067 2068//2068 2069//2069 -f 2070//2070 2071//2071 2072//2072 -f 2072//2072 2071//2071 2073//2073 -f 2072//2072 2073//2073 2074//2074 -f 2074//2074 2073//2073 2075//2075 -f 2074//2074 2075//2075 2076//2076 -f 2077//2077 2078//2078 1674//1674 -f 1674//1674 2078//2078 2079//2079 -f 1674//1674 2079//2079 1668//1668 -f 1668//1668 2079//2079 2080//2080 -f 1668//1668 2080//2080 2081//2081 -f 2081//2081 2080//2080 2082//2082 -f 2083//2083 2084//2084 1695//1695 -f 1695//1695 2084//2084 2085//2085 -f 1695//1695 2085//2085 1691//1691 -f 1691//1691 2085//2085 2086//2086 -f 1691//1691 2086//2086 2087//2087 -f 2087//2087 2086//2086 2088//2088 -f 2089//2089 2090//2090 1711//1711 -f 1711//1711 2090//2090 2091//2091 -f 1711//1711 2091//2091 1704//1704 -f 1704//1704 2091//2091 2092//2092 -f 1704//1704 2092//2092 2093//2093 -f 2093//2093 2092//2092 2094//2094 -f 2095//2095 2096//2096 2097//2097 -f 2097//2097 2096//2096 2098//2098 -f 2099//2099 2100//2100 2101//2101 -f 2102//2102 2103//2103 2104//2104 -f 2104//2104 2103//2103 2099//2099 -f 2104//2104 2099//2099 2105//2105 -f 2105//2105 2099//2099 2101//2101 -f 2102//2102 2106//2106 2103//2103 -f 2103//2103 2106//2106 2107//2107 -f 2103//2103 2107//2107 2095//2095 -f 2095//2095 2107//2107 2108//2108 -f 2095//2095 2108//2108 2096//2096 -f 2098//2098 2109//2109 2097//2097 -f 2097//2097 2109//2109 2110//2110 -f 2097//2097 2110//2110 2100//2100 -f 2100//2100 2110//2110 2111//2111 -f 2100//2100 2111//2111 2101//2101 -f 2112//2112 2113//2113 2114//2114 -f 2114//2114 2113//2113 2115//2115 -f 2116//2116 2117//2117 2118//2118 -f 2118//2118 2117//2117 2119//2119 -f 2118//2118 2119//2119 2120//2120 -f 2120//2120 2119//2119 2121//2121 -f 2120//2120 2121//2121 2122//2122 -f 2114//2114 2123//2123 2112//2112 -f 2112//2112 2123//2123 2124//2124 -f 2112//2112 2124//2124 2121//2121 -f 2121//2121 2124//2124 2125//2125 -f 2121//2121 2125//2125 2122//2122 -f 2116//2116 2126//2126 2117//2117 -f 2117//2117 2126//2126 2127//2127 -f 2117//2117 2127//2127 2113//2113 -f 2113//2113 2127//2127 2128//2128 -f 2113//2113 2128//2128 2115//2115 -f 2129//2129 2130//2130 2131//2131 -f 2131//2131 2130//2130 2132//2132 -f 2131//2131 2132//2132 2133//2133 -f 2133//2133 2132//2132 2134//2134 -f 2133//2133 2134//2134 2135//2135 -f 2136//2136 2137//2137 2100//2100 -f 2100//2100 2137//2137 2138//2138 -f 2100//2100 2138//2138 2097//2097 -f 2097//2097 2138//2138 2139//2139 -f 2097//2097 2139//2139 2140//2140 -f 2140//2140 2139//2139 2141//2141 -f 2142//2142 2143//2143 2144//2144 -f 2145//2145 2146//2146 2147//2147 -f 2142//2142 2144//2144 2147//2147 -f 2147//2147 2144//2144 2148//2148 -f 2147//2147 2148//2148 2145//2145 -f 2149//2149 2150//2150 2112//2112 -f 2112//2112 2150//2150 2151//2151 -f 2112//2112 2151//2151 2113//2113 -f 2113//2113 2151//2151 2152//2152 -f 2113//2113 2152//2152 2153//2153 -f 2153//2153 2152//2152 2154//2154 -f 2155//2155 1847//1847 2156//2156 -f 2156//2156 1847//1847 1846//1846 -f 2156//2156 1846//1846 128//128 -f 116//116 1855//1855 2157//2157 -f 2157//2157 1855//1855 1998//1998 -f 1998//1998 2001//2001 2157//2157 -f 2157//2157 2001//2001 2039//2039 -f 2157//2157 2039//2039 2158//2158 -f 2158//2158 2039//2039 1955//1955 -f 1955//1955 1957//1957 2158//2158 -f 2158//2158 1957//1957 1871//1871 -f 2158//2158 1871//1871 114//114 -f 1881//1881 2159//2159 1882//1882 -f 1882//1882 2159//2159 2160//2160 -f 1882//1882 2160//2160 86//86 -f 1881//1881 1880//1880 2159//2159 -f 2159//2159 1880//1880 2161//2161 -f 2159//2159 2161//2161 2162//2162 -f 2162//2162 2161//2161 1412//1412 -f 2162//2162 1412//1412 2163//2163 -f 2163//2163 1412//1412 1228//1228 -f 1729//1729 2164//2164 1730//1730 -f 1730//1730 2164//2164 2161//2161 -f 1730//1730 2161//2161 1880//1880 -f 2080//2080 1573//1573 2164//2164 -f 2164//2164 1573//1573 1231//1231 -f 2164//2164 1231//1231 1230//1230 -f 1729//1729 1727//1727 2164//2164 -f 2164//2164 1727//1727 2082//2082 -f 2164//2164 2082//2082 2080//2080 -f 2165//2165 1258//1258 1260//1260 -f 1736//1736 1735//1735 2078//2078 -f 2078//2078 1735//1735 2165//2165 -f 2078//2078 2165//2165 2079//2079 -f 2079//2079 2165//2165 1260//1260 -f 2079//2079 1260//1260 1570//1570 -f 2165//2165 1735//1735 2166//2166 -f 2166//2166 1735//1735 1743//1743 -f 2086//2086 1411//1411 2166//2166 -f 2166//2166 1411//1411 1410//1410 -f 2166//2166 1410//1410 1408//1408 -f 1743//1743 1740//1740 2166//2166 -f 2166//2166 1740//1740 2088//2088 -f 2166//2166 2088//2088 2086//2086 -f 1724//1724 1723//1723 2167//2167 -f 2167//2167 1403//1403 1402//1402 -f 1724//1724 2167//2167 2084//2084 -f 2084//2084 2167//2167 2085//2085 -f 2085//2085 2167//2167 1402//1402 -f 2085//2085 1402//1402 1404//1404 -f 1752//1752 2168//2168 1751//1751 -f 1751//1751 2168//2168 2167//2167 -f 1751//1751 2167//2167 1723//1723 -f 2092//2092 1576//1576 2168//2168 -f 2168//2168 1576//1576 1284//1284 -f 2168//2168 1284//1284 1283//1283 -f 1752//1752 1746//1746 2168//2168 -f 2168//2168 1746//1746 2094//2094 -f 2168//2168 2094//2094 2092//2092 -f 2169//2169 1274//1274 1280//1280 -f 2055//2055 1749//1749 2090//2090 -f 2090//2090 1749//1749 2169//2169 -f 2090//2090 2169//2169 2091//2091 -f 2091//2091 2169//2169 1280//1280 -f 2091//2091 1280//1280 1574//1574 -f 1753//1753 2170//2170 1748//1748 -f 1748//1748 2170//2170 2169//2169 -f 1748//1748 2169//2169 1749//1749 -f 2139//2139 1580//1580 2170//2170 -f 2170//2170 1580//1580 1440//1440 -f 2170//2170 1440//1440 1439//1439 -f 1753//1753 1924//1924 2170//2170 -f 2170//2170 1924//1924 2141//2141 -f 2170//2170 2141//2141 2139//2139 -f 2171//2171 1397//1397 1396//1396 -f 1762//1762 1759//1759 2137//2137 -f 2137//2137 1759//1759 2171//2171 -f 2137//2137 2171//2171 2138//2138 -f 2138//2138 2171//2171 1396//1396 -f 2138//2138 1396//1396 1577//1577 -f 2171//2171 1759//1759 2172//2172 -f 2172//2172 1759//1759 1758//1758 -f 2172//2172 1758//1758 1400//1400 -f 1400//1400 1758//1758 1757//1757 -f 1766//1766 2173//2173 1767//1767 -f 1767//1767 2173//2173 1400//1400 -f 1767//1767 1400//1400 1757//1757 -f 2173//2173 1766//1766 2174//2174 -f 2174//2174 1766//1766 1768//1768 -f 2174//2174 1768//1768 1770//1770 -f 1398//1398 1399//1399 2152//2152 -f 2152//2152 1399//1399 2174//2174 -f 2152//2152 2174//2174 2154//2154 -f 2154//2154 2174//2174 1770//1770 -f 2175//2175 1393//1393 1392//1392 -f 1772//1772 1774//1774 2150//2150 -f 2150//2150 1774//1774 2175//2175 -f 2150//2150 2175//2175 2151//2151 -f 2151//2151 2175//2175 1392//1392 -f 1774//1774 1776//1776 2175//2175 -f 2175//2175 1776//1776 1778//1778 -f 2175//2175 1778//1778 2176//2176 -f 2176//2176 1778//1778 1780//1780 -f 2176//2176 1780//1780 1782//1782 -f 2176//2176 1782//1782 1784//1784 -f 1386//1386 1388//1388 2177//2177 -f 2177//2177 1388//1388 2176//2176 -f 2177//2177 2176//2176 2178//2178 -f 2178//2178 2176//2176 1784//1784 -f 2179//2179 2180//2180 2181//2181 -f 2181//2181 2180//2180 2182//2182 -f 2181//2181 2182//2182 2183//2183 -f 2183//2183 2182//2182 2177//2177 -f 2183//2183 2177//2177 2184//2184 -f 2184//2184 2177//2177 2178//2178 -f 2185//2185 1383//1383 1382//1382 -f 1790//1790 1789//1789 2180//2180 -f 2180//2180 1789//1789 2185//2185 -f 2180//2180 2185//2185 2182//2182 -f 2182//2182 2185//2185 1382//1382 -f 2185//2185 1789//1789 2186//2186 -f 2186//2186 1789//1789 1813//1813 -f 2186//2186 1813//1813 1385//1385 -f 1385//1385 1813//1813 1812//1812 -f 1385//1385 1812//1812 1811//1811 -f 1385//1385 1811//1811 2187//2187 -f 2187//2187 1811//1811 1810//1810 -f 2187//2187 1810//1810 2188//2188 -f 2188//2188 1810//1810 1796//1796 -f 2188//2188 1796//1796 1804//1804 -f 1234//1234 1233//1233 2189//2189 -f 2189//2189 1233//1233 2188//2188 -f 2189//2189 2188//2188 2190//2190 -f 2190//2190 2188//2188 1804//1804 -f 2191//2191 2192//2192 2193//2193 -f 2193//2193 2192//2192 2194//2194 -f 2193//2193 2194//2194 2195//2195 -f 2195//2195 2194//2194 2189//2189 -f 2195//2195 2189//2189 2196//2196 -f 2196//2196 2189//2189 2190//2190 -f 2197//2197 1335//1335 1653//1653 -f 1721//1721 1720//1720 2192//2192 -f 2192//2192 1720//1720 2197//2197 -f 2192//2192 2197//2197 2194//2194 -f 2194//2194 2197//2197 1653//1653 -f 1819//1819 2198//2198 1793//1793 -f 1793//1793 2198//2198 2197//2197 -f 1793//1793 2197//2197 1720//1720 -f 2198//2198 1819//1819 1817//1817 -f 1348//1348 1337//1337 2199//2199 -f 2199//2199 1337//1337 2198//2198 -f 2199//2199 2198//2198 2200//2200 -f 2200//2200 2198//2198 1817//1817 -f 2201//2201 2202//2202 2203//2203 -f 2203//2203 2202//2202 2204//2204 -f 2203//2203 2204//2204 2205//2205 -f 2205//2205 2204//2204 2199//2199 -f 2205//2205 2199//2199 2206//2206 -f 2206//2206 2199//2199 2200//2200 -f 2207//2207 1342//1342 1340//1340 -f 1822//1822 1815//1815 2202//2202 -f 2202//2202 1815//1815 2207//2207 -f 2202//2202 2207//2207 2204//2204 -f 2204//2204 2207//2207 1340//1340 -f 1835//1835 2208//2208 1814//1814 -f 1814//1814 2208//2208 2207//2207 -f 1814//1814 2207//2207 1815//1815 -f 2208//2208 1835//1835 1833//1833 -f 1378//1378 1379//1379 2209//2209 -f 2209//2209 1379//1379 2208//2208 -f 2209//2209 2208//2208 2210//2210 -f 2210//2210 2208//2208 1833//1833 -f 2211//2211 2212//2212 2213//2213 -f 2213//2213 2212//2212 2214//2214 -f 2213//2213 2214//2214 2215//2215 -f 2215//2215 2214//2214 2209//2209 -f 2215//2215 2209//2209 2216//2216 -f 2216//2216 2209//2209 2210//2210 -f 1315//1315 1313//1313 2217//2217 -f 2217//2217 1313//1313 2214//2214 -f 2214//2214 2212//2212 2217//2217 -f 2217//2217 2212//2212 1836//1836 -f 2217//2217 1836//1836 1828//1828 -f 2217//2217 1828//1828 2218//2218 -f 2218//2218 1828//1828 1827//1827 -f 2218//2218 1827//1827 1831//1831 -f 1331//1331 1317//1317 2219//2219 -f 2219//2219 1317//1317 2218//2218 -f 2219//2219 2218//2218 2220//2220 -f 2220//2220 2218//2218 1831//1831 -f 2221//2221 2222//2222 2223//2223 -f 2223//2223 2222//2222 2224//2224 -f 2223//2223 2224//2224 2225//2225 -f 2225//2225 2224//2224 2219//2219 -f 2225//2225 2219//2219 2226//2226 -f 2226//2226 2219//2219 2220//2220 -f 2227//2227 1435//1435 1434//1434 -f 1845//1845 1840//1840 2222//2222 -f 2222//2222 1840//1840 2227//2227 -f 2222//2222 2227//2227 2224//2224 -f 2224//2224 2227//2227 1434//1434 -f 2026//2026 2228//2228 1839//1839 -f 1839//1839 2228//2228 2227//2227 -f 1839//1839 2227//2227 1840//1840 -f 2229//2229 1437//1437 1436//1436 -f 2026//2026 1847//1847 2228//2228 -f 2228//2228 1847//1847 2155//2155 -f 2228//2228 2155//2155 1436//1436 -f 1436//1436 2155//2155 2230//2230 -f 1436//1436 2230//2230 2229//2229 -f 1357//1357 2231//2231 1374//1374 -f 1374//1374 2231//2231 2232//2232 -f 1374//1374 2232//2232 1375//1375 -f 1375//1375 2232//2232 1377//1377 -f 2233//2233 1363//1363 2234//2234 -f 2234//2234 1363//1363 1362//1362 -f 2234//2234 1362//1362 1361//1361 -f 2235//2235 2236//2236 1365//1365 -f 1365//1365 1364//1364 2235//2235 -f 2235//2235 1364//1364 1618//1618 -f 2235//2235 1618//1618 1373//1373 -f 1472//1472 2237//2237 1367//1367 -f 1367//1367 2237//2237 2238//2238 -f 1367//1367 2238//2238 1368//1368 -f 2239//2239 2240//2240 2241//2241 -f 2241//2241 2240//2240 2242//2242 -f 1447//1447 2243//2243 1443//1443 -f 1443//1443 2243//2243 2244//2244 -f 1443//1443 2244//2244 1444//1444 -f 2245//2245 1460//1460 1459//1459 -f 2245//2245 1459//1459 2246//2246 -f 2246//2246 1459//1459 1465//1465 -f 2246//2246 1465//1465 1464//1464 -f 2247//2247 1461//1461 2248//2248 -f 2248//2248 1461//1461 1467//1467 -f 2248//2248 1467//1467 1466//1466 -f 2249//2249 1478//1478 1476//1476 -f 2249//2249 1476//1476 2250//2250 -f 2250//2250 1476//1476 1474//1474 -f 2250//2250 1474//1474 1473//1473 -f 2251//2251 2252//2252 2253//2253 -f 2253//2253 2252//2252 2254//2254 -f 2255//2255 2256//2256 2257//2257 -f 2257//2257 2256//2256 2183//2183 -f 2257//2257 2183//2183 1785//1785 -f 1785//1785 2183//2183 2184//2184 -f 2181//2181 2183//2183 2258//2258 -f 2258//2258 2183//2183 2259//2259 -f 2260//2260 2261//2261 2262//2262 -f 2262//2262 2261//2261 2181//2181 -f 2262//2262 2181//2181 2263//2263 -f 2263//2263 2181//2181 2258//2258 -f 2260//2260 2264//2264 2261//2261 -f 2261//2261 2264//2264 2265//2265 -f 2261//2261 2265//2265 2266//2266 -f 2266//2266 2265//2265 2267//2267 -f 2266//2266 2267//2267 2256//2256 -f 2256//2256 2267//2267 2268//2268 -f 2268//2268 2269//2269 2256//2256 -f 2256//2256 2269//2269 2270//2270 -f 2256//2256 2270//2270 2183//2183 -f 2183//2183 2270//2270 2271//2271 -f 2183//2183 2271//2271 2259//2259 -f 1788//1788 2179//2179 2272//2272 -f 2272//2272 2179//2179 2181//2181 -f 2272//2272 2181//2181 2273//2273 -f 2273//2273 2181//2181 2261//2261 -f 2255//2255 2274//2274 2256//2256 -f 2256//2256 2274//2274 2266//2266 -f 2274//2274 2273//2273 2266//2266 -f 2266//2266 2273//2273 2261//2261 -f 2272//2272 2273//2273 2275//2275 -f 2275//2275 2273//2273 2274//2274 -f 2275//2275 2274//2274 2276//2276 -f 2276//2276 2274//2274 2255//2255 -f 2276//2276 2255//2255 2257//2257 -f 1785//1785 1783//1783 2257//2257 -f 2257//2257 1783//1783 2276//2276 -f 1786//1786 2275//2275 2046//2046 -f 2046//2046 2275//2275 2276//2276 -f 2046//2046 2276//2276 1783//1783 -f 1786//1786 1788//1788 2275//2275 -f 2275//2275 1788//1788 2272//2272 -f 2277//2277 2278//2278 2279//2279 -f 2279//2279 2278//2278 2195//2195 -f 2279//2279 2195//2195 1805//1805 -f 1805//1805 2195//2195 2196//2196 -f 2280//2280 2193//2193 2281//2281 -f 2281//2281 2282//2282 2280//2280 -f 2280//2280 2282//2282 2283//2283 -f 2280//2280 2283//2283 2284//2284 -f 2284//2284 2283//2283 2285//2285 -f 2278//2278 2286//2286 2195//2195 -f 2195//2195 2286//2286 2287//2287 -f 2287//2287 2288//2288 2195//2195 -f 2195//2195 2288//2288 2289//2289 -f 2195//2195 2289//2289 2193//2193 -f 2193//2193 2289//2289 2290//2290 -f 2193//2193 2290//2290 2281//2281 -f 2285//2285 2291//2291 2284//2284 -f 2284//2284 2291//2291 2292//2292 -f 2284//2284 2292//2292 2278//2278 -f 2278//2278 2292//2292 2293//2293 -f 2278//2278 2293//2293 2286//2286 -f 1722//1722 2191//2191 2294//2294 -f 2294//2294 2191//2191 2193//2193 -f 2294//2294 2193//2193 2295//2295 -f 2295//2295 2193//2193 2280//2280 -f 2277//2277 2296//2296 2278//2278 -f 2278//2278 2296//2296 2284//2284 -f 2296//2296 2295//2295 2284//2284 -f 2284//2284 2295//2295 2280//2280 -f 2297//2297 2294//2294 2295//2295 -f 2277//2277 2279//2279 2298//2298 -f 2297//2297 2295//2295 2298//2298 -f 2298//2298 2295//2295 2296//2296 -f 2298//2298 2296//2296 2277//2277 -f 1806//1806 2298//2298 1805//1805 -f 1805//1805 2298//2298 2279//2279 -f 1791//1791 2297//2297 1806//1806 -f 1806//1806 2297//2297 2298//2298 -f 1722//1722 2294//2294 1791//1791 -f 1791//1791 2294//2294 2297//2297 -f 2258//2258 1629//1629 2263//2263 -f 2263//2263 1629//1629 1631//1631 -f 2263//2263 1631//1631 2262//2262 -f 2262//2262 1631//1631 1632//1632 -f 2262//2262 1632//1632 2260//2260 -f 2260//2260 1632//1632 1637//1637 -f 2260//2260 1637//1637 2264//2264 -f 2264//2264 1637//1637 1636//1636 -f 2264//2264 1636//1636 2265//2265 -f 2265//2265 1636//1636 1640//1640 -f 2265//2265 1640//1640 2267//2267 -f 2267//2267 1640//1640 1639//1639 -f 2267//2267 1639//1639 2268//2268 -f 2268//2268 1639//1639 1638//1638 -f 2268//2268 1638//1638 2269//2269 -f 2269//2269 1638//1638 1633//1633 -f 2269//2269 1633//1633 2270//2270 -f 2270//2270 1633//1633 1634//1634 -f 2270//2270 1634//1634 2271//2271 -f 2271//2271 1634//1634 1635//1635 -f 2271//2271 1635//1635 2259//2259 -f 2259//2259 1635//1635 1628//1628 -f 2259//2259 1628//1628 2258//2258 -f 2258//2258 1628//1628 1629//1629 -f 2286//2286 1662//1662 2287//2287 -f 2287//2287 1662//1662 1661//1661 -f 2287//2287 1661//1661 2288//2288 -f 2288//2288 1661//1661 1660//1660 -f 2288//2288 1660//1660 2289//2289 -f 2289//2289 1660//1660 1658//1658 -f 2289//2289 1658//1658 2290//2290 -f 2290//2290 1658//1658 1657//1657 -f 2290//2290 1657//1657 2281//2281 -f 2281//2281 1657//1657 1652//1652 -f 2281//2281 1652//1652 2282//2282 -f 2282//2282 1652//1652 1654//1654 -f 2282//2282 1654//1654 2283//2283 -f 2283//2283 1654//1654 1655//1655 -f 2283//2283 1655//1655 2285//2285 -f 2285//2285 1655//1655 1656//1656 -f 2285//2285 1656//1656 2291//2291 -f 2291//2291 1656//1656 1666//1666 -f 2291//2291 1666//1666 2292//2292 -f 2292//2292 1666//1666 1665//1665 -f 2292//2292 1665//1665 2293//2293 -f 2293//2293 1665//1665 1663//1663 -f 2293//2293 1663//1663 2286//2286 -f 2286//2286 1663//1663 1662//1662 -f 2299//2299 2300//2300 2301//2301 -f 2301//2301 2300//2300 2205//2205 -f 2301//2301 2205//2205 1816//1816 -f 1816//1816 2205//2205 2206//2206 -f 2302//2302 2203//2203 2303//2303 -f 2303//2303 2304//2304 2302//2302 -f 2302//2302 2304//2304 2305//2305 -f 2302//2302 2305//2305 2306//2306 -f 2306//2306 2305//2305 2307//2307 -f 2308//2308 2205//2205 2309//2309 -f 2309//2309 2205//2205 2300//2300 -f 2307//2307 2310//2310 2306//2306 -f 2306//2306 2310//2310 2311//2311 -f 2306//2306 2311//2311 2300//2300 -f 2300//2300 2311//2311 2312//2312 -f 2300//2300 2312//2312 2309//2309 -f 2308//2308 2313//2313 2205//2205 -f 2205//2205 2313//2313 2314//2314 -f 2205//2205 2314//2314 2203//2203 -f 2203//2203 2314//2314 2315//2315 -f 2203//2203 2315//2315 2303//2303 -f 1821//1821 2201//2201 2316//2316 -f 2316//2316 2201//2201 2203//2203 -f 2316//2316 2203//2203 2317//2317 -f 2317//2317 2203//2203 2302//2302 -f 2318//2318 2319//2319 2320//2320 -f 2320//2320 2319//2319 2215//2215 -f 2320//2320 2215//2215 1832//1832 -f 1832//1832 2215//2215 2216//2216 -f 2321//2321 2215//2215 2322//2322 -f 2322//2322 2215//2215 2319//2319 -f 2321//2321 2323//2323 2215//2215 -f 2215//2215 2323//2323 2324//2324 -f 2215//2215 2324//2324 2213//2213 -f 2325//2325 2326//2326 2327//2327 -f 2327//2327 2326//2326 2328//2328 -f 2325//2325 2329//2329 2326//2326 -f 2326//2326 2329//2329 2330//2330 -f 2326//2326 2330//2330 2319//2319 -f 2319//2319 2330//2330 2331//2331 -f 2319//2319 2331//2331 2322//2322 -f 2324//2324 2332//2332 2213//2213 -f 2213//2213 2332//2332 2333//2333 -f 2213//2213 2333//2333 2328//2328 -f 2328//2328 2333//2333 2334//2334 -f 2328//2328 2334//2334 2327//2327 -f 1837//1837 2211//2211 2335//2335 -f 2335//2335 2211//2211 2213//2213 -f 2335//2335 2213//2213 2336//2336 -f 2336//2336 2213//2213 2328//2328 -f 2337//2337 2338//2338 2339//2339 -f 2339//2339 2338//2338 2225//2225 -f 2339//2339 2225//2225 1841//1841 -f 1841//1841 2225//2225 2226//2226 -f 2340//2340 2341//2341 2342//2342 -f 2342//2342 2341//2341 2338//2338 -f 2343//2343 2223//2223 2344//2344 -f 2344//2344 2345//2345 2343//2343 -f 2343//2343 2345//2345 2346//2346 -f 2343//2343 2346//2346 2342//2342 -f 2342//2342 2346//2346 2347//2347 -f 2342//2342 2347//2347 2340//2340 -f 2341//2341 2348//2348 2338//2338 -f 2338//2338 2348//2348 2349//2349 -f 2338//2338 2349//2349 2225//2225 -f 2225//2225 2349//2349 2350//2350 -f 2350//2350 2351//2351 2225//2225 -f 2225//2225 2351//2351 2352//2352 -f 2225//2225 2352//2352 2223//2223 -f 2223//2223 2352//2352 2353//2353 -f 2223//2223 2353//2353 2344//2344 -f 1844//1844 2221//2221 2354//2354 -f 2354//2354 2221//2221 2223//2223 -f 2354//2354 2223//2223 2355//2355 -f 2355//2355 2223//2223 2343//2343 -f 2299//2299 2356//2356 2300//2300 -f 2300//2300 2356//2356 2306//2306 -f 2356//2356 2317//2317 2306//2306 -f 2306//2306 2317//2317 2302//2302 -f 2357//2357 2316//2316 2317//2317 -f 2299//2299 2301//2301 2358//2358 -f 2357//2357 2317//2317 2358//2358 -f 2358//2358 2317//2317 2356//2356 -f 2358//2358 2356//2356 2299//2299 -f 2318//2318 2359//2359 2319//2319 -f 2319//2319 2359//2359 2326//2326 -f 2359//2359 2336//2336 2326//2326 -f 2326//2326 2336//2336 2328//2328 -f 2360//2360 2335//2335 2336//2336 -f 2318//2318 2320//2320 2361//2361 -f 2360//2360 2336//2336 2361//2361 -f 2361//2361 2336//2336 2359//2359 -f 2361//2361 2359//2359 2318//2318 -f 2337//2337 2362//2362 2338//2338 -f 2338//2338 2362//2362 2342//2342 -f 2362//2362 2355//2355 2342//2342 -f 2342//2342 2355//2355 2343//2343 -f 2363//2363 2354//2354 2355//2355 -f 2337//2337 2339//2339 2364//2364 -f 2363//2363 2355//2355 2364//2364 -f 2364//2364 2355//2355 2362//2362 -f 2364//2364 2362//2362 2337//2337 -f 1818//1818 2358//2358 1816//1816 -f 1816//1816 2358//2358 2301//2301 -f 1820//1820 2357//2357 1818//1818 -f 1818//1818 2357//2357 2358//2358 -f 1821//1821 2316//2316 1820//1820 -f 1820//1820 2316//2316 2357//2357 -f 1834//1834 2361//2361 1832//1832 -f 1832//1832 2361//2361 2320//2320 -f 1838//1838 2360//2360 1834//1834 -f 1834//1834 2360//2360 2361//2361 -f 1837//1837 2335//2335 1838//1838 -f 1838//1838 2335//2335 2360//2360 -f 1842//1842 2364//2364 1841//1841 -f 1841//1841 2364//2364 2339//2339 -f 1843//1843 2363//2363 1842//1842 -f 1842//1842 2363//2363 2364//2364 -f 1844//1844 2354//2354 1843//1843 -f 1843//1843 2354//2354 2363//2363 -f 2309//2309 1350//1350 2308//2308 -f 2308//2308 1350//1350 1349//1349 -f 2308//2308 1349//1349 2313//2313 -f 2313//2313 1349//1349 1347//1347 -f 2313//2313 1347//1347 2314//2314 -f 2314//2314 1347//1347 1345//1345 -f 2314//2314 1345//1345 2315//2315 -f 2315//2315 1345//1345 1344//1344 -f 2315//2315 1344//1344 2303//2303 -f 2303//2303 1344//1344 1339//1339 -f 2303//2303 1339//1339 2304//2304 -f 2304//2304 1339//1339 1341//1341 -f 2304//2304 1341//1341 2305//2305 -f 2305//2305 1341//1341 1343//1343 -f 2305//2305 1343//1343 2307//2307 -f 2307//2307 1343//1343 1351//1351 -f 2307//2307 1351//1351 2310//2310 -f 2310//2310 1351//1351 1353//1353 -f 2310//2310 1353//1353 2311//2311 -f 2311//2311 1353//1353 1354//1354 -f 2311//2311 1354//1354 2312//2312 -f 2312//2312 1354//1354 1338//1338 -f 2312//2312 1338//1338 2309//2309 -f 2309//2309 1338//1338 1350//1350 -f 2322//2322 1222//1222 2321//2321 -f 2321//2321 1222//1222 1221//1221 -f 2321//2321 1221//1221 2323//2323 -f 2323//2323 1221//1221 1651//1651 -f 2323//2323 1651//1651 2324//2324 -f 2324//2324 1651//1651 1650//1650 -f 2324//2324 1650//1650 2332//2332 -f 2332//2332 1650//1650 1649//1649 -f 2332//2332 1649//1649 2333//2333 -f 2333//2333 1649//1649 1648//1648 -f 2333//2333 1648//1648 2334//2334 -f 2334//2334 1648//1648 1647//1647 -f 2334//2334 1647//1647 2327//2327 -f 2327//2327 1647//1647 1646//1646 -f 2327//2327 1646//1646 2325//2325 -f 2325//2325 1646//1646 1643//1643 -f 2325//2325 1643//1643 2329//2329 -f 2329//2329 1643//1643 1642//1642 -f 2329//2329 1642//1642 2330//2330 -f 2330//2330 1642//1642 1645//1645 -f 2330//2330 1645//1645 2331//2331 -f 2331//2331 1645//1645 1644//1644 -f 2331//2331 1644//1644 2322//2322 -f 2322//2322 1644//1644 1222//1222 -f 2349//2349 1333//1333 2350//2350 -f 2350//2350 1333//1333 1332//1332 -f 2350//2350 1332//1332 2351//2351 -f 2351//2351 1332//1332 1330//1330 -f 2351//2351 1330//1330 2352//2352 -f 2352//2352 1330//1330 1328//1328 -f 2352//2352 1328//1328 2353//2353 -f 2353//2353 1328//1328 1327//1327 -f 2353//2353 1327//1327 2344//2344 -f 2344//2344 1327//1327 1324//1324 -f 2344//2344 1324//1324 2345//2345 -f 2345//2345 1324//1324 1323//1323 -f 2345//2345 1323//1323 2346//2346 -f 2346//2346 1323//1323 1326//1326 -f 2346//2346 1326//1326 2347//2347 -f 2347//2347 1326//1326 1325//1325 -f 2347//2347 1325//1325 2340//2340 -f 2340//2340 1325//1325 1320//1320 -f 2340//2340 1320//1320 2341//2341 -f 2341//2341 1320//1320 1319//1319 -f 2341//2341 1319//1319 2348//2348 -f 2348//2348 1319//1319 1318//1318 -f 2348//2348 1318//1318 2349//2349 -f 2349//2349 1318//1318 1333//1333 -f 2145//2145 2117//2117 2146//2146 -f 2146//2146 2117//2117 2113//2113 -f 2146//2146 2113//2113 2047//2047 -f 2047//2047 2113//2113 2153//2153 -f 1773//1773 2149//2149 2143//2143 -f 2143//2143 2149//2149 2112//2112 -f 2143//2143 2112//2112 2144//2144 -f 2144//2144 2112//2112 2121//2121 -f 2145//2145 2148//2148 2117//2117 -f 2117//2117 2148//2148 2119//2119 -f 2148//2148 2144//2144 2119//2119 -f 2119//2119 2144//2144 2121//2121 -f 2048//2048 2147//2147 2047//2047 -f 2047//2047 2147//2147 2146//2146 -f 1775//1775 2142//2142 2049//2049 -f 2049//2049 2142//2142 2147//2147 -f 2049//2049 2147//2147 2048//2048 -f 1773//1773 2143//2143 1775//1775 -f 1775//1775 2143//2143 2142//2142 -f 2134//2134 2095//2095 2135//2135 -f 2135//2135 2095//2095 2097//2097 -f 2135//2135 2097//2097 1923//1923 -f 1923//1923 2097//2097 2140//2140 -f 1761//1761 2136//2136 2129//2129 -f 2129//2129 2136//2136 2100//2100 -f 2129//2129 2100//2100 2130//2130 -f 2130//2130 2100//2100 2099//2099 -f 2134//2134 2132//2132 2095//2095 -f 2095//2095 2132//2132 2103//2103 -f 2132//2132 2130//2130 2103//2103 -f 2103//2103 2130//2130 2099//2099 -f 1923//1923 1755//1755 2135//2135 -f 2135//2135 1755//1755 2133//2133 -f 1755//1755 1754//1754 2133//2133 -f 2133//2133 1754//1754 2131//2131 -f 1754//1754 1761//1761 2131//2131 -f 2131//2131 1761//1761 2129//2129 -f 2114//2114 1302//1302 2123//2123 -f 2123//2123 1302//1302 1301//1301 -f 2123//2123 1301//1301 2124//2124 -f 2124//2124 1301//1301 1300//1300 -f 2124//2124 1300//1300 2125//2125 -f 2125//2125 1300//1300 1298//1298 -f 2125//2125 1298//1298 2122//2122 -f 2122//2122 1298//1298 1297//1297 -f 2122//2122 1297//1297 2120//2120 -f 2120//2120 1297//1297 1295//1295 -f 2120//2120 1295//1295 2118//2118 -f 2118//2118 1295//1295 1294//1294 -f 2118//2118 1294//1294 2116//2116 -f 2116//2116 1294//1294 1311//1311 -f 2116//2116 1311//1311 2126//2126 -f 2126//2126 1311//1311 1309//1309 -f 2126//2126 1309//1309 2127//2127 -f 2127//2127 1309//1309 1307//1307 -f 2127//2127 1307//1307 2128//2128 -f 2128//2128 1307//1307 1305//1305 -f 2128//2128 1305//1305 2115//2115 -f 2115//2115 1305//1305 1304//1304 -f 2115//2115 1304//1304 2114//2114 -f 2114//2114 1304//1304 1302//1302 -f 2105//2105 1452//1452 2104//2104 -f 2104//2104 1452//1452 1451//1451 -f 2104//2104 1451//1451 2102//2102 -f 2102//2102 1451//1451 1450//1450 -f 2102//2102 1450//1450 2106//2106 -f 2106//2106 1450//1450 1448//1448 -f 2106//2106 1448//1448 2107//2107 -f 2107//2107 1448//1448 1446//1446 -f 2107//2107 1446//1446 2108//2108 -f 2108//2108 1446//1446 1445//1445 -f 2108//2108 1445//1445 2096//2096 -f 2096//2096 1445//1445 1442//1442 -f 2096//2096 1442//1442 2098//2098 -f 2098//2098 1442//1442 1441//1441 -f 2098//2098 1441//1441 2109//2109 -f 2109//2109 1441//1441 1457//1457 -f 2109//2109 1457//1457 2110//2110 -f 2110//2110 1457//1457 1456//1456 -f 2110//2110 1456//1456 2111//2111 -f 2111//2111 1456//1456 1454//1454 -f 2111//2111 1454//1454 2101//2101 -f 2101//2101 1454//1454 1453//1453 -f 2101//2101 1453//1453 2105//2105 -f 2105//2105 1453//1453 1452//1452 -f 2075//2075 1702//1702 2076//2076 -f 2076//2076 1702//1702 1704//1704 -f 2076//2076 1704//1704 1745//1745 -f 1745//1745 1704//1704 2093//2093 -f 2054//2054 2089//2089 2070//2070 -f 2070//2070 2089//2089 1711//1711 -f 2070//2070 1711//1711 2071//2071 -f 2071//2071 1711//1711 1713//1713 -f 2068//2068 1689//1689 2069//2069 -f 2069//2069 1689//1689 1691//1691 -f 2069//2069 1691//1691 1739//1739 -f 1739//1739 1691//1691 2087//2087 -f 1725//1725 2083//2083 2063//2063 -f 2063//2063 2083//2083 1695//1695 -f 2063//2063 1695//1695 2064//2064 -f 2064//2064 1695//1695 1685//1685 -f 2061//2061 1678//1678 2062//2062 -f 2062//2062 1678//1678 1668//1668 -f 2062//2062 1668//1668 1726//1726 -f 1726//1726 1668//1668 2081//2081 -f 1734//1734 2077//2077 2056//2056 -f 2056//2056 2077//2077 1674//1674 -f 2056//2056 1674//1674 2057//2057 -f 2057//2057 1674//1674 1677//1677 -f 2075//2075 2073//2073 1702//1702 -f 1702//1702 2073//2073 1706//1706 -f 2073//2073 2071//2071 1706//1706 -f 1706//1706 2071//2071 1713//1713 -f 2068//2068 2066//2066 1689//1689 -f 1689//1689 2066//2066 1687//1687 -f 2066//2066 2064//2064 1687//1687 -f 1687//1687 2064//2064 1685//1685 -f 2061//2061 2059//2059 1678//1678 -f 1678//1678 2059//2059 1671//1671 -f 2059//2059 2057//2057 1671//1671 -f 1671//1671 2057//2057 1677//1677 -f 1745//1745 1744//1744 2076//2076 -f 2076//2076 1744//1744 2074//2074 -f 1744//1744 1750//1750 2074//2074 -f 2074//2074 1750//1750 2072//2072 -f 1750//1750 2054//2054 2072//2072 -f 2072//2072 2054//2054 2070//2070 -f 1739//1739 1738//1738 2069//2069 -f 2069//2069 1738//1738 2067//2067 -f 1738//1738 1742//1742 2067//2067 -f 2067//2067 1742//1742 2065//2065 -f 1742//1742 1725//1725 2065//2065 -f 2065//2065 1725//1725 2063//2063 -f 1726//1726 1728//1728 2062//2062 -f 2062//2062 1728//1728 2060//2060 -f 1728//1728 1732//1732 2060//2060 -f 2060//2060 1732//1732 2058//2058 -f 1732//1732 1734//1734 2058//2058 -f 2058//2058 1734//1734 2056//2056 -f 1712//1712 1279//1279 1716//1716 -f 1716//1716 1279//1279 1278//1278 -f 1716//1716 1278//1278 1717//1717 -f 1717//1717 1278//1278 1273//1273 -f 1717//1717 1273//1273 1718//1718 -f 1718//1718 1273//1273 1290//1290 -f 1718//1718 1290//1290 1707//1707 -f 1707//1707 1290//1290 1289//1289 -f 1707//1707 1289//1289 1708//1708 -f 1708//1708 1289//1289 1287//1287 -f 1708//1708 1287//1287 1703//1703 -f 1703//1703 1287//1287 1286//1286 -f 1703//1703 1286//1286 1705//1705 -f 1705//1705 1286//1286 1285//1285 -f 1705//1705 1285//1285 1709//1709 -f 1709//1709 1285//1285 1293//1293 -f 1709//1709 1293//1293 1710//1710 -f 1710//1710 1293//1293 1292//1292 -f 1710//1710 1292//1292 1715//1715 -f 1715//1715 1292//1292 1291//1291 -f 1715//1715 1291//1291 1714//1714 -f 1714//1714 1291//1291 1281//1281 -f 1714//1714 1281//1281 1712//1712 -f 1712//1712 1281//1281 1279//1279 -f 1698//1698 1583//1583 1686//1686 -f 1686//1686 1583//1583 1582//1582 -f 1686//1686 1582//1582 1688//1688 -f 1688//1688 1582//1582 1593//1593 -f 1688//1688 1593//1593 1699//1699 -f 1699//1699 1593//1593 1592//1592 -f 1699//1699 1592//1592 1700//1700 -f 1700//1700 1592//1592 1591//1591 -f 1700//1700 1591//1591 1701//1701 -f 1701//1701 1591//1591 1588//1588 -f 1701//1701 1588//1588 1690//1690 -f 1690//1690 1588//1588 1589//1589 -f 1690//1690 1589//1589 1692//1692 -f 1692//1692 1589//1589 1590//1590 -f 1692//1692 1590//1590 1693//1693 -f 1693//1693 1590//1590 1587//1587 -f 1693//1693 1587//1587 1694//1694 -f 1694//1694 1587//1587 1586//1586 -f 1694//1694 1586//1586 1696//1696 -f 1696//1696 1586//1586 1585//1585 -f 1696//1696 1585//1585 1697//1697 -f 1697//1697 1585//1585 1584//1584 -f 1697//1697 1584//1584 1698//1698 -f 1698//1698 1584//1584 1583//1583 -f 1682//1682 1259//1259 1683//1683 -f 1683//1683 1259//1259 1257//1257 -f 1683//1683 1257//1257 1684//1684 -f 1684//1684 1257//1257 1256//1256 -f 1684//1684 1256//1256 1672//1672 -f 1672//1672 1256//1256 1267//1267 -f 1672//1672 1267//1267 1673//1673 -f 1673//1673 1267//1267 1269//1269 -f 1673//1673 1269//1269 1679//1679 -f 1679//1679 1269//1269 1271//1271 -f 1679//1679 1271//1271 1680//1680 -f 1680//1680 1271//1271 1272//1272 -f 1680//1680 1272//1272 1681//1681 -f 1681//1681 1272//1272 1266//1266 -f 1681//1681 1266//1266 1669//1669 -f 1669//1669 1266//1266 1265//1265 -f 1669//1669 1265//1265 1670//1670 -f 1670//1670 1265//1265 1264//1264 -f 1670//1670 1264//1264 1675//1675 -f 1675//1675 1264//1264 1263//1263 -f 1675//1675 1263//1263 1676//1676 -f 1676//1676 1263//1263 1261//1261 -f 1676//1676 1261//1261 1682//1682 -f 1682//1682 1261//1261 1259//1259 -f 2158//2158 114//114 2365//2365 -f 2365//2365 114//114 138//138 -f 2365//2365 138//138 2366//2366 -f 2366//2366 138//138 2367//2367 -f 2367//2367 138//138 109//109 -f 2367//2367 109//109 2368//2368 -f 2368//2368 109//109 2369//2369 -f 2369//2369 109//109 110//110 -f 2369//2369 110//110 2370//2370 -f 2370//2370 110//110 2371//2371 -f 2371//2371 110//110 112//112 -f 2371//2371 112//112 2372//2372 -f 2372//2372 112//112 2373//2373 -f 2373//2373 112//112 86//86 -f 2373//2373 86//86 2160//2160 -f 2156//2156 128//128 2374//2374 -f 2374//2374 128//128 135//135 -f 2374//2374 135//135 2375//2375 -f 2375//2375 135//135 2376//2376 -f 2376//2376 135//135 134//134 -f 2376//2376 134//134 2377//2377 -f 2377//2377 134//134 2378//2378 -f 2378//2378 134//134 120//120 -f 2378//2378 120//120 2379//2379 -f 2379//2379 120//120 2380//2380 -f 2380//2380 120//120 118//118 -f 2380//2380 118//118 2381//2381 -f 2381//2381 118//118 2382//2382 -f 2382//2382 118//118 116//116 -f 2382//2382 116//116 2157//2157 -f 2383//2383 1826//1826 1824//1824 -f 1824//1824 1823//1823 2383//2383 -f 2383//2383 1823//1823 1897//1897 -f 2383//2383 1897//1897 2384//2384 -f 2384//2384 1897//1897 1895//1895 -f 2384//2384 1895//1895 1893//1893 -f 1612//1612 2384//2384 1613//1613 -f 1613//1613 2384//2384 1614//1614 -f 1893//1893 1883//1883 2384//2384 -f 2384//2384 1883//1883 2385//2385 -f 2384//2384 2385//2385 1614//1614 -f 1614//1614 2385//2385 1480//1480 -f 1887//1887 2386//2386 1885//1885 -f 1885//1885 2386//2386 2385//2385 -f 1885//1885 2385//2385 1883//1883 -f 1887//1887 1889//1889 2386//2386 -f 2386//2386 1889//1889 1891//1891 -f 2386//2386 1891//1891 2021//2021 -f 2387//2387 2388//2388 2386//2386 -f 2021//2021 1826//1826 2386//2386 -f 2386//2386 1826//1826 2383//2383 -f 2386//2386 2383//2383 2387//2387 -f 2389//2389 2390//2390 2391//2391 -f 1901//1901 1902//1902 2391//2391 -f 2391//2391 1902//1902 2392//2392 -f 2391//2391 2392//2392 2389//2389 -f 2392//2392 1902//1902 1903//1903 -f 1903//1903 1908//1908 2392//2392 -f 2392//2392 1908//1908 1910//1910 -f 2392//2392 1910//1910 2393//2393 -f 2393//2393 1910//1910 1912//1912 -f 2393//2393 1912//1912 1907//1907 -f 1496//1496 2393//2393 1497//1497 -f 1497//1497 2393//2393 1499//1499 -f 1907//1907 1906//1906 2393//2393 -f 2393//2393 1906//1906 2394//2394 -f 2393//2393 2394//2394 1499//1499 -f 1499//1499 2394//2394 1501//1501 -f 1914//1914 2391//2391 1905//1905 -f 1905//1905 2391//2391 2394//2394 -f 1905//1905 2394//2394 1906//1906 -f 1914//1914 1916//1916 2391//2391 -f 2391//2391 1916//1916 1899//1899 -f 2391//2391 1899//1899 1901//1901 -f 2395//2395 1239//1239 1237//1237 -f 1515//1515 2396//2396 1237//1237 -f 1237//1237 2396//2396 2397//2397 -f 1237//1237 2397//2397 2395//2395 -f 1514//1514 2398//2398 1515//1515 -f 1515//1515 2398//2398 2399//2399 -f 1515//1515 2399//2399 2396//2396 -f 1512//1512 2400//2400 1514//1514 -f 1514//1514 2400//2400 2401//2401 -f 1514//1514 2401//2401 2398//2398 -f 1511//1511 2402//2402 1512//1512 -f 1512//1512 2402//2402 2403//2403 -f 1512//1512 2403//2403 2400//2400 -f 1510//1510 2404//2404 1511//1511 -f 1511//1511 2404//2404 2405//2405 -f 1511//1511 2405//2405 2402//2402 -f 1509//1509 2406//2406 1510//1510 -f 1510//1510 2406//2406 2407//2407 -f 1510//1510 2407//2407 2404//2404 -f 1505//1505 2408//2408 1509//1509 -f 1509//1509 2408//2408 2409//2409 -f 1509//1509 2409//2409 2406//2406 -f 1507//1507 2410//2410 1505//1505 -f 1505//1505 2410//2410 2411//2411 -f 1505//1505 2411//2411 2408//2408 -f 1520//1520 2412//2412 1507//1507 -f 1507//1507 2412//2412 2413//2413 -f 1507//1507 2413//2413 2410//2410 -f 1519//1519 2414//2414 1520//1520 -f 1520//1520 2414//2414 2415//2415 -f 1520//1520 2415//2415 2412//2412 -f 1517//1517 2416//2416 1519//1519 -f 1519//1519 2416//2416 2417//2417 -f 1519//1519 2417//2417 2414//2414 -f 1516//1516 2418//2418 1517//1517 -f 1517//1517 2418//2418 2419//2419 -f 1517//1517 2419//2419 2416//2416 -f 1526//1526 2420//2420 1516//1516 -f 1516//1516 2420//2420 2421//2421 -f 1516//1516 2421//2421 2418//2418 -f 1528//1528 2422//2422 1526//1526 -f 1526//1526 2422//2422 2423//2423 -f 1526//1526 2423//2423 2420//2420 -f 1529//1529 2424//2424 1528//1528 -f 1528//1528 2424//2424 2425//2425 -f 1528//1528 2425//2425 2422//2422 -f 1523//1523 2426//2426 1529//1529 -f 1529//1529 2426//2426 2427//2427 -f 1529//1529 2427//2427 2424//2424 -f 1525//1525 2428//2428 1523//1523 -f 1523//1523 2428//2428 2429//2429 -f 1523//1523 2429//2429 2426//2426 -f 1539//1539 2430//2430 1525//1525 -f 1525//1525 2430//2430 2431//2431 -f 1525//1525 2431//2431 2428//2428 -f 2395//2395 2432//2432 1239//1239 -f 1239//1239 2432//2432 2433//2433 -f 1239//1239 2433//2433 1539//1539 -f 1539//1539 2433//2433 2434//2434 -f 1539//1539 2434//2434 2430//2430 -f 2435//2435 2436//2436 2437//2437 -f 2437//2437 2436//2436 2438//2438 -f 2439//2439 2440//2440 2441//2441 -f 2441//2441 2440//2440 2442//2442 -f 2443//2443 2444//2444 2445//2445 -f 2446//2446 2447//2447 2444//2444 -f 2444//2444 2447//2447 2448//2448 -f 2444//2444 2448//2448 2445//2445 -f 2449//2449 2450//2450 2451//2451 -f 2451//2451 2450//2450 2452//2452 -f 2451//2451 2452//2452 2453//2453 -f 2454//2454 2455//2455 2456//2456 -f 2456//2456 2455//2455 2457//2457 -f 2440//2440 2458//2458 2442//2442 -f 2442//2442 2458//2458 2459//2459 -f 2442//2442 2459//2459 2460//2460 -f 2436//2436 2461//2461 2438//2438 -f 2438//2438 2461//2461 2462//2462 -f 2438//2438 2462//2462 2463//2463 -f 2464//2464 2465//2465 2437//2437 -f 2437//2437 2465//2465 2466//2466 -f 2437//2437 2466//2466 2435//2435 -f 2467//2467 2468//2468 2469//2469 -f 2469//2469 2468//2468 2470//2470 -f 2449//2449 2471//2471 2450//2450 -f 2450//2450 2471//2471 2472//2472 -f 2450//2450 2472//2472 2446//2446 -f 2446//2446 2472//2472 2473//2473 -f 2446//2446 2473//2473 2447//2447 -f 2453//2453 2452//2452 2474//2474 -f 2474//2474 2452//2452 2475//2475 -f 2474//2474 2475//2475 2476//2476 -f 2455//2455 2477//2477 2457//2457 -f 2457//2457 2477//2477 2478//2478 -f 2457//2457 2478//2478 2475//2475 -f 2475//2475 2478//2478 2479//2479 -f 2475//2475 2479//2479 2476//2476 -f 2459//2459 2480//2480 2460//2460 -f 2460//2460 2480//2480 2481//2481 -f 2460//2460 2481//2481 2456//2456 -f 2456//2456 2481//2481 2482//2482 -f 2456//2456 2482//2482 2454//2454 -f 2462//2462 2483//2483 2463//2463 -f 2463//2463 2483//2483 2484//2484 -f 2463//2463 2484//2484 2441//2441 -f 2441//2441 2484//2484 2485//2485 -f 2441//2441 2485//2485 2439//2439 -f 2468//2468 2486//2486 2470//2470 -f 2470//2470 2486//2486 2487//2487 -f 2470//2470 2487//2487 2464//2464 -f 2464//2464 2487//2487 2488//2488 -f 2464//2464 2488//2488 2465//2465 -f 2445//2445 2489//2489 2443//2443 -f 2443//2443 2489//2489 2490//2490 -f 2443//2443 2490//2490 2469//2469 -f 2469//2469 2490//2490 2491//2491 -f 2469//2469 2491//2491 2467//2467 -f 2492//2492 2438//2438 2493//2493 -f 2493//2493 2438//2438 2463//2463 -f 2493//2493 2463//2463 2494//2494 -f 2494//2494 2463//2463 2441//2441 -f 2494//2494 2441//2441 2495//2495 -f 2495//2495 2441//2441 2442//2442 -f 2495//2495 2442//2442 2496//2496 -f 2496//2496 2442//2442 2460//2460 -f 2496//2496 2460//2460 2497//2497 -f 2497//2497 2460//2460 2456//2456 -f 2497//2497 2456//2456 2498//2498 -f 2498//2498 2456//2456 2457//2457 -f 2498//2498 2457//2457 2499//2499 -f 2499//2499 2457//2457 2475//2475 -f 2499//2499 2475//2475 2500//2500 -f 2500//2500 2475//2475 2452//2452 -f 2500//2500 2452//2452 2501//2501 -f 2501//2501 2452//2452 2450//2450 -f 2501//2501 2450//2450 2502//2502 -f 2502//2502 2450//2450 2446//2446 -f 2502//2502 2446//2446 2503//2503 -f 2503//2503 2446//2446 2444//2444 -f 2503//2503 2444//2444 2504//2504 -f 2504//2504 2444//2444 2443//2443 -f 2504//2504 2443//2443 2505//2505 -f 2505//2505 2443//2443 2469//2469 -f 2505//2505 2469//2469 2506//2506 -f 2506//2506 2469//2469 2470//2470 -f 2506//2506 2470//2470 2507//2507 -f 2507//2507 2470//2470 2464//2464 -f 2507//2507 2464//2464 2508//2508 -f 2508//2508 2464//2464 2437//2437 -f 2508//2508 2437//2437 2492//2492 -f 2492//2492 2437//2437 2438//2438 -f 2509//2509 2507//2507 2510//2510 -f 2510//2510 2507//2507 2508//2508 -f 2510//2510 2508//2508 2511//2511 -f 2511//2511 2508//2508 2492//2492 -f 2511//2511 2492//2492 2512//2512 -f 2513//2513 2504//2504 2514//2514 -f 2514//2514 2504//2504 2505//2505 -f 2514//2514 2505//2505 2509//2509 -f 2509//2509 2505//2505 2506//2506 -f 2509//2509 2506//2506 2507//2507 -f 2515//2515 2500//2500 2516//2516 -f 2516//2516 2500//2500 2501//2501 -f 2516//2516 2501//2501 2517//2517 -f 2517//2517 2501//2501 2502//2502 -f 2517//2517 2502//2502 2513//2513 -f 2513//2513 2502//2502 2503//2503 -f 2513//2513 2503//2503 2504//2504 -f 2518//2518 2497//2497 2519//2519 -f 2519//2519 2497//2497 2498//2498 -f 2519//2519 2498//2498 2515//2515 -f 2515//2515 2498//2498 2499//2499 -f 2515//2515 2499//2499 2500//2500 -f 2492//2492 2493//2493 2512//2512 -f 2512//2512 2493//2493 2494//2494 -f 2512//2512 2494//2494 2520//2520 -f 2520//2520 2494//2494 2495//2495 -f 2520//2520 2495//2495 2518//2518 -f 2518//2518 2495//2495 2496//2496 -f 2518//2518 2496//2496 2497//2497 -f 2521//2521 2522//2522 2523//2523 -f 2524//2524 2522//2522 2521//2521 -f 2521//2521 2525//2525 2526//2526 -f 2527//2527 2525//2525 2521//2521 -f 2523//2523 2527//2527 2521//2521 -f 2521//2521 2528//2528 2529//2529 -f 2530//2530 2528//2528 2521//2521 -f 2526//2526 2530//2530 2521//2521 -f 2521//2521 2531//2531 2532//2532 -f 2533//2533 2531//2531 2521//2521 -f 2529//2529 2533//2533 2521//2521 -f 2532//2532 2524//2524 2521//2521 -f 2524//2524 2534//2534 2522//2522 -f 2522//2522 2534//2534 2535//2535 -f 2522//2522 2535//2535 2523//2523 -f 2523//2523 2535//2535 2536//2536 -f 2523//2523 2536//2536 2527//2527 -f 2527//2527 2536//2536 2537//2537 -f 2527//2527 2537//2537 2525//2525 -f 2525//2525 2537//2537 2538//2538 -f 2525//2525 2538//2538 2526//2526 -f 2526//2526 2538//2538 2539//2539 -f 2526//2526 2539//2539 2530//2530 -f 2530//2530 2539//2539 2540//2540 -f 2530//2530 2540//2540 2528//2528 -f 2528//2528 2540//2540 2541//2541 -f 2528//2528 2541//2541 2529//2529 -f 2529//2529 2541//2541 2542//2542 -f 2529//2529 2542//2542 2533//2533 -f 2533//2533 2542//2542 2543//2543 -f 2533//2533 2543//2543 2531//2531 -f 2531//2531 2543//2543 2544//2544 -f 2531//2531 2544//2544 2532//2532 -f 2532//2532 2544//2544 2545//2545 -f 2532//2532 2545//2545 2524//2524 -f 2524//2524 2545//2545 2534//2534 -f 2535//2535 1872//1872 2536//2536 -f 2536//2536 1872//1872 1870//1870 -f 2536//2536 1870//1870 2537//2537 -f 2537//2537 1870//1870 1869//1869 -f 2537//2537 1869//1869 2538//2538 -f 2538//2538 1869//1869 1868//1868 -f 2538//2538 1868//1868 2539//2539 -f 2539//2539 1868//1868 1867//1867 -f 2539//2539 1867//1867 2540//2540 -f 2540//2540 1867//1867 1865//1865 -f 2540//2540 1865//1865 2541//2541 -f 2541//2541 1865//1865 1878//1878 -f 2541//2541 1878//1878 2542//2542 -f 2542//2542 1878//1878 1877//1877 -f 2542//2542 1877//1877 2543//2543 -f 2543//2543 1877//1877 1876//1876 -f 2543//2543 1876//1876 2544//2544 -f 2544//2544 1876//1876 1875//1875 -f 2544//2544 1875//1875 2545//2545 -f 2545//2545 1875//1875 1874//1874 -f 2545//2545 1874//1874 2534//2534 -f 2534//2534 1874//1874 1873//1873 -f 2534//2534 1873//1873 2535//2535 -f 2535//2535 1873//1873 1872//1872 -f 2546//2546 2547//2547 2548//2548 -f 2549//2549 2547//2547 2546//2546 -f 2546//2546 2550//2550 2551//2551 -f 2552//2552 2550//2550 2546//2546 -f 2548//2548 2552//2552 2546//2546 -f 2546//2546 2553//2553 2554//2554 -f 2555//2555 2553//2553 2546//2546 -f 2551//2551 2555//2555 2546//2546 -f 2546//2546 2556//2556 2557//2557 -f 2558//2558 2556//2556 2546//2546 -f 2554//2554 2558//2558 2546//2546 -f 2557//2557 2549//2549 2546//2546 -f 2549//2549 2559//2559 2547//2547 -f 2547//2547 2559//2559 2560//2560 -f 2547//2547 2560//2560 2548//2548 -f 2548//2548 2560//2560 2561//2561 -f 2548//2548 2561//2561 2552//2552 -f 2552//2552 2561//2561 2562//2562 -f 2552//2552 2562//2562 2550//2550 -f 2550//2550 2562//2562 2563//2563 -f 2550//2550 2563//2563 2551//2551 -f 2551//2551 2563//2563 2564//2564 -f 2551//2551 2564//2564 2555//2555 -f 2555//2555 2564//2564 2565//2565 -f 2555//2555 2565//2565 2553//2553 -f 2553//2553 2565//2565 2566//2566 -f 2553//2553 2566//2566 2554//2554 -f 2554//2554 2566//2566 2567//2567 -f 2554//2554 2567//2567 2558//2558 -f 2558//2558 2567//2567 2568//2568 -f 2558//2558 2568//2568 2556//2556 -f 2556//2556 2568//2568 2569//2569 -f 2556//2556 2569//2569 2557//2557 -f 2557//2557 2569//2569 2570//2570 -f 2557//2557 2570//2570 2549//2549 -f 2549//2549 2570//2570 2559//2559 -f 2560//2560 1852//1852 2561//2561 -f 2561//2561 1852//1852 1851//1851 -f 2561//2561 1851//1851 2562//2562 -f 2562//2562 1851//1851 1850//1850 -f 2562//2562 1850//1850 2563//2563 -f 2563//2563 1850//1850 1849//1849 -f 2563//2563 1849//1849 2564//2564 -f 2564//2564 1849//1849 1863//1863 -f 2564//2564 1863//1863 2565//2565 -f 2565//2565 1863//1863 1862//1862 -f 2565//2565 1862//1862 2566//2566 -f 2566//2566 1862//1862 1860//1860 -f 2566//2566 1860//1860 2567//2567 -f 2567//2567 1860//1860 1858//1858 -f 2567//2567 1858//1858 2568//2568 -f 2568//2568 1858//1858 1857//1857 -f 2568//2568 1857//1857 2569//2569 -f 2569//2569 1857//1857 1856//1856 -f 2569//2569 1856//1856 2570//2570 -f 2570//2570 1856//1856 1854//1854 -f 2570//2570 1854//1854 2559//2559 -f 2559//2559 1854//1854 1853//1853 -f 2559//2559 1853//1853 2560//2560 -f 2560//2560 1853//1853 1852//1852 -f 2571//2571 2572//2572 2573//2573 -f 2574//2574 2572//2572 2571//2571 -f 2571//2571 2575//2575 2576//2576 -f 2577//2577 2575//2575 2571//2571 -f 2573//2573 2577//2577 2571//2571 -f 2571//2571 2578//2578 2579//2579 -f 2580//2580 2578//2578 2571//2571 -f 2576//2576 2580//2580 2571//2571 -f 2571//2571 2581//2581 2582//2582 -f 2583//2583 2581//2581 2571//2571 -f 2579//2579 2583//2583 2571//2571 -f 2582//2582 2574//2574 2571//2571 -f 2574//2574 2584//2584 2572//2572 -f 2572//2572 2584//2584 2585//2585 -f 2572//2572 2585//2585 2573//2573 -f 2573//2573 2585//2585 2586//2586 -f 2573//2573 2586//2586 2577//2577 -f 2577//2577 2586//2586 2587//2587 -f 2577//2577 2587//2587 2575//2575 -f 2575//2575 2587//2587 2588//2588 -f 2575//2575 2588//2588 2576//2576 -f 2576//2576 2588//2588 2589//2589 -f 2576//2576 2589//2589 2580//2580 -f 2580//2580 2589//2589 2590//2590 -f 2580//2580 2590//2590 2578//2578 -f 2578//2578 2590//2590 2591//2591 -f 2578//2578 2591//2591 2579//2579 -f 2579//2579 2591//2591 2592//2592 -f 2579//2579 2592//2592 2583//2583 -f 2583//2583 2592//2592 2593//2593 -f 2583//2583 2593//2593 2581//2581 -f 2581//2581 2593//2593 2594//2594 -f 2581//2581 2594//2594 2582//2582 -f 2582//2582 2594//2594 2595//2595 -f 2582//2582 2595//2595 2574//2574 -f 2574//2574 2595//2595 2584//2584 -f 2585//2585 1922//1922 2586//2586 -f 2586//2586 1922//1922 1928//1928 -f 2586//2586 1928//1928 2587//2587 -f 2587//2587 1928//1928 1927//1927 -f 2587//2587 1927//1927 2588//2588 -f 2588//2588 1927//1927 1926//1926 -f 2588//2588 1926//1926 2589//2589 -f 2589//2589 1926//1926 1918//1918 -f 2589//2589 1918//1918 2590//2590 -f 2590//2590 1918//1918 1920//1920 -f 2590//2590 1920//1920 2591//2591 -f 2591//2591 1920//1920 1763//1763 -f 2591//2591 1763//1763 2592//2592 -f 2592//2592 1763//1763 1764//1764 -f 2592//2592 1764//1764 2593//2593 -f 2593//2593 1764//1764 1765//1765 -f 2593//2593 1765//1765 2594//2594 -f 2594//2594 1765//1765 1760//1760 -f 2594//2594 1760//1760 2595//2595 -f 2595//2595 1760//1760 1756//1756 -f 2595//2595 1756//1756 2584//2584 -f 2584//2584 1756//1756 1925//1925 -f 2584//2584 1925//1925 2585//2585 -f 2585//2585 1925//1925 1922//1922 -f 2596//2596 2597//2597 2598//2598 -f 2599//2599 2597//2597 2596//2596 -f 2596//2596 2600//2600 2601//2601 -f 2602//2602 2600//2600 2596//2596 -f 2598//2598 2602//2602 2596//2596 -f 2596//2596 2603//2603 2604//2604 -f 2605//2605 2603//2603 2596//2596 -f 2601//2601 2605//2605 2596//2596 -f 2596//2596 2606//2606 2607//2607 -f 2608//2608 2606//2606 2596//2596 -f 2604//2604 2608//2608 2596//2596 -f 2607//2607 2599//2599 2596//2596 -f 2599//2599 2609//2609 2597//2597 -f 2597//2597 2609//2609 2610//2610 -f 2597//2597 2610//2610 2598//2598 -f 2598//2598 2610//2610 2611//2611 -f 2598//2598 2611//2611 2602//2602 -f 2602//2602 2611//2611 2612//2612 -f 2602//2602 2612//2612 2600//2600 -f 2600//2600 2612//2612 2613//2613 -f 2600//2600 2613//2613 2601//2601 -f 2601//2601 2613//2613 2614//2614 -f 2601//2601 2614//2614 2605//2605 -f 2605//2605 2614//2614 2615//2615 -f 2605//2605 2615//2615 2603//2603 -f 2603//2603 2615//2615 2616//2616 -f 2603//2603 2616//2616 2604//2604 -f 2604//2604 2616//2616 2617//2617 -f 2604//2604 2617//2617 2608//2608 -f 2608//2608 2617//2617 2618//2618 -f 2608//2608 2618//2618 2606//2606 -f 2606//2606 2618//2618 2619//2619 -f 2606//2606 2619//2619 2607//2607 -f 2607//2607 2619//2619 2620//2620 -f 2607//2607 2620//2620 2599//2599 -f 2599//2599 2620//2620 2609//2609 -f 2610//2610 1808//1808 2611//2611 -f 2611//2611 1808//1808 1807//1807 -f 2611//2611 1807//1807 2612//2612 -f 2612//2612 1807//1807 1798//1798 -f 2612//2612 1798//1798 2613//2613 -f 2613//2613 1798//1798 1797//1797 -f 2613//2613 1797//1797 2614//2614 -f 2614//2614 1797//1797 1795//1795 -f 2614//2614 1795//1795 2615//2615 -f 2615//2615 1795//1795 1794//1794 -f 2615//2615 1794//1794 2616//2616 -f 2616//2616 1794//1794 1803//1803 -f 2616//2616 1803//1803 2617//2617 -f 2617//2617 1803//1803 1802//1802 -f 2617//2617 1802//1802 2618//2618 -f 2618//2618 1802//1802 1801//1801 -f 2618//2618 1801//1801 2619//2619 -f 2619//2619 1801//1801 1800//1800 -f 2619//2619 1800//1800 2620//2620 -f 2620//2620 1800//1800 1799//1799 -f 2620//2620 1799//1799 2609//2609 -f 2609//2609 1799//1799 1809//1809 -f 2609//2609 1809//1809 2610//2610 -f 2610//2610 1809//1809 1808//1808 -f 1934//1934 2621//2621 1936//1936 -f 1936//1936 2621//2621 2622//2622 -f 1936//1936 2622//2622 1937//1937 -f 1937//1937 2622//2622 2623//2623 -f 1937//1937 2623//2623 1938//1938 -f 1938//1938 2623//2623 2624//2624 -f 1938//1938 2624//2624 1939//1939 -f 1939//1939 2624//2624 2625//2625 -f 1939//1939 2625//2625 1941//1941 -f 1941//1941 2625//2625 2626//2626 -f 1941//1941 2626//2626 1943//1943 -f 1943//1943 2626//2626 2627//2627 -f 1943//1943 2627//2627 1945//1945 -f 1945//1945 2627//2627 2628//2628 -f 1945//1945 2628//2628 1946//1946 -f 1946//1946 2628//2628 2629//2629 -f 1946//1946 2629//2629 1929//1929 -f 1929//1929 2629//2629 2630//2630 -f 1929//1929 2630//2630 1930//1930 -f 1930//1930 2630//2630 2631//2631 -f 1930//1930 2631//2631 1932//1932 -f 1932//1932 2631//2631 2632//2632 -f 1932//1932 2632//2632 1934//1934 -f 1934//1934 2632//2632 2621//2621 -f 2622//2622 2512//2512 2623//2623 -f 2623//2623 2512//2512 2520//2520 -f 2623//2623 2520//2520 2624//2624 -f 2624//2624 2520//2520 2518//2518 -f 2624//2624 2518//2518 2625//2625 -f 2625//2625 2518//2518 2519//2519 -f 2625//2625 2519//2519 2626//2626 -f 2626//2626 2519//2519 2515//2515 -f 2626//2626 2515//2515 2627//2627 -f 2627//2627 2515//2515 2516//2516 -f 2627//2627 2516//2516 2628//2628 -f 2628//2628 2516//2516 2517//2517 -f 2628//2628 2517//2517 2629//2629 -f 2629//2629 2517//2517 2513//2513 -f 2629//2629 2513//2513 2630//2630 -f 2630//2630 2513//2513 2514//2514 -f 2630//2630 2514//2514 2631//2631 -f 2631//2631 2514//2514 2509//2509 -f 2631//2631 2509//2509 2632//2632 -f 2632//2632 2509//2509 2510//2510 -f 2632//2632 2510//2510 2621//2621 -f 2621//2621 2510//2510 2511//2511 -f 2621//2621 2511//2511 2622//2622 -f 2622//2622 2511//2511 2512//2512 -f 1951//1951 2633//2633 1952//1952 -f 1952//1952 2633//2633 2634//2634 -f 1952//1952 2634//2634 2042//2042 -f 2042//2042 2634//2634 2635//2635 -f 2042//2042 2635//2635 1953//1953 -f 1953//1953 2635//2635 2636//2636 -f 1953//1953 2636//2636 1954//1954 -f 1954//1954 2636//2636 2637//2637 -f 1954//1954 2637//2637 1956//1956 -f 1956//1956 2637//2637 2638//2638 -f 1956//1956 2638//2638 1958//1958 -f 1958//1958 2638//2638 2639//2639 -f 1958//1958 2639//2639 1959//1959 -f 1959//1959 2639//2639 2640//2640 -f 1959//1959 2640//2640 2050//2050 -f 2050//2050 2640//2640 2641//2641 -f 2050//2050 2641//2641 1947//1947 -f 1947//1947 2641//2641 2642//2642 -f 1947//1947 2642//2642 1948//1948 -f 1948//1948 2642//2642 2643//2643 -f 1948//1948 2643//2643 1950//1950 -f 1950//1950 2643//2643 2644//2644 -f 1950//1950 2644//2644 1951//1951 -f 1951//1951 2644//2644 2633//2633 -f 2634//2634 1513//1513 2635//2635 -f 2635//2635 1513//1513 1236//1236 -f 2635//2635 1236//1236 2636//2636 -f 2636//2636 1236//1236 1238//1238 -f 2636//2636 1238//1238 2637//2637 -f 2637//2637 1238//1238 1240//1240 -f 2637//2637 1240//1240 2638//2638 -f 2638//2638 1240//1240 1249//1249 -f 2638//2638 1249//1249 2639//2639 -f 2639//2639 1249//1249 1251//1251 -f 2639//2639 1251//1251 2640//2640 -f 2640//2640 1251//1251 1253//1253 -f 2640//2640 1253//1253 2641//2641 -f 2641//2641 1253//1253 1248//1248 -f 2641//2641 1248//1248 2642//2642 -f 2642//2642 1248//1248 1247//1247 -f 2642//2642 1247//1247 2643//2643 -f 2643//2643 1247//1247 1245//1245 -f 2643//2643 1245//1245 2644//2644 -f 2644//2644 1245//1245 1244//1244 -f 2644//2644 1244//1244 2633//2633 -f 2633//2633 1244//1244 1243//1243 -f 2633//2633 1243//1243 2634//2634 -f 2634//2634 1243//1243 1513//1513 -f 1970//1970 2645//2645 1971//1971 -f 1971//1971 2645//2645 2646//2646 -f 1971//1971 2646//2646 1972//1972 -f 1972//1972 2646//2646 2647//2647 -f 1972//1972 2647//2647 1975//1975 -f 1975//1975 2647//2647 2648//2648 -f 1975//1975 2648//2648 1973//1973 -f 1973//1973 2648//2648 2649//2649 -f 1973//1973 2649//2649 1964//1964 -f 1964//1964 2649//2649 2650//2650 -f 1964//1964 2650//2650 1962//1962 -f 1962//1962 2650//2650 2651//2651 -f 1962//1962 2651//2651 1960//1960 -f 1960//1960 2651//2651 2652//2652 -f 1960//1960 2652//2652 1967//1967 -f 1967//1967 2652//2652 2653//2653 -f 1967//1967 2653//2653 1968//1968 -f 1968//1968 2653//2653 2654//2654 -f 1968//1968 2654//2654 1969//1969 -f 1969//1969 2654//2654 2655//2655 -f 1969//1969 2655//2655 1965//1965 -f 1965//1965 2655//2655 2656//2656 -f 1965//1965 2656//2656 1970//1970 -f 1970//1970 2656//2656 2645//2645 -f 2646//2646 1543//1543 2647//2647 -f 2647//2647 1543//1543 1542//1542 -f 2647//2647 1542//1542 2648//2648 -f 2648//2648 1542//1542 1547//1547 -f 2648//2648 1547//1547 2649//2649 -f 2649//2649 1547//1547 1546//1546 -f 2649//2649 1546//1546 2650//2650 -f 2650//2650 1546//1546 1545//1545 -f 2650//2650 1545//1545 2651//2651 -f 2651//2651 1545//1545 1544//1544 -f 2651//2651 1544//1544 2652//2652 -f 2652//2652 1544//1544 1552//1552 -f 2652//2652 1552//1552 2653//2653 -f 2653//2653 1552//1552 1551//1551 -f 2653//2653 1551//1551 2654//2654 -f 2654//2654 1551//1551 1549//1549 -f 2654//2654 1549//1549 2655//2655 -f 2655//2655 1549//1549 1548//1548 -f 2655//2655 1548//1548 2656//2656 -f 2656//2656 1548//1548 1541//1541 -f 2656//2656 1541//1541 2645//2645 -f 2645//2645 1541//1541 1540//1540 -f 2645//2645 1540//1540 2646//2646 -f 2646//2646 1540//1540 1543//1543 -f 1983//1983 2657//2657 1984//1984 -f 1984//1984 2657//2657 2658//2658 -f 1984//1984 2658//2658 1986//1986 -f 1986//1986 2658//2658 2659//2659 -f 1986//1986 2659//2659 1987//1987 -f 1987//1987 2659//2659 2660//2660 -f 1987//1987 2660//2660 1988//1988 -f 1988//1988 2660//2660 2661//2661 -f 1988//1988 2661//2661 1989//1989 -f 1989//1989 2661//2661 2662//2662 -f 1989//1989 2662//2662 1982//1982 -f 1982//1982 2662//2662 2663//2663 -f 1982//1982 2663//2663 1976//1976 -f 1976//1976 2663//2663 2664//2664 -f 1976//1976 2664//2664 1977//1977 -f 1977//1977 2664//2664 2665//2665 -f 1977//1977 2665//2665 1978//1978 -f 1978//1978 2665//2665 2666//2666 -f 1978//1978 2666//2666 1979//1979 -f 1979//1979 2666//2666 2667//2667 -f 1979//1979 2667//2667 1980//1980 -f 1980//1980 2667//2667 2668//2668 -f 1980//1980 2668//2668 1983//1983 -f 1983//1983 2668//2668 2657//2657 -f 2658//2658 1608//1608 2659//2659 -f 2659//2659 1608//1608 1609//1609 -f 2659//2659 1609//1609 2660//2660 -f 2660//2660 1609//1609 1607//1607 -f 2660//2660 1607//1607 2661//2661 -f 2661//2661 1607//1607 1606//1606 -f 2661//2661 1606//1606 2662//2662 -f 2662//2662 1606//1606 1605//1605 -f 2662//2662 1605//1605 2663//2663 -f 2663//2663 1605//1605 1598//1598 -f 2663//2663 1598//1598 2664//2664 -f 2664//2664 1598//1598 1597//1597 -f 2664//2664 1597//1597 2665//2665 -f 2665//2665 1597//1597 1601//1601 -f 2665//2665 1601//1601 2666//2666 -f 2666//2666 1601//1601 1600//1600 -f 2666//2666 1600//1600 2667//2667 -f 2667//2667 1600//1600 1599//1599 -f 2667//2667 1599//1599 2668//2668 -f 2668//2668 1599//1599 1596//1596 -f 2668//2668 1596//1596 2657//2657 -f 2657//2657 1596//1596 1595//1595 -f 2657//2657 1595//1595 2658//2658 -f 2658//2658 1595//1595 1608//1608 -f 1994//1994 2669//2669 1995//1995 -f 1995//1995 2669//2669 2670//2670 -f 1995//1995 2670//2670 2034//2034 -f 2034//2034 2670//2670 2671//2671 -f 2034//2034 2671//2671 1996//1996 -f 1996//1996 2671//2671 2672//2672 -f 1996//1996 2672//2672 1997//1997 -f 1997//1997 2672//2672 2673//2673 -f 1997//1997 2673//2673 1999//1999 -f 1999//1999 2673//2673 2674//2674 -f 1999//1999 2674//2674 2000//2000 -f 2000//2000 2674//2674 2675//2675 -f 2000//2000 2675//2675 2002//2002 -f 2002//2002 2675//2675 2676//2676 -f 2002//2002 2676//2676 2037//2037 -f 2037//2037 2676//2676 2677//2677 -f 2037//2037 2677//2677 1990//1990 -f 1990//1990 2677//2677 2678//2678 -f 1990//1990 2678//2678 1991//1991 -f 1991//1991 2678//2678 2679//2679 -f 1991//1991 2679//2679 1992//1992 -f 1992//1992 2679//2679 2680//2680 -f 1992//1992 2680//2680 1994//1994 -f 1994//1994 2680//2680 2669//2669 -f 2670//2670 1422//1422 2671//2671 -f 2671//2671 1422//1422 1424//1424 -f 2671//2671 1424//1424 2672//2672 -f 2672//2672 1424//1424 1425//1425 -f 2672//2672 1425//1425 2673//2673 -f 2673//2673 1425//1425 1428//1428 -f 2673//2673 1428//1428 2674//2674 -f 2674//2674 1428//1428 1533//1533 -f 2674//2674 1533//1533 2675//2675 -f 2675//2675 1533//1533 1535//1535 -f 2675//2675 1535//1535 2676//2676 -f 2676//2676 1535//1535 1537//1537 -f 2676//2676 1537//1537 2677//2677 -f 2677//2677 1537//1537 1538//1538 -f 2677//2677 1538//1538 2678//2678 -f 2678//2678 1538//1538 1522//1522 -f 2678//2678 1522//1522 2679//2679 -f 2679//2679 1522//1522 1521//1521 -f 2679//2679 1521//1521 2680//2680 -f 2680//2680 1521//1521 1530//1530 -f 2680//2680 1530//1530 2669//2669 -f 2669//2669 1530//1530 1420//1420 -f 2669//2669 1420//1420 2670//2670 -f 2670//2670 1420//1420 1422//1422 -f 2008//2008 2681//2681 2003//2003 -f 2003//2003 2681//2681 2682//2682 -f 2003//2003 2682//2682 2004//2004 -f 2004//2004 2682//2682 2683//2683 -f 2004//2004 2683//2683 2005//2005 -f 2005//2005 2683//2683 2684//2684 -f 2005//2005 2684//2684 2006//2006 -f 2006//2006 2684//2684 2685//2685 -f 2006//2006 2685//2685 2007//2007 -f 2007//2007 2685//2685 2686//2686 -f 2007//2007 2686//2686 2011//2011 -f 2011//2011 2686//2686 2687//2687 -f 2011//2011 2687//2687 2012//2012 -f 2012//2012 2687//2687 2688//2688 -f 2012//2012 2688//2688 2013//2013 -f 2013//2013 2688//2688 2689//2689 -f 2013//2013 2689//2689 2016//2016 -f 2016//2016 2689//2689 2690//2690 -f 2016//2016 2690//2690 2014//2014 -f 2014//2014 2690//2690 2691//2691 -f 2014//2014 2691//2691 2010//2010 -f 2010//2010 2691//2691 2692//2692 -f 2010//2010 2692//2692 2008//2008 -f 2008//2008 2692//2692 2681//2681 -f 2682//2682 1617//1617 2683//2683 -f 2683//2683 1617//1617 1627//1627 -f 2683//2683 1627//1627 2684//2684 -f 2684//2684 1627//1627 1626//1626 -f 2684//2684 1626//1626 2685//2685 -f 2685//2685 1626//1626 1625//1625 -f 2685//2685 1625//1625 2686//2686 -f 2686//2686 1625//1625 1624//1624 -f 2686//2686 1624//1624 2687//2687 -f 2687//2687 1624//1624 1623//1623 -f 2687//2687 1623//1623 2688//2688 -f 2688//2688 1623//1623 1622//1622 -f 2688//2688 1622//1622 2689//2689 -f 2689//2689 1622//1622 1619//1619 -f 2689//2689 1619//1619 2690//2690 -f 2690//2690 1619//1619 1620//1620 -f 2690//2690 1620//1620 2691//2691 -f 2691//2691 1620//1620 1621//1621 -f 2691//2691 1621//1621 2692//2692 -f 2692//2692 1621//1621 1616//1616 -f 2692//2692 1616//1616 2681//2681 -f 2681//2681 1616//1616 1615//1615 -f 2681//2681 1615//1615 2682//2682 -f 2682//2682 1615//1615 1617//1617 -f 2017//2017 2693//2693 2018//2018 -f 2018//2018 2693//2693 2694//2694 -f 2018//2018 2694//2694 2019//2019 -f 2019//2019 2694//2694 2695//2695 -f 2019//2019 2695//2695 2022//2022 -f 2022//2022 2695//2695 2696//2696 -f 2022//2022 2696//2696 2023//2023 -f 2023//2023 2696//2696 2697//2697 -f 2023//2023 2697//2697 2024//2024 -f 2024//2024 2697//2697 2698//2698 -f 2024//2024 2698//2698 2029//2029 -f 2029//2029 2698//2698 2699//2699 -f 2029//2029 2699//2699 2030//2030 -f 2030//2030 2699//2699 2700//2700 -f 2030//2030 2700//2700 2032//2032 -f 2032//2032 2700//2700 2701//2701 -f 2032//2032 2701//2701 2028//2028 -f 2028//2028 2701//2701 2702//2702 -f 2028//2028 2702//2702 2027//2027 -f 2027//2027 2702//2702 2703//2703 -f 2027//2027 2703//2703 2020//2020 -f 2020//2020 2703//2703 2704//2704 -f 2020//2020 2704//2704 2017//2017 -f 2017//2017 2704//2704 2693//2693 -f 2694//2694 1561//1561 2695//2695 -f 2695//2695 1561//1561 1560//1560 -f 2695//2695 1560//1560 2696//2696 -f 2696//2696 1560//1560 1558//1558 -f 2696//2696 1558//1558 2697//2697 -f 2697//2697 1558//1558 1565//1565 -f 2697//2697 1565//1565 2698//2698 -f 2698//2698 1565//1565 1564//1564 -f 2698//2698 1564//1564 2699//2699 -f 2699//2699 1564//1564 1569//1569 -f 2699//2699 1569//1569 2700//2700 -f 2700//2700 1569//1569 1568//1568 -f 2700//2700 1568//1568 2701//2701 -f 2701//2701 1568//1568 1567//1567 -f 2701//2701 1567//1567 2702//2702 -f 2702//2702 1567//1567 1566//1566 -f 2702//2702 1566//1566 2703//2703 -f 2703//2703 1566//1566 1554//1554 -f 2703//2703 1554//1554 2704//2704 -f 2704//2704 1554//1554 1553//1553 -f 2704//2704 1553//1553 2693//2693 -f 2693//2693 1553//1553 1556//1556 -f 2693//2693 1556//1556 2694//2694 -f 2694//2694 1556//1556 1561//1561 -f 2160//2160 2159//2159 2162//2162 -f 2160//2160 2162//2162 2705//2705 -f 2705//2705 2162//2162 2163//2163 -f 2705//2705 2163//2163 2706//2706 -f 2706//2706 2163//2163 1228//1228 -f 2706//2706 1228//1228 1227//1227 -f 1254//1254 2707//2707 2708//2708 -f 2707//2707 2709//2709 2710//2710 -f 2709//2709 2158//2158 2365//2365 -f 2709//2709 2365//2365 2710//2710 -f 2710//2710 2365//2365 2366//2366 -f 2710//2710 2366//2366 2711//2711 -f 2711//2711 2366//2366 2367//2367 -f 2711//2711 2367//2367 2712//2712 -f 2712//2712 2367//2367 2368//2368 -f 2712//2712 2368//2368 2713//2713 -f 2713//2713 2368//2368 2369//2369 -f 2713//2713 2369//2369 2714//2714 -f 2714//2714 2369//2369 2370//2370 -f 2714//2714 2370//2370 2715//2715 -f 2715//2715 2370//2370 2371//2371 -f 2715//2715 2371//2371 2716//2716 -f 2716//2716 2371//2371 2372//2372 -f 2716//2716 2372//2372 2717//2717 -f 2717//2717 2372//2372 2373//2373 -f 2717//2717 2373//2373 2718//2718 -f 2718//2718 2373//2373 2160//2160 -f 2718//2718 2160//2160 2705//2705 -f 2707//2707 2710//2710 2708//2708 -f 2708//2708 2710//2710 2711//2711 -f 2708//2708 2711//2711 2719//2719 -f 2719//2719 2711//2711 2712//2712 -f 2719//2719 2712//2712 2720//2720 -f 2720//2720 2712//2712 2713//2713 -f 2720//2720 2713//2713 2721//2721 -f 2721//2721 2713//2713 2714//2714 -f 2721//2721 2714//2714 2722//2722 -f 2722//2722 2714//2714 2715//2715 -f 2722//2722 2715//2715 2723//2723 -f 2723//2723 2715//2715 2716//2716 -f 2723//2723 2716//2716 2724//2724 -f 2724//2724 2716//2716 2717//2717 -f 2724//2724 2717//2717 2725//2725 -f 2725//2725 2717//2717 2718//2718 -f 2725//2725 2718//2718 2726//2726 -f 2726//2726 2718//2718 2705//2705 -f 2726//2726 2705//2705 2706//2706 -f 1254//1254 2708//2708 1255//1255 -f 1255//1255 2708//2708 2719//2719 -f 1255//1255 2719//2719 1246//1246 -f 1246//1246 2719//2719 2720//2720 -f 1246//1246 2720//2720 1413//1413 -f 1413//1413 2720//2720 2721//2721 -f 1413//1413 2721//2721 1414//1414 -f 1414//1414 2721//2721 2722//2722 -f 1414//1414 2722//2722 1417//1417 -f 1417//1417 2722//2722 2723//2723 -f 1417//1417 2723//2723 1418//1418 -f 1418//1418 2723//2723 2724//2724 -f 1418//1418 2724//2724 1419//1419 -f 1419//1419 2724//2724 2725//2725 -f 1419//1419 2725//2725 1416//1416 -f 1416//1416 2725//2725 2726//2726 -f 1416//1416 2726//2726 1415//1415 -f 1415//1415 2726//2726 2706//2706 -f 1415//1415 2706//2706 1227//1227 -f 1536//1536 1534//1534 2727//2727 -f 2157//2157 2158//2158 2709//2709 -f 2157//2157 2709//2709 2728//2728 -f 2728//2728 2709//2709 2707//2707 -f 2728//2728 2707//2707 2727//2727 -f 1254//1254 1252//1252 2707//2707 -f 2707//2707 1252//1252 1250//1250 -f 2707//2707 1250//1250 2727//2727 -f 2727//2727 1250//1250 1524//1524 -f 2727//2727 1524//1524 1536//1536 -f 1431//1431 2729//2729 2730//2730 -f 2729//2729 2731//2731 2732//2732 -f 2731//2731 2156//2156 2374//2374 -f 2731//2731 2374//2374 2732//2732 -f 2732//2732 2374//2374 2375//2375 -f 2732//2732 2375//2375 2733//2733 -f 2733//2733 2375//2375 2376//2376 -f 2733//2733 2376//2376 2734//2734 -f 2734//2734 2376//2376 2377//2377 -f 2734//2734 2377//2377 2735//2735 -f 2735//2735 2377//2377 2378//2378 -f 2735//2735 2378//2378 2736//2736 -f 2736//2736 2378//2378 2379//2379 -f 2736//2736 2379//2379 2737//2737 -f 2737//2737 2379//2379 2380//2380 -f 2737//2737 2380//2380 2738//2738 -f 2738//2738 2380//2380 2381//2381 -f 2738//2738 2381//2381 2739//2739 -f 2739//2739 2381//2381 2382//2382 -f 2739//2739 2382//2382 2740//2740 -f 2740//2740 2382//2382 2157//2157 -f 2740//2740 2157//2157 2728//2728 -f 2729//2729 2732//2732 2730//2730 -f 2730//2730 2732//2732 2733//2733 -f 2730//2730 2733//2733 2741//2741 -f 2741//2741 2733//2733 2734//2734 -f 2741//2741 2734//2734 2742//2742 -f 2742//2742 2734//2734 2735//2735 -f 2742//2742 2735//2735 2743//2743 -f 2743//2743 2735//2735 2736//2736 -f 2743//2743 2736//2736 2744//2744 -f 2744//2744 2736//2736 2737//2737 -f 2744//2744 2737//2737 2745//2745 -f 2745//2745 2737//2737 2738//2738 -f 2745//2745 2738//2738 2746//2746 -f 2746//2746 2738//2738 2739//2739 -f 2746//2746 2739//2739 2747//2747 -f 2747//2747 2739//2739 2740//2740 -f 2747//2747 2740//2740 2748//2748 -f 2748//2748 2740//2740 2728//2728 -f 2748//2748 2728//2728 2727//2727 -f 1431//1431 2730//2730 1432//1432 -f 1432//1432 2730//2730 2741//2741 -f 1432//1432 2741//2741 1433//1433 -f 1433//1433 2741//2741 2742//2742 -f 1433//1433 2742//2742 1641//1641 -f 1641//1641 2742//2742 2743//2743 -f 1641//1641 2743//2743 1426//1426 -f 1426//1426 2743//2743 2744//2744 -f 1426//1426 2744//2744 1427//1427 -f 1427//1427 2744//2744 2745//2745 -f 1427//1427 2745//2745 1430//1430 -f 1430//1430 2745//2745 2746//2746 -f 1430//1430 2746//2746 1429//1429 -f 1429//1429 2746//2746 2747//2747 -f 1429//1429 2747//2747 1531//1531 -f 1531//1531 2747//2747 2748//2748 -f 1531//1531 2748//2748 1532//1532 -f 1532//1532 2748//2748 2727//2727 -f 1532//1532 2727//2727 1534//1534 -f 2155//2155 2156//2156 2731//2731 -f 2155//2155 2731//2731 2230//2230 -f 2230//2230 2731//2731 2729//2729 -f 2230//2230 2729//2729 2229//2229 -f 2229//2229 2729//2729 1431//1431 -f 2229//2229 1431//1431 1437//1437 -f 2224//2224 1434//1434 1322//1322 -f 2224//2224 1322//1322 2219//2219 -f 2219//2219 1322//1322 1329//1329 -f 2219//2219 1329//1329 1331//1331 -f 2214//2214 1313//1313 1312//1312 -f 2214//2214 1312//1312 2209//2209 -f 2209//2209 1312//1312 1223//1223 -f 2209//2209 1223//1223 1378//1378 -f 2204//2204 1340//1340 2199//2199 -f 2199//2199 1340//1340 1346//1346 -f 2199//2199 1346//1346 1348//1348 -f 2189//2189 2194//2194 1653//1653 -f 1653//1653 1659//1659 2189//2189 -f 2189//2189 1659//1659 1235//1235 -f 2189//2189 1235//1235 1234//1234 -f 1382//1382 1381//1381 2182//2182 -f 2182//2182 1381//1381 1630//1630 -f 2182//2182 1630//1630 2177//2177 -f 2177//2177 1630//1630 1387//1387 -f 2177//2177 1387//1387 1386//1386 -f 1306//1306 1398//1398 2152//2152 -f 2151//2151 1392//1392 1299//1299 -f 2151//2151 1299//1299 2152//2152 -f 2152//2152 1299//1299 1303//1303 -f 2152//2152 1303//1303 1306//1306 -f 1580//1580 2139//2139 1579//1579 -f 1579//1579 2139//2139 2138//2138 -f 1579//1579 2138//2138 1578//1578 -f 1578//1578 2138//2138 1577//1577 -f 1576//1576 2092//2092 1575//1575 -f 1575//1575 2092//2092 2091//2091 -f 1575//1575 2091//2091 1574//1574 -f 1406//1406 1411//1411 2086//2086 -f 1406//1406 2086//2086 1405//1405 -f 1405//1405 2086//2086 2085//2085 -f 1405//1405 2085//2085 1404//1404 -f 2079//2079 1570//1570 1571//1571 -f 2079//2079 1571//1571 2080//2080 -f 2080//2080 1571//1571 1572//1572 -f 2080//2080 1572//1572 1573//1573 -f 1726//1726 2081//2081 1727//1727 -f 1727//1727 2081//2081 2082//2082 -f 1736//1736 2078//2078 1737//1737 -f 1737//1737 2078//2078 2077//2077 -f 1737//1737 2077//2077 1734//1734 -f 1739//1739 2087//2087 1740//1740 -f 1740//1740 2087//2087 2088//2088 -f 1724//1724 2084//2084 1725//1725 -f 1725//1725 2084//2084 2083//2083 -f 1745//1745 2093//2093 1746//1746 -f 1746//1746 2093//2093 2094//2094 -f 2055//2055 2090//2090 2054//2054 -f 2054//2054 2090//2090 2089//2089 -f 1923//1923 2140//2140 1924//1924 -f 1924//1924 2140//2140 2141//2141 -f 1762//1762 2137//2137 1761//1761 -f 1761//1761 2137//2137 2136//2136 -f 1845//1845 2222//2222 1844//1844 -f 1844//1844 2222//2222 2221//2221 -f 1841//1841 2226//2226 1830//1830 -f 1830//1830 2226//2226 2220//2220 -f 1830//1830 2220//2220 1831//1831 -f 1836//1836 2212//2212 1837//1837 -f 1837//1837 2212//2212 2211//2211 -f 1832//1832 2216//2216 1833//1833 -f 1833//1833 2216//2216 2210//2210 -f 1822//1822 2202//2202 1821//1821 -f 1821//1821 2202//2202 2201//2201 -f 1816//1816 2206//2206 1817//1817 -f 1817//1817 2206//2206 2200//2200 -f 1721//1721 2192//2192 1722//1722 -f 1722//1722 2192//2192 2191//2191 -f 1805//1805 2196//2196 1804//1804 -f 1804//1804 2196//2196 2190//2190 -f 2047//2047 2153//2153 1771//1771 -f 1771//1771 2153//2153 2154//2154 -f 1771//1771 2154//2154 1770//1770 -f 1772//1772 2150//2150 1773//1773 -f 1773//1773 2150//2150 2149//2149 -f 1785//1785 2184//2184 1784//1784 -f 1784//1784 2184//2184 2178//2178 -f 1790//1790 2180//2180 1788//1788 -f 1788//1788 2180//2180 2179//2179 -f 2228//2228 1436//1436 2227//2227 -f 2227//2227 1436//1436 1435//1435 -f 2218//2218 1317//1317 2217//2217 -f 2217//2217 1317//1317 1315//1315 -f 2208//2208 1379//1379 2207//2207 -f 2207//2207 1379//1379 1342//1342 -f 2198//2198 1337//1337 2197//2197 -f 2197//2197 1337//1337 1335//1335 -f 2188//2188 1233//1233 2187//2187 -f 2187//2187 1233//1233 1385//1385 -f 2186//2186 1385//1385 2185//2185 -f 2185//2185 1385//1385 1383//1383 -f 2164//2164 1230//1230 2161//2161 -f 2161//2161 1230//1230 1412//1412 -f 2166//2166 1408//1408 2165//2165 -f 2165//2165 1408//1408 1258//1258 -f 2168//2168 1283//1283 2167//2167 -f 2167//2167 1283//1283 1403//1403 -f 2170//2170 1439//1439 2169//2169 -f 2169//2169 1439//1439 1274//1274 -f 2174//2174 1399//1399 2173//2173 -f 2173//2173 1399//1399 1400//1400 -f 2172//2172 1400//1400 2171//2171 -f 2171//2171 1400//1400 1397//1397 -f 1393//1393 2175//2175 1394//1394 -f 1394//1394 2175//2175 2176//2176 -f 1394//1394 2176//2176 1389//1389 -f 1389//1389 2176//2176 1388//1388 -f 2388//2388 1493//1493 1562//1562 -f 1563//1563 1480//1480 2385//2385 -f 1563//1563 2385//2385 1562//1562 -f 1562//1562 2385//2385 2386//2386 -f 1562//1562 2386//2386 2388//2388 -f 1489//1489 2387//2387 1485//1485 -f 1485//1485 2387//2387 2383//2383 -f 1485//1485 2383//2383 1486//1486 -f 1486//1486 2383//2383 2384//2384 -f 1486//1486 2384//2384 1612//1612 -f 1503//1503 1501//1501 2394//2394 -f 1602//1602 1504//1504 2390//2390 -f 2390//2390 1504//1504 1503//1503 -f 2390//2390 1503//1503 2391//2391 -f 2391//2391 1503//1503 2394//2394 -f 2393//2393 1496//1496 2392//2392 -f 2392//2392 1496//1496 1495//1495 -f 2392//2392 1495//1495 2389//2389 -f 2389//2389 1495//1495 1225//1225 -f 2389//2389 1225//1225 1224//1224 -f 2387//2387 1489//1489 1488//1488 -f 2387//2387 1488//1488 2388//2388 -f 2388//2388 1488//1488 1491//1491 -f 2388//2388 1491//1491 1493//1493 -f 2389//2389 1224//1224 1604//1604 -f 2389//2389 1604//1604 2390//2390 -f 2390//2390 1604//1604 1603//1603 -f 2390//2390 1603//1603 1602//1602 -f 2234//2234 1361//1361 1360//1360 -f 2234//2234 1360//1360 2749//2749 -f 2749//2749 1360//1360 1359//1359 -f 2749//2749 1359//1359 2750//2750 -f 2750//2750 1359//1359 1365//1365 -f 2750//2750 1365//1365 2236//2236 -f 2242//2242 2240//2240 2751//2751 -f 2242//2242 2751//2751 2752//2752 -f 2752//2752 2751//2751 2753//2753 -f 2752//2752 2753//2753 2754//2754 -f 2754//2754 2753//2753 2233//2233 -f 2754//2754 2233//2233 2234//2234 -f 2231//2231 1357//1357 1356//1356 -f 2231//2231 1356//1356 2755//2755 -f 2755//2755 1356//1356 1667//1667 -f 2755//2755 1667//1667 2756//2756 -f 2756//2756 1667//1667 1363//1363 -f 2756//2756 1363//1363 2233//2233 -f 2236//2236 2757//2757 2758//2758 -f 2242//2242 2752//2752 2759//2759 -f 2757//2757 2760//2760 2758//2758 -f 2758//2758 2760//2760 2759//2759 -f 2758//2758 2759//2759 2761//2761 -f 2761//2761 2759//2759 2752//2752 -f 2761//2761 2752//2752 2754//2754 -f 2236//2236 2758//2758 2750//2750 -f 2750//2750 2758//2758 2761//2761 -f 2750//2750 2761//2761 2749//2749 -f 2749//2749 2761//2761 2754//2754 -f 2749//2749 2754//2754 2234//2234 -f 2760//2760 2242//2242 2759//2759 -f 2757//2757 2762//2762 2760//2760 -f 2760//2760 2762//2762 2242//2242 -f 2233//2233 2753//2753 2763//2763 -f 2240//2240 2764//2764 2765//2765 -f 2753//2753 2766//2766 2763//2763 -f 2763//2763 2766//2766 2765//2765 -f 2763//2763 2765//2765 2767//2767 -f 2767//2767 2765//2765 2764//2764 -f 2767//2767 2764//2764 2768//2768 -f 2233//2233 2763//2763 2756//2756 -f 2756//2756 2763//2763 2767//2767 -f 2756//2756 2767//2767 2755//2755 -f 2755//2755 2767//2767 2768//2768 -f 2755//2755 2768//2768 2231//2231 -f 2766//2766 2240//2240 2765//2765 -f 2753//2753 2751//2751 2766//2766 -f 2766//2766 2751//2751 2240//2240 -f 2235//2235 1373//1373 1371//1371 -f 2235//2235 1371//1371 2769//2769 -f 2769//2769 1371//1371 1370//1370 -f 2769//2769 1370//1370 2770//2770 -f 2770//2770 1370//1370 1368//1368 -f 2770//2770 1368//1368 2238//2238 -f 2241//2241 2242//2242 2762//2762 -f 2241//2241 2762//2762 2771//2771 -f 2771//2771 2762//2762 2757//2757 -f 2771//2771 2757//2757 2772//2772 -f 2772//2772 2757//2757 2236//2236 -f 2772//2772 2236//2236 2235//2235 -f 2240//2240 2239//2239 2773//2773 -f 2240//2240 2773//2773 2764//2764 -f 2764//2764 2773//2773 2774//2774 -f 2764//2764 2774//2774 2768//2768 -f 2768//2768 2774//2774 2232//2232 -f 2768//2768 2232//2232 2231//2231 -f 2237//2237 1472//1472 1470//1470 -f 2237//2237 1470//1470 2775//2775 -f 2775//2775 1470//1470 1391//1391 -f 2775//2775 1391//1391 2776//2776 -f 2776//2776 1391//1391 1377//1377 -f 2776//2776 1377//1377 2232//2232 -f 2238//2238 2777//2777 2778//2778 -f 2241//2241 2771//2771 2779//2779 -f 2777//2777 2780//2780 2778//2778 -f 2778//2778 2780//2780 2779//2779 -f 2778//2778 2779//2779 2781//2781 -f 2781//2781 2779//2779 2771//2771 -f 2781//2781 2771//2771 2772//2772 -f 2238//2238 2778//2778 2770//2770 -f 2770//2770 2778//2778 2781//2781 -f 2770//2770 2781//2781 2769//2769 -f 2769//2769 2781//2781 2772//2772 -f 2769//2769 2772//2772 2235//2235 -f 2780//2780 2241//2241 2779//2779 -f 2777//2777 2782//2782 2780//2780 -f 2780//2780 2782//2782 2241//2241 -f 2232//2232 2774//2774 2783//2783 -f 2239//2239 2784//2784 2785//2785 -f 2774//2774 2786//2786 2783//2783 -f 2783//2783 2786//2786 2785//2785 -f 2783//2783 2785//2785 2787//2787 -f 2787//2787 2785//2785 2784//2784 -f 2787//2787 2784//2784 2788//2788 -f 2232//2232 2783//2783 2776//2776 -f 2776//2776 2783//2783 2787//2787 -f 2776//2776 2787//2787 2775//2775 -f 2775//2775 2787//2787 2788//2788 -f 2775//2775 2788//2788 2237//2237 -f 2786//2786 2239//2239 2785//2785 -f 2774//2774 2773//2773 2786//2786 -f 2786//2786 2773//2773 2239//2239 -f 2239//2239 2241//2241 2782//2782 -f 2239//2239 2782//2782 2784//2784 -f 2784//2784 2782//2782 2777//2777 -f 2784//2784 2777//2777 2788//2788 -f 2788//2788 2777//2777 2238//2238 -f 2788//2788 2238//2238 2237//2237 -f 2246//2246 1464//1464 1463//1463 -f 2246//2246 1463//1463 2789//2789 -f 2789//2789 1463//1463 1462//1462 -f 2789//2789 1462//1462 2790//2790 -f 2790//2790 1462//1462 1461//1461 -f 2790//2790 1461//1461 2247//2247 -f 2245//2245 2246//2246 2791//2791 -f 2245//2245 2791//2791 2792//2792 -f 2792//2792 2791//2791 2793//2793 -f 2792//2792 2793//2793 2794//2794 -f 2794//2794 2793//2793 2254//2254 -f 2794//2794 2254//2254 2252//2252 -f 2243//2243 1447//1447 1449//1449 -f 2243//2243 1449//1449 2795//2795 -f 2795//2795 1449//1449 1458//1458 -f 2795//2795 1458//1458 2796//2796 -f 2796//2796 1458//1458 1460//1460 -f 2796//2796 1460//1460 2245//2245 -f 2247//2247 2797//2797 2798//2798 -f 2254//2254 2793//2793 2799//2799 -f 2797//2797 2800//2800 2798//2798 -f 2798//2798 2800//2800 2799//2799 -f 2798//2798 2799//2799 2801//2801 -f 2801//2801 2799//2799 2793//2793 -f 2801//2801 2793//2793 2791//2791 -f 2247//2247 2798//2798 2790//2790 -f 2790//2790 2798//2798 2801//2801 -f 2790//2790 2801//2801 2789//2789 -f 2789//2789 2801//2801 2791//2791 -f 2789//2789 2791//2791 2246//2246 -f 2800//2800 2254//2254 2799//2799 -f 2797//2797 2802//2802 2800//2800 -f 2800//2800 2802//2802 2254//2254 -f 2245//2245 2792//2792 2803//2803 -f 2252//2252 2804//2804 2805//2805 -f 2792//2792 2806//2806 2803//2803 -f 2803//2803 2806//2806 2805//2805 -f 2803//2803 2805//2805 2807//2807 -f 2807//2807 2805//2805 2804//2804 -f 2807//2807 2804//2804 2808//2808 -f 2245//2245 2803//2803 2796//2796 -f 2796//2796 2803//2803 2807//2807 -f 2796//2796 2807//2807 2795//2795 -f 2795//2795 2807//2807 2808//2808 -f 2795//2795 2808//2808 2243//2243 -f 2806//2806 2252//2252 2805//2805 -f 2792//2792 2794//2794 2806//2806 -f 2806//2806 2794//2794 2252//2252 -f 2248//2248 1466//1466 1471//1471 -f 2248//2248 1471//1471 2809//2809 -f 2809//2809 1471//1471 1479//1479 -f 2809//2809 1479//1479 2810//2810 -f 2810//2810 1479//1479 1478//1478 -f 2810//2810 1478//1478 2249//2249 -f 2247//2247 2248//2248 2811//2811 -f 2247//2247 2811//2811 2797//2797 -f 2797//2797 2811//2811 2812//2812 -f 2797//2797 2812//2812 2802//2802 -f 2802//2802 2812//2812 2253//2253 -f 2802//2802 2253//2253 2254//2254 -f 2244//2244 2243//2243 2808//2808 -f 2244//2244 2808//2808 2813//2813 -f 2813//2813 2808//2808 2804//2804 -f 2813//2813 2804//2804 2814//2814 -f 2814//2814 2804//2804 2252//2252 -f 2814//2814 2252//2252 2251//2251 -f 2250//2250 1473//1473 1277//1277 -f 2250//2250 1277//1277 2815//2815 -f 2815//2815 1277//1277 1276//1276 -f 2815//2815 1276//1276 2816//2816 -f 2816//2816 1276//1276 1444//1444 -f 2816//2816 1444//1444 2244//2244 -f 2249//2249 2817//2817 2818//2818 -f 2253//2253 2812//2812 2819//2819 -f 2817//2817 2820//2820 2818//2818 -f 2818//2818 2820//2820 2819//2819 -f 2818//2818 2819//2819 2821//2821 -f 2821//2821 2819//2819 2812//2812 -f 2821//2821 2812//2812 2811//2811 -f 2249//2249 2818//2818 2810//2810 -f 2810//2810 2818//2818 2821//2821 -f 2810//2810 2821//2821 2809//2809 -f 2809//2809 2821//2821 2811//2811 -f 2809//2809 2811//2811 2248//2248 -f 2820//2820 2253//2253 2819//2819 -f 2817//2817 2822//2822 2820//2820 -f 2820//2820 2822//2822 2253//2253 -f 2244//2244 2813//2813 2823//2823 -f 2251//2251 2824//2824 2825//2825 -f 2813//2813 2826//2826 2823//2823 -f 2823//2823 2826//2826 2825//2825 -f 2823//2823 2825//2825 2827//2827 -f 2827//2827 2825//2825 2824//2824 -f 2827//2827 2824//2824 2828//2828 -f 2244//2244 2823//2823 2816//2816 -f 2816//2816 2823//2823 2827//2827 -f 2816//2816 2827//2827 2815//2815 -f 2815//2815 2827//2827 2828//2828 -f 2815//2815 2828//2828 2250//2250 -f 2826//2826 2251//2251 2825//2825 -f 2813//2813 2814//2814 2826//2826 -f 2826//2826 2814//2814 2251//2251 -f 2249//2249 2250//2250 2828//2828 -f 2249//2249 2828//2828 2817//2817 -f 2817//2817 2828//2828 2824//2824 -f 2817//2817 2824//2824 2822//2822 -f 2822//2822 2824//2824 2251//2251 -f 2822//2822 2251//2251 2253//2253 -f 2461//2461 2829//2829 2462//2462 -f 2462//2462 2829//2829 2830//2830 -f 2462//2462 2830//2830 2483//2483 -f 2483//2483 2830//2830 2831//2831 -f 2483//2483 2831//2831 2484//2484 -f 2484//2484 2831//2831 2832//2832 -f 2484//2484 2832//2832 2485//2485 -f 2485//2485 2832//2832 2833//2833 -f 2485//2485 2833//2833 2439//2439 -f 2439//2439 2833//2833 2834//2834 -f 2439//2439 2834//2834 2440//2440 -f 2440//2440 2834//2834 2835//2835 -f 2440//2440 2835//2835 2458//2458 -f 2458//2458 2835//2835 2836//2836 -f 2458//2458 2836//2836 2459//2459 -f 2459//2459 2836//2836 2837//2837 -f 2459//2459 2837//2837 2480//2480 -f 2480//2480 2837//2837 2838//2838 -f 2480//2480 2838//2838 2481//2481 -f 2481//2481 2838//2838 2839//2839 -f 2481//2481 2839//2839 2482//2482 -f 2482//2482 2839//2839 2840//2840 -f 2482//2482 2840//2840 2454//2454 -f 2454//2454 2840//2840 2841//2841 -f 2454//2454 2841//2841 2455//2455 -f 2455//2455 2841//2841 2842//2842 -f 2455//2455 2842//2842 2477//2477 -f 2477//2477 2842//2842 2843//2843 -f 2477//2477 2843//2843 2478//2478 -f 2478//2478 2843//2843 2844//2844 -f 2478//2478 2844//2844 2479//2479 -f 2479//2479 2844//2844 2845//2845 -f 2479//2479 2845//2845 2476//2476 -f 2476//2476 2845//2845 2846//2846 -f 2476//2476 2846//2846 2474//2474 -f 2474//2474 2846//2846 2847//2847 -f 2474//2474 2847//2847 2453//2453 -f 2453//2453 2847//2847 2848//2848 -f 2453//2453 2848//2848 2451//2451 -f 2451//2451 2848//2848 2849//2849 -f 2451//2451 2849//2849 2449//2449 -f 2449//2449 2849//2849 2850//2850 -f 2449//2449 2850//2850 2471//2471 -f 2471//2471 2850//2850 2851//2851 -f 2471//2471 2851//2851 2472//2472 -f 2472//2472 2851//2851 2852//2852 -f 2472//2472 2852//2852 2473//2473 -f 2473//2473 2852//2852 2853//2853 -f 2473//2473 2853//2853 2447//2447 -f 2447//2447 2853//2853 2854//2854 -f 2447//2447 2854//2854 2448//2448 -f 2448//2448 2854//2854 2855//2855 -f 2448//2448 2855//2855 2445//2445 -f 2445//2445 2855//2855 2856//2856 -f 2445//2445 2856//2856 2489//2489 -f 2489//2489 2856//2856 2857//2857 -f 2489//2489 2857//2857 2490//2490 -f 2490//2490 2857//2857 2858//2858 -f 2490//2490 2858//2858 2491//2491 -f 2491//2491 2858//2858 2859//2859 -f 2491//2491 2859//2859 2467//2467 -f 2467//2467 2859//2859 2860//2860 -f 2467//2467 2860//2860 2468//2468 -f 2468//2468 2860//2860 2861//2861 -f 2468//2468 2861//2861 2486//2486 -f 2486//2486 2861//2861 2862//2862 -f 2486//2486 2862//2862 2487//2487 -f 2487//2487 2862//2862 2863//2863 -f 2487//2487 2863//2863 2488//2488 -f 2488//2488 2863//2863 2864//2864 -f 2488//2488 2864//2864 2465//2465 -f 2465//2465 2864//2864 2865//2865 -f 2465//2465 2865//2865 2466//2466 -f 2466//2466 2865//2865 2866//2866 -f 2466//2466 2866//2866 2435//2435 -f 2435//2435 2866//2866 2867//2867 -f 2435//2435 2867//2867 2436//2436 -f 2436//2436 2867//2867 2868//2868 -f 2436//2436 2868//2868 2461//2461 -f 2461//2461 2868//2868 2829//2829 -f 2868//2868 2869//2869 2829//2829 -f 2829//2829 2869//2869 2870//2870 -f 2829//2829 2870//2870 2830//2830 -f 2830//2830 2870//2870 2871//2871 -f 2830//2830 2871//2871 2831//2831 -f 2831//2831 2871//2871 2872//2872 -f 2831//2831 2872//2872 2832//2832 -f 2832//2832 2872//2872 2873//2873 -f 2832//2832 2873//2873 2833//2833 -f 2833//2833 2873//2873 2874//2874 -f 2833//2833 2874//2874 2834//2834 -f 2834//2834 2874//2874 2875//2875 -f 2834//2834 2875//2875 2835//2835 -f 2835//2835 2875//2875 2876//2876 -f 2835//2835 2876//2876 2836//2836 -f 2836//2836 2876//2876 2877//2877 -f 2836//2836 2877//2877 2837//2837 -f 2837//2837 2877//2877 2878//2878 -f 2837//2837 2878//2878 2838//2838 -f 2838//2838 2878//2878 2879//2879 -f 2838//2838 2879//2879 2839//2839 -f 2839//2839 2879//2879 2880//2880 -f 2839//2839 2880//2880 2840//2840 -f 2840//2840 2880//2880 2881//2881 -f 2840//2840 2881//2881 2841//2841 -f 2841//2841 2881//2881 2882//2882 -f 2841//2841 2882//2882 2842//2842 -f 2842//2842 2882//2882 2883//2883 -f 2842//2842 2883//2883 2843//2843 -f 2843//2843 2883//2883 2884//2884 -f 2843//2843 2884//2884 2844//2844 -f 2844//2844 2884//2884 2885//2885 -f 2844//2844 2885//2885 2845//2845 -f 2845//2845 2885//2885 2886//2886 -f 2845//2845 2886//2886 2846//2846 -f 2846//2846 2886//2886 2887//2887 -f 2846//2846 2887//2887 2847//2847 -f 2847//2847 2887//2887 2888//2888 -f 2847//2847 2888//2888 2848//2848 -f 2848//2848 2888//2888 2889//2889 -f 2848//2848 2889//2889 2849//2849 -f 2849//2849 2889//2889 2890//2890 -f 2849//2849 2890//2890 2850//2850 -f 2850//2850 2890//2890 2891//2891 -f 2850//2850 2891//2891 2851//2851 -f 2851//2851 2891//2891 2892//2892 -f 2851//2851 2892//2892 2852//2852 -f 2852//2852 2892//2892 2893//2893 -f 2852//2852 2893//2893 2853//2853 -f 2853//2853 2893//2893 2894//2894 -f 2853//2853 2894//2894 2854//2854 -f 2854//2854 2894//2894 2895//2895 -f 2854//2854 2895//2895 2855//2855 -f 2855//2855 2895//2895 2896//2896 -f 2855//2855 2896//2896 2856//2856 -f 2856//2856 2896//2896 2897//2897 -f 2856//2856 2897//2897 2857//2857 -f 2857//2857 2897//2897 2898//2898 -f 2857//2857 2898//2898 2858//2858 -f 2858//2858 2898//2898 2899//2899 -f 2858//2858 2899//2899 2859//2859 -f 2859//2859 2899//2899 2900//2900 -f 2859//2859 2900//2900 2860//2860 -f 2860//2860 2900//2900 2901//2901 -f 2860//2860 2901//2901 2861//2861 -f 2861//2861 2901//2901 2902//2902 -f 2861//2861 2902//2902 2862//2862 -f 2862//2862 2902//2902 2903//2903 -f 2862//2862 2903//2903 2863//2863 -f 2863//2863 2903//2903 2904//2904 -f 2863//2863 2904//2904 2864//2864 -f 2864//2864 2904//2904 2905//2905 -f 2864//2864 2905//2905 2865//2865 -f 2865//2865 2905//2905 2906//2906 -f 2865//2865 2906//2906 2866//2866 -f 2866//2866 2906//2906 2907//2907 -f 2866//2866 2907//2907 2867//2867 -f 2867//2867 2907//2907 2908//2908 -f 2867//2867 2908//2908 2868//2868 -f 2868//2868 2908//2908 2869//2869 -f 2908//2908 2414//2414 2869//2869 -f 2869//2869 2414//2414 2417//2417 -f 2869//2869 2417//2417 2870//2870 -f 2870//2870 2417//2417 2416//2416 -f 2870//2870 2416//2416 2871//2871 -f 2871//2871 2416//2416 2419//2419 -f 2871//2871 2419//2419 2872//2872 -f 2872//2872 2419//2419 2418//2418 -f 2872//2872 2418//2418 2873//2873 -f 2873//2873 2418//2418 2421//2421 -f 2873//2873 2421//2421 2874//2874 -f 2874//2874 2421//2421 2420//2420 -f 2874//2874 2420//2420 2875//2875 -f 2875//2875 2420//2420 2423//2423 -f 2875//2875 2423//2423 2876//2876 -f 2876//2876 2423//2423 2422//2422 -f 2876//2876 2422//2422 2877//2877 -f 2877//2877 2422//2422 2425//2425 -f 2877//2877 2425//2425 2878//2878 -f 2878//2878 2425//2425 2424//2424 -f 2878//2878 2424//2424 2879//2879 -f 2879//2879 2424//2424 2427//2427 -f 2879//2879 2427//2427 2880//2880 -f 2880//2880 2427//2427 2426//2426 -f 2880//2880 2426//2426 2881//2881 -f 2881//2881 2426//2426 2429//2429 -f 2881//2881 2429//2429 2882//2882 -f 2882//2882 2429//2429 2428//2428 -f 2882//2882 2428//2428 2883//2883 -f 2883//2883 2428//2428 2431//2431 -f 2883//2883 2431//2431 2884//2884 -f 2884//2884 2431//2431 2430//2430 -f 2884//2884 2430//2430 2885//2885 -f 2885//2885 2430//2430 2434//2434 -f 2885//2885 2434//2434 2886//2886 -f 2886//2886 2434//2434 2433//2433 -f 2886//2886 2433//2433 2887//2887 -f 2887//2887 2433//2433 2432//2432 -f 2887//2887 2432//2432 2888//2888 -f 2888//2888 2432//2432 2395//2395 -f 2888//2888 2395//2395 2889//2889 -f 2889//2889 2395//2395 2397//2397 -f 2889//2889 2397//2397 2890//2890 -f 2890//2890 2397//2397 2396//2396 -f 2890//2890 2396//2396 2891//2891 -f 2891//2891 2396//2396 2399//2399 -f 2891//2891 2399//2399 2892//2892 -f 2892//2892 2399//2399 2398//2398 -f 2892//2892 2398//2398 2893//2893 -f 2893//2893 2398//2398 2401//2401 -f 2893//2893 2401//2401 2894//2894 -f 2894//2894 2401//2401 2400//2400 -f 2894//2894 2400//2400 2895//2895 -f 2895//2895 2400//2400 2403//2403 -f 2895//2895 2403//2403 2896//2896 -f 2896//2896 2403//2403 2402//2402 -f 2896//2896 2402//2402 2897//2897 -f 2897//2897 2402//2402 2405//2405 -f 2897//2897 2405//2405 2898//2898 -f 2898//2898 2405//2405 2404//2404 -f 2898//2898 2404//2404 2899//2899 -f 2899//2899 2404//2404 2407//2407 -f 2899//2899 2407//2407 2900//2900 -f 2900//2900 2407//2407 2406//2406 -f 2900//2900 2406//2406 2901//2901 -f 2901//2901 2406//2406 2409//2409 -f 2901//2901 2409//2409 2902//2902 -f 2902//2902 2409//2409 2408//2408 -f 2902//2902 2408//2408 2903//2903 -f 2903//2903 2408//2408 2411//2411 -f 2903//2903 2411//2411 2904//2904 -f 2904//2904 2411//2411 2410//2410 -f 2904//2904 2410//2410 2905//2905 -f 2905//2905 2410//2410 2413//2413 -f 2905//2905 2413//2413 2906//2906 -f 2906//2906 2413//2413 2412//2412 -f 2906//2906 2412//2412 2907//2907 -f 2907//2907 2412//2412 2415//2415 -f 2907//2907 2415//2415 2908//2908 -f 2908//2908 2415//2415 2414//2414 -f 2909//2909 2910//2910 2911//2911 -f 2912//2912 2913//2913 2910//2910 -f 2910//2910 2913//2913 2914//2914 -f 2910//2910 2914//2914 2911//2911 -f 2915//2915 2916//2916 2912//2912 -f 2912//2912 2916//2916 2917//2917 -f 2912//2912 2917//2917 2913//2913 -f 2918//2918 2919//2919 2915//2915 -f 2915//2915 2919//2919 2920//2920 -f 2915//2915 2920//2920 2916//2916 -f 2921//2921 2922//2922 2918//2918 -f 2918//2918 2922//2922 2923//2923 -f 2918//2918 2923//2923 2919//2919 -f 2924//2924 2925//2925 2921//2921 -f 2921//2921 2925//2925 2926//2926 -f 2921//2921 2926//2926 2922//2922 -f 2927//2927 2928//2928 2924//2924 -f 2924//2924 2928//2928 2929//2929 -f 2924//2924 2929//2929 2925//2925 -f 2930//2930 2931//2931 2927//2927 -f 2927//2927 2931//2931 2932//2932 -f 2927//2927 2932//2932 2928//2928 -f 2933//2933 2934//2934 2930//2930 -f 2930//2930 2934//2934 2935//2935 -f 2930//2930 2935//2935 2931//2931 -f 2936//2936 2937//2937 2933//2933 -f 2933//2933 2937//2937 2938//2938 -f 2933//2933 2938//2938 2934//2934 -f 2939//2939 2940//2940 2936//2936 -f 2936//2936 2940//2940 2941//2941 -f 2936//2936 2941//2941 2937//2937 -f 2942//2942 2943//2943 2939//2939 -f 2939//2939 2943//2943 2944//2944 -f 2939//2939 2944//2944 2940//2940 -f 2945//2945 2946//2946 2942//2942 -f 2942//2942 2946//2946 2947//2947 -f 2942//2942 2947//2947 2943//2943 -f 2948//2948 2949//2949 2945//2945 -f 2945//2945 2949//2949 2950//2950 -f 2945//2945 2950//2950 2946//2946 -f 2951//2951 2952//2952 2948//2948 -f 2948//2948 2952//2952 2953//2953 -f 2948//2948 2953//2953 2949//2949 -f 2954//2954 2955//2955 2951//2951 -f 2951//2951 2955//2955 2956//2956 -f 2951//2951 2956//2956 2952//2952 -f 2957//2957 2958//2958 2954//2954 -f 2954//2954 2958//2958 2959//2959 -f 2954//2954 2959//2959 2955//2955 -f 2960//2960 2961//2961 2957//2957 -f 2957//2957 2961//2961 2962//2962 -f 2957//2957 2962//2962 2958//2958 -f 2911//2911 2963//2963 2909//2909 -f 2909//2909 2963//2963 2964//2964 -f 2909//2909 2964//2964 2960//2960 -f 2960//2960 2964//2964 2965//2965 -f 2960//2960 2965//2965 2961//2961 -f 2966//2966 2967//2967 2968//2968 -f 2969//2969 2970//2970 2971//2971 -f 2971//2971 2970//2970 2972//2972 -f 2973//2973 2974//2974 2975//2975 -f 2976//2976 2977//2977 2978//2978 -f 2979//2979 2980//2980 2981//2981 -f 2981//2981 2980//2980 2982//2982 -f 2981//2981 2982//2982 2983//2983 -f 2984//2984 2985//2985 2979//2979 -f 2979//2979 2985//2985 2986//2986 -f 2979//2979 2986//2986 2980//2980 -f 2975//2975 2987//2987 2973//2973 -f 2973//2973 2987//2987 2988//2988 -f 2973//2973 2988//2988 2989//2989 -f 2983//2983 2982//2982 2972//2972 -f 2972//2972 2982//2982 2990//2990 -f 2972//2972 2990//2990 2971//2971 -f 2991//2991 2992//2992 2993//2993 -f 2993//2993 2992//2992 2994//2994 -f 2993//2993 2994//2994 2984//2984 -f 2984//2984 2994//2994 2995//2995 -f 2984//2984 2995//2995 2985//2985 -f 2996//2996 2997//2997 2993//2993 -f 2993//2993 2997//2997 2998//2998 -f 2993//2993 2998//2998 2991//2991 -f 2999//2999 2997//2997 3000//3000 -f 3000//3000 2997//2997 2996//2996 -f 3000//3000 2996//2996 3001//3001 -f 3001//3001 2996//2996 3002//3002 -f 3001//3001 3002//3002 3003//3003 -f 3003//3003 3002//3002 2977//2977 -f 3003//3003 2977//2977 3004//3004 -f 3004//3004 2977//2977 2976//2976 -f 2999//2999 3005//3005 2997//2997 -f 2997//2997 3005//3005 3006//3006 -f 2997//2997 3006//3006 3007//3007 -f 3007//3007 3006//3006 3008//3008 -f 3007//3007 3008//3008 2988//2988 -f 2988//2988 3008//3008 3009//3009 -f 2988//2988 3009//3009 2989//2989 -f 2998//2998 3010//3010 2991//2991 -f 2991//2991 3010//3010 3011//3011 -f 2991//2991 3011//3011 3012//3012 -f 3012//3012 3011//3011 3013//3013 -f 3012//3012 3013//3013 3014//3014 -f 3014//3014 3013//3013 3015//3015 -f 3014//3014 3015//3015 3016//3016 -f 3016//3016 3015//3015 3017//3017 -f 3016//3016 3017//3017 2974//2974 -f 2974//2974 3017//3017 3018//3018 -f 2974//2974 3018//3018 2975//2975 -f 3019//3019 3020//3020 3021//3021 -f 3022//3022 3023//3023 3024//3024 -f 3025//3025 2968//2968 3026//3026 -f 3024//3024 3023//3023 3020//3020 -f 3020//3020 3023//3023 3027//3027 -f 3020//3020 3027//3027 3021//3021 -f 2967//2967 3028//3028 2968//2968 -f 2968//2968 3028//3028 3029//3029 -f 2968//2968 3029//3029 3026//3026 -f 2973//2973 3030//3030 2974//2974 -f 2974//2974 3030//3030 3031//3031 -f 2974//2974 3031//3031 3032//3032 -f 3032//3032 3031//3031 3033//3033 -f 3024//3024 3034//3034 3022//3022 -f 3022//3022 3034//3034 3035//3035 -f 3022//3022 3035//3035 2967//2967 -f 2967//2967 3035//3035 3036//3036 -f 2967//2967 3036//3036 3028//3028 -f 2973//2973 3037//3037 3030//3030 -f 3030//3030 3037//3037 3038//3038 -f 3030//3030 3038//3038 3039//3039 -f 3039//3039 3038//3038 3040//3040 -f 3039//3039 3040//3040 3026//3026 -f 3026//3026 3040//3040 3041//3041 -f 3026//3026 3041//3041 3025//3025 -f 3021//3021 3042//3042 3019//3019 -f 3019//3019 3042//3042 3043//3043 -f 3019//3019 3043//3043 3031//3031 -f 3031//3031 3043//3043 3044//3044 -f 3031//3031 3044//3044 3033//3033 -f 3045//3045 3046//3046 3047//3047 -f 3047//3047 3048//3048 3045//3045 -f 3045//3045 3048//3048 3049//3049 -f 3045//3045 3049//3049 2968//2968 -f 2968//2968 3049//3049 3050//3050 -f 2968//2968 3050//3050 2966//2966 -f 3051//3051 3052//3052 3053//3053 -f 3053//3053 3052//3052 2976//2976 -f 3053//3053 2976//2976 3054//3054 -f 3051//3051 3053//3053 3055//3055 -f 3055//3055 3053//3053 3056//3056 -f 3055//3055 3056//3056 3057//3057 -f 3057//3057 3056//3056 3058//3058 -f 3057//3057 3058//3058 3059//3059 -f 3059//3059 3058//3058 3045//3045 -f 3045//3045 3058//3058 3060//3060 -f 3045//3045 3060//3060 3046//3046 -f 3060//3060 3061//3061 3046//3046 -f 3046//3046 3061//3061 3062//3062 -f 3046//3046 3062//3062 3063//3063 -f 3063//3063 3062//3062 3064//3064 -f 3063//3063 3064//3064 3065//3065 -f 3065//3065 3064//3064 3066//3066 -f 3065//3065 3066//3066 3067//3067 -f 3067//3067 3066//3066 3068//3068 -f 3067//3067 3068//3068 3069//3069 -f 3069//3069 3068//3068 3070//3070 -f 3069//3069 3070//3070 3071//3071 -f 3071//3071 3070//3070 3072//3072 -f 2978//2978 2969//2969 2976//2976 -f 2976//2976 2969//2969 2971//2971 -f 2976//2976 2971//2971 3054//3054 -f 3054//3054 2971//2971 3073//3073 -f 3054//3054 3073//3073 3074//3074 -f 3074//3074 3075//3075 3054//3054 -f 3054//3054 3075//3075 3076//3076 -f 3054//3054 3076//3076 3072//3072 -f 3072//3072 3076//3076 3077//3077 -f 3072//3072 3077//3077 3071//3071 -f 3078//3078 3079//3079 3080//3080 -f 3080//3080 3079//3079 3081//3081 -f 3080//3080 3081//3081 3082//3082 -f 3082//3082 3081//3081 3083//3083 -f 3082//3082 3083//3083 3084//3084 -f 3084//3084 3083//3083 3085//3085 -f 3084//3084 3085//3085 3086//3086 -f 3086//3086 3085//3085 3087//3087 -f 3086//3086 3087//3087 3088//3088 -f 3088//3088 3087//3087 3089//3089 -f 3088//3088 3089//3089 3090//3090 -f 3090//3090 3089//3089 3091//3091 -f 3090//3090 3091//3091 3092//3092 -f 3092//3092 3091//3091 3093//3093 -f 3092//3092 3093//3093 3094//3094 -f 3094//3094 3093//3093 3095//3095 -f 3094//3094 3095//3095 3096//3096 -f 3096//3096 3095//3095 3097//3097 -f 3096//3096 3097//3097 3098//3098 -f 3098//3098 3097//3097 3099//3099 -f 3098//3098 3099//3099 3100//3100 -f 3100//3100 3099//3099 3101//3101 -f 3100//3100 3101//3101 3102//3102 -f 3102//3102 3101//3101 3103//3103 -f 3102//3102 3103//3103 3104//3104 -f 3104//3104 3103//3103 3105//3105 -f 3104//3104 3105//3105 3106//3106 -f 3106//3106 3105//3105 3107//3107 -f 3106//3106 3107//3107 3108//3108 -f 3108//3108 3107//3107 3109//3109 -f 3108//3108 3109//3109 3110//3110 -f 3110//3110 3109//3109 3111//3111 -f 3110//3110 3111//3111 3112//3112 -f 3112//3112 3111//3111 3113//3113 -f 3112//3112 3113//3113 3114//3114 -f 3114//3114 3113//3113 3115//3115 -f 3114//3114 3115//3115 3116//3116 -f 3116//3116 3115//3115 3117//3117 -f 3116//3116 3117//3117 3118//3118 -f 3118//3118 3117//3117 3119//3119 -f 3118//3118 3119//3119 3120//3120 -f 3120//3120 3119//3119 3121//3121 -f 3120//3120 3121//3121 3122//3122 -f 3122//3122 3121//3121 3123//3123 -f 3122//3122 3123//3123 3124//3124 -f 3124//3124 3123//3123 3125//3125 -f 3124//3124 3125//3125 3126//3126 -f 3126//3126 3125//3125 3127//3127 -f 3126//3126 3127//3127 3128//3128 -f 3128//3128 3127//3127 3129//3129 -f 3128//3128 3129//3129 3130//3130 -f 3130//3130 3129//3129 3131//3131 -f 3130//3130 3131//3131 3132//3132 -f 3132//3132 3131//3131 3133//3133 -f 3132//3132 3133//3133 3134//3134 -f 3134//3134 3133//3133 3135//3135 -f 3134//3134 3135//3135 3136//3136 -f 3136//3136 3135//3135 3137//3137 -f 3136//3136 3137//3137 3138//3138 -f 3138//3138 3137//3137 3139//3139 -f 3138//3138 3139//3139 3140//3140 -f 3140//3140 3139//3139 3141//3141 -f 3140//3140 3141//3141 3142//3142 -f 3142//3142 3141//3141 3143//3143 -f 3142//3142 3143//3143 3144//3144 -f 3144//3144 3143//3143 3145//3145 -f 3144//3144 3145//3145 3146//3146 -f 3146//3146 3145//3145 3147//3147 -f 3146//3146 3147//3147 3148//3148 -f 3148//3148 3147//3147 3149//3149 -f 3148//3148 3149//3149 3150//3150 -f 3150//3150 3149//3149 3151//3151 -f 3150//3150 3151//3151 3152//3152 -f 3152//3152 3151//3151 3153//3153 -f 3152//3152 3153//3153 3078//3078 -f 3078//3078 3153//3153 3079//3079 -f 3154//3154 3155//3155 3156//3156 -f 3156//3156 3155//3155 3157//3157 -f 3157//3157 3155//3155 3158//3158 -f 3157//3157 3158//3158 3159//3159 -f 3159//3159 3158//3158 3160//3160 -f 3159//3159 3160//3160 3161//3161 -f 3161//3161 3160//3160 3162//3162 -f 3161//3161 3162//3162 3163//3163 -f 3163//3163 3162//3162 3164//3164 -f 3163//3163 3164//3164 3165//3165 -f 3165//3165 3166//3166 3167//3167 -f 3167//3167 3166//3166 3168//3168 -f 3167//3167 3168//3168 3169//3169 -f 3170//3170 3171//3171 3172//3172 -f 3156//3156 3173//3173 3154//3154 -f 3154//3154 3173//3173 3174//3174 -f 3154//3154 3174//3174 3175//3175 -f 3170//3170 3176//3176 3171//3171 -f 3171//3171 3176//3176 3177//3177 -f 3171//3171 3177//3177 3178//3178 -f 3172//3172 3179//3179 3170//3170 -f 3170//3170 3179//3179 3180//3180 -f 3170//3170 3180//3180 3181//3181 -f 3181//3181 3180//3180 3182//3182 -f 3181//3181 3182//3182 3168//3168 -f 3168//3168 3182//3182 3183//3183 -f 3168//3168 3183//3183 3169//3169 -f 3184//3184 3185//3185 3186//3186 -f 3186//3186 3185//3185 3187//3187 -f 3186//3186 3187//3187 3188//3188 -f 3188//3188 3187//3187 3189//3189 -f 3188//3188 3189//3189 3178//3178 -f 3178//3178 3189//3189 3190//3190 -f 3178//3178 3190//3190 3171//3171 -f 3191//3191 3192//3192 3193//3193 -f 3193//3193 3192//3192 3194//3194 -f 3176//3176 3154//3154 3177//3177 -f 3177//3177 3154//3154 3175//3175 -f 3177//3177 3175//3175 3195//3195 -f 3195//3195 3175//3175 3196//3196 -f 3195//3195 3196//3196 3197//3197 -f 3198//3198 3199//3199 3200//3200 -f 3200//3200 3199//3199 3194//3194 -f 3194//3194 3199//3199 3201//3201 -f 3194//3194 3201//3201 3193//3193 -f 3200//3200 3202//3202 3198//3198 -f 3198//3198 3202//3202 3203//3203 -f 3198//3198 3203//3203 3204//3204 -f 3204//3204 3203//3203 3197//3197 -f 3204//3204 3197//3197 3205//3205 -f 3205//3205 3197//3197 3196//3196 -f 3206//3206 3207//3207 3208//3208 -f 3208//3208 3207//3207 3209//3209 -f 3207//3207 3210//3210 3211//3211 -f 3211//3211 3210//3210 3212//3212 -f 3211//3211 3212//3212 3213//3213 -f 3213//3213 3212//3212 3214//3214 -f 3213//3213 3214//3214 3215//3215 -f 3215//3215 3214//3214 3216//3216 -f 3215//3215 3216//3216 3217//3217 -f 3217//3217 3216//3216 3218//3218 -f 3217//3217 3218//3218 3219//3219 -f 3219//3219 3218//3218 3220//3220 -f 3219//3219 3220//3220 3221//3221 -f 3221//3221 3220//3220 3222//3222 -f 3221//3221 3222//3222 3223//3223 -f 3186//3186 3191//3191 3184//3184 -f 3184//3184 3191//3191 3193//3193 -f 3184//3184 3193//3193 3224//3224 -f 3224//3224 3193//3193 3225//3225 -f 3223//3223 3222//3222 3226//3226 -f 3226//3226 3222//3222 3227//3227 -f 3226//3226 3227//3227 3228//3228 -f 3208//3208 3229//3229 3206//3206 -f 3206//3206 3229//3229 3230//3230 -f 3206//3206 3230//3230 3231//3231 -f 3231//3231 3230//3230 3232//3232 -f 3231//3231 3232//3232 3233//3233 -f 3233//3233 3232//3232 3234//3234 -f 3234//3234 3225//3225 3233//3233 -f 3233//3233 3225//3225 3193//3193 -f 3233//3233 3193//3193 3227//3227 -f 3227//3227 3193//3193 3235//3235 -f 3227//3227 3235//3235 3228//3228 -f 3207//3207 3211//3211 3209//3209 -f 3209//3209 3211//3211 3236//3236 -f 3209//3209 3236//3236 3237//3237 -f 3237//3237 3238//3238 3209//3209 -f 3209//3209 3238//3238 3239//3239 -f 3209//3209 3239//3239 3240//3240 -f 3241//3241 3242//3242 3243//3243 -f 3244//3244 3245//3245 3246//3246 -f 3247//3247 3209//3209 3248//3248 -f 3249//3249 3250//3250 3251//3251 -f 3246//3246 3245//3245 3242//3242 -f 3242//3242 3245//3245 3252//3252 -f 3242//3242 3252//3252 3243//3243 -f 3165//3165 3167//3167 3163//3163 -f 3163//3163 3167//3167 3253//3253 -f 3163//3163 3253//3253 3254//3254 -f 3246//3246 3255//3255 3244//3244 -f 3244//3244 3255//3255 3256//3256 -f 3244//3244 3256//3256 3257//3257 -f 3257//3257 3256//3256 3258//3258 -f 3257//3257 3258//3258 3240//3240 -f 3240//3240 3258//3258 3259//3259 -f 3240//3240 3259//3259 3209//3209 -f 3209//3209 3259//3259 3260//3260 -f 3209//3209 3260//3260 3248//3248 -f 3250//3250 3163//3163 3251//3251 -f 3251//3251 3163//3163 3254//3254 -f 3251//3251 3254//3254 3261//3261 -f 3261//3261 3254//3254 3262//3262 -f 3261//3261 3262//3262 3263//3263 -f 3263//3263 3262//3262 3264//3264 -f 3263//3263 3264//3264 3248//3248 -f 3248//3248 3264//3264 3265//3265 -f 3248//3248 3265//3265 3247//3247 -f 3243//3243 3266//3266 3241//3241 -f 3241//3241 3266//3266 3267//3267 -f 3241//3241 3267//3267 3251//3251 -f 3251//3251 3267//3267 3268//3268 -f 3251//3251 3268//3268 3249//3249 -f 3183//3183 3182//3182 3269//3269 -f 3269//3269 3270//3270 3183//3183 -f 3183//3183 3270//3270 3271//3271 -f 3183//3183 3271//3271 3169//3169 -f 3169//3169 3271//3271 3272//3272 -f 3169//3169 3272//3272 3167//3167 -f 3167//3167 3272//3272 3273//3273 -f 3167//3167 3273//3273 3253//3253 -f 3273//3273 3274//3274 3253//3253 -f 3253//3253 3274//3274 3275//3275 -f 3253//3253 3275//3275 3254//3254 -f 3275//3275 3276//3276 3254//3254 -f 3254//3254 3276//3276 3277//3277 -f 3254//3254 3277//3277 3262//3262 -f 3277//3277 3278//3278 3262//3262 -f 3262//3262 3278//3278 3279//3279 -f 3262//3262 3279//3279 3264//3264 -f 3279//3279 3280//3280 3264//3264 -f 3264//3264 3280//3280 3281//3281 -f 3264//3264 3281//3281 3265//3265 -f 3281//3281 3282//3282 3265//3265 -f 3265//3265 3282//3282 3283//3283 -f 3265//3265 3283//3283 3247//3247 -f 3283//3283 3284//3284 3247//3247 -f 3247//3247 3284//3284 3285//3285 -f 3247//3247 3285//3285 3209//3209 -f 3285//3285 3286//3286 3209//3209 -f 3209//3209 3286//3286 3287//3287 -f 3209//3209 3287//3287 3208//3208 -f 3287//3287 3288//3288 3208//3208 -f 3208//3208 3288//3288 3289//3289 -f 3208//3208 3289//3289 3229//3229 -f 3289//3289 3290//3290 3229//3229 -f 3229//3229 3290//3290 3291//3291 -f 3229//3229 3291//3291 3230//3230 -f 3291//3291 3292//3292 3230//3230 -f 3230//3230 3292//3292 3293//3293 -f 3230//3230 3293//3293 3232//3232 -f 3293//3293 3294//3294 3232//3232 -f 3232//3232 3294//3294 3295//3295 -f 3232//3232 3295//3295 3234//3234 -f 3295//3295 3296//3296 3234//3234 -f 3234//3234 3296//3296 3297//3297 -f 3234//3234 3297//3297 3225//3225 -f 3297//3297 3298//3298 3225//3225 -f 3225//3225 3298//3298 3299//3299 -f 3225//3225 3299//3299 3224//3224 -f 3224//3224 3299//3299 3300//3300 -f 3224//3224 3300//3300 3184//3184 -f 3184//3184 3300//3300 3301//3301 -f 3184//3184 3301//3301 3185//3185 -f 3301//3301 3302//3302 3185//3185 -f 3185//3185 3302//3302 3303//3303 -f 3185//3185 3303//3303 3187//3187 -f 3303//3303 3304//3304 3187//3187 -f 3187//3187 3304//3304 3305//3305 -f 3187//3187 3305//3305 3189//3189 -f 3305//3305 3306//3306 3189//3189 -f 3189//3189 3306//3306 3307//3307 -f 3189//3189 3307//3307 3190//3190 -f 3307//3307 3308//3308 3190//3190 -f 3190//3190 3308//3308 3309//3309 -f 3190//3190 3309//3309 3171//3171 -f 3309//3309 3310//3310 3171//3171 -f 3171//3171 3310//3310 3311//3311 -f 3171//3171 3311//3311 3172//3172 -f 3311//3311 3312//3312 3172//3172 -f 3172//3172 3312//3312 3313//3313 -f 3172//3172 3313//3313 3179//3179 -f 3313//3313 3314//3314 3179//3179 -f 3179//3179 3314//3314 3315//3315 -f 3179//3179 3315//3315 3180//3180 -f 3315//3315 3316//3316 3180//3180 -f 3180//3180 3316//3316 3317//3317 -f 3180//3180 3317//3317 3182//3182 -f 3182//3182 3317//3317 3318//3318 -f 3182//3182 3318//3318 3269//3269 -f 3319//3319 3320//3320 3321//3321 -f 3322//3322 3323//3323 3324//3324 -f 3324//3324 3323//3323 3325//3325 -f 3324//3324 3325//3325 3326//3326 -f 3326//3326 3325//3325 3327//3327 -f 3326//3326 3327//3327 3321//3321 -f 3321//3321 3327//3327 3328//3328 -f 3321//3321 3328//3328 3319//3319 -f 3329//3329 3330//3330 3331//3331 -f 3331//3331 3330//3330 3332//3332 -f 3331//3331 3332//3332 3333//3333 -f 3333//3333 3332//3332 3334//3334 -f 3333//3333 3334//3334 3322//3322 -f 3322//3322 3334//3334 3335//3335 -f 3322//3322 3335//3335 3323//3323 -f 3336//3336 3337//3337 3338//3338 -f 3338//3338 3337//3337 3339//3339 -f 3338//3338 3339//3339 3340//3340 -f 3340//3340 3339//3339 3341//3341 -f 3340//3340 3341//3341 3329//3329 -f 3329//3329 3341//3341 3342//3342 -f 3329//3329 3342//3342 3330//3330 -f 3319//3319 3343//3343 3320//3320 -f 3320//3320 3343//3343 3344//3344 -f 3320//3320 3344//3344 3345//3345 -f 3345//3345 3344//3344 3346//3346 -f 3345//3345 3346//3346 3347//3347 -f 3347//3347 3346//3346 3348//3348 -f 3347//3347 3348//3348 3349//3349 -f 3350//3350 3351//3351 3352//3352 -f 3352//3352 3351//3351 3353//3353 -f 3352//3352 3353//3353 3354//3354 -f 3354//3354 3353//3353 3355//3355 -f 3354//3354 3355//3355 3336//3336 -f 3336//3336 3355//3355 3356//3356 -f 3336//3336 3356//3356 3337//3337 -f 3348//3348 3357//3357 3349//3349 -f 3349//3349 3357//3357 3358//3358 -f 3349//3349 3358//3358 3359//3359 -f 3359//3359 3358//3358 3360//3360 -f 3359//3359 3360//3360 3361//3361 -f 3361//3361 3360//3360 3362//3362 -f 3361//3361 3362//3362 3350//3350 -f 3350//3350 3362//3362 3363//3363 -f 3350//3350 3363//3363 3351//3351 -f 3364//3364 3320//3320 3365//3365 -f 3365//3365 3320//3320 3345//3345 -f 3365//3365 3345//3345 3366//3366 -f 3366//3366 3345//3345 3347//3347 -f 3366//3366 3347//3347 3367//3367 -f 3367//3367 3347//3347 3349//3349 -f 3367//3367 3349//3349 3368//3368 -f 3368//3368 3349//3349 3359//3359 -f 3368//3368 3359//3359 3369//3369 -f 3369//3369 3359//3359 3361//3361 -f 3369//3369 3361//3361 3370//3370 -f 3370//3370 3361//3361 3350//3350 -f 3370//3370 3350//3350 3371//3371 -f 3371//3371 3350//3350 3352//3352 -f 3371//3371 3352//3352 3372//3372 -f 3372//3372 3352//3352 3354//3354 -f 3372//3372 3354//3354 3373//3373 -f 3373//3373 3354//3354 3336//3336 -f 3373//3373 3336//3336 3374//3374 -f 3374//3374 3336//3336 3338//3338 -f 3374//3374 3338//3338 3375//3375 -f 3375//3375 3338//3338 3340//3340 -f 3375//3375 3340//3340 3376//3376 -f 3376//3376 3340//3340 3329//3329 -f 3376//3376 3329//3329 3377//3377 -f 3377//3377 3329//3329 3331//3331 -f 3377//3377 3331//3331 3378//3378 -f 3378//3378 3331//3331 3333//3333 -f 3378//3378 3333//3333 3379//3379 -f 3379//3379 3333//3333 3322//3322 -f 3379//3379 3322//3322 3380//3380 -f 3380//3380 3322//3322 3324//3324 -f 3380//3380 3324//3324 3381//3381 -f 3381//3381 3324//3324 3326//3326 -f 3381//3381 3326//3326 3382//3382 -f 3382//3382 3326//3326 3321//3321 -f 3382//3382 3321//3321 3364//3364 -f 3364//3364 3321//3321 3320//3320 -f 3383//3383 3381//3381 3384//3384 -f 3384//3384 3381//3381 3382//3382 -f 3384//3384 3382//3382 3385//3385 -f 3385//3385 3382//3382 3364//3364 -f 3385//3385 3364//3364 3386//3386 -f 3387//3387 3375//3375 3388//3388 -f 3388//3388 3375//3375 3376//3376 -f 3388//3388 3376//3376 3389//3389 -f 3376//3376 3377//3377 3389//3389 -f 3389//3389 3377//3377 3378//3378 -f 3389//3389 3378//3378 3390//3390 -f 3390//3390 3378//3378 3379//3379 -f 3390//3390 3379//3379 3383//3383 -f 3383//3383 3379//3379 3380//3380 -f 3383//3383 3380//3380 3381//3381 -f 3391//3391 3372//3372 3392//3392 -f 3392//3392 3372//3372 3373//3373 -f 3392//3392 3373//3373 3387//3387 -f 3387//3387 3373//3373 3374//3374 -f 3387//3387 3374//3374 3375//3375 -f 3393//3393 3369//3369 3394//3394 -f 3394//3394 3369//3369 3370//3370 -f 3394//3394 3370//3370 3391//3391 -f 3391//3391 3370//3370 3371//3371 -f 3391//3391 3371//3371 3372//3372 -f 3364//3364 3365//3365 3386//3386 -f 3386//3386 3365//3365 3366//3366 -f 3386//3386 3366//3366 3395//3395 -f 3395//3395 3366//3366 3367//3367 -f 3395//3395 3367//3367 3393//3393 -f 3393//3393 3367//3367 3368//3368 -f 3393//3393 3368//3368 3369//3369 -f 3396//3396 3385//3385 3397//3397 -f 3397//3397 3385//3385 3386//3386 -f 3397//3397 3386//3386 3398//3398 -f 3398//3398 3386//3386 3395//3395 -f 3398//3398 3395//3395 3399//3399 -f 3399//3399 3395//3395 3393//3393 -f 3399//3399 3393//3393 3400//3400 -f 3400//3400 3393//3393 3394//3394 -f 3400//3400 3394//3394 3401//3401 -f 3401//3401 3394//3394 3391//3391 -f 3401//3401 3391//3391 3402//3402 -f 3402//3402 3391//3391 3392//3392 -f 3402//3402 3392//3392 3403//3403 -f 3403//3403 3392//3392 3387//3387 -f 3403//3403 3387//3387 3404//3404 -f 3404//3404 3387//3387 3388//3388 -f 3404//3404 3388//3388 3405//3405 -f 3405//3405 3388//3388 3389//3389 -f 3405//3405 3389//3389 3406//3406 -f 3406//3406 3389//3389 3390//3390 -f 3406//3406 3390//3390 3407//3407 -f 3407//3407 3390//3390 3383//3383 -f 3407//3407 3383//3383 3408//3408 -f 3408//3408 3383//3383 3384//3384 -f 3408//3408 3384//3384 3396//3396 -f 3396//3396 3384//3384 3385//3385 -f 3404//3404 2939//2939 3403//3403 -f 3403//3403 2939//2939 2936//2936 -f 3403//3403 2936//2936 3402//3402 -f 3406//3406 2948//2948 3405//3405 -f 3405//3405 2948//2948 2945//2945 -f 3405//3405 2945//2945 3404//3404 -f 3404//3404 2945//2945 2942//2942 -f 3404//3404 2942//2942 2939//2939 -f 3408//3408 2957//2957 3407//3407 -f 3407//3407 2957//2957 2954//2954 -f 3407//3407 2954//2954 3406//3406 -f 3406//3406 2954//2954 2951//2951 -f 3406//3406 2951//2951 2948//2948 -f 3398//3398 2912//2912 3397//3397 -f 3397//3397 2912//2912 2910//2910 -f 3397//3397 2910//2910 3396//3396 -f 3396//3396 2910//2910 2909//2909 -f 3396//3396 2909//2909 3408//3408 -f 3408//3408 2909//2909 2960//2960 -f 3408//3408 2960//2960 2957//2957 -f 3400//3400 2921//2921 3399//3399 -f 3399//3399 2921//2921 2918//2918 -f 3399//3399 2918//2918 3398//3398 -f 3398//3398 2918//2918 2915//2915 -f 3398//3398 2915//2915 2912//2912 -f 2936//2936 2933//2933 3402//3402 -f 3402//3402 2933//2933 2930//2930 -f 3402//3402 2930//2930 3401//3401 -f 3401//3401 2930//2930 2927//2927 -f 3401//3401 2927//2927 3400//3400 -f 3400//3400 2927//2927 2924//2924 -f 3400//3400 2924//2924 2921//2921 -f 3409//3409 3158//3158 3410//3410 -f 3410//3410 3158//3158 3155//3155 -f 3410//3410 3155//3155 3411//3411 -f 3411//3411 3155//3155 3154//3154 -f 3411//3411 3154//3154 3412//3412 -f 3412//3412 3154//3154 3176//3176 -f 3412//3412 3176//3176 3413//3413 -f 3413//3413 3176//3176 3170//3170 -f 3413//3413 3170//3170 3414//3414 -f 3414//3414 3170//3170 3181//3181 -f 3414//3414 3181//3181 3415//3415 -f 3415//3415 3181//3181 3168//3168 -f 3415//3415 3168//3168 3416//3416 -f 3416//3416 3168//3168 3166//3166 -f 3416//3416 3166//3166 3417//3417 -f 3417//3417 3166//3166 3165//3165 -f 3417//3417 3165//3165 3418//3418 -f 3418//3418 3165//3165 3164//3164 -f 3418//3418 3164//3164 3419//3419 -f 3419//3419 3164//3164 3162//3162 -f 3419//3419 3162//3162 3420//3420 -f 3420//3420 3162//3162 3160//3160 -f 3420//3420 3160//3160 3409//3409 -f 3409//3409 3160//3160 3158//3158 -f 3414//3414 3421//3421 3413//3413 -f 3413//3413 3421//3421 3422//3422 -f 3413//3413 3422//3422 3412//3412 -f 3412//3412 3422//3422 3423//3423 -f 3412//3412 3423//3423 3411//3411 -f 3411//3411 3423//3423 3424//3424 -f 3411//3411 3424//3424 3410//3410 -f 3410//3410 3424//3424 3425//3425 -f 3410//3410 3425//3425 3409//3409 -f 3409//3409 3425//3425 3426//3426 -f 3409//3409 3426//3426 3420//3420 -f 3420//3420 3426//3426 3427//3427 -f 3420//3420 3427//3427 3419//3419 -f 3419//3419 3427//3427 3428//3428 -f 3419//3419 3428//3428 3418//3418 -f 3418//3418 3428//3428 3429//3429 -f 3418//3418 3429//3429 3417//3417 -f 3417//3417 3429//3429 3430//3430 -f 3417//3417 3430//3430 3416//3416 -f 3416//3416 3430//3430 3431//3431 -f 3416//3416 3431//3431 3415//3415 -f 3415//3415 3431//3431 3432//3432 -f 3415//3415 3432//3432 3414//3414 -f 3414//3414 3432//3432 3421//3421 -f 3422//3422 3053//3053 3423//3423 -f 3423//3423 3053//3053 3054//3054 -f 3423//3423 3054//3054 3424//3424 -f 3424//3424 3054//3054 3072//3072 -f 3424//3424 3072//3072 3425//3425 -f 3425//3425 3072//3072 3070//3070 -f 3425//3425 3070//3070 3426//3426 -f 3426//3426 3070//3070 3068//3068 -f 3426//3426 3068//3068 3427//3427 -f 3427//3427 3068//3068 3066//3066 -f 3427//3427 3066//3066 3428//3428 -f 3428//3428 3066//3066 3064//3064 -f 3428//3428 3064//3064 3429//3429 -f 3429//3429 3064//3064 3062//3062 -f 3429//3429 3062//3062 3430//3430 -f 3430//3430 3062//3062 3061//3061 -f 3430//3430 3061//3061 3431//3431 -f 3431//3431 3061//3061 3060//3060 -f 3431//3431 3060//3060 3432//3432 -f 3432//3432 3060//3060 3058//3058 -f 3432//3432 3058//3058 3421//3421 -f 3421//3421 3058//3058 3056//3056 -f 3421//3421 3056//3056 3422//3422 -f 3422//3422 3056//3056 3053//3053 -f 3433//3433 3251//3251 3434//3434 -f 3434//3434 3251//3251 3261//3261 -f 3434//3434 3261//3261 3435//3435 -f 3435//3435 3261//3261 3263//3263 -f 3435//3435 3263//3263 3436//3436 -f 3436//3436 3263//3263 3248//3248 -f 3436//3436 3248//3248 3437//3437 -f 3437//3437 3248//3248 3260//3260 -f 3437//3437 3260//3260 3438//3438 -f 3438//3438 3260//3260 3259//3259 -f 3438//3438 3259//3259 3439//3439 -f 3439//3439 3259//3259 3258//3258 -f 3439//3439 3258//3258 3440//3440 -f 3440//3440 3258//3258 3256//3256 -f 3440//3440 3256//3256 3441//3441 -f 3441//3441 3256//3256 3255//3255 -f 3441//3441 3255//3255 3442//3442 -f 3442//3442 3255//3255 3246//3246 -f 3442//3442 3246//3246 3443//3443 -f 3443//3443 3246//3246 3242//3242 -f 3443//3443 3242//3242 3444//3444 -f 3444//3444 3242//3242 3241//3241 -f 3444//3444 3241//3241 3433//3433 -f 3433//3433 3241//3241 3251//3251 -f 3438//3438 3445//3445 3437//3437 -f 3437//3437 3445//3445 3446//3446 -f 3437//3437 3446//3446 3436//3436 -f 3436//3436 3446//3446 3447//3447 -f 3436//3436 3447//3447 3435//3435 -f 3435//3435 3447//3447 3448//3448 -f 3435//3435 3448//3448 3434//3434 -f 3434//3434 3448//3448 3449//3449 -f 3434//3434 3449//3449 3433//3433 -f 3433//3433 3449//3449 3450//3450 -f 3433//3433 3450//3450 3444//3444 -f 3444//3444 3450//3450 3451//3451 -f 3444//3444 3451//3451 3443//3443 -f 3443//3443 3451//3451 3452//3452 -f 3443//3443 3452//3452 3442//3442 -f 3442//3442 3452//3452 3453//3453 -f 3442//3442 3453//3453 3441//3441 -f 3441//3441 3453//3453 3454//3454 -f 3441//3441 3454//3454 3440//3440 -f 3440//3440 3454//3454 3455//3455 -f 3440//3440 3455//3455 3439//3439 -f 3439//3439 3455//3455 3456//3456 -f 3439//3439 3456//3456 3438//3438 -f 3438//3438 3456//3456 3445//3445 -f 3446//3446 3031//3031 3447//3447 -f 3447//3447 3031//3031 3030//3030 -f 3447//3447 3030//3030 3448//3448 -f 3448//3448 3030//3030 3039//3039 -f 3448//3448 3039//3039 3449//3449 -f 3449//3449 3039//3039 3026//3026 -f 3449//3449 3026//3026 3450//3450 -f 3450//3450 3026//3026 3029//3029 -f 3450//3450 3029//3029 3451//3451 -f 3451//3451 3029//3029 3028//3028 -f 3451//3451 3028//3028 3452//3452 -f 3452//3452 3028//3028 3036//3036 -f 3452//3452 3036//3036 3453//3453 -f 3453//3453 3036//3036 3035//3035 -f 3453//3453 3035//3035 3454//3454 -f 3454//3454 3035//3035 3034//3034 -f 3454//3454 3034//3034 3455//3455 -f 3455//3455 3034//3034 3024//3024 -f 3455//3455 3024//3024 3456//3456 -f 3456//3456 3024//3024 3020//3020 -f 3456//3456 3020//3020 3445//3445 -f 3445//3445 3020//3020 3019//3019 -f 3445//3445 3019//3019 3446//3446 -f 3446//3446 3019//3019 3031//3031 -f 3457//3457 3233//3233 3458//3458 -f 3458//3458 3233//3233 3227//3227 -f 3458//3458 3227//3227 3459//3459 -f 3459//3459 3227//3227 3222//3222 -f 3459//3459 3222//3222 3460//3460 -f 3460//3460 3222//3222 3220//3220 -f 3460//3460 3220//3220 3461//3461 -f 3461//3461 3220//3220 3218//3218 -f 3461//3461 3218//3218 3462//3462 -f 3462//3462 3218//3218 3216//3216 -f 3462//3462 3216//3216 3463//3463 -f 3463//3463 3216//3216 3214//3214 -f 3463//3463 3214//3214 3464//3464 -f 3464//3464 3214//3214 3212//3212 -f 3464//3464 3212//3212 3465//3465 -f 3465//3465 3212//3212 3210//3210 -f 3465//3465 3210//3210 3466//3466 -f 3466//3466 3210//3210 3207//3207 -f 3466//3466 3207//3207 3467//3467 -f 3467//3467 3207//3207 3206//3206 -f 3467//3467 3206//3206 3468//3468 -f 3468//3468 3206//3206 3231//3231 -f 3468//3468 3231//3231 3457//3457 -f 3457//3457 3231//3231 3233//3233 -f 3462//3462 3469//3469 3461//3461 -f 3461//3461 3469//3469 3470//3470 -f 3461//3461 3470//3470 3460//3460 -f 3460//3460 3470//3470 3471//3471 -f 3460//3460 3471//3471 3459//3459 -f 3459//3459 3471//3471 3472//3472 -f 3459//3459 3472//3472 3458//3458 -f 3458//3458 3472//3472 3473//3473 -f 3458//3458 3473//3473 3457//3457 -f 3457//3457 3473//3473 3474//3474 -f 3457//3457 3474//3474 3468//3468 -f 3468//3468 3474//3474 3475//3475 -f 3468//3468 3475//3475 3467//3467 -f 3467//3467 3475//3475 3476//3476 -f 3467//3467 3476//3476 3466//3466 -f 3466//3466 3476//3476 3477//3477 -f 3466//3466 3477//3477 3465//3465 -f 3465//3465 3477//3477 3478//3478 -f 3465//3465 3478//3478 3464//3464 -f 3464//3464 3478//3478 3479//3479 -f 3464//3464 3479//3479 3463//3463 -f 3463//3463 3479//3479 3480//3480 -f 3463//3463 3480//3480 3462//3462 -f 3462//3462 3480//3480 3469//3469 -f 3470//3470 3013//3013 3471//3471 -f 3471//3471 3013//3013 3011//3011 -f 3471//3471 3011//3011 3472//3472 -f 3472//3472 3011//3011 3010//3010 -f 3472//3472 3010//3010 3473//3473 -f 3473//3473 3010//3010 2998//2998 -f 3473//3473 2998//2998 3474//3474 -f 3474//3474 2998//2998 2997//2997 -f 3474//3474 2997//2997 3475//3475 -f 3475//3475 2997//2997 3007//3007 -f 3475//3475 3007//3007 3476//3476 -f 3476//3476 3007//3007 2988//2988 -f 3476//3476 2988//2988 3477//3477 -f 3477//3477 2988//2988 2987//2987 -f 3477//3477 2987//2987 3478//3478 -f 3478//3478 2987//2987 2975//2975 -f 3478//3478 2975//2975 3479//3479 -f 3479//3479 2975//2975 3018//3018 -f 3479//3479 3018//3018 3480//3480 -f 3480//3480 3018//3018 3017//3017 -f 3480//3480 3017//3017 3469//3469 -f 3469//3469 3017//3017 3015//3015 -f 3469//3469 3015//3015 3470//3470 -f 3470//3470 3015//3015 3013//3013 -f 3481//3481 3197//3197 3482//3482 -f 3482//3482 3197//3197 3203//3203 -f 3482//3482 3203//3203 3483//3483 -f 3483//3483 3203//3203 3202//3202 -f 3483//3483 3202//3202 3484//3484 -f 3484//3484 3202//3202 3200//3200 -f 3484//3484 3200//3200 3485//3485 -f 3485//3485 3200//3200 3194//3194 -f 3485//3485 3194//3194 3486//3486 -f 3486//3486 3194//3194 3192//3192 -f 3486//3486 3192//3192 3487//3487 -f 3487//3487 3192//3192 3191//3191 -f 3487//3487 3191//3191 3488//3488 -f 3488//3488 3191//3191 3186//3186 -f 3488//3488 3186//3186 3489//3489 -f 3489//3489 3186//3186 3188//3188 -f 3489//3489 3188//3188 3490//3490 -f 3490//3490 3188//3188 3178//3178 -f 3490//3490 3178//3178 3491//3491 -f 3491//3491 3178//3178 3177//3177 -f 3491//3491 3177//3177 3492//3492 -f 3492//3492 3177//3177 3195//3195 -f 3492//3492 3195//3195 3481//3481 -f 3481//3481 3195//3195 3197//3197 -f 3486//3486 3493//3493 3485//3485 -f 3485//3485 3493//3493 3494//3494 -f 3485//3485 3494//3494 3484//3484 -f 3484//3484 3494//3494 3495//3495 -f 3484//3484 3495//3495 3483//3483 -f 3483//3483 3495//3495 3496//3496 -f 3483//3483 3496//3496 3482//3482 -f 3482//3482 3496//3496 3497//3497 -f 3482//3482 3497//3497 3481//3481 -f 3481//3481 3497//3497 3498//3498 -f 3481//3481 3498//3498 3492//3492 -f 3492//3492 3498//3498 3499//3499 -f 3492//3492 3499//3499 3491//3491 -f 3491//3491 3499//3499 3500//3500 -f 3491//3491 3500//3500 3490//3490 -f 3490//3490 3500//3500 3501//3501 -f 3490//3490 3501//3501 3489//3489 -f 3489//3489 3501//3501 3502//3502 -f 3489//3489 3502//3502 3488//3488 -f 3488//3488 3502//3502 3503//3503 -f 3488//3488 3503//3503 3487//3487 -f 3487//3487 3503//3503 3504//3504 -f 3487//3487 3504//3504 3486//3486 -f 3486//3486 3504//3504 3493//3493 -f 3494//3494 2979//2979 3495//3495 -f 3495//3495 2979//2979 2981//2981 -f 3495//3495 2981//2981 3496//3496 -f 3496//3496 2981//2981 2983//2983 -f 3496//3496 2983//2983 3497//3497 -f 3497//3497 2983//2983 2972//2972 -f 3497//3497 2972//2972 3498//3498 -f 3498//3498 2972//2972 2970//2970 -f 3498//3498 2970//2970 3499//3499 -f 3499//3499 2970//2970 2969//2969 -f 3499//3499 2969//2969 3500//3500 -f 3500//3500 2969//2969 2978//2978 -f 3500//3500 2978//2978 3501//3501 -f 3501//3501 2978//2978 2977//2977 -f 3501//3501 2977//2977 3502//3502 -f 3502//3502 2977//2977 3002//3002 -f 3502//3502 3002//3002 3503//3503 -f 3503//3503 3002//3002 2996//2996 -f 3503//3503 2996//2996 3504//3504 -f 3504//3504 2996//2996 2993//2993 -f 3504//3504 2993//2993 3493//3493 -f 3493//3493 2993//2993 2984//2984 -f 3493//3493 2984//2984 3494//3494 -f 3494//3494 2984//2984 2979//2979 -f 2989//2989 3009//3009 2940//2940 -f 2940//2940 2944//2944 2989//2989 -f 2989//2989 2944//2944 2943//2943 -f 2989//2989 2943//2943 2973//2973 -f 2973//2973 2943//2943 2947//2947 -f 2973//2973 2947//2947 3037//3037 -f 3037//3037 2947//2947 2946//2946 -f 3037//3037 2946//2946 3038//3038 -f 2946//2946 2950//2950 3038//3038 -f 3038//3038 2950//2950 2949//2949 -f 3038//3038 2949//2949 3040//3040 -f 2949//2949 2953//2953 3040//3040 -f 3040//3040 2953//2953 2952//2952 -f 3040//3040 2952//2952 3041//3041 -f 2952//2952 2956//2956 3041//3041 -f 3041//3041 2956//2956 2955//2955 -f 3041//3041 2955//2955 3025//3025 -f 2955//2955 2959//2959 3025//3025 -f 3025//3025 2959//2959 2958//2958 -f 3025//3025 2958//2958 2968//2968 -f 2968//2968 2958//2958 3045//3045 -f 3045//3045 2958//2958 2962//2962 -f 3045//3045 2962//2962 3059//3059 -f 3059//3059 2962//2962 2961//2961 -f 3059//3059 2961//2961 3057//3057 -f 2961//2961 2965//2965 3057//3057 -f 3057//3057 2965//2965 2964//2964 -f 3057//3057 2964//2964 3055//3055 -f 3055//3055 2964//2964 2963//2963 -f 3055//3055 2963//2963 3051//3051 -f 2963//2963 2911//2911 3051//3051 -f 3051//3051 2911//2911 2914//2914 -f 3051//3051 2914//2914 3052//3052 -f 2914//2914 2913//2913 3052//3052 -f 3052//3052 2913//2913 2917//2917 -f 3052//3052 2917//2917 2976//2976 -f 2976//2976 2917//2917 2916//2916 -f 2976//2976 2916//2916 3004//3004 -f 3004//3004 2916//2916 2920//2920 -f 3004//3004 2920//2920 3003//3003 -f 2920//2920 2919//2919 3003//3003 -f 3003//3003 2919//2919 2923//2923 -f 3003//3003 2923//2923 3001//3001 -f 2923//2923 2922//2922 3001//3001 -f 3001//3001 2922//2922 2926//2926 -f 3001//3001 2926//2926 3000//3000 -f 2926//2926 2925//2925 3000//3000 -f 3000//3000 2925//2925 2929//2929 -f 3000//3000 2929//2929 2999//2999 -f 2929//2929 2928//2928 2999//2999 -f 2999//2999 2928//2928 2932//2932 -f 2999//2999 2932//2932 3005//3005 -f 2932//2932 2931//2931 3005//3005 -f 3005//3005 2931//2931 2935//2935 -f 3005//3005 2935//2935 3006//3006 -f 2935//2935 2934//2934 3006//3006 -f 3006//3006 2934//2934 2938//2938 -f 3006//3006 2938//2938 3008//3008 -f 3008//3008 2938//2938 2937//2937 -f 3008//3008 2937//2937 3009//3009 -f 3009//3009 2937//2937 2941//2941 -f 3009//3009 2941//2941 2940//2940 -f 3337//3337 3293//3293 3292//3292 -f 3337//3337 3292//3292 3339//3339 -f 3339//3339 3292//3292 3291//3291 -f 3339//3339 3291//3291 3341//3341 -f 3291//3291 3290//3290 3341//3341 -f 3341//3341 3290//3290 3289//3289 -f 3341//3341 3289//3289 3342//3342 -f 3289//3289 3288//3288 3342//3342 -f 3342//3342 3288//3288 3287//3287 -f 3342//3342 3287//3287 3330//3330 -f 3287//3287 3286//3286 3330//3330 -f 3330//3330 3286//3286 3285//3285 -f 3330//3330 3285//3285 3332//3332 -f 3285//3285 3284//3284 3332//3332 -f 3332//3332 3284//3284 3283//3283 -f 3332//3332 3283//3283 3334//3334 -f 3334//3334 3283//3283 3282//3282 -f 3282//3282 3281//3281 3334//3334 -f 3334//3334 3281//3281 3280//3280 -f 3334//3334 3280//3280 3335//3335 -f 3280//3280 3279//3279 3335//3335 -f 3335//3335 3279//3279 3278//3278 -f 3335//3335 3278//3278 3323//3323 -f 3323//3323 3278//3278 3277//3277 -f 3323//3323 3277//3277 3325//3325 -f 3277//3277 3276//3276 3325//3325 -f 3325//3325 3276//3276 3275//3275 -f 3325//3325 3275//3275 3327//3327 -f 3275//3275 3274//3274 3327//3327 -f 3327//3327 3274//3274 3273//3273 -f 3327//3327 3273//3273 3328//3328 -f 3273//3273 3272//3272 3328//3328 -f 3328//3328 3272//3272 3271//3271 -f 3328//3328 3271//3271 3319//3319 -f 3271//3271 3270//3270 3319//3319 -f 3319//3319 3270//3270 3269//3269 -f 3319//3319 3269//3269 3343//3343 -f 3343//3343 3269//3269 3318//3318 -f 3343//3343 3318//3318 3344//3344 -f 3318//3318 3317//3317 3344//3344 -f 3344//3344 3317//3317 3316//3316 -f 3344//3344 3316//3316 3346//3346 -f 3346//3346 3316//3316 3315//3315 -f 3346//3346 3315//3315 3348//3348 -f 3315//3315 3314//3314 3348//3348 -f 3348//3348 3314//3314 3313//3313 -f 3348//3348 3313//3313 3357//3357 -f 3357//3357 3313//3313 3312//3312 -f 3312//3312 3311//3311 3357//3357 -f 3357//3357 3311//3311 3310//3310 -f 3357//3357 3310//3310 3358//3358 -f 3358//3358 3310//3310 3309//3309 -f 3358//3358 3309//3309 3360//3360 -f 3309//3309 3308//3308 3360//3360 -f 3360//3360 3308//3308 3307//3307 -f 3360//3360 3307//3307 3362//3362 -f 3307//3307 3306//3306 3362//3362 -f 3362//3362 3306//3306 3305//3305 -f 3362//3362 3305//3305 3363//3363 -f 3305//3305 3304//3304 3363//3363 -f 3363//3363 3304//3304 3303//3303 -f 3363//3363 3303//3303 3351//3351 -f 3303//3303 3302//3302 3351//3351 -f 3351//3351 3302//3302 3301//3301 -f 3351//3351 3301//3301 3353//3353 -f 3353//3353 3301//3301 3300//3300 -f 3300//3300 3299//3299 3353//3353 -f 3353//3353 3299//3299 3298//3298 -f 3353//3353 3298//3298 3355//3355 -f 3298//3298 3297//3297 3355//3355 -f 3355//3355 3297//3297 3296//3296 -f 3355//3355 3296//3296 3356//3356 -f 3356//3356 3296//3296 3295//3295 -f 3356//3356 3295//3295 3337//3337 -f 3337//3337 3295//3295 3294//3294 -f 3337//3337 3294//3294 3293//3293 -f 3161//3161 3163//3163 3150//3150 -f 3100//3100 3199//3199 3098//3098 -f 3098//3098 3199//3199 3198//3198 -f 3098//3098 3198//3198 3096//3096 -f 3096//3096 3198//3198 3204//3204 -f 3096//3096 3204//3204 3094//3094 -f 3094//3094 3204//3204 3205//3205 -f 3094//3094 3205//3205 3092//3092 -f 3092//3092 3205//3205 3196//3196 -f 3092//3092 3196//3196 3090//3090 -f 3090//3090 3196//3196 3175//3175 -f 3090//3090 3175//3175 3088//3088 -f 3088//3088 3175//3175 3174//3174 -f 3088//3088 3174//3174 3086//3086 -f 3086//3086 3174//3174 3173//3173 -f 3086//3086 3173//3173 3084//3084 -f 3084//3084 3173//3173 3156//3156 -f 3084//3084 3156//3156 3082//3082 -f 3082//3082 3156//3156 3157//3157 -f 3082//3082 3157//3157 3080//3080 -f 3080//3080 3157//3157 3159//3159 -f 3080//3080 3159//3159 3078//3078 -f 3078//3078 3159//3159 3161//3161 -f 3078//3078 3161//3161 3152//3152 -f 3152//3152 3161//3161 3150//3150 -f 3235//3235 3193//3193 3100//3100 -f 3100//3100 3193//3193 3201//3201 -f 3100//3100 3201//3201 3199//3199 -f 3163//3163 3250//3250 3150//3150 -f 3150//3150 3250//3250 3249//3249 -f 3150//3150 3249//3249 3148//3148 -f 3148//3148 3249//3249 3268//3268 -f 3148//3148 3268//3268 3146//3146 -f 3146//3146 3268//3268 3267//3267 -f 3146//3146 3267//3267 3144//3144 -f 3144//3144 3267//3267 3266//3266 -f 3144//3144 3266//3266 3142//3142 -f 3142//3142 3266//3266 3243//3243 -f 3142//3142 3243//3243 3140//3140 -f 3140//3140 3243//3243 3252//3252 -f 3140//3140 3252//3252 3138//3138 -f 3138//3138 3252//3252 3245//3245 -f 3138//3138 3245//3245 3136//3136 -f 3136//3136 3245//3245 3244//3244 -f 3136//3136 3244//3244 3134//3134 -f 3134//3134 3244//3244 3257//3257 -f 3134//3134 3257//3257 3132//3132 -f 3132//3132 3257//3257 3240//3240 -f 3132//3132 3240//3240 3130//3130 -f 3130//3130 3240//3240 3239//3239 -f 3130//3130 3239//3239 3128//3128 -f 3128//3128 3239//3239 3238//3238 -f 3128//3128 3238//3238 3126//3126 -f 3126//3126 3238//3238 3237//3237 -f 3126//3126 3237//3237 3124//3124 -f 3124//3124 3237//3237 3236//3236 -f 3124//3124 3236//3236 3122//3122 -f 3122//3122 3236//3236 3211//3211 -f 3122//3122 3211//3211 3120//3120 -f 3120//3120 3211//3211 3213//3213 -f 3120//3120 3213//3213 3118//3118 -f 3118//3118 3213//3213 3215//3215 -f 3118//3118 3215//3215 3116//3116 -f 3116//3116 3215//3215 3217//3217 -f 3116//3116 3217//3217 3114//3114 -f 3114//3114 3217//3217 3219//3219 -f 3114//3114 3219//3219 3112//3112 -f 3112//3112 3219//3219 3221//3221 -f 3112//3112 3221//3221 3110//3110 -f 3110//3110 3221//3221 3223//3223 -f 3110//3110 3223//3223 3108//3108 -f 3108//3108 3223//3223 3226//3226 -f 3108//3108 3226//3226 3106//3106 -f 3106//3106 3226//3226 3228//3228 -f 3106//3106 3228//3228 3104//3104 -f 3104//3104 3228//3228 3235//3235 -f 3104//3104 3235//3235 3102//3102 -f 3102//3102 3235//3235 3100//3100 -f 3095//3095 2982//2982 3097//3097 -f 3097//3097 2982//2982 2980//2980 -f 3097//3097 2980//2980 3099//3099 -f 3099//3099 2980//2980 2986//2986 -f 3099//3099 2986//2986 3101//3101 -f 3101//3101 2986//2986 2985//2985 -f 3101//3101 2985//2985 3103//3103 -f 3103//3103 2985//2985 2995//2995 -f 3103//3103 2995//2995 3105//3105 -f 3105//3105 2995//2995 2994//2994 -f 3105//3105 2994//2994 3107//3107 -f 3107//3107 2994//2994 2992//2992 -f 3107//3107 2992//2992 3109//3109 -f 3109//3109 2992//2992 2991//2991 -f 3109//3109 2991//2991 3111//3111 -f 3111//3111 2991//2991 3012//3012 -f 3111//3111 3012//3012 3113//3113 -f 3113//3113 3012//3012 3014//3014 -f 3113//3113 3014//3014 3115//3115 -f 3115//3115 3014//3014 3016//3016 -f 3115//3115 3016//3016 3117//3117 -f 3117//3117 3016//3016 2974//2974 -f 3117//3117 2974//2974 3119//3119 -f 2974//2974 3032//3032 3119//3119 -f 3119//3119 3032//3032 3033//3033 -f 3119//3119 3033//3033 3121//3121 -f 3121//3121 3033//3033 3044//3044 -f 3121//3121 3044//3044 3123//3123 -f 3123//3123 3044//3044 3043//3043 -f 3123//3123 3043//3043 3125//3125 -f 3125//3125 3043//3043 3042//3042 -f 3125//3125 3042//3042 3127//3127 -f 3127//3127 3042//3042 3021//3021 -f 3127//3127 3021//3021 3129//3129 -f 3129//3129 3021//3021 3027//3027 -f 3129//3129 3027//3027 3131//3131 -f 3131//3131 3027//3027 3023//3023 -f 3131//3131 3023//3023 3133//3133 -f 3133//3133 3023//3023 3022//3022 -f 3133//3133 3022//3022 3135//3135 -f 3135//3135 3022//3022 2967//2967 -f 3135//3135 2967//2967 3137//3137 -f 3137//3137 2967//2967 2966//2966 -f 3137//3137 2966//2966 3139//3139 -f 3139//3139 2966//2966 3050//3050 -f 3139//3139 3050//3050 3141//3141 -f 3141//3141 3050//3050 3049//3049 -f 3141//3141 3049//3049 3143//3143 -f 3143//3143 3049//3049 3048//3048 -f 3143//3143 3048//3048 3145//3145 -f 3145//3145 3048//3048 3047//3047 -f 3145//3145 3047//3047 3147//3147 -f 3147//3147 3047//3047 3046//3046 -f 3147//3147 3046//3046 3149//3149 -f 3149//3149 3046//3046 3063//3063 -f 3149//3149 3063//3063 3151//3151 -f 3151//3151 3063//3063 3065//3065 -f 3151//3151 3065//3065 3153//3153 -f 3153//3153 3065//3065 3067//3067 -f 3153//3153 3067//3067 3079//3079 -f 3079//3079 3067//3067 3069//3069 -f 3079//3079 3069//3069 3081//3081 -f 3081//3081 3069//3069 3071//3071 -f 3081//3081 3071//3071 3083//3083 -f 3083//3083 3071//3071 3077//3077 -f 3083//3083 3077//3077 3085//3085 -f 3085//3085 3077//3077 3076//3076 -f 3085//3085 3076//3076 3087//3087 -f 3087//3087 3076//3076 3075//3075 -f 3087//3087 3075//3075 3089//3089 -f 3089//3089 3075//3075 3074//3074 -f 3089//3089 3074//3074 3091//3091 -f 3091//3091 3074//3074 3073//3073 -f 3091//3091 3073//3073 3093//3093 -f 3093//3093 3073//3073 2971//2971 -f 3093//3093 2971//2971 3095//3095 -f 3095//3095 2971//2971 2990//2990 -f 3095//3095 2990//2990 2982//2982 -# 7304 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/connector.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/connector.obj deleted file mode 100644 index 1d7998408..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/connector.obj +++ /dev/null @@ -1,11600 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object connector.obj -# -# Vertices: 2896 -# Faces: 5792 -# -#### -vn 0.997348 0.000001 0.072783 -v 0.082690 0.069499 0.236342 -vn 0.953426 -0.093904 0.286637 -v 0.082609 0.068719 0.236630 -vn 0.992561 -0.097760 0.072571 -v 0.082651 0.068715 0.236342 -vn 0.939631 -0.186904 0.286638 -v 0.082494 0.067947 0.236630 -vn 0.978185 -0.194571 0.072774 -v 0.082536 0.067938 0.236342 -vn 0.916784 -0.278102 0.286646 -v 0.082305 0.067189 0.236630 -vn 0.954417 -0.289518 0.072576 -v 0.082345 0.067177 0.236342 -vn 0.885112 -0.366626 0.286640 -v 0.082042 0.066454 0.236630 -vn 0.921428 -0.381672 0.072775 -v 0.082081 0.066438 0.236342 -vn 0.844916 -0.451619 0.286632 -v 0.081708 0.065748 0.236630 -vn 0.879595 -0.470156 0.072563 -v 0.081745 0.065728 0.236342 -vn 0.796582 -0.532257 0.286636 -v 0.081306 0.065078 0.236630 -vn 0.829265 -0.554097 0.072768 -v 0.081341 0.065055 0.236342 -vn 0.740574 -0.607777 0.286630 -v 0.080841 0.064451 0.236630 -vn 0.770973 -0.632721 0.072560 -v 0.080874 0.064424 0.236342 -vn 0.677436 -0.677432 0.286646 -v 0.080317 0.063872 0.236630 -vn 0.705233 -0.705231 0.072774 -v 0.080346 0.063842 0.236342 -vn 0.607774 -0.740577 0.286630 -v 0.079738 0.063348 0.236630 -vn 0.632719 -0.770975 0.072560 -v 0.079765 0.063315 0.236342 -vn 0.532259 -0.796580 0.286636 -v 0.079111 0.062883 0.236630 -vn 0.554100 -0.829264 0.072769 -v 0.079134 0.062847 0.236342 -vn 0.451616 -0.844916 0.286635 -v 0.078441 0.062481 0.236630 -vn 0.470154 -0.879596 0.072564 -v 0.078461 0.062444 0.236342 -vn 0.366624 -0.885113 0.286640 -v 0.077735 0.062147 0.236630 -vn 0.381670 -0.921429 0.072780 -v 0.077751 0.062108 0.236342 -vn 0.278105 -0.916785 0.286642 -v 0.077000 0.061884 0.236630 -vn 0.289519 -0.954417 0.072570 -v 0.077012 0.061844 0.236342 -vn 0.186905 -0.939630 0.286638 -v 0.076242 0.061694 0.236630 -vn 0.194574 -0.978185 0.072773 -v 0.076250 0.061653 0.236342 -vn 0.093905 -0.953425 0.286640 -v 0.075470 0.061580 0.236630 -vn 0.097759 -0.992561 0.072570 -v 0.075474 0.061538 0.236342 -vn -0.000000 -0.958039 0.286639 -v 0.074690 0.061541 0.236630 -vn -0.000001 -0.997349 0.072772 -v 0.074690 0.061499 0.236342 -vn -0.093903 -0.953426 0.286639 -v 0.073910 0.061580 0.236630 -vn -0.097757 -0.992561 0.072571 -v 0.073905 0.061538 0.236342 -vn -0.186904 -0.939630 0.286638 -v 0.073137 0.061694 0.236630 -vn -0.194574 -0.978184 0.072775 -v 0.073129 0.061653 0.236342 -vn -0.278105 -0.916786 0.286637 -v 0.072380 0.061884 0.236630 -vn -0.289519 -0.954417 0.072568 -v 0.072367 0.061844 0.236342 -vn -0.366625 -0.885112 0.286640 -v 0.071644 0.062147 0.236630 -vn -0.381667 -0.921430 0.072780 -v 0.071628 0.062108 0.236342 -vn -0.451616 -0.844914 0.286642 -v 0.070938 0.062481 0.236630 -vn -0.470157 -0.879594 0.072568 -v 0.070918 0.062444 0.236342 -vn -0.532259 -0.796580 0.286637 -v 0.070269 0.062883 0.236630 -vn -0.554099 -0.829264 0.072769 -v 0.070245 0.062847 0.236342 -vn -0.607772 -0.740575 0.286637 -v 0.069641 0.063348 0.236630 -vn -0.632719 -0.770974 0.072566 -v 0.069614 0.063315 0.236342 -vn -0.677434 -0.677437 0.286640 -v 0.069063 0.063872 0.236630 -vn -0.705232 -0.705233 0.072766 -v 0.069033 0.063842 0.236342 -vn -0.740576 -0.607773 0.286635 -v 0.068538 0.064451 0.236630 -vn -0.770973 -0.632721 0.072561 -v 0.068506 0.064424 0.236342 -vn -0.796581 -0.532258 0.286638 -v 0.068073 0.065078 0.236630 -vn -0.829264 -0.554099 0.072778 -v 0.068038 0.065055 0.236342 -vn -0.844913 -0.451617 0.286642 -v 0.067672 0.065748 0.236630 -vn -0.879597 -0.470153 0.072562 -v 0.067634 0.065728 0.236342 -vn -0.885112 -0.366626 0.286638 -v 0.067338 0.066454 0.236630 -vn -0.921431 -0.381669 0.072765 -v 0.067299 0.066438 0.236342 -vn -0.916788 -0.278101 0.286635 -v 0.067075 0.067189 0.236630 -vn -0.954418 -0.289519 0.072565 -v 0.067034 0.067177 0.236342 -vn -0.939631 -0.186903 0.286638 -v 0.066885 0.067947 0.236630 -vn -0.978185 -0.194574 0.072773 -v 0.066843 0.067938 0.236342 -vn -0.953423 -0.093908 0.286645 -v 0.066770 0.068719 0.236630 -vn -0.992560 -0.097761 0.072570 -v 0.066728 0.068715 0.236342 -vn -0.958040 0.000002 0.286634 -v 0.066732 0.069499 0.236630 -vn -0.997349 0.000001 0.072772 -v 0.066690 0.069499 0.236342 -vn -0.953424 0.093905 0.286644 -v 0.066770 0.070279 0.236630 -vn -0.992561 0.097760 0.072571 -v 0.066728 0.070283 0.236342 -vn -0.939631 0.186902 0.286639 -v 0.066885 0.071052 0.236630 -vn -0.978185 0.194574 0.072774 -v 0.066843 0.071060 0.236342 -vn -0.916788 0.278103 0.286633 -v 0.067075 0.071809 0.236630 -vn -0.954418 0.289520 0.072561 -v 0.067034 0.071821 0.236342 -vn -0.885113 0.366628 0.286635 -v 0.067338 0.072544 0.236630 -vn -0.921430 0.381669 0.072765 -v 0.067299 0.072561 0.236342 -vn -0.844914 0.451616 0.286644 -v 0.067672 0.073250 0.236630 -vn -0.879596 0.470153 0.072569 -v 0.067634 0.073270 0.236342 -vn -0.796580 0.532258 0.286639 -v 0.068073 0.073920 0.236630 -vn -0.829265 0.554096 0.072779 -v 0.068038 0.073944 0.236342 -vn -0.740575 0.607770 0.286645 -v 0.068538 0.074547 0.236630 -vn -0.770972 0.632722 0.072566 -v 0.068506 0.074574 0.236342 -vn -0.677435 0.677439 0.286633 -v 0.069063 0.075126 0.236630 -vn -0.705230 0.705234 0.072768 -v 0.069033 0.075156 0.236342 -vn -0.607773 0.740572 0.286644 -v 0.069641 0.075650 0.236630 -vn -0.632722 0.770970 0.072577 -v 0.069614 0.075683 0.236342 -vn -0.532258 0.796580 0.286640 -v 0.070269 0.076116 0.236630 -vn -0.554098 0.829264 0.072779 -v 0.070245 0.076151 0.236342 -vn -0.451618 0.844911 0.286646 -v 0.070938 0.076517 0.236630 -vn -0.470155 0.879596 0.072568 -v 0.070918 0.076554 0.236342 -vn -0.366625 0.885112 0.286640 -v 0.071644 0.076851 0.236630 -vn -0.381669 0.921430 0.072769 -v 0.071628 0.076890 0.236342 -vn -0.278102 0.916786 0.286641 -v 0.072380 0.077114 0.236630 -vn -0.289517 0.954418 0.072562 -v 0.072367 0.077155 0.236342 -vn -0.186902 0.939631 0.286638 -v 0.073137 0.077304 0.236630 -vn -0.194575 0.978184 0.072775 -v 0.073129 0.077345 0.236342 -vn -0.093906 0.953423 0.286645 -v 0.073910 0.077418 0.236630 -vn -0.097761 0.992561 0.072571 -v 0.073905 0.077461 0.236342 -vn 0.000000 0.958037 0.286644 -v 0.074690 0.077457 0.236630 -vn 0.000001 0.997349 0.072772 -v 0.074690 0.077499 0.236342 -vn 0.093905 0.953424 0.286645 -v 0.075470 0.077418 0.236630 -vn 0.097760 0.992561 0.072571 -v 0.075474 0.077461 0.236342 -vn 0.186905 0.939630 0.286640 -v 0.076242 0.077304 0.236630 -vn 0.194574 0.978185 0.072772 -v 0.076250 0.077345 0.236342 -vn 0.278100 0.916785 0.286646 -v 0.077000 0.077114 0.236630 -vn 0.289519 0.954418 0.072564 -v 0.077012 0.077155 0.236342 -vn 0.366625 0.885112 0.286640 -v 0.077735 0.076851 0.236630 -vn 0.381669 0.921430 0.072769 -v 0.077751 0.076890 0.236342 -vn 0.451616 0.844915 0.286639 -v 0.078441 0.076517 0.236630 -vn 0.470153 0.879597 0.072564 -v 0.078461 0.076554 0.236342 -vn 0.532260 0.796579 0.286637 -v 0.079111 0.076116 0.236630 -vn 0.554096 0.829265 0.072779 -v 0.079134 0.076151 0.236342 -vn 0.607775 0.740573 0.286639 -v 0.079738 0.075650 0.236630 -vn 0.632722 0.770971 0.072569 -v 0.079765 0.075683 0.236342 -vn 0.677435 0.677436 0.286641 -v 0.080317 0.075126 0.236630 -vn 0.705232 0.705232 0.072775 -v 0.080346 0.075156 0.236342 -vn 0.740575 0.607773 0.286637 -v 0.080841 0.074547 0.236630 -vn 0.770973 0.632720 0.072567 -v 0.080874 0.074574 0.236342 -vn 0.796581 0.532257 0.286637 -v 0.081306 0.073920 0.236630 -vn 0.829265 0.554097 0.072770 -v 0.081341 0.073944 0.236342 -vn 0.844915 0.451618 0.286636 -v 0.081708 0.073250 0.236630 -vn 0.879595 0.470156 0.072569 -v 0.081745 0.073270 0.236342 -vn 0.885113 0.366627 0.286636 -v 0.082042 0.072544 0.236630 -vn 0.921429 0.381671 0.072776 -v 0.082081 0.072561 0.236342 -vn 0.916784 0.278106 0.286643 -v 0.082305 0.071809 0.236630 -vn 0.954417 0.289520 0.072573 -v 0.082345 0.071821 0.236342 -vn 0.939631 0.186902 0.286638 -v 0.082494 0.071052 0.236630 -vn 0.978185 0.194570 0.072775 -v 0.082536 0.071060 0.236342 -vn 0.953427 0.093902 0.286634 -v 0.082609 0.070279 0.236630 -vn 0.992561 0.097759 0.072572 -v 0.082651 0.070283 0.236342 -vn 0.958037 0.000002 0.286644 -v 0.082647 0.069499 0.236630 -vn 0.831586 -0.081904 0.549324 -v 0.082486 0.068731 0.236893 -vn 0.819551 -0.163019 0.549328 -v 0.082373 0.067971 0.236893 -vn 0.799625 -0.242563 0.549329 -v 0.082187 0.067225 0.236893 -vn 0.772000 -0.319771 0.549329 -v 0.081928 0.066501 0.236893 -vn 0.736940 -0.393903 0.549327 -v 0.081599 0.065806 0.236893 -vn 0.694782 -0.464238 0.549328 -v 0.081204 0.065147 0.236893 -vn 0.645931 -0.530105 0.549328 -v 0.080746 0.064529 0.236893 -vn 0.590862 -0.590862 0.549330 -v 0.080229 0.063959 0.236893 -vn 0.530104 -0.645931 0.549329 -v 0.079660 0.063443 0.236893 -vn 0.464238 -0.694782 0.549328 -v 0.079042 0.062985 0.236893 -vn 0.393903 -0.736937 0.549331 -v 0.078383 0.062590 0.236893 -vn 0.319772 -0.772005 0.549322 -v 0.077688 0.062261 0.236893 -vn 0.242565 -0.799628 0.549324 -v 0.076964 0.062002 0.236893 -vn 0.163019 -0.819552 0.549326 -v 0.076218 0.061815 0.236893 -vn 0.081904 -0.831583 0.549328 -v 0.075458 0.061703 0.236893 -vn 0.000000 -0.835607 0.549328 -v 0.074690 0.061665 0.236893 -vn -0.081903 -0.831583 0.549328 -v 0.073922 0.061703 0.236893 -vn -0.163021 -0.819553 0.549325 -v 0.073161 0.061815 0.236893 -vn -0.242564 -0.799627 0.549327 -v 0.072415 0.062002 0.236893 -vn -0.319775 -0.772002 0.549325 -v 0.071692 0.062261 0.236893 -vn -0.393902 -0.736939 0.549330 -v 0.070997 0.062590 0.236893 -vn -0.464240 -0.694784 0.549324 -v 0.070337 0.062985 0.236893 -vn -0.530105 -0.645935 0.549324 -v 0.069720 0.063443 0.236893 -vn -0.590862 -0.590862 0.549330 -v 0.069150 0.063959 0.236893 -vn -0.645927 -0.530102 0.549337 -v 0.068634 0.064529 0.236893 -vn -0.694783 -0.464238 0.549326 -v 0.068176 0.065147 0.236893 -vn -0.736940 -0.393902 0.549328 -v 0.067780 0.065806 0.236893 -vn -0.771998 -0.319773 0.549331 -v 0.067452 0.066501 0.236893 -vn -0.799626 -0.242563 0.549328 -v 0.067193 0.067225 0.236893 -vn -0.819556 -0.163017 0.549322 -v 0.067006 0.067971 0.236893 -vn -0.831584 -0.081906 0.549327 -v 0.066893 0.068731 0.236893 -vn -0.835606 -0.000001 0.549329 -v 0.066855 0.069499 0.236893 -vn -0.831585 0.081906 0.549324 -v 0.066893 0.070267 0.236893 -vn -0.819554 0.163019 0.549323 -v 0.067006 0.071028 0.236893 -vn -0.799625 0.242562 0.549330 -v 0.067193 0.071773 0.236893 -vn -0.771998 0.319775 0.549329 -v 0.067452 0.072497 0.236893 -vn -0.736939 0.393902 0.549329 -v 0.067780 0.073192 0.236893 -vn -0.694784 0.464241 0.549323 -v 0.068176 0.073852 0.236893 -vn -0.645933 0.530101 0.549330 -v 0.068634 0.074469 0.236893 -vn -0.590864 0.590866 0.549324 -v 0.069150 0.075039 0.236893 -vn -0.530104 0.645935 0.549324 -v 0.069720 0.075555 0.236893 -vn -0.464240 0.694786 0.549322 -v 0.070337 0.076013 0.236893 -vn -0.393903 0.736939 0.549328 -v 0.070997 0.076408 0.236893 -vn -0.319773 0.771999 0.549330 -v 0.071692 0.076737 0.236893 -vn -0.242564 0.799623 0.549333 -v 0.072415 0.076996 0.236893 -vn -0.163019 0.819555 0.549322 -v 0.073161 0.077183 0.236893 -vn -0.081904 0.831585 0.549325 -v 0.073922 0.077296 0.236893 -vn -0.000001 0.835604 0.549332 -v 0.074690 0.077333 0.236893 -vn 0.081904 0.831584 0.549326 -v 0.075458 0.077296 0.236893 -vn 0.163021 0.819554 0.549322 -v 0.076218 0.077183 0.236893 -vn 0.242562 0.799625 0.549330 -v 0.076964 0.076996 0.236893 -vn 0.319773 0.772001 0.549327 -v 0.077688 0.076737 0.236893 -vn 0.393901 0.736939 0.549330 -v 0.078383 0.076408 0.236893 -vn 0.464240 0.694781 0.549327 -v 0.079042 0.076013 0.236893 -vn 0.530104 0.645933 0.549327 -v 0.079660 0.075555 0.236893 -vn 0.590865 0.590866 0.549323 -v 0.080229 0.075039 0.236893 -vn 0.645935 0.530105 0.549323 -v 0.080746 0.074469 0.236893 -vn 0.694784 0.464239 0.549324 -v 0.081204 0.073852 0.236893 -vn 0.736939 0.393903 0.549328 -v 0.081599 0.073192 0.236893 -vn 0.772000 0.319773 0.549328 -v 0.081928 0.072497 0.236893 -vn 0.799624 0.242564 0.549331 -v 0.082187 0.071773 0.236893 -vn 0.819550 0.163020 0.549329 -v 0.082373 0.071028 0.236893 -vn 0.831586 0.081903 0.549323 -v 0.082486 0.070267 0.236893 -vn 0.835610 -0.000000 0.549323 -v 0.082524 0.069499 0.236893 -vn 0.692286 -0.067518 0.718458 -v 0.082293 0.068750 0.237110 -vn 0.682783 -0.136425 0.717771 -v 0.082183 0.068009 0.237110 -vn 0.665838 -0.201856 0.718271 -v 0.082001 0.067281 0.237110 -vn 0.642769 -0.266354 0.718265 -v 0.081748 0.066575 0.237110 -vn 0.611272 -0.328445 0.720049 -v 0.081428 0.065898 0.237110 -vn 0.578602 -0.384830 0.719114 -v 0.081042 0.065254 0.237110 -vn 0.537993 -0.440996 0.718391 -v 0.080596 0.064652 0.237110 -vn 0.491935 -0.492741 0.717779 -v 0.080092 0.064097 0.237110 -vn 0.441707 -0.537707 0.718169 -v 0.079537 0.063593 0.237110 -vn 0.386407 -0.578807 0.718103 -v 0.078934 0.063147 0.237110 -vn 0.326390 -0.612999 0.719515 -v 0.078291 0.062761 0.237110 -vn 0.267302 -0.641888 0.718700 -v 0.077613 0.062441 0.237110 -vn 0.202075 -0.665683 0.718354 -v 0.076907 0.062188 0.237110 -vn 0.135337 -0.682927 0.717841 -v 0.076180 0.062006 0.237110 -vn 0.068690 -0.692498 0.718142 -v 0.075438 0.061896 0.237110 -vn -0.000422 -0.696073 0.717971 -v 0.074690 0.061859 0.237110 -vn -0.068862 -0.691515 0.719072 -v 0.073941 0.061896 0.237110 -vn -0.134612 -0.682528 0.718356 -v 0.073199 0.062006 0.237110 -vn -0.202075 -0.665681 0.718355 -v 0.072472 0.062188 0.237110 -vn -0.266729 -0.642959 0.717955 -v 0.071766 0.062441 0.237110 -vn -0.327499 -0.613966 0.718185 -v 0.071088 0.062761 0.237110 -vn -0.387212 -0.578565 0.717865 -v 0.070445 0.063147 0.237110 -vn -0.441422 -0.537210 0.718716 -v 0.069843 0.063593 0.237110 -vn -0.491469 -0.492776 0.718074 -v 0.069287 0.064097 0.237110 -vn -0.537994 -0.440996 0.718391 -v 0.068784 0.064652 0.237110 -vn -0.578745 -0.386457 0.718126 -v 0.068337 0.065254 0.237110 -vn -0.613286 -0.328548 0.718288 -v 0.067952 0.065898 0.237110 -vn -0.643476 -0.265907 0.717797 -v 0.067631 0.066575 0.237110 -vn -0.665662 -0.201792 0.718453 -v 0.067378 0.067281 0.237110 -vn -0.682201 -0.135811 0.718441 -v 0.067196 0.068009 0.237110 -vn -0.690127 -0.066026 0.720670 -v 0.067086 0.068750 0.237110 -vn -0.694381 -0.001628 0.719606 -v 0.067049 0.069499 0.237110 -vn -0.692291 0.067519 0.718453 -v 0.067086 0.070248 0.237110 -vn -0.682787 0.136425 0.717767 -v 0.067196 0.070990 0.237110 -vn -0.665837 0.201853 0.718273 -v 0.067378 0.071717 0.237110 -vn -0.642771 0.266356 0.718262 -v 0.067631 0.072423 0.237110 -vn -0.611276 0.328449 0.720044 -v 0.067952 0.073101 0.237110 -vn -0.578602 0.384829 0.719115 -v 0.068337 0.073744 0.237110 -vn -0.537997 0.440997 0.718387 -v 0.068784 0.074346 0.237110 -vn -0.491935 0.492740 0.717779 -v 0.069287 0.074902 0.237110 -vn -0.441706 0.537710 0.718167 -v 0.069843 0.075405 0.237110 -vn -0.386409 0.578804 0.718105 -v 0.070445 0.075852 0.237110 -vn -0.326391 0.613005 0.719510 -v 0.071088 0.076237 0.237110 -vn -0.267302 0.641889 0.718699 -v 0.071766 0.076558 0.237110 -vn -0.202076 0.665684 0.718352 -v 0.072472 0.076810 0.237110 -vn -0.135339 0.682928 0.717839 -v 0.073199 0.076993 0.237110 -vn -0.068688 0.692504 0.718137 -v 0.073941 0.077103 0.237110 -vn 0.000420 0.696073 0.717971 -v 0.074690 0.077139 0.237110 -vn 0.068863 0.691521 0.719067 -v 0.075438 0.077103 0.237110 -vn 0.134613 0.682533 0.718351 -v 0.076180 0.076993 0.237110 -vn 0.202077 0.665686 0.718350 -v 0.076907 0.076810 0.237110 -vn 0.266730 0.642965 0.717949 -v 0.077613 0.076558 0.237110 -vn 0.327505 0.613970 0.718179 -v 0.078291 0.076237 0.237110 -vn 0.387208 0.578557 0.717873 -v 0.078934 0.075852 0.237110 -vn 0.441418 0.537207 0.718720 -v 0.079537 0.075405 0.237110 -vn 0.491467 0.492778 0.718074 -v 0.080092 0.074902 0.237110 -vn 0.537996 0.440999 0.718387 -v 0.080596 0.074346 0.237110 -vn 0.578756 0.386456 0.718118 -v 0.081042 0.073744 0.237110 -vn 0.613283 0.328546 0.718291 -v 0.081428 0.073101 0.237110 -vn 0.643469 0.265904 0.717805 -v 0.081748 0.072423 0.237110 -vn 0.665660 0.201790 0.718455 -v 0.082001 0.071717 0.237110 -vn 0.682194 0.135811 0.718447 -v 0.082183 0.070990 0.237110 -vn 0.690121 0.066029 0.720676 -v 0.082293 0.070248 0.237110 -vn 0.694386 0.001623 0.719601 -v 0.082330 0.069499 0.237110 -vn 0.177917 0.689774 0.701825 -v 0.076172 0.075995 0.237925 -vn 0.239981 0.670828 0.701712 -v 0.077124 0.075701 0.237925 -vn 0.288345 0.626135 0.724439 -v 0.077239 0.075654 0.237925 -vn 0.345238 0.622480 0.702374 -v 0.078021 0.075269 0.237925 -vn 0.373483 0.550416 0.746695 -v 0.078391 0.075039 0.237925 -vn 0.448442 0.555106 0.700540 -v 0.078844 0.074708 0.237925 -vn -0.239988 0.670825 0.701712 -v 0.072256 0.075701 0.237925 -vn -0.177919 0.689780 0.701818 -v 0.073207 0.075995 0.237925 -vn -0.107730 0.667639 0.736649 -v 0.073390 0.076034 0.237925 -vn -0.063177 0.708780 0.702594 -v 0.074192 0.076143 0.237925 -vn 0.000667 0.664600 0.747199 -v 0.074690 0.076162 0.237925 -vn 0.060820 0.711269 0.700284 -v 0.075188 0.076143 0.237925 -vn 0.112277 0.675143 0.729092 -v 0.075989 0.076034 0.237925 -vn -0.575239 0.420551 0.701596 -v 0.069185 0.073252 0.237925 -vn -0.534428 0.470873 0.701901 -v 0.069806 0.074031 0.237925 -vn -0.453612 0.484499 0.747995 -v 0.069979 0.074210 0.237925 -vn -0.449626 0.551262 0.702813 -v 0.070536 0.074708 0.237925 -vn -0.372625 0.551528 0.746302 -v 0.070988 0.075039 0.237925 -vn -0.347953 0.623616 0.700022 -v 0.071358 0.075269 0.237925 -vn -0.288686 0.630780 0.720262 -v 0.072140 0.075654 0.237925 -vn -0.534447 -0.470878 0.701884 -v 0.069806 0.064967 0.237925 -vn -0.575239 -0.420551 0.701596 -v 0.069185 0.065746 0.237925 -vn -0.598826 -0.367047 0.711817 -v 0.069150 0.065798 0.237925 -vn -0.635100 -0.321940 0.702142 -v 0.068687 0.066608 0.237925 -vn -0.619835 -0.247192 0.744783 -v 0.068534 0.066949 0.237925 -vn -0.682138 -0.208835 0.700768 -v 0.068323 0.067535 0.237925 -vn -0.657128 -0.142539 0.740180 -v 0.068155 0.068199 0.237925 -vn -0.708973 -0.090273 0.699434 -v 0.068102 0.068506 0.237925 -vn -0.711277 -0.001522 0.702910 -v 0.068027 0.069499 0.237925 -vn -0.706592 0.089574 0.701929 -v 0.068102 0.070492 0.237925 -vn -0.655560 0.143569 0.741369 -v 0.068155 0.070799 0.237925 -vn -0.681946 0.208771 0.700974 -v 0.068323 0.071463 0.237925 -vn -0.620154 0.248758 0.743995 -v 0.068534 0.072049 0.237925 -vn -0.637700 0.322024 0.699742 -v 0.068687 0.072390 0.237925 -vn -0.600568 0.368059 0.709825 -v 0.069150 0.073201 0.237925 -vn -0.177931 -0.689779 0.701816 -v 0.073207 0.063004 0.237925 -vn -0.239997 -0.670796 0.701737 -v 0.072256 0.063297 0.237925 -vn -0.288363 -0.626134 0.724433 -v 0.072140 0.063344 0.237925 -vn -0.345233 -0.622483 0.702374 -v 0.071358 0.063729 0.237925 -vn -0.373473 -0.550404 0.746708 -v 0.070988 0.063959 0.237925 -vn -0.448441 -0.555102 0.700544 -v 0.070536 0.064290 0.237925 -vn -0.466194 -0.490777 0.736071 -v 0.069979 0.064788 0.237925 -vn 0.239989 -0.670799 0.701737 -v 0.077124 0.063297 0.237925 -vn 0.177928 -0.689772 0.701823 -v 0.076172 0.063004 0.237925 -vn 0.107734 -0.667621 0.736665 -v 0.075989 0.062965 0.237925 -vn 0.063171 -0.708757 0.702619 -v 0.075188 0.062855 0.237925 -vn -0.000668 -0.664597 0.747202 -v 0.074690 0.062837 0.237925 -vn -0.060811 -0.711247 0.700307 -v 0.074192 0.062855 0.237925 -vn -0.112284 -0.675124 0.729109 -v 0.073390 0.062965 0.237925 -vn 0.575240 -0.420510 0.701620 -v 0.080194 0.065746 0.237925 -vn 0.534465 -0.470886 0.701865 -v 0.079574 0.064967 0.237925 -vn 0.453621 -0.484497 0.747991 -v 0.079401 0.064788 0.237925 -vn 0.449601 -0.551239 0.702847 -v 0.078844 0.064290 0.237925 -vn 0.372613 -0.551516 0.746317 -v 0.078391 0.063959 0.237925 -vn 0.347949 -0.623618 0.700023 -v 0.078021 0.063729 0.237925 -vn 0.288689 -0.630766 0.720273 -v 0.077239 0.063344 0.237925 -vn 0.466195 0.490777 0.736071 -v 0.079401 0.074210 0.237925 -vn 0.534446 0.470882 0.701882 -v 0.079574 0.074031 0.237925 -vn 0.575241 0.420510 0.701619 -v 0.080194 0.073252 0.237925 -vn 0.598837 0.367023 0.711821 -v 0.080229 0.073201 0.237925 -vn 0.635075 0.321918 0.702174 -v 0.080692 0.072390 0.237925 -vn 0.619837 0.247188 0.744782 -v 0.080845 0.072049 0.237925 -vn 0.682145 0.208840 0.700759 -v 0.081056 0.071463 0.237925 -vn 0.657120 0.142541 0.740186 -v 0.081224 0.070799 0.237925 -vn 0.708974 0.090270 0.699434 -v 0.081278 0.070492 0.237925 -vn 0.711301 0.001522 0.702886 -v 0.081352 0.069499 0.237925 -vn 0.706593 -0.089575 0.701928 -v 0.081278 0.068506 0.237925 -vn 0.655558 -0.143573 0.741371 -v 0.081224 0.068199 0.237925 -vn 0.681938 -0.208773 0.700981 -v 0.081056 0.067535 0.237925 -vn 0.620152 -0.248755 0.743997 -v 0.080845 0.066949 0.237925 -vn 0.637692 -0.322016 0.699753 -v 0.080692 0.066608 0.237925 -vn 0.600577 -0.368035 0.709830 -v 0.080229 0.065798 0.237925 -vn 0.847750 -0.260604 0.461959 -v 0.081008 0.067550 0.237988 -vn 0.878340 -0.123341 0.461850 -v 0.081228 0.068514 0.237988 -vn 0.986855 -0.148744 0.063184 -v 0.081207 0.068517 0.238066 -vn 0.315836 -0.828318 0.462749 -v 0.077105 0.063344 0.237988 -vn 0.438355 -0.771019 0.461924 -v 0.077996 0.063773 0.237988 -vn 0.499002 -0.864298 0.063144 -v 0.077985 0.063791 0.238066 -vn -0.437019 -0.772407 0.460871 -v 0.071384 0.063773 0.237988 -vn -0.316419 -0.828154 0.462645 -v 0.072274 0.063344 0.237988 -vn -0.364615 -0.929014 0.063153 -v 0.072282 0.063364 0.238066 -vn -0.878340 -0.123342 0.461850 -v 0.068151 0.068514 0.237988 -vn -0.847733 -0.260594 0.461996 -v 0.068371 0.067550 0.237988 -vn -0.953666 -0.294167 0.063139 -v 0.068391 0.067556 0.238066 -vn -0.655961 0.596699 0.462240 -v 0.069843 0.073997 0.237988 -vn -0.729384 0.504706 0.461812 -v 0.069226 0.073224 0.237988 -vn -0.824591 0.562195 0.063134 -v 0.069244 0.073212 0.238066 -vn 0.070503 0.884104 0.461941 -v 0.075184 0.076093 0.237988 -vn -0.073312 0.884697 0.460365 -v 0.074195 0.076093 0.237988 -vn -0.074581 0.995214 0.063134 -v 0.074197 0.076072 0.238066 -vn 0.729747 0.504326 0.461654 -v 0.080153 0.073224 0.237988 -vn 0.656328 0.596274 0.462268 -v 0.079537 0.073997 0.237988 -vn 0.731589 0.678815 0.063156 -v 0.079521 0.073982 0.238066 -vn 0.795830 -0.391542 0.461898 -v 0.080647 0.066630 0.237988 -vn 0.729406 -0.504709 0.461775 -v 0.080153 0.065774 0.237988 -vn 0.655970 -0.596701 0.462224 -v 0.079537 0.065002 0.237988 -vn -0.554966 -0.691806 0.461970 -v 0.070567 0.064330 0.237988 -vn -0.656316 -0.596265 0.462296 -v 0.069843 0.065002 0.237988 -vn -0.729747 -0.504334 0.461645 -v 0.069226 0.065774 0.237988 -vn -0.438357 0.771019 0.461923 -v 0.071384 0.075225 0.237988 -vn -0.205788 0.862361 0.462585 -v 0.073218 0.075946 0.237988 -vn 0.206354 0.862185 0.462661 -v 0.076161 0.075946 0.237988 -vn 0.437022 0.772406 0.460870 -v 0.077996 0.075225 0.237988 -vn 0.847754 0.260607 0.461950 -v 0.081008 0.071448 0.237988 -vn 0.878341 0.123339 0.461849 -v 0.081228 0.070485 0.237988 -vn 0.554966 0.691810 0.461965 -v 0.078812 0.074669 0.237988 -vn 0.316412 0.828169 0.462623 -v 0.077105 0.075654 0.237988 -vn -0.315838 0.828333 0.462722 -v 0.072274 0.075654 0.237988 -vn -0.795829 0.391536 0.461903 -v 0.068732 0.072368 0.237988 -vn -0.847736 0.260599 0.461987 -v 0.068371 0.071448 0.237988 -vn -0.206365 -0.862204 0.462621 -v 0.073218 0.063053 0.237988 -vn -0.070500 -0.884108 0.461933 -v 0.074195 0.062905 0.237988 -vn 0.205797 -0.862373 0.462559 -v 0.076161 0.063053 0.237988 -vn 0.899171 0.433021 0.063124 -v 0.080628 0.072359 0.238066 -vn 0.953665 0.294169 0.063155 -v 0.080988 0.071442 0.238066 -vn 0.584470 0.732902 -0.348208 -v 0.078806 0.074661 0.238146 -vn 0.622242 0.780271 0.063173 -v 0.078799 0.074652 0.238066 -vn 0.222077 0.972982 0.063154 -v 0.076156 0.075925 0.238066 -vn 0.364611 0.929017 0.063136 -v 0.077098 0.075634 0.238066 -vn -0.208595 0.913919 -0.348196 -v 0.073220 0.075936 0.238146 -vn -0.222077 0.972981 0.063165 -v 0.073223 0.075925 0.238066 -vn -0.622243 0.780271 0.063173 -v 0.070580 0.074652 0.238066 -vn -0.498999 0.864296 0.063184 -v 0.071394 0.075207 0.238066 -vn -0.844573 0.406721 -0.348244 -v 0.068741 0.072364 0.238146 -vn -0.899171 0.433021 0.063124 -v 0.068751 0.072359 0.238066 -vn -0.998004 0.000000 0.063148 -v 0.068099 0.069499 0.238066 -vn -0.986858 0.148743 0.063142 -v 0.068172 0.070481 0.238066 -vn -0.878342 0.123340 0.461848 -v 0.068151 0.070485 0.237988 -vn -0.844571 -0.406724 -0.348247 -v 0.068741 0.066634 0.238146 -vn -0.899172 -0.433019 0.063124 -v 0.068751 0.066639 0.238066 -vn -0.795662 -0.392495 0.461378 -v 0.068732 0.066630 0.237988 -vn -0.622246 -0.780272 0.063138 -v 0.070580 0.064346 0.238066 -vn -0.731591 -0.678815 0.063123 -v 0.069858 0.065016 0.238066 -vn -0.208596 -0.913921 -0.348190 -v 0.073220 0.063062 0.238146 -vn -0.222080 -0.972980 0.063166 -v 0.073223 0.063073 0.238066 -vn 0.222077 -0.972982 0.063154 -v 0.076156 0.063073 0.238066 -vn 0.074583 -0.995214 0.063137 -v 0.075182 0.062927 0.238066 -vn 0.073310 -0.884702 0.460357 -v 0.075184 0.062905 0.237988 -vn 0.584462 -0.732894 -0.348239 -v 0.078806 0.064337 0.238146 -vn 0.622245 -0.780273 0.063137 -v 0.078799 0.064346 0.238066 -vn 0.558478 -0.690363 0.459892 -v 0.078812 0.064330 0.237988 -vn 0.899173 -0.433016 0.063123 -v 0.080628 0.066639 0.238066 -vn 0.824591 -0.562195 0.063137 -v 0.080135 0.065786 0.238066 -vn 0.937416 0.000002 -0.348212 -v 0.081292 0.069499 0.238146 -vn 0.998004 0.000002 0.063148 -v 0.081281 0.069499 0.238066 -vn 0.889866 0.000000 0.456222 -v 0.081302 0.069499 0.237988 -vn 0.892871 0.286023 -0.347811 -v 0.080999 0.071445 0.238146 -vn 0.847129 0.407955 -0.340509 -v 0.080638 0.072364 0.238146 -vn 0.779981 0.520286 -0.347754 -v 0.080145 0.073218 0.238146 -vn 0.333066 0.876407 -0.347819 -v 0.077102 0.075645 0.238146 -vn 0.209224 0.916669 -0.340505 -v 0.076159 0.075936 0.238146 -vn 0.079539 0.934202 -0.347764 -v 0.075183 0.076083 0.238146 -vn -0.477544 0.806836 -0.347804 -v 0.071388 0.075217 0.238146 -vn -0.586237 0.735116 -0.340486 -v 0.070573 0.074661 0.238146 -vn -0.680797 0.644647 -0.347772 -v 0.069850 0.073990 0.238146 -vn -0.928537 0.129698 -0.347847 -v 0.068161 0.070483 0.238146 -vn -0.940241 0.000000 -0.340509 -v 0.068087 0.069499 0.238146 -vn -0.928480 -0.130336 -0.347761 -v 0.068161 0.068515 0.238146 -vn -0.680333 -0.645092 -0.347855 -v 0.069850 0.065008 0.238146 -vn -0.586229 -0.735107 -0.340520 -v 0.070573 0.064337 0.238146 -vn -0.476997 -0.807179 -0.347758 -v 0.071388 0.063781 0.238146 -vn 0.080173 -0.934134 -0.347802 -v 0.075183 0.062915 0.238146 -vn 0.209226 -0.916670 -0.340500 -v 0.076159 0.063062 0.238146 -vn 0.333671 -0.876195 -0.347774 -v 0.077102 0.063353 0.238146 -vn 0.780320 -0.519739 -0.347812 -v 0.080145 0.065780 0.238146 -vn 0.847127 -0.407957 -0.340511 -v 0.080638 0.066634 0.238146 -vn 0.893088 -0.285424 -0.347745 -v 0.080999 0.067553 0.238146 -vn 0.926119 0.145292 -0.348130 -v 0.081218 0.070483 0.238146 -vn 0.784521 0.130173 -0.606285 -v 0.081260 0.070489 0.238215 -vn 0.746744 0.059259 -0.662466 -v 0.081307 0.070095 0.238215 -vn 0.986856 0.148741 0.063185 -v 0.081207 0.070481 0.238066 -vn 0.795478 -0.000000 -0.605983 -v 0.081334 0.069499 0.238215 -vn 0.743730 0.181437 -0.643387 -v 0.081095 0.071267 0.238215 -vn 0.512097 0.546633 -0.662533 -v 0.079281 0.074302 0.238215 -vn 0.592377 0.529283 -0.607412 -v 0.079560 0.074018 0.238215 -vn 0.693683 0.631622 -0.346206 -v 0.079529 0.073990 0.238146 -vn 0.824593 0.562192 0.063136 -v 0.080135 0.073212 0.238066 -vn 0.795669 0.392492 0.461368 -v 0.080647 0.072368 0.237988 -vn 0.596073 0.467351 -0.652902 -v 0.080065 0.073405 0.238215 -vn 0.669653 0.428610 -0.606514 -v 0.080179 0.073242 0.238215 -vn 0.714841 0.344318 -0.608644 -v 0.080676 0.072382 0.238215 -vn 0.752561 0.256231 -0.606629 -v 0.081039 0.071458 0.238215 -vn 0.495731 0.621931 -0.606178 -v 0.078832 0.074694 0.238215 -vn 0.463831 0.814652 -0.348143 -v 0.077991 0.075217 0.238146 -vn 0.387480 0.694336 -0.606430 -v 0.078012 0.075253 0.238215 -vn 0.419247 0.620786 -0.662463 -v 0.078350 0.075044 0.238215 -vn 0.499001 0.864295 0.063182 -v 0.077985 0.075207 0.238066 -vn 0.321635 0.694527 -0.643571 -v 0.077301 0.075609 0.238215 -vn -0.107988 0.741129 -0.662621 -v 0.073798 0.076083 0.238215 -vn -0.044750 0.792875 -0.607739 -v 0.074193 0.076125 0.238215 -vn -0.061318 0.936144 -0.346228 -v 0.074196 0.076083 0.238146 -vn 0.074583 0.995214 0.063137 -v 0.075182 0.076072 0.238066 -vn 0.006537 0.757152 -0.653206 -v 0.074988 0.076137 0.238215 -vn 0.082597 0.790877 -0.606375 -v 0.075186 0.076125 0.238215 -vn 0.176424 0.773768 -0.608406 -v 0.076168 0.075977 0.238215 -vn 0.268851 0.748152 -0.606619 -v 0.077117 0.075684 0.238215 -vn -0.177254 0.775321 -0.606183 -v 0.073211 0.075977 0.238215 -vn -0.347725 0.870566 -0.348141 -v 0.072278 0.075645 0.238146 -vn -0.301009 0.737578 -0.604461 -v 0.072262 0.075684 0.238215 -vn -0.225480 0.715507 -0.661217 -v 0.072636 0.075818 0.238215 -vn -0.364615 0.929014 0.063154 -v 0.072282 0.075634 0.238066 -vn -0.342814 0.685171 -0.642666 -v 0.071541 0.075350 0.238215 -vn -0.646758 0.377657 -0.662631 -v 0.068986 0.072907 0.238215 -vn -0.647783 0.459110 -0.607944 -v 0.069200 0.073242 0.238215 -vn -0.770131 0.535731 -0.346253 -v 0.069235 0.073218 0.238146 -vn -0.731591 0.678815 0.063122 -v 0.069858 0.073982 0.238066 -vn -0.558497 0.690378 0.459847 -v 0.070567 0.074669 0.237988 -vn -0.587630 0.477223 -0.653414 -v 0.069686 0.073871 0.238215 -vn -0.566774 0.557946 -0.606187 -v 0.069819 0.074018 0.238215 -vn -0.495057 0.621348 -0.607327 -v 0.070547 0.074694 0.238215 -vn -0.418042 0.677266 -0.605435 -v 0.071367 0.075253 0.238215 -vn -0.716470 0.344925 -0.606380 -v 0.068703 0.072382 0.238215 -vn -0.897428 0.270919 -0.348174 -v 0.068381 0.071445 0.238146 -vn -0.764008 0.223975 -0.605085 -v 0.068340 0.071458 0.238215 -vn -0.699413 0.269865 -0.661812 -v 0.068469 0.071834 0.238215 -vn -0.953664 0.294170 0.063154 -v 0.068391 0.071442 0.238066 -vn -0.749187 0.159377 -0.642898 -v 0.068152 0.070686 0.238215 -vn -0.698576 -0.270315 -0.662511 -v 0.068469 0.067164 0.238215 -vn -0.762749 -0.220301 -0.608015 -v 0.068340 0.067541 0.238215 -vn -0.899022 -0.268093 -0.346245 -v 0.068381 0.067553 0.238146 -vn -0.986858 -0.148744 0.063138 -v 0.068172 0.068517 0.238066 -vn -0.889869 -0.000001 0.456216 -v 0.068077 0.069499 0.237988 -vn -0.739411 -0.161756 -0.653534 -v 0.068152 0.068313 0.238215 -vn -0.789484 -0.095334 -0.606322 -v 0.068119 0.068509 0.238215 -vn -0.794408 0.000432 -0.607384 -v 0.068045 0.069499 0.238215 -vn -0.789981 0.095163 -0.605702 -v 0.068119 0.070489 0.238215 -vn -0.716545 -0.345260 -0.606101 -v 0.068703 0.066616 0.238215 -vn -0.771353 -0.532722 -0.348170 -v 0.069235 0.065780 0.238146 -vn -0.650971 -0.457780 -0.605536 -v 0.069200 0.065756 0.238215 -vn -0.647227 -0.378053 -0.661947 -v 0.068986 0.066091 0.238215 -vn -0.824589 -0.562198 0.063135 -v 0.069244 0.065786 0.238066 -vn -0.591720 -0.486169 -0.643045 -v 0.069686 0.065128 0.238215 -vn -0.223651 -0.715606 -0.661732 -v 0.072636 0.063180 0.238215 -vn -0.303331 -0.733718 -0.607987 -v 0.072262 0.063314 0.238215 -vn -0.350928 -0.870041 -0.346234 -v 0.072278 0.063353 0.238146 -vn -0.499001 -0.864298 0.063144 -v 0.071394 0.063791 0.238066 -vn -0.334551 -0.678917 -0.653566 -v 0.071541 0.063648 0.238215 -vn -0.417427 -0.676652 -0.606545 -v 0.071367 0.063745 0.238215 -vn -0.495249 -0.620539 -0.607997 -v 0.070547 0.064304 0.238215 -vn -0.566829 -0.557953 -0.606130 -v 0.069819 0.064980 0.238215 -vn -0.177775 -0.775960 -0.605213 -v 0.073211 0.063021 0.238215 -vn -0.064433 -0.935231 -0.348127 -v 0.074196 0.062915 0.238146 -vn -0.047687 -0.794169 -0.605822 -v 0.074193 0.062873 0.238215 -vn -0.108188 -0.741471 -0.662205 -v 0.073798 0.062915 0.238215 -vn -0.074580 -0.995215 0.063134 -v 0.074197 0.062927 0.238066 -vn 0.011114 -0.765679 -0.643127 -v 0.074988 0.062861 0.238215 -vn 0.419583 -0.620991 -0.662058 -v 0.078350 0.063954 0.238215 -vn 0.384479 -0.694704 -0.607916 -v 0.078012 0.063745 0.238215 -vn 0.461423 -0.816828 -0.346238 -v 0.077991 0.063781 0.238146 -vn 0.364614 -0.929016 0.063135 -v 0.077098 0.063364 0.238066 -vn 0.322293 -0.684871 -0.653512 -v 0.077301 0.063389 0.238215 -vn 0.268843 -0.748132 -0.606649 -v 0.077117 0.063314 0.238215 -vn 0.176417 -0.773746 -0.608436 -v 0.076168 0.063021 0.238215 -vn 0.082623 -0.790848 -0.606410 -v 0.075186 0.062873 0.238215 -vn 0.495891 -0.622282 -0.605688 -v 0.078832 0.064304 0.238215 -vn 0.691013 -0.633477 -0.348150 -v 0.079529 0.065008 0.238146 -vn 0.591217 -0.532237 -0.605959 -v 0.079560 0.064980 0.238215 -vn 0.512028 -0.546888 -0.662375 -v 0.079281 0.064697 0.238215 -vn 0.731590 -0.678813 0.063156 -v 0.079521 0.065016 0.238066 -vn 0.605603 -0.468696 -0.643093 -v 0.080065 0.065594 0.238215 -vn 0.746852 -0.059390 -0.662333 -v 0.081307 0.068904 0.238215 -vn 0.782960 -0.132739 -0.607745 -v 0.081260 0.068509 0.238215 -vn 0.926333 -0.148537 -0.346184 -v 0.081218 0.068515 0.238146 -vn 0.953666 -0.294167 0.063142 -v 0.080988 0.067556 0.238066 -vn 0.736610 -0.174905 -0.653310 -v 0.081095 0.067731 0.238215 -vn 0.752560 -0.256232 -0.606629 -v 0.081039 0.067541 0.238215 -vn 0.714851 -0.344321 -0.608631 -v 0.080676 0.066616 0.238215 -vn 0.669657 -0.428604 -0.606513 -v 0.080179 0.065756 0.238215 -vn -0.728957 0.311178 -0.609746 -v 0.065978 0.072948 0.241135 -vn -0.702842 0.366508 -0.609659 -v 0.066479 0.074013 0.241135 -vn -0.680884 0.427025 -0.595019 -v 0.066646 0.074305 0.241135 -vn -0.644107 0.464193 -0.607990 -v 0.067109 0.075007 0.241135 -vn -0.609760 0.516083 -0.601541 -v 0.067633 0.075664 0.241135 -vn 0.131101 0.781483 -0.609998 -v 0.076445 0.078703 0.241135 -vn -0.565188 0.555255 -0.610127 -v 0.067859 0.075913 0.241135 -vn -0.521277 0.596526 -0.610268 -v 0.068717 0.076719 0.241135 -vn -0.479090 0.636475 -0.604460 -v 0.068848 0.076825 0.241135 -vn -0.432490 0.664129 -0.609824 -v 0.069669 0.077410 0.241135 -vn -0.382231 0.702783 -0.599997 -v 0.070250 0.077750 0.241135 -vn -0.324843 0.721987 -0.610910 -v 0.070700 0.077977 0.241135 -vn -0.245342 0.754133 -0.609173 -v 0.071794 0.078410 0.241135 -vn -0.162196 0.775917 -0.609627 -v 0.072934 0.078703 0.241135 -vn -0.096722 0.805088 -0.585216 -v 0.073432 0.078784 0.241135 -vn -0.047531 0.793166 -0.607148 -v 0.074101 0.078850 0.241135 -vn 0.016171 0.795465 -0.605783 -v 0.075110 0.078859 0.241135 -vn 0.070857 0.789205 -0.610028 -v 0.075278 0.078850 0.241135 -vn 0.195852 0.779332 -0.595217 -v 0.076775 0.078634 0.241135 -vn 0.242098 0.756077 -0.608059 -v 0.077585 0.078410 0.241135 -vn 0.302624 0.739452 -0.601357 -v 0.078372 0.078115 0.241135 -vn 0.353192 0.709565 -0.609732 -v 0.078679 0.077977 0.241135 -vn 0.406796 0.680223 -0.609765 -v 0.079710 0.077410 0.241135 -vn 0.457023 0.653224 -0.603679 -v 0.079851 0.077319 0.241135 -vn 0.498996 0.616642 -0.608897 -v 0.080662 0.076719 0.241135 -vn 0.550167 0.581603 -0.599211 -v 0.081165 0.076272 0.241135 -vn 0.587256 0.532012 -0.609995 -v 0.081520 0.075913 0.241135 -vn 0.641417 0.466339 -0.609190 -v 0.082270 0.075007 0.241135 -vn 0.687709 0.394009 -0.609765 -v 0.082900 0.074013 0.241135 -vn 0.735771 0.340687 -0.585298 -v 0.083132 0.073565 0.241135 -vn 0.739608 0.290591 -0.607072 -v 0.083401 0.072948 0.241135 -vn 0.761806 0.230313 -0.605481 -v 0.083722 0.071992 0.241135 -vn 0.772543 0.176556 -0.609922 -v 0.083765 0.071829 0.241135 -vn 0.783917 0.116726 -0.609794 -v 0.083986 0.070673 0.241135 -vn 0.801708 0.054565 -0.595220 -v 0.084022 0.070339 0.241135 -vn 0.793815 0.003223 -0.608151 -v 0.084059 0.069499 0.241135 -vn 0.796501 -0.059254 -0.601727 -v 0.084022 0.068659 0.241135 -vn 0.783808 -0.116576 -0.609963 -v 0.083986 0.068325 0.241135 -vn 0.772545 -0.176551 -0.609921 -v 0.083765 0.067169 0.241135 -vn 0.762573 -0.232748 -0.603581 -v 0.083722 0.067006 0.241135 -vn 0.740619 -0.284071 -0.608923 -v 0.083401 0.066050 0.241135 -vn 0.723190 -0.343499 -0.599170 -v 0.083132 0.065434 0.241135 -vn 0.687711 -0.394010 -0.609762 -v 0.082900 0.064985 0.241135 -vn 0.641500 -0.466320 -0.609117 -v 0.082270 0.063992 0.241135 -vn 0.587300 -0.532088 -0.609887 -v 0.081520 0.063085 0.241135 -vn 0.551181 -0.594491 -0.585474 -v 0.081165 0.062727 0.241135 -vn 0.504718 -0.613463 -0.607390 -v 0.080662 0.062280 0.241135 -vn 0.454201 -0.653013 -0.606033 -v 0.079851 0.061679 0.241135 -vn 0.406874 -0.679898 -0.610076 -v 0.079710 0.061588 0.241135 -vn 0.353191 -0.709567 -0.609731 -v 0.078679 0.061021 0.241135 -vn 0.299848 -0.745690 -0.595010 -v 0.078372 0.060883 0.241135 -vn 0.248231 -0.754088 -0.608057 -v 0.077585 0.060588 0.241135 -vn 0.189940 -0.775914 -0.601564 -v 0.076775 0.060364 0.241135 -vn 0.131099 -0.781483 -0.609998 -v 0.076445 0.060295 0.241135 -vn 0.070902 -0.789230 -0.609992 -v 0.075278 0.060148 0.241135 -vn 0.013927 -0.796867 -0.603994 -v 0.075110 0.060139 0.241135 -vn -0.040943 -0.791933 -0.609233 -v 0.074101 0.060148 0.241135 -vn -0.103472 -0.793642 -0.599522 -v 0.073432 0.060214 0.241135 -vn -0.162081 -0.775399 -0.610316 -v 0.072934 0.060295 0.241135 -vn -0.244744 -0.754403 -0.609079 -v 0.071794 0.060588 0.241135 -vn -0.324925 -0.723063 -0.609593 -v 0.070700 0.061021 0.241135 -vn -0.394948 -0.708248 -0.585151 -v 0.070250 0.061248 0.241135 -vn -0.427794 -0.669586 -0.607163 -v 0.069669 0.061588 0.241135 -vn -0.480642 -0.634080 -0.605744 -v 0.068848 0.062174 0.241135 -vn -0.521274 -0.596531 -0.610266 -v 0.068717 0.062280 0.241135 -vn -0.565183 -0.555232 -0.610153 -v 0.067859 0.063085 0.241135 -vn -0.616533 -0.514945 -0.595583 -v 0.067633 0.063334 0.241135 -vn -0.639859 -0.469279 -0.608570 -v 0.067109 0.063992 0.241135 -vn -0.679141 -0.419823 -0.602093 -v 0.066646 0.064693 0.241135 -vn -0.702231 -0.366700 -0.610249 -v 0.066479 0.064985 0.241135 -vn -0.728960 -0.311173 -0.609745 -v 0.065978 0.066050 0.241135 -vn -0.753761 -0.259980 -0.603535 -v 0.065917 0.066207 0.241135 -vn -0.766251 -0.205478 -0.608801 -v 0.065614 0.067169 0.241135 -vn -0.787026 -0.147261 -0.599087 -v 0.065470 0.067826 0.241135 -vn -0.787867 -0.085125 -0.609934 -v 0.065394 0.068325 0.241135 -vn -0.792501 0.000320 -0.609871 -v 0.065320 0.069499 0.241135 -vn -0.787551 0.084827 -0.610384 -v 0.065394 0.070673 0.241135 -vn -0.794971 0.157295 -0.585901 -v 0.065470 0.071172 0.241135 -vn -0.768633 0.199164 -0.607895 -v 0.065614 0.071829 0.241135 -vn -0.751571 0.261175 -0.605746 -v 0.065917 0.072791 0.241135 -vn 0.684476 -0.423107 0.593694 -v 0.082739 0.064690 0.242492 -vn 0.644939 -0.473003 0.600268 -v 0.082276 0.063988 0.242492 -vn 0.754748 -0.551761 0.354845 -v 0.082433 0.063873 0.242177 -vn 0.484446 -0.639085 0.597397 -v 0.080536 0.062168 0.242492 -vn 0.431190 -0.674881 0.598840 -v 0.079714 0.061582 0.242492 -vn 0.499523 -0.789825 0.355884 -v 0.079819 0.061417 0.242177 -vn -0.457785 -0.658181 0.597688 -v 0.069524 0.061673 0.242492 -vn -0.508709 -0.618321 0.599078 -v 0.068713 0.062274 0.242492 -vn -0.596809 -0.719144 0.355881 -v 0.068588 0.062124 0.242177 -vn -0.767822 0.232133 0.597130 -v 0.065651 0.071994 0.242492 -vn -0.745465 0.292882 0.598751 -v 0.065971 0.072951 0.242492 -vn -0.868370 0.345371 0.355882 -v 0.065790 0.073023 0.242177 -vn -0.016304 0.801744 0.597445 -v 0.074269 0.078867 0.242492 -vn 0.047899 0.799438 0.598836 -v 0.075278 0.078857 0.242492 -vn 0.060126 0.932594 0.355884 -v 0.075291 0.079052 0.242177 -vn -0.401171 -0.845168 0.353204 -v 0.070614 0.060838 0.242177 -vn -0.425774 -0.904815 -0.005177 -v 0.070586 0.060778 0.241812 -vn -0.309014 -0.951044 -0.005178 -v 0.071711 0.060332 0.241812 -vn -0.927769 0.120364 0.353210 -v 0.065193 0.070699 0.242177 -vn -0.992101 0.125332 -0.005176 -v 0.065127 0.070707 0.241812 -vn -0.999987 -0.000000 -0.005177 -v 0.065051 0.069499 0.241812 -vn -0.172224 0.919557 0.353204 -v 0.072896 0.078901 0.242177 -vn -0.187379 0.982274 -0.005176 -v 0.072884 0.078967 0.241812 -vn -0.309015 0.951043 -0.005178 -v 0.071711 0.078666 0.241812 -vn 0.821334 0.447953 0.353199 -v 0.083078 0.074110 0.242177 -vn 0.876295 0.481747 -0.005179 -v 0.083136 0.074143 0.241812 -vn 0.809007 0.587777 -0.005175 -v 0.082488 0.075165 0.241812 -vn -0.393753 -0.844440 -0.363152 -v 0.070616 0.060842 0.241448 -vn -0.287502 -0.884840 -0.366607 -v 0.071733 0.060399 0.241448 -vn -0.924785 0.113537 -0.363156 -v 0.065197 0.070698 0.241448 -vn -0.930373 0.000000 -0.366613 -v 0.065122 0.069499 0.241448 -vn -0.177798 0.914609 -0.363151 -v 0.072897 0.078898 0.241448 -vn -0.287503 0.884838 -0.366610 -v 0.071733 0.078599 0.241448 -vn 0.814904 0.451726 -0.363147 -v 0.083074 0.074109 0.241448 -vn 0.752690 0.546861 -0.366607 -v 0.082430 0.075123 0.241448 -vn 0.681436 -0.635427 -0.363149 -v 0.081664 0.062949 0.241448 -vn 0.924086 0.119875 -0.362898 -v 0.084182 0.070698 0.241448 -vn 0.903206 0.228780 -0.363151 -v 0.083957 0.071879 0.241448 -vn 0.682345 0.634663 -0.362778 -v 0.081664 0.076049 0.241448 -vn 0.590876 0.720197 -0.363567 -v 0.080789 0.076871 0.241448 -vn 0.497424 0.787604 -0.363661 -v 0.079816 0.077578 0.241448 -vn 0.400790 0.841445 -0.362407 -v 0.078764 0.078157 0.241448 -vn 0.285155 0.886460 -0.364521 -v 0.077646 0.078599 0.241448 -vn 0.171551 0.915902 -0.362897 -v 0.076483 0.078898 0.241448 -vn 0.061523 0.929695 -0.363156 -v 0.075290 0.079048 0.241448 -vn -0.392742 0.845071 -0.362780 -v 0.070616 0.078157 0.241448 -vn -0.502360 0.784510 -0.363564 -v 0.069563 0.077578 0.241448 -vn -0.595342 0.716462 -0.363662 -v 0.068591 0.076871 0.241448 -vn -0.676410 0.641194 -0.362408 -v 0.067715 0.076049 0.241448 -vn -0.754957 0.545129 -0.364520 -v 0.066949 0.075123 0.241448 -vn -0.818060 0.446185 -0.362899 -v 0.066305 0.074109 0.241448 -vn -0.865181 0.345807 -0.363153 -v 0.065793 0.073021 0.241448 -vn -0.925073 -0.112379 -0.362783 -v 0.065197 0.068300 0.241448 -vn -0.901351 -0.235344 -0.363565 -v 0.065422 0.067120 0.241448 -vn -0.865368 -0.344807 -0.363658 -v 0.065793 0.065977 0.241448 -vn -0.818832 -0.445164 -0.362413 -v 0.066305 0.064890 0.241448 -vn -0.751742 -0.549550 -0.364526 -v 0.066949 0.063875 0.241448 -vn -0.677141 -0.640147 -0.362894 -v 0.067715 0.062949 0.241448 -vn -0.596237 -0.715974 -0.363156 -v 0.068591 0.062127 0.241448 -vn -0.178985 -0.914525 -0.362778 -v 0.072897 0.060100 0.241448 -vn -0.054706 -0.929960 -0.363569 -v 0.074089 0.059950 0.241448 -vn 0.060514 -0.929562 -0.363667 -v 0.075290 0.059950 0.241448 -vn 0.170343 -0.916320 -0.362411 -v 0.076483 0.060100 0.241448 -vn 0.290355 -0.884771 -0.364518 -v 0.077646 0.060399 0.241448 -vn 0.399564 -0.841816 -0.362896 -v 0.078764 0.060842 0.241448 -vn 0.496685 -0.788302 -0.363157 -v 0.079816 0.061420 0.241448 -vn 0.902768 -0.229697 -0.363661 -v 0.083957 0.067120 0.241448 -vn 0.867539 -0.339402 -0.363567 -v 0.083586 0.065977 0.241448 -vn 0.924110 -0.121154 -0.362411 -v 0.084182 0.068300 0.241448 -vn 0.931192 0.002732 -0.364518 -v 0.084258 0.069499 0.241448 -vn 0.968570 0.248686 -0.005176 -v 0.084026 0.071896 0.241812 -vn 0.992101 0.125332 -0.005176 -v 0.084252 0.070707 0.241812 -vn 0.728958 0.684538 -0.005177 -v 0.081716 0.076097 0.241812 -vn 0.637415 0.770503 -0.005176 -v 0.080834 0.076926 0.241812 -vn 0.535818 0.844318 -0.005171 -v 0.079854 0.077637 0.241812 -vn 0.425775 0.904814 -0.005184 -v 0.078794 0.078221 0.241812 -vn 0.309014 0.951043 -0.005176 -v 0.077668 0.078666 0.241812 -vn 0.187379 0.982274 -0.005179 -v 0.076496 0.078967 0.241812 -vn 0.062790 0.998013 -0.005187 -v 0.075295 0.079119 0.241812 -vn -0.425774 0.904815 -0.005180 -v 0.070586 0.078221 0.241812 -vn -0.535821 0.844316 -0.005171 -v 0.069525 0.077637 0.241812 -vn -0.637414 0.770504 -0.005182 -v 0.068546 0.076926 0.241812 -vn -0.728958 0.684539 -0.005184 -v 0.067663 0.076097 0.241812 -vn -0.809006 0.587777 -0.005181 -v 0.066892 0.075165 0.241812 -vn -0.876295 0.481747 -0.005179 -v 0.066243 0.074143 0.241812 -vn -0.929764 0.368120 -0.005176 -v 0.065728 0.073047 0.241812 -vn -0.992101 -0.125333 -0.005177 -v 0.065127 0.068291 0.241812 -vn -0.968570 -0.248687 -0.005176 -v 0.065354 0.067102 0.241812 -vn -0.929764 -0.368121 -0.005174 -v 0.065728 0.065951 0.241812 -vn -0.876295 -0.481747 -0.005179 -v 0.066243 0.064856 0.241812 -vn -0.809006 -0.587778 -0.005180 -v 0.066892 0.063834 0.241812 -vn -0.728958 -0.684539 -0.005178 -v 0.067663 0.062901 0.241812 -vn -0.637416 -0.770502 -0.005183 -v 0.068546 0.062072 0.241812 -vn -0.187379 -0.982274 -0.005177 -v 0.072884 0.060031 0.241812 -vn -0.062789 -0.998013 -0.005177 -v 0.074084 0.059879 0.241812 -vn 0.062789 -0.998013 -0.005177 -v 0.075295 0.059879 0.241812 -vn 0.187379 -0.982274 -0.005178 -v 0.076496 0.060031 0.241812 -vn 0.309014 -0.951043 -0.005175 -v 0.077668 0.060332 0.241812 -vn 0.425772 -0.904816 -0.005181 -v 0.078794 0.060778 0.241812 -vn 0.535820 -0.844317 -0.005176 -v 0.079854 0.061361 0.241812 -vn 0.999987 0.000000 -0.005177 -v 0.084328 0.069499 0.241812 -vn 0.992101 -0.125333 -0.005178 -v 0.084252 0.068291 0.241812 -vn 0.968570 -0.248686 -0.005178 -v 0.084026 0.067102 0.241812 -vn 0.929764 -0.368119 -0.005182 -v 0.083651 0.065951 0.241812 -vn 0.905531 0.231003 0.355882 -v 0.083961 0.071880 0.242177 -vn 0.928481 0.113975 0.353458 -v 0.084186 0.070699 0.242177 -vn 0.757984 0.547307 0.354846 -v 0.082433 0.075125 0.242177 -vn 0.679091 0.643761 0.352714 -v 0.081667 0.076052 0.242177 -vn 0.597728 0.719320 0.353979 -v 0.080791 0.076874 0.242177 -vn 0.504378 0.787637 0.353880 -v 0.079819 0.077581 0.242177 -vn 0.394295 0.848449 0.353080 -v 0.078765 0.078160 0.242177 -vn 0.288660 0.888402 0.356955 -v 0.077648 0.078603 0.242177 -vn 0.178520 0.918256 0.353463 -v 0.076483 0.078901 0.242177 -vn -0.286288 0.890014 0.354843 -v 0.071732 0.078603 0.242177 -vn -0.402403 0.844790 0.352707 -v 0.070614 0.078160 0.242177 -vn -0.499406 0.790756 0.353976 -v 0.069561 0.077581 0.242177 -vn -0.593225 0.723087 0.353879 -v 0.068588 0.076874 0.242177 -vn -0.685078 0.637182 0.353082 -v 0.067712 0.076052 0.242177 -vn -0.755720 0.549062 0.356956 -v 0.066946 0.075125 0.242177 -vn -0.818149 0.453540 0.353459 -v 0.066302 0.074110 0.242177 -vn -0.934919 0.002756 0.354851 -v 0.065118 0.069499 0.242177 -vn -0.927788 -0.121654 0.352718 -v 0.065193 0.068299 0.242177 -vn -0.906378 -0.230607 0.353976 -v 0.065418 0.067119 0.242177 -vn -0.871012 -0.340746 0.353879 -v 0.065790 0.065975 0.242177 -vn -0.817696 -0.454649 0.353083 -v 0.066302 0.064888 0.242177 -vn -0.755720 -0.549063 0.356955 -v 0.066946 0.063873 0.242177 -vn -0.684165 -0.637957 0.353454 -v 0.067712 0.062947 0.242177 -vn -0.291526 -0.888312 0.354844 -v 0.071732 0.060396 0.242177 -vn -0.171006 -0.919973 0.352713 -v 0.072896 0.060097 0.242177 -vn -0.060765 -0.933277 0.353979 -v 0.074089 0.059946 0.242177 -vn 0.054911 -0.933677 0.353882 -v 0.075291 0.059946 0.242177 -vn 0.179716 -0.918168 0.353087 -v 0.076483 0.060097 0.242177 -vn 0.288659 -0.888403 0.356955 -v 0.077648 0.060396 0.242177 -vn 0.395312 -0.847818 0.353459 -v 0.078765 0.060838 0.242177 -vn 0.752688 -0.546860 -0.366613 -v 0.082430 0.063875 0.241448 -vn 0.728959 -0.684538 -0.005171 -v 0.081716 0.062901 0.241812 -vn 0.809006 -0.587777 -0.005173 -v 0.082488 0.063834 0.241812 -vn 0.679833 -0.642709 0.353202 -v 0.081667 0.062947 0.242177 -vn 0.934122 -0.000000 0.356955 -v 0.084262 0.069499 0.242177 -vn 0.928766 -0.112811 0.353084 -v 0.084186 0.068299 0.242177 -vn 0.904949 -0.236299 0.353879 -v 0.083961 0.067119 0.242177 -vn 0.868823 -0.346190 0.353976 -v 0.083589 0.065975 0.242177 -vn 0.801022 0.158484 0.577276 -v 0.083916 0.071173 0.242492 -vn 0.774720 0.200749 0.599591 -v 0.083772 0.071831 0.242492 -vn 0.757510 0.263236 0.597399 -v 0.083469 0.072794 0.242492 -vn 0.734761 0.313649 0.601457 -v 0.083408 0.072951 0.242492 -vn 0.868631 0.347196 0.353462 -v 0.083589 0.073023 0.242177 -vn 0.929765 0.368118 -0.005184 -v 0.083651 0.073047 0.241812 -vn 0.864898 0.343982 -0.365551 -v 0.083586 0.073021 0.241448 -vn 0.708432 0.369422 0.601375 -v 0.082907 0.074016 0.242492 -vn 0.482869 0.641483 0.596101 -v 0.080536 0.076830 0.242492 -vn 0.525430 0.601271 0.601994 -v 0.080667 0.076724 0.242492 -vn 0.569683 0.559672 0.601854 -v 0.081525 0.075918 0.242492 -vn 0.614536 0.520132 0.593134 -v 0.081751 0.075669 0.242492 -vn 0.649209 0.467882 0.599679 -v 0.082276 0.075011 0.242492 -vn 0.686165 0.430316 0.586520 -v 0.082739 0.074309 0.242492 -vn 0.435929 0.669408 0.601547 -v 0.079714 0.077416 0.242492 -vn 0.385213 0.708276 0.591571 -v 0.079133 0.077756 0.242492 -vn 0.327434 0.727731 0.602656 -v 0.078682 0.077984 0.242492 -vn 0.247291 0.760120 0.600887 -v 0.077587 0.078417 0.242492 -vn 0.163479 0.782088 0.601343 -v 0.076447 0.078710 0.242492 -vn 0.097476 0.811197 0.576591 -v 0.075948 0.078791 0.242492 -vn -0.071422 0.795482 0.601753 -v 0.074101 0.078857 0.242492 -vn -0.061783 0.933405 0.353466 -v 0.074089 0.079052 0.242177 -vn -0.062789 0.998013 -0.005186 -v 0.074084 0.079119 0.241812 -vn -0.059878 0.928865 -0.365548 -v 0.074089 0.079048 0.241448 -vn -0.132147 0.787701 0.601719 -v 0.072933 0.078710 0.242492 -vn -0.460609 0.658379 0.595295 -v 0.069524 0.077325 0.242492 -vn -0.410031 0.685642 0.601473 -v 0.069665 0.077416 0.242492 -vn -0.356001 0.715210 0.601447 -v 0.070697 0.077984 0.242492 -vn -0.305001 0.745247 0.592944 -v 0.071004 0.078121 0.242492 -vn -0.244023 0.762073 0.599748 -v 0.071792 0.078417 0.242492 -vn -0.197353 0.785370 0.586725 -v 0.072603 0.078641 0.242492 -vn -0.502960 0.621536 0.600603 -v 0.068713 0.076724 0.242492 -vn -0.554462 0.586140 0.590771 -v 0.068210 0.076277 0.242492 -vn -0.591927 0.536240 0.601721 -v 0.067854 0.075918 0.242492 -vn -0.646506 0.470041 0.600909 -v 0.067104 0.075011 0.242492 -vn -0.693179 0.397145 0.601480 -v 0.066473 0.074016 0.242492 -vn -0.741359 0.343293 0.576661 -v 0.066241 0.073568 0.242492 -vn -0.778691 0.177971 0.601636 -v 0.065607 0.071831 0.242492 -vn -0.906813 0.229680 0.353464 -v 0.065418 0.071880 0.242177 -vn -0.968570 0.248687 -0.005176 -v 0.065354 0.071896 0.241812 -vn -0.901909 0.230085 -0.365543 -v 0.065422 0.071879 0.241448 -vn -0.790158 0.117655 0.601504 -v 0.065387 0.070674 0.242492 -vn -0.768572 -0.234581 0.595205 -v 0.065651 0.067005 0.242492 -vn -0.778691 -0.177971 0.601636 -v 0.065607 0.067167 0.242492 -vn -0.790048 -0.117502 0.601679 -v 0.065387 0.068324 0.242492 -vn -0.802748 -0.059725 0.593320 -v 0.065350 0.068659 0.242492 -vn -0.800105 0.003244 0.599851 -v 0.065313 0.069499 0.242492 -vn -0.807922 0.054999 0.586717 -v 0.065350 0.070340 0.242492 -vn -0.746498 -0.286330 0.600629 -v 0.065971 0.066047 0.242492 -vn -0.728837 -0.346182 0.590724 -v 0.066241 0.065431 0.242492 -vn -0.693183 -0.397143 0.601477 -v 0.066473 0.064982 0.242492 -vn -0.646591 -0.470024 0.600830 -v 0.067104 0.063988 0.242492 -vn -0.591970 -0.536328 0.601602 -v 0.067854 0.063080 0.242492 -vn -0.555379 -0.598995 0.576853 -v 0.068210 0.062722 0.242492 -vn -0.410117 -0.685311 0.601791 -v 0.069665 0.061582 0.242492 -vn -0.498657 -0.791457 0.353464 -v 0.069561 0.061417 0.242177 -vn -0.535819 -0.844317 -0.005175 -v 0.069525 0.061361 0.241812 -vn -0.497528 -0.786664 -0.365549 -v 0.069563 0.061420 0.241448 -vn -0.355997 -0.715212 0.601446 -v 0.070697 0.061015 0.242492 -vn -0.014038 -0.803141 0.595624 -v 0.074269 0.060132 0.242492 -vn -0.071459 -0.795515 0.601705 -v 0.074101 0.060141 0.242492 -vn -0.132146 -0.787701 0.601718 -v 0.072933 0.060288 0.242492 -vn -0.191426 -0.781999 0.593156 -v 0.072603 0.060357 0.242492 -vn -0.250192 -0.760071 0.599747 -v 0.071792 0.060581 0.242492 -vn -0.302185 -0.751457 0.586512 -v 0.071004 0.060877 0.242492 -vn 0.041271 -0.798226 0.600943 -v 0.075278 0.060141 0.242492 -vn 0.104285 -0.799839 0.591086 -v 0.075948 0.060207 0.242492 -vn 0.163369 -0.781569 0.602047 -v 0.076447 0.060288 0.242492 -vn 0.246682 -0.760391 0.600793 -v 0.077587 0.060581 0.242492 -vn 0.327509 -0.728812 0.601308 -v 0.078682 0.061015 0.242492 -vn 0.397929 -0.713638 0.576518 -v 0.079133 0.061242 0.242492 -vn 0.525427 -0.601277 0.601991 -v 0.080667 0.062274 0.242492 -vn 0.598627 -0.718823 0.353467 -v 0.080791 0.062124 0.242177 -vn 0.637416 -0.770503 -0.005176 -v 0.080834 0.062072 0.241812 -vn 0.594416 -0.716271 -0.365548 -v 0.080789 0.062127 0.241448 -vn 0.569685 -0.559652 0.601871 -v 0.081525 0.063080 0.242492 -vn 0.621301 -0.518944 0.587096 -v 0.081751 0.063330 0.242492 -vn 0.707819 -0.369615 0.601978 -v 0.082907 0.064982 0.242492 -vn 0.822105 -0.446924 0.352707 -v 0.083078 0.064888 0.242177 -vn 0.876295 -0.481748 -0.005179 -v 0.083136 0.064856 0.241812 -vn 0.814458 -0.452827 -0.362775 -v 0.083074 0.064890 0.241448 -vn 0.734761 -0.313649 0.601457 -v 0.083408 0.066047 0.242492 -vn 0.793816 0.085496 0.602119 -v 0.083993 0.070674 0.242492 -vn 0.798799 0.000323 0.601598 -v 0.084067 0.069499 0.242492 -vn 0.794132 -0.085798 0.601659 -v 0.083993 0.068324 0.242492 -vn 0.793170 -0.148412 0.590640 -v 0.083916 0.067825 0.242492 -vn 0.772335 -0.207107 0.600504 -v 0.083772 0.067167 0.242492 -vn 0.759690 -0.262036 0.595153 -v 0.083469 0.066204 0.242492 -vn 0.718967 0.277386 0.637294 -v 0.080946 0.071847 0.245441 -vn 0.729991 0.351443 0.586175 -v 0.080710 0.072398 0.245441 -vn 0.664866 0.388266 0.638124 -v 0.080426 0.072926 0.245441 -vn 0.660022 0.467788 0.587831 -v 0.080211 0.073263 0.245441 -vn 0.603063 0.490089 0.629387 -v 0.079722 0.073895 0.245441 -vn 0.577460 0.568478 0.585980 -v 0.079588 0.074044 0.245441 -vn -0.179749 0.788355 0.588377 -v 0.073203 0.076014 0.245441 -vn -0.084164 0.805794 0.586185 -v 0.074190 0.076162 0.245441 -vn 0.504383 0.633043 0.587243 -v 0.078856 0.074723 0.245441 -vn 0.425904 0.690010 0.585228 -v 0.078031 0.075286 0.245441 -vn 0.351613 0.702240 0.619053 -v 0.077856 0.075383 0.245441 -vn 0.306672 0.751424 0.584221 -v 0.077131 0.075719 0.245441 -vn 0.231795 0.735483 0.636660 -v 0.076754 0.075854 0.245441 -vn 0.180589 0.789930 0.586001 -v 0.076177 0.076014 0.245441 -vn 0.110977 0.761906 0.638110 -v 0.075587 0.076121 0.245441 -vn 0.045589 0.807863 0.587605 -v 0.075189 0.076162 0.245441 -vn -0.006968 0.777236 0.629171 -v 0.074390 0.076174 0.245441 -vn -0.273918 0.762264 0.586449 -v 0.072248 0.075719 0.245441 -vn -0.329497 0.712064 0.619998 -v 0.072063 0.075643 0.245441 -vn -0.394788 0.707442 0.586232 -v 0.071349 0.075286 0.245441 -vn -0.430963 0.638212 0.637932 -v 0.071009 0.075076 0.245441 -vn -0.505094 0.633678 0.585946 -v 0.070523 0.074723 0.245441 -vn -0.526480 0.561930 0.638008 -v 0.070072 0.074329 0.245441 -vn -0.603573 0.539280 0.587262 -v 0.069791 0.074044 0.245441 -vn -0.612037 0.479531 0.628857 -v 0.069284 0.073427 0.245441 -vn -0.682303 0.436688 0.586316 -v 0.069169 0.073263 0.245441 -vn -0.728339 0.350817 0.588599 -v 0.068669 0.072398 0.245441 -vn -0.766765 0.261089 0.586433 -v 0.068304 0.071469 0.245441 -vn -0.762330 0.186230 0.619816 -v 0.068248 0.071277 0.245441 -vn -0.799317 0.132631 0.586090 -v 0.068082 0.070495 0.245441 -vn -0.767656 0.060959 0.637957 -v 0.068034 0.070098 0.245441 -vn -0.810477 -0.000000 0.585771 -v 0.068008 0.069499 0.245441 -vn -0.767759 -0.061091 0.637820 -v 0.068034 0.068900 0.245441 -vn -0.797755 -0.135256 0.587617 -v 0.068082 0.068503 0.245441 -vn -0.756085 -0.179801 0.629291 -v 0.068248 0.067721 0.245441 -vn -0.766759 -0.261089 0.586442 -v 0.068304 0.067530 0.245441 -vn -0.728348 -0.350819 0.588587 -v 0.068669 0.066600 0.245441 -vn -0.682318 -0.436687 0.586300 -v 0.069169 0.065735 0.245441 -vn -0.620947 -0.480262 0.619494 -v 0.069284 0.065572 0.245441 -vn -0.602355 -0.542263 0.585764 -v 0.069791 0.064954 0.245441 -vn -0.526395 -0.562175 0.637861 -v 0.070072 0.064669 0.245441 -vn -0.505251 -0.634019 0.585441 -v 0.070523 0.064275 0.245441 -vn -0.431284 -0.638392 0.637534 -v 0.071009 0.063922 0.245441 -vn -0.391743 -0.707867 0.587759 -v 0.071349 0.063712 0.245441 -vn -0.330625 -0.703158 0.629488 -v 0.072063 0.063355 0.245441 -vn -0.273912 -0.762247 0.586474 -v 0.072248 0.063279 0.245441 -vn -0.179749 -0.788355 0.588376 -v 0.073203 0.062985 0.245441 -vn -0.084177 -0.805767 0.586220 -v 0.074190 0.062836 0.245441 -vn -0.011630 -0.784895 0.619519 -v 0.074390 0.062824 0.245441 -vn 0.048579 -0.809137 0.585609 -v 0.075189 0.062836 0.245441 -vn 0.111180 -0.762239 0.637676 -v 0.075587 0.062878 0.245441 -vn 0.181122 -0.790573 0.584970 -v 0.076177 0.062985 0.245441 -vn 0.229957 -0.735606 0.637184 -v 0.076754 0.063144 0.245441 -vn 0.309070 -0.747586 0.587870 -v 0.077131 0.063279 0.245441 -vn 0.343662 -0.696821 0.629553 -v 0.077856 0.063615 0.245441 -vn 0.425330 -0.689416 0.586345 -v 0.078031 0.063712 0.245441 -vn 0.504588 -0.632239 0.587933 -v 0.078856 0.064275 0.245441 -vn 0.577493 -0.568482 0.585944 -v 0.079588 0.064954 0.245441 -vn 0.606380 -0.498544 0.619481 -v 0.079722 0.065103 0.245441 -vn 0.663233 -0.466402 0.585313 -v 0.080211 0.065735 0.245441 -vn 0.665326 -0.388657 0.637407 -v 0.080426 0.066072 0.245441 -vn 0.730060 -0.351777 0.585889 -v 0.080710 0.066600 0.245441 -vn 0.718140 -0.277847 0.638025 -v 0.080946 0.067151 0.245441 -vn 0.777180 -0.224453 0.587888 -v 0.081075 0.067530 0.245441 -vn 0.759096 -0.165799 0.629511 -v 0.081264 0.068306 0.245441 -vn 0.804395 -0.097112 0.586104 -v 0.081297 0.068503 0.245441 -vn 0.809386 0.000436 0.587277 -v 0.081372 0.069499 0.245441 -vn 0.804880 0.096937 0.585466 -v 0.081297 0.070495 0.245441 -vn 0.768020 0.163131 0.619301 -v 0.081264 0.070692 0.245441 -vn 0.778393 0.228176 0.584842 -v 0.081075 0.071469 0.245441 -vn 0.920064 -0.274519 0.279502 -v 0.081032 0.067543 0.245521 -vn 0.950340 -0.133860 0.280955 -v 0.081253 0.068510 0.245521 -vn 0.970169 -0.146233 -0.193363 -v 0.081249 0.068510 0.245614 -vn 0.359027 -0.890502 0.279474 -v 0.077114 0.063321 0.245521 -vn 0.487865 -0.826462 0.280977 -v 0.078008 0.063751 0.245521 -vn 0.490563 -0.849681 -0.193367 -v 0.078006 0.063754 0.245614 -vn -0.472370 -0.835920 0.279473 -v 0.071371 0.063751 0.245521 -vn -0.341981 -0.896717 0.280977 -v 0.072265 0.063321 0.245521 -vn -0.358444 -0.913302 -0.193386 -v 0.072266 0.063324 0.245614 -vn -0.948063 -0.151873 0.279484 -v 0.068127 0.068510 0.245521 -vn -0.914303 -0.291728 0.280971 -v 0.068347 0.067543 0.245521 -vn -0.937532 -0.289191 -0.193394 -v 0.068351 0.067544 0.245614 -vn -0.709845 0.646533 0.279491 -v 0.069824 0.074014 0.245521 -vn -0.798139 0.532941 0.280979 -v 0.069206 0.073238 0.245521 -vn -0.810646 0.552687 -0.193368 -v 0.069209 0.073236 0.245614 -vn 0.062903 0.958094 0.279463 -v 0.075186 0.076118 0.245521 -vn -0.080961 0.956297 0.280967 -v 0.074194 0.076118 0.245521 -vn -0.073322 0.978380 -0.193381 -v 0.074194 0.076114 0.245614 -vn 0.788279 0.548173 0.279504 -v 0.080173 0.073238 0.245521 -vn 0.697184 0.659540 0.280966 -v 0.079555 0.074014 0.245521 -vn 0.719219 0.667334 -0.193365 -v 0.079552 0.074011 0.245614 -vn 0.864519 -0.416333 0.281557 -v 0.080669 0.066619 0.245521 -vn 0.789627 -0.545193 0.281519 -v 0.080173 0.065760 0.245521 -vn 0.213516 -0.935481 0.281578 -v 0.076167 0.063028 0.245521 -vn 0.066073 -0.957274 0.281534 -v 0.075186 0.062881 0.245521 -vn -0.598265 -0.750196 0.281577 -v 0.070551 0.064310 0.245521 -vn -0.707232 -0.648512 0.281525 -v 0.069824 0.064985 0.245521 -vn -0.959535 0.000001 0.281588 -v 0.068052 0.069499 0.245521 -vn -0.947979 0.148596 0.281524 -v 0.068127 0.070488 0.245521 -vn -0.598254 0.750193 0.281606 -v 0.070551 0.074688 0.245521 -vn -0.474878 0.833804 0.281534 -v 0.071371 0.075247 0.245521 -vn 0.213516 0.935481 0.281578 -v 0.076167 0.075970 0.245521 -vn 0.355814 0.891150 0.281512 -v 0.077114 0.075677 0.245521 -vn 0.864519 0.416334 0.281555 -v 0.080669 0.072379 0.245521 -vn 0.918568 0.277431 0.281539 -v 0.081032 0.071455 0.245521 -vn 0.950408 0.133127 0.281071 -v 0.081253 0.070488 0.245521 -vn 0.488476 0.826056 0.281111 -v 0.078008 0.075247 0.245521 -vn -0.341280 0.896948 0.281091 -v 0.072265 0.075677 0.245521 -vn -0.914048 0.292421 0.281081 -v 0.068347 0.071455 0.245521 -vn -0.798524 -0.532313 0.281074 -v 0.069206 0.065760 0.245521 -vn -0.081683 -0.956193 0.281110 -v 0.074194 0.062881 0.245521 -vn 0.696652 -0.660054 0.281077 -v 0.079555 0.064985 0.245521 -vn 0.883959 0.425695 -0.193393 -v 0.080666 0.072377 0.245614 -vn 0.937543 0.289190 -0.193345 -v 0.081028 0.071454 0.245614 -vn 0.487991 0.611925 -0.622424 -v 0.078849 0.074715 0.245698 -vn 0.611722 0.767074 -0.193374 -v 0.078825 0.074685 0.245614 -vn 0.599714 0.752019 0.273518 -v 0.078828 0.074688 0.245521 -vn 0.218323 0.956526 -0.193375 -v 0.076166 0.075966 0.245614 -vn 0.358449 0.913305 -0.193363 -v 0.077113 0.075674 0.245614 -vn -0.174165 0.763055 -0.622425 -v 0.073205 0.076003 0.245698 -vn -0.218320 0.956526 -0.193375 -v 0.073214 0.075966 0.245614 -vn -0.214036 0.937751 0.273516 -v 0.073213 0.075970 0.245521 -vn -0.611723 0.767080 -0.193350 -v 0.070554 0.074685 0.245614 -vn -0.490562 0.849678 -0.193384 -v 0.071373 0.075244 0.245614 -vn -0.705177 0.339595 -0.622415 -v 0.068679 0.072394 0.245698 -vn -0.883965 0.425697 -0.193360 -v 0.068713 0.072377 0.245614 -vn -0.866612 0.417336 0.273524 -v 0.068710 0.072379 0.245521 -vn -0.981124 -0.000001 -0.193379 -v 0.068056 0.069499 0.245614 -vn -0.970167 0.146230 -0.193370 -v 0.068130 0.070488 0.245614 -vn -0.705174 -0.339595 -0.622419 -v 0.068679 0.066604 0.245698 -vn -0.883967 -0.425693 -0.193358 -v 0.068713 0.066621 0.245614 -vn -0.866611 -0.417336 0.273526 -v 0.068710 0.066619 0.245521 -vn -0.611724 -0.767078 -0.193353 -v 0.070554 0.064313 0.245614 -vn -0.719212 -0.667335 -0.193387 -v 0.069827 0.064987 0.245614 -vn -0.174167 -0.763069 -0.622408 -v 0.073205 0.062995 0.245698 -vn -0.218317 -0.956527 -0.193376 -v 0.073214 0.063032 0.245614 -vn -0.214038 -0.937751 0.273517 -v 0.073213 0.063028 0.245521 -vn 0.218321 -0.956526 -0.193375 -v 0.076166 0.063032 0.245614 -vn 0.073317 -0.978389 -0.193339 -v 0.075185 0.062884 0.245614 -vn 0.487996 -0.611929 -0.622417 -v 0.078849 0.064283 0.245698 -vn 0.611722 -0.767074 -0.193376 -v 0.078825 0.064313 0.245614 -vn 0.599722 -0.752023 0.273487 -v 0.078828 0.064310 0.245521 -vn 0.883962 -0.425688 -0.193394 -v 0.080666 0.066621 0.245614 -vn 0.810646 -0.552693 -0.193350 -v 0.080170 0.065762 0.245614 -vn 0.782695 -0.000000 -0.622406 -v 0.081361 0.069499 0.245698 -vn 0.981124 0.000001 -0.193382 -v 0.081323 0.069499 0.245614 -vn 0.961877 -0.000000 0.273484 -v 0.081327 0.069499 0.245521 -vn 0.745904 0.237798 -0.622157 -v 0.081065 0.071466 0.245698 -vn 0.708543 0.341213 -0.617690 -v 0.080700 0.072394 0.245698 -vn 0.650723 0.435379 -0.622097 -v 0.080202 0.073257 0.245698 -vn 0.279154 0.731452 -0.622135 -v 0.077127 0.075709 0.245698 -vn 0.174995 0.766701 -0.617694 -v 0.076174 0.076003 0.245698 -vn 0.065329 0.780217 -0.622088 -v 0.075188 0.076152 0.245698 -vn -0.397819 0.674288 -0.622154 -v 0.071354 0.075277 0.245698 -vn -0.490320 0.614845 -0.617699 -v 0.070530 0.074715 0.245698 -vn -0.569260 0.537530 -0.622097 -v 0.069799 0.074037 0.245698 -vn -0.775227 0.109394 -0.622138 -v 0.068093 0.070493 0.245698 -vn -0.786407 -0.000001 -0.617709 -v 0.068018 0.069499 0.245698 -vn -0.775198 -0.109920 -0.622081 -v 0.068093 0.068505 0.245698 -vn -0.568860 -0.537885 -0.622157 -v 0.069799 0.064961 0.245698 -vn -0.490326 -0.614847 -0.617692 -v 0.070530 0.064283 0.245698 -vn -0.397382 -0.674598 -0.622097 -v 0.071354 0.063721 0.245698 -vn 0.065856 -0.780128 -0.622145 -v 0.075188 0.062846 0.245698 -vn 0.174995 -0.766717 -0.617675 -v 0.076174 0.062995 0.245698 -vn 0.279664 -0.731304 -0.622080 -v 0.077127 0.063289 0.245698 -vn 0.650986 -0.434917 -0.622145 -v 0.080202 0.065741 0.245698 -vn 0.708539 -0.341216 -0.617693 -v 0.080700 0.066604 0.245698 -vn 0.746106 -0.237304 -0.622103 -v 0.081065 0.067533 0.245698 -vn 0.773348 0.120759 -0.622374 -v 0.081287 0.070493 0.245698 -vn 0.523130 0.086805 -0.847821 -v 0.081358 0.070504 0.245756 -vn 0.490304 0.038819 -0.870687 -v 0.081406 0.070104 0.245756 -vn 0.970167 0.146231 -0.193371 -v 0.081249 0.070488 0.245614 -vn 0.530436 -0.000000 -0.847725 -v 0.081433 0.069499 0.245756 -vn 0.491018 0.119682 -0.862889 -v 0.081190 0.071293 0.245756 -vn 0.336202 0.359144 -0.870623 -v 0.079350 0.074373 0.245756 -vn 0.394514 0.352634 -0.848533 -v 0.079633 0.074086 0.245756 -vn 0.578900 0.528222 -0.621174 -v 0.079580 0.074037 0.245698 -vn 0.810645 0.552687 -0.193368 -v 0.080170 0.073236 0.245614 -vn 0.392167 0.307536 -0.866964 -v 0.080145 0.073463 0.245756 -vn 0.446240 0.285878 -0.848023 -v 0.080261 0.073298 0.245756 -vn 0.475090 0.228792 -0.849673 -v 0.080765 0.072425 0.245756 -vn 0.501735 0.170645 -0.848023 -v 0.081134 0.071487 0.245756 -vn 0.330727 0.414717 -0.847720 -v 0.078894 0.074771 0.245756 -vn 0.387755 0.679912 -0.622387 -v 0.078025 0.075277 0.245698 -vn 0.258292 0.463117 -0.847825 -v 0.078061 0.075339 0.245756 -vn 0.275340 0.407531 -0.870693 -v 0.078405 0.075127 0.245756 -vn 0.490564 0.849681 -0.193365 -v 0.078006 0.075244 0.245614 -vn 0.212574 0.458515 -0.862888 -v 0.077340 0.075700 0.245756 -vn -0.071175 0.486781 -0.870620 -v 0.073784 0.076182 0.245756 -vn -0.029727 0.528310 -0.848531 -v 0.074186 0.076224 0.245756 -vn -0.052046 0.781932 -0.621187 -v 0.074191 0.076152 0.245698 -vn 0.073320 0.978381 -0.193378 -v 0.075185 0.076114 0.245614 -vn 0.004070 0.498361 -0.866960 -v 0.074992 0.076236 0.245756 -vn 0.054716 0.527128 -0.848023 -v 0.075194 0.076224 0.245756 -vn 0.117337 0.514089 -0.849674 -v 0.076190 0.076074 0.245756 -vn 0.179412 0.498675 -0.848018 -v 0.077153 0.075776 0.245756 -vn -0.118031 0.517137 -0.847725 -v 0.073189 0.076074 0.245756 -vn -0.289815 0.727084 -0.622379 -v 0.072252 0.075709 0.245698 -vn -0.201037 0.490692 -0.847824 -v 0.072226 0.075776 0.245756 -vn -0.146948 0.469359 -0.870694 -v 0.072606 0.075913 0.245756 -vn -0.358447 0.913308 -0.193350 -v 0.072266 0.075674 0.245614 -vn -0.225942 0.452070 -0.862892 -v 0.071494 0.075437 0.245756 -vn -0.424952 0.247854 -0.870623 -v 0.068901 0.072958 0.245756 -vn -0.431595 0.306167 -0.848521 -v 0.069118 0.073298 0.245756 -vn -0.643792 0.446841 -0.621180 -v 0.069177 0.073257 0.245698 -vn -0.719216 0.667338 -0.193362 -v 0.069827 0.074011 0.245614 -vn -0.387084 0.313894 -0.866970 -v 0.069611 0.073936 0.245756 -vn -0.378004 0.371441 -0.848024 -v 0.069746 0.074086 0.245756 -vn -0.328776 0.412274 -0.849669 -v 0.070485 0.074771 0.245756 -vn -0.278023 0.451188 -0.848017 -v 0.071318 0.075339 0.245756 -vn -0.477907 0.230149 -0.847724 -v 0.068614 0.072425 0.245756 -vn -0.749142 0.226738 -0.622396 -v 0.068314 0.071466 0.245698 -vn -0.508983 0.148764 -0.847824 -v 0.068246 0.071487 0.245756 -vn -0.458581 0.177757 -0.870693 -v 0.068376 0.071869 0.245756 -vn -0.937536 0.289188 -0.193382 -v 0.068351 0.071454 0.245614 -vn -0.494325 0.105215 -0.862886 -v 0.068054 0.070703 0.245756 -vn -0.458735 -0.177709 -0.870622 -v 0.068376 0.067130 0.245756 -vn -0.508448 -0.146539 -0.848532 -v 0.068246 0.067511 0.245756 -vn -0.750735 -0.224734 -0.621202 -v 0.068314 0.067533 0.245698 -vn -0.970169 -0.146230 -0.193364 -v 0.068130 0.068510 0.245614 -vn -0.486765 -0.106922 -0.866965 -v 0.068054 0.068295 0.245756 -vn -0.526090 -0.063950 -0.848021 -v 0.068021 0.068494 0.245756 -vn -0.527310 -0.000000 -0.849673 -v 0.067946 0.069499 0.245756 -vn -0.526093 0.063949 -0.848019 -v 0.068021 0.070504 0.245756 -vn -0.477916 -0.230152 -0.847718 -v 0.068614 0.066573 0.245756 -vn -0.644372 -0.444343 -0.622370 -v 0.069177 0.065741 0.245698 -vn -0.433658 -0.305190 -0.847821 -v 0.069118 0.065700 0.245756 -vn -0.424895 -0.247705 -0.870693 -v 0.068901 0.066040 0.245756 -vn -0.810648 -0.552690 -0.193349 -v 0.069209 0.065762 0.245614 -vn -0.390469 -0.320877 -0.862886 -v 0.069611 0.065062 0.245756 -vn -0.147082 -0.469459 -0.870618 -v 0.072606 0.063086 0.245756 -vn -0.202442 -0.488887 -0.848532 -v 0.072226 0.063222 0.245756 -vn -0.292377 -0.727080 -0.621185 -v 0.072252 0.063289 0.245698 -vn -0.490560 -0.849678 -0.193383 -v 0.071373 0.063754 0.245614 -vn -0.219899 -0.447241 -0.866960 -v 0.071494 0.063561 0.245756 -vn -0.278016 -0.451191 -0.848018 -v 0.071318 0.063659 0.245756 -vn -0.328766 -0.412262 -0.849678 -v 0.070485 0.064227 0.245756 -vn -0.378016 -0.371450 -0.848015 -v 0.069746 0.064912 0.245756 -vn -0.118039 -0.517156 -0.847713 -v 0.073189 0.062925 0.245756 -vn -0.054353 -0.780824 -0.622382 -v 0.074191 0.062846 0.245698 -vn -0.031775 -0.529326 -0.847823 -v 0.074186 0.062774 0.245756 -vn -0.071253 -0.486639 -0.870692 -v 0.073784 0.062817 0.245756 -vn -0.073321 -0.978388 -0.193342 -v 0.074194 0.062884 0.245614 -vn 0.007421 -0.505332 -0.862893 -v 0.074992 0.062762 0.245756 -vn 0.275331 -0.407691 -0.870621 -v 0.078405 0.063871 0.245756 -vn 0.256007 -0.463089 -0.848533 -v 0.078061 0.063659 0.245756 -vn 0.386158 -0.681911 -0.621192 -v 0.078025 0.063721 0.245698 -vn 0.358446 -0.913298 -0.193400 -v 0.077113 0.063324 0.245614 -vn 0.212558 -0.450768 -0.866965 -v 0.077340 0.063298 0.245756 -vn 0.179411 -0.498676 -0.848018 -v 0.077153 0.063222 0.245756 -vn 0.117340 -0.514108 -0.849662 -v 0.076190 0.062925 0.245756 -vn 0.054725 -0.527128 -0.848022 -v 0.075194 0.062774 0.245756 -vn 0.330715 -0.414706 -0.847730 -v 0.078894 0.064227 0.245756 -vn 0.576590 -0.529334 -0.622374 -v 0.079580 0.064961 0.245698 -vn 0.394042 -0.354877 -0.847816 -v 0.079633 0.064912 0.245756 -vn 0.336044 -0.359120 -0.870694 -v 0.079350 0.064625 0.245756 -vn 0.719216 -0.667329 -0.193390 -v 0.079552 0.064987 0.245614 -vn 0.399716 -0.309279 -0.862887 -v 0.080145 0.065535 0.245756 -vn 0.490417 -0.038928 -0.870618 -v 0.081406 0.068895 0.245756 -vn 0.521680 -0.088578 -0.848531 -v 0.081358 0.068494 0.245756 -vn 0.773914 -0.123256 -0.621180 -v 0.081287 0.068505 0.245698 -vn 0.937539 -0.289194 -0.193357 -v 0.081028 0.067544 0.245614 -vn 0.484948 -0.114862 -0.866967 -v 0.081190 0.067705 0.245756 -vn 0.501735 -0.170645 -0.848022 -v 0.081134 0.067511 0.245756 -vn 0.475098 -0.228796 -0.849667 -v 0.080765 0.066573 0.245756 -vn 0.446227 -0.285875 -0.848031 -v 0.080261 0.065700 0.245756 -vn -0.530094 0.040694 -0.846962 -v 0.065506 0.070089 0.246930 -vn -0.542330 0.079459 -0.836400 -v 0.065635 0.071142 0.246930 -vn -0.518430 0.116448 -0.847154 -v 0.065656 0.071258 0.246930 -vn -0.508184 0.156306 -0.846946 -v 0.065956 0.072399 0.246930 -vn -0.538447 0.213993 -0.815035 -v 0.066074 0.072733 0.246930 -vn -0.478883 0.230617 -0.847046 -v 0.066398 0.073492 0.246930 -vn -0.502863 0.287581 -0.815124 -v 0.066789 0.074219 0.246930 -vn -0.438982 0.299691 -0.847042 -v 0.066977 0.074520 0.246930 -vn -0.414295 0.332735 -0.847141 -v 0.067682 0.075465 0.246930 -vn -0.401020 0.377554 -0.834647 -v 0.067759 0.075554 0.246930 -vn -0.363430 0.388771 -0.846626 -v 0.068503 0.076312 0.246930 -vn -0.368539 0.462135 -0.806604 -v 0.068952 0.076694 0.246930 -vn -0.298693 0.439820 -0.846960 -v 0.069425 0.077047 0.246930 -vn -0.276024 0.473564 -0.836390 -v 0.070329 0.077603 0.246930 -vn -0.232210 0.477948 -0.847139 -v 0.070433 0.077658 0.246930 -vn -0.194648 0.494781 -0.846938 -v 0.071511 0.078136 0.246930 -vn -0.168414 0.554412 -0.815024 -v 0.071846 0.078252 0.246930 -vn -0.118271 0.518184 -0.847052 -v 0.072642 0.078471 0.246930 -vn -0.088690 0.572457 -0.815124 -v 0.073454 0.078619 0.246930 -vn -0.039398 0.530081 -0.847031 -v 0.073806 0.078659 0.246930 -vn 0.001833 0.531349 -0.847151 -v 0.074985 0.078697 0.246930 -vn 0.045149 0.548919 -0.834655 -v 0.075103 0.078693 0.246930 -vn 0.077364 0.526550 -0.846617 -v 0.076158 0.078584 0.246930 -vn 0.131526 0.576259 -0.806614 -v 0.076737 0.078471 0.246930 -vn 0.157627 0.507742 -0.846967 -v 0.077308 0.078322 0.246930 -vn 0.198161 0.511070 -0.836385 -v 0.078307 0.077961 0.246930 -vn 0.228903 0.479529 -0.847146 -v 0.078415 0.077914 0.246930 -vn 0.265473 0.460671 -0.846940 -v 0.079460 0.077369 0.246930 -vn 0.328450 0.477338 -0.815027 -v 0.079759 0.077180 0.246930 -vn 0.331404 0.415565 -0.847040 -v 0.080428 0.076694 0.246930 -vn 0.392261 0.426257 -0.815130 -v 0.081049 0.076151 0.246930 -vn 0.389869 0.361305 -0.847031 -v 0.081301 0.075901 0.246930 -vn 0.416581 0.329862 -0.847143 -v 0.082065 0.075003 0.246930 -vn 0.457321 0.306950 -0.834649 -v 0.082135 0.074908 0.246930 -vn 0.459909 0.267813 -0.846617 -v 0.082708 0.074015 0.246930 -vn 0.532544 0.256458 -0.806614 -v 0.082981 0.073492 0.246930 -vn 0.495258 0.193338 -0.846959 -v 0.083220 0.072953 0.246930 -vn 0.523115 0.163718 -0.836389 -v 0.083561 0.071947 0.246930 -vn 0.517625 0.120020 -0.847148 -v 0.083592 0.071833 0.246930 -vn 0.525689 0.079666 -0.846938 -v 0.083817 0.070676 0.246930 -vn 0.577974 0.040821 -0.815033 -v 0.083855 0.070324 0.246930 -vn 0.531532 0.000000 -0.847039 -v 0.083893 0.069499 0.246930 -vn 0.577841 -0.040915 -0.815123 -v 0.083855 0.068674 0.246930 -vn 0.525565 -0.079543 -0.847027 -v 0.083817 0.068322 0.246930 -vn 0.517625 -0.120016 -0.847148 -v 0.083592 0.067165 0.246930 -vn 0.525132 -0.166164 -0.834641 -v 0.083561 0.067051 0.246930 -vn 0.496134 -0.192592 -0.846617 -v 0.083220 0.066046 0.246930 -vn 0.532543 -0.256458 -0.806615 -v 0.082981 0.065506 0.246930 -vn 0.459936 -0.266660 -0.846966 -v 0.082708 0.064983 0.246930 -vn 0.454160 -0.306900 -0.836392 -v 0.082135 0.064090 0.246930 -vn 0.416599 -0.329864 -0.847134 -v 0.082065 0.063995 0.246930 -vn 0.390053 -0.361335 -0.846933 -v 0.081301 0.063097 0.246930 -vn 0.392283 -0.426436 -0.815026 -v 0.081049 0.062847 0.246930 -vn 0.331403 -0.415566 -0.847040 -v 0.080428 0.062304 0.246930 -vn 0.328287 -0.477279 -0.815127 -v 0.079759 0.061819 0.246930 -vn 0.265490 -0.460488 -0.847034 -v 0.079460 0.061629 0.246930 -vn 0.228890 -0.479536 -0.847145 -v 0.078415 0.061084 0.246930 -vn 0.197485 -0.514153 -0.834654 -v 0.078307 0.061037 0.246930 -vn 0.158757 -0.507960 -0.846624 -v 0.077308 0.060677 0.246930 -vn 0.131529 -0.576265 -0.806610 -v 0.076737 0.060527 0.246930 -vn 0.078282 -0.525851 -0.846967 -v 0.076158 0.060414 0.246930 -vn 0.043213 -0.546428 -0.836391 -v 0.075103 0.060306 0.246930 -vn 0.001833 -0.531360 -0.847144 -v 0.074985 0.060301 0.246930 -vn -0.039306 -0.530229 -0.846943 -v 0.073806 0.060339 0.246930 -vn -0.088815 -0.572573 -0.815029 -v 0.073454 0.060380 0.246930 -vn -0.118277 -0.518204 -0.847039 -v 0.072642 0.060527 0.246930 -vn -0.168469 -0.554245 -0.815126 -v 0.071846 0.060747 0.246930 -vn -0.194495 -0.494679 -0.847032 -v 0.071511 0.060863 0.246930 -vn -0.232210 -0.477948 -0.847139 -v 0.070433 0.061340 0.246930 -vn -0.278857 -0.474979 -0.834646 -v 0.070329 0.061395 0.246930 -vn -0.298156 -0.440831 -0.846623 -v 0.069425 0.061951 0.246930 -vn -0.368535 -0.462131 -0.806608 -v 0.068952 0.062304 0.246930 -vn -0.362327 -0.389076 -0.846958 -v 0.068503 0.062686 0.246930 -vn -0.400283 -0.374489 -0.836380 -v 0.067759 0.063444 0.246930 -vn -0.414303 -0.332745 -0.847133 -v 0.067682 0.063534 0.246930 -vn -0.439040 -0.299853 -0.846955 -v 0.066977 0.064479 0.246930 -vn -0.503027 -0.287554 -0.815032 -v 0.066789 0.064779 0.246930 -vn -0.478892 -0.230621 -0.847040 -v 0.066398 0.065506 0.246930 -vn -0.538362 -0.213848 -0.815129 -v 0.066074 0.066265 0.246930 -vn -0.508013 -0.156360 -0.847038 -v 0.065956 0.066599 0.246930 -vn -0.518436 -0.116447 -0.847151 -v 0.065656 0.067740 0.246930 -vn -0.545201 -0.078125 -0.834657 -v 0.065635 0.067856 0.246930 -vn -0.530561 -0.041745 -0.846618 -v 0.065506 0.068909 0.246930 -vn -0.591093 0.000000 -0.806603 -v 0.065487 0.069499 0.246930 -vn 0.779013 0.106276 -0.617935 -v 0.083886 0.070685 0.246985 -vn 0.785873 -0.000000 -0.618388 -v 0.083962 0.069499 0.246985 -vn 0.762116 0.194497 -0.617535 -v 0.083659 0.071851 0.246985 -vn 0.729729 0.291655 -0.618412 -v 0.083285 0.072979 0.246985 -vn 0.682236 0.389293 -0.618875 -v 0.082769 0.074049 0.246985 -vn 0.627397 0.474244 -0.617629 -v 0.082121 0.075045 0.246985 -vn 0.402615 0.675317 -0.617939 -v 0.079497 0.077429 0.246985 -vn 0.489983 0.614421 -0.618388 -v 0.080471 0.076749 0.246985 -vn 0.568791 0.542797 -0.617939 -v 0.081351 0.075950 0.246985 -vn 0.323104 0.717094 -0.617559 -v 0.078443 0.077978 0.246985 -vn 0.226955 0.752388 -0.618388 -v 0.077328 0.078389 0.246985 -vn 0.121004 0.776109 -0.618880 -v 0.076170 0.078653 0.246985 -vn 0.020396 0.786210 -0.617623 -v 0.074987 0.078767 0.246985 -vn -0.276957 0.735830 -0.617940 -v 0.071487 0.078201 0.246985 -vn -0.174870 0.766160 -0.618400 -v 0.072626 0.078539 0.246985 -vn -0.069734 0.783119 -0.617950 -v 0.073799 0.078729 0.246985 -vn -0.359207 0.699726 -0.617539 -v 0.070401 0.077720 0.246985 -vn -0.446731 0.646543 -0.618397 -v 0.069385 0.077104 0.246985 -vn -0.531345 0.578502 -0.618876 -v 0.068456 0.076364 0.246985 -vn -0.601962 0.506139 -0.617629 -v 0.067629 0.075510 0.246985 -vn -0.747971 0.242249 -0.617944 -v 0.065889 0.072421 0.246985 -vn -0.708046 0.340976 -0.618391 -v 0.066335 0.073522 0.246985 -vn -0.655746 0.433748 -0.617948 -v 0.066918 0.074558 0.246985 -vn -0.771033 0.155434 -0.617534 -v 0.065588 0.071272 0.246985 -vn -0.784004 0.053844 -0.618417 -v 0.065436 0.070093 0.246985 -vn -0.783556 -0.054726 -0.618907 -v 0.065436 0.068905 0.246985 -vn -0.771043 -0.155064 -0.617615 -v 0.065588 0.067727 0.246985 -vn -0.655747 -0.433749 -0.617947 -v 0.066918 0.064441 0.246985 -vn -0.708052 -0.340977 -0.618383 -v 0.066335 0.065476 0.246985 -vn -0.747967 -0.242248 -0.617949 -v 0.065889 0.066577 0.246985 -vn -0.602241 -0.505895 -0.617557 -v 0.067629 0.063488 0.246985 -vn -0.530925 -0.579401 -0.618396 -v 0.068456 0.062635 0.246985 -vn -0.445760 -0.646749 -0.618881 -v 0.069385 0.061894 0.246985 -vn -0.359503 -0.699504 -0.617618 -v 0.070401 0.061278 0.246985 -vn -0.069736 -0.783131 -0.617935 -v 0.073799 0.060269 0.246985 -vn -0.174874 -0.766174 -0.618383 -v 0.072626 0.060459 0.246985 -vn -0.276956 -0.735834 -0.617936 -v 0.071487 0.060797 0.246985 -vn 0.020035 -0.786288 -0.617535 -v 0.074987 0.060231 0.246985 -vn 0.121966 -0.776341 -0.618400 -v 0.076170 0.060345 0.246985 -vn 0.227723 -0.751754 -0.618877 -v 0.077328 0.060610 0.246985 -vn 0.322748 -0.717208 -0.617614 -v 0.078443 0.061020 0.246985 -vn 0.568789 -0.542792 -0.617946 -v 0.081351 0.063048 0.246985 -vn 0.489977 -0.614414 -0.618400 -v 0.080471 0.062249 0.246985 -vn 0.402619 -0.675318 -0.617935 -v 0.079497 0.061570 0.246985 -vn 0.627234 -0.474573 -0.617542 -v 0.082121 0.063953 0.246985 -vn 0.683027 -0.388690 -0.618380 -v 0.082769 0.064949 0.246985 -vn 0.729718 -0.290668 -0.618890 -v 0.083285 0.066019 0.246985 -vn 0.761963 -0.194828 -0.617620 -v 0.083659 0.067147 0.246985 -vn 0.779011 -0.106273 -0.617939 -v 0.083886 0.068313 0.246985 -vn 0.966860 -0.124665 -0.222800 -v 0.083925 0.068308 0.247065 -vn 0.942977 -0.247279 -0.222815 -v 0.083697 0.067137 0.247065 -vn 0.903620 -0.365834 -0.222794 -v 0.083321 0.066005 0.247065 -vn 0.849423 -0.478385 -0.222775 -v 0.082803 0.064930 0.247065 -vn 0.781269 -0.583074 -0.222809 -v 0.082152 0.063930 0.247065 -vn 0.700293 -0.678193 -0.222810 -v 0.081379 0.063021 0.247065 -vn 0.607816 -0.762177 -0.222814 -v 0.080495 0.062219 0.247065 -vn 0.505366 -0.833651 -0.222783 -v 0.079517 0.061536 0.247065 -vn 0.394609 -0.891432 -0.222785 -v 0.078459 0.060984 0.247065 -vn 0.277377 -0.934576 -0.222777 -v 0.077339 0.060572 0.247065 -vn 0.155589 -0.962372 -0.222785 -v 0.076176 0.060307 0.247065 -vn 0.031244 -0.974363 -0.222803 -v 0.074988 0.060192 0.247065 -vn -0.093608 -0.970363 -0.222787 -v 0.073795 0.060231 0.247065 -vn -0.216926 -0.950423 -0.222797 -v 0.072618 0.060421 0.247065 -vn -0.336685 -0.914881 -0.222792 -v 0.071474 0.060760 0.247065 -vn -0.450913 -0.864313 -0.222799 -v 0.070383 0.061243 0.247065 -vn -0.557736 -0.799557 -0.222799 -v 0.069362 0.061862 0.247065 -vn -0.655405 -0.721677 -0.222771 -v 0.068429 0.062606 0.247065 -vn -0.742306 -0.631933 -0.222804 -v 0.067599 0.063463 0.247065 -vn -0.817027 -0.531826 -0.222773 -v 0.066886 0.064419 0.247065 -vn -0.878322 -0.422975 -0.222809 -v 0.066300 0.065459 0.247065 -vn -0.925203 -0.307189 -0.222787 -v 0.065852 0.066565 0.247065 -vn -0.956890 -0.186358 -0.222783 -v 0.065550 0.067719 0.247065 -vn -0.972856 -0.062462 -0.222820 -v 0.065397 0.068903 0.247065 -vn -0.972856 0.062460 -0.222822 -v 0.065397 0.070096 0.247065 -vn -0.956890 0.186353 -0.222785 -v 0.065550 0.071279 0.247065 -vn -0.925201 0.307187 -0.222799 -v 0.065852 0.072433 0.247065 -vn -0.878324 0.422979 -0.222792 -v 0.066300 0.073539 0.247065 -vn -0.817025 0.531821 -0.222793 -v 0.066886 0.074579 0.247065 -vn -0.742306 0.631932 -0.222806 -v 0.067599 0.075535 0.247065 -vn -0.655407 0.721673 -0.222775 -v 0.068429 0.076392 0.247065 -vn -0.557736 0.799562 -0.222780 -v 0.069362 0.077136 0.247065 -vn -0.450915 0.864317 -0.222781 -v 0.070383 0.077755 0.247065 -vn -0.336684 0.914877 -0.222808 -v 0.071474 0.078238 0.247065 -vn -0.216928 0.950428 -0.222777 -v 0.072618 0.078577 0.247065 -vn -0.093606 0.970359 -0.222804 -v 0.073795 0.078768 0.247065 -vn 0.031244 0.974367 -0.222783 -v 0.074988 0.078806 0.247065 -vn 0.155589 0.962367 -0.222804 -v 0.076176 0.078691 0.247065 -vn 0.277374 0.934577 -0.222778 -v 0.077339 0.078426 0.247065 -vn 0.394607 0.891425 -0.222817 -v 0.078459 0.078014 0.247065 -vn 0.505363 0.833648 -0.222798 -v 0.079517 0.077462 0.247065 -vn 0.607819 0.762179 -0.222799 -v 0.080495 0.076779 0.247065 -vn 0.700297 0.678197 -0.222785 -v 0.081379 0.075977 0.247065 -vn 0.781272 0.583079 -0.222785 -v 0.082152 0.075068 0.247065 -vn 0.849421 0.478389 -0.222772 -v 0.082803 0.074068 0.247065 -vn 0.903616 0.365833 -0.222808 -v 0.083321 0.072993 0.247065 -vn 0.942978 0.247274 -0.222817 -v 0.083697 0.071861 0.247065 -vn 0.966862 0.124665 -0.222794 -v 0.083925 0.070690 0.247065 -vn 0.974866 0.000000 -0.222794 -v 0.084001 0.069499 0.247065 -vn 0.967741 -0.124778 0.218878 -v 0.083925 0.068308 0.247155 -vn 0.943841 -0.247503 0.218875 -v 0.083697 0.067137 0.247155 -vn 0.904440 -0.366168 0.218885 -v 0.083321 0.066005 0.247155 -vn 0.850190 -0.478818 0.218885 -v 0.082803 0.064930 0.247155 -vn 0.781981 -0.583608 0.218880 -v 0.082152 0.063930 0.247155 -vn 0.700929 -0.678813 0.218885 -v 0.081379 0.063021 0.247155 -vn 0.608370 -0.762871 0.218890 -v 0.080495 0.062219 0.247155 -vn 0.505821 -0.834410 0.218871 -v 0.079517 0.061536 0.247155 -vn 0.394969 -0.892240 0.218880 -v 0.078459 0.060984 0.247155 -vn 0.277629 -0.935423 0.218875 -v 0.077339 0.060572 0.247155 -vn 0.155732 -0.963243 0.218886 -v 0.076176 0.060307 0.247155 -vn 0.031274 -0.975253 0.218869 -v 0.074988 0.060192 0.247155 -vn -0.093696 -0.971244 0.218874 -v 0.073795 0.060230 0.247155 -vn -0.217127 -0.951290 0.218869 -v 0.072618 0.060421 0.247155 -vn -0.336990 -0.915716 0.218865 -v 0.071474 0.060760 0.247155 -vn -0.451324 -0.865104 0.218865 -v 0.070383 0.061243 0.247155 -vn -0.558245 -0.800284 0.218880 -v 0.069362 0.061862 0.247155 -vn -0.655996 -0.722324 0.218900 -v 0.068429 0.062606 0.247155 -vn -0.742980 -0.632507 0.218899 -v 0.067599 0.063463 0.247155 -vn -0.817761 -0.532305 0.218902 -v 0.066886 0.064419 0.247155 -vn -0.879127 -0.423364 0.218857 -v 0.066300 0.065459 0.247155 -vn -0.926044 -0.307465 0.218880 -v 0.065852 0.066565 0.247155 -vn -0.957761 -0.186523 0.218868 -v 0.065550 0.067719 0.247155 -vn -0.973745 -0.062517 0.218887 -v 0.065397 0.068903 0.247155 -vn -0.973745 0.062519 0.218887 -v 0.065397 0.070096 0.247155 -vn -0.957760 0.186528 0.218867 -v 0.065550 0.071279 0.247155 -vn -0.926043 0.307468 0.218879 -v 0.065852 0.072433 0.247155 -vn -0.879124 0.423362 0.218874 -v 0.066300 0.073539 0.247155 -vn -0.817765 0.532308 0.218881 -v 0.066886 0.074579 0.247155 -vn -0.742978 0.632509 0.218896 -v 0.067599 0.075535 0.247155 -vn -0.655995 0.722326 0.218897 -v 0.068429 0.076392 0.247155 -vn -0.558242 0.800277 0.218912 -v 0.069362 0.077136 0.247155 -vn -0.451324 0.865103 0.218868 -v 0.070383 0.077755 0.247155 -vn -0.336990 0.915716 0.218867 -v 0.071474 0.078238 0.247155 -vn -0.217127 0.951281 0.218906 -v 0.072618 0.078577 0.247155 -vn -0.093694 0.971248 0.218858 -v 0.073795 0.078768 0.247155 -vn 0.031274 0.975248 0.218889 -v 0.074988 0.078806 0.247155 -vn 0.155731 0.963248 0.218866 -v 0.076176 0.078692 0.247155 -vn 0.277629 0.935426 0.218859 -v 0.077339 0.078426 0.247155 -vn 0.394966 0.892237 0.218896 -v 0.078459 0.078014 0.247155 -vn 0.505823 0.834409 0.218872 -v 0.079517 0.077462 0.247155 -vn 0.608368 0.762870 0.218904 -v 0.080495 0.076779 0.247155 -vn 0.700930 0.678812 0.218885 -v 0.081379 0.075977 0.247155 -vn 0.781977 0.583604 0.218905 -v 0.082152 0.075069 0.247155 -vn 0.850186 0.478816 0.218904 -v 0.082803 0.074069 0.247155 -vn 0.904439 0.366168 0.218886 -v 0.083321 0.072994 0.247155 -vn 0.943841 0.247505 0.218874 -v 0.083697 0.071861 0.247155 -vn 0.967741 0.124777 0.218877 -v 0.083925 0.070690 0.247155 -vn 0.975747 0.000001 0.218902 -v 0.084001 0.069499 0.247155 -vn 0.779582 -0.100515 0.618181 -v 0.083887 0.068313 0.247235 -vn 0.760328 -0.199383 0.618180 -v 0.083660 0.067147 0.247235 -vn 0.728592 -0.294973 0.618178 -v 0.083285 0.066019 0.247235 -vn 0.684896 -0.385728 0.618167 -v 0.082770 0.064949 0.247235 -vn 0.629943 -0.470139 0.618175 -v 0.082121 0.063953 0.247235 -vn 0.564649 -0.546831 0.618181 -v 0.081351 0.063048 0.247235 -vn 0.490082 -0.614547 0.618185 -v 0.080471 0.062249 0.247235 -vn 0.407476 -0.672173 0.618180 -v 0.079497 0.061569 0.247235 -vn 0.318175 -0.718765 0.618177 -v 0.078443 0.061020 0.247235 -vn 0.223653 -0.753558 0.618166 -v 0.077328 0.060609 0.247235 -vn 0.125453 -0.775969 0.618170 -v 0.076170 0.060345 0.247235 -vn 0.025193 -0.785635 0.618177 -v 0.074987 0.060231 0.247235 -vn -0.075479 -0.782413 0.618169 -v 0.073799 0.060269 0.247235 -vn -0.174910 -0.766339 0.618167 -v 0.072626 0.060458 0.247235 -vn -0.271470 -0.737673 0.618176 -v 0.071487 0.060796 0.247235 -vn -0.363576 -0.696904 0.618173 -v 0.070400 0.061277 0.247235 -vn -0.449703 -0.644686 0.618180 -v 0.069384 0.061893 0.247235 -vn -0.528461 -0.581895 0.618165 -v 0.068455 0.062634 0.247235 -vn -0.598532 -0.509537 0.618167 -v 0.067629 0.063488 0.247235 -vn -0.658769 -0.428813 0.618178 -v 0.066918 0.064440 0.247235 -vn -0.708198 -0.341051 0.618174 -v 0.066335 0.065476 0.247235 -vn -0.746001 -0.247690 0.618169 -v 0.065889 0.066577 0.247235 -vn -0.771550 -0.150259 0.618169 -v 0.065587 0.067726 0.247235 -vn -0.784411 -0.050363 0.618194 -v 0.065435 0.068905 0.247235 -vn -0.784410 0.050360 0.618195 -v 0.065435 0.070093 0.247235 -vn -0.771546 0.150257 0.618175 -v 0.065587 0.071272 0.247235 -vn -0.745994 0.247686 0.618178 -v 0.065889 0.072421 0.247235 -vn -0.708198 0.341051 0.618175 -v 0.066335 0.073523 0.247235 -vn -0.658762 0.428808 0.618188 -v 0.066918 0.074558 0.247235 -vn -0.598520 0.509527 0.618187 -v 0.067629 0.075510 0.247235 -vn -0.528450 0.581882 0.618186 -v 0.068455 0.076364 0.247235 -vn -0.449711 0.644695 0.618165 -v 0.069384 0.077105 0.247235 -vn -0.363579 0.696912 0.618161 -v 0.070400 0.077721 0.247235 -vn -0.271468 0.737667 0.618185 -v 0.071487 0.078202 0.247235 -vn -0.174908 0.766328 0.618182 -v 0.072626 0.078540 0.247235 -vn -0.075478 0.782409 0.618174 -v 0.073799 0.078730 0.247235 -vn 0.025194 0.785642 0.618168 -v 0.074987 0.078768 0.247235 -vn 0.125450 0.775961 0.618180 -v 0.076170 0.078653 0.247235 -vn 0.223652 0.753555 0.618171 -v 0.077328 0.078389 0.247235 -vn 0.318167 0.718749 0.618199 -v 0.078443 0.077979 0.247235 -vn 0.407477 0.672173 0.618180 -v 0.079497 0.077429 0.247235 -vn 0.490085 0.614548 0.618181 -v 0.080471 0.076749 0.247235 -vn 0.564649 0.546830 0.618181 -v 0.081351 0.075950 0.247235 -vn 0.629944 0.470139 0.618175 -v 0.082121 0.075046 0.247235 -vn 0.684896 0.385728 0.618168 -v 0.082770 0.074050 0.247235 -vn 0.728592 0.294974 0.618178 -v 0.083285 0.072979 0.247235 -vn 0.760323 0.199380 0.618188 -v 0.083660 0.071851 0.247235 -vn 0.779582 0.100515 0.618182 -v 0.083887 0.070685 0.247235 -vn 0.786035 0.000000 0.618182 -v 0.083963 0.069499 0.247235 -vn 0.438055 -0.056480 0.897172 -v 0.083818 0.068322 0.247291 -vn 0.427252 -0.112039 0.897164 -v 0.083592 0.067165 0.247291 -vn 0.409394 -0.165744 0.897177 -v 0.083221 0.066045 0.247291 -vn 0.384862 -0.216750 0.897163 -v 0.082709 0.064983 0.247291 -vn 0.353981 -0.264182 0.897165 -v 0.082066 0.063994 0.247291 -vn 0.317281 -0.307271 0.897172 -v 0.081301 0.063096 0.247291 -vn 0.275389 -0.345326 0.897168 -v 0.080428 0.062303 0.247291 -vn 0.228963 -0.377700 0.897173 -v 0.079461 0.061629 0.247291 -vn 0.178787 -0.403884 0.897170 -v 0.078415 0.061083 0.247291 -vn 0.125673 -0.423434 0.897168 -v 0.077308 0.060676 0.247291 -vn 0.070493 -0.436026 0.897169 -v 0.076159 0.060413 0.247291 -vn 0.014158 -0.441462 0.897168 -v 0.074985 0.060300 0.247291 -vn -0.042411 -0.439651 0.897167 -v 0.073806 0.060338 0.247291 -vn -0.098287 -0.430618 0.897166 -v 0.072642 0.060526 0.247291 -vn -0.152541 -0.414504 0.897172 -v 0.071511 0.060862 0.247291 -vn -0.204291 -0.391588 0.897176 -v 0.070433 0.061339 0.247291 -vn -0.252699 -0.362261 0.897168 -v 0.069424 0.061951 0.247291 -vn -0.296944 -0.326969 0.897171 -v 0.068502 0.062686 0.247291 -vn -0.336321 -0.286314 0.897169 -v 0.067682 0.063533 0.247291 -vn -0.370181 -0.240961 0.897165 -v 0.066976 0.064478 0.247291 -vn -0.397942 -0.191640 0.897171 -v 0.066397 0.065506 0.247291 -vn -0.419191 -0.139180 0.897167 -v 0.065955 0.066599 0.247291 -vn -0.433545 -0.084433 0.897168 -v 0.065656 0.067740 0.247291 -vn -0.440768 -0.028298 0.897175 -v 0.065505 0.068909 0.247291 -vn -0.440767 0.028297 0.897175 -v 0.065505 0.070089 0.247291 -vn -0.433544 0.084433 0.897168 -v 0.065656 0.071258 0.247291 -vn -0.419191 0.139180 0.897166 -v 0.065955 0.072399 0.247291 -vn -0.397946 0.191640 0.897170 -v 0.066397 0.073492 0.247291 -vn -0.370170 0.240953 0.897171 -v 0.066976 0.074520 0.247291 -vn -0.336325 0.286317 0.897167 -v 0.067682 0.075465 0.247291 -vn -0.296948 0.326972 0.897168 -v 0.068502 0.076312 0.247291 -vn -0.252709 0.362278 0.897158 -v 0.069424 0.077048 0.247291 -vn -0.204290 0.391585 0.897177 -v 0.070433 0.077659 0.247291 -vn -0.152538 0.414496 0.897176 -v 0.071511 0.078136 0.247291 -vn -0.098286 0.430622 0.897165 -v 0.072642 0.078472 0.247291 -vn -0.042411 0.439627 0.897179 -v 0.073806 0.078660 0.247291 -vn 0.014159 0.441474 0.897162 -v 0.074985 0.078698 0.247291 -vn 0.070491 0.436018 0.897173 -v 0.076159 0.078585 0.247291 -vn 0.125666 0.423412 0.897179 -v 0.077308 0.078322 0.247291 -vn 0.178786 0.403880 0.897171 -v 0.078415 0.077915 0.247291 -vn 0.228960 0.377698 0.897174 -v 0.079461 0.077370 0.247291 -vn 0.275400 0.345338 0.897160 -v 0.080428 0.076695 0.247291 -vn 0.317285 0.307275 0.897169 -v 0.081301 0.075902 0.247291 -vn 0.353981 0.264182 0.897165 -v 0.082066 0.075004 0.247291 -vn 0.384862 0.216749 0.897163 -v 0.082709 0.074015 0.247291 -vn 0.409393 0.165746 0.897177 -v 0.083221 0.072953 0.247291 -vn 0.427254 0.112037 0.897163 -v 0.083592 0.071834 0.247291 -vn 0.438055 0.056482 0.897172 -v 0.083818 0.070676 0.247291 -vn 0.441696 -0.000001 0.897165 -v 0.083893 0.069499 0.247291 -vn 0.115621 -0.014908 0.993182 -v 0.083732 0.068333 0.247310 -vn 0.112760 -0.029569 0.993182 -v 0.083508 0.067187 0.247310 -vn 0.108054 -0.043746 0.993182 -v 0.083140 0.066078 0.247310 -vn 0.101572 -0.057204 0.993182 -v 0.082633 0.065025 0.247310 -vn 0.093430 -0.069729 0.993181 -v 0.081996 0.064046 0.247310 -vn 0.083742 -0.081100 0.993182 -v 0.081239 0.063157 0.247310 -vn 0.072684 -0.091143 0.993182 -v 0.080374 0.062371 0.247310 -vn 0.060436 -0.099695 0.993181 -v 0.079416 0.061703 0.247310 -vn 0.047188 -0.106599 0.993182 -v 0.078380 0.061163 0.247310 -vn 0.033169 -0.111757 0.993182 -v 0.077284 0.060759 0.247310 -vn 0.018606 -0.115082 0.993182 -v 0.076145 0.060499 0.247310 -vn 0.003736 -0.116516 0.993182 -v 0.074982 0.060387 0.247310 -vn -0.011194 -0.116039 0.993182 -v 0.073814 0.060425 0.247310 -vn -0.025941 -0.113654 0.993182 -v 0.072661 0.060611 0.247310 -vn -0.040262 -0.109403 0.993182 -v 0.071541 0.060943 0.247310 -vn -0.053920 -0.103356 0.993182 -v 0.070473 0.061416 0.247310 -vn -0.066693 -0.095610 0.993182 -v 0.069474 0.062022 0.247310 -vn -0.078369 -0.086294 0.993183 -v 0.068560 0.062750 0.247310 -vn -0.088767 -0.075569 0.993182 -v 0.067748 0.063589 0.247310 -vn -0.097702 -0.063598 0.993182 -v 0.067049 0.064526 0.247310 -vn -0.105031 -0.050580 0.993182 -v 0.066476 0.065544 0.247310 -vn -0.110638 -0.036735 0.993182 -v 0.066037 0.066626 0.247310 -vn -0.114426 -0.022285 0.993182 -v 0.065741 0.067756 0.247310 -vn -0.116346 -0.007470 0.993181 -v 0.065592 0.068915 0.247310 -vn -0.116346 0.007470 0.993181 -v 0.065592 0.070083 0.247310 -vn -0.114426 0.022284 0.993182 -v 0.065741 0.071242 0.247310 -vn -0.110638 0.036734 0.993182 -v 0.066037 0.072372 0.247310 -vn -0.105035 0.050582 0.993181 -v 0.066476 0.073455 0.247310 -vn -0.097702 0.063597 0.993182 -v 0.067049 0.074473 0.247310 -vn -0.088772 0.075573 0.993181 -v 0.067748 0.075409 0.247310 -vn -0.078374 0.086299 0.993182 -v 0.068560 0.076248 0.247310 -vn -0.066693 0.095610 0.993182 -v 0.069474 0.076976 0.247310 -vn -0.053918 0.103352 0.993182 -v 0.070473 0.077582 0.247310 -vn -0.040263 0.109407 0.993181 -v 0.071541 0.078055 0.247310 -vn -0.025942 0.113658 0.993181 -v 0.072661 0.078387 0.247310 -vn -0.011194 0.116039 0.993182 -v 0.073814 0.078574 0.247310 -vn 0.003736 0.116516 0.993182 -v 0.074982 0.078611 0.247310 -vn 0.018607 0.115086 0.993181 -v 0.076145 0.078499 0.247310 -vn 0.033169 0.111757 0.993182 -v 0.077284 0.078239 0.247310 -vn 0.047192 0.106607 0.993181 -v 0.078380 0.077836 0.247310 -vn 0.060434 0.099692 0.993181 -v 0.079416 0.077295 0.247310 -vn 0.072681 0.091140 0.993182 -v 0.080374 0.076627 0.247310 -vn 0.083747 0.081104 0.993181 -v 0.081239 0.075841 0.247310 -vn 0.093430 0.069728 0.993181 -v 0.081996 0.074952 0.247310 -vn 0.101572 0.057204 0.993182 -v 0.082633 0.073973 0.247310 -vn 0.108054 0.043746 0.993182 -v 0.083140 0.072920 0.247310 -vn 0.112762 0.029570 0.993182 -v 0.083508 0.071812 0.247310 -vn 0.115621 0.014907 0.993182 -v 0.083732 0.070665 0.247310 -vn 0.116576 -0.000000 0.993182 -v 0.083806 0.069499 0.247310 -vn 0.053499 -0.005623 0.998552 -v 0.066378 0.070373 0.247310 -vn 0.052618 -0.011184 0.998552 -v 0.066514 0.071237 0.247310 -vn 0.051161 -0.016623 0.998552 -v 0.066741 0.072082 0.247310 -vn 0.049143 -0.021880 0.998552 -v 0.067054 0.072899 0.247310 -vn 0.046586 -0.026897 0.998552 -v 0.067451 0.073678 0.247310 -vn 0.043520 -0.031619 0.998552 -v 0.067928 0.074412 0.247310 -vn 0.039976 -0.035995 0.998552 -v 0.068479 0.075092 0.247310 -vn 0.035995 -0.039976 0.998552 -v 0.069097 0.075710 0.247310 -vn 0.031619 -0.043520 0.998552 -v 0.069777 0.076261 0.247310 -vn 0.026897 -0.046587 0.998552 -v 0.070511 0.076737 0.247310 -vn 0.021880 -0.049143 0.998552 -v 0.071290 0.077134 0.247310 -vn 0.016623 -0.051161 0.998552 -v 0.072107 0.077448 0.247310 -vn 0.011184 -0.052618 0.998552 -v 0.072952 0.077674 0.247310 -vn 0.005623 -0.053500 0.998552 -v 0.073816 0.077811 0.247310 -vn 0.000000 -0.053794 0.998552 -v 0.074690 0.077857 0.247310 -vn -0.005623 -0.053500 0.998552 -v 0.075563 0.077811 0.247310 -vn -0.011184 -0.052618 0.998552 -v 0.076427 0.077674 0.247310 -vn -0.016623 -0.051161 0.998552 -v 0.077272 0.077448 0.247310 -vn -0.021880 -0.049143 0.998552 -v 0.078089 0.077134 0.247310 -vn -0.026897 -0.046587 0.998552 -v 0.078869 0.076737 0.247310 -vn -0.031619 -0.043520 0.998552 -v 0.079602 0.076261 0.247310 -vn -0.035995 -0.039977 0.998552 -v 0.080282 0.075710 0.247310 -vn -0.039976 -0.035995 0.998552 -v 0.080901 0.075092 0.247310 -vn -0.043520 -0.031619 0.998552 -v 0.081451 0.074412 0.247310 -vn -0.046587 -0.026897 0.998552 -v 0.081928 0.073678 0.247310 -vn -0.049143 -0.021880 0.998552 -v 0.082325 0.072899 0.247310 -vn -0.005623 0.053499 0.998552 -v 0.075563 0.061187 0.247310 -vn 0.000000 0.053793 0.998552 -v 0.074690 0.061141 0.247310 -vn 0.005623 0.053499 0.998552 -v 0.073816 0.061187 0.247310 -vn 0.011184 0.052618 0.998552 -v 0.072952 0.061324 0.247310 -vn 0.016623 0.051160 0.998552 -v 0.072107 0.061550 0.247310 -vn 0.021880 0.049143 0.998552 -v 0.071290 0.061864 0.247310 -vn 0.026897 0.046586 0.998552 -v 0.070511 0.062261 0.247310 -vn 0.031619 0.043520 0.998552 -v 0.069777 0.062737 0.247310 -vn 0.035995 0.039976 0.998552 -v 0.069097 0.063288 0.247310 -vn 0.039977 0.035995 0.998552 -v 0.068479 0.063907 0.247310 -vn 0.043520 0.031619 0.998552 -v 0.067928 0.064586 0.247310 -vn 0.046587 0.026897 0.998552 -v 0.067451 0.065320 0.247310 -vn 0.049143 0.021880 0.998552 -v 0.067054 0.066100 0.247310 -vn 0.051161 0.016623 0.998552 -v 0.066741 0.066916 0.247310 -vn 0.052618 0.011184 0.998552 -v 0.066514 0.067761 0.247310 -vn 0.053500 0.005623 0.998552 -v 0.066378 0.068625 0.247310 -vn 0.053793 -0.000000 0.998552 -v 0.066332 0.069499 0.247310 -vn -0.051161 -0.016623 0.998552 -v 0.082638 0.072082 0.247310 -vn -0.052619 -0.011185 0.998552 -v 0.082865 0.071237 0.247310 -vn -0.053499 -0.005623 0.998552 -v 0.083002 0.070373 0.247310 -vn -0.053794 -0.000000 0.998552 -v 0.083048 0.069499 0.247310 -vn -0.053499 0.005623 0.998552 -v 0.083002 0.068625 0.247310 -vn -0.031619 0.043520 0.998552 -v 0.079602 0.062737 0.247310 -vn -0.026897 0.046587 0.998552 -v 0.078869 0.062261 0.247310 -vn -0.021880 0.049143 0.998552 -v 0.078089 0.061864 0.247310 -vn -0.016623 0.051161 0.998552 -v 0.077272 0.061550 0.247310 -vn -0.011184 0.052618 0.998552 -v 0.076427 0.061324 0.247310 -vn -0.052619 0.011184 0.998552 -v 0.082865 0.067761 0.247310 -vn -0.051161 0.016623 0.998552 -v 0.082638 0.066916 0.247310 -vn -0.049143 0.021880 0.998552 -v 0.082325 0.066100 0.247310 -vn -0.046587 0.026897 0.998552 -v 0.081928 0.065320 0.247310 -vn -0.043520 0.031619 0.998552 -v 0.081451 0.064586 0.247310 -vn -0.039977 0.035995 0.998552 -v 0.080901 0.063907 0.247310 -vn -0.035995 0.039976 0.998552 -v 0.080282 0.063288 0.247310 -vn -0.216116 0.022714 0.976103 -v 0.082343 0.068695 0.247236 -vn -0.212558 0.045180 0.976103 -v 0.082217 0.067899 0.247236 -vn -0.206671 0.067152 0.976103 -v 0.082008 0.067121 0.247236 -vn -0.198520 0.088386 0.976103 -v 0.081720 0.066369 0.247236 -vn -0.188193 0.108653 0.976103 -v 0.081354 0.065651 0.247236 -vn -0.175805 0.127730 0.976103 -v 0.080915 0.064976 0.247236 -vn -0.161490 0.145406 0.976103 -v 0.080408 0.064350 0.247236 -vn -0.145406 0.161490 0.976103 -v 0.079839 0.063780 0.247236 -vn -0.127730 0.175805 0.976103 -v 0.079213 0.063273 0.247236 -vn -0.108653 0.188193 0.976103 -v 0.078537 0.062835 0.247236 -vn -0.088387 0.198519 0.976103 -v 0.077820 0.062469 0.247236 -vn -0.067151 0.206671 0.976103 -v 0.077068 0.062180 0.247236 -vn -0.045181 0.212558 0.976103 -v 0.076290 0.061972 0.247236 -vn -0.022715 0.216117 0.976103 -v 0.075494 0.061846 0.247236 -vn -0.000000 0.217307 0.976103 -v 0.074690 0.061804 0.247236 -vn 0.022715 0.216116 0.976103 -v 0.073885 0.061846 0.247236 -vn 0.045180 0.212558 0.976103 -v 0.073090 0.061972 0.247236 -vn 0.067152 0.206671 0.976103 -v 0.072312 0.062180 0.247236 -vn 0.088386 0.198520 0.976103 -v 0.071560 0.062469 0.247236 -vn 0.108654 0.188193 0.976103 -v 0.070842 0.062835 0.247236 -vn 0.127730 0.175805 0.976103 -v 0.070166 0.063273 0.247236 -vn 0.145406 0.161490 0.976103 -v 0.069540 0.063780 0.247236 -vn 0.161491 0.145407 0.976103 -v 0.068971 0.064350 0.247236 -vn 0.175805 0.127730 0.976103 -v 0.068464 0.064976 0.247236 -vn 0.188193 0.108653 0.976103 -v 0.068025 0.065651 0.247236 -vn 0.198519 0.088386 0.976104 -v 0.067660 0.066369 0.247236 -vn 0.206671 0.067151 0.976103 -v 0.067371 0.067121 0.247236 -vn 0.212559 0.045181 0.976103 -v 0.067162 0.067899 0.247236 -vn 0.216116 0.022715 0.976103 -v 0.067036 0.068695 0.247236 -vn 0.217307 -0.000000 0.976103 -v 0.066994 0.069499 0.247236 -vn 0.216116 -0.022715 0.976103 -v 0.067036 0.070304 0.247236 -vn 0.212559 -0.045182 0.976103 -v 0.067162 0.071099 0.247236 -vn 0.206671 -0.067151 0.976103 -v 0.067371 0.071877 0.247236 -vn 0.198519 -0.088387 0.976103 -v 0.067660 0.072629 0.247236 -vn 0.188193 -0.108653 0.976103 -v 0.068025 0.073347 0.247236 -vn 0.175805 -0.127730 0.976103 -v 0.068464 0.074022 0.247236 -vn 0.161491 -0.145408 0.976103 -v 0.068971 0.074648 0.247236 -vn 0.145407 -0.161491 0.976103 -v 0.069540 0.075218 0.247236 -vn 0.127730 -0.175805 0.976103 -v 0.070166 0.075725 0.247236 -vn 0.108654 -0.188193 0.976103 -v 0.070842 0.076164 0.247236 -vn 0.088386 -0.198520 0.976103 -v 0.071560 0.076529 0.247236 -vn 0.067151 -0.206671 0.976103 -v 0.072312 0.076818 0.247236 -vn 0.045181 -0.212559 0.976103 -v 0.073090 0.077026 0.247236 -vn 0.022715 -0.216116 0.976103 -v 0.073885 0.077152 0.247236 -vn 0.000000 -0.217307 0.976103 -v 0.074690 0.077194 0.247236 -vn -0.022715 -0.216117 0.976103 -v 0.075494 0.077152 0.247236 -vn -0.045181 -0.212559 0.976103 -v 0.076290 0.077026 0.247236 -vn -0.067150 -0.206671 0.976104 -v 0.077068 0.076818 0.247236 -vn -0.088387 -0.198519 0.976103 -v 0.077820 0.076529 0.247236 -vn -0.108654 -0.188194 0.976103 -v 0.078537 0.076164 0.247236 -vn -0.127729 -0.175805 0.976103 -v 0.079213 0.075725 0.247236 -vn -0.145408 -0.161491 0.976103 -v 0.079839 0.075218 0.247236 -vn -0.161490 -0.145406 0.976103 -v 0.080408 0.074648 0.247236 -vn -0.175805 -0.127730 0.976103 -v 0.080915 0.074022 0.247236 -vn -0.188192 -0.108653 0.976103 -v 0.081354 0.073347 0.247236 -vn -0.198520 -0.088387 0.976103 -v 0.081720 0.072629 0.247236 -vn -0.206671 -0.067152 0.976103 -v 0.082008 0.071877 0.247236 -vn -0.212558 -0.045180 0.976103 -v 0.082217 0.071099 0.247236 -vn -0.216116 -0.022715 0.976103 -v 0.082343 0.070304 0.247236 -vn -0.217307 -0.000000 0.976103 -v 0.082385 0.069499 0.247236 -vn -0.376279 0.039361 0.925670 -v 0.081716 0.068761 0.247018 -vn -0.370250 0.078884 0.925577 -v 0.081601 0.068030 0.247018 -vn -0.360007 0.116778 0.925612 -v 0.081409 0.067316 0.247018 -vn -0.345745 0.154132 0.925583 -v 0.081144 0.066625 0.247018 -vn -0.327616 0.189149 0.925684 -v 0.080809 0.065966 0.247018 -vn -0.306050 0.222359 0.925684 -v 0.080406 0.065346 0.247018 -vn -0.280490 0.253044 0.925902 -v 0.079940 0.064771 0.247018 -vn -0.253407 0.280647 0.925755 -v 0.079417 0.064248 0.247018 -vn -0.222228 0.306187 0.925670 -v 0.078843 0.063783 0.247018 -vn -0.189149 0.327616 0.925684 -v 0.078222 0.063380 0.247018 -vn -0.154051 0.345548 0.925670 -v 0.077563 0.063044 0.247018 -vn -0.116809 0.360088 0.925577 -v 0.076873 0.062779 0.247018 -vn -0.078872 0.370165 0.925612 -v 0.076159 0.062588 0.247018 -vn -0.039390 0.376491 0.925582 -v 0.075428 0.062472 0.247018 -vn 0.000000 0.378299 0.925683 -v 0.074690 0.062434 0.247018 -vn 0.039543 0.376227 0.925683 -v 0.073951 0.062472 0.247018 -vn 0.078898 0.369434 0.925902 -v 0.073221 0.062588 0.247018 -vn 0.116344 0.359780 0.925755 -v 0.072506 0.062779 0.247018 -vn 0.154051 0.345549 0.925670 -v 0.071816 0.063044 0.247018 -vn 0.189150 0.327616 0.925683 -v 0.071157 0.063380 0.247018 -vn 0.222229 0.306186 0.925670 -v 0.070537 0.063783 0.247018 -vn 0.253440 0.281205 0.925577 -v 0.069962 0.064248 0.247018 -vn 0.281137 0.253388 0.925612 -v 0.069439 0.064771 0.247018 -vn 0.306356 0.222357 0.925583 -v 0.068973 0.065346 0.247018 -vn 0.327616 0.189149 0.925684 -v 0.068571 0.065966 0.247018 -vn 0.345593 0.153867 0.925684 -v 0.068235 0.066625 0.247018 -vn 0.359388 0.116390 0.925902 -v 0.067970 0.067316 0.247018 -vn 0.369751 0.079135 0.925755 -v 0.067778 0.068030 0.247018 -vn 0.376279 0.039362 0.925670 -v 0.067663 0.068761 0.247018 -vn 0.378299 -0.000000 0.925684 -v 0.067624 0.069499 0.247018 -vn 0.376279 -0.039361 0.925670 -v 0.067663 0.070238 0.247018 -vn 0.370250 -0.078886 0.925577 -v 0.067778 0.070968 0.247018 -vn 0.360008 -0.116778 0.925612 -v 0.067970 0.071683 0.247018 -vn 0.345745 -0.154134 0.925583 -v 0.068235 0.072373 0.247018 -vn 0.327616 -0.189150 0.925683 -v 0.068571 0.073032 0.247018 -vn 0.306051 -0.222358 0.925684 -v 0.068973 0.073652 0.247018 -vn 0.280491 -0.253045 0.925901 -v 0.069439 0.074227 0.247018 -vn 0.253407 -0.280647 0.925755 -v 0.069962 0.074750 0.247018 -vn 0.222228 -0.306187 0.925670 -v 0.070537 0.075215 0.247018 -vn 0.189150 -0.327616 0.925683 -v 0.071157 0.075618 0.247018 -vn 0.154051 -0.345549 0.925670 -v 0.071816 0.075954 0.247018 -vn 0.116810 -0.360088 0.925577 -v 0.072506 0.076219 0.247018 -vn 0.078872 -0.370166 0.925612 -v 0.073221 0.076410 0.247018 -vn 0.039390 -0.376491 0.925583 -v 0.073951 0.076526 0.247018 -vn 0.000000 -0.378299 0.925684 -v 0.074690 0.076565 0.247018 -vn -0.039543 -0.376226 0.925684 -v 0.075428 0.076526 0.247018 -vn -0.078900 -0.369434 0.925901 -v 0.076159 0.076410 0.247018 -vn -0.116343 -0.359780 0.925755 -v 0.076873 0.076219 0.247018 -vn -0.154051 -0.345548 0.925670 -v 0.077563 0.075954 0.247018 -vn -0.189150 -0.327617 0.925683 -v 0.078222 0.075618 0.247018 -vn -0.222227 -0.306187 0.925670 -v 0.078843 0.075215 0.247018 -vn -0.253442 -0.281203 0.925577 -v 0.079417 0.074750 0.247018 -vn -0.281138 -0.253386 0.925612 -v 0.079940 0.074227 0.247018 -vn -0.306356 -0.222358 0.925582 -v 0.080406 0.073652 0.247018 -vn -0.327616 -0.189150 0.925684 -v 0.080809 0.073032 0.247018 -vn -0.345593 -0.153868 0.925683 -v 0.081144 0.072373 0.247018 -vn -0.359387 -0.116389 0.925902 -v 0.081409 0.071683 0.247018 -vn -0.369750 -0.079133 0.925755 -v 0.081601 0.070968 0.247018 -vn -0.376279 -0.039361 0.925670 -v 0.081716 0.070238 0.247018 -vn -0.378299 -0.000000 0.925684 -v 0.081755 0.069499 0.247018 -vn 0.526413 0.000000 0.850229 -v 0.069594 0.069499 0.246077 -vn 0.524126 -0.074552 0.848372 -v 0.069672 0.070384 0.246077 -vn 0.482352 -0.123631 0.867209 -v 0.069706 0.070558 0.246077 -vn 0.500109 -0.170154 0.849081 -v 0.069902 0.071242 0.246077 -vn 0.421474 -0.201492 0.884172 -v 0.070035 0.071571 0.246077 -vn 0.458895 -0.259438 0.849769 -v 0.070277 0.072047 0.246077 -vn 0.401426 -0.284791 0.870489 -v 0.070568 0.072494 0.246077 -vn 0.400769 -0.347745 0.847619 -v 0.070787 0.072774 0.246077 -vn 0.351240 -0.363672 0.862771 -v 0.071280 0.073286 0.246077 -vn 0.326628 -0.416629 0.848372 -v 0.071415 0.073402 0.246077 -vn 0.263206 -0.455884 0.850231 -v 0.072142 0.073912 0.246077 -vn 0.197496 -0.491187 0.848369 -v 0.072947 0.074287 0.246077 -vn 0.134109 -0.479561 0.867200 -v 0.073115 0.074345 0.246077 -vn 0.102695 -0.518179 0.849084 -v 0.073805 0.074517 0.246077 -vn 0.036244 -0.465758 0.884170 -v 0.074157 0.074566 0.246077 -vn 0.004770 -0.527137 0.849767 -v 0.074690 0.074594 0.246077 -vn -0.045925 -0.490034 0.870493 -v 0.075222 0.074566 0.246077 -vn -0.100769 -0.520936 0.847627 -v 0.075574 0.074517 0.246077 -vn -0.139325 -0.486028 0.862766 -v 0.076264 0.074345 0.246077 -vn -0.197493 -0.491187 0.848370 -v 0.076432 0.074287 0.246077 -vn -0.263205 -0.455885 0.850231 -v 0.077237 0.073912 0.246077 -vn -0.326628 -0.416629 0.848372 -v 0.077965 0.073402 0.246077 -vn -0.348251 -0.355917 0.867205 -v 0.078099 0.073286 0.246077 -vn -0.397411 -0.348026 0.849083 -v 0.078593 0.072774 0.246077 -vn -0.385237 -0.264267 0.884169 -v 0.078812 0.072494 0.246077 -vn -0.454127 -0.267697 0.849769 -v 0.079102 0.072047 0.246077 -vn -0.447344 -0.205245 0.870493 -v 0.079344 0.071571 0.246077 -vn -0.501529 -0.173200 0.847626 -v 0.079477 0.071242 0.246077 -vn -0.490571 -0.122354 0.862769 -v 0.079673 0.070558 0.246077 -vn -0.524123 -0.074560 0.848373 -v 0.079707 0.070384 0.246077 -vn -0.526414 -0.000000 0.850228 -v 0.079785 0.069499 0.246077 -vn -0.524127 0.074558 0.848370 -v 0.079707 0.068614 0.246077 -vn -0.482365 0.123640 0.867201 -v 0.079673 0.068440 0.246077 -vn -0.500109 0.170156 0.849081 -v 0.079477 0.067756 0.246077 -vn -0.421479 0.201491 0.884170 -v 0.079344 0.067427 0.246077 -vn -0.458906 0.259439 0.849763 -v 0.079102 0.066952 0.246077 -vn -0.401420 0.284787 0.870493 -v 0.078812 0.066504 0.246077 -vn -0.400758 0.347735 0.847628 -v 0.078593 0.066224 0.246077 -vn -0.351239 0.363669 0.862772 -v 0.078099 0.065713 0.246077 -vn -0.326628 0.416630 0.848372 -v 0.077965 0.065596 0.246077 -vn -0.263205 0.455885 0.850231 -v 0.077237 0.065087 0.246077 -vn -0.197501 0.491186 0.848369 -v 0.076432 0.064711 0.246077 -vn -0.134110 0.479549 0.867207 -v 0.076264 0.064653 0.246077 -vn -0.102696 0.518183 0.849082 -v 0.075574 0.064481 0.246077 -vn -0.036239 0.465751 0.884173 -v 0.075222 0.064432 0.246077 -vn -0.004770 0.527137 0.849767 -v 0.074690 0.064404 0.246077 -vn 0.045921 0.490028 0.870496 -v 0.074157 0.064432 0.246077 -vn 0.100769 0.520932 0.847629 -v 0.073805 0.064481 0.246077 -vn 0.139331 0.486010 0.862776 -v 0.073115 0.064653 0.246077 -vn 0.197504 0.491185 0.848369 -v 0.072947 0.064711 0.246077 -vn 0.263204 0.455885 0.850231 -v 0.072142 0.065087 0.246077 -vn 0.326629 0.416629 0.848371 -v 0.071415 0.065596 0.246077 -vn 0.348251 0.355917 0.867205 -v 0.071280 0.065713 0.246077 -vn 0.397421 0.348037 0.849074 -v 0.070787 0.066224 0.246077 -vn 0.385244 0.264268 0.884166 -v 0.070568 0.066504 0.246077 -vn 0.454136 0.267704 0.849762 -v 0.070277 0.066952 0.246077 -vn 0.447339 0.205246 0.870495 -v 0.070035 0.067427 0.246077 -vn 0.501530 0.173200 0.847626 -v 0.069902 0.067756 0.246077 -vn 0.490562 0.122342 0.862775 -v 0.069706 0.068440 0.246077 -vn 0.524129 0.074549 0.848370 -v 0.069672 0.068614 0.246077 -vn 0.078562 0.776468 -0.625240 -v 0.073973 0.064517 0.245762 -vn 0.166997 0.792210 -0.586954 -v 0.073816 0.064542 0.245762 -vn 0.176488 0.942875 -0.282556 -v 0.073823 0.064586 0.245843 -vn 0.632958 -0.456296 -0.625427 -v 0.070733 0.072611 0.245762 -vn 0.602546 -0.540625 -0.587080 -v 0.070834 0.072735 0.245762 -vn 0.728306 -0.624278 -0.282573 -v 0.070868 0.072706 0.245843 -vn -0.711764 -0.320345 -0.625116 -v 0.079363 0.071370 0.245762 -vn -0.769325 -0.251647 -0.587207 -v 0.079420 0.071221 0.245762 -vn -0.904802 -0.318595 -0.282543 -v 0.079378 0.071205 0.245843 -vn -0.630607 0.751527 0.193758 -v 0.077894 0.065680 0.245935 -vn -0.496046 0.604095 0.623704 -v 0.077918 0.065651 0.246019 -vn -0.595517 0.505894 0.624044 -v 0.078538 0.066270 0.246019 -vn 0.170359 0.966142 0.193775 -v 0.073824 0.064590 0.245935 -vn 0.140356 0.768681 0.624043 -v 0.073817 0.064552 0.246019 -vn -0.005370 0.783544 0.621313 -v 0.074690 0.064476 0.246019 -vn 0.966149 0.170355 0.193740 -v 0.069780 0.068633 0.245935 -vn 0.771206 0.127542 0.623678 -v 0.069743 0.068627 0.246019 -vn 0.735871 0.262786 0.624049 -v 0.069969 0.067781 0.246019 -vn 0.751524 -0.630601 0.193787 -v 0.070871 0.072703 0.245935 -vn 0.595527 -0.505900 0.624030 -v 0.070842 0.072728 0.246019 -vn 0.681245 -0.387117 0.621327 -v 0.070339 0.072011 0.246019 -vn -0.335535 -0.921879 0.193791 -v 0.076395 0.074183 0.245935 -vn -0.275135 -0.731635 0.623707 -v 0.076408 0.074219 0.246019 -vn -0.140361 -0.768681 0.624042 -v 0.075562 0.074446 0.246019 -vn -0.737708 0.261072 0.622598 -v 0.079410 0.067781 0.246019 -vn -0.681241 0.387114 0.621332 -v 0.079040 0.066988 0.246019 -vn -0.274519 0.731953 0.623605 -v 0.076408 0.064779 0.246019 -vn 0.594943 0.508336 0.622605 -v 0.070842 0.066270 0.246019 -vn 0.675870 0.396418 0.621331 -v 0.070339 0.066988 0.246019 -vn 0.771153 -0.128239 0.623601 -v 0.069743 0.070371 0.246019 -vn 0.142755 -0.769395 0.622617 -v 0.073817 0.074446 0.246019 -vn 0.005371 -0.783523 0.621340 -v 0.074690 0.074522 0.246019 -vn -0.496633 -0.603716 0.623605 -v 0.077918 0.073347 0.246019 -vn -0.785736 0.000001 0.618562 -v 0.079713 0.069499 0.246019 -vn -0.771184 -0.127545 0.623704 -v 0.079636 0.070371 0.246019 -vn -0.735899 -0.262791 0.624014 -v 0.079410 0.071217 0.246019 -vn -0.675875 -0.396417 0.621326 -v 0.079040 0.072011 0.246019 -vn -0.594934 -0.508330 0.622619 -v 0.078538 0.072728 0.246019 -vn 0.274511 -0.731944 0.623620 -v 0.072972 0.074219 0.246019 -vn 0.737697 -0.261062 0.622615 -v 0.069969 0.071217 0.246019 -vn 0.496621 0.603705 0.623625 -v 0.071461 0.065651 0.246019 -vn -0.142761 0.769393 0.622618 -v 0.075562 0.064552 0.246019 -vn -0.771136 0.128236 0.623623 -v 0.079636 0.068627 0.246019 -vn -0.392862 -0.680458 0.618576 -v 0.077201 0.073849 0.246019 -vn -0.490525 -0.849614 0.193756 -v 0.077182 0.073816 0.245935 -vn -0.479316 -0.830196 -0.284658 -v 0.077184 0.073820 0.245843 -vn 0.496057 -0.604109 0.623683 -v 0.071461 0.073347 0.246019 -vn 0.630604 -0.751529 0.193759 -v 0.071485 0.073318 0.245935 -vn 0.610978 -0.739827 -0.281714 -v 0.071483 0.073321 0.245843 -vn 0.785715 0.000002 0.618589 -v 0.069666 0.069499 0.246019 -vn 0.981048 0.000002 0.193767 -v 0.069705 0.069499 0.245935 -vn 0.958632 -0.000000 -0.284647 -v 0.069701 0.069499 0.245843 -vn 0.275149 0.731657 0.623676 -v 0.072972 0.064779 0.246019 -vn 0.335541 0.921887 0.193745 -v 0.072985 0.064815 0.245935 -vn 0.335228 0.899041 -0.281688 -v 0.072983 0.064811 0.245843 -vn -0.392862 0.680458 0.618576 -v 0.077201 0.065149 0.246019 -vn -0.490525 0.849614 0.193755 -v 0.077182 0.065182 0.245935 -vn -0.479318 0.830205 -0.284630 -v 0.077184 0.065179 0.245843 -vn -0.921888 -0.335538 0.193745 -v 0.079374 0.071204 0.245935 -vn -0.966142 -0.170356 0.193775 -v 0.079599 0.070365 0.245935 -vn -0.981047 0.000000 0.193771 -v 0.079675 0.069499 0.245935 -vn -0.966142 0.170355 0.193774 -v 0.079599 0.068633 0.245935 -vn -0.751527 -0.630608 0.193756 -v 0.078508 0.072703 0.245935 -vn -0.741380 -0.609321 -0.281218 -v 0.078511 0.072706 0.245843 -vn -0.836002 -0.470688 -0.282054 -v 0.079010 0.071993 0.245843 -vn 0.335541 -0.921880 0.193778 -v 0.072985 0.074183 0.245935 -vn 0.336015 -0.898658 -0.281972 -v 0.072983 0.074187 0.245843 -vn 0.175667 -0.942640 -0.283849 -v 0.073823 0.074412 0.245843 -vn 0.480867 -0.832886 -0.273986 -v 0.072195 0.073820 0.245843 -vn 0.490525 -0.849614 0.193754 -v 0.072197 0.073816 0.245935 -vn 0.392864 -0.680456 0.618577 -v 0.072178 0.073849 0.246019 -vn 0.921880 -0.335539 0.193778 -v 0.070005 0.071204 0.245935 -vn 0.898378 -0.337393 -0.281217 -v 0.070002 0.071205 0.245843 -vn 0.825622 -0.488650 -0.282080 -v 0.070369 0.071993 0.245843 -vn 0.630607 0.751527 0.193758 -v 0.071485 0.065680 0.245935 -vn 0.610254 0.740316 -0.281997 -v 0.071483 0.065678 0.245843 -vn 0.728520 0.623466 -0.283812 -v 0.070868 0.066292 0.245843 -vn 0.480871 0.832893 -0.273958 -v 0.072195 0.065179 0.245843 -vn 0.490527 0.849614 0.193753 -v 0.072197 0.065182 0.245935 -vn 0.392861 0.680458 0.618577 -v 0.072178 0.065149 0.246019 -vn -0.170356 0.966142 0.193775 -v 0.075555 0.064590 0.245935 -vn -0.156998 0.946719 -0.281204 -v 0.075556 0.064586 0.245843 -vn 0.010373 0.959348 -0.282035 -v 0.074690 0.064510 0.245843 -vn -0.946202 -0.159207 -0.281699 -v 0.079603 0.070365 0.245843 -vn -0.961747 -0.000001 -0.273938 -v 0.079678 0.069499 0.245843 -vn -0.946272 0.158335 -0.281957 -v 0.079603 0.068633 0.245843 -vn -0.904196 0.319186 -0.283812 -v 0.079378 0.067793 0.245843 -vn -0.849613 -0.490527 0.193755 -v 0.079007 0.071992 0.245935 -vn -0.774922 -0.185953 -0.604084 -v 0.079632 0.070452 0.245762 -vn -0.711476 -0.385195 -0.587730 -v 0.079049 0.072016 0.245762 -vn -0.442361 -0.628867 -0.639409 -v 0.077609 0.073599 0.245762 -vn -0.528555 -0.610714 -0.589625 -v 0.077925 0.073355 0.245762 -vn -0.624244 -0.729215 -0.280295 -v 0.077896 0.073321 0.245843 -vn -0.630604 -0.751529 0.193759 -v 0.077894 0.073318 0.245935 -vn -0.526053 -0.531289 -0.664078 -v 0.078333 0.072973 0.245762 -vn -0.630125 -0.506272 -0.588754 -v 0.078546 0.072735 0.245762 -vn -0.627257 -0.435734 -0.645511 -v 0.078924 0.072221 0.245762 -vn -0.405560 -0.701906 -0.585533 -v 0.077206 0.073858 0.245762 -vn -0.325208 -0.901791 -0.284629 -v 0.076396 0.074187 0.245843 -vn -0.270983 -0.763699 -0.585946 -v 0.076411 0.074229 0.245762 -vn -0.323154 -0.697276 -0.639826 -v 0.076781 0.074078 0.245762 -vn -0.170361 -0.966149 0.193738 -v 0.075555 0.074408 0.245935 -vn -0.161021 -0.945038 -0.284562 -v 0.075556 0.074412 0.245843 -vn -0.128350 -0.799941 -0.586191 -v 0.075564 0.074456 0.245762 -vn -0.194097 -0.746870 -0.636013 -v 0.075876 0.074391 0.245762 -vn 0.000002 -0.981048 0.193767 -v 0.074690 0.074484 0.245935 -vn 0.007867 -0.958687 -0.284355 -v 0.074690 0.074488 0.245843 -vn 0.019055 -0.810485 -0.585450 -v 0.074690 0.074533 0.245762 -vn -0.057046 -0.775665 -0.628562 -v 0.074929 0.074527 0.245762 -vn 0.170360 -0.966149 0.193737 -v 0.073824 0.074408 0.245935 -vn 0.083722 -0.782752 -0.616676 -v 0.073973 0.074482 0.245762 -vn 0.548737 -0.578122 -0.603873 -v 0.071393 0.073303 0.245762 -vn 0.496142 -0.640481 -0.586197 -v 0.071454 0.073355 0.245762 -vn 0.404284 -0.699866 -0.588848 -v 0.072173 0.073858 0.245762 -vn 0.306348 -0.749832 -0.586433 -v 0.072968 0.074229 0.245762 -vn 0.228892 -0.765397 -0.601478 -v 0.073043 0.074256 0.245762 -vn 0.165604 -0.793131 -0.586105 -v 0.073816 0.074456 0.245762 -vn 0.849613 -0.490526 0.193755 -v 0.070373 0.071992 0.245935 -vn 0.689281 -0.423211 -0.588034 -v 0.070330 0.072016 0.245762 -vn 0.765343 -0.069077 -0.639905 -v 0.069679 0.069978 0.245762 -vn 0.793178 -0.152455 -0.589598 -v 0.069732 0.070373 0.245762 -vn 0.943637 -0.176006 -0.280306 -v 0.069777 0.070365 0.245843 -vn 0.966148 -0.170359 0.193741 -v 0.069780 0.070365 0.245935 -vn 0.723214 -0.189884 -0.664007 -v 0.069860 0.070917 0.245762 -vn 0.753593 -0.292818 -0.588520 -v 0.069960 0.071221 0.245762 -vn 0.691220 -0.325251 -0.645312 -v 0.070216 0.071806 0.245762 -vn 0.810308 0.000191 -0.586005 -v 0.069656 0.069499 0.245762 -vn 0.943585 0.169261 -0.284603 -v 0.069777 0.068633 0.245843 -vn 0.797267 0.146840 -0.585494 -v 0.069732 0.068625 0.245762 -vn 0.765760 0.069198 -0.639393 -v 0.069679 0.069021 0.245762 -vn 0.921877 0.335541 0.193791 -v 0.070005 0.067794 0.245935 -vn 0.898940 0.333077 -0.284546 -v 0.070002 0.067793 0.245843 -vn 0.756967 0.289200 -0.585973 -v 0.069960 0.067778 0.245762 -vn 0.743829 0.205288 -0.636062 -v 0.069860 0.068081 0.245762 -vn 0.849613 0.490519 0.193773 -v 0.070373 0.067007 0.245935 -vn 0.826315 0.486150 -0.284362 -v 0.070369 0.067005 0.245843 -vn 0.691984 0.421227 -0.586282 -v 0.070330 0.066982 0.245762 -vn 0.700547 0.337925 -0.628522 -v 0.070216 0.067193 0.245762 -vn 0.751523 0.630603 0.193787 -v 0.070871 0.066295 0.245935 -vn 0.635364 0.464381 -0.616979 -v 0.070733 0.066388 0.245762 -vn 0.226279 0.764301 -0.603856 -v 0.073043 0.064742 0.245762 -vn 0.306389 0.749838 -0.586404 -v 0.072968 0.064769 0.245762 -vn 0.404292 0.699882 -0.588824 -v 0.072173 0.065140 0.245762 -vn 0.496157 0.640464 -0.586204 -v 0.071454 0.065643 0.245762 -vn 0.548981 0.580904 -0.600974 -v 0.071393 0.065695 0.245762 -vn 0.604361 0.540418 -0.585403 -v 0.070834 0.066264 0.245762 -vn -0.000000 0.981047 0.193772 -v 0.074690 0.064514 0.245935 -vn 0.022023 0.808620 -0.587918 -v 0.074690 0.064465 0.245762 -vn -0.322889 0.697367 -0.639861 -v 0.076781 0.064920 0.245762 -vn -0.264248 0.763668 -0.589053 -v 0.076411 0.064769 0.245762 -vn -0.319395 0.905218 -0.280298 -v 0.076396 0.064811 0.245843 -vn -0.335537 0.921885 0.193757 -v 0.076395 0.064815 0.245935 -vn -0.197719 0.721565 -0.663514 -v 0.075876 0.064607 0.245762 -vn -0.123472 0.798788 -0.588807 -v 0.075564 0.064542 0.245762 -vn -0.063613 0.760975 -0.645655 -v 0.074929 0.064471 0.245762 -vn -0.405301 0.701671 -0.585994 -v 0.077206 0.065140 0.245762 -vn -0.618371 0.732535 -0.284622 -v 0.077896 0.065678 0.245843 -vn -0.525542 0.616587 -0.586196 -v 0.077925 0.065643 0.245762 -vn -0.442299 0.628509 -0.639803 -v 0.077609 0.065399 0.245762 -vn -0.751526 0.630608 0.193757 -v 0.078508 0.066295 0.245935 -vn -0.737930 0.611971 -0.284518 -v 0.078511 0.066292 0.245843 -vn -0.629066 0.511392 -0.585452 -v 0.078546 0.066264 0.245762 -vn -0.550183 0.541105 -0.636006 -v 0.078333 0.066025 0.245762 -vn -0.849613 0.490521 0.193772 -v 0.079007 0.067007 0.245935 -vn -0.834185 0.472536 -0.284334 -v 0.079010 0.067005 0.245843 -vn -0.711096 0.388479 -0.586026 -v 0.079049 0.066982 0.245762 -vn -0.642907 0.437883 -0.628434 -v 0.078924 0.066778 0.245762 -vn -0.921885 0.335538 0.193758 -v 0.079374 0.067794 0.245935 -vn -0.719649 0.318533 -0.616962 -v 0.079363 0.067628 0.245762 -vn -0.802742 -0.109411 -0.586204 -v 0.079647 0.070373 0.245762 -vn -0.808972 0.000572 -0.587846 -v 0.079723 0.069499 0.245762 -vn -0.803391 0.109195 -0.585355 -v 0.079647 0.068625 0.245762 -vn -0.777434 0.184038 -0.601436 -v 0.079632 0.068546 0.245762 -vn -0.769433 0.253325 -0.586344 -v 0.079420 0.067778 0.245762 -vn -0.554665 -0.600536 -0.575937 -v 0.080609 0.075619 0.241954 -vn -0.629452 -0.578162 -0.519152 -v 0.080852 0.075375 0.241954 -vn -0.642080 -0.505855 -0.576059 -v 0.081372 0.074776 0.241954 -vn -0.706665 -0.475908 -0.523580 -v 0.081852 0.074102 0.241954 -vn -0.098034 -0.811649 -0.575861 -v 0.075542 0.077970 0.241954 -vn -0.163851 -0.800746 -0.576159 -v 0.076663 0.077781 0.241954 -vn -0.221537 -0.790484 -0.571013 -v 0.076697 0.077773 0.241954 -vn -0.280382 -0.768042 -0.575758 -v 0.077750 0.077444 0.241954 -vn -0.361595 -0.782373 -0.507091 -v 0.078227 0.077244 0.241954 -vn -0.400598 -0.712315 -0.576306 -v 0.078781 0.076966 0.241954 -vn -0.460935 -0.694522 -0.552429 -v 0.079628 0.076435 0.241954 -vn -0.503368 -0.643638 -0.576499 -v 0.079740 0.076354 0.241954 -vn 0.341865 -0.742414 -0.576151 -v 0.071106 0.077222 0.241954 -vn 0.296978 -0.795493 -0.528199 -v 0.071905 0.077545 0.241954 -vn 0.222354 -0.786430 -0.576269 -v 0.072167 0.077631 0.241954 -vn 0.157842 -0.801877 -0.576263 -v 0.073273 0.077895 0.241954 -vn 0.091077 -0.843829 -0.528827 -v 0.073478 0.077927 0.241954 -vn 0.036039 -0.817277 -0.575118 -v 0.074405 0.078008 0.241954 -vn -0.032138 -0.859529 -0.510076 -v 0.075095 0.078004 0.241954 -vn 0.454987 -0.678960 -0.576195 -v 0.070108 0.076676 0.241954 -vn 0.416507 -0.748771 -0.515620 -v 0.070433 0.076873 0.241954 -vn 0.740541 -0.345583 -0.576344 -v 0.067091 0.073339 0.241954 -vn 0.719760 -0.404892 -0.563922 -v 0.067122 0.073401 0.241954 -vn 0.681592 -0.452003 -0.575435 -v 0.067670 0.074318 0.241954 -vn 0.677167 -0.534050 -0.506196 -v 0.067997 0.074762 0.241954 -vn 0.598906 -0.556268 -0.576089 -v 0.068375 0.075210 0.241954 -vn 0.564420 -0.607628 -0.558765 -v 0.069114 0.075934 0.241954 -vn 0.508436 -0.639751 -0.576378 -v 0.069193 0.076001 0.241954 -vn 0.816746 -0.033374 -0.576032 -v 0.066195 0.070068 0.241954 -vn 0.848014 -0.109782 -0.518479 -v 0.066214 0.070308 0.241954 -vn 0.803541 -0.156054 -0.574430 -v 0.066346 0.071195 0.241954 -vn 0.826930 -0.231132 -0.512606 -v 0.066520 0.071898 0.241954 -vn 0.766322 -0.284326 -0.576116 -v 0.066647 0.072292 0.241954 -vn 0.680820 0.452551 -0.575919 -v 0.067670 0.064681 0.241954 -vn 0.719623 0.403383 -0.565177 -v 0.067122 0.065598 0.241954 -vn 0.740539 0.345606 -0.576331 -v 0.067091 0.065659 0.241954 -vn 0.766355 0.284392 -0.576039 -v 0.066647 0.066706 0.241954 -vn 0.826912 0.230902 -0.512738 -v 0.066520 0.067100 0.241954 -vn 0.801583 0.158871 -0.576389 -v 0.066346 0.067803 0.241954 -vn 0.839202 0.102505 -0.534072 -v 0.066214 0.068690 0.241954 -vn 0.816393 0.033713 -0.576512 -v 0.066195 0.068930 0.241954 -vn 0.454984 0.678953 -0.576206 -v 0.070108 0.062323 0.241954 -vn 0.508451 0.639743 -0.576374 -v 0.069193 0.062997 0.241954 -vn 0.567254 0.607082 -0.556485 -v 0.069114 0.063065 0.241954 -vn 0.597932 0.557526 -0.575883 -v 0.068375 0.063788 0.241954 -vn 0.677076 0.534063 -0.506305 -v 0.067997 0.064236 0.241954 -vn 0.222359 0.786439 -0.576256 -v 0.072167 0.061367 0.241954 -vn 0.296979 0.795492 -0.528201 -v 0.071905 0.061453 0.241954 -vn 0.341865 0.742414 -0.576150 -v 0.071106 0.061776 0.241954 -vn 0.416509 0.748766 -0.515625 -v 0.070433 0.062126 0.241954 -vn -0.098037 0.811648 -0.575861 -v 0.075542 0.061028 0.241954 -vn -0.032230 0.859607 -0.509938 -v 0.075095 0.060995 0.241954 -vn 0.033187 0.816717 -0.576083 -v 0.074405 0.060990 0.241954 -vn 0.095495 0.836635 -0.539372 -v 0.073478 0.061072 0.241954 -vn 0.157836 0.801847 -0.576307 -v 0.073273 0.061104 0.241954 -vn -0.554652 0.600529 -0.575957 -v 0.080609 0.063379 0.241954 -vn -0.503762 0.643690 -0.576096 -v 0.079740 0.062645 0.241954 -vn -0.460208 0.699142 -0.547183 -v 0.079628 0.062564 0.241954 -vn -0.402561 0.712196 -0.575083 -v 0.078781 0.062033 0.241954 -vn -0.361423 0.782482 -0.507045 -v 0.078227 0.061754 0.241954 -vn -0.280658 0.767596 -0.576218 -v 0.077750 0.061554 0.241954 -vn -0.220798 0.790087 -0.571849 -v 0.076697 0.061225 0.241954 -vn -0.164055 0.800486 -0.576462 -v 0.076663 0.061217 0.241954 -vn -0.786437 0.222997 -0.576011 -v 0.082901 0.067250 0.241954 -vn -0.787492 0.287121 -0.545360 -v 0.082594 0.066335 0.241954 -vn -0.743069 0.340159 -0.576316 -v 0.082528 0.066175 0.241954 -vn -0.713115 0.399402 -0.576147 -v 0.082015 0.065160 0.241954 -vn -0.706425 0.476038 -0.523786 -v 0.081852 0.064896 0.241954 -vn -0.641921 0.505597 -0.576462 -v 0.081372 0.064222 0.241954 -vn -0.629461 0.578028 -0.519290 -v 0.080852 0.063624 0.241954 -vn -0.713070 -0.399408 -0.576198 -v 0.082015 0.073838 0.241954 -vn -0.743076 -0.340165 -0.576304 -v 0.082528 0.072823 0.241954 -vn -0.793336 -0.285054 -0.537924 -v 0.082594 0.072664 0.241954 -vn -0.786615 -0.225344 -0.574854 -v 0.082901 0.071749 0.241954 -vn -0.844485 -0.169219 -0.508144 -v 0.083050 0.071110 0.241954 -vn -0.812024 -0.093313 -0.576116 -v 0.083128 0.070634 0.241954 -vn -0.817492 0.000380 -0.575939 -v 0.083204 0.069499 0.241954 -vn -0.811703 0.092921 -0.576632 -v 0.083128 0.068364 0.241954 -vn -0.844467 0.169178 -0.508187 -v 0.083050 0.067888 0.241954 -vn -0.445637 0.712393 0.542129 -v 0.078946 0.062127 0.241682 -vn -0.370009 0.721933 0.584728 -v 0.078781 0.062034 0.241682 -vn -0.459344 0.854717 0.241788 -v 0.078803 0.061992 0.241769 -vn 0.312309 0.755078 0.576472 -v 0.071153 0.061756 0.241682 -vn 0.364589 0.724706 0.584701 -v 0.071106 0.061777 0.241682 -vn 0.411748 0.878057 0.243885 -v 0.071086 0.061734 0.241769 -vn 0.515295 0.821815 0.243087 -v 0.070084 0.062284 0.241769 -vn 0.812810 -0.125771 0.568790 -v 0.066331 0.071110 0.241682 -vn 0.789763 -0.185800 0.584597 -v 0.066348 0.071195 0.241682 -vn 0.949540 -0.198801 0.242596 -v 0.066301 0.071204 0.241769 -vn 0.919027 -0.310507 0.242848 -v 0.066603 0.072307 0.241769 -vn 0.069828 -0.825328 0.560319 -v 0.074285 0.078002 0.241682 -vn 0.003154 -0.811334 0.584574 -v 0.074405 0.078007 0.241682 -vn 0.025578 -0.969937 0.242010 -v 0.074404 0.078054 0.241769 -vn -0.791419 -0.263887 0.551380 -v 0.082858 0.071897 0.241682 -vn -0.788282 -0.191882 0.584630 -v 0.082900 0.071748 0.241682 -vn -0.937815 -0.249067 0.241802 -v 0.082946 0.071761 0.241769 -vn -0.841296 0.488182 -0.232164 -v 0.082055 0.065136 0.241867 -vn -0.892290 0.387548 -0.231572 -v 0.082571 0.066157 0.241867 -vn -0.894487 0.374983 0.243478 -v 0.082570 0.066157 0.241769 -vn -0.105063 0.966750 -0.233146 -v 0.075547 0.060982 0.241867 -vn -0.222360 0.946274 -0.234778 -v 0.076674 0.061172 0.241867 -vn -0.225623 0.943305 0.243454 -v 0.076674 0.061172 0.241769 -vn 0.916019 0.326603 -0.232892 -v 0.066603 0.066691 0.241867 -vn 0.870410 0.433777 -0.232861 -v 0.067049 0.065638 0.241867 -vn 0.864949 0.438867 0.243431 -v 0.067050 0.065638 0.241769 -vn 0.530307 -0.815266 -0.232626 -v 0.070083 0.076715 0.241867 -vn 0.622682 -0.747292 -0.231996 -v 0.069163 0.076036 0.241867 -vn 0.628029 -0.739133 0.243437 -v 0.069163 0.076036 0.241769 -vn -0.342787 -0.909879 -0.233703 -v 0.077766 0.077488 0.241867 -vn -0.222668 -0.946168 -0.234914 -v 0.076674 0.077827 0.241867 -vn -0.225622 -0.943309 0.243439 -v 0.076674 0.077826 0.241769 -vn -0.971128 0.000000 -0.238560 -v 0.083250 0.069499 0.241867 -vn -0.964663 -0.122210 -0.233430 -v 0.083174 0.070640 0.241867 -vn -0.960351 -0.137808 0.242354 -v 0.083173 0.070640 0.241769 -vn -0.936878 0.260369 -0.233384 -v 0.082946 0.067237 0.241867 -vn -0.763375 0.602317 -0.233396 -v 0.081408 0.064194 0.241867 -vn -0.669994 0.705052 -0.232401 -v 0.080641 0.063346 0.241867 -vn -0.582876 0.778796 -0.231802 -v 0.079768 0.062607 0.241867 -vn -0.472494 0.849570 -0.234478 -v 0.078804 0.061992 0.241867 -vn 0.035297 0.971740 -0.233401 -v 0.074404 0.060943 0.241867 -vn 0.170411 0.957757 -0.231649 -v 0.073266 0.061058 0.241867 -vn 0.279762 0.931627 -0.231958 -v 0.072153 0.061323 0.241867 -vn 0.716690 0.656882 -0.234226 -v 0.068341 0.063757 0.241867 -vn 0.953297 0.191715 -0.233388 -v 0.066301 0.067794 0.241867 -vn 0.971145 0.056156 -0.231782 -v 0.066148 0.068927 0.241867 -vn 0.971086 -0.056771 -0.231882 -v 0.066148 0.070071 0.241867 -vn 0.805386 -0.544632 -0.233945 -v 0.067632 0.074344 0.241867 -vn 0.408216 -0.882542 -0.233407 -v 0.071086 0.077264 0.241867 -vn 0.279759 -0.931625 -0.231971 -v 0.072153 0.077675 0.241867 -vn 0.169788 -0.957847 -0.231737 -v 0.073266 0.077940 0.241867 -vn 0.037788 -0.971258 -0.235011 -v 0.074404 0.078055 0.241867 -vn -0.471157 -0.850615 -0.233380 -v 0.078804 0.077006 0.241867 -vn -0.583392 -0.778455 -0.231648 -v 0.079768 0.076391 0.241867 -vn -0.669997 -0.705048 -0.232406 -v 0.080641 0.075653 0.241867 -vn -0.936001 -0.262302 -0.234736 -v 0.082946 0.071761 0.241867 -vn -0.892515 -0.386958 -0.231689 -v 0.082571 0.072841 0.241867 -vn -0.841295 -0.488184 -0.232162 -v 0.082055 0.073862 0.241867 -vn -0.763378 -0.602319 -0.233379 -v 0.081408 0.074805 0.241867 -vn -0.105064 -0.966753 -0.233129 -v 0.075547 0.078017 0.241867 -vn 0.717689 -0.656087 -0.233393 -v 0.068341 0.075241 0.241867 -vn 0.870146 -0.434204 -0.233052 -v 0.067049 0.073360 0.241867 -vn 0.916019 -0.326607 -0.232890 -v 0.066603 0.072307 0.241867 -vn 0.953419 -0.188768 -0.235284 -v 0.066301 0.071204 0.241867 -vn 0.805018 0.545400 -0.233421 -v 0.067632 0.064654 0.241867 -vn 0.623112 0.746888 -0.232144 -v 0.069163 0.062962 0.241867 -vn 0.530307 0.815263 -0.232638 -v 0.070083 0.062283 0.241867 -vn 0.408217 0.882546 -0.233390 -v 0.071086 0.061734 0.241867 -vn -0.343210 0.909797 -0.233402 -v 0.077766 0.061511 0.241867 -vn -0.830901 -0.500326 0.243469 -v 0.082055 0.073861 0.241769 -vn -0.894932 -0.373135 0.244676 -v 0.082570 0.072841 0.241769 -vn -0.458808 -0.855034 0.241684 -v 0.078803 0.077006 0.241769 -vn -0.572764 -0.782729 0.243468 -v 0.079767 0.076391 0.241769 -vn -0.356831 -0.902243 0.242133 -v 0.077766 0.077487 0.241769 -vn -0.310172 -0.749666 0.584632 -v 0.077749 0.077443 0.241682 -vn -0.257804 -0.804499 0.535088 -v 0.077474 0.077544 0.241682 -vn 0.412152 -0.877919 0.243697 -v 0.071086 0.077264 0.241769 -vn 0.293363 -0.924480 0.243464 -v 0.072153 0.077675 0.241769 -vn 0.515293 -0.821813 0.243100 -v 0.070084 0.076714 0.241769 -vn 0.422497 -0.692756 0.584453 -v 0.070109 0.076674 0.241682 -vn 0.503884 -0.688392 0.521744 -v 0.069752 0.076433 0.241682 -vn 0.863085 -0.441400 0.245461 -v 0.067050 0.073360 0.241769 -vn 0.795280 -0.555844 0.242007 -v 0.067632 0.074344 0.241769 -vn 0.949471 0.199350 0.242412 -v 0.066301 0.067794 0.241769 -vn 0.967353 0.070299 0.243487 -v 0.066149 0.068927 0.241769 -vn 0.919027 0.310509 0.242846 -v 0.066603 0.066691 0.241769 -vn 0.772105 0.249683 0.584391 -v 0.066648 0.066707 0.241682 -vn 0.786623 0.328151 0.523012 -v 0.066787 0.066335 0.241682 -vn 0.629795 0.737049 0.245188 -v 0.069163 0.062962 0.241769 -vn 0.725056 0.644814 0.241886 -v 0.068341 0.063757 0.241769 -vn 0.024979 0.969995 0.241837 -v 0.074404 0.060944 0.241769 -vn 0.156637 0.957180 0.243458 -v 0.073266 0.061058 0.241769 -vn -0.088766 0.966057 0.242601 -v 0.075546 0.060982 0.241769 -vn -0.063079 0.809016 0.584392 -v 0.075542 0.061029 0.241682 -vn -0.135528 0.839379 0.526380 -v 0.075901 0.061073 0.241682 -vn -0.759706 0.601717 0.246544 -v 0.081408 0.064194 0.241769 -vn -0.679713 0.691933 0.243349 -v 0.080641 0.063346 0.241769 -vn -0.960352 0.137806 0.242349 -v 0.083173 0.068358 0.241769 -vn -0.938010 0.248474 0.241655 -v 0.082946 0.067238 0.241769 -vn -0.964664 0.122209 -0.233426 -v 0.083174 0.068358 0.241867 -vn -0.969909 0.000001 0.243467 -v 0.083250 0.069499 0.241769 -vn -0.801283 -0.126855 0.584683 -v 0.083126 0.070634 0.241682 -vn -0.845208 -0.063693 0.530629 -v 0.083164 0.070308 0.241682 -vn -0.751597 -0.307840 0.583383 -v 0.082527 0.072822 0.241682 -vn -0.763364 -0.387832 0.516586 -v 0.082256 0.073400 0.241682 -vn -0.690419 -0.426177 0.584547 -v 0.082014 0.073837 0.241682 -vn -0.759618 -0.601875 0.246430 -v 0.081408 0.074804 0.241769 -vn -0.619814 -0.523224 0.584865 -v 0.081370 0.074775 0.241682 -vn -0.655617 -0.480171 0.582753 -v 0.081381 0.074761 0.241682 -vn -0.679712 -0.691935 0.243344 -v 0.080641 0.075652 0.241769 -vn -0.575413 -0.572023 0.584542 -v 0.080608 0.075618 0.241682 -vn -0.554354 -0.651268 0.518209 -v 0.080264 0.075933 0.241682 -vn -0.370010 -0.721933 0.584727 -v 0.078781 0.076964 0.241682 -vn -0.438816 -0.709749 0.551088 -v 0.078946 0.076871 0.241682 -vn -0.476101 -0.657008 0.584525 -v 0.079739 0.076352 0.241682 -vn -0.189789 -0.788632 0.584842 -v 0.076663 0.077780 0.241682 -vn -0.088772 -0.966059 0.242590 -v 0.075546 0.078016 0.241769 -vn -0.063407 -0.808676 0.584827 -v 0.075542 0.077969 0.241682 -vn -0.135220 -0.839077 0.526939 -v 0.075901 0.077925 0.241682 -vn 0.155158 -0.957181 0.244397 -v 0.073266 0.077940 0.241769 -vn 0.123996 -0.802518 0.583601 -v 0.073274 0.077893 0.241682 -vn 0.199529 -0.833201 0.515717 -v 0.072683 0.077772 0.241682 -vn 0.364466 -0.724686 0.584803 -v 0.071106 0.077221 0.241682 -vn 0.312976 -0.754166 0.577304 -v 0.071153 0.077243 0.241682 -vn 0.252906 -0.770904 0.584590 -v 0.072168 0.077630 0.241682 -vn 0.525892 -0.616204 0.586285 -v 0.069194 0.076000 0.241682 -vn 0.725488 -0.644369 0.241777 -v 0.068341 0.075241 0.241769 -vn 0.615966 -0.527690 0.584917 -v 0.068376 0.075209 0.241682 -vn 0.590206 -0.595192 0.545347 -v 0.068529 0.075374 0.241682 -vn 0.656639 -0.476211 0.584849 -v 0.067671 0.074317 0.241682 -vn 0.772109 -0.249688 0.584383 -v 0.066648 0.072292 0.241682 -vn 0.786491 -0.328223 0.523164 -v 0.066787 0.072663 0.241682 -vn 0.721699 -0.372496 0.583435 -v 0.067092 0.073338 0.241682 -vn 0.731975 -0.436498 0.523147 -v 0.067528 0.074101 0.241682 -vn 0.967108 -0.071327 0.244161 -v 0.066149 0.070071 0.241769 -vn 0.809069 -0.066680 0.583919 -v 0.066196 0.070068 0.241682 -vn 0.856860 0.000094 0.515549 -v 0.066177 0.069499 0.241682 -vn 0.789609 0.185549 0.584883 -v 0.066348 0.067804 0.241682 -vn 0.810980 0.127264 0.571065 -v 0.066331 0.067888 0.241682 -vn 0.808564 0.065556 0.584745 -v 0.066196 0.068931 0.241682 -vn 0.722619 0.368964 0.584540 -v 0.067092 0.065660 0.241682 -vn 0.794953 0.556353 0.241913 -v 0.067632 0.064655 0.241769 -vn 0.656640 0.476225 0.584836 -v 0.067671 0.064681 0.241682 -vn 0.719511 0.436858 0.539870 -v 0.067528 0.064897 0.241682 -vn 0.615962 0.527697 0.584917 -v 0.068376 0.063789 0.241682 -vn 0.422500 0.692764 0.584442 -v 0.070109 0.062324 0.241682 -vn 0.503400 0.689853 0.520280 -v 0.069752 0.062565 0.241682 -vn 0.530476 0.615295 0.583102 -v 0.069194 0.062998 0.241682 -vn 0.592099 0.604745 0.532638 -v 0.068529 0.063625 0.241682 -vn 0.293930 0.924194 0.243867 -v 0.072153 0.061323 0.241769 -vn 0.253613 0.770897 0.584293 -v 0.072168 0.061369 0.241682 -vn 0.199233 0.833051 0.516074 -v 0.072683 0.061226 0.241682 -vn 0.003166 0.811334 0.584574 -v 0.074405 0.060991 0.241682 -vn 0.067291 0.822934 0.564138 -v 0.074285 0.060996 0.241682 -vn 0.125440 0.801302 0.584962 -v 0.073274 0.061105 0.241682 -vn -0.189775 0.788848 0.584555 -v 0.076663 0.061218 0.241682 -vn -0.356832 0.902242 0.242136 -v 0.077766 0.061511 0.241769 -vn -0.310119 0.749654 0.584675 -v 0.077749 0.061555 0.241682 -vn -0.258027 0.804522 0.534945 -v 0.077474 0.061455 0.241682 -vn -0.570703 0.783782 0.244916 -v 0.079767 0.062608 0.241769 -vn -0.474672 0.659162 0.583260 -v 0.079739 0.062646 0.241682 -vn -0.554362 0.651274 0.518194 -v 0.080264 0.063066 0.241682 -vn -0.763200 0.387236 0.517276 -v 0.082256 0.065598 0.241682 -vn -0.690058 0.426429 0.584789 -v 0.082014 0.065161 0.241682 -vn -0.830764 0.500490 0.243599 -v 0.082055 0.065137 0.241769 -vn -0.655786 0.479812 0.582860 -v 0.081381 0.064237 0.241682 -vn -0.619734 0.523309 0.584874 -v 0.081370 0.064223 0.241682 -vn -0.575423 0.572033 0.584523 -v 0.080608 0.063380 0.241682 -vn -0.749455 0.309422 0.585300 -v 0.082527 0.066176 0.241682 -vn -0.788532 0.259515 0.557556 -v 0.082858 0.067101 0.241682 -vn -0.811274 -0.000000 0.584667 -v 0.083202 0.069499 0.241682 -vn -0.845353 0.063540 0.530416 -v 0.083164 0.068690 0.241682 -vn -0.801412 0.127039 0.584466 -v 0.083126 0.068364 0.241682 -vn -0.788282 0.191882 0.584630 -v 0.082900 0.067250 0.241682 -vn 0.712627 -0.263330 0.650246 -v 0.069870 0.071429 0.238124 -vn 0.716656 -0.346008 0.605544 -v 0.069959 0.071638 0.238124 -vn 0.668255 -0.392852 0.631745 -v 0.070322 0.072306 0.238124 -vn 0.642637 -0.468480 0.606254 -v 0.070388 0.072406 0.238124 -vn 0.597149 -0.524206 0.607142 -v 0.070932 0.073082 0.238124 -vn 0.552499 -0.574543 0.603859 -v 0.070942 0.073091 0.238124 -vn 0.497595 -0.621291 0.605307 -v 0.071603 0.073673 0.238124 -vn 0.421970 -0.652198 0.629745 -v 0.071678 0.073728 0.238124 -vn 0.378642 -0.698324 0.607431 -v 0.072352 0.074135 0.238124 -vn -0.035911 -0.794541 0.606148 -v 0.074910 0.074686 0.238124 -vn 0.033041 -0.747053 0.663943 -v 0.074443 0.074685 0.238124 -vn 0.106798 -0.787996 0.606347 -v 0.074030 0.074649 0.238124 -vn 0.164669 -0.733837 0.659066 -v 0.073466 0.074544 0.238124 -vn 0.249589 -0.753583 0.608127 -v 0.073169 0.074463 0.238124 -vn 0.285652 -0.695837 0.658949 -v 0.072533 0.074221 0.238124 -vn -0.598982 -0.523022 0.606357 -v 0.078729 0.072761 0.238124 -vn -0.548718 -0.575527 0.606364 -v 0.078120 0.073396 0.238124 -vn -0.490675 -0.617975 0.614285 -v 0.078089 0.073423 0.238124 -vn -0.438685 -0.662995 0.606624 -v 0.077412 0.073920 0.238124 -vn -0.360419 -0.680955 0.637494 -v 0.077285 0.073995 0.238124 -vn -0.313342 -0.730896 0.606307 -v 0.076625 0.074316 0.238124 -vn -0.229868 -0.721089 0.653599 -v 0.076388 0.074405 0.238124 -vn -0.177416 -0.775583 0.605801 -v 0.075783 0.074574 0.238124 -vn -0.098985 -0.743006 0.661925 -v 0.075428 0.074638 0.238124 -vn -0.779354 -0.147014 0.609093 -v 0.079806 0.070376 0.238124 -vn -0.710624 -0.184294 0.679005 -v 0.079671 0.070962 0.238124 -vn -0.741825 -0.282356 0.608252 -v 0.079585 0.071229 0.238124 -vn -0.687169 -0.319896 0.652277 -v 0.079304 0.071878 0.238124 -vn -0.681025 -0.409605 0.606984 -v 0.079222 0.072031 0.238124 -vn -0.636804 -0.455826 0.621855 -v 0.078770 0.072708 0.238124 -vn -0.728411 0.198240 0.655834 -v 0.079671 0.068037 0.238124 -vn -0.782326 0.142425 0.606367 -v 0.079806 0.068622 0.238124 -vn -0.745404 0.065694 0.663368 -v 0.079858 0.069006 0.238124 -vn -0.795413 0.000000 0.606068 -v 0.079881 0.069499 0.238124 -vn -0.745532 -0.065854 0.663208 -v 0.079858 0.069993 0.238124 -vn -0.315352 0.728833 0.607746 -v 0.076625 0.064682 0.238124 -vn -0.353832 0.677628 0.644689 -v 0.077285 0.065003 0.238124 -vn -0.438671 0.663004 0.606625 -v 0.077412 0.065078 0.238124 -vn -0.490665 0.617960 0.614307 -v 0.078089 0.065576 0.238124 -vn -0.548706 0.575516 0.606386 -v 0.078120 0.065602 0.238124 -vn -0.598979 0.523022 0.606360 -v 0.078729 0.066238 0.238124 -vn -0.637382 0.457958 0.619692 -v 0.078770 0.066290 0.238124 -vn -0.682368 0.409179 0.605761 -v 0.079222 0.066967 0.238124 -vn -0.693160 0.327974 0.641843 -v 0.079304 0.067120 0.238124 -vn -0.745318 0.279933 0.605094 -v 0.079585 0.067770 0.238124 -vn 0.033559 0.747459 0.663460 -v 0.074443 0.064313 0.238124 -vn -0.035644 0.794351 0.606413 -v 0.074910 0.064312 0.238124 -vn -0.098972 0.742539 0.662450 -v 0.075428 0.064360 0.238124 -vn -0.181451 0.772204 0.608915 -v 0.075783 0.064424 0.238124 -vn -0.217989 0.707132 0.672641 -v 0.076388 0.064593 0.238124 -vn 0.642620 0.468492 0.606263 -v 0.070388 0.066592 0.238124 -vn 0.597218 0.522686 0.608382 -v 0.070932 0.065917 0.238124 -vn 0.551046 0.573267 0.606394 -v 0.070942 0.065907 0.238124 -vn 0.496156 0.621200 0.606581 -v 0.071603 0.065325 0.238124 -vn 0.425568 0.652961 0.626525 -v 0.071678 0.065270 0.238124 -vn 0.377462 0.699766 0.606506 -v 0.072352 0.064863 0.238124 -vn 0.295176 0.703598 0.646391 -v 0.072533 0.064777 0.238124 -vn 0.246606 0.756298 0.605969 -v 0.073169 0.064535 0.238124 -vn 0.164468 0.734189 0.658723 -v 0.073466 0.064454 0.238124 -vn 0.106683 0.788701 0.605450 -v 0.074030 0.064350 0.238124 -vn 0.763569 0.215440 0.608727 -v 0.069666 0.068191 0.238124 -vn 0.701922 0.251907 0.666220 -v 0.069870 0.067570 0.238124 -vn 0.714226 0.347235 0.607709 -v 0.069959 0.067361 0.238124 -vn 0.665820 0.387960 0.637315 -v 0.070322 0.066692 0.238124 -vn 0.766362 -0.211906 0.606453 -v 0.069666 0.070807 0.238124 -vn 0.739000 -0.131549 0.660737 -v 0.069592 0.070482 0.238124 -vn 0.792108 -0.071666 0.606159 -v 0.069517 0.069939 0.238124 -vn 0.747579 0.000128 0.664173 -v 0.069498 0.069499 0.238124 -vn 0.792401 0.071803 0.605760 -v 0.069517 0.069059 0.238124 -vn 0.739291 0.131423 0.660436 -v 0.069592 0.068517 0.238124 -vn -0.515155 0.469269 -0.717219 -v 0.078680 0.066150 0.237834 -vn -0.477484 0.532117 -0.699185 -v 0.078132 0.065588 0.237834 -vn -0.590382 0.661340 -0.462685 -v 0.078098 0.065626 0.237897 -vn -0.397344 0.533731 -0.746491 -v 0.077801 0.065320 0.237834 -vn -0.361059 0.623142 -0.693780 -v 0.077421 0.065063 0.237834 -vn -0.458692 0.759487 -0.461283 -v 0.077395 0.065106 0.237897 -vn -0.099028 0.674470 -0.731631 -v 0.075594 0.064369 0.237834 -vn -0.027108 0.722697 -0.690633 -v 0.074911 0.064294 0.237834 -vn -0.040491 0.885592 -0.462696 -v 0.074909 0.064344 0.237897 -vn 0.603239 0.360203 -0.711587 -v 0.070337 0.066636 0.237834 -vn 0.671222 0.305020 -0.675592 -v 0.069942 0.067353 0.237834 -vn 0.804786 0.371855 -0.462648 -v 0.069988 0.067374 0.237897 -vn 0.627285 0.229063 -0.744341 -v 0.069794 0.067717 0.237834 -vn 0.737608 0.164623 -0.654854 -v 0.069648 0.068186 0.237834 -vn 0.860568 0.216742 -0.460919 -v 0.069697 0.068199 0.237897 -vn 0.675045 -0.099101 -0.731091 -v 0.069515 0.070104 0.237834 -vn 0.703328 -0.176479 -0.688611 -v 0.069648 0.070812 0.237834 -vn 0.858914 -0.219497 -0.462697 -v 0.069697 0.070799 0.237897 -vn 0.624456 -0.224503 -0.748100 -v 0.069794 0.071281 0.237834 -vn 0.652101 -0.306349 -0.693480 -v 0.069942 0.071645 0.237834 -vn 0.804608 -0.373143 -0.461920 -v 0.069988 0.071624 0.237897 -vn 0.450288 -0.497988 -0.741113 -v 0.071115 0.073289 0.237834 -vn 0.429078 -0.579731 -0.692679 -v 0.071592 0.073688 0.237834 -vn 0.524208 -0.716959 -0.459538 -v 0.071622 0.073647 0.237897 -vn -0.092514 -0.662158 -0.743631 -v 0.075594 0.074630 0.237834 -vn -0.167632 -0.691363 -0.702793 -v 0.075787 0.074592 0.237834 -vn -0.196064 -0.864032 -0.463690 -v 0.075777 0.074543 0.237897 -vn -0.296352 -0.622704 -0.724165 -v 0.076753 0.074283 0.237834 -vn -0.364157 -0.618695 -0.696137 -v 0.077421 0.073935 0.237834 -vn -0.460421 -0.757571 -0.462708 -v 0.077395 0.073892 0.237897 -vn -0.396284 -0.532361 -0.748031 -v 0.077801 0.073678 0.237834 -vn -0.477568 -0.528219 -0.702078 -v 0.078132 0.073410 0.237834 -vn -0.592132 -0.660499 -0.461650 -v 0.078098 0.073372 0.237897 -vn -0.612567 -0.286109 -0.736820 -v 0.079345 0.071837 0.237834 -vn -0.670876 -0.242782 -0.700701 -v 0.079602 0.071235 0.237834 -vn -0.835298 -0.296957 -0.462703 -v 0.079554 0.071218 0.237897 -vn 0.646338 0.606399 -0.463171 -v 0.070965 0.065929 0.237897 -vn 0.720513 0.690555 -0.063203 -v 0.070980 0.065944 0.237975 -vn 0.593446 0.802390 -0.063186 -v 0.071634 0.065368 0.237975 -vn -0.210258 -0.975603 -0.063176 -v 0.075772 0.074522 0.237975 -vn -0.042357 -0.997102 -0.063200 -v 0.074908 0.074633 0.237975 -vn 0.676641 0.651284 0.343491 -v 0.070972 0.065936 0.238055 -vn 0.564763 0.747803 0.349046 -v 0.071628 0.065359 0.238055 -vn -0.201855 -0.914555 0.350492 -v 0.075775 0.074533 0.238055 -vn -0.040693 -0.935658 0.350554 -v 0.074908 0.074644 0.238055 -vn -0.623742 0.700499 0.346767 -v 0.078092 0.065634 0.238055 -vn -0.499031 0.792898 0.349686 -v 0.077390 0.065114 0.238055 -vn -0.040694 0.935672 0.350516 -v 0.074908 0.064354 0.238055 -vn 0.771109 0.532331 0.349307 -v 0.070423 0.066616 0.238055 -vn 0.933015 0.081304 0.350533 -v 0.069559 0.069062 0.238055 -vn 0.933017 -0.081303 0.350528 -v 0.069559 0.069936 0.238055 -vn 0.904952 -0.241352 0.350443 -v 0.069706 0.070797 0.238055 -vn 0.849900 -0.393697 0.350247 -v 0.069997 0.071620 0.238055 -vn 0.770589 -0.532965 0.349487 -v 0.070423 0.072383 0.238055 -vn -0.356614 -0.866077 0.350340 -v 0.076610 0.074277 0.238055 -vn -0.499701 -0.792415 0.349825 -v 0.077390 0.073884 0.238055 -vn -0.724876 -0.594438 0.348134 -v 0.078696 0.072734 0.238055 -vn -0.922756 -0.167720 0.346976 -v 0.079765 0.070369 0.238055 -vn -0.936548 -0.000002 0.350540 -v 0.079839 0.069499 0.238055 -vn -0.880501 -0.321744 0.348135 -v 0.079545 0.071215 0.238055 -vn -0.813013 -0.465998 0.349078 -v 0.079185 0.072010 0.238055 -vn 0.121755 -0.928603 0.350531 -v 0.074036 0.074607 0.238055 -vn 0.284508 -0.893303 0.347943 -v 0.073182 0.074423 0.238055 -vn 0.431177 -0.832068 0.348926 -v 0.072371 0.074097 0.238055 -vn 0.564170 -0.748342 0.348850 -v 0.071628 0.073639 0.238055 -vn 0.849725 0.395484 0.348655 -v 0.069997 0.067378 0.238055 -vn 0.429953 0.832169 0.350193 -v 0.072371 0.064901 0.238055 -vn 0.280362 0.893647 0.350418 -v 0.073182 0.064575 0.238055 -vn 0.121756 0.928618 0.350492 -v 0.074036 0.064391 0.238055 -vn -0.358966 0.865878 0.348422 -v 0.076610 0.064721 0.238055 -vn -0.812990 0.465325 0.350029 -v 0.079185 0.066988 0.238055 -vn -0.880677 0.318805 0.350387 -v 0.079545 0.067784 0.238055 -vn -0.922458 0.161972 0.350479 -v 0.079765 0.068629 0.238055 -vn -0.983646 -0.168663 -0.063195 -v 0.079754 0.070367 0.237975 -vn -0.998001 -0.000000 -0.063193 -v 0.079828 0.069499 0.237975 -vn 0.126764 -0.989919 -0.063179 -v 0.074037 0.074596 0.237975 -vn 0.292240 -0.954255 -0.063191 -v 0.073185 0.074412 0.237975 -vn 0.449303 -0.891141 -0.063204 -v 0.072376 0.074087 0.237975 -vn 0.593445 -0.802391 -0.063186 -v 0.071634 0.073630 0.237975 -vn 0.449306 0.891140 -0.063203 -v 0.072376 0.064911 0.237975 -vn 0.292238 0.954256 -0.063191 -v 0.073185 0.064586 0.237975 -vn 0.126759 0.989919 -0.063179 -v 0.074037 0.064403 0.237975 -vn -0.983647 0.168659 -0.063195 -v 0.079754 0.068631 0.237975 -vn -0.940993 0.332473 -0.063196 -v 0.079534 0.067787 0.237975 -vn -0.871271 0.486721 -0.063164 -v 0.079175 0.066993 0.237975 -vn -0.875365 -0.140505 -0.462595 -v 0.079775 0.070371 0.237897 -vn -0.889602 0.000000 -0.456737 -v 0.079849 0.069499 0.237897 -vn -0.623738 -0.700501 0.346771 -v 0.078092 0.073365 0.238055 -vn -0.776481 -0.626965 -0.063177 -v 0.078687 0.072727 0.237975 -vn -0.659354 -0.749173 -0.063184 -v 0.078084 0.073356 0.237975 -vn -0.694423 -0.550242 -0.463693 -v 0.078704 0.072740 0.237897 -vn -0.044226 -0.886499 -0.460612 -v 0.074909 0.074654 0.237897 -vn 0.121603 -0.878361 -0.462271 -v 0.074034 0.074617 0.237897 -vn 0.260494 -0.850607 -0.456739 -v 0.073179 0.074432 0.237897 -vn 0.390857 -0.795590 -0.462890 -v 0.072367 0.074106 0.237897 -vn 0.826853 -0.558856 -0.063194 -v 0.070433 0.072376 0.237975 -vn 0.909406 -0.411082 -0.063190 -v 0.070008 0.071616 0.237975 -vn 0.730704 -0.501734 -0.462963 -v 0.070415 0.072388 0.237897 -vn 0.904782 0.246047 0.347606 -v 0.069706 0.068202 0.238055 -vn 0.994407 0.084635 -0.063186 -v 0.069570 0.069063 0.237975 -vn 0.965799 0.251474 -0.063193 -v 0.069717 0.068204 0.237975 -vn 0.883471 0.065675 -0.463859 -v 0.069549 0.069062 0.237897 -vn 0.532373 0.710673 -0.459916 -v 0.071622 0.065351 0.237897 -vn 0.390272 0.795849 -0.462938 -v 0.072367 0.064892 0.237897 -vn 0.260492 0.850608 -0.456738 -v 0.073179 0.064566 0.237897 -vn 0.121597 0.878366 -0.462263 -v 0.074034 0.064382 0.237897 -vn -0.372114 0.926034 -0.063181 -v 0.076605 0.064732 0.237975 -vn -0.523259 0.849828 -0.063178 -v 0.077384 0.065124 0.237975 -vn -0.321907 0.825348 -0.463871 -v 0.076613 0.064712 0.237897 -vn -0.875361 0.140507 -0.462603 -v 0.079775 0.068627 0.237897 -vn -0.835064 0.301423 -0.460231 -v 0.079554 0.067780 0.237897 -vn -0.768873 0.440502 -0.463457 -v 0.079194 0.066983 0.237897 -vn -0.940993 -0.332476 -0.063180 -v 0.079534 0.071211 0.237975 -vn -0.647314 -0.163246 -0.744537 -v 0.079759 0.070701 0.237834 -vn -0.612707 -0.369126 -0.698811 -v 0.079238 0.072040 0.237834 -vn -0.768489 -0.441097 -0.463528 -v 0.079194 0.072015 0.237897 -vn -0.871270 -0.486721 -0.063186 -v 0.079175 0.072005 0.237975 -vn -0.567540 -0.428121 -0.703285 -v 0.078743 0.072772 0.237834 -vn -0.510919 -0.467625 -0.721310 -v 0.078680 0.072848 0.237834 -vn -0.523259 -0.849826 -0.063217 -v 0.077384 0.073874 0.237975 -vn -0.244260 -0.677289 -0.693986 -v 0.076632 0.074333 0.237834 -vn -0.321174 -0.825548 -0.464024 -v 0.076613 0.074286 0.237897 -vn -0.372113 -0.926035 -0.063182 -v 0.076605 0.074267 0.237975 -vn -0.033584 -0.715391 -0.697917 -v 0.074911 0.074704 0.237834 -vn 0.030171 -0.664501 -0.746678 -v 0.074387 0.074700 0.237834 -vn 0.109757 -0.712836 -0.692689 -v 0.074028 0.074667 0.237834 -vn 0.209820 -0.675415 -0.706959 -v 0.073164 0.074480 0.237834 -vn 0.308992 -0.644439 -0.699444 -v 0.072344 0.074151 0.237834 -vn 0.337977 -0.551055 -0.762962 -v 0.072085 0.074011 0.237834 -vn 0.533380 -0.485214 -0.692873 -v 0.070928 0.073104 0.237834 -vn 0.646777 -0.605889 -0.463226 -v 0.070965 0.073069 0.237897 -vn 0.720513 -0.690555 -0.063203 -v 0.070980 0.073054 0.237975 -vn 0.676642 -0.651282 0.343491 -v 0.070972 0.073062 0.238055 -vn 0.576230 -0.416829 -0.703003 -v 0.070373 0.072416 0.237834 -vn 0.598380 -0.360548 -0.715504 -v 0.070337 0.072362 0.237834 -vn 0.965801 -0.251472 -0.063178 -v 0.069717 0.070794 0.237975 -vn 0.714027 -0.038575 -0.699055 -v 0.069499 0.069941 0.237834 -vn 0.883476 -0.064927 -0.463956 -v 0.069549 0.069937 0.237897 -vn 0.994407 -0.084638 -0.063179 -v 0.069570 0.069935 0.237975 -vn 0.726536 0.028983 -0.686517 -v 0.069499 0.069057 0.237834 -vn 0.667197 0.105620 -0.737355 -v 0.069515 0.068894 0.237834 -vn 0.909408 0.411077 -0.063188 -v 0.070008 0.067383 0.237975 -vn 0.575179 0.418870 -0.702650 -v 0.070373 0.066582 0.237834 -vn 0.730252 0.502223 -0.463146 -v 0.070415 0.066610 0.237897 -vn 0.826854 0.558856 -0.063191 -v 0.070433 0.066622 0.237975 -vn 0.557533 0.487412 -0.672002 -v 0.070928 0.065894 0.237834 -vn 0.028772 0.667146 -0.744371 -v 0.074387 0.064298 0.237834 -vn 0.122885 0.724953 -0.677748 -v 0.074028 0.064332 0.237834 -vn 0.212781 0.677851 -0.703735 -v 0.073164 0.064518 0.237834 -vn 0.316830 0.650486 -0.690280 -v 0.072344 0.064847 0.237834 -vn 0.344273 0.577225 -0.740464 -v 0.072085 0.064987 0.237834 -vn 0.451415 0.580089 -0.678028 -v 0.071592 0.065311 0.237834 -vn 0.431621 0.493293 -0.755225 -v 0.071115 0.065710 0.237834 -vn -0.042355 0.997102 -0.063201 -v 0.074908 0.064366 0.237975 -vn -0.168086 0.695621 -0.698468 -v 0.075787 0.064406 0.237834 -vn -0.196773 0.863843 -0.463742 -v 0.075777 0.064456 0.237897 -vn -0.210255 0.975600 -0.063221 -v 0.075772 0.064476 0.237975 -vn -0.207091 0.914594 0.347319 -v 0.075775 0.064465 0.238055 -vn -0.239688 0.686597 -0.686392 -v 0.076632 0.064665 0.237834 -vn -0.299612 0.616777 -0.727886 -v 0.076753 0.064715 0.237834 -vn -0.659351 0.749176 -0.063186 -v 0.078084 0.065642 0.237975 -vn -0.569172 0.428366 -0.701816 -v 0.078743 0.066226 0.237834 -vn -0.694828 0.549616 -0.463828 -v 0.078704 0.066258 0.237897 -vn -0.776481 0.626966 -0.063177 -v 0.078687 0.066271 0.237975 -vn -0.724355 0.594949 0.348347 -v 0.078696 0.066264 0.238055 -vn -0.613220 0.372346 -0.696649 -v 0.079238 0.066958 0.237834 -vn -0.704927 -0.102671 -0.701810 -v 0.079824 0.070380 0.237834 -vn -0.711975 0.000330 -0.702205 -v 0.079899 0.069499 0.237834 -vn -0.705237 0.102688 -0.701496 -v 0.079824 0.068619 0.237834 -vn -0.647710 0.163677 -0.744098 -v 0.079759 0.068298 0.237834 -vn -0.668319 0.246192 -0.701954 -v 0.079602 0.067764 0.237834 -vn -0.603270 0.275016 -0.748620 -v 0.079345 0.067161 0.237834 -vn -0.298204 -0.672093 -0.677765 -v 0.076850 0.074423 0.237694 -vn -0.196065 -0.699067 -0.687651 -v 0.076010 0.074712 0.237694 -vn -0.124198 -0.736451 -0.664992 -v 0.075623 0.074794 0.237694 -vn -0.053892 -0.727399 -0.684096 -v 0.075134 0.074858 0.237694 -vn 0.018060 -0.740640 -0.671659 -v 0.074377 0.074867 0.237694 -vn 0.081642 -0.728512 -0.680151 -v 0.074246 0.074858 0.237694 -vn 0.156584 -0.705654 -0.691038 -v 0.073370 0.074712 0.237694 -vn 0.749475 0.063516 -0.658979 -v 0.069349 0.068875 0.237694 -vn 0.701724 0.015308 -0.712284 -v 0.069313 0.069499 0.237694 -vn 0.741204 -0.074079 -0.667180 -v 0.069349 0.070123 0.237694 -vn 0.713606 -0.137515 -0.686918 -v 0.069386 0.070384 0.237694 -vn 0.699498 -0.215945 -0.681227 -v 0.069604 0.071245 0.237694 -vn 0.685865 -0.275721 -0.673474 -v 0.069637 0.071338 0.237694 -vn 0.640987 -0.336987 -0.689619 -v 0.069961 0.072058 0.237694 -vn 0.625445 -0.408496 -0.664793 -v 0.070197 0.072454 0.237694 -vn 0.561874 -0.452917 -0.692217 -v 0.070446 0.072802 0.237694 -vn 0.522232 -0.519665 -0.676182 -v 0.071000 0.073410 0.237694 -vn 0.476271 -0.554910 -0.682086 -v 0.071048 0.073455 0.237694 -vn 0.411838 -0.602255 -0.683870 -v 0.071749 0.074001 0.237694 -vn 0.361849 -0.663835 -0.654514 -v 0.072001 0.074156 0.237694 -vn 0.290304 -0.664613 -0.688486 -v 0.072530 0.074423 0.237694 -vn 0.228536 -0.706030 -0.670294 -v 0.073147 0.074650 0.237694 -vn 0.697265 0.145768 -0.701836 -v 0.069386 0.068614 0.237694 -vn 0.685731 0.214953 -0.695390 -v 0.069604 0.067753 0.237694 -vn 0.681126 0.270937 -0.680191 -v 0.069637 0.067660 0.237694 -vn 0.625923 0.345617 -0.699121 -v 0.069961 0.066940 0.237694 -vn 0.651058 0.404618 -0.642190 -v 0.070197 0.066544 0.237694 -vn 0.541071 0.451768 -0.709329 -v 0.070446 0.066196 0.237694 -vn 0.525335 0.516806 -0.675970 -v 0.071000 0.065588 0.237694 -vn 0.470215 0.555576 -0.685735 -v 0.071048 0.065543 0.237694 -vn 0.404154 0.597271 -0.692768 -v 0.071749 0.064998 0.237694 -vn 0.363165 0.647169 -0.670286 -v 0.072001 0.064842 0.237694 -vn 0.274422 0.662410 -0.697069 -v 0.072530 0.064575 0.237694 -vn 0.239169 0.707824 -0.664667 -v 0.073147 0.064348 0.237694 -vn 0.145678 0.696966 -0.702151 -v 0.073370 0.064287 0.237694 -vn 0.080796 0.723192 -0.685904 -v 0.074246 0.064140 0.237694 -vn 0.020895 0.735493 -0.677210 -v 0.074377 0.064131 0.237694 -vn -0.065036 0.724199 -0.686517 -v 0.075134 0.064140 0.237694 -vn -0.114304 0.754663 -0.646079 -v 0.075623 0.064204 0.237694 -vn -0.199535 0.691535 -0.694237 -v 0.076010 0.064287 0.237694 -vn -0.297237 0.670266 -0.679995 -v 0.076850 0.064575 0.237694 -vn -0.387301 0.618542 -0.683670 -v 0.077631 0.064998 0.237694 -vn -0.450963 0.591757 -0.668174 -v 0.077901 0.065186 0.237694 -vn -0.502625 0.527647 -0.684804 -v 0.078331 0.065543 0.237694 -vn -0.552923 0.498629 -0.667567 -v 0.078809 0.066043 0.237694 -vn -0.589331 0.424520 -0.687365 -v 0.078933 0.066196 0.237694 -vn -0.632030 0.368482 -0.681733 -v 0.079419 0.066940 0.237694 -vn -0.669322 0.311913 -0.674328 -v 0.079495 0.067086 0.237694 -vn -0.694444 0.237093 -0.679364 -v 0.079775 0.067753 0.237694 -vn -0.735921 0.193189 -0.648921 -v 0.079922 0.068259 0.237694 -vn -0.723478 0.101567 -0.682835 -v 0.079993 0.068614 0.237694 -vn -0.731977 0.000280 -0.681329 -v 0.080067 0.069499 0.237694 -vn -0.723748 -0.101711 -0.682528 -v 0.079993 0.070384 0.237694 -vn -0.723823 -0.179052 -0.666349 -v 0.079922 0.070739 0.237694 -vn -0.690590 -0.245268 -0.680389 -v 0.079775 0.071245 0.237694 -vn -0.674811 -0.310064 -0.669694 -v 0.079495 0.071912 0.237694 -vn -0.633556 -0.368275 -0.680426 -v 0.079419 0.072058 0.237694 -vn -0.589637 -0.427481 -0.685265 -v 0.078933 0.072802 0.237694 -vn -0.554048 -0.491515 -0.671896 -v 0.078809 0.072955 0.237694 -vn -0.497323 -0.536501 -0.681790 -v 0.078331 0.073455 0.237694 -vn -0.467416 -0.597348 -0.651688 -v 0.077901 0.073812 0.237694 -vn -0.387971 -0.620984 -0.681071 -v 0.077631 0.074001 0.237694 -vn -0.918250 -0.147065 -0.367681 -v 0.080134 0.070408 0.237499 -vn -0.877470 -0.306351 -0.369047 -v 0.079911 0.071291 0.237499 -vn -0.815952 -0.445772 -0.368115 -v 0.079544 0.072126 0.237499 -vn -0.737384 -0.566882 -0.367300 -v 0.079046 0.072890 0.237499 -vn -0.626936 -0.685236 -0.370678 -v 0.078428 0.073560 0.237499 -vn -0.504629 -0.781014 -0.367923 -v 0.077709 0.074120 0.237499 -vn -0.372750 -0.849779 -0.372738 -v 0.076907 0.074554 0.237499 -vn -0.234007 -0.899936 -0.367908 -v 0.076045 0.074850 0.237499 -vn -0.071610 -0.926772 -0.368735 -v 0.075145 0.075000 0.237499 -vn 0.079922 -0.926179 -0.368517 -v 0.074234 0.075000 0.237499 -vn 0.222619 -0.903106 -0.367206 -v 0.073335 0.074850 0.237499 -vn 0.376137 -0.849335 -0.370338 -v 0.072472 0.074554 0.237499 -vn 0.512531 -0.775907 -0.367804 -v 0.071670 0.074120 0.237499 -vn 0.627455 -0.685358 -0.369575 -v 0.070951 0.073560 0.237499 -vn 0.731011 -0.574967 -0.367471 -v 0.070334 0.072890 0.237499 -vn 0.820188 -0.437651 -0.368446 -v 0.069835 0.072126 0.237499 -vn 0.879829 -0.299389 -0.369143 -v 0.069469 0.071291 0.237499 -vn 0.916423 -0.159099 -0.367227 -v 0.069245 0.070408 0.237499 -vn 0.929019 0.003704 -0.370014 -v 0.069170 0.069499 0.237499 -vn 0.916479 0.157587 -0.367739 -v 0.069245 0.068591 0.237499 -vn 0.880379 0.298448 -0.368595 -v 0.069469 0.067707 0.237499 -vn 0.815766 0.443136 -0.371695 -v 0.069835 0.066872 0.237499 -vn 0.730872 0.574484 -0.368503 -v 0.070334 0.066109 0.237499 -vn 0.627925 0.684685 -0.370023 -v 0.070951 0.065438 0.237499 -vn 0.513872 0.775248 -0.367323 -v 0.071670 0.064878 0.237499 -vn 0.369479 0.852540 -0.369677 -v 0.072472 0.064444 0.237499 -vn 0.224016 0.902535 -0.367760 -v 0.073335 0.064148 0.237499 -vn 0.081194 0.926299 -0.367937 -v 0.074234 0.063998 0.237499 -vn -0.078602 0.925157 -0.371358 -v 0.075145 0.063998 0.237499 -vn -0.232673 0.900126 -0.368289 -v 0.076045 0.064148 0.237499 -vn -0.372748 0.849779 -0.372739 -v 0.076907 0.064444 0.237499 -vn -0.503503 0.781949 -0.367478 -v 0.077709 0.064878 0.237499 -vn -0.632681 0.680655 -0.369357 -v 0.078428 0.065438 0.237499 -vn -0.736317 0.567897 -0.367872 -v 0.079046 0.066109 0.237499 -vn -0.815494 0.447097 -0.367524 -v 0.079544 0.066872 0.237499 -vn -0.879086 0.299258 -0.371016 -v 0.079911 0.067707 0.237499 -vn -0.917868 0.148424 -0.368088 -v 0.080134 0.068591 0.237499 -vn -0.927935 0.000001 -0.372743 -v 0.080210 0.069499 0.237499 -vn -0.981294 0.163749 0.101232 -v 0.080168 0.068585 0.237259 -vn -0.940960 0.323031 0.101224 -v 0.079943 0.067696 0.237259 -vn -0.874955 0.473503 0.101235 -v 0.079574 0.066856 0.237259 -vn -0.785087 0.611058 0.101225 -v 0.079073 0.066088 0.237259 -vn -0.673802 0.731945 0.101232 -v 0.078451 0.065413 0.237259 -vn -0.544137 0.832867 0.101230 -v 0.077728 0.064849 0.237259 -vn -0.399634 0.911068 0.101228 -v 0.076921 0.064413 0.237259 -vn -0.244225 0.964420 0.101230 -v 0.076053 0.064115 0.237259 -vn -0.082153 0.991465 0.101231 -v 0.075148 0.063964 0.237259 -vn 0.082154 0.991465 0.101231 -v 0.074231 0.063964 0.237259 -vn 0.244226 0.964421 0.101227 -v 0.073326 0.064115 0.237259 -vn 0.399633 0.911069 0.101229 -v 0.072458 0.064413 0.237259 -vn 0.544138 0.832866 0.101231 -v 0.071652 0.064849 0.237259 -vn 0.673803 0.731942 0.101240 -v 0.070928 0.065413 0.237259 -vn 0.785086 0.611058 0.101236 -v 0.070307 0.066088 0.237259 -vn 0.874956 0.473504 0.101225 -v 0.069805 0.066856 0.237259 -vn 0.940959 0.323030 0.101235 -v 0.069436 0.067696 0.237259 -vn 0.981294 0.163752 0.101231 -v 0.069211 0.068585 0.237259 -vn 0.994863 0.000000 0.101230 -v 0.069135 0.069499 0.237259 -vn 0.981294 -0.163751 0.101232 -v 0.069211 0.070413 0.237259 -vn 0.940958 -0.323032 0.101232 -v 0.069436 0.071303 0.237259 -vn 0.874956 -0.473503 0.101225 -v 0.069805 0.072143 0.237259 -vn 0.785086 -0.611057 0.101236 -v 0.070307 0.072911 0.237259 -vn 0.673802 -0.731944 0.101239 -v 0.070928 0.073586 0.237259 -vn 0.544140 -0.832865 0.101231 -v 0.071652 0.074149 0.237259 -vn 0.399629 -0.911069 0.101240 -v 0.072458 0.074586 0.237259 -vn 0.244226 -0.964420 0.101229 -v 0.073326 0.074883 0.237259 -vn 0.082153 -0.991464 0.101246 -v 0.074231 0.075034 0.237259 -vn -0.082155 -0.991464 0.101245 -v 0.075148 0.075034 0.237259 -vn -0.244222 -0.964421 0.101231 -v 0.076053 0.074883 0.237259 -vn -0.399632 -0.911068 0.101239 -v 0.076921 0.074586 0.237259 -vn -0.544137 -0.832867 0.101229 -v 0.077728 0.074149 0.237259 -vn -0.673802 -0.731945 0.101231 -v 0.078451 0.073586 0.237259 -vn -0.785087 -0.611058 0.101226 -v 0.079073 0.072911 0.237259 -vn -0.874956 -0.473502 0.101234 -v 0.079574 0.072143 0.237259 -vn -0.940959 -0.323034 0.101219 -v 0.079943 0.071303 0.237259 -vn -0.981295 -0.163747 0.101231 -v 0.080168 0.070413 0.237259 -vn -0.994863 -0.000000 0.101230 -v 0.080244 0.069499 0.237259 -vn -0.822313 0.137220 0.552243 -v 0.080087 0.068598 0.237031 -vn -0.788516 0.270697 0.552238 -v 0.079865 0.067722 0.237031 -vn -0.733204 0.396791 0.552240 -v 0.079502 0.066895 0.237031 -vn -0.657894 0.512059 0.552242 -v 0.079008 0.066138 0.237031 -vn -0.564642 0.613365 0.552234 -v 0.078396 0.065473 0.237031 -vn -0.455983 0.697937 0.552235 -v 0.077682 0.064918 0.237031 -vn -0.334894 0.763473 0.552227 -v 0.076888 0.064488 0.237031 -vn -0.204656 0.808174 0.552242 -v 0.076033 0.064195 0.237031 -vn -0.068845 0.830841 0.552236 -v 0.075141 0.064046 0.237031 -vn 0.068844 0.830841 0.552235 -v 0.074238 0.064046 0.237031 -vn 0.204659 0.808172 0.552243 -v 0.073346 0.064195 0.237031 -vn 0.334890 0.763472 0.552231 -v 0.072492 0.064488 0.237031 -vn 0.455986 0.697936 0.552235 -v 0.071697 0.064918 0.237031 -vn 0.564642 0.613364 0.552235 -v 0.070984 0.065473 0.237031 -vn 0.657896 0.512063 0.552236 -v 0.070372 0.066138 0.237031 -vn 0.733207 0.396792 0.552235 -v 0.069877 0.066895 0.237031 -vn 0.788520 0.270699 0.552231 -v 0.069514 0.067722 0.237031 -vn 0.822317 0.137222 0.552236 -v 0.069292 0.068598 0.237031 -vn 0.833685 -0.000001 0.552241 -v 0.069218 0.069499 0.237031 -vn 0.822318 -0.137221 0.552235 -v 0.069292 0.070400 0.237031 -vn 0.788519 -0.270698 0.552232 -v 0.069514 0.071276 0.237031 -vn 0.733206 -0.396791 0.552237 -v 0.069877 0.072103 0.237031 -vn 0.657897 -0.512064 0.552235 -v 0.070372 0.072860 0.237031 -vn 0.564638 -0.613361 0.552244 -v 0.070984 0.073525 0.237031 -vn 0.455985 -0.697933 0.552238 -v 0.071697 0.074080 0.237031 -vn 0.334888 -0.763467 0.552240 -v 0.072492 0.074510 0.237031 -vn 0.204659 -0.808177 0.552236 -v 0.073346 0.074804 0.237031 -vn 0.068844 -0.830841 0.552235 -v 0.074238 0.074952 0.237031 -vn -0.068844 -0.830842 0.552234 -v 0.075141 0.074952 0.237031 -vn -0.204658 -0.808178 0.552234 -v 0.076033 0.074804 0.237031 -vn -0.334889 -0.763468 0.552238 -v 0.076888 0.074510 0.237031 -vn -0.455983 -0.697935 0.552238 -v 0.077682 0.074080 0.237031 -vn -0.564638 -0.613361 0.552242 -v 0.078396 0.073525 0.237031 -vn -0.657894 -0.512061 0.552240 -v 0.079008 0.072860 0.237031 -vn -0.733203 -0.396790 0.552242 -v 0.079502 0.072103 0.237031 -vn -0.788514 -0.270698 0.552239 -v 0.079865 0.071276 0.237031 -vn -0.822313 -0.137217 0.552243 -v 0.080087 0.070400 0.237031 -vn -0.833689 -0.000001 0.552235 -v 0.080161 0.069499 0.237031 -vn -0.473338 0.078987 0.877333 -v 0.079909 0.068628 0.236869 -vn -0.453884 0.155818 0.877331 -v 0.079695 0.067781 0.236869 -vn -0.422047 0.228401 0.877331 -v 0.079344 0.066980 0.236869 -vn -0.378697 0.294752 0.877331 -v 0.078866 0.066249 0.236869 -vn -0.325018 0.353063 0.877331 -v 0.078274 0.065606 0.236869 -vn -0.262472 0.401743 0.877332 -v 0.077584 0.065069 0.236869 -vn -0.192771 0.439470 0.877328 -v 0.076815 0.064653 0.236869 -vn -0.117802 0.465196 0.877334 -v 0.075989 0.064369 0.236869 -vn -0.039631 0.478252 0.877328 -v 0.075127 0.064225 0.236869 -vn 0.039628 0.478250 0.877329 -v 0.074253 0.064225 0.236869 -vn 0.117804 0.465194 0.877335 -v 0.073391 0.064369 0.236869 -vn 0.192767 0.439470 0.877329 -v 0.072564 0.064653 0.236869 -vn 0.262473 0.401743 0.877332 -v 0.071795 0.065069 0.236869 -vn 0.325019 0.353065 0.877330 -v 0.071105 0.065606 0.236869 -vn 0.378702 0.294758 0.877327 -v 0.070514 0.066249 0.236869 -vn 0.422044 0.228397 0.877334 -v 0.070035 0.066980 0.236869 -vn 0.453892 0.155823 0.877326 -v 0.069684 0.067781 0.236869 -vn 0.473344 0.078986 0.877329 -v 0.069470 0.068628 0.236869 -vn 0.479884 -0.000001 0.877332 -v 0.069398 0.069499 0.236869 -vn 0.473346 -0.078987 0.877328 -v 0.069470 0.070370 0.236869 -vn 0.453889 -0.155819 0.877329 -v 0.069684 0.071217 0.236869 -vn 0.422044 -0.228401 0.877332 -v 0.070035 0.072018 0.236869 -vn 0.378699 -0.294754 0.877330 -v 0.070514 0.072750 0.236869 -vn 0.325019 -0.353064 0.877330 -v 0.071105 0.073393 0.236869 -vn 0.262476 -0.401748 0.877329 -v 0.071795 0.073929 0.236869 -vn 0.192768 -0.439469 0.877330 -v 0.072564 0.074345 0.236869 -vn 0.117803 -0.465201 0.877332 -v 0.073391 0.074629 0.236869 -vn 0.039628 -0.478250 0.877329 -v 0.074253 0.074773 0.236869 -vn -0.039628 -0.478251 0.877329 -v 0.075127 0.074773 0.236869 -vn -0.117806 -0.465203 0.877330 -v 0.075989 0.074629 0.236869 -vn -0.192770 -0.439471 0.877328 -v 0.076815 0.074345 0.236869 -vn -0.262474 -0.401748 0.877329 -v 0.077584 0.073929 0.236869 -vn -0.325017 -0.353063 0.877331 -v 0.078274 0.073393 0.236869 -vn -0.378693 -0.294748 0.877334 -v 0.078866 0.072750 0.236869 -vn -0.422049 -0.228404 0.877329 -v 0.079344 0.072018 0.236869 -vn -0.453881 -0.155816 0.877333 -v 0.079695 0.071217 0.236869 -vn -0.473339 -0.078987 0.877332 -v 0.079909 0.070370 0.236869 -vn -0.479893 -0.000001 0.877327 -v 0.079982 0.069499 0.236869 -vn -0.126597 0.021125 0.991729 -v 0.079678 0.068667 0.236810 -vn -0.121389 0.041673 0.991730 -v 0.079473 0.067857 0.236810 -vn -0.112876 0.061085 0.991730 -v 0.079137 0.067092 0.236810 -vn -0.101282 0.078831 0.991730 -v 0.078680 0.066393 0.236810 -vn -0.086925 0.094426 0.991730 -v 0.078115 0.065779 0.236810 -vn -0.070199 0.107446 0.991730 -v 0.077455 0.065266 0.236810 -vn -0.051555 0.117535 0.991730 -v 0.076721 0.064868 0.236810 -vn -0.031508 0.124419 0.991729 -v 0.075931 0.064597 0.236810 -vn -0.010599 0.127907 0.991729 -v 0.075107 0.064459 0.236810 -vn 0.010599 0.127907 0.991729 -v 0.074272 0.064459 0.236810 -vn 0.031507 0.124420 0.991729 -v 0.073448 0.064597 0.236810 -vn 0.051556 0.117536 0.991729 -v 0.072658 0.064868 0.236810 -vn 0.070199 0.107446 0.991730 -v 0.071924 0.065266 0.236810 -vn 0.086926 0.094427 0.991729 -v 0.071265 0.065779 0.236810 -vn 0.101283 0.078831 0.991730 -v 0.070699 0.066393 0.236810 -vn 0.112878 0.061087 0.991729 -v 0.070242 0.067092 0.236810 -vn 0.121390 0.041673 0.991730 -v 0.069907 0.067857 0.236810 -vn 0.126593 0.021124 0.991730 -v 0.069702 0.068667 0.236810 -vn 0.128345 0.000000 0.991730 -v 0.069633 0.069499 0.236810 -vn 0.126593 -0.021124 0.991730 -v 0.069702 0.070331 0.236810 -vn 0.121390 -0.041673 0.991730 -v 0.069907 0.071141 0.236810 -vn 0.112877 -0.061086 0.991729 -v 0.070242 0.071906 0.236810 -vn 0.101282 -0.078832 0.991730 -v 0.070699 0.072605 0.236810 -vn 0.086927 -0.094427 0.991729 -v 0.071265 0.073220 0.236810 -vn 0.070197 -0.107444 0.991730 -v 0.071924 0.073733 0.236810 -vn 0.051556 -0.117536 0.991729 -v 0.072658 0.074130 0.236810 -vn 0.031506 -0.124416 0.991730 -v 0.073448 0.074401 0.236810 -vn 0.010599 -0.127907 0.991729 -v 0.074272 0.074539 0.236810 -vn -0.010599 -0.127907 0.991729 -v 0.075107 0.074539 0.236810 -vn -0.031507 -0.124416 0.991730 -v 0.075931 0.074401 0.236810 -vn -0.051555 -0.117534 0.991730 -v 0.076721 0.074130 0.236810 -vn -0.070197 -0.107444 0.991730 -v 0.077455 0.073733 0.236810 -vn -0.086925 -0.094426 0.991730 -v 0.078115 0.073220 0.236810 -vn -0.101282 -0.078832 0.991730 -v 0.078680 0.072605 0.236810 -vn -0.112874 -0.061084 0.991730 -v 0.079137 0.071906 0.236810 -vn -0.121390 -0.041673 0.991730 -v 0.079473 0.071141 0.236810 -vn -0.126596 -0.021126 0.991729 -v 0.079678 0.070331 0.236810 -vn -0.128345 0.000000 0.991730 -v 0.079747 0.069499 0.236810 -vn 0.318958 -0.138341 0.937618 -v 0.072888 0.070245 0.236810 -vn 0.348370 -0.008374 0.937320 -v 0.072740 0.069499 0.236810 -vn -0.138421 0.323109 0.936184 -v 0.075436 0.067698 0.236810 -vn -0.004107 0.353502 0.935425 -v 0.074690 0.067549 0.236810 -vn 0.132557 0.329182 0.934916 -v 0.073943 0.067698 0.236810 -vn 0.249732 0.253318 0.934593 -v 0.073311 0.068120 0.236810 -vn 0.241967 -0.250185 0.937475 -v 0.073311 0.070878 0.236810 -vn 0.128049 -0.323770 0.937431 -v 0.073943 0.071301 0.236810 -vn -0.005077 -0.347876 0.937527 -v 0.074690 0.071449 0.236810 -vn -0.136729 -0.319102 0.937806 -v 0.075436 0.071301 0.236810 -vn -0.319425 0.129196 0.938763 -v 0.076491 0.068753 0.236810 -vn -0.249192 0.243787 0.937268 -v 0.076068 0.068120 0.236810 -vn 0.328571 0.137538 0.934411 -v 0.072888 0.068753 0.236810 -vn -0.246603 -0.242349 0.938325 -v 0.076068 0.070878 0.236810 -vn -0.340452 -0.000001 0.940262 -v 0.076640 0.069499 0.236810 -vn -0.317981 -0.130025 0.939139 -v 0.076491 0.070245 0.236810 -vn 0.843141 -0.377022 0.383363 -v 0.073073 0.070169 0.236610 -vn 0.789316 -0.520387 0.325850 -v 0.073274 0.070528 0.236610 -vn 0.626902 -0.677523 0.384651 -v 0.073452 0.070737 0.236610 -vn 0.514809 -0.787083 0.339812 -v 0.073815 0.071015 0.236610 -vn 0.310203 -0.868816 0.385919 -v 0.074020 0.071116 0.236610 -vn 0.158406 -0.922259 0.352628 -v 0.074507 0.071240 0.236610 -vn -0.055983 -0.920303 0.387180 -v 0.074690 0.071249 0.236610 -vn -0.220915 -0.904745 0.364188 -v 0.075230 0.071163 0.236610 -vn -0.412714 -0.823893 0.388418 -v 0.075359 0.071116 0.236610 -vn -0.560860 -0.738437 0.374362 -v 0.075861 0.070800 0.236610 -vn -0.702768 -0.595224 0.389648 -v 0.075927 0.070737 0.236610 -vn -0.805841 -0.451552 0.383043 -v 0.076288 0.070211 0.236610 -vn -0.879589 -0.271187 0.390871 -v 0.076306 0.070169 0.236610 -vn -0.916261 -0.000002 0.400581 -v 0.076440 0.069499 0.236610 -vn -0.879589 0.271190 0.390870 -v 0.076306 0.068829 0.236610 -vn -0.806329 0.448923 0.385098 -v 0.076288 0.068787 0.236610 -vn -0.700815 0.596530 0.391165 -v 0.075927 0.068262 0.236610 -vn -0.563991 0.733274 0.379767 -v 0.075861 0.068199 0.236610 -vn -0.408159 0.824743 0.391415 -v 0.075359 0.067882 0.236610 -vn -0.228876 0.898512 0.374557 -v 0.075230 0.067835 0.236610 -vn -0.049188 0.918812 0.391618 -v 0.074690 0.067749 0.236610 -vn 0.144323 0.917805 0.369870 -v 0.074507 0.067759 0.236610 -vn 0.317713 0.863461 0.391782 -v 0.074020 0.067882 0.236610 -vn 0.494866 0.788104 0.366061 -v 0.073815 0.067984 0.236610 -vn 0.632919 0.667704 0.391899 -v 0.073452 0.068262 0.236610 -vn 0.765820 0.530541 0.363381 -v 0.073274 0.068471 0.236610 -vn 0.845167 0.363401 0.391961 -v 0.073073 0.068829 0.236610 -vn 0.913240 0.186951 0.361997 -v 0.072978 0.069135 0.236610 -vn 0.924006 -0.015513 0.382064 -v 0.072940 0.069499 0.236610 -vn 0.936033 -0.165076 0.310794 -v 0.072978 0.069863 0.236610 -vn -0.879581 -0.271187 -0.390891 -v 0.076306 0.070169 0.235510 -vn -0.916253 0.000003 -0.400600 -v 0.076440 0.069499 0.235510 -vn -0.879583 0.271186 -0.390887 -v 0.076306 0.068829 0.235510 -vn -0.805835 0.451550 -0.383056 -v 0.076288 0.068787 0.235510 -vn -0.702745 0.595238 -0.389669 -v 0.075927 0.068262 0.235510 -vn -0.560840 0.738442 -0.374382 -v 0.075861 0.068199 0.235510 -vn -0.412713 0.823884 -0.388437 -v 0.075359 0.067882 0.235510 -vn -0.220913 0.904739 -0.364205 -v 0.075230 0.067835 0.235510 -vn -0.055963 0.920299 -0.387192 -v 0.074690 0.067749 0.235510 -vn 0.158412 0.922252 -0.352643 -v 0.074507 0.067759 0.235510 -vn 0.310194 0.868810 -0.385938 -v 0.074020 0.067882 0.235510 -vn 0.514806 0.787078 -0.339829 -v 0.073815 0.067984 0.235510 -vn 0.626902 0.677512 -0.384670 -v 0.073452 0.068262 0.235510 -vn 0.789309 0.520382 -0.325874 -v 0.073274 0.068471 0.235510 -vn 0.843135 0.377019 -0.383379 -v 0.073073 0.068829 0.235510 -vn 0.936027 0.165074 -0.310811 -v 0.072978 0.069135 0.235510 -vn 0.923998 0.015514 -0.382083 -v 0.072940 0.069499 0.235510 -vn 0.913233 -0.186950 -0.362015 -v 0.072978 0.069863 0.235510 -vn 0.845159 -0.363396 -0.391982 -v 0.073073 0.070169 0.235510 -vn 0.765812 -0.530541 -0.363399 -v 0.073274 0.070528 0.235510 -vn 0.632908 -0.667704 -0.391917 -v 0.073452 0.070737 0.235510 -vn 0.494863 -0.788098 -0.366078 -v 0.073815 0.071015 0.235510 -vn 0.317716 -0.863452 -0.391799 -v 0.074020 0.071116 0.235510 -vn 0.144314 -0.917798 -0.369892 -v 0.074507 0.071240 0.235510 -vn -0.049206 -0.918801 -0.391643 -v 0.074690 0.071249 0.235510 -vn -0.228875 -0.898503 -0.374577 -v 0.075230 0.071163 0.235510 -vn -0.408151 -0.824738 -0.391432 -v 0.075359 0.071116 0.235510 -vn -0.564002 -0.733256 -0.379785 -v 0.075861 0.070800 0.235510 -vn -0.700828 -0.596505 -0.391180 -v 0.075927 0.070737 0.235510 -vn -0.806321 -0.448920 -0.385120 -v 0.076288 0.070211 0.235510 -vn -0.249184 -0.243776 -0.937273 -v 0.076068 0.070878 0.235310 -vn -0.319406 -0.129191 -0.938770 -v 0.076491 0.070245 0.235310 -vn -0.138415 -0.323096 -0.936189 -v 0.075436 0.071301 0.235310 -vn -0.004109 -0.353480 -0.935433 -v 0.074690 0.071449 0.235310 -vn 0.132554 -0.329168 -0.934921 -v 0.073943 0.071301 0.235310 -vn 0.249720 -0.253309 -0.934599 -v 0.073311 0.070878 0.235310 -vn 0.328554 -0.137531 -0.934418 -v 0.072888 0.070245 0.235310 -vn 0.348354 0.008375 -0.937326 -v 0.072740 0.069499 0.235310 -vn 0.318947 0.138335 -0.937623 -v 0.072888 0.068753 0.235310 -vn 0.241956 0.250172 -0.937482 -v 0.073311 0.068120 0.235310 -vn 0.128041 0.323755 -0.937437 -v 0.073943 0.067698 0.235310 -vn -0.005075 0.347867 -0.937530 -v 0.074690 0.067549 0.235310 -vn -0.136722 0.319087 -0.937811 -v 0.075436 0.067698 0.235310 -vn -0.246590 0.242336 -0.938332 -v 0.076068 0.068120 0.235310 -vn -0.317970 0.130019 -0.939143 -v 0.076491 0.068753 0.235310 -vn -0.340436 0.000002 -0.940268 -v 0.076640 0.069499 0.235310 -vn -0.243570 -0.335246 -0.910101 -v 0.076335 0.071764 0.235310 -vn -0.335240 -0.243568 -0.910104 -v 0.076955 0.071145 0.235310 -vn -0.394097 -0.128050 -0.910105 -v 0.077353 0.070364 0.235310 -vn -0.414375 0.000000 -0.910106 -v 0.077490 0.069499 0.235310 -vn 0.335241 -0.243566 -0.910104 -v 0.072424 0.071145 0.235310 -vn 0.243568 -0.335248 -0.910101 -v 0.073044 0.071764 0.235310 -vn 0.128051 -0.394096 -0.910105 -v 0.073824 0.072162 0.235310 -vn -0.000002 -0.414385 -0.910102 -v 0.074690 0.072299 0.235310 -vn -0.128048 -0.394096 -0.910105 -v 0.075555 0.072162 0.235310 -vn 0.243567 0.335240 -0.910104 -v 0.073044 0.067234 0.235310 -vn 0.335240 0.243567 -0.910104 -v 0.072424 0.067853 0.235310 -vn 0.394105 0.128051 -0.910101 -v 0.072027 0.068634 0.235310 -vn 0.414384 0.000001 -0.910102 -v 0.071890 0.069499 0.235310 -vn 0.394105 -0.128052 -0.910101 -v 0.072027 0.070364 0.235310 -vn -0.394097 0.128050 -0.910105 -v 0.077353 0.068634 0.235310 -vn -0.335240 0.243567 -0.910104 -v 0.076955 0.067853 0.235310 -vn -0.243567 0.335240 -0.910104 -v 0.076335 0.067234 0.235310 -vn -0.128050 0.394097 -0.910105 -v 0.075555 0.066836 0.235310 -vn -0.000001 0.414375 -0.910106 -v 0.074690 0.066699 0.235310 -vn 0.128050 0.394097 -0.910105 -v 0.073824 0.066836 0.235310 -vn -0.883398 0.286835 -0.370585 -v 0.077543 0.068572 0.235110 -vn -0.751365 0.545694 -0.371037 -v 0.077117 0.067736 0.235110 -vn -0.545851 0.751053 -0.371438 -v 0.076453 0.067072 0.235110 -vn -0.286984 0.882845 -0.371787 -v 0.075617 0.066646 0.235110 -vn -0.000103 0.928199 -0.372083 -v 0.074690 0.066499 0.235110 -vn 0.286722 0.882704 -0.372322 -v 0.073763 0.066646 0.235110 -vn 0.545433 0.750827 -0.372507 -v 0.072926 0.067072 0.235110 -vn 0.750726 0.545482 -0.372640 -v 0.072263 0.067736 0.235110 -vn 0.882523 0.286768 -0.372716 -v 0.071836 0.068572 0.235110 -vn 0.927934 0.000001 -0.372744 -v 0.071690 0.069499 0.235110 -vn 0.882523 -0.286768 -0.372716 -v 0.071836 0.070426 0.235110 -vn 0.750725 -0.545483 -0.372640 -v 0.072263 0.071262 0.235110 -vn 0.545432 -0.750831 -0.372502 -v 0.072926 0.071926 0.235110 -vn 0.286723 -0.882704 -0.372321 -v 0.073763 0.072352 0.235110 -vn -0.000104 -0.928202 -0.372076 -v 0.074690 0.072499 0.235110 -vn -0.286983 -0.882845 -0.371786 -v 0.075617 0.072352 0.235110 -vn -0.545852 -0.751055 -0.371432 -v 0.076453 0.071926 0.235110 -vn -0.751364 -0.545696 -0.371037 -v 0.077117 0.071262 0.235110 -vn -0.883398 -0.286835 -0.370585 -v 0.077543 0.070426 0.235110 -vn -0.928900 0.000000 -0.370330 -v 0.077690 0.069499 0.235110 -vn -0.897605 0.207323 -0.389002 -v 0.077556 0.068615 0.229510 -vn -0.855529 0.347710 -0.383624 -v 0.077543 0.068572 0.229510 -vn -0.793981 0.467762 -0.388320 -v 0.077168 0.067809 0.229510 -vn -0.710555 0.593700 -0.377667 -v 0.077117 0.067736 0.229510 -vn -0.616782 0.685077 -0.387621 -v 0.076560 0.067154 0.229510 -vn -0.497247 0.784405 -0.370747 -v 0.076453 0.067072 0.229510 -vn -0.382400 0.839087 -0.386914 -v 0.075786 0.066707 0.229510 -vn -0.235570 0.901528 -0.362980 -v 0.075617 0.066646 0.229510 -vn -0.112447 0.915533 -0.386207 -v 0.074914 0.066508 0.229510 -vn 0.050001 0.933727 -0.354476 -v 0.074690 0.066499 0.229510 -vn 0.168091 0.907275 -0.385482 -v 0.074022 0.066574 0.229510 -vn 0.332609 0.877579 -0.345291 -v 0.073763 0.066646 0.229510 -vn 0.433254 0.815015 -0.384761 -v 0.073190 0.066901 0.229510 -vn 0.585565 0.737925 -0.335529 -v 0.072926 0.067072 0.229510 -vn 0.658481 0.647243 -0.384030 -v 0.072490 0.067459 0.229510 -vn 0.784865 0.527480 -0.325196 -v 0.072263 0.067736 0.229510 -vn 0.822901 0.419433 -0.383288 -v 0.071987 0.068197 0.229510 -vn 0.911372 0.265682 -0.314347 -v 0.071836 0.068572 0.229510 -vn 0.911241 0.152640 -0.382546 -v 0.071723 0.069052 0.229510 -vn 0.952709 -0.023118 -0.303003 -v 0.071690 0.069499 0.229510 -vn 0.915276 -0.128468 -0.381792 -v 0.071723 0.069946 0.229510 -vn 0.890270 -0.280577 -0.358743 -v 0.071836 0.070426 0.229510 -vn 0.825109 -0.408998 -0.389763 -v 0.071987 0.070801 0.229510 -vn 0.764335 -0.534982 -0.359981 -v 0.072263 0.071262 0.229510 -vn 0.663064 -0.639106 -0.389730 -v 0.072490 0.071540 0.229510 -vn 0.567539 -0.739491 -0.362013 -v 0.072926 0.071926 0.229510 -vn 0.439106 -0.809529 -0.389678 -v 0.073190 0.072097 0.229510 -vn 0.318252 -0.875021 -0.364766 -v 0.073763 0.072352 0.229510 -vn 0.174120 -0.904369 -0.389613 -v 0.074022 0.072424 0.229510 -vn 0.039738 -0.928916 -0.368153 -v 0.074690 0.072499 0.229510 -vn -0.107141 -0.914762 -0.389527 -v 0.074914 0.072491 0.229510 -vn -0.241976 -0.896125 -0.372031 -v 0.075617 0.072352 0.229510 -vn -0.378426 -0.839730 -0.389419 -v 0.075786 0.072292 0.229510 -vn -0.500523 -0.779692 -0.376241 -v 0.076453 0.071926 0.229510 -vn -0.614378 -0.686283 -0.389301 -v 0.076560 0.071845 0.229510 -vn -0.711715 -0.590454 -0.380561 -v 0.077117 0.071262 0.229510 -vn -0.793015 -0.468701 -0.389163 -v 0.077168 0.071189 0.229510 -vn -0.855652 -0.346158 -0.384751 -v 0.077543 0.070426 0.229510 -vn -0.897610 -0.207301 -0.389001 -v 0.077556 0.070383 0.229510 -vn -0.918181 0.000001 -0.396162 -v 0.077690 0.069499 0.229510 -vn -0.296774 -0.198276 -0.934137 -v 0.077334 0.071302 0.229310 -vn -0.338863 -0.102112 -0.935278 -v 0.077747 0.070442 0.229310 -vn -0.227055 -0.278246 -0.933287 -v 0.076685 0.072001 0.229310 -vn -0.135812 -0.334192 -0.932669 -v 0.075859 0.072478 0.229310 -vn -0.031288 -0.360514 -0.932229 -v 0.074929 0.072690 0.229310 -vn 0.076914 -0.354420 -0.931918 -v 0.073978 0.072619 0.229310 -vn 0.178787 -0.316180 -0.931700 -v 0.073090 0.072270 0.229310 -vn 0.264862 -0.249100 -0.931556 -v 0.072344 0.071676 0.229310 -vn 0.327134 -0.159224 -0.931467 -v 0.071807 0.070888 0.229310 -vn 0.354155 -0.045847 -0.934062 -v 0.071525 0.069976 0.229310 -vn 0.351968 0.058966 -0.934153 -v 0.071525 0.069022 0.229310 -vn 0.319225 0.160495 -0.933990 -v 0.071807 0.068111 0.229310 -vn 0.257893 0.247772 -0.933863 -v 0.072344 0.067323 0.229310 -vn 0.173537 0.312958 -0.933778 -v 0.073090 0.066728 0.229310 -vn 0.073801 0.350230 -0.933752 -v 0.073978 0.066379 0.229310 -vn -0.032279 0.356306 -0.933812 -v 0.074929 0.066308 0.229310 -vn -0.135095 0.330815 -0.933976 -v 0.075859 0.066520 0.229310 -vn -0.225374 0.276244 -0.934289 -v 0.076685 0.066997 0.229310 -vn -0.295053 0.197774 -0.934788 -v 0.077334 0.067696 0.229310 -vn -0.338033 0.102762 -0.935507 -v 0.077747 0.068556 0.229310 -vn -0.350740 0.000001 -0.936473 -v 0.077890 0.069499 0.229310 -vn 0.284761 0.284762 -0.915326 -v 0.080205 0.075015 0.229310 -vn 0.334846 0.223738 -0.915325 -v 0.081175 0.073833 0.229310 -vn 0.372058 0.154112 -0.915326 -v 0.081896 0.072484 0.229310 -vn 0.394969 0.078564 -0.915329 -v 0.082340 0.071021 0.229310 -vn -0.154110 0.372056 -0.915328 -v 0.071705 0.076705 0.229310 -vn -0.078566 0.394978 -0.915325 -v 0.073168 0.077149 0.229310 -vn 0.000001 0.402705 -0.915330 -v 0.074690 0.077299 0.229310 -vn 0.078565 0.394979 -0.915325 -v 0.076211 0.077149 0.229310 -vn 0.154110 0.372055 -0.915328 -v 0.077675 0.076705 0.229310 -vn 0.223731 0.334836 -0.915330 -v 0.079023 0.075985 0.229310 -vn -0.334840 0.223734 -0.915328 -v 0.068204 0.073833 0.229310 -vn -0.284761 0.284761 -0.915326 -v 0.069174 0.075015 0.229310 -vn -0.223734 0.334840 -0.915328 -v 0.070356 0.075985 0.229310 -vn -0.402715 0.000000 -0.915326 -v 0.066890 0.069499 0.229310 -vn -0.394978 0.078566 -0.915325 -v 0.067039 0.071021 0.229310 -vn -0.372058 0.154112 -0.915326 -v 0.067483 0.072484 0.229310 -vn 0.078564 -0.394969 -0.915329 -v 0.076211 0.061849 0.229310 -vn 0.000000 -0.402710 -0.915328 -v 0.074690 0.061699 0.229310 -vn 0.284761 -0.284761 -0.915326 -v 0.080205 0.063984 0.229310 -vn 0.223734 -0.334842 -0.915327 -v 0.079023 0.063014 0.229310 -vn 0.154108 -0.372052 -0.915330 -v 0.077675 0.062293 0.229310 -vn 0.402706 -0.000000 -0.915329 -v 0.082490 0.069499 0.229310 -vn 0.394971 -0.078565 -0.915328 -v 0.082340 0.067977 0.229310 -vn 0.372056 -0.154110 -0.915328 -v 0.081896 0.066514 0.229310 -vn 0.334843 -0.223734 -0.915327 -v 0.081175 0.065166 0.229310 -vn -0.334837 -0.223729 -0.915330 -v 0.068204 0.065166 0.229310 -vn -0.372056 -0.154110 -0.915328 -v 0.067483 0.066514 0.229310 -vn -0.394980 -0.078568 -0.915324 -v 0.067039 0.067977 0.229310 -vn -0.078564 -0.394969 -0.915329 -v 0.073168 0.061849 0.229310 -vn -0.154109 -0.372052 -0.915329 -v 0.071705 0.062293 0.229310 -vn -0.223737 -0.334847 -0.915325 -v 0.070356 0.063014 0.229310 -vn -0.284761 -0.284761 -0.915327 -v 0.069174 0.063984 0.229310 -vn -0.926244 0.000000 -0.376925 -v 0.066690 0.069499 0.229510 -vn -0.908447 -0.180702 -0.376923 -v 0.066843 0.067938 0.229510 -vn -0.855736 -0.354457 -0.376930 -v 0.067299 0.066438 0.229510 -vn -0.770141 -0.514591 -0.376934 -v 0.068038 0.065055 0.229510 -vn -0.654952 -0.654954 -0.376926 -v 0.069033 0.063842 0.229510 -vn -0.514594 -0.770144 -0.376924 -v 0.070245 0.062847 0.229510 -vn -0.354458 -0.855734 -0.376933 -v 0.071628 0.062108 0.229510 -vn -0.180700 -0.908444 -0.376931 -v 0.073129 0.061653 0.229510 -vn 0.000000 -0.926242 -0.376929 -v 0.074690 0.061499 0.229510 -vn 0.180700 -0.908444 -0.376932 -v 0.076250 0.061653 0.229510 -vn 0.354457 -0.855735 -0.376933 -v 0.077751 0.062108 0.229510 -vn 0.514593 -0.770142 -0.376928 -v 0.079134 0.062847 0.229510 -vn 0.654953 -0.654953 -0.376926 -v 0.080346 0.063842 0.229510 -vn 0.770142 -0.514593 -0.376928 -v 0.081341 0.065055 0.229510 -vn 0.855736 -0.354458 -0.376929 -v 0.082081 0.066438 0.229510 -vn 0.908444 -0.180700 -0.376930 -v 0.082536 0.067938 0.229510 -vn 0.926241 -0.000000 -0.376933 -v 0.082690 0.069499 0.229510 -vn 0.908444 0.180701 -0.376931 -v 0.082536 0.071060 0.229510 -vn 0.855737 0.354459 -0.376926 -v 0.082081 0.072561 0.229510 -vn 0.770144 0.514594 -0.376923 -v 0.081341 0.073944 0.229510 -vn 0.654953 0.654952 -0.376927 -v 0.080346 0.075156 0.229510 -vn 0.514592 0.770140 -0.376934 -v 0.079134 0.076151 0.229510 -vn 0.354457 0.855736 -0.376929 -v 0.077751 0.076890 0.229510 -vn 0.180701 0.908447 -0.376924 -v 0.076250 0.077345 0.229510 -vn 0.000001 0.926241 -0.376933 -v 0.074690 0.077499 0.229510 -vn -0.180702 0.908447 -0.376924 -v 0.073129 0.077345 0.229510 -vn -0.354457 0.855736 -0.376929 -v 0.071628 0.076890 0.229510 -vn -0.514593 0.770142 -0.376930 -v 0.070245 0.076151 0.229510 -vn -0.654953 0.654953 -0.376927 -v 0.069033 0.075156 0.229510 -vn -0.770142 0.514592 -0.376930 -v 0.068038 0.073944 0.229510 -vn -0.855738 0.354457 -0.376926 -v 0.067299 0.072561 0.229510 -vn -0.908447 0.180702 -0.376924 -v 0.066843 0.071060 0.229510 -# 2896 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 1//1 -f 1//1 128//128 2//2 -f 128//128 129//129 2//2 -f 2//2 129//129 130//130 -f 2//2 130//130 4//4 -f 4//4 130//130 131//131 -f 4//4 131//131 6//6 -f 6//6 131//131 132//132 -f 6//6 132//132 8//8 -f 8//8 132//132 133//133 -f 8//8 133//133 10//10 -f 10//10 133//133 134//134 -f 10//10 134//134 12//12 -f 12//12 134//134 135//135 -f 12//12 135//135 14//14 -f 14//14 135//135 136//136 -f 14//14 136//136 16//16 -f 16//16 136//136 137//137 -f 16//16 137//137 18//18 -f 18//18 137//137 138//138 -f 18//18 138//138 20//20 -f 20//20 138//138 139//139 -f 20//20 139//139 22//22 -f 22//22 139//139 140//140 -f 22//22 140//140 24//24 -f 24//24 140//140 141//141 -f 24//24 141//141 26//26 -f 26//26 141//141 142//142 -f 26//26 142//142 28//28 -f 28//28 142//142 143//143 -f 28//28 143//143 30//30 -f 30//30 143//143 144//144 -f 30//30 144//144 32//32 -f 32//32 144//144 145//145 -f 32//32 145//145 34//34 -f 34//34 145//145 146//146 -f 34//34 146//146 36//36 -f 36//36 146//146 147//147 -f 36//36 147//147 38//38 -f 38//38 147//147 148//148 -f 38//38 148//148 40//40 -f 40//40 148//148 149//149 -f 40//40 149//149 42//42 -f 42//42 149//149 150//150 -f 42//42 150//150 44//44 -f 44//44 150//150 151//151 -f 44//44 151//151 46//46 -f 46//46 151//151 152//152 -f 46//46 152//152 48//48 -f 48//48 152//152 153//153 -f 48//48 153//153 50//50 -f 50//50 153//153 154//154 -f 50//50 154//154 52//52 -f 52//52 154//154 155//155 -f 52//52 155//155 54//54 -f 54//54 155//155 156//156 -f 54//54 156//156 56//56 -f 56//56 156//156 157//157 -f 56//56 157//157 58//58 -f 58//58 157//157 158//158 -f 58//58 158//158 60//60 -f 60//60 158//158 159//159 -f 60//60 159//159 62//62 -f 62//62 159//159 160//160 -f 62//62 160//160 64//64 -f 64//64 160//160 161//161 -f 64//64 161//161 66//66 -f 66//66 161//161 162//162 -f 66//66 162//162 68//68 -f 68//68 162//162 163//163 -f 68//68 163//163 70//70 -f 70//70 163//163 164//164 -f 70//70 164//164 72//72 -f 72//72 164//164 165//165 -f 72//72 165//165 74//74 -f 74//74 165//165 166//166 -f 74//74 166//166 76//76 -f 76//76 166//166 167//167 -f 76//76 167//167 78//78 -f 78//78 167//167 168//168 -f 78//78 168//168 80//80 -f 80//80 168//168 169//169 -f 80//80 169//169 82//82 -f 82//82 169//169 170//170 -f 82//82 170//170 84//84 -f 84//84 170//170 171//171 -f 84//84 171//171 86//86 -f 86//86 171//171 172//172 -f 86//86 172//172 88//88 -f 88//88 172//172 173//173 -f 88//88 173//173 90//90 -f 90//90 173//173 174//174 -f 90//90 174//174 92//92 -f 92//92 174//174 175//175 -f 92//92 175//175 94//94 -f 94//94 175//175 176//176 -f 94//94 176//176 96//96 -f 96//96 176//176 177//177 -f 96//96 177//177 98//98 -f 98//98 177//177 178//178 -f 98//98 178//178 100//100 -f 100//100 178//178 179//179 -f 100//100 179//179 102//102 -f 102//102 179//179 180//180 -f 102//102 180//180 104//104 -f 104//104 180//180 181//181 -f 104//104 181//181 106//106 -f 106//106 181//181 182//182 -f 106//106 182//182 108//108 -f 108//108 182//182 183//183 -f 108//108 183//183 110//110 -f 110//110 183//183 184//184 -f 110//110 184//184 112//112 -f 112//112 184//184 185//185 -f 112//112 185//185 114//114 -f 114//114 185//185 186//186 -f 114//114 186//186 116//116 -f 116//116 186//186 187//187 -f 116//116 187//187 118//118 -f 118//118 187//187 188//188 -f 118//118 188//188 120//120 -f 120//120 188//188 189//189 -f 120//120 189//189 122//122 -f 122//122 189//189 190//190 -f 122//122 190//190 124//124 -f 124//124 190//190 191//191 -f 124//124 191//191 126//126 -f 126//126 191//191 192//192 -f 126//126 192//192 128//128 -f 128//128 192//192 129//129 -f 192//192 193//193 129//129 -f 129//129 193//193 194//194 -f 129//129 194//194 130//130 -f 130//130 194//194 195//195 -f 130//130 195//195 131//131 -f 131//131 195//195 196//196 -f 131//131 196//196 132//132 -f 132//132 196//196 197//197 -f 132//132 197//197 133//133 -f 133//133 197//197 198//198 -f 133//133 198//198 134//134 -f 134//134 198//198 199//199 -f 134//134 199//199 135//135 -f 135//135 199//199 200//200 -f 135//135 200//200 136//136 -f 136//136 200//200 201//201 -f 136//136 201//201 137//137 -f 137//137 201//201 202//202 -f 137//137 202//202 138//138 -f 138//138 202//202 203//203 -f 138//138 203//203 139//139 -f 139//139 203//203 204//204 -f 139//139 204//204 140//140 -f 140//140 204//204 205//205 -f 140//140 205//205 141//141 -f 141//141 205//205 206//206 -f 141//141 206//206 142//142 -f 142//142 206//206 207//207 -f 142//142 207//207 143//143 -f 143//143 207//207 208//208 -f 143//143 208//208 144//144 -f 144//144 208//208 209//209 -f 144//144 209//209 145//145 -f 145//145 209//209 210//210 -f 145//145 210//210 146//146 -f 146//146 210//210 211//211 -f 146//146 211//211 147//147 -f 147//147 211//211 212//212 -f 147//147 212//212 148//148 -f 148//148 212//212 213//213 -f 148//148 213//213 149//149 -f 149//149 213//213 214//214 -f 149//149 214//214 150//150 -f 150//150 214//214 215//215 -f 150//150 215//215 151//151 -f 151//151 215//215 216//216 -f 151//151 216//216 152//152 -f 152//152 216//216 217//217 -f 152//152 217//217 153//153 -f 153//153 217//217 218//218 -f 153//153 218//218 154//154 -f 154//154 218//218 219//219 -f 154//154 219//219 155//155 -f 155//155 219//219 220//220 -f 155//155 220//220 156//156 -f 156//156 220//220 221//221 -f 156//156 221//221 157//157 -f 157//157 221//221 222//222 -f 157//157 222//222 158//158 -f 158//158 222//222 223//223 -f 158//158 223//223 159//159 -f 159//159 223//223 224//224 -f 159//159 224//224 160//160 -f 160//160 224//224 225//225 -f 160//160 225//225 161//161 -f 161//161 225//225 226//226 -f 161//161 226//226 162//162 -f 162//162 226//226 227//227 -f 162//162 227//227 163//163 -f 163//163 227//227 228//228 -f 163//163 228//228 164//164 -f 164//164 228//228 229//229 -f 164//164 229//229 165//165 -f 165//165 229//229 230//230 -f 165//165 230//230 166//166 -f 166//166 230//230 231//231 -f 166//166 231//231 167//167 -f 167//167 231//231 232//232 -f 167//167 232//232 168//168 -f 168//168 232//232 233//233 -f 168//168 233//233 169//169 -f 169//169 233//233 234//234 -f 169//169 234//234 170//170 -f 170//170 234//234 235//235 -f 170//170 235//235 171//171 -f 171//171 235//235 236//236 -f 171//171 236//236 172//172 -f 172//172 236//236 237//237 -f 172//172 237//237 173//173 -f 173//173 237//237 238//238 -f 173//173 238//238 174//174 -f 174//174 238//238 239//239 -f 174//174 239//239 175//175 -f 175//175 239//239 240//240 -f 175//175 240//240 176//176 -f 176//176 240//240 241//241 -f 176//176 241//241 177//177 -f 177//177 241//241 242//242 -f 177//177 242//242 178//178 -f 178//178 242//242 243//243 -f 178//178 243//243 179//179 -f 179//179 243//243 244//244 -f 179//179 244//244 180//180 -f 180//180 244//244 245//245 -f 180//180 245//245 181//181 -f 181//181 245//245 246//246 -f 181//181 246//246 182//182 -f 182//182 246//246 247//247 -f 182//182 247//247 183//183 -f 183//183 247//247 248//248 -f 183//183 248//248 184//184 -f 184//184 248//248 249//249 -f 184//184 249//249 185//185 -f 185//185 249//249 250//250 -f 185//185 250//250 186//186 -f 186//186 250//250 251//251 -f 186//186 251//251 187//187 -f 187//187 251//251 252//252 -f 187//187 252//252 188//188 -f 188//188 252//252 253//253 -f 188//188 253//253 189//189 -f 189//189 253//253 254//254 -f 189//189 254//254 190//190 -f 190//190 254//254 255//255 -f 190//190 255//255 191//191 -f 191//191 255//255 256//256 -f 191//191 256//256 192//192 -f 192//192 256//256 193//193 -f 242//242 257//257 243//243 -f 243//243 257//257 258//258 -f 243//243 258//258 244//244 -f 244//244 258//258 259//259 -f 244//244 259//259 245//245 -f 245//245 259//259 260//260 -f 245//245 260//260 246//246 -f 246//246 260//260 261//261 -f 246//246 261//261 247//247 -f 247//247 261//261 262//262 -f 247//247 262//262 248//248 -f 236//236 263//263 237//237 -f 237//237 263//263 264//264 -f 237//237 264//264 238//238 -f 238//238 264//264 265//265 -f 238//238 265//265 239//239 -f 239//239 265//265 266//266 -f 239//239 266//266 240//240 -f 240//240 266//266 267//267 -f 240//240 267//267 241//241 -f 241//241 267//267 268//268 -f 241//241 268//268 242//242 -f 242//242 268//268 269//269 -f 242//242 269//269 257//257 -f 230//230 270//270 231//231 -f 231//231 270//270 271//271 -f 231//231 271//271 232//232 -f 232//232 271//271 272//272 -f 232//232 272//272 233//233 -f 233//233 272//272 273//273 -f 233//233 273//273 234//234 -f 234//234 273//273 274//274 -f 234//234 274//274 235//235 -f 235//235 274//274 275//275 -f 235//235 275//275 236//236 -f 236//236 275//275 276//276 -f 236//236 276//276 263//263 -f 216//216 277//277 217//217 -f 217//217 277//277 278//278 -f 217//217 278//278 218//218 -f 218//218 278//278 279//279 -f 218//218 279//279 219//219 -f 219//219 279//279 280//280 -f 219//219 280//280 220//220 -f 220//220 280//280 281//281 -f 220//220 281//281 221//221 -f 221//221 281//281 282//282 -f 221//221 282//282 222//222 -f 222//222 282//282 283//283 -f 222//222 283//283 223//223 -f 223//223 283//283 284//284 -f 223//223 284//284 224//224 -f 224//224 284//284 285//285 -f 224//224 285//285 225//225 -f 225//225 285//285 286//286 -f 225//225 286//286 226//226 -f 226//226 286//286 287//287 -f 226//226 287//287 227//227 -f 227//227 287//287 288//288 -f 227//227 288//288 228//228 -f 228//228 288//288 289//289 -f 228//228 289//289 229//229 -f 229//229 289//289 290//290 -f 229//229 290//290 230//230 -f 230//230 290//290 291//291 -f 230//230 291//291 270//270 -f 210//210 292//292 211//211 -f 211//211 292//292 293//293 -f 211//211 293//293 212//212 -f 212//212 293//293 294//294 -f 212//212 294//294 213//213 -f 213//213 294//294 295//295 -f 213//213 295//295 214//214 -f 214//214 295//295 296//296 -f 214//214 296//296 215//215 -f 215//215 296//296 297//297 -f 215//215 297//297 216//216 -f 216//216 297//297 298//298 -f 216//216 298//298 277//277 -f 204//204 299//299 205//205 -f 205//205 299//299 300//300 -f 205//205 300//300 206//206 -f 206//206 300//300 301//301 -f 206//206 301//301 207//207 -f 207//207 301//301 302//302 -f 207//207 302//302 208//208 -f 208//208 302//302 303//303 -f 208//208 303//303 209//209 -f 209//209 303//303 304//304 -f 209//209 304//304 210//210 -f 210//210 304//304 305//305 -f 210//210 305//305 292//292 -f 198//198 306//306 199//199 -f 199//199 306//306 307//307 -f 199//199 307//307 200//200 -f 200//200 307//307 308//308 -f 200//200 308//308 201//201 -f 201//201 308//308 309//309 -f 201//201 309//309 202//202 -f 202//202 309//309 310//310 -f 202//202 310//310 203//203 -f 203//203 310//310 311//311 -f 203//203 311//311 204//204 -f 204//204 311//311 312//312 -f 204//204 312//312 299//299 -f 262//262 313//313 248//248 -f 248//248 313//313 314//314 -f 248//248 314//314 249//249 -f 249//249 314//314 315//315 -f 249//249 315//315 250//250 -f 250//250 315//315 316//316 -f 250//250 316//316 251//251 -f 251//251 316//316 317//317 -f 251//251 317//317 252//252 -f 252//252 317//317 318//318 -f 252//252 318//318 253//253 -f 253//253 318//318 319//319 -f 253//253 319//319 254//254 -f 254//254 319//319 320//320 -f 254//254 320//320 255//255 -f 255//255 320//320 321//321 -f 255//255 321//321 256//256 -f 256//256 321//321 322//322 -f 256//256 322//322 193//193 -f 193//193 322//322 323//323 -f 193//193 323//323 194//194 -f 194//194 323//323 324//324 -f 194//194 324//324 195//195 -f 195//195 324//324 325//325 -f 195//195 325//325 196//196 -f 196//196 325//325 326//326 -f 196//196 326//326 197//197 -f 197//197 326//326 327//327 -f 197//197 327//327 198//198 -f 198//198 327//327 328//328 -f 198//198 328//328 306//306 -f 329//329 330//330 331//331 -f 332//332 333//333 334//334 -f 335//335 336//336 337//337 -f 338//338 339//339 340//340 -f 341//341 342//342 343//343 -f 344//344 345//345 346//346 -f 347//347 348//348 349//349 -f 328//328 327//327 350//350 -f 307//307 306//306 351//351 -f 308//308 307//307 352//352 -f 296//296 295//295 335//335 -f 298//298 297//297 353//353 -f 278//278 277//277 354//354 -f 279//279 278//278 355//355 -f 276//276 275//275 356//356 -f 265//265 264//264 357//357 -f 258//258 257//257 358//358 -f 261//261 260//260 359//359 -f 320//320 319//319 360//360 -f 322//322 321//321 361//361 -f 361//361 321//321 320//320 -f 317//317 316//316 347//347 -f 347//347 316//316 315//315 -f 347//347 315//315 348//348 -f 348//348 315//315 314//314 -f 348//348 314//314 313//313 -f 362//362 262//262 261//261 -f 260//260 259//259 363//363 -f 266//266 345//345 267//267 -f 267//267 345//345 344//344 -f 267//267 344//344 268//268 -f 268//268 344//344 269//269 -f 264//264 263//263 364//364 -f 364//364 263//263 276//276 -f 273//273 272//272 341//341 -f 341//341 272//272 271//271 -f 341//341 271//271 342//342 -f 342//342 271//271 270//270 -f 342//342 270//270 291//291 -f 365//365 290//290 289//289 -f 289//289 288//288 366//366 -f 366//366 288//288 287//287 -f 285//285 284//284 338//338 -f 338//338 284//284 283//283 -f 338//338 283//283 339//339 -f 339//339 283//283 282//282 -f 339//339 282//282 281//281 -f 279//279 355//355 280//280 -f 335//335 295//295 336//336 -f 336//336 295//295 294//294 -f 336//336 294//294 293//293 -f 367//367 292//292 305//305 -f 305//305 304//304 368//368 -f 368//368 304//304 303//303 -f 302//302 301//301 369//369 -f 300//300 299//299 332//332 -f 332//332 299//299 312//312 -f 332//332 312//312 333//333 -f 333//333 312//312 311//311 -f 333//333 311//311 310//310 -f 308//308 352//352 309//309 -f 326//326 325//325 329//329 -f 329//329 325//325 324//324 -f 329//329 324//324 330//330 -f 330//330 324//324 323//323 -f 370//370 371//371 360//360 -f 372//372 349//349 373//373 -f 373//373 349//349 348//348 -f 373//373 348//348 362//362 -f 362//362 348//348 313//313 -f 362//362 313//313 262//262 -f 374//374 375//375 363//363 -f 376//376 346//346 377//377 -f 377//377 346//346 345//345 -f 377//377 345//345 357//357 -f 357//357 345//345 266//266 -f 357//357 266//266 265//265 -f 378//378 379//379 356//356 -f 380//380 343//343 381//381 -f 381//381 343//343 342//342 -f 381//381 342//342 365//365 -f 365//365 342//342 291//291 -f 365//365 291//291 290//290 -f 382//382 383//383 384//384 -f 385//385 340//340 386//386 -f 386//386 340//340 339//339 -f 386//386 339//339 387//387 -f 387//387 339//339 281//281 -f 387//387 281//281 280//280 -f 388//388 389//389 354//354 -f 390//390 337//337 391//391 -f 391//391 337//337 336//336 -f 391//391 336//336 367//367 -f 367//367 336//336 293//293 -f 367//367 293//293 292//292 -f 392//392 393//393 394//394 -f 395//395 334//334 396//396 -f 396//396 334//334 333//333 -f 396//396 333//333 397//397 -f 397//397 333//333 310//310 -f 397//397 310//310 309//309 -f 398//398 399//399 351//351 -f 400//400 331//331 401//401 -f 401//401 331//331 330//330 -f 401//401 330//330 402//402 -f 402//402 330//330 323//323 -f 402//402 323//323 322//322 -f 403//403 371//371 404//404 -f 404//404 371//371 370//370 -f 404//404 370//370 405//405 -f 406//406 375//375 407//407 -f 407//407 375//375 374//374 -f 407//407 374//374 408//408 -f 409//409 379//379 410//410 -f 410//410 379//379 378//378 -f 410//410 378//378 411//411 -f 412//412 383//383 413//413 -f 413//413 383//383 382//382 -f 413//413 382//382 414//414 -f 415//415 389//389 416//416 -f 416//416 389//389 388//388 -f 416//416 388//388 417//417 -f 418//418 393//393 419//419 -f 419//419 393//393 392//392 -f 419//419 392//392 420//420 -f 421//421 399//399 422//422 -f 422//422 399//399 398//398 -f 422//422 398//398 423//423 -f 424//424 425//425 426//426 -f 322//322 361//361 402//402 -f 402//402 361//361 427//427 -f 402//402 427//427 401//401 -f 401//401 427//427 424//424 -f 401//401 424//424 400//400 -f 400//400 424//424 426//426 -f 400//400 426//426 428//428 -f 320//320 360//360 361//361 -f 361//361 360//360 371//371 -f 361//361 371//371 427//427 -f 427//427 371//371 403//403 -f 427//427 403//403 424//424 -f 424//424 403//403 429//429 -f 424//424 429//429 425//425 -f 430//430 431//431 432//432 -f 432//432 431//431 405//405 -f 432//432 405//405 433//433 -f 433//433 405//405 370//370 -f 433//433 370//370 434//434 -f 434//434 370//370 360//360 -f 434//434 360//360 318//318 -f 318//318 360//360 319//319 -f 431//431 435//435 405//405 -f 405//405 435//435 436//436 -f 405//405 436//436 404//404 -f 404//404 436//436 437//437 -f 404//404 437//437 403//403 -f 403//403 437//437 438//438 -f 403//403 438//438 429//429 -f 318//318 317//317 434//434 -f 434//434 317//317 347//347 -f 434//434 347//347 433//433 -f 433//433 347//347 349//349 -f 433//433 349//349 432//432 -f 432//432 349//349 372//372 -f 432//432 372//372 430//430 -f 430//430 372//372 439//439 -f 440//440 441//441 442//442 -f 261//261 359//359 362//362 -f 362//362 359//359 443//443 -f 362//362 443//443 373//373 -f 373//373 443//443 440//440 -f 373//373 440//440 372//372 -f 372//372 440//440 442//442 -f 372//372 442//442 439//439 -f 260//260 363//363 359//359 -f 359//359 363//363 375//375 -f 359//359 375//375 443//443 -f 443//443 375//375 406//406 -f 443//443 406//406 440//440 -f 440//440 406//406 444//444 -f 440//440 444//444 441//441 -f 445//445 446//446 447//447 -f 447//447 446//446 408//408 -f 447//447 408//408 448//448 -f 448//448 408//408 374//374 -f 448//448 374//374 358//358 -f 358//358 374//374 363//363 -f 358//358 363//363 258//258 -f 258//258 363//363 259//259 -f 446//446 449//449 408//408 -f 408//408 449//449 450//450 -f 408//408 450//450 407//407 -f 407//407 450//450 451//451 -f 407//407 451//451 406//406 -f 406//406 451//451 452//452 -f 406//406 452//452 444//444 -f 257//257 269//269 358//358 -f 358//358 269//269 344//344 -f 358//358 344//344 448//448 -f 448//448 344//344 346//346 -f 448//448 346//346 447//447 -f 447//447 346//346 376//376 -f 447//447 376//376 445//445 -f 445//445 376//376 453//453 -f 454//454 455//455 456//456 -f 264//264 364//364 357//357 -f 357//357 364//364 457//457 -f 357//357 457//457 377//377 -f 377//377 457//457 454//454 -f 377//377 454//454 376//376 -f 376//376 454//454 456//456 -f 376//376 456//456 453//453 -f 276//276 356//356 364//364 -f 364//364 356//356 379//379 -f 364//364 379//379 457//457 -f 457//457 379//379 409//409 -f 457//457 409//409 454//454 -f 454//454 409//409 458//458 -f 454//454 458//458 455//455 -f 459//459 460//460 461//461 -f 461//461 460//460 411//411 -f 461//461 411//411 462//462 -f 462//462 411//411 378//378 -f 462//462 378//378 463//463 -f 463//463 378//378 356//356 -f 463//463 356//356 274//274 -f 274//274 356//356 275//275 -f 460//460 464//464 411//411 -f 411//411 464//464 465//465 -f 411//411 465//465 410//410 -f 410//410 465//465 466//466 -f 410//410 466//466 409//409 -f 409//409 466//466 467//467 -f 409//409 467//467 458//458 -f 274//274 273//273 463//463 -f 463//463 273//273 341//341 -f 463//463 341//341 462//462 -f 462//462 341//341 343//343 -f 462//462 343//343 461//461 -f 461//461 343//343 380//380 -f 461//461 380//380 459//459 -f 459//459 380//380 468//468 -f 469//469 470//470 471//471 -f 289//289 366//366 365//365 -f 365//365 366//366 472//472 -f 365//365 472//472 381//381 -f 381//381 472//472 469//469 -f 381//381 469//469 380//380 -f 380//380 469//469 471//471 -f 380//380 471//471 468//468 -f 287//287 384//384 366//366 -f 366//366 384//384 383//383 -f 366//366 383//383 472//472 -f 472//472 383//383 412//412 -f 472//472 412//412 469//469 -f 469//469 412//412 473//473 -f 469//469 473//473 470//470 -f 474//474 475//475 476//476 -f 476//476 475//475 414//414 -f 476//476 414//414 477//477 -f 477//477 414//414 382//382 -f 477//477 382//382 478//478 -f 478//478 382//382 384//384 -f 478//478 384//384 286//286 -f 286//286 384//384 287//287 -f 475//475 479//479 414//414 -f 414//414 479//479 480//480 -f 414//414 480//480 413//413 -f 413//413 480//480 481//481 -f 413//413 481//481 412//412 -f 412//412 481//481 482//482 -f 412//412 482//482 473//473 -f 286//286 285//285 478//478 -f 478//478 285//285 338//338 -f 478//478 338//338 477//477 -f 477//477 338//338 340//340 -f 477//477 340//340 476//476 -f 476//476 340//340 385//385 -f 476//476 385//385 474//474 -f 474//474 385//385 483//483 -f 484//484 485//485 486//486 -f 280//280 355//355 387//387 -f 387//387 355//355 487//487 -f 387//387 487//487 386//386 -f 386//386 487//487 484//484 -f 386//386 484//484 385//385 -f 385//385 484//484 486//486 -f 385//385 486//486 483//483 -f 278//278 354//354 355//355 -f 355//355 354//354 389//389 -f 355//355 389//389 487//487 -f 487//487 389//389 415//415 -f 487//487 415//415 484//484 -f 484//484 415//415 488//488 -f 484//484 488//488 485//485 -f 489//489 490//490 491//491 -f 491//491 490//490 417//417 -f 491//491 417//417 492//492 -f 492//492 417//417 388//388 -f 492//492 388//388 353//353 -f 353//353 388//388 354//354 -f 353//353 354//354 298//298 -f 298//298 354//354 277//277 -f 490//490 493//493 417//417 -f 417//417 493//493 494//494 -f 417//417 494//494 416//416 -f 416//416 494//494 495//495 -f 416//416 495//495 415//415 -f 415//415 495//495 496//496 -f 415//415 496//496 488//488 -f 297//297 296//296 353//353 -f 353//353 296//296 335//335 -f 353//353 335//335 492//492 -f 492//492 335//335 337//337 -f 492//492 337//337 491//491 -f 491//491 337//337 390//390 -f 491//491 390//390 489//489 -f 489//489 390//390 497//497 -f 498//498 499//499 500//500 -f 305//305 368//368 367//367 -f 367//367 368//368 501//501 -f 367//367 501//501 391//391 -f 391//391 501//501 498//498 -f 391//391 498//498 390//390 -f 390//390 498//498 500//500 -f 390//390 500//500 497//497 -f 303//303 394//394 368//368 -f 368//368 394//394 393//393 -f 368//368 393//393 501//501 -f 501//501 393//393 418//418 -f 501//501 418//418 498//498 -f 498//498 418//418 502//502 -f 498//498 502//502 499//499 -f 503//503 504//504 505//505 -f 505//505 504//504 420//420 -f 505//505 420//420 506//506 -f 506//506 420//420 392//392 -f 506//506 392//392 369//369 -f 369//369 392//392 394//394 -f 369//369 394//394 302//302 -f 302//302 394//394 303//303 -f 504//504 507//507 420//420 -f 420//420 507//507 508//508 -f 420//420 508//508 419//419 -f 419//419 508//508 509//509 -f 419//419 509//509 418//418 -f 418//418 509//509 510//510 -f 418//418 510//510 502//502 -f 301//301 300//300 369//369 -f 369//369 300//300 332//332 -f 369//369 332//332 506//506 -f 506//506 332//332 334//334 -f 506//506 334//334 505//505 -f 505//505 334//334 395//395 -f 505//505 395//395 503//503 -f 503//503 395//395 511//511 -f 512//512 513//513 514//514 -f 309//309 352//352 397//397 -f 397//397 352//352 515//515 -f 397//397 515//515 396//396 -f 396//396 515//515 512//512 -f 396//396 512//512 395//395 -f 395//395 512//512 514//514 -f 395//395 514//514 511//511 -f 307//307 351//351 352//352 -f 352//352 351//351 399//399 -f 352//352 399//399 515//515 -f 515//515 399//399 421//421 -f 515//515 421//421 512//512 -f 512//512 421//421 516//516 -f 512//512 516//516 513//513 -f 517//517 518//518 519//519 -f 519//519 518//518 423//423 -f 519//519 423//423 520//520 -f 520//520 423//423 398//398 -f 520//520 398//398 350//350 -f 350//350 398//398 351//351 -f 350//350 351//351 328//328 -f 328//328 351//351 306//306 -f 518//518 521//521 423//423 -f 423//423 521//521 522//522 -f 423//423 522//522 422//422 -f 422//422 522//522 523//523 -f 422//422 523//523 421//421 -f 421//421 523//523 524//524 -f 421//421 524//524 516//516 -f 327//327 326//326 350//350 -f 350//350 326//326 329//329 -f 350//350 329//329 520//520 -f 520//520 329//329 331//331 -f 520//520 331//331 519//519 -f 519//519 331//331 400//400 -f 519//519 400//400 517//517 -f 517//517 400//400 428//428 -f 471//471 525//525 468//468 -f 468//468 525//525 526//526 -f 468//468 526//526 459//459 -f 459//459 526//526 527//527 -f 459//459 527//527 460//460 -f 460//460 527//527 528//528 -f 460//460 528//528 464//464 -f 464//464 528//528 529//529 -f 464//464 529//529 465//465 -f 530//530 451//451 450//450 -f 529//529 531//531 465//465 -f 465//465 531//531 532//532 -f 465//465 532//532 466//466 -f 466//466 532//532 533//533 -f 466//466 533//533 467//467 -f 467//467 533//533 534//534 -f 467//467 534//534 458//458 -f 458//458 534//534 535//535 -f 458//458 535//535 455//455 -f 455//455 535//535 536//536 -f 455//455 536//536 456//456 -f 456//456 536//536 537//537 -f 456//456 537//537 453//453 -f 453//453 537//537 538//538 -f 453//453 538//538 445//445 -f 445//445 538//538 539//539 -f 445//445 539//539 446//446 -f 446//446 539//539 540//540 -f 446//446 540//540 449//449 -f 449//449 540//540 541//541 -f 449//449 541//541 450//450 -f 450//450 541//541 542//542 -f 450//450 542//542 530//530 -f 530//530 543//543 451//451 -f 451//451 543//543 544//544 -f 451//451 544//544 452//452 -f 452//452 544//544 545//545 -f 452//452 545//545 444//444 -f 444//444 545//545 546//546 -f 444//444 546//546 441//441 -f 441//441 546//546 547//547 -f 441//441 547//547 442//442 -f 442//442 547//547 548//548 -f 442//442 548//548 439//439 -f 439//439 548//548 549//549 -f 439//439 549//549 430//430 -f 430//430 549//549 550//550 -f 430//430 550//550 431//431 -f 431//431 550//550 551//551 -f 431//431 551//551 435//435 -f 435//435 551//551 552//552 -f 435//435 552//552 436//436 -f 436//436 552//552 553//553 -f 436//436 553//553 437//437 -f 553//553 554//554 437//437 -f 437//437 554//554 555//555 -f 437//437 555//555 438//438 -f 438//438 555//555 556//556 -f 438//438 556//556 429//429 -f 429//429 556//556 557//557 -f 429//429 557//557 425//425 -f 425//425 557//557 558//558 -f 425//425 558//558 426//426 -f 426//426 558//558 559//559 -f 426//426 559//559 428//428 -f 428//428 559//559 560//560 -f 428//428 560//560 517//517 -f 517//517 560//560 561//561 -f 517//517 561//561 518//518 -f 561//561 562//562 518//518 -f 518//518 562//562 563//563 -f 518//518 563//563 521//521 -f 521//521 563//563 564//564 -f 521//521 564//564 522//522 -f 522//522 564//564 565//565 -f 522//522 565//565 523//523 -f 565//565 566//566 523//523 -f 523//523 566//566 567//567 -f 523//523 567//567 524//524 -f 524//524 567//567 568//568 -f 524//524 568//568 516//516 -f 516//516 568//568 513//513 -f 513//513 568//568 569//569 -f 513//513 569//569 514//514 -f 514//514 569//569 570//570 -f 514//514 570//570 511//511 -f 511//511 570//570 571//571 -f 511//511 571//571 503//503 -f 503//503 571//571 572//572 -f 503//503 572//572 504//504 -f 572//572 573//573 504//504 -f 504//504 573//573 574//574 -f 504//504 574//574 507//507 -f 507//507 574//574 575//575 -f 507//507 575//575 508//508 -f 508//508 575//575 576//576 -f 508//508 576//576 509//509 -f 576//576 577//577 509//509 -f 509//509 577//577 578//578 -f 509//509 578//578 510//510 -f 510//510 578//578 579//579 -f 510//510 579//579 502//502 -f 502//502 579//579 580//580 -f 502//502 580//580 499//499 -f 499//499 580//580 581//581 -f 499//499 581//581 500//500 -f 500//500 581//581 582//582 -f 500//500 582//582 497//497 -f 497//497 582//582 583//583 -f 497//497 583//583 489//489 -f 489//489 583//583 584//584 -f 489//489 584//584 490//490 -f 490//490 584//584 585//585 -f 490//490 585//585 493//493 -f 493//493 585//585 586//586 -f 493//493 586//586 494//494 -f 494//494 586//586 587//587 -f 494//494 587//587 495//495 -f 587//587 588//588 495//495 -f 495//495 588//588 589//589 -f 495//495 589//589 496//496 -f 496//496 589//589 590//590 -f 496//496 590//590 488//488 -f 488//488 590//590 591//591 -f 488//488 591//591 485//485 -f 485//485 591//591 592//592 -f 485//485 592//592 486//486 -f 486//486 592//592 593//593 -f 486//486 593//593 483//483 -f 593//593 594//594 483//483 -f 483//483 594//594 595//595 -f 483//483 595//595 474//474 -f 474//474 595//595 596//596 -f 474//474 596//596 475//475 -f 475//475 596//596 597//597 -f 475//475 597//597 479//479 -f 479//479 597//597 598//598 -f 479//479 598//598 480//480 -f 480//480 598//598 599//599 -f 480//480 599//599 481//481 -f 481//481 599//599 600//600 -f 481//481 600//600 482//482 -f 482//482 600//600 601//601 -f 482//482 601//601 473//473 -f 473//473 601//601 602//602 -f 473//473 602//602 470//470 -f 470//470 602//602 603//603 -f 470//470 603//603 471//471 -f 471//471 603//603 604//604 -f 471//471 604//604 525//525 -f 605//605 606//606 607//607 -f 608//608 609//609 610//610 -f 611//611 612//612 613//613 -f 614//614 615//615 616//616 -f 617//617 618//618 619//619 -f 620//620 621//621 622//622 -f 623//623 624//624 625//625 -f 626//626 627//627 628//628 -f 629//629 630//630 631//631 -f 621//621 632//632 633//633 -f 624//624 634//634 635//635 -f 627//627 636//636 637//637 -f 630//630 638//638 639//639 -f 570//570 569//569 640//640 -f 558//558 557//557 641//641 -f 641//641 557//557 642//642 -f 555//555 554//554 638//638 -f 554//554 553//553 638//638 -f 638//638 553//553 552//552 -f 638//638 552//552 639//639 -f 639//639 552//552 551//551 -f 639//639 551//551 643//643 -f 643//643 551//551 550//550 -f 643//643 550//550 644//644 -f 644//644 550//550 549//549 -f 644//644 549//549 645//645 -f 645//645 549//549 548//548 -f 548//548 547//547 645//645 -f 645//645 547//547 546//546 -f 645//645 546//546 646//646 -f 646//646 546//546 545//545 -f 646//646 545//545 647//647 -f 647//647 545//545 544//544 -f 647//647 544//544 648//648 -f 648//648 544//544 543//543 -f 543//543 530//530 648//648 -f 648//648 530//530 542//542 -f 648//648 542//542 649//649 -f 540//540 539//539 636//636 -f 539//539 538//538 636//636 -f 636//636 538//538 537//537 -f 636//636 537//537 637//637 -f 637//637 537//537 536//536 -f 637//637 536//536 650//650 -f 650//650 536//536 535//535 -f 650//650 535//535 651//651 -f 651//651 535//535 534//534 -f 651//651 534//534 652//652 -f 652//652 534//534 533//533 -f 533//533 532//532 652//652 -f 652//652 532//532 531//531 -f 652//652 531//531 653//653 -f 653//653 531//531 529//529 -f 653//653 529//529 654//654 -f 654//654 529//529 528//528 -f 654//654 528//528 655//655 -f 655//655 528//528 527//527 -f 527//527 526//526 655//655 -f 655//655 526//526 525//525 -f 655//655 525//525 656//656 -f 603//603 602//602 634//634 -f 602//602 601//601 634//634 -f 634//634 601//601 600//600 -f 634//634 600//600 635//635 -f 635//635 600//600 599//599 -f 635//635 599//599 657//657 -f 657//657 599//599 598//598 -f 657//657 598//598 658//658 -f 658//658 598//598 597//597 -f 658//658 597//597 659//659 -f 659//659 597//597 596//596 -f 596//596 595//595 659//659 -f 659//659 595//595 594//594 -f 659//659 594//594 660//660 -f 660//660 594//594 593//593 -f 660//660 593//593 661//661 -f 661//661 593//593 592//592 -f 661//661 592//592 662//662 -f 662//662 592//592 591//591 -f 591//591 590//590 662//662 -f 662//662 590//590 589//589 -f 662//662 589//589 663//663 -f 587//587 586//586 632//632 -f 586//586 585//585 632//632 -f 632//632 585//585 584//584 -f 632//632 584//584 633//633 -f 633//633 584//584 583//583 -f 633//633 583//583 664//664 -f 664//664 583//583 582//582 -f 664//664 582//582 665//665 -f 665//665 582//582 581//581 -f 665//665 581//581 666//666 -f 666//666 581//581 580//580 -f 580//580 579//579 666//666 -f 666//666 579//579 578//578 -f 666//666 578//578 667//667 -f 667//667 578//578 577//577 -f 667//667 577//577 668//668 -f 668//668 577//577 576//576 -f 668//668 576//576 669//669 -f 669//669 576//576 575//575 -f 575//575 574//574 669//669 -f 669//669 574//574 573//573 -f 669//669 573//573 670//670 -f 570//570 640//640 571//571 -f 564//564 671//671 565//565 -f 565//565 671//671 672//672 -f 565//565 672//672 566//566 -f 564//564 563//563 671//671 -f 671//671 563//563 562//562 -f 671//671 562//562 673//673 -f 673//673 562//562 561//561 -f 673//673 561//561 674//674 -f 674//674 561//561 560//560 -f 674//674 560//560 641//641 -f 641//641 560//560 559//559 -f 641//641 559//559 558//558 -f 642//642 675//675 676//676 -f 630//630 639//639 631//631 -f 631//631 639//639 643//643 -f 631//631 643//643 677//677 -f 677//677 643//643 644//644 -f 677//677 644//644 678//678 -f 678//678 644//644 645//645 -f 678//678 645//645 679//679 -f 679//679 645//645 646//646 -f 679//679 646//646 680//680 -f 680//680 646//646 647//647 -f 680//680 647//647 681//681 -f 681//681 647//647 648//648 -f 681//681 648//648 682//682 -f 682//682 648//648 649//649 -f 682//682 649//649 683//683 -f 627//627 637//637 628//628 -f 628//628 637//637 650//650 -f 628//628 650//650 684//684 -f 684//684 650//650 651//651 -f 684//684 651//651 685//685 -f 685//685 651//651 652//652 -f 685//685 652//652 686//686 -f 686//686 652//652 653//653 -f 686//686 653//653 687//687 -f 687//687 653//653 654//654 -f 687//687 654//654 688//688 -f 688//688 654//654 655//655 -f 688//688 655//655 689//689 -f 689//689 655//655 656//656 -f 689//689 656//656 690//690 -f 624//624 635//635 625//625 -f 625//625 635//635 657//657 -f 625//625 657//657 691//691 -f 691//691 657//657 658//658 -f 691//691 658//658 692//692 -f 692//692 658//658 659//659 -f 692//692 659//659 693//693 -f 693//693 659//659 660//660 -f 693//693 660//660 694//694 -f 694//694 660//660 661//661 -f 694//694 661//661 695//695 -f 695//695 661//661 662//662 -f 695//695 662//662 696//696 -f 696//696 662//662 663//663 -f 696//696 663//663 697//697 -f 621//621 633//633 622//622 -f 622//622 633//633 664//664 -f 622//622 664//664 698//698 -f 698//698 664//664 665//665 -f 698//698 665//665 699//699 -f 699//699 665//665 666//666 -f 699//699 666//666 700//700 -f 700//700 666//666 667//667 -f 700//700 667//667 701//701 -f 701//701 667//667 668//668 -f 701//701 668//668 702//702 -f 702//702 668//668 669//669 -f 702//702 669//669 703//703 -f 703//703 669//669 670//670 -f 703//703 670//670 704//704 -f 642//642 676//676 641//641 -f 641//641 676//676 705//705 -f 641//641 705//705 674//674 -f 674//674 705//705 706//706 -f 674//674 706//706 673//673 -f 673//673 706//706 707//707 -f 673//673 707//707 671//671 -f 671//671 707//707 708//708 -f 671//671 708//708 672//672 -f 675//675 709//709 710//710 -f 629//629 631//631 711//711 -f 711//711 631//631 677//677 -f 711//711 677//677 712//712 -f 712//712 677//677 678//678 -f 712//712 678//678 713//713 -f 713//713 678//678 679//679 -f 713//713 679//679 714//714 -f 714//714 679//679 680//680 -f 714//714 680//680 715//715 -f 715//715 680//680 681//681 -f 715//715 681//681 716//716 -f 716//716 681//681 682//682 -f 716//716 682//682 717//717 -f 717//717 682//682 683//683 -f 717//717 683//683 619//619 -f 626//626 628//628 718//718 -f 718//718 628//628 684//684 -f 718//718 684//684 719//719 -f 719//719 684//684 685//685 -f 719//719 685//685 720//720 -f 720//720 685//685 686//686 -f 720//720 686//686 721//721 -f 721//721 686//686 687//687 -f 721//721 687//687 722//722 -f 722//722 687//687 688//688 -f 722//722 688//688 723//723 -f 723//723 688//688 689//689 -f 723//723 689//689 724//724 -f 724//724 689//689 690//690 -f 724//724 690//690 616//616 -f 623//623 625//625 725//725 -f 725//725 625//625 691//691 -f 725//725 691//691 726//726 -f 726//726 691//691 692//692 -f 726//726 692//692 727//727 -f 727//727 692//692 693//693 -f 727//727 693//693 728//728 -f 728//728 693//693 694//694 -f 728//728 694//694 729//729 -f 729//729 694//694 695//695 -f 729//729 695//695 730//730 -f 730//730 695//695 696//696 -f 730//730 696//696 731//731 -f 731//731 696//696 697//697 -f 731//731 697//697 613//613 -f 620//620 622//622 732//732 -f 732//732 622//622 698//698 -f 732//732 698//698 733//733 -f 733//733 698//698 699//699 -f 733//733 699//699 734//734 -f 734//734 699//699 700//700 -f 734//734 700//700 735//735 -f 735//735 700//700 701//701 -f 735//735 701//701 736//736 -f 736//736 701//701 702//702 -f 736//736 702//702 737//737 -f 737//737 702//702 703//703 -f 737//737 703//703 738//738 -f 738//738 703//703 704//704 -f 738//738 704//704 610//610 -f 569//569 568//568 640//640 -f 640//640 568//568 739//739 -f 640//640 739//739 740//740 -f 740//740 739//739 741//741 -f 740//740 741//741 742//742 -f 742//742 741//741 607//607 -f 675//675 710//710 676//676 -f 676//676 710//710 743//743 -f 676//676 743//743 705//705 -f 705//705 743//743 744//744 -f 705//705 744//744 706//706 -f 706//706 744//744 745//745 -f 706//706 745//745 707//707 -f 707//707 745//745 746//746 -f 707//707 746//746 708//708 -f 747//747 710//710 748//748 -f 748//748 710//710 709//709 -f 748//748 709//709 749//749 -f 750//750 749//749 751//751 -f 751//751 749//749 709//709 -f 751//751 709//709 752//752 -f 752//752 709//709 675//675 -f 752//752 675//675 753//753 -f 753//753 675//675 642//642 -f 753//753 642//642 556//556 -f 556//556 642//642 557//557 -f 556//556 555//555 753//753 -f 753//753 555//555 638//638 -f 753//753 638//638 752//752 -f 752//752 638//638 630//630 -f 752//752 630//630 751//751 -f 751//751 630//630 629//629 -f 751//751 629//629 750//750 -f 750//750 629//629 754//754 -f 755//755 756//756 713//713 -f 713//713 756//756 757//757 -f 713//713 757//757 712//712 -f 712//712 757//757 758//758 -f 712//712 758//758 711//711 -f 711//711 758//758 759//759 -f 711//711 759//759 629//629 -f 629//629 759//759 760//760 -f 629//629 760//760 754//754 -f 755//755 713//713 761//761 -f 761//761 713//713 714//714 -f 761//761 714//714 762//762 -f 762//762 714//714 715//715 -f 762//762 715//715 763//763 -f 763//763 715//715 716//716 -f 763//763 716//716 764//764 -f 764//764 716//716 717//717 -f 764//764 717//717 765//765 -f 619//619 618//618 717//717 -f 717//717 618//618 766//766 -f 717//717 766//766 765//765 -f 767//767 617//617 768//768 -f 768//768 617//617 619//619 -f 768//768 619//619 769//769 -f 769//769 619//619 683//683 -f 769//769 683//683 770//770 -f 770//770 683//683 649//649 -f 770//770 649//649 541//541 -f 541//541 649//649 542//542 -f 541//541 540//540 770//770 -f 770//770 540//540 636//636 -f 770//770 636//636 769//769 -f 769//769 636//636 627//627 -f 769//769 627//627 768//768 -f 768//768 627//627 626//626 -f 768//768 626//626 767//767 -f 767//767 626//626 771//771 -f 772//772 773//773 720//720 -f 720//720 773//773 774//774 -f 720//720 774//774 719//719 -f 719//719 774//774 775//775 -f 719//719 775//775 718//718 -f 718//718 775//775 776//776 -f 718//718 776//776 626//626 -f 626//626 776//776 777//777 -f 626//626 777//777 771//771 -f 772//772 720//720 778//778 -f 778//778 720//720 721//721 -f 778//778 721//721 779//779 -f 779//779 721//721 722//722 -f 779//779 722//722 780//780 -f 780//780 722//722 723//723 -f 780//780 723//723 781//781 -f 781//781 723//723 724//724 -f 781//781 724//724 782//782 -f 616//616 615//615 724//724 -f 724//724 615//615 783//783 -f 724//724 783//783 782//782 -f 784//784 614//614 785//785 -f 785//785 614//614 616//616 -f 785//785 616//616 786//786 -f 786//786 616//616 690//690 -f 786//786 690//690 787//787 -f 787//787 690//690 656//656 -f 787//787 656//656 604//604 -f 604//604 656//656 525//525 -f 604//604 603//603 787//787 -f 787//787 603//603 634//634 -f 787//787 634//634 786//786 -f 786//786 634//634 624//624 -f 786//786 624//624 785//785 -f 785//785 624//624 623//623 -f 785//785 623//623 784//784 -f 784//784 623//623 788//788 -f 789//789 790//790 727//727 -f 727//727 790//790 791//791 -f 727//727 791//791 726//726 -f 726//726 791//791 792//792 -f 726//726 792//792 725//725 -f 725//725 792//792 793//793 -f 725//725 793//793 623//623 -f 623//623 793//793 794//794 -f 623//623 794//794 788//788 -f 789//789 727//727 795//795 -f 795//795 727//727 728//728 -f 795//795 728//728 796//796 -f 796//796 728//728 729//729 -f 796//796 729//729 797//797 -f 797//797 729//729 730//730 -f 797//797 730//730 798//798 -f 798//798 730//730 731//731 -f 798//798 731//731 799//799 -f 613//613 612//612 731//731 -f 731//731 612//612 800//800 -f 731//731 800//800 799//799 -f 801//801 611//611 802//802 -f 802//802 611//611 613//613 -f 802//802 613//613 803//803 -f 803//803 613//613 697//697 -f 803//803 697//697 804//804 -f 804//804 697//697 663//663 -f 804//804 663//663 588//588 -f 588//588 663//663 589//589 -f 588//588 587//587 804//804 -f 804//804 587//587 632//632 -f 804//804 632//632 803//803 -f 803//803 632//632 621//621 -f 803//803 621//621 802//802 -f 802//802 621//621 620//620 -f 802//802 620//620 801//801 -f 801//801 620//620 805//805 -f 806//806 807//807 734//734 -f 734//734 807//807 808//808 -f 734//734 808//808 733//733 -f 733//733 808//808 809//809 -f 733//733 809//809 732//732 -f 732//732 809//809 810//810 -f 732//732 810//810 620//620 -f 620//620 810//810 811//811 -f 620//620 811//811 805//805 -f 806//806 734//734 812//812 -f 812//812 734//734 735//735 -f 812//812 735//735 813//813 -f 813//813 735//735 736//736 -f 813//813 736//736 814//814 -f 814//814 736//736 737//737 -f 814//814 737//737 815//815 -f 815//815 737//737 738//738 -f 815//815 738//738 816//816 -f 610//610 609//609 738//738 -f 738//738 609//609 817//817 -f 738//738 817//817 816//816 -f 818//818 608//608 819//819 -f 819//819 608//608 610//610 -f 819//819 610//610 820//820 -f 820//820 610//610 704//704 -f 820//820 704//704 821//821 -f 821//821 704//704 670//670 -f 821//821 670//670 572//572 -f 572//572 670//670 573//573 -f 572//572 571//571 821//821 -f 821//821 571//571 640//640 -f 821//821 640//640 820//820 -f 820//820 640//640 740//740 -f 820//820 740//740 819//819 -f 819//819 740//740 742//742 -f 819//819 742//742 818//818 -f 818//818 742//742 822//822 -f 607//607 606//606 742//742 -f 742//742 606//606 823//823 -f 742//742 823//823 822//822 -f 824//824 605//605 825//825 -f 825//825 605//605 607//607 -f 825//825 607//607 826//826 -f 826//826 607//607 741//741 -f 826//826 741//741 827//827 -f 827//827 741//741 739//739 -f 827//827 739//739 567//567 -f 567//567 739//739 568//568 -f 567//567 566//566 827//827 -f 827//827 566//566 672//672 -f 827//827 672//672 826//826 -f 826//826 672//672 708//708 -f 826//826 708//708 825//825 -f 825//825 708//708 746//746 -f 825//825 746//746 824//824 -f 824//824 746//746 828//828 -f 747//747 829//829 710//710 -f 710//710 829//829 830//830 -f 710//710 830//830 743//743 -f 743//743 830//830 831//831 -f 743//743 831//831 744//744 -f 744//744 831//831 832//832 -f 744//744 832//832 745//745 -f 745//745 832//832 833//833 -f 745//745 833//833 746//746 -f 746//746 833//833 834//834 -f 746//746 834//834 828//828 -f 835//835 750//750 836//836 -f 836//836 750//750 754//754 -f 836//836 754//754 837//837 -f 837//837 754//754 760//760 -f 837//837 760//760 838//838 -f 838//838 760//760 759//759 -f 838//838 759//759 839//839 -f 839//839 759//759 758//758 -f 839//839 758//758 840//840 -f 771//771 841//841 842//842 -f 758//758 757//757 840//840 -f 840//840 757//757 756//756 -f 840//840 756//756 843//843 -f 843//843 756//756 755//755 -f 843//843 755//755 844//844 -f 844//844 755//755 761//761 -f 844//844 761//761 845//845 -f 845//845 761//761 762//762 -f 845//845 762//762 846//846 -f 846//846 762//762 763//763 -f 846//846 763//763 847//847 -f 847//847 763//763 764//764 -f 847//847 764//764 848//848 -f 848//848 764//764 765//765 -f 848//848 765//765 849//849 -f 849//849 765//765 766//766 -f 849//849 766//766 850//850 -f 850//850 766//766 618//618 -f 850//850 618//618 851//851 -f 851//851 618//618 617//617 -f 851//851 617//617 842//842 -f 842//842 617//617 767//767 -f 842//842 767//767 771//771 -f 771//771 777//777 841//841 -f 841//841 777//777 776//776 -f 841//841 776//776 852//852 -f 852//852 776//776 775//775 -f 852//852 775//775 853//853 -f 853//853 775//775 774//774 -f 853//853 774//774 854//854 -f 854//854 774//774 773//773 -f 854//854 773//773 855//855 -f 855//855 773//773 772//772 -f 855//855 772//772 856//856 -f 856//856 772//772 778//778 -f 856//856 778//778 857//857 -f 857//857 778//778 779//779 -f 857//857 779//779 858//858 -f 858//858 779//779 780//780 -f 858//858 780//780 859//859 -f 859//859 780//780 781//781 -f 859//859 781//781 860//860 -f 860//860 781//781 782//782 -f 860//860 782//782 861//861 -f 782//782 783//783 861//861 -f 861//861 783//783 615//615 -f 861//861 615//615 862//862 -f 862//862 615//615 614//614 -f 862//862 614//614 863//863 -f 863//863 614//614 784//784 -f 863//863 784//784 864//864 -f 864//864 784//784 788//788 -f 864//864 788//788 865//865 -f 865//865 788//788 794//794 -f 865//865 794//794 866//866 -f 866//866 794//794 793//793 -f 866//866 793//793 867//867 -f 867//867 793//793 792//792 -f 867//867 792//792 868//868 -f 792//792 791//791 868//868 -f 868//868 791//791 790//790 -f 868//868 790//790 869//869 -f 869//869 790//790 789//789 -f 869//869 789//789 870//870 -f 870//870 789//789 795//795 -f 870//870 795//795 871//871 -f 795//795 796//796 871//871 -f 871//871 796//796 797//797 -f 871//871 797//797 872//872 -f 872//872 797//797 798//798 -f 872//872 798//798 873//873 -f 873//873 798//798 874//874 -f 874//874 798//798 799//799 -f 874//874 799//799 875//875 -f 875//875 799//799 800//800 -f 875//875 800//800 876//876 -f 876//876 800//800 612//612 -f 876//876 612//612 877//877 -f 877//877 612//612 611//611 -f 877//877 611//611 878//878 -f 611//611 801//801 878//878 -f 878//878 801//801 805//805 -f 878//878 805//805 879//879 -f 879//879 805//805 811//811 -f 879//879 811//811 880//880 -f 880//880 811//811 810//810 -f 880//880 810//810 881//881 -f 810//810 809//809 881//881 -f 881//881 809//809 808//808 -f 881//881 808//808 882//882 -f 882//882 808//808 807//807 -f 882//882 807//807 883//883 -f 883//883 807//807 806//806 -f 883//883 806//806 884//884 -f 884//884 806//806 812//812 -f 884//884 812//812 885//885 -f 885//885 812//812 813//813 -f 885//885 813//813 886//886 -f 886//886 813//813 814//814 -f 886//886 814//814 887//887 -f 887//887 814//814 815//815 -f 887//887 815//815 888//888 -f 888//888 815//815 816//816 -f 888//888 816//816 889//889 -f 889//889 816//816 817//817 -f 889//889 817//817 890//890 -f 890//890 817//817 609//609 -f 890//890 609//609 891//891 -f 609//609 608//608 891//891 -f 891//891 608//608 818//818 -f 891//891 818//818 892//892 -f 892//892 818//818 822//822 -f 892//892 822//822 893//893 -f 893//893 822//822 823//823 -f 893//893 823//823 894//894 -f 894//894 823//823 606//606 -f 894//894 606//606 895//895 -f 895//895 606//606 605//605 -f 895//895 605//605 896//896 -f 605//605 824//824 896//896 -f 896//896 824//824 828//828 -f 896//896 828//828 897//897 -f 897//897 828//828 834//834 -f 897//897 834//834 898//898 -f 898//898 834//834 833//833 -f 898//898 833//833 899//899 -f 899//899 833//833 832//832 -f 899//899 832//832 900//900 -f 900//900 832//832 831//831 -f 900//900 831//831 901//901 -f 901//901 831//831 830//830 -f 901//901 830//830 902//902 -f 902//902 830//830 829//829 -f 902//902 829//829 903//903 -f 903//903 829//829 747//747 -f 903//903 747//747 904//904 -f 904//904 747//747 748//748 -f 904//904 748//748 835//835 -f 835//835 748//748 749//749 -f 835//835 749//749 750//750 -f 905//905 906//906 907//907 -f 908//908 909//909 910//910 -f 911//911 912//912 913//913 -f 914//914 915//915 916//916 -f 917//917 918//918 919//919 -f 920//920 921//921 922//922 -f 923//923 924//924 925//925 -f 897//897 898//898 905//905 -f 895//895 896//896 926//926 -f 893//893 894//894 927//927 -f 887//887 888//888 908//908 -f 885//885 886//886 928//928 -f 883//883 884//884 929//929 -f 877//877 878//878 911//911 -f 875//875 876//876 930//930 -f 873//873 874//874 931//931 -f 867//867 868//868 914//914 -f 865//865 866//866 932//932 -f 863//863 864//864 933//933 -f 857//857 858//858 917//917 -f 855//855 856//856 934//934 -f 853//853 854//854 935//935 -f 849//849 850//850 920//920 -f 847//847 848//848 936//936 -f 845//845 846//846 937//937 -f 837//837 838//838 923//923 -f 835//835 836//836 938//938 -f 903//903 904//904 939//939 -f 901//901 902//902 940//940 -f 940//940 902//902 903//903 -f 923//923 838//838 924//924 -f 924//924 838//838 839//839 -f 924//924 839//839 840//840 -f 843//843 844//844 941//941 -f 941//941 844//844 845//845 -f 920//920 850//850 921//921 -f 921//921 850//850 851//851 -f 921//921 851//851 842//842 -f 841//841 852//852 942//942 -f 942//942 852//852 853//853 -f 917//917 858//858 918//918 -f 918//918 858//858 859//859 -f 918//918 859//859 860//860 -f 861//861 862//862 943//943 -f 943//943 862//862 863//863 -f 914//914 868//868 915//915 -f 915//915 868//868 869//869 -f 915//915 869//869 870//870 -f 871//871 872//872 944//944 -f 944//944 872//872 873//873 -f 911//911 878//878 912//912 -f 912//912 878//878 879//879 -f 912//912 879//879 880//880 -f 881//881 882//882 945//945 -f 945//945 882//882 883//883 -f 908//908 888//888 909//909 -f 909//909 888//888 889//889 -f 909//909 889//889 890//890 -f 891//891 892//892 946//946 -f 946//946 892//892 893//893 -f 905//905 898//898 906//906 -f 906//906 898//898 899//899 -f 906//906 899//899 900//900 -f 947//947 948//948 939//939 -f 949//949 925//925 950//950 -f 950//950 925//925 924//924 -f 950//950 924//924 951//951 -f 951//951 924//924 840//840 -f 951//951 840//840 843//843 -f 952//952 953//953 937//937 -f 954//954 922//922 955//955 -f 955//955 922//922 921//921 -f 955//955 921//921 956//956 -f 956//956 921//921 842//842 -f 956//956 842//842 841//841 -f 957//957 958//958 935//935 -f 959//959 919//919 960//960 -f 960//960 919//919 918//918 -f 960//960 918//918 961//961 -f 961//961 918//918 860//860 -f 961//961 860//860 861//861 -f 962//962 963//963 933//933 -f 964//964 916//916 965//965 -f 965//965 916//916 915//915 -f 965//965 915//915 966//966 -f 966//966 915//915 870//870 -f 966//966 870//870 871//871 -f 967//967 968//968 931//931 -f 969//969 913//913 970//970 -f 970//970 913//913 912//912 -f 970//970 912//912 971//971 -f 971//971 912//912 880//880 -f 971//971 880//880 881//881 -f 972//972 973//973 929//929 -f 974//974 910//910 975//975 -f 975//975 910//910 909//909 -f 975//975 909//909 976//976 -f 976//976 909//909 890//890 -f 976//976 890//890 891//891 -f 977//977 978//978 927//927 -f 979//979 907//907 980//980 -f 980//980 907//907 906//906 -f 980//980 906//906 981//981 -f 981//981 906//906 900//900 -f 981//981 900//900 901//901 -f 982//982 948//948 983//983 -f 983//983 948//948 947//947 -f 983//983 947//947 984//984 -f 985//985 953//953 986//986 -f 986//986 953//953 952//952 -f 986//986 952//952 987//987 -f 988//988 958//958 989//989 -f 989//989 958//958 957//957 -f 989//989 957//957 990//990 -f 991//991 963//963 992//992 -f 992//992 963//963 962//962 -f 992//992 962//962 993//993 -f 994//994 968//968 995//995 -f 995//995 968//968 967//967 -f 995//995 967//967 996//996 -f 997//997 973//973 998//998 -f 998//998 973//973 972//972 -f 998//998 972//972 999//999 -f 1000//1000 978//978 1001//1001 -f 1001//1001 978//978 977//977 -f 1001//1001 977//977 1002//1002 -f 1003//1003 1004//1004 1005//1005 -f 901//901 940//940 981//981 -f 981//981 940//940 1006//1006 -f 981//981 1006//1006 980//980 -f 980//980 1006//1006 1003//1003 -f 980//980 1003//1003 979//979 -f 979//979 1003//1003 1005//1005 -f 979//979 1005//1005 1007//1007 -f 903//903 939//939 940//940 -f 940//940 939//939 948//948 -f 940//940 948//948 1006//1006 -f 1006//1006 948//948 982//982 -f 1006//1006 982//982 1003//1003 -f 1003//1003 982//982 1008//1008 -f 1003//1003 1008//1008 1004//1004 -f 1009//1009 1010//1010 1011//1011 -f 1011//1011 1010//1010 984//984 -f 1011//1011 984//984 1012//1012 -f 1012//1012 984//984 947//947 -f 1012//1012 947//947 938//938 -f 938//938 947//947 939//939 -f 938//938 939//939 835//835 -f 835//835 939//939 904//904 -f 1010//1010 1013//1013 984//984 -f 984//984 1013//1013 1014//1014 -f 984//984 1014//1014 983//983 -f 983//983 1014//1014 1015//1015 -f 983//983 1015//1015 982//982 -f 982//982 1015//1015 1016//1016 -f 982//982 1016//1016 1008//1008 -f 836//836 837//837 938//938 -f 938//938 837//837 923//923 -f 938//938 923//923 1012//1012 -f 1012//1012 923//923 925//925 -f 1012//1012 925//925 1011//1011 -f 1011//1011 925//925 949//949 -f 1011//1011 949//949 1009//1009 -f 1009//1009 949//949 1017//1017 -f 1018//1018 1019//1019 1020//1020 -f 843//843 941//941 951//951 -f 951//951 941//941 1021//1021 -f 951//951 1021//1021 950//950 -f 950//950 1021//1021 1018//1018 -f 950//950 1018//1018 949//949 -f 949//949 1018//1018 1020//1020 -f 949//949 1020//1020 1017//1017 -f 845//845 937//937 941//941 -f 941//941 937//937 953//953 -f 941//941 953//953 1021//1021 -f 1021//1021 953//953 985//985 -f 1021//1021 985//985 1018//1018 -f 1018//1018 985//985 1022//1022 -f 1018//1018 1022//1022 1019//1019 -f 1023//1023 1024//1024 1025//1025 -f 1025//1025 1024//1024 987//987 -f 1025//1025 987//987 1026//1026 -f 1026//1026 987//987 952//952 -f 1026//1026 952//952 936//936 -f 936//936 952//952 937//937 -f 936//936 937//937 847//847 -f 847//847 937//937 846//846 -f 1024//1024 1027//1027 987//987 -f 987//987 1027//1027 1028//1028 -f 987//987 1028//1028 986//986 -f 986//986 1028//1028 1029//1029 -f 986//986 1029//1029 985//985 -f 985//985 1029//1029 1030//1030 -f 985//985 1030//1030 1022//1022 -f 848//848 849//849 936//936 -f 936//936 849//849 920//920 -f 936//936 920//920 1026//1026 -f 1026//1026 920//920 922//922 -f 1026//1026 922//922 1025//1025 -f 1025//1025 922//922 954//954 -f 1025//1025 954//954 1023//1023 -f 1023//1023 954//954 1031//1031 -f 1032//1032 1033//1033 1034//1034 -f 841//841 942//942 956//956 -f 956//956 942//942 1035//1035 -f 956//956 1035//1035 955//955 -f 955//955 1035//1035 1032//1032 -f 955//955 1032//1032 954//954 -f 954//954 1032//1032 1034//1034 -f 954//954 1034//1034 1031//1031 -f 853//853 935//935 942//942 -f 942//942 935//935 958//958 -f 942//942 958//958 1035//1035 -f 1035//1035 958//958 988//988 -f 1035//1035 988//988 1032//1032 -f 1032//1032 988//988 1036//1036 -f 1032//1032 1036//1036 1033//1033 -f 1037//1037 1038//1038 1039//1039 -f 1039//1039 1038//1038 990//990 -f 1039//1039 990//990 1040//1040 -f 1040//1040 990//990 957//957 -f 1040//1040 957//957 934//934 -f 934//934 957//957 935//935 -f 934//934 935//935 855//855 -f 855//855 935//935 854//854 -f 1038//1038 1041//1041 990//990 -f 990//990 1041//1041 1042//1042 -f 990//990 1042//1042 989//989 -f 989//989 1042//1042 1043//1043 -f 989//989 1043//1043 988//988 -f 988//988 1043//1043 1044//1044 -f 988//988 1044//1044 1036//1036 -f 856//856 857//857 934//934 -f 934//934 857//857 917//917 -f 934//934 917//917 1040//1040 -f 1040//1040 917//917 919//919 -f 1040//1040 919//919 1039//1039 -f 1039//1039 919//919 959//959 -f 1039//1039 959//959 1037//1037 -f 1037//1037 959//959 1045//1045 -f 1046//1046 1047//1047 1048//1048 -f 861//861 943//943 961//961 -f 961//961 943//943 1049//1049 -f 961//961 1049//1049 960//960 -f 960//960 1049//1049 1046//1046 -f 960//960 1046//1046 959//959 -f 959//959 1046//1046 1048//1048 -f 959//959 1048//1048 1045//1045 -f 863//863 933//933 943//943 -f 943//943 933//933 963//963 -f 943//943 963//963 1049//1049 -f 1049//1049 963//963 991//991 -f 1049//1049 991//991 1046//1046 -f 1046//1046 991//991 1050//1050 -f 1046//1046 1050//1050 1047//1047 -f 1051//1051 1052//1052 1053//1053 -f 1053//1053 1052//1052 993//993 -f 1053//1053 993//993 1054//1054 -f 1054//1054 993//993 962//962 -f 1054//1054 962//962 932//932 -f 932//932 962//962 933//933 -f 932//932 933//933 865//865 -f 865//865 933//933 864//864 -f 1052//1052 1055//1055 993//993 -f 993//993 1055//1055 1056//1056 -f 993//993 1056//1056 992//992 -f 992//992 1056//1056 1057//1057 -f 992//992 1057//1057 991//991 -f 991//991 1057//1057 1058//1058 -f 991//991 1058//1058 1050//1050 -f 866//866 867//867 932//932 -f 932//932 867//867 914//914 -f 932//932 914//914 1054//1054 -f 1054//1054 914//914 916//916 -f 1054//1054 916//916 1053//1053 -f 1053//1053 916//916 964//964 -f 1053//1053 964//964 1051//1051 -f 1051//1051 964//964 1059//1059 -f 1060//1060 1061//1061 1062//1062 -f 871//871 944//944 966//966 -f 966//966 944//944 1063//1063 -f 966//966 1063//1063 965//965 -f 965//965 1063//1063 1060//1060 -f 965//965 1060//1060 964//964 -f 964//964 1060//1060 1062//1062 -f 964//964 1062//1062 1059//1059 -f 873//873 931//931 944//944 -f 944//944 931//931 968//968 -f 944//944 968//968 1063//1063 -f 1063//1063 968//968 994//994 -f 1063//1063 994//994 1060//1060 -f 1060//1060 994//994 1064//1064 -f 1060//1060 1064//1064 1061//1061 -f 1065//1065 1066//1066 1067//1067 -f 1067//1067 1066//1066 996//996 -f 1067//1067 996//996 1068//1068 -f 1068//1068 996//996 967//967 -f 1068//1068 967//967 930//930 -f 930//930 967//967 931//931 -f 930//930 931//931 875//875 -f 875//875 931//931 874//874 -f 1066//1066 1069//1069 996//996 -f 996//996 1069//1069 1070//1070 -f 996//996 1070//1070 995//995 -f 995//995 1070//1070 1071//1071 -f 995//995 1071//1071 994//994 -f 994//994 1071//1071 1072//1072 -f 994//994 1072//1072 1064//1064 -f 876//876 877//877 930//930 -f 930//930 877//877 911//911 -f 930//930 911//911 1068//1068 -f 1068//1068 911//911 913//913 -f 1068//1068 913//913 1067//1067 -f 1067//1067 913//913 969//969 -f 1067//1067 969//969 1065//1065 -f 1065//1065 969//969 1073//1073 -f 1074//1074 1075//1075 1076//1076 -f 881//881 945//945 971//971 -f 971//971 945//945 1077//1077 -f 971//971 1077//1077 970//970 -f 970//970 1077//1077 1074//1074 -f 970//970 1074//1074 969//969 -f 969//969 1074//1074 1076//1076 -f 969//969 1076//1076 1073//1073 -f 883//883 929//929 945//945 -f 945//945 929//929 973//973 -f 945//945 973//973 1077//1077 -f 1077//1077 973//973 997//997 -f 1077//1077 997//997 1074//1074 -f 1074//1074 997//997 1078//1078 -f 1074//1074 1078//1078 1075//1075 -f 1079//1079 1080//1080 1081//1081 -f 1081//1081 1080//1080 999//999 -f 1081//1081 999//999 1082//1082 -f 1082//1082 999//999 972//972 -f 1082//1082 972//972 928//928 -f 928//928 972//972 929//929 -f 928//928 929//929 885//885 -f 885//885 929//929 884//884 -f 1080//1080 1083//1083 999//999 -f 999//999 1083//1083 1084//1084 -f 999//999 1084//1084 998//998 -f 998//998 1084//1084 1085//1085 -f 998//998 1085//1085 997//997 -f 997//997 1085//1085 1086//1086 -f 997//997 1086//1086 1078//1078 -f 886//886 887//887 928//928 -f 928//928 887//887 908//908 -f 928//928 908//908 1082//1082 -f 1082//1082 908//908 910//910 -f 1082//1082 910//910 1081//1081 -f 1081//1081 910//910 974//974 -f 1081//1081 974//974 1079//1079 -f 1079//1079 974//974 1087//1087 -f 1088//1088 1089//1089 1090//1090 -f 891//891 946//946 976//976 -f 976//976 946//946 1091//1091 -f 976//976 1091//1091 975//975 -f 975//975 1091//1091 1088//1088 -f 975//975 1088//1088 974//974 -f 974//974 1088//1088 1090//1090 -f 974//974 1090//1090 1087//1087 -f 893//893 927//927 946//946 -f 946//946 927//927 978//978 -f 946//946 978//978 1091//1091 -f 1091//1091 978//978 1000//1000 -f 1091//1091 1000//1000 1088//1088 -f 1088//1088 1000//1000 1092//1092 -f 1088//1088 1092//1092 1089//1089 -f 1093//1093 1094//1094 1095//1095 -f 1095//1095 1094//1094 1002//1002 -f 1095//1095 1002//1002 1096//1096 -f 1096//1096 1002//1002 977//977 -f 1096//1096 977//977 926//926 -f 926//926 977//977 927//927 -f 926//926 927//927 895//895 -f 895//895 927//927 894//894 -f 1094//1094 1097//1097 1002//1002 -f 1002//1002 1097//1097 1098//1098 -f 1002//1002 1098//1098 1001//1001 -f 1001//1001 1098//1098 1099//1099 -f 1001//1001 1099//1099 1000//1000 -f 1000//1000 1099//1099 1100//1100 -f 1000//1000 1100//1100 1092//1092 -f 896//896 897//897 926//926 -f 926//926 897//897 905//905 -f 926//926 905//905 1096//1096 -f 1096//1096 905//905 907//907 -f 1096//1096 907//907 1095//1095 -f 1095//1095 907//907 979//979 -f 1095//1095 979//979 1093//1093 -f 1093//1093 979//979 1007//1007 -f 1057//1057 1101//1101 1058//1058 -f 1058//1058 1101//1101 1102//1102 -f 1058//1058 1102//1102 1050//1050 -f 1050//1050 1102//1102 1103//1103 -f 1050//1050 1103//1103 1047//1047 -f 1047//1047 1103//1103 1104//1104 -f 1047//1047 1104//1104 1048//1048 -f 1048//1048 1104//1104 1105//1105 -f 1048//1048 1105//1105 1045//1045 -f 1045//1045 1105//1105 1106//1106 -f 1045//1045 1106//1106 1037//1037 -f 1037//1037 1106//1106 1107//1107 -f 1037//1037 1107//1107 1038//1038 -f 1107//1107 1108//1108 1038//1038 -f 1038//1038 1108//1108 1109//1109 -f 1038//1038 1109//1109 1041//1041 -f 1041//1041 1109//1109 1110//1110 -f 1041//1041 1110//1110 1042//1042 -f 1042//1042 1110//1110 1111//1111 -f 1042//1042 1111//1111 1043//1043 -f 1111//1111 1112//1112 1043//1043 -f 1043//1043 1112//1112 1113//1113 -f 1043//1043 1113//1113 1044//1044 -f 1044//1044 1113//1113 1114//1114 -f 1044//1044 1114//1114 1036//1036 -f 1036//1036 1114//1114 1115//1115 -f 1036//1036 1115//1115 1033//1033 -f 1033//1033 1115//1115 1116//1116 -f 1033//1033 1116//1116 1034//1034 -f 1034//1034 1116//1116 1117//1117 -f 1034//1034 1117//1117 1031//1031 -f 1031//1031 1117//1117 1118//1118 -f 1031//1031 1118//1118 1023//1023 -f 1023//1023 1118//1118 1119//1119 -f 1023//1023 1119//1119 1024//1024 -f 1119//1119 1120//1120 1024//1024 -f 1024//1024 1120//1120 1121//1121 -f 1024//1024 1121//1121 1027//1027 -f 1027//1027 1121//1121 1122//1122 -f 1027//1027 1122//1122 1028//1028 -f 1028//1028 1122//1122 1123//1123 -f 1028//1028 1123//1123 1029//1029 -f 1123//1123 1124//1124 1029//1029 -f 1029//1029 1124//1124 1125//1125 -f 1029//1029 1125//1125 1030//1030 -f 1030//1030 1125//1125 1126//1126 -f 1030//1030 1126//1126 1022//1022 -f 1022//1022 1126//1126 1127//1127 -f 1022//1022 1127//1127 1019//1019 -f 1019//1019 1127//1127 1128//1128 -f 1019//1019 1128//1128 1020//1020 -f 1020//1020 1128//1128 1129//1129 -f 1020//1020 1129//1129 1017//1017 -f 1017//1017 1129//1129 1130//1130 -f 1017//1017 1130//1130 1009//1009 -f 1009//1009 1130//1130 1131//1131 -f 1009//1009 1131//1131 1010//1010 -f 1131//1131 1132//1132 1010//1010 -f 1010//1010 1132//1132 1133//1133 -f 1010//1010 1133//1133 1013//1013 -f 1013//1013 1133//1133 1134//1134 -f 1013//1013 1134//1134 1014//1014 -f 1014//1014 1134//1134 1135//1135 -f 1014//1014 1135//1135 1015//1015 -f 1135//1135 1136//1136 1015//1015 -f 1015//1015 1136//1136 1137//1137 -f 1015//1015 1137//1137 1016//1016 -f 1016//1016 1137//1137 1138//1138 -f 1016//1016 1138//1138 1008//1008 -f 1008//1008 1138//1138 1139//1139 -f 1008//1008 1139//1139 1004//1004 -f 1004//1004 1139//1139 1140//1140 -f 1004//1004 1140//1140 1005//1005 -f 1005//1005 1140//1140 1141//1141 -f 1005//1005 1141//1141 1007//1007 -f 1007//1007 1141//1141 1142//1142 -f 1007//1007 1142//1142 1093//1093 -f 1093//1093 1142//1142 1143//1143 -f 1093//1093 1143//1143 1094//1094 -f 1143//1143 1144//1144 1094//1094 -f 1094//1094 1144//1144 1145//1145 -f 1094//1094 1145//1145 1097//1097 -f 1097//1097 1145//1145 1146//1146 -f 1097//1097 1146//1146 1098//1098 -f 1098//1098 1146//1146 1147//1147 -f 1098//1098 1147//1147 1099//1099 -f 1147//1147 1148//1148 1099//1099 -f 1099//1099 1148//1148 1149//1149 -f 1099//1099 1149//1149 1100//1100 -f 1100//1100 1149//1149 1150//1150 -f 1100//1100 1150//1150 1092//1092 -f 1092//1092 1150//1150 1151//1151 -f 1092//1092 1151//1151 1089//1089 -f 1089//1089 1151//1151 1152//1152 -f 1089//1089 1152//1152 1090//1090 -f 1090//1090 1152//1152 1153//1153 -f 1090//1090 1153//1153 1087//1087 -f 1087//1087 1153//1153 1154//1154 -f 1087//1087 1154//1154 1079//1079 -f 1079//1079 1154//1154 1155//1155 -f 1079//1079 1155//1155 1080//1080 -f 1155//1155 1156//1156 1080//1080 -f 1080//1080 1156//1156 1157//1157 -f 1080//1080 1157//1157 1083//1083 -f 1083//1083 1157//1157 1158//1158 -f 1083//1083 1158//1158 1084//1084 -f 1084//1084 1158//1158 1159//1159 -f 1084//1084 1159//1159 1085//1085 -f 1159//1159 1160//1160 1085//1085 -f 1085//1085 1160//1160 1161//1161 -f 1085//1085 1161//1161 1086//1086 -f 1086//1086 1161//1161 1162//1162 -f 1086//1086 1162//1162 1078//1078 -f 1078//1078 1162//1162 1163//1163 -f 1078//1078 1163//1163 1075//1075 -f 1075//1075 1163//1163 1164//1164 -f 1075//1075 1164//1164 1076//1076 -f 1076//1076 1164//1164 1165//1165 -f 1076//1076 1165//1165 1073//1073 -f 1073//1073 1165//1165 1166//1166 -f 1073//1073 1166//1166 1065//1065 -f 1065//1065 1166//1166 1167//1167 -f 1065//1065 1167//1167 1066//1066 -f 1167//1167 1168//1168 1066//1066 -f 1066//1066 1168//1168 1169//1169 -f 1066//1066 1169//1169 1069//1069 -f 1069//1069 1169//1169 1170//1170 -f 1069//1069 1170//1170 1070//1070 -f 1070//1070 1170//1170 1171//1171 -f 1070//1070 1171//1171 1071//1071 -f 1171//1171 1172//1172 1071//1071 -f 1071//1071 1172//1172 1173//1173 -f 1071//1071 1173//1173 1072//1072 -f 1072//1072 1173//1173 1174//1174 -f 1072//1072 1174//1174 1064//1064 -f 1064//1064 1174//1174 1175//1175 -f 1064//1064 1175//1175 1061//1061 -f 1061//1061 1175//1175 1176//1176 -f 1061//1061 1176//1176 1062//1062 -f 1062//1062 1176//1176 1177//1177 -f 1062//1062 1177//1177 1059//1059 -f 1059//1059 1177//1177 1178//1178 -f 1059//1059 1178//1178 1051//1051 -f 1051//1051 1178//1178 1179//1179 -f 1051//1051 1179//1179 1052//1052 -f 1179//1179 1180//1180 1052//1052 -f 1052//1052 1180//1180 1181//1181 -f 1052//1052 1181//1181 1055//1055 -f 1055//1055 1181//1181 1182//1182 -f 1055//1055 1182//1182 1056//1056 -f 1056//1056 1182//1182 1183//1183 -f 1056//1056 1183//1183 1057//1057 -f 1057//1057 1183//1183 1184//1184 -f 1057//1057 1184//1184 1101//1101 -f 1141//1141 1185//1185 1186//1186 -f 1141//1141 1140//1140 1185//1185 -f 1185//1185 1140//1140 1139//1139 -f 1185//1185 1139//1139 1187//1187 -f 1187//1187 1139//1139 1138//1138 -f 1187//1187 1138//1138 1188//1188 -f 1138//1138 1137//1137 1188//1188 -f 1188//1188 1137//1137 1136//1136 -f 1188//1188 1136//1136 1189//1189 -f 1189//1189 1136//1136 1135//1135 -f 1189//1189 1135//1135 1190//1190 -f 1190//1190 1135//1135 1134//1134 -f 1129//1129 1191//1191 1192//1192 -f 1134//1134 1133//1133 1190//1190 -f 1190//1190 1133//1133 1132//1132 -f 1190//1190 1132//1132 1193//1193 -f 1193//1193 1132//1132 1131//1131 -f 1193//1193 1131//1131 1192//1192 -f 1192//1192 1131//1131 1130//1130 -f 1192//1192 1130//1130 1129//1129 -f 1129//1129 1128//1128 1191//1191 -f 1191//1191 1128//1128 1127//1127 -f 1191//1191 1127//1127 1194//1194 -f 1194//1194 1127//1127 1126//1126 -f 1194//1194 1126//1126 1195//1195 -f 1126//1126 1125//1125 1195//1195 -f 1195//1195 1125//1125 1124//1124 -f 1195//1195 1124//1124 1196//1196 -f 1196//1196 1124//1124 1123//1123 -f 1196//1196 1123//1123 1197//1197 -f 1197//1197 1123//1123 1122//1122 -f 1117//1117 1198//1198 1199//1199 -f 1122//1122 1121//1121 1197//1197 -f 1197//1197 1121//1121 1120//1120 -f 1197//1197 1120//1120 1200//1200 -f 1200//1200 1120//1120 1119//1119 -f 1200//1200 1119//1119 1199//1199 -f 1199//1199 1119//1119 1118//1118 -f 1199//1199 1118//1118 1117//1117 -f 1117//1117 1116//1116 1198//1198 -f 1198//1198 1116//1116 1115//1115 -f 1198//1198 1115//1115 1201//1201 -f 1201//1201 1115//1115 1114//1114 -f 1201//1201 1114//1114 1202//1202 -f 1114//1114 1113//1113 1202//1202 -f 1202//1202 1113//1113 1112//1112 -f 1202//1202 1112//1112 1203//1203 -f 1203//1203 1112//1112 1111//1111 -f 1203//1203 1111//1111 1204//1204 -f 1204//1204 1111//1111 1110//1110 -f 1105//1105 1205//1205 1206//1206 -f 1110//1110 1109//1109 1204//1204 -f 1204//1204 1109//1109 1108//1108 -f 1204//1204 1108//1108 1207//1207 -f 1207//1207 1108//1108 1107//1107 -f 1207//1207 1107//1107 1206//1206 -f 1206//1206 1107//1107 1106//1106 -f 1206//1206 1106//1106 1105//1105 -f 1105//1105 1104//1104 1205//1205 -f 1205//1205 1104//1104 1103//1103 -f 1205//1205 1103//1103 1208//1208 -f 1208//1208 1103//1103 1102//1102 -f 1208//1208 1102//1102 1209//1209 -f 1102//1102 1101//1101 1209//1209 -f 1209//1209 1101//1101 1184//1184 -f 1209//1209 1184//1184 1210//1210 -f 1210//1210 1184//1184 1183//1183 -f 1210//1210 1183//1183 1211//1211 -f 1211//1211 1183//1183 1182//1182 -f 1177//1177 1212//1212 1213//1213 -f 1182//1182 1181//1181 1211//1211 -f 1211//1211 1181//1181 1180//1180 -f 1211//1211 1180//1180 1214//1214 -f 1214//1214 1180//1180 1179//1179 -f 1214//1214 1179//1179 1213//1213 -f 1213//1213 1179//1179 1178//1178 -f 1213//1213 1178//1178 1177//1177 -f 1177//1177 1176//1176 1212//1212 -f 1212//1212 1176//1176 1175//1175 -f 1212//1212 1175//1175 1215//1215 -f 1215//1215 1175//1175 1174//1174 -f 1215//1215 1174//1174 1216//1216 -f 1174//1174 1173//1173 1216//1216 -f 1216//1216 1173//1173 1172//1172 -f 1216//1216 1172//1172 1217//1217 -f 1217//1217 1172//1172 1171//1171 -f 1217//1217 1171//1171 1218//1218 -f 1218//1218 1171//1171 1170//1170 -f 1165//1165 1219//1219 1220//1220 -f 1170//1170 1169//1169 1218//1218 -f 1218//1218 1169//1169 1168//1168 -f 1218//1218 1168//1168 1221//1221 -f 1221//1221 1168//1168 1167//1167 -f 1221//1221 1167//1167 1220//1220 -f 1220//1220 1167//1167 1166//1166 -f 1220//1220 1166//1166 1165//1165 -f 1165//1165 1164//1164 1219//1219 -f 1219//1219 1164//1164 1163//1163 -f 1219//1219 1163//1163 1222//1222 -f 1222//1222 1163//1163 1162//1162 -f 1222//1222 1162//1162 1223//1223 -f 1162//1162 1161//1161 1223//1223 -f 1223//1223 1161//1161 1160//1160 -f 1223//1223 1160//1160 1224//1224 -f 1224//1224 1160//1160 1159//1159 -f 1224//1224 1159//1159 1225//1225 -f 1225//1225 1159//1159 1158//1158 -f 1153//1153 1226//1226 1227//1227 -f 1158//1158 1157//1157 1225//1225 -f 1225//1225 1157//1157 1156//1156 -f 1225//1225 1156//1156 1228//1228 -f 1228//1228 1156//1156 1155//1155 -f 1228//1228 1155//1155 1227//1227 -f 1227//1227 1155//1155 1154//1154 -f 1227//1227 1154//1154 1153//1153 -f 1153//1153 1152//1152 1226//1226 -f 1226//1226 1152//1152 1151//1151 -f 1226//1226 1151//1151 1229//1229 -f 1229//1229 1151//1151 1150//1150 -f 1229//1229 1150//1150 1230//1230 -f 1150//1150 1149//1149 1230//1230 -f 1230//1230 1149//1149 1148//1148 -f 1230//1230 1148//1148 1231//1231 -f 1231//1231 1148//1148 1147//1147 -f 1231//1231 1147//1147 1232//1232 -f 1232//1232 1147//1147 1146//1146 -f 1146//1146 1145//1145 1232//1232 -f 1232//1232 1145//1145 1144//1144 -f 1232//1232 1144//1144 1233//1233 -f 1233//1233 1144//1144 1143//1143 -f 1233//1233 1143//1143 1186//1186 -f 1186//1186 1143//1143 1142//1142 -f 1186//1186 1142//1142 1141//1141 -f 1186//1186 1234//1234 1233//1233 -f 1233//1233 1234//1234 1235//1235 -f 1233//1233 1235//1235 1232//1232 -f 1232//1232 1235//1235 1236//1236 -f 1232//1232 1236//1236 1231//1231 -f 1231//1231 1236//1236 1237//1237 -f 1231//1231 1237//1237 1230//1230 -f 1230//1230 1237//1237 1238//1238 -f 1230//1230 1238//1238 1229//1229 -f 1229//1229 1238//1238 1239//1239 -f 1229//1229 1239//1239 1226//1226 -f 1226//1226 1239//1239 1240//1240 -f 1226//1226 1240//1240 1227//1227 -f 1227//1227 1240//1240 1241//1241 -f 1227//1227 1241//1241 1228//1228 -f 1228//1228 1241//1241 1242//1242 -f 1228//1228 1242//1242 1225//1225 -f 1225//1225 1242//1242 1243//1243 -f 1225//1225 1243//1243 1224//1224 -f 1224//1224 1243//1243 1244//1244 -f 1224//1224 1244//1244 1223//1223 -f 1223//1223 1244//1244 1245//1245 -f 1223//1223 1245//1245 1222//1222 -f 1222//1222 1245//1245 1246//1246 -f 1222//1222 1246//1246 1219//1219 -f 1219//1219 1246//1246 1247//1247 -f 1219//1219 1247//1247 1220//1220 -f 1220//1220 1247//1247 1248//1248 -f 1220//1220 1248//1248 1221//1221 -f 1221//1221 1248//1248 1249//1249 -f 1221//1221 1249//1249 1218//1218 -f 1218//1218 1249//1249 1250//1250 -f 1218//1218 1250//1250 1217//1217 -f 1217//1217 1250//1250 1251//1251 -f 1217//1217 1251//1251 1216//1216 -f 1216//1216 1251//1251 1252//1252 -f 1216//1216 1252//1252 1215//1215 -f 1215//1215 1252//1252 1253//1253 -f 1215//1215 1253//1253 1212//1212 -f 1212//1212 1253//1253 1254//1254 -f 1212//1212 1254//1254 1213//1213 -f 1213//1213 1254//1254 1255//1255 -f 1213//1213 1255//1255 1214//1214 -f 1214//1214 1255//1255 1256//1256 -f 1214//1214 1256//1256 1211//1211 -f 1211//1211 1256//1256 1257//1257 -f 1211//1211 1257//1257 1210//1210 -f 1210//1210 1257//1257 1258//1258 -f 1210//1210 1258//1258 1209//1209 -f 1209//1209 1258//1258 1259//1259 -f 1209//1209 1259//1259 1208//1208 -f 1208//1208 1259//1259 1260//1260 -f 1208//1208 1260//1260 1205//1205 -f 1205//1205 1260//1260 1261//1261 -f 1205//1205 1261//1261 1206//1206 -f 1206//1206 1261//1261 1262//1262 -f 1206//1206 1262//1262 1207//1207 -f 1207//1207 1262//1262 1263//1263 -f 1207//1207 1263//1263 1204//1204 -f 1204//1204 1263//1263 1264//1264 -f 1204//1204 1264//1264 1203//1203 -f 1203//1203 1264//1264 1265//1265 -f 1203//1203 1265//1265 1202//1202 -f 1202//1202 1265//1265 1266//1266 -f 1202//1202 1266//1266 1201//1201 -f 1201//1201 1266//1266 1267//1267 -f 1201//1201 1267//1267 1198//1198 -f 1198//1198 1267//1267 1268//1268 -f 1198//1198 1268//1268 1199//1199 -f 1199//1199 1268//1268 1269//1269 -f 1199//1199 1269//1269 1200//1200 -f 1200//1200 1269//1269 1270//1270 -f 1200//1200 1270//1270 1197//1197 -f 1197//1197 1270//1270 1271//1271 -f 1197//1197 1271//1271 1196//1196 -f 1196//1196 1271//1271 1272//1272 -f 1196//1196 1272//1272 1195//1195 -f 1195//1195 1272//1272 1273//1273 -f 1195//1195 1273//1273 1194//1194 -f 1194//1194 1273//1273 1274//1274 -f 1194//1194 1274//1274 1191//1191 -f 1191//1191 1274//1274 1275//1275 -f 1191//1191 1275//1275 1192//1192 -f 1192//1192 1275//1275 1276//1276 -f 1192//1192 1276//1276 1193//1193 -f 1193//1193 1276//1276 1277//1277 -f 1193//1193 1277//1277 1190//1190 -f 1190//1190 1277//1277 1278//1278 -f 1190//1190 1278//1278 1189//1189 -f 1189//1189 1278//1278 1279//1279 -f 1189//1189 1279//1279 1188//1188 -f 1188//1188 1279//1279 1280//1280 -f 1188//1188 1280//1280 1187//1187 -f 1187//1187 1280//1280 1281//1281 -f 1187//1187 1281//1281 1185//1185 -f 1185//1185 1281//1281 1282//1282 -f 1185//1185 1282//1282 1186//1186 -f 1186//1186 1282//1282 1234//1234 -f 1282//1282 1283//1283 1234//1234 -f 1234//1234 1283//1283 1284//1284 -f 1234//1234 1284//1284 1235//1235 -f 1235//1235 1284//1284 1285//1285 -f 1235//1235 1285//1285 1236//1236 -f 1236//1236 1285//1285 1286//1286 -f 1236//1236 1286//1286 1237//1237 -f 1237//1237 1286//1286 1287//1287 -f 1237//1237 1287//1287 1238//1238 -f 1238//1238 1287//1287 1288//1288 -f 1238//1238 1288//1288 1239//1239 -f 1239//1239 1288//1288 1289//1289 -f 1239//1239 1289//1289 1240//1240 -f 1240//1240 1289//1289 1290//1290 -f 1240//1240 1290//1290 1241//1241 -f 1241//1241 1290//1290 1291//1291 -f 1241//1241 1291//1291 1242//1242 -f 1242//1242 1291//1291 1292//1292 -f 1242//1242 1292//1292 1243//1243 -f 1243//1243 1292//1292 1293//1293 -f 1243//1243 1293//1293 1244//1244 -f 1244//1244 1293//1293 1294//1294 -f 1244//1244 1294//1294 1245//1245 -f 1245//1245 1294//1294 1295//1295 -f 1245//1245 1295//1295 1246//1246 -f 1246//1246 1295//1295 1296//1296 -f 1246//1246 1296//1296 1247//1247 -f 1247//1247 1296//1296 1297//1297 -f 1247//1247 1297//1297 1248//1248 -f 1248//1248 1297//1297 1298//1298 -f 1248//1248 1298//1298 1249//1249 -f 1249//1249 1298//1298 1299//1299 -f 1249//1249 1299//1299 1250//1250 -f 1250//1250 1299//1299 1300//1300 -f 1250//1250 1300//1300 1251//1251 -f 1251//1251 1300//1300 1301//1301 -f 1251//1251 1301//1301 1252//1252 -f 1252//1252 1301//1301 1302//1302 -f 1252//1252 1302//1302 1253//1253 -f 1253//1253 1302//1302 1303//1303 -f 1253//1253 1303//1303 1254//1254 -f 1254//1254 1303//1303 1304//1304 -f 1254//1254 1304//1304 1255//1255 -f 1255//1255 1304//1304 1305//1305 -f 1255//1255 1305//1305 1256//1256 -f 1256//1256 1305//1305 1306//1306 -f 1256//1256 1306//1306 1257//1257 -f 1257//1257 1306//1306 1307//1307 -f 1257//1257 1307//1307 1258//1258 -f 1258//1258 1307//1307 1308//1308 -f 1258//1258 1308//1308 1259//1259 -f 1259//1259 1308//1308 1309//1309 -f 1259//1259 1309//1309 1260//1260 -f 1260//1260 1309//1309 1310//1310 -f 1260//1260 1310//1310 1261//1261 -f 1261//1261 1310//1310 1311//1311 -f 1261//1261 1311//1311 1262//1262 -f 1262//1262 1311//1311 1312//1312 -f 1262//1262 1312//1312 1263//1263 -f 1263//1263 1312//1312 1313//1313 -f 1263//1263 1313//1313 1264//1264 -f 1264//1264 1313//1313 1314//1314 -f 1264//1264 1314//1314 1265//1265 -f 1265//1265 1314//1314 1315//1315 -f 1265//1265 1315//1315 1266//1266 -f 1266//1266 1315//1315 1316//1316 -f 1266//1266 1316//1316 1267//1267 -f 1267//1267 1316//1316 1317//1317 -f 1267//1267 1317//1317 1268//1268 -f 1268//1268 1317//1317 1318//1318 -f 1268//1268 1318//1318 1269//1269 -f 1269//1269 1318//1318 1319//1319 -f 1269//1269 1319//1319 1270//1270 -f 1270//1270 1319//1319 1320//1320 -f 1270//1270 1320//1320 1271//1271 -f 1271//1271 1320//1320 1321//1321 -f 1271//1271 1321//1321 1272//1272 -f 1272//1272 1321//1321 1322//1322 -f 1272//1272 1322//1322 1273//1273 -f 1273//1273 1322//1322 1323//1323 -f 1273//1273 1323//1323 1274//1274 -f 1274//1274 1323//1323 1324//1324 -f 1274//1274 1324//1324 1275//1275 -f 1275//1275 1324//1324 1325//1325 -f 1275//1275 1325//1325 1276//1276 -f 1276//1276 1325//1325 1326//1326 -f 1276//1276 1326//1326 1277//1277 -f 1277//1277 1326//1326 1327//1327 -f 1277//1277 1327//1327 1278//1278 -f 1278//1278 1327//1327 1328//1328 -f 1278//1278 1328//1328 1279//1279 -f 1279//1279 1328//1328 1329//1329 -f 1279//1279 1329//1329 1280//1280 -f 1280//1280 1329//1329 1330//1330 -f 1280//1280 1330//1330 1281//1281 -f 1281//1281 1330//1330 1331//1331 -f 1281//1281 1331//1331 1282//1282 -f 1282//1282 1331//1331 1283//1283 -f 1331//1331 1332//1332 1283//1283 -f 1283//1283 1332//1332 1333//1333 -f 1283//1283 1333//1333 1284//1284 -f 1284//1284 1333//1333 1334//1334 -f 1284//1284 1334//1334 1285//1285 -f 1285//1285 1334//1334 1335//1335 -f 1285//1285 1335//1335 1286//1286 -f 1286//1286 1335//1335 1336//1336 -f 1286//1286 1336//1336 1287//1287 -f 1287//1287 1336//1336 1337//1337 -f 1287//1287 1337//1337 1288//1288 -f 1288//1288 1337//1337 1338//1338 -f 1288//1288 1338//1338 1289//1289 -f 1289//1289 1338//1338 1339//1339 -f 1289//1289 1339//1339 1290//1290 -f 1290//1290 1339//1339 1340//1340 -f 1290//1290 1340//1340 1291//1291 -f 1291//1291 1340//1340 1341//1341 -f 1291//1291 1341//1341 1292//1292 -f 1292//1292 1341//1341 1342//1342 -f 1292//1292 1342//1342 1293//1293 -f 1293//1293 1342//1342 1343//1343 -f 1293//1293 1343//1343 1294//1294 -f 1294//1294 1343//1343 1344//1344 -f 1294//1294 1344//1344 1295//1295 -f 1295//1295 1344//1344 1345//1345 -f 1295//1295 1345//1345 1296//1296 -f 1296//1296 1345//1345 1346//1346 -f 1296//1296 1346//1346 1297//1297 -f 1297//1297 1346//1346 1347//1347 -f 1297//1297 1347//1347 1298//1298 -f 1298//1298 1347//1347 1348//1348 -f 1298//1298 1348//1348 1299//1299 -f 1299//1299 1348//1348 1349//1349 -f 1299//1299 1349//1349 1300//1300 -f 1300//1300 1349//1349 1350//1350 -f 1300//1300 1350//1350 1301//1301 -f 1301//1301 1350//1350 1351//1351 -f 1301//1301 1351//1351 1302//1302 -f 1302//1302 1351//1351 1352//1352 -f 1302//1302 1352//1352 1303//1303 -f 1303//1303 1352//1352 1353//1353 -f 1303//1303 1353//1353 1304//1304 -f 1304//1304 1353//1353 1354//1354 -f 1304//1304 1354//1354 1305//1305 -f 1305//1305 1354//1354 1355//1355 -f 1305//1305 1355//1355 1306//1306 -f 1306//1306 1355//1355 1356//1356 -f 1306//1306 1356//1356 1307//1307 -f 1307//1307 1356//1356 1357//1357 -f 1307//1307 1357//1357 1308//1308 -f 1308//1308 1357//1357 1358//1358 -f 1308//1308 1358//1358 1309//1309 -f 1309//1309 1358//1358 1359//1359 -f 1309//1309 1359//1359 1310//1310 -f 1310//1310 1359//1359 1360//1360 -f 1310//1310 1360//1360 1311//1311 -f 1311//1311 1360//1360 1361//1361 -f 1311//1311 1361//1361 1312//1312 -f 1312//1312 1361//1361 1362//1362 -f 1312//1312 1362//1362 1313//1313 -f 1313//1313 1362//1362 1363//1363 -f 1313//1313 1363//1363 1314//1314 -f 1314//1314 1363//1363 1364//1364 -f 1314//1314 1364//1364 1315//1315 -f 1315//1315 1364//1364 1365//1365 -f 1315//1315 1365//1365 1316//1316 -f 1316//1316 1365//1365 1366//1366 -f 1316//1316 1366//1366 1317//1317 -f 1317//1317 1366//1366 1367//1367 -f 1317//1317 1367//1367 1318//1318 -f 1318//1318 1367//1367 1368//1368 -f 1318//1318 1368//1368 1319//1319 -f 1319//1319 1368//1368 1369//1369 -f 1319//1319 1369//1369 1320//1320 -f 1320//1320 1369//1369 1370//1370 -f 1320//1320 1370//1370 1321//1321 -f 1321//1321 1370//1370 1371//1371 -f 1321//1321 1371//1371 1322//1322 -f 1322//1322 1371//1371 1372//1372 -f 1322//1322 1372//1372 1323//1323 -f 1323//1323 1372//1372 1373//1373 -f 1323//1323 1373//1373 1324//1324 -f 1324//1324 1373//1373 1374//1374 -f 1324//1324 1374//1374 1325//1325 -f 1325//1325 1374//1374 1375//1375 -f 1325//1325 1375//1375 1326//1326 -f 1326//1326 1375//1375 1376//1376 -f 1326//1326 1376//1376 1327//1327 -f 1327//1327 1376//1376 1377//1377 -f 1327//1327 1377//1377 1328//1328 -f 1328//1328 1377//1377 1378//1378 -f 1328//1328 1378//1378 1329//1329 -f 1329//1329 1378//1378 1379//1379 -f 1329//1329 1379//1379 1330//1330 -f 1330//1330 1379//1379 1380//1380 -f 1330//1330 1380//1380 1331//1331 -f 1331//1331 1380//1380 1332//1332 -f 1380//1380 1381//1381 1332//1332 -f 1332//1332 1381//1381 1382//1382 -f 1332//1332 1382//1382 1333//1333 -f 1333//1333 1382//1382 1383//1383 -f 1333//1333 1383//1383 1334//1334 -f 1334//1334 1383//1383 1384//1384 -f 1334//1334 1384//1384 1335//1335 -f 1335//1335 1384//1384 1385//1385 -f 1335//1335 1385//1385 1336//1336 -f 1336//1336 1385//1385 1386//1386 -f 1336//1336 1386//1386 1337//1337 -f 1337//1337 1386//1386 1387//1387 -f 1337//1337 1387//1387 1338//1338 -f 1338//1338 1387//1387 1388//1388 -f 1338//1338 1388//1388 1339//1339 -f 1339//1339 1388//1388 1389//1389 -f 1339//1339 1389//1389 1340//1340 -f 1340//1340 1389//1389 1390//1390 -f 1340//1340 1390//1390 1341//1341 -f 1341//1341 1390//1390 1391//1391 -f 1341//1341 1391//1391 1342//1342 -f 1342//1342 1391//1391 1392//1392 -f 1342//1342 1392//1392 1343//1343 -f 1343//1343 1392//1392 1393//1393 -f 1343//1343 1393//1393 1344//1344 -f 1344//1344 1393//1393 1394//1394 -f 1344//1344 1394//1394 1345//1345 -f 1345//1345 1394//1394 1395//1395 -f 1345//1345 1395//1395 1346//1346 -f 1346//1346 1395//1395 1396//1396 -f 1346//1346 1396//1396 1347//1347 -f 1347//1347 1396//1396 1397//1397 -f 1347//1347 1397//1397 1348//1348 -f 1348//1348 1397//1397 1398//1398 -f 1348//1348 1398//1398 1349//1349 -f 1349//1349 1398//1398 1399//1399 -f 1349//1349 1399//1399 1350//1350 -f 1350//1350 1399//1399 1400//1400 -f 1350//1350 1400//1400 1351//1351 -f 1351//1351 1400//1400 1401//1401 -f 1351//1351 1401//1401 1352//1352 -f 1352//1352 1401//1401 1402//1402 -f 1352//1352 1402//1402 1353//1353 -f 1353//1353 1402//1402 1403//1403 -f 1353//1353 1403//1403 1354//1354 -f 1354//1354 1403//1403 1404//1404 -f 1354//1354 1404//1404 1355//1355 -f 1355//1355 1404//1404 1405//1405 -f 1355//1355 1405//1405 1356//1356 -f 1356//1356 1405//1405 1406//1406 -f 1356//1356 1406//1406 1357//1357 -f 1357//1357 1406//1406 1407//1407 -f 1357//1357 1407//1407 1358//1358 -f 1358//1358 1407//1407 1408//1408 -f 1358//1358 1408//1408 1359//1359 -f 1359//1359 1408//1408 1409//1409 -f 1359//1359 1409//1409 1360//1360 -f 1360//1360 1409//1409 1410//1410 -f 1360//1360 1410//1410 1361//1361 -f 1361//1361 1410//1410 1411//1411 -f 1361//1361 1411//1411 1362//1362 -f 1362//1362 1411//1411 1412//1412 -f 1362//1362 1412//1412 1363//1363 -f 1363//1363 1412//1412 1413//1413 -f 1363//1363 1413//1413 1364//1364 -f 1364//1364 1413//1413 1414//1414 -f 1364//1364 1414//1414 1365//1365 -f 1365//1365 1414//1414 1415//1415 -f 1365//1365 1415//1415 1366//1366 -f 1366//1366 1415//1415 1416//1416 -f 1366//1366 1416//1416 1367//1367 -f 1367//1367 1416//1416 1417//1417 -f 1367//1367 1417//1417 1368//1368 -f 1368//1368 1417//1417 1418//1418 -f 1368//1368 1418//1418 1369//1369 -f 1369//1369 1418//1418 1419//1419 -f 1369//1369 1419//1419 1370//1370 -f 1370//1370 1419//1419 1420//1420 -f 1370//1370 1420//1420 1371//1371 -f 1371//1371 1420//1420 1421//1421 -f 1371//1371 1421//1421 1372//1372 -f 1372//1372 1421//1421 1422//1422 -f 1372//1372 1422//1422 1373//1373 -f 1373//1373 1422//1422 1423//1423 -f 1373//1373 1423//1423 1374//1374 -f 1374//1374 1423//1423 1424//1424 -f 1374//1374 1424//1424 1375//1375 -f 1375//1375 1424//1424 1425//1425 -f 1375//1375 1425//1425 1376//1376 -f 1376//1376 1425//1425 1426//1426 -f 1376//1376 1426//1426 1377//1377 -f 1377//1377 1426//1426 1427//1427 -f 1377//1377 1427//1427 1378//1378 -f 1378//1378 1427//1427 1428//1428 -f 1378//1378 1428//1428 1379//1379 -f 1379//1379 1428//1428 1429//1429 -f 1379//1379 1429//1429 1380//1380 -f 1380//1380 1429//1429 1381//1381 -f 1429//1429 1430//1430 1381//1381 -f 1381//1381 1430//1430 1431//1431 -f 1381//1381 1431//1431 1382//1382 -f 1382//1382 1431//1431 1432//1432 -f 1382//1382 1432//1432 1383//1383 -f 1383//1383 1432//1432 1433//1433 -f 1383//1383 1433//1433 1384//1384 -f 1384//1384 1433//1433 1434//1434 -f 1384//1384 1434//1434 1385//1385 -f 1385//1385 1434//1434 1435//1435 -f 1385//1385 1435//1435 1386//1386 -f 1386//1386 1435//1435 1436//1436 -f 1386//1386 1436//1436 1387//1387 -f 1387//1387 1436//1436 1437//1437 -f 1387//1387 1437//1437 1388//1388 -f 1388//1388 1437//1437 1438//1438 -f 1388//1388 1438//1438 1389//1389 -f 1389//1389 1438//1438 1439//1439 -f 1389//1389 1439//1439 1390//1390 -f 1390//1390 1439//1439 1440//1440 -f 1390//1390 1440//1440 1391//1391 -f 1391//1391 1440//1440 1441//1441 -f 1391//1391 1441//1441 1392//1392 -f 1392//1392 1441//1441 1442//1442 -f 1392//1392 1442//1442 1393//1393 -f 1393//1393 1442//1442 1443//1443 -f 1393//1393 1443//1443 1394//1394 -f 1394//1394 1443//1443 1444//1444 -f 1394//1394 1444//1444 1395//1395 -f 1395//1395 1444//1444 1445//1445 -f 1395//1395 1445//1445 1396//1396 -f 1396//1396 1445//1445 1446//1446 -f 1396//1396 1446//1446 1397//1397 -f 1397//1397 1446//1446 1447//1447 -f 1397//1397 1447//1447 1398//1398 -f 1398//1398 1447//1447 1448//1448 -f 1398//1398 1448//1448 1399//1399 -f 1399//1399 1448//1448 1449//1449 -f 1399//1399 1449//1449 1400//1400 -f 1400//1400 1449//1449 1450//1450 -f 1400//1400 1450//1450 1401//1401 -f 1401//1401 1450//1450 1451//1451 -f 1401//1401 1451//1451 1402//1402 -f 1402//1402 1451//1451 1452//1452 -f 1402//1402 1452//1452 1403//1403 -f 1403//1403 1452//1452 1453//1453 -f 1403//1403 1453//1453 1404//1404 -f 1404//1404 1453//1453 1454//1454 -f 1404//1404 1454//1454 1405//1405 -f 1405//1405 1454//1454 1455//1455 -f 1405//1405 1455//1455 1406//1406 -f 1406//1406 1455//1455 1456//1456 -f 1406//1406 1456//1456 1407//1407 -f 1407//1407 1456//1456 1457//1457 -f 1407//1407 1457//1457 1408//1408 -f 1408//1408 1457//1457 1458//1458 -f 1408//1408 1458//1458 1409//1409 -f 1409//1409 1458//1458 1459//1459 -f 1409//1409 1459//1459 1410//1410 -f 1410//1410 1459//1459 1460//1460 -f 1410//1410 1460//1460 1411//1411 -f 1411//1411 1460//1460 1461//1461 -f 1411//1411 1461//1461 1412//1412 -f 1412//1412 1461//1461 1462//1462 -f 1412//1412 1462//1462 1413//1413 -f 1413//1413 1462//1462 1463//1463 -f 1413//1413 1463//1463 1414//1414 -f 1414//1414 1463//1463 1464//1464 -f 1414//1414 1464//1464 1415//1415 -f 1415//1415 1464//1464 1465//1465 -f 1415//1415 1465//1465 1416//1416 -f 1416//1416 1465//1465 1466//1466 -f 1416//1416 1466//1466 1417//1417 -f 1417//1417 1466//1466 1467//1467 -f 1417//1417 1467//1467 1418//1418 -f 1418//1418 1467//1467 1468//1468 -f 1418//1418 1468//1468 1419//1419 -f 1419//1419 1468//1468 1469//1469 -f 1419//1419 1469//1469 1420//1420 -f 1420//1420 1469//1469 1470//1470 -f 1420//1420 1470//1470 1421//1421 -f 1421//1421 1470//1470 1471//1471 -f 1421//1421 1471//1471 1422//1422 -f 1422//1422 1471//1471 1472//1472 -f 1422//1422 1472//1472 1423//1423 -f 1423//1423 1472//1472 1473//1473 -f 1423//1423 1473//1473 1424//1424 -f 1424//1424 1473//1473 1474//1474 -f 1424//1424 1474//1474 1425//1425 -f 1425//1425 1474//1474 1475//1475 -f 1425//1425 1475//1475 1426//1426 -f 1426//1426 1475//1475 1476//1476 -f 1426//1426 1476//1476 1427//1427 -f 1427//1427 1476//1476 1477//1477 -f 1427//1427 1477//1477 1428//1428 -f 1428//1428 1477//1477 1478//1478 -f 1428//1428 1478//1478 1429//1429 -f 1429//1429 1478//1478 1430//1430 -f 1454//1454 1479//1479 1455//1455 -f 1455//1455 1479//1479 1480//1480 -f 1455//1455 1480//1480 1456//1456 -f 1456//1456 1480//1480 1481//1481 -f 1456//1456 1481//1481 1457//1457 -f 1457//1457 1481//1481 1482//1482 -f 1457//1457 1482//1482 1458//1458 -f 1482//1482 1483//1483 1458//1458 -f 1458//1458 1483//1483 1484//1484 -f 1458//1458 1484//1484 1459//1459 -f 1459//1459 1484//1484 1485//1485 -f 1459//1459 1485//1485 1460//1460 -f 1460//1460 1485//1485 1486//1486 -f 1460//1460 1486//1486 1461//1461 -f 1461//1461 1486//1486 1487//1487 -f 1461//1461 1487//1487 1462//1462 -f 1487//1487 1488//1488 1462//1462 -f 1462//1462 1488//1488 1489//1489 -f 1462//1462 1489//1489 1463//1463 -f 1463//1463 1489//1489 1490//1490 -f 1463//1463 1490//1490 1464//1464 -f 1464//1464 1490//1490 1491//1491 -f 1464//1464 1491//1491 1465//1465 -f 1465//1465 1491//1491 1492//1492 -f 1465//1465 1492//1492 1466//1466 -f 1466//1466 1492//1492 1493//1493 -f 1466//1466 1493//1493 1467//1467 -f 1493//1493 1494//1494 1467//1467 -f 1467//1467 1494//1494 1495//1495 -f 1467//1467 1495//1495 1468//1468 -f 1468//1468 1495//1495 1496//1496 -f 1468//1468 1496//1496 1469//1469 -f 1469//1469 1496//1496 1497//1497 -f 1469//1469 1497//1497 1470//1470 -f 1470//1470 1497//1497 1498//1498 -f 1470//1470 1498//1498 1471//1471 -f 1498//1498 1499//1499 1471//1471 -f 1471//1471 1499//1499 1500//1500 -f 1471//1471 1500//1500 1472//1472 -f 1472//1472 1500//1500 1501//1501 -f 1472//1472 1501//1501 1473//1473 -f 1473//1473 1501//1501 1502//1502 -f 1473//1473 1502//1502 1474//1474 -f 1474//1474 1502//1502 1503//1503 -f 1474//1474 1503//1503 1475//1475 -f 1475//1475 1503//1503 1504//1504 -f 1475//1475 1504//1504 1476//1476 -f 1440//1440 1505//1505 1441//1441 -f 1441//1441 1505//1505 1506//1506 -f 1441//1441 1506//1506 1442//1442 -f 1442//1442 1506//1506 1507//1507 -f 1442//1442 1507//1507 1443//1443 -f 1443//1443 1507//1507 1508//1508 -f 1443//1443 1508//1508 1444//1444 -f 1444//1444 1508//1508 1509//1509 -f 1444//1444 1509//1509 1445//1445 -f 1509//1509 1510//1510 1445//1445 -f 1445//1445 1510//1510 1511//1511 -f 1445//1445 1511//1511 1446//1446 -f 1446//1446 1511//1511 1512//1512 -f 1446//1446 1512//1512 1447//1447 -f 1447//1447 1512//1512 1513//1513 -f 1447//1447 1513//1513 1448//1448 -f 1448//1448 1513//1513 1514//1514 -f 1448//1448 1514//1514 1449//1449 -f 1514//1514 1515//1515 1449//1449 -f 1449//1449 1515//1515 1516//1516 -f 1449//1449 1516//1516 1450//1450 -f 1450//1450 1516//1516 1517//1517 -f 1450//1450 1517//1517 1451//1451 -f 1451//1451 1517//1517 1518//1518 -f 1451//1451 1518//1518 1452//1452 -f 1452//1452 1518//1518 1519//1519 -f 1452//1452 1519//1519 1453//1453 -f 1453//1453 1519//1519 1520//1520 -f 1453//1453 1520//1520 1454//1454 -f 1454//1454 1520//1520 1521//1521 -f 1454//1454 1521//1521 1479//1479 -f 1504//1504 1522//1522 1476//1476 -f 1476//1476 1522//1522 1523//1523 -f 1476//1476 1523//1523 1477//1477 -f 1477//1477 1523//1523 1524//1524 -f 1477//1477 1524//1524 1478//1478 -f 1478//1478 1524//1524 1525//1525 -f 1478//1478 1525//1525 1430//1430 -f 1430//1430 1525//1525 1526//1526 -f 1430//1430 1526//1526 1431//1431 -f 1436//1436 1527//1527 1437//1437 -f 1437//1437 1527//1527 1528//1528 -f 1437//1437 1528//1528 1438//1438 -f 1438//1438 1528//1528 1529//1529 -f 1438//1438 1529//1529 1439//1439 -f 1439//1439 1529//1529 1530//1530 -f 1439//1439 1530//1530 1440//1440 -f 1440//1440 1530//1530 1531//1531 -f 1440//1440 1531//1531 1505//1505 -f 1526//1526 1532//1532 1431//1431 -f 1431//1431 1532//1532 1533//1533 -f 1431//1431 1533//1533 1432//1432 -f 1432//1432 1533//1533 1534//1534 -f 1432//1432 1534//1534 1433//1433 -f 1433//1433 1534//1534 1535//1535 -f 1433//1433 1535//1535 1434//1434 -f 1434//1434 1535//1535 1536//1536 -f 1434//1434 1536//1536 1435//1435 -f 1435//1435 1536//1536 1537//1537 -f 1435//1435 1537//1537 1436//1436 -f 1436//1436 1537//1537 1538//1538 -f 1436//1436 1538//1538 1527//1527 -f 1525//1525 1539//1539 1526//1526 -f 1526//1526 1539//1539 1540//1540 -f 1526//1526 1540//1540 1532//1532 -f 1532//1532 1540//1540 1541//1541 -f 1532//1532 1541//1541 1533//1533 -f 1533//1533 1541//1541 1542//1542 -f 1533//1533 1542//1542 1534//1534 -f 1534//1534 1542//1542 1543//1543 -f 1534//1534 1543//1543 1535//1535 -f 1535//1535 1543//1543 1544//1544 -f 1535//1535 1544//1544 1536//1536 -f 1536//1536 1544//1544 1545//1545 -f 1536//1536 1545//1545 1537//1537 -f 1537//1537 1545//1545 1546//1546 -f 1537//1537 1546//1546 1538//1538 -f 1538//1538 1546//1546 1547//1547 -f 1538//1538 1547//1547 1527//1527 -f 1527//1527 1547//1547 1548//1548 -f 1527//1527 1548//1548 1528//1528 -f 1528//1528 1548//1548 1549//1549 -f 1528//1528 1549//1549 1529//1529 -f 1529//1529 1549//1549 1550//1550 -f 1529//1529 1550//1550 1530//1530 -f 1530//1530 1550//1550 1551//1551 -f 1530//1530 1551//1551 1531//1531 -f 1531//1531 1551//1551 1552//1552 -f 1531//1531 1552//1552 1505//1505 -f 1505//1505 1552//1552 1553//1553 -f 1505//1505 1553//1553 1506//1506 -f 1506//1506 1553//1553 1554//1554 -f 1506//1506 1554//1554 1507//1507 -f 1507//1507 1554//1554 1555//1555 -f 1507//1507 1555//1555 1508//1508 -f 1508//1508 1555//1555 1556//1556 -f 1508//1508 1556//1556 1509//1509 -f 1509//1509 1556//1556 1557//1557 -f 1509//1509 1557//1557 1510//1510 -f 1510//1510 1557//1557 1558//1558 -f 1510//1510 1558//1558 1511//1511 -f 1511//1511 1558//1558 1559//1559 -f 1511//1511 1559//1559 1512//1512 -f 1512//1512 1559//1559 1560//1560 -f 1512//1512 1560//1560 1513//1513 -f 1513//1513 1560//1560 1561//1561 -f 1513//1513 1561//1561 1514//1514 -f 1514//1514 1561//1561 1562//1562 -f 1514//1514 1562//1562 1515//1515 -f 1515//1515 1562//1562 1563//1563 -f 1515//1515 1563//1563 1516//1516 -f 1516//1516 1563//1563 1564//1564 -f 1516//1516 1564//1564 1517//1517 -f 1517//1517 1564//1564 1565//1565 -f 1517//1517 1565//1565 1518//1518 -f 1518//1518 1565//1565 1566//1566 -f 1518//1518 1566//1566 1519//1519 -f 1519//1519 1566//1566 1567//1567 -f 1519//1519 1567//1567 1520//1520 -f 1520//1520 1567//1567 1568//1568 -f 1520//1520 1568//1568 1521//1521 -f 1521//1521 1568//1568 1569//1569 -f 1521//1521 1569//1569 1479//1479 -f 1479//1479 1569//1569 1570//1570 -f 1479//1479 1570//1570 1480//1480 -f 1480//1480 1570//1570 1571//1571 -f 1480//1480 1571//1571 1481//1481 -f 1481//1481 1571//1571 1572//1572 -f 1481//1481 1572//1572 1482//1482 -f 1482//1482 1572//1572 1573//1573 -f 1482//1482 1573//1573 1483//1483 -f 1483//1483 1573//1573 1574//1574 -f 1483//1483 1574//1574 1484//1484 -f 1484//1484 1574//1574 1575//1575 -f 1484//1484 1575//1575 1485//1485 -f 1485//1485 1575//1575 1576//1576 -f 1485//1485 1576//1576 1486//1486 -f 1486//1486 1576//1576 1577//1577 -f 1486//1486 1577//1577 1487//1487 -f 1487//1487 1577//1577 1578//1578 -f 1487//1487 1578//1578 1488//1488 -f 1488//1488 1578//1578 1579//1579 -f 1488//1488 1579//1579 1489//1489 -f 1489//1489 1579//1579 1580//1580 -f 1489//1489 1580//1580 1490//1490 -f 1490//1490 1580//1580 1581//1581 -f 1490//1490 1581//1581 1491//1491 -f 1491//1491 1581//1581 1582//1582 -f 1491//1491 1582//1582 1492//1492 -f 1492//1492 1582//1582 1583//1583 -f 1492//1492 1583//1583 1493//1493 -f 1493//1493 1583//1583 1584//1584 -f 1493//1493 1584//1584 1494//1494 -f 1494//1494 1584//1584 1585//1585 -f 1494//1494 1585//1585 1495//1495 -f 1495//1495 1585//1585 1586//1586 -f 1495//1495 1586//1586 1496//1496 -f 1496//1496 1586//1586 1587//1587 -f 1496//1496 1587//1587 1497//1497 -f 1497//1497 1587//1587 1588//1588 -f 1497//1497 1588//1588 1498//1498 -f 1498//1498 1588//1588 1589//1589 -f 1498//1498 1589//1589 1499//1499 -f 1499//1499 1589//1589 1590//1590 -f 1499//1499 1590//1590 1500//1500 -f 1500//1500 1590//1590 1591//1591 -f 1500//1500 1591//1591 1501//1501 -f 1501//1501 1591//1591 1592//1592 -f 1501//1501 1592//1592 1502//1502 -f 1502//1502 1592//1592 1593//1593 -f 1502//1502 1593//1593 1503//1503 -f 1503//1503 1593//1593 1594//1594 -f 1503//1503 1594//1594 1504//1504 -f 1504//1504 1594//1594 1595//1595 -f 1504//1504 1595//1595 1522//1522 -f 1522//1522 1595//1595 1596//1596 -f 1522//1522 1596//1596 1523//1523 -f 1523//1523 1596//1596 1597//1597 -f 1523//1523 1597//1597 1524//1524 -f 1524//1524 1597//1597 1598//1598 -f 1524//1524 1598//1598 1525//1525 -f 1525//1525 1598//1598 1539//1539 -f 1598//1598 1599//1599 1539//1539 -f 1539//1539 1599//1599 1600//1600 -f 1539//1539 1600//1600 1540//1540 -f 1540//1540 1600//1600 1601//1601 -f 1540//1540 1601//1601 1541//1541 -f 1541//1541 1601//1601 1602//1602 -f 1541//1541 1602//1602 1542//1542 -f 1542//1542 1602//1602 1603//1603 -f 1542//1542 1603//1603 1543//1543 -f 1543//1543 1603//1603 1604//1604 -f 1543//1543 1604//1604 1544//1544 -f 1544//1544 1604//1604 1605//1605 -f 1544//1544 1605//1605 1545//1545 -f 1545//1545 1605//1605 1606//1606 -f 1545//1545 1606//1606 1546//1546 -f 1546//1546 1606//1606 1607//1607 -f 1546//1546 1607//1607 1547//1547 -f 1547//1547 1607//1607 1608//1608 -f 1547//1547 1608//1608 1548//1548 -f 1548//1548 1608//1608 1609//1609 -f 1548//1548 1609//1609 1549//1549 -f 1549//1549 1609//1609 1610//1610 -f 1549//1549 1610//1610 1550//1550 -f 1550//1550 1610//1610 1611//1611 -f 1550//1550 1611//1611 1551//1551 -f 1551//1551 1611//1611 1612//1612 -f 1551//1551 1612//1612 1552//1552 -f 1552//1552 1612//1612 1613//1613 -f 1552//1552 1613//1613 1553//1553 -f 1553//1553 1613//1613 1614//1614 -f 1553//1553 1614//1614 1554//1554 -f 1554//1554 1614//1614 1615//1615 -f 1554//1554 1615//1615 1555//1555 -f 1555//1555 1615//1615 1616//1616 -f 1555//1555 1616//1616 1556//1556 -f 1556//1556 1616//1616 1617//1617 -f 1556//1556 1617//1617 1557//1557 -f 1557//1557 1617//1617 1618//1618 -f 1557//1557 1618//1618 1558//1558 -f 1558//1558 1618//1618 1619//1619 -f 1558//1558 1619//1619 1559//1559 -f 1559//1559 1619//1619 1620//1620 -f 1559//1559 1620//1620 1560//1560 -f 1560//1560 1620//1620 1621//1621 -f 1560//1560 1621//1621 1561//1561 -f 1561//1561 1621//1621 1622//1622 -f 1561//1561 1622//1622 1562//1562 -f 1562//1562 1622//1622 1623//1623 -f 1562//1562 1623//1623 1563//1563 -f 1563//1563 1623//1623 1624//1624 -f 1563//1563 1624//1624 1564//1564 -f 1564//1564 1624//1624 1625//1625 -f 1564//1564 1625//1625 1565//1565 -f 1565//1565 1625//1625 1626//1626 -f 1565//1565 1626//1626 1566//1566 -f 1566//1566 1626//1626 1627//1627 -f 1566//1566 1627//1627 1567//1567 -f 1567//1567 1627//1627 1628//1628 -f 1567//1567 1628//1628 1568//1568 -f 1568//1568 1628//1628 1629//1629 -f 1568//1568 1629//1629 1569//1569 -f 1569//1569 1629//1629 1630//1630 -f 1569//1569 1630//1630 1570//1570 -f 1570//1570 1630//1630 1631//1631 -f 1570//1570 1631//1631 1571//1571 -f 1571//1571 1631//1631 1632//1632 -f 1571//1571 1632//1632 1572//1572 -f 1572//1572 1632//1632 1633//1633 -f 1572//1572 1633//1633 1573//1573 -f 1573//1573 1633//1633 1634//1634 -f 1573//1573 1634//1634 1574//1574 -f 1574//1574 1634//1634 1635//1635 -f 1574//1574 1635//1635 1575//1575 -f 1575//1575 1635//1635 1636//1636 -f 1575//1575 1636//1636 1576//1576 -f 1576//1576 1636//1636 1637//1637 -f 1576//1576 1637//1637 1577//1577 -f 1577//1577 1637//1637 1638//1638 -f 1577//1577 1638//1638 1578//1578 -f 1578//1578 1638//1638 1639//1639 -f 1578//1578 1639//1639 1579//1579 -f 1579//1579 1639//1639 1640//1640 -f 1579//1579 1640//1640 1580//1580 -f 1580//1580 1640//1640 1641//1641 -f 1580//1580 1641//1641 1581//1581 -f 1581//1581 1641//1641 1642//1642 -f 1581//1581 1642//1642 1582//1582 -f 1582//1582 1642//1642 1643//1643 -f 1582//1582 1643//1643 1583//1583 -f 1583//1583 1643//1643 1644//1644 -f 1583//1583 1644//1644 1584//1584 -f 1584//1584 1644//1644 1645//1645 -f 1584//1584 1645//1645 1585//1585 -f 1585//1585 1645//1645 1646//1646 -f 1585//1585 1646//1646 1586//1586 -f 1586//1586 1646//1646 1647//1647 -f 1586//1586 1647//1647 1587//1587 -f 1587//1587 1647//1647 1648//1648 -f 1587//1587 1648//1648 1588//1588 -f 1588//1588 1648//1648 1649//1649 -f 1588//1588 1649//1649 1589//1589 -f 1589//1589 1649//1649 1650//1650 -f 1589//1589 1650//1650 1590//1590 -f 1590//1590 1650//1650 1651//1651 -f 1590//1590 1651//1651 1591//1591 -f 1591//1591 1651//1651 1652//1652 -f 1591//1591 1652//1652 1592//1592 -f 1592//1592 1652//1652 1653//1653 -f 1592//1592 1653//1653 1593//1593 -f 1593//1593 1653//1653 1654//1654 -f 1593//1593 1654//1654 1594//1594 -f 1594//1594 1654//1654 1655//1655 -f 1594//1594 1655//1655 1595//1595 -f 1595//1595 1655//1655 1656//1656 -f 1595//1595 1656//1656 1596//1596 -f 1596//1596 1656//1656 1657//1657 -f 1596//1596 1657//1657 1597//1597 -f 1597//1597 1657//1657 1658//1658 -f 1597//1597 1658//1658 1598//1598 -f 1598//1598 1658//1658 1599//1599 -f 1659//1659 1660//1660 1629//1629 -f 1629//1629 1660//1660 1630//1630 -f 1630//1630 1660//1660 1661//1661 -f 1630//1630 1661//1661 1631//1631 -f 1631//1631 1661//1661 1662//1662 -f 1631//1631 1662//1662 1632//1632 -f 1632//1632 1662//1662 1663//1663 -f 1632//1632 1663//1663 1633//1633 -f 1633//1633 1663//1663 1664//1664 -f 1633//1633 1664//1664 1634//1634 -f 1634//1634 1664//1664 1665//1665 -f 1634//1634 1665//1665 1635//1635 -f 1635//1635 1665//1665 1666//1666 -f 1635//1635 1666//1666 1636//1636 -f 1666//1666 1667//1667 1636//1636 -f 1636//1636 1667//1667 1668//1668 -f 1636//1636 1668//1668 1637//1637 -f 1637//1637 1668//1668 1669//1669 -f 1637//1637 1669//1669 1638//1638 -f 1638//1638 1669//1669 1639//1639 -f 1639//1639 1669//1669 1670//1670 -f 1639//1639 1670//1670 1640//1640 -f 1640//1640 1670//1670 1671//1671 -f 1640//1640 1671//1671 1641//1641 -f 1641//1641 1671//1671 1672//1672 -f 1641//1641 1672//1672 1642//1642 -f 1642//1642 1672//1672 1673//1673 -f 1642//1642 1673//1673 1643//1643 -f 1643//1643 1673//1673 1674//1674 -f 1643//1643 1674//1674 1644//1644 -f 1644//1644 1674//1674 1675//1675 -f 1644//1644 1675//1675 1645//1645 -f 1645//1645 1675//1675 1676//1676 -f 1645//1645 1676//1676 1646//1646 -f 1676//1676 1677//1677 1646//1646 -f 1646//1646 1677//1677 1678//1678 -f 1646//1646 1678//1678 1647//1647 -f 1647//1647 1678//1678 1679//1679 -f 1647//1647 1679//1679 1648//1648 -f 1648//1648 1679//1679 1649//1649 -f 1649//1649 1679//1679 1680//1680 -f 1649//1649 1680//1680 1650//1650 -f 1650//1650 1680//1680 1681//1681 -f 1650//1650 1681//1681 1651//1651 -f 1651//1651 1681//1681 1682//1682 -f 1651//1651 1682//1682 1652//1652 -f 1652//1652 1682//1682 1683//1683 -f 1652//1652 1683//1683 1653//1653 -f 1653//1653 1683//1683 1684//1684 -f 1653//1653 1684//1684 1654//1654 -f 1654//1654 1684//1684 1685//1685 -f 1654//1654 1685//1685 1655//1655 -f 1655//1655 1685//1685 1686//1686 -f 1655//1655 1686//1686 1656//1656 -f 1686//1686 1687//1687 1656//1656 -f 1656//1656 1687//1687 1688//1688 -f 1656//1656 1688//1688 1657//1657 -f 1657//1657 1688//1688 1689//1689 -f 1657//1657 1689//1689 1658//1658 -f 1658//1658 1689//1689 1599//1599 -f 1599//1599 1689//1689 1690//1690 -f 1599//1599 1690//1690 1600//1600 -f 1600//1600 1690//1690 1691//1691 -f 1600//1600 1691//1691 1601//1601 -f 1601//1601 1691//1691 1692//1692 -f 1601//1601 1692//1692 1602//1602 -f 1602//1602 1692//1692 1693//1693 -f 1602//1602 1693//1693 1603//1603 -f 1603//1603 1693//1693 1694//1694 -f 1603//1603 1694//1694 1604//1604 -f 1604//1604 1694//1694 1695//1695 -f 1604//1604 1695//1695 1605//1605 -f 1605//1605 1695//1695 1696//1696 -f 1605//1605 1696//1696 1606//1606 -f 1696//1696 1697//1697 1606//1606 -f 1606//1606 1697//1697 1698//1698 -f 1606//1606 1698//1698 1607//1607 -f 1607//1607 1698//1698 1699//1699 -f 1607//1607 1699//1699 1608//1608 -f 1608//1608 1699//1699 1609//1609 -f 1609//1609 1699//1699 1700//1700 -f 1609//1609 1700//1700 1610//1610 -f 1610//1610 1700//1700 1701//1701 -f 1610//1610 1701//1701 1611//1611 -f 1611//1611 1701//1701 1702//1702 -f 1611//1611 1702//1702 1612//1612 -f 1612//1612 1702//1702 1703//1703 -f 1612//1612 1703//1703 1613//1613 -f 1613//1613 1703//1703 1704//1704 -f 1613//1613 1704//1704 1614//1614 -f 1614//1614 1704//1704 1705//1705 -f 1614//1614 1705//1705 1615//1615 -f 1615//1615 1705//1705 1706//1706 -f 1615//1615 1706//1706 1616//1616 -f 1706//1706 1707//1707 1616//1616 -f 1616//1616 1707//1707 1708//1708 -f 1616//1616 1708//1708 1617//1617 -f 1617//1617 1708//1708 1709//1709 -f 1617//1617 1709//1709 1618//1618 -f 1618//1618 1709//1709 1619//1619 -f 1619//1619 1709//1709 1710//1710 -f 1619//1619 1710//1710 1620//1620 -f 1620//1620 1710//1710 1711//1711 -f 1620//1620 1711//1711 1621//1621 -f 1621//1621 1711//1711 1712//1712 -f 1621//1621 1712//1712 1622//1622 -f 1622//1622 1712//1712 1713//1713 -f 1622//1622 1713//1713 1623//1623 -f 1623//1623 1713//1713 1714//1714 -f 1623//1623 1714//1714 1624//1624 -f 1624//1624 1714//1714 1715//1715 -f 1624//1624 1715//1715 1625//1625 -f 1625//1625 1715//1715 1716//1716 -f 1625//1625 1716//1716 1626//1626 -f 1716//1716 1717//1717 1626//1626 -f 1626//1626 1717//1717 1718//1718 -f 1626//1626 1718//1718 1627//1627 -f 1627//1627 1718//1718 1659//1659 -f 1627//1627 1659//1659 1628//1628 -f 1628//1628 1659//1659 1629//1629 -f 1719//1719 1720//1720 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1725//1725 1726//1726 1727//1727 -f 1728//1728 1729//1729 1730//1730 -f 1731//1731 1732//1732 1733//1733 -f 1734//1734 1735//1735 1736//1736 -f 1737//1737 1738//1738 1739//1739 -f 1740//1740 1741//1741 1742//1742 -f 1693//1693 1692//1692 1743//1743 -f 1695//1695 1694//1694 1744//1744 -f 1701//1701 1700//1700 1745//1745 -f 1713//1713 1712//1712 1746//1746 -f 1715//1715 1714//1714 1747//1747 -f 1661//1661 1660//1660 1748//1748 -f 1673//1673 1672//1672 1749//1749 -f 1675//1675 1674//1674 1750//1750 -f 1681//1681 1680//1680 1751//1751 -f 1752//1752 1689//1689 1688//1688 -f 1752//1752 1688//1688 1753//1753 -f 1753//1753 1688//1688 1687//1687 -f 1753//1753 1687//1687 1754//1754 -f 1684//1684 1755//1755 1685//1685 -f 1685//1685 1755//1755 1754//1754 -f 1685//1685 1754//1754 1686//1686 -f 1686//1686 1754//1754 1687//1687 -f 1684//1684 1683//1683 1756//1756 -f 1681//1681 1751//1751 1682//1682 -f 1741//1741 1678//1678 1677//1677 -f 1741//1741 1677//1677 1742//1742 -f 1742//1742 1677//1677 1676//1676 -f 1742//1742 1676//1676 1675//1675 -f 1673//1673 1749//1749 1674//1674 -f 1672//1672 1671//1671 1757//1757 -f 1757//1757 1671//1671 1670//1670 -f 1757//1757 1670//1670 1669//1669 -f 1664//1664 1739//1739 1665//1665 -f 1665//1665 1739//1739 1738//1738 -f 1665//1665 1738//1738 1666//1666 -f 1666//1666 1738//1738 1667//1667 -f 1664//1664 1663//1663 1758//1758 -f 1661//1661 1748//1748 1662//1662 -f 1735//1735 1718//1718 1717//1717 -f 1735//1735 1717//1717 1736//1736 -f 1736//1736 1717//1717 1716//1716 -f 1736//1736 1716//1716 1715//1715 -f 1713//1713 1746//1746 1714//1714 -f 1712//1712 1711//1711 1759//1759 -f 1759//1759 1711//1711 1710//1710 -f 1759//1759 1710//1710 1709//1709 -f 1704//1704 1733//1733 1705//1705 -f 1705//1705 1733//1733 1732//1732 -f 1705//1705 1732//1732 1706//1706 -f 1706//1706 1732//1732 1707//1707 -f 1704//1704 1703//1703 1760//1760 -f 1701//1701 1745//1745 1702//1702 -f 1729//1729 1698//1698 1697//1697 -f 1729//1729 1697//1697 1730//1730 -f 1730//1730 1697//1697 1696//1696 -f 1730//1730 1696//1696 1695//1695 -f 1693//1693 1743//1743 1694//1694 -f 1692//1692 1691//1691 1761//1761 -f 1761//1761 1691//1691 1690//1690 -f 1761//1761 1690//1690 1689//1689 -f 1679//1679 1678//1678 1762//1762 -f 1762//1762 1678//1678 1741//1741 -f 1762//1762 1741//1741 1763//1763 -f 1763//1763 1741//1741 1740//1740 -f 1763//1763 1740//1740 1764//1764 -f 1668//1668 1667//1667 1765//1765 -f 1765//1765 1667//1667 1738//1738 -f 1765//1765 1738//1738 1766//1766 -f 1766//1766 1738//1738 1737//1737 -f 1766//1766 1737//1737 1767//1767 -f 1659//1659 1718//1718 1768//1768 -f 1768//1768 1718//1718 1735//1735 -f 1768//1768 1735//1735 1769//1769 -f 1769//1769 1735//1735 1734//1734 -f 1769//1769 1734//1734 1770//1770 -f 1708//1708 1707//1707 1771//1771 -f 1771//1771 1707//1707 1732//1732 -f 1771//1771 1732//1732 1772//1772 -f 1772//1772 1732//1732 1731//1731 -f 1772//1772 1731//1731 1773//1773 -f 1699//1699 1698//1698 1774//1774 -f 1774//1774 1698//1698 1729//1729 -f 1774//1774 1729//1729 1775//1775 -f 1775//1775 1729//1729 1728//1728 -f 1775//1775 1728//1728 1776//1776 -f 1755//1755 1777//1777 1754//1754 -f 1754//1754 1777//1777 1778//1778 -f 1754//1754 1778//1778 1753//1753 -f 1753//1753 1778//1778 1779//1779 -f 1753//1753 1779//1779 1752//1752 -f 1752//1752 1779//1779 1780//1780 -f 1781//1781 1782//1782 1783//1783 -f 1784//1784 1785//1785 1786//1786 -f 1787//1787 1785//1785 1788//1788 -f 1788//1788 1785//1785 1784//1784 -f 1788//1788 1784//1784 1789//1789 -f 1669//1669 1668//1668 1789//1789 -f 1789//1789 1668//1668 1765//1765 -f 1789//1789 1765//1765 1788//1788 -f 1788//1788 1765//1765 1766//1766 -f 1788//1788 1766//1766 1787//1787 -f 1787//1787 1766//1766 1767//1767 -f 1790//1790 1791//1791 1792//1792 -f 1793//1793 1794//1794 1795//1795 -f 1796//1796 1794//1794 1797//1797 -f 1797//1797 1794//1794 1793//1793 -f 1797//1797 1793//1793 1798//1798 -f 1709//1709 1708//1708 1798//1798 -f 1798//1798 1708//1708 1771//1771 -f 1798//1798 1771//1771 1797//1797 -f 1797//1797 1771//1771 1772//1772 -f 1797//1797 1772//1772 1796//1796 -f 1796//1796 1772//1772 1773//1773 -f 1799//1799 1800//1800 1801//1801 -f 1777//1777 1802//1802 1778//1778 -f 1778//1778 1802//1802 1803//1803 -f 1778//1778 1803//1803 1779//1779 -f 1779//1779 1803//1803 1804//1804 -f 1779//1779 1804//1804 1780//1780 -f 1780//1780 1804//1804 1805//1805 -f 1684//1684 1756//1756 1755//1755 -f 1755//1755 1756//1756 1806//1806 -f 1755//1755 1806//1806 1777//1777 -f 1777//1777 1806//1806 1727//1727 -f 1777//1777 1727//1727 1802//1802 -f 1802//1802 1727//1727 1726//1726 -f 1802//1802 1726//1726 1807//1807 -f 1756//1756 1781//1781 1806//1806 -f 1806//1806 1781//1781 1783//1783 -f 1806//1806 1783//1783 1727//1727 -f 1727//1727 1783//1783 1808//1808 -f 1727//1727 1808//1808 1725//1725 -f 1809//1809 1810//1810 1811//1811 -f 1811//1811 1810//1810 1782//1782 -f 1811//1811 1782//1782 1812//1812 -f 1812//1812 1782//1782 1781//1781 -f 1812//1812 1781//1781 1751//1751 -f 1751//1751 1781//1781 1756//1756 -f 1751//1751 1756//1756 1682//1682 -f 1682//1682 1756//1756 1683//1683 -f 1810//1810 1813//1813 1782//1782 -f 1782//1782 1813//1813 1814//1814 -f 1782//1782 1814//1814 1783//1783 -f 1783//1783 1814//1814 1815//1815 -f 1783//1783 1815//1815 1808//1808 -f 1680//1680 1679//1679 1751//1751 -f 1751//1751 1679//1679 1762//1762 -f 1751//1751 1762//1762 1812//1812 -f 1812//1812 1762//1762 1763//1763 -f 1812//1812 1763//1763 1811//1811 -f 1811//1811 1763//1763 1764//1764 -f 1811//1811 1764//1764 1809//1809 -f 1809//1809 1764//1764 1816//1816 -f 1817//1817 1818//1818 1819//1819 -f 1675//1675 1750//1750 1742//1742 -f 1742//1742 1750//1750 1820//1820 -f 1742//1742 1820//1820 1740//1740 -f 1740//1740 1820//1820 1817//1817 -f 1740//1740 1817//1817 1764//1764 -f 1764//1764 1817//1817 1819//1819 -f 1764//1764 1819//1819 1816//1816 -f 1821//1821 1822//1822 1823//1823 -f 1674//1674 1749//1749 1750//1750 -f 1750//1750 1749//1749 1824//1824 -f 1750//1750 1824//1824 1820//1820 -f 1820//1820 1824//1824 1821//1821 -f 1820//1820 1821//1821 1817//1817 -f 1817//1817 1821//1821 1823//1823 -f 1817//1817 1823//1823 1818//1818 -f 1825//1825 1826//1826 1827//1827 -f 1672//1672 1757//1757 1749//1749 -f 1749//1749 1757//1757 1828//1828 -f 1749//1749 1828//1828 1824//1824 -f 1824//1824 1828//1828 1825//1825 -f 1824//1824 1825//1825 1821//1821 -f 1821//1821 1825//1825 1827//1827 -f 1821//1821 1827//1827 1822//1822 -f 1669//1669 1789//1789 1757//1757 -f 1757//1757 1789//1789 1784//1784 -f 1757//1757 1784//1784 1828//1828 -f 1828//1828 1784//1784 1786//1786 -f 1828//1828 1786//1786 1825//1825 -f 1825//1825 1786//1786 1829//1829 -f 1825//1825 1829//1829 1826//1826 -f 1830//1830 1831//1831 1767//1767 -f 1767//1767 1831//1831 1832//1832 -f 1767//1767 1832//1832 1787//1787 -f 1787//1787 1832//1832 1833//1833 -f 1787//1787 1833//1833 1785//1785 -f 1785//1785 1833//1833 1834//1834 -f 1785//1785 1834//1834 1786//1786 -f 1786//1786 1834//1834 1835//1835 -f 1786//1786 1835//1835 1829//1829 -f 1664//1664 1758//1758 1739//1739 -f 1739//1739 1758//1758 1836//1836 -f 1739//1739 1836//1836 1737//1737 -f 1737//1737 1836//1836 1724//1724 -f 1737//1737 1724//1724 1767//1767 -f 1767//1767 1724//1724 1723//1723 -f 1767//1767 1723//1723 1830//1830 -f 1758//1758 1790//1790 1836//1836 -f 1836//1836 1790//1790 1792//1792 -f 1836//1836 1792//1792 1724//1724 -f 1724//1724 1792//1792 1837//1837 -f 1724//1724 1837//1837 1722//1722 -f 1838//1838 1839//1839 1840//1840 -f 1840//1840 1839//1839 1791//1791 -f 1840//1840 1791//1791 1841//1841 -f 1841//1841 1791//1791 1790//1790 -f 1841//1841 1790//1790 1748//1748 -f 1748//1748 1790//1790 1758//1758 -f 1748//1748 1758//1758 1662//1662 -f 1662//1662 1758//1758 1663//1663 -f 1839//1839 1842//1842 1791//1791 -f 1791//1791 1842//1842 1843//1843 -f 1791//1791 1843//1843 1792//1792 -f 1792//1792 1843//1843 1844//1844 -f 1792//1792 1844//1844 1837//1837 -f 1660//1660 1659//1659 1748//1748 -f 1748//1748 1659//1659 1768//1768 -f 1748//1748 1768//1768 1841//1841 -f 1841//1841 1768//1768 1769//1769 -f 1841//1841 1769//1769 1840//1840 -f 1840//1840 1769//1769 1770//1770 -f 1840//1840 1770//1770 1838//1838 -f 1838//1838 1770//1770 1845//1845 -f 1846//1846 1847//1847 1848//1848 -f 1715//1715 1747//1747 1736//1736 -f 1736//1736 1747//1747 1849//1849 -f 1736//1736 1849//1849 1734//1734 -f 1734//1734 1849//1849 1846//1846 -f 1734//1734 1846//1846 1770//1770 -f 1770//1770 1846//1846 1848//1848 -f 1770//1770 1848//1848 1845//1845 -f 1850//1850 1851//1851 1852//1852 -f 1714//1714 1746//1746 1747//1747 -f 1747//1747 1746//1746 1853//1853 -f 1747//1747 1853//1853 1849//1849 -f 1849//1849 1853//1853 1850//1850 -f 1849//1849 1850//1850 1846//1846 -f 1846//1846 1850//1850 1852//1852 -f 1846//1846 1852//1852 1847//1847 -f 1854//1854 1855//1855 1856//1856 -f 1712//1712 1759//1759 1746//1746 -f 1746//1746 1759//1759 1857//1857 -f 1746//1746 1857//1857 1853//1853 -f 1853//1853 1857//1857 1854//1854 -f 1853//1853 1854//1854 1850//1850 -f 1850//1850 1854//1854 1856//1856 -f 1850//1850 1856//1856 1851//1851 -f 1709//1709 1798//1798 1759//1759 -f 1759//1759 1798//1798 1793//1793 -f 1759//1759 1793//1793 1857//1857 -f 1857//1857 1793//1793 1795//1795 -f 1857//1857 1795//1795 1854//1854 -f 1854//1854 1795//1795 1858//1858 -f 1854//1854 1858//1858 1855//1855 -f 1859//1859 1860//1860 1773//1773 -f 1773//1773 1860//1860 1861//1861 -f 1773//1773 1861//1861 1796//1796 -f 1796//1796 1861//1861 1862//1862 -f 1796//1796 1862//1862 1794//1794 -f 1794//1794 1862//1862 1863//1863 -f 1794//1794 1863//1863 1795//1795 -f 1795//1795 1863//1863 1864//1864 -f 1795//1795 1864//1864 1858//1858 -f 1704//1704 1760//1760 1733//1733 -f 1733//1733 1760//1760 1865//1865 -f 1733//1733 1865//1865 1731//1731 -f 1731//1731 1865//1865 1721//1721 -f 1731//1731 1721//1721 1773//1773 -f 1773//1773 1721//1721 1720//1720 -f 1773//1773 1720//1720 1859//1859 -f 1760//1760 1799//1799 1865//1865 -f 1865//1865 1799//1799 1801//1801 -f 1865//1865 1801//1801 1721//1721 -f 1721//1721 1801//1801 1866//1866 -f 1721//1721 1866//1866 1719//1719 -f 1867//1867 1868//1868 1869//1869 -f 1869//1869 1868//1868 1800//1800 -f 1869//1869 1800//1800 1870//1870 -f 1870//1870 1800//1800 1799//1799 -f 1870//1870 1799//1799 1745//1745 -f 1745//1745 1799//1799 1760//1760 -f 1745//1745 1760//1760 1702//1702 -f 1702//1702 1760//1760 1703//1703 -f 1868//1868 1871//1871 1800//1800 -f 1800//1800 1871//1871 1872//1872 -f 1800//1800 1872//1872 1801//1801 -f 1801//1801 1872//1872 1873//1873 -f 1801//1801 1873//1873 1866//1866 -f 1700//1700 1699//1699 1745//1745 -f 1745//1745 1699//1699 1774//1774 -f 1745//1745 1774//1774 1870//1870 -f 1870//1870 1774//1774 1775//1775 -f 1870//1870 1775//1775 1869//1869 -f 1869//1869 1775//1775 1776//1776 -f 1869//1869 1776//1776 1867//1867 -f 1867//1867 1776//1776 1874//1874 -f 1875//1875 1876//1876 1877//1877 -f 1695//1695 1744//1744 1730//1730 -f 1730//1730 1744//1744 1878//1878 -f 1730//1730 1878//1878 1728//1728 -f 1728//1728 1878//1878 1875//1875 -f 1728//1728 1875//1875 1776//1776 -f 1776//1776 1875//1875 1877//1877 -f 1776//1776 1877//1877 1874//1874 -f 1879//1879 1880//1880 1881//1881 -f 1694//1694 1743//1743 1744//1744 -f 1744//1744 1743//1743 1882//1882 -f 1744//1744 1882//1882 1878//1878 -f 1878//1878 1882//1882 1879//1879 -f 1878//1878 1879//1879 1875//1875 -f 1875//1875 1879//1879 1881//1881 -f 1875//1875 1881//1881 1876//1876 -f 1883//1883 1884//1884 1885//1885 -f 1692//1692 1761//1761 1743//1743 -f 1743//1743 1761//1761 1886//1886 -f 1743//1743 1886//1886 1882//1882 -f 1882//1882 1886//1886 1883//1883 -f 1882//1882 1883//1883 1879//1879 -f 1879//1879 1883//1883 1885//1885 -f 1879//1879 1885//1885 1880//1880 -f 1689//1689 1752//1752 1761//1761 -f 1761//1761 1752//1752 1780//1780 -f 1761//1761 1780//1780 1886//1886 -f 1886//1886 1780//1780 1805//1805 -f 1886//1886 1805//1805 1883//1883 -f 1883//1883 1805//1805 1887//1887 -f 1883//1883 1887//1887 1884//1884 -f 1807//1807 1888//1888 1802//1802 -f 1802//1802 1888//1888 1889//1889 -f 1802//1802 1889//1889 1803//1803 -f 1803//1803 1889//1889 1890//1890 -f 1803//1803 1890//1890 1804//1804 -f 1804//1804 1890//1890 1891//1891 -f 1804//1804 1891//1891 1805//1805 -f 1805//1805 1891//1891 1892//1892 -f 1805//1805 1892//1892 1887//1887 -f 1810//1810 1893//1893 1813//1813 -f 1813//1813 1893//1893 1894//1894 -f 1813//1813 1894//1894 1814//1814 -f 1814//1814 1894//1894 1895//1895 -f 1814//1814 1895//1895 1815//1815 -f 1815//1815 1895//1895 1896//1896 -f 1815//1815 1896//1896 1808//1808 -f 1827//1827 1897//1897 1822//1822 -f 1822//1822 1897//1897 1898//1898 -f 1822//1822 1898//1898 1823//1823 -f 1823//1823 1898//1898 1899//1899 -f 1823//1823 1899//1899 1818//1818 -f 1818//1818 1899//1899 1900//1900 -f 1818//1818 1900//1900 1819//1819 -f 1819//1819 1900//1900 1901//1901 -f 1819//1819 1901//1901 1816//1816 -f 1816//1816 1901//1901 1902//1902 -f 1816//1816 1902//1902 1809//1809 -f 1809//1809 1902//1902 1903//1903 -f 1809//1809 1903//1903 1810//1810 -f 1810//1810 1903//1903 1904//1904 -f 1810//1810 1904//1904 1893//1893 -f 1832//1832 1905//1905 1833//1833 -f 1833//1833 1905//1905 1906//1906 -f 1833//1833 1906//1906 1834//1834 -f 1834//1834 1906//1906 1907//1907 -f 1834//1834 1907//1907 1835//1835 -f 1835//1835 1907//1907 1908//1908 -f 1835//1835 1908//1908 1829//1829 -f 1829//1829 1908//1908 1909//1909 -f 1829//1829 1909//1909 1826//1826 -f 1826//1826 1909//1909 1910//1910 -f 1826//1826 1910//1910 1827//1827 -f 1827//1827 1910//1910 1911//1911 -f 1827//1827 1911//1911 1897//1897 -f 1831//1831 1912//1912 1832//1832 -f 1832//1832 1912//1912 1913//1913 -f 1832//1832 1913//1913 1905//1905 -f 1843//1843 1914//1914 1844//1844 -f 1844//1844 1914//1914 1915//1915 -f 1844//1844 1915//1915 1837//1837 -f 1837//1837 1915//1915 1916//1916 -f 1837//1837 1916//1916 1722//1722 -f 1722//1722 1916//1916 1917//1917 -f 1722//1722 1917//1917 1723//1723 -f 1723//1723 1917//1917 1918//1918 -f 1723//1723 1918//1918 1830//1830 -f 1830//1830 1918//1918 1919//1919 -f 1830//1830 1919//1919 1831//1831 -f 1831//1831 1919//1919 1920//1920 -f 1831//1831 1920//1920 1912//1912 -f 1845//1845 1921//1921 1838//1838 -f 1838//1838 1921//1921 1922//1922 -f 1838//1838 1922//1922 1839//1839 -f 1839//1839 1922//1922 1923//1923 -f 1839//1839 1923//1923 1842//1842 -f 1842//1842 1923//1923 1924//1924 -f 1842//1842 1924//1924 1843//1843 -f 1843//1843 1924//1924 1925//1925 -f 1843//1843 1925//1925 1914//1914 -f 1858//1858 1926//1926 1855//1855 -f 1855//1855 1926//1926 1927//1927 -f 1855//1855 1927//1927 1856//1856 -f 1856//1856 1927//1927 1928//1928 -f 1856//1856 1928//1928 1851//1851 -f 1851//1851 1928//1928 1929//1929 -f 1851//1851 1929//1929 1852//1852 -f 1852//1852 1929//1929 1930//1930 -f 1852//1852 1930//1930 1847//1847 -f 1847//1847 1930//1930 1931//1931 -f 1847//1847 1931//1931 1848//1848 -f 1848//1848 1931//1931 1932//1932 -f 1848//1848 1932//1932 1845//1845 -f 1845//1845 1932//1932 1933//1933 -f 1845//1845 1933//1933 1921//1921 -f 1861//1861 1934//1934 1862//1862 -f 1862//1862 1934//1934 1935//1935 -f 1862//1862 1935//1935 1863//1863 -f 1863//1863 1935//1935 1936//1936 -f 1863//1863 1936//1936 1864//1864 -f 1864//1864 1936//1936 1937//1937 -f 1864//1864 1937//1937 1858//1858 -f 1858//1858 1937//1937 1938//1938 -f 1858//1858 1938//1938 1926//1926 -f 1720//1720 1939//1939 1859//1859 -f 1859//1859 1939//1939 1940//1940 -f 1859//1859 1940//1940 1860//1860 -f 1860//1860 1940//1940 1941//1941 -f 1860//1860 1941//1941 1861//1861 -f 1861//1861 1941//1941 1942//1942 -f 1861//1861 1942//1942 1934//1934 -f 1872//1872 1943//1943 1873//1873 -f 1873//1873 1943//1943 1944//1944 -f 1873//1873 1944//1944 1866//1866 -f 1866//1866 1944//1944 1945//1945 -f 1866//1866 1945//1945 1719//1719 -f 1719//1719 1945//1945 1946//1946 -f 1719//1719 1946//1946 1720//1720 -f 1720//1720 1946//1946 1947//1947 -f 1720//1720 1947//1947 1939//1939 -f 1881//1881 1948//1948 1876//1876 -f 1876//1876 1948//1948 1949//1949 -f 1876//1876 1949//1949 1877//1877 -f 1877//1877 1949//1949 1950//1950 -f 1877//1877 1950//1950 1874//1874 -f 1874//1874 1950//1950 1951//1951 -f 1874//1874 1951//1951 1867//1867 -f 1867//1867 1951//1951 1952//1952 -f 1867//1867 1952//1952 1868//1868 -f 1868//1868 1952//1952 1953//1953 -f 1868//1868 1953//1953 1871//1871 -f 1871//1871 1953//1953 1954//1954 -f 1871//1871 1954//1954 1872//1872 -f 1872//1872 1954//1954 1955//1955 -f 1872//1872 1955//1955 1943//1943 -f 1891//1891 1956//1956 1892//1892 -f 1892//1892 1956//1956 1957//1957 -f 1892//1892 1957//1957 1887//1887 -f 1887//1887 1957//1957 1958//1958 -f 1887//1887 1958//1958 1884//1884 -f 1884//1884 1958//1958 1959//1959 -f 1884//1884 1959//1959 1885//1885 -f 1885//1885 1959//1959 1960//1960 -f 1885//1885 1960//1960 1880//1880 -f 1880//1880 1960//1960 1961//1961 -f 1880//1880 1961//1961 1881//1881 -f 1881//1881 1961//1961 1962//1962 -f 1881//1881 1962//1962 1948//1948 -f 1896//1896 1963//1963 1808//1808 -f 1808//1808 1963//1963 1964//1964 -f 1808//1808 1964//1964 1725//1725 -f 1725//1725 1964//1964 1965//1965 -f 1725//1725 1965//1965 1726//1726 -f 1726//1726 1965//1965 1966//1966 -f 1726//1726 1966//1966 1807//1807 -f 1807//1807 1966//1966 1967//1967 -f 1807//1807 1967//1967 1888//1888 -f 1888//1888 1967//1967 1968//1968 -f 1888//1888 1968//1968 1889//1889 -f 1889//1889 1968//1968 1969//1969 -f 1889//1889 1969//1969 1890//1890 -f 1890//1890 1969//1969 1970//1970 -f 1890//1890 1970//1970 1891//1891 -f 1891//1891 1970//1970 1971//1971 -f 1891//1891 1971//1971 1956//1956 -f 1972//1972 1973//1973 1974//1974 -f 1975//1975 1976//1976 1977//1977 -f 1977//1977 1976//1976 1978//1978 -f 1979//1979 1980//1980 1981//1981 -f 1981//1981 1980//1980 1982//1982 -f 1983//1983 1984//1984 1985//1985 -f 1986//1986 1987//1987 1988//1988 -f 1989//1989 1990//1990 1991//1991 -f 1992//1992 1993//1993 1994//1994 -f 1995//1995 1996//1996 1997//1997 -f 1998//1998 1999//1999 2000//2000 -f 2001//2001 2002//2002 2003//2003 -f 2004//2004 2005//2005 2006//2006 -f 1970//1970 1969//1969 2004//2004 -f 1957//1957 1956//1956 2007//2007 -f 1960//1960 1959//1959 1989//1989 -f 1962//1962 1961//1961 2008//2008 -f 1949//1949 1948//1948 2009//2009 -f 1950//1950 1949//1949 2010//2010 -f 1952//1952 1951//1951 2011//2011 -f 1944//1944 1943//1943 1992//1992 -f 1946//1946 1945//1945 2012//2012 -f 1939//1939 1947//1947 2013//2013 -f 1940//1940 1939//1939 2014//2014 -f 1938//1938 1937//1937 2015//2015 -f 1930//1930 1929//1929 1995//1995 -f 1932//1932 1931//1931 2016//2016 -f 1921//1921 1933//1933 2017//2017 -f 1922//1922 1921//1921 2018//2018 -f 1917//1917 1916//1916 2019//2019 -f 1913//1913 1912//1912 1998//1998 -f 1906//1906 1905//1905 2020//2020 -f 1908//1908 1907//1907 2021//2021 -f 1909//1909 1908//1908 2022//2022 -f 1911//1911 1910//1910 2023//2023 -f 1901//1901 1900//1900 2001//2001 -f 1903//1903 1902//1902 2024//2024 -f 1893//1893 1904//1904 2025//2025 -f 1894//1894 1893//1893 2026//2026 -f 1967//1967 1966//1966 2027//2027 -f 2004//2004 1969//1969 2005//2005 -f 2005//2005 1969//1969 1968//1968 -f 2005//2005 1968//1968 1967//1967 -f 2027//2027 1966//1966 2028//2028 -f 1966//1966 1965//1965 2028//2028 -f 2028//2028 1965//1965 1964//1964 -f 2028//2028 1964//1964 2029//2029 -f 2029//2029 1964//1964 1963//1963 -f 2029//2029 1963//1963 1896//1896 -f 1896//1896 1895//1895 2030//2030 -f 2030//2030 1895//1895 1894//1894 -f 2001//2001 1900//1900 2002//2002 -f 2002//2002 1900//1900 1899//1899 -f 2002//2002 1899//1899 1898//1898 -f 1898//1898 1897//1897 2031//2031 -f 2031//2031 1897//1897 1911//1911 -f 1909//1909 2022//2022 1910//1910 -f 1998//1998 1912//1912 1999//1999 -f 1999//1999 1912//1912 1920//1920 -f 1999//1999 1920//1920 1919//1919 -f 1919//1919 1918//1918 2032//2032 -f 2032//2032 1918//1918 1917//1917 -f 2019//2019 1916//1916 2033//2033 -f 1916//1916 1915//1915 2033//2033 -f 2033//2033 1915//1915 1914//1914 -f 2033//2033 1914//1914 2034//2034 -f 1923//1923 2035//2035 1924//1924 -f 1924//1924 2035//2035 2034//2034 -f 1924//1924 2034//2034 1925//1925 -f 1925//1925 2034//2034 1914//1914 -f 1922//1922 2018//2018 1923//1923 -f 1995//1995 1929//1929 1996//1996 -f 1996//1996 1929//1929 1928//1928 -f 1996//1996 1928//1928 1927//1927 -f 1927//1927 1926//1926 2036//2036 -f 2036//2036 1926//1926 1938//1938 -f 2015//2015 1937//1937 2037//2037 -f 1937//1937 1936//1936 2037//2037 -f 2037//2037 1936//1936 1935//1935 -f 2037//2037 1935//1935 2038//2038 -f 1935//1935 1934//1934 2038//2038 -f 2038//2038 1934//1934 1942//1942 -f 2038//2038 1942//1942 2039//2039 -f 2039//2039 1942//1942 1941//1941 -f 2039//2039 1941//1941 1940//1940 -f 1992//1992 1943//1943 1993//1993 -f 1993//1993 1943//1943 1955//1955 -f 1993//1993 1955//1955 1954//1954 -f 1954//1954 1953//1953 2040//2040 -f 2040//2040 1953//1953 1952//1952 -f 1950//1950 2010//2010 1951//1951 -f 1989//1989 1959//1959 1990//1990 -f 1990//1990 1959//1959 1958//1958 -f 1990//1990 1958//1958 1957//1957 -f 2029//2029 2041//2041 2028//2028 -f 2028//2028 2041//2041 2042//2042 -f 2028//2028 2042//2042 2027//2027 -f 2027//2027 2042//2042 1988//1988 -f 2043//2043 2044//2044 2025//2025 -f 1904//1904 1903//1903 2025//2025 -f 2025//2025 1903//1903 2024//2024 -f 2025//2025 2024//2024 2043//2043 -f 2043//2043 2024//2024 2045//2045 -f 2043//2043 2045//2045 2046//2046 -f 2046//2046 2045//2045 2047//2047 -f 2048//2048 2049//2049 2021//2021 -f 1907//1907 1906//1906 2021//2021 -f 2021//2021 1906//1906 2020//2020 -f 2021//2021 2020//2020 2048//2048 -f 2048//2048 2020//2020 2050//2050 -f 2048//2048 2050//2050 2051//2051 -f 2051//2051 2050//2050 2052//2052 -f 2035//2035 1981//1981 2034//2034 -f 2034//2034 1981//1981 1982//1982 -f 2034//2034 1982//1982 2033//2033 -f 2033//2033 1982//1982 2053//2053 -f 2033//2033 2053//2053 2019//2019 -f 2019//2019 2053//2053 2054//2054 -f 2055//2055 2056//2056 2017//2017 -f 1933//1933 1932//1932 2017//2017 -f 2017//2017 1932//1932 2016//2016 -f 2017//2017 2016//2016 2055//2055 -f 2055//2055 2016//2016 2057//2057 -f 2055//2055 2057//2057 2058//2058 -f 2058//2058 2057//2057 2059//2059 -f 2039//2039 1977//1977 2038//2038 -f 2038//2038 1977//1977 1978//1978 -f 2038//2038 1978//1978 2037//2037 -f 2037//2037 1978//1978 2060//2060 -f 2037//2037 2060//2060 2015//2015 -f 2015//2015 2060//2060 2061//2061 -f 2062//2062 2063//2063 2013//2013 -f 1947//1947 1946//1946 2013//2013 -f 2013//2013 1946//1946 2012//2012 -f 2013//2013 2012//2012 2062//2062 -f 2062//2062 2012//2012 2064//2064 -f 2062//2062 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2067//2067 2068//2068 2009//2009 -f 2069//2069 2070//2070 2007//2007 -f 1956//1956 1971//1971 2007//2007 -f 2007//2007 1971//1971 2071//2071 -f 2007//2007 2071//2071 2069//2069 -f 2069//2069 2071//2071 2072//2072 -f 2073//2073 2074//2074 2006//2006 -f 2006//2006 2074//2074 2072//2072 -f 2006//2006 2072//2072 2004//2004 -f 2004//2004 2072//2072 2071//2071 -f 2004//2004 2071//2071 1970//1970 -f 1970//1970 2071//2071 1971//1971 -f 1967//1967 2027//2027 2005//2005 -f 2005//2005 2027//2027 1988//1988 -f 2005//2005 1988//1988 2006//2006 -f 2006//2006 1988//1988 1987//1987 -f 2006//2006 1987//1987 2073//2073 -f 1986//1986 1988//1988 2075//2075 -f 2075//2075 1988//1988 2042//2042 -f 2075//2075 2042//2042 2076//2076 -f 2076//2076 2042//2042 2041//2041 -f 2076//2076 2041//2041 2077//2077 -f 2078//2078 2079//2079 2080//2080 -f 1896//1896 2030//2030 2029//2029 -f 2029//2029 2030//2030 2078//2078 -f 2029//2029 2078//2078 2041//2041 -f 2041//2041 2078//2078 2080//2080 -f 2041//2041 2080//2080 2077//2077 -f 1894//1894 2026//2026 2030//2030 -f 2030//2030 2026//2026 2081//2081 -f 2030//2030 2081//2081 2078//2078 -f 2078//2078 2081//2081 2082//2082 -f 2078//2078 2082//2082 2079//2079 -f 1893//1893 2025//2025 2026//2026 -f 2026//2026 2025//2025 2044//2044 -f 2026//2026 2044//2044 2081//2081 -f 2081//2081 2044//2044 2083//2083 -f 2081//2081 2083//2083 2082//2082 -f 2046//2046 2084//2084 2043//2043 -f 2043//2043 2084//2084 2085//2085 -f 2043//2043 2085//2085 2044//2044 -f 2044//2044 2085//2085 2086//2086 -f 2044//2044 2086//2086 2083//2083 -f 1902//1902 1901//1901 2024//2024 -f 2024//2024 1901//1901 2001//2001 -f 2024//2024 2001//2001 2045//2045 -f 2045//2045 2001//2001 2003//2003 -f 2045//2045 2003//2003 2047//2047 -f 2047//2047 2003//2003 2087//2087 -f 2088//2088 2089//2089 2090//2090 -f 1898//1898 2031//2031 2002//2002 -f 2002//2002 2031//2031 2088//2088 -f 2002//2002 2088//2088 2003//2003 -f 2003//2003 2088//2088 2090//2090 -f 2003//2003 2090//2090 2087//2087 -f 1911//1911 2023//2023 2031//2031 -f 2031//2031 2023//2023 1985//1985 -f 2031//2031 1985//1985 2088//2088 -f 2088//2088 1985//1985 1984//1984 -f 2088//2088 1984//1984 2089//2089 -f 1910//1910 2022//2022 2023//2023 -f 2023//2023 2022//2022 2091//2091 -f 2023//2023 2091//2091 1985//1985 -f 1985//1985 2091//2091 2092//2092 -f 1985//1985 2092//2092 1983//1983 -f 1908//1908 2021//2021 2022//2022 -f 2022//2022 2021//2021 2049//2049 -f 2022//2022 2049//2049 2091//2091 -f 2091//2091 2049//2049 2093//2093 -f 2091//2091 2093//2093 2092//2092 -f 2051//2051 2094//2094 2048//2048 -f 2048//2048 2094//2094 2095//2095 -f 2048//2048 2095//2095 2049//2049 -f 2049//2049 2095//2095 2096//2096 -f 2049//2049 2096//2096 2093//2093 -f 1905//1905 1913//1913 2020//2020 -f 2020//2020 1913//1913 1998//1998 -f 2020//2020 1998//1998 2050//2050 -f 2050//2050 1998//1998 2000//2000 -f 2050//2050 2000//2000 2052//2052 -f 2052//2052 2000//2000 2097//2097 -f 2098//2098 2099//2099 2100//2100 -f 1919//1919 2032//2032 1999//1999 -f 1999//1999 2032//2032 2098//2098 -f 1999//1999 2098//2098 2000//2000 -f 2000//2000 2098//2098 2100//2100 -f 2000//2000 2100//2100 2097//2097 -f 1917//1917 2019//2019 2032//2032 -f 2032//2032 2019//2019 2054//2054 -f 2032//2032 2054//2054 2098//2098 -f 2098//2098 2054//2054 2101//2101 -f 2098//2098 2101//2101 2099//2099 -f 1980//1980 2102//2102 1982//1982 -f 1982//1982 2102//2102 2103//2103 -f 1982//1982 2103//2103 2053//2053 -f 2053//2053 2103//2103 2104//2104 -f 2053//2053 2104//2104 2054//2054 -f 2054//2054 2104//2104 2105//2105 -f 2054//2054 2105//2105 2101//2101 -f 1923//1923 2018//2018 2035//2035 -f 2035//2035 2018//2018 2106//2106 -f 2035//2035 2106//2106 1981//1981 -f 1981//1981 2106//2106 2107//2107 -f 1981//1981 2107//2107 1979//1979 -f 1921//1921 2017//2017 2018//2018 -f 2018//2018 2017//2017 2056//2056 -f 2018//2018 2056//2056 2106//2106 -f 2106//2106 2056//2056 2108//2108 -f 2106//2106 2108//2108 2107//2107 -f 2058//2058 2109//2109 2055//2055 -f 2055//2055 2109//2109 2110//2110 -f 2055//2055 2110//2110 2056//2056 -f 2056//2056 2110//2110 2111//2111 -f 2056//2056 2111//2111 2108//2108 -f 1931//1931 1930//1930 2016//2016 -f 2016//2016 1930//1930 1995//1995 -f 2016//2016 1995//1995 2057//2057 -f 2057//2057 1995//1995 1997//1997 -f 2057//2057 1997//1997 2059//2059 -f 2059//2059 1997//1997 2112//2112 -f 2113//2113 2114//2114 2115//2115 -f 1927//1927 2036//2036 1996//1996 -f 1996//1996 2036//2036 2113//2113 -f 1996//1996 2113//2113 1997//1997 -f 1997//1997 2113//2113 2115//2115 -f 1997//1997 2115//2115 2112//2112 -f 1938//1938 2015//2015 2036//2036 -f 2036//2036 2015//2015 2061//2061 -f 2036//2036 2061//2061 2113//2113 -f 2113//2113 2061//2061 2116//2116 -f 2113//2113 2116//2116 2114//2114 -f 1976//1976 2117//2117 1978//1978 -f 1978//1978 2117//2117 2118//2118 -f 1978//1978 2118//2118 2060//2060 -f 2060//2060 2118//2118 2119//2119 -f 2060//2060 2119//2119 2061//2061 -f 2061//2061 2119//2119 2120//2120 -f 2061//2061 2120//2120 2116//2116 -f 1940//1940 2014//2014 2039//2039 -f 2039//2039 2014//2014 2121//2121 -f 2039//2039 2121//2121 1977//1977 -f 1977//1977 2121//2121 2122//2122 -f 1977//1977 2122//2122 1975//1975 -f 1939//1939 2013//2013 2014//2014 -f 2014//2014 2013//2013 2063//2063 -f 2014//2014 2063//2063 2121//2121 -f 2121//2121 2063//2063 2123//2123 -f 2121//2121 2123//2123 2122//2122 -f 2065//2065 2124//2124 2062//2062 -f 2062//2062 2124//2124 2125//2125 -f 2062//2062 2125//2125 2063//2063 -f 2063//2063 2125//2125 2126//2126 -f 2063//2063 2126//2126 2123//2123 -f 1945//1945 1944//1944 2012//2012 -f 2012//2012 1944//1944 1992//1992 -f 2012//2012 1992//1992 2064//2064 -f 2064//2064 1992//1992 1994//1994 -f 2064//2064 1994//1994 2066//2066 -f 2066//2066 1994//1994 2127//2127 -f 2128//2128 2129//2129 2130//2130 -f 1954//1954 2040//2040 1993//1993 -f 1993//1993 2040//2040 2128//2128 -f 1993//1993 2128//2128 1994//1994 -f 1994//1994 2128//2128 2130//2130 -f 1994//1994 2130//2130 2127//2127 -f 1952//1952 2011//2011 2040//2040 -f 2040//2040 2011//2011 1974//1974 -f 2040//2040 1974//1974 2128//2128 -f 2128//2128 1974//1974 1973//1973 -f 2128//2128 1973//1973 2129//2129 -f 1951//1951 2010//2010 2011//2011 -f 2011//2011 2010//2010 2131//2131 -f 2011//2011 2131//2131 1974//1974 -f 1974//1974 2131//2131 2132//2132 -f 1974//1974 2132//2132 1972//1972 -f 1949//1949 2009//2009 2010//2010 -f 2010//2010 2009//2009 2068//2068 -f 2010//2010 2068//2068 2131//2131 -f 2131//2131 2068//2068 2133//2133 -f 2131//2131 2133//2133 2132//2132 -f 2134//2134 2135//2135 2136//2136 -f 2136//2136 2135//2135 2067//2067 -f 2136//2136 2067//2067 2008//2008 -f 2008//2008 2067//2067 2009//2009 -f 2008//2008 2009//2009 1962//1962 -f 1962//1962 2009//2009 1948//1948 -f 2135//2135 2137//2137 2067//2067 -f 2067//2067 2137//2137 2138//2138 -f 2067//2067 2138//2138 2068//2068 -f 2068//2068 2138//2138 2139//2139 -f 2068//2068 2139//2139 2133//2133 -f 1961//1961 1960//1960 2008//2008 -f 2008//2008 1960//1960 1989//1989 -f 2008//2008 1989//1989 2136//2136 -f 2136//2136 1989//1989 1991//1991 -f 2136//2136 1991//1991 2134//2134 -f 2134//2134 1991//1991 2140//2140 -f 1957//1957 2007//2007 1990//1990 -f 1990//1990 2007//2007 2070//2070 -f 1990//1990 2070//2070 1991//1991 -f 1991//1991 2070//2070 2141//2141 -f 1991//1991 2141//2141 2140//2140 -f 2074//2074 2142//2142 2072//2072 -f 2072//2072 2142//2142 2143//2143 -f 2072//2072 2143//2143 2069//2069 -f 2069//2069 2143//2143 2144//2144 -f 2069//2069 2144//2144 2070//2070 -f 2070//2070 2144//2144 2145//2145 -f 2070//2070 2145//2145 2141//2141 -f 2146//2146 2147//2147 2104//2104 -f 2104//2104 2147//2147 2105//2105 -f 2105//2105 2147//2147 2148//2148 -f 2105//2105 2148//2148 2101//2101 -f 2101//2101 2148//2148 2149//2149 -f 2101//2101 2149//2149 2099//2099 -f 2099//2099 2149//2149 2150//2150 -f 2099//2099 2150//2150 2100//2100 -f 2100//2100 2150//2150 2097//2097 -f 2097//2097 2150//2150 2151//2151 -f 2097//2097 2151//2151 2052//2052 -f 2151//2151 2152//2152 2052//2052 -f 2052//2052 2152//2152 2153//2153 -f 2052//2052 2153//2153 2051//2051 -f 2051//2051 2153//2153 2154//2154 -f 2155//2155 1984//1984 2156//2156 -f 2156//2156 1984//1984 1983//1983 -f 2156//2156 1983//1983 2157//2157 -f 2157//2157 1983//1983 2092//2092 -f 2157//2157 2092//2092 2158//2158 -f 2158//2158 2092//2092 2093//2093 -f 2158//2158 2093//2093 2159//2159 -f 2159//2159 2093//2093 2096//2096 -f 2159//2159 2096//2096 2160//2160 -f 2160//2160 2096//2096 2095//2095 -f 2160//2160 2095//2095 2154//2154 -f 2154//2154 2095//2095 2094//2094 -f 2154//2154 2094//2094 2051//2051 -f 2161//2161 2082//2082 2162//2162 -f 2162//2162 2082//2082 2083//2083 -f 2162//2162 2083//2083 2163//2163 -f 2163//2163 2083//2083 2086//2086 -f 2163//2163 2086//2086 2164//2164 -f 2164//2164 2086//2086 2085//2085 -f 2164//2164 2085//2085 2165//2165 -f 2165//2165 2085//2085 2084//2084 -f 2165//2165 2084//2084 2166//2166 -f 2166//2166 2084//2084 2046//2046 -f 2166//2166 2046//2046 2167//2167 -f 2167//2167 2046//2046 2047//2047 -f 2167//2167 2047//2047 2168//2168 -f 2168//2168 2047//2047 2087//2087 -f 2168//2168 2087//2087 2169//2169 -f 2169//2169 2087//2087 2090//2090 -f 2169//2169 2090//2090 2155//2155 -f 2155//2155 2090//2090 2089//2089 -f 2155//2155 2089//2089 1984//1984 -f 2170//2170 1987//1987 2171//2171 -f 2171//2171 1987//1987 1986//1986 -f 2171//2171 1986//1986 2172//2172 -f 2172//2172 1986//1986 2075//2075 -f 2172//2172 2075//2075 2173//2173 -f 2173//2173 2075//2075 2076//2076 -f 2173//2173 2076//2076 2174//2174 -f 2174//2174 2076//2076 2077//2077 -f 2174//2174 2077//2077 2175//2175 -f 2175//2175 2077//2077 2080//2080 -f 2175//2175 2080//2080 2161//2161 -f 2161//2161 2080//2080 2079//2079 -f 2161//2161 2079//2079 2082//2082 -f 2176//2176 2145//2145 2177//2177 -f 2177//2177 2145//2145 2144//2144 -f 2177//2177 2144//2144 2178//2178 -f 2178//2178 2144//2144 2143//2143 -f 2178//2178 2143//2143 2179//2179 -f 2179//2179 2143//2143 2142//2142 -f 2179//2179 2142//2142 2180//2180 -f 2180//2180 2142//2142 2074//2074 -f 2180//2180 2074//2074 2170//2170 -f 2170//2170 2074//2074 2073//2073 -f 2170//2170 2073//2073 1987//1987 -f 2181//2181 1973//1973 2182//2182 -f 2182//2182 1973//1973 1972//1972 -f 2182//2182 1972//1972 2183//2183 -f 2183//2183 1972//1972 2132//2132 -f 2183//2183 2132//2132 2184//2184 -f 2184//2184 2132//2132 2133//2133 -f 2184//2184 2133//2133 2185//2185 -f 2185//2185 2133//2133 2139//2139 -f 2185//2185 2139//2139 2186//2186 -f 2186//2186 2139//2139 2138//2138 -f 2186//2186 2138//2138 2187//2187 -f 2187//2187 2138//2138 2137//2137 -f 2187//2187 2137//2137 2188//2188 -f 2188//2188 2137//2137 2135//2135 -f 2188//2188 2135//2135 2189//2189 -f 2189//2189 2135//2135 2134//2134 -f 2189//2189 2134//2134 2190//2190 -f 2190//2190 2134//2134 2140//2140 -f 2190//2190 2140//2140 2176//2176 -f 2176//2176 2140//2140 2141//2141 -f 2176//2176 2141//2141 2145//2145 -f 2191//2191 2124//2124 2192//2192 -f 2192//2192 2124//2124 2065//2065 -f 2192//2192 2065//2065 2193//2193 -f 2193//2193 2065//2065 2066//2066 -f 2193//2193 2066//2066 2194//2194 -f 2194//2194 2066//2066 2127//2127 -f 2194//2194 2127//2127 2195//2195 -f 2195//2195 2127//2127 2130//2130 -f 2195//2195 2130//2130 2181//2181 -f 2181//2181 2130//2130 2129//2129 -f 2181//2181 2129//2129 1973//1973 -f 2196//2196 2116//2116 2197//2197 -f 2197//2197 2116//2116 2120//2120 -f 2197//2197 2120//2120 2198//2198 -f 2198//2198 2120//2120 2119//2119 -f 2198//2198 2119//2119 2199//2199 -f 2199//2199 2119//2119 2118//2118 -f 2199//2199 2118//2118 2200//2200 -f 2200//2200 2118//2118 2117//2117 -f 2200//2200 2117//2117 2201//2201 -f 2201//2201 2117//2117 1976//1976 -f 2201//2201 1976//1976 2202//2202 -f 2202//2202 1976//1976 1975//1975 -f 2202//2202 1975//1975 2203//2203 -f 2203//2203 1975//1975 2122//2122 -f 2203//2203 2122//2122 2204//2204 -f 2204//2204 2122//2122 2123//2123 -f 2204//2204 2123//2123 2205//2205 -f 2205//2205 2123//2123 2126//2126 -f 2205//2205 2126//2126 2191//2191 -f 2191//2191 2126//2126 2125//2125 -f 2191//2191 2125//2125 2124//2124 -f 2206//2206 2058//2058 2207//2207 -f 2207//2207 2058//2058 2059//2059 -f 2207//2207 2059//2059 2208//2208 -f 2208//2208 2059//2059 2112//2112 -f 2208//2208 2112//2112 2209//2209 -f 2209//2209 2112//2112 2115//2115 -f 2209//2209 2115//2115 2196//2196 -f 2196//2196 2115//2115 2114//2114 -f 2196//2196 2114//2114 2116//2116 -f 2104//2104 2103//2103 2146//2146 -f 2146//2146 2103//2103 2102//2102 -f 2146//2146 2102//2102 2210//2210 -f 2210//2210 2102//2102 1980//1980 -f 2210//2210 1980//1980 2211//2211 -f 2211//2211 1980//1980 1979//1979 -f 2211//2211 1979//1979 2212//2212 -f 2212//2212 1979//1979 2107//2107 -f 2212//2212 2107//2107 2213//2213 -f 2213//2213 2107//2107 2108//2108 -f 2213//2213 2108//2108 2214//2214 -f 2214//2214 2108//2108 2111//2111 -f 2214//2214 2111//2111 2215//2215 -f 2215//2215 2111//2111 2110//2110 -f 2215//2215 2110//2110 2206//2206 -f 2206//2206 2110//2110 2109//2109 -f 2206//2206 2109//2109 2058//2058 -f 2216//2216 2217//2217 2218//2218 -f 2219//2219 2220//2220 2221//2221 -f 2222//2222 2223//2223 2224//2224 -f 2225//2225 2226//2226 2227//2227 -f 2228//2228 2229//2229 2230//2230 -f 2231//2231 2232//2232 2233//2233 -f 2234//2234 2235//2235 2236//2236 -f 2237//2237 2238//2238 2239//2239 -f 2240//2240 2241//2241 2242//2242 -f 2243//2243 2244//2244 2245//2245 -f 2246//2246 2247//2247 2248//2248 -f 2249//2249 2250//2250 2251//2251 -f 2252//2252 2253//2253 2254//2254 -f 2242//2242 2255//2255 2256//2256 -f 2253//2253 2257//2257 2258//2258 -f 2255//2255 2259//2259 2260//2260 -f 2184//2184 2185//2185 2261//2261 -f 2182//2182 2183//2183 2262//2262 -f 2191//2191 2192//2192 2263//2263 -f 2209//2209 2196//2196 2264//2264 -f 2213//2213 2214//2214 2265//2265 -f 2211//2211 2212//2212 2266//2266 -f 2146//2146 2210//2210 2267//2267 -f 2148//2148 2147//2147 2268//2268 -f 2150//2150 2149//2149 2269//2269 -f 2165//2165 2166//2166 2270//2270 -f 2163//2163 2164//2164 2271//2271 -f 2175//2175 2161//2161 2272//2272 -f 2180//2180 2273//2273 2274//2274 -f 2170//2170 2171//2171 2275//2275 -f 2172//2172 2173//2173 2276//2276 -f 2175//2175 2272//2272 2174//2174 -f 2156//2156 2277//2277 2260//2260 -f 2167//2167 2168//2168 2259//2259 -f 2259//2259 2168//2168 2169//2169 -f 2259//2259 2169//2169 2260//2260 -f 2260//2260 2169//2169 2155//2155 -f 2260//2260 2155//2155 2156//2156 -f 2156//2156 2157//2157 2277//2277 -f 2277//2277 2157//2157 2158//2158 -f 2277//2277 2158//2158 2278//2278 -f 2278//2278 2158//2158 2159//2159 -f 2278//2278 2159//2159 2279//2279 -f 2159//2159 2160//2160 2279//2279 -f 2279//2279 2160//2160 2154//2154 -f 2279//2279 2154//2154 2280//2280 -f 2280//2280 2154//2154 2153//2153 -f 2280//2280 2153//2153 2152//2152 -f 2206//2206 2207//2207 2281//2281 -f 2209//2209 2264//2264 2208//2208 -f 2197//2197 2198//2198 2257//2257 -f 2257//2257 2198//2198 2199//2199 -f 2257//2257 2199//2199 2258//2258 -f 2258//2258 2199//2199 2200//2200 -f 2258//2258 2200//2200 2282//2282 -f 2200//2200 2201//2201 2282//2282 -f 2282//2282 2201//2201 2202//2202 -f 2282//2282 2202//2202 2283//2283 -f 2205//2205 2284//2284 2204//2204 -f 2204//2204 2284//2284 2283//2283 -f 2204//2204 2283//2283 2203//2203 -f 2203//2203 2283//2283 2202//2202 -f 2194//2194 2195//2195 2285//2285 -f 2182//2182 2262//2262 2181//2181 -f 2187//2187 2188//2188 2286//2286 -f 2286//2286 2188//2188 2189//2189 -f 2286//2286 2189//2189 2287//2287 -f 2189//2189 2190//2190 2287//2287 -f 2287//2287 2190//2190 2176//2176 -f 2287//2287 2176//2176 2288//2288 -f 2176//2176 2177//2177 2288//2288 -f 2288//2288 2177//2177 2178//2178 -f 2288//2288 2178//2178 2274//2274 -f 2274//2274 2178//2178 2179//2179 -f 2274//2274 2179//2179 2180//2180 -f 2273//2273 2289//2289 2290//2290 -f 2255//2255 2260//2260 2256//2256 -f 2256//2256 2260//2260 2277//2277 -f 2256//2256 2277//2277 2291//2291 -f 2291//2291 2277//2277 2278//2278 -f 2291//2291 2278//2278 2292//2292 -f 2292//2292 2278//2278 2279//2279 -f 2292//2292 2279//2279 2293//2293 -f 2293//2293 2279//2279 2280//2280 -f 2293//2293 2280//2280 2294//2294 -f 2253//2253 2258//2258 2254//2254 -f 2254//2254 2258//2258 2282//2282 -f 2254//2254 2282//2282 2295//2295 -f 2295//2295 2282//2282 2283//2283 -f 2295//2295 2283//2283 2296//2296 -f 2296//2296 2283//2283 2284//2284 -f 2296//2296 2284//2284 2297//2297 -f 2273//2273 2290//2290 2274//2274 -f 2274//2274 2290//2290 2298//2298 -f 2274//2274 2298//2298 2288//2288 -f 2288//2288 2298//2298 2299//2299 -f 2288//2288 2299//2299 2287//2287 -f 2287//2287 2299//2299 2300//2300 -f 2287//2287 2300//2300 2286//2286 -f 2289//2289 2301//2301 2302//2302 -f 2161//2161 2162//2162 2272//2272 -f 2272//2272 2162//2162 2303//2303 -f 2272//2272 2303//2303 2304//2304 -f 2304//2304 2303//2303 2305//2305 -f 2304//2304 2305//2305 2306//2306 -f 2306//2306 2305//2305 2248//2248 -f 2242//2242 2256//2256 2307//2307 -f 2307//2307 2256//2256 2291//2291 -f 2307//2307 2291//2291 2308//2308 -f 2308//2308 2291//2291 2292//2292 -f 2308//2308 2292//2292 2309//2309 -f 2309//2309 2292//2292 2293//2293 -f 2309//2309 2293//2293 2310//2310 -f 2310//2310 2293//2293 2294//2294 -f 2310//2310 2294//2294 2239//2239 -f 2149//2149 2148//2148 2269//2269 -f 2269//2269 2148//2148 2268//2268 -f 2269//2269 2268//2268 2311//2311 -f 2311//2311 2268//2268 2312//2312 -f 2311//2311 2312//2312 2313//2313 -f 2313//2313 2312//2312 2236//2236 -f 2214//2214 2215//2215 2265//2265 -f 2265//2265 2215//2215 2314//2314 -f 2265//2265 2314//2314 2315//2315 -f 2315//2315 2314//2314 2316//2316 -f 2315//2315 2316//2316 2317//2317 -f 2317//2317 2316//2316 2230//2230 -f 2252//2252 2254//2254 2318//2318 -f 2318//2318 2254//2254 2295//2295 -f 2318//2318 2295//2295 2319//2319 -f 2319//2319 2295//2295 2296//2296 -f 2319//2319 2296//2296 2320//2320 -f 2320//2320 2296//2296 2297//2297 -f 2320//2320 2297//2297 2321//2321 -f 2195//2195 2181//2181 2285//2285 -f 2285//2285 2181//2181 2262//2262 -f 2285//2285 2262//2262 2322//2322 -f 2322//2322 2262//2262 2323//2323 -f 2322//2322 2323//2323 2324//2324 -f 2324//2324 2323//2323 2221//2221 -f 2289//2289 2302//2302 2290//2290 -f 2290//2290 2302//2302 2325//2325 -f 2290//2290 2325//2325 2298//2298 -f 2298//2298 2325//2325 2326//2326 -f 2298//2298 2326//2326 2299//2299 -f 2299//2299 2326//2326 2327//2327 -f 2299//2299 2327//2327 2300//2300 -f 2180//2180 2170//2170 2273//2273 -f 2273//2273 2170//2170 2275//2275 -f 2273//2273 2275//2275 2289//2289 -f 2289//2289 2275//2275 2328//2328 -f 2289//2289 2328//2328 2301//2301 -f 2301//2301 2328//2328 2251//2251 -f 2301//2301 2251//2251 2329//2329 -f 2329//2329 2251//2251 2250//2250 -f 2330//2330 2249//2249 2331//2331 -f 2331//2331 2249//2249 2251//2251 -f 2331//2331 2251//2251 2332//2332 -f 2332//2332 2251//2251 2328//2328 -f 2332//2332 2328//2328 2276//2276 -f 2276//2276 2328//2328 2275//2275 -f 2276//2276 2275//2275 2172//2172 -f 2172//2172 2275//2275 2171//2171 -f 2173//2173 2174//2174 2276//2276 -f 2276//2276 2174//2174 2272//2272 -f 2276//2276 2272//2272 2332//2332 -f 2332//2332 2272//2272 2304//2304 -f 2332//2332 2304//2304 2331//2331 -f 2331//2331 2304//2304 2306//2306 -f 2331//2331 2306//2306 2330//2330 -f 2330//2330 2306//2306 2333//2333 -f 2248//2248 2247//2247 2306//2306 -f 2306//2306 2247//2247 2334//2334 -f 2306//2306 2334//2334 2333//2333 -f 2162//2162 2163//2163 2303//2303 -f 2303//2303 2163//2163 2271//2271 -f 2303//2303 2271//2271 2305//2305 -f 2305//2305 2271//2271 2335//2335 -f 2305//2305 2335//2335 2248//2248 -f 2248//2248 2335//2335 2245//2245 -f 2248//2248 2245//2245 2246//2246 -f 2246//2246 2245//2245 2244//2244 -f 2336//2336 2243//2243 2337//2337 -f 2337//2337 2243//2243 2245//2245 -f 2337//2337 2245//2245 2338//2338 -f 2338//2338 2245//2245 2335//2335 -f 2338//2338 2335//2335 2270//2270 -f 2270//2270 2335//2335 2271//2271 -f 2270//2270 2271//2271 2165//2165 -f 2165//2165 2271//2271 2164//2164 -f 2166//2166 2167//2167 2270//2270 -f 2270//2270 2167//2167 2259//2259 -f 2270//2270 2259//2259 2338//2338 -f 2338//2338 2259//2259 2255//2255 -f 2338//2338 2255//2255 2337//2337 -f 2337//2337 2255//2255 2242//2242 -f 2337//2337 2242//2242 2336//2336 -f 2336//2336 2242//2242 2241//2241 -f 2240//2240 2242//2242 2339//2339 -f 2339//2339 2242//2242 2307//2307 -f 2339//2339 2307//2307 2340//2340 -f 2340//2340 2307//2307 2308//2308 -f 2340//2340 2308//2308 2341//2341 -f 2341//2341 2308//2308 2309//2309 -f 2341//2341 2309//2309 2342//2342 -f 2342//2342 2309//2309 2310//2310 -f 2342//2342 2310//2310 2343//2343 -f 2239//2239 2238//2238 2310//2310 -f 2310//2310 2238//2238 2344//2344 -f 2310//2310 2344//2344 2343//2343 -f 2345//2345 2237//2237 2346//2346 -f 2346//2346 2237//2237 2239//2239 -f 2346//2346 2239//2239 2347//2347 -f 2347//2347 2239//2239 2294//2294 -f 2347//2347 2294//2294 2348//2348 -f 2348//2348 2294//2294 2280//2280 -f 2348//2348 2280//2280 2151//2151 -f 2151//2151 2280//2280 2152//2152 -f 2151//2151 2150//2150 2348//2348 -f 2348//2348 2150//2150 2269//2269 -f 2348//2348 2269//2269 2347//2347 -f 2347//2347 2269//2269 2311//2311 -f 2347//2347 2311//2311 2346//2346 -f 2346//2346 2311//2311 2313//2313 -f 2346//2346 2313//2313 2345//2345 -f 2345//2345 2313//2313 2349//2349 -f 2236//2236 2235//2235 2313//2313 -f 2313//2313 2235//2235 2350//2350 -f 2313//2313 2350//2350 2349//2349 -f 2147//2147 2146//2146 2268//2268 -f 2268//2268 2146//2146 2267//2267 -f 2268//2268 2267//2267 2312//2312 -f 2312//2312 2267//2267 2351//2351 -f 2312//2312 2351//2351 2236//2236 -f 2236//2236 2351//2351 2233//2233 -f 2236//2236 2233//2233 2234//2234 -f 2234//2234 2233//2233 2232//2232 -f 2352//2352 2231//2231 2353//2353 -f 2353//2353 2231//2231 2233//2233 -f 2353//2353 2233//2233 2354//2354 -f 2354//2354 2233//2233 2351//2351 -f 2354//2354 2351//2351 2266//2266 -f 2266//2266 2351//2351 2267//2267 -f 2266//2266 2267//2267 2211//2211 -f 2211//2211 2267//2267 2210//2210 -f 2212//2212 2213//2213 2266//2266 -f 2266//2266 2213//2213 2265//2265 -f 2266//2266 2265//2265 2354//2354 -f 2354//2354 2265//2265 2315//2315 -f 2354//2354 2315//2315 2353//2353 -f 2353//2353 2315//2315 2317//2317 -f 2353//2353 2317//2317 2352//2352 -f 2352//2352 2317//2317 2355//2355 -f 2230//2230 2229//2229 2317//2317 -f 2317//2317 2229//2229 2356//2356 -f 2317//2317 2356//2356 2355//2355 -f 2226//2226 2228//2228 2227//2227 -f 2227//2227 2228//2228 2230//2230 -f 2227//2227 2230//2230 2357//2357 -f 2357//2357 2230//2230 2316//2316 -f 2357//2357 2316//2316 2281//2281 -f 2281//2281 2316//2316 2314//2314 -f 2281//2281 2314//2314 2206//2206 -f 2206//2206 2314//2314 2215//2215 -f 2358//2358 2225//2225 2359//2359 -f 2359//2359 2225//2225 2227//2227 -f 2359//2359 2227//2227 2360//2360 -f 2360//2360 2227//2227 2357//2357 -f 2360//2360 2357//2357 2264//2264 -f 2264//2264 2357//2357 2281//2281 -f 2264//2264 2281//2281 2208//2208 -f 2208//2208 2281//2281 2207//2207 -f 2196//2196 2197//2197 2264//2264 -f 2264//2264 2197//2197 2257//2257 -f 2264//2264 2257//2257 2360//2360 -f 2360//2360 2257//2257 2253//2253 -f 2360//2360 2253//2253 2359//2359 -f 2359//2359 2253//2253 2252//2252 -f 2359//2359 2252//2252 2358//2358 -f 2358//2358 2252//2252 2361//2361 -f 2362//2362 2363//2363 2321//2321 -f 2321//2321 2363//2363 2364//2364 -f 2321//2321 2364//2364 2320//2320 -f 2320//2320 2364//2364 2365//2365 -f 2320//2320 2365//2365 2319//2319 -f 2319//2319 2365//2365 2366//2366 -f 2319//2319 2366//2366 2318//2318 -f 2318//2318 2366//2366 2367//2367 -f 2318//2318 2367//2367 2252//2252 -f 2252//2252 2367//2367 2368//2368 -f 2252//2252 2368//2368 2361//2361 -f 2205//2205 2191//2191 2284//2284 -f 2284//2284 2191//2191 2263//2263 -f 2284//2284 2263//2263 2297//2297 -f 2297//2297 2263//2263 2369//2369 -f 2297//2297 2369//2369 2321//2321 -f 2321//2321 2369//2369 2224//2224 -f 2321//2321 2224//2224 2362//2362 -f 2362//2362 2224//2224 2223//2223 -f 2370//2370 2222//2222 2371//2371 -f 2371//2371 2222//2222 2224//2224 -f 2371//2371 2224//2224 2372//2372 -f 2372//2372 2224//2224 2369//2369 -f 2372//2372 2369//2369 2373//2373 -f 2373//2373 2369//2369 2263//2263 -f 2373//2373 2263//2263 2193//2193 -f 2193//2193 2263//2263 2192//2192 -f 2193//2193 2194//2194 2373//2373 -f 2373//2373 2194//2194 2285//2285 -f 2373//2373 2285//2285 2372//2372 -f 2372//2372 2285//2285 2322//2322 -f 2372//2372 2322//2322 2371//2371 -f 2371//2371 2322//2322 2324//2324 -f 2371//2371 2324//2324 2370//2370 -f 2370//2370 2324//2324 2374//2374 -f 2221//2221 2220//2220 2324//2324 -f 2324//2324 2220//2220 2375//2375 -f 2324//2324 2375//2375 2374//2374 -f 2217//2217 2219//2219 2218//2218 -f 2218//2218 2219//2219 2221//2221 -f 2218//2218 2221//2221 2376//2376 -f 2376//2376 2221//2221 2323//2323 -f 2376//2376 2323//2323 2261//2261 -f 2261//2261 2323//2323 2262//2262 -f 2261//2261 2262//2262 2184//2184 -f 2184//2184 2262//2262 2183//2183 -f 2377//2377 2216//2216 2378//2378 -f 2378//2378 2216//2216 2218//2218 -f 2378//2378 2218//2218 2379//2379 -f 2379//2379 2218//2218 2376//2376 -f 2379//2379 2376//2376 2380//2380 -f 2380//2380 2376//2376 2261//2261 -f 2380//2380 2261//2261 2186//2186 -f 2186//2186 2261//2261 2185//2185 -f 2186//2186 2187//2187 2380//2380 -f 2380//2380 2187//2187 2286//2286 -f 2380//2380 2286//2286 2379//2379 -f 2379//2379 2286//2286 2300//2300 -f 2379//2379 2300//2300 2378//2378 -f 2378//2378 2300//2300 2327//2327 -f 2378//2378 2327//2327 2377//2377 -f 2377//2377 2327//2327 2381//2381 -f 2329//2329 2382//2382 2301//2301 -f 2301//2301 2382//2382 2383//2383 -f 2301//2301 2383//2383 2302//2302 -f 2302//2302 2383//2383 2384//2384 -f 2302//2302 2384//2384 2325//2325 -f 2325//2325 2384//2384 2385//2385 -f 2325//2325 2385//2385 2326//2326 -f 2326//2326 2385//2385 2386//2386 -f 2326//2326 2386//2386 2327//2327 -f 2327//2327 2386//2386 2387//2387 -f 2327//2327 2387//2387 2381//2381 -f 2388//2388 2336//2336 2389//2389 -f 2389//2389 2336//2336 2241//2241 -f 2389//2389 2241//2241 2390//2390 -f 2390//2390 2241//2241 2240//2240 -f 2390//2390 2240//2240 2391//2391 -f 2391//2391 2240//2240 2339//2339 -f 2391//2391 2339//2339 2392//2392 -f 2392//2392 2339//2339 2340//2340 -f 2392//2392 2340//2340 2393//2393 -f 2393//2393 2340//2340 2341//2341 -f 2393//2393 2341//2341 2394//2394 -f 2394//2394 2341//2341 2342//2342 -f 2395//2395 2396//2396 2352//2352 -f 2352//2352 2396//2396 2397//2397 -f 2352//2352 2397//2397 2231//2231 -f 2231//2231 2397//2397 2398//2398 -f 2231//2231 2398//2398 2232//2232 -f 2232//2232 2398//2398 2399//2399 -f 2232//2232 2399//2399 2234//2234 -f 2234//2234 2399//2399 2400//2400 -f 2234//2234 2400//2400 2235//2235 -f 2235//2235 2400//2400 2401//2401 -f 2235//2235 2401//2401 2350//2350 -f 2350//2350 2401//2401 2402//2402 -f 2350//2350 2402//2402 2349//2349 -f 2349//2349 2402//2402 2403//2403 -f 2349//2349 2403//2403 2345//2345 -f 2345//2345 2403//2403 2404//2404 -f 2345//2345 2404//2404 2237//2237 -f 2237//2237 2404//2404 2405//2405 -f 2237//2237 2405//2405 2238//2238 -f 2238//2238 2405//2405 2406//2406 -f 2238//2238 2406//2406 2344//2344 -f 2344//2344 2406//2406 2407//2407 -f 2344//2344 2407//2407 2343//2343 -f 2343//2343 2407//2407 2408//2408 -f 2343//2343 2408//2408 2342//2342 -f 2342//2342 2408//2408 2409//2409 -f 2342//2342 2409//2409 2394//2394 -f 2352//2352 2355//2355 2395//2395 -f 2395//2395 2355//2355 2356//2356 -f 2395//2395 2356//2356 2410//2410 -f 2410//2410 2356//2356 2411//2411 -f 2411//2411 2356//2356 2229//2229 -f 2411//2411 2229//2229 2412//2412 -f 2412//2412 2229//2229 2228//2228 -f 2412//2412 2228//2228 2413//2413 -f 2413//2413 2228//2228 2226//2226 -f 2413//2413 2226//2226 2414//2414 -f 2226//2226 2225//2225 2414//2414 -f 2414//2414 2225//2225 2358//2358 -f 2414//2414 2358//2358 2415//2415 -f 2415//2415 2358//2358 2416//2416 -f 2358//2358 2361//2361 2416//2416 -f 2416//2416 2361//2361 2368//2368 -f 2416//2416 2368//2368 2417//2417 -f 2417//2417 2368//2368 2418//2418 -f 2418//2418 2368//2368 2367//2367 -f 2418//2418 2367//2367 2419//2419 -f 2419//2419 2367//2367 2366//2366 -f 2419//2419 2366//2366 2420//2420 -f 2420//2420 2366//2366 2365//2365 -f 2420//2420 2365//2365 2421//2421 -f 2421//2421 2365//2365 2364//2364 -f 2421//2421 2364//2364 2422//2422 -f 2422//2422 2364//2364 2423//2423 -f 2423//2423 2364//2364 2363//2363 -f 2423//2423 2363//2363 2424//2424 -f 2424//2424 2363//2363 2362//2362 -f 2424//2424 2362//2362 2425//2425 -f 2425//2425 2362//2362 2223//2223 -f 2425//2425 2223//2223 2426//2426 -f 2426//2426 2223//2223 2222//2222 -f 2426//2426 2222//2222 2427//2427 -f 2427//2427 2222//2222 2370//2370 -f 2427//2427 2370//2370 2428//2428 -f 2370//2370 2374//2374 2428//2428 -f 2428//2428 2374//2374 2375//2375 -f 2428//2428 2375//2375 2429//2429 -f 2429//2429 2375//2375 2220//2220 -f 2429//2429 2220//2220 2430//2430 -f 2430//2430 2220//2220 2219//2219 -f 2430//2430 2219//2219 2431//2431 -f 2431//2431 2219//2219 2217//2217 -f 2431//2431 2217//2217 2432//2432 -f 2432//2432 2217//2217 2216//2216 -f 2432//2432 2216//2216 2433//2433 -f 2433//2433 2216//2216 2377//2377 -f 2433//2433 2377//2377 2434//2434 -f 2434//2434 2377//2377 2381//2381 -f 2434//2434 2381//2381 2435//2435 -f 2435//2435 2381//2381 2387//2387 -f 2435//2435 2387//2387 2436//2436 -f 2436//2436 2387//2387 2386//2386 -f 2436//2436 2386//2386 2437//2437 -f 2437//2437 2386//2386 2385//2385 -f 2437//2437 2385//2385 2438//2438 -f 2438//2438 2385//2385 2384//2384 -f 2438//2438 2384//2384 2439//2439 -f 2439//2439 2384//2384 2383//2383 -f 2439//2439 2383//2383 2440//2440 -f 2440//2440 2383//2383 2382//2382 -f 2440//2440 2382//2382 2441//2441 -f 2441//2441 2382//2382 2329//2329 -f 2441//2441 2329//2329 2442//2442 -f 2442//2442 2329//2329 2250//2250 -f 2442//2442 2250//2250 2443//2443 -f 2443//2443 2250//2250 2249//2249 -f 2443//2443 2249//2249 2444//2444 -f 2444//2444 2249//2249 2330//2330 -f 2444//2444 2330//2330 2445//2445 -f 2445//2445 2330//2330 2333//2333 -f 2445//2445 2333//2333 2446//2446 -f 2446//2446 2333//2333 2334//2334 -f 2446//2446 2334//2334 2447//2447 -f 2447//2447 2334//2334 2247//2247 -f 2447//2447 2247//2247 2448//2448 -f 2448//2448 2247//2247 2246//2246 -f 2448//2448 2246//2246 2449//2449 -f 2449//2449 2246//2246 2244//2244 -f 2449//2449 2244//2244 2388//2388 -f 2388//2388 2244//2244 2243//2243 -f 2388//2388 2243//2243 2336//2336 -f 2450//2450 2441//2441 2451//2451 -f 2451//2451 2441//2441 2442//2442 -f 2451//2451 2442//2442 2452//2452 -f 2442//2442 2443//2443 2452//2452 -f 2452//2452 2443//2443 2444//2444 -f 2452//2452 2444//2444 2453//2453 -f 2444//2444 2445//2445 2453//2453 -f 2453//2453 2445//2445 2446//2446 -f 2453//2453 2446//2446 2454//2454 -f 2454//2454 2446//2446 2447//2447 -f 2454//2454 2447//2447 2455//2455 -f 2447//2447 2448//2448 2455//2455 -f 2455//2455 2448//2448 2449//2449 -f 2455//2455 2449//2449 2456//2456 -f 2456//2456 2449//2449 2388//2388 -f 2456//2456 2388//2388 2457//2457 -f 2388//2388 2389//2389 2457//2457 -f 2457//2457 2389//2389 2390//2390 -f 2457//2457 2390//2390 2458//2458 -f 2458//2458 2390//2390 2391//2391 -f 2458//2458 2391//2391 2459//2459 -f 2391//2391 2392//2392 2459//2459 -f 2459//2459 2392//2392 2393//2393 -f 2459//2459 2393//2393 2460//2460 -f 2393//2393 2394//2394 2460//2460 -f 2460//2460 2394//2394 2409//2409 -f 2460//2460 2409//2409 2461//2461 -f 2461//2461 2409//2409 2408//2408 -f 2461//2461 2408//2408 2462//2462 -f 2408//2408 2407//2407 2462//2462 -f 2462//2462 2407//2407 2406//2406 -f 2462//2462 2406//2406 2463//2463 -f 2406//2406 2405//2405 2463//2463 -f 2463//2463 2405//2405 2404//2404 -f 2463//2463 2404//2404 2464//2464 -f 2404//2404 2403//2403 2464//2464 -f 2464//2464 2403//2403 2402//2402 -f 2464//2464 2402//2402 2465//2465 -f 2465//2465 2402//2402 2401//2401 -f 2465//2465 2401//2401 2466//2466 -f 2401//2401 2400//2400 2466//2466 -f 2466//2466 2400//2400 2399//2399 -f 2466//2466 2399//2399 2467//2467 -f 2399//2399 2398//2398 2467//2467 -f 2467//2467 2398//2398 2397//2397 -f 2467//2467 2397//2397 2468//2468 -f 2468//2468 2397//2397 2396//2396 -f 2468//2468 2396//2396 2469//2469 -f 2396//2396 2395//2395 2469//2469 -f 2469//2469 2395//2395 2410//2410 -f 2469//2469 2410//2410 2470//2470 -f 2410//2410 2411//2411 2470//2470 -f 2470//2470 2411//2411 2412//2412 -f 2470//2470 2412//2412 2471//2471 -f 2471//2471 2412//2412 2413//2413 -f 2471//2471 2413//2413 2472//2472 -f 2413//2413 2414//2414 2472//2472 -f 2472//2472 2414//2414 2415//2415 -f 2472//2472 2415//2415 2473//2473 -f 2415//2415 2416//2416 2473//2473 -f 2473//2473 2416//2416 2417//2417 -f 2473//2473 2417//2417 2474//2474 -f 2417//2417 2418//2418 2474//2474 -f 2474//2474 2418//2418 2419//2419 -f 2474//2474 2419//2419 2475//2475 -f 2475//2475 2419//2419 2420//2420 -f 2475//2475 2420//2420 2476//2476 -f 2420//2420 2421//2421 2476//2476 -f 2476//2476 2421//2421 2422//2422 -f 2476//2476 2422//2422 2477//2477 -f 2422//2422 2423//2423 2477//2477 -f 2477//2477 2423//2423 2424//2424 -f 2477//2477 2424//2424 2478//2478 -f 2478//2478 2424//2424 2425//2425 -f 2478//2478 2425//2425 2479//2479 -f 2425//2425 2426//2426 2479//2479 -f 2479//2479 2426//2426 2427//2427 -f 2479//2479 2427//2427 2480//2480 -f 2480//2480 2427//2427 2428//2428 -f 2480//2480 2428//2428 2481//2481 -f 2428//2428 2429//2429 2481//2481 -f 2481//2481 2429//2429 2430//2430 -f 2481//2481 2430//2430 2482//2482 -f 2482//2482 2430//2430 2431//2431 -f 2482//2482 2431//2431 2483//2483 -f 2431//2431 2432//2432 2483//2483 -f 2483//2483 2432//2432 2433//2433 -f 2483//2483 2433//2433 2484//2484 -f 2433//2433 2434//2434 2484//2484 -f 2484//2484 2434//2434 2435//2435 -f 2484//2484 2435//2435 2485//2485 -f 2485//2485 2435//2435 2436//2436 -f 2485//2485 2436//2436 2486//2486 -f 2436//2436 2437//2437 2486//2486 -f 2486//2486 2437//2437 2438//2438 -f 2486//2486 2438//2438 2487//2487 -f 2487//2487 2438//2438 2439//2439 -f 2487//2487 2439//2439 2450//2450 -f 2450//2450 2439//2439 2440//2440 -f 2450//2450 2440//2440 2441//2441 -f 2486//2486 2488//2488 2485//2485 -f 2485//2485 2488//2488 2489//2489 -f 2485//2485 2489//2489 2484//2484 -f 2484//2484 2489//2489 2490//2490 -f 2484//2484 2490//2490 2483//2483 -f 2483//2483 2490//2490 2491//2491 -f 2483//2483 2491//2491 2482//2482 -f 2482//2482 2491//2491 2492//2492 -f 2482//2482 2492//2492 2481//2481 -f 2481//2481 2492//2492 2493//2493 -f 2481//2481 2493//2493 2480//2480 -f 2480//2480 2493//2493 2494//2494 -f 2480//2480 2494//2494 2479//2479 -f 2479//2479 2494//2494 2495//2495 -f 2479//2479 2495//2495 2478//2478 -f 2478//2478 2495//2495 2496//2496 -f 2478//2478 2496//2496 2477//2477 -f 2477//2477 2496//2496 2497//2497 -f 2477//2477 2497//2497 2476//2476 -f 2476//2476 2497//2497 2498//2498 -f 2476//2476 2498//2498 2475//2475 -f 2475//2475 2498//2498 2499//2499 -f 2475//2475 2499//2499 2474//2474 -f 2474//2474 2499//2499 2500//2500 -f 2474//2474 2500//2500 2473//2473 -f 2473//2473 2500//2500 2501//2501 -f 2473//2473 2501//2501 2472//2472 -f 2472//2472 2501//2501 2502//2502 -f 2472//2472 2502//2502 2471//2471 -f 2471//2471 2502//2502 2503//2503 -f 2471//2471 2503//2503 2470//2470 -f 2470//2470 2503//2503 2504//2504 -f 2470//2470 2504//2504 2469//2469 -f 2469//2469 2504//2504 2505//2505 -f 2469//2469 2505//2505 2468//2468 -f 2468//2468 2505//2505 2506//2506 -f 2468//2468 2506//2506 2467//2467 -f 2467//2467 2506//2506 2507//2507 -f 2467//2467 2507//2507 2466//2466 -f 2466//2466 2507//2507 2508//2508 -f 2466//2466 2508//2508 2465//2465 -f 2465//2465 2508//2508 2509//2509 -f 2465//2465 2509//2509 2464//2464 -f 2464//2464 2509//2509 2510//2510 -f 2464//2464 2510//2510 2463//2463 -f 2463//2463 2510//2510 2511//2511 -f 2463//2463 2511//2511 2462//2462 -f 2462//2462 2511//2511 2512//2512 -f 2462//2462 2512//2512 2461//2461 -f 2461//2461 2512//2512 2513//2513 -f 2461//2461 2513//2513 2460//2460 -f 2460//2460 2513//2513 2514//2514 -f 2460//2460 2514//2514 2459//2459 -f 2459//2459 2514//2514 2515//2515 -f 2459//2459 2515//2515 2458//2458 -f 2458//2458 2515//2515 2516//2516 -f 2458//2458 2516//2516 2457//2457 -f 2457//2457 2516//2516 2517//2517 -f 2457//2457 2517//2517 2456//2456 -f 2456//2456 2517//2517 2518//2518 -f 2456//2456 2518//2518 2455//2455 -f 2455//2455 2518//2518 2519//2519 -f 2455//2455 2519//2519 2454//2454 -f 2454//2454 2519//2519 2520//2520 -f 2454//2454 2520//2520 2453//2453 -f 2453//2453 2520//2520 2521//2521 -f 2453//2453 2521//2521 2452//2452 -f 2452//2452 2521//2521 2522//2522 -f 2452//2452 2522//2522 2451//2451 -f 2451//2451 2522//2522 2523//2523 -f 2451//2451 2523//2523 2450//2450 -f 2450//2450 2523//2523 2524//2524 -f 2450//2450 2524//2524 2487//2487 -f 2487//2487 2524//2524 2525//2525 -f 2487//2487 2525//2525 2486//2486 -f 2486//2486 2525//2525 2488//2488 -f 2488//2488 2526//2526 2489//2489 -f 2489//2489 2526//2526 2527//2527 -f 2489//2489 2527//2527 2490//2490 -f 2490//2490 2527//2527 2528//2528 -f 2490//2490 2528//2528 2491//2491 -f 2491//2491 2528//2528 2529//2529 -f 2491//2491 2529//2529 2492//2492 -f 2492//2492 2529//2529 2530//2530 -f 2492//2492 2530//2530 2493//2493 -f 2493//2493 2530//2530 2531//2531 -f 2493//2493 2531//2531 2494//2494 -f 2494//2494 2531//2531 2532//2532 -f 2494//2494 2532//2532 2495//2495 -f 2495//2495 2532//2532 2533//2533 -f 2495//2495 2533//2533 2496//2496 -f 2496//2496 2533//2533 2534//2534 -f 2496//2496 2534//2534 2497//2497 -f 2497//2497 2534//2534 2535//2535 -f 2497//2497 2535//2535 2498//2498 -f 2498//2498 2535//2535 2536//2536 -f 2498//2498 2536//2536 2499//2499 -f 2499//2499 2536//2536 2537//2537 -f 2499//2499 2537//2537 2500//2500 -f 2500//2500 2537//2537 2538//2538 -f 2500//2500 2538//2538 2501//2501 -f 2501//2501 2538//2538 2539//2539 -f 2501//2501 2539//2539 2502//2502 -f 2502//2502 2539//2539 2540//2540 -f 2502//2502 2540//2540 2503//2503 -f 2503//2503 2540//2540 2541//2541 -f 2503//2503 2541//2541 2504//2504 -f 2504//2504 2541//2541 2542//2542 -f 2504//2504 2542//2542 2505//2505 -f 2505//2505 2542//2542 2543//2543 -f 2505//2505 2543//2543 2506//2506 -f 2506//2506 2543//2543 2544//2544 -f 2506//2506 2544//2544 2507//2507 -f 2507//2507 2544//2544 2545//2545 -f 2507//2507 2545//2545 2508//2508 -f 2508//2508 2545//2545 2546//2546 -f 2508//2508 2546//2546 2509//2509 -f 2509//2509 2546//2546 2547//2547 -f 2509//2509 2547//2547 2510//2510 -f 2510//2510 2547//2547 2548//2548 -f 2510//2510 2548//2548 2511//2511 -f 2511//2511 2548//2548 2549//2549 -f 2511//2511 2549//2549 2512//2512 -f 2512//2512 2549//2549 2550//2550 -f 2512//2512 2550//2550 2513//2513 -f 2513//2513 2550//2550 2551//2551 -f 2513//2513 2551//2551 2514//2514 -f 2514//2514 2551//2551 2552//2552 -f 2514//2514 2552//2552 2515//2515 -f 2515//2515 2552//2552 2553//2553 -f 2515//2515 2553//2553 2516//2516 -f 2516//2516 2553//2553 2554//2554 -f 2516//2516 2554//2554 2517//2517 -f 2517//2517 2554//2554 2555//2555 -f 2517//2517 2555//2555 2518//2518 -f 2518//2518 2555//2555 2556//2556 -f 2518//2518 2556//2556 2519//2519 -f 2519//2519 2556//2556 2557//2557 -f 2519//2519 2557//2557 2520//2520 -f 2520//2520 2557//2557 2558//2558 -f 2520//2520 2558//2558 2521//2521 -f 2521//2521 2558//2558 2559//2559 -f 2521//2521 2559//2559 2522//2522 -f 2522//2522 2559//2559 2560//2560 -f 2522//2522 2560//2560 2523//2523 -f 2523//2523 2560//2560 2561//2561 -f 2523//2523 2561//2561 2524//2524 -f 2524//2524 2561//2561 2562//2562 -f 2524//2524 2562//2562 2525//2525 -f 2525//2525 2562//2562 2563//2563 -f 2525//2525 2563//2563 2488//2488 -f 2488//2488 2563//2563 2526//2526 -f 2526//2526 2564//2564 2527//2527 -f 2527//2527 2564//2564 2565//2565 -f 2527//2527 2565//2565 2528//2528 -f 2528//2528 2565//2565 2566//2566 -f 2528//2528 2566//2566 2529//2529 -f 2529//2529 2566//2566 2567//2567 -f 2529//2529 2567//2567 2530//2530 -f 2530//2530 2567//2567 2568//2568 -f 2530//2530 2568//2568 2531//2531 -f 2531//2531 2568//2568 2569//2569 -f 2531//2531 2569//2569 2532//2532 -f 2532//2532 2569//2569 2570//2570 -f 2532//2532 2570//2570 2533//2533 -f 2533//2533 2570//2570 2571//2571 -f 2533//2533 2571//2571 2534//2534 -f 2534//2534 2571//2571 2572//2572 -f 2534//2534 2572//2572 2535//2535 -f 2535//2535 2572//2572 2573//2573 -f 2535//2535 2573//2573 2536//2536 -f 2536//2536 2573//2573 2574//2574 -f 2536//2536 2574//2574 2537//2537 -f 2537//2537 2574//2574 2575//2575 -f 2537//2537 2575//2575 2538//2538 -f 2538//2538 2575//2575 2576//2576 -f 2538//2538 2576//2576 2539//2539 -f 2539//2539 2576//2576 2577//2577 -f 2539//2539 2577//2577 2540//2540 -f 2540//2540 2577//2577 2578//2578 -f 2540//2540 2578//2578 2541//2541 -f 2541//2541 2578//2578 2579//2579 -f 2541//2541 2579//2579 2542//2542 -f 2542//2542 2579//2579 2580//2580 -f 2542//2542 2580//2580 2543//2543 -f 2543//2543 2580//2580 2581//2581 -f 2543//2543 2581//2581 2544//2544 -f 2544//2544 2581//2581 2582//2582 -f 2544//2544 2582//2582 2545//2545 -f 2545//2545 2582//2582 2583//2583 -f 2545//2545 2583//2583 2546//2546 -f 2546//2546 2583//2583 2584//2584 -f 2546//2546 2584//2584 2547//2547 -f 2547//2547 2584//2584 2585//2585 -f 2547//2547 2585//2585 2548//2548 -f 2548//2548 2585//2585 2586//2586 -f 2548//2548 2586//2586 2549//2549 -f 2549//2549 2586//2586 2587//2587 -f 2549//2549 2587//2587 2550//2550 -f 2550//2550 2587//2587 2588//2588 -f 2550//2550 2588//2588 2551//2551 -f 2551//2551 2588//2588 2589//2589 -f 2551//2551 2589//2589 2552//2552 -f 2552//2552 2589//2589 2590//2590 -f 2552//2552 2590//2590 2553//2553 -f 2553//2553 2590//2590 2591//2591 -f 2553//2553 2591//2591 2554//2554 -f 2554//2554 2591//2591 2592//2592 -f 2554//2554 2592//2592 2555//2555 -f 2555//2555 2592//2592 2593//2593 -f 2555//2555 2593//2593 2556//2556 -f 2556//2556 2593//2593 2594//2594 -f 2556//2556 2594//2594 2557//2557 -f 2557//2557 2594//2594 2595//2595 -f 2557//2557 2595//2595 2558//2558 -f 2558//2558 2595//2595 2596//2596 -f 2558//2558 2596//2596 2559//2559 -f 2559//2559 2596//2596 2597//2597 -f 2559//2559 2597//2597 2560//2560 -f 2560//2560 2597//2597 2598//2598 -f 2560//2560 2598//2598 2561//2561 -f 2561//2561 2598//2598 2599//2599 -f 2561//2561 2599//2599 2562//2562 -f 2562//2562 2599//2599 2600//2600 -f 2562//2562 2600//2600 2563//2563 -f 2563//2563 2600//2600 2601//2601 -f 2563//2563 2601//2601 2526//2526 -f 2526//2526 2601//2601 2564//2564 -f 2564//2564 2602//2602 2565//2565 -f 2565//2565 2602//2602 2603//2603 -f 2565//2565 2603//2603 2566//2566 -f 2566//2566 2603//2603 2604//2604 -f 2566//2566 2604//2604 2567//2567 -f 2567//2567 2604//2604 2605//2605 -f 2567//2567 2605//2605 2568//2568 -f 2568//2568 2605//2605 2606//2606 -f 2568//2568 2606//2606 2569//2569 -f 2569//2569 2606//2606 2607//2607 -f 2569//2569 2607//2607 2570//2570 -f 2570//2570 2607//2607 2608//2608 -f 2570//2570 2608//2608 2571//2571 -f 2571//2571 2608//2608 2609//2609 -f 2571//2571 2609//2609 2572//2572 -f 2572//2572 2609//2609 2610//2610 -f 2572//2572 2610//2610 2573//2573 -f 2573//2573 2610//2610 2611//2611 -f 2573//2573 2611//2611 2574//2574 -f 2574//2574 2611//2611 2612//2612 -f 2574//2574 2612//2612 2575//2575 -f 2575//2575 2612//2612 2613//2613 -f 2575//2575 2613//2613 2576//2576 -f 2576//2576 2613//2613 2614//2614 -f 2576//2576 2614//2614 2577//2577 -f 2577//2577 2614//2614 2615//2615 -f 2577//2577 2615//2615 2578//2578 -f 2578//2578 2615//2615 2616//2616 -f 2578//2578 2616//2616 2579//2579 -f 2579//2579 2616//2616 2617//2617 -f 2579//2579 2617//2617 2580//2580 -f 2580//2580 2617//2617 2618//2618 -f 2580//2580 2618//2618 2581//2581 -f 2581//2581 2618//2618 2619//2619 -f 2581//2581 2619//2619 2582//2582 -f 2582//2582 2619//2619 2620//2620 -f 2582//2582 2620//2620 2583//2583 -f 2583//2583 2620//2620 2621//2621 -f 2583//2583 2621//2621 2584//2584 -f 2584//2584 2621//2621 2622//2622 -f 2584//2584 2622//2622 2585//2585 -f 2585//2585 2622//2622 2623//2623 -f 2585//2585 2623//2623 2586//2586 -f 2586//2586 2623//2623 2624//2624 -f 2586//2586 2624//2624 2587//2587 -f 2587//2587 2624//2624 2625//2625 -f 2587//2587 2625//2625 2588//2588 -f 2588//2588 2625//2625 2626//2626 -f 2588//2588 2626//2626 2589//2589 -f 2589//2589 2626//2626 2627//2627 -f 2589//2589 2627//2627 2590//2590 -f 2590//2590 2627//2627 2628//2628 -f 2590//2590 2628//2628 2591//2591 -f 2591//2591 2628//2628 2629//2629 -f 2591//2591 2629//2629 2592//2592 -f 2592//2592 2629//2629 2630//2630 -f 2592//2592 2630//2630 2593//2593 -f 2593//2593 2630//2630 2631//2631 -f 2593//2593 2631//2631 2594//2594 -f 2594//2594 2631//2631 2632//2632 -f 2594//2594 2632//2632 2595//2595 -f 2595//2595 2632//2632 2633//2633 -f 2595//2595 2633//2633 2596//2596 -f 2596//2596 2633//2633 2634//2634 -f 2596//2596 2634//2634 2597//2597 -f 2597//2597 2634//2634 2635//2635 -f 2597//2597 2635//2635 2598//2598 -f 2598//2598 2635//2635 2636//2636 -f 2598//2598 2636//2636 2599//2599 -f 2599//2599 2636//2636 2637//2637 -f 2599//2599 2637//2637 2600//2600 -f 2600//2600 2637//2637 2638//2638 -f 2600//2600 2638//2638 2601//2601 -f 2601//2601 2638//2638 2639//2639 -f 2601//2601 2639//2639 2564//2564 -f 2564//2564 2639//2639 2602//2602 -f 2622//2622 2621//2621 2640//2640 -f 2640//2640 2621//2621 2641//2641 -f 2609//2609 2642//2642 2643//2643 -f 2613//2613 2644//2644 2614//2614 -f 2614//2614 2644//2644 2645//2645 -f 2614//2614 2645//2645 2615//2615 -f 2646//2646 2624//2624 2640//2640 -f 2640//2640 2624//2624 2623//2623 -f 2640//2640 2623//2623 2622//2622 -f 2647//2647 2626//2626 2646//2646 -f 2646//2646 2626//2626 2625//2625 -f 2646//2646 2625//2625 2624//2624 -f 2630//2630 2629//2629 2648//2648 -f 2648//2648 2629//2629 2628//2628 -f 2648//2648 2628//2628 2647//2647 -f 2647//2647 2628//2628 2627//2627 -f 2647//2647 2627//2627 2626//2626 -f 2630//2630 2648//2648 2631//2631 -f 2631//2631 2648//2648 2649//2649 -f 2631//2631 2649//2649 2632//2632 -f 2604//2604 2650//2650 2605//2605 -f 2605//2605 2650//2650 2651//2651 -f 2609//2609 2608//2608 2642//2642 -f 2642//2642 2608//2608 2607//2607 -f 2642//2642 2607//2607 2651//2651 -f 2651//2651 2607//2607 2606//2606 -f 2651//2651 2606//2606 2605//2605 -f 2613//2613 2612//2612 2644//2644 -f 2644//2644 2612//2612 2611//2611 -f 2644//2644 2611//2611 2643//2643 -f 2643//2643 2611//2611 2610//2610 -f 2643//2643 2610//2610 2609//2609 -f 2615//2615 2645//2645 2616//2616 -f 2616//2616 2645//2645 2652//2652 -f 2616//2616 2652//2652 2617//2617 -f 2621//2621 2620//2620 2641//2641 -f 2641//2641 2620//2620 2619//2619 -f 2641//2641 2619//2619 2652//2652 -f 2652//2652 2619//2619 2618//2618 -f 2652//2652 2618//2618 2617//2617 -f 2632//2632 2649//2649 2633//2633 -f 2633//2633 2649//2649 2653//2653 -f 2633//2633 2653//2653 2634//2634 -f 2604//2604 2603//2603 2650//2650 -f 2650//2650 2603//2603 2602//2602 -f 2650//2650 2602//2602 2654//2654 -f 2602//2602 2639//2639 2654//2654 -f 2654//2654 2639//2639 2638//2638 -f 2654//2654 2638//2638 2655//2655 -f 2638//2638 2637//2637 2655//2655 -f 2655//2655 2637//2637 2636//2636 -f 2655//2655 2636//2636 2653//2653 -f 2653//2653 2636//2636 2635//2635 -f 2653//2653 2635//2635 2634//2634 -f 2646//2646 2640//2640 2656//2656 -f 2656//2656 2657//2657 2646//2646 -f 2646//2646 2657//2657 2658//2658 -f 2646//2646 2658//2658 2647//2647 -f 2658//2658 2659//2659 2647//2647 -f 2647//2647 2659//2659 2660//2660 -f 2647//2647 2660//2660 2648//2648 -f 2660//2660 2661//2661 2648//2648 -f 2648//2648 2661//2661 2662//2662 -f 2648//2648 2662//2662 2649//2649 -f 2662//2662 2663//2663 2649//2649 -f 2649//2649 2663//2663 2664//2664 -f 2649//2649 2664//2664 2653//2653 -f 2664//2664 2665//2665 2653//2653 -f 2653//2653 2665//2665 2666//2666 -f 2653//2653 2666//2666 2655//2655 -f 2666//2666 2667//2667 2655//2655 -f 2655//2655 2667//2667 2668//2668 -f 2655//2655 2668//2668 2654//2654 -f 2654//2654 2668//2668 2669//2669 -f 2654//2654 2669//2669 2650//2650 -f 2669//2669 2670//2670 2650//2650 -f 2650//2650 2670//2670 2671//2671 -f 2650//2650 2671//2671 2651//2651 -f 2671//2671 2672//2672 2651//2651 -f 2651//2651 2672//2672 2673//2673 -f 2651//2651 2673//2673 2642//2642 -f 2673//2673 2674//2674 2642//2642 -f 2642//2642 2674//2674 2675//2675 -f 2642//2642 2675//2675 2643//2643 -f 2675//2675 2676//2676 2643//2643 -f 2643//2643 2676//2676 2677//2677 -f 2643//2643 2677//2677 2644//2644 -f 2677//2677 2678//2678 2644//2644 -f 2644//2644 2678//2678 2679//2679 -f 2644//2644 2679//2679 2645//2645 -f 2679//2679 2680//2680 2645//2645 -f 2645//2645 2680//2680 2681//2681 -f 2645//2645 2681//2681 2652//2652 -f 2681//2681 2682//2682 2652//2652 -f 2652//2652 2682//2682 2683//2683 -f 2652//2652 2683//2683 2641//2641 -f 2641//2641 2683//2683 2684//2684 -f 2641//2641 2684//2684 2640//2640 -f 2640//2640 2684//2684 2685//2685 -f 2640//2640 2685//2685 2656//2656 -f 2668//2668 2686//2686 2669//2669 -f 2669//2669 2686//2686 2687//2687 -f 2669//2669 2687//2687 2670//2670 -f 2670//2670 2687//2687 2688//2688 -f 2670//2670 2688//2688 2671//2671 -f 2671//2671 2688//2688 2689//2689 -f 2671//2671 2689//2689 2672//2672 -f 2672//2672 2689//2689 2690//2690 -f 2672//2672 2690//2690 2673//2673 -f 2673//2673 2690//2690 2691//2691 -f 2673//2673 2691//2691 2674//2674 -f 2674//2674 2691//2691 2692//2692 -f 2674//2674 2692//2692 2675//2675 -f 2675//2675 2692//2692 2693//2693 -f 2675//2675 2693//2693 2676//2676 -f 2676//2676 2693//2693 2694//2694 -f 2676//2676 2694//2694 2677//2677 -f 2677//2677 2694//2694 2695//2695 -f 2677//2677 2695//2695 2678//2678 -f 2678//2678 2695//2695 2696//2696 -f 2678//2678 2696//2696 2679//2679 -f 2679//2679 2696//2696 2697//2697 -f 2679//2679 2697//2697 2680//2680 -f 2680//2680 2697//2697 2698//2698 -f 2680//2680 2698//2698 2681//2681 -f 2681//2681 2698//2698 2699//2699 -f 2681//2681 2699//2699 2682//2682 -f 2682//2682 2699//2699 2700//2700 -f 2682//2682 2700//2700 2683//2683 -f 2683//2683 2700//2700 2701//2701 -f 2683//2683 2701//2701 2684//2684 -f 2684//2684 2701//2701 2702//2702 -f 2684//2684 2702//2702 2685//2685 -f 2685//2685 2702//2702 2703//2703 -f 2685//2685 2703//2703 2656//2656 -f 2656//2656 2703//2703 2704//2704 -f 2656//2656 2704//2704 2657//2657 -f 2657//2657 2704//2704 2705//2705 -f 2657//2657 2705//2705 2658//2658 -f 2658//2658 2705//2705 2706//2706 -f 2658//2658 2706//2706 2659//2659 -f 2659//2659 2706//2706 2707//2707 -f 2659//2659 2707//2707 2660//2660 -f 2660//2660 2707//2707 2708//2708 -f 2660//2660 2708//2708 2661//2661 -f 2661//2661 2708//2708 2709//2709 -f 2661//2661 2709//2709 2662//2662 -f 2662//2662 2709//2709 2710//2710 -f 2662//2662 2710//2710 2663//2663 -f 2663//2663 2710//2710 2711//2711 -f 2663//2663 2711//2711 2664//2664 -f 2664//2664 2711//2711 2712//2712 -f 2664//2664 2712//2712 2665//2665 -f 2665//2665 2712//2712 2713//2713 -f 2665//2665 2713//2713 2666//2666 -f 2666//2666 2713//2713 2714//2714 -f 2666//2666 2714//2714 2667//2667 -f 2667//2667 2714//2714 2715//2715 -f 2667//2667 2715//2715 2668//2668 -f 2668//2668 2715//2715 2686//2686 -f 2716//2716 2717//2717 2715//2715 -f 2715//2715 2714//2714 2716//2716 -f 2716//2716 2714//2714 2713//2713 -f 2716//2716 2713//2713 2718//2718 -f 2713//2713 2712//2712 2718//2718 -f 2718//2718 2712//2712 2711//2711 -f 2718//2718 2711//2711 2719//2719 -f 2711//2711 2710//2710 2719//2719 -f 2719//2719 2710//2710 2709//2709 -f 2719//2719 2709//2709 2720//2720 -f 2709//2709 2708//2708 2720//2720 -f 2720//2720 2708//2708 2707//2707 -f 2720//2720 2707//2707 2721//2721 -f 2707//2707 2706//2706 2721//2721 -f 2721//2721 2706//2706 2705//2705 -f 2721//2721 2705//2705 2722//2722 -f 2705//2705 2704//2704 2722//2722 -f 2722//2722 2704//2704 2703//2703 -f 2722//2722 2703//2703 2723//2723 -f 2723//2723 2703//2703 2702//2702 -f 2723//2723 2702//2702 2724//2724 -f 2702//2702 2701//2701 2724//2724 -f 2724//2724 2701//2701 2700//2700 -f 2724//2724 2700//2700 2725//2725 -f 2700//2700 2699//2699 2725//2725 -f 2725//2725 2699//2699 2698//2698 -f 2725//2725 2698//2698 2726//2726 -f 2698//2698 2697//2697 2726//2726 -f 2726//2726 2697//2697 2696//2696 -f 2726//2726 2696//2696 2727//2727 -f 2696//2696 2695//2695 2727//2727 -f 2727//2727 2695//2695 2694//2694 -f 2727//2727 2694//2694 2728//2728 -f 2694//2694 2693//2693 2728//2728 -f 2728//2728 2693//2693 2692//2692 -f 2728//2728 2692//2692 2729//2729 -f 2692//2692 2691//2691 2729//2729 -f 2729//2729 2691//2691 2690//2690 -f 2729//2729 2690//2690 2730//2730 -f 2690//2690 2689//2689 2730//2730 -f 2730//2730 2689//2689 2688//2688 -f 2730//2730 2688//2688 2731//2731 -f 2731//2731 2688//2688 2687//2687 -f 2731//2731 2687//2687 2717//2717 -f 2717//2717 2687//2687 2686//2686 -f 2717//2717 2686//2686 2715//2715 -f 2718//2718 2732//2732 2716//2716 -f 2716//2716 2732//2732 2733//2733 -f 2716//2716 2733//2733 2717//2717 -f 2717//2717 2733//2733 2734//2734 -f 2717//2717 2734//2734 2731//2731 -f 2731//2731 2734//2734 2735//2735 -f 2731//2731 2735//2735 2730//2730 -f 2722//2722 2736//2736 2721//2721 -f 2721//2721 2736//2736 2737//2737 -f 2721//2721 2737//2737 2720//2720 -f 2720//2720 2737//2737 2738//2738 -f 2720//2720 2738//2738 2719//2719 -f 2719//2719 2738//2738 2739//2739 -f 2719//2719 2739//2739 2718//2718 -f 2718//2718 2739//2739 2740//2740 -f 2718//2718 2740//2740 2732//2732 -f 2726//2726 2741//2741 2725//2725 -f 2725//2725 2741//2741 2742//2742 -f 2725//2725 2742//2742 2724//2724 -f 2724//2724 2742//2742 2743//2743 -f 2724//2724 2743//2743 2723//2723 -f 2723//2723 2743//2743 2744//2744 -f 2723//2723 2744//2744 2722//2722 -f 2722//2722 2744//2744 2745//2745 -f 2722//2722 2745//2745 2736//2736 -f 2735//2735 2746//2746 2730//2730 -f 2730//2730 2746//2746 2747//2747 -f 2730//2730 2747//2747 2729//2729 -f 2729//2729 2747//2747 2748//2748 -f 2729//2729 2748//2748 2728//2728 -f 2728//2728 2748//2748 2749//2749 -f 2728//2728 2749//2749 2727//2727 -f 2727//2727 2749//2749 2750//2750 -f 2727//2727 2750//2750 2726//2726 -f 2726//2726 2750//2750 2751//2751 -f 2726//2726 2751//2751 2741//2741 -f 2746//2746 2752//2752 2747//2747 -f 2747//2747 2752//2752 2753//2753 -f 2747//2747 2753//2753 2748//2748 -f 2748//2748 2753//2753 2754//2754 -f 2748//2748 2754//2754 2749//2749 -f 2749//2749 2754//2754 2755//2755 -f 2749//2749 2755//2755 2750//2750 -f 2750//2750 2755//2755 2756//2756 -f 2750//2750 2756//2756 2751//2751 -f 2751//2751 2756//2756 2757//2757 -f 2751//2751 2757//2757 2741//2741 -f 2741//2741 2757//2757 2758//2758 -f 2741//2741 2758//2758 2742//2742 -f 2742//2742 2758//2758 2759//2759 -f 2742//2742 2759//2759 2743//2743 -f 2743//2743 2759//2759 2760//2760 -f 2743//2743 2760//2760 2744//2744 -f 2744//2744 2760//2760 2761//2761 -f 2744//2744 2761//2761 2745//2745 -f 2745//2745 2761//2761 2762//2762 -f 2745//2745 2762//2762 2736//2736 -f 2736//2736 2762//2762 2763//2763 -f 2736//2736 2763//2763 2737//2737 -f 2737//2737 2763//2763 2764//2764 -f 2737//2737 2764//2764 2738//2738 -f 2738//2738 2764//2764 2765//2765 -f 2738//2738 2765//2765 2739//2739 -f 2739//2739 2765//2765 2766//2766 -f 2739//2739 2766//2766 2740//2740 -f 2740//2740 2766//2766 2767//2767 -f 2740//2740 2767//2767 2732//2732 -f 2732//2732 2767//2767 2768//2768 -f 2732//2732 2768//2768 2733//2733 -f 2733//2733 2768//2768 2769//2769 -f 2733//2733 2769//2769 2734//2734 -f 2734//2734 2769//2769 2770//2770 -f 2734//2734 2770//2770 2735//2735 -f 2735//2735 2770//2770 2771//2771 -f 2735//2735 2771//2771 2746//2746 -f 2746//2746 2771//2771 2752//2752 -f 2772//2772 2752//2752 2771//2771 -f 2772//2772 2773//2773 2752//2752 -f 2752//2752 2773//2773 2774//2774 -f 2752//2752 2774//2774 2753//2753 -f 2774//2774 2775//2775 2753//2753 -f 2753//2753 2775//2775 2776//2776 -f 2753//2753 2776//2776 2754//2754 -f 2776//2776 2777//2777 2754//2754 -f 2754//2754 2777//2777 2778//2778 -f 2754//2754 2778//2778 2755//2755 -f 2778//2778 2779//2779 2755//2755 -f 2755//2755 2779//2779 2780//2780 -f 2755//2755 2780//2780 2756//2756 -f 2780//2780 2781//2781 2756//2756 -f 2756//2756 2781//2781 2782//2782 -f 2756//2756 2782//2782 2757//2757 -f 2782//2782 2783//2783 2757//2757 -f 2757//2757 2783//2783 2784//2784 -f 2757//2757 2784//2784 2758//2758 -f 2784//2784 2785//2785 2758//2758 -f 2758//2758 2785//2785 2786//2786 -f 2758//2758 2786//2786 2759//2759 -f 2786//2786 2787//2787 2759//2759 -f 2759//2759 2787//2787 2788//2788 -f 2759//2759 2788//2788 2760//2760 -f 2788//2788 2789//2789 2760//2760 -f 2760//2760 2789//2789 2790//2790 -f 2760//2760 2790//2790 2761//2761 -f 2790//2790 2791//2791 2761//2761 -f 2761//2761 2791//2791 2792//2792 -f 2761//2761 2792//2792 2762//2762 -f 2792//2792 2793//2793 2762//2762 -f 2762//2762 2793//2793 2794//2794 -f 2762//2762 2794//2794 2763//2763 -f 2794//2794 2795//2795 2763//2763 -f 2763//2763 2795//2795 2796//2796 -f 2763//2763 2796//2796 2764//2764 -f 2796//2796 2797//2797 2764//2764 -f 2764//2764 2797//2797 2798//2798 -f 2764//2764 2798//2798 2765//2765 -f 2798//2798 2799//2799 2765//2765 -f 2765//2765 2799//2799 2800//2800 -f 2765//2765 2800//2800 2766//2766 -f 2800//2800 2801//2801 2766//2766 -f 2766//2766 2801//2801 2802//2802 -f 2766//2766 2802//2802 2767//2767 -f 2802//2802 2803//2803 2767//2767 -f 2767//2767 2803//2803 2804//2804 -f 2767//2767 2804//2804 2768//2768 -f 2804//2804 2805//2805 2768//2768 -f 2768//2768 2805//2805 2806//2806 -f 2768//2768 2806//2806 2769//2769 -f 2806//2806 2807//2807 2769//2769 -f 2769//2769 2807//2807 2808//2808 -f 2769//2769 2808//2808 2770//2770 -f 2808//2808 2809//2809 2770//2770 -f 2770//2770 2809//2809 2810//2810 -f 2770//2770 2810//2810 2771//2771 -f 2771//2771 2810//2810 2811//2811 -f 2771//2771 2811//2811 2772//2772 -f 2812//2812 2813//2813 2809//2809 -f 2809//2809 2808//2808 2812//2812 -f 2812//2812 2808//2808 2807//2807 -f 2812//2812 2807//2807 2814//2814 -f 2807//2807 2806//2806 2814//2814 -f 2814//2814 2806//2806 2805//2805 -f 2814//2814 2805//2805 2815//2815 -f 2805//2805 2804//2804 2815//2815 -f 2815//2815 2804//2804 2803//2803 -f 2815//2815 2803//2803 2816//2816 -f 2803//2803 2802//2802 2816//2816 -f 2816//2816 2802//2802 2801//2801 -f 2816//2816 2801//2801 2817//2817 -f 2801//2801 2800//2800 2817//2817 -f 2817//2817 2800//2800 2799//2799 -f 2817//2817 2799//2799 2818//2818 -f 2799//2799 2798//2798 2818//2818 -f 2818//2818 2798//2798 2797//2797 -f 2818//2818 2797//2797 2819//2819 -f 2797//2797 2796//2796 2819//2819 -f 2819//2819 2796//2796 2795//2795 -f 2819//2819 2795//2795 2820//2820 -f 2795//2795 2794//2794 2820//2820 -f 2820//2820 2794//2794 2793//2793 -f 2820//2820 2793//2793 2821//2821 -f 2821//2821 2793//2793 2792//2792 -f 2821//2821 2792//2792 2822//2822 -f 2792//2792 2791//2791 2822//2822 -f 2822//2822 2791//2791 2790//2790 -f 2822//2822 2790//2790 2823//2823 -f 2790//2790 2789//2789 2823//2823 -f 2823//2823 2789//2789 2788//2788 -f 2823//2823 2788//2788 2824//2824 -f 2788//2788 2787//2787 2824//2824 -f 2824//2824 2787//2787 2786//2786 -f 2824//2824 2786//2786 2825//2825 -f 2786//2786 2785//2785 2825//2825 -f 2825//2825 2785//2785 2784//2784 -f 2825//2825 2784//2784 2826//2826 -f 2784//2784 2783//2783 2826//2826 -f 2826//2826 2783//2783 2782//2782 -f 2826//2826 2782//2782 2827//2827 -f 2782//2782 2781//2781 2827//2827 -f 2827//2827 2781//2781 2780//2780 -f 2827//2827 2780//2780 2828//2828 -f 2780//2780 2779//2779 2828//2828 -f 2828//2828 2779//2779 2778//2778 -f 2828//2828 2778//2778 2829//2829 -f 2778//2778 2777//2777 2829//2829 -f 2829//2829 2777//2777 2776//2776 -f 2829//2829 2776//2776 2830//2830 -f 2776//2776 2775//2775 2830//2830 -f 2830//2830 2775//2775 2774//2774 -f 2830//2830 2774//2774 2831//2831 -f 2774//2774 2773//2773 2831//2831 -f 2831//2831 2773//2773 2772//2772 -f 2831//2831 2772//2772 2832//2832 -f 2832//2832 2772//2772 2811//2811 -f 2832//2832 2811//2811 2813//2813 -f 2813//2813 2811//2811 2810//2810 -f 2813//2813 2810//2810 2809//2809 -f 2814//2814 2833//2833 2812//2812 -f 2812//2812 2833//2833 2834//2834 -f 2812//2812 2834//2834 2813//2813 -f 2834//2834 2835//2835 2813//2813 -f 2813//2813 2835//2835 2836//2836 -f 2813//2813 2836//2836 2832//2832 -f 2818//2818 2837//2837 2817//2817 -f 2817//2817 2837//2837 2838//2838 -f 2817//2817 2838//2838 2816//2816 -f 2838//2838 2839//2839 2816//2816 -f 2816//2816 2839//2839 2840//2840 -f 2816//2816 2840//2840 2815//2815 -f 2815//2815 2840//2840 2841//2841 -f 2815//2815 2841//2841 2814//2814 -f 2814//2814 2841//2841 2842//2842 -f 2814//2814 2842//2842 2833//2833 -f 2820//2820 2843//2843 2819//2819 -f 2819//2819 2843//2843 2844//2844 -f 2819//2819 2844//2844 2818//2818 -f 2818//2818 2844//2844 2845//2845 -f 2818//2818 2845//2845 2837//2837 -f 2822//2822 2846//2846 2821//2821 -f 2821//2821 2846//2846 2847//2847 -f 2821//2821 2847//2847 2820//2820 -f 2820//2820 2847//2847 2848//2848 -f 2820//2820 2848//2848 2843//2843 -f 2828//2828 2849//2849 2827//2827 -f 2827//2827 2849//2849 2850//2850 -f 2827//2827 2850//2850 2826//2826 -f 2830//2830 2851//2851 2829//2829 -f 2829//2829 2851//2851 2852//2852 -f 2829//2829 2852//2852 2828//2828 -f 2828//2828 2852//2852 2853//2853 -f 2828//2828 2853//2853 2849//2849 -f 2836//2836 2854//2854 2832//2832 -f 2832//2832 2854//2854 2855//2855 -f 2832//2832 2855//2855 2831//2831 -f 2831//2831 2855//2855 2856//2856 -f 2831//2831 2856//2856 2830//2830 -f 2830//2830 2856//2856 2857//2857 -f 2830//2830 2857//2857 2851//2851 -f 2824//2824 2858//2858 2823//2823 -f 2823//2823 2858//2858 2859//2859 -f 2823//2823 2859//2859 2822//2822 -f 2822//2822 2859//2859 2860//2860 -f 2822//2822 2860//2860 2846//2846 -f 2850//2850 2861//2861 2826//2826 -f 2826//2826 2861//2861 2862//2862 -f 2826//2826 2862//2862 2825//2825 -f 2825//2825 2862//2862 2863//2863 -f 2825//2825 2863//2863 2824//2824 -f 2824//2824 2863//2863 2864//2864 -f 2824//2824 2864//2864 2858//2858 -f 2865//2865 2860//2860 2866//2866 -f 2866//2866 2860//2860 2859//2859 -f 2866//2866 2859//2859 2867//2867 -f 2867//2867 2859//2859 2858//2858 -f 2867//2867 2858//2858 2868//2868 -f 2868//2868 2858//2858 2864//2864 -f 2868//2868 2864//2864 2869//2869 -f 2869//2869 2864//2864 2863//2863 -f 2869//2869 2863//2863 2870//2870 -f 2870//2870 2863//2863 2862//2862 -f 2870//2870 2862//2862 2871//2871 -f 2871//2871 2862//2862 2861//2861 -f 2871//2871 2861//2861 2872//2872 -f 2872//2872 2861//2861 2850//2850 -f 2872//2872 2850//2850 2873//2873 -f 2873//2873 2850//2850 2849//2849 -f 2873//2873 2849//2849 2874//2874 -f 2874//2874 2849//2849 2853//2853 -f 2874//2874 2853//2853 2875//2875 -f 2875//2875 2853//2853 2852//2852 -f 2875//2875 2852//2852 2876//2876 -f 2876//2876 2852//2852 2851//2851 -f 2876//2876 2851//2851 2877//2877 -f 2877//2877 2851//2851 2857//2857 -f 2877//2877 2857//2857 2878//2878 -f 2878//2878 2857//2857 2856//2856 -f 2878//2878 2856//2856 2879//2879 -f 2879//2879 2856//2856 2855//2855 -f 2879//2879 2855//2855 2880//2880 -f 2880//2880 2855//2855 2854//2854 -f 2880//2880 2854//2854 2881//2881 -f 2881//2881 2854//2854 2836//2836 -f 2881//2881 2836//2836 2882//2882 -f 2882//2882 2836//2836 2835//2835 -f 2882//2882 2835//2835 2883//2883 -f 2883//2883 2835//2835 2834//2834 -f 2883//2883 2834//2834 2884//2884 -f 2884//2884 2834//2834 2833//2833 -f 2884//2884 2833//2833 2885//2885 -f 2885//2885 2833//2833 2842//2842 -f 2885//2885 2842//2842 2886//2886 -f 2886//2886 2842//2842 2841//2841 -f 2886//2886 2841//2841 2887//2887 -f 2887//2887 2841//2841 2840//2840 -f 2887//2887 2840//2840 2888//2888 -f 2888//2888 2840//2840 2839//2839 -f 2888//2888 2839//2839 2889//2889 -f 2889//2889 2839//2839 2838//2838 -f 2889//2889 2838//2838 2890//2890 -f 2890//2890 2838//2838 2837//2837 -f 2890//2890 2837//2837 2891//2891 -f 2891//2891 2837//2837 2845//2845 -f 2891//2891 2845//2845 2892//2892 -f 2892//2892 2845//2845 2844//2844 -f 2892//2892 2844//2844 2893//2893 -f 2893//2893 2844//2844 2843//2843 -f 2893//2893 2843//2843 2894//2894 -f 2894//2894 2843//2843 2848//2848 -f 2894//2894 2848//2848 2895//2895 -f 2895//2895 2848//2848 2847//2847 -f 2895//2895 2847//2847 2896//2896 -f 2896//2896 2847//2847 2846//2846 -f 2896//2896 2846//2846 2865//2865 -f 2865//2865 2846//2846 2860//2860 -f 127//127 2881//2881 2882//2882 -f 2883//2883 123//123 2882//2882 -f 2882//2882 123//123 125//125 -f 2882//2882 125//125 127//127 -f 2884//2884 119//119 2883//2883 -f 2883//2883 119//119 121//121 -f 2883//2883 121//121 123//123 -f 2885//2885 115//115 2884//2884 -f 2884//2884 115//115 117//117 -f 2884//2884 117//117 119//119 -f 2886//2886 111//111 2885//2885 -f 2885//2885 111//111 113//113 -f 2885//2885 113//113 115//115 -f 2887//2887 107//107 2886//2886 -f 2886//2886 107//107 109//109 -f 2886//2886 109//109 111//111 -f 2888//2888 103//103 2887//2887 -f 2887//2887 103//103 105//105 -f 2887//2887 105//105 107//107 -f 2889//2889 99//99 2888//2888 -f 2888//2888 99//99 101//101 -f 2888//2888 101//101 103//103 -f 2890//2890 95//95 2889//2889 -f 2889//2889 95//95 97//97 -f 2889//2889 97//97 99//99 -f 2891//2891 91//91 2890//2890 -f 2890//2890 91//91 93//93 -f 2890//2890 93//93 95//95 -f 2892//2892 87//87 2891//2891 -f 2891//2891 87//87 89//89 -f 2891//2891 89//89 91//91 -f 2893//2893 83//83 2892//2892 -f 2892//2892 83//83 85//85 -f 2892//2892 85//85 87//87 -f 2894//2894 79//79 2893//2893 -f 2893//2893 79//79 81//81 -f 2893//2893 81//81 83//83 -f 2895//2895 75//75 2894//2894 -f 2894//2894 75//75 77//77 -f 2894//2894 77//77 79//79 -f 2896//2896 71//71 2895//2895 -f 2895//2895 71//71 73//73 -f 2895//2895 73//73 75//75 -f 2865//2865 67//67 2896//2896 -f 2896//2896 67//67 69//69 -f 2896//2896 69//69 71//71 -f 2866//2866 63//63 2865//2865 -f 2865//2865 63//63 65//65 -f 2865//2865 65//65 67//67 -f 2867//2867 59//59 2866//2866 -f 2866//2866 59//59 61//61 -f 2866//2866 61//61 63//63 -f 2868//2868 55//55 2867//2867 -f 2867//2867 55//55 57//57 -f 2867//2867 57//57 59//59 -f 2869//2869 51//51 2868//2868 -f 2868//2868 51//51 53//53 -f 2868//2868 53//53 55//55 -f 2870//2870 47//47 2869//2869 -f 2869//2869 47//47 49//49 -f 2869//2869 49//49 51//51 -f 2871//2871 43//43 2870//2870 -f 2870//2870 43//43 45//45 -f 2870//2870 45//45 47//47 -f 2872//2872 39//39 2871//2871 -f 2871//2871 39//39 41//41 -f 2871//2871 41//41 43//43 -f 2873//2873 35//35 2872//2872 -f 2872//2872 35//35 37//37 -f 2872//2872 37//37 39//39 -f 2874//2874 31//31 2873//2873 -f 2873//2873 31//31 33//33 -f 2873//2873 33//33 35//35 -f 2875//2875 27//27 2874//2874 -f 2874//2874 27//27 29//29 -f 2874//2874 29//29 31//31 -f 2876//2876 23//23 2875//2875 -f 2875//2875 23//23 25//25 -f 2875//2875 25//25 27//27 -f 2877//2877 19//19 2876//2876 -f 2876//2876 19//19 21//21 -f 2876//2876 21//21 23//23 -f 2878//2878 15//15 2877//2877 -f 2877//2877 15//15 17//17 -f 2877//2877 17//17 19//19 -f 2879//2879 11//11 2878//2878 -f 2878//2878 11//11 13//13 -f 2878//2878 13//13 15//15 -f 2880//2880 7//7 2879//2879 -f 2879//2879 7//7 9//9 -f 2879//2879 9//9 11//11 -f 127//127 1//1 2881//2881 -f 2881//2881 1//1 3//3 -f 2881//2881 3//3 2880//2880 -f 2880//2880 3//3 5//5 -f 2880//2880 5//5 7//7 -# 5792 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/connector2.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/connector2.obj deleted file mode 100644 index 291aee86e..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/connector2.obj +++ /dev/null @@ -1,11600 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object connector2.obj -# -# Vertices: 2896 -# Faces: 5792 -# -#### -vn 0.997349 -0.072772 0.000000 -v 0.084459 0.032618 0.254545 -vn 0.953427 -0.286634 -0.093908 -v 0.084378 0.032330 0.253765 -vn 0.992561 -0.072559 -0.097762 -v 0.084420 0.032618 0.253761 -vn 0.939630 -0.286637 -0.186907 -v 0.084263 0.032330 0.252993 -vn 0.978185 -0.072774 -0.194573 -v 0.084305 0.032618 0.252984 -vn 0.916786 -0.286638 -0.278106 -v 0.084074 0.032330 0.252235 -vn 0.954417 -0.072570 -0.289521 -v 0.084114 0.032618 0.252223 -vn 0.885112 -0.286631 -0.366633 -v 0.083811 0.032330 0.251500 -vn 0.921430 -0.072770 -0.381670 -v 0.083850 0.032618 0.251484 -vn 0.844913 -0.286648 -0.451614 -v 0.083477 0.032330 0.250794 -vn 0.879597 -0.072585 -0.470150 -v 0.083514 0.032618 0.250774 -vn 0.796581 -0.286647 -0.532252 -v 0.083075 0.032330 0.250124 -vn 0.829265 -0.072774 -0.554097 -v 0.083110 0.032618 0.250100 -vn 0.740576 -0.286634 -0.607772 -v 0.082610 0.032330 0.249497 -vn 0.770975 -0.072568 -0.632718 -v 0.082643 0.032618 0.249470 -vn 0.677438 -0.286639 -0.677434 -v 0.082086 0.032330 0.248918 -vn 0.705234 -0.072760 -0.705232 -v 0.082116 0.032618 0.248888 -vn 0.607770 -0.286626 -0.740581 -v 0.081507 0.032330 0.248394 -vn 0.632717 -0.072568 -0.770976 -v 0.081534 0.032618 0.248361 -vn 0.532257 -0.286625 -0.796585 -v 0.080880 0.032330 0.247929 -vn 0.554093 -0.072766 -0.829268 -v 0.080903 0.032618 0.247893 -vn 0.451619 -0.286628 -0.844917 -v 0.080210 0.032330 0.247527 -vn 0.470160 -0.072538 -0.879595 -v 0.080230 0.032618 0.247490 -vn 0.366630 -0.286656 -0.885105 -v 0.079504 0.032330 0.247193 -vn 0.381677 -0.072795 -0.921425 -v 0.079520 0.032618 0.247154 -vn 0.278101 -0.286628 -0.916790 -v 0.078769 0.032330 0.246930 -vn 0.289511 -0.072554 -0.954421 -v 0.078781 0.032618 0.246890 -vn 0.186906 -0.286641 -0.939629 -v 0.078011 0.032330 0.246740 -vn 0.194574 -0.072761 -0.978186 -v 0.078019 0.032618 0.246699 -vn 0.093896 -0.286630 -0.953429 -v 0.077239 0.032330 0.246626 -vn 0.097752 -0.072541 -0.992563 -v 0.077243 0.032618 0.246584 -vn 0.000003 -0.286646 -0.958036 -v 0.076459 0.032330 0.246587 -vn 0.000008 -0.072791 -0.997347 -v 0.076459 0.032618 0.246545 -vn -0.093899 -0.286636 -0.953427 -v 0.075679 0.032330 0.246626 -vn -0.097764 -0.072537 -0.992563 -v 0.075675 0.032618 0.246584 -vn -0.186902 -0.286636 -0.939632 -v 0.074906 0.032330 0.246740 -vn -0.194570 -0.072763 -0.978186 -v 0.074898 0.032618 0.246699 -vn -0.278110 -0.286622 -0.916789 -v 0.074149 0.032330 0.246930 -vn -0.289518 -0.072558 -0.954419 -v 0.074136 0.032618 0.246890 -vn -0.366619 -0.286659 -0.885109 -v 0.073413 0.032330 0.247193 -vn -0.381662 -0.072793 -0.921431 -v 0.073397 0.032618 0.247154 -vn -0.451621 -0.286635 -0.844914 -v 0.072707 0.032330 0.247527 -vn -0.470172 -0.072540 -0.879589 -v 0.072688 0.032618 0.247490 -vn -0.532262 -0.286618 -0.796585 -v 0.072038 0.032330 0.247929 -vn -0.554091 -0.072770 -0.829269 -v 0.072014 0.032618 0.247893 -vn -0.607770 -0.286631 -0.740580 -v 0.071410 0.032330 0.248394 -vn -0.632715 -0.072566 -0.770977 -v 0.071384 0.032618 0.248361 -vn -0.677436 -0.286639 -0.677436 -v 0.070832 0.032330 0.248918 -vn -0.705237 -0.072760 -0.705228 -v 0.070802 0.032618 0.248888 -vn -0.740578 -0.286631 -0.607771 -v 0.070307 0.032330 0.249497 -vn -0.770973 -0.072569 -0.632720 -v 0.070275 0.032618 0.249470 -vn -0.796581 -0.286639 -0.532256 -v 0.069842 0.032330 0.250124 -vn -0.829266 -0.072774 -0.554096 -v 0.069807 0.032618 0.250100 -vn -0.844911 -0.286648 -0.451619 -v 0.069441 0.032330 0.250794 -vn -0.879595 -0.072573 -0.470156 -v 0.069403 0.032618 0.250774 -vn -0.885114 -0.286631 -0.366627 -v 0.069107 0.032330 0.251500 -vn -0.921433 -0.072757 -0.381665 -v 0.069068 0.032618 0.251484 -vn -0.916787 -0.286636 -0.278104 -v 0.068844 0.032330 0.252235 -vn -0.954416 -0.072570 -0.289522 -v 0.068803 0.032618 0.252223 -vn -0.939629 -0.286640 -0.186908 -v 0.068654 0.032330 0.252993 -vn -0.978184 -0.072774 -0.194577 -v 0.068612 0.032618 0.252984 -vn -0.953423 -0.286646 -0.093907 -v 0.068539 0.032330 0.253765 -vn -0.992561 -0.072570 -0.097760 -v 0.068497 0.032618 0.253761 -vn -0.958037 -0.286645 -0.000001 -v 0.068501 0.032330 0.254545 -vn -0.997349 -0.072773 -0.000000 -v 0.068459 0.032618 0.254545 -vn -0.953424 -0.286644 0.093906 -v 0.068539 0.032330 0.255325 -vn -0.992561 -0.072571 0.097760 -v 0.068497 0.032618 0.255329 -vn -0.939630 -0.286640 0.186904 -v 0.068654 0.032330 0.256097 -vn -0.978183 -0.072782 0.194577 -v 0.068612 0.032618 0.256106 -vn -0.916787 -0.286640 0.278100 -v 0.068844 0.032330 0.256855 -vn -0.954417 -0.072568 0.289519 -v 0.068803 0.032618 0.256867 -vn -0.885113 -0.286631 0.366630 -v 0.069107 0.032330 0.257590 -vn -0.921430 -0.072758 0.381671 -v 0.069068 0.032618 0.257607 -vn -0.844913 -0.286645 0.451615 -v 0.069441 0.032330 0.258296 -vn -0.879597 -0.072575 0.470152 -v 0.069403 0.032618 0.258316 -vn -0.796581 -0.286638 0.532257 -v 0.069842 0.032330 0.258966 -vn -0.829265 -0.072774 0.554097 -v 0.069807 0.032618 0.258990 -vn -0.740576 -0.286634 0.607772 -v 0.070307 0.032330 0.259593 -vn -0.770975 -0.072568 0.632718 -v 0.070275 0.032618 0.259620 -vn -0.677434 -0.286642 0.677436 -v 0.070832 0.032330 0.260172 -vn -0.705234 -0.072760 0.705232 -v 0.070802 0.032618 0.260202 -vn -0.607768 -0.286656 0.740571 -v 0.071410 0.032330 0.260696 -vn -0.632717 -0.072568 0.770976 -v 0.071384 0.032618 0.260729 -vn -0.532257 -0.286625 0.796585 -v 0.072038 0.032330 0.261162 -vn -0.554095 -0.072767 0.829267 -v 0.072014 0.032618 0.261197 -vn -0.451620 -0.286633 0.844915 -v 0.072707 0.032330 0.261563 -vn -0.470152 -0.072538 0.879599 -v 0.072688 0.032618 0.261600 -vn -0.366626 -0.286613 0.885120 -v 0.073413 0.032330 0.261897 -vn -0.381671 -0.072754 0.921430 -v 0.073397 0.032618 0.261936 -vn -0.278108 -0.286622 0.916790 -v 0.074149 0.032330 0.262160 -vn -0.289528 -0.072554 0.954416 -v 0.074136 0.032618 0.262201 -vn -0.186906 -0.286641 0.939629 -v 0.074906 0.032330 0.262350 -vn -0.194574 -0.072761 0.978186 -v 0.074898 0.032618 0.262391 -vn -0.093895 -0.286629 0.953429 -v 0.075679 0.032330 0.262464 -vn -0.097752 -0.072541 0.992563 -v 0.075675 0.032618 0.262507 -vn -0.000002 -0.286646 0.958036 -v 0.076459 0.032330 0.262503 -vn -0.000008 -0.072791 0.997347 -v 0.076459 0.032618 0.262545 -vn 0.093899 -0.286637 0.953427 -v 0.077239 0.032330 0.262464 -vn 0.097764 -0.072537 0.992563 -v 0.077243 0.032618 0.262507 -vn 0.186902 -0.286636 0.939632 -v 0.078011 0.032330 0.262350 -vn 0.194570 -0.072763 0.978186 -v 0.078019 0.032618 0.262391 -vn 0.278110 -0.286622 0.916789 -v 0.078769 0.032330 0.262160 -vn 0.289528 -0.072553 0.954416 -v 0.078781 0.032618 0.262201 -vn 0.366629 -0.286622 0.885117 -v 0.079504 0.032330 0.261897 -vn 0.381672 -0.072751 0.921430 -v 0.079520 0.032618 0.261936 -vn 0.451617 -0.286625 0.844919 -v 0.080210 0.032330 0.261563 -vn 0.470158 -0.072534 0.879597 -v 0.080230 0.032618 0.261600 -vn 0.532265 -0.286621 0.796582 -v 0.080880 0.032330 0.261162 -vn 0.554089 -0.072770 0.829270 -v 0.080903 0.032618 0.261197 -vn 0.607760 -0.286661 0.740577 -v 0.081507 0.032330 0.260696 -vn 0.632715 -0.072566 0.770977 -v 0.081534 0.032618 0.260729 -vn 0.677436 -0.286639 0.677436 -v 0.082086 0.032330 0.260172 -vn 0.705237 -0.072760 0.705228 -v 0.082116 0.032618 0.260202 -vn 0.740579 -0.286632 0.607770 -v 0.082610 0.032330 0.259593 -vn 0.770973 -0.072569 0.632720 -v 0.082643 0.032618 0.259620 -vn 0.796580 -0.286645 0.532254 -v 0.083075 0.032330 0.258966 -vn 0.829267 -0.072776 0.554095 -v 0.083110 0.032618 0.258990 -vn 0.844911 -0.286648 0.451617 -v 0.083477 0.032330 0.258296 -vn 0.879594 -0.072584 0.470155 -v 0.083514 0.032618 0.258316 -vn 0.885112 -0.286634 0.366629 -v 0.083811 0.032330 0.257590 -vn 0.921432 -0.072768 0.381666 -v 0.083850 0.032618 0.257607 -vn 0.916787 -0.286636 0.278104 -v 0.084074 0.032330 0.256855 -vn 0.954417 -0.072571 0.289520 -v 0.084114 0.032618 0.256867 -vn 0.939630 -0.286640 0.186904 -v 0.084263 0.032330 0.256097 -vn 0.978184 -0.072781 0.194576 -v 0.084305 0.032618 0.256106 -vn 0.953426 -0.286636 0.093906 -v 0.084378 0.032330 0.255325 -vn 0.992562 -0.072559 0.097758 -v 0.084420 0.032618 0.255329 -vn 0.958037 -0.286644 0.000001 -v 0.084416 0.032330 0.254545 -vn 0.831585 -0.549326 -0.081904 -v 0.084255 0.032066 0.253777 -vn 0.819555 -0.549322 -0.163020 -v 0.084142 0.032066 0.253017 -vn 0.799637 -0.549309 -0.242570 -v 0.083956 0.032066 0.252271 -vn 0.772008 -0.549313 -0.319779 -v 0.083697 0.032066 0.251547 -vn 0.736951 -0.549304 -0.393913 -v 0.083368 0.032066 0.250852 -vn 0.694794 -0.549311 -0.464240 -v 0.082973 0.032066 0.250193 -vn 0.645941 -0.549313 -0.530109 -v 0.082515 0.032066 0.249575 -vn 0.590867 -0.549327 -0.590860 -v 0.081998 0.032066 0.249005 -vn 0.530106 -0.549323 -0.645935 -v 0.081429 0.032066 0.248489 -vn 0.464242 -0.549300 -0.694802 -v 0.080811 0.032066 0.248031 -vn 0.393906 -0.549321 -0.736943 -v 0.080152 0.032066 0.247636 -vn 0.319778 -0.549320 -0.772003 -v 0.079457 0.032066 0.247307 -vn 0.242569 -0.549309 -0.799637 -v 0.078733 0.032066 0.247048 -vn 0.163014 -0.549313 -0.819562 -v 0.077987 0.032066 0.246861 -vn 0.081907 -0.549332 -0.831580 -v 0.077227 0.032066 0.246749 -vn -0.000008 -0.549292 -0.835631 -v 0.076459 0.032066 0.246711 -vn -0.081896 -0.549329 -0.831583 -v 0.075691 0.032066 0.246749 -vn -0.163017 -0.549316 -0.819560 -v 0.074930 0.032066 0.246861 -vn -0.242569 -0.549312 -0.799635 -v 0.074185 0.032066 0.247048 -vn -0.319780 -0.549315 -0.772007 -v 0.073461 0.032066 0.247307 -vn -0.393902 -0.549321 -0.736945 -v 0.072766 0.032066 0.247636 -vn -0.464246 -0.549303 -0.694796 -v 0.072106 0.032066 0.248031 -vn -0.530108 -0.549315 -0.645940 -v 0.071489 0.032066 0.248489 -vn -0.590866 -0.549325 -0.590863 -v 0.070919 0.032066 0.249005 -vn -0.645941 -0.549313 -0.530109 -v 0.070403 0.032066 0.249575 -vn -0.694796 -0.549307 -0.464243 -v 0.069945 0.032066 0.250193 -vn -0.736951 -0.549308 -0.393908 -v 0.069550 0.032066 0.250852 -vn -0.772002 -0.549322 -0.319779 -v 0.069221 0.032066 0.251547 -vn -0.799638 -0.549310 -0.242566 -v 0.068962 0.032066 0.252271 -vn -0.819558 -0.549316 -0.163021 -v 0.068775 0.032066 0.253017 -vn -0.831585 -0.549324 -0.081906 -v 0.068662 0.032066 0.253777 -vn -0.835611 -0.549322 -0.000000 -v 0.068624 0.032066 0.254545 -vn -0.831586 -0.549325 0.081902 -v 0.068662 0.032066 0.255313 -vn -0.819562 -0.549309 0.163027 -v 0.068775 0.032066 0.256073 -vn -0.799634 -0.549316 0.242566 -v 0.068962 0.032066 0.256819 -vn -0.772005 -0.549320 0.319774 -v 0.069221 0.032066 0.257543 -vn -0.736950 -0.549308 0.393911 -v 0.069550 0.032066 0.258238 -vn -0.694794 -0.549310 0.464242 -v 0.069945 0.032066 0.258898 -vn -0.645940 -0.549312 0.530111 -v 0.070403 0.032066 0.259515 -vn -0.590864 -0.549323 0.590867 -v 0.070919 0.032066 0.260085 -vn -0.530108 -0.549325 0.645932 -v 0.071489 0.032066 0.260601 -vn -0.464247 -0.549299 0.694799 -v 0.072106 0.032066 0.261059 -vn -0.393907 -0.549321 0.736942 -v 0.072766 0.032066 0.261454 -vn -0.319779 -0.549320 0.772004 -v 0.073461 0.032066 0.261783 -vn -0.242568 -0.549309 0.799638 -v 0.074185 0.032066 0.262042 -vn -0.163015 -0.549313 0.819562 -v 0.074930 0.032066 0.262229 -vn -0.081908 -0.549332 0.831580 -v 0.075691 0.032066 0.262342 -vn 0.000009 -0.549292 0.835631 -v 0.076459 0.032066 0.262379 -vn 0.081895 -0.549330 0.831583 -v 0.077227 0.032066 0.262342 -vn 0.163017 -0.549316 0.819560 -v 0.077987 0.032066 0.262229 -vn 0.242570 -0.549312 0.799635 -v 0.078733 0.032066 0.262042 -vn 0.319779 -0.549316 0.772007 -v 0.079457 0.032066 0.261783 -vn 0.393901 -0.549322 0.736945 -v 0.080152 0.032066 0.261454 -vn 0.464254 -0.549304 0.694791 -v 0.080811 0.032066 0.261059 -vn 0.530103 -0.549326 0.645935 -v 0.081429 0.032066 0.260601 -vn 0.590860 -0.549328 0.590867 -v 0.081998 0.032066 0.260085 -vn 0.645943 -0.549312 0.530108 -v 0.082515 0.032066 0.259515 -vn 0.694794 -0.549309 0.464241 -v 0.082973 0.032066 0.258898 -vn 0.736951 -0.549307 0.393910 -v 0.083368 0.032066 0.258238 -vn 0.772007 -0.549314 0.319779 -v 0.083697 0.032066 0.257543 -vn 0.799632 -0.549318 0.242567 -v 0.083956 0.032066 0.256819 -vn 0.819558 -0.549316 0.163022 -v 0.084142 0.032066 0.256073 -vn 0.831586 -0.549324 0.081906 -v 0.084255 0.032066 0.255313 -vn 0.835611 -0.549322 -0.000001 -v 0.084293 0.032066 0.254545 -vn 0.692292 -0.718452 -0.067518 -v 0.084062 0.031849 0.253796 -vn 0.682788 -0.717768 -0.136419 -v 0.083952 0.031849 0.253055 -vn 0.665850 -0.718260 -0.201859 -v 0.083770 0.031849 0.252327 -vn 0.642777 -0.718255 -0.266360 -v 0.083517 0.031849 0.251621 -vn 0.611283 -0.720037 -0.328452 -v 0.083197 0.031849 0.250943 -vn 0.578617 -0.719097 -0.384842 -v 0.082811 0.031849 0.250300 -vn 0.538001 -0.718383 -0.441001 -v 0.082365 0.031849 0.249698 -vn 0.491936 -0.717773 -0.492748 -v 0.081861 0.031849 0.249143 -vn 0.441708 -0.718171 -0.537702 -v 0.081306 0.031849 0.248639 -vn 0.386413 -0.718096 -0.578811 -v 0.080703 0.031849 0.248192 -vn 0.326393 -0.719492 -0.613025 -v 0.080060 0.031849 0.247807 -vn 0.267308 -0.718694 -0.641893 -v 0.079382 0.031849 0.247486 -vn 0.202083 -0.718346 -0.665689 -v 0.078677 0.031849 0.247234 -vn 0.135332 -0.717826 -0.682943 -v 0.077949 0.031849 0.247052 -vn 0.068696 -0.718129 -0.692512 -v 0.077208 0.031849 0.246942 -vn -0.000424 -0.717951 -0.696093 -v 0.076459 0.031849 0.246905 -vn -0.068863 -0.719057 -0.691531 -v 0.075710 0.031849 0.246942 -vn -0.134613 -0.718338 -0.682547 -v 0.074968 0.031849 0.247052 -vn -0.202083 -0.718345 -0.665690 -v 0.074241 0.031849 0.247234 -vn -0.266728 -0.717949 -0.642966 -v 0.073535 0.031849 0.247486 -vn -0.327511 -0.718162 -0.613987 -v 0.072857 0.031849 0.247807 -vn -0.387219 -0.717856 -0.578571 -v 0.072214 0.031849 0.248192 -vn -0.441422 -0.718717 -0.537208 -v 0.071612 0.031849 0.248639 -vn -0.491474 -0.718068 -0.492780 -v 0.071056 0.031849 0.249143 -vn -0.537997 -0.718384 -0.441004 -v 0.070553 0.031849 0.249698 -vn -0.578760 -0.718110 -0.386464 -v 0.070106 0.031849 0.250300 -vn -0.613298 -0.718275 -0.328553 -v 0.069721 0.031849 0.250943 -vn -0.643480 -0.717791 -0.265911 -v 0.069400 0.031849 0.251621 -vn -0.665675 -0.718440 -0.201794 -v 0.069148 0.031849 0.252327 -vn -0.682206 -0.718436 -0.135807 -v 0.068965 0.031849 0.253055 -vn -0.690127 -0.720670 -0.066027 -v 0.068855 0.031849 0.253796 -vn -0.694395 -0.719592 -0.001625 -v 0.068819 0.031849 0.254545 -vn -0.692293 -0.718452 0.067514 -v 0.068855 0.031849 0.255294 -vn -0.682792 -0.717763 0.136425 -v 0.068965 0.031849 0.256036 -vn -0.665845 -0.718265 0.201854 -v 0.069148 0.031849 0.256763 -vn -0.642779 -0.718255 0.266356 -v 0.069400 0.031849 0.257469 -vn -0.611286 -0.720032 0.328456 -v 0.069721 0.031849 0.258147 -vn -0.578613 -0.719101 0.384839 -v 0.070106 0.031849 0.258790 -vn -0.538000 -0.718383 0.441001 -v 0.070553 0.031849 0.259392 -vn -0.491938 -0.717773 0.492746 -v 0.071056 0.031849 0.259947 -vn -0.441720 -0.718150 0.537722 -v 0.071612 0.031849 0.260451 -vn -0.386419 -0.718091 0.578814 -v 0.072214 0.031849 0.260898 -vn -0.326392 -0.719492 0.613025 -v 0.072857 0.031849 0.261283 -vn -0.267307 -0.718696 0.641890 -v 0.073535 0.031849 0.261604 -vn -0.202082 -0.718346 0.665689 -v 0.074241 0.031849 0.261856 -vn -0.135333 -0.717826 0.682943 -v 0.074968 0.031849 0.262038 -vn -0.068696 -0.718129 0.692512 -v 0.075710 0.031849 0.262148 -vn 0.000425 -0.717951 0.696093 -v 0.076459 0.031849 0.262185 -vn 0.068863 -0.719057 0.691531 -v 0.077208 0.031849 0.262148 -vn 0.134612 -0.718338 0.682547 -v 0.077949 0.031849 0.262038 -vn 0.202083 -0.718345 0.665690 -v 0.078677 0.031849 0.261856 -vn 0.266729 -0.717947 0.642968 -v 0.079382 0.031849 0.261604 -vn 0.327512 -0.718161 0.613987 -v 0.080060 0.031849 0.261283 -vn 0.387217 -0.717859 0.578568 -v 0.080703 0.031849 0.260898 -vn 0.441432 -0.718702 0.537220 -v 0.081306 0.031849 0.260451 -vn 0.491471 -0.718066 0.492786 -v 0.081861 0.031849 0.259947 -vn 0.537997 -0.718384 0.441004 -v 0.082365 0.031849 0.259392 -vn 0.578767 -0.718105 0.386464 -v 0.082811 0.031849 0.258790 -vn 0.613293 -0.718279 0.328553 -v 0.083197 0.031849 0.258147 -vn 0.643481 -0.717792 0.265908 -v 0.083517 0.031849 0.257469 -vn 0.665669 -0.718447 0.201788 -v 0.083770 0.031849 0.256763 -vn 0.682200 -0.718442 0.135810 -v 0.083952 0.031849 0.256036 -vn 0.690127 -0.720670 0.066028 -v 0.084062 0.031849 0.255294 -vn 0.694394 -0.719593 0.001623 -v 0.084099 0.031849 0.254545 -vn 0.177905 -0.701829 0.689773 -v 0.077941 0.031035 0.261041 -vn 0.239967 -0.701671 0.670875 -v 0.078893 0.031035 0.260747 -vn 0.288330 -0.724430 0.626153 -v 0.079008 0.031035 0.260700 -vn 0.345233 -0.702385 0.622470 -v 0.079790 0.031035 0.260315 -vn 0.373479 -0.746701 0.550410 -v 0.080160 0.031035 0.260085 -vn 0.448436 -0.700556 0.555091 -v 0.080613 0.031035 0.259754 -vn -0.239970 -0.701670 0.670875 -v 0.074025 0.031035 0.260747 -vn -0.177905 -0.701827 0.689775 -v 0.074976 0.031035 0.261041 -vn -0.107732 -0.736624 0.667667 -v 0.075159 0.031035 0.261080 -vn -0.063172 -0.702644 0.708732 -v 0.075961 0.031035 0.261189 -vn 0.000669 -0.747215 0.664582 -v 0.076459 0.031035 0.261208 -vn 0.060814 -0.700335 0.711219 -v 0.076957 0.031035 0.261189 -vn 0.112272 -0.729079 0.675159 -v 0.077758 0.031035 0.261080 -vn -0.575256 -0.701607 0.420509 -v 0.070954 0.031035 0.258298 -vn -0.534440 -0.701879 0.470893 -v 0.071575 0.031035 0.259077 -vn -0.453651 -0.747949 0.484534 -v 0.071748 0.031035 0.259256 -vn -0.449617 -0.702827 0.551252 -v 0.072305 0.031035 0.259754 -vn -0.372625 -0.746300 0.551531 -v 0.072757 0.031035 0.260085 -vn -0.347953 -0.700021 0.623618 -v 0.073127 0.031035 0.260315 -vn -0.288665 -0.720259 0.630792 -v 0.073909 0.031035 0.260700 -vn -0.534440 -0.701879 -0.470894 -v 0.071575 0.031035 0.250013 -vn -0.575257 -0.701607 -0.420509 -v 0.070954 0.031035 0.250792 -vn -0.598859 -0.711801 -0.367024 -v 0.070919 0.031035 0.250844 -vn -0.635150 -0.702086 -0.321963 -v 0.070456 0.031035 0.251654 -vn -0.619866 -0.744754 -0.247199 -v 0.070303 0.031035 0.251995 -vn -0.682137 -0.700769 -0.208834 -v 0.070092 0.031035 0.252581 -vn -0.657146 -0.740162 -0.142545 -v 0.069924 0.031035 0.253245 -vn -0.708994 -0.699412 -0.090279 -v 0.069871 0.031035 0.253552 -vn -0.711301 -0.702886 -0.001522 -v 0.069796 0.031035 0.254545 -vn -0.706612 -0.701908 0.089579 -v 0.069871 0.031035 0.255538 -vn -0.655581 -0.741350 0.143578 -v 0.069924 0.031035 0.255845 -vn -0.681939 -0.700982 0.208769 -v 0.070092 0.031035 0.256509 -vn -0.620183 -0.743968 0.248765 -v 0.070303 0.031035 0.257095 -vn -0.637759 -0.699675 0.322053 -v 0.070456 0.031035 0.257436 -vn -0.600602 -0.709805 0.368041 -v 0.070919 0.031035 0.258247 -vn -0.177907 -0.701828 -0.689773 -v 0.074976 0.031035 0.248050 -vn -0.239967 -0.701671 -0.670875 -v 0.074025 0.031035 0.248343 -vn -0.288330 -0.724430 -0.626153 -v 0.073909 0.031035 0.248390 -vn -0.345237 -0.702373 -0.622481 -v 0.073127 0.031035 0.248775 -vn -0.373485 -0.746691 -0.550419 -v 0.072757 0.031035 0.249005 -vn -0.448445 -0.700541 -0.555103 -v 0.072305 0.031035 0.249336 -vn -0.466219 -0.736036 -0.490807 -v 0.071748 0.031035 0.249834 -vn 0.239970 -0.701670 -0.670875 -v 0.078893 0.031035 0.248343 -vn 0.177902 -0.701827 -0.689775 -v 0.077941 0.031035 0.248050 -vn 0.107731 -0.736622 -0.667670 -v 0.077758 0.031035 0.248011 -vn 0.063172 -0.702644 -0.708732 -v 0.076957 0.031035 0.247901 -vn -0.000669 -0.747215 -0.664582 -v 0.076459 0.031035 0.247883 -vn -0.060813 -0.700335 -0.711219 -v 0.075961 0.031035 0.247901 -vn -0.112274 -0.729081 -0.675156 -v 0.075159 0.031035 0.248011 -vn 0.575256 -0.701607 -0.420509 -v 0.081964 0.031035 0.250792 -vn 0.534440 -0.701879 -0.470893 -v 0.081343 0.031035 0.250013 -vn 0.453651 -0.747949 -0.484535 -v 0.081170 0.031035 0.249834 -vn 0.449608 -0.702842 -0.551241 -v 0.080613 0.031035 0.249336 -vn 0.372619 -0.746310 -0.551522 -v 0.080160 0.031035 0.249005 -vn 0.347948 -0.700033 -0.623607 -v 0.079790 0.031035 0.248775 -vn 0.288665 -0.720260 -0.630791 -v 0.079008 0.031035 0.248390 -vn 0.466215 -0.736039 0.490805 -v 0.081170 0.031035 0.259256 -vn 0.534440 -0.701879 0.470894 -v 0.081343 0.031035 0.259077 -vn 0.575257 -0.701607 0.420509 -v 0.081964 0.031035 0.258298 -vn 0.598860 -0.711801 0.367024 -v 0.081998 0.031035 0.258247 -vn 0.635152 -0.702086 0.321958 -v 0.082461 0.031035 0.257436 -vn 0.619883 -0.744739 0.247202 -v 0.082614 0.031035 0.257095 -vn 0.682160 -0.700744 0.208844 -v 0.082825 0.031035 0.256509 -vn 0.657147 -0.740160 0.142548 -v 0.082993 0.031035 0.255845 -vn 0.708993 -0.699413 0.090276 -v 0.083047 0.031035 0.255538 -vn 0.711324 -0.702863 0.001521 -v 0.083121 0.031035 0.254545 -vn 0.706613 -0.701907 -0.089580 -v 0.083047 0.031035 0.253552 -vn 0.655581 -0.741349 -0.143578 -v 0.082993 0.031035 0.253245 -vn 0.681958 -0.700960 -0.208779 -v 0.082825 0.031035 0.252581 -vn 0.620200 -0.743953 -0.248769 -v 0.082614 0.031035 0.251995 -vn 0.637764 -0.699674 -0.322047 -v 0.082461 0.031035 0.251654 -vn 0.600602 -0.709805 -0.368041 -v 0.081998 0.031035 0.250844 -vn 0.847769 -0.461921 -0.260606 -v 0.082777 0.030971 0.252596 -vn 0.878360 -0.461812 -0.123342 -v 0.082997 0.030971 0.253560 -vn 0.986860 -0.063111 -0.148744 -v 0.082976 0.030893 0.253563 -vn 0.315840 -0.462644 -0.828375 -v 0.078874 0.030971 0.248390 -vn 0.438360 -0.461913 -0.771023 -v 0.079765 0.030971 0.248819 -vn 0.499014 -0.063048 -0.864298 -v 0.079754 0.030893 0.248837 -vn -0.437026 -0.460863 -0.772408 -v 0.073153 0.030971 0.248819 -vn -0.316417 -0.462539 -0.828214 -v 0.074043 0.030971 0.248390 -vn -0.364612 -0.063125 -0.929017 -v 0.074051 0.030893 0.248410 -vn -0.878360 -0.461812 -0.123343 -v 0.069920 0.030971 0.253560 -vn -0.847753 -0.461953 -0.260603 -v 0.070140 0.030971 0.252596 -vn -0.953671 -0.063085 -0.294163 -v 0.070161 0.030893 0.252602 -vn -0.655997 -0.462150 0.596729 -v 0.071612 0.030971 0.259042 -vn -0.729416 -0.461761 0.504707 -v 0.070995 0.030971 0.258270 -vn -0.824591 -0.063119 0.562197 -v 0.071013 0.030893 0.258258 -vn 0.070503 -0.461921 0.884114 -v 0.076953 0.030971 0.261139 -vn -0.073312 -0.460351 0.884705 -v 0.075965 0.030971 0.261139 -vn -0.074585 -0.063117 0.995215 -v 0.075966 0.030893 0.261118 -vn 0.729769 -0.461614 0.504331 -v 0.081922 0.030971 0.258270 -vn 0.656349 -0.462200 0.596302 -v 0.081306 0.030971 0.259042 -vn 0.731586 -0.063169 0.678817 -v 0.081290 0.030893 0.259028 -vn 0.795835 -0.461878 -0.391555 -v 0.082416 0.030971 0.251676 -vn 0.729416 -0.461761 -0.504707 -v 0.081922 0.030971 0.250820 -vn 0.655996 -0.462150 -0.596730 -v 0.081306 0.030971 0.250048 -vn -0.554974 -0.461958 -0.691808 -v 0.072336 0.030971 0.249375 -vn -0.656349 -0.462200 -0.596302 -v 0.071612 0.030971 0.250048 -vn -0.729769 -0.461614 -0.504332 -v 0.070995 0.030971 0.250820 -vn -0.438361 -0.461917 0.771021 -v 0.073153 0.030971 0.260271 -vn -0.205769 -0.462622 0.862346 -v 0.074987 0.030971 0.260991 -vn 0.206346 -0.462687 0.862173 -v 0.077930 0.030971 0.260991 -vn 0.437026 -0.460859 0.772410 -v 0.079765 0.030971 0.260271 -vn 0.847767 -0.461923 0.260609 -v 0.082777 0.030971 0.256494 -vn 0.878360 -0.461812 0.123341 -v 0.082997 0.030971 0.255531 -vn 0.554973 -0.461953 0.691812 -v 0.080581 0.030971 0.259715 -vn 0.316411 -0.462543 0.828214 -v 0.078874 0.030971 0.260700 -vn -0.315840 -0.462645 0.828375 -v 0.074043 0.030971 0.260700 -vn -0.795833 -0.461880 0.391557 -v 0.070501 0.030971 0.257414 -vn -0.847755 -0.461952 0.260600 -v 0.070140 0.030971 0.256494 -vn -0.206360 -0.462541 -0.862248 -v 0.074987 0.030971 0.248099 -vn -0.070503 -0.461921 -0.884114 -v 0.075965 0.030971 0.247951 -vn 0.205793 -0.462474 -0.862419 -v 0.077930 0.030971 0.248099 -vn 0.899171 -0.063225 0.433006 -v 0.082397 0.030893 0.257405 -vn 0.953665 -0.063139 0.294170 -v 0.082757 0.030893 0.256488 -vn 0.584459 0.348235 0.732898 -v 0.080575 0.030813 0.259707 -vn 0.622252 -0.063049 0.780274 -v 0.080568 0.030893 0.259698 -vn 0.222074 -0.063182 0.972981 -v 0.077925 0.030893 0.260971 -vn 0.364606 -0.063120 0.929020 -v 0.078867 0.030893 0.260680 -vn -0.208592 0.348247 0.913900 -v 0.074990 0.030813 0.260982 -vn -0.222069 -0.063180 0.972982 -v 0.074992 0.030893 0.260971 -vn -0.622254 -0.063055 0.780272 -v 0.072349 0.030893 0.259698 -vn -0.499010 -0.063047 0.864300 -v 0.073163 0.030893 0.260253 -vn -0.844571 0.348251 0.406721 -v 0.070510 0.030813 0.257410 -vn -0.899168 -0.063224 0.433012 -v 0.070520 0.030893 0.257405 -vn -0.998005 -0.063131 -0.000001 -v 0.069868 0.030893 0.254545 -vn -0.986860 -0.063111 0.148743 -v 0.069941 0.030893 0.255527 -vn -0.878360 -0.461812 0.123341 -v 0.069920 0.030971 0.255531 -vn -0.844560 0.348262 -0.406734 -v 0.070510 0.030813 0.251680 -vn -0.899178 -0.063147 -0.433003 -v 0.070520 0.030893 0.251685 -vn -0.795672 -0.461349 -0.392508 -v 0.070501 0.030971 0.251676 -vn -0.622250 -0.063048 -0.780275 -v 0.072349 0.030893 0.249392 -vn -0.731587 -0.063169 -0.678816 -v 0.071627 0.030893 0.250062 -vn -0.208608 0.348087 -0.913957 -v 0.074990 0.030813 0.248108 -vn -0.222070 -0.063185 -0.972981 -v 0.074992 0.030893 0.248119 -vn 0.222065 -0.063183 -0.972983 -v 0.077925 0.030893 0.248119 -vn 0.074577 -0.063121 -0.995216 -v 0.076951 0.030893 0.247973 -vn 0.073305 -0.460347 -0.884707 -v 0.076953 0.030971 0.247951 -vn 0.584464 0.348239 -0.732893 -v 0.080575 0.030813 0.249383 -vn 0.622256 -0.063055 -0.780270 -v 0.080568 0.030893 0.249392 -vn 0.558489 -0.459857 -0.690378 -v 0.080581 0.030971 0.249375 -vn 0.899176 -0.063144 -0.433007 -v 0.082397 0.030893 0.251685 -vn 0.824587 -0.063153 -0.562199 -v 0.081904 0.030893 0.250832 -vn 0.937412 0.348223 -0.000001 -v 0.083061 0.030813 0.254545 -vn 0.998005 -0.063131 -0.000002 -v 0.083050 0.030893 0.254545 -vn 0.889884 -0.456187 -0.000001 -v 0.083071 0.030971 0.254545 -vn 0.892860 0.347831 0.286031 -v 0.082768 0.030813 0.256491 -vn 0.847115 0.340554 0.407945 -v 0.082407 0.030813 0.257410 -vn 0.779986 0.347755 0.520278 -v 0.081914 0.030813 0.258264 -vn 0.333068 0.347854 0.876392 -v 0.078871 0.030813 0.260691 -vn 0.209216 0.340555 0.916652 -v 0.077928 0.030813 0.260982 -vn 0.079544 0.347805 0.934187 -v 0.076952 0.030813 0.261129 -vn -0.477519 0.347884 0.806816 -v 0.073158 0.030813 0.260263 -vn -0.586227 0.340542 0.735099 -v 0.072342 0.030813 0.259707 -vn -0.680821 0.347697 0.644663 -v 0.071619 0.030813 0.259036 -vn -0.928533 0.347855 0.129703 -v 0.069930 0.030813 0.255529 -vn -0.940235 0.340526 -0.000001 -v 0.069856 0.030813 0.254545 -vn -0.928474 0.347776 -0.130340 -v 0.069930 0.030813 0.253561 -vn -0.680366 0.347771 -0.645102 -v 0.071619 0.030813 0.250054 -vn -0.586226 0.340535 -0.735102 -v 0.072342 0.030813 0.249383 -vn -0.476980 0.347809 -0.807168 -v 0.073158 0.030813 0.248827 -vn 0.080179 0.347880 -0.934104 -v 0.076952 0.030813 0.247961 -vn 0.209225 0.340391 -0.916711 -v 0.077928 0.030813 0.248108 -vn 0.333679 0.347770 -0.876193 -v 0.078871 0.030813 0.248399 -vn 0.780315 0.347830 -0.519733 -v 0.081914 0.030813 0.250826 -vn 0.847108 0.340559 -0.407957 -v 0.082407 0.030813 0.251680 -vn 0.893078 0.347753 -0.285446 -v 0.082768 0.030813 0.252599 -vn 0.926101 0.348178 0.145291 -v 0.082987 0.030813 0.255529 -vn 0.784532 0.606274 0.130162 -v 0.083029 0.030744 0.255535 -vn 0.746759 0.662450 0.059253 -v 0.083076 0.030744 0.255141 -vn 0.986860 -0.063112 0.148745 -v 0.082976 0.030893 0.255527 -vn 0.795478 0.605982 -0.000001 -v 0.083103 0.030744 0.254545 -vn 0.743703 0.643414 0.181451 -v 0.082864 0.030744 0.256313 -vn 0.512104 0.662536 0.546622 -v 0.081050 0.030744 0.259348 -vn 0.592381 0.607413 0.529278 -v 0.081329 0.030744 0.259064 -vn 0.693714 0.346132 0.631628 -v 0.081299 0.030813 0.259036 -vn 0.824587 -0.063162 0.562199 -v 0.081904 0.030893 0.258258 -vn 0.795675 -0.461347 0.392506 -v 0.082416 0.030971 0.257414 -vn 0.596037 0.652955 0.467323 -v 0.081834 0.030744 0.258451 -vn 0.669644 0.606538 0.428588 -v 0.081949 0.030744 0.258288 -vn 0.714823 0.608669 0.344311 -v 0.082445 0.030744 0.257428 -vn 0.752555 0.606626 0.256255 -v 0.082808 0.030744 0.256503 -vn 0.495759 0.606128 0.621957 -v 0.080601 0.030744 0.259740 -vn 0.463809 0.348212 0.814635 -v 0.079760 0.030813 0.260263 -vn 0.387487 0.606402 0.694356 -v 0.079781 0.030744 0.260299 -vn 0.419259 0.662442 0.620800 -v 0.080119 0.030744 0.260090 -vn 0.499011 -0.063051 0.864299 -v 0.079754 0.030893 0.260253 -vn 0.321647 0.643566 0.694526 -v 0.079070 0.030744 0.260655 -vn -0.107996 0.662627 0.741122 -v 0.075567 0.030744 0.261129 -vn -0.044767 0.607831 0.792804 -v 0.075962 0.030744 0.261171 -vn -0.061330 0.346262 0.936131 -v 0.075965 0.030813 0.261129 -vn 0.074582 -0.063123 0.995215 -v 0.076951 0.030893 0.261118 -vn 0.006537 0.653277 0.757090 -v 0.076757 0.030744 0.261183 -vn 0.082592 0.606462 0.790811 -v 0.076955 0.030744 0.261171 -vn 0.176418 0.608435 0.773746 -v 0.077937 0.030744 0.261023 -vn 0.268854 0.606678 0.748104 -v 0.078886 0.030744 0.260730 -vn -0.177245 0.606214 0.775299 -v 0.074980 0.030744 0.261023 -vn -0.347708 0.348189 0.870554 -v 0.074047 0.030813 0.260691 -vn -0.300978 0.604516 0.737545 -v 0.074031 0.030744 0.260730 -vn -0.225468 0.661209 0.715518 -v 0.074405 0.030744 0.260864 -vn -0.364605 -0.063120 0.929021 -v 0.074051 0.030893 0.260680 -vn -0.342821 0.642612 0.685218 -v 0.073310 0.030744 0.260396 -vn -0.646759 0.662631 0.377655 -v 0.070755 0.030744 0.257953 -vn -0.647783 0.607944 0.459109 -v 0.070969 0.030744 0.258288 -vn -0.770145 0.346216 0.535734 -v 0.071004 0.030813 0.258264 -vn -0.731582 -0.063172 0.678820 -v 0.071627 0.030893 0.259028 -vn -0.558491 -0.459859 0.690374 -v 0.072336 0.030971 0.259715 -vn -0.587617 0.653432 0.477213 -v 0.071455 0.030744 0.258917 -vn -0.566770 0.606206 0.557930 -v 0.071588 0.030744 0.259064 -vn -0.495086 0.607278 0.621372 -v 0.072316 0.030744 0.259740 -vn -0.418033 0.605409 0.677296 -v 0.073137 0.030744 0.260299 -vn -0.716448 0.606406 0.344926 -v 0.070472 0.030744 0.257428 -vn -0.897425 0.348182 0.270919 -v 0.070150 0.030813 0.256491 -vn -0.763989 0.605114 0.223961 -v 0.070110 0.030744 0.256503 -vn -0.699378 0.661855 0.269851 -v 0.070238 0.030744 0.256880 -vn -0.953666 -0.063140 0.294168 -v 0.070161 0.030893 0.256488 -vn -0.749193 0.642889 0.159384 -v 0.069921 0.030744 0.255731 -vn -0.698563 0.662528 -0.270308 -v 0.070238 0.030744 0.252210 -vn -0.762757 0.608008 -0.220290 -v 0.070110 0.030744 0.252587 -vn -0.899017 0.346252 -0.268102 -v 0.070150 0.030813 0.252599 -vn -0.986860 -0.063111 -0.148745 -v 0.069941 0.030893 0.253563 -vn -0.889868 -0.456219 0.000000 -v 0.069847 0.030971 0.254545 -vn -0.739419 0.653523 -0.161761 -v 0.069921 0.030744 0.253359 -vn -0.789488 0.606317 -0.095334 -v 0.069889 0.030744 0.253555 -vn -0.794431 0.607354 0.000432 -v 0.069814 0.030744 0.254545 -vn -0.789987 0.605694 0.095161 -v 0.069889 0.030744 0.255535 -vn -0.716552 0.606086 -0.345271 -v 0.070472 0.030744 0.251662 -vn -0.771357 0.348159 -0.532723 -v 0.071004 0.030813 0.250826 -vn -0.650973 0.605535 -0.457779 -v 0.070969 0.030744 0.250802 -vn -0.647237 0.661933 -0.378060 -v 0.070755 0.030744 0.251137 -vn -0.824587 -0.063125 -0.562202 -v 0.071013 0.030893 0.250832 -vn -0.591699 0.643073 -0.486157 -v 0.071455 0.030744 0.250173 -vn -0.223642 0.661704 -0.715635 -v 0.074405 0.030744 0.248226 -vn -0.303303 0.608014 -0.733707 -v 0.074031 0.030744 0.248360 -vn -0.350915 0.346254 -0.870039 -v 0.074047 0.030813 0.248399 -vn -0.499007 -0.063051 -0.864301 -v 0.073163 0.030893 0.248837 -vn -0.334571 0.653514 -0.678957 -v 0.073310 0.030744 0.248694 -vn -0.417428 0.606518 -0.676675 -v 0.073137 0.030744 0.248791 -vn -0.495279 0.607952 -0.620559 -v 0.072316 0.030744 0.249350 -vn -0.566806 0.606174 -0.557928 -v 0.071588 0.030744 0.250026 -vn -0.177776 0.605212 -0.775960 -v 0.074980 0.030744 0.248067 -vn -0.064439 0.348200 -0.935203 -v 0.075965 0.030813 0.247961 -vn -0.047705 0.605913 -0.794099 -v 0.075962 0.030744 0.247919 -vn -0.108199 0.662208 -0.741467 -v 0.075567 0.030744 0.247961 -vn -0.074574 -0.063118 -0.995216 -v 0.075966 0.030893 0.247973 -vn 0.011114 0.643202 -0.765616 -v 0.076757 0.030744 0.247907 -vn 0.419585 0.662055 -0.620993 -v 0.080119 0.030744 0.249000 -vn 0.384483 0.607888 -0.694727 -v 0.079781 0.030744 0.248791 -vn 0.461411 0.346269 -0.816822 -v 0.079760 0.030813 0.248827 -vn 0.364613 -0.063116 -0.929018 -v 0.078867 0.030893 0.248410 -vn 0.322312 0.653490 -0.684883 -v 0.079070 0.030744 0.248435 -vn 0.268854 0.606678 -0.748104 -v 0.078886 0.030744 0.248360 -vn 0.176414 0.608436 -0.773746 -v 0.077937 0.030744 0.248067 -vn 0.082622 0.606498 -0.790781 -v 0.076955 0.030744 0.247919 -vn 0.495920 0.605639 -0.622307 -v 0.080601 0.030744 0.249350 -vn 0.691038 0.348077 -0.633489 -v 0.081299 0.030813 0.250054 -vn 0.591209 0.605978 -0.532224 -v 0.081329 0.030744 0.250026 -vn 0.512023 0.662395 -0.546868 -v 0.081050 0.030744 0.249743 -vn 0.731582 -0.063172 -0.678820 -v 0.081290 0.030893 0.250062 -vn 0.605581 0.643125 -0.468681 -v 0.081834 0.030744 0.250640 -vn 0.746867 0.662316 -0.059385 -v 0.083076 0.030744 0.253949 -vn 0.782965 0.607740 -0.132732 -v 0.083029 0.030744 0.253555 -vn 0.926315 0.346236 -0.148533 -v 0.082987 0.030813 0.253561 -vn 0.953672 -0.063087 -0.294160 -v 0.082757 0.030893 0.252602 -vn 0.736595 0.653323 -0.174918 -v 0.082864 0.030744 0.252777 -vn 0.752584 0.606587 -0.256262 -v 0.082808 0.030744 0.252587 -vn 0.714860 0.608618 -0.344323 -v 0.082445 0.030744 0.251662 -vn 0.669644 0.606537 -0.428589 -v 0.081949 0.030744 0.250802 -vn -0.728951 0.609755 0.311174 -v 0.067747 0.027824 0.257994 -vn -0.702841 0.609661 0.366509 -v 0.068248 0.027824 0.259059 -vn -0.680879 0.595024 0.427026 -v 0.068415 0.027824 0.259351 -vn -0.644100 0.607999 0.464190 -v 0.068878 0.027824 0.260052 -vn -0.609759 0.601548 0.516076 -v 0.069403 0.027824 0.260710 -vn 0.131102 0.610005 0.781477 -v 0.078214 0.027824 0.263749 -vn -0.565196 0.610125 0.555248 -v 0.069628 0.027824 0.260959 -vn -0.521281 0.610280 0.596511 -v 0.070486 0.027824 0.261765 -vn -0.479101 0.604469 0.636459 -v 0.070617 0.027824 0.261871 -vn -0.432489 0.609810 0.664142 -v 0.071438 0.027824 0.262456 -vn -0.382227 0.600001 0.702781 -v 0.072019 0.027824 0.262796 -vn -0.324834 0.610928 0.721977 -v 0.072469 0.027824 0.263023 -vn -0.245346 0.609175 0.754129 -v 0.073563 0.027824 0.263456 -vn -0.162184 0.609634 0.775915 -v 0.074703 0.027824 0.263749 -vn -0.096714 0.585236 0.805075 -v 0.075201 0.027824 0.263830 -vn -0.047533 0.607169 0.793150 -v 0.075870 0.027824 0.263896 -vn 0.016185 0.605800 0.795452 -v 0.076879 0.027824 0.263905 -vn 0.070872 0.610048 0.789189 -v 0.077047 0.027824 0.263896 -vn 0.195852 0.595231 0.779321 -v 0.078544 0.027824 0.263680 -vn 0.242103 0.608061 0.756074 -v 0.079354 0.027824 0.263456 -vn 0.302621 0.601375 0.739438 -v 0.080141 0.027824 0.263161 -vn 0.353186 0.609750 0.709552 -v 0.080448 0.027824 0.263023 -vn 0.406810 0.609748 0.680231 -v 0.081479 0.027824 0.262456 -vn 0.457043 0.603666 0.653222 -v 0.081620 0.027824 0.262365 -vn 0.498987 0.608907 0.616639 -v 0.082431 0.027824 0.261765 -vn 0.550165 0.599211 0.581604 -v 0.082934 0.027824 0.261317 -vn 0.587256 0.609993 0.532013 -v 0.083289 0.027824 0.260959 -vn 0.641413 0.609199 0.466333 -v 0.084039 0.027824 0.260052 -vn 0.687706 0.609766 0.394011 -v 0.084670 0.027824 0.259059 -vn 0.735775 0.585293 0.340685 -v 0.084901 0.027824 0.258610 -vn 0.739606 0.607075 0.290589 -v 0.085171 0.027824 0.257994 -vn 0.761807 0.605481 0.230310 -v 0.085491 0.027824 0.257038 -vn 0.772544 0.609923 0.176551 -v 0.085534 0.027824 0.256875 -vn 0.783917 0.609794 0.116727 -v 0.085755 0.027824 0.255719 -vn 0.801707 0.595221 0.054565 -v 0.085791 0.027824 0.255385 -vn 0.793814 0.608152 0.003222 -v 0.085829 0.027824 0.254545 -vn 0.796500 0.601728 -0.059254 -v 0.085791 0.027824 0.253705 -vn 0.783807 0.609964 -0.116576 -v 0.085755 0.027824 0.253371 -vn 0.772544 0.609922 -0.176551 -v 0.085534 0.027824 0.252215 -vn 0.762572 0.603582 -0.232749 -v 0.085491 0.027824 0.252052 -vn 0.740618 0.608926 -0.284067 -v 0.085171 0.027824 0.251096 -vn 0.723190 0.599171 -0.343497 -v 0.084901 0.027824 0.250480 -vn 0.687706 0.609767 -0.394010 -v 0.084670 0.027824 0.250031 -vn 0.641494 0.609125 -0.466318 -v 0.084039 0.027824 0.249038 -vn 0.587302 0.609879 -0.532093 -v 0.083289 0.027824 0.248131 -vn 0.551184 0.585476 -0.594486 -v 0.082934 0.027824 0.247773 -vn 0.504723 0.607384 -0.613465 -v 0.082431 0.027824 0.247325 -vn 0.454211 0.606022 -0.653015 -v 0.081620 0.027824 0.246725 -vn 0.406896 0.610061 -0.679898 -v 0.081479 0.027824 0.246634 -vn 0.353167 0.609729 -0.709580 -v 0.080448 0.027824 0.246067 -vn 0.299830 0.595028 -0.745683 -v 0.080141 0.027824 0.245929 -vn 0.248230 0.608062 -0.754084 -v 0.079354 0.027824 0.245634 -vn 0.189944 0.601575 -0.775905 -v 0.078544 0.027824 0.245410 -vn 0.131103 0.610006 -0.781476 -v 0.078214 0.027824 0.245341 -vn 0.070907 0.610005 -0.789218 -v 0.077047 0.027824 0.245194 -vn 0.013933 0.604005 -0.796858 -v 0.076879 0.027824 0.245185 -vn -0.040946 0.609246 -0.791923 -v 0.075870 0.027824 0.245194 -vn -0.103464 0.599539 -0.793630 -v 0.075201 0.027824 0.245260 -vn -0.162070 0.610323 -0.775396 -v 0.074703 0.027824 0.245341 -vn -0.244741 0.609083 -0.754401 -v 0.073563 0.027824 0.245634 -vn -0.324935 0.609587 -0.723063 -v 0.072469 0.027824 0.246067 -vn -0.394941 0.585167 -0.708238 -v 0.072019 0.027824 0.246294 -vn -0.427801 0.607150 -0.669593 -v 0.071438 0.027824 0.246634 -vn -0.480621 0.605743 -0.634097 -v 0.070617 0.027824 0.247219 -vn -0.521255 0.610259 -0.596555 -v 0.070486 0.027824 0.247325 -vn -0.565201 0.610144 -0.555223 -v 0.069628 0.027824 0.248131 -vn -0.616533 0.595590 -0.514936 -v 0.069403 0.027824 0.248380 -vn -0.639851 0.608580 -0.469278 -v 0.068878 0.027824 0.249038 -vn -0.679137 0.602100 -0.419819 -v 0.068415 0.027824 0.249739 -vn -0.702228 0.610254 -0.366696 -v 0.068248 0.027824 0.250031 -vn -0.728951 0.609755 -0.311173 -v 0.067747 0.027824 0.251096 -vn -0.753754 0.603543 -0.259983 -v 0.067686 0.027824 0.251253 -vn -0.766243 0.608809 -0.205482 -v 0.067383 0.027824 0.252215 -vn -0.787025 0.599087 -0.147264 -v 0.067239 0.027824 0.252872 -vn -0.787866 0.609935 -0.085122 -v 0.067163 0.027824 0.253371 -vn -0.792504 0.609866 0.000318 -v 0.067089 0.027824 0.254545 -vn -0.787550 0.610384 0.084828 -v 0.067163 0.027824 0.255719 -vn -0.794971 0.585899 0.157300 -v 0.067239 0.027824 0.256218 -vn -0.768628 0.607902 0.199165 -v 0.067383 0.027824 0.256875 -vn -0.751565 0.605755 0.261173 -v 0.067686 0.027824 0.257837 -vn 0.684481 -0.593690 -0.423105 -v 0.084508 0.026467 0.249736 -vn 0.644940 -0.600270 -0.472999 -v 0.084045 0.026467 0.249033 -vn 0.754753 -0.354832 -0.551762 -v 0.084203 0.026783 0.248919 -vn 0.484437 -0.597383 -0.639104 -v 0.082305 0.026467 0.247214 -vn 0.431183 -0.598844 -0.674883 -v 0.081483 0.026467 0.246628 -vn 0.499517 -0.355893 -0.789825 -v 0.081588 0.026783 0.246463 -vn -0.457779 -0.597687 -0.658186 -v 0.071293 0.026467 0.246719 -vn -0.508711 -0.599059 -0.618338 -v 0.070482 0.026467 0.247320 -vn -0.596801 -0.355883 -0.719149 -v 0.070357 0.026783 0.247170 -vn -0.767822 -0.597130 0.232132 -v 0.067420 0.026467 0.257040 -vn -0.745467 -0.598746 0.292886 -v 0.067740 0.026467 0.257997 -vn -0.868373 -0.355873 0.345374 -v 0.067559 0.026783 0.258069 -vn -0.016303 -0.597449 0.801741 -v 0.076038 0.026467 0.263912 -vn 0.047891 -0.598837 0.799438 -v 0.077047 0.026467 0.263903 -vn 0.060123 -0.355879 0.932596 -v 0.077060 0.026783 0.264098 -vn -0.401168 -0.353204 -0.845169 -v 0.072383 0.026783 0.245884 -vn -0.425770 0.005164 -0.904817 -v 0.072355 0.027147 0.245824 -vn -0.309012 0.005167 -0.951044 -v 0.073480 0.027147 0.245378 -vn -0.927774 -0.353197 0.120364 -v 0.066962 0.026783 0.255745 -vn -0.992102 0.005179 0.125329 -v 0.066896 0.027147 0.255753 -vn -0.999987 0.005187 0.000000 -v 0.066820 0.027147 0.254545 -vn -0.172219 -0.353204 0.919558 -v 0.074665 0.026783 0.263947 -vn -0.187377 0.005170 0.982274 -v 0.074653 0.027147 0.264013 -vn -0.309018 0.005168 0.951042 -v 0.073480 0.027147 0.263712 -vn 0.821333 -0.353200 0.447954 -v 0.084847 0.026783 0.259156 -vn 0.876295 0.005171 0.481747 -v 0.084905 0.027147 0.259189 -vn 0.809007 0.005175 0.587777 -v 0.084257 0.027147 0.260211 -vn -0.393755 0.363161 -0.844436 -v 0.072385 0.027511 0.245888 -vn -0.287500 0.366607 -0.884840 -v 0.073502 0.027511 0.245445 -vn -0.924787 0.363151 0.113534 -v 0.066966 0.027511 0.255744 -vn -0.930375 0.366609 -0.000000 -v 0.066891 0.027511 0.254545 -vn -0.177792 0.363154 0.914609 -v 0.074666 0.027511 0.263944 -vn -0.287505 0.366608 0.884839 -v 0.073502 0.027511 0.263645 -vn 0.814902 0.363154 0.451724 -v 0.084843 0.027511 0.259155 -vn 0.752688 0.366609 0.546863 -v 0.084199 0.027511 0.260169 -vn 0.681435 0.363153 -0.635427 -v 0.083434 0.027511 0.247995 -vn 0.924085 0.362902 0.119874 -v 0.085951 0.027511 0.255744 -vn 0.903202 0.363162 0.228776 -v 0.085726 0.027511 0.256925 -vn 0.682346 0.362776 0.634663 -v 0.083434 0.027511 0.261095 -vn 0.590870 0.363567 0.720203 -v 0.082558 0.027511 0.261917 -vn 0.497430 0.363673 0.787595 -v 0.081586 0.027511 0.262624 -vn 0.400787 0.362413 0.841443 -v 0.080533 0.027511 0.263203 -vn 0.285160 0.364520 0.886459 -v 0.079415 0.027511 0.263645 -vn 0.171551 0.362901 0.915900 -v 0.078252 0.027511 0.263944 -vn 0.061523 0.363154 0.929696 -v 0.077059 0.027511 0.264094 -vn -0.392745 0.362778 0.845070 -v 0.072385 0.027511 0.263203 -vn -0.502352 0.363571 0.784511 -v 0.071332 0.027511 0.262624 -vn -0.595346 0.363660 0.716460 -v 0.070360 0.027511 0.261917 -vn -0.676410 0.362409 0.641194 -v 0.069484 0.027511 0.261095 -vn -0.754955 0.364522 0.545130 -v 0.068718 0.027511 0.260169 -vn -0.818060 0.362900 0.446185 -v 0.068074 0.027511 0.259155 -vn -0.865177 0.363163 0.345805 -v 0.067562 0.027511 0.258067 -vn -0.925075 0.362778 -0.112378 -v 0.066966 0.027511 0.253346 -vn -0.901348 0.363572 -0.235345 -v 0.067191 0.027511 0.252166 -vn -0.865364 0.363669 -0.344803 -v 0.067562 0.027511 0.251023 -vn -0.818832 0.362412 -0.445164 -v 0.068074 0.027511 0.249936 -vn -0.751739 0.364522 -0.549556 -v 0.068718 0.027511 0.248921 -vn -0.677145 0.362896 -0.640141 -v 0.069484 0.027511 0.247995 -vn -0.596231 0.363165 -0.715974 -v 0.070360 0.027511 0.247173 -vn -0.178982 0.362783 -0.914524 -v 0.074666 0.027511 0.245146 -vn -0.054703 0.363567 -0.929960 -v 0.075858 0.027511 0.244996 -vn 0.060513 0.363660 -0.929564 -v 0.077059 0.027511 0.244996 -vn 0.170343 0.362412 -0.916319 -v 0.078252 0.027511 0.245146 -vn 0.290354 0.364520 -0.884771 -v 0.079415 0.027511 0.245445 -vn 0.399559 0.362907 -0.841814 -v 0.080533 0.027511 0.245888 -vn 0.496688 0.363162 -0.788298 -v 0.081586 0.027511 0.246466 -vn 0.902764 0.363671 -0.229697 -v 0.085726 0.027511 0.252166 -vn 0.867538 0.363573 -0.339400 -v 0.085355 0.027511 0.251023 -vn 0.924109 0.362415 -0.121153 -v 0.085951 0.027511 0.253346 -vn 0.931191 0.364521 0.002732 -v 0.086027 0.027511 0.254545 -vn 0.968571 0.005190 0.248684 -v 0.085795 0.027147 0.256942 -vn 0.992101 0.005179 0.125331 -v 0.086021 0.027147 0.255753 -vn 0.728959 0.005197 0.684538 -v 0.083485 0.027147 0.261143 -vn 0.637415 0.005175 0.770503 -v 0.082603 0.027147 0.261972 -vn 0.535822 0.005185 0.844315 -v 0.081623 0.027147 0.262683 -vn 0.425771 0.005164 0.904816 -v 0.080563 0.027147 0.263266 -vn 0.309019 0.005171 0.951042 -v 0.079437 0.027147 0.263712 -vn 0.187378 0.005168 0.982274 -v 0.078265 0.027147 0.264013 -vn 0.062785 0.005167 0.998014 -v 0.077064 0.027147 0.264165 -vn -0.425775 0.005167 0.904814 -v 0.072355 0.027147 0.263266 -vn -0.535817 0.005187 0.844318 -v 0.071294 0.027147 0.262683 -vn -0.637420 0.005170 0.770500 -v 0.070315 0.027147 0.261972 -vn -0.728954 0.005196 0.684543 -v 0.069432 0.027147 0.261143 -vn -0.809007 0.005183 0.587776 -v 0.068661 0.027147 0.260211 -vn -0.876296 0.005172 0.481745 -v 0.068012 0.027147 0.259189 -vn -0.929764 0.005176 0.368120 -v 0.067497 0.027147 0.258093 -vn -0.992101 0.005179 -0.125332 -v 0.066896 0.027147 0.253337 -vn -0.968571 0.005180 -0.248684 -v 0.067123 0.027147 0.252148 -vn -0.929764 0.005178 -0.368120 -v 0.067497 0.027147 0.250997 -vn -0.876295 0.005171 -0.481747 -v 0.068012 0.027147 0.249902 -vn -0.809007 0.005182 -0.587776 -v 0.068661 0.027147 0.248880 -vn -0.728962 0.005200 -0.684535 -v 0.069432 0.027147 0.247947 -vn -0.637413 0.005174 -0.770505 -v 0.070315 0.027147 0.247118 -vn -0.187378 0.005168 -0.982274 -v 0.074653 0.027147 0.245077 -vn -0.062785 0.005167 -0.998014 -v 0.075853 0.027147 0.244925 -vn 0.062785 0.005169 -0.998014 -v 0.077064 0.027147 0.244925 -vn 0.187377 0.005170 -0.982274 -v 0.078265 0.027147 0.245077 -vn 0.309012 0.005171 -0.951044 -v 0.079437 0.027147 0.245378 -vn 0.425773 0.005168 -0.904815 -v 0.080563 0.027147 0.245824 -vn 0.535818 0.005187 -0.844318 -v 0.081623 0.027147 0.246407 -vn 0.999987 0.005178 -0.000001 -v 0.086097 0.027147 0.254545 -vn 0.992102 0.005179 -0.125330 -v 0.086021 0.027147 0.253337 -vn 0.968570 0.005189 -0.248686 -v 0.085795 0.027147 0.252148 -vn 0.929764 0.005186 -0.368120 -v 0.085421 0.027147 0.250997 -vn 0.905532 -0.355877 0.231004 -v 0.085730 0.026783 0.256925 -vn 0.928483 -0.353455 0.113973 -v 0.085955 0.026783 0.255745 -vn 0.757992 -0.354830 0.547306 -v 0.084203 0.026783 0.260171 -vn 0.679087 -0.352708 0.643768 -v 0.083436 0.026783 0.261097 -vn 0.597732 -0.353956 0.719327 -v 0.082560 0.026783 0.261920 -vn 0.504374 -0.353890 0.787635 -v 0.081588 0.026783 0.262627 -vn 0.394295 -0.353078 0.848450 -v 0.080534 0.026783 0.263206 -vn 0.288666 -0.356947 0.888404 -v 0.079417 0.026783 0.263648 -vn 0.178519 -0.353461 0.918257 -v 0.078252 0.026783 0.263947 -vn -0.286293 -0.354833 0.890017 -v 0.073501 0.026783 0.263648 -vn -0.402403 -0.352700 0.844792 -v 0.072383 0.026783 0.263206 -vn -0.499404 -0.353983 0.790754 -v 0.071330 0.026783 0.262627 -vn -0.593233 -0.353852 0.723093 -v 0.070357 0.026783 0.261920 -vn -0.685079 -0.353076 0.637185 -v 0.069481 0.026783 0.261097 -vn -0.755724 -0.356944 0.549065 -v 0.068715 0.026783 0.260171 -vn -0.818151 -0.353459 0.453537 -v 0.068071 0.026783 0.259156 -vn -0.934924 -0.354838 0.002756 -v 0.066887 0.026783 0.254545 -vn -0.927793 -0.352705 -0.121653 -v 0.066962 0.026783 0.253345 -vn -0.906380 -0.353971 -0.230608 -v 0.067188 0.026783 0.252165 -vn -0.871014 -0.353871 -0.340750 -v 0.067559 0.026783 0.251021 -vn -0.817696 -0.353083 -0.454649 -v 0.068071 0.026783 0.249934 -vn -0.755727 -0.356940 -0.549063 -v 0.068715 0.026783 0.248919 -vn -0.684169 -0.353440 -0.637960 -v 0.069481 0.026783 0.247993 -vn -0.291530 -0.354835 -0.888314 -v 0.073501 0.026783 0.245442 -vn -0.171000 -0.352711 -0.919975 -v 0.074665 0.026783 0.245143 -vn -0.060770 -0.353963 -0.933283 -v 0.075858 0.026783 0.244992 -vn 0.054904 -0.353875 -0.933680 -v 0.077060 0.026783 0.244992 -vn 0.179719 -0.353088 -0.918167 -v 0.078252 0.026783 0.245143 -vn 0.288658 -0.356950 -0.888405 -v 0.079417 0.026783 0.245442 -vn 0.395318 -0.353463 -0.847813 -v 0.080534 0.026783 0.245884 -vn 0.752687 0.366611 -0.546863 -v 0.084199 0.027511 0.248921 -vn 0.728958 0.005193 -0.684539 -v 0.083485 0.027147 0.247947 -vn 0.809008 0.005176 -0.587775 -v 0.084257 0.027147 0.248880 -vn 0.679837 -0.353181 -0.642716 -v 0.083436 0.026783 0.247993 -vn 0.934123 -0.356951 -0.000001 -v 0.086031 0.026783 0.254545 -vn 0.928767 -0.353080 -0.112808 -v 0.085955 0.026783 0.253345 -vn 0.904950 -0.353875 -0.236300 -v 0.085730 0.026783 0.252165 -vn 0.868825 -0.353966 -0.346194 -v 0.085358 0.026783 0.251021 -vn 0.801021 -0.577278 0.158480 -v 0.085685 0.026467 0.256219 -vn 0.774719 -0.599593 0.200746 -v 0.085541 0.026467 0.256877 -vn 0.757511 -0.597396 0.263240 -v 0.085238 0.026467 0.257840 -vn 0.734764 -0.601452 0.313651 -v 0.085177 0.026467 0.257997 -vn 0.868632 -0.353454 0.347200 -v 0.085358 0.026783 0.258069 -vn 0.929764 0.005186 0.368119 -v 0.085421 0.027147 0.258093 -vn 0.864896 0.365555 0.343983 -v 0.085355 0.027511 0.258067 -vn 0.708438 -0.601366 0.369425 -v 0.084676 0.026467 0.259062 -vn 0.482856 -0.596083 0.641510 -v 0.082305 0.026467 0.261876 -vn 0.525430 -0.601970 0.601295 -v 0.082436 0.026467 0.261770 -vn 0.569661 -0.601867 0.559680 -v 0.083294 0.026467 0.260964 -vn 0.614526 -0.593136 0.520142 -v 0.083520 0.026467 0.260714 -vn 0.649213 -0.599676 0.467879 -v 0.084045 0.026467 0.260057 -vn 0.686172 -0.586511 0.430317 -v 0.084508 0.026467 0.259354 -vn 0.435925 -0.601548 0.669410 -v 0.081483 0.026467 0.262462 -vn 0.385209 -0.591576 0.708274 -v 0.080902 0.026467 0.262802 -vn 0.327439 -0.602656 0.727729 -v 0.080451 0.026467 0.263029 -vn 0.247295 -0.600881 0.760123 -v 0.079356 0.026467 0.263463 -vn 0.163487 -0.601347 0.782083 -v 0.078216 0.026467 0.263756 -vn 0.097468 -0.576569 0.811214 -v 0.077717 0.026467 0.263837 -vn -0.071418 -0.601756 0.795480 -v 0.075870 0.026467 0.263903 -vn -0.061778 -0.353461 0.933407 -v 0.075858 0.026783 0.264098 -vn -0.062785 0.005169 0.998014 -v 0.075853 0.027147 0.264165 -vn -0.059878 0.365546 0.928865 -v 0.075858 0.027511 0.264094 -vn -0.132127 -0.601723 0.787700 -v 0.074702 0.026467 0.263756 -vn -0.460601 -0.595300 0.658380 -v 0.071293 0.026467 0.262371 -vn -0.410028 -0.601476 0.685641 -v 0.071434 0.026467 0.262462 -vn -0.356012 -0.601451 0.715201 -v 0.072466 0.026467 0.263029 -vn -0.305013 -0.592938 0.745246 -v 0.072773 0.026467 0.263167 -vn -0.244026 -0.599741 0.762078 -v 0.073561 0.026467 0.263463 -vn -0.197347 -0.586717 0.785377 -v 0.074372 0.026467 0.263687 -vn -0.502970 -0.600583 0.621547 -v 0.070482 0.026467 0.261770 -vn -0.554470 -0.590765 0.586140 -v 0.069979 0.026467 0.261323 -vn -0.591929 -0.601732 0.536227 -v 0.069623 0.026467 0.260964 -vn -0.646507 -0.600907 0.470043 -v 0.068873 0.026467 0.260057 -vn -0.693183 -0.601477 0.397143 -v 0.068242 0.026467 0.259062 -vn -0.741352 -0.576665 0.343299 -v 0.068010 0.026467 0.258614 -vn -0.778691 -0.601636 0.177971 -v 0.067376 0.026467 0.256877 -vn -0.906815 -0.353459 0.229681 -v 0.067188 0.026783 0.256925 -vn -0.968571 0.005181 0.248685 -v 0.067123 0.027147 0.256942 -vn -0.901905 0.365554 0.230084 -v 0.067191 0.027511 0.256925 -vn -0.790161 -0.601501 0.117654 -v 0.067156 0.026467 0.255720 -vn -0.768571 -0.595208 -0.234577 -v 0.067420 0.026467 0.252050 -vn -0.778691 -0.601637 -0.177971 -v 0.067376 0.026467 0.252213 -vn -0.790051 -0.601676 -0.117500 -v 0.067156 0.026467 0.253370 -vn -0.802749 -0.593318 -0.059723 -v 0.067120 0.026467 0.253705 -vn -0.800107 -0.599849 0.003243 -v 0.067082 0.026467 0.254545 -vn -0.807924 -0.586715 0.054998 -v 0.067120 0.026467 0.255386 -vn -0.746500 -0.600625 -0.286335 -v 0.067740 0.026467 0.251093 -vn -0.728834 -0.590723 -0.346189 -v 0.068010 0.026467 0.250477 -vn -0.693183 -0.601478 -0.397142 -v 0.068242 0.026467 0.250028 -vn -0.646594 -0.600831 -0.470019 -v 0.068873 0.026467 0.249033 -vn -0.591972 -0.601600 -0.536328 -v 0.069623 0.026467 0.248126 -vn -0.555380 -0.576852 -0.598995 -v 0.069979 0.026467 0.247767 -vn -0.410114 -0.601792 -0.685312 -v 0.071434 0.026467 0.246628 -vn -0.498657 -0.353474 -0.791452 -v 0.071330 0.026783 0.246463 -vn -0.535822 0.005185 -0.844315 -v 0.071294 0.027147 0.246407 -vn -0.497533 0.365554 -0.786658 -v 0.071332 0.027511 0.246466 -vn -0.355999 -0.601426 -0.715228 -v 0.072466 0.026467 0.246061 -vn -0.014085 -0.595609 -0.803151 -v 0.076038 0.026467 0.245178 -vn -0.071525 -0.601714 -0.795502 -v 0.075870 0.026467 0.245187 -vn -0.132127 -0.601723 -0.787700 -v 0.074702 0.026467 0.245334 -vn -0.191419 -0.593151 -0.782005 -v 0.074372 0.026467 0.245403 -vn -0.250195 -0.599741 -0.760074 -v 0.073561 0.026467 0.245627 -vn -0.302177 -0.586496 -0.751473 -v 0.072773 0.026467 0.245923 -vn 0.041267 -0.600948 -0.798222 -v 0.077047 0.026467 0.245187 -vn 0.104284 -0.591083 -0.799841 -v 0.077717 0.026467 0.245253 -vn 0.163376 -0.602051 -0.781564 -v 0.078216 0.026467 0.245334 -vn 0.246679 -0.600785 -0.760399 -v 0.079356 0.026467 0.245627 -vn 0.327533 -0.601283 -0.728822 -v 0.080451 0.026467 0.246061 -vn 0.397941 -0.576519 -0.713631 -v 0.080902 0.026467 0.246288 -vn 0.525421 -0.601973 -0.601300 -v 0.082436 0.026467 0.247320 -vn 0.598626 -0.353462 -0.718827 -v 0.082560 0.026783 0.247170 -vn 0.637418 0.005170 -0.770501 -v 0.082603 0.027147 0.247118 -vn 0.594415 0.365553 -0.716269 -v 0.082558 0.027511 0.247173 -vn 0.569685 -0.601873 -0.559649 -v 0.083294 0.026467 0.248126 -vn 0.621302 -0.587098 -0.518941 -v 0.083520 0.026467 0.248376 -vn 0.707823 -0.601971 -0.369617 -v 0.084676 0.026467 0.250028 -vn 0.822106 -0.352708 -0.446921 -v 0.084847 0.026783 0.249934 -vn 0.876296 0.005172 -0.481745 -v 0.084905 0.027147 0.249902 -vn 0.814456 0.362779 -0.452828 -v 0.084843 0.027511 0.249936 -vn 0.734764 -0.601451 -0.313652 -v 0.085177 0.026467 0.251093 -vn 0.793818 -0.602115 0.085498 -v 0.085762 0.026467 0.255720 -vn 0.798801 -0.601595 0.000323 -v 0.085836 0.026467 0.254545 -vn 0.794135 -0.601655 -0.085798 -v 0.085762 0.026467 0.253370 -vn 0.793171 -0.590640 -0.148409 -v 0.085685 0.026467 0.252871 -vn 0.772335 -0.600504 -0.207105 -v 0.085541 0.026467 0.252213 -vn 0.759693 -0.595149 -0.262037 -v 0.085238 0.026467 0.251250 -vn 0.718983 -0.637278 0.277383 -v 0.082715 0.023519 0.256893 -vn 0.729993 -0.586172 0.351442 -v 0.082479 0.023519 0.257444 -vn 0.664873 -0.638109 0.388279 -v 0.082195 0.023519 0.257972 -vn 0.660024 -0.587827 0.467791 -v 0.081980 0.023519 0.258309 -vn 0.603100 -0.629342 0.490101 -v 0.081491 0.023519 0.258941 -vn 0.577481 -0.585980 0.568457 -v 0.081357 0.023519 0.259090 -vn -0.179757 -0.588347 0.788375 -v 0.074972 0.023519 0.261060 -vn -0.084150 -0.586209 0.805778 -v 0.075959 0.023519 0.261208 -vn 0.504385 -0.587236 0.633048 -v 0.080625 0.023519 0.259769 -vn 0.425923 -0.585200 0.690022 -v 0.079800 0.023519 0.260332 -vn 0.351620 -0.619049 0.702240 -v 0.079625 0.023519 0.260429 -vn 0.306663 -0.584232 0.751419 -v 0.078900 0.023519 0.260765 -vn 0.231790 -0.636658 0.735486 -v 0.078524 0.023519 0.260900 -vn 0.180603 -0.585970 0.789951 -v 0.077946 0.023519 0.261060 -vn 0.110977 -0.638145 0.761876 -v 0.077356 0.023519 0.261167 -vn 0.045581 -0.587629 0.807845 -v 0.076958 0.023519 0.261208 -vn -0.006963 -0.629165 0.777241 -v 0.076159 0.023519 0.261220 -vn -0.273912 -0.586473 0.762248 -v 0.074017 0.023519 0.260765 -vn -0.329498 -0.620002 0.712060 -v 0.073832 0.023519 0.260689 -vn -0.394800 -0.586204 0.707459 -v 0.073118 0.023519 0.260332 -vn -0.430972 -0.637908 0.638229 -v 0.072778 0.023519 0.260122 -vn -0.505100 -0.585940 0.633679 -v 0.072293 0.023519 0.259769 -vn -0.526499 -0.637968 0.561957 -v 0.071841 0.023519 0.259375 -vn -0.603580 -0.587239 0.539298 -v 0.071560 0.023519 0.259090 -vn -0.612047 -0.628838 0.479543 -v 0.071053 0.023519 0.258473 -vn -0.682300 -0.586313 0.436697 -v 0.070938 0.023519 0.258309 -vn -0.728342 -0.588596 0.350818 -v 0.070438 0.023519 0.257444 -vn -0.766768 -0.586430 0.261087 -v 0.070074 0.023519 0.256515 -vn -0.762333 -0.619812 0.186233 -v 0.070017 0.023519 0.256323 -vn -0.799316 -0.586092 0.132626 -v 0.069851 0.023519 0.255541 -vn -0.767672 -0.637937 0.060958 -v 0.069804 0.023519 0.255144 -vn -0.810479 -0.585768 -0.000001 -v 0.069777 0.023519 0.254545 -vn -0.767778 -0.637797 -0.061091 -v 0.069804 0.023519 0.253946 -vn -0.797751 -0.587623 -0.135250 -v 0.069851 0.023519 0.253549 -vn -0.756093 -0.629280 -0.179806 -v 0.070017 0.023519 0.252767 -vn -0.766768 -0.586430 -0.261088 -v 0.070074 0.023519 0.252575 -vn -0.728342 -0.588596 -0.350816 -v 0.070438 0.023519 0.251646 -vn -0.682300 -0.586312 -0.436698 -v 0.070938 0.023519 0.250781 -vn -0.620956 -0.619475 -0.480276 -v 0.071053 0.023519 0.250617 -vn -0.602363 -0.585741 -0.542279 -v 0.071560 0.023519 0.250000 -vn -0.526416 -0.637821 -0.562202 -v 0.071841 0.023519 0.249715 -vn -0.505254 -0.585435 -0.634023 -v 0.072293 0.023519 0.249321 -vn -0.431294 -0.637506 -0.638414 -v 0.072778 0.023519 0.248968 -vn -0.391750 -0.587757 -0.707866 -v 0.073118 0.023519 0.248758 -vn -0.330631 -0.629474 -0.703168 -v 0.073832 0.023519 0.248401 -vn -0.273914 -0.586471 -0.762248 -v 0.074017 0.023519 0.248325 -vn -0.179752 -0.588348 -0.788376 -v 0.074972 0.023519 0.248031 -vn -0.084180 -0.586245 -0.805748 -v 0.075959 0.023519 0.247882 -vn -0.011631 -0.619540 -0.784879 -v 0.076159 0.023519 0.247870 -vn 0.048573 -0.585635 -0.809118 -v 0.076958 0.023519 0.247882 -vn 0.111180 -0.637711 -0.762210 -v 0.077356 0.023519 0.247923 -vn 0.181135 -0.584939 -0.790593 -v 0.077946 0.023519 0.248031 -vn 0.229952 -0.637171 -0.735619 -v 0.078524 0.023519 0.248190 -vn 0.309069 -0.587857 -0.747596 -v 0.078900 0.023519 0.248325 -vn 0.343664 -0.629550 -0.696823 -v 0.079625 0.023519 0.248661 -vn 0.425328 -0.586341 -0.689421 -v 0.079800 0.023519 0.248758 -vn 0.504589 -0.587926 -0.632245 -v 0.080625 0.023519 0.249321 -vn 0.577494 -0.585941 -0.568483 -v 0.081357 0.023519 0.250000 -vn 0.606382 -0.619483 -0.498540 -v 0.081491 0.023519 0.250149 -vn 0.663226 -0.585326 -0.466395 -v 0.081980 0.023519 0.250781 -vn 0.665325 -0.637404 -0.388664 -v 0.082195 0.023519 0.251118 -vn 0.730053 -0.585899 -0.351774 -v 0.082479 0.023519 0.251646 -vn 0.718154 -0.638012 -0.277843 -v 0.082715 0.023519 0.252197 -vn 0.777188 -0.587878 -0.224452 -v 0.082844 0.023519 0.252575 -vn 0.759092 -0.629512 -0.165811 -v 0.083033 0.023519 0.253352 -vn 0.804370 -0.586136 -0.097132 -v 0.083066 0.023519 0.253549 -vn 0.809388 -0.587274 0.000437 -v 0.083141 0.023519 0.254545 -vn 0.804858 -0.585494 0.096955 -v 0.083066 0.023519 0.255541 -vn 0.768021 -0.619296 0.163143 -v 0.083033 0.023519 0.255738 -vn 0.778395 -0.584839 0.228176 -v 0.082844 0.023519 0.256515 -vn 0.920083 -0.279440 -0.274518 -v 0.082801 0.023438 0.252589 -vn 0.950328 -0.280992 -0.133870 -v 0.083022 0.023438 0.253556 -vn 0.970167 0.193377 -0.146227 -v 0.083018 0.023346 0.253556 -vn 0.359012 -0.279536 -0.890489 -v 0.078884 0.023438 0.248367 -vn 0.487877 -0.280907 -0.826479 -v 0.079777 0.023438 0.248797 -vn 0.490556 0.193381 -0.849682 -v 0.079775 0.023346 0.248800 -vn -0.472377 -0.279401 -0.835940 -v 0.073140 0.023438 0.248797 -vn -0.341977 -0.281038 -0.896699 -v 0.074034 0.023438 0.248367 -vn -0.358443 0.193395 -0.913300 -v 0.074035 0.023346 0.248370 -vn -0.948061 -0.279493 -0.151867 -v 0.069896 0.023438 0.253556 -vn -0.914311 -0.280943 -0.291729 -v 0.070116 0.023438 0.252589 -vn -0.937532 0.193388 -0.289196 -v 0.070120 0.023346 0.252590 -vn -0.709849 -0.279456 0.646543 -v 0.071593 0.023438 0.259059 -vn -0.798146 -0.280948 0.532946 -v 0.070975 0.023438 0.258284 -vn -0.810646 0.193344 0.552695 -v 0.070978 0.023346 0.258282 -vn 0.062898 -0.279496 0.958085 -v 0.076955 0.023438 0.261164 -vn -0.080954 -0.280992 0.956290 -v 0.075963 0.023438 0.261164 -vn -0.073319 0.193463 0.978364 -v 0.075963 0.023346 0.261160 -vn 0.788286 -0.279475 0.548178 -v 0.081943 0.023438 0.258284 -vn 0.697196 -0.280951 0.659534 -v 0.081324 0.023438 0.259059 -vn 0.719219 0.193353 0.667337 -v 0.081321 0.023346 0.259057 -vn 0.864508 -0.281596 -0.416329 -v 0.082439 0.023438 0.251665 -vn 0.789633 -0.281511 -0.545190 -v 0.081943 0.023438 0.250806 -vn 0.213528 -0.281510 -0.935499 -v 0.077936 0.023438 0.248074 -vn 0.066069 -0.281528 -0.957276 -v 0.076955 0.023438 0.247926 -vn -0.598263 -0.281565 -0.750202 -v 0.072321 0.023438 0.249356 -vn -0.707238 -0.281491 -0.648519 -v 0.071593 0.023438 0.250031 -vn -0.959538 -0.281579 -0.000001 -v 0.069822 0.023438 0.254545 -vn -0.947978 -0.281527 0.148594 -v 0.069896 0.023438 0.255534 -vn -0.598260 -0.281567 0.750203 -v 0.072321 0.023438 0.259734 -vn -0.474894 -0.281434 0.833829 -v 0.073140 0.023438 0.260293 -vn 0.213522 -0.281508 0.935501 -v 0.077936 0.023438 0.261016 -vn 0.355810 -0.281570 0.891133 -v 0.078884 0.023438 0.260723 -vn 0.864510 -0.281596 0.416326 -v 0.082439 0.023438 0.257425 -vn 0.918587 -0.281475 0.277435 -v 0.082801 0.023438 0.256501 -vn 0.950399 -0.281100 0.133134 -v 0.083022 0.023438 0.255534 -vn 0.488486 -0.281017 0.826081 -v 0.079777 0.023438 0.260293 -vn -0.341267 -0.281145 0.896936 -v 0.074034 0.023438 0.260723 -vn -0.914058 -0.281052 0.292416 -v 0.070116 0.023438 0.256501 -vn -0.798525 -0.281058 -0.532319 -v 0.070975 0.023438 0.250806 -vn -0.081688 -0.281101 -0.956195 -v 0.075963 0.023438 0.247926 -vn 0.696655 -0.281072 -0.660054 -v 0.081324 0.023438 0.250031 -vn 0.883964 0.193372 0.425694 -v 0.082435 0.023346 0.257423 -vn 0.937532 0.193388 0.289196 -v 0.082797 0.023346 0.256500 -vn 0.488037 0.622345 0.611970 -v 0.080618 0.023262 0.259761 -vn 0.611731 0.193303 0.767085 -v 0.080595 0.023346 0.259731 -vn 0.599714 -0.273504 0.752023 -v 0.080597 0.023438 0.259734 -vn 0.218323 0.193427 0.956515 -v 0.077935 0.023346 0.261012 -vn 0.358443 0.193395 0.913300 -v 0.078882 0.023346 0.260720 -vn -0.174171 0.622374 0.763096 -v 0.074974 0.023262 0.261049 -vn -0.218321 0.193420 0.956517 -v 0.074983 0.023346 0.261012 -vn -0.214047 -0.273443 0.937770 -v 0.074982 0.023438 0.261016 -vn -0.611726 0.193304 0.767088 -v 0.072323 0.023346 0.259731 -vn -0.490556 0.193381 0.849682 -v 0.073142 0.023346 0.260290 -vn -0.705180 0.622411 0.339597 -v 0.070448 0.023262 0.257440 -vn -0.883965 0.193372 0.425692 -v 0.070482 0.023346 0.257423 -vn -0.866608 -0.273533 0.417337 -v 0.070479 0.023438 0.257425 -vn -0.981121 0.193393 -0.000002 -v 0.069825 0.023346 0.254545 -vn -0.970166 0.193378 0.146227 -v 0.069899 0.023346 0.255534 -vn -0.705178 0.622411 -0.339600 -v 0.070448 0.023262 0.251650 -vn -0.883965 0.193371 -0.425692 -v 0.070482 0.023346 0.251667 -vn -0.866610 -0.273534 -0.417332 -v 0.070479 0.023438 0.251665 -vn -0.611730 0.193302 -0.767086 -v 0.072323 0.023346 0.249359 -vn -0.719221 0.193325 -0.667343 -v 0.071596 0.023346 0.250033 -vn -0.174177 0.622374 -0.763095 -v 0.074974 0.023262 0.248041 -vn -0.218322 0.193419 -0.956517 -v 0.074983 0.023346 0.248078 -vn -0.214037 -0.273441 -0.937773 -v 0.074982 0.023438 0.248074 -vn 0.218322 0.193429 -0.956515 -v 0.077935 0.023346 0.248078 -vn 0.073319 0.193463 -0.978364 -v 0.076954 0.023346 0.247930 -vn 0.488009 0.622402 -0.611934 -v 0.080618 0.023262 0.249329 -vn 0.611726 0.193304 -0.767088 -v 0.080595 0.023346 0.249359 -vn 0.599710 -0.273505 -0.752025 -v 0.080597 0.023438 0.249356 -vn 0.883963 0.193372 -0.425695 -v 0.082435 0.023346 0.251667 -vn 0.810640 0.193374 -0.552693 -v 0.081939 0.023346 0.250808 -vn 0.782706 0.622392 -0.000001 -v 0.083130 0.023262 0.254545 -vn 0.981128 0.193357 -0.000002 -v 0.083092 0.023346 0.254545 -vn 0.961867 -0.273517 -0.000001 -v 0.083096 0.023438 0.254545 -vn 0.745945 0.622106 0.237802 -v 0.082834 0.023262 0.256512 -vn 0.708544 0.617685 0.341219 -v 0.082470 0.023262 0.257440 -vn 0.650743 0.622073 0.435382 -v 0.081971 0.023262 0.258303 -vn 0.279132 0.622170 0.731430 -v 0.078896 0.023262 0.260755 -vn 0.175009 0.617644 0.766738 -v 0.077943 0.023262 0.261049 -vn 0.065332 0.622110 0.780200 -v 0.076957 0.023262 0.261198 -vn -0.397855 0.622056 0.674358 -v 0.073123 0.023262 0.260323 -vn -0.490361 0.617617 0.614894 -v 0.072299 0.023262 0.259761 -vn -0.569280 0.622068 0.537543 -v 0.071568 0.023262 0.259083 -vn -0.775239 0.622123 0.109394 -v 0.069862 0.023262 0.255539 -vn -0.786435 0.617673 -0.000001 -v 0.069787 0.023262 0.254545 -vn -0.775206 0.622071 -0.109923 -v 0.069862 0.023262 0.253551 -vn -0.568884 0.622123 -0.537898 -v 0.071568 0.023262 0.250007 -vn -0.490335 0.617680 -0.614852 -v 0.072299 0.023262 0.249329 -vn -0.397390 0.622057 -0.674631 -v 0.073123 0.023262 0.248767 -vn 0.065861 0.622166 -0.780111 -v 0.076957 0.023262 0.247892 -vn 0.175001 0.617645 -0.766740 -v 0.077943 0.023262 0.248041 -vn 0.279650 0.622117 -0.731277 -v 0.078896 0.023262 0.248335 -vn 0.651003 0.622127 -0.434918 -v 0.081971 0.023262 0.250787 -vn 0.708546 0.617685 -0.341217 -v 0.082470 0.023262 0.251650 -vn 0.746146 0.622052 -0.237312 -v 0.082834 0.023262 0.252579 -vn 0.773357 0.622363 0.120762 -v 0.083056 0.023262 0.255539 -vn 0.523151 0.847807 0.086814 -v 0.083127 0.023204 0.255550 -vn 0.490311 0.870683 0.038820 -v 0.083175 0.023204 0.255150 -vn 0.970167 0.193376 0.146226 -v 0.083018 0.023346 0.255534 -vn 0.530462 0.847709 -0.000000 -v 0.083202 0.023204 0.254545 -vn 0.491049 0.862871 0.119690 -v 0.082959 0.023204 0.256339 -vn 0.336207 0.870615 0.359159 -v 0.081119 0.023204 0.259419 -vn 0.394520 0.848526 0.352643 -v 0.081402 0.023204 0.259132 -vn 0.578911 0.621152 0.528235 -v 0.081349 0.023262 0.259083 -vn 0.810640 0.193371 0.552693 -v 0.081939 0.023346 0.258282 -vn 0.392171 0.866961 0.307540 -v 0.081914 0.023204 0.258509 -vn 0.446247 0.848017 0.285885 -v 0.082030 0.023204 0.258344 -vn 0.475113 0.849657 0.228802 -v 0.082534 0.023204 0.257471 -vn 0.501771 0.847998 0.170660 -v 0.082903 0.023204 0.256533 -vn 0.330746 0.847704 0.414736 -v 0.080663 0.023204 0.259817 -vn 0.387792 0.622293 0.679977 -v 0.079794 0.023262 0.260323 -vn 0.258319 0.847785 0.463175 -v 0.079830 0.023204 0.260385 -vn 0.275343 0.870691 0.407534 -v 0.080174 0.023204 0.260173 -vn 0.490552 0.193386 0.849683 -v 0.079775 0.023346 0.260290 -vn 0.212577 0.862881 0.458528 -v 0.079109 0.023204 0.260746 -vn -0.071180 0.870609 0.486799 -v 0.075553 0.023204 0.261228 -vn -0.029725 0.848502 0.528357 -v 0.075955 0.023204 0.261270 -vn -0.052043 0.621210 0.781914 -v 0.075960 0.023262 0.261198 -vn 0.073317 0.193466 0.978364 -v 0.076954 0.023346 0.261160 -vn 0.004072 0.866946 0.498385 -v 0.076761 0.023204 0.261282 -vn 0.054732 0.847993 0.527173 -v 0.076963 0.023204 0.261270 -vn 0.117354 0.849637 0.514145 -v 0.077959 0.023204 0.261119 -vn 0.179410 0.848002 0.498704 -v 0.078922 0.023204 0.260822 -vn -0.118051 0.847686 0.517196 -v 0.074958 0.023204 0.261119 -vn -0.289813 0.622406 0.727062 -v 0.074021 0.023262 0.260755 -vn -0.201052 0.847804 0.490721 -v 0.073995 0.023204 0.260822 -vn -0.146953 0.870678 0.469388 -v 0.074375 0.023204 0.260959 -vn -0.358443 0.193392 0.913301 -v 0.074035 0.023346 0.260720 -vn -0.225966 0.862863 0.452113 -v 0.073263 0.023204 0.260483 -vn -0.424971 0.870610 0.247868 -v 0.070670 0.023204 0.258004 -vn -0.431587 0.848528 0.306159 -v 0.070887 0.023204 0.258344 -vn -0.643816 0.621150 0.446849 -v 0.070946 0.023262 0.258303 -vn -0.719221 0.193324 0.667343 -v 0.071596 0.023346 0.259057 -vn -0.387097 0.866961 0.313903 -v 0.071380 0.023204 0.258982 -vn -0.378004 0.848027 0.371434 -v 0.071515 0.023204 0.259132 -vn -0.328790 0.849653 0.412295 -v 0.072254 0.023204 0.259817 -vn -0.278049 0.847986 0.451229 -v 0.073087 0.023204 0.260385 -vn -0.477929 0.847709 0.230161 -v 0.070383 0.023204 0.257471 -vn -0.749184 0.622344 0.226742 -v 0.070084 0.023262 0.256512 -vn -0.509022 0.847799 0.148772 -v 0.070015 0.023204 0.256533 -vn -0.458602 0.870681 0.177759 -v 0.070145 0.023204 0.256915 -vn -0.937533 0.193386 0.289195 -v 0.070120 0.023346 0.256500 -vn -0.494352 0.862870 0.105223 -v 0.069824 0.023204 0.255749 -vn -0.458751 0.870613 -0.177709 -v 0.070145 0.023204 0.252176 -vn -0.508488 0.848507 -0.146546 -v 0.070015 0.023204 0.252557 -vn -0.750778 0.621149 -0.224734 -v 0.070084 0.023262 0.252579 -vn -0.970167 0.193376 -0.146227 -v 0.069899 0.023346 0.253556 -vn -0.486775 0.866958 -0.106928 -v 0.069824 0.023204 0.253341 -vn -0.526117 0.848005 -0.063949 -v 0.069791 0.023204 0.253540 -vn -0.527355 0.849645 0.000000 -v 0.069715 0.023204 0.254545 -vn -0.526114 0.848006 0.063954 -v 0.069791 0.023204 0.255550 -vn -0.477928 0.847709 -0.230161 -v 0.070383 0.023204 0.251619 -vn -0.644391 0.622345 -0.444350 -v 0.070946 0.023262 0.250787 -vn -0.433660 0.847820 -0.305188 -v 0.070887 0.023204 0.250746 -vn -0.424917 0.870678 -0.247720 -v 0.070670 0.023204 0.251086 -vn -0.810647 0.193342 -0.552694 -v 0.070978 0.023346 0.250808 -vn -0.390473 0.862884 -0.320876 -v 0.071380 0.023204 0.250108 -vn -0.147086 0.870610 -0.469472 -v 0.074375 0.023204 0.248132 -vn -0.202459 0.848511 -0.488916 -v 0.073995 0.023204 0.248268 -vn -0.292366 0.621212 -0.727061 -v 0.074021 0.023262 0.248335 -vn -0.490552 0.193386 -0.849683 -v 0.073142 0.023346 0.248800 -vn -0.219899 0.866943 -0.447274 -v 0.073263 0.023204 0.248607 -vn -0.277981 0.848034 -0.451183 -v 0.073087 0.023204 0.248705 -vn -0.328750 0.849693 -0.412244 -v 0.072254 0.023204 0.249273 -vn -0.378006 0.848027 -0.371431 -v 0.071515 0.023204 0.249958 -vn -0.118049 0.847686 -0.517197 -v 0.074958 0.023204 0.247971 -vn -0.054351 0.622402 -0.780808 -v 0.075960 0.023262 0.247892 -vn -0.031777 0.847794 -0.529373 -v 0.075955 0.023204 0.247820 -vn -0.071263 0.870677 -0.486666 -v 0.075553 0.023204 0.247863 -vn -0.073317 0.193466 -0.978364 -v 0.075963 0.023346 0.247930 -vn 0.007421 0.862867 -0.505376 -v 0.076761 0.023204 0.247808 -vn 0.275328 0.870625 -0.407684 -v 0.080174 0.023204 0.248917 -vn 0.256000 0.848540 -0.463081 -v 0.079830 0.023204 0.248705 -vn 0.386167 0.621167 -0.681928 -v 0.079794 0.023262 0.248767 -vn 0.358442 0.193393 -0.913301 -v 0.078882 0.023346 0.248370 -vn 0.212556 0.866956 -0.450784 -v 0.079109 0.023204 0.248344 -vn 0.179412 0.848001 -0.498704 -v 0.078922 0.023204 0.248268 -vn 0.117352 0.849637 -0.514146 -v 0.077959 0.023204 0.247971 -vn 0.054733 0.847994 -0.527173 -v 0.076963 0.023204 0.247820 -vn 0.330702 0.847746 -0.414685 -v 0.080663 0.023204 0.249273 -vn 0.576605 0.622346 -0.529351 -v 0.081349 0.023262 0.250007 -vn 0.394034 0.847819 -0.354880 -v 0.081402 0.023204 0.249958 -vn 0.336053 0.870684 -0.359134 -v 0.081119 0.023204 0.249671 -vn 0.719220 0.193353 -0.667336 -v 0.081321 0.023346 0.250033 -vn 0.399723 0.862883 -0.309280 -v 0.081914 0.023204 0.250581 -vn 0.490425 0.870613 -0.038931 -v 0.083175 0.023204 0.253941 -vn 0.521705 0.848514 -0.088588 -v 0.083127 0.023204 0.253540 -vn 0.773922 0.621170 -0.123260 -v 0.083056 0.023262 0.253551 -vn 0.937533 0.193386 -0.289195 -v 0.082797 0.023346 0.252590 -vn 0.484981 0.866947 -0.114872 -v 0.082959 0.023204 0.252751 -vn 0.501770 0.847999 -0.170660 -v 0.082903 0.023204 0.252557 -vn 0.475112 0.849658 -0.228802 -v 0.082534 0.023204 0.251619 -vn 0.446247 0.848018 -0.285884 -v 0.082030 0.023204 0.250746 -vn -0.530102 0.846957 0.040695 -v 0.067275 0.022030 0.255135 -vn -0.542333 0.836398 0.079453 -v 0.067404 0.022030 0.256188 -vn -0.518443 0.847147 0.116442 -v 0.067426 0.022030 0.256304 -vn -0.508177 0.846951 0.156303 -v 0.067725 0.022030 0.257445 -vn -0.538433 0.815046 0.213987 -v 0.067843 0.022030 0.257779 -vn -0.478888 0.847042 0.230623 -v 0.068167 0.022030 0.258538 -vn -0.502836 0.815145 0.287567 -v 0.068559 0.022030 0.259265 -vn -0.438998 0.847034 0.299690 -v 0.068746 0.022030 0.259566 -vn -0.414295 0.847129 0.332764 -v 0.069451 0.022030 0.260511 -vn -0.401006 0.834650 0.377562 -v 0.069528 0.022030 0.260600 -vn -0.363404 0.846653 0.388737 -v 0.070272 0.022030 0.261358 -vn -0.368519 0.806631 0.462103 -v 0.070721 0.022030 0.261740 -vn -0.298710 0.846944 0.439839 -v 0.071194 0.022030 0.262093 -vn -0.276024 0.836387 0.473569 -v 0.072098 0.022030 0.262649 -vn -0.232213 0.847136 0.477952 -v 0.072202 0.022030 0.262704 -vn -0.194634 0.846955 0.494758 -v 0.073280 0.022030 0.263182 -vn -0.168396 0.815066 0.554356 -v 0.073615 0.022030 0.263297 -vn -0.118280 0.847035 0.518211 -v 0.074411 0.022030 0.263517 -vn -0.088687 0.815138 0.572438 -v 0.075223 0.022030 0.263665 -vn -0.039404 0.847027 0.530087 -v 0.075575 0.022030 0.263705 -vn 0.001819 0.847162 0.531332 -v 0.076754 0.022030 0.263743 -vn 0.045137 0.834655 0.548921 -v 0.076872 0.022030 0.263739 -vn 0.077375 0.846573 0.526619 -v 0.077927 0.022030 0.263630 -vn 0.131531 0.806579 0.576307 -v 0.078507 0.022030 0.263517 -vn 0.157633 0.846963 0.507746 -v 0.079077 0.022030 0.263368 -vn 0.198126 0.836406 0.511050 -v 0.080076 0.022030 0.263007 -vn 0.228875 0.847128 0.479574 -v 0.080184 0.022030 0.262960 -vn 0.265438 0.846973 0.460628 -v 0.081229 0.022030 0.262415 -vn 0.328443 0.815029 0.477339 -v 0.081529 0.022030 0.262226 -vn 0.331377 0.847068 0.415530 -v 0.082197 0.022030 0.261740 -vn 0.392274 0.815120 0.426262 -v 0.082818 0.022030 0.261197 -vn 0.389860 0.847046 0.361278 -v 0.083070 0.022030 0.260947 -vn 0.416580 0.847139 0.329874 -v 0.083834 0.022030 0.260049 -vn 0.457331 0.834638 0.306966 -v 0.083904 0.022030 0.259954 -vn 0.459912 0.846613 0.267821 -v 0.084477 0.022030 0.259061 -vn 0.532570 0.806592 0.256472 -v 0.084750 0.022030 0.258538 -vn 0.495250 0.846966 0.193328 -v 0.084989 0.022030 0.257999 -vn 0.523099 0.836399 0.163718 -v 0.085330 0.022030 0.256993 -vn 0.517621 0.847150 0.120023 -v 0.085361 0.022030 0.256879 -vn 0.525705 0.846928 0.079670 -v 0.085586 0.022030 0.255722 -vn 0.577984 0.815027 0.040821 -v 0.085625 0.022030 0.255370 -vn 0.531538 0.847035 -0.000000 -v 0.085662 0.022030 0.254545 -vn 0.577849 0.815117 -0.040917 -v 0.085625 0.022030 0.253720 -vn 0.525580 0.847017 -0.079545 -v 0.085586 0.022030 0.253368 -vn 0.517620 0.847150 -0.120025 -v 0.085361 0.022030 0.252211 -vn 0.525108 0.834657 -0.166164 -v 0.085330 0.022030 0.252097 -vn 0.496125 0.846623 -0.192583 -v 0.084989 0.022030 0.251092 -vn 0.532570 0.806592 -0.256473 -v 0.084750 0.022030 0.250552 -vn 0.459949 0.846955 -0.266672 -v 0.084477 0.022030 0.250029 -vn 0.454185 0.836377 -0.306903 -v 0.083904 0.022030 0.249136 -vn 0.416649 0.847103 -0.329879 -v 0.083834 0.022030 0.249041 -vn 0.390064 0.846920 -0.361353 -v 0.083070 0.022030 0.248143 -vn 0.392280 0.815029 -0.426432 -v 0.082818 0.022030 0.247893 -vn 0.331377 0.847067 -0.415531 -v 0.082197 0.022030 0.247350 -vn 0.328287 0.815118 -0.477295 -v 0.081529 0.022030 0.246865 -vn 0.265456 0.847059 -0.460460 -v 0.081229 0.022030 0.246675 -vn 0.228878 0.847126 -0.479575 -v 0.080184 0.022030 0.246130 -vn 0.197467 0.834665 -0.514142 -v 0.080076 0.022030 0.246083 -vn 0.158760 0.846621 -0.507965 -v 0.079077 0.022030 0.245723 -vn 0.131526 0.806621 -0.576249 -v 0.078507 0.022030 0.245573 -vn 0.078281 0.846970 -0.525846 -v 0.077927 0.022030 0.245460 -vn 0.043198 0.836399 -0.546417 -v 0.076872 0.022030 0.245351 -vn 0.001818 0.847161 -0.531333 -v 0.076754 0.022030 0.245347 -vn -0.039310 0.846938 -0.530236 -v 0.075575 0.022030 0.245385 -vn -0.088809 0.815049 -0.572545 -v 0.075223 0.022030 0.245425 -vn -0.118278 0.847035 -0.518211 -v 0.074411 0.022030 0.245573 -vn -0.168459 0.815155 -0.554206 -v 0.073615 0.022030 0.245793 -vn -0.194488 0.847043 -0.494665 -v 0.073280 0.022030 0.245908 -vn -0.232212 0.847135 -0.477953 -v 0.072202 0.022030 0.246386 -vn -0.278853 0.834645 -0.474983 -v 0.072098 0.022030 0.246441 -vn -0.298179 0.846601 -0.440858 -v 0.071194 0.022030 0.246997 -vn -0.368518 0.806629 -0.462109 -v 0.070721 0.022030 0.247350 -vn -0.362332 0.846954 -0.389083 -v 0.070272 0.022030 0.247732 -vn -0.400258 0.836396 -0.374480 -v 0.069528 0.022030 0.248490 -vn -0.414294 0.847130 -0.332765 -v 0.069451 0.022030 0.248579 -vn -0.439048 0.846947 -0.299862 -v 0.068746 0.022030 0.249525 -vn -0.503039 0.815019 -0.287568 -v 0.068559 0.022030 0.249825 -vn -0.478889 0.847042 -0.230619 -v 0.068167 0.022030 0.250552 -vn -0.538355 0.815135 -0.213844 -v 0.067843 0.022030 0.251311 -vn -0.508013 0.847039 -0.156360 -v 0.067725 0.022030 0.251645 -vn -0.518443 0.847147 -0.116443 -v 0.067426 0.022030 0.252786 -vn -0.545203 0.834656 -0.078121 -v 0.067404 0.022030 0.252902 -vn -0.530566 0.846615 -0.041746 -v 0.067275 0.022030 0.253955 -vn -0.591098 0.806600 -0.000000 -v 0.067256 0.022030 0.254545 -vn 0.779016 0.617932 0.106270 -v 0.085655 0.021974 0.255731 -vn 0.785872 0.618389 -0.000001 -v 0.085731 0.021974 0.254545 -vn 0.762102 0.617554 0.194493 -v 0.085428 0.021974 0.256897 -vn 0.729740 0.618393 0.291667 -v 0.085054 0.021974 0.258025 -vn 0.682243 0.618859 0.389304 -v 0.084538 0.021974 0.259095 -vn 0.627366 0.617682 0.474216 -v 0.083890 0.021974 0.260091 -vn 0.402611 0.617934 0.675324 -v 0.081266 0.021974 0.262475 -vn 0.490000 0.618343 0.614453 -v 0.082240 0.021974 0.261795 -vn 0.568763 0.618007 0.542749 -v 0.083120 0.021974 0.260996 -vn 0.323094 0.617553 0.717104 -v 0.080212 0.021974 0.263024 -vn 0.226961 0.618340 0.752426 -v 0.079097 0.021974 0.263435 -vn 0.121011 0.618852 0.776130 -v 0.077939 0.021974 0.263699 -vn 0.020393 0.617668 0.786174 -v 0.076756 0.021974 0.263813 -vn -0.276955 0.617944 0.735827 -v 0.073256 0.021974 0.263247 -vn -0.174864 0.618413 0.766151 -v 0.074395 0.021974 0.263585 -vn -0.069745 0.617895 0.783161 -v 0.075568 0.021974 0.263775 -vn -0.359187 0.617593 0.699689 -v 0.072170 0.021974 0.262766 -vn -0.446739 0.618385 0.646548 -v 0.071154 0.021974 0.262150 -vn -0.531346 0.618876 0.578502 -v 0.070225 0.021974 0.261409 -vn -0.601952 0.617641 0.506136 -v 0.069398 0.021974 0.260556 -vn -0.747961 0.617957 0.242247 -v 0.067658 0.021974 0.257467 -vn -0.708042 0.618394 0.340977 -v 0.068104 0.021974 0.258568 -vn -0.655727 0.617980 0.433732 -v 0.068687 0.021974 0.259604 -vn -0.771039 0.617527 0.155431 -v 0.067357 0.021974 0.256318 -vn -0.784024 0.618391 0.053840 -v 0.067205 0.021974 0.255139 -vn -0.783577 0.618880 -0.054725 -v 0.067205 0.021974 0.253951 -vn -0.771050 0.617605 -0.155066 -v 0.067357 0.021974 0.252772 -vn -0.655728 0.617975 -0.433737 -v 0.068687 0.021974 0.249486 -vn -0.708044 0.618392 -0.340977 -v 0.068104 0.021974 0.250522 -vn -0.747962 0.617956 -0.242246 -v 0.067658 0.021974 0.251623 -vn -0.602234 0.617564 -0.505894 -v 0.069398 0.021974 0.248534 -vn -0.530953 0.618333 -0.579442 -v 0.070225 0.021974 0.247681 -vn -0.445770 0.618870 -0.646753 -v 0.071154 0.021974 0.246940 -vn -0.359485 0.617672 -0.699465 -v 0.072170 0.021974 0.246324 -vn -0.069734 0.618013 -0.783069 -v 0.075568 0.021974 0.245315 -vn -0.174870 0.618414 -0.766149 -v 0.074395 0.021974 0.245505 -vn -0.276950 0.617946 -0.735828 -v 0.073256 0.021974 0.245843 -vn 0.020026 0.617594 -0.786242 -v 0.076756 0.021974 0.245277 -vn 0.121978 0.618325 -0.776399 -v 0.077939 0.021974 0.245391 -vn 0.227734 0.618829 -0.751790 -v 0.079097 0.021974 0.245656 -vn 0.322734 0.617633 -0.717198 -v 0.080212 0.021974 0.246066 -vn 0.568786 0.617953 -0.542786 -v 0.083120 0.021974 0.248094 -vn 0.490007 0.618341 -0.614449 -v 0.082240 0.021974 0.247295 -vn 0.402608 0.617938 -0.675322 -v 0.081266 0.021974 0.246616 -vn 0.627227 0.617564 -0.474553 -v 0.083890 0.021974 0.248999 -vn 0.683032 0.618372 -0.388695 -v 0.084538 0.021974 0.249995 -vn 0.729722 0.618881 -0.290674 -v 0.085054 0.021974 0.251065 -vn 0.761953 0.617631 -0.194831 -v 0.085428 0.021974 0.252193 -vn 0.779017 0.617931 -0.106269 -v 0.085655 0.021974 0.253359 -vn 0.966858 0.222812 -0.124662 -v 0.085694 0.021894 0.253354 -vn 0.942988 0.222765 -0.247283 -v 0.085466 0.021894 0.252183 -vn 0.903626 0.222761 -0.365838 -v 0.085090 0.021894 0.251051 -vn 0.849421 0.222781 -0.478385 -v 0.084572 0.021894 0.249976 -vn 0.781266 0.222808 -0.583078 -v 0.083921 0.021894 0.248976 -vn 0.700286 0.222817 -0.678198 -v 0.083148 0.021894 0.248067 -vn 0.607828 0.222736 -0.762190 -v 0.082264 0.021894 0.247265 -vn 0.505373 0.222728 -0.833661 -v 0.081286 0.021894 0.246582 -vn 0.394612 0.222752 -0.891439 -v 0.080228 0.021894 0.246030 -vn 0.277380 0.222756 -0.934580 -v 0.079108 0.021894 0.245618 -vn 0.155598 0.222707 -0.962388 -v 0.077945 0.021894 0.245353 -vn 0.031249 0.222824 -0.974358 -v 0.076757 0.021894 0.245238 -vn -0.093607 0.222880 -0.970341 -v 0.075565 0.021894 0.245276 -vn -0.216928 0.222853 -0.950410 -v 0.074387 0.021894 0.245467 -vn -0.336684 0.222835 -0.914871 -v 0.073243 0.021894 0.245806 -vn -0.450908 0.222816 -0.864312 -v 0.072152 0.021894 0.246289 -vn -0.557733 0.222826 -0.799551 -v 0.071131 0.021894 0.246908 -vn -0.655402 0.222819 -0.721665 -v 0.070199 0.021894 0.247652 -vn -0.742294 0.222863 -0.631927 -v 0.069368 0.021894 0.248509 -vn -0.817014 0.222829 -0.531822 -v 0.068655 0.021894 0.249465 -vn -0.878333 0.222731 -0.422992 -v 0.068069 0.021894 0.250505 -vn -0.925200 0.222808 -0.307184 -v 0.067621 0.021894 0.251611 -vn -0.956892 0.222778 -0.186352 -v 0.067319 0.021894 0.252765 -vn -0.972863 0.222793 -0.062464 -v 0.067166 0.021894 0.253948 -vn -0.972862 0.222795 0.062464 -v 0.067166 0.021894 0.255142 -vn -0.956893 0.222779 0.186350 -v 0.067319 0.021894 0.256325 -vn -0.925199 0.222805 0.307188 -v 0.067621 0.021894 0.257479 -vn -0.878336 0.222730 0.422986 -v 0.068069 0.021894 0.258585 -vn -0.817012 0.222831 0.531824 -v 0.068655 0.021894 0.259625 -vn -0.742291 0.222867 0.631929 -v 0.069368 0.021894 0.260581 -vn -0.655403 0.222819 0.721664 -v 0.070199 0.021894 0.261438 -vn -0.557734 0.222819 0.799553 -v 0.071131 0.021894 0.262182 -vn -0.450909 0.222818 0.864311 -v 0.072152 0.021894 0.262801 -vn -0.336678 0.222834 0.914873 -v 0.073243 0.021894 0.263284 -vn -0.216929 0.222694 0.950447 -v 0.074387 0.021894 0.263623 -vn -0.093613 0.222741 0.970373 -v 0.075565 0.021894 0.263814 -vn 0.031245 0.222825 0.974358 -v 0.076757 0.021894 0.263852 -vn 0.155591 0.222849 0.962356 -v 0.077945 0.021894 0.263737 -vn 0.277377 0.222755 0.934581 -v 0.079108 0.021894 0.263472 -vn 0.394613 0.222751 0.891439 -v 0.080228 0.021894 0.263060 -vn 0.505371 0.222734 0.833660 -v 0.081286 0.021894 0.262508 -vn 0.607826 0.222733 0.762193 -v 0.082264 0.021894 0.261825 -vn 0.700289 0.222810 0.678197 -v 0.083148 0.021894 0.261023 -vn 0.781266 0.222810 0.583077 -v 0.083921 0.021894 0.260114 -vn 0.849421 0.222785 0.478384 -v 0.084572 0.021894 0.259114 -vn 0.903626 0.222760 0.365838 -v 0.085090 0.021894 0.258039 -vn 0.942988 0.222765 0.247285 -v 0.085466 0.021894 0.256907 -vn 0.966858 0.222812 0.124659 -v 0.085694 0.021894 0.255736 -vn 0.974864 0.222802 -0.000001 -v 0.085770 0.021894 0.254545 -vn 0.967738 -0.218894 -0.124776 -v 0.085694 0.021805 0.253354 -vn 0.943830 -0.218930 -0.247496 -v 0.085466 0.021805 0.252183 -vn 0.904437 -0.218905 -0.366163 -v 0.085090 0.021805 0.251051 -vn 0.850186 -0.218901 -0.478817 -v 0.084572 0.021805 0.249976 -vn 0.781980 -0.218919 -0.583594 -v 0.083921 0.021805 0.248976 -vn 0.700921 -0.218944 -0.678802 -v 0.083148 0.021805 0.248067 -vn 0.608372 -0.218827 -0.762888 -v 0.082265 0.021805 0.247265 -vn 0.505825 -0.218900 -0.834400 -v 0.081286 0.021805 0.246582 -vn 0.394975 -0.218870 -0.892239 -v 0.080228 0.021805 0.246030 -vn 0.277624 -0.218864 -0.935427 -v 0.079108 0.021805 0.245618 -vn 0.155733 -0.218896 -0.963240 -v 0.077945 0.021805 0.245353 -vn 0.031282 -0.218921 -0.975241 -v 0.076757 0.021805 0.245238 -vn -0.093691 -0.218964 -0.971224 -v 0.075565 0.021805 0.245276 -vn -0.217115 -0.219002 -0.951262 -v 0.074387 0.021805 0.245467 -vn -0.337001 -0.218845 -0.915717 -v 0.073243 0.021805 0.245806 -vn -0.451311 -0.218980 -0.865082 -v 0.072152 0.021805 0.246289 -vn -0.558240 -0.218913 -0.800278 -v 0.071131 0.021805 0.246908 -vn -0.656000 -0.218868 -0.722330 -v 0.070198 0.021805 0.247652 -vn -0.742974 -0.218918 -0.632507 -v 0.069368 0.021805 0.248509 -vn -0.817757 -0.218939 -0.532296 -v 0.068655 0.021805 0.249465 -vn -0.879107 -0.218960 -0.423352 -v 0.068069 0.021805 0.250505 -vn -0.926033 -0.218922 -0.307468 -v 0.067621 0.021805 0.251611 -vn -0.957757 -0.218890 -0.186518 -v 0.067319 0.021805 0.252765 -vn -0.973748 -0.218877 -0.062508 -v 0.067166 0.021805 0.253948 -vn -0.973746 -0.218887 0.062513 -v 0.067166 0.021805 0.255142 -vn -0.957756 -0.218892 0.186518 -v 0.067319 0.021805 0.256325 -vn -0.926033 -0.218920 0.307468 -v 0.067621 0.021805 0.257479 -vn -0.879108 -0.218960 0.423350 -v 0.068069 0.021805 0.258585 -vn -0.817756 -0.218943 0.532296 -v 0.068655 0.021805 0.259625 -vn -0.742974 -0.218919 0.632506 -v 0.069368 0.021805 0.260581 -vn -0.655997 -0.218867 0.722333 -v 0.070198 0.021805 0.261438 -vn -0.558240 -0.218909 0.800280 -v 0.071131 0.021805 0.262182 -vn -0.451318 -0.218980 0.865078 -v 0.072152 0.021805 0.262801 -vn -0.336985 -0.218845 0.915723 -v 0.073243 0.021805 0.263284 -vn -0.217118 -0.219017 0.951258 -v 0.074387 0.021805 0.263623 -vn -0.093696 -0.218825 0.971255 -v 0.075565 0.021805 0.263814 -vn 0.031271 -0.218919 0.975242 -v 0.076757 0.021805 0.263852 -vn 0.155733 -0.218896 0.963240 -v 0.077945 0.021805 0.263737 -vn 0.277631 -0.218862 0.935425 -v 0.079108 0.021805 0.263472 -vn 0.394958 -0.218999 0.892215 -v 0.080228 0.021805 0.263060 -vn 0.505821 -0.218904 0.834402 -v 0.081286 0.021805 0.262508 -vn 0.608378 -0.218827 0.762884 -v 0.082265 0.021805 0.261825 -vn 0.700920 -0.218943 0.678804 -v 0.083148 0.021805 0.261023 -vn 0.781960 -0.219004 0.583589 -v 0.083921 0.021805 0.260115 -vn 0.850186 -0.218902 0.478817 -v 0.084572 0.021805 0.259115 -vn 0.904437 -0.218904 0.366162 -v 0.085090 0.021805 0.258039 -vn 0.943830 -0.218931 0.247497 -v 0.085466 0.021805 0.256907 -vn 0.967733 -0.218912 0.124780 -v 0.085694 0.021805 0.255736 -vn 0.975748 -0.218897 -0.000001 -v 0.085770 0.021805 0.254545 -vn 0.779566 -0.618201 -0.100518 -v 0.085656 0.021725 0.253359 -vn 0.760329 -0.618181 -0.199381 -v 0.085429 0.021725 0.252193 -vn 0.728584 -0.618188 -0.294974 -v 0.085054 0.021725 0.251065 -vn 0.684891 -0.618180 -0.385718 -v 0.084539 0.021725 0.249995 -vn 0.629942 -0.618171 -0.470147 -v 0.083890 0.021725 0.248999 -vn 0.564620 -0.618232 -0.546802 -v 0.083120 0.021725 0.248094 -vn 0.490079 -0.618184 -0.614550 -v 0.082240 0.021725 0.247295 -vn 0.407473 -0.618186 -0.672170 -v 0.081266 0.021725 0.246615 -vn 0.318182 -0.618143 -0.718790 -v 0.080212 0.021725 0.246065 -vn 0.223646 -0.618193 -0.753538 -v 0.079097 0.021725 0.245655 -vn 0.125453 -0.618163 -0.775974 -v 0.077939 0.021725 0.245391 -vn 0.025194 -0.618193 -0.785622 -v 0.076756 0.021725 0.245277 -vn -0.075468 -0.618274 -0.782331 -v 0.075568 0.021725 0.245315 -vn -0.174902 -0.618236 -0.766285 -v 0.074395 0.021725 0.245504 -vn -0.271456 -0.618229 -0.737634 -v 0.073256 0.021725 0.245842 -vn -0.363573 -0.618183 -0.696897 -v 0.072169 0.021725 0.246323 -vn -0.449694 -0.618200 -0.644674 -v 0.071153 0.021725 0.246939 -vn -0.528443 -0.618204 -0.581870 -v 0.070224 0.021725 0.247680 -vn -0.598512 -0.618206 -0.509515 -v 0.069398 0.021725 0.248534 -vn -0.658759 -0.618199 -0.428797 -v 0.068687 0.021725 0.249486 -vn -0.708182 -0.618196 -0.341044 -v 0.068104 0.021725 0.250522 -vn -0.745959 -0.618224 -0.247675 -v 0.067658 0.021725 0.251623 -vn -0.771528 -0.618197 -0.150258 -v 0.067356 0.021725 0.252772 -vn -0.784417 -0.618185 -0.050368 -v 0.067205 0.021725 0.253951 -vn -0.784416 -0.618187 0.050357 -v 0.067205 0.021725 0.255139 -vn -0.771529 -0.618195 0.150258 -v 0.067356 0.021725 0.256318 -vn -0.745960 -0.618225 0.247673 -v 0.067658 0.021725 0.257467 -vn -0.708182 -0.618195 0.341046 -v 0.068104 0.021725 0.258569 -vn -0.658760 -0.618197 0.428798 -v 0.068687 0.021725 0.259604 -vn -0.598509 -0.618208 0.509515 -v 0.069398 0.021725 0.260556 -vn -0.528412 -0.618263 0.581836 -v 0.070224 0.021725 0.261410 -vn -0.449694 -0.618201 0.644673 -v 0.071153 0.021725 0.262151 -vn -0.363570 -0.618184 0.696897 -v 0.072169 0.021725 0.262767 -vn -0.271455 -0.618229 0.737635 -v 0.073256 0.021725 0.263248 -vn -0.174903 -0.618196 0.766317 -v 0.074395 0.021725 0.263586 -vn -0.075482 -0.618157 0.782422 -v 0.075568 0.021725 0.263775 -vn 0.025191 -0.618190 0.785625 -v 0.076756 0.021725 0.263814 -vn 0.125456 -0.618165 0.775973 -v 0.077939 0.021725 0.263699 -vn 0.223647 -0.618194 0.753537 -v 0.079097 0.021725 0.263435 -vn 0.318176 -0.618182 0.718760 -v 0.080212 0.021725 0.263025 -vn 0.407467 -0.618187 0.672172 -v 0.081266 0.021725 0.262475 -vn 0.490081 -0.618184 0.614548 -v 0.082240 0.021725 0.261795 -vn 0.564620 -0.618231 0.546804 -v 0.083120 0.021725 0.260996 -vn 0.629933 -0.618195 0.470127 -v 0.083890 0.021725 0.260091 -vn 0.684889 -0.618180 0.385720 -v 0.084539 0.021725 0.259096 -vn 0.728583 -0.618188 0.294975 -v 0.085054 0.021725 0.258025 -vn 0.760330 -0.618180 0.199378 -v 0.085429 0.021725 0.256897 -vn 0.779563 -0.618207 0.100507 -v 0.085656 0.021725 0.255731 -vn 0.786023 -0.618197 -0.000001 -v 0.085732 0.021725 0.254545 -vn 0.438085 -0.897157 -0.056484 -v 0.085587 0.021669 0.253368 -vn 0.427277 -0.897151 -0.112050 -v 0.085361 0.021669 0.252210 -vn 0.409424 -0.897160 -0.165756 -v 0.084990 0.021669 0.251091 -vn 0.384886 -0.897148 -0.216768 -v 0.084478 0.021669 0.250029 -vn 0.353980 -0.897166 -0.264180 -v 0.083835 0.021669 0.249040 -vn 0.317285 -0.897171 -0.307269 -v 0.083070 0.021669 0.248142 -vn 0.275393 -0.897166 -0.345329 -v 0.082197 0.021669 0.247349 -vn 0.228983 -0.897153 -0.377733 -v 0.081230 0.021669 0.246675 -vn 0.178784 -0.897179 -0.403864 -v 0.080184 0.021669 0.246129 -vn 0.125675 -0.897166 -0.423437 -v 0.079077 0.021669 0.245722 -vn 0.070504 -0.897135 -0.436095 -v 0.077928 0.021669 0.245459 -vn 0.014158 -0.897148 -0.441504 -v 0.076754 0.021669 0.245346 -vn -0.042413 -0.897162 -0.439661 -v 0.075575 0.021669 0.245384 -vn -0.098303 -0.897130 -0.430691 -v 0.074411 0.021669 0.245572 -vn -0.152537 -0.897173 -0.414503 -v 0.073280 0.021669 0.245908 -vn -0.204327 -0.897138 -0.391656 -v 0.072202 0.021669 0.246385 -vn -0.252722 -0.897145 -0.362300 -v 0.071193 0.021669 0.246996 -vn -0.296978 -0.897145 -0.327010 -v 0.070271 0.021669 0.247732 -vn -0.336362 -0.897142 -0.286351 -v 0.069451 0.021669 0.248579 -vn -0.370222 -0.897140 -0.240988 -v 0.068745 0.021669 0.249524 -vn -0.397965 -0.897159 -0.191649 -v 0.068167 0.021669 0.250552 -vn -0.419211 -0.897155 -0.139191 -v 0.067724 0.021669 0.251645 -vn -0.433572 -0.897154 -0.084436 -v 0.067425 0.021669 0.252786 -vn -0.440793 -0.897163 -0.028299 -v 0.067274 0.021669 0.253955 -vn -0.440799 -0.897160 0.028303 -v 0.067274 0.021669 0.255135 -vn -0.433572 -0.897154 0.084436 -v 0.067425 0.021669 0.256304 -vn -0.419212 -0.897155 0.139191 -v 0.067724 0.021669 0.257445 -vn -0.397965 -0.897160 0.191646 -v 0.068167 0.021669 0.258538 -vn -0.370220 -0.897141 0.240989 -v 0.068745 0.021669 0.259566 -vn -0.336361 -0.897141 0.286355 -v 0.069451 0.021669 0.260511 -vn -0.296950 -0.897169 0.326970 -v 0.070271 0.021669 0.261358 -vn -0.252724 -0.897146 0.362299 -v 0.071193 0.021669 0.262094 -vn -0.204325 -0.897137 0.391659 -v 0.072202 0.021669 0.262705 -vn -0.152540 -0.897173 0.414503 -v 0.073280 0.021669 0.263182 -vn -0.098285 -0.897162 0.430629 -v 0.074411 0.021669 0.263518 -vn -0.042417 -0.897177 0.439631 -v 0.075575 0.021669 0.263706 -vn 0.014158 -0.897149 0.441501 -v 0.076754 0.021669 0.263744 -vn 0.070508 -0.897134 0.436095 -v 0.077928 0.021669 0.263631 -vn 0.125674 -0.897165 0.423439 -v 0.079077 0.021669 0.263368 -vn 0.178817 -0.897137 0.403943 -v 0.080184 0.021669 0.262961 -vn 0.228984 -0.897152 0.377735 -v 0.081230 0.021669 0.262415 -vn 0.275393 -0.897165 0.345330 -v 0.082197 0.021669 0.261741 -vn 0.317284 -0.897171 0.307269 -v 0.083070 0.021669 0.260948 -vn 0.354022 -0.897139 0.264214 -v 0.083835 0.021669 0.260050 -vn 0.384887 -0.897147 0.216768 -v 0.084478 0.021669 0.259061 -vn 0.409424 -0.897160 0.165758 -v 0.084990 0.021669 0.257999 -vn 0.427276 -0.897151 0.112048 -v 0.085361 0.021669 0.256880 -vn 0.438097 -0.897151 0.056489 -v 0.085587 0.021669 0.255722 -vn 0.441708 -0.897159 0.000000 -v 0.085662 0.021669 0.254545 -vn 0.115662 -0.993177 -0.014913 -v 0.085501 0.021649 0.253379 -vn 0.112796 -0.993178 -0.029577 -v 0.085277 0.021649 0.252233 -vn 0.108101 -0.993176 -0.043766 -v 0.084909 0.021649 0.251124 -vn 0.101601 -0.993178 -0.057219 -v 0.084402 0.021649 0.250071 -vn 0.093454 -0.993178 -0.069746 -v 0.083765 0.021649 0.249092 -vn 0.083772 -0.993177 -0.081129 -v 0.083008 0.021649 0.248203 -vn 0.072713 -0.993176 -0.091179 -v 0.082143 0.021649 0.247417 -vn 0.060453 -0.993177 -0.099724 -v 0.081185 0.021649 0.246749 -vn 0.047200 -0.993178 -0.106626 -v 0.080149 0.021649 0.246209 -vn 0.033179 -0.993178 -0.111788 -v 0.079053 0.021649 0.245805 -vn 0.018612 -0.993177 -0.115119 -v 0.077914 0.021649 0.245545 -vn 0.003738 -0.993178 -0.116548 -v 0.076751 0.021649 0.245433 -vn -0.011203 -0.993173 -0.116108 -v 0.075583 0.021649 0.245470 -vn -0.025943 -0.993180 -0.113666 -v 0.074430 0.021649 0.245657 -vn -0.040275 -0.993177 -0.109438 -v 0.073310 0.021649 0.245989 -vn -0.053933 -0.993178 -0.103382 -v 0.072242 0.021649 0.246462 -vn -0.066722 -0.993177 -0.095649 -v 0.071243 0.021649 0.247068 -vn -0.078384 -0.993180 -0.086309 -v 0.070330 0.021649 0.247796 -vn -0.088789 -0.993178 -0.075587 -v 0.069517 0.021649 0.248635 -vn -0.097725 -0.993178 -0.063611 -v 0.068818 0.021649 0.249572 -vn -0.105068 -0.993177 -0.050598 -v 0.068245 0.021649 0.250589 -vn -0.110681 -0.993176 -0.036748 -v 0.067806 0.021649 0.251672 -vn -0.114469 -0.993177 -0.022293 -v 0.067510 0.021649 0.252802 -vn -0.116378 -0.993177 -0.007471 -v 0.067361 0.021649 0.253961 -vn -0.116378 -0.993177 0.007471 -v 0.067361 0.021649 0.255129 -vn -0.114469 -0.993177 0.022293 -v 0.067510 0.021649 0.256288 -vn -0.110681 -0.993176 0.036748 -v 0.067806 0.021649 0.257418 -vn -0.105069 -0.993177 0.050598 -v 0.068245 0.021649 0.258501 -vn -0.097726 -0.993178 0.063610 -v 0.068818 0.021649 0.259519 -vn -0.088789 -0.993178 0.075588 -v 0.069517 0.021649 0.260455 -vn -0.078402 -0.993177 0.086329 -v 0.070330 0.021649 0.261294 -vn -0.066721 -0.993176 0.095649 -v 0.071243 0.021649 0.262022 -vn -0.053934 -0.993178 0.103382 -v 0.072242 0.021649 0.262628 -vn -0.040274 -0.993177 0.109439 -v 0.073310 0.021649 0.263101 -vn -0.025951 -0.993176 0.113701 -v 0.074430 0.021649 0.263433 -vn -0.011198 -0.993178 0.116070 -v 0.075583 0.021649 0.263620 -vn 0.003736 -0.993178 0.116549 -v 0.076751 0.021649 0.263657 -vn 0.018612 -0.993177 0.115119 -v 0.077914 0.021649 0.263545 -vn 0.033179 -0.993178 0.111788 -v 0.079053 0.021649 0.263285 -vn 0.047200 -0.993178 0.106626 -v 0.080149 0.021649 0.262881 -vn 0.060453 -0.993177 0.099723 -v 0.081185 0.021649 0.262341 -vn 0.072713 -0.993176 0.091179 -v 0.082143 0.021649 0.261673 -vn 0.083772 -0.993177 0.081129 -v 0.083008 0.021649 0.260887 -vn 0.093455 -0.993178 0.069747 -v 0.083765 0.021649 0.259998 -vn 0.101600 -0.993178 0.057220 -v 0.084402 0.021649 0.259019 -vn 0.108102 -0.993176 0.043765 -v 0.084909 0.021649 0.257966 -vn 0.112796 -0.993178 0.029578 -v 0.085277 0.021649 0.256858 -vn 0.115662 -0.993177 0.014912 -v 0.085501 0.021649 0.255711 -vn 0.116618 -0.993177 -0.000000 -v 0.085575 0.021649 0.254545 -vn 0.053496 -0.998552 -0.005623 -v 0.068147 0.021649 0.255419 -vn 0.052615 -0.998552 -0.011184 -v 0.068283 0.021649 0.256283 -vn 0.051158 -0.998552 -0.016622 -v 0.068510 0.021649 0.257128 -vn 0.049141 -0.998552 -0.021879 -v 0.068823 0.021649 0.257944 -vn 0.046584 -0.998552 -0.026894 -v 0.069221 0.021649 0.258724 -vn 0.043517 -0.998552 -0.031618 -v 0.069697 0.021649 0.259458 -vn 0.039975 -0.998552 -0.035994 -v 0.070248 0.021649 0.260138 -vn 0.035994 -0.998552 -0.039975 -v 0.070866 0.021649 0.260756 -vn 0.031617 -0.998552 -0.043517 -v 0.071546 0.021649 0.261307 -vn 0.026896 -0.998552 -0.046585 -v 0.072280 0.021649 0.261783 -vn 0.021879 -0.998552 -0.049141 -v 0.073059 0.021649 0.262180 -vn 0.016622 -0.998552 -0.051157 -v 0.073876 0.021649 0.262494 -vn 0.011184 -0.998552 -0.052617 -v 0.074721 0.021649 0.262720 -vn 0.005623 -0.998552 -0.053498 -v 0.075585 0.021649 0.262857 -vn 0.000001 -0.998552 -0.053789 -v 0.076459 0.021649 0.262903 -vn -0.005623 -0.998552 -0.053498 -v 0.077332 0.021649 0.262857 -vn -0.011184 -0.998552 -0.052617 -v 0.078196 0.021649 0.262720 -vn -0.016621 -0.998552 -0.051157 -v 0.079041 0.021649 0.262494 -vn -0.021880 -0.998552 -0.049141 -v 0.079858 0.021649 0.262180 -vn -0.026896 -0.998552 -0.046585 -v 0.080638 0.021649 0.261783 -vn -0.031617 -0.998552 -0.043517 -v 0.081371 0.021649 0.261307 -vn -0.035994 -0.998552 -0.039975 -v 0.082051 0.021649 0.260756 -vn -0.039974 -0.998552 -0.035994 -v 0.082670 0.021649 0.260138 -vn -0.043517 -0.998552 -0.031617 -v 0.083220 0.021649 0.259458 -vn -0.046583 -0.998552 -0.026895 -v 0.083697 0.021649 0.258724 -vn -0.049142 -0.998552 -0.021879 -v 0.084094 0.021649 0.257944 -vn -0.005623 -0.998552 0.053495 -v 0.077332 0.021649 0.246233 -vn -0.000000 -0.998552 0.053790 -v 0.076459 0.021649 0.246187 -vn 0.005623 -0.998552 0.053495 -v 0.075585 0.021649 0.246233 -vn 0.011185 -0.998552 0.052618 -v 0.074721 0.021649 0.246370 -vn 0.016622 -0.998552 0.051159 -v 0.073876 0.021649 0.246596 -vn 0.021880 -0.998552 0.049141 -v 0.073059 0.021649 0.246910 -vn 0.026896 -0.998552 0.046585 -v 0.072280 0.021649 0.247307 -vn 0.031617 -0.998552 0.043518 -v 0.071546 0.021649 0.247783 -vn 0.035994 -0.998552 0.039974 -v 0.070866 0.021649 0.248334 -vn 0.039975 -0.998552 0.035994 -v 0.070248 0.021649 0.248953 -vn 0.043517 -0.998552 0.031617 -v 0.069697 0.021649 0.249632 -vn 0.046583 -0.998552 0.026895 -v 0.069221 0.021649 0.250366 -vn 0.049140 -0.998552 0.021879 -v 0.068823 0.021649 0.251146 -vn 0.051158 -0.998552 0.016622 -v 0.068510 0.021649 0.251962 -vn 0.052615 -0.998552 0.011184 -v 0.068283 0.021649 0.252807 -vn 0.053496 -0.998552 0.005623 -v 0.068147 0.021649 0.253671 -vn 0.053791 -0.998552 -0.000000 -v 0.068101 0.021649 0.254545 -vn -0.051157 -0.998552 -0.016622 -v 0.084408 0.021649 0.257128 -vn -0.052615 -0.998552 -0.011184 -v 0.084634 0.021649 0.256283 -vn -0.053496 -0.998552 -0.005623 -v 0.084771 0.021649 0.255419 -vn -0.053791 -0.998552 0.000000 -v 0.084817 0.021649 0.254545 -vn -0.053496 -0.998552 0.005623 -v 0.084771 0.021649 0.253671 -vn -0.031617 -0.998552 0.043517 -v 0.081371 0.021649 0.247783 -vn -0.026896 -0.998552 0.046585 -v 0.080638 0.021649 0.247307 -vn -0.021880 -0.998552 0.049141 -v 0.079858 0.021649 0.246910 -vn -0.016622 -0.998552 0.051159 -v 0.079041 0.021649 0.246596 -vn -0.011184 -0.998552 0.052617 -v 0.078196 0.021649 0.246370 -vn -0.052615 -0.998552 0.011184 -v 0.084634 0.021649 0.252807 -vn -0.051158 -0.998552 0.016622 -v 0.084408 0.021649 0.251962 -vn -0.049140 -0.998552 0.021879 -v 0.084094 0.021649 0.251146 -vn -0.046584 -0.998552 0.026895 -v 0.083697 0.021649 0.250366 -vn -0.043517 -0.998552 0.031618 -v 0.083220 0.021649 0.249632 -vn -0.039975 -0.998552 0.035994 -v 0.082670 0.021649 0.248953 -vn -0.035994 -0.998552 0.039975 -v 0.082051 0.021649 0.248334 -vn -0.216121 -0.976102 0.022715 -v 0.084112 0.021723 0.253741 -vn -0.212562 -0.976103 0.045181 -v 0.083986 0.021723 0.252945 -vn -0.206675 -0.976103 0.067152 -v 0.083777 0.021723 0.252167 -vn -0.198522 -0.976103 0.088389 -v 0.083489 0.021723 0.251415 -vn -0.188198 -0.976102 0.108656 -v 0.083123 0.021723 0.250697 -vn -0.175807 -0.976103 0.127730 -v 0.082684 0.021723 0.250022 -vn -0.161495 -0.976102 0.145412 -v 0.082177 0.021723 0.249396 -vn -0.145410 -0.976103 0.161493 -v 0.081608 0.021723 0.248826 -vn -0.127732 -0.976103 0.175808 -v 0.080982 0.021723 0.248319 -vn -0.108657 -0.976102 0.188199 -v 0.080306 0.021723 0.247881 -vn -0.088390 -0.976103 0.198521 -v 0.079589 0.021723 0.247515 -vn -0.067152 -0.976103 0.206673 -v 0.078837 0.021723 0.247226 -vn -0.045180 -0.976102 0.212564 -v 0.078059 0.021723 0.247018 -vn -0.022715 -0.976102 0.216121 -v 0.077263 0.021723 0.246892 -vn 0.000001 -0.976101 0.217315 -v 0.076459 0.021723 0.246850 -vn 0.022713 -0.976103 0.216119 -v 0.075654 0.021723 0.246892 -vn 0.045182 -0.976102 0.212563 -v 0.074859 0.021723 0.247018 -vn 0.067151 -0.976103 0.206673 -v 0.074081 0.021723 0.247226 -vn 0.088390 -0.976102 0.198523 -v 0.073329 0.021723 0.247515 -vn 0.108659 -0.976102 0.188199 -v 0.072611 0.021723 0.247881 -vn 0.127730 -0.976103 0.175808 -v 0.071935 0.021723 0.248319 -vn 0.145410 -0.976102 0.161493 -v 0.071309 0.021723 0.248826 -vn 0.161497 -0.976102 0.145411 -v 0.070740 0.021723 0.249396 -vn 0.175806 -0.976103 0.127732 -v 0.070233 0.021723 0.250022 -vn 0.188198 -0.976102 0.108656 -v 0.069794 0.021723 0.250697 -vn 0.198522 -0.976103 0.088389 -v 0.069429 0.021723 0.251415 -vn 0.206675 -0.976102 0.067152 -v 0.069140 0.021723 0.252167 -vn 0.212562 -0.976102 0.045181 -v 0.068931 0.021723 0.252945 -vn 0.216122 -0.976102 0.022716 -v 0.068805 0.021723 0.253741 -vn 0.217311 -0.976102 0.000000 -v 0.068763 0.021723 0.254545 -vn 0.216122 -0.976102 -0.022716 -v 0.068805 0.021723 0.255349 -vn 0.212562 -0.976103 -0.045181 -v 0.068931 0.021723 0.256145 -vn 0.206675 -0.976102 -0.067152 -v 0.069140 0.021723 0.256923 -vn 0.198523 -0.976102 -0.088390 -v 0.069429 0.021723 0.257675 -vn 0.188198 -0.976102 -0.108656 -v 0.069794 0.021723 0.258393 -vn 0.175807 -0.976103 -0.127730 -v 0.070233 0.021723 0.259068 -vn 0.161495 -0.976102 -0.145413 -v 0.070740 0.021723 0.259694 -vn 0.145409 -0.976103 -0.161492 -v 0.071309 0.021723 0.260264 -vn 0.127732 -0.976103 -0.175808 -v 0.071935 0.021723 0.260771 -vn 0.108657 -0.976102 -0.188199 -v 0.072611 0.021723 0.261209 -vn 0.088388 -0.976103 -0.198522 -v 0.073329 0.021723 0.261575 -vn 0.067154 -0.976102 -0.206678 -v 0.074081 0.021723 0.261864 -vn 0.045183 -0.976102 -0.212562 -v 0.074859 0.021723 0.262072 -vn 0.022714 -0.976102 -0.216123 -v 0.075654 0.021723 0.262198 -vn -0.000000 -0.976101 -0.217316 -v 0.076459 0.021723 0.262240 -vn -0.022714 -0.976102 -0.216121 -v 0.077263 0.021723 0.262198 -vn -0.045184 -0.976102 -0.212563 -v 0.078059 0.021723 0.262072 -vn -0.067154 -0.976102 -0.206678 -v 0.078837 0.021723 0.261864 -vn -0.088386 -0.976103 -0.198523 -v 0.079589 0.021723 0.261575 -vn -0.108659 -0.976102 -0.188199 -v 0.080306 0.021723 0.261209 -vn -0.127730 -0.976103 -0.175808 -v 0.080982 0.021723 0.260771 -vn -0.145410 -0.976102 -0.161493 -v 0.081608 0.021723 0.260264 -vn -0.161496 -0.976102 -0.145411 -v 0.082177 0.021723 0.259694 -vn -0.175806 -0.976103 -0.127732 -v 0.082684 0.021723 0.259068 -vn -0.188198 -0.976102 -0.108655 -v 0.083123 0.021723 0.258393 -vn -0.198522 -0.976103 -0.088389 -v 0.083489 0.021723 0.257675 -vn -0.206675 -0.976102 -0.067152 -v 0.083777 0.021723 0.256923 -vn -0.212562 -0.976103 -0.045181 -v 0.083986 0.021723 0.256145 -vn -0.216121 -0.976102 -0.022715 -v 0.084112 0.021723 0.255349 -vn -0.217311 -0.976102 0.000000 -v 0.084154 0.021723 0.254545 -vn -0.376286 -0.925667 0.039362 -v 0.083486 0.021942 0.253807 -vn -0.370256 -0.925574 0.078884 -v 0.083370 0.021942 0.253076 -vn -0.360014 -0.925609 0.116780 -v 0.083178 0.021942 0.252362 -vn -0.345751 -0.925580 0.154136 -v 0.082913 0.021942 0.251671 -vn -0.327623 -0.925680 0.189153 -v 0.082578 0.021942 0.251012 -vn -0.306056 -0.925681 0.222360 -v 0.082175 0.021942 0.250392 -vn -0.280494 -0.925899 0.253051 -v 0.081709 0.021942 0.249817 -vn -0.253411 -0.925753 0.280651 -v 0.081186 0.021942 0.249294 -vn -0.222233 -0.925667 0.306190 -v 0.080612 0.021942 0.248829 -vn -0.189154 -0.925680 0.327623 -v 0.079991 0.021942 0.248426 -vn -0.154053 -0.925668 0.345553 -v 0.079333 0.021942 0.248090 -vn -0.116811 -0.925576 0.360090 -v 0.078642 0.021942 0.247825 -vn -0.078873 -0.925610 0.370170 -v 0.077928 0.021942 0.247634 -vn -0.039391 -0.925580 0.376497 -v 0.077197 0.021942 0.247518 -vn 0.000001 -0.925680 0.378308 -v 0.076459 0.021942 0.247479 -vn 0.039544 -0.925681 0.376233 -v 0.075720 0.021942 0.247518 -vn 0.078900 -0.925899 0.369439 -v 0.074990 0.021942 0.247634 -vn 0.116345 -0.925754 0.359783 -v 0.074275 0.021942 0.247825 -vn 0.154051 -0.925668 0.345552 -v 0.073585 0.021942 0.248090 -vn 0.189155 -0.925681 0.327622 -v 0.072926 0.021942 0.248426 -vn 0.222232 -0.925667 0.306192 -v 0.072306 0.021942 0.248829 -vn 0.253442 -0.925574 0.281210 -v 0.071731 0.021942 0.249294 -vn 0.281144 -0.925608 0.253391 -v 0.071208 0.021942 0.249817 -vn 0.306361 -0.925580 0.222361 -v 0.070743 0.021942 0.250392 -vn 0.327623 -0.925680 0.189154 -v 0.070340 0.021942 0.251012 -vn 0.345599 -0.925681 0.153872 -v 0.070004 0.021942 0.251671 -vn 0.359395 -0.925899 0.116390 -v 0.069739 0.021942 0.252362 -vn 0.369757 -0.925753 0.079135 -v 0.069548 0.021942 0.253076 -vn 0.376286 -0.925667 0.039364 -v 0.069432 0.021942 0.253807 -vn 0.378305 -0.925681 0.000001 -v 0.069393 0.021942 0.254545 -vn 0.376286 -0.925667 -0.039364 -v 0.069432 0.021942 0.255284 -vn 0.370257 -0.925574 -0.078885 -v 0.069548 0.021942 0.256014 -vn 0.360015 -0.925609 -0.116779 -v 0.069739 0.021942 0.256728 -vn 0.345751 -0.925580 -0.154136 -v 0.070004 0.021942 0.257419 -vn 0.327623 -0.925680 -0.189154 -v 0.070340 0.021942 0.258078 -vn 0.306057 -0.925681 -0.222359 -v 0.070743 0.021942 0.258698 -vn 0.280494 -0.925899 -0.253051 -v 0.071208 0.021942 0.259273 -vn 0.253411 -0.925753 -0.280652 -v 0.071731 0.021942 0.259796 -vn 0.222233 -0.925667 -0.306190 -v 0.072306 0.021942 0.260261 -vn 0.189154 -0.925680 -0.327623 -v 0.072926 0.021942 0.260664 -vn 0.154053 -0.925668 -0.345553 -v 0.073585 0.021942 0.261000 -vn 0.116811 -0.925574 -0.360095 -v 0.074275 0.021942 0.261265 -vn 0.078874 -0.925610 -0.370170 -v 0.074990 0.021942 0.261456 -vn 0.039392 -0.925581 -0.376496 -v 0.075720 0.021942 0.261572 -vn -0.000001 -0.925680 -0.378308 -v 0.076459 0.021942 0.261611 -vn -0.039544 -0.925681 -0.376233 -v 0.077197 0.021942 0.261572 -vn -0.078901 -0.925900 -0.369438 -v 0.077928 0.021942 0.261456 -vn -0.116347 -0.925752 -0.359787 -v 0.078642 0.021942 0.261265 -vn -0.154050 -0.925668 -0.345554 -v 0.079333 0.021942 0.261000 -vn -0.189155 -0.925681 -0.327622 -v 0.079991 0.021942 0.260664 -vn -0.222232 -0.925667 -0.306192 -v 0.080612 0.021942 0.260261 -vn -0.253443 -0.925574 -0.281209 -v 0.081186 0.021942 0.259796 -vn -0.281143 -0.925609 -0.253391 -v 0.081709 0.021942 0.259273 -vn -0.306360 -0.925580 -0.222361 -v 0.082175 0.021942 0.258698 -vn -0.327623 -0.925681 -0.189152 -v 0.082578 0.021942 0.258078 -vn -0.345598 -0.925681 -0.153872 -v 0.082913 0.021942 0.257419 -vn -0.359394 -0.925899 -0.116391 -v 0.083178 0.021942 0.256728 -vn -0.369757 -0.925753 -0.079134 -v 0.083370 0.021942 0.256014 -vn -0.376286 -0.925667 -0.039362 -v 0.083486 0.021942 0.255284 -vn -0.378305 -0.925681 0.000000 -v 0.083524 0.021942 0.254545 -vn 0.526407 -0.850233 0.000000 -v 0.071364 0.022882 0.254545 -vn 0.524103 -0.848386 -0.074554 -v 0.071441 0.022882 0.255430 -vn 0.482349 -0.867211 -0.123632 -v 0.071475 0.022882 0.255604 -vn 0.500084 -0.849098 -0.170146 -v 0.071671 0.022882 0.256288 -vn 0.421461 -0.884180 -0.201484 -v 0.071804 0.022882 0.256617 -vn 0.458855 -0.849797 -0.259418 -v 0.072046 0.022882 0.257093 -vn 0.401386 -0.870515 -0.284766 -v 0.072337 0.022882 0.257540 -vn 0.400746 -0.847636 -0.347729 -v 0.072556 0.022882 0.257820 -vn 0.351222 -0.862788 -0.363647 -v 0.073049 0.022882 0.258331 -vn 0.326613 -0.848387 -0.416609 -v 0.073184 0.022882 0.258448 -vn 0.263206 -0.850226 -0.455893 -v 0.073911 0.022882 0.258958 -vn 0.197499 -0.848373 -0.491179 -v 0.074716 0.022882 0.259333 -vn 0.134105 -0.867217 -0.479532 -v 0.074884 0.022882 0.259391 -vn 0.102697 -0.849089 -0.518172 -v 0.075574 0.022882 0.259563 -vn 0.036250 -0.884178 -0.465741 -v 0.075926 0.022882 0.259612 -vn 0.004769 -0.849784 -0.527109 -v 0.076459 0.022882 0.259640 -vn -0.045929 -0.870504 -0.490013 -v 0.076991 0.022882 0.259612 -vn -0.100772 -0.847631 -0.520928 -v 0.077343 0.022882 0.259563 -vn -0.139323 -0.862781 -0.486002 -v 0.078033 0.022882 0.259391 -vn -0.197496 -0.848374 -0.491180 -v 0.078201 0.022882 0.259333 -vn -0.263208 -0.850226 -0.455892 -v 0.079006 0.022882 0.258958 -vn -0.326611 -0.848388 -0.416609 -v 0.079734 0.022882 0.258448 -vn -0.348232 -0.867223 -0.355892 -v 0.079868 0.022882 0.258331 -vn -0.397400 -0.849091 -0.348020 -v 0.080362 0.022882 0.257820 -vn -0.385209 -0.884186 -0.264253 -v 0.080581 0.022882 0.257540 -vn -0.454086 -0.849798 -0.267675 -v 0.080871 0.022882 0.257093 -vn -0.447307 -0.870515 -0.205231 -v 0.081113 0.022882 0.256617 -vn -0.501486 -0.847655 -0.173183 -v 0.081247 0.022882 0.256288 -vn -0.490550 -0.862782 -0.122346 -v 0.081442 0.022882 0.255604 -vn -0.524103 -0.848386 -0.074553 -v 0.081476 0.022882 0.255430 -vn -0.526388 -0.850245 0.000000 -v 0.081554 0.022882 0.254545 -vn -0.524103 -0.848385 0.074554 -v 0.081476 0.022882 0.253660 -vn -0.482349 -0.867211 0.123632 -v 0.081442 0.022882 0.253486 -vn -0.500065 -0.849109 0.170142 -v 0.081247 0.022882 0.252802 -vn -0.421450 -0.884187 0.201478 -v 0.081113 0.022882 0.252473 -vn -0.458855 -0.849797 0.259416 -v 0.080871 0.022882 0.251997 -vn -0.401387 -0.870515 0.284767 -v 0.080581 0.022882 0.251550 -vn -0.400747 -0.847636 0.347729 -v 0.080362 0.022882 0.251270 -vn -0.351222 -0.862788 0.363647 -v 0.079868 0.022882 0.250759 -vn -0.326613 -0.848387 0.416609 -v 0.079734 0.022882 0.250642 -vn -0.263206 -0.850226 0.455893 -v 0.079006 0.022882 0.250133 -vn -0.197496 -0.848374 0.491179 -v 0.078201 0.022882 0.249757 -vn -0.134119 -0.867206 0.479547 -v 0.078033 0.022882 0.249699 -vn -0.102665 -0.849137 0.518099 -v 0.077343 0.022882 0.249527 -vn -0.036238 -0.884180 0.465738 -v 0.076991 0.022882 0.249478 -vn -0.004769 -0.849784 0.527109 -v 0.076459 0.022882 0.249450 -vn 0.045919 -0.870507 0.490010 -v 0.075926 0.022882 0.249478 -vn 0.100742 -0.847686 0.520845 -v 0.075574 0.022882 0.249527 -vn 0.139329 -0.862785 0.485994 -v 0.074884 0.022882 0.249699 -vn 0.197499 -0.848373 0.491179 -v 0.074716 0.022882 0.249757 -vn 0.263207 -0.850226 0.455892 -v 0.073911 0.022882 0.250133 -vn 0.326611 -0.848388 0.416609 -v 0.073184 0.022882 0.250642 -vn 0.348231 -0.867223 0.355892 -v 0.073049 0.022882 0.250759 -vn 0.397400 -0.849091 0.348020 -v 0.072556 0.022882 0.251270 -vn 0.385209 -0.884186 0.264253 -v 0.072337 0.022882 0.251550 -vn 0.454085 -0.849798 0.267675 -v 0.072046 0.022882 0.251997 -vn 0.447314 -0.870510 0.205236 -v 0.071804 0.022882 0.252473 -vn 0.501504 -0.847643 0.173190 -v 0.071671 0.022882 0.252802 -vn 0.490554 -0.862780 0.122345 -v 0.071475 0.022882 0.253486 -vn 0.524103 -0.848385 0.074555 -v 0.071441 0.022882 0.253660 -vn 0.078559 0.625265 0.776448 -v 0.075742 0.023198 0.249563 -vn 0.166992 0.586978 0.792194 -v 0.075585 0.023198 0.249588 -vn 0.176492 0.282516 0.942887 -v 0.075592 0.023117 0.249632 -vn 0.632932 0.625452 -0.456296 -v 0.072502 0.023198 0.257657 -vn 0.602542 0.587047 -0.540666 -v 0.072603 0.023198 0.257781 -vn 0.728277 0.282615 -0.624293 -v 0.072637 0.023117 0.257752 -vn -0.711737 0.625147 -0.320346 -v 0.081132 0.023198 0.256416 -vn -0.769295 0.587248 -0.251644 -v 0.081189 0.023198 0.256267 -vn -0.904792 0.282577 -0.318595 -v 0.081147 0.023117 0.256251 -vn -0.630611 -0.193791 0.751515 -v 0.079663 0.023025 0.250726 -vn -0.496021 -0.623757 0.604061 -v 0.079688 0.022940 0.250697 -vn -0.595505 -0.624059 0.505890 -v 0.080307 0.022940 0.251316 -vn 0.170362 -0.193724 0.966151 -v 0.075593 0.023025 0.249636 -vn 0.140365 -0.624027 0.768692 -v 0.075586 0.022940 0.249598 -vn -0.005373 -0.621320 0.783539 -v 0.076459 0.022940 0.249522 -vn 0.966144 -0.193767 0.170352 -v 0.071549 0.023025 0.253679 -vn 0.771173 -0.623718 0.127548 -v 0.071512 0.022940 0.253673 -vn 0.735872 -0.624050 0.262782 -v 0.071738 0.022940 0.252827 -vn 0.751538 -0.193710 -0.630609 -v 0.072640 0.023025 0.257749 -vn 0.595505 -0.624059 -0.505890 -v 0.072611 0.022940 0.257774 -vn 0.681242 -0.621329 -0.387116 -v 0.072109 0.022940 0.257057 -vn -0.335541 -0.193729 -0.921890 -v 0.078164 0.023025 0.259229 -vn -0.275135 -0.623702 -0.731640 -v 0.078177 0.022940 0.259265 -vn -0.140382 -0.623954 -0.768749 -v 0.077331 0.022940 0.259492 -vn -0.737694 -0.622617 0.261067 -v 0.081179 0.022940 0.252827 -vn -0.681243 -0.621330 0.387113 -v 0.080809 0.022940 0.252033 -vn -0.274515 -0.623618 0.731944 -v 0.078177 0.022940 0.249825 -vn 0.594922 -0.622630 0.508330 -v 0.072611 0.022940 0.251316 -vn 0.675876 -0.621329 0.396410 -v 0.072109 0.022940 0.252033 -vn 0.771123 -0.623638 -0.128238 -v 0.071512 0.022940 0.255417 -vn 0.142772 -0.622531 -0.769462 -v 0.075586 0.022940 0.259492 -vn 0.005373 -0.621320 -0.783539 -v 0.076459 0.022940 0.259568 -vn -0.496595 -0.623676 -0.603673 -v 0.079688 0.022940 0.258393 -vn -0.785728 -0.618572 0.000002 -v 0.081482 0.022940 0.254545 -vn -0.771173 -0.623718 -0.127548 -v 0.081406 0.022940 0.255417 -vn -0.735878 -0.624042 -0.262784 -v 0.081179 0.022940 0.256263 -vn -0.675876 -0.621329 -0.396410 -v 0.080809 0.022940 0.257057 -vn -0.594922 -0.622630 -0.508330 -v 0.080307 0.022940 0.257774 -vn 0.274515 -0.623609 -0.731951 -v 0.074741 0.022940 0.259265 -vn 0.737690 -0.622624 -0.261061 -v 0.071738 0.022940 0.256263 -vn 0.496595 -0.623676 0.603673 -v 0.073230 0.022940 0.250697 -vn -0.142751 -0.622601 0.769409 -v 0.077331 0.022940 0.249598 -vn -0.771123 -0.623639 0.128237 -v 0.081406 0.022940 0.253673 -vn -0.392842 -0.618615 -0.680435 -v 0.078970 0.022940 0.258895 -vn -0.490528 -0.193748 -0.849614 -v 0.078951 0.023025 0.258862 -vn -0.479304 0.284725 -0.830180 -v 0.078953 0.023117 0.258865 -vn 0.496022 -0.623757 -0.604060 -v 0.073230 0.022940 0.258393 -vn 0.630612 -0.193792 -0.751514 -v 0.073254 0.023025 0.258364 -vn 0.610974 0.281809 -0.739794 -v 0.073252 0.023117 0.258367 -vn 0.785722 -0.618579 0.000000 -v 0.071436 0.022940 0.254545 -vn 0.981051 -0.193749 0.000001 -v 0.071474 0.023025 0.254545 -vn 0.958623 0.284678 0.000001 -v 0.071470 0.023117 0.254545 -vn 0.275137 -0.623694 0.731646 -v 0.074741 0.022940 0.249825 -vn 0.335544 -0.193717 0.921892 -v 0.074754 0.023025 0.249861 -vn 0.335226 0.281755 0.899020 -v 0.074752 0.023117 0.249857 -vn -0.392843 -0.618614 0.680435 -v 0.078970 0.022940 0.250195 -vn -0.490527 -0.193750 0.849614 -v 0.078951 0.023025 0.250228 -vn -0.479300 0.284725 0.830183 -v 0.078953 0.023117 0.250225 -vn -0.921888 -0.193737 -0.335541 -v 0.081143 0.023025 0.256250 -vn -0.966144 -0.193765 -0.170352 -v 0.081368 0.023025 0.255411 -vn -0.981058 -0.193713 0.000004 -v 0.081444 0.023025 0.254545 -vn -0.966145 -0.193767 0.170349 -v 0.081368 0.023025 0.253679 -vn -0.751540 -0.193713 -0.630605 -v 0.080277 0.023025 0.257749 -vn -0.741366 0.281257 -0.609320 -v 0.080280 0.023117 0.257752 -vn -0.836009 0.282037 -0.470684 -v 0.080779 0.023117 0.257039 -vn 0.335542 -0.193727 -0.921890 -v 0.074754 0.023025 0.259229 -vn 0.336017 0.282021 -0.898642 -v 0.074752 0.023117 0.259233 -vn 0.175683 0.283781 -0.942658 -v 0.075592 0.023117 0.259458 -vn 0.480857 0.274032 -0.832876 -v 0.073964 0.023117 0.258865 -vn 0.490532 -0.193751 -0.849611 -v 0.073966 0.023025 0.258862 -vn 0.392847 -0.618600 -0.680445 -v 0.073947 0.022940 0.258895 -vn 0.921882 -0.193773 -0.335538 -v 0.071774 0.023025 0.256250 -vn 0.898377 0.281223 -0.337391 -v 0.071771 0.023117 0.256251 -vn 0.825625 0.282058 -0.488658 -v 0.072138 0.023117 0.257039 -vn 0.630607 -0.193791 0.751518 -v 0.073254 0.023025 0.250726 -vn 0.610247 0.282073 0.740292 -v 0.073252 0.023117 0.250723 -vn 0.728493 0.283879 0.623467 -v 0.072637 0.023117 0.251338 -vn 0.480856 0.274035 0.832876 -v 0.073964 0.023117 0.250225 -vn 0.490533 -0.193749 0.849611 -v 0.073966 0.023025 0.250228 -vn 0.392847 -0.618601 0.680444 -v 0.073947 0.022940 0.250195 -vn -0.170359 -0.193728 0.966151 -v 0.077324 0.023025 0.249636 -vn -0.157006 0.281160 0.946730 -v 0.077325 0.023117 0.249632 -vn 0.010381 0.282027 0.959350 -v 0.076459 0.023117 0.249556 -vn -0.946185 0.281751 -0.159217 -v 0.081372 0.023117 0.255411 -vn -0.961728 0.274005 0.000001 -v 0.081447 0.023117 0.254545 -vn -0.946253 0.282014 0.158344 -v 0.081372 0.023117 0.253679 -vn -0.904190 0.283836 0.319182 -v 0.081147 0.023117 0.252839 -vn -0.849616 -0.193720 -0.490536 -v 0.080776 0.023025 0.257038 -vn -0.774897 0.604107 -0.185981 -v 0.081401 0.023198 0.255498 -vn -0.711488 0.587726 -0.385179 -v 0.080818 0.023198 0.257062 -vn -0.442348 0.639446 -0.628838 -v 0.079379 0.023198 0.258645 -vn -0.528523 0.589688 -0.610681 -v 0.079694 0.023198 0.258401 -vn -0.624223 0.280402 -0.729192 -v 0.079665 0.023117 0.258367 -vn -0.630606 -0.193792 -0.751519 -v 0.079663 0.023025 0.258364 -vn -0.526056 0.664082 -0.531281 -v 0.080102 0.023198 0.258019 -vn -0.630133 0.588749 -0.506268 -v 0.080315 0.023198 0.257781 -vn -0.627232 0.645552 -0.435709 -v 0.080693 0.023198 0.257266 -vn -0.405556 0.585532 -0.701909 -v 0.078976 0.023198 0.258904 -vn -0.325201 0.284657 -0.901784 -v 0.078165 0.023117 0.259233 -vn -0.270978 0.585942 -0.763703 -v 0.078180 0.023198 0.259275 -vn -0.323140 0.639834 -0.697276 -v 0.078550 0.023198 0.259124 -vn -0.170363 -0.193723 -0.966151 -v 0.077324 0.023025 0.259454 -vn -0.161024 0.284478 -0.945063 -v 0.077325 0.023117 0.259458 -vn -0.128352 0.586214 -0.799924 -v 0.077333 0.023198 0.259502 -vn -0.194090 0.636031 -0.746856 -v 0.077645 0.023198 0.259437 -vn 0.000004 -0.193788 -0.981043 -v 0.076459 0.023025 0.259530 -vn 0.007869 0.284310 -0.958700 -v 0.076459 0.023117 0.259534 -vn 0.019063 0.585472 -0.810468 -v 0.076459 0.023198 0.259579 -vn -0.057039 0.628609 -0.775627 -v 0.076698 0.023198 0.259573 -vn 0.170358 -0.193728 -0.966151 -v 0.075593 0.023025 0.259454 -vn 0.083728 0.616721 -0.782716 -v 0.075742 0.023198 0.259527 -vn 0.548750 0.603907 -0.578073 -v 0.073162 0.023198 0.258349 -vn 0.496150 0.586268 -0.640410 -v 0.073223 0.023198 0.258401 -vn 0.404283 0.588849 -0.699866 -v 0.073942 0.023198 0.258904 -vn 0.306400 0.586425 -0.749816 -v 0.074737 0.023198 0.259275 -vn 0.228921 0.601513 -0.765361 -v 0.074812 0.023198 0.259302 -vn 0.165613 0.586126 -0.793113 -v 0.075585 0.023198 0.259502 -vn 0.849615 -0.193716 -0.490539 -v 0.072142 0.023025 0.257038 -vn 0.689279 0.588028 -0.423223 -v 0.072099 0.023198 0.257062 -vn 0.765308 0.639947 -0.069077 -v 0.071448 0.023198 0.255024 -vn 0.793139 0.589653 -0.152446 -v 0.071502 0.023198 0.255419 -vn 0.943618 0.280373 -0.175999 -v 0.071546 0.023117 0.255411 -vn 0.966144 -0.193768 -0.170350 -v 0.071549 0.023025 0.255411 -vn 0.723187 0.664038 -0.189879 -v 0.071629 0.023198 0.255963 -vn 0.753583 0.588533 -0.292817 -v 0.071729 0.023198 0.256267 -vn 0.691189 0.645348 -0.325243 -v 0.071985 0.023198 0.256852 -vn 0.810291 0.586028 0.000192 -v 0.071425 0.023198 0.254545 -vn 0.943566 0.284669 0.169255 -v 0.071546 0.023117 0.253679 -vn 0.797228 0.585549 0.146833 -v 0.071502 0.023198 0.253671 -vn 0.765726 0.639434 0.069200 -v 0.071448 0.023198 0.254067 -vn 0.921881 -0.193771 0.335541 -v 0.071774 0.023025 0.252840 -vn 0.898942 0.284542 0.333076 -v 0.071771 0.023117 0.252839 -vn 0.756964 0.585975 0.289203 -v 0.071729 0.023198 0.252823 -vn 0.743797 0.636103 0.205278 -v 0.071629 0.023198 0.253127 -vn 0.849616 -0.193720 0.490536 -v 0.072142 0.023025 0.252053 -vn 0.826316 0.284344 0.486159 -v 0.072138 0.023117 0.252051 -vn 0.691986 0.586275 0.421233 -v 0.072099 0.023198 0.252028 -vn 0.700529 0.628545 0.337921 -v 0.071985 0.023198 0.252238 -vn 0.751540 -0.193713 0.630605 -v 0.072640 0.023025 0.251341 -vn 0.635332 0.617011 0.464381 -v 0.072502 0.023198 0.251433 -vn 0.226283 0.603897 0.764268 -v 0.074812 0.023198 0.249788 -vn 0.306400 0.586425 0.749817 -v 0.074737 0.023198 0.249815 -vn 0.404281 0.588847 0.699869 -v 0.073942 0.023198 0.250186 -vn 0.496148 0.586271 0.640409 -v 0.073223 0.023198 0.250689 -vn 0.548970 0.601017 0.580870 -v 0.073162 0.023198 0.250741 -vn 0.604347 0.585388 0.540449 -v 0.072603 0.023198 0.251309 -vn -0.000004 -0.193788 0.981043 -v 0.076459 0.023025 0.249560 -vn 0.022035 0.587940 0.808604 -v 0.076459 0.023198 0.249511 -vn -0.322869 0.639888 0.697352 -v 0.078550 0.023198 0.249966 -vn -0.264236 0.589077 0.763654 -v 0.078180 0.023198 0.249815 -vn -0.319382 0.280363 0.905203 -v 0.078165 0.023117 0.249857 -vn -0.335540 -0.193740 0.921888 -v 0.078164 0.023025 0.249861 -vn -0.197713 0.663541 0.721542 -v 0.077645 0.023198 0.249653 -vn -0.123472 0.588831 0.798770 -v 0.077333 0.023198 0.249588 -vn -0.063607 0.645709 0.760930 -v 0.076698 0.023198 0.249517 -vn -0.405292 0.586018 0.701656 -v 0.078976 0.023198 0.250186 -vn -0.618363 0.284698 0.732512 -v 0.079665 0.023117 0.250723 -vn -0.525512 0.586263 0.616549 -v 0.079694 0.023198 0.250689 -vn -0.442289 0.639842 0.628477 -v 0.079379 0.023198 0.250445 -vn -0.751538 -0.193710 0.630609 -v 0.080277 0.023025 0.251341 -vn -0.737905 0.284576 0.611975 -v 0.080280 0.023117 0.251338 -vn -0.629059 0.585462 0.511390 -v 0.080315 0.023198 0.251309 -vn -0.550168 0.636029 0.541094 -v 0.080102 0.023198 0.251071 -vn -0.849616 -0.193715 0.490538 -v 0.080776 0.023025 0.252053 -vn -0.834193 0.284317 0.472532 -v 0.080779 0.023117 0.252051 -vn -0.711108 0.586021 0.388465 -v 0.080818 0.023198 0.252028 -vn -0.642889 0.628468 0.437861 -v 0.080693 0.023198 0.251824 -vn -0.921888 -0.193740 0.335542 -v 0.081143 0.023025 0.252840 -vn -0.719629 0.616987 0.318529 -v 0.081132 0.023198 0.252674 -vn -0.802693 0.586263 -0.109455 -v 0.081416 0.023198 0.255419 -vn -0.808955 0.587870 0.000572 -v 0.081492 0.023198 0.254545 -vn -0.803344 0.585410 0.109237 -v 0.081416 0.023198 0.253671 -vn -0.777406 0.601466 0.184061 -v 0.081401 0.023198 0.253592 -vn -0.769411 0.586377 0.253316 -v 0.081189 0.023198 0.252823 -vn -0.554664 0.575938 -0.600536 -v 0.082378 0.027006 0.260665 -vn -0.629460 0.519139 -0.578164 -v 0.082621 0.027006 0.260420 -vn -0.642098 0.576025 -0.505870 -v 0.083141 0.027006 0.259822 -vn -0.706661 0.523587 -0.475906 -v 0.083621 0.027006 0.259148 -vn -0.098035 0.575887 -0.811630 -v 0.077311 0.027006 0.263016 -vn -0.163685 0.576171 -0.800771 -v 0.078432 0.027006 0.262827 -vn -0.221402 0.570982 -0.790545 -v 0.078466 0.027006 0.262819 -vn -0.280360 0.575808 -0.768013 -v 0.079519 0.027006 0.262490 -vn -0.361591 0.507094 -0.782373 -v 0.079996 0.027006 0.262290 -vn -0.400592 0.576329 -0.712300 -v 0.080550 0.027006 0.262011 -vn -0.460942 0.552432 -0.694515 -v 0.081397 0.027006 0.261480 -vn -0.503372 0.576521 -0.643615 -v 0.081509 0.027006 0.261400 -vn 0.341854 0.576175 -0.742400 -v 0.072875 0.027006 0.262268 -vn 0.296967 0.528259 -0.795458 -v 0.073674 0.027006 0.262591 -vn 0.222357 0.576295 -0.786411 -v 0.073936 0.027006 0.262677 -vn 0.157864 0.576290 -0.801853 -v 0.075043 0.027006 0.262941 -vn 0.091087 0.528789 -0.843852 -v 0.075247 0.027006 0.262973 -vn 0.036041 0.575142 -0.817259 -v 0.076174 0.027006 0.263054 -vn -0.032133 0.510097 -0.859516 -v 0.076864 0.027006 0.263050 -vn 0.454967 0.576255 -0.678922 -v 0.071877 0.027006 0.261722 -vn 0.416504 0.515655 -0.748749 -v 0.072202 0.027006 0.261918 -vn 0.740563 0.576321 -0.345572 -v 0.068860 0.027006 0.258385 -vn 0.719790 0.563882 -0.404896 -v 0.068891 0.027006 0.258446 -vn 0.681575 0.575464 -0.451991 -v 0.069439 0.027006 0.259364 -vn 0.677144 0.506246 -0.534033 -v 0.069766 0.027006 0.259808 -vn 0.598909 0.576089 -0.556264 -v 0.070144 0.027006 0.260256 -vn 0.564418 0.558800 -0.607597 -v 0.070883 0.027006 0.260980 -vn 0.508441 0.576394 -0.639732 -v 0.070962 0.027006 0.261047 -vn 0.816766 0.576003 -0.033374 -v 0.067964 0.027006 0.255114 -vn 0.848043 0.518431 -0.109787 -v 0.067983 0.027006 0.255354 -vn 0.803556 0.574407 -0.156058 -v 0.068115 0.027006 0.256241 -vn 0.826930 0.512606 -0.231132 -v 0.068289 0.027006 0.256944 -vn 0.766323 0.576113 -0.284328 -v 0.068416 0.027006 0.257338 -vn 0.680809 0.575934 0.452548 -v 0.069439 0.027006 0.249727 -vn 0.719658 0.565144 0.403366 -v 0.068891 0.027006 0.250644 -vn 0.740563 0.576321 0.345572 -v 0.068860 0.027006 0.250705 -vn 0.766350 0.576045 0.284394 -v 0.068416 0.027006 0.251752 -vn 0.826912 0.512739 0.230902 -v 0.068289 0.027006 0.252146 -vn 0.801595 0.576373 0.158873 -v 0.068115 0.027006 0.252849 -vn 0.839226 0.534034 0.102507 -v 0.067983 0.027006 0.253736 -vn 0.816413 0.576484 0.033711 -v 0.067964 0.027006 0.253976 -vn 0.454965 0.576256 0.678923 -v 0.071877 0.027006 0.247369 -vn 0.508441 0.576391 0.639735 -v 0.070962 0.027006 0.248043 -vn 0.567243 0.556507 0.607071 -v 0.070883 0.027006 0.248111 -vn 0.597945 0.575865 0.557531 -v 0.070144 0.027006 0.248834 -vn 0.677062 0.506334 0.534053 -v 0.069766 0.027006 0.249282 -vn 0.222355 0.576294 0.786412 -v 0.073936 0.027006 0.246413 -vn 0.296967 0.528259 0.795458 -v 0.073674 0.027006 0.246499 -vn 0.341855 0.576175 0.742400 -v 0.072875 0.027006 0.246822 -vn 0.416504 0.515655 0.748749 -v 0.072202 0.027006 0.247172 -vn -0.098030 0.575889 0.811629 -v 0.077311 0.027006 0.246074 -vn -0.032226 0.509981 0.859582 -v 0.076864 0.027006 0.246041 -vn 0.033184 0.576109 0.816699 -v 0.076174 0.027006 0.246036 -vn 0.095506 0.539350 0.836648 -v 0.075247 0.027006 0.246118 -vn 0.157850 0.576307 0.801844 -v 0.075043 0.027006 0.246150 -vn -0.554663 0.575936 0.600538 -v 0.082378 0.027006 0.248425 -vn -0.503758 0.576138 0.643655 -v 0.081509 0.027006 0.247691 -vn -0.460206 0.547210 0.699122 -v 0.081397 0.027006 0.247610 -vn -0.402555 0.575108 0.712180 -v 0.080550 0.027006 0.247079 -vn -0.361429 0.507045 0.782480 -v 0.079996 0.027006 0.246800 -vn -0.280671 0.576179 0.767621 -v 0.079519 0.027006 0.246600 -vn -0.220611 0.571896 0.790105 -v 0.078466 0.027006 0.246271 -vn -0.163829 0.576563 0.800459 -v 0.078432 0.027006 0.246263 -vn -0.786417 0.576038 0.222998 -v 0.084670 0.027006 0.252296 -vn -0.787491 0.545365 0.287116 -v 0.084363 0.027006 0.251381 -vn -0.743092 0.576291 0.340153 -v 0.084297 0.027006 0.251221 -vn -0.713096 0.576183 0.399384 -v 0.083784 0.027006 0.250206 -vn -0.706414 0.523806 0.476033 -v 0.083621 0.027006 0.249942 -vn -0.641949 0.576411 0.505621 -v 0.083141 0.027006 0.249268 -vn -0.629472 0.519275 0.578030 -v 0.082621 0.027006 0.248670 -vn -0.713056 0.576222 -0.399398 -v 0.083784 0.027006 0.258884 -vn -0.743092 0.576291 -0.340151 -v 0.084297 0.027006 0.257869 -vn -0.793336 0.537930 -0.285044 -v 0.084363 0.027006 0.257709 -vn -0.786581 0.574902 -0.225339 -v 0.084670 0.027006 0.256794 -vn -0.844490 0.508135 -0.169218 -v 0.084819 0.027006 0.256156 -vn -0.812025 0.576116 -0.093310 -v 0.084897 0.027006 0.255680 -vn -0.817512 0.575912 0.000382 -v 0.084973 0.027006 0.254545 -vn -0.811701 0.576635 0.092916 -v 0.084897 0.027006 0.253410 -vn -0.844470 0.508184 0.169174 -v 0.084819 0.027006 0.252934 -vn -0.445640 -0.542148 0.712377 -v 0.080715 0.027277 0.247173 -vn -0.370028 -0.584712 0.721936 -v 0.080550 0.027277 0.247080 -vn -0.459355 -0.241760 0.854719 -v 0.080573 0.027191 0.247038 -vn 0.312358 -0.576425 0.755094 -v 0.072922 0.027277 0.246802 -vn 0.364644 -0.584675 0.724700 -v 0.072875 0.027277 0.246823 -vn 0.411755 -0.243893 0.878052 -v 0.072855 0.027191 0.246780 -vn 0.515290 -0.243131 0.821805 -v 0.071853 0.027191 0.247330 -vn 0.812819 -0.568777 -0.125768 -v 0.068100 0.027277 0.256156 -vn 0.789780 -0.584574 -0.185799 -v 0.068117 0.027277 0.256241 -vn 0.949553 -0.242550 -0.198793 -v 0.068070 0.027191 0.256250 -vn 0.919031 -0.242824 -0.310513 -v 0.068372 0.027191 0.257353 -vn 0.069836 -0.560309 -0.825334 -v 0.076054 0.027277 0.263048 -vn 0.003155 -0.584571 -0.811337 -v 0.076174 0.027277 0.263053 -vn 0.025586 -0.241967 -0.969947 -v 0.076173 0.027191 0.263100 -vn -0.791412 -0.551386 -0.263895 -v 0.084627 0.027277 0.256943 -vn -0.788299 -0.584599 -0.191909 -v 0.084669 0.027277 0.256794 -vn -0.937810 -0.241820 -0.249068 -v 0.084715 0.027191 0.256807 -vn -0.841295 0.232158 0.488186 -v 0.083824 0.027092 0.250182 -vn -0.892284 0.231625 0.387530 -v 0.084340 0.027092 0.251203 -vn -0.894502 -0.243413 0.374989 -v 0.084340 0.027191 0.251203 -vn -0.105056 0.233195 0.966738 -v 0.077316 0.027092 0.246027 -vn -0.222334 0.234827 0.946268 -v 0.078443 0.027092 0.246218 -vn -0.225613 -0.243532 0.943287 -v 0.078443 0.027191 0.246218 -vn 0.916014 0.232923 0.326597 -v 0.068372 0.027092 0.251737 -vn 0.870419 0.232854 0.433762 -v 0.068818 0.027092 0.250684 -vn 0.864952 -0.243408 0.438875 -v 0.068819 0.027191 0.250684 -vn 0.530307 0.232631 -0.815265 -v 0.071852 0.027092 0.261761 -vn 0.622693 0.231911 -0.747309 -v 0.070932 0.027092 0.261082 -vn 0.628018 -0.243519 -0.739116 -v 0.070932 0.027191 0.261082 -vn -0.342778 0.233749 -0.909871 -v 0.079535 0.027092 0.262534 -vn -0.222648 0.235005 -0.946150 -v 0.078443 0.027092 0.262872 -vn -0.225624 -0.243398 -0.943319 -v 0.078443 0.027191 0.262872 -vn -0.971135 0.238529 0.000002 -v 0.085019 0.027092 0.254545 -vn -0.964667 0.233413 -0.122213 -v 0.084943 0.027092 0.255686 -vn -0.960350 -0.242363 -0.137800 -v 0.084942 0.027191 0.255686 -vn -0.936882 0.233358 0.260379 -v 0.084715 0.027092 0.252283 -vn -0.763379 0.233407 0.602307 -v 0.083177 0.027092 0.249240 -vn -0.670003 0.232331 0.705066 -v 0.082410 0.027092 0.248391 -vn -0.582879 0.231816 0.778790 -v 0.081537 0.027092 0.247653 -vn -0.472491 0.234519 0.849560 -v 0.080573 0.027092 0.247038 -vn 0.035295 0.233450 0.971728 -v 0.076173 0.027092 0.245989 -vn 0.170420 0.231641 0.957758 -v 0.075035 0.027092 0.246104 -vn 0.279763 0.231937 0.931632 -v 0.073922 0.027092 0.246369 -vn 0.716709 0.234130 0.656895 -v 0.070110 0.027092 0.248803 -vn 0.953297 0.233384 0.191721 -v 0.068070 0.027092 0.252840 -vn 0.971145 0.231786 0.056155 -v 0.067917 0.027092 0.253973 -vn 0.971085 0.231887 -0.056767 -v 0.067917 0.027092 0.255117 -vn 0.805387 0.233932 -0.544635 -v 0.069401 0.027092 0.259390 -vn 0.408217 0.233370 -0.882552 -v 0.072855 0.027092 0.262310 -vn 0.279760 0.231935 -0.931633 -v 0.073922 0.027092 0.262721 -vn 0.169798 0.231751 -0.957841 -v 0.075035 0.027092 0.262986 -vn 0.037790 0.235077 -0.971242 -v 0.076173 0.027092 0.263101 -vn -0.471148 0.233436 -0.850604 -v 0.080573 0.027092 0.262052 -vn -0.583393 0.231668 -0.778449 -v 0.081537 0.027092 0.261437 -vn -0.670012 0.232327 -0.705059 -v 0.082410 0.027092 0.260699 -vn -0.935996 0.234747 -0.262306 -v 0.084715 0.027092 0.256807 -vn -0.892503 0.231754 -0.386947 -v 0.084340 0.027092 0.257887 -vn -0.841297 0.232155 -0.488183 -v 0.083824 0.027092 0.258908 -vn -0.763389 0.233318 -0.602329 -v 0.083177 0.027092 0.259850 -vn -0.105065 0.233196 -0.966737 -v 0.077316 0.027092 0.263063 -vn 0.717702 0.233321 -0.656099 -v 0.070110 0.027092 0.260287 -vn 0.870155 0.233040 -0.434193 -v 0.068818 0.027092 0.258406 -vn 0.916015 0.232922 -0.326595 -v 0.068372 0.027092 0.257353 -vn 0.953419 0.235281 -0.188773 -v 0.068070 0.027092 0.256250 -vn 0.805023 0.233386 0.545407 -v 0.069401 0.027092 0.249700 -vn 0.623119 0.232080 0.746901 -v 0.070932 0.027092 0.248008 -vn 0.530305 0.232631 0.815267 -v 0.071852 0.027092 0.247329 -vn 0.408215 0.233370 0.882552 -v 0.072855 0.027092 0.246780 -vn -0.343219 0.233366 0.909803 -v 0.079535 0.027092 0.246556 -vn -0.830901 -0.243468 -0.500327 -v 0.083824 0.027191 0.258907 -vn -0.894941 -0.244621 -0.373150 -v 0.084340 0.027191 0.257887 -vn -0.458789 -0.241734 -0.855031 -v 0.080573 0.027191 0.262052 -vn -0.572765 -0.243465 -0.782729 -v 0.081536 0.027191 0.261437 -vn -0.356821 -0.242175 -0.902236 -v 0.079535 0.027191 0.262533 -vn -0.310157 -0.584654 -0.749655 -v 0.079518 0.027277 0.262489 -vn -0.257791 -0.535152 -0.804460 -v 0.079243 0.027277 0.262590 -vn 0.412164 -0.243716 -0.877909 -v 0.072855 0.027191 0.262310 -vn 0.293364 -0.243476 -0.924477 -v 0.073923 0.027191 0.262721 -vn 0.515291 -0.243130 -0.821805 -v 0.071853 0.027191 0.261760 -vn 0.422506 -0.584426 -0.692773 -v 0.071878 0.027277 0.261720 -vn 0.503896 -0.521708 -0.688410 -v 0.071521 0.027277 0.261479 -vn 0.863075 -0.245483 -0.441407 -v 0.068819 0.027191 0.258406 -vn 0.795261 -0.242066 -0.555845 -v 0.069401 0.027191 0.259390 -vn 0.949483 -0.242375 0.199341 -v 0.068070 0.027191 0.252840 -vn 0.967364 -0.243443 0.070299 -v 0.067918 0.027191 0.253973 -vn 0.919031 -0.242826 0.310512 -v 0.068372 0.027191 0.251737 -vn 0.772104 -0.584395 0.249678 -v 0.068417 0.027277 0.251753 -vn 0.786627 -0.523003 0.328154 -v 0.068556 0.027277 0.251381 -vn 0.629786 -0.245267 0.737030 -v 0.070932 0.027191 0.248008 -vn 0.725052 -0.241896 0.644815 -v 0.070110 0.027191 0.248803 -vn 0.024981 -0.241809 0.970002 -v 0.076173 0.027191 0.245990 -vn 0.156638 -0.243366 0.957203 -v 0.075035 0.027191 0.246104 -vn -0.088768 -0.242580 0.966062 -v 0.077316 0.027191 0.246028 -vn -0.063085 -0.584387 0.809019 -v 0.077311 0.027277 0.246075 -vn -0.135530 -0.526404 0.839363 -v 0.077670 0.027277 0.246119 -vn -0.759706 -0.246505 0.601732 -v 0.083177 0.027191 0.249240 -vn -0.679717 -0.243336 0.691934 -v 0.082410 0.027191 0.248392 -vn -0.960349 -0.242365 0.137800 -v 0.084942 0.027191 0.253404 -vn -0.938003 -0.241681 0.248478 -v 0.084715 0.027191 0.252284 -vn -0.964667 0.233414 0.122211 -v 0.084943 0.027092 0.253404 -vn -0.969910 -0.243463 0.000001 -v 0.085019 0.027191 0.254545 -vn -0.801286 -0.584678 -0.126853 -v 0.084895 0.027277 0.255680 -vn -0.845211 -0.530623 -0.063694 -v 0.084933 0.027277 0.255354 -vn -0.751588 -0.583399 -0.307833 -v 0.084296 0.027277 0.257868 -vn -0.763358 -0.516594 -0.387835 -v 0.084025 0.027277 0.258446 -vn -0.690437 -0.584520 -0.426185 -v 0.083783 0.027277 0.258883 -vn -0.759612 -0.246414 -0.601888 -v 0.083177 0.027191 0.259850 -vn -0.619681 -0.584849 -0.523400 -v 0.083139 0.027277 0.259821 -vn -0.655521 -0.582709 -0.480357 -v 0.083150 0.027277 0.259807 -vn -0.679712 -0.243416 -0.691911 -v 0.082410 0.027191 0.260698 -vn -0.575425 -0.584537 -0.572017 -v 0.082377 0.027277 0.260664 -vn -0.554381 -0.518168 -0.651278 -v 0.082033 0.027277 0.260979 -vn -0.369953 -0.584809 -0.721895 -v 0.080550 0.027277 0.262010 -vn -0.438788 -0.551115 -0.709744 -v 0.080715 0.027277 0.261917 -vn -0.476102 -0.584521 -0.657010 -v 0.081508 0.027277 0.261398 -vn -0.189787 -0.584897 -0.788591 -v 0.078432 0.027277 0.262826 -vn -0.088773 -0.242578 -0.966062 -v 0.077316 0.027191 0.263062 -vn -0.063405 -0.584850 -0.808659 -v 0.077311 0.027277 0.263015 -vn -0.135219 -0.526966 -0.839061 -v 0.077670 0.027277 0.262971 -vn 0.155150 -0.244419 -0.957177 -v 0.075035 0.027191 0.262986 -vn 0.123985 -0.583620 -0.802506 -v 0.075043 0.027277 0.262939 -vn 0.199539 -0.515634 -0.833250 -v 0.074452 0.027277 0.262818 -vn 0.364545 -0.584776 -0.724668 -v 0.072875 0.027277 0.262267 -vn 0.313047 -0.577247 -0.754180 -v 0.072922 0.027277 0.262288 -vn 0.252918 -0.584543 -0.770935 -v 0.073937 0.027277 0.262676 -vn 0.525904 -0.586260 -0.616217 -v 0.070963 0.027277 0.261046 -vn 0.725482 -0.241793 -0.644369 -v 0.070110 0.027191 0.260287 -vn 0.615990 -0.584857 -0.527731 -v 0.070145 0.027277 0.260255 -vn 0.590212 -0.545316 -0.595214 -v 0.070298 0.027277 0.260419 -vn 0.656620 -0.584860 -0.476224 -v 0.069440 0.027277 0.259363 -vn 0.772102 -0.584396 -0.249680 -v 0.068417 0.027277 0.257337 -vn 0.786496 -0.523154 -0.328229 -v 0.068556 0.027277 0.257709 -vn 0.721679 -0.583466 -0.372486 -v 0.068861 0.027277 0.258384 -vn 0.732011 -0.523079 -0.436518 -v 0.069297 0.027277 0.259147 -vn 0.967119 -0.244115 -0.071328 -v 0.067918 0.027191 0.255117 -vn 0.809074 -0.583912 -0.066682 -v 0.067965 0.027277 0.255114 -vn 0.856862 -0.515545 0.000094 -v 0.067946 0.027277 0.254545 -vn 0.789626 -0.584860 0.185550 -v 0.068117 0.027277 0.252849 -vn 0.810989 -0.571052 0.127262 -v 0.068100 0.027277 0.252934 -vn 0.808569 -0.584738 0.065558 -v 0.067965 0.027277 0.253976 -vn 0.722622 -0.584536 0.368964 -v 0.068861 0.027277 0.250706 -vn 0.794937 -0.241967 0.556351 -v 0.069401 0.027191 0.249700 -vn 0.656622 -0.584849 0.476235 -v 0.069440 0.027277 0.249727 -vn 0.719524 -0.539833 0.436881 -v 0.069297 0.027277 0.249943 -vn 0.615987 -0.584858 0.527732 -v 0.070145 0.027277 0.248835 -vn 0.422506 -0.584425 0.692774 -v 0.071878 0.027277 0.247370 -vn 0.503406 -0.520260 0.689864 -v 0.071521 0.027277 0.247611 -vn 0.530480 -0.583096 0.615297 -v 0.070963 0.027277 0.248044 -vn 0.592117 -0.532580 0.604778 -v 0.070298 0.027277 0.248671 -vn 0.293935 -0.243879 0.924189 -v 0.073923 0.027191 0.246369 -vn 0.253627 -0.584246 0.770928 -v 0.073937 0.027277 0.246415 -vn 0.199251 -0.515979 0.833105 -v 0.074452 0.027277 0.246272 -vn 0.003155 -0.584570 0.811337 -v 0.076174 0.027277 0.246037 -vn 0.067286 -0.564116 0.822949 -v 0.076054 0.027277 0.246042 -vn 0.125450 -0.584873 0.801365 -v 0.075043 0.027277 0.246151 -vn -0.189760 -0.584599 0.788819 -v 0.078432 0.027277 0.246264 -vn -0.356837 -0.242162 0.902233 -v 0.079535 0.027191 0.246557 -vn -0.310131 -0.584709 0.749623 -v 0.079518 0.027277 0.246601 -vn -0.258044 -0.534908 0.804541 -v 0.079243 0.027277 0.246501 -vn -0.570702 -0.244939 0.783775 -v 0.081536 0.027191 0.247654 -vn -0.474675 -0.583256 0.659163 -v 0.081508 0.027277 0.247692 -vn -0.554375 -0.518163 0.651287 -v 0.082033 0.027277 0.248112 -vn -0.763195 -0.517281 0.387239 -v 0.084025 0.027277 0.250644 -vn -0.690085 -0.584749 0.426440 -v 0.083783 0.027277 0.250207 -vn -0.830763 -0.243602 0.500491 -v 0.083824 0.027191 0.250183 -vn -0.655716 -0.582878 0.479886 -v 0.083150 0.027277 0.249283 -vn -0.619647 -0.584908 0.523374 -v 0.083139 0.027277 0.249269 -vn -0.575452 -0.584460 0.572067 -v 0.082377 0.027277 0.248426 -vn -0.749451 -0.585306 0.309419 -v 0.084296 0.027277 0.251222 -vn -0.788526 -0.557562 0.259523 -v 0.084627 0.027277 0.252147 -vn -0.811277 -0.584662 0.000001 -v 0.084971 0.027277 0.254545 -vn -0.845354 -0.530415 0.063542 -v 0.084933 0.027277 0.253736 -vn -0.801413 -0.584465 0.127038 -v 0.084895 0.027277 0.253410 -vn -0.788300 -0.584598 0.191908 -v 0.084669 0.027277 0.252296 -vn 0.712624 -0.650248 -0.263333 -v 0.071639 0.030836 0.256475 -vn 0.716670 -0.605516 -0.346026 -v 0.071728 0.030836 0.256683 -vn 0.668274 -0.631717 -0.392865 -v 0.072091 0.030836 0.257352 -vn 0.642662 -0.606218 -0.468493 -v 0.072157 0.030836 0.257452 -vn 0.597175 -0.607102 -0.524222 -v 0.072701 0.030836 0.258128 -vn 0.552523 -0.603817 -0.574564 -v 0.072711 0.030836 0.258137 -vn 0.497517 -0.605355 -0.621307 -v 0.073372 0.030836 0.258719 -vn 0.421941 -0.629721 -0.652240 -v 0.073447 0.030836 0.258774 -vn 0.378646 -0.607405 -0.698345 -v 0.074121 0.030836 0.259181 -vn -0.035920 -0.606148 -0.794540 -v 0.076679 0.030836 0.259732 -vn 0.033043 -0.663995 -0.747007 -v 0.076212 0.030836 0.259731 -vn 0.106799 -0.606375 -0.787974 -v 0.075799 0.030836 0.259695 -vn 0.164668 -0.659101 -0.733806 -v 0.075235 0.030836 0.259590 -vn 0.249628 -0.608067 -0.753618 -v 0.074939 0.030836 0.259509 -vn 0.285648 -0.658916 -0.695870 -v 0.074302 0.030836 0.259267 -vn -0.598992 -0.606400 -0.522960 -v 0.080498 0.030836 0.257806 -vn -0.548598 -0.606436 -0.575566 -v 0.079889 0.030836 0.258442 -vn -0.490589 -0.614316 -0.618012 -v 0.079858 0.030836 0.258469 -vn -0.438668 -0.606633 -0.662998 -v 0.079181 0.030836 0.258966 -vn -0.360407 -0.637485 -0.680969 -v 0.079054 0.030836 0.259041 -vn -0.313354 -0.606249 -0.730938 -v 0.078394 0.030836 0.259362 -vn -0.229886 -0.653546 -0.721131 -v 0.078157 0.030836 0.259451 -vn -0.177439 -0.605741 -0.775625 -v 0.077552 0.030836 0.259620 -vn -0.098982 -0.661917 -0.743013 -v 0.077198 0.030836 0.259684 -vn -0.779364 -0.609082 -0.147009 -v 0.081576 0.030836 0.255422 -vn -0.710629 -0.679001 -0.184294 -v 0.081440 0.030836 0.256008 -vn -0.741808 -0.608280 -0.282340 -v 0.081354 0.030836 0.256275 -vn -0.687170 -0.652271 -0.319907 -v 0.081073 0.030836 0.256924 -vn -0.681032 -0.606968 -0.409616 -v 0.080991 0.030836 0.257077 -vn -0.636824 -0.621864 -0.455785 -v 0.080540 0.030836 0.257754 -vn -0.728416 -0.655828 0.198242 -v 0.081440 0.030836 0.253082 -vn -0.782336 -0.606356 0.142420 -v 0.081576 0.030836 0.253668 -vn -0.745418 -0.663353 0.065689 -v 0.081627 0.030836 0.254052 -vn -0.795413 -0.606067 0.000001 -v 0.081650 0.030836 0.254545 -vn -0.745544 -0.663195 -0.065847 -v 0.081627 0.030836 0.255039 -vn -0.315305 -0.607803 0.728806 -v 0.078394 0.030836 0.249728 -vn -0.353833 -0.644696 0.677620 -v 0.079054 0.030836 0.250049 -vn -0.438668 -0.606633 0.662998 -v 0.079181 0.030836 0.250124 -vn -0.490589 -0.614316 0.618012 -v 0.079858 0.030836 0.250622 -vn -0.548597 -0.606437 0.575566 -v 0.079889 0.030836 0.250648 -vn -0.598989 -0.606403 0.522960 -v 0.080498 0.030836 0.251284 -vn -0.637403 -0.619699 0.457920 -v 0.080540 0.030836 0.251336 -vn -0.682371 -0.605745 0.409197 -v 0.080991 0.030836 0.252013 -vn -0.693150 -0.641849 0.327983 -v 0.081073 0.030836 0.252166 -vn -0.745308 -0.605111 0.279922 -v 0.081354 0.030836 0.252816 -vn 0.033561 -0.663492 0.747430 -v 0.076212 0.030836 0.249359 -vn -0.035652 -0.606413 0.794350 -v 0.076679 0.030836 0.249358 -vn -0.098974 -0.662421 0.742565 -v 0.077198 0.030836 0.249406 -vn -0.181478 -0.608827 0.772267 -v 0.077552 0.030836 0.249470 -vn -0.217974 -0.672627 0.707150 -v 0.078157 0.030836 0.249639 -vn 0.642631 -0.606245 0.468499 -v 0.072157 0.030836 0.251638 -vn 0.597243 -0.608343 0.522704 -v 0.072701 0.030836 0.250962 -vn 0.551076 -0.606348 0.573286 -v 0.072711 0.030836 0.250953 -vn 0.496127 -0.606644 0.621162 -v 0.073372 0.030836 0.250371 -vn 0.425545 -0.626581 0.652923 -v 0.073447 0.030836 0.250316 -vn 0.377467 -0.606478 0.699788 -v 0.074121 0.030836 0.249909 -vn 0.295175 -0.646373 0.703614 -v 0.074302 0.030836 0.249823 -vn 0.246629 -0.605939 0.756315 -v 0.074939 0.030836 0.249581 -vn 0.164468 -0.658754 0.734162 -v 0.075235 0.030836 0.249500 -vn 0.106682 -0.605480 0.788678 -v 0.075799 0.030836 0.249396 -vn 0.763563 -0.608734 0.215438 -v 0.071435 0.030836 0.253237 -vn 0.701915 -0.666226 0.251909 -v 0.071639 0.030836 0.252616 -vn 0.714231 -0.607694 0.347250 -v 0.071728 0.030836 0.252407 -vn 0.665829 -0.637301 0.387968 -v 0.072091 0.030836 0.251738 -vn 0.766350 -0.606469 -0.211905 -v 0.071435 0.030836 0.255853 -vn 0.738995 -0.660743 -0.131549 -v 0.071361 0.030836 0.255528 -vn 0.792104 -0.606165 -0.071668 -v 0.071286 0.030836 0.254985 -vn 0.747579 -0.664173 0.000129 -v 0.071267 0.030836 0.254545 -vn 0.792399 -0.605762 0.071805 -v 0.071286 0.030836 0.254105 -vn 0.739290 -0.660438 0.131423 -v 0.071361 0.030836 0.253563 -vn -0.515185 0.717154 0.469334 -v 0.080450 0.031126 0.251196 -vn -0.477495 0.699170 0.532127 -v 0.079901 0.031126 0.250634 -vn -0.590427 0.462582 0.661372 -v 0.079867 0.031062 0.250672 -vn -0.397374 0.746457 0.533757 -v 0.079570 0.031126 0.250366 -vn -0.361095 0.693702 0.623207 -v 0.079190 0.031126 0.250109 -vn -0.458690 0.461256 0.759504 -v 0.079164 0.031062 0.250152 -vn -0.099039 0.731595 0.674508 -v 0.077363 0.031126 0.249415 -vn -0.027119 0.690566 0.722761 -v 0.076680 0.031126 0.249340 -vn -0.040494 0.462653 0.885614 -v 0.076678 0.031062 0.249390 -vn 0.603312 0.711538 0.360180 -v 0.072106 0.031126 0.251682 -vn 0.671269 0.675530 0.305052 -v 0.071711 0.031126 0.252399 -vn 0.804776 0.462660 0.371862 -v 0.071757 0.031062 0.252420 -vn 0.627315 0.744313 0.229074 -v 0.071563 0.031126 0.252763 -vn 0.737638 0.654819 0.164626 -v 0.071417 0.031126 0.253232 -vn 0.860553 0.460947 0.216741 -v 0.071466 0.031062 0.253245 -vn 0.675087 0.731051 -0.099105 -v 0.071284 0.031126 0.255150 -vn 0.703367 0.688569 -0.176484 -v 0.071417 0.031126 0.255858 -vn 0.858903 0.462714 -0.219504 -v 0.071466 0.031062 0.255845 -vn 0.624499 0.748060 -0.224515 -v 0.071563 0.031126 0.256327 -vn 0.652153 0.693420 -0.306374 -v 0.071711 0.031126 0.256691 -vn 0.804590 0.461946 -0.373149 -v 0.071757 0.031062 0.256670 -vn 0.450294 0.741119 -0.497974 -v 0.072884 0.031126 0.258334 -vn 0.429093 0.692642 -0.579764 -v 0.073361 0.031126 0.258734 -vn 0.524198 0.459557 -0.716954 -v 0.073391 0.031062 0.258693 -vn -0.092525 0.743608 -0.662183 -v 0.077363 0.031126 0.259676 -vn -0.167659 0.702736 -0.691414 -v 0.077556 0.031126 0.259638 -vn -0.196085 0.463573 -0.864090 -v 0.077546 0.031062 0.259589 -vn -0.296377 0.724103 -0.622764 -v 0.078522 0.031126 0.259329 -vn -0.364192 0.696079 -0.618740 -v 0.079190 0.031126 0.258981 -vn -0.460431 0.462676 -0.757585 -v 0.079164 0.031062 0.258938 -vn -0.396308 0.747999 -0.532389 -v 0.079570 0.031126 0.258724 -vn -0.477578 0.702065 -0.528227 -v 0.079901 0.031126 0.258456 -vn -0.592181 0.461520 -0.660546 -v 0.079867 0.031062 0.258418 -vn -0.612597 0.736790 -0.286120 -v 0.081114 0.031126 0.256883 -vn -0.670871 0.700705 -0.242783 -v 0.081371 0.031126 0.256281 -vn -0.835291 0.462714 -0.296959 -v 0.081323 0.031062 0.256264 -vn 0.646365 0.463095 0.606428 -v 0.072734 0.031062 0.250975 -vn 0.720510 0.063225 0.690556 -v 0.072749 0.030984 0.250990 -vn 0.593444 0.063232 0.802388 -v 0.073403 0.030984 0.250414 -vn -0.210250 0.063123 -0.975608 -v 0.077541 0.030984 0.259568 -vn -0.042360 0.063266 -0.997097 -v 0.076677 0.030984 0.259679 -vn 0.676663 -0.343414 0.651302 -v 0.072741 0.030904 0.250982 -vn 0.564748 -0.349101 0.747789 -v 0.073397 0.030904 0.250405 -vn -0.201864 -0.350424 -0.914579 -v 0.077544 0.030904 0.259579 -vn -0.040689 -0.350518 -0.935672 -v 0.076677 0.030904 0.259690 -vn -0.623737 -0.346740 0.700517 -v 0.079861 0.030904 0.250679 -vn -0.499032 -0.349698 0.792892 -v 0.079159 0.030904 0.250160 -vn -0.040689 -0.350515 0.935673 -v 0.076677 0.030904 0.249400 -vn 0.771116 -0.349286 0.532334 -v 0.072192 0.030904 0.251661 -vn 0.933015 -0.350533 0.081301 -v 0.071328 0.030904 0.254108 -vn 0.933015 -0.350532 -0.081300 -v 0.071328 0.030904 0.254982 -vn 0.904931 -0.350504 -0.241343 -v 0.071475 0.030904 0.255843 -vn 0.849882 -0.350290 -0.393697 -v 0.071766 0.030904 0.256666 -vn 0.770599 -0.349444 -0.532979 -v 0.072192 0.030904 0.257429 -vn -0.356621 -0.350272 -0.866101 -v 0.078379 0.030904 0.259323 -vn -0.499695 -0.349829 -0.792417 -v 0.079159 0.030904 0.258930 -vn -0.724876 -0.348173 -0.594416 -v 0.080465 0.030904 0.257780 -vn -0.922737 -0.347023 -0.167728 -v 0.081534 0.030904 0.255415 -vn -0.936548 -0.350539 0.000002 -v 0.081608 0.030904 0.254545 -vn -0.880486 -0.348181 -0.321736 -v 0.081314 0.030904 0.256261 -vn -0.813001 -0.349102 -0.466002 -v 0.080954 0.030904 0.257056 -vn 0.121753 -0.350485 -0.928621 -v 0.075805 0.030904 0.259653 -vn 0.284519 -0.347908 -0.893314 -v 0.074951 0.030904 0.259469 -vn 0.431173 -0.348928 -0.832069 -v 0.074140 0.030904 0.259143 -vn 0.564141 -0.348887 -0.748347 -v 0.073397 0.030904 0.258685 -vn 0.849707 -0.348698 0.395485 -v 0.071766 0.030904 0.252424 -vn 0.429945 -0.350201 0.832170 -v 0.074140 0.030904 0.249947 -vn 0.280361 -0.350419 0.893647 -v 0.074951 0.030904 0.249621 -vn 0.121759 -0.350486 0.928619 -v 0.075805 0.030904 0.249437 -vn -0.358945 -0.348479 0.865864 -v 0.078379 0.030904 0.249767 -vn -0.812977 -0.350054 0.465329 -v 0.080954 0.030904 0.252034 -vn -0.880664 -0.350420 0.318806 -v 0.081314 0.030904 0.252830 -vn -0.922443 -0.350520 0.161972 -v 0.081534 0.030904 0.253675 -vn -0.983647 0.063216 -0.168648 -v 0.081523 0.030984 0.255413 -vn -0.998000 0.063214 0.000001 -v 0.081597 0.030984 0.254545 -vn 0.126761 0.063337 -0.989909 -v 0.075806 0.030984 0.259642 -vn 0.292246 0.063141 -0.954256 -v 0.074954 0.030984 0.259458 -vn 0.449305 0.063145 -0.891144 -v 0.074146 0.030984 0.259133 -vn 0.593446 0.063229 -0.802386 -v 0.073403 0.030984 0.258676 -vn 0.449302 0.063145 0.891146 -v 0.074146 0.030984 0.249957 -vn 0.292238 0.063142 0.954259 -v 0.074954 0.030984 0.249632 -vn 0.126773 0.063336 0.989908 -v 0.075806 0.030984 0.249449 -vn -0.983647 0.063214 0.168651 -v 0.081523 0.030984 0.253677 -vn -0.940993 0.063173 0.332477 -v 0.081303 0.030984 0.252833 -vn -0.871274 0.063207 0.486709 -v 0.080944 0.030984 0.252039 -vn -0.875361 0.462602 -0.140508 -v 0.081544 0.031062 0.255417 -vn -0.889593 0.456755 0.000003 -v 0.081618 0.031062 0.254545 -vn -0.623741 -0.346739 -0.700513 -v 0.079861 0.030904 0.258411 -vn -0.776482 0.063147 -0.626968 -v 0.080456 0.030984 0.257773 -vn -0.659348 0.063172 -0.749179 -v 0.079853 0.030984 0.258402 -vn -0.694426 0.463676 -0.550252 -v 0.080473 0.031062 0.257786 -vn -0.044233 0.460532 -0.886540 -v 0.076678 0.031062 0.259700 -vn 0.121606 0.462260 -0.878366 -v 0.075803 0.031062 0.259663 -vn 0.260508 0.456685 -0.850632 -v 0.074948 0.031062 0.259478 -vn 0.390866 0.462819 -0.795627 -v 0.074136 0.031062 0.259152 -vn 0.826850 0.063212 -0.558859 -v 0.072202 0.030984 0.257422 -vn 0.909408 0.063227 -0.411070 -v 0.071777 0.030984 0.256661 -vn 0.730717 0.462953 -0.501724 -v 0.072184 0.031062 0.257434 -vn 0.904760 -0.347667 0.246043 -v 0.071475 0.030904 0.253247 -vn 0.994405 0.063202 0.084646 -v 0.071339 0.030984 0.254109 -vn 0.965798 0.063223 0.251469 -v 0.071486 0.030984 0.253250 -vn 0.883482 0.463840 0.065673 -v 0.071318 0.031062 0.254108 -vn 0.532375 0.459901 0.710681 -v 0.073391 0.031062 0.250397 -vn 0.390270 0.462972 0.795830 -v 0.074136 0.031062 0.249938 -vn 0.260490 0.456815 0.850567 -v 0.074948 0.031062 0.249612 -vn 0.121601 0.462268 0.878363 -v 0.075803 0.031062 0.249427 -vn -0.372110 0.063217 0.926034 -v 0.078374 0.030984 0.249777 -vn -0.523257 0.063253 0.849824 -v 0.079153 0.030984 0.250170 -vn -0.321913 0.463831 0.825368 -v 0.078382 0.031062 0.249758 -vn -0.875360 0.462602 0.140511 -v 0.081544 0.031062 0.253673 -vn -0.835061 0.460245 0.301410 -v 0.081323 0.031062 0.252826 -vn -0.768855 0.463495 0.440493 -v 0.080963 0.031062 0.252029 -vn -0.940992 0.063173 -0.332480 -v 0.081303 0.030984 0.256257 -vn -0.647340 0.744513 -0.163253 -v 0.081528 0.031126 0.255746 -vn -0.612730 0.698791 -0.369126 -v 0.081007 0.031126 0.257086 -vn -0.768476 0.463562 -0.441083 -v 0.080963 0.031062 0.257061 -vn -0.871274 0.063206 -0.486709 -v 0.080944 0.030984 0.257051 -vn -0.567508 0.703302 -0.428137 -v 0.080512 0.031126 0.257818 -vn -0.510902 0.721310 -0.467644 -v 0.080450 0.031126 0.257894 -vn -0.523261 0.063248 -0.849822 -v 0.079153 0.030984 0.258920 -vn -0.244279 0.693916 -0.677354 -v 0.078401 0.031126 0.259379 -vn -0.321189 0.463949 -0.825584 -v 0.078382 0.031062 0.259332 -vn -0.372112 0.063220 -0.926032 -v 0.078374 0.030984 0.259313 -vn -0.033591 0.697855 -0.715450 -v 0.076680 0.031126 0.259750 -vn 0.030166 0.746629 -0.664556 -v 0.076156 0.031126 0.259746 -vn 0.109768 0.692635 -0.712887 -v 0.075797 0.031126 0.259713 -vn 0.209821 0.706946 -0.675428 -v 0.074933 0.031126 0.259526 -vn 0.309002 0.699401 -0.644481 -v 0.074113 0.031126 0.259197 -vn 0.337984 0.762939 -0.551081 -v 0.073854 0.031126 0.259057 -vn 0.533385 0.692874 -0.485207 -v 0.072698 0.031126 0.258150 -vn 0.646777 0.463232 -0.605884 -v 0.072734 0.031062 0.258115 -vn 0.720526 0.063101 -0.690551 -v 0.072749 0.030984 0.258100 -vn 0.676628 -0.343525 -0.651280 -v 0.072741 0.030904 0.258108 -vn 0.576281 0.702988 -0.416782 -v 0.072142 0.031126 0.257462 -vn 0.598455 0.715455 -0.360523 -v 0.072106 0.031126 0.257408 -vn 0.965798 0.063223 -0.251470 -v 0.071486 0.030984 0.255840 -vn 0.714060 0.699021 -0.038579 -v 0.071268 0.031126 0.254987 -vn 0.883486 0.463936 -0.064927 -v 0.071318 0.031062 0.254983 -vn 0.994405 0.063202 -0.084645 -v 0.071339 0.030984 0.254981 -vn 0.726573 0.686478 0.028980 -v 0.071268 0.031126 0.254103 -vn 0.667226 0.737329 0.105621 -v 0.071284 0.031126 0.253940 -vn 0.909409 0.063229 0.411069 -v 0.071777 0.030984 0.252429 -vn 0.575233 0.702634 0.418822 -v 0.072142 0.031126 0.251628 -vn 0.730271 0.463131 0.502209 -v 0.072184 0.031062 0.251656 -vn 0.826855 0.063216 0.558851 -v 0.072202 0.030984 0.251668 -vn 0.557580 0.671940 0.487443 -v 0.072698 0.031126 0.250940 -vn 0.028771 0.744316 0.667208 -v 0.076156 0.031126 0.249344 -vn 0.122888 0.677673 0.725023 -v 0.075797 0.031126 0.249378 -vn 0.212762 0.703793 0.677796 -v 0.074933 0.031126 0.249564 -vn 0.316838 0.690303 0.650458 -v 0.074113 0.031126 0.249893 -vn 0.344289 0.740443 0.577243 -v 0.073854 0.031126 0.250033 -vn 0.451429 0.677996 0.580115 -v 0.073361 0.031126 0.250356 -vn 0.431650 0.755195 0.493314 -v 0.072884 0.031126 0.250756 -vn -0.042356 0.063267 0.997097 -v 0.076677 0.030984 0.249412 -vn -0.168093 0.698437 0.695651 -v 0.077556 0.031126 0.249452 -vn -0.196793 0.463653 0.863886 -v 0.077546 0.031062 0.249501 -vn -0.210261 0.063124 0.975605 -v 0.077541 0.030984 0.249522 -vn -0.207105 -0.347254 0.914616 -v 0.077544 0.030904 0.249511 -vn -0.239702 0.686348 0.686636 -v 0.078401 0.031126 0.249711 -vn -0.299634 0.727841 0.616821 -v 0.078522 0.031126 0.249761 -vn -0.659349 0.063177 0.749178 -v 0.079853 0.030984 0.250688 -vn -0.569174 0.701770 0.428440 -v 0.080512 0.031126 0.251272 -vn -0.694803 0.463852 0.549627 -v 0.080473 0.031062 0.251304 -vn -0.776481 0.063249 0.626959 -v 0.080456 0.030984 0.251317 -vn -0.724357 -0.348382 0.594926 -v 0.080465 0.030904 0.251310 -vn -0.613250 0.696617 0.372357 -v 0.081007 0.031126 0.252004 -vn -0.704986 0.701750 -0.102671 -v 0.081593 0.031126 0.255425 -vn -0.711986 0.702193 0.000336 -v 0.081668 0.031126 0.254545 -vn -0.705295 0.701438 0.102682 -v 0.081593 0.031126 0.253665 -vn -0.647732 0.744078 0.163681 -v 0.081528 0.031126 0.253344 -vn -0.668311 0.701961 0.246194 -v 0.081371 0.031126 0.252809 -vn -0.603309 0.748583 0.275030 -v 0.081114 0.031126 0.252207 -vn -0.298195 0.677777 -0.672085 -v 0.078619 0.031265 0.259469 -vn -0.196068 0.687647 -0.699070 -v 0.077779 0.031265 0.259758 -vn -0.124215 0.664991 -0.736450 -v 0.077392 0.031265 0.259840 -vn -0.053893 0.684111 -0.727385 -v 0.076903 0.031265 0.259904 -vn 0.018058 0.671672 -0.740629 -v 0.076146 0.031265 0.259913 -vn 0.081645 0.680157 -0.728506 -v 0.076015 0.031265 0.259904 -vn 0.156568 0.691036 -0.705659 -v 0.075139 0.031265 0.259758 -vn 0.749476 0.658978 0.063512 -v 0.071118 0.031265 0.253921 -vn 0.701726 0.712283 0.015309 -v 0.071082 0.031265 0.254545 -vn 0.741208 0.667176 -0.074074 -v 0.071118 0.031265 0.255169 -vn 0.713610 0.686916 -0.137506 -v 0.071155 0.031265 0.255430 -vn 0.699494 0.681231 -0.215944 -v 0.071373 0.031265 0.256291 -vn 0.685861 0.673477 -0.275725 -v 0.071406 0.031265 0.256384 -vn 0.640980 0.689628 -0.336985 -v 0.071730 0.031265 0.257104 -vn 0.625448 0.664791 -0.408494 -v 0.071966 0.031265 0.257500 -vn 0.561884 0.692202 -0.452926 -v 0.072215 0.031265 0.257848 -vn 0.522264 0.676170 -0.519648 -v 0.072769 0.031265 0.258456 -vn 0.476298 0.682071 -0.554905 -v 0.072817 0.031265 0.258501 -vn 0.411843 0.683869 -0.602253 -v 0.073518 0.031265 0.259046 -vn 0.361852 0.654520 -0.663827 -v 0.073770 0.031265 0.259202 -vn 0.290303 0.688498 -0.664601 -v 0.074299 0.031265 0.259469 -vn 0.228508 0.670297 -0.706035 -v 0.074917 0.031265 0.259696 -vn 0.697276 0.701826 0.145760 -v 0.071155 0.031265 0.253660 -vn 0.685730 0.695392 0.214952 -v 0.071373 0.031265 0.252799 -vn 0.681129 0.680188 0.270939 -v 0.071406 0.031265 0.252706 -vn 0.625917 0.699125 0.345619 -v 0.071730 0.031265 0.251986 -vn 0.651068 0.642182 0.404615 -v 0.071966 0.031265 0.251590 -vn 0.541083 0.709316 0.451774 -v 0.072215 0.031265 0.251242 -vn 0.525385 0.675957 0.516772 -v 0.072769 0.031265 0.250634 -vn 0.470267 0.685717 0.555554 -v 0.072817 0.031265 0.250589 -vn 0.404152 0.692765 0.597275 -v 0.073518 0.031265 0.250044 -vn 0.363172 0.670285 0.647166 -v 0.073770 0.031265 0.249888 -vn 0.274435 0.697059 0.662415 -v 0.074299 0.031265 0.249621 -vn 0.239149 0.664667 0.707831 -v 0.074917 0.031265 0.249394 -vn 0.145655 0.702157 0.696965 -v 0.075139 0.031265 0.249333 -vn 0.080796 0.685916 0.723181 -v 0.076015 0.031265 0.249186 -vn 0.020895 0.677224 0.735480 -v 0.076146 0.031265 0.249177 -vn -0.065039 0.686541 0.724176 -v 0.076903 0.031265 0.249186 -vn -0.114306 0.646116 0.754632 -v 0.077392 0.031265 0.249250 -vn -0.199527 0.694255 0.691520 -v 0.077779 0.031265 0.249333 -vn -0.297233 0.680011 0.670252 -v 0.078619 0.031265 0.249621 -vn -0.387293 0.683664 0.618552 -v 0.079400 0.031265 0.250044 -vn -0.450958 0.668175 0.591760 -v 0.079670 0.031265 0.250232 -vn -0.502622 0.684810 0.527642 -v 0.080100 0.031265 0.250589 -vn -0.552925 0.667571 0.498621 -v 0.080578 0.031265 0.251089 -vn -0.589338 0.687359 0.424522 -v 0.080702 0.031265 0.251242 -vn -0.632024 0.681727 0.368504 -v 0.081188 0.031265 0.251986 -vn -0.669317 0.674329 0.311923 -v 0.081264 0.031265 0.252132 -vn -0.694443 0.679364 0.237094 -v 0.081544 0.031265 0.252799 -vn -0.735937 0.648901 0.193194 -v 0.081691 0.031265 0.253305 -vn -0.723481 0.682833 0.101560 -v 0.081762 0.031265 0.253660 -vn -0.731981 0.681325 0.000280 -v 0.081836 0.031265 0.254545 -vn -0.723752 0.682525 -0.101703 -v 0.081762 0.031265 0.255430 -vn -0.723827 0.666345 -0.179047 -v 0.081691 0.031265 0.255785 -vn -0.690585 0.680393 -0.245271 -v 0.081544 0.031265 0.256291 -vn -0.674803 0.669698 -0.310074 -v 0.081264 0.031265 0.256958 -vn -0.633551 0.680428 -0.368281 -v 0.081188 0.031265 0.257104 -vn -0.589651 0.685253 -0.427482 -v 0.080702 0.031265 0.257848 -vn -0.554054 0.671890 -0.491517 -v 0.080578 0.031265 0.258001 -vn -0.497316 0.681800 -0.536494 -v 0.080100 0.031265 0.258501 -vn -0.467407 0.651692 -0.597351 -v 0.079670 0.031265 0.258858 -vn -0.387962 0.681077 -0.620983 -v 0.079400 0.031265 0.259046 -vn -0.918252 0.367676 -0.147065 -v 0.081903 0.031461 0.255454 -vn -0.877475 0.369031 -0.306357 -v 0.081680 0.031461 0.256337 -vn -0.815952 0.368104 -0.445782 -v 0.081313 0.031461 0.257172 -vn -0.737385 0.367303 -0.566880 -v 0.080815 0.031461 0.257935 -vn -0.626941 0.370663 -0.685241 -v 0.080197 0.031461 0.258606 -vn -0.504624 0.367923 -0.781017 -v 0.079478 0.031461 0.259166 -vn -0.372751 0.372731 -0.849781 -v 0.078676 0.031461 0.259600 -vn -0.233998 0.367943 -0.899924 -v 0.077814 0.031461 0.259896 -vn -0.071620 0.368728 -0.926774 -v 0.076915 0.031461 0.260046 -vn 0.079926 0.368516 -0.926179 -v 0.076003 0.031461 0.260046 -vn 0.222619 0.367237 -0.903094 -v 0.075104 0.031461 0.259896 -vn 0.376135 0.370317 -0.849345 -v 0.074241 0.031461 0.259600 -vn 0.512534 0.367799 -0.775908 -v 0.073440 0.031461 0.259166 -vn 0.627455 0.369568 -0.685361 -v 0.072720 0.031461 0.258606 -vn 0.731010 0.367486 -0.574959 -v 0.072103 0.031461 0.257935 -vn 0.820186 0.368441 -0.437660 -v 0.071604 0.031461 0.257172 -vn 0.879832 0.369132 -0.299396 -v 0.071238 0.031461 0.256337 -vn 0.916425 0.367226 -0.159096 -v 0.071014 0.031461 0.255454 -vn 0.929024 0.370000 0.003702 -v 0.070939 0.031461 0.254545 -vn 0.916480 0.367738 0.157586 -v 0.071014 0.031461 0.253636 -vn 0.880381 0.368587 0.298451 -v 0.071238 0.031461 0.252753 -vn 0.815760 0.371701 0.443141 -v 0.071604 0.031461 0.251918 -vn 0.730867 0.368518 0.574481 -v 0.072103 0.031461 0.251155 -vn 0.627930 0.370018 0.684683 -v 0.072720 0.031461 0.250484 -vn 0.513872 0.367321 0.775249 -v 0.073440 0.031461 0.249924 -vn 0.369488 0.369663 0.852542 -v 0.074241 0.031461 0.249490 -vn 0.224007 0.367768 0.902534 -v 0.075104 0.031461 0.249194 -vn 0.081195 0.367930 0.926302 -v 0.076003 0.031461 0.249044 -vn -0.078601 0.371351 0.925160 -v 0.076915 0.031461 0.249044 -vn -0.232672 0.368302 0.900121 -v 0.077814 0.031461 0.249194 -vn -0.372750 0.372730 0.849782 -v 0.078676 0.031461 0.249490 -vn -0.503504 0.367482 0.781947 -v 0.079478 0.031461 0.249924 -vn -0.632683 0.369344 0.680659 -v 0.080197 0.031461 0.250484 -vn -0.736320 0.367873 0.567893 -v 0.080815 0.031461 0.251155 -vn -0.815493 0.367514 0.447108 -v 0.081313 0.031461 0.251918 -vn -0.879090 0.371004 0.299260 -v 0.081680 0.031461 0.252753 -vn -0.917871 0.368081 0.148424 -v 0.081903 0.031461 0.253636 -vn -0.927937 0.372738 0.000002 -v 0.081979 0.031461 0.254545 -vn -0.981295 -0.101227 0.163746 -v 0.081937 0.031700 0.253631 -vn -0.940959 -0.101233 0.323030 -v 0.081712 0.031700 0.252742 -vn -0.874954 -0.101242 0.473503 -v 0.081344 0.031700 0.251902 -vn -0.785087 -0.101232 0.611057 -v 0.080842 0.031700 0.251134 -vn -0.673800 -0.101248 0.731944 -v 0.080221 0.031700 0.250459 -vn -0.544146 -0.101206 0.832864 -v 0.079497 0.031700 0.249895 -vn -0.399635 -0.101247 0.911066 -v 0.078690 0.031700 0.249459 -vn -0.244222 -0.101266 0.964417 -v 0.077822 0.031700 0.249161 -vn -0.082152 -0.101273 0.991461 -v 0.076917 0.031700 0.249010 -vn 0.082151 -0.101270 0.991461 -v 0.076000 0.031700 0.249010 -vn 0.244226 -0.101267 0.964416 -v 0.075095 0.031700 0.249161 -vn 0.399637 -0.101247 0.911065 -v 0.074228 0.031700 0.249459 -vn 0.544137 -0.101212 0.832869 -v 0.073421 0.031700 0.249895 -vn 0.673806 -0.101243 0.731940 -v 0.072697 0.031700 0.250459 -vn 0.785085 -0.101232 0.611060 -v 0.072076 0.031700 0.251134 -vn 0.874955 -0.101247 0.473500 -v 0.071574 0.031700 0.251902 -vn 0.940959 -0.101233 0.323030 -v 0.071205 0.031700 0.252742 -vn 0.981295 -0.101228 0.163746 -v 0.070980 0.031700 0.253631 -vn 0.994863 -0.101226 0.000002 -v 0.070904 0.031700 0.254545 -vn 0.981295 -0.101227 -0.163745 -v 0.070980 0.031700 0.255459 -vn 0.940959 -0.101233 -0.323030 -v 0.071205 0.031700 0.256349 -vn 0.874954 -0.101242 -0.473503 -v 0.071574 0.031700 0.257189 -vn 0.785087 -0.101232 -0.611057 -v 0.072076 0.031700 0.257957 -vn 0.673801 -0.101249 -0.731944 -v 0.072697 0.031700 0.258631 -vn 0.544144 -0.101214 -0.832864 -v 0.073421 0.031700 0.259195 -vn 0.399630 -0.101237 -0.911069 -v 0.074228 0.031700 0.259632 -vn 0.244231 -0.101212 -0.964421 -v 0.075095 0.031700 0.259929 -vn 0.082151 -0.101272 -0.991461 -v 0.076000 0.031700 0.260080 -vn -0.082159 -0.101266 -0.991461 -v 0.076917 0.031700 0.260080 -vn -0.244218 -0.101214 -0.964424 -v 0.077822 0.031700 0.259929 -vn -0.399638 -0.101251 -0.911064 -v 0.078690 0.031700 0.259632 -vn -0.544137 -0.101205 -0.832870 -v 0.079497 0.031700 0.259195 -vn -0.673806 -0.101243 -0.731940 -v 0.080221 0.031700 0.258631 -vn -0.785085 -0.101232 -0.611060 -v 0.080842 0.031700 0.257957 -vn -0.874955 -0.101247 -0.473500 -v 0.081344 0.031700 0.257189 -vn -0.940959 -0.101233 -0.323030 -v 0.081712 0.031700 0.256349 -vn -0.981295 -0.101228 -0.163745 -v 0.081937 0.031700 0.255459 -vn -0.994863 -0.101226 0.000001 -v 0.082013 0.031700 0.254545 -vn -0.822313 -0.552242 0.137224 -v 0.081856 0.031928 0.253644 -vn -0.788511 -0.552242 0.270701 -v 0.081634 0.031928 0.252768 -vn -0.733203 -0.552241 0.396791 -v 0.081271 0.031928 0.251941 -vn -0.657899 -0.552236 0.512059 -v 0.080777 0.031928 0.251184 -vn -0.564641 -0.552241 0.613360 -v 0.080165 0.031928 0.250519 -vn -0.455985 -0.552234 0.697936 -v 0.079452 0.031928 0.249964 -vn -0.334882 -0.552249 0.763463 -v 0.078657 0.031928 0.249534 -vn -0.204655 -0.552250 0.808168 -v 0.077802 0.031928 0.249241 -vn -0.068843 -0.552238 0.830839 -v 0.076911 0.031928 0.249092 -vn 0.068843 -0.552239 0.830839 -v 0.076007 0.031928 0.249092 -vn 0.204657 -0.552250 0.808168 -v 0.075115 0.031928 0.249241 -vn 0.334886 -0.552240 0.763467 -v 0.074261 0.031928 0.249534 -vn 0.455983 -0.552231 0.697940 -v 0.073466 0.031928 0.249964 -vn 0.564641 -0.552247 0.613355 -v 0.072753 0.031928 0.250519 -vn 0.657898 -0.552236 0.512060 -v 0.072141 0.031928 0.251184 -vn 0.733206 -0.552237 0.396792 -v 0.071646 0.031928 0.251941 -vn 0.788512 -0.552240 0.270702 -v 0.071283 0.031928 0.252768 -vn 0.822313 -0.552242 0.137223 -v 0.071062 0.031928 0.253644 -vn 0.833687 -0.552237 0.000002 -v 0.070987 0.031928 0.254545 -vn 0.822313 -0.552242 -0.137222 -v 0.071062 0.031928 0.255446 -vn 0.788511 -0.552242 -0.270701 -v 0.071283 0.031928 0.256322 -vn 0.733203 -0.552241 -0.396791 -v 0.071646 0.031928 0.257149 -vn 0.657887 -0.552254 -0.512055 -v 0.072141 0.031928 0.257906 -vn 0.564642 -0.552243 -0.613357 -v 0.072753 0.031928 0.258571 -vn 0.455988 -0.552230 -0.697938 -v 0.073466 0.031928 0.259126 -vn 0.334884 -0.552247 -0.763463 -v 0.074261 0.031928 0.259556 -vn 0.204653 -0.552253 -0.808167 -v 0.075115 0.031928 0.259849 -vn 0.068845 -0.552238 -0.830839 -v 0.076007 0.031928 0.259998 -vn -0.068841 -0.552239 -0.830839 -v 0.076911 0.031928 0.259998 -vn -0.204658 -0.552247 -0.808170 -v 0.077802 0.031928 0.259849 -vn -0.334885 -0.552242 -0.763467 -v 0.078657 0.031928 0.259556 -vn -0.455982 -0.552235 -0.697937 -v 0.079452 0.031928 0.259126 -vn -0.564640 -0.552247 -0.613355 -v 0.080165 0.031928 0.258571 -vn -0.657889 -0.552254 -0.512052 -v 0.080777 0.031928 0.257906 -vn -0.733204 -0.552238 -0.396794 -v 0.081271 0.031928 0.257149 -vn -0.788512 -0.552240 -0.270702 -v 0.081634 0.031928 0.256322 -vn -0.822313 -0.552242 -0.137222 -v 0.081856 0.031928 0.255446 -vn -0.833687 -0.552237 0.000000 -v 0.081931 0.031928 0.254545 -vn -0.473337 -0.877333 0.078984 -v 0.081678 0.032090 0.253674 -vn -0.453873 -0.877337 0.155816 -v 0.081464 0.032090 0.252827 -vn -0.422050 -0.877329 0.228402 -v 0.081113 0.032090 0.252026 -vn -0.378712 -0.877321 0.294763 -v 0.080635 0.032090 0.251295 -vn -0.325020 -0.877329 0.353067 -v 0.080043 0.032090 0.250652 -vn -0.262461 -0.877341 0.401731 -v 0.079353 0.032090 0.250115 -vn -0.192767 -0.877333 0.439463 -v 0.078584 0.032090 0.249699 -vn -0.117813 -0.877321 0.465219 -v 0.077758 0.032090 0.249415 -vn -0.039628 -0.877324 0.478260 -v 0.076896 0.032090 0.249271 -vn 0.039629 -0.877324 0.478259 -v 0.076022 0.032090 0.249271 -vn 0.117808 -0.877322 0.465217 -v 0.075160 0.032090 0.249415 -vn 0.192765 -0.877337 0.439456 -v 0.074333 0.032090 0.249699 -vn 0.262469 -0.877337 0.401733 -v 0.073564 0.032090 0.250115 -vn 0.325022 -0.877327 0.353070 -v 0.072875 0.032090 0.250652 -vn 0.378712 -0.877319 0.294768 -v 0.072283 0.032090 0.251295 -vn 0.422048 -0.877330 0.228401 -v 0.071805 0.032090 0.252026 -vn 0.453875 -0.877336 0.155815 -v 0.071453 0.032090 0.252827 -vn 0.473337 -0.877333 0.078985 -v 0.071239 0.032090 0.253674 -vn 0.479880 -0.877334 0.000000 -v 0.071167 0.032090 0.254545 -vn 0.473338 -0.877333 -0.078984 -v 0.071239 0.032090 0.255416 -vn 0.453876 -0.877336 -0.155817 -v 0.071453 0.032090 0.256263 -vn 0.422048 -0.877330 -0.228403 -v 0.071805 0.032090 0.257064 -vn 0.378695 -0.877333 -0.294750 -v 0.072283 0.032090 0.257795 -vn 0.325025 -0.877328 -0.353064 -v 0.072875 0.032090 0.258438 -vn 0.262465 -0.877338 -0.401734 -v 0.073564 0.032090 0.258975 -vn 0.192764 -0.877335 -0.439460 -v 0.074333 0.032090 0.259391 -vn 0.117808 -0.877327 -0.465209 -v 0.075160 0.032090 0.259675 -vn 0.039629 -0.877325 -0.478258 -v 0.076022 0.032090 0.259819 -vn -0.039629 -0.877324 -0.478259 -v 0.076896 0.032090 0.259819 -vn -0.117807 -0.877328 -0.465206 -v 0.077758 0.032090 0.259675 -vn -0.192765 -0.877336 -0.439459 -v 0.078584 0.032090 0.259391 -vn -0.262466 -0.877340 -0.401729 -v 0.079353 0.032090 0.258975 -vn -0.325022 -0.877327 -0.353069 -v 0.080043 0.032090 0.258438 -vn -0.378695 -0.877334 -0.294747 -v 0.080635 0.032090 0.257795 -vn -0.422046 -0.877330 -0.228405 -v 0.081113 0.032090 0.257064 -vn -0.453873 -0.877338 -0.155813 -v 0.081464 0.032090 0.256263 -vn -0.473337 -0.877333 -0.078985 -v 0.081678 0.032090 0.255416 -vn -0.479880 -0.877334 0.000001 -v 0.081751 0.032090 0.254545 -vn -0.126601 -0.991729 0.021126 -v 0.081447 0.032149 0.253713 -vn -0.121396 -0.991729 0.041675 -v 0.081242 0.032149 0.252903 -vn -0.112880 -0.991729 0.061086 -v 0.080906 0.032149 0.252138 -vn -0.101287 -0.991729 0.078835 -v 0.080449 0.032149 0.251439 -vn -0.086934 -0.991728 0.094436 -v 0.079884 0.032149 0.250825 -vn -0.070204 -0.991728 0.107456 -v 0.079225 0.032149 0.250312 -vn -0.051560 -0.991728 0.117544 -v 0.078490 0.032149 0.249914 -vn -0.031510 -0.991728 0.124428 -v 0.077700 0.032149 0.249643 -vn -0.010597 -0.991730 0.127906 -v 0.076876 0.032149 0.249505 -vn 0.010598 -0.991729 0.127907 -v 0.076041 0.032149 0.249505 -vn 0.031509 -0.991728 0.124429 -v 0.075217 0.032149 0.249643 -vn 0.051560 -0.991728 0.117544 -v 0.074427 0.032149 0.249914 -vn 0.070204 -0.991728 0.107456 -v 0.073693 0.032149 0.250312 -vn 0.086933 -0.991728 0.094436 -v 0.073034 0.032149 0.250825 -vn 0.101289 -0.991728 0.078836 -v 0.072468 0.032149 0.251439 -vn 0.112880 -0.991729 0.061085 -v 0.072011 0.032149 0.252138 -vn 0.121399 -0.991728 0.041677 -v 0.071676 0.032149 0.252903 -vn 0.126601 -0.991729 0.021126 -v 0.071471 0.032149 0.253713 -vn 0.128352 -0.991729 0.000000 -v 0.071402 0.032149 0.254545 -vn 0.126601 -0.991729 -0.021126 -v 0.071471 0.032149 0.255377 -vn 0.121400 -0.991728 -0.041676 -v 0.071676 0.032149 0.256187 -vn 0.112879 -0.991729 -0.061088 -v 0.072011 0.032149 0.256952 -vn 0.101289 -0.991729 -0.078835 -v 0.072468 0.032149 0.257651 -vn 0.086935 -0.991728 -0.094435 -v 0.073034 0.032149 0.258266 -vn 0.070204 -0.991728 -0.107456 -v 0.073693 0.032149 0.258779 -vn 0.051560 -0.991728 -0.117544 -v 0.074427 0.032149 0.259176 -vn 0.031505 -0.991730 -0.124413 -v 0.075217 0.032149 0.259447 -vn 0.010600 -0.991729 -0.127908 -v 0.076041 0.032149 0.259585 -vn -0.010599 -0.991729 -0.127907 -v 0.076876 0.032149 0.259585 -vn -0.031507 -0.991730 -0.124413 -v 0.077700 0.032149 0.259447 -vn -0.051559 -0.991728 -0.117546 -v 0.078490 0.032149 0.259176 -vn -0.070204 -0.991728 -0.107456 -v 0.079225 0.032149 0.258779 -vn -0.086934 -0.991728 -0.094436 -v 0.079884 0.032149 0.258266 -vn -0.101286 -0.991729 -0.078833 -v 0.080449 0.032149 0.257651 -vn -0.112880 -0.991729 -0.061087 -v 0.080906 0.032149 0.256952 -vn -0.121396 -0.991729 -0.041675 -v 0.081242 0.032149 0.256187 -vn -0.126601 -0.991729 -0.021126 -v 0.081447 0.032149 0.255377 -vn -0.128352 -0.991729 0.000000 -v 0.081516 0.032149 0.254545 -vn 0.318954 -0.937620 -0.138338 -v 0.074657 0.032149 0.255291 -vn 0.348364 -0.937322 -0.008371 -v 0.074509 0.032149 0.254545 -vn -0.138425 -0.936185 0.323103 -v 0.077205 0.032149 0.252743 -vn -0.004103 -0.935431 0.353486 -v 0.076459 0.032149 0.252595 -vn 0.132557 -0.934917 0.329180 -v 0.075712 0.032149 0.252743 -vn 0.249739 -0.934590 0.253323 -v 0.075080 0.032149 0.253166 -vn 0.241974 -0.937473 -0.250188 -v 0.075080 0.032149 0.255924 -vn 0.128049 -0.937431 -0.323768 -v 0.075712 0.032149 0.256347 -vn -0.005074 -0.937531 -0.347866 -v 0.076459 0.032149 0.256495 -vn -0.136732 -0.937808 -0.319094 -v 0.077205 0.032149 0.256347 -vn -0.319418 -0.938765 0.129200 -v 0.078260 0.032149 0.253799 -vn -0.249196 -0.937267 0.243786 -v 0.077838 0.032149 0.253166 -vn 0.328563 -0.934415 0.137535 -v 0.074657 0.032149 0.253799 -vn -0.246603 -0.938325 -0.242349 -v 0.077838 0.032149 0.255924 -vn -0.340449 -0.940263 0.000001 -v 0.078409 0.032149 0.254545 -vn -0.317980 -0.939139 -0.130028 -v 0.078260 0.032149 0.255291 -vn 0.843142 -0.383368 -0.377017 -v 0.074842 0.032349 0.255215 -vn 0.789312 -0.325855 -0.520389 -v 0.075043 0.032349 0.255574 -vn 0.626920 -0.384644 -0.677510 -v 0.075221 0.032349 0.255782 -vn 0.514808 -0.339807 -0.787086 -v 0.075584 0.032349 0.256061 -vn 0.310186 -0.385925 -0.868819 -v 0.075789 0.032349 0.256162 -vn 0.158426 -0.352646 -0.922248 -v 0.076276 0.032349 0.256285 -vn -0.055947 -0.387188 -0.920302 -v 0.076459 0.032349 0.256295 -vn -0.220933 -0.364190 -0.904740 -v 0.076999 0.032349 0.256209 -vn -0.412738 -0.388424 -0.823878 -v 0.077128 0.032349 0.256162 -vn -0.560845 -0.374361 -0.738449 -v 0.077630 0.032349 0.255846 -vn -0.702750 -0.389652 -0.595243 -v 0.077696 0.032349 0.255782 -vn -0.805788 -0.383029 -0.451657 -v 0.078057 0.032349 0.255257 -vn -0.879549 -0.390882 -0.271303 -v 0.078075 0.032349 0.255215 -vn -0.916260 -0.400584 0.000004 -v 0.078209 0.032349 0.254545 -vn -0.879547 -0.390882 0.271307 -v 0.078075 0.032349 0.253875 -vn -0.806275 -0.385087 0.449031 -v 0.078057 0.032349 0.253833 -vn -0.700817 -0.391164 0.596528 -v 0.077696 0.032349 0.253308 -vn -0.563993 -0.379767 0.733273 -v 0.077630 0.032349 0.253245 -vn -0.408179 -0.391420 0.824730 -v 0.077128 0.032349 0.252928 -vn -0.228897 -0.374564 0.898503 -v 0.076999 0.032349 0.252881 -vn -0.049169 -0.391634 0.918806 -v 0.076459 0.032349 0.252795 -vn 0.144342 -0.369883 0.917797 -v 0.076276 0.032349 0.252805 -vn 0.317699 -0.391785 0.863465 -v 0.075789 0.032349 0.252928 -vn 0.494864 -0.366057 0.788106 -v 0.075584 0.032349 0.253029 -vn 0.632932 -0.391892 0.667697 -v 0.075221 0.032349 0.253308 -vn 0.765818 -0.363380 0.530545 -v 0.075043 0.032349 0.253516 -vn 0.845166 -0.391968 0.363395 -v 0.074842 0.032349 0.253875 -vn 0.913237 -0.362007 0.186948 -v 0.074747 0.032349 0.254181 -vn 0.924002 -0.382073 -0.015506 -v 0.074709 0.032349 0.254545 -vn 0.936026 -0.310816 -0.165074 -v 0.074747 0.032349 0.254909 -vn -0.879548 0.390883 -0.271303 -v 0.078075 0.033449 0.255215 -vn -0.916260 0.400584 0.000004 -v 0.078209 0.033449 0.254545 -vn -0.879548 0.390882 0.271307 -v 0.078075 0.033449 0.253875 -vn -0.805788 0.383029 0.451657 -v 0.078057 0.033449 0.253833 -vn -0.702750 0.389652 0.595243 -v 0.077696 0.033449 0.253308 -vn -0.560845 0.374361 0.738449 -v 0.077630 0.033449 0.253245 -vn -0.412738 0.388424 0.823878 -v 0.077128 0.033449 0.252928 -vn -0.220933 0.364190 0.904740 -v 0.076999 0.033449 0.252881 -vn -0.055947 0.387188 0.920302 -v 0.076459 0.033449 0.252795 -vn 0.158426 0.352646 0.922249 -v 0.076276 0.033449 0.252805 -vn 0.310186 0.385925 0.868819 -v 0.075789 0.033449 0.252928 -vn 0.514808 0.339807 0.787086 -v 0.075584 0.033449 0.253029 -vn 0.626920 0.384644 0.677510 -v 0.075221 0.033449 0.253308 -vn 0.789312 0.325855 0.520389 -v 0.075043 0.033449 0.253516 -vn 0.843142 0.383368 0.377017 -v 0.074842 0.033449 0.253875 -vn 0.936023 0.310820 0.165079 -v 0.074747 0.033449 0.254181 -vn 0.924002 0.382073 0.015514 -v 0.074709 0.033449 0.254545 -vn 0.913239 0.362004 -0.186944 -v 0.074747 0.033449 0.254909 -vn 0.845166 0.391968 -0.363395 -v 0.074842 0.033449 0.255215 -vn 0.765818 0.363380 -0.530545 -v 0.075043 0.033449 0.255574 -vn 0.632932 0.391892 -0.667697 -v 0.075221 0.033449 0.255782 -vn 0.494864 0.366057 -0.788106 -v 0.075584 0.033449 0.256061 -vn 0.317699 0.391785 -0.863465 -v 0.075789 0.033449 0.256162 -vn 0.144342 0.369883 -0.917797 -v 0.076276 0.033449 0.256285 -vn -0.049169 0.391634 -0.918806 -v 0.076459 0.033449 0.256295 -vn -0.228897 0.374564 -0.898503 -v 0.076999 0.033449 0.256209 -vn -0.408179 0.391420 -0.824730 -v 0.077128 0.033449 0.256162 -vn -0.563993 0.379767 -0.733273 -v 0.077630 0.033449 0.255846 -vn -0.700817 0.391164 -0.596528 -v 0.077696 0.033449 0.255782 -vn -0.806275 0.385087 -0.449031 -v 0.078057 0.033449 0.255257 -vn -0.249196 0.937267 -0.243786 -v 0.077838 0.033649 0.255924 -vn -0.319417 0.938765 -0.129198 -v 0.078260 0.033649 0.255291 -vn -0.138425 0.936185 -0.323104 -v 0.077205 0.033649 0.256347 -vn -0.004103 0.935431 -0.353486 -v 0.076459 0.033649 0.256495 -vn 0.132557 0.934917 -0.329180 -v 0.075712 0.033649 0.256347 -vn 0.249739 0.934590 -0.253323 -v 0.075080 0.033649 0.255924 -vn 0.328563 0.934415 -0.137535 -v 0.074657 0.033649 0.255291 -vn 0.348364 0.937322 0.008374 -v 0.074509 0.033649 0.254545 -vn 0.318954 0.937620 0.138339 -v 0.074657 0.033649 0.253799 -vn 0.241974 0.937473 0.250188 -v 0.075080 0.033649 0.253166 -vn 0.128049 0.937431 0.323768 -v 0.075712 0.033649 0.252743 -vn -0.005074 0.937531 0.347866 -v 0.076459 0.033649 0.252595 -vn -0.136732 0.937808 0.319094 -v 0.077205 0.033649 0.252743 -vn -0.246603 0.938325 0.242349 -v 0.077838 0.033649 0.253166 -vn -0.317980 0.939139 0.130029 -v 0.078260 0.033649 0.253799 -vn -0.340449 0.940263 0.000001 -v 0.078409 0.033649 0.254545 -vn -0.243568 0.910104 -0.335239 -v 0.078105 0.033649 0.256810 -vn -0.335230 0.910111 -0.243555 -v 0.078724 0.033649 0.256191 -vn -0.394089 0.910109 -0.128047 -v 0.079122 0.033649 0.255410 -vn -0.414381 0.910104 0.000003 -v 0.079259 0.033649 0.254545 -vn 0.335231 0.910112 -0.243552 -v 0.074193 0.033649 0.256191 -vn 0.243566 0.910105 -0.335238 -v 0.074813 0.033649 0.256810 -vn 0.128050 0.910099 -0.394111 -v 0.075593 0.033649 0.257208 -vn 0.000003 0.910108 -0.414371 -v 0.076459 0.033649 0.257345 -vn -0.128052 0.910101 -0.394106 -v 0.077324 0.033649 0.257208 -vn 0.243568 0.910104 0.335239 -v 0.074813 0.033649 0.252280 -vn 0.335230 0.910111 0.243555 -v 0.074193 0.033649 0.252899 -vn 0.394088 0.910109 0.128048 -v 0.073796 0.033649 0.253680 -vn 0.414381 0.910104 -0.000000 -v 0.073659 0.033649 0.254545 -vn 0.394091 0.910108 -0.128046 -v 0.073796 0.033649 0.255410 -vn -0.394090 0.910108 0.128047 -v 0.079122 0.033649 0.253680 -vn -0.335231 0.910112 0.243552 -v 0.078724 0.033649 0.252899 -vn -0.243566 0.910105 0.335239 -v 0.078105 0.033649 0.252280 -vn -0.128048 0.910100 0.394108 -v 0.077324 0.033649 0.251882 -vn -0.000003 0.910108 0.414370 -v 0.076459 0.033649 0.251745 -vn 0.128055 0.910099 0.394108 -v 0.075593 0.033649 0.251882 -vn -0.883395 0.370592 0.286835 -v 0.079312 0.033849 0.253618 -vn -0.751364 0.371049 0.545688 -v 0.078886 0.033849 0.252782 -vn -0.545852 0.371438 0.751052 -v 0.078222 0.033849 0.252118 -vn -0.286983 0.371780 0.882848 -v 0.077386 0.033849 0.251692 -vn -0.000105 0.372085 0.928199 -v 0.076459 0.033849 0.251545 -vn 0.286725 0.372313 0.882707 -v 0.075532 0.033849 0.251692 -vn 0.545434 0.372511 0.750824 -v 0.074695 0.033849 0.252118 -vn 0.750721 0.372655 0.545479 -v 0.074032 0.033849 0.252782 -vn 0.882517 0.372730 0.286770 -v 0.073606 0.033849 0.253618 -vn 0.927932 0.372749 0.000001 -v 0.073459 0.033849 0.254545 -vn 0.882517 0.372730 -0.286767 -v 0.073606 0.033849 0.255472 -vn 0.750722 0.372654 -0.545477 -v 0.074032 0.033849 0.256308 -vn 0.545434 0.372508 -0.750826 -v 0.074695 0.033849 0.256972 -vn 0.286722 0.372312 -0.882708 -v 0.075532 0.033849 0.257398 -vn -0.000101 0.372085 -0.928199 -v 0.076459 0.033849 0.257545 -vn -0.286987 0.371779 -0.882847 -v 0.077386 0.033849 0.257398 -vn -0.545853 0.371440 -0.751051 -v 0.078222 0.033849 0.256972 -vn -0.751362 0.371050 -0.545689 -v 0.078886 0.033849 0.256308 -vn -0.883396 0.370591 -0.286834 -v 0.079312 0.033849 0.255472 -vn -0.928901 0.370327 0.000003 -v 0.079459 0.033849 0.254545 -vn -0.897597 0.388995 0.207370 -v 0.079325 0.039449 0.253661 -vn -0.855520 0.383610 0.347748 -v 0.079312 0.039449 0.253618 -vn -0.793982 0.388311 0.467769 -v 0.078937 0.039449 0.252855 -vn -0.710548 0.377658 0.593713 -v 0.078886 0.039449 0.252782 -vn -0.616823 0.387607 0.685047 -v 0.078329 0.039449 0.252200 -vn -0.497284 0.370732 0.784389 -v 0.078222 0.039449 0.252118 -vn -0.382415 0.386896 0.839089 -v 0.077555 0.039449 0.251752 -vn -0.235579 0.362959 0.901534 -v 0.077386 0.039449 0.251692 -vn -0.112474 0.386180 0.915540 -v 0.076683 0.039449 0.251553 -vn 0.049984 0.354438 0.933743 -v 0.076459 0.039449 0.251545 -vn 0.168090 0.385481 0.907276 -v 0.075791 0.039449 0.251620 -vn 0.332594 0.345305 0.877580 -v 0.075532 0.039449 0.251692 -vn 0.433267 0.384726 0.815025 -v 0.074959 0.039449 0.251947 -vn 0.585586 0.335485 0.737929 -v 0.074695 0.039449 0.252118 -vn 0.658486 0.384020 0.647244 -v 0.074260 0.039449 0.252505 -vn 0.784858 0.325199 0.527489 -v 0.074032 0.039449 0.252782 -vn 0.822909 0.383266 0.419437 -v 0.073756 0.039449 0.253243 -vn 0.911376 0.314333 0.265684 -v 0.073606 0.039449 0.253618 -vn 0.911246 0.382531 0.152645 -v 0.073492 0.039449 0.254098 -vn 0.952712 0.302994 -0.023116 -v 0.073459 0.039449 0.254545 -vn 0.915281 0.381779 -0.128471 -v 0.073492 0.039449 0.254992 -vn 0.890275 0.358728 -0.280578 -v 0.073606 0.039449 0.255472 -vn 0.825117 0.389739 -0.409006 -v 0.073756 0.039449 0.255847 -vn 0.764342 0.359955 -0.534990 -v 0.074032 0.039449 0.256308 -vn 0.663081 0.389699 -0.639107 -v 0.074260 0.039449 0.256586 -vn 0.567533 0.361984 -0.739509 -v 0.074695 0.039449 0.256972 -vn 0.439094 0.389665 -0.809542 -v 0.074959 0.039449 0.257143 -vn 0.318264 0.364758 -0.875020 -v 0.075532 0.039449 0.257398 -vn 0.174125 0.389608 -0.904370 -v 0.075791 0.039449 0.257470 -vn 0.039712 0.368128 -0.928927 -v 0.076459 0.039449 0.257545 -vn -0.107167 0.389501 -0.914770 -v 0.076683 0.039449 0.257537 -vn -0.241986 0.372012 -0.896130 -v 0.077386 0.039449 0.257398 -vn -0.378438 0.389403 -0.839732 -v 0.077555 0.039449 0.257338 -vn -0.500561 0.376230 -0.779673 -v 0.078222 0.039449 0.256972 -vn -0.614421 0.389288 -0.686252 -v 0.078329 0.039449 0.256891 -vn -0.711717 0.380537 -0.590467 -v 0.078886 0.039449 0.256308 -vn -0.793020 0.389139 -0.468711 -v 0.078937 0.039449 0.256235 -vn -0.855663 0.384746 -0.346137 -v 0.079312 0.039449 0.255472 -vn -0.897620 0.388991 -0.207278 -v 0.079325 0.039449 0.255429 -vn -0.918183 0.396157 0.000000 -v 0.079459 0.039449 0.254545 -vn -0.296794 0.934128 -0.198287 -v 0.079103 0.039649 0.256348 -vn -0.338868 0.935276 -0.102116 -v 0.079517 0.039649 0.255488 -vn -0.227066 0.933282 -0.278253 -v 0.078454 0.039649 0.257047 -vn -0.135818 0.932662 -0.334208 -v 0.077628 0.039649 0.257524 -vn -0.031295 0.932218 -0.360541 -v 0.076698 0.039649 0.257736 -vn 0.076917 0.931916 -0.354424 -v 0.075747 0.039649 0.257665 -vn 0.178793 0.931694 -0.316195 -v 0.074859 0.039649 0.257316 -vn 0.264886 0.931545 -0.249118 -v 0.074113 0.039649 0.256722 -vn 0.327152 0.931459 -0.159234 -v 0.073576 0.039649 0.255933 -vn 0.354166 0.934058 -0.045850 -v 0.073294 0.039649 0.255022 -vn 0.351981 0.934148 0.058968 -v 0.073294 0.039649 0.254068 -vn 0.319247 0.933981 0.160502 -v 0.073576 0.039649 0.253157 -vn 0.257894 0.933861 0.247778 -v 0.074113 0.039649 0.252368 -vn 0.173561 0.933764 0.312989 -v 0.074859 0.039649 0.251774 -vn 0.073794 0.933754 0.350224 -v 0.075747 0.039649 0.251425 -vn -0.032285 0.933802 0.356331 -v 0.076698 0.039649 0.251354 -vn -0.135101 0.933970 0.330828 -v 0.077628 0.039649 0.251566 -vn -0.225384 0.934284 0.276253 -v 0.078454 0.039649 0.252043 -vn -0.295058 0.934785 0.197782 -v 0.079103 0.039649 0.252742 -vn -0.338042 0.935503 0.102768 -v 0.079517 0.039649 0.253602 -vn -0.350744 0.936471 0.000000 -v 0.079659 0.039649 0.254545 -vn 0.284774 0.915317 0.284778 -v 0.081974 0.039649 0.260060 -vn 0.334855 0.915320 0.223743 -v 0.082944 0.039649 0.258878 -vn 0.372070 0.915321 0.154117 -v 0.083665 0.039649 0.257530 -vn 0.394978 0.915325 0.078563 -v 0.084109 0.039649 0.256067 -vn -0.154119 0.915321 0.372069 -v 0.073474 0.039649 0.261751 -vn -0.078569 0.915323 0.394983 -v 0.074937 0.039649 0.262195 -vn 0.000000 0.915324 0.402719 -v 0.076459 0.039649 0.262345 -vn 0.078569 0.915323 0.394983 -v 0.077980 0.039649 0.262195 -vn 0.154118 0.915321 0.372069 -v 0.079444 0.039649 0.261751 -vn 0.223737 0.915325 0.334847 -v 0.080792 0.039649 0.261030 -vn -0.334855 0.915320 0.223744 -v 0.069973 0.039649 0.258878 -vn -0.284775 0.915317 0.284776 -v 0.070943 0.039649 0.260060 -vn -0.223738 0.915323 0.334852 -v 0.072125 0.039649 0.261030 -vn -0.402719 0.915324 0.000000 -v 0.068659 0.039649 0.254545 -vn -0.394987 0.915321 0.078565 -v 0.068809 0.039649 0.256067 -vn -0.372071 0.915320 0.154117 -v 0.069252 0.039649 0.257530 -vn 0.078564 0.915324 -0.394982 -v 0.077980 0.039649 0.246895 -vn -0.000000 0.915324 -0.402719 -v 0.076459 0.039649 0.246745 -vn 0.284775 0.915317 -0.284776 -v 0.081974 0.039649 0.249030 -vn 0.223754 0.915312 -0.334870 -v 0.080792 0.039649 0.248060 -vn 0.154116 0.915320 -0.372072 -v 0.079444 0.039649 0.247339 -vn 0.402719 0.915324 -0.000000 -v 0.084259 0.039649 0.254545 -vn 0.394978 0.915325 -0.078565 -v 0.084109 0.039649 0.253023 -vn 0.372071 0.915320 -0.154116 -v 0.083665 0.039649 0.251560 -vn 0.334855 0.915320 -0.223744 -v 0.082944 0.039649 0.250212 -vn -0.334855 0.915320 -0.223743 -v 0.069973 0.039649 0.250212 -vn -0.372070 0.915321 -0.154117 -v 0.069252 0.039649 0.251560 -vn -0.394986 0.915321 -0.078566 -v 0.068809 0.039649 0.253023 -vn -0.078565 0.915323 -0.394982 -v 0.074937 0.039649 0.246895 -vn -0.154118 0.915319 -0.372073 -v 0.073474 0.039649 0.247339 -vn -0.223755 0.915309 -0.334876 -v 0.072125 0.039649 0.248060 -vn -0.284775 0.915318 -0.284774 -v 0.070943 0.039649 0.249030 -vn -0.926246 0.376921 -0.000000 -v 0.068459 0.039449 0.254545 -vn -0.908449 0.376916 -0.180706 -v 0.068612 0.039449 0.252984 -vn -0.855742 0.376914 -0.354460 -v 0.069068 0.039449 0.251484 -vn -0.770149 0.376913 -0.514594 -v 0.069807 0.039449 0.250100 -vn -0.654958 0.376907 -0.654958 -v 0.070802 0.039449 0.248888 -vn -0.514603 0.376892 -0.770153 -v 0.072014 0.039449 0.247893 -vn -0.354462 0.376912 -0.855742 -v 0.073397 0.039449 0.247154 -vn -0.180698 0.376919 -0.908449 -v 0.074898 0.039449 0.246699 -vn -0.000000 0.376920 -0.926246 -v 0.076459 0.039449 0.246545 -vn 0.180698 0.376918 -0.908450 -v 0.078019 0.039449 0.246699 -vn 0.354461 0.376911 -0.855743 -v 0.079520 0.039449 0.247154 -vn 0.514605 0.376896 -0.770150 -v 0.080903 0.039449 0.247893 -vn 0.654957 0.376909 -0.654959 -v 0.082116 0.039449 0.248888 -vn 0.770149 0.376913 -0.514594 -v 0.083110 0.039449 0.250100 -vn 0.855742 0.376915 -0.354459 -v 0.083850 0.039449 0.251484 -vn 0.908446 0.376924 -0.180705 -v 0.084305 0.039449 0.252984 -vn 0.926246 0.376921 -0.000001 -v 0.084459 0.039449 0.254545 -vn 0.908447 0.376923 0.180703 -v 0.084305 0.039449 0.256106 -vn 0.855742 0.376914 0.354460 -v 0.083850 0.039449 0.257607 -vn 0.770149 0.376913 0.514594 -v 0.083110 0.039449 0.258990 -vn 0.654956 0.376909 0.654960 -v 0.082116 0.039449 0.260202 -vn 0.514592 0.376922 0.770146 -v 0.080903 0.039449 0.261197 -vn 0.354462 0.376914 0.855741 -v 0.079520 0.039449 0.261936 -vn 0.180706 0.376919 0.908448 -v 0.078019 0.039449 0.262391 -vn 0.000000 0.376920 0.926246 -v 0.076459 0.039449 0.262545 -vn -0.180706 0.376918 0.908448 -v 0.074898 0.039449 0.262391 -vn -0.354463 0.376915 0.855740 -v 0.073397 0.039449 0.261936 -vn -0.514591 0.376918 0.770149 -v 0.072014 0.039449 0.261197 -vn -0.654957 0.376909 0.654959 -v 0.070802 0.039449 0.260202 -vn -0.770149 0.376913 0.514594 -v 0.069807 0.039449 0.258990 -vn -0.855742 0.376914 0.354460 -v 0.069068 0.039449 0.257607 -vn -0.908449 0.376916 0.180705 -v 0.068612 0.039449 0.256106 -# 2896 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 1//1 -f 1//1 128//128 2//2 -f 128//128 129//129 2//2 -f 2//2 129//129 130//130 -f 2//2 130//130 4//4 -f 4//4 130//130 131//131 -f 4//4 131//131 6//6 -f 6//6 131//131 132//132 -f 6//6 132//132 8//8 -f 8//8 132//132 133//133 -f 8//8 133//133 10//10 -f 10//10 133//133 134//134 -f 10//10 134//134 12//12 -f 12//12 134//134 135//135 -f 12//12 135//135 14//14 -f 14//14 135//135 136//136 -f 14//14 136//136 16//16 -f 16//16 136//136 137//137 -f 16//16 137//137 18//18 -f 18//18 137//137 138//138 -f 18//18 138//138 20//20 -f 20//20 138//138 139//139 -f 20//20 139//139 22//22 -f 22//22 139//139 140//140 -f 22//22 140//140 24//24 -f 24//24 140//140 141//141 -f 24//24 141//141 26//26 -f 26//26 141//141 142//142 -f 26//26 142//142 28//28 -f 28//28 142//142 143//143 -f 28//28 143//143 30//30 -f 30//30 143//143 144//144 -f 30//30 144//144 32//32 -f 32//32 144//144 145//145 -f 32//32 145//145 34//34 -f 34//34 145//145 146//146 -f 34//34 146//146 36//36 -f 36//36 146//146 147//147 -f 36//36 147//147 38//38 -f 38//38 147//147 148//148 -f 38//38 148//148 40//40 -f 40//40 148//148 149//149 -f 40//40 149//149 42//42 -f 42//42 149//149 150//150 -f 42//42 150//150 44//44 -f 44//44 150//150 151//151 -f 44//44 151//151 46//46 -f 46//46 151//151 152//152 -f 46//46 152//152 48//48 -f 48//48 152//152 153//153 -f 48//48 153//153 50//50 -f 50//50 153//153 154//154 -f 50//50 154//154 52//52 -f 52//52 154//154 155//155 -f 52//52 155//155 54//54 -f 54//54 155//155 156//156 -f 54//54 156//156 56//56 -f 56//56 156//156 157//157 -f 56//56 157//157 58//58 -f 58//58 157//157 158//158 -f 58//58 158//158 60//60 -f 60//60 158//158 159//159 -f 60//60 159//159 62//62 -f 62//62 159//159 160//160 -f 62//62 160//160 64//64 -f 64//64 160//160 161//161 -f 64//64 161//161 66//66 -f 66//66 161//161 162//162 -f 66//66 162//162 68//68 -f 68//68 162//162 163//163 -f 68//68 163//163 70//70 -f 70//70 163//163 164//164 -f 70//70 164//164 72//72 -f 72//72 164//164 165//165 -f 72//72 165//165 74//74 -f 74//74 165//165 166//166 -f 74//74 166//166 76//76 -f 76//76 166//166 167//167 -f 76//76 167//167 78//78 -f 78//78 167//167 168//168 -f 78//78 168//168 80//80 -f 80//80 168//168 169//169 -f 80//80 169//169 82//82 -f 82//82 169//169 170//170 -f 82//82 170//170 84//84 -f 84//84 170//170 171//171 -f 84//84 171//171 86//86 -f 86//86 171//171 172//172 -f 86//86 172//172 88//88 -f 88//88 172//172 173//173 -f 88//88 173//173 90//90 -f 90//90 173//173 174//174 -f 90//90 174//174 92//92 -f 92//92 174//174 175//175 -f 92//92 175//175 94//94 -f 94//94 175//175 176//176 -f 94//94 176//176 96//96 -f 96//96 176//176 177//177 -f 96//96 177//177 98//98 -f 98//98 177//177 178//178 -f 98//98 178//178 100//100 -f 100//100 178//178 179//179 -f 100//100 179//179 102//102 -f 102//102 179//179 180//180 -f 102//102 180//180 104//104 -f 104//104 180//180 181//181 -f 104//104 181//181 106//106 -f 106//106 181//181 182//182 -f 106//106 182//182 108//108 -f 108//108 182//182 183//183 -f 108//108 183//183 110//110 -f 110//110 183//183 184//184 -f 110//110 184//184 112//112 -f 112//112 184//184 185//185 -f 112//112 185//185 114//114 -f 114//114 185//185 186//186 -f 114//114 186//186 116//116 -f 116//116 186//186 187//187 -f 116//116 187//187 118//118 -f 118//118 187//187 188//188 -f 118//118 188//188 120//120 -f 120//120 188//188 189//189 -f 120//120 189//189 122//122 -f 122//122 189//189 190//190 -f 122//122 190//190 124//124 -f 124//124 190//190 191//191 -f 124//124 191//191 126//126 -f 126//126 191//191 192//192 -f 126//126 192//192 128//128 -f 128//128 192//192 129//129 -f 192//192 193//193 129//129 -f 129//129 193//193 194//194 -f 129//129 194//194 130//130 -f 130//130 194//194 195//195 -f 130//130 195//195 131//131 -f 131//131 195//195 196//196 -f 131//131 196//196 132//132 -f 132//132 196//196 197//197 -f 132//132 197//197 133//133 -f 133//133 197//197 198//198 -f 133//133 198//198 134//134 -f 134//134 198//198 199//199 -f 134//134 199//199 135//135 -f 135//135 199//199 200//200 -f 135//135 200//200 136//136 -f 136//136 200//200 201//201 -f 136//136 201//201 137//137 -f 137//137 201//201 202//202 -f 137//137 202//202 138//138 -f 138//138 202//202 203//203 -f 138//138 203//203 139//139 -f 139//139 203//203 204//204 -f 139//139 204//204 140//140 -f 140//140 204//204 205//205 -f 140//140 205//205 141//141 -f 141//141 205//205 206//206 -f 141//141 206//206 142//142 -f 142//142 206//206 207//207 -f 142//142 207//207 143//143 -f 143//143 207//207 208//208 -f 143//143 208//208 144//144 -f 144//144 208//208 209//209 -f 144//144 209//209 145//145 -f 145//145 209//209 210//210 -f 145//145 210//210 146//146 -f 146//146 210//210 211//211 -f 146//146 211//211 147//147 -f 147//147 211//211 212//212 -f 147//147 212//212 148//148 -f 148//148 212//212 213//213 -f 148//148 213//213 149//149 -f 149//149 213//213 214//214 -f 149//149 214//214 150//150 -f 150//150 214//214 215//215 -f 150//150 215//215 151//151 -f 151//151 215//215 216//216 -f 151//151 216//216 152//152 -f 152//152 216//216 217//217 -f 152//152 217//217 153//153 -f 153//153 217//217 218//218 -f 153//153 218//218 154//154 -f 154//154 218//218 219//219 -f 154//154 219//219 155//155 -f 155//155 219//219 220//220 -f 155//155 220//220 156//156 -f 156//156 220//220 221//221 -f 156//156 221//221 157//157 -f 157//157 221//221 222//222 -f 157//157 222//222 158//158 -f 158//158 222//222 223//223 -f 158//158 223//223 159//159 -f 159//159 223//223 224//224 -f 159//159 224//224 160//160 -f 160//160 224//224 225//225 -f 160//160 225//225 161//161 -f 161//161 225//225 226//226 -f 161//161 226//226 162//162 -f 162//162 226//226 227//227 -f 162//162 227//227 163//163 -f 163//163 227//227 228//228 -f 163//163 228//228 164//164 -f 164//164 228//228 229//229 -f 164//164 229//229 165//165 -f 165//165 229//229 230//230 -f 165//165 230//230 166//166 -f 166//166 230//230 231//231 -f 166//166 231//231 167//167 -f 167//167 231//231 232//232 -f 167//167 232//232 168//168 -f 168//168 232//232 233//233 -f 168//168 233//233 169//169 -f 169//169 233//233 234//234 -f 169//169 234//234 170//170 -f 170//170 234//234 235//235 -f 170//170 235//235 171//171 -f 171//171 235//235 236//236 -f 171//171 236//236 172//172 -f 172//172 236//236 237//237 -f 172//172 237//237 173//173 -f 173//173 237//237 238//238 -f 173//173 238//238 174//174 -f 174//174 238//238 239//239 -f 174//174 239//239 175//175 -f 175//175 239//239 240//240 -f 175//175 240//240 176//176 -f 176//176 240//240 241//241 -f 176//176 241//241 177//177 -f 177//177 241//241 242//242 -f 177//177 242//242 178//178 -f 178//178 242//242 243//243 -f 178//178 243//243 179//179 -f 179//179 243//243 244//244 -f 179//179 244//244 180//180 -f 180//180 244//244 245//245 -f 180//180 245//245 181//181 -f 181//181 245//245 246//246 -f 181//181 246//246 182//182 -f 182//182 246//246 247//247 -f 182//182 247//247 183//183 -f 183//183 247//247 248//248 -f 183//183 248//248 184//184 -f 184//184 248//248 249//249 -f 184//184 249//249 185//185 -f 185//185 249//249 250//250 -f 185//185 250//250 186//186 -f 186//186 250//250 251//251 -f 186//186 251//251 187//187 -f 187//187 251//251 252//252 -f 187//187 252//252 188//188 -f 188//188 252//252 253//253 -f 188//188 253//253 189//189 -f 189//189 253//253 254//254 -f 189//189 254//254 190//190 -f 190//190 254//254 255//255 -f 190//190 255//255 191//191 -f 191//191 255//255 256//256 -f 191//191 256//256 192//192 -f 192//192 256//256 193//193 -f 242//242 257//257 243//243 -f 243//243 257//257 258//258 -f 243//243 258//258 244//244 -f 244//244 258//258 259//259 -f 244//244 259//259 245//245 -f 245//245 259//259 260//260 -f 245//245 260//260 246//246 -f 246//246 260//260 261//261 -f 246//246 261//261 247//247 -f 247//247 261//261 262//262 -f 247//247 262//262 248//248 -f 236//236 263//263 237//237 -f 237//237 263//263 264//264 -f 237//237 264//264 238//238 -f 238//238 264//264 265//265 -f 238//238 265//265 239//239 -f 239//239 265//265 266//266 -f 239//239 266//266 240//240 -f 240//240 266//266 267//267 -f 240//240 267//267 241//241 -f 241//241 267//267 268//268 -f 241//241 268//268 242//242 -f 242//242 268//268 269//269 -f 242//242 269//269 257//257 -f 230//230 270//270 231//231 -f 231//231 270//270 271//271 -f 231//231 271//271 232//232 -f 232//232 271//271 272//272 -f 232//232 272//272 233//233 -f 233//233 272//272 273//273 -f 233//233 273//273 234//234 -f 234//234 273//273 274//274 -f 234//234 274//274 235//235 -f 235//235 274//274 275//275 -f 235//235 275//275 236//236 -f 236//236 275//275 276//276 -f 236//236 276//276 263//263 -f 216//216 277//277 217//217 -f 217//217 277//277 278//278 -f 217//217 278//278 218//218 -f 218//218 278//278 279//279 -f 218//218 279//279 219//219 -f 219//219 279//279 280//280 -f 219//219 280//280 220//220 -f 220//220 280//280 281//281 -f 220//220 281//281 221//221 -f 221//221 281//281 282//282 -f 221//221 282//282 222//222 -f 222//222 282//282 283//283 -f 222//222 283//283 223//223 -f 223//223 283//283 284//284 -f 223//223 284//284 224//224 -f 224//224 284//284 285//285 -f 224//224 285//285 225//225 -f 225//225 285//285 286//286 -f 225//225 286//286 226//226 -f 226//226 286//286 287//287 -f 226//226 287//287 227//227 -f 227//227 287//287 288//288 -f 227//227 288//288 228//228 -f 228//228 288//288 289//289 -f 228//228 289//289 229//229 -f 229//229 289//289 290//290 -f 229//229 290//290 230//230 -f 230//230 290//290 291//291 -f 230//230 291//291 270//270 -f 210//210 292//292 211//211 -f 211//211 292//292 293//293 -f 211//211 293//293 212//212 -f 212//212 293//293 294//294 -f 212//212 294//294 213//213 -f 213//213 294//294 295//295 -f 213//213 295//295 214//214 -f 214//214 295//295 296//296 -f 214//214 296//296 215//215 -f 215//215 296//296 297//297 -f 215//215 297//297 216//216 -f 216//216 297//297 298//298 -f 216//216 298//298 277//277 -f 204//204 299//299 205//205 -f 205//205 299//299 300//300 -f 205//205 300//300 206//206 -f 206//206 300//300 301//301 -f 206//206 301//301 207//207 -f 207//207 301//301 302//302 -f 207//207 302//302 208//208 -f 208//208 302//302 303//303 -f 208//208 303//303 209//209 -f 209//209 303//303 304//304 -f 209//209 304//304 210//210 -f 210//210 304//304 305//305 -f 210//210 305//305 292//292 -f 198//198 306//306 199//199 -f 199//199 306//306 307//307 -f 199//199 307//307 200//200 -f 200//200 307//307 308//308 -f 200//200 308//308 201//201 -f 201//201 308//308 309//309 -f 201//201 309//309 202//202 -f 202//202 309//309 310//310 -f 202//202 310//310 203//203 -f 203//203 310//310 311//311 -f 203//203 311//311 204//204 -f 204//204 311//311 312//312 -f 204//204 312//312 299//299 -f 262//262 313//313 248//248 -f 248//248 313//313 314//314 -f 248//248 314//314 249//249 -f 249//249 314//314 315//315 -f 249//249 315//315 250//250 -f 250//250 315//315 316//316 -f 250//250 316//316 251//251 -f 251//251 316//316 317//317 -f 251//251 317//317 252//252 -f 252//252 317//317 318//318 -f 252//252 318//318 253//253 -f 253//253 318//318 319//319 -f 253//253 319//319 254//254 -f 254//254 319//319 320//320 -f 254//254 320//320 255//255 -f 255//255 320//320 321//321 -f 255//255 321//321 256//256 -f 256//256 321//321 322//322 -f 256//256 322//322 193//193 -f 193//193 322//322 323//323 -f 193//193 323//323 194//194 -f 194//194 323//323 324//324 -f 194//194 324//324 195//195 -f 195//195 324//324 325//325 -f 195//195 325//325 196//196 -f 196//196 325//325 326//326 -f 196//196 326//326 197//197 -f 197//197 326//326 327//327 -f 197//197 327//327 198//198 -f 198//198 327//327 328//328 -f 198//198 328//328 306//306 -f 329//329 330//330 331//331 -f 332//332 333//333 334//334 -f 335//335 336//336 337//337 -f 338//338 339//339 340//340 -f 341//341 342//342 343//343 -f 344//344 345//345 346//346 -f 347//347 348//348 349//349 -f 328//328 327//327 350//350 -f 307//307 306//306 351//351 -f 308//308 307//307 352//352 -f 296//296 295//295 335//335 -f 298//298 297//297 353//353 -f 278//278 277//277 354//354 -f 279//279 278//278 355//355 -f 276//276 275//275 356//356 -f 265//265 264//264 357//357 -f 258//258 257//257 358//358 -f 261//261 260//260 359//359 -f 320//320 319//319 360//360 -f 322//322 321//321 361//361 -f 361//361 321//321 320//320 -f 317//317 316//316 347//347 -f 347//347 316//316 315//315 -f 347//347 315//315 348//348 -f 348//348 315//315 314//314 -f 348//348 314//314 313//313 -f 362//362 262//262 261//261 -f 260//260 259//259 363//363 -f 266//266 345//345 267//267 -f 267//267 345//345 344//344 -f 267//267 344//344 268//268 -f 268//268 344//344 269//269 -f 264//264 263//263 364//364 -f 364//364 263//263 276//276 -f 273//273 272//272 341//341 -f 341//341 272//272 271//271 -f 341//341 271//271 342//342 -f 342//342 271//271 270//270 -f 342//342 270//270 291//291 -f 365//365 290//290 289//289 -f 289//289 288//288 366//366 -f 366//366 288//288 287//287 -f 285//285 284//284 338//338 -f 338//338 284//284 283//283 -f 338//338 283//283 339//339 -f 339//339 283//283 282//282 -f 339//339 282//282 281//281 -f 279//279 355//355 280//280 -f 335//335 295//295 336//336 -f 336//336 295//295 294//294 -f 336//336 294//294 293//293 -f 367//367 292//292 305//305 -f 305//305 304//304 368//368 -f 368//368 304//304 303//303 -f 302//302 301//301 369//369 -f 300//300 299//299 332//332 -f 332//332 299//299 312//312 -f 332//332 312//312 333//333 -f 333//333 312//312 311//311 -f 333//333 311//311 310//310 -f 308//308 352//352 309//309 -f 326//326 325//325 329//329 -f 329//329 325//325 324//324 -f 329//329 324//324 330//330 -f 330//330 324//324 323//323 -f 370//370 371//371 360//360 -f 372//372 349//349 373//373 -f 373//373 349//349 348//348 -f 373//373 348//348 362//362 -f 362//362 348//348 313//313 -f 362//362 313//313 262//262 -f 374//374 375//375 363//363 -f 376//376 346//346 377//377 -f 377//377 346//346 345//345 -f 377//377 345//345 357//357 -f 357//357 345//345 266//266 -f 357//357 266//266 265//265 -f 378//378 379//379 356//356 -f 380//380 343//343 381//381 -f 381//381 343//343 342//342 -f 381//381 342//342 365//365 -f 365//365 342//342 291//291 -f 365//365 291//291 290//290 -f 382//382 383//383 384//384 -f 385//385 340//340 386//386 -f 386//386 340//340 339//339 -f 386//386 339//339 387//387 -f 387//387 339//339 281//281 -f 387//387 281//281 280//280 -f 388//388 389//389 354//354 -f 390//390 337//337 391//391 -f 391//391 337//337 336//336 -f 391//391 336//336 367//367 -f 367//367 336//336 293//293 -f 367//367 293//293 292//292 -f 392//392 393//393 394//394 -f 395//395 334//334 396//396 -f 396//396 334//334 333//333 -f 396//396 333//333 397//397 -f 397//397 333//333 310//310 -f 397//397 310//310 309//309 -f 398//398 399//399 351//351 -f 400//400 331//331 401//401 -f 401//401 331//331 330//330 -f 401//401 330//330 402//402 -f 402//402 330//330 323//323 -f 402//402 323//323 322//322 -f 403//403 371//371 404//404 -f 404//404 371//371 370//370 -f 404//404 370//370 405//405 -f 406//406 375//375 407//407 -f 407//407 375//375 374//374 -f 407//407 374//374 408//408 -f 409//409 379//379 410//410 -f 410//410 379//379 378//378 -f 410//410 378//378 411//411 -f 412//412 383//383 413//413 -f 413//413 383//383 382//382 -f 413//413 382//382 414//414 -f 415//415 389//389 416//416 -f 416//416 389//389 388//388 -f 416//416 388//388 417//417 -f 418//418 393//393 419//419 -f 419//419 393//393 392//392 -f 419//419 392//392 420//420 -f 421//421 399//399 422//422 -f 422//422 399//399 398//398 -f 422//422 398//398 423//423 -f 424//424 425//425 426//426 -f 322//322 361//361 402//402 -f 402//402 361//361 427//427 -f 402//402 427//427 401//401 -f 401//401 427//427 424//424 -f 401//401 424//424 400//400 -f 400//400 424//424 426//426 -f 400//400 426//426 428//428 -f 320//320 360//360 361//361 -f 361//361 360//360 371//371 -f 361//361 371//371 427//427 -f 427//427 371//371 403//403 -f 427//427 403//403 424//424 -f 424//424 403//403 429//429 -f 424//424 429//429 425//425 -f 430//430 431//431 432//432 -f 432//432 431//431 405//405 -f 432//432 405//405 433//433 -f 433//433 405//405 370//370 -f 433//433 370//370 434//434 -f 434//434 370//370 360//360 -f 434//434 360//360 318//318 -f 318//318 360//360 319//319 -f 431//431 435//435 405//405 -f 405//405 435//435 436//436 -f 405//405 436//436 404//404 -f 404//404 436//436 437//437 -f 404//404 437//437 403//403 -f 403//403 437//437 438//438 -f 403//403 438//438 429//429 -f 318//318 317//317 434//434 -f 434//434 317//317 347//347 -f 434//434 347//347 433//433 -f 433//433 347//347 349//349 -f 433//433 349//349 432//432 -f 432//432 349//349 372//372 -f 432//432 372//372 430//430 -f 430//430 372//372 439//439 -f 440//440 441//441 442//442 -f 261//261 359//359 362//362 -f 362//362 359//359 443//443 -f 362//362 443//443 373//373 -f 373//373 443//443 440//440 -f 373//373 440//440 372//372 -f 372//372 440//440 442//442 -f 372//372 442//442 439//439 -f 260//260 363//363 359//359 -f 359//359 363//363 375//375 -f 359//359 375//375 443//443 -f 443//443 375//375 406//406 -f 443//443 406//406 440//440 -f 440//440 406//406 444//444 -f 440//440 444//444 441//441 -f 445//445 446//446 447//447 -f 447//447 446//446 408//408 -f 447//447 408//408 448//448 -f 448//448 408//408 374//374 -f 448//448 374//374 358//358 -f 358//358 374//374 363//363 -f 358//358 363//363 258//258 -f 258//258 363//363 259//259 -f 446//446 449//449 408//408 -f 408//408 449//449 450//450 -f 408//408 450//450 407//407 -f 407//407 450//450 451//451 -f 407//407 451//451 406//406 -f 406//406 451//451 452//452 -f 406//406 452//452 444//444 -f 257//257 269//269 358//358 -f 358//358 269//269 344//344 -f 358//358 344//344 448//448 -f 448//448 344//344 346//346 -f 448//448 346//346 447//447 -f 447//447 346//346 376//376 -f 447//447 376//376 445//445 -f 445//445 376//376 453//453 -f 454//454 455//455 456//456 -f 264//264 364//364 357//357 -f 357//357 364//364 457//457 -f 357//357 457//457 377//377 -f 377//377 457//457 454//454 -f 377//377 454//454 376//376 -f 376//376 454//454 456//456 -f 376//376 456//456 453//453 -f 276//276 356//356 364//364 -f 364//364 356//356 379//379 -f 364//364 379//379 457//457 -f 457//457 379//379 409//409 -f 457//457 409//409 454//454 -f 454//454 409//409 458//458 -f 454//454 458//458 455//455 -f 459//459 460//460 461//461 -f 461//461 460//460 411//411 -f 461//461 411//411 462//462 -f 462//462 411//411 378//378 -f 462//462 378//378 463//463 -f 463//463 378//378 356//356 -f 463//463 356//356 274//274 -f 274//274 356//356 275//275 -f 460//460 464//464 411//411 -f 411//411 464//464 465//465 -f 411//411 465//465 410//410 -f 410//410 465//465 466//466 -f 410//410 466//466 409//409 -f 409//409 466//466 467//467 -f 409//409 467//467 458//458 -f 274//274 273//273 463//463 -f 463//463 273//273 341//341 -f 463//463 341//341 462//462 -f 462//462 341//341 343//343 -f 462//462 343//343 461//461 -f 461//461 343//343 380//380 -f 461//461 380//380 459//459 -f 459//459 380//380 468//468 -f 469//469 470//470 471//471 -f 289//289 366//366 365//365 -f 365//365 366//366 472//472 -f 365//365 472//472 381//381 -f 381//381 472//472 469//469 -f 381//381 469//469 380//380 -f 380//380 469//469 471//471 -f 380//380 471//471 468//468 -f 287//287 384//384 366//366 -f 366//366 384//384 383//383 -f 366//366 383//383 472//472 -f 472//472 383//383 412//412 -f 472//472 412//412 469//469 -f 469//469 412//412 473//473 -f 469//469 473//473 470//470 -f 474//474 475//475 476//476 -f 476//476 475//475 414//414 -f 476//476 414//414 477//477 -f 477//477 414//414 382//382 -f 477//477 382//382 478//478 -f 478//478 382//382 384//384 -f 478//478 384//384 286//286 -f 286//286 384//384 287//287 -f 475//475 479//479 414//414 -f 414//414 479//479 480//480 -f 414//414 480//480 413//413 -f 413//413 480//480 481//481 -f 413//413 481//481 412//412 -f 412//412 481//481 482//482 -f 412//412 482//482 473//473 -f 286//286 285//285 478//478 -f 478//478 285//285 338//338 -f 478//478 338//338 477//477 -f 477//477 338//338 340//340 -f 477//477 340//340 476//476 -f 476//476 340//340 385//385 -f 476//476 385//385 474//474 -f 474//474 385//385 483//483 -f 484//484 485//485 486//486 -f 280//280 355//355 387//387 -f 387//387 355//355 487//487 -f 387//387 487//487 386//386 -f 386//386 487//487 484//484 -f 386//386 484//484 385//385 -f 385//385 484//484 486//486 -f 385//385 486//486 483//483 -f 278//278 354//354 355//355 -f 355//355 354//354 389//389 -f 355//355 389//389 487//487 -f 487//487 389//389 415//415 -f 487//487 415//415 484//484 -f 484//484 415//415 488//488 -f 484//484 488//488 485//485 -f 489//489 490//490 491//491 -f 491//491 490//490 417//417 -f 491//491 417//417 492//492 -f 492//492 417//417 388//388 -f 492//492 388//388 353//353 -f 353//353 388//388 354//354 -f 353//353 354//354 298//298 -f 298//298 354//354 277//277 -f 490//490 493//493 417//417 -f 417//417 493//493 494//494 -f 417//417 494//494 416//416 -f 416//416 494//494 495//495 -f 416//416 495//495 415//415 -f 415//415 495//495 496//496 -f 415//415 496//496 488//488 -f 297//297 296//296 353//353 -f 353//353 296//296 335//335 -f 353//353 335//335 492//492 -f 492//492 335//335 337//337 -f 492//492 337//337 491//491 -f 491//491 337//337 390//390 -f 491//491 390//390 489//489 -f 489//489 390//390 497//497 -f 498//498 499//499 500//500 -f 305//305 368//368 367//367 -f 367//367 368//368 501//501 -f 367//367 501//501 391//391 -f 391//391 501//501 498//498 -f 391//391 498//498 390//390 -f 390//390 498//498 500//500 -f 390//390 500//500 497//497 -f 303//303 394//394 368//368 -f 368//368 394//394 393//393 -f 368//368 393//393 501//501 -f 501//501 393//393 418//418 -f 501//501 418//418 498//498 -f 498//498 418//418 502//502 -f 498//498 502//502 499//499 -f 503//503 504//504 505//505 -f 505//505 504//504 420//420 -f 505//505 420//420 506//506 -f 506//506 420//420 392//392 -f 506//506 392//392 369//369 -f 369//369 392//392 394//394 -f 369//369 394//394 302//302 -f 302//302 394//394 303//303 -f 504//504 507//507 420//420 -f 420//420 507//507 508//508 -f 420//420 508//508 419//419 -f 419//419 508//508 509//509 -f 419//419 509//509 418//418 -f 418//418 509//509 510//510 -f 418//418 510//510 502//502 -f 301//301 300//300 369//369 -f 369//369 300//300 332//332 -f 369//369 332//332 506//506 -f 506//506 332//332 334//334 -f 506//506 334//334 505//505 -f 505//505 334//334 395//395 -f 505//505 395//395 503//503 -f 503//503 395//395 511//511 -f 512//512 513//513 514//514 -f 309//309 352//352 397//397 -f 397//397 352//352 515//515 -f 397//397 515//515 396//396 -f 396//396 515//515 512//512 -f 396//396 512//512 395//395 -f 395//395 512//512 514//514 -f 395//395 514//514 511//511 -f 307//307 351//351 352//352 -f 352//352 351//351 399//399 -f 352//352 399//399 515//515 -f 515//515 399//399 421//421 -f 515//515 421//421 512//512 -f 512//512 421//421 516//516 -f 512//512 516//516 513//513 -f 517//517 518//518 519//519 -f 519//519 518//518 423//423 -f 519//519 423//423 520//520 -f 520//520 423//423 398//398 -f 520//520 398//398 350//350 -f 350//350 398//398 351//351 -f 350//350 351//351 328//328 -f 328//328 351//351 306//306 -f 518//518 521//521 423//423 -f 423//423 521//521 522//522 -f 423//423 522//522 422//422 -f 422//422 522//522 523//523 -f 422//422 523//523 421//421 -f 421//421 523//523 524//524 -f 421//421 524//524 516//516 -f 327//327 326//326 350//350 -f 350//350 326//326 329//329 -f 350//350 329//329 520//520 -f 520//520 329//329 331//331 -f 520//520 331//331 519//519 -f 519//519 331//331 400//400 -f 519//519 400//400 517//517 -f 517//517 400//400 428//428 -f 471//471 525//525 468//468 -f 468//468 525//525 526//526 -f 468//468 526//526 459//459 -f 459//459 526//526 527//527 -f 459//459 527//527 460//460 -f 460//460 527//527 528//528 -f 460//460 528//528 464//464 -f 464//464 528//528 529//529 -f 464//464 529//529 465//465 -f 530//530 451//451 450//450 -f 529//529 531//531 465//465 -f 465//465 531//531 532//532 -f 465//465 532//532 466//466 -f 466//466 532//532 533//533 -f 466//466 533//533 467//467 -f 467//467 533//533 534//534 -f 467//467 534//534 458//458 -f 458//458 534//534 535//535 -f 458//458 535//535 455//455 -f 455//455 535//535 536//536 -f 455//455 536//536 456//456 -f 456//456 536//536 537//537 -f 456//456 537//537 453//453 -f 453//453 537//537 538//538 -f 453//453 538//538 445//445 -f 445//445 538//538 539//539 -f 445//445 539//539 446//446 -f 446//446 539//539 540//540 -f 446//446 540//540 449//449 -f 449//449 540//540 541//541 -f 449//449 541//541 450//450 -f 450//450 541//541 542//542 -f 450//450 542//542 530//530 -f 530//530 543//543 451//451 -f 451//451 543//543 544//544 -f 451//451 544//544 452//452 -f 452//452 544//544 545//545 -f 452//452 545//545 444//444 -f 444//444 545//545 546//546 -f 444//444 546//546 441//441 -f 441//441 546//546 547//547 -f 441//441 547//547 442//442 -f 442//442 547//547 548//548 -f 442//442 548//548 439//439 -f 439//439 548//548 549//549 -f 439//439 549//549 430//430 -f 430//430 549//549 550//550 -f 430//430 550//550 431//431 -f 431//431 550//550 551//551 -f 431//431 551//551 435//435 -f 435//435 551//551 552//552 -f 435//435 552//552 436//436 -f 436//436 552//552 553//553 -f 436//436 553//553 437//437 -f 553//553 554//554 437//437 -f 437//437 554//554 555//555 -f 437//437 555//555 438//438 -f 438//438 555//555 556//556 -f 438//438 556//556 429//429 -f 429//429 556//556 557//557 -f 429//429 557//557 425//425 -f 425//425 557//557 558//558 -f 425//425 558//558 426//426 -f 426//426 558//558 559//559 -f 426//426 559//559 428//428 -f 428//428 559//559 560//560 -f 428//428 560//560 517//517 -f 517//517 560//560 561//561 -f 517//517 561//561 518//518 -f 561//561 562//562 518//518 -f 518//518 562//562 563//563 -f 518//518 563//563 521//521 -f 521//521 563//563 564//564 -f 521//521 564//564 522//522 -f 522//522 564//564 565//565 -f 522//522 565//565 523//523 -f 565//565 566//566 523//523 -f 523//523 566//566 567//567 -f 523//523 567//567 524//524 -f 524//524 567//567 568//568 -f 524//524 568//568 516//516 -f 516//516 568//568 513//513 -f 513//513 568//568 569//569 -f 513//513 569//569 514//514 -f 514//514 569//569 570//570 -f 514//514 570//570 511//511 -f 511//511 570//570 571//571 -f 511//511 571//571 503//503 -f 503//503 571//571 572//572 -f 503//503 572//572 504//504 -f 572//572 573//573 504//504 -f 504//504 573//573 574//574 -f 504//504 574//574 507//507 -f 507//507 574//574 575//575 -f 507//507 575//575 508//508 -f 508//508 575//575 576//576 -f 508//508 576//576 509//509 -f 576//576 577//577 509//509 -f 509//509 577//577 578//578 -f 509//509 578//578 510//510 -f 510//510 578//578 579//579 -f 510//510 579//579 502//502 -f 502//502 579//579 580//580 -f 502//502 580//580 499//499 -f 499//499 580//580 581//581 -f 499//499 581//581 500//500 -f 500//500 581//581 582//582 -f 500//500 582//582 497//497 -f 497//497 582//582 583//583 -f 497//497 583//583 489//489 -f 489//489 583//583 584//584 -f 489//489 584//584 490//490 -f 490//490 584//584 585//585 -f 490//490 585//585 493//493 -f 493//493 585//585 586//586 -f 493//493 586//586 494//494 -f 494//494 586//586 587//587 -f 494//494 587//587 495//495 -f 587//587 588//588 495//495 -f 495//495 588//588 589//589 -f 495//495 589//589 496//496 -f 496//496 589//589 590//590 -f 496//496 590//590 488//488 -f 488//488 590//590 591//591 -f 488//488 591//591 485//485 -f 485//485 591//591 592//592 -f 485//485 592//592 486//486 -f 486//486 592//592 593//593 -f 486//486 593//593 483//483 -f 593//593 594//594 483//483 -f 483//483 594//594 595//595 -f 483//483 595//595 474//474 -f 474//474 595//595 596//596 -f 474//474 596//596 475//475 -f 475//475 596//596 597//597 -f 475//475 597//597 479//479 -f 479//479 597//597 598//598 -f 479//479 598//598 480//480 -f 480//480 598//598 599//599 -f 480//480 599//599 481//481 -f 481//481 599//599 600//600 -f 481//481 600//600 482//482 -f 482//482 600//600 601//601 -f 482//482 601//601 473//473 -f 473//473 601//601 602//602 -f 473//473 602//602 470//470 -f 470//470 602//602 603//603 -f 470//470 603//603 471//471 -f 471//471 603//603 604//604 -f 471//471 604//604 525//525 -f 605//605 606//606 607//607 -f 608//608 609//609 610//610 -f 611//611 612//612 613//613 -f 614//614 615//615 616//616 -f 617//617 618//618 619//619 -f 620//620 621//621 622//622 -f 623//623 624//624 625//625 -f 626//626 627//627 628//628 -f 629//629 630//630 631//631 -f 621//621 632//632 633//633 -f 624//624 634//634 635//635 -f 627//627 636//636 637//637 -f 630//630 638//638 639//639 -f 570//570 569//569 640//640 -f 558//558 557//557 641//641 -f 641//641 557//557 642//642 -f 555//555 554//554 638//638 -f 554//554 553//553 638//638 -f 638//638 553//553 552//552 -f 638//638 552//552 639//639 -f 639//639 552//552 551//551 -f 639//639 551//551 643//643 -f 643//643 551//551 550//550 -f 643//643 550//550 644//644 -f 644//644 550//550 549//549 -f 644//644 549//549 645//645 -f 645//645 549//549 548//548 -f 548//548 547//547 645//645 -f 645//645 547//547 546//546 -f 645//645 546//546 646//646 -f 646//646 546//546 545//545 -f 646//646 545//545 647//647 -f 647//647 545//545 544//544 -f 647//647 544//544 648//648 -f 648//648 544//544 543//543 -f 543//543 530//530 648//648 -f 648//648 530//530 542//542 -f 648//648 542//542 649//649 -f 540//540 539//539 636//636 -f 539//539 538//538 636//636 -f 636//636 538//538 537//537 -f 636//636 537//537 637//637 -f 637//637 537//537 536//536 -f 637//637 536//536 650//650 -f 650//650 536//536 535//535 -f 650//650 535//535 651//651 -f 651//651 535//535 534//534 -f 651//651 534//534 652//652 -f 652//652 534//534 533//533 -f 533//533 532//532 652//652 -f 652//652 532//532 531//531 -f 652//652 531//531 653//653 -f 653//653 531//531 529//529 -f 653//653 529//529 654//654 -f 654//654 529//529 528//528 -f 654//654 528//528 655//655 -f 655//655 528//528 527//527 -f 527//527 526//526 655//655 -f 655//655 526//526 525//525 -f 655//655 525//525 656//656 -f 603//603 602//602 634//634 -f 602//602 601//601 634//634 -f 634//634 601//601 600//600 -f 634//634 600//600 635//635 -f 635//635 600//600 599//599 -f 635//635 599//599 657//657 -f 657//657 599//599 598//598 -f 657//657 598//598 658//658 -f 658//658 598//598 597//597 -f 658//658 597//597 659//659 -f 659//659 597//597 596//596 -f 596//596 595//595 659//659 -f 659//659 595//595 594//594 -f 659//659 594//594 660//660 -f 660//660 594//594 593//593 -f 660//660 593//593 661//661 -f 661//661 593//593 592//592 -f 661//661 592//592 662//662 -f 662//662 592//592 591//591 -f 591//591 590//590 662//662 -f 662//662 590//590 589//589 -f 662//662 589//589 663//663 -f 587//587 586//586 632//632 -f 586//586 585//585 632//632 -f 632//632 585//585 584//584 -f 632//632 584//584 633//633 -f 633//633 584//584 583//583 -f 633//633 583//583 664//664 -f 664//664 583//583 582//582 -f 664//664 582//582 665//665 -f 665//665 582//582 581//581 -f 665//665 581//581 666//666 -f 666//666 581//581 580//580 -f 580//580 579//579 666//666 -f 666//666 579//579 578//578 -f 666//666 578//578 667//667 -f 667//667 578//578 577//577 -f 667//667 577//577 668//668 -f 668//668 577//577 576//576 -f 668//668 576//576 669//669 -f 669//669 576//576 575//575 -f 575//575 574//574 669//669 -f 669//669 574//574 573//573 -f 669//669 573//573 670//670 -f 570//570 640//640 571//571 -f 564//564 671//671 565//565 -f 565//565 671//671 672//672 -f 565//565 672//672 566//566 -f 564//564 563//563 671//671 -f 671//671 563//563 562//562 -f 671//671 562//562 673//673 -f 673//673 562//562 561//561 -f 673//673 561//561 674//674 -f 674//674 561//561 560//560 -f 674//674 560//560 641//641 -f 641//641 560//560 559//559 -f 641//641 559//559 558//558 -f 642//642 675//675 676//676 -f 630//630 639//639 631//631 -f 631//631 639//639 643//643 -f 631//631 643//643 677//677 -f 677//677 643//643 644//644 -f 677//677 644//644 678//678 -f 678//678 644//644 645//645 -f 678//678 645//645 679//679 -f 679//679 645//645 646//646 -f 679//679 646//646 680//680 -f 680//680 646//646 647//647 -f 680//680 647//647 681//681 -f 681//681 647//647 648//648 -f 681//681 648//648 682//682 -f 682//682 648//648 649//649 -f 682//682 649//649 683//683 -f 627//627 637//637 628//628 -f 628//628 637//637 650//650 -f 628//628 650//650 684//684 -f 684//684 650//650 651//651 -f 684//684 651//651 685//685 -f 685//685 651//651 652//652 -f 685//685 652//652 686//686 -f 686//686 652//652 653//653 -f 686//686 653//653 687//687 -f 687//687 653//653 654//654 -f 687//687 654//654 688//688 -f 688//688 654//654 655//655 -f 688//688 655//655 689//689 -f 689//689 655//655 656//656 -f 689//689 656//656 690//690 -f 624//624 635//635 625//625 -f 625//625 635//635 657//657 -f 625//625 657//657 691//691 -f 691//691 657//657 658//658 -f 691//691 658//658 692//692 -f 692//692 658//658 659//659 -f 692//692 659//659 693//693 -f 693//693 659//659 660//660 -f 693//693 660//660 694//694 -f 694//694 660//660 661//661 -f 694//694 661//661 695//695 -f 695//695 661//661 662//662 -f 695//695 662//662 696//696 -f 696//696 662//662 663//663 -f 696//696 663//663 697//697 -f 621//621 633//633 622//622 -f 622//622 633//633 664//664 -f 622//622 664//664 698//698 -f 698//698 664//664 665//665 -f 698//698 665//665 699//699 -f 699//699 665//665 666//666 -f 699//699 666//666 700//700 -f 700//700 666//666 667//667 -f 700//700 667//667 701//701 -f 701//701 667//667 668//668 -f 701//701 668//668 702//702 -f 702//702 668//668 669//669 -f 702//702 669//669 703//703 -f 703//703 669//669 670//670 -f 703//703 670//670 704//704 -f 642//642 676//676 641//641 -f 641//641 676//676 705//705 -f 641//641 705//705 674//674 -f 674//674 705//705 706//706 -f 674//674 706//706 673//673 -f 673//673 706//706 707//707 -f 673//673 707//707 671//671 -f 671//671 707//707 708//708 -f 671//671 708//708 672//672 -f 675//675 709//709 710//710 -f 629//629 631//631 711//711 -f 711//711 631//631 677//677 -f 711//711 677//677 712//712 -f 712//712 677//677 678//678 -f 712//712 678//678 713//713 -f 713//713 678//678 679//679 -f 713//713 679//679 714//714 -f 714//714 679//679 680//680 -f 714//714 680//680 715//715 -f 715//715 680//680 681//681 -f 715//715 681//681 716//716 -f 716//716 681//681 682//682 -f 716//716 682//682 717//717 -f 717//717 682//682 683//683 -f 717//717 683//683 619//619 -f 626//626 628//628 718//718 -f 718//718 628//628 684//684 -f 718//718 684//684 719//719 -f 719//719 684//684 685//685 -f 719//719 685//685 720//720 -f 720//720 685//685 686//686 -f 720//720 686//686 721//721 -f 721//721 686//686 687//687 -f 721//721 687//687 722//722 -f 722//722 687//687 688//688 -f 722//722 688//688 723//723 -f 723//723 688//688 689//689 -f 723//723 689//689 724//724 -f 724//724 689//689 690//690 -f 724//724 690//690 616//616 -f 623//623 625//625 725//725 -f 725//725 625//625 691//691 -f 725//725 691//691 726//726 -f 726//726 691//691 692//692 -f 726//726 692//692 727//727 -f 727//727 692//692 693//693 -f 727//727 693//693 728//728 -f 728//728 693//693 694//694 -f 728//728 694//694 729//729 -f 729//729 694//694 695//695 -f 729//729 695//695 730//730 -f 730//730 695//695 696//696 -f 730//730 696//696 731//731 -f 731//731 696//696 697//697 -f 731//731 697//697 613//613 -f 620//620 622//622 732//732 -f 732//732 622//622 698//698 -f 732//732 698//698 733//733 -f 733//733 698//698 699//699 -f 733//733 699//699 734//734 -f 734//734 699//699 700//700 -f 734//734 700//700 735//735 -f 735//735 700//700 701//701 -f 735//735 701//701 736//736 -f 736//736 701//701 702//702 -f 736//736 702//702 737//737 -f 737//737 702//702 703//703 -f 737//737 703//703 738//738 -f 738//738 703//703 704//704 -f 738//738 704//704 610//610 -f 569//569 568//568 640//640 -f 640//640 568//568 739//739 -f 640//640 739//739 740//740 -f 740//740 739//739 741//741 -f 740//740 741//741 742//742 -f 742//742 741//741 607//607 -f 675//675 710//710 676//676 -f 676//676 710//710 743//743 -f 676//676 743//743 705//705 -f 705//705 743//743 744//744 -f 705//705 744//744 706//706 -f 706//706 744//744 745//745 -f 706//706 745//745 707//707 -f 707//707 745//745 746//746 -f 707//707 746//746 708//708 -f 747//747 710//710 748//748 -f 748//748 710//710 709//709 -f 748//748 709//709 749//749 -f 750//750 749//749 751//751 -f 751//751 749//749 709//709 -f 751//751 709//709 752//752 -f 752//752 709//709 675//675 -f 752//752 675//675 753//753 -f 753//753 675//675 642//642 -f 753//753 642//642 556//556 -f 556//556 642//642 557//557 -f 556//556 555//555 753//753 -f 753//753 555//555 638//638 -f 753//753 638//638 752//752 -f 752//752 638//638 630//630 -f 752//752 630//630 751//751 -f 751//751 630//630 629//629 -f 751//751 629//629 750//750 -f 750//750 629//629 754//754 -f 755//755 756//756 713//713 -f 713//713 756//756 757//757 -f 713//713 757//757 712//712 -f 712//712 757//757 758//758 -f 712//712 758//758 711//711 -f 711//711 758//758 759//759 -f 711//711 759//759 629//629 -f 629//629 759//759 760//760 -f 629//629 760//760 754//754 -f 755//755 713//713 761//761 -f 761//761 713//713 714//714 -f 761//761 714//714 762//762 -f 762//762 714//714 715//715 -f 762//762 715//715 763//763 -f 763//763 715//715 716//716 -f 763//763 716//716 764//764 -f 764//764 716//716 717//717 -f 764//764 717//717 765//765 -f 619//619 618//618 717//717 -f 717//717 618//618 766//766 -f 717//717 766//766 765//765 -f 767//767 617//617 768//768 -f 768//768 617//617 619//619 -f 768//768 619//619 769//769 -f 769//769 619//619 683//683 -f 769//769 683//683 770//770 -f 770//770 683//683 649//649 -f 770//770 649//649 541//541 -f 541//541 649//649 542//542 -f 541//541 540//540 770//770 -f 770//770 540//540 636//636 -f 770//770 636//636 769//769 -f 769//769 636//636 627//627 -f 769//769 627//627 768//768 -f 768//768 627//627 626//626 -f 768//768 626//626 767//767 -f 767//767 626//626 771//771 -f 772//772 773//773 720//720 -f 720//720 773//773 774//774 -f 720//720 774//774 719//719 -f 719//719 774//774 775//775 -f 719//719 775//775 718//718 -f 718//718 775//775 776//776 -f 718//718 776//776 626//626 -f 626//626 776//776 777//777 -f 626//626 777//777 771//771 -f 772//772 720//720 778//778 -f 778//778 720//720 721//721 -f 778//778 721//721 779//779 -f 779//779 721//721 722//722 -f 779//779 722//722 780//780 -f 780//780 722//722 723//723 -f 780//780 723//723 781//781 -f 781//781 723//723 724//724 -f 781//781 724//724 782//782 -f 616//616 615//615 724//724 -f 724//724 615//615 783//783 -f 724//724 783//783 782//782 -f 784//784 614//614 785//785 -f 785//785 614//614 616//616 -f 785//785 616//616 786//786 -f 786//786 616//616 690//690 -f 786//786 690//690 787//787 -f 787//787 690//690 656//656 -f 787//787 656//656 604//604 -f 604//604 656//656 525//525 -f 604//604 603//603 787//787 -f 787//787 603//603 634//634 -f 787//787 634//634 786//786 -f 786//786 634//634 624//624 -f 786//786 624//624 785//785 -f 785//785 624//624 623//623 -f 785//785 623//623 784//784 -f 784//784 623//623 788//788 -f 789//789 790//790 727//727 -f 727//727 790//790 791//791 -f 727//727 791//791 726//726 -f 726//726 791//791 792//792 -f 726//726 792//792 725//725 -f 725//725 792//792 793//793 -f 725//725 793//793 623//623 -f 623//623 793//793 794//794 -f 623//623 794//794 788//788 -f 789//789 727//727 795//795 -f 795//795 727//727 728//728 -f 795//795 728//728 796//796 -f 796//796 728//728 729//729 -f 796//796 729//729 797//797 -f 797//797 729//729 730//730 -f 797//797 730//730 798//798 -f 798//798 730//730 731//731 -f 798//798 731//731 799//799 -f 613//613 612//612 731//731 -f 731//731 612//612 800//800 -f 731//731 800//800 799//799 -f 801//801 611//611 802//802 -f 802//802 611//611 613//613 -f 802//802 613//613 803//803 -f 803//803 613//613 697//697 -f 803//803 697//697 804//804 -f 804//804 697//697 663//663 -f 804//804 663//663 588//588 -f 588//588 663//663 589//589 -f 588//588 587//587 804//804 -f 804//804 587//587 632//632 -f 804//804 632//632 803//803 -f 803//803 632//632 621//621 -f 803//803 621//621 802//802 -f 802//802 621//621 620//620 -f 802//802 620//620 801//801 -f 801//801 620//620 805//805 -f 806//806 807//807 734//734 -f 734//734 807//807 808//808 -f 734//734 808//808 733//733 -f 733//733 808//808 809//809 -f 733//733 809//809 732//732 -f 732//732 809//809 810//810 -f 732//732 810//810 620//620 -f 620//620 810//810 811//811 -f 620//620 811//811 805//805 -f 806//806 734//734 812//812 -f 812//812 734//734 735//735 -f 812//812 735//735 813//813 -f 813//813 735//735 736//736 -f 813//813 736//736 814//814 -f 814//814 736//736 737//737 -f 814//814 737//737 815//815 -f 815//815 737//737 738//738 -f 815//815 738//738 816//816 -f 610//610 609//609 738//738 -f 738//738 609//609 817//817 -f 738//738 817//817 816//816 -f 818//818 608//608 819//819 -f 819//819 608//608 610//610 -f 819//819 610//610 820//820 -f 820//820 610//610 704//704 -f 820//820 704//704 821//821 -f 821//821 704//704 670//670 -f 821//821 670//670 572//572 -f 572//572 670//670 573//573 -f 572//572 571//571 821//821 -f 821//821 571//571 640//640 -f 821//821 640//640 820//820 -f 820//820 640//640 740//740 -f 820//820 740//740 819//819 -f 819//819 740//740 742//742 -f 819//819 742//742 818//818 -f 818//818 742//742 822//822 -f 607//607 606//606 742//742 -f 742//742 606//606 823//823 -f 742//742 823//823 822//822 -f 824//824 605//605 825//825 -f 825//825 605//605 607//607 -f 825//825 607//607 826//826 -f 826//826 607//607 741//741 -f 826//826 741//741 827//827 -f 827//827 741//741 739//739 -f 827//827 739//739 567//567 -f 567//567 739//739 568//568 -f 567//567 566//566 827//827 -f 827//827 566//566 672//672 -f 827//827 672//672 826//826 -f 826//826 672//672 708//708 -f 826//826 708//708 825//825 -f 825//825 708//708 746//746 -f 825//825 746//746 824//824 -f 824//824 746//746 828//828 -f 747//747 829//829 710//710 -f 710//710 829//829 830//830 -f 710//710 830//830 743//743 -f 743//743 830//830 831//831 -f 743//743 831//831 744//744 -f 744//744 831//831 832//832 -f 744//744 832//832 745//745 -f 745//745 832//832 833//833 -f 745//745 833//833 746//746 -f 746//746 833//833 834//834 -f 746//746 834//834 828//828 -f 835//835 750//750 836//836 -f 836//836 750//750 754//754 -f 836//836 754//754 837//837 -f 837//837 754//754 760//760 -f 837//837 760//760 838//838 -f 838//838 760//760 759//759 -f 838//838 759//759 839//839 -f 839//839 759//759 758//758 -f 839//839 758//758 840//840 -f 771//771 841//841 842//842 -f 758//758 757//757 840//840 -f 840//840 757//757 756//756 -f 840//840 756//756 843//843 -f 843//843 756//756 755//755 -f 843//843 755//755 844//844 -f 844//844 755//755 761//761 -f 844//844 761//761 845//845 -f 845//845 761//761 762//762 -f 845//845 762//762 846//846 -f 846//846 762//762 763//763 -f 846//846 763//763 847//847 -f 847//847 763//763 764//764 -f 847//847 764//764 848//848 -f 848//848 764//764 765//765 -f 848//848 765//765 849//849 -f 849//849 765//765 766//766 -f 849//849 766//766 850//850 -f 850//850 766//766 618//618 -f 850//850 618//618 851//851 -f 851//851 618//618 617//617 -f 851//851 617//617 842//842 -f 842//842 617//617 767//767 -f 842//842 767//767 771//771 -f 771//771 777//777 841//841 -f 841//841 777//777 776//776 -f 841//841 776//776 852//852 -f 852//852 776//776 775//775 -f 852//852 775//775 853//853 -f 853//853 775//775 774//774 -f 853//853 774//774 854//854 -f 854//854 774//774 773//773 -f 854//854 773//773 855//855 -f 855//855 773//773 772//772 -f 855//855 772//772 856//856 -f 856//856 772//772 778//778 -f 856//856 778//778 857//857 -f 857//857 778//778 779//779 -f 857//857 779//779 858//858 -f 858//858 779//779 780//780 -f 858//858 780//780 859//859 -f 859//859 780//780 781//781 -f 859//859 781//781 860//860 -f 860//860 781//781 782//782 -f 860//860 782//782 861//861 -f 782//782 783//783 861//861 -f 861//861 783//783 615//615 -f 861//861 615//615 862//862 -f 862//862 615//615 614//614 -f 862//862 614//614 863//863 -f 863//863 614//614 784//784 -f 863//863 784//784 864//864 -f 864//864 784//784 788//788 -f 864//864 788//788 865//865 -f 865//865 788//788 794//794 -f 865//865 794//794 866//866 -f 866//866 794//794 793//793 -f 866//866 793//793 867//867 -f 867//867 793//793 792//792 -f 867//867 792//792 868//868 -f 792//792 791//791 868//868 -f 868//868 791//791 790//790 -f 868//868 790//790 869//869 -f 869//869 790//790 789//789 -f 869//869 789//789 870//870 -f 870//870 789//789 795//795 -f 870//870 795//795 871//871 -f 795//795 796//796 871//871 -f 871//871 796//796 797//797 -f 871//871 797//797 872//872 -f 872//872 797//797 798//798 -f 872//872 798//798 873//873 -f 873//873 798//798 874//874 -f 874//874 798//798 799//799 -f 874//874 799//799 875//875 -f 875//875 799//799 800//800 -f 875//875 800//800 876//876 -f 876//876 800//800 612//612 -f 876//876 612//612 877//877 -f 877//877 612//612 611//611 -f 877//877 611//611 878//878 -f 611//611 801//801 878//878 -f 878//878 801//801 805//805 -f 878//878 805//805 879//879 -f 879//879 805//805 811//811 -f 879//879 811//811 880//880 -f 880//880 811//811 810//810 -f 880//880 810//810 881//881 -f 810//810 809//809 881//881 -f 881//881 809//809 808//808 -f 881//881 808//808 882//882 -f 882//882 808//808 807//807 -f 882//882 807//807 883//883 -f 883//883 807//807 806//806 -f 883//883 806//806 884//884 -f 884//884 806//806 812//812 -f 884//884 812//812 885//885 -f 885//885 812//812 813//813 -f 885//885 813//813 886//886 -f 886//886 813//813 814//814 -f 886//886 814//814 887//887 -f 887//887 814//814 815//815 -f 887//887 815//815 888//888 -f 888//888 815//815 816//816 -f 888//888 816//816 889//889 -f 889//889 816//816 817//817 -f 889//889 817//817 890//890 -f 890//890 817//817 609//609 -f 890//890 609//609 891//891 -f 609//609 608//608 891//891 -f 891//891 608//608 818//818 -f 891//891 818//818 892//892 -f 892//892 818//818 822//822 -f 892//892 822//822 893//893 -f 893//893 822//822 823//823 -f 893//893 823//823 894//894 -f 894//894 823//823 606//606 -f 894//894 606//606 895//895 -f 895//895 606//606 605//605 -f 895//895 605//605 896//896 -f 605//605 824//824 896//896 -f 896//896 824//824 828//828 -f 896//896 828//828 897//897 -f 897//897 828//828 834//834 -f 897//897 834//834 898//898 -f 898//898 834//834 833//833 -f 898//898 833//833 899//899 -f 899//899 833//833 832//832 -f 899//899 832//832 900//900 -f 900//900 832//832 831//831 -f 900//900 831//831 901//901 -f 901//901 831//831 830//830 -f 901//901 830//830 902//902 -f 902//902 830//830 829//829 -f 902//902 829//829 903//903 -f 903//903 829//829 747//747 -f 903//903 747//747 904//904 -f 904//904 747//747 748//748 -f 904//904 748//748 835//835 -f 835//835 748//748 749//749 -f 835//835 749//749 750//750 -f 905//905 906//906 907//907 -f 908//908 909//909 910//910 -f 911//911 912//912 913//913 -f 914//914 915//915 916//916 -f 917//917 918//918 919//919 -f 920//920 921//921 922//922 -f 923//923 924//924 925//925 -f 897//897 898//898 905//905 -f 895//895 896//896 926//926 -f 893//893 894//894 927//927 -f 887//887 888//888 908//908 -f 885//885 886//886 928//928 -f 883//883 884//884 929//929 -f 877//877 878//878 911//911 -f 875//875 876//876 930//930 -f 873//873 874//874 931//931 -f 867//867 868//868 914//914 -f 865//865 866//866 932//932 -f 863//863 864//864 933//933 -f 857//857 858//858 917//917 -f 855//855 856//856 934//934 -f 853//853 854//854 935//935 -f 849//849 850//850 920//920 -f 847//847 848//848 936//936 -f 845//845 846//846 937//937 -f 837//837 838//838 923//923 -f 835//835 836//836 938//938 -f 903//903 904//904 939//939 -f 901//901 902//902 940//940 -f 940//940 902//902 903//903 -f 923//923 838//838 924//924 -f 924//924 838//838 839//839 -f 924//924 839//839 840//840 -f 843//843 844//844 941//941 -f 941//941 844//844 845//845 -f 920//920 850//850 921//921 -f 921//921 850//850 851//851 -f 921//921 851//851 842//842 -f 841//841 852//852 942//942 -f 942//942 852//852 853//853 -f 917//917 858//858 918//918 -f 918//918 858//858 859//859 -f 918//918 859//859 860//860 -f 861//861 862//862 943//943 -f 943//943 862//862 863//863 -f 914//914 868//868 915//915 -f 915//915 868//868 869//869 -f 915//915 869//869 870//870 -f 871//871 872//872 944//944 -f 944//944 872//872 873//873 -f 911//911 878//878 912//912 -f 912//912 878//878 879//879 -f 912//912 879//879 880//880 -f 881//881 882//882 945//945 -f 945//945 882//882 883//883 -f 908//908 888//888 909//909 -f 909//909 888//888 889//889 -f 909//909 889//889 890//890 -f 891//891 892//892 946//946 -f 946//946 892//892 893//893 -f 905//905 898//898 906//906 -f 906//906 898//898 899//899 -f 906//906 899//899 900//900 -f 947//947 948//948 939//939 -f 949//949 925//925 950//950 -f 950//950 925//925 924//924 -f 950//950 924//924 951//951 -f 951//951 924//924 840//840 -f 951//951 840//840 843//843 -f 952//952 953//953 937//937 -f 954//954 922//922 955//955 -f 955//955 922//922 921//921 -f 955//955 921//921 956//956 -f 956//956 921//921 842//842 -f 956//956 842//842 841//841 -f 957//957 958//958 935//935 -f 959//959 919//919 960//960 -f 960//960 919//919 918//918 -f 960//960 918//918 961//961 -f 961//961 918//918 860//860 -f 961//961 860//860 861//861 -f 962//962 963//963 933//933 -f 964//964 916//916 965//965 -f 965//965 916//916 915//915 -f 965//965 915//915 966//966 -f 966//966 915//915 870//870 -f 966//966 870//870 871//871 -f 967//967 968//968 931//931 -f 969//969 913//913 970//970 -f 970//970 913//913 912//912 -f 970//970 912//912 971//971 -f 971//971 912//912 880//880 -f 971//971 880//880 881//881 -f 972//972 973//973 929//929 -f 974//974 910//910 975//975 -f 975//975 910//910 909//909 -f 975//975 909//909 976//976 -f 976//976 909//909 890//890 -f 976//976 890//890 891//891 -f 977//977 978//978 927//927 -f 979//979 907//907 980//980 -f 980//980 907//907 906//906 -f 980//980 906//906 981//981 -f 981//981 906//906 900//900 -f 981//981 900//900 901//901 -f 982//982 948//948 983//983 -f 983//983 948//948 947//947 -f 983//983 947//947 984//984 -f 985//985 953//953 986//986 -f 986//986 953//953 952//952 -f 986//986 952//952 987//987 -f 988//988 958//958 989//989 -f 989//989 958//958 957//957 -f 989//989 957//957 990//990 -f 991//991 963//963 992//992 -f 992//992 963//963 962//962 -f 992//992 962//962 993//993 -f 994//994 968//968 995//995 -f 995//995 968//968 967//967 -f 995//995 967//967 996//996 -f 997//997 973//973 998//998 -f 998//998 973//973 972//972 -f 998//998 972//972 999//999 -f 1000//1000 978//978 1001//1001 -f 1001//1001 978//978 977//977 -f 1001//1001 977//977 1002//1002 -f 1003//1003 1004//1004 1005//1005 -f 901//901 940//940 981//981 -f 981//981 940//940 1006//1006 -f 981//981 1006//1006 980//980 -f 980//980 1006//1006 1003//1003 -f 980//980 1003//1003 979//979 -f 979//979 1003//1003 1005//1005 -f 979//979 1005//1005 1007//1007 -f 903//903 939//939 940//940 -f 940//940 939//939 948//948 -f 940//940 948//948 1006//1006 -f 1006//1006 948//948 982//982 -f 1006//1006 982//982 1003//1003 -f 1003//1003 982//982 1008//1008 -f 1003//1003 1008//1008 1004//1004 -f 1009//1009 1010//1010 1011//1011 -f 1011//1011 1010//1010 984//984 -f 1011//1011 984//984 1012//1012 -f 1012//1012 984//984 947//947 -f 1012//1012 947//947 938//938 -f 938//938 947//947 939//939 -f 938//938 939//939 835//835 -f 835//835 939//939 904//904 -f 1010//1010 1013//1013 984//984 -f 984//984 1013//1013 1014//1014 -f 984//984 1014//1014 983//983 -f 983//983 1014//1014 1015//1015 -f 983//983 1015//1015 982//982 -f 982//982 1015//1015 1016//1016 -f 982//982 1016//1016 1008//1008 -f 836//836 837//837 938//938 -f 938//938 837//837 923//923 -f 938//938 923//923 1012//1012 -f 1012//1012 923//923 925//925 -f 1012//1012 925//925 1011//1011 -f 1011//1011 925//925 949//949 -f 1011//1011 949//949 1009//1009 -f 1009//1009 949//949 1017//1017 -f 1018//1018 1019//1019 1020//1020 -f 843//843 941//941 951//951 -f 951//951 941//941 1021//1021 -f 951//951 1021//1021 950//950 -f 950//950 1021//1021 1018//1018 -f 950//950 1018//1018 949//949 -f 949//949 1018//1018 1020//1020 -f 949//949 1020//1020 1017//1017 -f 845//845 937//937 941//941 -f 941//941 937//937 953//953 -f 941//941 953//953 1021//1021 -f 1021//1021 953//953 985//985 -f 1021//1021 985//985 1018//1018 -f 1018//1018 985//985 1022//1022 -f 1018//1018 1022//1022 1019//1019 -f 1023//1023 1024//1024 1025//1025 -f 1025//1025 1024//1024 987//987 -f 1025//1025 987//987 1026//1026 -f 1026//1026 987//987 952//952 -f 1026//1026 952//952 936//936 -f 936//936 952//952 937//937 -f 936//936 937//937 847//847 -f 847//847 937//937 846//846 -f 1024//1024 1027//1027 987//987 -f 987//987 1027//1027 1028//1028 -f 987//987 1028//1028 986//986 -f 986//986 1028//1028 1029//1029 -f 986//986 1029//1029 985//985 -f 985//985 1029//1029 1030//1030 -f 985//985 1030//1030 1022//1022 -f 848//848 849//849 936//936 -f 936//936 849//849 920//920 -f 936//936 920//920 1026//1026 -f 1026//1026 920//920 922//922 -f 1026//1026 922//922 1025//1025 -f 1025//1025 922//922 954//954 -f 1025//1025 954//954 1023//1023 -f 1023//1023 954//954 1031//1031 -f 1032//1032 1033//1033 1034//1034 -f 841//841 942//942 956//956 -f 956//956 942//942 1035//1035 -f 956//956 1035//1035 955//955 -f 955//955 1035//1035 1032//1032 -f 955//955 1032//1032 954//954 -f 954//954 1032//1032 1034//1034 -f 954//954 1034//1034 1031//1031 -f 853//853 935//935 942//942 -f 942//942 935//935 958//958 -f 942//942 958//958 1035//1035 -f 1035//1035 958//958 988//988 -f 1035//1035 988//988 1032//1032 -f 1032//1032 988//988 1036//1036 -f 1032//1032 1036//1036 1033//1033 -f 1037//1037 1038//1038 1039//1039 -f 1039//1039 1038//1038 990//990 -f 1039//1039 990//990 1040//1040 -f 1040//1040 990//990 957//957 -f 1040//1040 957//957 934//934 -f 934//934 957//957 935//935 -f 934//934 935//935 855//855 -f 855//855 935//935 854//854 -f 1038//1038 1041//1041 990//990 -f 990//990 1041//1041 1042//1042 -f 990//990 1042//1042 989//989 -f 989//989 1042//1042 1043//1043 -f 989//989 1043//1043 988//988 -f 988//988 1043//1043 1044//1044 -f 988//988 1044//1044 1036//1036 -f 856//856 857//857 934//934 -f 934//934 857//857 917//917 -f 934//934 917//917 1040//1040 -f 1040//1040 917//917 919//919 -f 1040//1040 919//919 1039//1039 -f 1039//1039 919//919 959//959 -f 1039//1039 959//959 1037//1037 -f 1037//1037 959//959 1045//1045 -f 1046//1046 1047//1047 1048//1048 -f 861//861 943//943 961//961 -f 961//961 943//943 1049//1049 -f 961//961 1049//1049 960//960 -f 960//960 1049//1049 1046//1046 -f 960//960 1046//1046 959//959 -f 959//959 1046//1046 1048//1048 -f 959//959 1048//1048 1045//1045 -f 863//863 933//933 943//943 -f 943//943 933//933 963//963 -f 943//943 963//963 1049//1049 -f 1049//1049 963//963 991//991 -f 1049//1049 991//991 1046//1046 -f 1046//1046 991//991 1050//1050 -f 1046//1046 1050//1050 1047//1047 -f 1051//1051 1052//1052 1053//1053 -f 1053//1053 1052//1052 993//993 -f 1053//1053 993//993 1054//1054 -f 1054//1054 993//993 962//962 -f 1054//1054 962//962 932//932 -f 932//932 962//962 933//933 -f 932//932 933//933 865//865 -f 865//865 933//933 864//864 -f 1052//1052 1055//1055 993//993 -f 993//993 1055//1055 1056//1056 -f 993//993 1056//1056 992//992 -f 992//992 1056//1056 1057//1057 -f 992//992 1057//1057 991//991 -f 991//991 1057//1057 1058//1058 -f 991//991 1058//1058 1050//1050 -f 866//866 867//867 932//932 -f 932//932 867//867 914//914 -f 932//932 914//914 1054//1054 -f 1054//1054 914//914 916//916 -f 1054//1054 916//916 1053//1053 -f 1053//1053 916//916 964//964 -f 1053//1053 964//964 1051//1051 -f 1051//1051 964//964 1059//1059 -f 1060//1060 1061//1061 1062//1062 -f 871//871 944//944 966//966 -f 966//966 944//944 1063//1063 -f 966//966 1063//1063 965//965 -f 965//965 1063//1063 1060//1060 -f 965//965 1060//1060 964//964 -f 964//964 1060//1060 1062//1062 -f 964//964 1062//1062 1059//1059 -f 873//873 931//931 944//944 -f 944//944 931//931 968//968 -f 944//944 968//968 1063//1063 -f 1063//1063 968//968 994//994 -f 1063//1063 994//994 1060//1060 -f 1060//1060 994//994 1064//1064 -f 1060//1060 1064//1064 1061//1061 -f 1065//1065 1066//1066 1067//1067 -f 1067//1067 1066//1066 996//996 -f 1067//1067 996//996 1068//1068 -f 1068//1068 996//996 967//967 -f 1068//1068 967//967 930//930 -f 930//930 967//967 931//931 -f 930//930 931//931 875//875 -f 875//875 931//931 874//874 -f 1066//1066 1069//1069 996//996 -f 996//996 1069//1069 1070//1070 -f 996//996 1070//1070 995//995 -f 995//995 1070//1070 1071//1071 -f 995//995 1071//1071 994//994 -f 994//994 1071//1071 1072//1072 -f 994//994 1072//1072 1064//1064 -f 876//876 877//877 930//930 -f 930//930 877//877 911//911 -f 930//930 911//911 1068//1068 -f 1068//1068 911//911 913//913 -f 1068//1068 913//913 1067//1067 -f 1067//1067 913//913 969//969 -f 1067//1067 969//969 1065//1065 -f 1065//1065 969//969 1073//1073 -f 1074//1074 1075//1075 1076//1076 -f 881//881 945//945 971//971 -f 971//971 945//945 1077//1077 -f 971//971 1077//1077 970//970 -f 970//970 1077//1077 1074//1074 -f 970//970 1074//1074 969//969 -f 969//969 1074//1074 1076//1076 -f 969//969 1076//1076 1073//1073 -f 883//883 929//929 945//945 -f 945//945 929//929 973//973 -f 945//945 973//973 1077//1077 -f 1077//1077 973//973 997//997 -f 1077//1077 997//997 1074//1074 -f 1074//1074 997//997 1078//1078 -f 1074//1074 1078//1078 1075//1075 -f 1079//1079 1080//1080 1081//1081 -f 1081//1081 1080//1080 999//999 -f 1081//1081 999//999 1082//1082 -f 1082//1082 999//999 972//972 -f 1082//1082 972//972 928//928 -f 928//928 972//972 929//929 -f 928//928 929//929 885//885 -f 885//885 929//929 884//884 -f 1080//1080 1083//1083 999//999 -f 999//999 1083//1083 1084//1084 -f 999//999 1084//1084 998//998 -f 998//998 1084//1084 1085//1085 -f 998//998 1085//1085 997//997 -f 997//997 1085//1085 1086//1086 -f 997//997 1086//1086 1078//1078 -f 886//886 887//887 928//928 -f 928//928 887//887 908//908 -f 928//928 908//908 1082//1082 -f 1082//1082 908//908 910//910 -f 1082//1082 910//910 1081//1081 -f 1081//1081 910//910 974//974 -f 1081//1081 974//974 1079//1079 -f 1079//1079 974//974 1087//1087 -f 1088//1088 1089//1089 1090//1090 -f 891//891 946//946 976//976 -f 976//976 946//946 1091//1091 -f 976//976 1091//1091 975//975 -f 975//975 1091//1091 1088//1088 -f 975//975 1088//1088 974//974 -f 974//974 1088//1088 1090//1090 -f 974//974 1090//1090 1087//1087 -f 893//893 927//927 946//946 -f 946//946 927//927 978//978 -f 946//946 978//978 1091//1091 -f 1091//1091 978//978 1000//1000 -f 1091//1091 1000//1000 1088//1088 -f 1088//1088 1000//1000 1092//1092 -f 1088//1088 1092//1092 1089//1089 -f 1093//1093 1094//1094 1095//1095 -f 1095//1095 1094//1094 1002//1002 -f 1095//1095 1002//1002 1096//1096 -f 1096//1096 1002//1002 977//977 -f 1096//1096 977//977 926//926 -f 926//926 977//977 927//927 -f 926//926 927//927 895//895 -f 895//895 927//927 894//894 -f 1094//1094 1097//1097 1002//1002 -f 1002//1002 1097//1097 1098//1098 -f 1002//1002 1098//1098 1001//1001 -f 1001//1001 1098//1098 1099//1099 -f 1001//1001 1099//1099 1000//1000 -f 1000//1000 1099//1099 1100//1100 -f 1000//1000 1100//1100 1092//1092 -f 896//896 897//897 926//926 -f 926//926 897//897 905//905 -f 926//926 905//905 1096//1096 -f 1096//1096 905//905 907//907 -f 1096//1096 907//907 1095//1095 -f 1095//1095 907//907 979//979 -f 1095//1095 979//979 1093//1093 -f 1093//1093 979//979 1007//1007 -f 1057//1057 1101//1101 1058//1058 -f 1058//1058 1101//1101 1102//1102 -f 1058//1058 1102//1102 1050//1050 -f 1050//1050 1102//1102 1103//1103 -f 1050//1050 1103//1103 1047//1047 -f 1047//1047 1103//1103 1104//1104 -f 1047//1047 1104//1104 1048//1048 -f 1048//1048 1104//1104 1105//1105 -f 1048//1048 1105//1105 1045//1045 -f 1045//1045 1105//1105 1106//1106 -f 1045//1045 1106//1106 1037//1037 -f 1037//1037 1106//1106 1107//1107 -f 1037//1037 1107//1107 1038//1038 -f 1107//1107 1108//1108 1038//1038 -f 1038//1038 1108//1108 1109//1109 -f 1038//1038 1109//1109 1041//1041 -f 1041//1041 1109//1109 1110//1110 -f 1041//1041 1110//1110 1042//1042 -f 1042//1042 1110//1110 1111//1111 -f 1042//1042 1111//1111 1043//1043 -f 1111//1111 1112//1112 1043//1043 -f 1043//1043 1112//1112 1113//1113 -f 1043//1043 1113//1113 1044//1044 -f 1044//1044 1113//1113 1114//1114 -f 1044//1044 1114//1114 1036//1036 -f 1036//1036 1114//1114 1115//1115 -f 1036//1036 1115//1115 1033//1033 -f 1033//1033 1115//1115 1116//1116 -f 1033//1033 1116//1116 1034//1034 -f 1034//1034 1116//1116 1117//1117 -f 1034//1034 1117//1117 1031//1031 -f 1031//1031 1117//1117 1118//1118 -f 1031//1031 1118//1118 1023//1023 -f 1023//1023 1118//1118 1119//1119 -f 1023//1023 1119//1119 1024//1024 -f 1119//1119 1120//1120 1024//1024 -f 1024//1024 1120//1120 1121//1121 -f 1024//1024 1121//1121 1027//1027 -f 1027//1027 1121//1121 1122//1122 -f 1027//1027 1122//1122 1028//1028 -f 1028//1028 1122//1122 1123//1123 -f 1028//1028 1123//1123 1029//1029 -f 1123//1123 1124//1124 1029//1029 -f 1029//1029 1124//1124 1125//1125 -f 1029//1029 1125//1125 1030//1030 -f 1030//1030 1125//1125 1126//1126 -f 1030//1030 1126//1126 1022//1022 -f 1022//1022 1126//1126 1127//1127 -f 1022//1022 1127//1127 1019//1019 -f 1019//1019 1127//1127 1128//1128 -f 1019//1019 1128//1128 1020//1020 -f 1020//1020 1128//1128 1129//1129 -f 1020//1020 1129//1129 1017//1017 -f 1017//1017 1129//1129 1130//1130 -f 1017//1017 1130//1130 1009//1009 -f 1009//1009 1130//1130 1131//1131 -f 1009//1009 1131//1131 1010//1010 -f 1131//1131 1132//1132 1010//1010 -f 1010//1010 1132//1132 1133//1133 -f 1010//1010 1133//1133 1013//1013 -f 1013//1013 1133//1133 1134//1134 -f 1013//1013 1134//1134 1014//1014 -f 1014//1014 1134//1134 1135//1135 -f 1014//1014 1135//1135 1015//1015 -f 1135//1135 1136//1136 1015//1015 -f 1015//1015 1136//1136 1137//1137 -f 1015//1015 1137//1137 1016//1016 -f 1016//1016 1137//1137 1138//1138 -f 1016//1016 1138//1138 1008//1008 -f 1008//1008 1138//1138 1139//1139 -f 1008//1008 1139//1139 1004//1004 -f 1004//1004 1139//1139 1140//1140 -f 1004//1004 1140//1140 1005//1005 -f 1005//1005 1140//1140 1141//1141 -f 1005//1005 1141//1141 1007//1007 -f 1007//1007 1141//1141 1142//1142 -f 1007//1007 1142//1142 1093//1093 -f 1093//1093 1142//1142 1143//1143 -f 1093//1093 1143//1143 1094//1094 -f 1143//1143 1144//1144 1094//1094 -f 1094//1094 1144//1144 1145//1145 -f 1094//1094 1145//1145 1097//1097 -f 1097//1097 1145//1145 1146//1146 -f 1097//1097 1146//1146 1098//1098 -f 1098//1098 1146//1146 1147//1147 -f 1098//1098 1147//1147 1099//1099 -f 1147//1147 1148//1148 1099//1099 -f 1099//1099 1148//1148 1149//1149 -f 1099//1099 1149//1149 1100//1100 -f 1100//1100 1149//1149 1150//1150 -f 1100//1100 1150//1150 1092//1092 -f 1092//1092 1150//1150 1151//1151 -f 1092//1092 1151//1151 1089//1089 -f 1089//1089 1151//1151 1152//1152 -f 1089//1089 1152//1152 1090//1090 -f 1090//1090 1152//1152 1153//1153 -f 1090//1090 1153//1153 1087//1087 -f 1087//1087 1153//1153 1154//1154 -f 1087//1087 1154//1154 1079//1079 -f 1079//1079 1154//1154 1155//1155 -f 1079//1079 1155//1155 1080//1080 -f 1155//1155 1156//1156 1080//1080 -f 1080//1080 1156//1156 1157//1157 -f 1080//1080 1157//1157 1083//1083 -f 1083//1083 1157//1157 1158//1158 -f 1083//1083 1158//1158 1084//1084 -f 1084//1084 1158//1158 1159//1159 -f 1084//1084 1159//1159 1085//1085 -f 1159//1159 1160//1160 1085//1085 -f 1085//1085 1160//1160 1161//1161 -f 1085//1085 1161//1161 1086//1086 -f 1086//1086 1161//1161 1162//1162 -f 1086//1086 1162//1162 1078//1078 -f 1078//1078 1162//1162 1163//1163 -f 1078//1078 1163//1163 1075//1075 -f 1075//1075 1163//1163 1164//1164 -f 1075//1075 1164//1164 1076//1076 -f 1076//1076 1164//1164 1165//1165 -f 1076//1076 1165//1165 1073//1073 -f 1073//1073 1165//1165 1166//1166 -f 1073//1073 1166//1166 1065//1065 -f 1065//1065 1166//1166 1167//1167 -f 1065//1065 1167//1167 1066//1066 -f 1167//1167 1168//1168 1066//1066 -f 1066//1066 1168//1168 1169//1169 -f 1066//1066 1169//1169 1069//1069 -f 1069//1069 1169//1169 1170//1170 -f 1069//1069 1170//1170 1070//1070 -f 1070//1070 1170//1170 1171//1171 -f 1070//1070 1171//1171 1071//1071 -f 1171//1171 1172//1172 1071//1071 -f 1071//1071 1172//1172 1173//1173 -f 1071//1071 1173//1173 1072//1072 -f 1072//1072 1173//1173 1174//1174 -f 1072//1072 1174//1174 1064//1064 -f 1064//1064 1174//1174 1175//1175 -f 1064//1064 1175//1175 1061//1061 -f 1061//1061 1175//1175 1176//1176 -f 1061//1061 1176//1176 1062//1062 -f 1062//1062 1176//1176 1177//1177 -f 1062//1062 1177//1177 1059//1059 -f 1059//1059 1177//1177 1178//1178 -f 1059//1059 1178//1178 1051//1051 -f 1051//1051 1178//1178 1179//1179 -f 1051//1051 1179//1179 1052//1052 -f 1179//1179 1180//1180 1052//1052 -f 1052//1052 1180//1180 1181//1181 -f 1052//1052 1181//1181 1055//1055 -f 1055//1055 1181//1181 1182//1182 -f 1055//1055 1182//1182 1056//1056 -f 1056//1056 1182//1182 1183//1183 -f 1056//1056 1183//1183 1057//1057 -f 1057//1057 1183//1183 1184//1184 -f 1057//1057 1184//1184 1101//1101 -f 1141//1141 1185//1185 1186//1186 -f 1141//1141 1140//1140 1185//1185 -f 1185//1185 1140//1140 1139//1139 -f 1185//1185 1139//1139 1187//1187 -f 1187//1187 1139//1139 1138//1138 -f 1187//1187 1138//1138 1188//1188 -f 1138//1138 1137//1137 1188//1188 -f 1188//1188 1137//1137 1136//1136 -f 1188//1188 1136//1136 1189//1189 -f 1189//1189 1136//1136 1135//1135 -f 1189//1189 1135//1135 1190//1190 -f 1190//1190 1135//1135 1134//1134 -f 1129//1129 1191//1191 1192//1192 -f 1134//1134 1133//1133 1190//1190 -f 1190//1190 1133//1133 1132//1132 -f 1190//1190 1132//1132 1193//1193 -f 1193//1193 1132//1132 1131//1131 -f 1193//1193 1131//1131 1192//1192 -f 1192//1192 1131//1131 1130//1130 -f 1192//1192 1130//1130 1129//1129 -f 1129//1129 1128//1128 1191//1191 -f 1191//1191 1128//1128 1127//1127 -f 1191//1191 1127//1127 1194//1194 -f 1194//1194 1127//1127 1126//1126 -f 1194//1194 1126//1126 1195//1195 -f 1126//1126 1125//1125 1195//1195 -f 1195//1195 1125//1125 1124//1124 -f 1195//1195 1124//1124 1196//1196 -f 1196//1196 1124//1124 1123//1123 -f 1196//1196 1123//1123 1197//1197 -f 1197//1197 1123//1123 1122//1122 -f 1117//1117 1198//1198 1199//1199 -f 1122//1122 1121//1121 1197//1197 -f 1197//1197 1121//1121 1120//1120 -f 1197//1197 1120//1120 1200//1200 -f 1200//1200 1120//1120 1119//1119 -f 1200//1200 1119//1119 1199//1199 -f 1199//1199 1119//1119 1118//1118 -f 1199//1199 1118//1118 1117//1117 -f 1117//1117 1116//1116 1198//1198 -f 1198//1198 1116//1116 1115//1115 -f 1198//1198 1115//1115 1201//1201 -f 1201//1201 1115//1115 1114//1114 -f 1201//1201 1114//1114 1202//1202 -f 1114//1114 1113//1113 1202//1202 -f 1202//1202 1113//1113 1112//1112 -f 1202//1202 1112//1112 1203//1203 -f 1203//1203 1112//1112 1111//1111 -f 1203//1203 1111//1111 1204//1204 -f 1204//1204 1111//1111 1110//1110 -f 1105//1105 1205//1205 1206//1206 -f 1110//1110 1109//1109 1204//1204 -f 1204//1204 1109//1109 1108//1108 -f 1204//1204 1108//1108 1207//1207 -f 1207//1207 1108//1108 1107//1107 -f 1207//1207 1107//1107 1206//1206 -f 1206//1206 1107//1107 1106//1106 -f 1206//1206 1106//1106 1105//1105 -f 1105//1105 1104//1104 1205//1205 -f 1205//1205 1104//1104 1103//1103 -f 1205//1205 1103//1103 1208//1208 -f 1208//1208 1103//1103 1102//1102 -f 1208//1208 1102//1102 1209//1209 -f 1102//1102 1101//1101 1209//1209 -f 1209//1209 1101//1101 1184//1184 -f 1209//1209 1184//1184 1210//1210 -f 1210//1210 1184//1184 1183//1183 -f 1210//1210 1183//1183 1211//1211 -f 1211//1211 1183//1183 1182//1182 -f 1177//1177 1212//1212 1213//1213 -f 1182//1182 1181//1181 1211//1211 -f 1211//1211 1181//1181 1180//1180 -f 1211//1211 1180//1180 1214//1214 -f 1214//1214 1180//1180 1179//1179 -f 1214//1214 1179//1179 1213//1213 -f 1213//1213 1179//1179 1178//1178 -f 1213//1213 1178//1178 1177//1177 -f 1177//1177 1176//1176 1212//1212 -f 1212//1212 1176//1176 1175//1175 -f 1212//1212 1175//1175 1215//1215 -f 1215//1215 1175//1175 1174//1174 -f 1215//1215 1174//1174 1216//1216 -f 1174//1174 1173//1173 1216//1216 -f 1216//1216 1173//1173 1172//1172 -f 1216//1216 1172//1172 1217//1217 -f 1217//1217 1172//1172 1171//1171 -f 1217//1217 1171//1171 1218//1218 -f 1218//1218 1171//1171 1170//1170 -f 1165//1165 1219//1219 1220//1220 -f 1170//1170 1169//1169 1218//1218 -f 1218//1218 1169//1169 1168//1168 -f 1218//1218 1168//1168 1221//1221 -f 1221//1221 1168//1168 1167//1167 -f 1221//1221 1167//1167 1220//1220 -f 1220//1220 1167//1167 1166//1166 -f 1220//1220 1166//1166 1165//1165 -f 1165//1165 1164//1164 1219//1219 -f 1219//1219 1164//1164 1163//1163 -f 1219//1219 1163//1163 1222//1222 -f 1222//1222 1163//1163 1162//1162 -f 1222//1222 1162//1162 1223//1223 -f 1162//1162 1161//1161 1223//1223 -f 1223//1223 1161//1161 1160//1160 -f 1223//1223 1160//1160 1224//1224 -f 1224//1224 1160//1160 1159//1159 -f 1224//1224 1159//1159 1225//1225 -f 1225//1225 1159//1159 1158//1158 -f 1153//1153 1226//1226 1227//1227 -f 1158//1158 1157//1157 1225//1225 -f 1225//1225 1157//1157 1156//1156 -f 1225//1225 1156//1156 1228//1228 -f 1228//1228 1156//1156 1155//1155 -f 1228//1228 1155//1155 1227//1227 -f 1227//1227 1155//1155 1154//1154 -f 1227//1227 1154//1154 1153//1153 -f 1153//1153 1152//1152 1226//1226 -f 1226//1226 1152//1152 1151//1151 -f 1226//1226 1151//1151 1229//1229 -f 1229//1229 1151//1151 1150//1150 -f 1229//1229 1150//1150 1230//1230 -f 1150//1150 1149//1149 1230//1230 -f 1230//1230 1149//1149 1148//1148 -f 1230//1230 1148//1148 1231//1231 -f 1231//1231 1148//1148 1147//1147 -f 1231//1231 1147//1147 1232//1232 -f 1232//1232 1147//1147 1146//1146 -f 1146//1146 1145//1145 1232//1232 -f 1232//1232 1145//1145 1144//1144 -f 1232//1232 1144//1144 1233//1233 -f 1233//1233 1144//1144 1143//1143 -f 1233//1233 1143//1143 1186//1186 -f 1186//1186 1143//1143 1142//1142 -f 1186//1186 1142//1142 1141//1141 -f 1186//1186 1234//1234 1233//1233 -f 1233//1233 1234//1234 1235//1235 -f 1233//1233 1235//1235 1232//1232 -f 1232//1232 1235//1235 1236//1236 -f 1232//1232 1236//1236 1231//1231 -f 1231//1231 1236//1236 1237//1237 -f 1231//1231 1237//1237 1230//1230 -f 1230//1230 1237//1237 1238//1238 -f 1230//1230 1238//1238 1229//1229 -f 1229//1229 1238//1238 1239//1239 -f 1229//1229 1239//1239 1226//1226 -f 1226//1226 1239//1239 1240//1240 -f 1226//1226 1240//1240 1227//1227 -f 1227//1227 1240//1240 1241//1241 -f 1227//1227 1241//1241 1228//1228 -f 1228//1228 1241//1241 1242//1242 -f 1228//1228 1242//1242 1225//1225 -f 1225//1225 1242//1242 1243//1243 -f 1225//1225 1243//1243 1224//1224 -f 1224//1224 1243//1243 1244//1244 -f 1224//1224 1244//1244 1223//1223 -f 1223//1223 1244//1244 1245//1245 -f 1223//1223 1245//1245 1222//1222 -f 1222//1222 1245//1245 1246//1246 -f 1222//1222 1246//1246 1219//1219 -f 1219//1219 1246//1246 1247//1247 -f 1219//1219 1247//1247 1220//1220 -f 1220//1220 1247//1247 1248//1248 -f 1220//1220 1248//1248 1221//1221 -f 1221//1221 1248//1248 1249//1249 -f 1221//1221 1249//1249 1218//1218 -f 1218//1218 1249//1249 1250//1250 -f 1218//1218 1250//1250 1217//1217 -f 1217//1217 1250//1250 1251//1251 -f 1217//1217 1251//1251 1216//1216 -f 1216//1216 1251//1251 1252//1252 -f 1216//1216 1252//1252 1215//1215 -f 1215//1215 1252//1252 1253//1253 -f 1215//1215 1253//1253 1212//1212 -f 1212//1212 1253//1253 1254//1254 -f 1212//1212 1254//1254 1213//1213 -f 1213//1213 1254//1254 1255//1255 -f 1213//1213 1255//1255 1214//1214 -f 1214//1214 1255//1255 1256//1256 -f 1214//1214 1256//1256 1211//1211 -f 1211//1211 1256//1256 1257//1257 -f 1211//1211 1257//1257 1210//1210 -f 1210//1210 1257//1257 1258//1258 -f 1210//1210 1258//1258 1209//1209 -f 1209//1209 1258//1258 1259//1259 -f 1209//1209 1259//1259 1208//1208 -f 1208//1208 1259//1259 1260//1260 -f 1208//1208 1260//1260 1205//1205 -f 1205//1205 1260//1260 1261//1261 -f 1205//1205 1261//1261 1206//1206 -f 1206//1206 1261//1261 1262//1262 -f 1206//1206 1262//1262 1207//1207 -f 1207//1207 1262//1262 1263//1263 -f 1207//1207 1263//1263 1204//1204 -f 1204//1204 1263//1263 1264//1264 -f 1204//1204 1264//1264 1203//1203 -f 1203//1203 1264//1264 1265//1265 -f 1203//1203 1265//1265 1202//1202 -f 1202//1202 1265//1265 1266//1266 -f 1202//1202 1266//1266 1201//1201 -f 1201//1201 1266//1266 1267//1267 -f 1201//1201 1267//1267 1198//1198 -f 1198//1198 1267//1267 1268//1268 -f 1198//1198 1268//1268 1199//1199 -f 1199//1199 1268//1268 1269//1269 -f 1199//1199 1269//1269 1200//1200 -f 1200//1200 1269//1269 1270//1270 -f 1200//1200 1270//1270 1197//1197 -f 1197//1197 1270//1270 1271//1271 -f 1197//1197 1271//1271 1196//1196 -f 1196//1196 1271//1271 1272//1272 -f 1196//1196 1272//1272 1195//1195 -f 1195//1195 1272//1272 1273//1273 -f 1195//1195 1273//1273 1194//1194 -f 1194//1194 1273//1273 1274//1274 -f 1194//1194 1274//1274 1191//1191 -f 1191//1191 1274//1274 1275//1275 -f 1191//1191 1275//1275 1192//1192 -f 1192//1192 1275//1275 1276//1276 -f 1192//1192 1276//1276 1193//1193 -f 1193//1193 1276//1276 1277//1277 -f 1193//1193 1277//1277 1190//1190 -f 1190//1190 1277//1277 1278//1278 -f 1190//1190 1278//1278 1189//1189 -f 1189//1189 1278//1278 1279//1279 -f 1189//1189 1279//1279 1188//1188 -f 1188//1188 1279//1279 1280//1280 -f 1188//1188 1280//1280 1187//1187 -f 1187//1187 1280//1280 1281//1281 -f 1187//1187 1281//1281 1185//1185 -f 1185//1185 1281//1281 1282//1282 -f 1185//1185 1282//1282 1186//1186 -f 1186//1186 1282//1282 1234//1234 -f 1282//1282 1283//1283 1234//1234 -f 1234//1234 1283//1283 1284//1284 -f 1234//1234 1284//1284 1235//1235 -f 1235//1235 1284//1284 1285//1285 -f 1235//1235 1285//1285 1236//1236 -f 1236//1236 1285//1285 1286//1286 -f 1236//1236 1286//1286 1237//1237 -f 1237//1237 1286//1286 1287//1287 -f 1237//1237 1287//1287 1238//1238 -f 1238//1238 1287//1287 1288//1288 -f 1238//1238 1288//1288 1239//1239 -f 1239//1239 1288//1288 1289//1289 -f 1239//1239 1289//1289 1240//1240 -f 1240//1240 1289//1289 1290//1290 -f 1240//1240 1290//1290 1241//1241 -f 1241//1241 1290//1290 1291//1291 -f 1241//1241 1291//1291 1242//1242 -f 1242//1242 1291//1291 1292//1292 -f 1242//1242 1292//1292 1243//1243 -f 1243//1243 1292//1292 1293//1293 -f 1243//1243 1293//1293 1244//1244 -f 1244//1244 1293//1293 1294//1294 -f 1244//1244 1294//1294 1245//1245 -f 1245//1245 1294//1294 1295//1295 -f 1245//1245 1295//1295 1246//1246 -f 1246//1246 1295//1295 1296//1296 -f 1246//1246 1296//1296 1247//1247 -f 1247//1247 1296//1296 1297//1297 -f 1247//1247 1297//1297 1248//1248 -f 1248//1248 1297//1297 1298//1298 -f 1248//1248 1298//1298 1249//1249 -f 1249//1249 1298//1298 1299//1299 -f 1249//1249 1299//1299 1250//1250 -f 1250//1250 1299//1299 1300//1300 -f 1250//1250 1300//1300 1251//1251 -f 1251//1251 1300//1300 1301//1301 -f 1251//1251 1301//1301 1252//1252 -f 1252//1252 1301//1301 1302//1302 -f 1252//1252 1302//1302 1253//1253 -f 1253//1253 1302//1302 1303//1303 -f 1253//1253 1303//1303 1254//1254 -f 1254//1254 1303//1303 1304//1304 -f 1254//1254 1304//1304 1255//1255 -f 1255//1255 1304//1304 1305//1305 -f 1255//1255 1305//1305 1256//1256 -f 1256//1256 1305//1305 1306//1306 -f 1256//1256 1306//1306 1257//1257 -f 1257//1257 1306//1306 1307//1307 -f 1257//1257 1307//1307 1258//1258 -f 1258//1258 1307//1307 1308//1308 -f 1258//1258 1308//1308 1259//1259 -f 1259//1259 1308//1308 1309//1309 -f 1259//1259 1309//1309 1260//1260 -f 1260//1260 1309//1309 1310//1310 -f 1260//1260 1310//1310 1261//1261 -f 1261//1261 1310//1310 1311//1311 -f 1261//1261 1311//1311 1262//1262 -f 1262//1262 1311//1311 1312//1312 -f 1262//1262 1312//1312 1263//1263 -f 1263//1263 1312//1312 1313//1313 -f 1263//1263 1313//1313 1264//1264 -f 1264//1264 1313//1313 1314//1314 -f 1264//1264 1314//1314 1265//1265 -f 1265//1265 1314//1314 1315//1315 -f 1265//1265 1315//1315 1266//1266 -f 1266//1266 1315//1315 1316//1316 -f 1266//1266 1316//1316 1267//1267 -f 1267//1267 1316//1316 1317//1317 -f 1267//1267 1317//1317 1268//1268 -f 1268//1268 1317//1317 1318//1318 -f 1268//1268 1318//1318 1269//1269 -f 1269//1269 1318//1318 1319//1319 -f 1269//1269 1319//1319 1270//1270 -f 1270//1270 1319//1319 1320//1320 -f 1270//1270 1320//1320 1271//1271 -f 1271//1271 1320//1320 1321//1321 -f 1271//1271 1321//1321 1272//1272 -f 1272//1272 1321//1321 1322//1322 -f 1272//1272 1322//1322 1273//1273 -f 1273//1273 1322//1322 1323//1323 -f 1273//1273 1323//1323 1274//1274 -f 1274//1274 1323//1323 1324//1324 -f 1274//1274 1324//1324 1275//1275 -f 1275//1275 1324//1324 1325//1325 -f 1275//1275 1325//1325 1276//1276 -f 1276//1276 1325//1325 1326//1326 -f 1276//1276 1326//1326 1277//1277 -f 1277//1277 1326//1326 1327//1327 -f 1277//1277 1327//1327 1278//1278 -f 1278//1278 1327//1327 1328//1328 -f 1278//1278 1328//1328 1279//1279 -f 1279//1279 1328//1328 1329//1329 -f 1279//1279 1329//1329 1280//1280 -f 1280//1280 1329//1329 1330//1330 -f 1280//1280 1330//1330 1281//1281 -f 1281//1281 1330//1330 1331//1331 -f 1281//1281 1331//1331 1282//1282 -f 1282//1282 1331//1331 1283//1283 -f 1331//1331 1332//1332 1283//1283 -f 1283//1283 1332//1332 1333//1333 -f 1283//1283 1333//1333 1284//1284 -f 1284//1284 1333//1333 1334//1334 -f 1284//1284 1334//1334 1285//1285 -f 1285//1285 1334//1334 1335//1335 -f 1285//1285 1335//1335 1286//1286 -f 1286//1286 1335//1335 1336//1336 -f 1286//1286 1336//1336 1287//1287 -f 1287//1287 1336//1336 1337//1337 -f 1287//1287 1337//1337 1288//1288 -f 1288//1288 1337//1337 1338//1338 -f 1288//1288 1338//1338 1289//1289 -f 1289//1289 1338//1338 1339//1339 -f 1289//1289 1339//1339 1290//1290 -f 1290//1290 1339//1339 1340//1340 -f 1290//1290 1340//1340 1291//1291 -f 1291//1291 1340//1340 1341//1341 -f 1291//1291 1341//1341 1292//1292 -f 1292//1292 1341//1341 1342//1342 -f 1292//1292 1342//1342 1293//1293 -f 1293//1293 1342//1342 1343//1343 -f 1293//1293 1343//1343 1294//1294 -f 1294//1294 1343//1343 1344//1344 -f 1294//1294 1344//1344 1295//1295 -f 1295//1295 1344//1344 1345//1345 -f 1295//1295 1345//1345 1296//1296 -f 1296//1296 1345//1345 1346//1346 -f 1296//1296 1346//1346 1297//1297 -f 1297//1297 1346//1346 1347//1347 -f 1297//1297 1347//1347 1298//1298 -f 1298//1298 1347//1347 1348//1348 -f 1298//1298 1348//1348 1299//1299 -f 1299//1299 1348//1348 1349//1349 -f 1299//1299 1349//1349 1300//1300 -f 1300//1300 1349//1349 1350//1350 -f 1300//1300 1350//1350 1301//1301 -f 1301//1301 1350//1350 1351//1351 -f 1301//1301 1351//1351 1302//1302 -f 1302//1302 1351//1351 1352//1352 -f 1302//1302 1352//1352 1303//1303 -f 1303//1303 1352//1352 1353//1353 -f 1303//1303 1353//1353 1304//1304 -f 1304//1304 1353//1353 1354//1354 -f 1304//1304 1354//1354 1305//1305 -f 1305//1305 1354//1354 1355//1355 -f 1305//1305 1355//1355 1306//1306 -f 1306//1306 1355//1355 1356//1356 -f 1306//1306 1356//1356 1307//1307 -f 1307//1307 1356//1356 1357//1357 -f 1307//1307 1357//1357 1308//1308 -f 1308//1308 1357//1357 1358//1358 -f 1308//1308 1358//1358 1309//1309 -f 1309//1309 1358//1358 1359//1359 -f 1309//1309 1359//1359 1310//1310 -f 1310//1310 1359//1359 1360//1360 -f 1310//1310 1360//1360 1311//1311 -f 1311//1311 1360//1360 1361//1361 -f 1311//1311 1361//1361 1312//1312 -f 1312//1312 1361//1361 1362//1362 -f 1312//1312 1362//1362 1313//1313 -f 1313//1313 1362//1362 1363//1363 -f 1313//1313 1363//1363 1314//1314 -f 1314//1314 1363//1363 1364//1364 -f 1314//1314 1364//1364 1315//1315 -f 1315//1315 1364//1364 1365//1365 -f 1315//1315 1365//1365 1316//1316 -f 1316//1316 1365//1365 1366//1366 -f 1316//1316 1366//1366 1317//1317 -f 1317//1317 1366//1366 1367//1367 -f 1317//1317 1367//1367 1318//1318 -f 1318//1318 1367//1367 1368//1368 -f 1318//1318 1368//1368 1319//1319 -f 1319//1319 1368//1368 1369//1369 -f 1319//1319 1369//1369 1320//1320 -f 1320//1320 1369//1369 1370//1370 -f 1320//1320 1370//1370 1321//1321 -f 1321//1321 1370//1370 1371//1371 -f 1321//1321 1371//1371 1322//1322 -f 1322//1322 1371//1371 1372//1372 -f 1322//1322 1372//1372 1323//1323 -f 1323//1323 1372//1372 1373//1373 -f 1323//1323 1373//1373 1324//1324 -f 1324//1324 1373//1373 1374//1374 -f 1324//1324 1374//1374 1325//1325 -f 1325//1325 1374//1374 1375//1375 -f 1325//1325 1375//1375 1326//1326 -f 1326//1326 1375//1375 1376//1376 -f 1326//1326 1376//1376 1327//1327 -f 1327//1327 1376//1376 1377//1377 -f 1327//1327 1377//1377 1328//1328 -f 1328//1328 1377//1377 1378//1378 -f 1328//1328 1378//1378 1329//1329 -f 1329//1329 1378//1378 1379//1379 -f 1329//1329 1379//1379 1330//1330 -f 1330//1330 1379//1379 1380//1380 -f 1330//1330 1380//1380 1331//1331 -f 1331//1331 1380//1380 1332//1332 -f 1380//1380 1381//1381 1332//1332 -f 1332//1332 1381//1381 1382//1382 -f 1332//1332 1382//1382 1333//1333 -f 1333//1333 1382//1382 1383//1383 -f 1333//1333 1383//1383 1334//1334 -f 1334//1334 1383//1383 1384//1384 -f 1334//1334 1384//1384 1335//1335 -f 1335//1335 1384//1384 1385//1385 -f 1335//1335 1385//1385 1336//1336 -f 1336//1336 1385//1385 1386//1386 -f 1336//1336 1386//1386 1337//1337 -f 1337//1337 1386//1386 1387//1387 -f 1337//1337 1387//1387 1338//1338 -f 1338//1338 1387//1387 1388//1388 -f 1338//1338 1388//1388 1339//1339 -f 1339//1339 1388//1388 1389//1389 -f 1339//1339 1389//1389 1340//1340 -f 1340//1340 1389//1389 1390//1390 -f 1340//1340 1390//1390 1341//1341 -f 1341//1341 1390//1390 1391//1391 -f 1341//1341 1391//1391 1342//1342 -f 1342//1342 1391//1391 1392//1392 -f 1342//1342 1392//1392 1343//1343 -f 1343//1343 1392//1392 1393//1393 -f 1343//1343 1393//1393 1344//1344 -f 1344//1344 1393//1393 1394//1394 -f 1344//1344 1394//1394 1345//1345 -f 1345//1345 1394//1394 1395//1395 -f 1345//1345 1395//1395 1346//1346 -f 1346//1346 1395//1395 1396//1396 -f 1346//1346 1396//1396 1347//1347 -f 1347//1347 1396//1396 1397//1397 -f 1347//1347 1397//1397 1348//1348 -f 1348//1348 1397//1397 1398//1398 -f 1348//1348 1398//1398 1349//1349 -f 1349//1349 1398//1398 1399//1399 -f 1349//1349 1399//1399 1350//1350 -f 1350//1350 1399//1399 1400//1400 -f 1350//1350 1400//1400 1351//1351 -f 1351//1351 1400//1400 1401//1401 -f 1351//1351 1401//1401 1352//1352 -f 1352//1352 1401//1401 1402//1402 -f 1352//1352 1402//1402 1353//1353 -f 1353//1353 1402//1402 1403//1403 -f 1353//1353 1403//1403 1354//1354 -f 1354//1354 1403//1403 1404//1404 -f 1354//1354 1404//1404 1355//1355 -f 1355//1355 1404//1404 1405//1405 -f 1355//1355 1405//1405 1356//1356 -f 1356//1356 1405//1405 1406//1406 -f 1356//1356 1406//1406 1357//1357 -f 1357//1357 1406//1406 1407//1407 -f 1357//1357 1407//1407 1358//1358 -f 1358//1358 1407//1407 1408//1408 -f 1358//1358 1408//1408 1359//1359 -f 1359//1359 1408//1408 1409//1409 -f 1359//1359 1409//1409 1360//1360 -f 1360//1360 1409//1409 1410//1410 -f 1360//1360 1410//1410 1361//1361 -f 1361//1361 1410//1410 1411//1411 -f 1361//1361 1411//1411 1362//1362 -f 1362//1362 1411//1411 1412//1412 -f 1362//1362 1412//1412 1363//1363 -f 1363//1363 1412//1412 1413//1413 -f 1363//1363 1413//1413 1364//1364 -f 1364//1364 1413//1413 1414//1414 -f 1364//1364 1414//1414 1365//1365 -f 1365//1365 1414//1414 1415//1415 -f 1365//1365 1415//1415 1366//1366 -f 1366//1366 1415//1415 1416//1416 -f 1366//1366 1416//1416 1367//1367 -f 1367//1367 1416//1416 1417//1417 -f 1367//1367 1417//1417 1368//1368 -f 1368//1368 1417//1417 1418//1418 -f 1368//1368 1418//1418 1369//1369 -f 1369//1369 1418//1418 1419//1419 -f 1369//1369 1419//1419 1370//1370 -f 1370//1370 1419//1419 1420//1420 -f 1370//1370 1420//1420 1371//1371 -f 1371//1371 1420//1420 1421//1421 -f 1371//1371 1421//1421 1372//1372 -f 1372//1372 1421//1421 1422//1422 -f 1372//1372 1422//1422 1373//1373 -f 1373//1373 1422//1422 1423//1423 -f 1373//1373 1423//1423 1374//1374 -f 1374//1374 1423//1423 1424//1424 -f 1374//1374 1424//1424 1375//1375 -f 1375//1375 1424//1424 1425//1425 -f 1375//1375 1425//1425 1376//1376 -f 1376//1376 1425//1425 1426//1426 -f 1376//1376 1426//1426 1377//1377 -f 1377//1377 1426//1426 1427//1427 -f 1377//1377 1427//1427 1378//1378 -f 1378//1378 1427//1427 1428//1428 -f 1378//1378 1428//1428 1379//1379 -f 1379//1379 1428//1428 1429//1429 -f 1379//1379 1429//1429 1380//1380 -f 1380//1380 1429//1429 1381//1381 -f 1429//1429 1430//1430 1381//1381 -f 1381//1381 1430//1430 1431//1431 -f 1381//1381 1431//1431 1382//1382 -f 1382//1382 1431//1431 1432//1432 -f 1382//1382 1432//1432 1383//1383 -f 1383//1383 1432//1432 1433//1433 -f 1383//1383 1433//1433 1384//1384 -f 1384//1384 1433//1433 1434//1434 -f 1384//1384 1434//1434 1385//1385 -f 1385//1385 1434//1434 1435//1435 -f 1385//1385 1435//1435 1386//1386 -f 1386//1386 1435//1435 1436//1436 -f 1386//1386 1436//1436 1387//1387 -f 1387//1387 1436//1436 1437//1437 -f 1387//1387 1437//1437 1388//1388 -f 1388//1388 1437//1437 1438//1438 -f 1388//1388 1438//1438 1389//1389 -f 1389//1389 1438//1438 1439//1439 -f 1389//1389 1439//1439 1390//1390 -f 1390//1390 1439//1439 1440//1440 -f 1390//1390 1440//1440 1391//1391 -f 1391//1391 1440//1440 1441//1441 -f 1391//1391 1441//1441 1392//1392 -f 1392//1392 1441//1441 1442//1442 -f 1392//1392 1442//1442 1393//1393 -f 1393//1393 1442//1442 1443//1443 -f 1393//1393 1443//1443 1394//1394 -f 1394//1394 1443//1443 1444//1444 -f 1394//1394 1444//1444 1395//1395 -f 1395//1395 1444//1444 1445//1445 -f 1395//1395 1445//1445 1396//1396 -f 1396//1396 1445//1445 1446//1446 -f 1396//1396 1446//1446 1397//1397 -f 1397//1397 1446//1446 1447//1447 -f 1397//1397 1447//1447 1398//1398 -f 1398//1398 1447//1447 1448//1448 -f 1398//1398 1448//1448 1399//1399 -f 1399//1399 1448//1448 1449//1449 -f 1399//1399 1449//1449 1400//1400 -f 1400//1400 1449//1449 1450//1450 -f 1400//1400 1450//1450 1401//1401 -f 1401//1401 1450//1450 1451//1451 -f 1401//1401 1451//1451 1402//1402 -f 1402//1402 1451//1451 1452//1452 -f 1402//1402 1452//1452 1403//1403 -f 1403//1403 1452//1452 1453//1453 -f 1403//1403 1453//1453 1404//1404 -f 1404//1404 1453//1453 1454//1454 -f 1404//1404 1454//1454 1405//1405 -f 1405//1405 1454//1454 1455//1455 -f 1405//1405 1455//1455 1406//1406 -f 1406//1406 1455//1455 1456//1456 -f 1406//1406 1456//1456 1407//1407 -f 1407//1407 1456//1456 1457//1457 -f 1407//1407 1457//1457 1408//1408 -f 1408//1408 1457//1457 1458//1458 -f 1408//1408 1458//1458 1409//1409 -f 1409//1409 1458//1458 1459//1459 -f 1409//1409 1459//1459 1410//1410 -f 1410//1410 1459//1459 1460//1460 -f 1410//1410 1460//1460 1411//1411 -f 1411//1411 1460//1460 1461//1461 -f 1411//1411 1461//1461 1412//1412 -f 1412//1412 1461//1461 1462//1462 -f 1412//1412 1462//1462 1413//1413 -f 1413//1413 1462//1462 1463//1463 -f 1413//1413 1463//1463 1414//1414 -f 1414//1414 1463//1463 1464//1464 -f 1414//1414 1464//1464 1415//1415 -f 1415//1415 1464//1464 1465//1465 -f 1415//1415 1465//1465 1416//1416 -f 1416//1416 1465//1465 1466//1466 -f 1416//1416 1466//1466 1417//1417 -f 1417//1417 1466//1466 1467//1467 -f 1417//1417 1467//1467 1418//1418 -f 1418//1418 1467//1467 1468//1468 -f 1418//1418 1468//1468 1419//1419 -f 1419//1419 1468//1468 1469//1469 -f 1419//1419 1469//1469 1420//1420 -f 1420//1420 1469//1469 1470//1470 -f 1420//1420 1470//1470 1421//1421 -f 1421//1421 1470//1470 1471//1471 -f 1421//1421 1471//1471 1422//1422 -f 1422//1422 1471//1471 1472//1472 -f 1422//1422 1472//1472 1423//1423 -f 1423//1423 1472//1472 1473//1473 -f 1423//1423 1473//1473 1424//1424 -f 1424//1424 1473//1473 1474//1474 -f 1424//1424 1474//1474 1425//1425 -f 1425//1425 1474//1474 1475//1475 -f 1425//1425 1475//1475 1426//1426 -f 1426//1426 1475//1475 1476//1476 -f 1426//1426 1476//1476 1427//1427 -f 1427//1427 1476//1476 1477//1477 -f 1427//1427 1477//1477 1428//1428 -f 1428//1428 1477//1477 1478//1478 -f 1428//1428 1478//1478 1429//1429 -f 1429//1429 1478//1478 1430//1430 -f 1454//1454 1479//1479 1455//1455 -f 1455//1455 1479//1479 1480//1480 -f 1455//1455 1480//1480 1456//1456 -f 1456//1456 1480//1480 1481//1481 -f 1456//1456 1481//1481 1457//1457 -f 1457//1457 1481//1481 1482//1482 -f 1457//1457 1482//1482 1458//1458 -f 1482//1482 1483//1483 1458//1458 -f 1458//1458 1483//1483 1484//1484 -f 1458//1458 1484//1484 1459//1459 -f 1459//1459 1484//1484 1485//1485 -f 1459//1459 1485//1485 1460//1460 -f 1460//1460 1485//1485 1486//1486 -f 1460//1460 1486//1486 1461//1461 -f 1461//1461 1486//1486 1487//1487 -f 1461//1461 1487//1487 1462//1462 -f 1487//1487 1488//1488 1462//1462 -f 1462//1462 1488//1488 1489//1489 -f 1462//1462 1489//1489 1463//1463 -f 1463//1463 1489//1489 1490//1490 -f 1463//1463 1490//1490 1464//1464 -f 1464//1464 1490//1490 1491//1491 -f 1464//1464 1491//1491 1465//1465 -f 1465//1465 1491//1491 1492//1492 -f 1465//1465 1492//1492 1466//1466 -f 1466//1466 1492//1492 1493//1493 -f 1466//1466 1493//1493 1467//1467 -f 1493//1493 1494//1494 1467//1467 -f 1467//1467 1494//1494 1495//1495 -f 1467//1467 1495//1495 1468//1468 -f 1468//1468 1495//1495 1496//1496 -f 1468//1468 1496//1496 1469//1469 -f 1469//1469 1496//1496 1497//1497 -f 1469//1469 1497//1497 1470//1470 -f 1470//1470 1497//1497 1498//1498 -f 1470//1470 1498//1498 1471//1471 -f 1498//1498 1499//1499 1471//1471 -f 1471//1471 1499//1499 1500//1500 -f 1471//1471 1500//1500 1472//1472 -f 1472//1472 1500//1500 1501//1501 -f 1472//1472 1501//1501 1473//1473 -f 1473//1473 1501//1501 1502//1502 -f 1473//1473 1502//1502 1474//1474 -f 1474//1474 1502//1502 1503//1503 -f 1474//1474 1503//1503 1475//1475 -f 1475//1475 1503//1503 1504//1504 -f 1475//1475 1504//1504 1476//1476 -f 1440//1440 1505//1505 1441//1441 -f 1441//1441 1505//1505 1506//1506 -f 1441//1441 1506//1506 1442//1442 -f 1442//1442 1506//1506 1507//1507 -f 1442//1442 1507//1507 1443//1443 -f 1443//1443 1507//1507 1508//1508 -f 1443//1443 1508//1508 1444//1444 -f 1444//1444 1508//1508 1509//1509 -f 1444//1444 1509//1509 1445//1445 -f 1509//1509 1510//1510 1445//1445 -f 1445//1445 1510//1510 1511//1511 -f 1445//1445 1511//1511 1446//1446 -f 1446//1446 1511//1511 1512//1512 -f 1446//1446 1512//1512 1447//1447 -f 1447//1447 1512//1512 1513//1513 -f 1447//1447 1513//1513 1448//1448 -f 1448//1448 1513//1513 1514//1514 -f 1448//1448 1514//1514 1449//1449 -f 1514//1514 1515//1515 1449//1449 -f 1449//1449 1515//1515 1516//1516 -f 1449//1449 1516//1516 1450//1450 -f 1450//1450 1516//1516 1517//1517 -f 1450//1450 1517//1517 1451//1451 -f 1451//1451 1517//1517 1518//1518 -f 1451//1451 1518//1518 1452//1452 -f 1452//1452 1518//1518 1519//1519 -f 1452//1452 1519//1519 1453//1453 -f 1453//1453 1519//1519 1520//1520 -f 1453//1453 1520//1520 1454//1454 -f 1454//1454 1520//1520 1521//1521 -f 1454//1454 1521//1521 1479//1479 -f 1504//1504 1522//1522 1476//1476 -f 1476//1476 1522//1522 1523//1523 -f 1476//1476 1523//1523 1477//1477 -f 1477//1477 1523//1523 1524//1524 -f 1477//1477 1524//1524 1478//1478 -f 1478//1478 1524//1524 1525//1525 -f 1478//1478 1525//1525 1430//1430 -f 1430//1430 1525//1525 1526//1526 -f 1430//1430 1526//1526 1431//1431 -f 1436//1436 1527//1527 1437//1437 -f 1437//1437 1527//1527 1528//1528 -f 1437//1437 1528//1528 1438//1438 -f 1438//1438 1528//1528 1529//1529 -f 1438//1438 1529//1529 1439//1439 -f 1439//1439 1529//1529 1530//1530 -f 1439//1439 1530//1530 1440//1440 -f 1440//1440 1530//1530 1531//1531 -f 1440//1440 1531//1531 1505//1505 -f 1526//1526 1532//1532 1431//1431 -f 1431//1431 1532//1532 1533//1533 -f 1431//1431 1533//1533 1432//1432 -f 1432//1432 1533//1533 1534//1534 -f 1432//1432 1534//1534 1433//1433 -f 1433//1433 1534//1534 1535//1535 -f 1433//1433 1535//1535 1434//1434 -f 1434//1434 1535//1535 1536//1536 -f 1434//1434 1536//1536 1435//1435 -f 1435//1435 1536//1536 1537//1537 -f 1435//1435 1537//1537 1436//1436 -f 1436//1436 1537//1537 1538//1538 -f 1436//1436 1538//1538 1527//1527 -f 1525//1525 1539//1539 1526//1526 -f 1526//1526 1539//1539 1540//1540 -f 1526//1526 1540//1540 1532//1532 -f 1532//1532 1540//1540 1541//1541 -f 1532//1532 1541//1541 1533//1533 -f 1533//1533 1541//1541 1542//1542 -f 1533//1533 1542//1542 1534//1534 -f 1534//1534 1542//1542 1543//1543 -f 1534//1534 1543//1543 1535//1535 -f 1535//1535 1543//1543 1544//1544 -f 1535//1535 1544//1544 1536//1536 -f 1536//1536 1544//1544 1545//1545 -f 1536//1536 1545//1545 1537//1537 -f 1537//1537 1545//1545 1546//1546 -f 1537//1537 1546//1546 1538//1538 -f 1538//1538 1546//1546 1547//1547 -f 1538//1538 1547//1547 1527//1527 -f 1527//1527 1547//1547 1548//1548 -f 1527//1527 1548//1548 1528//1528 -f 1528//1528 1548//1548 1549//1549 -f 1528//1528 1549//1549 1529//1529 -f 1529//1529 1549//1549 1550//1550 -f 1529//1529 1550//1550 1530//1530 -f 1530//1530 1550//1550 1551//1551 -f 1530//1530 1551//1551 1531//1531 -f 1531//1531 1551//1551 1552//1552 -f 1531//1531 1552//1552 1505//1505 -f 1505//1505 1552//1552 1553//1553 -f 1505//1505 1553//1553 1506//1506 -f 1506//1506 1553//1553 1554//1554 -f 1506//1506 1554//1554 1507//1507 -f 1507//1507 1554//1554 1555//1555 -f 1507//1507 1555//1555 1508//1508 -f 1508//1508 1555//1555 1556//1556 -f 1508//1508 1556//1556 1509//1509 -f 1509//1509 1556//1556 1557//1557 -f 1509//1509 1557//1557 1510//1510 -f 1510//1510 1557//1557 1558//1558 -f 1510//1510 1558//1558 1511//1511 -f 1511//1511 1558//1558 1559//1559 -f 1511//1511 1559//1559 1512//1512 -f 1512//1512 1559//1559 1560//1560 -f 1512//1512 1560//1560 1513//1513 -f 1513//1513 1560//1560 1561//1561 -f 1513//1513 1561//1561 1514//1514 -f 1514//1514 1561//1561 1562//1562 -f 1514//1514 1562//1562 1515//1515 -f 1515//1515 1562//1562 1563//1563 -f 1515//1515 1563//1563 1516//1516 -f 1516//1516 1563//1563 1564//1564 -f 1516//1516 1564//1564 1517//1517 -f 1517//1517 1564//1564 1565//1565 -f 1517//1517 1565//1565 1518//1518 -f 1518//1518 1565//1565 1566//1566 -f 1518//1518 1566//1566 1519//1519 -f 1519//1519 1566//1566 1567//1567 -f 1519//1519 1567//1567 1520//1520 -f 1520//1520 1567//1567 1568//1568 -f 1520//1520 1568//1568 1521//1521 -f 1521//1521 1568//1568 1569//1569 -f 1521//1521 1569//1569 1479//1479 -f 1479//1479 1569//1569 1570//1570 -f 1479//1479 1570//1570 1480//1480 -f 1480//1480 1570//1570 1571//1571 -f 1480//1480 1571//1571 1481//1481 -f 1481//1481 1571//1571 1572//1572 -f 1481//1481 1572//1572 1482//1482 -f 1482//1482 1572//1572 1573//1573 -f 1482//1482 1573//1573 1483//1483 -f 1483//1483 1573//1573 1574//1574 -f 1483//1483 1574//1574 1484//1484 -f 1484//1484 1574//1574 1575//1575 -f 1484//1484 1575//1575 1485//1485 -f 1485//1485 1575//1575 1576//1576 -f 1485//1485 1576//1576 1486//1486 -f 1486//1486 1576//1576 1577//1577 -f 1486//1486 1577//1577 1487//1487 -f 1487//1487 1577//1577 1578//1578 -f 1487//1487 1578//1578 1488//1488 -f 1488//1488 1578//1578 1579//1579 -f 1488//1488 1579//1579 1489//1489 -f 1489//1489 1579//1579 1580//1580 -f 1489//1489 1580//1580 1490//1490 -f 1490//1490 1580//1580 1581//1581 -f 1490//1490 1581//1581 1491//1491 -f 1491//1491 1581//1581 1582//1582 -f 1491//1491 1582//1582 1492//1492 -f 1492//1492 1582//1582 1583//1583 -f 1492//1492 1583//1583 1493//1493 -f 1493//1493 1583//1583 1584//1584 -f 1493//1493 1584//1584 1494//1494 -f 1494//1494 1584//1584 1585//1585 -f 1494//1494 1585//1585 1495//1495 -f 1495//1495 1585//1585 1586//1586 -f 1495//1495 1586//1586 1496//1496 -f 1496//1496 1586//1586 1587//1587 -f 1496//1496 1587//1587 1497//1497 -f 1497//1497 1587//1587 1588//1588 -f 1497//1497 1588//1588 1498//1498 -f 1498//1498 1588//1588 1589//1589 -f 1498//1498 1589//1589 1499//1499 -f 1499//1499 1589//1589 1590//1590 -f 1499//1499 1590//1590 1500//1500 -f 1500//1500 1590//1590 1591//1591 -f 1500//1500 1591//1591 1501//1501 -f 1501//1501 1591//1591 1592//1592 -f 1501//1501 1592//1592 1502//1502 -f 1502//1502 1592//1592 1593//1593 -f 1502//1502 1593//1593 1503//1503 -f 1503//1503 1593//1593 1594//1594 -f 1503//1503 1594//1594 1504//1504 -f 1504//1504 1594//1594 1595//1595 -f 1504//1504 1595//1595 1522//1522 -f 1522//1522 1595//1595 1596//1596 -f 1522//1522 1596//1596 1523//1523 -f 1523//1523 1596//1596 1597//1597 -f 1523//1523 1597//1597 1524//1524 -f 1524//1524 1597//1597 1598//1598 -f 1524//1524 1598//1598 1525//1525 -f 1525//1525 1598//1598 1539//1539 -f 1598//1598 1599//1599 1539//1539 -f 1539//1539 1599//1599 1600//1600 -f 1539//1539 1600//1600 1540//1540 -f 1540//1540 1600//1600 1601//1601 -f 1540//1540 1601//1601 1541//1541 -f 1541//1541 1601//1601 1602//1602 -f 1541//1541 1602//1602 1542//1542 -f 1542//1542 1602//1602 1603//1603 -f 1542//1542 1603//1603 1543//1543 -f 1543//1543 1603//1603 1604//1604 -f 1543//1543 1604//1604 1544//1544 -f 1544//1544 1604//1604 1605//1605 -f 1544//1544 1605//1605 1545//1545 -f 1545//1545 1605//1605 1606//1606 -f 1545//1545 1606//1606 1546//1546 -f 1546//1546 1606//1606 1607//1607 -f 1546//1546 1607//1607 1547//1547 -f 1547//1547 1607//1607 1608//1608 -f 1547//1547 1608//1608 1548//1548 -f 1548//1548 1608//1608 1609//1609 -f 1548//1548 1609//1609 1549//1549 -f 1549//1549 1609//1609 1610//1610 -f 1549//1549 1610//1610 1550//1550 -f 1550//1550 1610//1610 1611//1611 -f 1550//1550 1611//1611 1551//1551 -f 1551//1551 1611//1611 1612//1612 -f 1551//1551 1612//1612 1552//1552 -f 1552//1552 1612//1612 1613//1613 -f 1552//1552 1613//1613 1553//1553 -f 1553//1553 1613//1613 1614//1614 -f 1553//1553 1614//1614 1554//1554 -f 1554//1554 1614//1614 1615//1615 -f 1554//1554 1615//1615 1555//1555 -f 1555//1555 1615//1615 1616//1616 -f 1555//1555 1616//1616 1556//1556 -f 1556//1556 1616//1616 1617//1617 -f 1556//1556 1617//1617 1557//1557 -f 1557//1557 1617//1617 1618//1618 -f 1557//1557 1618//1618 1558//1558 -f 1558//1558 1618//1618 1619//1619 -f 1558//1558 1619//1619 1559//1559 -f 1559//1559 1619//1619 1620//1620 -f 1559//1559 1620//1620 1560//1560 -f 1560//1560 1620//1620 1621//1621 -f 1560//1560 1621//1621 1561//1561 -f 1561//1561 1621//1621 1622//1622 -f 1561//1561 1622//1622 1562//1562 -f 1562//1562 1622//1622 1623//1623 -f 1562//1562 1623//1623 1563//1563 -f 1563//1563 1623//1623 1624//1624 -f 1563//1563 1624//1624 1564//1564 -f 1564//1564 1624//1624 1625//1625 -f 1564//1564 1625//1625 1565//1565 -f 1565//1565 1625//1625 1626//1626 -f 1565//1565 1626//1626 1566//1566 -f 1566//1566 1626//1626 1627//1627 -f 1566//1566 1627//1627 1567//1567 -f 1567//1567 1627//1627 1628//1628 -f 1567//1567 1628//1628 1568//1568 -f 1568//1568 1628//1628 1629//1629 -f 1568//1568 1629//1629 1569//1569 -f 1569//1569 1629//1629 1630//1630 -f 1569//1569 1630//1630 1570//1570 -f 1570//1570 1630//1630 1631//1631 -f 1570//1570 1631//1631 1571//1571 -f 1571//1571 1631//1631 1632//1632 -f 1571//1571 1632//1632 1572//1572 -f 1572//1572 1632//1632 1633//1633 -f 1572//1572 1633//1633 1573//1573 -f 1573//1573 1633//1633 1634//1634 -f 1573//1573 1634//1634 1574//1574 -f 1574//1574 1634//1634 1635//1635 -f 1574//1574 1635//1635 1575//1575 -f 1575//1575 1635//1635 1636//1636 -f 1575//1575 1636//1636 1576//1576 -f 1576//1576 1636//1636 1637//1637 -f 1576//1576 1637//1637 1577//1577 -f 1577//1577 1637//1637 1638//1638 -f 1577//1577 1638//1638 1578//1578 -f 1578//1578 1638//1638 1639//1639 -f 1578//1578 1639//1639 1579//1579 -f 1579//1579 1639//1639 1640//1640 -f 1579//1579 1640//1640 1580//1580 -f 1580//1580 1640//1640 1641//1641 -f 1580//1580 1641//1641 1581//1581 -f 1581//1581 1641//1641 1642//1642 -f 1581//1581 1642//1642 1582//1582 -f 1582//1582 1642//1642 1643//1643 -f 1582//1582 1643//1643 1583//1583 -f 1583//1583 1643//1643 1644//1644 -f 1583//1583 1644//1644 1584//1584 -f 1584//1584 1644//1644 1645//1645 -f 1584//1584 1645//1645 1585//1585 -f 1585//1585 1645//1645 1646//1646 -f 1585//1585 1646//1646 1586//1586 -f 1586//1586 1646//1646 1647//1647 -f 1586//1586 1647//1647 1587//1587 -f 1587//1587 1647//1647 1648//1648 -f 1587//1587 1648//1648 1588//1588 -f 1588//1588 1648//1648 1649//1649 -f 1588//1588 1649//1649 1589//1589 -f 1589//1589 1649//1649 1650//1650 -f 1589//1589 1650//1650 1590//1590 -f 1590//1590 1650//1650 1651//1651 -f 1590//1590 1651//1651 1591//1591 -f 1591//1591 1651//1651 1652//1652 -f 1591//1591 1652//1652 1592//1592 -f 1592//1592 1652//1652 1653//1653 -f 1592//1592 1653//1653 1593//1593 -f 1593//1593 1653//1653 1654//1654 -f 1593//1593 1654//1654 1594//1594 -f 1594//1594 1654//1654 1655//1655 -f 1594//1594 1655//1655 1595//1595 -f 1595//1595 1655//1655 1656//1656 -f 1595//1595 1656//1656 1596//1596 -f 1596//1596 1656//1656 1657//1657 -f 1596//1596 1657//1657 1597//1597 -f 1597//1597 1657//1657 1658//1658 -f 1597//1597 1658//1658 1598//1598 -f 1598//1598 1658//1658 1599//1599 -f 1659//1659 1660//1660 1629//1629 -f 1629//1629 1660//1660 1630//1630 -f 1630//1630 1660//1660 1661//1661 -f 1630//1630 1661//1661 1631//1631 -f 1631//1631 1661//1661 1662//1662 -f 1631//1631 1662//1662 1632//1632 -f 1632//1632 1662//1662 1663//1663 -f 1632//1632 1663//1663 1633//1633 -f 1633//1633 1663//1663 1664//1664 -f 1633//1633 1664//1664 1634//1634 -f 1634//1634 1664//1664 1665//1665 -f 1634//1634 1665//1665 1635//1635 -f 1635//1635 1665//1665 1666//1666 -f 1635//1635 1666//1666 1636//1636 -f 1666//1666 1667//1667 1636//1636 -f 1636//1636 1667//1667 1668//1668 -f 1636//1636 1668//1668 1637//1637 -f 1637//1637 1668//1668 1669//1669 -f 1637//1637 1669//1669 1638//1638 -f 1638//1638 1669//1669 1639//1639 -f 1639//1639 1669//1669 1670//1670 -f 1639//1639 1670//1670 1640//1640 -f 1640//1640 1670//1670 1671//1671 -f 1640//1640 1671//1671 1641//1641 -f 1641//1641 1671//1671 1672//1672 -f 1641//1641 1672//1672 1642//1642 -f 1642//1642 1672//1672 1673//1673 -f 1642//1642 1673//1673 1643//1643 -f 1643//1643 1673//1673 1674//1674 -f 1643//1643 1674//1674 1644//1644 -f 1644//1644 1674//1674 1675//1675 -f 1644//1644 1675//1675 1645//1645 -f 1645//1645 1675//1675 1676//1676 -f 1645//1645 1676//1676 1646//1646 -f 1676//1676 1677//1677 1646//1646 -f 1646//1646 1677//1677 1678//1678 -f 1646//1646 1678//1678 1647//1647 -f 1647//1647 1678//1678 1679//1679 -f 1647//1647 1679//1679 1648//1648 -f 1648//1648 1679//1679 1649//1649 -f 1649//1649 1679//1679 1680//1680 -f 1649//1649 1680//1680 1650//1650 -f 1650//1650 1680//1680 1681//1681 -f 1650//1650 1681//1681 1651//1651 -f 1651//1651 1681//1681 1682//1682 -f 1651//1651 1682//1682 1652//1652 -f 1652//1652 1682//1682 1683//1683 -f 1652//1652 1683//1683 1653//1653 -f 1653//1653 1683//1683 1684//1684 -f 1653//1653 1684//1684 1654//1654 -f 1654//1654 1684//1684 1685//1685 -f 1654//1654 1685//1685 1655//1655 -f 1655//1655 1685//1685 1686//1686 -f 1655//1655 1686//1686 1656//1656 -f 1686//1686 1687//1687 1656//1656 -f 1656//1656 1687//1687 1688//1688 -f 1656//1656 1688//1688 1657//1657 -f 1657//1657 1688//1688 1689//1689 -f 1657//1657 1689//1689 1658//1658 -f 1658//1658 1689//1689 1599//1599 -f 1599//1599 1689//1689 1690//1690 -f 1599//1599 1690//1690 1600//1600 -f 1600//1600 1690//1690 1691//1691 -f 1600//1600 1691//1691 1601//1601 -f 1601//1601 1691//1691 1692//1692 -f 1601//1601 1692//1692 1602//1602 -f 1602//1602 1692//1692 1693//1693 -f 1602//1602 1693//1693 1603//1603 -f 1603//1603 1693//1693 1694//1694 -f 1603//1603 1694//1694 1604//1604 -f 1604//1604 1694//1694 1695//1695 -f 1604//1604 1695//1695 1605//1605 -f 1605//1605 1695//1695 1696//1696 -f 1605//1605 1696//1696 1606//1606 -f 1696//1696 1697//1697 1606//1606 -f 1606//1606 1697//1697 1698//1698 -f 1606//1606 1698//1698 1607//1607 -f 1607//1607 1698//1698 1699//1699 -f 1607//1607 1699//1699 1608//1608 -f 1608//1608 1699//1699 1609//1609 -f 1609//1609 1699//1699 1700//1700 -f 1609//1609 1700//1700 1610//1610 -f 1610//1610 1700//1700 1701//1701 -f 1610//1610 1701//1701 1611//1611 -f 1611//1611 1701//1701 1702//1702 -f 1611//1611 1702//1702 1612//1612 -f 1612//1612 1702//1702 1703//1703 -f 1612//1612 1703//1703 1613//1613 -f 1613//1613 1703//1703 1704//1704 -f 1613//1613 1704//1704 1614//1614 -f 1614//1614 1704//1704 1705//1705 -f 1614//1614 1705//1705 1615//1615 -f 1615//1615 1705//1705 1706//1706 -f 1615//1615 1706//1706 1616//1616 -f 1706//1706 1707//1707 1616//1616 -f 1616//1616 1707//1707 1708//1708 -f 1616//1616 1708//1708 1617//1617 -f 1617//1617 1708//1708 1709//1709 -f 1617//1617 1709//1709 1618//1618 -f 1618//1618 1709//1709 1619//1619 -f 1619//1619 1709//1709 1710//1710 -f 1619//1619 1710//1710 1620//1620 -f 1620//1620 1710//1710 1711//1711 -f 1620//1620 1711//1711 1621//1621 -f 1621//1621 1711//1711 1712//1712 -f 1621//1621 1712//1712 1622//1622 -f 1622//1622 1712//1712 1713//1713 -f 1622//1622 1713//1713 1623//1623 -f 1623//1623 1713//1713 1714//1714 -f 1623//1623 1714//1714 1624//1624 -f 1624//1624 1714//1714 1715//1715 -f 1624//1624 1715//1715 1625//1625 -f 1625//1625 1715//1715 1716//1716 -f 1625//1625 1716//1716 1626//1626 -f 1716//1716 1717//1717 1626//1626 -f 1626//1626 1717//1717 1718//1718 -f 1626//1626 1718//1718 1627//1627 -f 1627//1627 1718//1718 1659//1659 -f 1627//1627 1659//1659 1628//1628 -f 1628//1628 1659//1659 1629//1629 -f 1719//1719 1720//1720 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1725//1725 1726//1726 1727//1727 -f 1728//1728 1729//1729 1730//1730 -f 1731//1731 1732//1732 1733//1733 -f 1734//1734 1735//1735 1736//1736 -f 1737//1737 1738//1738 1739//1739 -f 1740//1740 1741//1741 1742//1742 -f 1693//1693 1692//1692 1743//1743 -f 1695//1695 1694//1694 1744//1744 -f 1701//1701 1700//1700 1745//1745 -f 1713//1713 1712//1712 1746//1746 -f 1715//1715 1714//1714 1747//1747 -f 1661//1661 1660//1660 1748//1748 -f 1673//1673 1672//1672 1749//1749 -f 1675//1675 1674//1674 1750//1750 -f 1681//1681 1680//1680 1751//1751 -f 1752//1752 1689//1689 1688//1688 -f 1752//1752 1688//1688 1753//1753 -f 1753//1753 1688//1688 1687//1687 -f 1753//1753 1687//1687 1754//1754 -f 1684//1684 1755//1755 1685//1685 -f 1685//1685 1755//1755 1754//1754 -f 1685//1685 1754//1754 1686//1686 -f 1686//1686 1754//1754 1687//1687 -f 1684//1684 1683//1683 1756//1756 -f 1681//1681 1751//1751 1682//1682 -f 1741//1741 1678//1678 1677//1677 -f 1741//1741 1677//1677 1742//1742 -f 1742//1742 1677//1677 1676//1676 -f 1742//1742 1676//1676 1675//1675 -f 1673//1673 1749//1749 1674//1674 -f 1672//1672 1671//1671 1757//1757 -f 1757//1757 1671//1671 1670//1670 -f 1757//1757 1670//1670 1669//1669 -f 1664//1664 1739//1739 1665//1665 -f 1665//1665 1739//1739 1738//1738 -f 1665//1665 1738//1738 1666//1666 -f 1666//1666 1738//1738 1667//1667 -f 1664//1664 1663//1663 1758//1758 -f 1661//1661 1748//1748 1662//1662 -f 1735//1735 1718//1718 1717//1717 -f 1735//1735 1717//1717 1736//1736 -f 1736//1736 1717//1717 1716//1716 -f 1736//1736 1716//1716 1715//1715 -f 1713//1713 1746//1746 1714//1714 -f 1712//1712 1711//1711 1759//1759 -f 1759//1759 1711//1711 1710//1710 -f 1759//1759 1710//1710 1709//1709 -f 1704//1704 1733//1733 1705//1705 -f 1705//1705 1733//1733 1732//1732 -f 1705//1705 1732//1732 1706//1706 -f 1706//1706 1732//1732 1707//1707 -f 1704//1704 1703//1703 1760//1760 -f 1701//1701 1745//1745 1702//1702 -f 1729//1729 1698//1698 1697//1697 -f 1729//1729 1697//1697 1730//1730 -f 1730//1730 1697//1697 1696//1696 -f 1730//1730 1696//1696 1695//1695 -f 1693//1693 1743//1743 1694//1694 -f 1692//1692 1691//1691 1761//1761 -f 1761//1761 1691//1691 1690//1690 -f 1761//1761 1690//1690 1689//1689 -f 1679//1679 1678//1678 1762//1762 -f 1762//1762 1678//1678 1741//1741 -f 1762//1762 1741//1741 1763//1763 -f 1763//1763 1741//1741 1740//1740 -f 1763//1763 1740//1740 1764//1764 -f 1668//1668 1667//1667 1765//1765 -f 1765//1765 1667//1667 1738//1738 -f 1765//1765 1738//1738 1766//1766 -f 1766//1766 1738//1738 1737//1737 -f 1766//1766 1737//1737 1767//1767 -f 1659//1659 1718//1718 1768//1768 -f 1768//1768 1718//1718 1735//1735 -f 1768//1768 1735//1735 1769//1769 -f 1769//1769 1735//1735 1734//1734 -f 1769//1769 1734//1734 1770//1770 -f 1708//1708 1707//1707 1771//1771 -f 1771//1771 1707//1707 1732//1732 -f 1771//1771 1732//1732 1772//1772 -f 1772//1772 1732//1732 1731//1731 -f 1772//1772 1731//1731 1773//1773 -f 1699//1699 1698//1698 1774//1774 -f 1774//1774 1698//1698 1729//1729 -f 1774//1774 1729//1729 1775//1775 -f 1775//1775 1729//1729 1728//1728 -f 1775//1775 1728//1728 1776//1776 -f 1755//1755 1777//1777 1754//1754 -f 1754//1754 1777//1777 1778//1778 -f 1754//1754 1778//1778 1753//1753 -f 1753//1753 1778//1778 1779//1779 -f 1753//1753 1779//1779 1752//1752 -f 1752//1752 1779//1779 1780//1780 -f 1781//1781 1782//1782 1783//1783 -f 1784//1784 1785//1785 1786//1786 -f 1787//1787 1785//1785 1788//1788 -f 1788//1788 1785//1785 1784//1784 -f 1788//1788 1784//1784 1789//1789 -f 1669//1669 1668//1668 1789//1789 -f 1789//1789 1668//1668 1765//1765 -f 1789//1789 1765//1765 1788//1788 -f 1788//1788 1765//1765 1766//1766 -f 1788//1788 1766//1766 1787//1787 -f 1787//1787 1766//1766 1767//1767 -f 1790//1790 1791//1791 1792//1792 -f 1793//1793 1794//1794 1795//1795 -f 1796//1796 1794//1794 1797//1797 -f 1797//1797 1794//1794 1793//1793 -f 1797//1797 1793//1793 1798//1798 -f 1709//1709 1708//1708 1798//1798 -f 1798//1798 1708//1708 1771//1771 -f 1798//1798 1771//1771 1797//1797 -f 1797//1797 1771//1771 1772//1772 -f 1797//1797 1772//1772 1796//1796 -f 1796//1796 1772//1772 1773//1773 -f 1799//1799 1800//1800 1801//1801 -f 1777//1777 1802//1802 1778//1778 -f 1778//1778 1802//1802 1803//1803 -f 1778//1778 1803//1803 1779//1779 -f 1779//1779 1803//1803 1804//1804 -f 1779//1779 1804//1804 1780//1780 -f 1780//1780 1804//1804 1805//1805 -f 1684//1684 1756//1756 1755//1755 -f 1755//1755 1756//1756 1806//1806 -f 1755//1755 1806//1806 1777//1777 -f 1777//1777 1806//1806 1727//1727 -f 1777//1777 1727//1727 1802//1802 -f 1802//1802 1727//1727 1726//1726 -f 1802//1802 1726//1726 1807//1807 -f 1756//1756 1781//1781 1806//1806 -f 1806//1806 1781//1781 1783//1783 -f 1806//1806 1783//1783 1727//1727 -f 1727//1727 1783//1783 1808//1808 -f 1727//1727 1808//1808 1725//1725 -f 1809//1809 1810//1810 1811//1811 -f 1811//1811 1810//1810 1782//1782 -f 1811//1811 1782//1782 1812//1812 -f 1812//1812 1782//1782 1781//1781 -f 1812//1812 1781//1781 1751//1751 -f 1751//1751 1781//1781 1756//1756 -f 1751//1751 1756//1756 1682//1682 -f 1682//1682 1756//1756 1683//1683 -f 1810//1810 1813//1813 1782//1782 -f 1782//1782 1813//1813 1814//1814 -f 1782//1782 1814//1814 1783//1783 -f 1783//1783 1814//1814 1815//1815 -f 1783//1783 1815//1815 1808//1808 -f 1680//1680 1679//1679 1751//1751 -f 1751//1751 1679//1679 1762//1762 -f 1751//1751 1762//1762 1812//1812 -f 1812//1812 1762//1762 1763//1763 -f 1812//1812 1763//1763 1811//1811 -f 1811//1811 1763//1763 1764//1764 -f 1811//1811 1764//1764 1809//1809 -f 1809//1809 1764//1764 1816//1816 -f 1817//1817 1818//1818 1819//1819 -f 1675//1675 1750//1750 1742//1742 -f 1742//1742 1750//1750 1820//1820 -f 1742//1742 1820//1820 1740//1740 -f 1740//1740 1820//1820 1817//1817 -f 1740//1740 1817//1817 1764//1764 -f 1764//1764 1817//1817 1819//1819 -f 1764//1764 1819//1819 1816//1816 -f 1821//1821 1822//1822 1823//1823 -f 1674//1674 1749//1749 1750//1750 -f 1750//1750 1749//1749 1824//1824 -f 1750//1750 1824//1824 1820//1820 -f 1820//1820 1824//1824 1821//1821 -f 1820//1820 1821//1821 1817//1817 -f 1817//1817 1821//1821 1823//1823 -f 1817//1817 1823//1823 1818//1818 -f 1825//1825 1826//1826 1827//1827 -f 1672//1672 1757//1757 1749//1749 -f 1749//1749 1757//1757 1828//1828 -f 1749//1749 1828//1828 1824//1824 -f 1824//1824 1828//1828 1825//1825 -f 1824//1824 1825//1825 1821//1821 -f 1821//1821 1825//1825 1827//1827 -f 1821//1821 1827//1827 1822//1822 -f 1669//1669 1789//1789 1757//1757 -f 1757//1757 1789//1789 1784//1784 -f 1757//1757 1784//1784 1828//1828 -f 1828//1828 1784//1784 1786//1786 -f 1828//1828 1786//1786 1825//1825 -f 1825//1825 1786//1786 1829//1829 -f 1825//1825 1829//1829 1826//1826 -f 1830//1830 1831//1831 1767//1767 -f 1767//1767 1831//1831 1832//1832 -f 1767//1767 1832//1832 1787//1787 -f 1787//1787 1832//1832 1833//1833 -f 1787//1787 1833//1833 1785//1785 -f 1785//1785 1833//1833 1834//1834 -f 1785//1785 1834//1834 1786//1786 -f 1786//1786 1834//1834 1835//1835 -f 1786//1786 1835//1835 1829//1829 -f 1664//1664 1758//1758 1739//1739 -f 1739//1739 1758//1758 1836//1836 -f 1739//1739 1836//1836 1737//1737 -f 1737//1737 1836//1836 1724//1724 -f 1737//1737 1724//1724 1767//1767 -f 1767//1767 1724//1724 1723//1723 -f 1767//1767 1723//1723 1830//1830 -f 1758//1758 1790//1790 1836//1836 -f 1836//1836 1790//1790 1792//1792 -f 1836//1836 1792//1792 1724//1724 -f 1724//1724 1792//1792 1837//1837 -f 1724//1724 1837//1837 1722//1722 -f 1838//1838 1839//1839 1840//1840 -f 1840//1840 1839//1839 1791//1791 -f 1840//1840 1791//1791 1841//1841 -f 1841//1841 1791//1791 1790//1790 -f 1841//1841 1790//1790 1748//1748 -f 1748//1748 1790//1790 1758//1758 -f 1748//1748 1758//1758 1662//1662 -f 1662//1662 1758//1758 1663//1663 -f 1839//1839 1842//1842 1791//1791 -f 1791//1791 1842//1842 1843//1843 -f 1791//1791 1843//1843 1792//1792 -f 1792//1792 1843//1843 1844//1844 -f 1792//1792 1844//1844 1837//1837 -f 1660//1660 1659//1659 1748//1748 -f 1748//1748 1659//1659 1768//1768 -f 1748//1748 1768//1768 1841//1841 -f 1841//1841 1768//1768 1769//1769 -f 1841//1841 1769//1769 1840//1840 -f 1840//1840 1769//1769 1770//1770 -f 1840//1840 1770//1770 1838//1838 -f 1838//1838 1770//1770 1845//1845 -f 1846//1846 1847//1847 1848//1848 -f 1715//1715 1747//1747 1736//1736 -f 1736//1736 1747//1747 1849//1849 -f 1736//1736 1849//1849 1734//1734 -f 1734//1734 1849//1849 1846//1846 -f 1734//1734 1846//1846 1770//1770 -f 1770//1770 1846//1846 1848//1848 -f 1770//1770 1848//1848 1845//1845 -f 1850//1850 1851//1851 1852//1852 -f 1714//1714 1746//1746 1747//1747 -f 1747//1747 1746//1746 1853//1853 -f 1747//1747 1853//1853 1849//1849 -f 1849//1849 1853//1853 1850//1850 -f 1849//1849 1850//1850 1846//1846 -f 1846//1846 1850//1850 1852//1852 -f 1846//1846 1852//1852 1847//1847 -f 1854//1854 1855//1855 1856//1856 -f 1712//1712 1759//1759 1746//1746 -f 1746//1746 1759//1759 1857//1857 -f 1746//1746 1857//1857 1853//1853 -f 1853//1853 1857//1857 1854//1854 -f 1853//1853 1854//1854 1850//1850 -f 1850//1850 1854//1854 1856//1856 -f 1850//1850 1856//1856 1851//1851 -f 1709//1709 1798//1798 1759//1759 -f 1759//1759 1798//1798 1793//1793 -f 1759//1759 1793//1793 1857//1857 -f 1857//1857 1793//1793 1795//1795 -f 1857//1857 1795//1795 1854//1854 -f 1854//1854 1795//1795 1858//1858 -f 1854//1854 1858//1858 1855//1855 -f 1859//1859 1860//1860 1773//1773 -f 1773//1773 1860//1860 1861//1861 -f 1773//1773 1861//1861 1796//1796 -f 1796//1796 1861//1861 1862//1862 -f 1796//1796 1862//1862 1794//1794 -f 1794//1794 1862//1862 1863//1863 -f 1794//1794 1863//1863 1795//1795 -f 1795//1795 1863//1863 1864//1864 -f 1795//1795 1864//1864 1858//1858 -f 1704//1704 1760//1760 1733//1733 -f 1733//1733 1760//1760 1865//1865 -f 1733//1733 1865//1865 1731//1731 -f 1731//1731 1865//1865 1721//1721 -f 1731//1731 1721//1721 1773//1773 -f 1773//1773 1721//1721 1720//1720 -f 1773//1773 1720//1720 1859//1859 -f 1760//1760 1799//1799 1865//1865 -f 1865//1865 1799//1799 1801//1801 -f 1865//1865 1801//1801 1721//1721 -f 1721//1721 1801//1801 1866//1866 -f 1721//1721 1866//1866 1719//1719 -f 1867//1867 1868//1868 1869//1869 -f 1869//1869 1868//1868 1800//1800 -f 1869//1869 1800//1800 1870//1870 -f 1870//1870 1800//1800 1799//1799 -f 1870//1870 1799//1799 1745//1745 -f 1745//1745 1799//1799 1760//1760 -f 1745//1745 1760//1760 1702//1702 -f 1702//1702 1760//1760 1703//1703 -f 1868//1868 1871//1871 1800//1800 -f 1800//1800 1871//1871 1872//1872 -f 1800//1800 1872//1872 1801//1801 -f 1801//1801 1872//1872 1873//1873 -f 1801//1801 1873//1873 1866//1866 -f 1700//1700 1699//1699 1745//1745 -f 1745//1745 1699//1699 1774//1774 -f 1745//1745 1774//1774 1870//1870 -f 1870//1870 1774//1774 1775//1775 -f 1870//1870 1775//1775 1869//1869 -f 1869//1869 1775//1775 1776//1776 -f 1869//1869 1776//1776 1867//1867 -f 1867//1867 1776//1776 1874//1874 -f 1875//1875 1876//1876 1877//1877 -f 1695//1695 1744//1744 1730//1730 -f 1730//1730 1744//1744 1878//1878 -f 1730//1730 1878//1878 1728//1728 -f 1728//1728 1878//1878 1875//1875 -f 1728//1728 1875//1875 1776//1776 -f 1776//1776 1875//1875 1877//1877 -f 1776//1776 1877//1877 1874//1874 -f 1879//1879 1880//1880 1881//1881 -f 1694//1694 1743//1743 1744//1744 -f 1744//1744 1743//1743 1882//1882 -f 1744//1744 1882//1882 1878//1878 -f 1878//1878 1882//1882 1879//1879 -f 1878//1878 1879//1879 1875//1875 -f 1875//1875 1879//1879 1881//1881 -f 1875//1875 1881//1881 1876//1876 -f 1883//1883 1884//1884 1885//1885 -f 1692//1692 1761//1761 1743//1743 -f 1743//1743 1761//1761 1886//1886 -f 1743//1743 1886//1886 1882//1882 -f 1882//1882 1886//1886 1883//1883 -f 1882//1882 1883//1883 1879//1879 -f 1879//1879 1883//1883 1885//1885 -f 1879//1879 1885//1885 1880//1880 -f 1689//1689 1752//1752 1761//1761 -f 1761//1761 1752//1752 1780//1780 -f 1761//1761 1780//1780 1886//1886 -f 1886//1886 1780//1780 1805//1805 -f 1886//1886 1805//1805 1883//1883 -f 1883//1883 1805//1805 1887//1887 -f 1883//1883 1887//1887 1884//1884 -f 1807//1807 1888//1888 1802//1802 -f 1802//1802 1888//1888 1889//1889 -f 1802//1802 1889//1889 1803//1803 -f 1803//1803 1889//1889 1890//1890 -f 1803//1803 1890//1890 1804//1804 -f 1804//1804 1890//1890 1891//1891 -f 1804//1804 1891//1891 1805//1805 -f 1805//1805 1891//1891 1892//1892 -f 1805//1805 1892//1892 1887//1887 -f 1810//1810 1893//1893 1813//1813 -f 1813//1813 1893//1893 1894//1894 -f 1813//1813 1894//1894 1814//1814 -f 1814//1814 1894//1894 1895//1895 -f 1814//1814 1895//1895 1815//1815 -f 1815//1815 1895//1895 1896//1896 -f 1815//1815 1896//1896 1808//1808 -f 1827//1827 1897//1897 1822//1822 -f 1822//1822 1897//1897 1898//1898 -f 1822//1822 1898//1898 1823//1823 -f 1823//1823 1898//1898 1899//1899 -f 1823//1823 1899//1899 1818//1818 -f 1818//1818 1899//1899 1900//1900 -f 1818//1818 1900//1900 1819//1819 -f 1819//1819 1900//1900 1901//1901 -f 1819//1819 1901//1901 1816//1816 -f 1816//1816 1901//1901 1902//1902 -f 1816//1816 1902//1902 1809//1809 -f 1809//1809 1902//1902 1903//1903 -f 1809//1809 1903//1903 1810//1810 -f 1810//1810 1903//1903 1904//1904 -f 1810//1810 1904//1904 1893//1893 -f 1832//1832 1905//1905 1833//1833 -f 1833//1833 1905//1905 1906//1906 -f 1833//1833 1906//1906 1834//1834 -f 1834//1834 1906//1906 1907//1907 -f 1834//1834 1907//1907 1835//1835 -f 1835//1835 1907//1907 1908//1908 -f 1835//1835 1908//1908 1829//1829 -f 1829//1829 1908//1908 1909//1909 -f 1829//1829 1909//1909 1826//1826 -f 1826//1826 1909//1909 1910//1910 -f 1826//1826 1910//1910 1827//1827 -f 1827//1827 1910//1910 1911//1911 -f 1827//1827 1911//1911 1897//1897 -f 1831//1831 1912//1912 1832//1832 -f 1832//1832 1912//1912 1913//1913 -f 1832//1832 1913//1913 1905//1905 -f 1843//1843 1914//1914 1844//1844 -f 1844//1844 1914//1914 1915//1915 -f 1844//1844 1915//1915 1837//1837 -f 1837//1837 1915//1915 1916//1916 -f 1837//1837 1916//1916 1722//1722 -f 1722//1722 1916//1916 1917//1917 -f 1722//1722 1917//1917 1723//1723 -f 1723//1723 1917//1917 1918//1918 -f 1723//1723 1918//1918 1830//1830 -f 1830//1830 1918//1918 1919//1919 -f 1830//1830 1919//1919 1831//1831 -f 1831//1831 1919//1919 1920//1920 -f 1831//1831 1920//1920 1912//1912 -f 1845//1845 1921//1921 1838//1838 -f 1838//1838 1921//1921 1922//1922 -f 1838//1838 1922//1922 1839//1839 -f 1839//1839 1922//1922 1923//1923 -f 1839//1839 1923//1923 1842//1842 -f 1842//1842 1923//1923 1924//1924 -f 1842//1842 1924//1924 1843//1843 -f 1843//1843 1924//1924 1925//1925 -f 1843//1843 1925//1925 1914//1914 -f 1858//1858 1926//1926 1855//1855 -f 1855//1855 1926//1926 1927//1927 -f 1855//1855 1927//1927 1856//1856 -f 1856//1856 1927//1927 1928//1928 -f 1856//1856 1928//1928 1851//1851 -f 1851//1851 1928//1928 1929//1929 -f 1851//1851 1929//1929 1852//1852 -f 1852//1852 1929//1929 1930//1930 -f 1852//1852 1930//1930 1847//1847 -f 1847//1847 1930//1930 1931//1931 -f 1847//1847 1931//1931 1848//1848 -f 1848//1848 1931//1931 1932//1932 -f 1848//1848 1932//1932 1845//1845 -f 1845//1845 1932//1932 1933//1933 -f 1845//1845 1933//1933 1921//1921 -f 1861//1861 1934//1934 1862//1862 -f 1862//1862 1934//1934 1935//1935 -f 1862//1862 1935//1935 1863//1863 -f 1863//1863 1935//1935 1936//1936 -f 1863//1863 1936//1936 1864//1864 -f 1864//1864 1936//1936 1937//1937 -f 1864//1864 1937//1937 1858//1858 -f 1858//1858 1937//1937 1938//1938 -f 1858//1858 1938//1938 1926//1926 -f 1720//1720 1939//1939 1859//1859 -f 1859//1859 1939//1939 1940//1940 -f 1859//1859 1940//1940 1860//1860 -f 1860//1860 1940//1940 1941//1941 -f 1860//1860 1941//1941 1861//1861 -f 1861//1861 1941//1941 1942//1942 -f 1861//1861 1942//1942 1934//1934 -f 1872//1872 1943//1943 1873//1873 -f 1873//1873 1943//1943 1944//1944 -f 1873//1873 1944//1944 1866//1866 -f 1866//1866 1944//1944 1945//1945 -f 1866//1866 1945//1945 1719//1719 -f 1719//1719 1945//1945 1946//1946 -f 1719//1719 1946//1946 1720//1720 -f 1720//1720 1946//1946 1947//1947 -f 1720//1720 1947//1947 1939//1939 -f 1881//1881 1948//1948 1876//1876 -f 1876//1876 1948//1948 1949//1949 -f 1876//1876 1949//1949 1877//1877 -f 1877//1877 1949//1949 1950//1950 -f 1877//1877 1950//1950 1874//1874 -f 1874//1874 1950//1950 1951//1951 -f 1874//1874 1951//1951 1867//1867 -f 1867//1867 1951//1951 1952//1952 -f 1867//1867 1952//1952 1868//1868 -f 1868//1868 1952//1952 1953//1953 -f 1868//1868 1953//1953 1871//1871 -f 1871//1871 1953//1953 1954//1954 -f 1871//1871 1954//1954 1872//1872 -f 1872//1872 1954//1954 1955//1955 -f 1872//1872 1955//1955 1943//1943 -f 1891//1891 1956//1956 1892//1892 -f 1892//1892 1956//1956 1957//1957 -f 1892//1892 1957//1957 1887//1887 -f 1887//1887 1957//1957 1958//1958 -f 1887//1887 1958//1958 1884//1884 -f 1884//1884 1958//1958 1959//1959 -f 1884//1884 1959//1959 1885//1885 -f 1885//1885 1959//1959 1960//1960 -f 1885//1885 1960//1960 1880//1880 -f 1880//1880 1960//1960 1961//1961 -f 1880//1880 1961//1961 1881//1881 -f 1881//1881 1961//1961 1962//1962 -f 1881//1881 1962//1962 1948//1948 -f 1896//1896 1963//1963 1808//1808 -f 1808//1808 1963//1963 1964//1964 -f 1808//1808 1964//1964 1725//1725 -f 1725//1725 1964//1964 1965//1965 -f 1725//1725 1965//1965 1726//1726 -f 1726//1726 1965//1965 1966//1966 -f 1726//1726 1966//1966 1807//1807 -f 1807//1807 1966//1966 1967//1967 -f 1807//1807 1967//1967 1888//1888 -f 1888//1888 1967//1967 1968//1968 -f 1888//1888 1968//1968 1889//1889 -f 1889//1889 1968//1968 1969//1969 -f 1889//1889 1969//1969 1890//1890 -f 1890//1890 1969//1969 1970//1970 -f 1890//1890 1970//1970 1891//1891 -f 1891//1891 1970//1970 1971//1971 -f 1891//1891 1971//1971 1956//1956 -f 1972//1972 1973//1973 1974//1974 -f 1975//1975 1976//1976 1977//1977 -f 1977//1977 1976//1976 1978//1978 -f 1979//1979 1980//1980 1981//1981 -f 1981//1981 1980//1980 1982//1982 -f 1983//1983 1984//1984 1985//1985 -f 1986//1986 1987//1987 1988//1988 -f 1989//1989 1990//1990 1991//1991 -f 1992//1992 1993//1993 1994//1994 -f 1995//1995 1996//1996 1997//1997 -f 1998//1998 1999//1999 2000//2000 -f 2001//2001 2002//2002 2003//2003 -f 2004//2004 2005//2005 2006//2006 -f 1970//1970 1969//1969 2004//2004 -f 1957//1957 1956//1956 2007//2007 -f 1960//1960 1959//1959 1989//1989 -f 1962//1962 1961//1961 2008//2008 -f 1949//1949 1948//1948 2009//2009 -f 1950//1950 1949//1949 2010//2010 -f 1952//1952 1951//1951 2011//2011 -f 1944//1944 1943//1943 1992//1992 -f 1946//1946 1945//1945 2012//2012 -f 1939//1939 1947//1947 2013//2013 -f 1940//1940 1939//1939 2014//2014 -f 1938//1938 1937//1937 2015//2015 -f 1930//1930 1929//1929 1995//1995 -f 1932//1932 1931//1931 2016//2016 -f 1921//1921 1933//1933 2017//2017 -f 1922//1922 1921//1921 2018//2018 -f 1917//1917 1916//1916 2019//2019 -f 1913//1913 1912//1912 1998//1998 -f 1906//1906 1905//1905 2020//2020 -f 1908//1908 1907//1907 2021//2021 -f 1909//1909 1908//1908 2022//2022 -f 1911//1911 1910//1910 2023//2023 -f 1901//1901 1900//1900 2001//2001 -f 1903//1903 1902//1902 2024//2024 -f 1893//1893 1904//1904 2025//2025 -f 1894//1894 1893//1893 2026//2026 -f 1967//1967 1966//1966 2027//2027 -f 2004//2004 1969//1969 2005//2005 -f 2005//2005 1969//1969 1968//1968 -f 2005//2005 1968//1968 1967//1967 -f 2027//2027 1966//1966 2028//2028 -f 1966//1966 1965//1965 2028//2028 -f 2028//2028 1965//1965 1964//1964 -f 2028//2028 1964//1964 2029//2029 -f 2029//2029 1964//1964 1963//1963 -f 2029//2029 1963//1963 1896//1896 -f 1896//1896 1895//1895 2030//2030 -f 2030//2030 1895//1895 1894//1894 -f 2001//2001 1900//1900 2002//2002 -f 2002//2002 1900//1900 1899//1899 -f 2002//2002 1899//1899 1898//1898 -f 1898//1898 1897//1897 2031//2031 -f 2031//2031 1897//1897 1911//1911 -f 1909//1909 2022//2022 1910//1910 -f 1998//1998 1912//1912 1999//1999 -f 1999//1999 1912//1912 1920//1920 -f 1999//1999 1920//1920 1919//1919 -f 1919//1919 1918//1918 2032//2032 -f 2032//2032 1918//1918 1917//1917 -f 2019//2019 1916//1916 2033//2033 -f 1916//1916 1915//1915 2033//2033 -f 2033//2033 1915//1915 1914//1914 -f 2033//2033 1914//1914 2034//2034 -f 1923//1923 2035//2035 1924//1924 -f 1924//1924 2035//2035 2034//2034 -f 1924//1924 2034//2034 1925//1925 -f 1925//1925 2034//2034 1914//1914 -f 1922//1922 2018//2018 1923//1923 -f 1995//1995 1929//1929 1996//1996 -f 1996//1996 1929//1929 1928//1928 -f 1996//1996 1928//1928 1927//1927 -f 1927//1927 1926//1926 2036//2036 -f 2036//2036 1926//1926 1938//1938 -f 2015//2015 1937//1937 2037//2037 -f 1937//1937 1936//1936 2037//2037 -f 2037//2037 1936//1936 1935//1935 -f 2037//2037 1935//1935 2038//2038 -f 1935//1935 1934//1934 2038//2038 -f 2038//2038 1934//1934 1942//1942 -f 2038//2038 1942//1942 2039//2039 -f 2039//2039 1942//1942 1941//1941 -f 2039//2039 1941//1941 1940//1940 -f 1992//1992 1943//1943 1993//1993 -f 1993//1993 1943//1943 1955//1955 -f 1993//1993 1955//1955 1954//1954 -f 1954//1954 1953//1953 2040//2040 -f 2040//2040 1953//1953 1952//1952 -f 1950//1950 2010//2010 1951//1951 -f 1989//1989 1959//1959 1990//1990 -f 1990//1990 1959//1959 1958//1958 -f 1990//1990 1958//1958 1957//1957 -f 2029//2029 2041//2041 2028//2028 -f 2028//2028 2041//2041 2042//2042 -f 2028//2028 2042//2042 2027//2027 -f 2027//2027 2042//2042 1988//1988 -f 2043//2043 2044//2044 2025//2025 -f 1904//1904 1903//1903 2025//2025 -f 2025//2025 1903//1903 2024//2024 -f 2025//2025 2024//2024 2043//2043 -f 2043//2043 2024//2024 2045//2045 -f 2043//2043 2045//2045 2046//2046 -f 2046//2046 2045//2045 2047//2047 -f 2048//2048 2049//2049 2021//2021 -f 1907//1907 1906//1906 2021//2021 -f 2021//2021 1906//1906 2020//2020 -f 2021//2021 2020//2020 2048//2048 -f 2048//2048 2020//2020 2050//2050 -f 2048//2048 2050//2050 2051//2051 -f 2051//2051 2050//2050 2052//2052 -f 2035//2035 1981//1981 2034//2034 -f 2034//2034 1981//1981 1982//1982 -f 2034//2034 1982//1982 2033//2033 -f 2033//2033 1982//1982 2053//2053 -f 2033//2033 2053//2053 2019//2019 -f 2019//2019 2053//2053 2054//2054 -f 2055//2055 2056//2056 2017//2017 -f 1933//1933 1932//1932 2017//2017 -f 2017//2017 1932//1932 2016//2016 -f 2017//2017 2016//2016 2055//2055 -f 2055//2055 2016//2016 2057//2057 -f 2055//2055 2057//2057 2058//2058 -f 2058//2058 2057//2057 2059//2059 -f 2039//2039 1977//1977 2038//2038 -f 2038//2038 1977//1977 1978//1978 -f 2038//2038 1978//1978 2037//2037 -f 2037//2037 1978//1978 2060//2060 -f 2037//2037 2060//2060 2015//2015 -f 2015//2015 2060//2060 2061//2061 -f 2062//2062 2063//2063 2013//2013 -f 1947//1947 1946//1946 2013//2013 -f 2013//2013 1946//1946 2012//2012 -f 2013//2013 2012//2012 2062//2062 -f 2062//2062 2012//2012 2064//2064 -f 2062//2062 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2067//2067 2068//2068 2009//2009 -f 2069//2069 2070//2070 2007//2007 -f 1956//1956 1971//1971 2007//2007 -f 2007//2007 1971//1971 2071//2071 -f 2007//2007 2071//2071 2069//2069 -f 2069//2069 2071//2071 2072//2072 -f 2073//2073 2074//2074 2006//2006 -f 2006//2006 2074//2074 2072//2072 -f 2006//2006 2072//2072 2004//2004 -f 2004//2004 2072//2072 2071//2071 -f 2004//2004 2071//2071 1970//1970 -f 1970//1970 2071//2071 1971//1971 -f 1967//1967 2027//2027 2005//2005 -f 2005//2005 2027//2027 1988//1988 -f 2005//2005 1988//1988 2006//2006 -f 2006//2006 1988//1988 1987//1987 -f 2006//2006 1987//1987 2073//2073 -f 1986//1986 1988//1988 2075//2075 -f 2075//2075 1988//1988 2042//2042 -f 2075//2075 2042//2042 2076//2076 -f 2076//2076 2042//2042 2041//2041 -f 2076//2076 2041//2041 2077//2077 -f 2078//2078 2079//2079 2080//2080 -f 1896//1896 2030//2030 2029//2029 -f 2029//2029 2030//2030 2078//2078 -f 2029//2029 2078//2078 2041//2041 -f 2041//2041 2078//2078 2080//2080 -f 2041//2041 2080//2080 2077//2077 -f 1894//1894 2026//2026 2030//2030 -f 2030//2030 2026//2026 2081//2081 -f 2030//2030 2081//2081 2078//2078 -f 2078//2078 2081//2081 2082//2082 -f 2078//2078 2082//2082 2079//2079 -f 1893//1893 2025//2025 2026//2026 -f 2026//2026 2025//2025 2044//2044 -f 2026//2026 2044//2044 2081//2081 -f 2081//2081 2044//2044 2083//2083 -f 2081//2081 2083//2083 2082//2082 -f 2046//2046 2084//2084 2043//2043 -f 2043//2043 2084//2084 2085//2085 -f 2043//2043 2085//2085 2044//2044 -f 2044//2044 2085//2085 2086//2086 -f 2044//2044 2086//2086 2083//2083 -f 1902//1902 1901//1901 2024//2024 -f 2024//2024 1901//1901 2001//2001 -f 2024//2024 2001//2001 2045//2045 -f 2045//2045 2001//2001 2003//2003 -f 2045//2045 2003//2003 2047//2047 -f 2047//2047 2003//2003 2087//2087 -f 2088//2088 2089//2089 2090//2090 -f 1898//1898 2031//2031 2002//2002 -f 2002//2002 2031//2031 2088//2088 -f 2002//2002 2088//2088 2003//2003 -f 2003//2003 2088//2088 2090//2090 -f 2003//2003 2090//2090 2087//2087 -f 1911//1911 2023//2023 2031//2031 -f 2031//2031 2023//2023 1985//1985 -f 2031//2031 1985//1985 2088//2088 -f 2088//2088 1985//1985 1984//1984 -f 2088//2088 1984//1984 2089//2089 -f 1910//1910 2022//2022 2023//2023 -f 2023//2023 2022//2022 2091//2091 -f 2023//2023 2091//2091 1985//1985 -f 1985//1985 2091//2091 2092//2092 -f 1985//1985 2092//2092 1983//1983 -f 1908//1908 2021//2021 2022//2022 -f 2022//2022 2021//2021 2049//2049 -f 2022//2022 2049//2049 2091//2091 -f 2091//2091 2049//2049 2093//2093 -f 2091//2091 2093//2093 2092//2092 -f 2051//2051 2094//2094 2048//2048 -f 2048//2048 2094//2094 2095//2095 -f 2048//2048 2095//2095 2049//2049 -f 2049//2049 2095//2095 2096//2096 -f 2049//2049 2096//2096 2093//2093 -f 1905//1905 1913//1913 2020//2020 -f 2020//2020 1913//1913 1998//1998 -f 2020//2020 1998//1998 2050//2050 -f 2050//2050 1998//1998 2000//2000 -f 2050//2050 2000//2000 2052//2052 -f 2052//2052 2000//2000 2097//2097 -f 2098//2098 2099//2099 2100//2100 -f 1919//1919 2032//2032 1999//1999 -f 1999//1999 2032//2032 2098//2098 -f 1999//1999 2098//2098 2000//2000 -f 2000//2000 2098//2098 2100//2100 -f 2000//2000 2100//2100 2097//2097 -f 1917//1917 2019//2019 2032//2032 -f 2032//2032 2019//2019 2054//2054 -f 2032//2032 2054//2054 2098//2098 -f 2098//2098 2054//2054 2101//2101 -f 2098//2098 2101//2101 2099//2099 -f 1980//1980 2102//2102 1982//1982 -f 1982//1982 2102//2102 2103//2103 -f 1982//1982 2103//2103 2053//2053 -f 2053//2053 2103//2103 2104//2104 -f 2053//2053 2104//2104 2054//2054 -f 2054//2054 2104//2104 2105//2105 -f 2054//2054 2105//2105 2101//2101 -f 1923//1923 2018//2018 2035//2035 -f 2035//2035 2018//2018 2106//2106 -f 2035//2035 2106//2106 1981//1981 -f 1981//1981 2106//2106 2107//2107 -f 1981//1981 2107//2107 1979//1979 -f 1921//1921 2017//2017 2018//2018 -f 2018//2018 2017//2017 2056//2056 -f 2018//2018 2056//2056 2106//2106 -f 2106//2106 2056//2056 2108//2108 -f 2106//2106 2108//2108 2107//2107 -f 2058//2058 2109//2109 2055//2055 -f 2055//2055 2109//2109 2110//2110 -f 2055//2055 2110//2110 2056//2056 -f 2056//2056 2110//2110 2111//2111 -f 2056//2056 2111//2111 2108//2108 -f 1931//1931 1930//1930 2016//2016 -f 2016//2016 1930//1930 1995//1995 -f 2016//2016 1995//1995 2057//2057 -f 2057//2057 1995//1995 1997//1997 -f 2057//2057 1997//1997 2059//2059 -f 2059//2059 1997//1997 2112//2112 -f 2113//2113 2114//2114 2115//2115 -f 1927//1927 2036//2036 1996//1996 -f 1996//1996 2036//2036 2113//2113 -f 1996//1996 2113//2113 1997//1997 -f 1997//1997 2113//2113 2115//2115 -f 1997//1997 2115//2115 2112//2112 -f 1938//1938 2015//2015 2036//2036 -f 2036//2036 2015//2015 2061//2061 -f 2036//2036 2061//2061 2113//2113 -f 2113//2113 2061//2061 2116//2116 -f 2113//2113 2116//2116 2114//2114 -f 1976//1976 2117//2117 1978//1978 -f 1978//1978 2117//2117 2118//2118 -f 1978//1978 2118//2118 2060//2060 -f 2060//2060 2118//2118 2119//2119 -f 2060//2060 2119//2119 2061//2061 -f 2061//2061 2119//2119 2120//2120 -f 2061//2061 2120//2120 2116//2116 -f 1940//1940 2014//2014 2039//2039 -f 2039//2039 2014//2014 2121//2121 -f 2039//2039 2121//2121 1977//1977 -f 1977//1977 2121//2121 2122//2122 -f 1977//1977 2122//2122 1975//1975 -f 1939//1939 2013//2013 2014//2014 -f 2014//2014 2013//2013 2063//2063 -f 2014//2014 2063//2063 2121//2121 -f 2121//2121 2063//2063 2123//2123 -f 2121//2121 2123//2123 2122//2122 -f 2065//2065 2124//2124 2062//2062 -f 2062//2062 2124//2124 2125//2125 -f 2062//2062 2125//2125 2063//2063 -f 2063//2063 2125//2125 2126//2126 -f 2063//2063 2126//2126 2123//2123 -f 1945//1945 1944//1944 2012//2012 -f 2012//2012 1944//1944 1992//1992 -f 2012//2012 1992//1992 2064//2064 -f 2064//2064 1992//1992 1994//1994 -f 2064//2064 1994//1994 2066//2066 -f 2066//2066 1994//1994 2127//2127 -f 2128//2128 2129//2129 2130//2130 -f 1954//1954 2040//2040 1993//1993 -f 1993//1993 2040//2040 2128//2128 -f 1993//1993 2128//2128 1994//1994 -f 1994//1994 2128//2128 2130//2130 -f 1994//1994 2130//2130 2127//2127 -f 1952//1952 2011//2011 2040//2040 -f 2040//2040 2011//2011 1974//1974 -f 2040//2040 1974//1974 2128//2128 -f 2128//2128 1974//1974 1973//1973 -f 2128//2128 1973//1973 2129//2129 -f 1951//1951 2010//2010 2011//2011 -f 2011//2011 2010//2010 2131//2131 -f 2011//2011 2131//2131 1974//1974 -f 1974//1974 2131//2131 2132//2132 -f 1974//1974 2132//2132 1972//1972 -f 1949//1949 2009//2009 2010//2010 -f 2010//2010 2009//2009 2068//2068 -f 2010//2010 2068//2068 2131//2131 -f 2131//2131 2068//2068 2133//2133 -f 2131//2131 2133//2133 2132//2132 -f 2134//2134 2135//2135 2136//2136 -f 2136//2136 2135//2135 2067//2067 -f 2136//2136 2067//2067 2008//2008 -f 2008//2008 2067//2067 2009//2009 -f 2008//2008 2009//2009 1962//1962 -f 1962//1962 2009//2009 1948//1948 -f 2135//2135 2137//2137 2067//2067 -f 2067//2067 2137//2137 2138//2138 -f 2067//2067 2138//2138 2068//2068 -f 2068//2068 2138//2138 2139//2139 -f 2068//2068 2139//2139 2133//2133 -f 1961//1961 1960//1960 2008//2008 -f 2008//2008 1960//1960 1989//1989 -f 2008//2008 1989//1989 2136//2136 -f 2136//2136 1989//1989 1991//1991 -f 2136//2136 1991//1991 2134//2134 -f 2134//2134 1991//1991 2140//2140 -f 1957//1957 2007//2007 1990//1990 -f 1990//1990 2007//2007 2070//2070 -f 1990//1990 2070//2070 1991//1991 -f 1991//1991 2070//2070 2141//2141 -f 1991//1991 2141//2141 2140//2140 -f 2074//2074 2142//2142 2072//2072 -f 2072//2072 2142//2142 2143//2143 -f 2072//2072 2143//2143 2069//2069 -f 2069//2069 2143//2143 2144//2144 -f 2069//2069 2144//2144 2070//2070 -f 2070//2070 2144//2144 2145//2145 -f 2070//2070 2145//2145 2141//2141 -f 2146//2146 2147//2147 2104//2104 -f 2104//2104 2147//2147 2105//2105 -f 2105//2105 2147//2147 2148//2148 -f 2105//2105 2148//2148 2101//2101 -f 2101//2101 2148//2148 2149//2149 -f 2101//2101 2149//2149 2099//2099 -f 2099//2099 2149//2149 2150//2150 -f 2099//2099 2150//2150 2100//2100 -f 2100//2100 2150//2150 2097//2097 -f 2097//2097 2150//2150 2151//2151 -f 2097//2097 2151//2151 2052//2052 -f 2151//2151 2152//2152 2052//2052 -f 2052//2052 2152//2152 2153//2153 -f 2052//2052 2153//2153 2051//2051 -f 2051//2051 2153//2153 2154//2154 -f 2155//2155 1984//1984 2156//2156 -f 2156//2156 1984//1984 1983//1983 -f 2156//2156 1983//1983 2157//2157 -f 2157//2157 1983//1983 2092//2092 -f 2157//2157 2092//2092 2158//2158 -f 2158//2158 2092//2092 2093//2093 -f 2158//2158 2093//2093 2159//2159 -f 2159//2159 2093//2093 2096//2096 -f 2159//2159 2096//2096 2160//2160 -f 2160//2160 2096//2096 2095//2095 -f 2160//2160 2095//2095 2154//2154 -f 2154//2154 2095//2095 2094//2094 -f 2154//2154 2094//2094 2051//2051 -f 2161//2161 2082//2082 2162//2162 -f 2162//2162 2082//2082 2083//2083 -f 2162//2162 2083//2083 2163//2163 -f 2163//2163 2083//2083 2086//2086 -f 2163//2163 2086//2086 2164//2164 -f 2164//2164 2086//2086 2085//2085 -f 2164//2164 2085//2085 2165//2165 -f 2165//2165 2085//2085 2084//2084 -f 2165//2165 2084//2084 2166//2166 -f 2166//2166 2084//2084 2046//2046 -f 2166//2166 2046//2046 2167//2167 -f 2167//2167 2046//2046 2047//2047 -f 2167//2167 2047//2047 2168//2168 -f 2168//2168 2047//2047 2087//2087 -f 2168//2168 2087//2087 2169//2169 -f 2169//2169 2087//2087 2090//2090 -f 2169//2169 2090//2090 2155//2155 -f 2155//2155 2090//2090 2089//2089 -f 2155//2155 2089//2089 1984//1984 -f 2170//2170 1987//1987 2171//2171 -f 2171//2171 1987//1987 1986//1986 -f 2171//2171 1986//1986 2172//2172 -f 2172//2172 1986//1986 2075//2075 -f 2172//2172 2075//2075 2173//2173 -f 2173//2173 2075//2075 2076//2076 -f 2173//2173 2076//2076 2174//2174 -f 2174//2174 2076//2076 2077//2077 -f 2174//2174 2077//2077 2175//2175 -f 2175//2175 2077//2077 2080//2080 -f 2175//2175 2080//2080 2161//2161 -f 2161//2161 2080//2080 2079//2079 -f 2161//2161 2079//2079 2082//2082 -f 2176//2176 2145//2145 2177//2177 -f 2177//2177 2145//2145 2144//2144 -f 2177//2177 2144//2144 2178//2178 -f 2178//2178 2144//2144 2143//2143 -f 2178//2178 2143//2143 2179//2179 -f 2179//2179 2143//2143 2142//2142 -f 2179//2179 2142//2142 2180//2180 -f 2180//2180 2142//2142 2074//2074 -f 2180//2180 2074//2074 2170//2170 -f 2170//2170 2074//2074 2073//2073 -f 2170//2170 2073//2073 1987//1987 -f 2181//2181 1973//1973 2182//2182 -f 2182//2182 1973//1973 1972//1972 -f 2182//2182 1972//1972 2183//2183 -f 2183//2183 1972//1972 2132//2132 -f 2183//2183 2132//2132 2184//2184 -f 2184//2184 2132//2132 2133//2133 -f 2184//2184 2133//2133 2185//2185 -f 2185//2185 2133//2133 2139//2139 -f 2185//2185 2139//2139 2186//2186 -f 2186//2186 2139//2139 2138//2138 -f 2186//2186 2138//2138 2187//2187 -f 2187//2187 2138//2138 2137//2137 -f 2187//2187 2137//2137 2188//2188 -f 2188//2188 2137//2137 2135//2135 -f 2188//2188 2135//2135 2189//2189 -f 2189//2189 2135//2135 2134//2134 -f 2189//2189 2134//2134 2190//2190 -f 2190//2190 2134//2134 2140//2140 -f 2190//2190 2140//2140 2176//2176 -f 2176//2176 2140//2140 2141//2141 -f 2176//2176 2141//2141 2145//2145 -f 2191//2191 2124//2124 2192//2192 -f 2192//2192 2124//2124 2065//2065 -f 2192//2192 2065//2065 2193//2193 -f 2193//2193 2065//2065 2066//2066 -f 2193//2193 2066//2066 2194//2194 -f 2194//2194 2066//2066 2127//2127 -f 2194//2194 2127//2127 2195//2195 -f 2195//2195 2127//2127 2130//2130 -f 2195//2195 2130//2130 2181//2181 -f 2181//2181 2130//2130 2129//2129 -f 2181//2181 2129//2129 1973//1973 -f 2196//2196 2116//2116 2197//2197 -f 2197//2197 2116//2116 2120//2120 -f 2197//2197 2120//2120 2198//2198 -f 2198//2198 2120//2120 2119//2119 -f 2198//2198 2119//2119 2199//2199 -f 2199//2199 2119//2119 2118//2118 -f 2199//2199 2118//2118 2200//2200 -f 2200//2200 2118//2118 2117//2117 -f 2200//2200 2117//2117 2201//2201 -f 2201//2201 2117//2117 1976//1976 -f 2201//2201 1976//1976 2202//2202 -f 2202//2202 1976//1976 1975//1975 -f 2202//2202 1975//1975 2203//2203 -f 2203//2203 1975//1975 2122//2122 -f 2203//2203 2122//2122 2204//2204 -f 2204//2204 2122//2122 2123//2123 -f 2204//2204 2123//2123 2205//2205 -f 2205//2205 2123//2123 2126//2126 -f 2205//2205 2126//2126 2191//2191 -f 2191//2191 2126//2126 2125//2125 -f 2191//2191 2125//2125 2124//2124 -f 2206//2206 2058//2058 2207//2207 -f 2207//2207 2058//2058 2059//2059 -f 2207//2207 2059//2059 2208//2208 -f 2208//2208 2059//2059 2112//2112 -f 2208//2208 2112//2112 2209//2209 -f 2209//2209 2112//2112 2115//2115 -f 2209//2209 2115//2115 2196//2196 -f 2196//2196 2115//2115 2114//2114 -f 2196//2196 2114//2114 2116//2116 -f 2104//2104 2103//2103 2146//2146 -f 2146//2146 2103//2103 2102//2102 -f 2146//2146 2102//2102 2210//2210 -f 2210//2210 2102//2102 1980//1980 -f 2210//2210 1980//1980 2211//2211 -f 2211//2211 1980//1980 1979//1979 -f 2211//2211 1979//1979 2212//2212 -f 2212//2212 1979//1979 2107//2107 -f 2212//2212 2107//2107 2213//2213 -f 2213//2213 2107//2107 2108//2108 -f 2213//2213 2108//2108 2214//2214 -f 2214//2214 2108//2108 2111//2111 -f 2214//2214 2111//2111 2215//2215 -f 2215//2215 2111//2111 2110//2110 -f 2215//2215 2110//2110 2206//2206 -f 2206//2206 2110//2110 2109//2109 -f 2206//2206 2109//2109 2058//2058 -f 2216//2216 2217//2217 2218//2218 -f 2219//2219 2220//2220 2221//2221 -f 2222//2222 2223//2223 2224//2224 -f 2225//2225 2226//2226 2227//2227 -f 2228//2228 2229//2229 2230//2230 -f 2231//2231 2232//2232 2233//2233 -f 2234//2234 2235//2235 2236//2236 -f 2237//2237 2238//2238 2239//2239 -f 2240//2240 2241//2241 2242//2242 -f 2243//2243 2244//2244 2245//2245 -f 2246//2246 2247//2247 2248//2248 -f 2249//2249 2250//2250 2251//2251 -f 2252//2252 2253//2253 2254//2254 -f 2242//2242 2255//2255 2256//2256 -f 2253//2253 2257//2257 2258//2258 -f 2255//2255 2259//2259 2260//2260 -f 2184//2184 2185//2185 2261//2261 -f 2182//2182 2183//2183 2262//2262 -f 2191//2191 2192//2192 2263//2263 -f 2209//2209 2196//2196 2264//2264 -f 2213//2213 2214//2214 2265//2265 -f 2211//2211 2212//2212 2266//2266 -f 2146//2146 2210//2210 2267//2267 -f 2148//2148 2147//2147 2268//2268 -f 2150//2150 2149//2149 2269//2269 -f 2165//2165 2166//2166 2270//2270 -f 2163//2163 2164//2164 2271//2271 -f 2175//2175 2161//2161 2272//2272 -f 2180//2180 2273//2273 2274//2274 -f 2170//2170 2171//2171 2275//2275 -f 2172//2172 2173//2173 2276//2276 -f 2175//2175 2272//2272 2174//2174 -f 2156//2156 2277//2277 2260//2260 -f 2167//2167 2168//2168 2259//2259 -f 2259//2259 2168//2168 2169//2169 -f 2259//2259 2169//2169 2260//2260 -f 2260//2260 2169//2169 2155//2155 -f 2260//2260 2155//2155 2156//2156 -f 2156//2156 2157//2157 2277//2277 -f 2277//2277 2157//2157 2158//2158 -f 2277//2277 2158//2158 2278//2278 -f 2278//2278 2158//2158 2159//2159 -f 2278//2278 2159//2159 2279//2279 -f 2159//2159 2160//2160 2279//2279 -f 2279//2279 2160//2160 2154//2154 -f 2279//2279 2154//2154 2280//2280 -f 2280//2280 2154//2154 2153//2153 -f 2280//2280 2153//2153 2152//2152 -f 2206//2206 2207//2207 2281//2281 -f 2209//2209 2264//2264 2208//2208 -f 2197//2197 2198//2198 2257//2257 -f 2257//2257 2198//2198 2199//2199 -f 2257//2257 2199//2199 2258//2258 -f 2258//2258 2199//2199 2200//2200 -f 2258//2258 2200//2200 2282//2282 -f 2200//2200 2201//2201 2282//2282 -f 2282//2282 2201//2201 2202//2202 -f 2282//2282 2202//2202 2283//2283 -f 2205//2205 2284//2284 2204//2204 -f 2204//2204 2284//2284 2283//2283 -f 2204//2204 2283//2283 2203//2203 -f 2203//2203 2283//2283 2202//2202 -f 2194//2194 2195//2195 2285//2285 -f 2182//2182 2262//2262 2181//2181 -f 2187//2187 2188//2188 2286//2286 -f 2286//2286 2188//2188 2189//2189 -f 2286//2286 2189//2189 2287//2287 -f 2189//2189 2190//2190 2287//2287 -f 2287//2287 2190//2190 2176//2176 -f 2287//2287 2176//2176 2288//2288 -f 2176//2176 2177//2177 2288//2288 -f 2288//2288 2177//2177 2178//2178 -f 2288//2288 2178//2178 2274//2274 -f 2274//2274 2178//2178 2179//2179 -f 2274//2274 2179//2179 2180//2180 -f 2273//2273 2289//2289 2290//2290 -f 2255//2255 2260//2260 2256//2256 -f 2256//2256 2260//2260 2277//2277 -f 2256//2256 2277//2277 2291//2291 -f 2291//2291 2277//2277 2278//2278 -f 2291//2291 2278//2278 2292//2292 -f 2292//2292 2278//2278 2279//2279 -f 2292//2292 2279//2279 2293//2293 -f 2293//2293 2279//2279 2280//2280 -f 2293//2293 2280//2280 2294//2294 -f 2253//2253 2258//2258 2254//2254 -f 2254//2254 2258//2258 2282//2282 -f 2254//2254 2282//2282 2295//2295 -f 2295//2295 2282//2282 2283//2283 -f 2295//2295 2283//2283 2296//2296 -f 2296//2296 2283//2283 2284//2284 -f 2296//2296 2284//2284 2297//2297 -f 2273//2273 2290//2290 2274//2274 -f 2274//2274 2290//2290 2298//2298 -f 2274//2274 2298//2298 2288//2288 -f 2288//2288 2298//2298 2299//2299 -f 2288//2288 2299//2299 2287//2287 -f 2287//2287 2299//2299 2300//2300 -f 2287//2287 2300//2300 2286//2286 -f 2289//2289 2301//2301 2302//2302 -f 2161//2161 2162//2162 2272//2272 -f 2272//2272 2162//2162 2303//2303 -f 2272//2272 2303//2303 2304//2304 -f 2304//2304 2303//2303 2305//2305 -f 2304//2304 2305//2305 2306//2306 -f 2306//2306 2305//2305 2248//2248 -f 2242//2242 2256//2256 2307//2307 -f 2307//2307 2256//2256 2291//2291 -f 2307//2307 2291//2291 2308//2308 -f 2308//2308 2291//2291 2292//2292 -f 2308//2308 2292//2292 2309//2309 -f 2309//2309 2292//2292 2293//2293 -f 2309//2309 2293//2293 2310//2310 -f 2310//2310 2293//2293 2294//2294 -f 2310//2310 2294//2294 2239//2239 -f 2149//2149 2148//2148 2269//2269 -f 2269//2269 2148//2148 2268//2268 -f 2269//2269 2268//2268 2311//2311 -f 2311//2311 2268//2268 2312//2312 -f 2311//2311 2312//2312 2313//2313 -f 2313//2313 2312//2312 2236//2236 -f 2214//2214 2215//2215 2265//2265 -f 2265//2265 2215//2215 2314//2314 -f 2265//2265 2314//2314 2315//2315 -f 2315//2315 2314//2314 2316//2316 -f 2315//2315 2316//2316 2317//2317 -f 2317//2317 2316//2316 2230//2230 -f 2252//2252 2254//2254 2318//2318 -f 2318//2318 2254//2254 2295//2295 -f 2318//2318 2295//2295 2319//2319 -f 2319//2319 2295//2295 2296//2296 -f 2319//2319 2296//2296 2320//2320 -f 2320//2320 2296//2296 2297//2297 -f 2320//2320 2297//2297 2321//2321 -f 2195//2195 2181//2181 2285//2285 -f 2285//2285 2181//2181 2262//2262 -f 2285//2285 2262//2262 2322//2322 -f 2322//2322 2262//2262 2323//2323 -f 2322//2322 2323//2323 2324//2324 -f 2324//2324 2323//2323 2221//2221 -f 2289//2289 2302//2302 2290//2290 -f 2290//2290 2302//2302 2325//2325 -f 2290//2290 2325//2325 2298//2298 -f 2298//2298 2325//2325 2326//2326 -f 2298//2298 2326//2326 2299//2299 -f 2299//2299 2326//2326 2327//2327 -f 2299//2299 2327//2327 2300//2300 -f 2180//2180 2170//2170 2273//2273 -f 2273//2273 2170//2170 2275//2275 -f 2273//2273 2275//2275 2289//2289 -f 2289//2289 2275//2275 2328//2328 -f 2289//2289 2328//2328 2301//2301 -f 2301//2301 2328//2328 2251//2251 -f 2301//2301 2251//2251 2329//2329 -f 2329//2329 2251//2251 2250//2250 -f 2330//2330 2249//2249 2331//2331 -f 2331//2331 2249//2249 2251//2251 -f 2331//2331 2251//2251 2332//2332 -f 2332//2332 2251//2251 2328//2328 -f 2332//2332 2328//2328 2276//2276 -f 2276//2276 2328//2328 2275//2275 -f 2276//2276 2275//2275 2172//2172 -f 2172//2172 2275//2275 2171//2171 -f 2173//2173 2174//2174 2276//2276 -f 2276//2276 2174//2174 2272//2272 -f 2276//2276 2272//2272 2332//2332 -f 2332//2332 2272//2272 2304//2304 -f 2332//2332 2304//2304 2331//2331 -f 2331//2331 2304//2304 2306//2306 -f 2331//2331 2306//2306 2330//2330 -f 2330//2330 2306//2306 2333//2333 -f 2248//2248 2247//2247 2306//2306 -f 2306//2306 2247//2247 2334//2334 -f 2306//2306 2334//2334 2333//2333 -f 2162//2162 2163//2163 2303//2303 -f 2303//2303 2163//2163 2271//2271 -f 2303//2303 2271//2271 2305//2305 -f 2305//2305 2271//2271 2335//2335 -f 2305//2305 2335//2335 2248//2248 -f 2248//2248 2335//2335 2245//2245 -f 2248//2248 2245//2245 2246//2246 -f 2246//2246 2245//2245 2244//2244 -f 2336//2336 2243//2243 2337//2337 -f 2337//2337 2243//2243 2245//2245 -f 2337//2337 2245//2245 2338//2338 -f 2338//2338 2245//2245 2335//2335 -f 2338//2338 2335//2335 2270//2270 -f 2270//2270 2335//2335 2271//2271 -f 2270//2270 2271//2271 2165//2165 -f 2165//2165 2271//2271 2164//2164 -f 2166//2166 2167//2167 2270//2270 -f 2270//2270 2167//2167 2259//2259 -f 2270//2270 2259//2259 2338//2338 -f 2338//2338 2259//2259 2255//2255 -f 2338//2338 2255//2255 2337//2337 -f 2337//2337 2255//2255 2242//2242 -f 2337//2337 2242//2242 2336//2336 -f 2336//2336 2242//2242 2241//2241 -f 2240//2240 2242//2242 2339//2339 -f 2339//2339 2242//2242 2307//2307 -f 2339//2339 2307//2307 2340//2340 -f 2340//2340 2307//2307 2308//2308 -f 2340//2340 2308//2308 2341//2341 -f 2341//2341 2308//2308 2309//2309 -f 2341//2341 2309//2309 2342//2342 -f 2342//2342 2309//2309 2310//2310 -f 2342//2342 2310//2310 2343//2343 -f 2239//2239 2238//2238 2310//2310 -f 2310//2310 2238//2238 2344//2344 -f 2310//2310 2344//2344 2343//2343 -f 2345//2345 2237//2237 2346//2346 -f 2346//2346 2237//2237 2239//2239 -f 2346//2346 2239//2239 2347//2347 -f 2347//2347 2239//2239 2294//2294 -f 2347//2347 2294//2294 2348//2348 -f 2348//2348 2294//2294 2280//2280 -f 2348//2348 2280//2280 2151//2151 -f 2151//2151 2280//2280 2152//2152 -f 2151//2151 2150//2150 2348//2348 -f 2348//2348 2150//2150 2269//2269 -f 2348//2348 2269//2269 2347//2347 -f 2347//2347 2269//2269 2311//2311 -f 2347//2347 2311//2311 2346//2346 -f 2346//2346 2311//2311 2313//2313 -f 2346//2346 2313//2313 2345//2345 -f 2345//2345 2313//2313 2349//2349 -f 2236//2236 2235//2235 2313//2313 -f 2313//2313 2235//2235 2350//2350 -f 2313//2313 2350//2350 2349//2349 -f 2147//2147 2146//2146 2268//2268 -f 2268//2268 2146//2146 2267//2267 -f 2268//2268 2267//2267 2312//2312 -f 2312//2312 2267//2267 2351//2351 -f 2312//2312 2351//2351 2236//2236 -f 2236//2236 2351//2351 2233//2233 -f 2236//2236 2233//2233 2234//2234 -f 2234//2234 2233//2233 2232//2232 -f 2352//2352 2231//2231 2353//2353 -f 2353//2353 2231//2231 2233//2233 -f 2353//2353 2233//2233 2354//2354 -f 2354//2354 2233//2233 2351//2351 -f 2354//2354 2351//2351 2266//2266 -f 2266//2266 2351//2351 2267//2267 -f 2266//2266 2267//2267 2211//2211 -f 2211//2211 2267//2267 2210//2210 -f 2212//2212 2213//2213 2266//2266 -f 2266//2266 2213//2213 2265//2265 -f 2266//2266 2265//2265 2354//2354 -f 2354//2354 2265//2265 2315//2315 -f 2354//2354 2315//2315 2353//2353 -f 2353//2353 2315//2315 2317//2317 -f 2353//2353 2317//2317 2352//2352 -f 2352//2352 2317//2317 2355//2355 -f 2230//2230 2229//2229 2317//2317 -f 2317//2317 2229//2229 2356//2356 -f 2317//2317 2356//2356 2355//2355 -f 2226//2226 2228//2228 2227//2227 -f 2227//2227 2228//2228 2230//2230 -f 2227//2227 2230//2230 2357//2357 -f 2357//2357 2230//2230 2316//2316 -f 2357//2357 2316//2316 2281//2281 -f 2281//2281 2316//2316 2314//2314 -f 2281//2281 2314//2314 2206//2206 -f 2206//2206 2314//2314 2215//2215 -f 2358//2358 2225//2225 2359//2359 -f 2359//2359 2225//2225 2227//2227 -f 2359//2359 2227//2227 2360//2360 -f 2360//2360 2227//2227 2357//2357 -f 2360//2360 2357//2357 2264//2264 -f 2264//2264 2357//2357 2281//2281 -f 2264//2264 2281//2281 2208//2208 -f 2208//2208 2281//2281 2207//2207 -f 2196//2196 2197//2197 2264//2264 -f 2264//2264 2197//2197 2257//2257 -f 2264//2264 2257//2257 2360//2360 -f 2360//2360 2257//2257 2253//2253 -f 2360//2360 2253//2253 2359//2359 -f 2359//2359 2253//2253 2252//2252 -f 2359//2359 2252//2252 2358//2358 -f 2358//2358 2252//2252 2361//2361 -f 2362//2362 2363//2363 2321//2321 -f 2321//2321 2363//2363 2364//2364 -f 2321//2321 2364//2364 2320//2320 -f 2320//2320 2364//2364 2365//2365 -f 2320//2320 2365//2365 2319//2319 -f 2319//2319 2365//2365 2366//2366 -f 2319//2319 2366//2366 2318//2318 -f 2318//2318 2366//2366 2367//2367 -f 2318//2318 2367//2367 2252//2252 -f 2252//2252 2367//2367 2368//2368 -f 2252//2252 2368//2368 2361//2361 -f 2205//2205 2191//2191 2284//2284 -f 2284//2284 2191//2191 2263//2263 -f 2284//2284 2263//2263 2297//2297 -f 2297//2297 2263//2263 2369//2369 -f 2297//2297 2369//2369 2321//2321 -f 2321//2321 2369//2369 2224//2224 -f 2321//2321 2224//2224 2362//2362 -f 2362//2362 2224//2224 2223//2223 -f 2370//2370 2222//2222 2371//2371 -f 2371//2371 2222//2222 2224//2224 -f 2371//2371 2224//2224 2372//2372 -f 2372//2372 2224//2224 2369//2369 -f 2372//2372 2369//2369 2373//2373 -f 2373//2373 2369//2369 2263//2263 -f 2373//2373 2263//2263 2193//2193 -f 2193//2193 2263//2263 2192//2192 -f 2193//2193 2194//2194 2373//2373 -f 2373//2373 2194//2194 2285//2285 -f 2373//2373 2285//2285 2372//2372 -f 2372//2372 2285//2285 2322//2322 -f 2372//2372 2322//2322 2371//2371 -f 2371//2371 2322//2322 2324//2324 -f 2371//2371 2324//2324 2370//2370 -f 2370//2370 2324//2324 2374//2374 -f 2221//2221 2220//2220 2324//2324 -f 2324//2324 2220//2220 2375//2375 -f 2324//2324 2375//2375 2374//2374 -f 2217//2217 2219//2219 2218//2218 -f 2218//2218 2219//2219 2221//2221 -f 2218//2218 2221//2221 2376//2376 -f 2376//2376 2221//2221 2323//2323 -f 2376//2376 2323//2323 2261//2261 -f 2261//2261 2323//2323 2262//2262 -f 2261//2261 2262//2262 2184//2184 -f 2184//2184 2262//2262 2183//2183 -f 2377//2377 2216//2216 2378//2378 -f 2378//2378 2216//2216 2218//2218 -f 2378//2378 2218//2218 2379//2379 -f 2379//2379 2218//2218 2376//2376 -f 2379//2379 2376//2376 2380//2380 -f 2380//2380 2376//2376 2261//2261 -f 2380//2380 2261//2261 2186//2186 -f 2186//2186 2261//2261 2185//2185 -f 2186//2186 2187//2187 2380//2380 -f 2380//2380 2187//2187 2286//2286 -f 2380//2380 2286//2286 2379//2379 -f 2379//2379 2286//2286 2300//2300 -f 2379//2379 2300//2300 2378//2378 -f 2378//2378 2300//2300 2327//2327 -f 2378//2378 2327//2327 2377//2377 -f 2377//2377 2327//2327 2381//2381 -f 2329//2329 2382//2382 2301//2301 -f 2301//2301 2382//2382 2383//2383 -f 2301//2301 2383//2383 2302//2302 -f 2302//2302 2383//2383 2384//2384 -f 2302//2302 2384//2384 2325//2325 -f 2325//2325 2384//2384 2385//2385 -f 2325//2325 2385//2385 2326//2326 -f 2326//2326 2385//2385 2386//2386 -f 2326//2326 2386//2386 2327//2327 -f 2327//2327 2386//2386 2387//2387 -f 2327//2327 2387//2387 2381//2381 -f 2388//2388 2336//2336 2389//2389 -f 2389//2389 2336//2336 2241//2241 -f 2389//2389 2241//2241 2390//2390 -f 2390//2390 2241//2241 2240//2240 -f 2390//2390 2240//2240 2391//2391 -f 2391//2391 2240//2240 2339//2339 -f 2391//2391 2339//2339 2392//2392 -f 2392//2392 2339//2339 2340//2340 -f 2392//2392 2340//2340 2393//2393 -f 2393//2393 2340//2340 2341//2341 -f 2393//2393 2341//2341 2394//2394 -f 2394//2394 2341//2341 2342//2342 -f 2395//2395 2396//2396 2352//2352 -f 2352//2352 2396//2396 2397//2397 -f 2352//2352 2397//2397 2231//2231 -f 2231//2231 2397//2397 2398//2398 -f 2231//2231 2398//2398 2232//2232 -f 2232//2232 2398//2398 2399//2399 -f 2232//2232 2399//2399 2234//2234 -f 2234//2234 2399//2399 2400//2400 -f 2234//2234 2400//2400 2235//2235 -f 2235//2235 2400//2400 2401//2401 -f 2235//2235 2401//2401 2350//2350 -f 2350//2350 2401//2401 2402//2402 -f 2350//2350 2402//2402 2349//2349 -f 2349//2349 2402//2402 2403//2403 -f 2349//2349 2403//2403 2345//2345 -f 2345//2345 2403//2403 2404//2404 -f 2345//2345 2404//2404 2237//2237 -f 2237//2237 2404//2404 2405//2405 -f 2237//2237 2405//2405 2238//2238 -f 2238//2238 2405//2405 2406//2406 -f 2238//2238 2406//2406 2344//2344 -f 2344//2344 2406//2406 2407//2407 -f 2344//2344 2407//2407 2343//2343 -f 2343//2343 2407//2407 2408//2408 -f 2343//2343 2408//2408 2342//2342 -f 2342//2342 2408//2408 2409//2409 -f 2342//2342 2409//2409 2394//2394 -f 2352//2352 2355//2355 2395//2395 -f 2395//2395 2355//2355 2356//2356 -f 2395//2395 2356//2356 2410//2410 -f 2410//2410 2356//2356 2411//2411 -f 2411//2411 2356//2356 2229//2229 -f 2411//2411 2229//2229 2412//2412 -f 2412//2412 2229//2229 2228//2228 -f 2412//2412 2228//2228 2413//2413 -f 2413//2413 2228//2228 2226//2226 -f 2413//2413 2226//2226 2414//2414 -f 2226//2226 2225//2225 2414//2414 -f 2414//2414 2225//2225 2358//2358 -f 2414//2414 2358//2358 2415//2415 -f 2415//2415 2358//2358 2416//2416 -f 2358//2358 2361//2361 2416//2416 -f 2416//2416 2361//2361 2368//2368 -f 2416//2416 2368//2368 2417//2417 -f 2417//2417 2368//2368 2418//2418 -f 2418//2418 2368//2368 2367//2367 -f 2418//2418 2367//2367 2419//2419 -f 2419//2419 2367//2367 2366//2366 -f 2419//2419 2366//2366 2420//2420 -f 2420//2420 2366//2366 2365//2365 -f 2420//2420 2365//2365 2421//2421 -f 2421//2421 2365//2365 2364//2364 -f 2421//2421 2364//2364 2422//2422 -f 2422//2422 2364//2364 2423//2423 -f 2423//2423 2364//2364 2363//2363 -f 2423//2423 2363//2363 2424//2424 -f 2424//2424 2363//2363 2362//2362 -f 2424//2424 2362//2362 2425//2425 -f 2425//2425 2362//2362 2223//2223 -f 2425//2425 2223//2223 2426//2426 -f 2426//2426 2223//2223 2222//2222 -f 2426//2426 2222//2222 2427//2427 -f 2427//2427 2222//2222 2370//2370 -f 2427//2427 2370//2370 2428//2428 -f 2370//2370 2374//2374 2428//2428 -f 2428//2428 2374//2374 2375//2375 -f 2428//2428 2375//2375 2429//2429 -f 2429//2429 2375//2375 2220//2220 -f 2429//2429 2220//2220 2430//2430 -f 2430//2430 2220//2220 2219//2219 -f 2430//2430 2219//2219 2431//2431 -f 2431//2431 2219//2219 2217//2217 -f 2431//2431 2217//2217 2432//2432 -f 2432//2432 2217//2217 2216//2216 -f 2432//2432 2216//2216 2433//2433 -f 2433//2433 2216//2216 2377//2377 -f 2433//2433 2377//2377 2434//2434 -f 2434//2434 2377//2377 2381//2381 -f 2434//2434 2381//2381 2435//2435 -f 2435//2435 2381//2381 2387//2387 -f 2435//2435 2387//2387 2436//2436 -f 2436//2436 2387//2387 2386//2386 -f 2436//2436 2386//2386 2437//2437 -f 2437//2437 2386//2386 2385//2385 -f 2437//2437 2385//2385 2438//2438 -f 2438//2438 2385//2385 2384//2384 -f 2438//2438 2384//2384 2439//2439 -f 2439//2439 2384//2384 2383//2383 -f 2439//2439 2383//2383 2440//2440 -f 2440//2440 2383//2383 2382//2382 -f 2440//2440 2382//2382 2441//2441 -f 2441//2441 2382//2382 2329//2329 -f 2441//2441 2329//2329 2442//2442 -f 2442//2442 2329//2329 2250//2250 -f 2442//2442 2250//2250 2443//2443 -f 2443//2443 2250//2250 2249//2249 -f 2443//2443 2249//2249 2444//2444 -f 2444//2444 2249//2249 2330//2330 -f 2444//2444 2330//2330 2445//2445 -f 2445//2445 2330//2330 2333//2333 -f 2445//2445 2333//2333 2446//2446 -f 2446//2446 2333//2333 2334//2334 -f 2446//2446 2334//2334 2447//2447 -f 2447//2447 2334//2334 2247//2247 -f 2447//2447 2247//2247 2448//2448 -f 2448//2448 2247//2247 2246//2246 -f 2448//2448 2246//2246 2449//2449 -f 2449//2449 2246//2246 2244//2244 -f 2449//2449 2244//2244 2388//2388 -f 2388//2388 2244//2244 2243//2243 -f 2388//2388 2243//2243 2336//2336 -f 2450//2450 2441//2441 2451//2451 -f 2451//2451 2441//2441 2442//2442 -f 2451//2451 2442//2442 2452//2452 -f 2442//2442 2443//2443 2452//2452 -f 2452//2452 2443//2443 2444//2444 -f 2452//2452 2444//2444 2453//2453 -f 2444//2444 2445//2445 2453//2453 -f 2453//2453 2445//2445 2446//2446 -f 2453//2453 2446//2446 2454//2454 -f 2454//2454 2446//2446 2447//2447 -f 2454//2454 2447//2447 2455//2455 -f 2447//2447 2448//2448 2455//2455 -f 2455//2455 2448//2448 2449//2449 -f 2455//2455 2449//2449 2456//2456 -f 2456//2456 2449//2449 2388//2388 -f 2456//2456 2388//2388 2457//2457 -f 2388//2388 2389//2389 2457//2457 -f 2457//2457 2389//2389 2390//2390 -f 2457//2457 2390//2390 2458//2458 -f 2458//2458 2390//2390 2391//2391 -f 2458//2458 2391//2391 2459//2459 -f 2391//2391 2392//2392 2459//2459 -f 2459//2459 2392//2392 2393//2393 -f 2459//2459 2393//2393 2460//2460 -f 2393//2393 2394//2394 2460//2460 -f 2460//2460 2394//2394 2409//2409 -f 2460//2460 2409//2409 2461//2461 -f 2461//2461 2409//2409 2408//2408 -f 2461//2461 2408//2408 2462//2462 -f 2408//2408 2407//2407 2462//2462 -f 2462//2462 2407//2407 2406//2406 -f 2462//2462 2406//2406 2463//2463 -f 2406//2406 2405//2405 2463//2463 -f 2463//2463 2405//2405 2404//2404 -f 2463//2463 2404//2404 2464//2464 -f 2404//2404 2403//2403 2464//2464 -f 2464//2464 2403//2403 2402//2402 -f 2464//2464 2402//2402 2465//2465 -f 2465//2465 2402//2402 2401//2401 -f 2465//2465 2401//2401 2466//2466 -f 2401//2401 2400//2400 2466//2466 -f 2466//2466 2400//2400 2399//2399 -f 2466//2466 2399//2399 2467//2467 -f 2399//2399 2398//2398 2467//2467 -f 2467//2467 2398//2398 2397//2397 -f 2467//2467 2397//2397 2468//2468 -f 2468//2468 2397//2397 2396//2396 -f 2468//2468 2396//2396 2469//2469 -f 2396//2396 2395//2395 2469//2469 -f 2469//2469 2395//2395 2410//2410 -f 2469//2469 2410//2410 2470//2470 -f 2410//2410 2411//2411 2470//2470 -f 2470//2470 2411//2411 2412//2412 -f 2470//2470 2412//2412 2471//2471 -f 2471//2471 2412//2412 2413//2413 -f 2471//2471 2413//2413 2472//2472 -f 2413//2413 2414//2414 2472//2472 -f 2472//2472 2414//2414 2415//2415 -f 2472//2472 2415//2415 2473//2473 -f 2415//2415 2416//2416 2473//2473 -f 2473//2473 2416//2416 2417//2417 -f 2473//2473 2417//2417 2474//2474 -f 2417//2417 2418//2418 2474//2474 -f 2474//2474 2418//2418 2419//2419 -f 2474//2474 2419//2419 2475//2475 -f 2475//2475 2419//2419 2420//2420 -f 2475//2475 2420//2420 2476//2476 -f 2420//2420 2421//2421 2476//2476 -f 2476//2476 2421//2421 2422//2422 -f 2476//2476 2422//2422 2477//2477 -f 2422//2422 2423//2423 2477//2477 -f 2477//2477 2423//2423 2424//2424 -f 2477//2477 2424//2424 2478//2478 -f 2478//2478 2424//2424 2425//2425 -f 2478//2478 2425//2425 2479//2479 -f 2425//2425 2426//2426 2479//2479 -f 2479//2479 2426//2426 2427//2427 -f 2479//2479 2427//2427 2480//2480 -f 2480//2480 2427//2427 2428//2428 -f 2480//2480 2428//2428 2481//2481 -f 2428//2428 2429//2429 2481//2481 -f 2481//2481 2429//2429 2430//2430 -f 2481//2481 2430//2430 2482//2482 -f 2482//2482 2430//2430 2431//2431 -f 2482//2482 2431//2431 2483//2483 -f 2431//2431 2432//2432 2483//2483 -f 2483//2483 2432//2432 2433//2433 -f 2483//2483 2433//2433 2484//2484 -f 2433//2433 2434//2434 2484//2484 -f 2484//2484 2434//2434 2435//2435 -f 2484//2484 2435//2435 2485//2485 -f 2485//2485 2435//2435 2436//2436 -f 2485//2485 2436//2436 2486//2486 -f 2436//2436 2437//2437 2486//2486 -f 2486//2486 2437//2437 2438//2438 -f 2486//2486 2438//2438 2487//2487 -f 2487//2487 2438//2438 2439//2439 -f 2487//2487 2439//2439 2450//2450 -f 2450//2450 2439//2439 2440//2440 -f 2450//2450 2440//2440 2441//2441 -f 2486//2486 2488//2488 2485//2485 -f 2485//2485 2488//2488 2489//2489 -f 2485//2485 2489//2489 2484//2484 -f 2484//2484 2489//2489 2490//2490 -f 2484//2484 2490//2490 2483//2483 -f 2483//2483 2490//2490 2491//2491 -f 2483//2483 2491//2491 2482//2482 -f 2482//2482 2491//2491 2492//2492 -f 2482//2482 2492//2492 2481//2481 -f 2481//2481 2492//2492 2493//2493 -f 2481//2481 2493//2493 2480//2480 -f 2480//2480 2493//2493 2494//2494 -f 2480//2480 2494//2494 2479//2479 -f 2479//2479 2494//2494 2495//2495 -f 2479//2479 2495//2495 2478//2478 -f 2478//2478 2495//2495 2496//2496 -f 2478//2478 2496//2496 2477//2477 -f 2477//2477 2496//2496 2497//2497 -f 2477//2477 2497//2497 2476//2476 -f 2476//2476 2497//2497 2498//2498 -f 2476//2476 2498//2498 2475//2475 -f 2475//2475 2498//2498 2499//2499 -f 2475//2475 2499//2499 2474//2474 -f 2474//2474 2499//2499 2500//2500 -f 2474//2474 2500//2500 2473//2473 -f 2473//2473 2500//2500 2501//2501 -f 2473//2473 2501//2501 2472//2472 -f 2472//2472 2501//2501 2502//2502 -f 2472//2472 2502//2502 2471//2471 -f 2471//2471 2502//2502 2503//2503 -f 2471//2471 2503//2503 2470//2470 -f 2470//2470 2503//2503 2504//2504 -f 2470//2470 2504//2504 2469//2469 -f 2469//2469 2504//2504 2505//2505 -f 2469//2469 2505//2505 2468//2468 -f 2468//2468 2505//2505 2506//2506 -f 2468//2468 2506//2506 2467//2467 -f 2467//2467 2506//2506 2507//2507 -f 2467//2467 2507//2507 2466//2466 -f 2466//2466 2507//2507 2508//2508 -f 2466//2466 2508//2508 2465//2465 -f 2465//2465 2508//2508 2509//2509 -f 2465//2465 2509//2509 2464//2464 -f 2464//2464 2509//2509 2510//2510 -f 2464//2464 2510//2510 2463//2463 -f 2463//2463 2510//2510 2511//2511 -f 2463//2463 2511//2511 2462//2462 -f 2462//2462 2511//2511 2512//2512 -f 2462//2462 2512//2512 2461//2461 -f 2461//2461 2512//2512 2513//2513 -f 2461//2461 2513//2513 2460//2460 -f 2460//2460 2513//2513 2514//2514 -f 2460//2460 2514//2514 2459//2459 -f 2459//2459 2514//2514 2515//2515 -f 2459//2459 2515//2515 2458//2458 -f 2458//2458 2515//2515 2516//2516 -f 2458//2458 2516//2516 2457//2457 -f 2457//2457 2516//2516 2517//2517 -f 2457//2457 2517//2517 2456//2456 -f 2456//2456 2517//2517 2518//2518 -f 2456//2456 2518//2518 2455//2455 -f 2455//2455 2518//2518 2519//2519 -f 2455//2455 2519//2519 2454//2454 -f 2454//2454 2519//2519 2520//2520 -f 2454//2454 2520//2520 2453//2453 -f 2453//2453 2520//2520 2521//2521 -f 2453//2453 2521//2521 2452//2452 -f 2452//2452 2521//2521 2522//2522 -f 2452//2452 2522//2522 2451//2451 -f 2451//2451 2522//2522 2523//2523 -f 2451//2451 2523//2523 2450//2450 -f 2450//2450 2523//2523 2524//2524 -f 2450//2450 2524//2524 2487//2487 -f 2487//2487 2524//2524 2525//2525 -f 2487//2487 2525//2525 2486//2486 -f 2486//2486 2525//2525 2488//2488 -f 2488//2488 2526//2526 2489//2489 -f 2489//2489 2526//2526 2527//2527 -f 2489//2489 2527//2527 2490//2490 -f 2490//2490 2527//2527 2528//2528 -f 2490//2490 2528//2528 2491//2491 -f 2491//2491 2528//2528 2529//2529 -f 2491//2491 2529//2529 2492//2492 -f 2492//2492 2529//2529 2530//2530 -f 2492//2492 2530//2530 2493//2493 -f 2493//2493 2530//2530 2531//2531 -f 2493//2493 2531//2531 2494//2494 -f 2494//2494 2531//2531 2532//2532 -f 2494//2494 2532//2532 2495//2495 -f 2495//2495 2532//2532 2533//2533 -f 2495//2495 2533//2533 2496//2496 -f 2496//2496 2533//2533 2534//2534 -f 2496//2496 2534//2534 2497//2497 -f 2497//2497 2534//2534 2535//2535 -f 2497//2497 2535//2535 2498//2498 -f 2498//2498 2535//2535 2536//2536 -f 2498//2498 2536//2536 2499//2499 -f 2499//2499 2536//2536 2537//2537 -f 2499//2499 2537//2537 2500//2500 -f 2500//2500 2537//2537 2538//2538 -f 2500//2500 2538//2538 2501//2501 -f 2501//2501 2538//2538 2539//2539 -f 2501//2501 2539//2539 2502//2502 -f 2502//2502 2539//2539 2540//2540 -f 2502//2502 2540//2540 2503//2503 -f 2503//2503 2540//2540 2541//2541 -f 2503//2503 2541//2541 2504//2504 -f 2504//2504 2541//2541 2542//2542 -f 2504//2504 2542//2542 2505//2505 -f 2505//2505 2542//2542 2543//2543 -f 2505//2505 2543//2543 2506//2506 -f 2506//2506 2543//2543 2544//2544 -f 2506//2506 2544//2544 2507//2507 -f 2507//2507 2544//2544 2545//2545 -f 2507//2507 2545//2545 2508//2508 -f 2508//2508 2545//2545 2546//2546 -f 2508//2508 2546//2546 2509//2509 -f 2509//2509 2546//2546 2547//2547 -f 2509//2509 2547//2547 2510//2510 -f 2510//2510 2547//2547 2548//2548 -f 2510//2510 2548//2548 2511//2511 -f 2511//2511 2548//2548 2549//2549 -f 2511//2511 2549//2549 2512//2512 -f 2512//2512 2549//2549 2550//2550 -f 2512//2512 2550//2550 2513//2513 -f 2513//2513 2550//2550 2551//2551 -f 2513//2513 2551//2551 2514//2514 -f 2514//2514 2551//2551 2552//2552 -f 2514//2514 2552//2552 2515//2515 -f 2515//2515 2552//2552 2553//2553 -f 2515//2515 2553//2553 2516//2516 -f 2516//2516 2553//2553 2554//2554 -f 2516//2516 2554//2554 2517//2517 -f 2517//2517 2554//2554 2555//2555 -f 2517//2517 2555//2555 2518//2518 -f 2518//2518 2555//2555 2556//2556 -f 2518//2518 2556//2556 2519//2519 -f 2519//2519 2556//2556 2557//2557 -f 2519//2519 2557//2557 2520//2520 -f 2520//2520 2557//2557 2558//2558 -f 2520//2520 2558//2558 2521//2521 -f 2521//2521 2558//2558 2559//2559 -f 2521//2521 2559//2559 2522//2522 -f 2522//2522 2559//2559 2560//2560 -f 2522//2522 2560//2560 2523//2523 -f 2523//2523 2560//2560 2561//2561 -f 2523//2523 2561//2561 2524//2524 -f 2524//2524 2561//2561 2562//2562 -f 2524//2524 2562//2562 2525//2525 -f 2525//2525 2562//2562 2563//2563 -f 2525//2525 2563//2563 2488//2488 -f 2488//2488 2563//2563 2526//2526 -f 2526//2526 2564//2564 2527//2527 -f 2527//2527 2564//2564 2565//2565 -f 2527//2527 2565//2565 2528//2528 -f 2528//2528 2565//2565 2566//2566 -f 2528//2528 2566//2566 2529//2529 -f 2529//2529 2566//2566 2567//2567 -f 2529//2529 2567//2567 2530//2530 -f 2530//2530 2567//2567 2568//2568 -f 2530//2530 2568//2568 2531//2531 -f 2531//2531 2568//2568 2569//2569 -f 2531//2531 2569//2569 2532//2532 -f 2532//2532 2569//2569 2570//2570 -f 2532//2532 2570//2570 2533//2533 -f 2533//2533 2570//2570 2571//2571 -f 2533//2533 2571//2571 2534//2534 -f 2534//2534 2571//2571 2572//2572 -f 2534//2534 2572//2572 2535//2535 -f 2535//2535 2572//2572 2573//2573 -f 2535//2535 2573//2573 2536//2536 -f 2536//2536 2573//2573 2574//2574 -f 2536//2536 2574//2574 2537//2537 -f 2537//2537 2574//2574 2575//2575 -f 2537//2537 2575//2575 2538//2538 -f 2538//2538 2575//2575 2576//2576 -f 2538//2538 2576//2576 2539//2539 -f 2539//2539 2576//2576 2577//2577 -f 2539//2539 2577//2577 2540//2540 -f 2540//2540 2577//2577 2578//2578 -f 2540//2540 2578//2578 2541//2541 -f 2541//2541 2578//2578 2579//2579 -f 2541//2541 2579//2579 2542//2542 -f 2542//2542 2579//2579 2580//2580 -f 2542//2542 2580//2580 2543//2543 -f 2543//2543 2580//2580 2581//2581 -f 2543//2543 2581//2581 2544//2544 -f 2544//2544 2581//2581 2582//2582 -f 2544//2544 2582//2582 2545//2545 -f 2545//2545 2582//2582 2583//2583 -f 2545//2545 2583//2583 2546//2546 -f 2546//2546 2583//2583 2584//2584 -f 2546//2546 2584//2584 2547//2547 -f 2547//2547 2584//2584 2585//2585 -f 2547//2547 2585//2585 2548//2548 -f 2548//2548 2585//2585 2586//2586 -f 2548//2548 2586//2586 2549//2549 -f 2549//2549 2586//2586 2587//2587 -f 2549//2549 2587//2587 2550//2550 -f 2550//2550 2587//2587 2588//2588 -f 2550//2550 2588//2588 2551//2551 -f 2551//2551 2588//2588 2589//2589 -f 2551//2551 2589//2589 2552//2552 -f 2552//2552 2589//2589 2590//2590 -f 2552//2552 2590//2590 2553//2553 -f 2553//2553 2590//2590 2591//2591 -f 2553//2553 2591//2591 2554//2554 -f 2554//2554 2591//2591 2592//2592 -f 2554//2554 2592//2592 2555//2555 -f 2555//2555 2592//2592 2593//2593 -f 2555//2555 2593//2593 2556//2556 -f 2556//2556 2593//2593 2594//2594 -f 2556//2556 2594//2594 2557//2557 -f 2557//2557 2594//2594 2595//2595 -f 2557//2557 2595//2595 2558//2558 -f 2558//2558 2595//2595 2596//2596 -f 2558//2558 2596//2596 2559//2559 -f 2559//2559 2596//2596 2597//2597 -f 2559//2559 2597//2597 2560//2560 -f 2560//2560 2597//2597 2598//2598 -f 2560//2560 2598//2598 2561//2561 -f 2561//2561 2598//2598 2599//2599 -f 2561//2561 2599//2599 2562//2562 -f 2562//2562 2599//2599 2600//2600 -f 2562//2562 2600//2600 2563//2563 -f 2563//2563 2600//2600 2601//2601 -f 2563//2563 2601//2601 2526//2526 -f 2526//2526 2601//2601 2564//2564 -f 2564//2564 2602//2602 2565//2565 -f 2565//2565 2602//2602 2603//2603 -f 2565//2565 2603//2603 2566//2566 -f 2566//2566 2603//2603 2604//2604 -f 2566//2566 2604//2604 2567//2567 -f 2567//2567 2604//2604 2605//2605 -f 2567//2567 2605//2605 2568//2568 -f 2568//2568 2605//2605 2606//2606 -f 2568//2568 2606//2606 2569//2569 -f 2569//2569 2606//2606 2607//2607 -f 2569//2569 2607//2607 2570//2570 -f 2570//2570 2607//2607 2608//2608 -f 2570//2570 2608//2608 2571//2571 -f 2571//2571 2608//2608 2609//2609 -f 2571//2571 2609//2609 2572//2572 -f 2572//2572 2609//2609 2610//2610 -f 2572//2572 2610//2610 2573//2573 -f 2573//2573 2610//2610 2611//2611 -f 2573//2573 2611//2611 2574//2574 -f 2574//2574 2611//2611 2612//2612 -f 2574//2574 2612//2612 2575//2575 -f 2575//2575 2612//2612 2613//2613 -f 2575//2575 2613//2613 2576//2576 -f 2576//2576 2613//2613 2614//2614 -f 2576//2576 2614//2614 2577//2577 -f 2577//2577 2614//2614 2615//2615 -f 2577//2577 2615//2615 2578//2578 -f 2578//2578 2615//2615 2616//2616 -f 2578//2578 2616//2616 2579//2579 -f 2579//2579 2616//2616 2617//2617 -f 2579//2579 2617//2617 2580//2580 -f 2580//2580 2617//2617 2618//2618 -f 2580//2580 2618//2618 2581//2581 -f 2581//2581 2618//2618 2619//2619 -f 2581//2581 2619//2619 2582//2582 -f 2582//2582 2619//2619 2620//2620 -f 2582//2582 2620//2620 2583//2583 -f 2583//2583 2620//2620 2621//2621 -f 2583//2583 2621//2621 2584//2584 -f 2584//2584 2621//2621 2622//2622 -f 2584//2584 2622//2622 2585//2585 -f 2585//2585 2622//2622 2623//2623 -f 2585//2585 2623//2623 2586//2586 -f 2586//2586 2623//2623 2624//2624 -f 2586//2586 2624//2624 2587//2587 -f 2587//2587 2624//2624 2625//2625 -f 2587//2587 2625//2625 2588//2588 -f 2588//2588 2625//2625 2626//2626 -f 2588//2588 2626//2626 2589//2589 -f 2589//2589 2626//2626 2627//2627 -f 2589//2589 2627//2627 2590//2590 -f 2590//2590 2627//2627 2628//2628 -f 2590//2590 2628//2628 2591//2591 -f 2591//2591 2628//2628 2629//2629 -f 2591//2591 2629//2629 2592//2592 -f 2592//2592 2629//2629 2630//2630 -f 2592//2592 2630//2630 2593//2593 -f 2593//2593 2630//2630 2631//2631 -f 2593//2593 2631//2631 2594//2594 -f 2594//2594 2631//2631 2632//2632 -f 2594//2594 2632//2632 2595//2595 -f 2595//2595 2632//2632 2633//2633 -f 2595//2595 2633//2633 2596//2596 -f 2596//2596 2633//2633 2634//2634 -f 2596//2596 2634//2634 2597//2597 -f 2597//2597 2634//2634 2635//2635 -f 2597//2597 2635//2635 2598//2598 -f 2598//2598 2635//2635 2636//2636 -f 2598//2598 2636//2636 2599//2599 -f 2599//2599 2636//2636 2637//2637 -f 2599//2599 2637//2637 2600//2600 -f 2600//2600 2637//2637 2638//2638 -f 2600//2600 2638//2638 2601//2601 -f 2601//2601 2638//2638 2639//2639 -f 2601//2601 2639//2639 2564//2564 -f 2564//2564 2639//2639 2602//2602 -f 2622//2622 2621//2621 2640//2640 -f 2640//2640 2621//2621 2641//2641 -f 2609//2609 2642//2642 2643//2643 -f 2613//2613 2644//2644 2614//2614 -f 2614//2614 2644//2644 2645//2645 -f 2614//2614 2645//2645 2615//2615 -f 2646//2646 2624//2624 2640//2640 -f 2640//2640 2624//2624 2623//2623 -f 2640//2640 2623//2623 2622//2622 -f 2647//2647 2626//2626 2646//2646 -f 2646//2646 2626//2626 2625//2625 -f 2646//2646 2625//2625 2624//2624 -f 2630//2630 2629//2629 2648//2648 -f 2648//2648 2629//2629 2628//2628 -f 2648//2648 2628//2628 2647//2647 -f 2647//2647 2628//2628 2627//2627 -f 2647//2647 2627//2627 2626//2626 -f 2630//2630 2648//2648 2631//2631 -f 2631//2631 2648//2648 2649//2649 -f 2631//2631 2649//2649 2632//2632 -f 2604//2604 2650//2650 2605//2605 -f 2605//2605 2650//2650 2651//2651 -f 2609//2609 2608//2608 2642//2642 -f 2642//2642 2608//2608 2607//2607 -f 2642//2642 2607//2607 2651//2651 -f 2651//2651 2607//2607 2606//2606 -f 2651//2651 2606//2606 2605//2605 -f 2613//2613 2612//2612 2644//2644 -f 2644//2644 2612//2612 2611//2611 -f 2644//2644 2611//2611 2643//2643 -f 2643//2643 2611//2611 2610//2610 -f 2643//2643 2610//2610 2609//2609 -f 2615//2615 2645//2645 2616//2616 -f 2616//2616 2645//2645 2652//2652 -f 2616//2616 2652//2652 2617//2617 -f 2621//2621 2620//2620 2641//2641 -f 2641//2641 2620//2620 2619//2619 -f 2641//2641 2619//2619 2652//2652 -f 2652//2652 2619//2619 2618//2618 -f 2652//2652 2618//2618 2617//2617 -f 2632//2632 2649//2649 2633//2633 -f 2633//2633 2649//2649 2653//2653 -f 2633//2633 2653//2653 2634//2634 -f 2604//2604 2603//2603 2650//2650 -f 2650//2650 2603//2603 2602//2602 -f 2650//2650 2602//2602 2654//2654 -f 2602//2602 2639//2639 2654//2654 -f 2654//2654 2639//2639 2638//2638 -f 2654//2654 2638//2638 2655//2655 -f 2638//2638 2637//2637 2655//2655 -f 2655//2655 2637//2637 2636//2636 -f 2655//2655 2636//2636 2653//2653 -f 2653//2653 2636//2636 2635//2635 -f 2653//2653 2635//2635 2634//2634 -f 2646//2646 2640//2640 2656//2656 -f 2656//2656 2657//2657 2646//2646 -f 2646//2646 2657//2657 2658//2658 -f 2646//2646 2658//2658 2647//2647 -f 2658//2658 2659//2659 2647//2647 -f 2647//2647 2659//2659 2660//2660 -f 2647//2647 2660//2660 2648//2648 -f 2660//2660 2661//2661 2648//2648 -f 2648//2648 2661//2661 2662//2662 -f 2648//2648 2662//2662 2649//2649 -f 2662//2662 2663//2663 2649//2649 -f 2649//2649 2663//2663 2664//2664 -f 2649//2649 2664//2664 2653//2653 -f 2664//2664 2665//2665 2653//2653 -f 2653//2653 2665//2665 2666//2666 -f 2653//2653 2666//2666 2655//2655 -f 2666//2666 2667//2667 2655//2655 -f 2655//2655 2667//2667 2668//2668 -f 2655//2655 2668//2668 2654//2654 -f 2654//2654 2668//2668 2669//2669 -f 2654//2654 2669//2669 2650//2650 -f 2669//2669 2670//2670 2650//2650 -f 2650//2650 2670//2670 2671//2671 -f 2650//2650 2671//2671 2651//2651 -f 2671//2671 2672//2672 2651//2651 -f 2651//2651 2672//2672 2673//2673 -f 2651//2651 2673//2673 2642//2642 -f 2673//2673 2674//2674 2642//2642 -f 2642//2642 2674//2674 2675//2675 -f 2642//2642 2675//2675 2643//2643 -f 2675//2675 2676//2676 2643//2643 -f 2643//2643 2676//2676 2677//2677 -f 2643//2643 2677//2677 2644//2644 -f 2677//2677 2678//2678 2644//2644 -f 2644//2644 2678//2678 2679//2679 -f 2644//2644 2679//2679 2645//2645 -f 2679//2679 2680//2680 2645//2645 -f 2645//2645 2680//2680 2681//2681 -f 2645//2645 2681//2681 2652//2652 -f 2681//2681 2682//2682 2652//2652 -f 2652//2652 2682//2682 2683//2683 -f 2652//2652 2683//2683 2641//2641 -f 2641//2641 2683//2683 2684//2684 -f 2641//2641 2684//2684 2640//2640 -f 2640//2640 2684//2684 2685//2685 -f 2640//2640 2685//2685 2656//2656 -f 2668//2668 2686//2686 2669//2669 -f 2669//2669 2686//2686 2687//2687 -f 2669//2669 2687//2687 2670//2670 -f 2670//2670 2687//2687 2688//2688 -f 2670//2670 2688//2688 2671//2671 -f 2671//2671 2688//2688 2689//2689 -f 2671//2671 2689//2689 2672//2672 -f 2672//2672 2689//2689 2690//2690 -f 2672//2672 2690//2690 2673//2673 -f 2673//2673 2690//2690 2691//2691 -f 2673//2673 2691//2691 2674//2674 -f 2674//2674 2691//2691 2692//2692 -f 2674//2674 2692//2692 2675//2675 -f 2675//2675 2692//2692 2693//2693 -f 2675//2675 2693//2693 2676//2676 -f 2676//2676 2693//2693 2694//2694 -f 2676//2676 2694//2694 2677//2677 -f 2677//2677 2694//2694 2695//2695 -f 2677//2677 2695//2695 2678//2678 -f 2678//2678 2695//2695 2696//2696 -f 2678//2678 2696//2696 2679//2679 -f 2679//2679 2696//2696 2697//2697 -f 2679//2679 2697//2697 2680//2680 -f 2680//2680 2697//2697 2698//2698 -f 2680//2680 2698//2698 2681//2681 -f 2681//2681 2698//2698 2699//2699 -f 2681//2681 2699//2699 2682//2682 -f 2682//2682 2699//2699 2700//2700 -f 2682//2682 2700//2700 2683//2683 -f 2683//2683 2700//2700 2701//2701 -f 2683//2683 2701//2701 2684//2684 -f 2684//2684 2701//2701 2702//2702 -f 2684//2684 2702//2702 2685//2685 -f 2685//2685 2702//2702 2703//2703 -f 2685//2685 2703//2703 2656//2656 -f 2656//2656 2703//2703 2704//2704 -f 2656//2656 2704//2704 2657//2657 -f 2657//2657 2704//2704 2705//2705 -f 2657//2657 2705//2705 2658//2658 -f 2658//2658 2705//2705 2706//2706 -f 2658//2658 2706//2706 2659//2659 -f 2659//2659 2706//2706 2707//2707 -f 2659//2659 2707//2707 2660//2660 -f 2660//2660 2707//2707 2708//2708 -f 2660//2660 2708//2708 2661//2661 -f 2661//2661 2708//2708 2709//2709 -f 2661//2661 2709//2709 2662//2662 -f 2662//2662 2709//2709 2710//2710 -f 2662//2662 2710//2710 2663//2663 -f 2663//2663 2710//2710 2711//2711 -f 2663//2663 2711//2711 2664//2664 -f 2664//2664 2711//2711 2712//2712 -f 2664//2664 2712//2712 2665//2665 -f 2665//2665 2712//2712 2713//2713 -f 2665//2665 2713//2713 2666//2666 -f 2666//2666 2713//2713 2714//2714 -f 2666//2666 2714//2714 2667//2667 -f 2667//2667 2714//2714 2715//2715 -f 2667//2667 2715//2715 2668//2668 -f 2668//2668 2715//2715 2686//2686 -f 2716//2716 2717//2717 2715//2715 -f 2715//2715 2714//2714 2716//2716 -f 2716//2716 2714//2714 2713//2713 -f 2716//2716 2713//2713 2718//2718 -f 2713//2713 2712//2712 2718//2718 -f 2718//2718 2712//2712 2711//2711 -f 2718//2718 2711//2711 2719//2719 -f 2711//2711 2710//2710 2719//2719 -f 2719//2719 2710//2710 2709//2709 -f 2719//2719 2709//2709 2720//2720 -f 2709//2709 2708//2708 2720//2720 -f 2720//2720 2708//2708 2707//2707 -f 2720//2720 2707//2707 2721//2721 -f 2707//2707 2706//2706 2721//2721 -f 2721//2721 2706//2706 2705//2705 -f 2721//2721 2705//2705 2722//2722 -f 2705//2705 2704//2704 2722//2722 -f 2722//2722 2704//2704 2703//2703 -f 2722//2722 2703//2703 2723//2723 -f 2723//2723 2703//2703 2702//2702 -f 2723//2723 2702//2702 2724//2724 -f 2702//2702 2701//2701 2724//2724 -f 2724//2724 2701//2701 2700//2700 -f 2724//2724 2700//2700 2725//2725 -f 2700//2700 2699//2699 2725//2725 -f 2725//2725 2699//2699 2698//2698 -f 2725//2725 2698//2698 2726//2726 -f 2698//2698 2697//2697 2726//2726 -f 2726//2726 2697//2697 2696//2696 -f 2726//2726 2696//2696 2727//2727 -f 2696//2696 2695//2695 2727//2727 -f 2727//2727 2695//2695 2694//2694 -f 2727//2727 2694//2694 2728//2728 -f 2694//2694 2693//2693 2728//2728 -f 2728//2728 2693//2693 2692//2692 -f 2728//2728 2692//2692 2729//2729 -f 2692//2692 2691//2691 2729//2729 -f 2729//2729 2691//2691 2690//2690 -f 2729//2729 2690//2690 2730//2730 -f 2690//2690 2689//2689 2730//2730 -f 2730//2730 2689//2689 2688//2688 -f 2730//2730 2688//2688 2731//2731 -f 2731//2731 2688//2688 2687//2687 -f 2731//2731 2687//2687 2717//2717 -f 2717//2717 2687//2687 2686//2686 -f 2717//2717 2686//2686 2715//2715 -f 2718//2718 2732//2732 2716//2716 -f 2716//2716 2732//2732 2733//2733 -f 2716//2716 2733//2733 2717//2717 -f 2717//2717 2733//2733 2734//2734 -f 2717//2717 2734//2734 2731//2731 -f 2731//2731 2734//2734 2735//2735 -f 2731//2731 2735//2735 2730//2730 -f 2722//2722 2736//2736 2721//2721 -f 2721//2721 2736//2736 2737//2737 -f 2721//2721 2737//2737 2720//2720 -f 2720//2720 2737//2737 2738//2738 -f 2720//2720 2738//2738 2719//2719 -f 2719//2719 2738//2738 2739//2739 -f 2719//2719 2739//2739 2718//2718 -f 2718//2718 2739//2739 2740//2740 -f 2718//2718 2740//2740 2732//2732 -f 2726//2726 2741//2741 2725//2725 -f 2725//2725 2741//2741 2742//2742 -f 2725//2725 2742//2742 2724//2724 -f 2724//2724 2742//2742 2743//2743 -f 2724//2724 2743//2743 2723//2723 -f 2723//2723 2743//2743 2744//2744 -f 2723//2723 2744//2744 2722//2722 -f 2722//2722 2744//2744 2745//2745 -f 2722//2722 2745//2745 2736//2736 -f 2735//2735 2746//2746 2730//2730 -f 2730//2730 2746//2746 2747//2747 -f 2730//2730 2747//2747 2729//2729 -f 2729//2729 2747//2747 2748//2748 -f 2729//2729 2748//2748 2728//2728 -f 2728//2728 2748//2748 2749//2749 -f 2728//2728 2749//2749 2727//2727 -f 2727//2727 2749//2749 2750//2750 -f 2727//2727 2750//2750 2726//2726 -f 2726//2726 2750//2750 2751//2751 -f 2726//2726 2751//2751 2741//2741 -f 2746//2746 2752//2752 2747//2747 -f 2747//2747 2752//2752 2753//2753 -f 2747//2747 2753//2753 2748//2748 -f 2748//2748 2753//2753 2754//2754 -f 2748//2748 2754//2754 2749//2749 -f 2749//2749 2754//2754 2755//2755 -f 2749//2749 2755//2755 2750//2750 -f 2750//2750 2755//2755 2756//2756 -f 2750//2750 2756//2756 2751//2751 -f 2751//2751 2756//2756 2757//2757 -f 2751//2751 2757//2757 2741//2741 -f 2741//2741 2757//2757 2758//2758 -f 2741//2741 2758//2758 2742//2742 -f 2742//2742 2758//2758 2759//2759 -f 2742//2742 2759//2759 2743//2743 -f 2743//2743 2759//2759 2760//2760 -f 2743//2743 2760//2760 2744//2744 -f 2744//2744 2760//2760 2761//2761 -f 2744//2744 2761//2761 2745//2745 -f 2745//2745 2761//2761 2762//2762 -f 2745//2745 2762//2762 2736//2736 -f 2736//2736 2762//2762 2763//2763 -f 2736//2736 2763//2763 2737//2737 -f 2737//2737 2763//2763 2764//2764 -f 2737//2737 2764//2764 2738//2738 -f 2738//2738 2764//2764 2765//2765 -f 2738//2738 2765//2765 2739//2739 -f 2739//2739 2765//2765 2766//2766 -f 2739//2739 2766//2766 2740//2740 -f 2740//2740 2766//2766 2767//2767 -f 2740//2740 2767//2767 2732//2732 -f 2732//2732 2767//2767 2768//2768 -f 2732//2732 2768//2768 2733//2733 -f 2733//2733 2768//2768 2769//2769 -f 2733//2733 2769//2769 2734//2734 -f 2734//2734 2769//2769 2770//2770 -f 2734//2734 2770//2770 2735//2735 -f 2735//2735 2770//2770 2771//2771 -f 2735//2735 2771//2771 2746//2746 -f 2746//2746 2771//2771 2752//2752 -f 2772//2772 2752//2752 2771//2771 -f 2772//2772 2773//2773 2752//2752 -f 2752//2752 2773//2773 2774//2774 -f 2752//2752 2774//2774 2753//2753 -f 2774//2774 2775//2775 2753//2753 -f 2753//2753 2775//2775 2776//2776 -f 2753//2753 2776//2776 2754//2754 -f 2776//2776 2777//2777 2754//2754 -f 2754//2754 2777//2777 2778//2778 -f 2754//2754 2778//2778 2755//2755 -f 2778//2778 2779//2779 2755//2755 -f 2755//2755 2779//2779 2780//2780 -f 2755//2755 2780//2780 2756//2756 -f 2780//2780 2781//2781 2756//2756 -f 2756//2756 2781//2781 2782//2782 -f 2756//2756 2782//2782 2757//2757 -f 2782//2782 2783//2783 2757//2757 -f 2757//2757 2783//2783 2784//2784 -f 2757//2757 2784//2784 2758//2758 -f 2784//2784 2785//2785 2758//2758 -f 2758//2758 2785//2785 2786//2786 -f 2758//2758 2786//2786 2759//2759 -f 2786//2786 2787//2787 2759//2759 -f 2759//2759 2787//2787 2788//2788 -f 2759//2759 2788//2788 2760//2760 -f 2788//2788 2789//2789 2760//2760 -f 2760//2760 2789//2789 2790//2790 -f 2760//2760 2790//2790 2761//2761 -f 2790//2790 2791//2791 2761//2761 -f 2761//2761 2791//2791 2792//2792 -f 2761//2761 2792//2792 2762//2762 -f 2792//2792 2793//2793 2762//2762 -f 2762//2762 2793//2793 2794//2794 -f 2762//2762 2794//2794 2763//2763 -f 2794//2794 2795//2795 2763//2763 -f 2763//2763 2795//2795 2796//2796 -f 2763//2763 2796//2796 2764//2764 -f 2796//2796 2797//2797 2764//2764 -f 2764//2764 2797//2797 2798//2798 -f 2764//2764 2798//2798 2765//2765 -f 2798//2798 2799//2799 2765//2765 -f 2765//2765 2799//2799 2800//2800 -f 2765//2765 2800//2800 2766//2766 -f 2800//2800 2801//2801 2766//2766 -f 2766//2766 2801//2801 2802//2802 -f 2766//2766 2802//2802 2767//2767 -f 2802//2802 2803//2803 2767//2767 -f 2767//2767 2803//2803 2804//2804 -f 2767//2767 2804//2804 2768//2768 -f 2804//2804 2805//2805 2768//2768 -f 2768//2768 2805//2805 2806//2806 -f 2768//2768 2806//2806 2769//2769 -f 2806//2806 2807//2807 2769//2769 -f 2769//2769 2807//2807 2808//2808 -f 2769//2769 2808//2808 2770//2770 -f 2808//2808 2809//2809 2770//2770 -f 2770//2770 2809//2809 2810//2810 -f 2770//2770 2810//2810 2771//2771 -f 2771//2771 2810//2810 2811//2811 -f 2771//2771 2811//2811 2772//2772 -f 2812//2812 2813//2813 2809//2809 -f 2809//2809 2808//2808 2812//2812 -f 2812//2812 2808//2808 2807//2807 -f 2812//2812 2807//2807 2814//2814 -f 2807//2807 2806//2806 2814//2814 -f 2814//2814 2806//2806 2805//2805 -f 2814//2814 2805//2805 2815//2815 -f 2805//2805 2804//2804 2815//2815 -f 2815//2815 2804//2804 2803//2803 -f 2815//2815 2803//2803 2816//2816 -f 2803//2803 2802//2802 2816//2816 -f 2816//2816 2802//2802 2801//2801 -f 2816//2816 2801//2801 2817//2817 -f 2801//2801 2800//2800 2817//2817 -f 2817//2817 2800//2800 2799//2799 -f 2817//2817 2799//2799 2818//2818 -f 2799//2799 2798//2798 2818//2818 -f 2818//2818 2798//2798 2797//2797 -f 2818//2818 2797//2797 2819//2819 -f 2797//2797 2796//2796 2819//2819 -f 2819//2819 2796//2796 2795//2795 -f 2819//2819 2795//2795 2820//2820 -f 2795//2795 2794//2794 2820//2820 -f 2820//2820 2794//2794 2793//2793 -f 2820//2820 2793//2793 2821//2821 -f 2821//2821 2793//2793 2792//2792 -f 2821//2821 2792//2792 2822//2822 -f 2792//2792 2791//2791 2822//2822 -f 2822//2822 2791//2791 2790//2790 -f 2822//2822 2790//2790 2823//2823 -f 2790//2790 2789//2789 2823//2823 -f 2823//2823 2789//2789 2788//2788 -f 2823//2823 2788//2788 2824//2824 -f 2788//2788 2787//2787 2824//2824 -f 2824//2824 2787//2787 2786//2786 -f 2824//2824 2786//2786 2825//2825 -f 2786//2786 2785//2785 2825//2825 -f 2825//2825 2785//2785 2784//2784 -f 2825//2825 2784//2784 2826//2826 -f 2784//2784 2783//2783 2826//2826 -f 2826//2826 2783//2783 2782//2782 -f 2826//2826 2782//2782 2827//2827 -f 2782//2782 2781//2781 2827//2827 -f 2827//2827 2781//2781 2780//2780 -f 2827//2827 2780//2780 2828//2828 -f 2780//2780 2779//2779 2828//2828 -f 2828//2828 2779//2779 2778//2778 -f 2828//2828 2778//2778 2829//2829 -f 2778//2778 2777//2777 2829//2829 -f 2829//2829 2777//2777 2776//2776 -f 2829//2829 2776//2776 2830//2830 -f 2776//2776 2775//2775 2830//2830 -f 2830//2830 2775//2775 2774//2774 -f 2830//2830 2774//2774 2831//2831 -f 2774//2774 2773//2773 2831//2831 -f 2831//2831 2773//2773 2772//2772 -f 2831//2831 2772//2772 2832//2832 -f 2832//2832 2772//2772 2811//2811 -f 2832//2832 2811//2811 2813//2813 -f 2813//2813 2811//2811 2810//2810 -f 2813//2813 2810//2810 2809//2809 -f 2814//2814 2833//2833 2812//2812 -f 2812//2812 2833//2833 2834//2834 -f 2812//2812 2834//2834 2813//2813 -f 2834//2834 2835//2835 2813//2813 -f 2813//2813 2835//2835 2836//2836 -f 2813//2813 2836//2836 2832//2832 -f 2818//2818 2837//2837 2817//2817 -f 2817//2817 2837//2837 2838//2838 -f 2817//2817 2838//2838 2816//2816 -f 2838//2838 2839//2839 2816//2816 -f 2816//2816 2839//2839 2840//2840 -f 2816//2816 2840//2840 2815//2815 -f 2815//2815 2840//2840 2841//2841 -f 2815//2815 2841//2841 2814//2814 -f 2814//2814 2841//2841 2842//2842 -f 2814//2814 2842//2842 2833//2833 -f 2820//2820 2843//2843 2819//2819 -f 2819//2819 2843//2843 2844//2844 -f 2819//2819 2844//2844 2818//2818 -f 2818//2818 2844//2844 2845//2845 -f 2818//2818 2845//2845 2837//2837 -f 2822//2822 2846//2846 2821//2821 -f 2821//2821 2846//2846 2847//2847 -f 2821//2821 2847//2847 2820//2820 -f 2820//2820 2847//2847 2848//2848 -f 2820//2820 2848//2848 2843//2843 -f 2828//2828 2849//2849 2827//2827 -f 2827//2827 2849//2849 2850//2850 -f 2827//2827 2850//2850 2826//2826 -f 2830//2830 2851//2851 2829//2829 -f 2829//2829 2851//2851 2852//2852 -f 2829//2829 2852//2852 2828//2828 -f 2828//2828 2852//2852 2853//2853 -f 2828//2828 2853//2853 2849//2849 -f 2836//2836 2854//2854 2832//2832 -f 2832//2832 2854//2854 2855//2855 -f 2832//2832 2855//2855 2831//2831 -f 2831//2831 2855//2855 2856//2856 -f 2831//2831 2856//2856 2830//2830 -f 2830//2830 2856//2856 2857//2857 -f 2830//2830 2857//2857 2851//2851 -f 2824//2824 2858//2858 2823//2823 -f 2823//2823 2858//2858 2859//2859 -f 2823//2823 2859//2859 2822//2822 -f 2822//2822 2859//2859 2860//2860 -f 2822//2822 2860//2860 2846//2846 -f 2850//2850 2861//2861 2826//2826 -f 2826//2826 2861//2861 2862//2862 -f 2826//2826 2862//2862 2825//2825 -f 2825//2825 2862//2862 2863//2863 -f 2825//2825 2863//2863 2824//2824 -f 2824//2824 2863//2863 2864//2864 -f 2824//2824 2864//2864 2858//2858 -f 2865//2865 2860//2860 2866//2866 -f 2866//2866 2860//2860 2859//2859 -f 2866//2866 2859//2859 2867//2867 -f 2867//2867 2859//2859 2858//2858 -f 2867//2867 2858//2858 2868//2868 -f 2868//2868 2858//2858 2864//2864 -f 2868//2868 2864//2864 2869//2869 -f 2869//2869 2864//2864 2863//2863 -f 2869//2869 2863//2863 2870//2870 -f 2870//2870 2863//2863 2862//2862 -f 2870//2870 2862//2862 2871//2871 -f 2871//2871 2862//2862 2861//2861 -f 2871//2871 2861//2861 2872//2872 -f 2872//2872 2861//2861 2850//2850 -f 2872//2872 2850//2850 2873//2873 -f 2873//2873 2850//2850 2849//2849 -f 2873//2873 2849//2849 2874//2874 -f 2874//2874 2849//2849 2853//2853 -f 2874//2874 2853//2853 2875//2875 -f 2875//2875 2853//2853 2852//2852 -f 2875//2875 2852//2852 2876//2876 -f 2876//2876 2852//2852 2851//2851 -f 2876//2876 2851//2851 2877//2877 -f 2877//2877 2851//2851 2857//2857 -f 2877//2877 2857//2857 2878//2878 -f 2878//2878 2857//2857 2856//2856 -f 2878//2878 2856//2856 2879//2879 -f 2879//2879 2856//2856 2855//2855 -f 2879//2879 2855//2855 2880//2880 -f 2880//2880 2855//2855 2854//2854 -f 2880//2880 2854//2854 2881//2881 -f 2881//2881 2854//2854 2836//2836 -f 2881//2881 2836//2836 2882//2882 -f 2882//2882 2836//2836 2835//2835 -f 2882//2882 2835//2835 2883//2883 -f 2883//2883 2835//2835 2834//2834 -f 2883//2883 2834//2834 2884//2884 -f 2884//2884 2834//2834 2833//2833 -f 2884//2884 2833//2833 2885//2885 -f 2885//2885 2833//2833 2842//2842 -f 2885//2885 2842//2842 2886//2886 -f 2886//2886 2842//2842 2841//2841 -f 2886//2886 2841//2841 2887//2887 -f 2887//2887 2841//2841 2840//2840 -f 2887//2887 2840//2840 2888//2888 -f 2888//2888 2840//2840 2839//2839 -f 2888//2888 2839//2839 2889//2889 -f 2889//2889 2839//2839 2838//2838 -f 2889//2889 2838//2838 2890//2890 -f 2890//2890 2838//2838 2837//2837 -f 2890//2890 2837//2837 2891//2891 -f 2891//2891 2837//2837 2845//2845 -f 2891//2891 2845//2845 2892//2892 -f 2892//2892 2845//2845 2844//2844 -f 2892//2892 2844//2844 2893//2893 -f 2893//2893 2844//2844 2843//2843 -f 2893//2893 2843//2843 2894//2894 -f 2894//2894 2843//2843 2848//2848 -f 2894//2894 2848//2848 2895//2895 -f 2895//2895 2848//2848 2847//2847 -f 2895//2895 2847//2847 2896//2896 -f 2896//2896 2847//2847 2846//2846 -f 2896//2896 2846//2846 2865//2865 -f 2865//2865 2846//2846 2860//2860 -f 127//127 2881//2881 2882//2882 -f 2883//2883 123//123 2882//2882 -f 2882//2882 123//123 125//125 -f 2882//2882 125//125 127//127 -f 2884//2884 119//119 2883//2883 -f 2883//2883 119//119 121//121 -f 2883//2883 121//121 123//123 -f 2885//2885 115//115 2884//2884 -f 2884//2884 115//115 117//117 -f 2884//2884 117//117 119//119 -f 2886//2886 111//111 2885//2885 -f 2885//2885 111//111 113//113 -f 2885//2885 113//113 115//115 -f 2887//2887 107//107 2886//2886 -f 2886//2886 107//107 109//109 -f 2886//2886 109//109 111//111 -f 2888//2888 103//103 2887//2887 -f 2887//2887 103//103 105//105 -f 2887//2887 105//105 107//107 -f 2889//2889 99//99 2888//2888 -f 2888//2888 99//99 101//101 -f 2888//2888 101//101 103//103 -f 2890//2890 95//95 2889//2889 -f 2889//2889 95//95 97//97 -f 2889//2889 97//97 99//99 -f 2891//2891 91//91 2890//2890 -f 2890//2890 91//91 93//93 -f 2890//2890 93//93 95//95 -f 2892//2892 87//87 2891//2891 -f 2891//2891 87//87 89//89 -f 2891//2891 89//89 91//91 -f 2893//2893 83//83 2892//2892 -f 2892//2892 83//83 85//85 -f 2892//2892 85//85 87//87 -f 2894//2894 79//79 2893//2893 -f 2893//2893 79//79 81//81 -f 2893//2893 81//81 83//83 -f 2895//2895 75//75 2894//2894 -f 2894//2894 75//75 77//77 -f 2894//2894 77//77 79//79 -f 2896//2896 71//71 2895//2895 -f 2895//2895 71//71 73//73 -f 2895//2895 73//73 75//75 -f 2865//2865 67//67 2896//2896 -f 2896//2896 67//67 69//69 -f 2896//2896 69//69 71//71 -f 2866//2866 63//63 2865//2865 -f 2865//2865 63//63 65//65 -f 2865//2865 65//65 67//67 -f 2867//2867 59//59 2866//2866 -f 2866//2866 59//59 61//61 -f 2866//2866 61//61 63//63 -f 2868//2868 55//55 2867//2867 -f 2867//2867 55//55 57//57 -f 2867//2867 57//57 59//59 -f 2869//2869 51//51 2868//2868 -f 2868//2868 51//51 53//53 -f 2868//2868 53//53 55//55 -f 2870//2870 47//47 2869//2869 -f 2869//2869 47//47 49//49 -f 2869//2869 49//49 51//51 -f 2871//2871 43//43 2870//2870 -f 2870//2870 43//43 45//45 -f 2870//2870 45//45 47//47 -f 2872//2872 39//39 2871//2871 -f 2871//2871 39//39 41//41 -f 2871//2871 41//41 43//43 -f 2873//2873 35//35 2872//2872 -f 2872//2872 35//35 37//37 -f 2872//2872 37//37 39//39 -f 2874//2874 31//31 2873//2873 -f 2873//2873 31//31 33//33 -f 2873//2873 33//33 35//35 -f 2875//2875 27//27 2874//2874 -f 2874//2874 27//27 29//29 -f 2874//2874 29//29 31//31 -f 2876//2876 23//23 2875//2875 -f 2875//2875 23//23 25//25 -f 2875//2875 25//25 27//27 -f 2877//2877 19//19 2876//2876 -f 2876//2876 19//19 21//21 -f 2876//2876 21//21 23//23 -f 2878//2878 15//15 2877//2877 -f 2877//2877 15//15 17//17 -f 2877//2877 17//17 19//19 -f 2879//2879 11//11 2878//2878 -f 2878//2878 11//11 13//13 -f 2878//2878 13//13 15//15 -f 2880//2880 7//7 2879//2879 -f 2879//2879 7//7 9//9 -f 2879//2879 9//9 11//11 -f 127//127 1//1 2881//2881 -f 2881//2881 1//1 3//3 -f 2881//2881 3//3 2880//2880 -f 2880//2880 3//3 5//5 -f 2880//2880 5//5 7//7 -# 5792 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper.obj deleted file mode 100644 index f107f94e9..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper.obj +++ /dev/null @@ -1,1576 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object gripper.obj -# -# Vertices: 380 -# Faces: 800 -# -#### -vn 0.680956 0.548153 -0.485621 -v 0.054603 0.078631 0.171353 -vn 0.680956 0.648441 -0.340327 -v 0.054603 0.080275 0.173734 -vn 0.750899 -0.444920 0.488055 -v 0.054603 0.073119 0.175504 -vn 0.770261 0.637729 0.000000 -v 0.054603 0.060399 0.179310 -vn 0.770261 0.552291 -0.318862 -v 0.054603 0.060567 0.179935 -vn 0.693766 -0.718887 -0.043485 -v 0.054603 0.057649 0.179310 -vn 0.750899 0.527024 -0.397991 -v 0.054603 0.065539 0.182414 -vn 0.750898 0.347665 -0.561499 -v 0.054603 0.066938 0.183689 -vn 0.770261 -0.552291 -0.318862 -v 0.054603 0.062732 0.179935 -vn 0.669352 -0.737701 -0.088123 -v 0.054603 0.057649 0.222310 -vn 0.770265 -0.318861 -0.552287 -v 0.054603 0.070274 0.188393 -vn 0.770261 -0.552291 -0.318862 -v 0.054603 0.070732 0.187935 -vn 0.991445 0.000000 -0.130528 -v 0.054603 0.072849 0.222310 -vn 0.770261 -0.637728 -0.000000 -v 0.054603 0.070899 0.187310 -vn 0.728477 -0.447348 -0.518845 -v 0.054603 0.072903 0.183302 -vn 0.770263 -0.552286 0.318865 -v 0.054603 0.070732 0.186685 -vn 0.736219 -0.321097 -0.595717 -v 0.054603 0.072360 0.183689 -vn 0.770260 -0.318866 0.552291 -v 0.054603 0.070274 0.186228 -vn 0.770263 0.552286 0.318865 -v 0.054603 0.060567 0.178685 -vn 0.692178 -0.708929 -0.135314 -v 0.054603 0.057998 0.176439 -vn 0.770260 0.318865 0.552291 -v 0.054603 0.061024 0.178228 -vn 0.693767 -0.684364 -0.224353 -v 0.054603 0.058087 0.176097 -vn 0.770264 -0.000000 0.637725 -v 0.054603 0.061649 0.178060 -vn 0.770263 0.552286 0.318865 -v 0.054603 0.068567 0.186685 -vn 0.770258 0.000000 -0.637732 -v 0.054603 0.061649 0.180560 -vn 0.770265 -0.318861 -0.552287 -v 0.054603 0.062274 0.180393 -vn 0.770261 0.637729 0.000000 -v 0.054603 0.068399 0.187310 -vn 0.770265 0.318861 -0.552286 -v 0.054603 0.061024 0.180393 -vn 0.770261 0.552291 -0.318862 -v 0.054603 0.068567 0.187935 -vn 0.770265 0.318861 -0.552286 -v 0.054603 0.069024 0.188393 -vn 0.770258 0.000000 -0.637732 -v 0.054603 0.069649 0.188560 -vn 0.770260 -0.318866 0.552291 -v 0.054603 0.062274 0.178228 -vn 0.728477 0.539108 0.422710 -v 0.054603 0.065655 0.176060 -vn 0.770263 -0.552286 0.318865 -v 0.054603 0.062732 0.178685 -vn 0.741775 0.611020 0.276450 -v 0.054603 0.065039 0.177015 -vn 0.770261 -0.637728 -0.000000 -v 0.054603 0.062899 0.179310 -vn 0.750899 0.657600 0.060936 -v 0.054603 0.064521 0.178835 -vn 0.750899 0.635206 -0.180731 -v 0.054603 0.064696 0.180720 -vn 0.770260 0.318865 0.552291 -v 0.054603 0.069024 0.186228 -vn 0.739566 0.154105 -0.655206 -v 0.054603 0.068703 0.184373 -vn 0.770264 -0.000000 0.637725 -v 0.054603 0.069649 0.186060 -vn 0.728478 -0.000000 -0.685069 -v 0.054603 0.069649 0.184460 -vn 0.739565 -0.154105 -0.655206 -v 0.054603 0.070595 0.184373 -vn 0.770261 -0.552291 -0.318862 -v 0.054603 0.070732 0.171935 -vn 0.770261 -0.637728 -0.000000 -v 0.054603 0.070899 0.171310 -vn 0.680956 0.259685 -0.684735 -v 0.054603 0.073904 0.168090 -vn 0.770263 -0.552286 0.318865 -v 0.054603 0.070732 0.170685 -vn 0.680957 0.088272 -0.726984 -v 0.054603 0.071096 0.167398 -vn 0.770260 -0.318866 0.552291 -v 0.054603 0.070274 0.170228 -vn 0.770264 -0.000000 0.637725 -v 0.054603 0.069649 0.170060 -vn 0.680956 -0.088271 -0.726985 -v 0.054603 0.068203 0.167398 -vn 0.770260 0.318865 0.552291 -v 0.054603 0.069024 0.170228 -vn 0.680956 -0.259685 -0.684735 -v 0.054603 0.065394 0.168090 -vn 0.770263 0.552286 0.318865 -v 0.054603 0.068567 0.170685 -vn 0.680956 -0.416006 -0.602692 -v 0.054603 0.062832 0.169435 -vn 0.770261 0.637728 0.000000 -v 0.054603 0.068399 0.171310 -vn 0.680956 -0.548153 -0.485621 -v 0.054603 0.060667 0.171353 -vn 0.682487 -0.644663 -0.344415 -v 0.054603 0.059024 0.173734 -vn 0.770261 0.552291 -0.318862 -v 0.054603 0.068567 0.171935 -vn 0.770265 -0.318861 -0.552287 -v 0.054603 0.070274 0.172393 -vn 0.750899 -0.238569 0.615821 -v 0.054603 0.071510 0.174508 -vn 0.770258 0.000000 -0.637732 -v 0.054603 0.069649 0.172560 -vn 0.750898 -0.000000 0.660418 -v 0.054603 0.069649 0.174160 -vn 0.770265 0.318861 -0.552286 -v 0.054603 0.069024 0.172393 -vn 0.750899 0.238569 0.615821 -v 0.054603 0.067789 0.174508 -vn 0.737366 0.426798 0.523579 -v 0.054603 0.066180 0.175504 -vn 0.680956 0.416007 -0.602691 -v 0.054603 0.076466 0.169435 -vn 0.770265 0.318861 -0.552286 -v 0.054603 0.077024 0.180393 -vn 0.770258 0.000000 -0.637732 -v 0.054603 0.077649 0.180560 -vn 0.669352 0.737701 -0.088123 -v 0.054603 0.081649 0.222310 -vn 0.770265 -0.318861 -0.552287 -v 0.054603 0.078274 0.180393 -vn 0.693766 0.718887 -0.043485 -v 0.054603 0.081649 0.179310 -vn 0.770261 -0.552291 -0.318862 -v 0.054603 0.078732 0.179935 -vn 0.770261 -0.637728 -0.000000 -v 0.054603 0.078899 0.179310 -vn 0.680957 0.711044 -0.175257 -v 0.054603 0.081300 0.176439 -vn 0.770263 -0.552286 0.318865 -v 0.054603 0.078732 0.178685 -vn 0.742934 -0.546940 -0.385884 -v 0.054603 0.073759 0.182414 -vn 0.770260 -0.318866 0.552291 -v 0.054603 0.078274 0.178228 -vn 0.770264 -0.000000 0.637725 -v 0.054603 0.077649 0.178060 -vn 0.770260 0.318865 0.552291 -v 0.054603 0.077024 0.178228 -vn 0.750899 -0.591181 0.294374 -v 0.054603 0.074259 0.177015 -vn 0.770263 0.552286 0.318865 -v 0.054603 0.076567 0.178685 -vn 0.750899 -0.657600 0.060935 -v 0.054603 0.074777 0.178835 -vn 0.770261 0.637729 0.000000 -v 0.054603 0.076399 0.179310 -vn 0.750899 -0.635206 -0.180733 -v 0.054603 0.074603 0.180720 -vn 0.770261 0.552291 -0.318862 -v 0.054603 0.076567 0.179935 -vn -0.680956 0.416007 -0.602691 -v 0.050603 0.076466 0.169435 -vn -0.680956 0.259685 -0.684735 -v 0.050603 0.073904 0.168090 -vn -0.750899 -0.444920 0.488055 -v 0.050603 0.073119 0.175504 -vn -0.770261 -0.637729 -0.000000 -v 0.050603 0.070899 0.187310 -vn -0.770261 -0.552291 -0.318862 -v 0.050603 0.070732 0.187935 -vn -0.991445 -0.000000 0.130526 -v 0.050603 0.072849 0.227310 -vn -0.770263 -0.552286 0.318865 -v 0.050603 0.070732 0.186685 -vn -0.728477 -0.447348 -0.518845 -v 0.050603 0.072903 0.183302 -vn -0.736219 -0.321097 -0.595717 -v 0.050603 0.072360 0.183689 -vn -0.770265 -0.318861 -0.552286 -v 0.050603 0.070274 0.188393 -vn -0.770258 0.000000 -0.637732 -v 0.050603 0.069649 0.188560 -vn -0.727973 -0.678874 0.095839 -v 0.050603 0.057649 0.227310 -vn -0.770264 0.318861 -0.552287 -v 0.050603 0.069024 0.188393 -vn -0.770261 0.552291 -0.318861 -v 0.050603 0.068567 0.187935 -vn -0.693766 -0.718887 -0.043485 -v 0.050603 0.057649 0.179310 -vn -0.770261 0.637728 0.000000 -v 0.050603 0.068399 0.187310 -vn -0.770263 0.552286 0.318865 -v 0.050603 0.068567 0.186685 -vn -0.770264 0.318861 -0.552287 -v 0.050603 0.061024 0.180393 -vn -0.770258 0.000000 -0.637732 -v 0.050603 0.061649 0.180560 -vn -0.770261 0.552291 -0.318861 -v 0.050603 0.060567 0.179935 -vn -0.770261 0.637728 0.000000 -v 0.050603 0.060399 0.179310 -vn -0.692178 -0.708929 -0.135314 -v 0.050603 0.057998 0.176439 -vn -0.770263 0.552286 0.318865 -v 0.050603 0.060567 0.178685 -vn -0.693767 -0.684364 -0.224353 -v 0.050603 0.058087 0.176097 -vn -0.770260 0.318865 0.552291 -v 0.050603 0.061024 0.178228 -vn -0.770264 -0.000000 0.637725 -v 0.050603 0.061649 0.178060 -vn -0.728477 0.539108 0.422710 -v 0.050603 0.065655 0.176060 -vn -0.770260 -0.318866 0.552291 -v 0.050603 0.062274 0.178228 -vn -0.741775 0.611020 0.276450 -v 0.050603 0.065039 0.177015 -vn -0.770263 -0.552286 0.318865 -v 0.050603 0.062732 0.178685 -vn -0.750899 0.657600 0.060936 -v 0.050603 0.064521 0.178835 -vn -0.770261 -0.637729 -0.000000 -v 0.050603 0.062899 0.179310 -vn -0.750899 0.635206 -0.180731 -v 0.050603 0.064696 0.180720 -vn -0.770261 -0.552291 -0.318862 -v 0.050603 0.062732 0.179935 -vn -0.770260 0.318865 0.552291 -v 0.050603 0.069024 0.186228 -vn -0.750898 0.347665 -0.561499 -v 0.050603 0.066938 0.183689 -vn -0.770260 -0.318866 0.552291 -v 0.050603 0.070274 0.186228 -vn -0.739565 -0.154105 -0.655206 -v 0.050603 0.070595 0.184373 -vn -0.770264 -0.000000 0.637725 -v 0.050603 0.069649 0.186060 -vn -0.728478 -0.000000 -0.685070 -v 0.050603 0.069649 0.184460 -vn -0.739566 0.154105 -0.655206 -v 0.050603 0.068703 0.184373 -vn -0.770265 -0.318861 -0.552286 -v 0.050603 0.062274 0.180393 -vn -0.750899 0.527024 -0.397991 -v 0.050603 0.065539 0.182414 -vn -0.770260 0.318865 0.552291 -v 0.050603 0.077024 0.178228 -vn -0.770264 -0.000000 0.637725 -v 0.050603 0.077649 0.178060 -vn -0.680956 0.648441 -0.340327 -v 0.050603 0.080275 0.173734 -vn -0.770260 -0.318866 0.552291 -v 0.050603 0.078274 0.178228 -vn -0.680957 0.711044 -0.175257 -v 0.050603 0.081300 0.176439 -vn -0.770263 -0.552286 0.318865 -v 0.050603 0.078732 0.178685 -vn -0.693766 0.718887 -0.043485 -v 0.050603 0.081649 0.179310 -vn -0.770261 -0.637729 -0.000000 -v 0.050603 0.078899 0.179310 -vn -0.770261 -0.552291 -0.318862 -v 0.050603 0.078732 0.179935 -vn -0.727971 0.678876 0.095839 -v 0.050603 0.081649 0.227310 -vn -0.770265 -0.318861 -0.552286 -v 0.050603 0.078274 0.180393 -vn -0.750899 -0.591181 0.294374 -v 0.050603 0.074259 0.177015 -vn -0.750899 -0.657600 0.060935 -v 0.050603 0.074777 0.178835 -vn -0.770261 0.637728 0.000000 -v 0.050603 0.076399 0.179310 -vn -0.770261 0.552291 -0.318861 -v 0.050603 0.076567 0.179935 -vn -0.750899 -0.635206 -0.180733 -v 0.050603 0.074603 0.180720 -vn -0.770265 0.318861 -0.552286 -v 0.050603 0.077024 0.180393 -vn -0.742934 -0.546940 -0.385884 -v 0.050603 0.073759 0.182414 -vn -0.770263 0.552286 0.318865 -v 0.050603 0.076567 0.178685 -vn -0.770258 0.000000 -0.637732 -v 0.050603 0.077649 0.180560 -vn -0.680956 0.548153 -0.485621 -v 0.050603 0.078631 0.171353 -vn -0.680956 0.088272 -0.726985 -v 0.050603 0.071096 0.167398 -vn -0.770264 -0.000000 0.637725 -v 0.050603 0.069649 0.170060 -vn -0.770260 -0.318866 0.552291 -v 0.050603 0.070274 0.170228 -vn -0.770260 0.318865 0.552291 -v 0.050603 0.069024 0.170228 -vn -0.680956 -0.088271 -0.726984 -v 0.050603 0.068203 0.167398 -vn -0.770263 0.552286 0.318865 -v 0.050603 0.068567 0.170685 -vn -0.737366 0.426798 0.523579 -v 0.050603 0.066180 0.175504 -vn -0.680956 -0.259685 -0.684735 -v 0.050603 0.065394 0.168090 -vn -0.680956 -0.416006 -0.602692 -v 0.050603 0.062832 0.169435 -vn -0.770261 0.637728 0.000000 -v 0.050603 0.068399 0.171310 -vn -0.680956 -0.548153 -0.485621 -v 0.050603 0.060667 0.171353 -vn -0.770261 0.552291 -0.318861 -v 0.050603 0.068567 0.171935 -vn -0.682487 -0.644663 -0.344415 -v 0.050603 0.059024 0.173734 -vn -0.770263 -0.552286 0.318865 -v 0.050603 0.070732 0.170685 -vn -0.770261 -0.637728 -0.000000 -v 0.050603 0.070899 0.171310 -vn -0.770261 -0.552291 -0.318862 -v 0.050603 0.070732 0.171935 -vn -0.750899 -0.238569 0.615821 -v 0.050603 0.071510 0.174508 -vn -0.770265 -0.318861 -0.552286 -v 0.050603 0.070274 0.172393 -vn -0.750898 -0.000000 0.660418 -v 0.050603 0.069649 0.174160 -vn -0.770258 0.000000 -0.637732 -v 0.050603 0.069649 0.172560 -vn -0.750899 0.238569 0.615821 -v 0.050603 0.067789 0.174508 -vn -0.770264 0.318861 -0.552287 -v 0.050603 0.069024 0.172393 -vn 0.727973 0.678874 0.095841 -v 0.098603 0.081649 0.227310 -vn 0.693766 0.718887 -0.043485 -v 0.098603 0.081649 0.179310 -vn -0.693766 0.718887 -0.043485 -v 0.094603 0.081649 0.179310 -vn 0.378582 0.653227 0.655721 -v 0.097603 0.081649 0.229042 -vn 0.655721 0.653227 0.378582 -v 0.098335 0.081649 0.228310 -vn -0.378581 0.653227 0.655721 -v 0.051603 0.081649 0.229042 -vn -0.095841 0.678874 0.727973 -v 0.052603 0.081649 0.229310 -vn -0.655722 0.653226 0.378582 -v 0.050871 0.081649 0.228310 -vn 0.318865 0.770261 -0.552289 -v 0.055603 0.081649 0.224042 -vn 0.552288 0.770262 -0.318865 -v 0.054871 0.081649 0.223310 -vn 0.095840 0.678874 0.727973 -v 0.096603 0.081649 0.229310 -vn -0.552288 0.770261 -0.318866 -v 0.094335 0.081649 0.223310 -vn -0.669352 0.737701 -0.088124 -v 0.094603 0.081649 0.222310 -vn -0.318865 0.770261 -0.552288 -v 0.093603 0.081649 0.224042 -vn -0.088123 0.737701 -0.669352 -v 0.092603 0.081649 0.224310 -vn 0.088123 0.737701 -0.669352 -v 0.056603 0.081649 0.224310 -vn -0.095841 -0.678874 0.727973 -v 0.052603 0.057649 0.229310 -vn 0.544705 -0.000000 0.838628 -v 0.069811 0.069649 0.229310 -vn 0.272352 -0.471728 0.838628 -v 0.072207 0.073799 0.229310 -vn -0.272352 -0.471728 0.838628 -v 0.076999 0.073799 0.229310 -vn -0.544705 -0.000000 0.838628 -v 0.079395 0.069649 0.229310 -vn 0.095840 -0.678874 0.727973 -v 0.096603 0.057649 0.229310 -vn -0.272352 0.471728 0.838628 -v 0.076999 0.065499 0.229310 -vn 0.272352 0.471728 0.838628 -v 0.072207 0.065499 0.229310 -vn -0.693766 -0.718887 -0.043485 -v 0.094603 0.057649 0.179310 -vn 0.693766 -0.718886 -0.043485 -v 0.098603 0.057649 0.179310 -vn -0.669351 -0.737701 -0.088124 -v 0.094603 0.057649 0.222310 -vn 0.727971 -0.678876 0.095841 -v 0.098603 0.057649 0.227310 -vn -0.552288 -0.770261 -0.318866 -v 0.094335 0.057649 0.223310 -vn 0.552288 -0.770262 -0.318866 -v 0.054871 0.057649 0.223310 -vn -0.655722 -0.653227 0.378582 -v 0.050871 0.057649 0.228310 -vn 0.318865 -0.770261 -0.552289 -v 0.055603 0.057649 0.224042 -vn -0.378581 -0.653227 0.655721 -v 0.051603 0.057649 0.229042 -vn -0.318865 -0.770262 -0.552288 -v 0.093603 0.057649 0.224042 -vn 0.378582 -0.653227 0.655721 -v 0.097603 0.057649 0.229042 -vn 0.655721 -0.653227 0.378582 -v 0.098335 0.057649 0.228310 -vn 0.088123 -0.737701 -0.669352 -v 0.056603 0.057649 0.224310 -vn -0.088123 -0.737701 -0.669352 -v 0.092603 0.057649 0.224310 -vn -0.544705 -0.000000 -0.838628 -v 0.079395 0.069649 0.224310 -vn -0.272352 -0.471728 -0.838628 -v 0.076999 0.073799 0.224310 -vn 0.272352 -0.471728 -0.838628 -v 0.072207 0.073799 0.224310 -vn 0.544705 -0.000000 -0.838628 -v 0.069811 0.069649 0.224310 -vn 0.272352 0.471728 -0.838628 -v 0.072207 0.065499 0.224310 -vn -0.272352 0.471728 -0.838628 -v 0.076999 0.065499 0.224310 -vn -0.991444 -0.000000 -0.130529 -v 0.094603 0.066449 0.222310 -vn -0.728477 0.447348 -0.518847 -v 0.094603 0.066395 0.183302 -vn -0.742934 0.546938 -0.385884 -v 0.094603 0.065539 0.182414 -vn -0.770265 -0.318861 -0.552286 -v 0.094603 0.062274 0.180393 -vn -0.770258 0.000000 -0.637732 -v 0.094603 0.061649 0.180560 -vn -0.770264 0.318861 -0.552287 -v 0.094603 0.061024 0.180393 -vn -0.770261 0.552291 -0.318861 -v 0.094603 0.060567 0.179935 -vn -0.770261 0.637728 0.000000 -v 0.094603 0.060399 0.179310 -vn -0.680956 -0.711044 -0.175257 -v 0.094603 0.057998 0.176439 -vn -0.770263 0.552286 0.318865 -v 0.094603 0.060567 0.178685 -vn -0.680956 -0.648441 -0.340328 -v 0.094603 0.059024 0.173734 -vn -0.770260 0.318865 0.552291 -v 0.094603 0.061024 0.178228 -vn -0.770264 -0.000000 0.637725 -v 0.094603 0.061649 0.178060 -vn -0.750899 0.444920 0.488055 -v 0.094603 0.066180 0.175504 -vn -0.770260 -0.318866 0.552291 -v 0.094603 0.062274 0.178228 -vn -0.750899 0.591181 0.294374 -v 0.094603 0.065039 0.177015 -vn -0.770263 -0.552286 0.318865 -v 0.094603 0.062732 0.178685 -vn -0.750899 0.657600 0.060936 -v 0.094603 0.064521 0.178835 -vn -0.770261 -0.637729 -0.000000 -v 0.094603 0.062899 0.179310 -vn -0.750899 0.635206 -0.180731 -v 0.094603 0.064696 0.180720 -vn -0.770261 -0.552291 -0.318862 -v 0.094603 0.062732 0.179935 -vn -0.680956 -0.259685 -0.684735 -v 0.094603 0.065394 0.168090 -vn -0.680956 -0.416007 -0.602692 -v 0.094603 0.062832 0.169435 -vn -0.680956 -0.548153 -0.485621 -v 0.094603 0.060667 0.171353 -vn -0.680956 0.088272 -0.726985 -v 0.094603 0.071096 0.167398 -vn -0.770260 -0.318866 0.552291 -v 0.094603 0.070274 0.170228 -vn -0.680956 0.259685 -0.684735 -v 0.094603 0.073904 0.168090 -vn -0.770263 -0.552286 0.318865 -v 0.094603 0.070732 0.170685 -vn -0.680956 0.416007 -0.602692 -v 0.094603 0.076466 0.169435 -vn -0.770261 -0.637728 -0.000000 -v 0.094603 0.070899 0.171310 -vn -0.680956 0.548153 -0.485621 -v 0.094603 0.078631 0.171353 -vn -0.770263 0.552286 0.318865 -v 0.094603 0.068567 0.170685 -vn -0.680957 -0.088271 -0.726984 -v 0.094603 0.068203 0.167398 -vn -0.770260 0.318865 0.552291 -v 0.094603 0.069024 0.170228 -vn -0.770264 -0.000000 0.637725 -v 0.094603 0.069649 0.170060 -vn -0.682487 0.644663 -0.344415 -v 0.094603 0.080275 0.173734 -vn -0.770261 -0.552291 -0.318862 -v 0.094603 0.070732 0.171935 -vn -0.693765 0.684366 -0.224350 -v 0.094603 0.081211 0.176097 -vn -0.692179 0.708928 -0.135310 -v 0.094603 0.081300 0.176439 -vn -0.770263 -0.552286 0.318865 -v 0.094603 0.078732 0.178685 -vn -0.770261 -0.552291 -0.318862 -v 0.094603 0.070732 0.187935 -vn -0.770265 -0.318861 -0.552286 -v 0.094603 0.070274 0.188393 -vn -0.770260 -0.318866 0.552291 -v 0.094603 0.078274 0.178228 -vn -0.770264 -0.000000 0.637725 -v 0.094603 0.077649 0.178060 -vn -0.770258 0.000000 -0.637732 -v 0.094603 0.077649 0.180560 -vn -0.770265 0.318861 -0.552287 -v 0.094603 0.077024 0.180393 -vn -0.770263 -0.552286 0.318865 -v 0.094603 0.070732 0.186685 -vn -0.770260 0.318865 0.552291 -v 0.094603 0.077024 0.178228 -vn -0.728475 -0.539110 0.422711 -v 0.094603 0.073643 0.176060 -vn -0.737366 -0.426800 0.523577 -v 0.094603 0.073119 0.175504 -vn -0.750899 -0.238569 0.615821 -v 0.094603 0.071510 0.174508 -vn -0.770265 -0.318861 -0.552286 -v 0.094603 0.070274 0.172393 -vn -0.750898 -0.000000 0.660418 -v 0.094603 0.069649 0.174160 -vn -0.770258 0.000000 -0.637732 -v 0.094603 0.069649 0.172560 -vn -0.750899 0.238569 0.615821 -v 0.094603 0.067789 0.174508 -vn -0.770264 0.318861 -0.552287 -v 0.094603 0.069024 0.172393 -vn -0.770261 0.552291 -0.318861 -v 0.094603 0.068567 0.171935 -vn -0.770261 0.637728 0.000000 -v 0.094603 0.068399 0.171310 -vn -0.770261 -0.637729 -0.000000 -v 0.094603 0.078899 0.179310 -vn -0.770261 -0.552291 -0.318862 -v 0.094603 0.078732 0.179935 -vn -0.770265 -0.318861 -0.552286 -v 0.094603 0.078274 0.180393 -vn -0.750898 -0.527025 -0.397991 -v 0.094603 0.073759 0.182414 -vn -0.750899 -0.347665 -0.561498 -v 0.094603 0.072360 0.183689 -vn -0.770261 0.552291 -0.318862 -v 0.094603 0.076567 0.179935 -vn -0.770258 0.000000 -0.637732 -v 0.094603 0.069649 0.188560 -vn -0.770265 0.318861 -0.552287 -v 0.094603 0.069024 0.188393 -vn -0.770261 0.552291 -0.318861 -v 0.094603 0.068567 0.187935 -vn -0.770261 0.637728 0.000000 -v 0.094603 0.068399 0.187310 -vn -0.770263 0.552286 0.318865 -v 0.094603 0.068567 0.186685 -vn -0.736219 0.321097 -0.595717 -v 0.094603 0.066938 0.183689 -vn -0.770260 0.318865 0.552291 -v 0.094603 0.069024 0.186228 -vn -0.770261 -0.637729 -0.000000 -v 0.094603 0.070899 0.187310 -vn -0.770260 -0.318866 0.552291 -v 0.094603 0.070274 0.186228 -vn -0.739565 -0.154105 -0.655206 -v 0.094603 0.070595 0.184373 -vn -0.770264 -0.000000 0.637725 -v 0.094603 0.069649 0.186060 -vn -0.728478 -0.000000 -0.685070 -v 0.094603 0.069649 0.184460 -vn -0.739566 0.154105 -0.655206 -v 0.094603 0.068703 0.184373 -vn -0.770263 0.552286 0.318865 -v 0.094603 0.076567 0.178685 -vn -0.741776 -0.611018 0.276451 -v 0.094603 0.074259 0.177015 -vn -0.770261 0.637728 0.000000 -v 0.094603 0.076399 0.179310 -vn -0.750899 -0.657600 0.060935 -v 0.094603 0.074777 0.178835 -vn -0.750899 -0.635206 -0.180733 -v 0.094603 0.074603 0.180720 -vn 0.680956 -0.416006 -0.602692 -v 0.098603 0.062832 0.169435 -vn 0.680956 -0.259685 -0.684735 -v 0.098603 0.065394 0.168090 -vn 0.750899 0.444920 0.488055 -v 0.098603 0.066180 0.175504 -vn 0.770261 0.637729 0.000000 -v 0.098603 0.068399 0.187310 -vn 0.770261 0.552291 -0.318862 -v 0.098603 0.068567 0.187935 -vn 0.991445 0.000000 0.130527 -v 0.098603 0.066449 0.227310 -vn 0.770263 0.552286 0.318865 -v 0.098603 0.068567 0.186685 -vn 0.728477 0.447348 -0.518846 -v 0.098603 0.066395 0.183302 -vn 0.736219 0.321097 -0.595717 -v 0.098603 0.066938 0.183689 -vn 0.770265 0.318861 -0.552286 -v 0.098603 0.069024 0.188393 -vn 0.770258 0.000000 -0.637732 -v 0.098603 0.069649 0.188560 -vn 0.770265 -0.318861 -0.552287 -v 0.098603 0.070274 0.188393 -vn 0.770261 -0.552291 -0.318862 -v 0.098603 0.070732 0.187935 -vn 0.770261 -0.637728 -0.000000 -v 0.098603 0.078899 0.179310 -vn 0.692179 0.708929 -0.135310 -v 0.098603 0.081300 0.176439 -vn 0.770263 -0.552286 0.318865 -v 0.098603 0.078732 0.178685 -vn 0.693765 0.684366 -0.224350 -v 0.098603 0.081211 0.176097 -vn 0.770260 -0.318866 0.552291 -v 0.098603 0.078274 0.178228 -vn 0.770264 -0.000000 0.637725 -v 0.098603 0.077649 0.178060 -vn 0.770258 0.000000 -0.637732 -v 0.098603 0.077649 0.180560 -vn 0.770265 -0.318861 -0.552287 -v 0.098603 0.078274 0.180393 -vn 0.770261 -0.552291 -0.318862 -v 0.098603 0.078732 0.179935 -vn 0.770263 -0.552286 0.318865 -v 0.098603 0.070732 0.186685 -vn 0.770260 -0.318866 0.552291 -v 0.098603 0.070274 0.186228 -vn 0.750899 -0.347665 -0.561498 -v 0.098603 0.072360 0.183689 -vn 0.770261 -0.637728 -0.000000 -v 0.098603 0.070899 0.187310 -vn 0.770265 0.318861 -0.552286 -v 0.098603 0.077024 0.180393 -vn 0.770261 0.552291 -0.318862 -v 0.098603 0.076567 0.179935 -vn 0.770260 0.318865 0.552291 -v 0.098603 0.069024 0.186228 -vn 0.739566 0.154105 -0.655206 -v 0.098603 0.068703 0.184373 -vn 0.770264 -0.000000 0.637725 -v 0.098603 0.069649 0.186060 -vn 0.728478 -0.000000 -0.685069 -v 0.098603 0.069649 0.184460 -vn 0.739565 -0.154105 -0.655206 -v 0.098603 0.070595 0.184373 -vn 0.728476 -0.539110 0.422711 -v 0.098603 0.073643 0.176060 -vn 0.770260 0.318866 0.552291 -v 0.098603 0.077024 0.178228 -vn 0.741776 -0.611018 0.276451 -v 0.098603 0.074259 0.177015 -vn 0.770263 0.552286 0.318865 -v 0.098603 0.076567 0.178685 -vn 0.750899 -0.657600 0.060935 -v 0.098603 0.074777 0.178835 -vn 0.770261 0.637729 0.000000 -v 0.098603 0.076399 0.179310 -vn 0.750899 -0.635206 -0.180733 -v 0.098603 0.074603 0.180720 -vn 0.750899 -0.527024 -0.397991 -v 0.098603 0.073759 0.182414 -vn 0.750899 0.591181 0.294374 -v 0.098603 0.065039 0.177015 -vn 0.750899 0.657600 0.060936 -v 0.098603 0.064521 0.178835 -vn 0.770261 -0.637728 -0.000000 -v 0.098603 0.062899 0.179310 -vn 0.770265 -0.318861 -0.552286 -v 0.098603 0.062274 0.180393 -vn 0.770258 0.000000 -0.637732 -v 0.098603 0.061649 0.180560 -vn 0.770260 -0.318866 0.552291 -v 0.098603 0.062274 0.178228 -vn 0.770264 -0.000000 0.637725 -v 0.098603 0.061649 0.178060 -vn 0.680957 -0.648441 -0.340328 -v 0.098603 0.059024 0.173734 -vn 0.770260 0.318865 0.552291 -v 0.098603 0.061024 0.178228 -vn 0.680956 -0.711044 -0.175257 -v 0.098603 0.057998 0.176439 -vn 0.770263 0.552286 0.318865 -v 0.098603 0.060567 0.178685 -vn 0.770261 0.637729 0.000000 -v 0.098603 0.060399 0.179310 -vn 0.770261 0.552291 -0.318862 -v 0.098603 0.060567 0.179935 -vn 0.770265 0.318861 -0.552286 -v 0.098603 0.061024 0.180393 -vn 0.770261 -0.552291 -0.318862 -v 0.098603 0.062732 0.179935 -vn 0.750899 0.635206 -0.180731 -v 0.098603 0.064696 0.180720 -vn 0.742935 0.546938 -0.385884 -v 0.098603 0.065539 0.182414 -vn 0.770263 -0.552286 0.318865 -v 0.098603 0.062732 0.178685 -vn 0.680956 -0.548153 -0.485621 -v 0.098603 0.060667 0.171353 -vn 0.770263 -0.552286 0.318865 -v 0.098603 0.070732 0.170685 -vn 0.770260 -0.318866 0.552291 -v 0.098603 0.070274 0.170228 -vn 0.680956 0.088272 -0.726984 -v 0.098603 0.071096 0.167398 -vn 0.770264 -0.000000 0.637725 -v 0.098603 0.069649 0.170060 -vn 0.680956 -0.088271 -0.726985 -v 0.098603 0.068203 0.167398 -vn 0.770260 0.318865 0.552291 -v 0.098603 0.069024 0.170228 -vn 0.737366 -0.426800 0.523577 -v 0.098603 0.073119 0.175504 -vn 0.680956 0.259685 -0.684735 -v 0.098603 0.073904 0.168090 -vn 0.680956 0.416007 -0.602692 -v 0.098603 0.076466 0.169435 -vn 0.770261 -0.637728 -0.000000 -v 0.098603 0.070899 0.171310 -vn 0.680956 0.548153 -0.485621 -v 0.098603 0.078631 0.171353 -vn 0.770261 -0.552291 -0.318862 -v 0.098603 0.070732 0.171935 -vn 0.682487 0.644663 -0.344415 -v 0.098603 0.080275 0.173734 -vn 0.770263 0.552286 0.318865 -v 0.098603 0.068567 0.170685 -vn 0.770261 0.637728 0.000000 -v 0.098603 0.068399 0.171310 -vn 0.770261 0.552291 -0.318862 -v 0.098603 0.068567 0.171935 -vn 0.750899 0.238569 0.615821 -v 0.098603 0.067789 0.174508 -vn 0.770265 0.318861 -0.552286 -v 0.098603 0.069024 0.172393 -vn 0.750898 -0.000000 0.660418 -v 0.098603 0.069649 0.174160 -vn 0.770258 0.000000 -0.637732 -v 0.098603 0.069649 0.172560 -vn 0.750899 -0.238569 0.615821 -v 0.098603 0.071510 0.174508 -vn 0.770265 -0.318861 -0.552287 -v 0.098603 0.070274 0.172393 -# 380 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 6//6 5//5 10//10 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 4//4 6//6 19//19 -f 19//19 6//6 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 24//24 25//25 26//26 -f 24//24 27//27 25//25 -f 25//25 27//27 10//10 -f 25//25 10//10 28//28 -f 28//28 10//10 5//5 -f 27//27 29//29 10//10 -f 10//10 29//29 30//30 -f 10//10 30//30 13//13 -f 13//13 30//30 31//31 -f 13//13 31//31 11//11 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 34//34 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 9//9 -f 9//9 37//37 38//38 -f 9//9 38//38 7//7 -f 26//26 9//9 24//24 -f 24//24 9//9 8//8 -f 24//24 8//8 39//39 -f 39//39 8//8 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 18//18 -f 18//18 42//42 43//43 -f 18//18 43//43 17//17 -f 44//44 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 48//48 -f 47//47 49//49 48//48 -f 48//48 49//49 50//50 -f 48//48 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 58//58 56//56 59//59 -f 58//58 59//59 22//22 -f 44//44 3//3 60//60 -f 60//60 3//3 61//61 -f 60//60 61//61 62//62 -f 62//62 61//61 63//63 -f 62//62 63//63 64//64 -f 64//64 63//63 65//65 -f 64//64 65//65 59//59 -f 59//59 65//65 66//66 -f 59//59 66//66 22//22 -f 22//22 66//66 33//33 -f 22//22 33//33 23//23 -f 23//23 33//33 32//32 -f 44//44 46//46 3//3 -f 3//3 46//46 67//67 -f 3//3 67//67 1//1 -f 68//68 69//69 70//70 -f 70//70 69//69 71//71 -f 70//70 71//71 72//72 -f 71//71 73//73 72//72 -f 72//72 73//73 74//74 -f 72//72 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 2//2 -f 77//77 13//13 15//15 -f 15//15 13//13 14//14 -f 15//15 14//14 16//16 -f 76//76 78//78 2//2 -f 2//2 78//78 79//79 -f 2//2 79//79 3//3 -f 3//3 79//79 80//80 -f 3//3 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 77//77 -f 77//77 86//86 68//68 -f 77//77 68//68 13//13 -f 13//13 68//68 70//70 -f 87//87 88//88 89//89 -f 90//90 91//91 92//92 -f 93//93 94//94 95//95 -f 91//91 96//96 92//92 -f 92//92 96//96 97//97 -f 92//92 97//97 98//98 -f 97//97 99//99 98//98 -f 98//98 99//99 100//100 -f 98//98 100//100 101//101 -f 100//100 102//102 101//101 -f 101//101 102//102 103//103 -f 101//101 103//103 104//104 -f 104//104 103//103 105//105 -f 104//104 106//106 101//101 -f 101//101 106//106 107//107 -f 101//101 107//107 108//108 -f 108//108 107//107 109//109 -f 108//108 109//109 110//110 -f 110//110 109//109 111//111 -f 110//110 111//111 112//112 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 103//103 121//121 122//122 -f 93//93 95//95 123//123 -f 123//123 95//95 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 121//121 -f 121//121 126//126 127//127 -f 121//121 127//127 122//122 -f 105//105 103//103 128//128 -f 128//128 103//103 122//122 -f 128//128 122//122 120//120 -f 120//120 122//122 129//129 -f 120//120 129//129 119//119 -f 130//130 131//131 132//132 -f 132//132 131//131 133//133 -f 132//132 133//133 134//134 -f 134//134 133//133 135//135 -f 134//134 135//135 136//136 -f 135//135 137//137 136//136 -f 136//136 137//137 138//138 -f 136//136 138//138 139//139 -f 139//139 138//138 140//140 -f 141//141 142//142 143//143 -f 143//143 142//142 144//144 -f 144//144 142//142 145//145 -f 144//144 145//145 146//146 -f 146//146 145//145 147//147 -f 146//146 147//147 94//94 -f 143//143 148//148 141//141 -f 141//141 148//148 130//130 -f 141//141 130//130 89//89 -f 93//93 90//90 94//94 -f 94//94 90//90 92//92 -f 94//94 92//92 146//146 -f 146//146 92//92 139//139 -f 146//146 139//139 149//149 -f 149//149 139//139 140//140 -f 130//130 132//132 89//89 -f 89//89 132//132 150//150 -f 89//89 150//150 87//87 -f 151//151 152//152 153//153 -f 151//151 153//153 88//88 -f 152//152 151//151 154//154 -f 154//154 151//151 155//155 -f 154//154 155//155 156//156 -f 157//157 110//110 113//113 -f 113//113 110//110 112//112 -f 113//113 112//112 114//114 -f 155//155 158//158 156//156 -f 156//156 158//158 159//159 -f 156//156 159//159 160//160 -f 160//160 159//159 161//161 -f 160//160 161//161 162//162 -f 162//162 161//161 163//163 -f 153//153 164//164 88//88 -f 88//88 164//164 165//165 -f 88//88 165//165 89//89 -f 89//89 165//165 166//166 -f 89//89 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 157//157 -f 157//157 172//172 162//162 -f 157//157 162//162 110//110 -f 110//110 162//162 163//163 -f 101//101 108//108 6//6 -f 6//6 108//108 20//20 -f 20//20 108//108 22//22 -f 22//22 108//108 110//110 -f 22//22 110//110 58//58 -f 110//110 163//163 58//58 -f 58//58 163//163 161//161 -f 58//58 161//161 57//57 -f 57//57 161//161 159//159 -f 57//57 159//159 55//55 -f 55//55 159//159 158//158 -f 55//55 158//158 53//53 -f 53//53 158//158 155//155 -f 53//53 155//155 51//51 -f 51//51 155//155 151//151 -f 51//51 151//151 48//48 -f 48//48 151//151 88//88 -f 48//48 88//88 46//46 -f 46//46 88//88 87//87 -f 46//46 87//87 67//67 -f 67//67 87//87 150//150 -f 67//67 150//150 1//1 -f 1//1 150//150 132//132 -f 1//1 132//132 2//2 -f 2//2 132//132 134//134 -f 2//2 134//134 75//75 -f 75//75 134//134 136//136 -f 75//75 136//136 72//72 -f 173//173 174//174 175//175 -f 176//176 177//177 173//173 -f 72//72 136//136 70//70 -f 70//70 136//136 139//139 -f 178//178 179//179 180//180 -f 180//180 179//179 181//181 -f 180//180 181//181 139//139 -f 139//139 181//181 182//182 -f 139//139 182//182 70//70 -f 183//183 176//176 184//184 -f 184//184 176//176 173//173 -f 184//184 173//173 185//185 -f 185//185 173//173 175//175 -f 184//184 186//186 183//183 -f 183//183 186//186 187//187 -f 183//183 187//187 179//179 -f 179//179 187//187 188//188 -f 179//179 188//188 181//181 -f 189//189 190//190 179//179 -f 179//179 190//190 191//191 -f 179//179 191//191 183//183 -f 191//191 192//192 183//183 -f 183//183 192//192 193//193 -f 183//183 193//193 194//194 -f 194//194 193//193 195//195 -f 194//194 195//195 189//189 -f 189//189 195//195 196//196 -f 189//189 196//196 190//190 -f 197//197 198//198 199//199 -f 199//199 198//198 200//200 -f 199//199 200//200 201//201 -f 98//98 101//101 6//6 -f 6//6 10//10 98//98 -f 98//98 10//10 202//202 -f 98//98 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 194//194 206//206 207//207 -f 207//207 206//206 201//201 -f 207//207 201//201 208//208 -f 208//208 201//201 200//200 -f 205//205 204//204 189//189 -f 189//189 204//204 209//209 -f 189//189 209//209 194//194 -f 194//194 209//209 210//210 -f 194//194 210//210 206//206 -f 63//63 169//169 65//65 -f 65//65 169//169 171//171 -f 65//65 171//171 66//66 -f 66//66 171//171 157//157 -f 66//66 157//157 33//33 -f 33//33 157//157 113//113 -f 33//33 113//113 35//35 -f 35//35 113//113 115//115 -f 35//35 115//115 37//37 -f 37//37 115//115 117//117 -f 37//37 117//117 38//38 -f 38//38 117//117 119//119 -f 38//38 119//119 7//7 -f 7//7 119//119 129//129 -f 7//7 129//129 8//8 -f 8//8 129//129 122//122 -f 8//8 122//122 40//40 -f 40//40 122//122 127//127 -f 40//40 127//127 42//42 -f 42//42 127//127 126//126 -f 42//42 126//126 43//43 -f 43//43 126//126 124//124 -f 43//43 124//124 17//17 -f 17//17 124//124 95//95 -f 17//17 95//95 15//15 -f 15//15 95//95 94//94 -f 15//15 94//94 77//77 -f 77//77 94//94 147//147 -f 77//77 147//147 85//85 -f 85//85 147//147 145//145 -f 85//85 145//145 83//83 -f 83//83 145//145 142//142 -f 83//83 142//142 81//81 -f 81//81 142//142 141//141 -f 81//81 141//141 3//3 -f 3//3 141//141 89//89 -f 3//3 89//89 61//61 -f 61//61 89//89 167//167 -f 61//61 167//167 63//63 -f 63//63 167//167 169//169 -f 23//23 112//112 21//21 -f 21//21 112//112 111//111 -f 21//21 111//111 19//19 -f 19//19 111//111 109//109 -f 19//19 109//109 4//4 -f 4//4 109//109 107//107 -f 4//4 107//107 5//5 -f 5//5 107//107 106//106 -f 5//5 106//106 28//28 -f 28//28 106//106 104//104 -f 28//28 104//104 25//25 -f 25//25 104//104 105//105 -f 25//25 105//105 26//26 -f 26//26 105//105 128//128 -f 26//26 128//128 9//9 -f 9//9 128//128 120//120 -f 9//9 120//120 36//36 -f 36//36 120//120 118//118 -f 36//36 118//118 34//34 -f 34//34 118//118 116//116 -f 34//34 116//116 32//32 -f 32//32 116//116 114//114 -f 32//32 114//114 23//23 -f 23//23 114//114 112//112 -f 41//41 125//125 39//39 -f 39//39 125//125 121//121 -f 39//39 121//121 24//24 -f 24//24 121//121 103//103 -f 24//24 103//103 27//27 -f 27//27 103//103 102//102 -f 27//27 102//102 29//29 -f 29//29 102//102 100//100 -f 29//29 100//100 30//30 -f 30//30 100//100 99//99 -f 30//30 99//99 31//31 -f 31//31 99//99 97//97 -f 31//31 97//97 11//11 -f 11//11 97//97 96//96 -f 11//11 96//96 12//12 -f 12//12 96//96 91//91 -f 12//12 91//91 14//14 -f 14//14 91//91 90//90 -f 14//14 90//90 16//16 -f 16//16 90//90 93//93 -f 16//16 93//93 18//18 -f 18//18 93//93 123//123 -f 18//18 123//123 41//41 -f 41//41 123//123 125//125 -f 79//79 131//131 80//80 -f 80//80 131//131 130//130 -f 80//80 130//130 82//82 -f 82//82 130//130 148//148 -f 82//82 148//148 84//84 -f 84//84 148//148 143//143 -f 84//84 143//143 86//86 -f 86//86 143//143 144//144 -f 86//86 144//144 68//68 -f 68//68 144//144 146//146 -f 68//68 146//146 69//69 -f 69//69 146//146 149//149 -f 69//69 149//149 71//71 -f 71//71 149//149 140//140 -f 71//71 140//140 73//73 -f 73//73 140//140 138//138 -f 73//73 138//138 74//74 -f 74//74 138//138 137//137 -f 74//74 137//137 76//76 -f 76//76 137//137 135//135 -f 76//76 135//135 78//78 -f 78//78 135//135 133//133 -f 78//78 133//133 79//79 -f 79//79 133//133 131//131 -f 50//50 152//152 52//52 -f 52//52 152//152 154//154 -f 52//52 154//154 54//54 -f 54//54 154//154 156//156 -f 54//54 156//156 56//56 -f 56//56 156//156 160//160 -f 56//56 160//160 59//59 -f 59//59 160//160 162//162 -f 59//59 162//162 64//64 -f 64//64 162//162 172//172 -f 64//64 172//172 62//62 -f 62//62 172//172 170//170 -f 62//62 170//170 60//60 -f 60//60 170//170 168//168 -f 60//60 168//168 44//44 -f 44//44 168//168 166//166 -f 44//44 166//166 45//45 -f 45//45 166//166 165//165 -f 45//45 165//165 47//47 -f 47//47 165//165 164//164 -f 47//47 164//164 49//49 -f 49//49 164//164 153//153 -f 49//49 153//153 50//50 -f 50//50 153//153 152//152 -f 210//210 211//211 187//187 -f 187//187 211//211 212//212 -f 187//187 212//212 188//188 -f 212//212 213//213 188//188 -f 188//188 213//213 214//214 -f 188//188 214//214 209//209 -f 209//209 214//214 215//215 -f 209//209 215//215 210//210 -f 210//210 215//215 216//216 -f 210//210 216//216 211//211 -f 217//217 218//218 219//219 -f 220//220 221//221 199//199 -f 199//199 221//221 222//222 -f 199//199 222//222 197//197 -f 222//222 223//223 197//197 -f 197//197 223//223 224//224 -f 197//197 224//224 225//225 -f 225//225 224//224 226//226 -f 225//225 226//226 227//227 -f 226//226 228//228 227//227 -f 227//227 228//228 229//229 -f 227//227 229//229 230//230 -f 230//230 229//229 231//231 -f 230//230 231//231 232//232 -f 232//232 231//231 233//233 -f 232//232 233//233 234//234 -f 234//234 233//233 235//235 -f 234//234 235//235 236//236 -f 236//236 235//235 237//237 -f 236//236 237//237 219//219 -f 219//219 237//237 220//220 -f 219//219 220//220 217//217 -f 217//217 220//220 199//199 -f 238//238 239//239 230//230 -f 230//230 239//239 240//240 -f 230//230 240//240 227//227 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 238//238 248//248 249//249 -f 249//249 248//248 250//250 -f 249//249 250//250 241//241 -f 241//241 250//250 251//251 -f 241//241 251//251 242//242 -f 247//247 246//246 252//252 -f 252//252 246//246 253//253 -f 252//252 253//253 254//254 -f 175//175 255//255 256//256 -f 257//257 258//258 185//185 -f 256//256 255//255 259//259 -f 259//259 255//255 254//254 -f 259//259 254//254 260//260 -f 261//261 262//262 263//263 -f 264//264 260//260 265//265 -f 265//265 260//260 254//254 -f 265//265 254//254 266//266 -f 266//266 254//254 253//253 -f 266//266 253//253 267//267 -f 267//267 253//253 268//268 -f 267//267 268//268 269//269 -f 269//269 268//268 270//270 -f 269//269 270//270 271//271 -f 271//271 270//270 272//272 -f 271//271 272//272 230//230 -f 230//230 272//272 273//273 -f 230//230 273//273 238//238 -f 238//238 273//273 274//274 -f 238//238 274//274 248//248 -f 256//256 275//275 175//175 -f 175//175 275//275 276//276 -f 175//175 276//276 277//277 -f 278//278 279//279 280//280 -f 185//185 258//258 217//217 -f 217//217 258//258 281//281 -f 217//217 281//281 282//282 -f 282//282 283//283 217//217 -f 217//217 283//283 284//284 -f 217//217 284//284 218//218 -f 218//218 284//284 285//285 -f 218//218 285//285 286//286 -f 286//286 285//285 287//287 -f 257//257 185//185 288//288 -f 288//288 185//185 175//175 -f 288//288 175//175 263//263 -f 263//263 175//175 277//277 -f 263//263 277//277 261//261 -f 262//262 280//280 263//263 -f 263//263 280//280 279//279 -f 263//263 279//279 289//289 -f 289//289 279//279 290//290 -f 289//289 290//290 291//291 -f 291//291 290//290 292//292 -f 291//291 292//292 287//287 -f 287//287 292//292 293//293 -f 287//287 293//293 286//286 -f 264//264 265//265 294//294 -f 294//294 265//265 295//295 -f 294//294 295//295 296//296 -f 296//296 295//295 297//297 -f 296//296 297//297 280//280 -f 280//280 297//297 298//298 -f 280//280 298//298 278//278 -f 299//299 300//300 301//301 -f 302//302 303//303 304//304 -f 305//305 306//306 307//307 -f 303//303 308//308 304//304 -f 304//304 308//308 309//309 -f 304//304 309//309 173//173 -f 173//173 309//309 310//310 -f 173//173 310//310 311//311 -f 174//174 312//312 313//313 -f 313//313 312//312 314//314 -f 313//313 314//314 315//315 -f 315//315 314//314 316//316 -f 315//315 316//316 317//317 -f 311//311 318//318 173//173 -f 173//173 318//318 319//319 -f 173//173 319//319 174//174 -f 174//174 319//319 320//320 -f 174//174 320//320 312//312 -f 321//321 322//322 323//323 -f 311//311 324//324 318//318 -f 318//318 324//324 321//321 -f 318//318 321//321 325//325 -f 325//325 321//321 323//323 -f 325//325 323//323 326//326 -f 305//305 307//307 327//327 -f 327//327 307//307 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 322//322 -f 322//322 330//330 331//331 -f 322//322 331//331 323//323 -f 332//332 333//333 334//334 -f 334//334 333//333 335//335 -f 334//334 335//335 336//336 -f 336//336 335//335 337//337 -f 336//336 337//337 338//338 -f 338//338 337//337 326//326 -f 338//338 326//326 339//339 -f 339//339 326//326 323//323 -f 340//340 341//341 342//342 -f 305//305 302//302 306//306 -f 306//306 302//302 304//304 -f 306//306 304//304 343//343 -f 343//343 304//304 200//200 -f 343//343 200//200 344//344 -f 345//345 346//346 347//347 -f 347//347 346//346 348//348 -f 347//347 348//348 349//349 -f 349//349 348//348 350//350 -f 349//349 350//350 198//198 -f 350//350 351//351 198//198 -f 198//198 351//351 352//352 -f 198//198 352//352 200//200 -f 200//200 352//352 353//353 -f 200//200 353//353 344//344 -f 342//342 341//341 354//354 -f 354//354 341//341 355//355 -f 354//354 355//355 343//343 -f 343//343 355//355 356//356 -f 343//343 356//356 306//306 -f 342//342 357//357 340//340 -f 340//340 357//357 345//345 -f 340//340 345//345 301//301 -f 345//345 347//347 301//301 -f 301//301 347//347 358//358 -f 301//301 358//358 299//299 -f 359//359 360//360 361//361 -f 361//361 360//360 362//362 -f 361//361 362//362 363//363 -f 363//363 362//362 364//364 -f 363//363 364//364 300//300 -f 365//365 315//315 332//332 -f 332//332 315//315 317//317 -f 332//332 317//317 333//333 -f 361//361 366//366 359//359 -f 359//359 366//366 367//367 -f 359//359 367//367 368//368 -f 368//368 367//367 369//369 -f 368//368 369//369 370//370 -f 370//370 369//369 371//371 -f 364//364 372//372 300//300 -f 300//300 372//372 373//373 -f 300//300 373//373 301//301 -f 301//301 373//373 374//374 -f 301//301 374//374 375//375 -f 375//375 374//374 376//376 -f 375//375 376//376 377//377 -f 377//377 376//376 378//378 -f 377//377 378//378 379//379 -f 379//379 378//378 380//380 -f 379//379 380//380 365//365 -f 365//365 380//380 370//370 -f 365//365 370//370 315//315 -f 315//315 370//370 371//371 -f 174//174 313//313 175//175 -f 175//175 313//313 255//255 -f 255//255 313//313 254//254 -f 254//254 313//313 315//315 -f 254//254 315//315 252//252 -f 315//315 371//371 252//252 -f 252//252 371//371 369//369 -f 252//252 369//369 247//247 -f 247//247 369//369 367//367 -f 247//247 367//367 245//245 -f 245//245 367//367 366//366 -f 245//245 366//366 243//243 -f 243//243 366//366 361//361 -f 243//243 361//361 241//241 -f 241//241 361//361 363//363 -f 241//241 363//363 249//249 -f 249//249 363//363 300//300 -f 249//249 300//300 238//238 -f 238//238 300//300 299//299 -f 238//238 299//299 239//239 -f 239//239 299//299 358//358 -f 239//239 358//358 240//240 -f 240//240 358//358 347//347 -f 240//240 347//347 227//227 -f 227//227 347//347 349//349 -f 227//227 349//349 225//225 -f 225//225 349//349 198//198 -f 225//225 198//198 197//197 -f 269//269 377//377 267//267 -f 267//267 377//377 379//379 -f 267//267 379//379 266//266 -f 266//266 379//379 365//365 -f 266//266 365//365 265//265 -f 265//265 365//365 332//332 -f 265//265 332//332 295//295 -f 295//295 332//332 334//334 -f 295//295 334//334 297//297 -f 297//297 334//334 336//336 -f 297//297 336//336 298//298 -f 298//298 336//336 338//338 -f 298//298 338//338 278//278 -f 278//278 338//338 339//339 -f 278//278 339//339 279//279 -f 279//279 339//339 323//323 -f 279//279 323//323 290//290 -f 290//290 323//323 331//331 -f 290//290 331//331 292//292 -f 292//292 331//331 330//330 -f 292//292 330//330 293//293 -f 293//293 330//330 328//328 -f 293//293 328//328 286//286 -f 286//286 328//328 307//307 -f 286//286 307//307 218//218 -f 218//218 307//307 306//306 -f 218//218 306//306 219//219 -f 219//219 306//306 356//356 -f 219//219 356//356 236//236 -f 236//236 356//356 355//355 -f 236//236 355//355 234//234 -f 234//234 355//355 341//341 -f 234//234 341//341 232//232 -f 232//232 341//341 340//340 -f 232//232 340//340 230//230 -f 230//230 340//340 301//301 -f 230//230 301//301 271//271 -f 271//271 301//301 375//375 -f 271//271 375//375 269//269 -f 269//269 375//375 377//377 -f 229//229 346//346 231//231 -f 231//231 346//346 345//345 -f 231//231 345//345 233//233 -f 233//233 345//345 357//357 -f 233//233 357//357 235//235 -f 235//235 357//357 342//342 -f 235//235 342//342 237//237 -f 237//237 342//342 354//354 -f 237//237 354//354 220//220 -f 220//220 354//354 343//343 -f 220//220 343//343 221//221 -f 221//221 343//343 344//344 -f 221//221 344//344 222//222 -f 222//222 344//344 353//353 -f 222//222 353//353 223//223 -f 223//223 353//353 352//352 -f 223//223 352//352 224//224 -f 224//224 352//352 351//351 -f 224//224 351//351 226//226 -f 226//226 351//351 350//350 -f 226//226 350//350 228//228 -f 228//228 350//350 348//348 -f 228//228 348//348 229//229 -f 229//229 348//348 346//346 -f 291//291 329//329 289//289 -f 289//289 329//329 322//322 -f 289//289 322//322 263//263 -f 263//263 322//322 321//321 -f 263//263 321//321 288//288 -f 288//288 321//321 324//324 -f 288//288 324//324 257//257 -f 257//257 324//324 311//311 -f 257//257 311//311 258//258 -f 258//258 311//311 310//310 -f 258//258 310//310 281//281 -f 281//281 310//310 309//309 -f 281//281 309//309 282//282 -f 282//282 309//309 308//308 -f 282//282 308//308 283//283 -f 283//283 308//308 303//303 -f 283//283 303//303 284//284 -f 284//284 303//303 302//302 -f 284//284 302//302 285//285 -f 285//285 302//302 305//305 -f 285//285 305//305 287//287 -f 287//287 305//305 327//327 -f 287//287 327//327 291//291 -f 291//291 327//327 329//329 -f 260//260 317//317 259//259 -f 259//259 317//317 316//316 -f 259//259 316//316 256//256 -f 256//256 316//316 314//314 -f 256//256 314//314 275//275 -f 275//275 314//314 312//312 -f 275//275 312//312 276//276 -f 276//276 312//312 320//320 -f 276//276 320//320 277//277 -f 277//277 320//320 319//319 -f 277//277 319//319 261//261 -f 261//261 319//319 318//318 -f 261//261 318//318 262//262 -f 262//262 318//318 325//325 -f 262//262 325//325 280//280 -f 280//280 325//325 326//326 -f 280//280 326//326 296//296 -f 296//296 326//326 337//337 -f 296//296 337//337 294//294 -f 294//294 337//337 335//335 -f 294//294 335//335 264//264 -f 264//264 335//335 333//333 -f 264//264 333//333 260//260 -f 260//260 333//333 317//317 -f 251//251 362//362 242//242 -f 242//242 362//362 360//360 -f 242//242 360//360 244//244 -f 244//244 360//360 359//359 -f 244//244 359//359 246//246 -f 246//246 359//359 368//368 -f 246//246 368//368 253//253 -f 253//253 368//368 370//370 -f 253//253 370//370 268//268 -f 268//268 370//370 380//380 -f 268//268 380//380 270//270 -f 270//270 380//380 378//378 -f 270//270 378//378 272//272 -f 272//272 378//378 376//376 -f 272//272 376//376 273//273 -f 273//273 376//376 374//374 -f 273//273 374//374 274//274 -f 274//274 374//374 373//373 -f 274//274 373//373 248//248 -f 248//248 373//373 372//372 -f 248//248 372//372 250//250 -f 250//250 372//372 364//364 -f 250//250 364//364 251//251 -f 251//251 364//364 362//362 -f 190//190 214//214 191//191 -f 191//191 214//214 213//213 -f 191//191 213//213 192//192 -f 192//192 213//213 212//212 -f 192//192 212//212 193//193 -f 193//193 212//212 211//211 -f 193//193 211//211 195//195 -f 195//195 211//211 216//216 -f 195//195 216//216 196//196 -f 196//196 216//216 215//215 -f 196//196 215//215 190//190 -f 190//190 215//215 214//214 -f 92//92 98//98 203//203 -f 180//180 139//139 92//92 -f 92//92 203//203 180//180 -f 180//180 203//203 205//205 -f 180//180 205//205 178//178 -f 178//178 205//205 189//189 -f 178//178 189//189 179//179 -f 13//13 70//70 182//182 -f 10//10 13//13 202//202 -f 202//202 13//13 182//182 -f 202//202 182//182 204//204 -f 204//204 182//182 181//181 -f 204//204 181//181 209//209 -f 209//209 181//181 188//188 -f 183//183 194//194 207//207 -f 208//208 200//200 304//304 -f 183//183 207//207 176//176 -f 176//176 207//207 208//208 -f 176//176 208//208 177//177 -f 177//177 208//208 304//304 -f 177//177 304//304 173//173 -f 217//217 199//199 201//201 -f 185//185 217//217 184//184 -f 184//184 217//217 201//201 -f 184//184 201//201 186//186 -f 186//186 201//201 206//206 -f 186//186 206//206 187//187 -f 187//187 206//206 210//210 -# 800 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper2.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper2.obj deleted file mode 100644 index 3cf432cc9..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper2.obj +++ /dev/null @@ -1,1620 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object gripper2.obj -# -# Vertices: 393 -# Faces: 818 -# -#### -vn 0.234914 -0.437641 -0.867920 -v 0.060032 0.040639 0.245689 -vn 0.155680 -0.431048 -0.888798 -v 0.061513 0.040092 0.246306 -vn -0.636192 -0.725561 -0.262338 -v 0.051603 0.039649 0.246795 -vn 0.077771 -0.427551 -0.900640 -v 0.063019 0.039764 0.246669 -vn 0.026407 -0.716094 -0.697504 -v 0.064603 0.039649 0.246795 -vn 0.474903 -0.475021 -0.740825 -v 0.056513 0.043158 0.242673 -vn 0.395132 -0.460601 -0.794807 -v 0.057510 0.042210 0.243844 -vn 0.314478 -0.447596 -0.837115 -v 0.058725 0.041336 0.244885 -vn 0.652473 -0.563257 -0.506971 -v 0.054728 0.046337 0.238370 -vn 0.609073 -0.540861 -0.580086 -v 0.055093 0.045269 0.239885 -vn -0.716546 -0.560904 -0.414666 -v 0.051603 0.045105 0.240112 -vn 0.575236 -0.516059 -0.634654 -v 0.055169 0.045105 0.240112 -vn 0.549719 -0.498963 -0.669959 -v 0.055747 0.044116 0.241440 -vn -0.718701 -0.688556 0.096744 -v 0.051603 0.059261 0.182913 -vn 0.718701 -0.688556 0.096744 -v 0.054603 0.059261 0.182913 -vn -0.719749 -0.693842 0.023327 -v 0.051603 0.060027 0.191506 -vn 0.719749 -0.693842 0.023327 -v 0.054603 0.060027 0.191506 -vn -0.719749 -0.692183 -0.053324 -v 0.051603 0.059840 0.200131 -vn 0.719749 -0.692183 -0.053324 -v 0.054603 0.059840 0.200131 -vn -0.719749 -0.682082 -0.129326 -v 0.051603 0.058704 0.208683 -vn 0.719749 -0.682082 -0.129326 -v 0.054603 0.058704 0.208683 -vn -0.719749 -0.663662 -0.203749 -v 0.051603 0.056631 0.217057 -vn 0.719749 -0.663662 -0.203749 -v 0.054603 0.056631 0.217057 -vn -0.719749 -0.637147 -0.275689 -v 0.051603 0.053648 0.225152 -vn 0.719749 -0.637147 -0.275688 -v 0.054603 0.053648 0.225152 -vn -0.719749 -0.602862 -0.344265 -v 0.051603 0.049790 0.232868 -vn 0.719600 -0.603940 -0.342683 -v 0.054603 0.049790 0.232868 -vn 0.715621 -0.575820 -0.395370 -v 0.054603 0.047391 0.236795 -vn -0.692002 -0.582528 -0.426373 -v 0.098603 0.047391 0.236795 -vn -0.999903 0.009829 -0.009829 -v 0.098603 0.053649 0.236795 -vn -0.716762 -0.609949 -0.337957 -v 0.098603 0.049790 0.232868 -vn -0.719749 -0.637147 -0.275689 -v 0.098603 0.053648 0.225152 -vn -0.770257 -0.000000 -0.637733 -v 0.098603 0.061649 0.180181 -vn -0.770265 0.318860 -0.552286 -v 0.098603 0.061206 0.180063 -vn -0.718701 -0.688556 0.096744 -v 0.098603 0.059261 0.182913 -vn -0.676012 -0.736129 0.033485 -v 0.098603 0.058661 0.179795 -vn -0.770260 0.552292 -0.318862 -v 0.098603 0.068882 0.187738 -vn -0.695295 0.536499 0.478260 -v 0.098603 0.060223 0.245069 -vn -0.770266 0.318860 -0.552286 -v 0.098603 0.069206 0.188063 -vn -0.695294 0.584400 0.418382 -v 0.098603 0.065765 0.238140 -vn -0.770258 -0.000001 -0.637733 -v 0.098603 0.069649 0.188181 -vn -0.770261 0.637728 0.000000 -v 0.098603 0.068763 0.187295 -vn -0.770260 0.552292 0.318862 -v 0.098603 0.068882 0.186852 -vn -0.770261 -0.552289 -0.318865 -v 0.098603 0.070417 0.171738 -vn -0.770262 -0.637728 -0.000000 -v 0.098603 0.070535 0.171295 -vn -0.695294 0.686388 0.213161 -v 0.098603 0.077565 0.214396 -vn -0.770258 -0.000001 -0.637733 -v 0.098603 0.077649 0.180181 -vn -0.770265 0.318860 -0.552286 -v 0.098603 0.077206 0.180063 -vn -0.770264 -0.318859 -0.552289 -v 0.098603 0.070092 0.172063 -vn -0.770258 -0.000001 -0.637733 -v 0.098603 0.069649 0.172181 -vn -0.770266 0.318860 -0.552286 -v 0.098603 0.069206 0.172063 -vn -0.770260 -0.318870 0.552288 -v 0.098603 0.070092 0.186528 -vn -0.770262 0.637727 0.000000 -v 0.098603 0.076763 0.179295 -vn -0.770260 0.552292 0.318862 -v 0.098603 0.076882 0.178852 -vn -0.676013 0.616597 -0.403504 -v 0.098603 0.078853 0.173272 -vn -0.770266 0.318860 0.552286 -v 0.098603 0.077206 0.178528 -vn -0.770258 -0.000001 0.637733 -v 0.098603 0.077649 0.178409 -vn -0.695296 0.718592 -0.013731 -v 0.098603 0.081292 0.188144 -vn -0.770265 -0.318861 -0.552285 -v 0.098603 0.078092 0.180063 -vn -0.695295 0.715967 0.062904 -v 0.098603 0.080988 0.197011 -vn -0.695295 0.705190 0.138822 -v 0.098603 0.079741 0.205795 -vn -0.700862 0.492112 0.516351 -v 0.098603 0.053974 0.251367 -vn -0.684115 0.505098 0.526177 -v 0.098603 0.053649 0.251660 -vn -0.770259 -0.552292 -0.318865 -v 0.098603 0.062417 0.179738 -vn -0.770265 -0.318860 -0.552286 -v 0.098603 0.062092 0.180063 -vn -0.676013 -0.500704 -0.540650 -v 0.098603 0.062175 0.171224 -vn -0.770262 0.637727 0.000000 -v 0.098603 0.068763 0.171295 -vn -0.676012 -0.325375 -0.661165 -v 0.098603 0.064792 0.169425 -vn -0.770260 0.552292 0.318862 -v 0.098603 0.068882 0.170852 -vn -0.676012 -0.122920 -0.726566 -v 0.098603 0.067814 0.168449 -vn -0.770266 0.318860 0.552286 -v 0.098603 0.069206 0.170528 -vn -0.676013 0.089779 -0.731401 -v 0.098603 0.070989 0.168377 -vn -0.695295 0.625646 0.353740 -v 0.098603 0.070537 0.230661 -vn -0.695294 0.659772 0.285073 -v 0.098603 0.074486 0.222716 -vn -0.770264 -0.318859 -0.552289 -v 0.098603 0.070092 0.188063 -vn -0.770262 -0.552288 -0.318864 -v 0.098603 0.070417 0.187738 -vn -0.770262 -0.637727 -0.000000 -v 0.098603 0.070535 0.187295 -vn -0.770262 -0.552288 0.318864 -v 0.098603 0.070417 0.186852 -vn -0.676012 0.706178 -0.210526 -v 0.098603 0.080191 0.176152 -vn -0.770265 -0.318861 0.552286 -v 0.098603 0.078092 0.178528 -vn -0.770260 -0.552292 0.318862 -v 0.098603 0.078417 0.178852 -vn -0.699052 0.710853 -0.077554 -v 0.098603 0.080649 0.179295 -vn -0.770262 -0.637727 -0.000000 -v 0.098603 0.078535 0.179295 -vn -0.770260 -0.552292 -0.318862 -v 0.098603 0.078417 0.179738 -vn -0.719749 -0.693842 0.023327 -v 0.098603 0.060027 0.191506 -vn -0.719749 -0.692183 -0.053324 -v 0.098603 0.059840 0.200131 -vn -0.719749 -0.682082 -0.129326 -v 0.098603 0.058704 0.208683 -vn -0.719749 -0.663662 -0.203749 -v 0.098603 0.056631 0.217057 -vn -0.770258 -0.000001 0.637733 -v 0.098603 0.069649 0.170409 -vn -0.770264 -0.318859 0.552289 -v 0.098603 0.070092 0.170528 -vn -0.676012 0.294994 -0.675267 -v 0.098603 0.074053 0.169215 -vn -0.770262 -0.552288 0.318864 -v 0.098603 0.070417 0.170852 -vn -0.676013 0.475619 -0.562844 -v 0.098603 0.076749 0.170893 -vn -0.770260 0.552292 -0.318862 -v 0.098603 0.076882 0.179738 -vn -0.770265 -0.318860 0.552286 -v 0.098603 0.062092 0.178528 -vn -0.770259 -0.552292 0.318865 -v 0.098603 0.062417 0.178852 -vn -0.770264 -0.637725 0.000000 -v 0.098603 0.062535 0.179295 -vn -0.770262 0.318871 0.552285 -v 0.098603 0.069206 0.186528 -vn -0.770266 -0.000001 0.637723 -v 0.098603 0.069649 0.186409 -vn -0.770260 0.552292 -0.318862 -v 0.098603 0.060882 0.179738 -vn -0.770262 0.637727 0.000000 -v 0.098603 0.060763 0.179295 -vn -0.676012 -0.715014 -0.178220 -v 0.098603 0.058976 0.176635 -vn -0.770260 0.552292 0.318862 -v 0.098603 0.060882 0.178852 -vn -0.676012 -0.634296 -0.375068 -v 0.098603 0.060181 0.173696 -vn -0.770265 0.318860 0.552286 -v 0.098603 0.061206 0.178528 -vn -0.770258 0.000000 0.637733 -v 0.098603 0.061649 0.178409 -vn -0.770260 0.552292 -0.318862 -v 0.098603 0.068882 0.171738 -vn 0.676013 0.089779 -0.731400 -v 0.101603 0.070989 0.168377 -vn 0.770258 -0.000001 0.637733 -v 0.101603 0.069649 0.170409 -vn 0.676012 -0.122920 -0.726566 -v 0.101603 0.067814 0.168449 -vn 0.770266 0.318860 0.552286 -v 0.101603 0.069206 0.170528 -vn 0.676012 -0.325375 -0.661165 -v 0.101603 0.064792 0.169425 -vn 0.770260 0.552292 0.318862 -v 0.101603 0.068882 0.170852 -vn 0.676012 -0.500704 -0.540650 -v 0.101603 0.062175 0.171224 -vn 0.719749 -0.637147 -0.275688 -v 0.101603 0.053648 0.225152 -vn 0.719749 -0.663662 -0.203750 -v 0.101603 0.056631 0.217057 -vn 0.695295 0.625646 0.353740 -v 0.101603 0.070537 0.230661 -vn 0.770266 -0.000001 0.637722 -v 0.101603 0.069649 0.186409 -vn 0.770262 0.637728 -0.000000 -v 0.101603 0.068763 0.171295 -vn 0.770260 0.552292 -0.318862 -v 0.101603 0.068882 0.171738 -vn 0.770266 0.318860 0.552286 -v 0.101603 0.077206 0.178528 -vn 0.676013 0.475619 -0.562844 -v 0.101603 0.076749 0.170893 -vn 0.770258 -0.000001 0.637733 -v 0.101603 0.077649 0.178409 -vn 0.676012 0.616597 -0.403504 -v 0.101603 0.078853 0.173272 -vn 0.770265 -0.318861 0.552286 -v 0.101603 0.078092 0.178528 -vn 0.676012 0.706178 -0.210526 -v 0.101603 0.080191 0.176152 -vn 0.770260 -0.552292 0.318862 -v 0.101603 0.078417 0.178852 -vn 0.555769 -0.398255 0.729736 -v 0.101603 0.039649 0.261795 -vn 0.636168 -0.725287 -0.263152 -v 0.101603 0.039649 0.246795 -vn 0.698461 0.416374 0.582052 -v 0.101603 0.047090 0.256964 -vn 0.713870 -0.564301 -0.414673 -v 0.101603 0.045105 0.240112 -vn 0.717160 -0.607982 -0.340646 -v 0.101603 0.049790 0.232868 -vn 0.770266 0.318860 -0.552286 -v 0.101603 0.069206 0.172063 -vn 0.770258 -0.000001 -0.637733 -v 0.101603 0.069649 0.172181 -vn 0.770260 -0.318870 0.552288 -v 0.101603 0.070092 0.186528 -vn 0.770260 0.552292 -0.318862 -v 0.101603 0.060882 0.179738 -vn 0.770265 0.318860 -0.552286 -v 0.101603 0.061206 0.180063 -vn 0.676012 -0.736129 0.033485 -v 0.101603 0.058661 0.179795 -vn 0.770260 0.552292 0.318862 -v 0.101603 0.068882 0.186852 -vn 0.718701 -0.688556 0.096744 -v 0.101603 0.059261 0.182913 -vn 0.770262 0.637727 -0.000000 -v 0.101603 0.068763 0.187295 -vn 0.719749 -0.693842 0.023327 -v 0.101603 0.060027 0.191506 -vn 0.770260 0.552292 -0.318862 -v 0.101603 0.068882 0.187738 -vn 0.719749 -0.692183 -0.053324 -v 0.101603 0.059840 0.200131 -vn 0.770266 0.318860 -0.552286 -v 0.101603 0.069206 0.188063 -vn 0.719749 -0.682082 -0.129326 -v 0.101603 0.058704 0.208683 -vn 0.770258 -0.000001 -0.637733 -v 0.101603 0.069649 0.188181 -vn 0.695295 0.705190 0.138822 -v 0.101603 0.079741 0.205795 -vn 0.695295 0.686388 0.213161 -v 0.101603 0.077565 0.214396 -vn 0.770257 -0.000001 -0.637733 -v 0.101603 0.077649 0.180181 -vn 0.770264 -0.318859 -0.552289 -v 0.101603 0.070092 0.172063 -vn 0.770262 -0.552288 -0.318864 -v 0.101603 0.070417 0.171738 -vn 0.770262 -0.637727 0.000000 -v 0.101603 0.070535 0.171295 -vn 0.676012 0.294994 -0.675267 -v 0.101603 0.074053 0.169215 -vn 0.770262 -0.552288 0.318864 -v 0.101603 0.070417 0.170852 -vn 0.770264 -0.318859 0.552289 -v 0.101603 0.070092 0.170528 -vn 0.770260 0.552292 0.318862 -v 0.101603 0.076882 0.178852 -vn 0.770258 0.000000 -0.637733 -v 0.101603 0.061649 0.180181 -vn 0.770265 -0.318860 -0.552286 -v 0.101603 0.062092 0.180063 -vn 0.770262 0.318871 0.552285 -v 0.101603 0.069206 0.186528 -vn 0.770259 -0.552292 -0.318865 -v 0.101603 0.062417 0.179738 -vn 0.770264 -0.637725 -0.000000 -v 0.101603 0.062535 0.179295 -vn 0.770259 -0.552292 0.318865 -v 0.101603 0.062417 0.178852 -vn 0.770265 -0.318860 0.552286 -v 0.101603 0.062092 0.178528 -vn 0.770258 -0.000000 0.637733 -v 0.101603 0.061649 0.178409 -vn 0.676012 -0.634296 -0.375068 -v 0.101603 0.060181 0.173696 -vn 0.770265 0.318860 0.552286 -v 0.101603 0.061206 0.178528 -vn 0.676012 -0.715014 -0.178220 -v 0.101603 0.058976 0.176635 -vn 0.770260 0.552292 0.318862 -v 0.101603 0.060882 0.178852 -vn 0.770262 0.637727 -0.000000 -v 0.101603 0.060763 0.179295 -vn 0.695295 0.584399 0.418382 -v 0.101603 0.065765 0.238140 -vn 0.695295 0.536500 0.478261 -v 0.101603 0.060223 0.245069 -vn 0.698531 0.484788 0.526341 -v 0.101603 0.053974 0.251367 -vn 0.695295 0.659772 0.285073 -v 0.101603 0.074486 0.222716 -vn 0.770265 0.318860 -0.552286 -v 0.101603 0.077206 0.180063 -vn 0.770262 -0.552289 -0.318864 -v 0.101603 0.070417 0.187738 -vn 0.770264 -0.318859 -0.552289 -v 0.101603 0.070092 0.188063 -vn 0.770262 -0.637727 0.000000 -v 0.101603 0.078535 0.179295 -vn 0.699052 0.710853 -0.077554 -v 0.101603 0.080649 0.179295 -vn 0.770260 -0.552292 -0.318862 -v 0.101603 0.078417 0.179738 -vn 0.695296 0.718592 -0.013731 -v 0.101603 0.081292 0.188144 -vn 0.770265 -0.318861 -0.552286 -v 0.101603 0.078092 0.180063 -vn 0.770262 0.637727 -0.000000 -v 0.101603 0.076763 0.179295 -vn 0.770260 0.552292 -0.318862 -v 0.101603 0.076882 0.179738 -vn 0.770262 -0.552289 0.318864 -v 0.101603 0.070417 0.186852 -vn 0.770262 -0.637727 0.000000 -v 0.101603 0.070535 0.187295 -vn 0.695295 0.715967 0.062904 -v 0.101603 0.080988 0.197011 -vn -0.648694 -0.572877 -0.501007 -v 0.098479 0.046338 0.238368 -vn -0.026360 -0.716101 -0.697499 -v 0.088603 0.039649 0.246795 -vn -0.077535 -0.427648 -0.900614 -v 0.090180 0.039763 0.246670 -vn -0.155433 -0.431088 -0.888821 -v 0.091693 0.040092 0.246306 -vn -0.234719 -0.437602 -0.867993 -v 0.093167 0.040636 0.245693 -vn -0.314314 -0.447511 -0.837222 -v 0.094481 0.041336 0.244885 -vn -0.394796 -0.460519 -0.795021 -v 0.095687 0.042203 0.243853 -vn -0.474748 -0.475009 -0.740932 -v 0.096693 0.043158 0.242673 -vn -0.536660 -0.494484 -0.683726 -v 0.097460 0.044118 0.241437 -vn -0.593868 -0.533681 -0.602084 -v 0.098114 0.045269 0.239885 -vn -0.555620 -0.398868 0.729514 -v 0.051603 0.039649 0.261795 -vn -0.272353 -0.838628 0.471727 -v 0.079057 0.039649 0.250045 -vn 0.272353 -0.838628 0.471728 -v 0.074149 0.039649 0.250045 -vn 0.544705 -0.838628 -0.000001 -v 0.071696 0.039649 0.254295 -vn 0.272352 -0.838628 -0.471729 -v 0.074149 0.039649 0.258545 -vn -0.272352 -0.838628 -0.471728 -v 0.079057 0.039649 0.258545 -vn -0.544705 -0.838628 -0.000001 -v 0.081511 0.039649 0.254295 -vn 0.677247 0.511703 0.528674 -v 0.054603 0.053649 0.251660 -vn 0.700862 0.492112 0.516351 -v 0.054603 0.053974 0.251367 -vn -0.698629 0.484991 0.526024 -v 0.051603 0.053974 0.251367 -vn 0.695295 0.536500 0.478260 -v 0.054603 0.060223 0.245069 -vn -0.695296 0.536499 0.478260 -v 0.051603 0.060223 0.245069 -vn 0.695295 0.584399 0.418382 -v 0.054603 0.065765 0.238140 -vn -0.695294 0.584400 0.418382 -v 0.051603 0.065765 0.238140 -vn 0.695295 0.625646 0.353740 -v 0.054603 0.070537 0.230661 -vn -0.695295 0.625646 0.353740 -v 0.051603 0.070537 0.230661 -vn 0.695295 0.659772 0.285073 -v 0.054603 0.074486 0.222716 -vn -0.695294 0.659772 0.285073 -v 0.051603 0.074486 0.222716 -vn 0.695295 0.686388 0.213161 -v 0.054603 0.077565 0.214396 -vn -0.695294 0.686388 0.213161 -v 0.051603 0.077565 0.214396 -vn 0.695295 0.705190 0.138822 -v 0.054603 0.079741 0.205795 -vn -0.695295 0.705190 0.138822 -v 0.051603 0.079741 0.205795 -vn 0.695295 0.715967 0.062904 -v 0.054603 0.080988 0.197011 -vn -0.695295 0.715967 0.062904 -v 0.051603 0.080988 0.197011 -vn 0.695296 0.718592 -0.013731 -v 0.054603 0.081292 0.188144 -vn -0.695296 0.718592 -0.013731 -v 0.051603 0.081292 0.188144 -vn 0.699052 0.710853 -0.077554 -v 0.054603 0.080649 0.179295 -vn -0.699052 0.710853 -0.077554 -v 0.051603 0.080649 0.179295 -vn 0.465485 0.725915 0.506331 -v 0.056513 0.047771 0.256462 -vn 0.523207 0.681290 0.511956 -v 0.055680 0.049135 0.255426 -vn -0.699702 0.416880 0.580197 -v 0.051603 0.047090 0.256964 -vn 0.567006 0.636896 0.522367 -v 0.055092 0.050559 0.254296 -vn 0.629250 0.566201 0.532410 -v 0.054723 0.052105 0.253010 -vn -0.237747 0.827640 0.508417 -v 0.093157 0.044746 0.258609 -vn -0.160573 0.846568 0.507483 -v 0.091693 0.044139 0.259016 -vn -0.309280 0.803817 0.508158 -v 0.094481 0.045559 0.258052 -vn -0.081180 0.857257 0.508448 -v 0.090180 0.043774 0.259257 -vn -0.021588 0.866140 0.499336 -v 0.088603 0.043649 0.259339 -vn 0.021515 0.866164 0.499296 -v 0.064603 0.043649 0.259339 -vn 0.081035 0.857268 0.508454 -v 0.063032 0.043773 0.259257 -vn 0.160511 0.846548 0.507536 -v 0.061513 0.044139 0.259016 -vn 0.237832 0.827614 0.508421 -v 0.060046 0.044748 0.258608 -vn 0.309350 0.803788 0.508161 -v 0.058725 0.045559 0.258052 -vn 0.376492 0.773693 0.509562 -v 0.057836 0.046287 0.257541 -vn 0.428261 0.750509 0.503318 -v 0.057077 0.047064 0.256983 -vn -0.572217 0.634682 0.519371 -v 0.098114 0.050559 0.254296 -vn -0.523513 0.683297 0.508958 -v 0.097525 0.049133 0.255428 -vn -0.627981 0.567171 0.532876 -v 0.098483 0.052106 0.253009 -vn -0.474770 0.722868 0.502050 -v 0.096693 0.047771 0.256462 -vn -0.424698 0.746639 0.512017 -v 0.096152 0.047090 0.256964 -vn -0.368011 0.776617 0.511306 -v 0.095368 0.046285 0.257542 -vn -0.272352 0.838628 -0.471728 -v 0.079057 0.043649 0.258545 -vn 0.272352 0.838628 -0.471728 -v 0.074149 0.043649 0.258545 -vn 0.544705 0.838628 -0.000001 -v 0.071696 0.043649 0.254295 -vn 0.056842 0.705958 -0.705969 -v 0.064603 0.043649 0.246795 -vn 0.272353 0.838628 0.471727 -v 0.074149 0.043649 0.250045 -vn -0.056906 0.705985 -0.705937 -v 0.088603 0.043649 0.246795 -vn -0.272353 0.838628 0.471727 -v 0.079057 0.043649 0.250045 -vn -0.544705 0.838628 -0.000001 -v 0.081511 0.043649 0.254295 -vn 0.999903 0.009829 -0.009829 -v 0.054603 0.053649 0.236795 -vn 0.770264 -0.318859 0.552289 -v 0.054603 0.070092 0.170528 -vn 0.770258 -0.000001 0.637733 -v 0.054603 0.069649 0.170409 -vn 0.676013 0.089779 -0.731400 -v 0.054603 0.070989 0.168377 -vn 0.770266 0.318860 -0.552286 -v 0.054603 0.069206 0.172063 -vn 0.770266 -0.000001 0.637722 -v 0.054603 0.069649 0.186409 -vn 0.770260 0.552292 -0.318862 -v 0.054603 0.068882 0.171738 -vn 0.770262 0.637727 -0.000000 -v 0.054603 0.068763 0.171295 -vn 0.770266 0.318860 0.552286 -v 0.054603 0.077206 0.178528 -vn 0.676012 0.294994 -0.675267 -v 0.054603 0.074053 0.169215 -vn 0.676012 0.706178 -0.210526 -v 0.054603 0.080191 0.176152 -vn 0.770262 -0.637727 0.000000 -v 0.054603 0.078535 0.179295 -vn 0.770257 -0.000001 0.637733 -v 0.054603 0.077649 0.178409 -vn 0.676012 -0.122920 -0.726566 -v 0.054603 0.067814 0.168449 -vn 0.770266 0.318860 0.552286 -v 0.054603 0.069206 0.170528 -vn 0.770260 0.552292 0.318862 -v 0.054603 0.068882 0.170852 -vn 0.676012 -0.325375 -0.661165 -v 0.054603 0.064792 0.169425 -vn 0.770265 -0.318860 0.552286 -v 0.054603 0.062092 0.178528 -vn 0.676012 -0.500704 -0.540650 -v 0.054603 0.062175 0.171224 -vn 0.770258 -0.000000 0.637733 -v 0.054603 0.061649 0.178409 -vn 0.676012 -0.634296 -0.375068 -v 0.054603 0.060181 0.173696 -vn 0.770265 0.318860 0.552286 -v 0.054603 0.061206 0.178528 -vn 0.676012 -0.715014 -0.178220 -v 0.054603 0.058976 0.176635 -vn 0.770260 0.552292 0.318862 -v 0.054603 0.060882 0.178852 -vn 0.676012 -0.736129 0.033485 -v 0.054603 0.058661 0.179795 -vn 0.770262 -0.552289 -0.318864 -v 0.054603 0.070417 0.187738 -vn 0.770262 0.637728 -0.000000 -v 0.054603 0.076763 0.179295 -vn 0.770260 0.552292 -0.318862 -v 0.054603 0.076882 0.179738 -vn 0.770260 -0.552292 -0.318862 -v 0.054603 0.078417 0.179738 -vn 0.770265 -0.318861 -0.552286 -v 0.054603 0.078092 0.180063 -vn 0.770260 0.552292 0.318862 -v 0.054603 0.076882 0.178852 -vn 0.770264 -0.318859 -0.552289 -v 0.054603 0.070092 0.172063 -vn 0.770259 -0.552292 0.318865 -v 0.054603 0.062417 0.178852 -vn 0.770262 0.318871 0.552285 -v 0.054603 0.069206 0.186528 -vn 0.770264 -0.637725 -0.000000 -v 0.054603 0.062535 0.179295 -vn 0.770259 -0.552292 -0.318865 -v 0.054603 0.062417 0.179738 -vn 0.770260 -0.552292 0.318862 -v 0.054603 0.078417 0.178852 -vn 0.770265 -0.318861 0.552286 -v 0.054603 0.078092 0.178528 -vn 0.676012 0.616597 -0.403504 -v 0.054603 0.078853 0.173272 -vn 0.676012 0.475619 -0.562844 -v 0.054603 0.076749 0.170893 -vn 0.770262 -0.552288 -0.318864 -v 0.054603 0.070417 0.171738 -vn 0.770262 -0.637727 0.000000 -v 0.054603 0.070535 0.171295 -vn 0.770262 -0.552288 0.318864 -v 0.054603 0.070417 0.170852 -vn 0.770257 0.000000 -0.637733 -v 0.054603 0.061649 0.180181 -vn 0.770265 -0.318860 -0.552286 -v 0.054603 0.062092 0.180063 -vn 0.770262 0.637727 -0.000000 -v 0.054603 0.068763 0.187295 -vn 0.770262 -0.637727 0.000000 -v 0.054603 0.070535 0.187295 -vn 0.770262 -0.552289 0.318864 -v 0.054603 0.070417 0.186852 -vn 0.770260 -0.318870 0.552288 -v 0.054603 0.070092 0.186528 -vn 0.770258 -0.000001 -0.637733 -v 0.054603 0.069649 0.172181 -vn 0.770265 0.318860 -0.552286 -v 0.054603 0.061206 0.180063 -vn 0.770260 0.552292 -0.318862 -v 0.054603 0.060882 0.179738 -vn 0.770262 0.637727 -0.000000 -v 0.054603 0.060763 0.179295 -vn 0.770258 -0.000001 -0.637733 -v 0.054603 0.077649 0.180181 -vn 0.770266 0.318860 -0.552286 -v 0.054603 0.077206 0.180063 -vn 0.770260 0.552292 0.318862 -v 0.054603 0.068882 0.186852 -vn 0.770260 0.552292 -0.318862 -v 0.054603 0.068882 0.187738 -vn 0.770266 0.318860 -0.552286 -v 0.054603 0.069206 0.188063 -vn 0.770258 -0.000001 -0.637733 -v 0.054603 0.069649 0.188181 -vn 0.770264 -0.318859 -0.552289 -v 0.054603 0.070092 0.188063 -vn -0.770262 0.637727 0.000000 -v 0.051603 0.076763 0.179295 -vn -0.770261 -0.552289 0.318864 -v 0.051603 0.070417 0.170852 -vn -0.770260 0.552292 -0.318862 -v 0.051603 0.076882 0.179738 -vn -0.770262 -0.637727 -0.000000 -v 0.051603 0.070535 0.171295 -vn -0.676012 -0.736129 0.033485 -v 0.051603 0.058661 0.179795 -vn -0.770265 0.318860 -0.552286 -v 0.051603 0.061206 0.180063 -vn -0.770258 -0.000001 -0.637733 -v 0.051603 0.077649 0.180181 -vn -0.770265 0.318860 -0.552286 -v 0.051603 0.077206 0.180063 -vn -0.770260 -0.318870 0.552288 -v 0.051603 0.070092 0.186528 -vn -0.770262 -0.552288 0.318864 -v 0.051603 0.070417 0.186852 -vn -0.770266 0.318860 -0.552286 -v 0.051603 0.069206 0.172063 -vn -0.770262 0.637728 0.000000 -v 0.051603 0.068763 0.187295 -vn -0.770258 -0.000001 -0.637732 -v 0.051603 0.069649 0.172181 -vn -0.770260 0.552292 0.318862 -v 0.051603 0.068882 0.186852 -vn -0.770262 0.318871 0.552285 -v 0.051603 0.069206 0.186528 -vn -0.770265 -0.318861 -0.552285 -v 0.051603 0.078092 0.180063 -vn -0.770262 -0.637727 -0.000000 -v 0.051603 0.070535 0.187295 -vn -0.770262 -0.552288 -0.318864 -v 0.051603 0.070417 0.187738 -vn -0.770264 -0.318859 -0.552289 -v 0.051603 0.070092 0.188063 -vn -0.770258 -0.000001 -0.637733 -v 0.051603 0.069649 0.188181 -vn -0.770257 -0.000000 -0.637733 -v 0.051603 0.061649 0.180181 -vn -0.770260 0.552292 -0.318862 -v 0.051603 0.068882 0.187738 -vn -0.770266 0.318860 -0.552286 -v 0.051603 0.069206 0.188063 -vn -0.770260 0.552292 -0.318862 -v 0.051603 0.060882 0.179738 -vn -0.770262 0.637727 0.000000 -v 0.051603 0.060763 0.179295 -vn -0.676012 -0.715014 -0.178220 -v 0.051603 0.058976 0.176635 -vn -0.770260 0.552292 0.318862 -v 0.051603 0.060882 0.178852 -vn -0.676012 -0.634296 -0.375068 -v 0.051603 0.060181 0.173696 -vn -0.770265 0.318860 0.552286 -v 0.051603 0.061206 0.178528 -vn -0.676013 -0.500704 -0.540650 -v 0.051603 0.062175 0.171224 -vn -0.676013 0.089779 -0.731400 -v 0.051603 0.070989 0.168377 -vn -0.770264 -0.318859 0.552289 -v 0.051603 0.070092 0.170528 -vn -0.770262 -0.552288 -0.318864 -v 0.051603 0.070417 0.171738 -vn -0.770264 -0.318859 -0.552289 -v 0.051603 0.070092 0.172063 -vn -0.770266 -0.000001 0.637723 -v 0.051603 0.069649 0.186409 -vn -0.770259 -0.552292 0.318865 -v 0.051603 0.062417 0.178852 -vn -0.770264 -0.637725 0.000000 -v 0.051603 0.062535 0.179295 -vn -0.770259 -0.552292 -0.318865 -v 0.051603 0.062417 0.179738 -vn -0.770265 -0.318860 -0.552286 -v 0.051603 0.062092 0.180063 -vn -0.676012 0.294994 -0.675267 -v 0.051603 0.074053 0.169215 -vn -0.770266 0.318860 0.552286 -v 0.051603 0.077206 0.178528 -vn -0.770260 0.552292 0.318862 -v 0.051603 0.076882 0.178852 -vn -0.676012 0.475619 -0.562844 -v 0.051603 0.076749 0.170893 -vn -0.770258 -0.000001 0.637733 -v 0.051603 0.077649 0.178409 -vn -0.676012 0.616597 -0.403504 -v 0.051603 0.078853 0.173272 -vn -0.770265 -0.318861 0.552286 -v 0.051603 0.078092 0.178528 -vn -0.676012 0.706177 -0.210526 -v 0.051603 0.080191 0.176152 -vn -0.770260 -0.552292 0.318862 -v 0.051603 0.078417 0.178852 -vn -0.770262 -0.637727 -0.000000 -v 0.051603 0.078535 0.179295 -vn -0.770260 -0.552292 -0.318862 -v 0.051603 0.078417 0.179738 -vn -0.770258 0.000000 0.637733 -v 0.051603 0.061649 0.178409 -vn -0.770265 -0.318860 0.552286 -v 0.051603 0.062092 0.178528 -vn -0.770262 0.637727 0.000000 -v 0.051603 0.068763 0.171295 -vn -0.770260 0.552292 -0.318862 -v 0.051603 0.068882 0.171738 -vn -0.676012 -0.325375 -0.661165 -v 0.051603 0.064792 0.169425 -vn -0.770260 0.552292 0.318862 -v 0.051603 0.068882 0.170852 -vn -0.676012 -0.122920 -0.726566 -v 0.051603 0.067814 0.168449 -vn -0.770266 0.318860 0.552286 -v 0.051603 0.069206 0.170528 -vn -0.770258 -0.000001 0.637733 -v 0.051603 0.069649 0.170409 -vn -0.735892 0.477045 -0.480511 -v 0.094481 0.045559 0.244885 -vn -0.603689 0.563739 -0.563700 -v 0.093143 0.044739 0.245705 -vn -0.434283 0.637041 -0.636849 -v 0.091693 0.044139 0.246306 -vn -0.228384 0.688431 -0.688407 -v 0.090167 0.043772 0.246672 -vn -0.831814 0.392091 -0.392874 -v 0.095674 0.046578 0.243866 -vn -0.901920 0.304704 -0.306099 -v 0.096693 0.047771 0.242673 -vn -0.949986 0.220801 -0.220849 -v 0.097513 0.049109 0.241335 -vn -0.981941 0.145466 -0.120958 -v 0.098114 0.050559 0.239885 -vn -0.995975 0.066265 -0.060348 -v 0.098480 0.052085 0.238359 -vn 0.947340 0.228280 -0.224578 -v 0.055693 0.049109 0.241335 -vn 0.980924 0.130421 -0.144147 -v 0.055092 0.050559 0.239885 -vn 0.996309 0.059759 -0.061627 -v 0.054726 0.052085 0.238359 -vn 0.906892 0.301253 -0.294607 -v 0.056513 0.047771 0.242673 -vn 0.737629 0.472098 -0.482729 -v 0.058725 0.045559 0.244885 -vn 0.830630 0.392308 -0.395156 -v 0.057532 0.046578 0.243866 -vn 0.228349 0.688342 -0.688507 -v 0.063039 0.043772 0.246672 -vn 0.434385 0.636999 -0.636822 -v 0.061513 0.044139 0.246306 -vn 0.603665 0.563759 -0.563706 -v 0.060063 0.044739 0.245705 -# 393 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 6//6 7//7 3//3 -f 3//3 7//7 8//8 -f 3//3 8//8 1//1 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 3//3 -f 3//3 12//12 13//13 -f 3//3 13//13 6//6 -f 14//14 15//15 16//16 -f 16//16 15//15 17//17 -f 16//16 17//17 18//18 -f 18//18 17//17 19//19 -f 18//18 19//19 20//20 -f 20//20 19//19 21//21 -f 20//20 21//21 22//22 -f 22//22 21//21 23//23 -f 22//22 23//23 24//24 -f 24//24 23//23 25//25 -f 24//24 25//25 26//26 -f 26//26 25//25 27//27 -f 26//26 27//27 11//11 -f 11//11 27//27 28//28 -f 11//11 28//28 9//9 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 42//42 43//43 44//44 -f 44//44 43//43 45//45 -f 46//46 47//47 48//48 -f 44//44 49//49 42//42 -f 42//42 49//49 50//50 -f 42//42 50//50 51//51 -f 52//52 53//53 54//54 -f 55//55 56//56 57//57 -f 58//58 59//59 60//60 -f 60//60 59//59 47//47 -f 60//60 47//47 61//61 -f 61//61 47//47 46//46 -f 38//38 30//30 62//62 -f 62//62 30//30 63//63 -f 51//51 64//64 42//42 -f 42//42 64//64 65//65 -f 42//42 65//65 37//37 -f 37//37 65//65 33//33 -f 37//37 33//33 38//38 -f 66//66 67//67 68//68 -f 68//68 67//67 69//69 -f 68//68 69//69 70//70 -f 70//70 69//69 71//71 -f 70//70 71//71 72//72 -f 40//40 73//73 41//41 -f 41//41 73//73 74//74 -f 41//41 74//74 75//75 -f 75//75 74//74 46//46 -f 75//75 46//46 76//76 -f 76//76 46//46 48//48 -f 76//76 48//48 77//77 -f 77//77 48//48 78//78 -f 55//55 57//57 79//79 -f 57//57 80//80 79//79 -f 79//79 80//80 81//81 -f 79//79 81//81 82//82 -f 82//82 81//81 83//83 -f 82//82 83//83 58//58 -f 58//58 83//83 84//84 -f 58//58 84//84 59//59 -f 35//35 85//85 33//33 -f 33//33 85//85 86//86 -f 33//33 86//86 38//38 -f 38//38 86//86 87//87 -f 38//38 87//87 30//30 -f 30//30 87//87 88//88 -f 30//30 88//88 32//32 -f 71//71 89//89 72//72 -f 72//72 89//89 90//90 -f 72//72 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 45//45 -f 78//78 48//48 52//52 -f 52//52 48//48 94//94 -f 52//52 94//94 53//53 -f 95//95 96//96 51//51 -f 51//51 96//96 97//97 -f 51//51 97//97 64//64 -f 43//43 98//98 45//45 -f 45//45 98//98 99//99 -f 45//45 99//99 93//93 -f 93//93 99//99 52//52 -f 93//93 52//52 55//55 -f 55//55 52//52 54//54 -f 55//55 54//54 56//56 -f 34//34 100//100 36//36 -f 36//36 100//100 101//101 -f 36//36 101//101 102//102 -f 102//102 101//101 103//103 -f 102//102 103//103 104//104 -f 104//104 103//103 105//105 -f 104//104 105//105 66//66 -f 66//66 105//105 106//106 -f 66//66 106//106 67//67 -f 67//67 106//106 95//95 -f 67//67 95//95 107//107 -f 107//107 95//95 51//51 -f 108//108 109//109 110//110 -f 110//110 109//109 111//111 -f 110//110 111//111 112//112 -f 112//112 111//111 113//113 -f 112//112 113//113 114//114 -f 115//115 116//116 117//117 -f 118//118 119//119 120//120 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 128//128 129//129 130//130 -f 130//130 129//129 131//131 -f 115//115 117//117 132//132 -f 120//120 133//133 118//118 -f 118//118 133//133 134//134 -f 118//118 134//134 135//135 -f 136//136 137//137 138//138 -f 138//138 137//137 139//139 -f 138//138 139//139 140//140 -f 140//140 139//139 141//141 -f 140//140 141//141 142//142 -f 142//142 141//141 143//143 -f 142//142 143//143 144//144 -f 144//144 143//143 145//145 -f 144//144 145//145 146//146 -f 146//146 145//145 147//147 -f 148//148 149//149 150//150 -f 151//151 152//152 122//122 -f 122//122 152//152 153//153 -f 122//122 153//153 154//154 -f 154//154 153//153 155//155 -f 154//154 155//155 108//108 -f 108//108 155//155 156//156 -f 108//108 156//156 109//109 -f 121//121 157//157 122//122 -f 122//122 157//157 135//135 -f 122//122 135//135 151//151 -f 151//151 135//135 134//134 -f 137//137 158//158 139//139 -f 139//139 158//158 159//159 -f 139//139 159//159 160//160 -f 160//160 159//159 161//161 -f 160//160 161//161 118//118 -f 118//118 161//161 162//162 -f 118//118 162//162 119//119 -f 119//119 162//162 163//163 -f 119//119 163//163 113//113 -f 113//113 163//163 164//164 -f 113//113 164//164 114//114 -f 114//114 164//164 165//165 -f 114//114 165//165 166//166 -f 166//166 165//165 167//167 -f 166//166 167//167 168//168 -f 168//168 167//167 169//169 -f 168//168 169//169 138//138 -f 138//138 169//169 170//170 -f 138//138 170//170 136//136 -f 117//117 171//171 132//132 -f 132//132 171//171 172//172 -f 132//132 172//172 131//131 -f 131//131 172//172 173//173 -f 131//131 173//173 130//130 -f 116//116 146//146 117//117 -f 117//117 146//146 147//147 -f 117//117 147//147 174//174 -f 174//174 147//147 149//149 -f 175//175 150//150 176//176 -f 176//176 150//150 149//149 -f 176//176 149//149 177//177 -f 177//177 149//149 147//147 -f 127//127 126//126 178//178 -f 178//178 126//126 179//179 -f 178//178 179//179 180//180 -f 180//180 179//179 181//181 -f 180//180 181//181 182//182 -f 157//157 183//183 135//135 -f 135//135 183//183 184//184 -f 135//135 184//184 185//185 -f 185//185 184//184 175//175 -f 185//185 175//175 186//186 -f 186//186 175//175 176//176 -f 182//182 181//181 150//150 -f 150//150 181//181 187//187 -f 150//150 187//187 148//148 -f 140//140 35//35 36//36 -f 140//140 36//36 138//138 -f 138//138 36//36 102//102 -f 138//138 102//102 168//168 -f 168//168 102//102 104//104 -f 168//168 104//104 166//166 -f 166//166 104//104 66//66 -f 166//166 66//66 114//114 -f 114//114 66//66 68//68 -f 114//114 68//68 112//112 -f 112//112 68//68 70//70 -f 112//112 70//70 110//110 -f 110//110 70//70 72//72 -f 110//110 72//72 108//108 -f 108//108 72//72 91//91 -f 108//108 91//91 154//154 -f 154//154 91//91 93//93 -f 154//154 93//93 122//122 -f 122//122 93//93 55//55 -f 122//122 55//55 124//124 -f 124//124 55//55 79//79 -f 124//124 79//79 126//126 -f 126//126 79//79 82//82 -f 126//126 82//82 179//179 -f 150//150 47//47 182//182 -f 182//182 47//47 59//59 -f 182//182 59//59 180//180 -f 180//180 59//59 84//84 -f 180//180 84//84 178//178 -f 178//178 84//84 83//83 -f 178//178 83//83 127//127 -f 127//127 83//83 81//81 -f 127//127 81//81 125//125 -f 125//125 81//81 80//80 -f 125//125 80//80 123//123 -f 123//123 80//80 57//57 -f 123//123 57//57 121//121 -f 121//121 57//57 56//56 -f 121//121 56//56 157//157 -f 157//157 56//56 54//54 -f 157//157 54//54 183//183 -f 183//183 54//54 53//53 -f 183//183 53//53 184//184 -f 184//184 53//53 94//94 -f 184//184 94//94 175//175 -f 175//175 94//94 48//48 -f 175//175 48//48 150//150 -f 150//150 48//48 47//47 -f 134//134 50//50 151//151 -f 151//151 50//50 49//49 -f 151//151 49//49 152//152 -f 152//152 49//49 44//44 -f 152//152 44//44 153//153 -f 153//153 44//44 45//45 -f 153//153 45//45 155//155 -f 155//155 45//45 92//92 -f 155//155 92//92 156//156 -f 156//156 92//92 90//90 -f 156//156 90//90 109//109 -f 109//109 90//90 89//89 -f 109//109 89//89 111//111 -f 111//111 89//89 71//71 -f 111//111 71//71 113//113 -f 113//113 71//71 69//69 -f 113//113 69//69 119//119 -f 119//119 69//69 67//67 -f 119//119 67//67 120//120 -f 120//120 67//67 107//107 -f 120//120 107//107 133//133 -f 133//133 107//107 51//51 -f 133//133 51//51 134//134 -f 134//134 51//51 50//50 -f 158//158 33//33 159//159 -f 159//159 33//33 65//65 -f 159//159 65//65 161//161 -f 161//161 65//65 64//64 -f 161//161 64//64 162//162 -f 162//162 64//64 97//97 -f 162//162 97//97 163//163 -f 163//163 97//97 96//96 -f 163//163 96//96 164//164 -f 164//164 96//96 95//95 -f 164//164 95//95 165//165 -f 165//165 95//95 106//106 -f 165//165 106//106 167//167 -f 167//167 106//106 105//105 -f 167//167 105//105 169//169 -f 169//169 105//105 103//103 -f 169//169 103//103 170//170 -f 170//170 103//103 101//101 -f 170//170 101//101 136//136 -f 136//136 101//101 100//100 -f 136//136 100//100 137//137 -f 137//137 100//100 34//34 -f 137//137 34//34 158//158 -f 158//158 34//34 33//33 -f 147//147 41//41 177//177 -f 177//177 41//41 75//75 -f 177//177 75//75 176//176 -f 176//176 75//75 76//76 -f 176//176 76//76 186//186 -f 186//186 76//76 77//77 -f 186//186 77//77 185//185 -f 185//185 77//77 78//78 -f 185//185 78//78 135//135 -f 135//135 78//78 52//52 -f 135//135 52//52 118//118 -f 118//118 52//52 99//99 -f 118//118 99//99 160//160 -f 160//160 99//99 98//98 -f 160//160 98//98 139//139 -f 139//139 98//98 43//43 -f 139//139 43//43 141//141 -f 141//141 43//43 42//42 -f 141//141 42//42 143//143 -f 143//143 42//42 37//37 -f 143//143 37//37 145//145 -f 145//145 37//37 39//39 -f 145//145 39//39 147//147 -f 147//147 39//39 41//41 -f 35//35 140//140 85//85 -f 85//85 140//140 142//142 -f 85//85 142//142 86//86 -f 86//86 142//142 144//144 -f 86//86 144//144 87//87 -f 87//87 144//144 146//146 -f 87//87 146//146 88//88 -f 88//88 146//146 116//116 -f 88//88 116//116 32//32 -f 32//32 116//116 115//115 -f 32//32 115//115 31//31 -f 31//31 115//115 132//132 -f 31//31 132//132 29//29 -f 29//29 132//132 131//131 -f 29//29 131//131 188//188 -f 189//189 190//190 129//129 -f 129//129 190//190 191//191 -f 191//191 192//192 129//129 -f 129//129 192//192 193//193 -f 129//129 193//193 194//194 -f 194//194 195//195 129//129 -f 129//129 195//195 196//196 -f 129//129 196//196 131//131 -f 131//131 196//196 197//197 -f 131//131 197//197 188//188 -f 198//198 3//3 5//5 -f 199//199 200//200 5//5 -f 5//5 200//200 201//201 -f 5//5 201//201 198//198 -f 198//198 201//201 202//202 -f 198//198 202//202 128//128 -f 128//128 202//202 203//203 -f 128//128 203//203 129//129 -f 129//129 203//203 204//204 -f 129//129 204//204 189//189 -f 189//189 204//204 199//199 -f 189//189 199//199 5//5 -f 205//205 206//206 207//207 -f 207//207 206//206 208//208 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 213//213 212//212 214//214 -f 213//213 214//214 215//215 -f 215//215 214//214 216//216 -f 215//215 216//216 217//217 -f 217//217 216//216 218//218 -f 217//217 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 207//207 -f 207//207 229//229 230//230 -f 207//207 230//230 205//205 -f 231//231 232//232 128//128 -f 231//231 128//128 233//233 -f 232//232 234//234 128//128 -f 128//128 234//234 235//235 -f 128//128 235//235 198//198 -f 198//198 235//235 236//236 -f 236//236 237//237 198//198 -f 198//198 237//237 238//238 -f 198//198 238//238 239//239 -f 239//239 240//240 198//198 -f 198//198 240//240 241//241 -f 198//198 241//241 228//228 -f 228//228 241//241 242//242 -f 228//228 242//242 226//226 -f 243//243 244//244 130//130 -f 243//243 130//130 245//245 -f 245//245 130//130 173//173 -f 245//245 173//173 63//63 -f 244//244 246//246 130//130 -f 130//130 246//246 247//247 -f 130//130 247//247 128//128 -f 128//128 247//247 248//248 -f 128//128 248//248 233//233 -f 63//63 173//173 62//62 -f 62//62 173//173 172//172 -f 62//62 172//172 38//38 -f 38//38 172//172 171//171 -f 38//38 171//171 40//40 -f 40//40 171//171 117//117 -f 40//40 117//117 73//73 -f 73//73 117//117 174//174 -f 73//73 174//174 74//74 -f 74//74 174//174 149//149 -f 74//74 149//149 46//46 -f 46//46 149//149 148//148 -f 46//46 148//148 61//61 -f 61//61 148//148 187//187 -f 61//61 187//187 60//60 -f 60//60 187//187 181//181 -f 60//60 181//181 58//58 -f 58//58 181//181 179//179 -f 58//58 179//179 82//82 -f 236//236 235//235 249//249 -f 249//249 250//250 236//236 -f 236//236 250//250 251//251 -f 236//236 251//251 252//252 -f 252//252 251//251 253//253 -f 252//252 253//253 254//254 -f 254//254 253//253 255//255 -f 254//254 255//255 235//235 -f 235//235 255//255 256//256 -f 235//235 256//256 249//249 -f 206//206 205//205 257//257 -f 258//258 259//259 260//260 -f 261//261 262//262 263//263 -f 263//263 262//262 264//264 -f 216//216 214//214 257//257 -f 257//257 214//214 212//212 -f 212//212 210//210 257//257 -f 257//257 210//210 208//208 -f 257//257 208//208 206//206 -f 265//265 260//260 266//266 -f 267//267 224//224 268//268 -f 265//265 266//266 269//269 -f 260//260 259//259 270//270 -f 270//270 259//259 271//271 -f 270//270 271//271 272//272 -f 273//273 274//274 275//275 -f 275//275 274//274 276//276 -f 275//275 276//276 277//277 -f 277//277 276//276 278//278 -f 277//277 278//278 279//279 -f 279//279 278//278 280//280 -f 279//279 280//280 281//281 -f 282//282 283//283 284//284 -f 268//268 224//224 285//285 -f 285//285 224//224 222//222 -f 285//285 222//222 286//286 -f 265//265 287//287 288//288 -f 289//289 290//290 291//291 -f 291//291 290//290 292//292 -f 273//273 270//270 274//274 -f 274//274 270//270 272//272 -f 274//274 272//272 289//289 -f 289//289 272//272 264//264 -f 289//289 264//264 290//290 -f 290//290 264//264 262//262 -f 268//268 293//293 267//267 -f 267//267 293//293 294//294 -f 267//267 294//294 295//295 -f 295//295 294//294 269//269 -f 295//295 269//269 296//296 -f 296//296 269//269 266//266 -f 288//288 297//297 265//265 -f 265//265 297//297 298//298 -f 265//265 298//298 260//260 -f 260//260 298//298 299//299 -f 260//260 299//299 258//258 -f 300//300 301//301 302//302 -f 282//282 303//303 283//283 -f 283//283 303//303 304//304 -f 283//283 304//304 287//287 -f 287//287 304//304 305//305 -f 287//287 305//305 288//288 -f 288//288 305//305 262//262 -f 288//288 262//262 306//306 -f 306//306 262//262 261//261 -f 307//307 15//15 308//308 -f 308//308 15//15 281//281 -f 308//308 281//281 309//309 -f 309//309 281//281 280//280 -f 25//25 23//23 216//216 -f 216//216 23//23 21//21 -f 218//218 216//216 310//310 -f 310//310 216//216 282//282 -f 310//310 282//282 311//311 -f 311//311 282//282 284//284 -f 286//286 222//222 310//310 -f 310//310 222//222 220//220 -f 310//310 220//220 218//218 -f 292//292 290//290 301//301 -f 301//301 290//290 312//312 -f 301//301 312//312 302//302 -f 307//307 300//300 15//15 -f 15//15 300//300 302//302 -f 15//15 302//302 17//17 -f 17//17 302//302 313//313 -f 17//17 313//313 19//19 -f 19//19 313//313 314//314 -f 19//19 314//314 21//21 -f 21//21 314//314 315//315 -f 21//21 315//315 216//216 -f 216//216 315//315 316//316 -f 216//216 316//316 282//282 -f 25//25 216//216 27//27 -f 27//27 216//216 257//257 -f 27//27 257//257 28//28 -f 317//317 318//318 319//319 -f 319//319 318//318 320//320 -f 321//321 14//14 322//322 -f 20//20 22//22 209//209 -f 217//217 323//323 324//324 -f 319//319 325//325 324//324 -f 324//324 325//325 326//326 -f 22//22 24//24 209//209 -f 209//209 24//24 26//26 -f 209//209 26//26 207//207 -f 207//207 26//26 11//11 -f 207//207 11//11 228//228 -f 228//228 11//11 3//3 -f 228//228 3//3 198//198 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 331//331 -f 223//223 332//332 221//221 -f 221//221 332//332 323//323 -f 221//221 323//323 219//219 -f 219//219 323//323 217//217 -f 326//326 333//333 324//324 -f 324//324 333//333 334//334 -f 324//324 334//334 217//217 -f 217//217 334//334 335//335 -f 217//217 335//335 215//215 -f 215//215 335//335 336//336 -f 322//322 14//14 337//337 -f 337//337 14//14 16//16 -f 337//337 16//16 18//18 -f 338//338 209//209 339//339 -f 339//339 209//209 211//211 -f 339//339 211//211 336//336 -f 336//336 211//211 213//213 -f 336//336 213//213 215//215 -f 322//322 340//340 321//321 -f 321//321 340//340 341//341 -f 321//321 341//341 342//342 -f 342//342 341//341 343//343 -f 342//342 343//343 344//344 -f 344//344 343//343 345//345 -f 344//344 345//345 346//346 -f 347//347 348//348 318//318 -f 320//320 349//349 319//319 -f 319//319 349//349 350//350 -f 319//319 350//350 325//325 -f 325//325 350//350 329//329 -f 325//325 329//329 351//351 -f 351//351 329//329 331//331 -f 352//352 353//353 327//327 -f 327//327 353//353 354//354 -f 327//327 354//354 328//328 -f 328//328 354//354 355//355 -f 328//328 355//355 338//338 -f 338//338 355//355 337//337 -f 338//338 337//337 209//209 -f 209//209 337//337 18//18 -f 209//209 18//18 20//20 -f 356//356 347//347 357//357 -f 357//357 347//347 318//318 -f 357//357 318//318 358//358 -f 358//358 318//318 317//317 -f 356//356 357//357 359//359 -f 359//359 357//357 360//360 -f 359//359 360//360 361//361 -f 361//361 360//360 362//362 -f 361//361 362//362 363//363 -f 363//363 362//362 364//364 -f 363//363 364//364 225//225 -f 225//225 364//364 365//365 -f 225//225 365//365 223//223 -f 223//223 365//365 366//366 -f 223//223 366//366 332//332 -f 367//367 368//368 369//369 -f 352//352 327//327 368//368 -f 368//368 327//327 370//370 -f 368//368 370//370 369//369 -f 345//345 367//367 346//346 -f 346//346 367//367 369//369 -f 346//346 369//369 371//371 -f 371//371 369//369 372//372 -f 371//371 372//372 373//373 -f 373//373 372//372 374//374 -f 373//373 374//374 347//347 -f 347//347 374//374 375//375 -f 347//347 375//375 348//348 -f 225//225 224//224 267//267 -f 225//225 267//267 363//363 -f 363//363 267//267 295//295 -f 363//363 295//295 361//361 -f 361//361 295//295 296//296 -f 361//361 296//296 359//359 -f 359//359 296//296 266//266 -f 359//359 266//266 356//356 -f 356//356 266//266 260//260 -f 356//356 260//260 347//347 -f 347//347 260//260 270//270 -f 347//347 270//270 373//373 -f 373//373 270//270 273//273 -f 373//373 273//273 371//371 -f 371//371 273//273 275//275 -f 371//371 275//275 346//346 -f 346//346 275//275 277//277 -f 346//346 277//277 344//344 -f 344//344 277//277 279//279 -f 344//344 279//279 342//342 -f 342//342 279//279 281//281 -f 342//342 281//281 321//321 -f 321//321 281//281 15//15 -f 321//321 15//15 14//14 -f 351//351 262//262 325//325 -f 325//325 262//262 305//305 -f 325//325 305//305 326//326 -f 326//326 305//305 304//304 -f 326//326 304//304 333//333 -f 333//333 304//304 303//303 -f 333//333 303//303 334//334 -f 334//334 303//303 282//282 -f 334//334 282//282 335//335 -f 335//335 282//282 316//316 -f 335//335 316//316 336//336 -f 336//336 316//316 315//315 -f 336//336 315//315 339//339 -f 339//339 315//315 314//314 -f 339//339 314//314 338//338 -f 338//338 314//314 313//313 -f 338//338 313//313 328//328 -f 328//328 313//313 302//302 -f 328//328 302//302 330//330 -f 330//330 302//302 312//312 -f 330//330 312//312 331//331 -f 331//331 312//312 290//290 -f 331//331 290//290 351//351 -f 351//351 290//290 262//262 -f 367//367 276//276 368//368 -f 368//368 276//276 274//274 -f 368//368 274//274 352//352 -f 352//352 274//274 289//289 -f 352//352 289//289 353//353 -f 353//353 289//289 291//291 -f 353//353 291//291 354//354 -f 354//354 291//291 292//292 -f 354//354 292//292 355//355 -f 355//355 292//292 301//301 -f 355//355 301//301 337//337 -f 337//337 301//301 300//300 -f 337//337 300//300 322//322 -f 322//322 300//300 307//307 -f 322//322 307//307 340//340 -f 340//340 307//307 308//308 -f 340//340 308//308 341//341 -f 341//341 308//308 309//309 -f 341//341 309//309 343//343 -f 343//343 309//309 280//280 -f 343//343 280//280 345//345 -f 345//345 280//280 278//278 -f 345//345 278//278 367//367 -f 367//367 278//278 276//276 -f 375//375 259//259 348//348 -f 348//348 259//259 258//258 -f 348//348 258//258 318//318 -f 318//318 258//258 299//299 -f 318//318 299//299 320//320 -f 320//320 299//299 298//298 -f 320//320 298//298 349//349 -f 349//349 298//298 297//297 -f 349//349 297//297 350//350 -f 350//350 297//297 288//288 -f 350//350 288//288 329//329 -f 329//329 288//288 306//306 -f 329//329 306//306 327//327 -f 327//327 306//306 261//261 -f 327//327 261//261 370//370 -f 370//370 261//261 263//263 -f 370//370 263//263 369//369 -f 369//369 263//263 264//264 -f 369//369 264//264 372//372 -f 372//372 264//264 272//272 -f 372//372 272//272 374//374 -f 374//374 272//272 271//271 -f 374//374 271//271 375//375 -f 375//375 271//271 259//259 -f 360//360 269//269 362//362 -f 362//362 269//269 294//294 -f 362//362 294//294 364//364 -f 364//364 294//294 293//293 -f 364//364 293//293 365//365 -f 365//365 293//293 268//268 -f 365//365 268//268 366//366 -f 366//366 268//268 285//285 -f 366//366 285//285 332//332 -f 332//332 285//285 286//286 -f 332//332 286//286 323//323 -f 323//323 286//286 310//310 -f 323//323 310//310 324//324 -f 324//324 310//310 311//311 -f 324//324 311//311 319//319 -f 319//319 311//311 284//284 -f 319//319 284//284 317//317 -f 317//317 284//284 283//283 -f 317//317 283//283 358//358 -f 358//358 283//283 287//287 -f 358//358 287//287 357//357 -f 357//357 287//287 265//265 -f 357//357 265//265 360//360 -f 360//360 265//265 269//269 -f 255//255 199//199 256//256 -f 256//256 199//199 204//204 -f 253//253 200//200 255//255 -f 255//255 200//200 199//199 -f 251//251 201//201 253//253 -f 253//253 201//201 200//200 -f 250//250 202//202 251//251 -f 251//251 202//202 201//201 -f 249//249 203//203 250//250 -f 250//250 203//203 202//202 -f 256//256 204//204 249//249 -f 249//249 204//204 203//203 -f 189//189 5//5 254//254 -f 254//254 5//5 252//252 -f 233//233 376//376 377//377 -f 233//233 377//377 231//231 -f 231//231 377//377 378//378 -f 231//231 378//378 232//232 -f 232//232 378//378 379//379 -f 232//232 379//379 234//234 -f 234//234 379//379 254//254 -f 234//234 254//254 235//235 -f 233//233 248//248 376//376 -f 376//376 248//248 247//247 -f 376//376 247//247 380//380 -f 380//380 247//247 246//246 -f 380//380 246//246 381//381 -f 381//381 246//246 244//244 -f 381//381 244//244 382//382 -f 382//382 244//244 243//243 -f 382//382 243//243 383//383 -f 383//383 243//243 245//245 -f 383//383 245//245 384//384 -f 384//384 245//245 63//63 -f 384//384 63//63 30//30 -f 384//384 30//30 29//29 -f 384//384 29//29 383//383 -f 189//189 254//254 190//190 -f 190//190 254//254 379//379 -f 190//190 379//379 191//191 -f 191//191 379//379 378//378 -f 191//191 378//378 192//192 -f 192//192 378//378 377//377 -f 192//192 377//377 193//193 -f 193//193 377//377 376//376 -f 193//193 376//376 194//194 -f 194//194 376//376 380//380 -f 194//194 380//380 195//195 -f 195//195 380//380 381//381 -f 195//195 381//381 196//196 -f 196//196 381//381 382//382 -f 196//196 382//382 197//197 -f 197//197 382//382 383//383 -f 197//197 383//383 188//188 -f 188//188 383//383 29//29 -f 385//385 386//386 229//229 -f 387//387 257//257 205//205 -f 387//387 205//205 386//386 -f 386//386 205//205 230//230 -f 386//386 230//230 229//229 -f 385//385 229//229 388//388 -f 388//388 229//229 227//227 -f 388//388 227//227 226//226 -f 242//242 389//389 226//226 -f 226//226 389//389 390//390 -f 226//226 390//390 388//388 -f 236//236 252//252 237//237 -f 237//237 252//252 391//391 -f 237//237 391//391 238//238 -f 238//238 391//391 392//392 -f 238//238 392//392 239//239 -f 239//239 392//392 393//393 -f 239//239 393//393 240//240 -f 240//240 393//393 389//389 -f 240//240 389//389 241//241 -f 241//241 389//389 242//242 -f 388//388 12//12 385//385 -f 385//385 12//12 10//10 -f 385//385 10//10 386//386 -f 386//386 10//10 9//9 -f 386//386 9//9 387//387 -f 387//387 9//9 28//28 -f 387//387 28//28 257//257 -f 392//392 1//1 393//393 -f 393//393 1//1 8//8 -f 393//393 8//8 389//389 -f 389//389 8//8 7//7 -f 389//389 7//7 390//390 -f 390//390 7//7 6//6 -f 390//390 6//6 388//388 -f 388//388 6//6 13//13 -f 388//388 13//13 12//12 -f 252//252 5//5 391//391 -f 391//391 5//5 4//4 -f 391//391 4//4 392//392 -f 392//392 4//4 2//2 -f 392//392 2//2 1//1 -# 818 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper_dodatno.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper_dodatno.obj deleted file mode 100644 index b804ac171..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/gripper_dodatno.obj +++ /dev/null @@ -1,11820 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object gripper_dodatno.obj -# -# Vertices: 2951 -# Faces: 5902 -# -#### -vn -0.671961 -0.000000 -0.740587 -v 0.077190 0.069499 0.217310 -vn -0.644743 -0.189312 -0.740586 -v 0.077088 0.070203 0.217310 -vn 0.135582 0.024200 -0.990470 -v 0.078627 0.070202 0.217310 -vn 0.095630 -0.665122 -0.740586 -v 0.074334 0.071974 0.217310 -vn 0.000000 0.707098 -0.707116 -v 0.074690 0.073499 0.217310 -vn -0.095630 -0.665122 -0.740586 -v 0.075045 0.071974 0.217310 -vn 0.023552 0.135539 -0.990492 -v 0.075368 0.073441 0.217310 -vn -0.279141 -0.611239 -0.740586 -v 0.075728 0.071773 0.217310 -vn -0.440040 -0.507834 -0.740588 -v 0.076327 0.071389 0.217310 -vn 0.105597 0.088152 -0.990494 -v 0.077765 0.072057 0.217310 -vn -0.565291 -0.363287 -0.740587 -v 0.076793 0.070851 0.217310 -vn 0.612367 0.353548 -0.707114 -v 0.078154 0.071499 0.217310 -vn 0.129155 0.047373 -0.990492 -v 0.078443 0.070883 0.217310 -vn 0.440040 -0.507834 -0.740588 -v 0.073052 0.071389 0.217310 -vn -0.068861 0.119273 -0.990471 -v 0.072690 0.072963 0.217310 -vn 0.279141 -0.611239 -0.740586 -v 0.073651 0.071773 0.217310 -vn -0.046835 0.129516 -0.990471 -v 0.073329 0.073261 0.217310 -vn -0.023545 0.135534 -0.990493 -v 0.074012 0.073441 0.217310 -vn 0.440042 0.507835 -0.740586 -v 0.073052 0.067610 0.217310 -vn -0.105597 -0.088152 -0.990494 -v 0.071615 0.066941 0.217310 -vn 0.565288 0.363292 -0.740586 -v 0.072587 0.068148 0.217310 -vn -0.612364 -0.353549 -0.707116 -v 0.071226 0.067499 0.217310 -vn 0.644741 0.189315 -0.740587 -v 0.072291 0.068795 0.217310 -vn -0.095630 0.665122 -0.740586 -v 0.075045 0.067025 0.217310 -vn 0.000233 -0.707094 -0.707120 -v 0.074690 0.065499 0.217310 -vn 0.095630 0.665122 -0.740586 -v 0.074334 0.067025 0.217310 -vn -0.023551 -0.135521 -0.990495 -v 0.074012 0.065557 0.217310 -vn 0.279143 0.611236 -0.740587 -v 0.073651 0.067225 0.217310 -vn 0.046833 0.129517 -0.990471 -v 0.076050 0.073261 0.217310 -vn 0.068862 0.119273 -0.990471 -v 0.076690 0.072963 0.217310 -vn 0.088749 0.105321 -0.990470 -v 0.077267 0.072558 0.217310 -vn 0.671961 0.000000 -0.740587 -v 0.072190 0.069499 0.217310 -vn -0.135587 0.024198 -0.990470 -v 0.070752 0.070202 0.217310 -vn 0.644741 -0.189315 -0.740587 -v 0.072291 0.070203 0.217310 -vn -0.129135 0.047371 -0.990495 -v 0.070937 0.070883 0.217310 -vn 0.565290 -0.363291 -0.740585 -v 0.072587 0.070851 0.217310 -vn -0.046833 -0.129518 -0.990470 -v 0.073329 0.065738 0.217310 -vn -0.068863 -0.119273 -0.990471 -v 0.072690 0.066035 0.217310 -vn -0.088747 -0.105318 -0.990471 -v 0.072112 0.066440 0.217310 -vn -0.565289 0.363289 -0.740587 -v 0.076793 0.068148 0.217310 -vn 0.103571 -0.092640 -0.990298 -v 0.077676 0.066838 0.217310 -vn -0.440042 0.507835 -0.740586 -v 0.076327 0.067610 0.217310 -vn 0.082586 -0.110021 -0.990492 -v 0.077053 0.066272 0.217310 -vn -0.279143 0.611236 -0.740587 -v 0.075728 0.067225 0.217310 -vn 0.054738 -0.126143 -0.990501 -v 0.076326 0.065849 0.217310 -vn 0.029100 -0.136062 -0.990273 -v 0.075526 0.065588 0.217310 -vn 0.137725 -0.000000 -0.990471 -v 0.078690 0.069499 0.217310 -vn 0.135583 -0.024199 -0.990470 -v 0.078627 0.068796 0.217310 -vn -0.644743 0.189312 -0.740586 -v 0.077088 0.068795 0.217310 -vn 0.129151 -0.047376 -0.990493 -v 0.078443 0.068115 0.217310 -vn 0.612266 -0.353713 -0.707119 -v 0.078154 0.067499 0.217310 -vn -0.612365 0.353550 -0.707115 -v 0.071226 0.071499 0.217310 -vn -0.105596 0.088160 -0.990493 -v 0.071615 0.072057 0.217310 -vn -0.088752 0.105319 -0.990470 -v 0.072112 0.072558 0.217310 -vn -0.129143 -0.047366 -0.990494 -v 0.070937 0.068115 0.217310 -vn -0.135587 -0.024202 -0.990470 -v 0.070752 0.068796 0.217310 -vn -0.137724 0.000001 -0.990471 -v 0.070690 0.069499 0.217310 -vn -0.865074 -0.000002 0.501645 -v 0.070071 0.069499 0.226145 -vn -0.865074 -0.000001 -0.501645 -v 0.070071 0.069499 0.217476 -vn -0.709881 -0.339168 0.617279 -v 0.070502 0.068752 0.226242 -vn -0.708458 -0.340361 -0.618257 -v 0.070502 0.068752 0.217378 -vn -0.698960 -0.366136 0.614328 -v 0.070882 0.068095 0.226295 -vn -0.697059 -0.368049 -0.615345 -v 0.070882 0.068095 0.217326 -vn -0.792377 -0.465546 0.394214 -v 0.071226 0.067499 0.226310 -vn -0.667279 -0.419640 -0.615338 -v 0.071570 0.066903 0.217326 -vn -0.666597 -0.423330 0.613547 -v 0.071570 0.066903 0.226295 -vn -0.648989 -0.443361 -0.618259 -v 0.071949 0.066247 0.217378 -vn -0.649891 -0.443458 0.617242 -v 0.071949 0.066247 0.226242 -vn -0.432537 -0.749175 -0.501645 -v 0.072380 0.065499 0.217476 -vn -0.433085 -0.749266 0.501037 -v 0.072380 0.065499 0.226145 -vn -0.059466 -0.783721 -0.618260 -v 0.073243 0.065499 0.217378 -vn -0.060713 -0.784059 0.617710 -v 0.073243 0.065499 0.226242 -vn -0.029789 -0.787692 -0.615349 -v 0.074002 0.065499 0.217326 -vn -0.029789 -0.787692 0.615349 -v 0.074002 0.065499 0.226295 -vn 0.000000 -0.916449 0.400151 -v 0.074690 0.065499 0.226310 -vn 0.036939 -0.786134 -0.616951 -v 0.075545 0.065499 0.217335 -vn 0.025633 -0.789581 0.613111 -v 0.075378 0.065499 0.226295 -vn 0.066944 -0.782756 -0.618718 -v 0.076483 0.065499 0.217413 -vn 0.058877 -0.785311 0.616296 -v 0.076136 0.065499 0.226242 -vn 0.432829 -0.749394 -0.501067 -v 0.076999 0.065499 0.217476 -vn 0.433146 -0.749541 0.500572 -v 0.076999 0.065499 0.226145 -vn 0.650987 -0.442667 0.616653 -v 0.077431 0.066247 0.226242 -vn 0.644842 -0.448785 -0.618684 -v 0.077272 0.065972 0.217410 -vn 0.666604 -0.423324 0.613544 -v 0.077810 0.066903 0.226295 -vn 0.662893 -0.424370 -0.616833 -v 0.077739 0.066781 0.217333 -vn 0.792378 -0.465546 0.394214 -v 0.078154 0.067499 0.226310 -vn 0.697065 -0.368060 -0.615331 -v 0.078498 0.068095 0.217326 -vn 0.698736 -0.368058 0.613434 -v 0.078498 0.068095 0.226295 -vn 0.708456 -0.340360 -0.618259 -v 0.078877 0.068752 0.217378 -vn 0.709972 -0.339044 0.617244 -v 0.078877 0.068752 0.226242 -vn 0.865074 -0.000002 -0.501645 -v 0.079308 0.069499 0.217476 -vn 0.865074 -0.000002 0.501645 -v 0.079308 0.069499 0.226145 -vn 0.709879 0.339173 0.617279 -v 0.078877 0.070247 0.226242 -vn 0.708456 0.340363 -0.618258 -v 0.078877 0.070247 0.217378 -vn 0.698967 0.366139 0.614319 -v 0.078498 0.070903 0.226295 -vn 0.697065 0.368053 -0.615335 -v 0.078498 0.070903 0.217326 -vn 0.792348 0.465598 0.394212 -v 0.078154 0.071499 0.226310 -vn 0.663138 0.427857 0.614156 -v 0.077739 0.072217 0.226288 -vn 0.667277 0.419644 -0.615337 -v 0.077810 0.072095 0.217326 -vn 0.644556 0.450421 0.617793 -v 0.077272 0.073026 0.226211 -vn 0.648987 0.443365 -0.618258 -v 0.077431 0.072752 0.217378 -vn 0.433246 0.749631 0.500351 -v 0.076999 0.073499 0.226145 -vn 0.432537 0.749175 -0.501645 -v 0.076999 0.073499 0.217476 -vn -0.432537 0.749175 -0.501645 -v 0.072380 0.073499 0.217476 -vn -0.433146 0.749542 0.500571 -v 0.072380 0.073499 0.226145 -vn -0.058878 0.785311 0.616295 -v 0.073243 0.073499 0.226242 -vn -0.059469 0.783721 -0.618259 -v 0.073243 0.073499 0.217378 -vn -0.025635 0.789588 0.613101 -v 0.074002 0.073499 0.226295 -vn -0.029782 0.787705 -0.615333 -v 0.074002 0.073499 0.217326 -vn 0.003753 0.915552 0.402183 -v 0.074690 0.073499 0.226310 -vn 0.034105 0.788107 0.614593 -v 0.075545 0.073499 0.226286 -vn 0.029787 0.787704 -0.615334 -v 0.075378 0.073499 0.217326 -vn 0.066719 0.783389 0.617940 -v 0.076483 0.073499 0.226208 -vn 0.059467 0.783721 -0.618260 -v 0.076136 0.073499 0.217378 -vn -0.650992 0.442666 0.616650 -v 0.071949 0.072752 0.226242 -vn -0.648992 0.443360 -0.618257 -v 0.071949 0.072752 0.217378 -vn -0.666603 0.423329 0.613542 -v 0.071570 0.072095 0.226295 -vn -0.667271 0.419647 -0.615342 -v 0.071570 0.072095 0.217326 -vn -0.792378 0.465546 0.394213 -v 0.071226 0.071499 0.226310 -vn -0.697057 0.368059 -0.615341 -v 0.070882 0.070903 0.217326 -vn -0.698728 0.368057 0.613443 -v 0.070882 0.070903 0.226295 -vn -0.708459 0.340358 -0.618257 -v 0.070502 0.070247 0.217378 -vn -0.709975 0.339043 0.617241 -v 0.070502 0.070247 0.226242 -vn 0.977846 0.184731 0.098450 -v 0.072736 0.069069 0.235110 -vn 0.635954 0.206603 -0.743558 -v 0.072788 0.068881 0.220810 -vn 0.668641 0.000000 -0.743585 -v 0.072690 0.069499 0.220810 -vn 0.942437 0.333593 -0.022979 -v 0.072788 0.068881 0.235110 -vn 0.900380 0.425504 0.090896 -v 0.072874 0.068659 0.235110 -vn 0.540545 0.393155 -0.743802 -v 0.073072 0.068324 0.220810 -vn 0.833381 0.546352 0.083518 -v 0.073072 0.068324 0.235110 -vn 0.393180 0.540550 -0.743784 -v 0.073514 0.067881 0.220810 -vn 0.762191 0.639535 0.100299 -v 0.073097 0.068289 0.235110 -vn 0.670824 0.735007 0.098790 -v 0.073395 0.067975 0.235110 -vn 0.345675 0.936137 0.064464 -v 0.074072 0.067597 0.235110 -vn 0.206459 0.635922 -0.743625 -v 0.074072 0.067597 0.220810 -vn 0.466674 0.879570 0.092588 -v 0.073753 0.067732 0.235110 -vn 0.558823 0.829255 0.007261 -v 0.073514 0.067881 0.235110 -vn 0.224160 0.969558 0.098534 -v 0.074155 0.067572 0.235110 -vn 0.094460 0.990640 0.098540 -v 0.074581 0.067502 0.235110 -vn 0.000157 0.668600 -0.743622 -v 0.074690 0.067499 0.220810 -vn -0.282501 0.957938 0.050478 -v 0.075308 0.067597 0.235110 -vn -0.206807 0.635748 -0.743677 -v 0.075308 0.067597 0.220810 -vn -0.152426 0.983809 0.094265 -v 0.075013 0.067525 0.235110 -vn -0.043615 0.998359 0.037112 -v 0.074690 0.067499 0.235110 -vn -0.403446 0.909666 0.098689 -v 0.075430 0.067641 0.235110 -vn -0.519614 0.848691 0.098612 -v 0.075812 0.067844 0.235110 -vn -0.392771 0.540978 -0.743689 -v 0.075865 0.067881 0.220810 -vn -0.800049 0.598479 0.041772 -v 0.076308 0.068324 0.235110 -vn -0.540973 0.392660 -0.743752 -v 0.076308 0.068324 0.220810 -vn -0.710733 0.696888 0.095942 -v 0.076142 0.068124 0.235110 -vn -0.626236 0.776887 0.065381 -v 0.075865 0.067881 0.235110 -vn -0.869095 0.484667 0.098854 -v 0.076403 0.068468 0.235110 -vn -0.925242 0.366311 0.098706 -v 0.076585 0.068861 0.235110 -vn -0.635630 0.206824 -0.743773 -v 0.076592 0.068881 0.220810 -vn -0.962371 0.256615 0.089387 -v 0.076592 0.068881 0.235110 -vn -0.986298 0.132992 0.097621 -v 0.076678 0.069283 0.235110 -vn -0.668677 0.000000 -0.743553 -v 0.076690 0.069499 0.220810 -vn -0.999054 -0.021150 -0.038008 -v 0.076690 0.069499 0.235110 -vn -0.988689 -0.119929 0.090059 -v 0.076678 0.069715 0.235110 -vn -0.635572 -0.206854 -0.743814 -v 0.076592 0.070117 0.220810 -vn -0.961472 -0.258947 0.092289 -v 0.076592 0.070117 0.235110 -vn -0.540965 -0.392596 -0.743791 -v 0.076308 0.070675 0.220810 -vn -0.925471 -0.365274 0.100392 -v 0.076585 0.070138 0.235110 -vn -0.869102 -0.484650 0.098873 -v 0.076403 0.070530 0.235110 -vn -0.790516 -0.612392 -0.007853 -v 0.076308 0.070675 0.235110 -vn -0.720245 -0.687627 0.091738 -v 0.076142 0.070875 0.235110 -vn -0.392590 -0.540965 -0.743795 -v 0.075865 0.071117 0.220810 -vn -0.620888 -0.780355 0.074467 -v 0.075865 0.071117 0.235110 -vn -0.206907 -0.635600 -0.743776 -v 0.075308 0.071401 0.220810 -vn -0.520364 -0.848044 0.100215 -v 0.075812 0.071155 0.235110 -vn -0.403446 -0.909661 0.098731 -v 0.075430 0.071357 0.235110 -vn -0.033634 -0.997816 0.056854 -v 0.074690 0.071499 0.235110 -vn 0.000192 -0.668567 -0.743652 -v 0.074690 0.071499 0.220810 -vn -0.165558 -0.981761 0.093469 -v 0.075013 0.071473 0.235110 -vn -0.271005 -0.962319 0.022331 -v 0.075308 0.071401 0.235110 -vn 0.094529 -0.990627 0.098599 -v 0.074581 0.071496 0.235110 -vn 0.224124 -0.969561 0.098593 -v 0.074155 0.071426 0.235110 -vn 0.206421 -0.635905 -0.743650 -v 0.074072 0.071401 0.220810 -vn 0.570267 -0.820202 0.045442 -v 0.073514 0.071117 0.235110 -vn 0.393149 -0.540671 -0.743713 -v 0.073514 0.071117 0.220810 -vn 0.454792 -0.885504 0.095113 -v 0.073753 0.071266 0.235110 -vn 0.353070 -0.934174 0.051577 -v 0.074072 0.071401 0.235110 -vn 0.670812 -0.735018 0.098792 -v 0.073395 0.071023 0.235110 -vn 0.761635 -0.640450 0.098673 -v 0.073097 0.070709 0.235110 -vn 0.540663 -0.393125 -0.743731 -v 0.073072 0.070675 0.220810 -vn 0.836059 -0.543035 0.078220 -v 0.073072 0.070675 0.235110 -vn 0.894131 -0.437222 0.096782 -v 0.072874 0.070339 0.235110 -vn 0.635955 -0.206601 -0.743557 -v 0.072788 0.070117 0.220810 -vn 0.948129 -0.315414 0.039567 -v 0.072788 0.070117 0.235110 -vn 0.977845 -0.184738 0.098442 -v 0.072736 0.069929 0.235110 -vn 0.995120 0.000001 0.098671 -v 0.072690 0.069499 0.235110 -vn 0.919028 -0.000000 0.394193 -v 0.077690 0.069499 0.227310 -vn 0.487644 0.070987 0.870152 -v 0.078627 0.070202 0.226310 -vn 0.906307 0.164249 0.389398 -v 0.077614 0.070167 0.227310 -vn 0.485655 0.123674 0.865358 -v 0.078589 0.070389 0.226310 -vn 0.880684 0.270379 0.388962 -v 0.077587 0.070276 0.227310 -vn 0.465211 0.166106 0.869475 -v 0.078443 0.070883 0.226310 -vn 0.839967 0.377264 0.390035 -v 0.077393 0.070801 0.227310 -vn 0.547339 0.271894 0.791514 -v 0.078294 0.071235 0.226310 -vn 0.789689 0.475816 0.387285 -v 0.077288 0.070999 0.227310 -vn 0.725807 0.567921 0.388162 -v 0.077035 0.071370 0.227310 -vn 0.424454 0.314214 0.849181 -v 0.077817 0.071993 0.226310 -vn 0.651380 0.653784 0.385059 -v 0.076811 0.071620 0.227310 -vn 0.358490 0.337273 0.870478 -v 0.077676 0.072161 0.226310 -vn 0.570030 0.724588 0.387348 -v 0.076560 0.071845 0.227310 -vn 0.323425 0.377478 0.867702 -v 0.077184 0.072626 0.226310 -vn 0.278839 0.406704 0.869966 -v 0.077053 0.072726 0.226310 -vn 0.474808 0.790036 0.387815 -v 0.076190 0.072097 0.227310 -vn 0.229435 0.437342 0.869535 -v 0.076425 0.073103 0.226310 -vn 0.376797 0.840355 0.389650 -v 0.075991 0.072202 0.227310 -vn 0.183458 0.458497 0.869554 -v 0.076326 0.073149 0.226310 -vn 0.271390 0.880910 0.387744 -v 0.075466 0.072397 0.227310 -vn 0.132899 0.479910 0.867193 -v 0.075580 0.073399 0.226310 -vn 0.163161 0.906929 0.388406 -v 0.075357 0.072424 0.227310 -vn 0.079447 0.486860 0.869859 -v 0.075526 0.073411 0.226310 -vn 0.001309 0.919284 0.393592 -v 0.074690 0.072499 0.227310 -vn -0.069425 0.487769 0.870208 -v 0.074012 0.073441 0.226310 -vn -0.164374 0.906227 0.389529 -v 0.074022 0.072424 0.227310 -vn -0.119518 0.491894 0.862413 -v 0.073800 0.073399 0.226310 -vn -0.270183 0.880878 0.388657 -v 0.073913 0.072397 0.227310 -vn -0.165641 0.464459 0.869966 -v 0.073329 0.073261 0.226310 -vn -0.377537 0.840003 0.389693 -v 0.073388 0.072202 0.227310 -vn -0.212007 0.449064 0.867983 -v 0.072954 0.073103 0.226310 -vn -0.475934 0.789486 0.387556 -v 0.073190 0.072097 0.227310 -vn -0.254412 0.422354 0.869995 -v 0.072690 0.072963 0.226310 -vn -0.567684 0.725853 0.388423 -v 0.072819 0.071845 0.227310 -vn -0.297189 0.395388 0.869107 -v 0.072196 0.072626 0.226310 -vn -0.651595 0.652221 0.387339 -v 0.072568 0.071620 0.227310 -vn -0.330138 0.366426 0.869909 -v 0.072112 0.072558 0.226310 -vn -0.368629 0.330473 0.868850 -v 0.071615 0.072057 0.226310 -vn -0.726040 0.567336 0.388581 -v 0.072344 0.071370 0.227310 -vn -0.408931 0.300190 0.861778 -v 0.071562 0.071993 0.226310 -vn -0.789574 0.475884 0.387437 -v 0.072092 0.070999 0.227310 -vn -0.839992 0.377630 0.389626 -v 0.071987 0.070801 0.227310 -vn -0.547299 0.271873 0.791548 -v 0.071086 0.071235 0.226310 -vn -0.463917 0.167127 0.869971 -v 0.070937 0.070883 0.226310 -vn -0.880950 0.270121 0.388538 -v 0.071792 0.070276 0.227310 -vn -0.485042 0.122735 0.865835 -v 0.070790 0.070389 0.226310 -vn -0.906254 0.164061 0.389601 -v 0.071765 0.070167 0.227310 -vn -0.487644 0.070986 0.870152 -v 0.070752 0.070202 0.226310 -vn -0.918815 -0.000000 0.394689 -v 0.071690 0.069499 0.227310 -vn -0.488933 -0.000001 0.872321 -v 0.070690 0.069499 0.226310 -vn -0.487646 -0.070985 0.870151 -v 0.070752 0.068796 0.226310 -vn -0.906252 -0.164068 0.389602 -v 0.071765 0.068832 0.227310 -vn -0.485657 -0.123679 0.865356 -v 0.070790 0.068609 0.226310 -vn -0.880948 -0.270128 0.388537 -v 0.071792 0.068723 0.227310 -vn -0.465200 -0.166104 0.869482 -v 0.070937 0.068115 0.226310 -vn -0.839992 -0.377630 0.389626 -v 0.071987 0.068198 0.227310 -vn -0.547278 -0.271863 0.791566 -v 0.071086 0.067764 0.226310 -vn -0.789576 -0.475881 0.387436 -v 0.072092 0.067999 0.227310 -vn -0.725905 -0.567392 0.388752 -v 0.072344 0.067629 0.227310 -vn -0.408935 -0.300178 0.861780 -v 0.071562 0.067005 0.226310 -vn -0.368633 -0.330469 0.868850 -v 0.071615 0.066941 0.226310 -vn -0.651802 -0.651694 0.387878 -v 0.072568 0.067378 0.227310 -vn -0.332073 -0.366940 0.868955 -v 0.072112 0.066440 0.226310 -vn -0.567221 -0.725939 0.388938 -v 0.072819 0.067154 0.227310 -vn -0.296928 -0.399381 0.867369 -v 0.072196 0.066372 0.226310 -vn -0.476002 -0.789484 0.387477 -v 0.073190 0.066901 0.227310 -vn -0.255343 -0.422367 0.869716 -v 0.072690 0.066035 0.226310 -vn -0.377496 -0.840057 0.389616 -v 0.073388 0.066796 0.227310 -vn -0.211310 -0.451293 0.866996 -v 0.072954 0.065895 0.226310 -vn -0.167544 -0.465034 0.869294 -v 0.073329 0.065738 0.226310 -vn -0.270182 -0.880879 0.388657 -v 0.073913 0.066601 0.227310 -vn -0.117715 -0.501949 0.856849 -v 0.073800 0.065599 0.226310 -vn -0.164374 -0.906228 0.389528 -v 0.074022 0.066574 0.227310 -vn -0.073248 -0.489319 0.869023 -v 0.074012 0.065557 0.226310 -vn 0.000175 -0.918795 0.394734 -v 0.074690 0.066499 0.227310 -vn 0.069427 -0.487758 0.870214 -v 0.075368 0.065557 0.226310 -vn 0.164182 -0.906160 0.389767 -v 0.075357 0.066574 0.227310 -vn 0.119517 -0.491889 0.862416 -v 0.075580 0.065599 0.226310 -vn 0.270205 -0.880850 0.388707 -v 0.075466 0.066601 0.227310 -vn 0.165639 -0.464460 0.869966 -v 0.076050 0.065738 0.226310 -vn 0.377508 -0.840009 0.389709 -v 0.075991 0.066796 0.227310 -vn 0.212007 -0.449064 0.867983 -v 0.076425 0.065895 0.226310 -vn 0.475796 -0.789723 0.387241 -v 0.076190 0.066901 0.227310 -vn 0.254414 -0.422353 0.869995 -v 0.076690 0.066035 0.226310 -vn 0.567947 -0.725801 0.388135 -v 0.076560 0.067154 0.227310 -vn 0.297191 -0.395387 0.869107 -v 0.077184 0.066372 0.226310 -vn 0.651736 -0.651740 0.387912 -v 0.076811 0.067378 0.227310 -vn 0.330135 -0.366428 0.869909 -v 0.077267 0.066440 0.226310 -vn 0.368640 -0.330447 0.868855 -v 0.077765 0.066941 0.226310 -vn 0.725593 -0.567439 0.389266 -v 0.077035 0.067629 0.227310 -vn 0.408935 -0.300165 0.861785 -v 0.077817 0.067005 0.226310 -vn 0.789488 -0.475931 0.387555 -v 0.077288 0.067999 0.227310 -vn 0.839963 -0.377199 0.390107 -v 0.077393 0.068198 0.227310 -vn 0.547318 -0.271884 0.791531 -v 0.078294 0.067764 0.226310 -vn 0.463929 -0.167130 0.869964 -v 0.078443 0.068115 0.226310 -vn 0.880633 -0.270432 0.389040 -v 0.077587 0.068723 0.227310 -vn 0.485043 -0.122734 0.865835 -v 0.078589 0.068609 0.226310 -vn 0.906305 -0.164256 0.389398 -v 0.077614 0.068832 0.227310 -vn 0.487644 -0.070988 0.870152 -v 0.078627 0.068796 0.226310 -vn 0.488932 0.000000 0.872322 -v 0.078690 0.069499 0.226310 -vn -0.983220 0.153679 -0.098287 -v 0.071738 0.070035 0.233110 -vn -0.964034 0.263531 -0.034501 -v 0.071792 0.070276 0.233110 -vn -0.925788 0.365120 -0.098003 -v 0.071881 0.070553 0.233110 -vn -0.883363 0.461242 -0.083221 -v 0.072092 0.070999 0.233110 -vn -0.832669 0.545050 -0.097888 -v 0.072114 0.071038 0.233110 -vn -0.767428 0.633603 -0.097993 -v 0.072430 0.071473 0.233110 -vn -0.686652 0.726963 0.005859 -v 0.072568 0.071620 0.233110 -vn -0.619454 0.779484 -0.093172 -v 0.072819 0.071845 0.233110 -vn -0.530272 0.845142 -0.067430 -v 0.073190 0.072097 0.233110 -vn -0.438731 0.893251 -0.098072 -v 0.073268 0.072141 0.233110 -vn -0.337331 0.936277 -0.097944 -v 0.073763 0.072352 0.233110 -vn -0.225238 0.974101 -0.019898 -v 0.073913 0.072397 0.233110 -vn -0.137549 0.986008 -0.094170 -v 0.074287 0.072472 0.233110 -vn -0.028762 0.998175 -0.053090 -v 0.074690 0.072499 0.233110 -vn 0.078187 0.992079 -0.098314 -v 0.074824 0.072496 0.233110 -vn 0.186728 0.977484 -0.098271 -v 0.075357 0.072424 0.233110 -vn 0.297349 0.953650 -0.046205 -v 0.075466 0.072397 0.233110 -vn 0.381798 0.919242 -0.096040 -v 0.075869 0.072258 0.233110 -vn 0.482480 0.874870 -0.042611 -v 0.076190 0.072097 0.233110 -vn 0.572670 0.813927 -0.097836 -v 0.076342 0.072003 0.233110 -vn 0.659151 0.745632 -0.097740 -v 0.076763 0.071668 0.233110 -vn 0.735588 0.673838 -0.069659 -v 0.076811 0.071620 0.233110 -vn 0.796085 0.597469 -0.096331 -v 0.077117 0.071263 0.233110 -vn 0.860464 0.508224 -0.036194 -v 0.077288 0.070999 0.233110 -vn 0.907641 0.408063 -0.098349 -v 0.077393 0.070801 0.233110 -vn 0.946962 0.305972 -0.098208 -v 0.077582 0.070297 0.233110 -vn 0.972598 0.214257 -0.090268 -v 0.077587 0.070276 0.233110 -vn 0.989100 0.110306 -0.097537 -v 0.077678 0.069768 0.233110 -vn 0.999420 -0.000000 -0.034066 -v 0.077690 0.069499 0.233110 -vn 0.989137 -0.109451 -0.098129 -v 0.077678 0.069230 0.233110 -vn 0.971816 -0.216529 -0.093209 -v 0.077587 0.068723 0.233110 -vn 0.947166 -0.304593 -0.100495 -v 0.077582 0.068701 0.233110 -vn 0.907640 -0.408061 -0.098369 -v 0.077393 0.068198 0.233110 -vn 0.852848 -0.521831 0.018501 -v 0.077288 0.067999 0.233110 -vn 0.802972 -0.588718 -0.092990 -v 0.077117 0.067736 0.233110 -vn 0.732516 -0.676502 -0.075925 -v 0.076811 0.067378 0.233110 -vn 0.078186 -0.992079 -0.098315 -v 0.074824 0.066502 0.233110 -vn 0.659388 -0.745335 -0.098401 -v 0.076763 0.067331 0.233110 -vn 0.572685 -0.813912 -0.097873 -v 0.076342 0.066995 0.233110 -vn 0.472437 -0.881337 -0.006955 -v 0.076190 0.066901 0.233110 -vn 0.392271 -0.915083 -0.093529 -v 0.075869 0.066741 0.233110 -vn 0.290068 -0.955139 -0.059749 -v 0.075466 0.066601 0.233110 -vn 0.186729 -0.977484 -0.098272 -v 0.075357 0.066574 0.233110 -vn -0.037513 -0.998751 -0.033008 -v 0.074690 0.066499 0.233110 -vn -0.126576 -0.987421 -0.094752 -v 0.074287 0.066526 0.233110 -vn -0.235151 -0.970816 -0.047120 -v 0.073913 0.066601 0.233110 -vn -0.337337 -0.936275 -0.097943 -v 0.073763 0.066646 0.233110 -vn -0.438586 -0.893342 -0.097894 -v 0.073268 0.066857 0.233110 -vn -0.535255 -0.842692 -0.058071 -v 0.073190 0.066901 0.233110 -vn -0.610588 -0.786104 -0.096040 -v 0.072819 0.067154 0.233110 -vn -0.696175 -0.716802 -0.039174 -v 0.072568 0.067378 0.233110 -vn -0.767275 -0.633742 -0.098285 -v 0.072430 0.067525 0.233110 -vn -0.832671 -0.545049 -0.097886 -v 0.072114 0.067960 0.233110 -vn -0.884622 -0.459292 -0.080592 -v 0.072092 0.067999 0.233110 -vn -0.925269 -0.366743 -0.096833 -v 0.071881 0.068445 0.233110 -vn -0.964035 -0.263527 -0.034506 -v 0.071792 0.068723 0.233110 -vn -0.983221 -0.153676 -0.098285 -v 0.071738 0.068963 0.233110 -vn -0.995129 -0.000004 -0.098582 -v 0.071690 0.069499 0.233110 -vn -0.791174 -0.479205 -0.380009 -v 0.072101 0.067953 0.233187 -vn -0.431094 -0.819223 -0.378195 -v 0.073261 0.066844 0.233187 -vn 0.051089 -0.924339 -0.378136 -v 0.074825 0.066487 0.233187 -vn 0.517778 -0.767114 -0.378737 -v 0.076351 0.066983 0.233187 -vn 0.837381 -0.393375 -0.379537 -v 0.077406 0.068191 0.233187 -vn 0.889869 0.248752 -0.382433 -v 0.077596 0.070301 0.233187 -vn 0.634207 0.674044 -0.378742 -v 0.076773 0.071679 0.233187 -vn 0.196975 0.904590 -0.378045 -v 0.075361 0.072439 0.233187 -vn -0.295187 0.877306 -0.378417 -v 0.073758 0.072367 0.233187 -vn -0.702908 0.601816 -0.379128 -v 0.072419 0.071483 0.233187 -vn -0.367103 0.066620 -0.927792 -v 0.071616 0.070057 0.233295 -vn -0.349287 0.131088 -0.927801 -v 0.071765 0.070597 0.233295 -vn -0.656669 0.246451 -0.712774 -v 0.071826 0.070574 0.233252 -vn -0.086601 -0.032501 -0.995713 -v 0.071694 0.068375 0.233310 -vn -0.091003 -0.016514 -0.995714 -v 0.071541 0.068928 0.233310 -vn -0.367105 -0.066618 -0.927791 -v 0.071616 0.068941 0.233295 -vn -0.079407 -0.047443 -0.995713 -v 0.071943 0.067858 0.233310 -vn -0.349291 -0.131091 -0.927799 -v 0.071765 0.068402 0.233295 -vn -0.069657 -0.060857 -0.995713 -v 0.072280 0.067394 0.233310 -vn -0.320278 -0.191358 -0.927796 -v 0.072008 0.067897 0.233295 -vn -0.057665 -0.072311 -0.995714 -v 0.072694 0.066997 0.233310 -vn -0.280963 -0.245473 -0.927795 -v 0.072337 0.067444 0.233295 -vn -0.043829 -0.081448 -0.995713 -v 0.073173 0.066681 0.233310 -vn -0.232629 -0.291706 -0.927789 -v 0.072742 0.067057 0.233295 -vn -0.028584 -0.087973 -0.995713 -v 0.073701 0.066456 0.233310 -vn -0.176796 -0.328544 -0.927794 -v 0.073210 0.066749 0.233295 -vn -0.012417 -0.091661 -0.995713 -v 0.074260 0.066328 0.233310 -vn -0.115288 -0.354824 -0.927798 -v 0.073724 0.066529 0.233295 -vn 0.004150 -0.092402 -0.995713 -v 0.074833 0.066302 0.233310 -vn -0.050081 -0.369712 -0.927796 -v 0.074270 0.066404 0.233295 -vn 0.020582 -0.090174 -0.995713 -v 0.075402 0.066379 0.233310 -vn 0.016739 -0.372711 -0.927797 -v 0.074830 0.066379 0.233295 -vn 0.036351 -0.085047 -0.995714 -v 0.075947 0.066557 0.233310 -vn 0.083021 -0.363739 -0.927794 -v 0.075385 0.066454 0.233295 -vn 0.050955 -0.077194 -0.995713 -v 0.076453 0.066829 0.233310 -vn 0.146632 -0.343066 -0.927796 -v 0.075917 0.066627 0.233295 -vn 0.063918 -0.066853 -0.995713 -v 0.076901 0.067186 0.233310 -vn 0.205531 -0.311367 -0.927797 -v 0.076410 0.066892 0.233295 -vn 0.074827 -0.054365 -0.995714 -v 0.077278 0.067618 0.233310 -vn 0.257823 -0.269664 -0.927798 -v 0.076848 0.067242 0.233295 -vn 0.083336 -0.040133 -0.995713 -v 0.077573 0.068111 0.233310 -vn 0.301837 -0.219299 -0.927795 -v 0.077217 0.067663 0.233295 -vn 0.089155 -0.024604 -0.995714 -v 0.077774 0.068648 0.233310 -vn 0.336134 -0.161871 -0.927799 -v 0.077504 0.068144 0.233295 -vn 0.092123 -0.008291 -0.995713 -v 0.077877 0.069212 0.233310 -vn 0.359633 -0.099252 -0.927800 -v 0.077701 0.068668 0.233295 -vn 0.092123 0.008291 -0.995713 -v 0.077877 0.069786 0.233310 -vn 0.371600 -0.033446 -0.927790 -v 0.077801 0.069219 0.233295 -vn 0.089155 0.024605 -0.995714 -v 0.077774 0.070350 0.233310 -vn 0.371602 0.033443 -0.927789 -v 0.077801 0.069779 0.233295 -vn 0.083336 0.040132 -0.995713 -v 0.077573 0.070888 0.233310 -vn 0.359634 0.099253 -0.927800 -v 0.077701 0.070330 0.233295 -vn 0.074827 0.054365 -0.995713 -v 0.077278 0.071380 0.233310 -vn 0.336123 0.161869 -0.927804 -v 0.077504 0.070854 0.233295 -vn 0.063919 0.066853 -0.995713 -v 0.076901 0.071812 0.233310 -vn 0.301837 0.219298 -0.927795 -v 0.077217 0.071335 0.233295 -vn 0.050951 0.077188 -0.995714 -v 0.076453 0.072170 0.233310 -vn 0.257836 0.269674 -0.927791 -v 0.076848 0.071757 0.233295 -vn 0.036352 0.085048 -0.995714 -v 0.075947 0.072442 0.233310 -vn 0.205526 0.311362 -0.927800 -v 0.076410 0.072106 0.233295 -vn 0.020582 0.090173 -0.995713 -v 0.075402 0.072619 0.233310 -vn 0.146644 0.343083 -0.927787 -v 0.075917 0.072371 0.233295 -vn 0.004150 0.092403 -0.995713 -v 0.074833 0.072696 0.233310 -vn 0.083014 0.363719 -0.927803 -v 0.075385 0.072544 0.233295 -vn -0.012415 0.091653 -0.995714 -v 0.074260 0.072670 0.233310 -vn 0.016738 0.372711 -0.927797 -v 0.074830 0.072619 0.233295 -vn -0.028582 0.087965 -0.995713 -v 0.073701 0.072543 0.233310 -vn -0.050080 0.369704 -0.927799 -v 0.074270 0.072594 0.233295 -vn -0.043830 0.081448 -0.995713 -v 0.073173 0.072317 0.233310 -vn -0.115293 0.354836 -0.927793 -v 0.073724 0.072470 0.233295 -vn -0.057670 0.072316 -0.995713 -v 0.072694 0.072001 0.233310 -vn -0.176796 0.328543 -0.927794 -v 0.073210 0.072250 0.233295 -vn -0.069653 0.060854 -0.995714 -v 0.072280 0.071605 0.233310 -vn -0.232619 0.291699 -0.927793 -v 0.072742 0.071941 0.233295 -vn -0.079403 0.047441 -0.995713 -v 0.071943 0.071140 0.233310 -vn -0.280961 0.245469 -0.927796 -v 0.072337 0.071554 0.233295 -vn -0.086598 0.032501 -0.995713 -v 0.071694 0.070624 0.233310 -vn -0.091003 0.016514 -0.995714 -v 0.071541 0.070071 0.233310 -vn -0.092490 -0.000000 -0.995714 -v 0.071490 0.069499 0.233310 -vn -0.373099 -0.000000 -0.927791 -v 0.071566 0.069499 0.233295 -vn -0.790790 0.480202 -0.379549 -v 0.072101 0.071046 0.233187 -vn -0.602132 0.359756 -0.712750 -v 0.072064 0.071068 0.233252 -vn -0.320274 0.191356 -0.927797 -v 0.072008 0.071101 0.233295 -vn -0.690135 -0.125241 -0.712761 -v 0.071680 0.068953 0.233252 -vn -0.701420 0.000001 -0.712748 -v 0.071631 0.069499 0.233252 -vn -0.690136 0.125242 -0.712760 -v 0.071680 0.070045 0.233252 -vn -0.911839 -0.155805 -0.379834 -v 0.071723 0.068961 0.233187 -vn -0.922201 -0.000003 -0.386711 -v 0.071674 0.069499 0.233187 -vn -0.911840 0.155807 -0.379831 -v 0.071723 0.070038 0.233187 -vn -0.863722 0.331318 -0.379754 -v 0.071867 0.070559 0.233187 -vn -0.528219 0.461491 -0.712749 -v 0.072386 0.071512 0.233252 -vn -0.437322 0.548380 -0.712762 -v 0.072783 0.071890 0.233252 -vn -0.578062 0.719703 -0.384542 -v 0.072810 0.071857 0.233187 -vn -0.430000 0.819995 -0.377767 -v 0.073261 0.072154 0.233187 -vn -0.332377 0.617656 -0.712760 -v 0.073240 0.072193 0.233252 -vn -0.216744 0.667060 -0.712778 -v 0.073744 0.072408 0.233252 -vn -0.094150 0.695067 -0.712753 -v 0.074279 0.072530 0.233252 -vn -0.128702 0.914552 -0.383444 -v 0.074285 0.072487 0.233187 -vn 0.052432 0.924393 -0.377821 -v 0.074825 0.072511 0.233187 -vn 0.031467 0.700703 -0.712759 -v 0.074827 0.072555 0.233252 -vn 0.156071 0.683811 -0.712772 -v 0.075370 0.072481 0.233252 -vn 0.275679 0.644975 -0.712747 -v 0.075892 0.072312 0.233252 -vn 0.357379 0.852079 -0.382415 -v 0.075875 0.072272 0.233187 -vn 0.518873 0.766511 -0.378459 -v 0.076351 0.072016 0.233187 -vn 0.386411 0.585389 -0.712746 -v 0.076375 0.072052 0.233252 -vn 0.484712 0.506973 -0.712764 -v 0.076803 0.071710 0.233252 -vn 0.567456 0.412276 -0.712756 -v 0.077164 0.071297 0.233252 -vn 0.743345 0.549560 -0.381341 -v 0.077129 0.071271 0.233187 -vn 0.837938 0.392394 -0.379325 -v 0.077406 0.070807 0.233187 -vn 0.631946 0.304328 -0.712762 -v 0.077445 0.070826 0.233252 -vn 0.676134 0.186602 -0.712757 -v 0.077638 0.070313 0.233252 -vn 0.698583 0.062878 -0.712761 -v 0.077736 0.069773 0.233252 -vn 0.920280 0.091815 -0.380334 -v 0.077693 0.069769 0.233187 -vn 0.920582 -0.091023 -0.379795 -v 0.077693 0.069229 0.233187 -vn 0.698585 -0.062874 -0.712759 -v 0.077736 0.069225 0.233252 -vn 0.889822 -0.249431 -0.382100 -v 0.077596 0.068697 0.233187 -vn 0.676136 -0.186603 -0.712755 -v 0.077638 0.068685 0.233252 -vn 0.631951 -0.304333 -0.712755 -v 0.077445 0.068172 0.233252 -vn 0.567440 -0.412269 -0.712774 -v 0.077164 0.067701 0.233252 -vn 0.748055 -0.540489 -0.385079 -v 0.077129 0.067727 0.233187 -vn 0.633419 -0.675032 -0.378302 -v 0.076773 0.067320 0.233187 -vn 0.484708 -0.506961 -0.712776 -v 0.076803 0.067288 0.233252 -vn 0.386408 -0.585389 -0.712747 -v 0.076375 0.066947 0.233252 -vn 0.275673 -0.644959 -0.712764 -v 0.075892 0.066687 0.233252 -vn 0.366580 -0.847457 -0.383974 -v 0.075875 0.066727 0.233187 -vn 0.195687 -0.905019 -0.377688 -v 0.075361 0.066560 0.233187 -vn 0.156080 -0.683829 -0.712753 -v 0.075370 0.066517 0.233252 -vn 0.031468 -0.700704 -0.712758 -v 0.074827 0.066444 0.233252 -vn -0.094155 -0.695065 -0.712754 -v 0.074279 0.066468 0.233252 -vn -0.118520 -0.916151 -0.382909 -v 0.074285 0.066511 0.233187 -vn -0.296457 -0.877012 -0.378104 -v 0.073758 0.066632 0.233187 -vn -0.216744 -0.667067 -0.712772 -v 0.073744 0.066590 0.233252 -vn -0.332378 -0.617654 -0.712761 -v 0.073240 0.066806 0.233252 -vn -0.437317 -0.548377 -0.712767 -v 0.072783 0.067108 0.233252 -vn -0.570758 -0.726914 -0.381880 -v 0.072810 0.067142 0.233187 -vn -0.703751 -0.600969 -0.378908 -v 0.072419 0.067515 0.233187 -vn -0.528206 -0.461481 -0.712764 -v 0.072386 0.067487 0.233252 -vn -0.602120 -0.359749 -0.712764 -v 0.072064 0.067930 0.233252 -vn -0.656666 -0.246453 -0.712777 -v 0.071826 0.068424 0.233252 -vn -0.862722 -0.332680 -0.380834 -v 0.071867 0.068440 0.233187 -vn -0.080421 0.083727 -0.993238 -v 0.072196 0.072095 0.233310 -vn -0.065948 0.095543 -0.993238 -v 0.072645 0.072462 0.233310 -vn -0.049772 0.104892 -0.993237 -v 0.073146 0.072752 0.233310 -vn -0.032298 0.111511 -0.993238 -v 0.073688 0.072957 0.233310 -vn -0.013995 0.115252 -0.993238 -v 0.074256 0.073073 0.233310 -vn 0.004675 0.116000 -0.993238 -v 0.074835 0.073096 0.233310 -vn 0.023221 0.113746 -0.993238 -v 0.075410 0.073026 0.233310 -vn 0.041167 0.108549 -0.993238 -v 0.075966 0.072865 0.233310 -vn 0.058050 0.100545 -0.993238 -v 0.076490 0.072617 0.233310 -vn -0.092814 -0.069746 -0.993238 -v 0.071812 0.067336 0.233310 -vn -0.102797 -0.053953 -0.993238 -v 0.071502 0.067826 0.233310 -vn -0.110125 -0.036766 -0.993238 -v 0.071275 0.068359 0.233310 -vn -0.114594 -0.018623 -0.993238 -v 0.071136 0.068922 0.233310 -vn -0.116097 -0.000000 -0.993238 -v 0.071090 0.069499 0.233310 -vn -0.114593 0.018622 -0.993238 -v 0.071136 0.070077 0.233310 -vn -0.110122 0.036764 -0.993238 -v 0.071275 0.070639 0.233310 -vn -0.102793 0.053950 -0.993239 -v 0.071502 0.071172 0.233310 -vn -0.092810 0.069742 -0.993238 -v 0.071812 0.071662 0.233310 -vn 0.073422 -0.089926 -0.993239 -v 0.076966 0.066711 0.233310 -vn 0.058050 -0.100544 -0.993238 -v 0.076490 0.066381 0.233310 -vn 0.041170 -0.108557 -0.993237 -v 0.075966 0.066133 0.233310 -vn 0.023224 -0.113755 -0.993237 -v 0.075410 0.065972 0.233310 -vn 0.004675 -0.116000 -0.993238 -v 0.074835 0.065902 0.233310 -vn -0.013994 -0.115253 -0.993238 -v 0.074256 0.065925 0.233310 -vn -0.032299 -0.111510 -0.993238 -v 0.073688 0.066041 0.233310 -vn -0.049769 -0.104884 -0.993238 -v 0.073146 0.066247 0.233310 -vn -0.065948 -0.095542 -0.993238 -v 0.072645 0.066536 0.233310 -vn -0.080421 -0.083727 -0.993238 -v 0.072196 0.066903 0.233310 -vn 0.073427 0.089931 -0.993238 -v 0.076966 0.072288 0.233310 -vn 0.086900 0.076986 -0.993238 -v 0.077384 0.071886 0.233310 -vn 0.098125 0.062051 -0.993238 -v 0.077732 0.071423 0.233310 -vn 0.106803 0.045504 -0.993238 -v 0.078002 0.070910 0.233310 -vn 0.112721 0.027783 -0.993238 -v 0.078185 0.070361 0.233310 -vn 0.115718 0.009342 -0.993238 -v 0.078278 0.069789 0.233310 -vn 0.115718 -0.009342 -0.993238 -v 0.078278 0.069209 0.233310 -vn 0.112721 -0.027783 -0.993238 -v 0.078185 0.068638 0.233310 -vn 0.106803 -0.045505 -0.993238 -v 0.078002 0.068088 0.233310 -vn 0.098126 -0.062051 -0.993238 -v 0.077732 0.067575 0.233310 -vn 0.086900 -0.076987 -0.993238 -v 0.077384 0.067112 0.233310 -vn -0.770636 0.477884 0.421601 -v 0.071548 0.071565 0.233630 -vn -0.780134 0.595849 0.190671 -v 0.071655 0.071780 0.233550 -vn -0.765914 0.401145 0.502452 -v 0.071360 0.071247 0.233630 -vn -0.867148 0.458170 0.195281 -v 0.071328 0.071263 0.233550 -vn -0.812110 0.326900 0.483336 -v 0.071156 0.070785 0.233630 -vn -0.933977 0.303025 0.189374 -v 0.071089 0.070701 0.233550 -vn -0.826864 0.246083 0.505706 -v 0.071123 0.070690 0.233630 -vn -0.967778 0.165483 0.189790 -v 0.070943 0.070108 0.233550 -vn -0.847320 0.162589 0.505582 -v 0.070978 0.070102 0.233630 -vn -0.677087 0.534755 0.505559 -v 0.071684 0.071758 0.233630 -vn -0.620462 0.599295 0.505838 -v 0.072085 0.072211 0.233630 -vn -0.682697 0.704970 0.192202 -v 0.072060 0.072237 0.233550 -vn -0.569083 0.653077 0.499635 -v 0.072109 0.072234 0.233630 -vn -0.563033 0.804056 0.191018 -v 0.072533 0.072623 0.233550 -vn -0.502140 0.700929 0.506511 -v 0.072554 0.072594 0.233630 -vn -0.444743 0.769657 0.458074 -v 0.072810 0.072755 0.233630 -vn -0.413935 0.889909 0.191626 -v 0.073062 0.072929 0.233550 -vn -0.355395 0.786472 0.505130 -v 0.073078 0.072896 0.233630 -vn -0.269817 0.943464 0.192548 -v 0.073634 0.073145 0.233550 -vn -0.282160 0.819874 0.498190 -v 0.073611 0.073101 0.233630 -vn -0.208783 0.836997 0.505812 -v 0.073644 0.073111 0.233630 -vn -0.124037 0.853423 0.506245 -v 0.074236 0.073232 0.233630 -vn -0.126939 0.973445 0.190505 -v 0.074232 0.073267 0.233550 -vn -0.041367 0.886287 0.461285 -v 0.074471 0.073253 0.233630 -vn 0.045569 0.980180 0.192795 -v 0.074842 0.073292 0.233550 -vn 0.045234 0.862371 0.504252 -v 0.074841 0.073256 0.233630 -vn 0.203446 0.960539 0.189670 -v 0.075449 0.073218 0.233550 -vn 0.118965 0.871287 0.476138 -v 0.075343 0.073202 0.233630 -vn 0.200313 0.839125 0.505711 -v 0.075442 0.073183 0.233630 -vn 0.283274 0.814339 0.506564 -v 0.076023 0.073015 0.233630 -vn 0.339550 0.921289 0.189560 -v 0.076036 0.073048 0.233550 -vn 0.368018 0.802103 0.470312 -v 0.076179 0.072952 0.233630 -vn 0.494331 0.847338 0.194048 -v 0.076588 0.072787 0.233550 -vn 0.436249 0.745863 0.503364 -v 0.076570 0.072755 0.233630 -vn 0.627197 0.755375 0.189823 -v 0.077090 0.072440 0.233550 -vn 0.508979 0.733853 0.449889 -v 0.076935 0.072515 0.233630 -vn 0.564454 0.652488 0.505619 -v 0.077068 0.072412 0.233630 -vn 0.626543 0.593049 0.505704 -v 0.077504 0.071992 0.233630 -vn 0.729423 0.657341 0.189328 -v 0.077531 0.072016 0.233550 -vn 0.689157 0.539862 0.483334 -v 0.077570 0.071916 0.233630 -vn 0.830367 0.521882 0.195267 -v 0.077898 0.071528 0.233550 -vn 0.730345 0.462716 0.502484 -v 0.077868 0.071509 0.233630 -vn 0.906091 0.377691 0.190652 -v 0.078182 0.070987 0.233550 -vn 0.799178 0.428450 0.421599 -v 0.078050 0.071187 0.233630 -vn 0.801649 0.318992 0.505572 -v 0.078149 0.070973 0.233630 -vn 0.829256 0.237632 0.505832 -v 0.078340 0.070399 0.233630 -vn 0.951870 0.238741 0.192213 -v 0.078375 0.070408 0.233550 -vn 0.850128 0.166252 0.499643 -v 0.078348 0.070366 0.233630 -vn 0.977855 0.085572 0.190988 -v 0.078473 0.069805 0.233550 -vn 0.858101 0.084402 0.506496 -v 0.078437 0.069802 0.233630 -vn 0.888915 0.000330 0.458072 -v 0.078450 0.069499 0.233630 -vn 0.977655 -0.086470 0.191607 -v 0.078473 0.069194 0.233550 -vn 0.858809 -0.085452 0.505119 -v 0.078437 0.069197 0.233630 -vn 0.951973 -0.238055 0.192554 -v 0.078375 0.068591 0.233550 -vn 0.851104 -0.165535 0.498217 -v 0.078348 0.068632 0.233630 -vn 0.829260 -0.237636 0.505823 -v 0.078340 0.068599 0.233630 -vn 0.801099 -0.319296 0.506252 -v 0.078149 0.068025 0.233630 -vn 0.906501 -0.376794 0.190481 -v 0.078182 0.068011 0.233550 -vn 0.788225 -0.407318 0.461296 -v 0.078050 0.067812 0.233630 -vn 0.826078 -0.529555 0.192784 -v 0.077898 0.067470 0.233550 -vn 0.724210 -0.470359 0.504264 -v 0.077868 0.067490 0.233630 -vn 0.730128 -0.656453 0.189688 -v 0.077531 0.066982 0.233550 -vn 0.695079 -0.538679 0.476120 -v 0.077570 0.067082 0.233630 -vn 0.626545 -0.593047 0.505704 -v 0.077504 0.067006 0.233630 -vn 0.563603 -0.652516 0.506533 -v 0.077068 0.066587 0.233630 -vn 0.628082 -0.754698 0.189590 -v 0.077090 0.066559 0.233550 -vn 0.510631 -0.719766 0.470311 -v 0.076935 0.066483 0.233630 -vn 0.486646 -0.851775 0.194051 -v 0.076588 0.066212 0.233550 -vn 0.427814 -0.750733 0.503363 -v 0.076570 0.066243 0.233630 -vn 0.340575 -0.920860 0.189806 -v 0.076036 0.065950 0.233550 -vn 0.381049 -0.807728 0.449864 -v 0.076179 0.066047 0.233630 -vn 0.282848 -0.815089 0.505596 -v 0.076023 0.065983 0.233630 -vn 0.200317 -0.839143 0.505679 -v 0.075442 0.065815 0.233630 -vn 0.204561 -0.960368 0.189337 -v 0.075449 0.065780 0.233550 -vn 0.122948 -0.866773 0.483311 -v 0.075343 0.065796 0.233630 -vn 0.036788 -0.980054 0.195298 -v 0.074842 0.065706 0.233550 -vn 0.035556 -0.863874 0.502452 -v 0.074841 0.065742 0.233630 -vn -0.125953 -0.973539 0.190677 -v 0.074232 0.065731 0.233550 -vn -0.028539 -0.906342 0.421581 -v 0.074471 0.065746 0.233630 -vn -0.124573 -0.853748 0.505565 -v 0.074236 0.065767 0.233630 -vn -0.208873 -0.836975 0.505812 -v 0.073644 0.065888 0.233630 -vn -0.269182 -0.943712 0.192221 -v 0.073634 0.065853 0.233550 -vn -0.281114 -0.819354 0.499634 -v 0.073611 0.065897 0.233630 -vn -0.414819 -0.889638 0.190970 -v 0.073062 0.066070 0.233550 -vn -0.355949 -0.785334 0.506509 -v 0.073078 0.066102 0.233630 -vn -0.444172 -0.769987 0.458075 -v 0.072810 0.066243 0.233630 -vn -0.563716 -0.803438 0.191605 -v 0.072533 0.066375 0.233550 -vn -0.503409 -0.701013 0.505133 -v 0.072554 0.066405 0.233630 -vn -0.682151 -0.705402 0.192554 -v 0.072060 0.066761 0.233550 -vn -0.568906 -0.654322 0.498206 -v 0.072109 0.066764 0.233630 -vn -0.620423 -0.599356 0.505814 -v 0.072085 0.066787 0.233630 -vn -0.677089 -0.534127 0.506221 -v 0.071684 0.067240 0.233630 -vn -0.779563 -0.596650 0.190501 -v 0.071655 0.067219 0.233550 -vn -0.746867 -0.478959 0.461289 -v 0.071548 0.067433 0.233630 -vn -0.871643 -0.450623 0.192816 -v 0.071328 0.067735 0.233550 -vn -0.769447 -0.392005 0.504266 -v 0.071360 0.067752 0.233630 -vn -0.933564 -0.304085 0.189711 -v 0.071089 0.068297 0.233550 -vn -0.814036 -0.332622 0.476139 -v 0.071156 0.068213 0.233630 -vn -0.826860 -0.246095 0.505707 -v 0.071123 0.068308 0.233630 -vn -0.846901 -0.161846 0.506522 -v 0.070978 0.068896 0.233630 -vn -0.967638 -0.166586 0.189542 -v 0.070943 0.068890 0.233550 -vn -0.878664 -0.082342 0.470287 -v 0.070955 0.069063 0.233630 -vn -0.980986 0.004440 0.194028 -v 0.070894 0.069499 0.233550 -vn -0.864063 0.004873 0.503360 -v 0.070930 0.069499 0.233630 -vn -0.890038 0.073864 0.449863 -v 0.070955 0.069936 0.233630 -vn -0.958866 -0.155829 -0.237260 -v 0.070945 0.068891 0.233462 -vn -0.921449 -0.307623 -0.237277 -v 0.071091 0.068298 0.233462 -vn -0.860171 -0.451453 -0.237269 -v 0.071330 0.067736 0.233462 -vn -0.776617 -0.583586 -0.237261 -v 0.071656 0.067220 0.233462 -vn -0.672943 -0.700609 -0.237267 -v 0.072061 0.066763 0.233462 -vn -0.551842 -0.799482 -0.237274 -v 0.072534 0.066377 0.233462 -vn -0.416451 -0.877646 -0.237291 -v 0.073063 0.066071 0.233462 -vn -0.270274 -0.933090 -0.237265 -v 0.073634 0.065855 0.233462 -vn -0.117097 -0.964359 -0.237278 -v 0.074232 0.065733 0.233462 -vn 0.039118 -0.970661 -0.237248 -v 0.074842 0.065708 0.233462 -vn 0.194316 -0.951815 -0.237255 -v 0.075449 0.065782 0.233462 -vn 0.344480 -0.908317 -0.237263 -v 0.076035 0.065952 0.233462 -vn 0.485719 -0.841294 -0.237278 -v 0.076587 0.066213 0.233462 -vn 0.614387 -0.752486 -0.237265 -v 0.077089 0.066560 0.233462 -vn 0.727133 -0.644184 -0.237286 -v 0.077530 0.066983 0.233462 -vn 0.821054 -0.519200 -0.237280 -v 0.077896 0.067471 0.233462 -vn 0.893701 -0.380775 -0.237296 -v 0.078180 0.068012 0.233462 -vn 0.943212 -0.232484 -0.237280 -v 0.078374 0.068591 0.233462 -vn 0.968295 -0.078165 -0.237267 -v 0.078471 0.069194 0.233462 -vn 0.968295 0.078166 -0.237267 -v 0.078471 0.069804 0.233462 -vn 0.943212 0.232479 -0.237287 -v 0.078374 0.070407 0.233462 -vn 0.893702 0.380773 -0.237294 -v 0.078180 0.070986 0.233462 -vn 0.821048 0.519201 -0.237298 -v 0.077896 0.071527 0.233462 -vn 0.727133 0.644181 -0.237294 -v 0.077530 0.072015 0.233462 -vn 0.614382 0.752479 -0.237297 -v 0.077089 0.072438 0.233462 -vn 0.485722 0.841301 -0.237248 -v 0.076587 0.072785 0.233462 -vn 0.344479 0.908308 -0.237297 -v 0.076035 0.073047 0.233462 -vn 0.194315 0.951804 -0.237298 -v 0.075449 0.073217 0.233462 -vn 0.039115 0.970651 -0.237291 -v 0.074842 0.073290 0.233462 -vn -0.117097 0.964359 -0.237278 -v 0.074232 0.073266 0.233462 -vn -0.270272 0.933091 -0.237263 -v 0.073634 0.073144 0.233462 -vn -0.416450 0.877656 -0.237255 -v 0.073063 0.072927 0.233462 -vn -0.551843 0.799482 -0.237270 -v 0.072534 0.072622 0.233462 -vn -0.672938 0.700604 -0.237296 -v 0.072061 0.072236 0.233462 -vn -0.776619 0.583582 -0.237265 -v 0.071656 0.071778 0.233462 -vn -0.860170 0.451456 -0.237266 -v 0.071330 0.071262 0.233462 -vn -0.921452 0.307623 -0.237264 -v 0.071091 0.070701 0.233462 -vn -0.958868 0.155830 -0.237253 -v 0.070945 0.070108 0.233462 -vn -0.971444 0.000001 -0.237271 -v 0.070895 0.069499 0.233462 -vn -0.768701 -0.124926 -0.627290 -v 0.070983 0.068897 0.233384 -vn -0.738689 -0.246608 -0.627314 -v 0.071128 0.068310 0.233384 -vn -0.689575 -0.361922 -0.627295 -v 0.071365 0.067754 0.233384 -vn -0.622577 -0.467833 -0.627320 -v 0.071688 0.067243 0.233384 -vn -0.539470 -0.561647 -0.627316 -v 0.072089 0.066791 0.233384 -vn -0.442392 -0.640925 -0.627299 -v 0.072557 0.066409 0.233384 -vn -0.333860 -0.703592 -0.627293 -v 0.073080 0.066107 0.233384 -vn -0.216671 -0.748027 -0.627303 -v 0.073645 0.065893 0.233384 -vn -0.093870 -0.773088 -0.627315 -v 0.074237 0.065772 0.233384 -vn 0.031359 -0.778141 -0.627307 -v 0.074841 0.065747 0.233384 -vn 0.155774 -0.763033 -0.627308 -v 0.075441 0.065820 0.233384 -vn 0.276159 -0.728167 -0.627303 -v 0.076021 0.065988 0.233384 -vn 0.389378 -0.674427 -0.627322 -v 0.076567 0.066247 0.233384 -vn 0.492526 -0.603233 -0.627318 -v 0.077064 0.066591 0.233384 -vn 0.582919 -0.516419 -0.627309 -v 0.077500 0.067009 0.233384 -vn 0.658224 -0.416233 -0.627289 -v 0.077863 0.067492 0.233384 -vn 0.716475 -0.305259 -0.627281 -v 0.078144 0.068027 0.233384 -vn 0.756140 -0.186376 -0.627309 -v 0.078335 0.068601 0.233384 -vn 0.776259 -0.062665 -0.627292 -v 0.078432 0.069197 0.233384 -vn 0.776259 0.062667 -0.627292 -v 0.078432 0.069801 0.233384 -vn 0.756144 0.186371 -0.627305 -v 0.078335 0.070398 0.233384 -vn 0.716467 0.305261 -0.627289 -v 0.078144 0.070971 0.233384 -vn 0.658213 0.416224 -0.627306 -v 0.077863 0.071506 0.233384 -vn 0.582921 0.516427 -0.627301 -v 0.077500 0.071989 0.233384 -vn 0.492529 0.603231 -0.627318 -v 0.077064 0.072408 0.233384 -vn 0.389388 0.674445 -0.627297 -v 0.076567 0.072751 0.233384 -vn 0.276160 0.728181 -0.627286 -v 0.076021 0.073010 0.233384 -vn 0.155777 0.763049 -0.627288 -v 0.075441 0.073178 0.233384 -vn 0.031359 0.778142 -0.627305 -v 0.074841 0.073251 0.233384 -vn -0.093868 0.773088 -0.627315 -v 0.074237 0.073227 0.233384 -vn -0.216668 0.748027 -0.627305 -v 0.073645 0.073106 0.233384 -vn -0.333853 0.703581 -0.627309 -v 0.073080 0.072891 0.233384 -vn -0.442392 0.640917 -0.627307 -v 0.072557 0.072589 0.233384 -vn -0.539477 0.561654 -0.627303 -v 0.072089 0.072207 0.233384 -vn -0.622586 0.467845 -0.627303 -v 0.071688 0.071755 0.233384 -vn -0.689574 0.361915 -0.627300 -v 0.071365 0.071244 0.233384 -vn -0.738693 0.246616 -0.627307 -v 0.071128 0.070688 0.233384 -vn -0.768701 0.124922 -0.627290 -v 0.070983 0.070101 0.233384 -vn -0.778773 0.000001 -0.627306 -v 0.070935 0.069499 0.233384 -vn -0.431932 -0.070195 -0.899170 -v 0.071052 0.068908 0.233330 -vn -0.415087 -0.138576 -0.899166 -v 0.071194 0.068332 0.233330 -vn -0.387483 -0.203366 -0.899166 -v 0.071426 0.067786 0.233330 -vn -0.349842 -0.262891 -0.899166 -v 0.071743 0.067285 0.233330 -vn -0.303136 -0.315594 -0.899171 -v 0.072136 0.066841 0.233330 -vn -0.248588 -0.360139 -0.899168 -v 0.072596 0.066466 0.233330 -vn -0.187601 -0.395361 -0.899164 -v 0.073110 0.066169 0.233330 -vn -0.121752 -0.420333 -0.899164 -v 0.073664 0.065959 0.233330 -vn -0.052748 -0.434420 -0.899164 -v 0.074245 0.065840 0.233330 -vn 0.017622 -0.437257 -0.899164 -v 0.074838 0.065816 0.233330 -vn 0.087530 -0.428749 -0.899174 -v 0.075427 0.065888 0.233330 -vn 0.155176 -0.409163 -0.899170 -v 0.075997 0.066053 0.233330 -vn 0.218803 -0.378978 -0.899167 -v 0.076532 0.066307 0.233330 -vn 0.276757 -0.338969 -0.899169 -v 0.077021 0.066644 0.233330 -vn 0.327558 -0.290190 -0.899164 -v 0.077448 0.067055 0.233330 -vn 0.369852 -0.233884 -0.899171 -v 0.077805 0.067529 0.233330 -vn 0.402613 -0.171536 -0.899154 -v 0.078080 0.068054 0.233330 -vn 0.424888 -0.104727 -0.899167 -v 0.078268 0.068617 0.233330 -vn 0.436202 -0.035214 -0.899159 -v 0.078363 0.069203 0.233330 -vn 0.436203 0.035215 -0.899159 -v 0.078363 0.069796 0.233330 -vn 0.424894 0.104727 -0.899165 -v 0.078268 0.070381 0.233330 -vn 0.402604 0.171535 -0.899158 -v 0.078080 0.070944 0.233330 -vn 0.369854 0.233882 -0.899170 -v 0.077805 0.071469 0.233330 -vn 0.327547 0.290179 -0.899171 -v 0.077448 0.071943 0.233330 -vn 0.276762 0.338972 -0.899167 -v 0.077021 0.072354 0.233330 -vn 0.218804 0.378979 -0.899166 -v 0.076532 0.072691 0.233330 -vn 0.155179 0.409178 -0.899162 -v 0.075997 0.072945 0.233330 -vn 0.087533 0.428764 -0.899166 -v 0.075427 0.073110 0.233330 -vn 0.017619 0.437257 -0.899164 -v 0.074838 0.073182 0.233330 -vn -0.052748 0.434420 -0.899164 -v 0.074245 0.073158 0.233330 -vn -0.121751 0.420333 -0.899164 -v 0.073664 0.073039 0.233330 -vn -0.187593 0.395349 -0.899171 -v 0.073110 0.072829 0.233330 -vn -0.248599 0.360155 -0.899159 -v 0.072596 0.072532 0.233330 -vn -0.303147 0.315609 -0.899162 -v 0.072136 0.072157 0.233330 -vn -0.349838 0.262889 -0.899168 -v 0.071743 0.071713 0.233330 -vn -0.387489 0.203370 -0.899162 -v 0.071426 0.071212 0.233330 -vn -0.415086 0.138576 -0.899167 -v 0.071194 0.070666 0.233330 -vn -0.431931 0.070196 -0.899171 -v 0.071052 0.070090 0.233330 -vn -0.437602 -0.000001 -0.899169 -v 0.071004 0.069499 0.233330 -vn 0.708317 0.167046 0.685844 -v 0.077181 0.070090 0.235230 -vn 0.683157 0.248312 0.686759 -v 0.077095 0.070375 0.235230 -vn 0.649349 0.326595 0.686791 -v 0.076977 0.070648 0.235230 -vn 0.607698 0.400061 0.686043 -v 0.076828 0.070906 0.235230 -vn 0.557480 0.466983 0.686398 -v 0.076651 0.071145 0.235230 -vn 0.498810 0.528549 0.686894 -v 0.076446 0.071361 0.235230 -vn 0.433715 0.583280 0.686787 -v 0.076218 0.071553 0.235230 -vn 0.363637 0.629834 0.686350 -v 0.075970 0.071716 0.235230 -vn 0.288057 0.667782 0.686360 -v 0.075704 0.071850 0.235230 -vn 0.208815 0.696460 0.686542 -v 0.075424 0.071952 0.235230 -vn 0.125924 0.715959 0.686692 -v 0.075134 0.072020 0.235230 -vn 0.042501 0.725839 0.686551 -v 0.074838 0.072055 0.235230 -vn -0.042492 0.725819 0.686572 -v 0.074541 0.072055 0.235230 -vn -0.126178 0.716200 0.686394 -v 0.074245 0.072020 0.235230 -vn -0.208665 0.696562 0.686484 -v 0.073955 0.071952 0.235230 -vn -0.287608 0.667685 0.686643 -v 0.073676 0.071850 0.235230 -vn -0.363777 0.629356 0.686715 -v 0.073410 0.071716 0.235230 -vn -0.435271 0.583493 0.685621 -v 0.073161 0.071553 0.235230 -vn -0.498820 0.529886 0.685857 -v 0.072933 0.071361 0.235230 -vn -0.556629 0.467480 0.686751 -v 0.072729 0.071145 0.235230 -vn -0.607517 0.399057 0.686787 -v 0.072551 0.070906 0.235230 -vn -0.650312 0.326245 0.686045 -v 0.072402 0.070648 0.235230 -vn -0.683162 0.249299 0.686396 -v 0.072284 0.070375 0.235230 -vn -0.707140 0.167702 0.686898 -v 0.072199 0.070090 0.235230 -vn -0.721999 0.083983 0.686778 -v 0.072147 0.069796 0.235230 -vn -0.727269 -0.000001 0.686352 -v 0.072130 0.069499 0.235230 -vn -0.722351 -0.084432 0.686353 -v 0.072147 0.069202 0.235230 -vn -0.707553 -0.167394 0.686548 -v 0.072199 0.068909 0.235230 -vn -0.683013 -0.248924 0.686680 -v 0.072284 0.068624 0.235230 -vn -0.649849 -0.326104 0.686551 -v 0.072402 0.068350 0.235230 -vn -0.607331 -0.399714 0.686570 -v 0.072551 0.068092 0.235230 -vn -0.557169 -0.467391 0.686373 -v 0.072729 0.067854 0.235230 -vn -0.498903 -0.528992 0.686486 -v 0.072933 0.067637 0.235230 -vn -0.434441 -0.582920 0.686633 -v 0.073161 0.067446 0.235230 -vn -0.363148 -0.629721 0.686713 -v 0.073410 0.067282 0.235230 -vn -0.287686 -0.668719 0.685603 -v 0.073676 0.067149 0.235230 -vn -0.209488 -0.696937 0.685853 -v 0.073955 0.067047 0.235230 -vn -0.126537 -0.715791 0.686755 -v 0.074245 0.066978 0.235230 -vn -0.041840 -0.725653 0.686788 -v 0.074541 0.066943 0.235230 -vn 0.042617 -0.726312 0.686042 -v 0.074838 0.066943 0.235230 -vn 0.125689 -0.716287 0.686393 -v 0.075134 0.066978 0.235230 -vn 0.208338 -0.696258 0.686892 -v 0.075424 0.067047 0.235230 -vn 0.288272 -0.667268 0.686770 -v 0.075704 0.067149 0.235230 -vn 0.363636 -0.629837 0.686348 -v 0.075970 0.067282 0.235230 -vn 0.434297 -0.583361 0.686350 -v 0.076218 0.067446 0.235230 -vn 0.498745 -0.529066 0.686544 -v 0.076446 0.067637 0.235230 -vn 0.557079 -0.467045 0.686682 -v 0.076651 0.067854 0.235230 -vn 0.607343 -0.399731 0.686549 -v 0.076828 0.068092 0.235230 -vn 0.649824 -0.326106 0.686573 -v 0.076977 0.068350 0.235230 -vn 0.683348 -0.248824 0.686383 -v 0.077095 0.068624 0.235230 -vn 0.707581 -0.167575 0.686475 -v 0.077181 0.068909 0.235230 -vn 0.722045 -0.084771 0.686633 -v 0.077232 0.069202 0.235230 -vn 0.726925 0.000365 0.686717 -v 0.077250 0.069499 0.235230 -vn 0.722965 0.085213 0.685609 -v 0.077232 0.069796 0.235230 -vn -0.119875 -0.000001 0.992789 -v 0.072290 0.069499 0.235310 -vn -0.450920 -0.052707 0.891007 -v 0.072217 0.069210 0.235289 -vn -0.119071 -0.013917 0.992788 -v 0.072306 0.069221 0.235310 -vn -0.441745 -0.104697 0.891011 -v 0.072267 0.068925 0.235289 -vn -0.116646 -0.027646 0.992789 -v 0.072354 0.068946 0.235310 -vn -0.426603 -0.155272 0.891011 -v 0.072350 0.068648 0.235289 -vn -0.112645 -0.041000 0.992789 -v 0.072434 0.068678 0.235310 -vn -0.405699 -0.203745 0.891009 -v 0.072465 0.068382 0.235289 -vn -0.107133 -0.053801 0.992788 -v 0.072545 0.068422 0.235310 -vn -0.379302 -0.249469 0.891008 -v 0.072610 0.068131 0.235289 -vn -0.100153 -0.065872 0.992789 -v 0.072684 0.068180 0.235310 -vn -0.347775 -0.291823 0.891006 -v 0.072783 0.067899 0.235289 -vn -0.091823 -0.077051 0.992790 -v 0.072851 0.067956 0.235310 -vn -0.311541 -0.330220 0.891009 -v 0.072981 0.067688 0.235289 -vn -0.082266 -0.087195 0.992789 -v 0.073043 0.067753 0.235310 -vn -0.271111 -0.364157 0.891004 -v 0.073203 0.067502 0.235289 -vn -0.071591 -0.096160 0.992788 -v 0.073256 0.067574 0.235310 -vn -0.226996 -0.393170 0.891005 -v 0.073445 0.067343 0.235289 -vn -0.059936 -0.103814 0.992789 -v 0.073490 0.067421 0.235310 -vn -0.179817 -0.416870 0.891003 -v 0.073704 0.067213 0.235289 -vn -0.047482 -0.110076 0.992788 -v 0.073739 0.067295 0.235310 -vn -0.130207 -0.434921 0.891005 -v 0.073976 0.067114 0.235289 -vn -0.034382 -0.114844 0.992788 -v 0.074001 0.067200 0.235310 -vn -0.078839 -0.447097 0.891004 -v 0.074257 0.067048 0.235289 -vn -0.020817 -0.118059 0.992788 -v 0.074273 0.067136 0.235310 -vn -0.026396 -0.453215 0.891010 -v 0.074545 0.067014 0.235289 -vn -0.006969 -0.119668 0.992790 -v 0.074550 0.067103 0.235310 -vn 0.026398 -0.453214 0.891011 -v 0.074834 0.067014 0.235289 -vn 0.006970 -0.119669 0.992789 -v 0.074829 0.067103 0.235310 -vn 0.078835 -0.447094 0.891006 -v 0.075122 0.067048 0.235289 -vn 0.020816 -0.118061 0.992788 -v 0.075106 0.067136 0.235310 -vn 0.130207 -0.434920 0.891005 -v 0.075404 0.067114 0.235289 -vn 0.034381 -0.114841 0.992789 -v 0.075378 0.067200 0.235310 -vn 0.179817 -0.416868 0.891003 -v 0.075676 0.067213 0.235289 -vn 0.047480 -0.110072 0.992789 -v 0.075640 0.067295 0.235310 -vn 0.226995 -0.393167 0.891007 -v 0.075934 0.067343 0.235289 -vn 0.059937 -0.103813 0.992789 -v 0.075890 0.067421 0.235310 -vn 0.271105 -0.364156 0.891006 -v 0.076176 0.067502 0.235289 -vn 0.071586 -0.096157 0.992789 -v 0.076123 0.067574 0.235310 -vn 0.311544 -0.330218 0.891009 -v 0.076398 0.067688 0.235289 -vn 0.082265 -0.087196 0.992789 -v 0.076337 0.067753 0.235310 -vn 0.347769 -0.291813 0.891012 -v 0.076597 0.067899 0.235289 -vn 0.091830 -0.077054 0.992789 -v 0.076528 0.067956 0.235310 -vn 0.379297 -0.249469 0.891010 -v 0.076770 0.068131 0.235289 -vn 0.100153 -0.065872 0.992789 -v 0.076695 0.068180 0.235310 -vn 0.405692 -0.203747 0.891012 -v 0.076914 0.068382 0.235289 -vn 0.107124 -0.053800 0.992789 -v 0.076834 0.068422 0.235310 -vn 0.426606 -0.155270 0.891010 -v 0.077029 0.068648 0.235289 -vn 0.112645 -0.040999 0.992789 -v 0.076945 0.068678 0.235310 -vn 0.441758 -0.104700 0.891004 -v 0.077112 0.068925 0.235289 -vn 0.116637 -0.027642 0.992790 -v 0.077025 0.068946 0.235310 -vn 0.450914 -0.052703 0.891010 -v 0.077162 0.069210 0.235289 -vn 0.119063 -0.013916 0.992789 -v 0.077073 0.069221 0.235310 -vn 0.453985 -0.000000 0.891010 -v 0.077179 0.069499 0.235289 -vn 0.119874 -0.000000 0.992789 -v 0.077090 0.069499 0.235310 -vn 0.450916 0.052705 0.891009 -v 0.077162 0.069788 0.235289 -vn 0.119062 0.013916 0.992789 -v 0.077073 0.069778 0.235310 -vn 0.441761 0.104696 0.891003 -v 0.077112 0.070073 0.235289 -vn 0.116639 0.027644 0.992790 -v 0.077025 0.070053 0.235310 -vn 0.426606 0.155271 0.891010 -v 0.077029 0.070351 0.235289 -vn 0.112649 0.041000 0.992789 -v 0.076945 0.070320 0.235310 -vn 0.405695 0.203749 0.891010 -v 0.076914 0.070616 0.235289 -vn 0.107127 0.053802 0.992789 -v 0.076834 0.070576 0.235310 -vn 0.379298 0.249469 0.891010 -v 0.076770 0.070867 0.235289 -vn 0.100152 0.065872 0.992789 -v 0.076695 0.070818 0.235310 -vn 0.347773 0.291813 0.891010 -v 0.076597 0.071099 0.235289 -vn 0.091836 0.077057 0.992788 -v 0.076528 0.071042 0.235310 -vn 0.311546 0.330218 0.891008 -v 0.076398 0.071310 0.235289 -vn 0.082265 0.087197 0.992789 -v 0.076337 0.071245 0.235310 -vn 0.271090 0.364146 0.891015 -v 0.076176 0.071496 0.235289 -vn 0.071585 0.096157 0.992789 -v 0.076123 0.071424 0.235310 -vn 0.227000 0.393170 0.891004 -v 0.075934 0.071655 0.235289 -vn 0.059942 0.103821 0.992788 -v 0.075890 0.071578 0.235310 -vn 0.179811 0.416848 0.891014 -v 0.075676 0.071785 0.235289 -vn 0.047480 0.110071 0.992789 -v 0.075640 0.071703 0.235310 -vn 0.130207 0.434912 0.891009 -v 0.075404 0.071884 0.235289 -vn 0.034378 0.114834 0.992790 -v 0.075378 0.071798 0.235310 -vn 0.078824 0.447072 0.891018 -v 0.075122 0.071951 0.235289 -vn 0.020818 0.118060 0.992788 -v 0.075106 0.071863 0.235310 -vn 0.026398 0.453222 0.891007 -v 0.074834 0.071984 0.235289 -vn 0.006971 0.119678 0.992788 -v 0.074829 0.071895 0.235310 -vn -0.026395 0.453221 0.891008 -v 0.074545 0.071984 0.235289 -vn -0.006971 0.119678 0.992788 -v 0.074550 0.071895 0.235310 -vn -0.078833 0.447075 0.891016 -v 0.074257 0.071951 0.235289 -vn -0.020816 0.118058 0.992788 -v 0.074273 0.071863 0.235310 -vn -0.130204 0.434916 0.891008 -v 0.073976 0.071884 0.235289 -vn -0.034381 0.114836 0.992789 -v 0.074001 0.071798 0.235310 -vn -0.179814 0.416848 0.891013 -v 0.073704 0.071785 0.235289 -vn -0.047481 0.110076 0.992788 -v 0.073739 0.071703 0.235310 -vn -0.226996 0.393174 0.891003 -v 0.073445 0.071655 0.235289 -vn -0.059942 0.103822 0.992788 -v 0.073490 0.071578 0.235310 -vn -0.271098 0.364144 0.891014 -v 0.073203 0.071496 0.235289 -vn -0.071589 0.096160 0.992788 -v 0.073256 0.071424 0.235310 -vn -0.311545 0.330222 0.891007 -v 0.072981 0.071310 0.235289 -vn -0.082265 0.087196 0.992789 -v 0.073043 0.071245 0.235310 -vn -0.347779 0.291824 0.891004 -v 0.072783 0.071099 0.235289 -vn -0.091829 0.077054 0.992789 -v 0.072851 0.071042 0.235310 -vn -0.379301 0.249466 0.891009 -v 0.072610 0.070867 0.235289 -vn -0.100154 0.065872 0.992789 -v 0.072684 0.070818 0.235310 -vn -0.405701 0.203747 0.891007 -v 0.072465 0.070616 0.235289 -vn -0.107135 0.053806 0.992787 -v 0.072545 0.070576 0.235310 -vn -0.426607 0.155272 0.891009 -v 0.072350 0.070351 0.235289 -vn -0.112648 0.040999 0.992789 -v 0.072434 0.070320 0.235310 -vn -0.441747 0.104695 0.891010 -v 0.072267 0.070073 0.235289 -vn -0.116649 0.027647 0.992788 -v 0.072354 0.070053 0.235310 -vn -0.450920 0.052709 0.891006 -v 0.072217 0.069788 0.235289 -vn -0.119071 0.013918 0.992788 -v 0.072306 0.069778 0.235310 -vn -0.453988 -0.000001 0.891008 -v 0.072200 0.069499 0.235289 -vn 0.072720 -0.055280 0.995819 -v 0.072938 0.070831 0.235310 -vn 0.059132 -0.069616 0.995820 -v 0.073265 0.071176 0.235310 -vn 0.042786 -0.080705 0.995819 -v 0.073659 0.071443 0.235310 -vn 0.024437 -0.088015 0.995819 -v 0.074101 0.071619 0.235310 -vn -0.051265 -0.075609 0.995819 -v 0.075924 0.071320 0.235310 -vn -0.066315 0.062817 0.995819 -v 0.076287 0.067986 0.235310 -vn -0.051260 0.075604 0.995820 -v 0.075924 0.067678 0.235310 -vn 0.089203 -0.019634 0.995820 -v 0.072541 0.069972 0.235310 -vn 0.082899 -0.038353 0.995820 -v 0.072693 0.070423 0.235310 -vn -0.033808 -0.084853 0.995820 -v 0.075504 0.071543 0.235310 -vn -0.066315 -0.062817 0.995819 -v 0.076287 0.071012 0.235310 -vn -0.078268 -0.047092 0.995819 -v 0.076575 0.070633 0.235310 -vn 0.024437 0.088014 0.995819 -v 0.074101 0.067379 0.235310 -vn 0.042787 0.080705 0.995819 -v 0.073659 0.067555 0.235310 -vn 0.059136 0.069621 0.995819 -v 0.073265 0.067822 0.235310 -vn 0.091347 -0.000001 0.995819 -v 0.072490 0.069499 0.235310 -vn 0.089203 0.019635 0.995820 -v 0.072541 0.069026 0.235310 -vn -0.014778 -0.090141 0.995819 -v 0.075046 0.071670 0.235310 -vn 0.004945 -0.091213 0.995819 -v 0.074571 0.071696 0.235310 -vn 0.072715 0.055277 0.995820 -v 0.072938 0.068168 0.235310 -vn 0.082903 0.038354 0.995819 -v 0.072693 0.068575 0.235310 -vn -0.033809 0.084853 0.995820 -v 0.075504 0.067455 0.235310 -vn -0.014778 0.090141 0.995819 -v 0.075046 0.067328 0.235310 -vn -0.086560 -0.029165 0.995820 -v 0.076774 0.070202 0.235310 -vn -0.090802 0.009875 0.995820 -v 0.076877 0.069261 0.235310 -vn -0.090802 -0.009875 0.995820 -v 0.076877 0.069737 0.235310 -vn -0.086560 0.029165 0.995820 -v 0.076774 0.068797 0.235310 -vn -0.078268 0.047093 0.995819 -v 0.076575 0.068365 0.235310 -vn 0.004944 0.091205 0.995820 -v 0.074571 0.067302 0.235310 -vn 0.238707 -0.894546 0.377897 -v 0.074151 0.071441 0.235187 -vn 0.426173 -0.819990 0.382091 -v 0.073746 0.071280 0.235187 -vn 0.608351 -0.697858 0.378026 -v 0.073385 0.071035 0.235187 -vn 0.732716 -0.564662 0.379848 -v 0.073085 0.070719 0.235187 -vn 0.061971 -0.924021 0.377286 -v 0.074581 0.071511 0.235187 -vn -0.154866 -0.910416 0.383614 -v 0.075016 0.071488 0.235187 -vn -0.352120 -0.856207 0.378049 -v 0.075436 0.071371 0.235187 -vn -0.511425 -0.771826 0.377794 -v 0.075821 0.071167 0.235187 -vn -0.672309 -0.632190 0.385146 -v 0.076153 0.070885 0.235187 -vn -0.797977 -0.468650 0.378946 -v 0.076416 0.070538 0.235187 -vn -0.874351 -0.299101 0.382164 -v 0.076599 0.070143 0.235187 -vn -0.916925 -0.098575 0.386694 -v 0.076693 0.069717 0.235187 -vn -0.918499 0.108730 0.380182 -v 0.076693 0.069281 0.235187 -vn -0.874454 0.298152 0.382669 -v 0.076599 0.068856 0.235187 -vn -0.798945 0.467310 0.378561 -v 0.076416 0.068460 0.235187 -vn -0.665256 0.641880 0.381345 -v 0.076153 0.068113 0.235187 -vn -0.512743 0.770647 0.378415 -v 0.075821 0.067831 0.235187 -vn -0.353891 0.855688 0.377569 -v 0.075436 0.067627 0.235187 -vn -0.142971 0.912681 0.382849 -v 0.075016 0.067510 0.235187 -vn 0.060074 0.923939 0.377794 -v 0.074581 0.067487 0.235187 -vn 0.236973 0.895275 0.377261 -v 0.074151 0.067557 0.235187 -vn 0.436378 0.813544 0.384344 -v 0.073746 0.067719 0.235187 -vn 0.606921 0.698878 0.378439 -v 0.073385 0.067963 0.235187 -vn 0.732025 0.565992 0.379200 -v 0.073085 0.068280 0.235187 -vn 0.838228 0.385302 0.385896 -v 0.072861 0.068653 0.235187 -vn 0.905515 0.189725 0.379537 -v 0.072722 0.069066 0.235187 -vn 0.921881 0.000001 0.387473 -v 0.072674 0.069499 0.235187 -vn 0.905959 -0.188246 0.379211 -v 0.072722 0.069932 0.235187 -vn 0.835284 -0.396788 0.380604 -v 0.072861 0.070345 0.235187 -vn 0.683881 0.150536 0.713895 -v 0.072679 0.069057 0.235252 -vn 0.635535 0.294027 0.713893 -v 0.072821 0.068635 0.235252 -vn 0.557484 0.423783 0.713876 -v 0.073051 0.068253 0.235252 -vn 0.453327 0.533704 0.713901 -v 0.073357 0.067930 0.235252 -vn 0.328006 0.618689 0.713887 -v 0.073725 0.067680 0.235252 -vn 0.187341 0.674734 0.713889 -v 0.074139 0.067516 0.235252 -vn 0.037916 0.699238 0.713883 -v 0.074578 0.067444 0.235252 -vn -0.113288 0.691008 0.713914 -v 0.075023 0.067468 0.235252 -vn -0.259192 0.650513 0.713899 -v 0.075452 0.067587 0.235252 -vn -0.392972 0.579602 0.713887 -v 0.075845 0.067795 0.235252 -vn -0.508375 0.481557 0.713903 -v 0.076184 0.068083 0.235252 -vn -0.600005 0.361007 0.713911 -v 0.076454 0.068438 0.235252 -vn -0.663601 0.223596 0.713890 -v 0.076640 0.068842 0.235252 -vn -0.696159 0.075714 0.713884 -v 0.076736 0.069277 0.235252 -vn -0.696156 -0.075711 0.713887 -v 0.076736 0.069722 0.235252 -vn -0.663601 -0.223593 0.713891 -v 0.076640 0.070156 0.235252 -vn -0.600012 -0.361017 0.713900 -v 0.076454 0.070560 0.235252 -vn -0.508375 -0.481557 0.713903 -v 0.076184 0.070915 0.235252 -vn -0.392974 -0.579598 0.713889 -v 0.075845 0.071203 0.235252 -vn -0.259193 -0.650523 0.713890 -v 0.075452 0.071412 0.235252 -vn -0.113294 -0.691033 0.713889 -v 0.075023 0.071531 0.235252 -vn 0.037913 -0.699211 0.713909 -v 0.074578 0.071555 0.235252 -vn 0.187336 -0.674727 0.713896 -v 0.074139 0.071483 0.235252 -vn 0.327995 -0.618671 0.713909 -v 0.073725 0.071318 0.235252 -vn 0.453337 -0.533712 0.713889 -v 0.073357 0.071068 0.235252 -vn 0.557476 -0.423777 0.713887 -v 0.073051 0.070745 0.235252 -vn 0.635532 -0.294029 0.713895 -v 0.072821 0.070364 0.235252 -vn 0.683881 -0.150536 0.713895 -v 0.072679 0.069942 0.235252 -vn 0.700246 0.000001 0.713901 -v 0.072631 0.069499 0.235252 -vn 0.362406 0.079773 0.928600 -v 0.072616 0.069043 0.235295 -vn 0.336782 0.155812 0.928601 -v 0.072762 0.068608 0.235295 -vn 0.295419 0.224569 0.928599 -v 0.072999 0.068214 0.235295 -vn 0.240229 0.282821 0.928602 -v 0.073315 0.067881 0.235295 -vn 0.173821 0.327856 0.928599 -v 0.073695 0.067623 0.235295 -vn 0.099271 0.357542 0.928606 -v 0.074122 0.067453 0.235295 -vn 0.020090 0.370534 0.928602 -v 0.074575 0.067379 0.235295 -vn -0.060034 0.366195 0.928599 -v 0.075033 0.067404 0.235295 -vn -0.137354 0.344733 0.928597 -v 0.075476 0.067527 0.235295 -vn -0.208245 0.307135 0.928602 -v 0.075881 0.067742 0.235295 -vn -0.269408 0.255203 0.928596 -v 0.076231 0.068039 0.235295 -vn -0.317952 0.191302 0.928607 -v 0.076509 0.068404 0.235295 -vn -0.351651 0.118484 0.928603 -v 0.076702 0.068821 0.235295 -vn -0.368918 0.040121 0.928596 -v 0.076801 0.069270 0.235295 -vn -0.368917 -0.040123 0.928596 -v 0.076801 0.069729 0.235295 -vn -0.351653 -0.118486 0.928602 -v 0.076702 0.070177 0.235295 -vn -0.317961 -0.191308 0.928602 -v 0.076509 0.070594 0.235295 -vn -0.269412 -0.255200 0.928596 -v 0.076231 0.070959 0.235295 -vn -0.208249 -0.307141 0.928600 -v 0.075881 0.071257 0.235295 -vn -0.137343 -0.344714 0.928606 -v 0.075476 0.071472 0.235295 -vn -0.060036 -0.366196 0.928599 -v 0.075033 0.071595 0.235295 -vn 0.020089 -0.370542 0.928598 -v 0.074575 0.071620 0.235295 -vn 0.099278 -0.357564 0.928597 -v 0.074122 0.071545 0.235295 -vn 0.173820 -0.327855 0.928600 -v 0.073695 0.071375 0.235295 -vn 0.240238 -0.282828 0.928598 -v 0.073315 0.071118 0.235295 -vn 0.295411 -0.224565 0.928603 -v 0.072999 0.070784 0.235295 -vn 0.336788 -0.155812 0.928599 -v 0.072762 0.070391 0.235295 -vn 0.362407 -0.079773 0.928600 -v 0.072616 0.069956 0.235295 -vn 0.371081 -0.000000 0.928601 -v 0.072566 0.069499 0.235295 -vn -0.736504 0.000000 -0.676434 -v 0.077190 0.069499 0.220810 -vn -0.706670 0.207495 -0.676434 -v 0.077088 0.068795 0.220810 -vn -0.619587 0.398184 -0.676433 -v 0.076793 0.068148 0.220810 -vn -0.482307 0.556612 -0.676434 -v 0.076327 0.067610 0.220810 -vn -0.305956 0.669947 -0.676433 -v 0.075728 0.067225 0.220810 -vn -0.104815 0.729007 -0.676434 -v 0.075045 0.067025 0.220810 -vn 0.104815 0.729007 -0.676434 -v 0.074334 0.067025 0.220810 -vn 0.305956 0.669947 -0.676433 -v 0.073651 0.067225 0.220810 -vn 0.482307 0.556612 -0.676434 -v 0.073052 0.067610 0.220810 -vn 0.619584 0.398186 -0.676434 -v 0.072587 0.068148 0.220810 -vn 0.706670 0.207499 -0.676433 -v 0.072291 0.068795 0.220810 -vn 0.736504 -0.000000 -0.676434 -v 0.072190 0.069499 0.220810 -vn 0.706670 -0.207499 -0.676433 -v 0.072291 0.070203 0.220810 -vn 0.619585 -0.398184 -0.676435 -v 0.072587 0.070851 0.220810 -vn 0.482307 -0.556613 -0.676433 -v 0.073052 0.071389 0.220810 -vn 0.305952 -0.669948 -0.676434 -v 0.073651 0.071773 0.220810 -vn 0.104815 -0.729007 -0.676434 -v 0.074334 0.071974 0.220810 -vn -0.104815 -0.729007 -0.676434 -v 0.075045 0.071974 0.220810 -vn -0.305953 -0.669948 -0.676434 -v 0.075728 0.071773 0.220810 -vn -0.482307 -0.556613 -0.676433 -v 0.076327 0.071389 0.220810 -vn -0.619588 -0.398181 -0.676434 -v 0.076793 0.070851 0.220810 -vn -0.706670 -0.207495 -0.676434 -v 0.077088 0.070203 0.220810 -vn 0.000000 -0.686918 -0.726735 -v 0.074690 0.053999 0.200480 -vn 0.133539 0.686915 -0.714363 -v 0.075471 0.063999 0.200553 -vn 0.133539 -0.686916 -0.714363 -v 0.075471 0.053999 0.200553 -vn 0.262529 0.686918 -0.677659 -v 0.076225 0.063999 0.200767 -vn 0.262529 -0.686918 -0.677659 -v 0.076225 0.053999 0.200767 -vn 0.382576 0.686917 -0.617885 -v 0.076927 0.063999 0.201117 -vn 0.382576 -0.686917 -0.617885 -v 0.076927 0.053999 0.201117 -vn 0.489600 0.686916 -0.537064 -v 0.077553 0.063999 0.201590 -vn 0.489600 -0.686916 -0.537064 -v 0.077553 0.053999 0.201590 -vn 0.579945 0.686919 -0.437957 -v 0.078081 0.063999 0.202169 -vn 0.579945 -0.686919 -0.437957 -v 0.078081 0.053999 0.202169 -vn 0.650548 0.686915 -0.323936 -v 0.078494 0.063999 0.202836 -vn 0.650548 -0.686915 -0.323936 -v 0.078494 0.053999 0.202836 -vn 0.698993 0.686918 -0.198879 -v 0.078777 0.063999 0.203567 -vn 0.698993 -0.686918 -0.198879 -v 0.078777 0.053999 0.203567 -vn 0.723636 0.686917 -0.067056 -v 0.078922 0.063999 0.204338 -vn 0.723636 -0.686917 -0.067056 -v 0.078922 0.053999 0.204338 -vn 0.723636 0.686916 0.067057 -v 0.078922 0.063999 0.205123 -vn 0.723636 -0.686916 0.067057 -v 0.078922 0.053999 0.205123 -vn 0.698992 0.686919 0.198880 -v 0.078777 0.063999 0.205893 -vn 0.698992 -0.686919 0.198880 -v 0.078777 0.053999 0.205893 -vn 0.650549 0.686916 0.323933 -v 0.078494 0.063999 0.206625 -vn 0.650549 -0.686916 0.323933 -v 0.078494 0.053999 0.206625 -vn 0.579946 0.686916 0.437959 -v 0.078081 0.063999 0.207292 -vn 0.579946 -0.686916 0.437959 -v 0.078081 0.053999 0.207292 -vn 0.489596 0.686918 0.537066 -v 0.077553 0.063999 0.207871 -vn 0.489596 -0.686918 0.537066 -v 0.077553 0.053999 0.207871 -vn 0.382580 0.686919 0.617880 -v 0.076927 0.063999 0.208344 -vn 0.382580 -0.686919 0.617880 -v 0.076927 0.053999 0.208344 -vn 0.262529 0.686915 0.677662 -v 0.076225 0.063999 0.208693 -vn 0.262530 -0.686915 0.677662 -v 0.076225 0.053999 0.208693 -vn 0.133532 0.686917 0.714362 -v 0.075471 0.063999 0.208908 -vn 0.133532 -0.686917 0.714362 -v 0.075471 0.053999 0.208908 -vn 0.000000 0.686918 0.726735 -v 0.074690 0.063999 0.208980 -vn 0.000000 -0.686918 0.726735 -v 0.074690 0.053999 0.208980 -vn -0.133532 0.686917 0.714363 -v 0.073909 0.063999 0.208908 -vn -0.133532 -0.686917 0.714363 -v 0.073909 0.053999 0.208908 -vn -0.262530 0.686915 0.677662 -v 0.073154 0.063999 0.208693 -vn -0.262529 -0.686915 0.677662 -v 0.073154 0.053999 0.208693 -vn -0.382582 0.686918 0.617879 -v 0.072452 0.063999 0.208344 -vn -0.382582 -0.686918 0.617879 -v 0.072452 0.053999 0.208344 -vn -0.489595 0.686919 0.537065 -v 0.071826 0.063999 0.207871 -vn -0.489595 -0.686919 0.537065 -v 0.071826 0.053999 0.207871 -vn -0.579948 0.686915 0.437960 -v 0.071298 0.063999 0.207292 -vn -0.579948 -0.686915 0.437960 -v 0.071298 0.053999 0.207292 -vn -0.650547 0.686918 0.323932 -v 0.070885 0.063999 0.206625 -vn -0.650547 -0.686918 0.323932 -v 0.070885 0.053999 0.206625 -vn -0.698994 0.686917 0.198880 -v 0.070602 0.063999 0.205893 -vn -0.698994 -0.686917 0.198880 -v 0.070602 0.053999 0.205893 -vn -0.723636 0.686917 0.067054 -v 0.070458 0.063999 0.205123 -vn -0.723636 -0.686917 0.067054 -v 0.070458 0.053999 0.205123 -vn -0.723635 0.686918 -0.067053 -v 0.070458 0.063999 0.204338 -vn -0.723635 -0.686918 -0.067052 -v 0.070458 0.053999 0.204338 -vn -0.698994 0.686916 -0.198879 -v 0.070602 0.063999 0.203567 -vn -0.698994 -0.686916 -0.198879 -v 0.070602 0.053999 0.203567 -vn -0.650547 0.686917 -0.323936 -v 0.070885 0.063999 0.202836 -vn -0.650547 -0.686917 -0.323936 -v 0.070885 0.053999 0.202836 -vn -0.579947 0.686917 -0.437958 -v 0.071298 0.063999 0.202169 -vn -0.579947 -0.686917 -0.437958 -v 0.071298 0.053999 0.202169 -vn -0.489599 0.686918 -0.537063 -v 0.071826 0.063999 0.201590 -vn -0.489599 -0.686918 -0.537063 -v 0.071826 0.053999 0.201590 -vn -0.382578 0.686916 -0.617884 -v 0.072452 0.063999 0.201117 -vn -0.382578 -0.686916 -0.617884 -v 0.072452 0.053999 0.201117 -vn -0.262529 0.686918 -0.677659 -v 0.073154 0.063999 0.200767 -vn -0.262529 -0.686918 -0.677659 -v 0.073154 0.053999 0.200767 -vn -0.133539 0.686915 -0.714363 -v 0.073909 0.063999 0.200553 -vn -0.133539 -0.686915 -0.714363 -v 0.073909 0.053999 0.200553 -vn 0.000000 0.686918 -0.726735 -v 0.074690 0.063999 0.200480 -vn -0.653123 0.724830 -0.219206 -v 0.078008 0.063999 0.205923 -vn -0.610151 0.725548 -0.318269 -v 0.077797 0.063999 0.206421 -vn -0.551289 0.725683 -0.411660 -v 0.077490 0.063999 0.206910 -vn -0.479318 0.725246 -0.494239 -v 0.077127 0.063999 0.207322 -vn -0.392449 0.726393 -0.564214 -v 0.076702 0.063999 0.207674 -vn -0.290027 0.727385 -0.621929 -v 0.076167 0.063999 0.207983 -vn -0.177648 0.727150 -0.663094 -v 0.075594 0.063999 0.208192 -vn 0.642248 0.724880 0.249133 -v 0.071426 0.063999 0.203546 -vn 0.594126 0.725798 0.346746 -v 0.071661 0.063999 0.203057 -vn 0.530078 0.725901 0.438275 -v 0.071999 0.063999 0.202572 -vn 0.453683 0.725290 0.517809 -v 0.072382 0.063999 0.202179 -vn 0.363248 0.726412 0.583417 -v 0.072826 0.063999 0.201848 -vn 0.258232 0.727304 0.635881 -v 0.073375 0.063999 0.201567 -vn 0.144373 0.727065 0.671218 -v 0.073956 0.063999 0.201388 -vn 0.029438 0.726156 0.686899 -v 0.074551 0.063999 0.201313 -vn -0.083114 0.725867 0.682795 -v 0.075105 0.063999 0.201335 -vn -0.061337 0.726851 -0.684051 -v 0.075000 0.063999 0.208297 -vn 0.055398 0.726634 -0.684788 -v 0.074407 0.063999 0.208299 -vn 0.169354 0.726404 -0.666075 -v 0.073825 0.063999 0.208202 -vn 0.277133 0.726063 -0.629309 -v 0.073277 0.063999 0.208013 -vn 0.375776 0.725735 -0.576282 -v 0.072776 0.063999 0.207741 -vn 0.463151 0.725418 -0.509176 -v 0.072333 0.063999 0.207398 -vn -0.193811 0.726335 0.659451 -v 0.075679 0.063999 0.201453 -vn -0.299852 0.726013 0.618865 -v 0.076218 0.063999 0.201662 -vn -0.396201 0.725645 0.562551 -v 0.076707 0.063999 0.201951 -vn -0.480491 0.725132 0.493267 -v 0.077136 0.063999 0.202307 -vn -0.551240 0.724847 0.413195 -v 0.077490 0.063999 0.202710 -vn -0.608075 0.724739 0.324035 -v 0.077780 0.063999 0.203167 -vn -0.650400 0.724378 0.228597 -v 0.077992 0.063999 0.203652 -vn 0.535528 0.723107 -0.436263 -v 0.071956 0.063999 0.206996 -vn 0.590793 0.722935 -0.358230 -v 0.071712 0.063999 0.206650 -vn 0.634721 0.724637 -0.268383 -v 0.071464 0.063999 0.206170 -vn 0.668217 0.724209 -0.170312 -v 0.071298 0.063999 0.205673 -vn 0.685423 0.725067 -0.066875 -v 0.071208 0.063999 0.205165 -vn 0.687099 0.725388 0.041312 -v 0.071197 0.063999 0.204590 -vn 0.672956 0.724776 0.147751 -v 0.071271 0.063999 0.204061 -vn -0.677406 0.724095 0.129644 -v 0.078128 0.063999 0.204155 -vn -0.694568 0.717864 0.047399 -v 0.078187 0.063999 0.204663 -vn -0.694402 0.719243 -0.022263 -v 0.078190 0.063999 0.204810 -vn -0.678505 0.725748 -0.113665 -v 0.078139 0.063999 0.205403 -vn -0.061337 -0.726851 -0.684051 -v 0.075000 0.053999 0.208297 -vn -0.177648 -0.727150 -0.663094 -v 0.075594 0.053999 0.208192 -vn -0.290027 -0.727385 -0.621929 -v 0.076167 0.053999 0.207983 -vn -0.392449 -0.726393 -0.564214 -v 0.076702 0.053999 0.207674 -vn -0.479318 -0.725246 -0.494239 -v 0.077127 0.053999 0.207322 -vn -0.551289 -0.725683 -0.411660 -v 0.077490 0.053999 0.206910 -vn -0.610151 -0.725548 -0.318269 -v 0.077797 0.053999 0.206421 -vn -0.653123 -0.724830 -0.219206 -v 0.078008 0.053999 0.205923 -vn -0.678505 -0.725748 -0.113665 -v 0.078139 0.053999 0.205403 -vn -0.001815 -0.999840 -0.017811 -v 0.078190 0.053999 0.204810 -vn -0.193811 -0.726335 0.659450 -v 0.075679 0.053999 0.201453 -vn -0.083114 -0.725867 0.682795 -v 0.075105 0.053999 0.201335 -vn 0.029438 -0.726156 0.686899 -v 0.074551 0.053999 0.201313 -vn 0.144373 -0.727065 0.671218 -v 0.073956 0.053999 0.201388 -vn 0.258232 -0.727304 0.635881 -v 0.073375 0.053999 0.201567 -vn 0.363248 -0.726412 0.583417 -v 0.072826 0.053999 0.201848 -vn 0.453683 -0.725290 0.517809 -v 0.072382 0.053999 0.202179 -vn 0.530078 -0.725901 0.438275 -v 0.071999 0.053999 0.202572 -vn 0.594126 -0.725798 0.346746 -v 0.071661 0.053999 0.203057 -vn -0.694568 -0.717864 0.047399 -v 0.078187 0.053999 0.204663 -vn -0.677406 -0.724095 0.129644 -v 0.078128 0.053999 0.204155 -vn -0.650399 -0.724379 0.228597 -v 0.077992 0.053999 0.203652 -vn -0.608075 -0.724739 0.324035 -v 0.077780 0.053999 0.203167 -vn -0.003123 -0.999976 -0.006230 -v 0.077490 0.053999 0.202710 -vn -0.480491 -0.725132 0.493267 -v 0.077136 0.053999 0.202307 -vn -0.396201 -0.725645 0.562551 -v 0.076707 0.053999 0.201951 -vn -0.299852 -0.726013 0.618865 -v 0.076218 0.053999 0.201662 -vn 0.535528 -0.723107 -0.436263 -v 0.071956 0.053999 0.206996 -vn 0.463152 -0.725417 -0.509176 -v 0.072333 0.053999 0.207398 -vn 0.375776 -0.725735 -0.576282 -v 0.072776 0.053999 0.207741 -vn 0.277133 -0.726063 -0.629309 -v 0.073277 0.053999 0.208013 -vn 0.169354 -0.726404 -0.666075 -v 0.073825 0.053999 0.208202 -vn 0.055398 -0.726634 -0.684788 -v 0.074407 0.053999 0.208299 -vn 0.642248 -0.724880 0.249133 -v 0.071426 0.053999 0.203546 -vn 0.672956 -0.724776 0.147751 -v 0.071271 0.053999 0.204061 -vn 0.687099 -0.725388 0.041312 -v 0.071197 0.053999 0.204590 -vn 0.685423 -0.725067 -0.066875 -v 0.071208 0.053999 0.205165 -vn 0.668217 -0.724209 -0.170312 -v 0.071298 0.053999 0.205673 -vn 0.634721 -0.724637 -0.268383 -v 0.071464 0.053999 0.206170 -vn 0.590793 -0.722935 -0.358231 -v 0.071712 0.053999 0.206650 -vn -0.690231 -0.689288 -0.220142 -v 0.071369 0.053999 0.203703 -vn -0.651070 -0.696198 -0.302351 -v 0.071544 0.053999 0.203277 -vn -0.618867 -0.696550 -0.363073 -v 0.071639 0.053999 0.203094 -vn -0.580175 -0.695314 -0.424188 -v 0.071890 0.053999 0.202710 -vn 0.121028 -0.692939 -0.710765 -v 0.075424 0.053999 0.201388 -vn 0.203074 -0.694006 -0.690737 -v 0.075551 0.053999 0.201418 -vn -0.480634 -0.695046 -0.534698 -v 0.072388 0.053999 0.202173 -vn -0.531955 -0.694599 -0.484310 -v 0.072071 0.053999 0.202488 -vn 0.532521 -0.695472 -0.482432 -v 0.077312 0.053999 0.202493 -vn 0.479634 -0.695625 -0.534843 -v 0.076991 0.053999 0.202173 -vn -0.312855 -0.700456 0.641470 -v 0.073082 0.053999 0.207919 -vn -0.366043 -0.695776 0.617987 -v 0.073043 0.053999 0.207899 -vn 0.639311 -0.695905 0.327106 -v 0.077836 0.053999 0.206344 -vn 0.665332 -0.697672 0.265683 -v 0.077925 0.053999 0.206145 -vn 0.598966 -0.696545 -0.395052 -v 0.077543 0.053999 0.202784 -vn 0.602777 -0.695671 0.390771 -v 0.077591 0.053999 0.206768 -vn 0.562939 -0.698589 0.441671 -v 0.077454 0.053999 0.206958 -vn 0.523772 -0.695911 0.491295 -v 0.077260 0.053999 0.207186 -vn 0.469893 -0.694960 0.544272 -v 0.076969 0.053999 0.207467 -vn 0.409109 -0.695625 0.590539 -v 0.076683 0.053999 0.207688 -vn 0.357697 -0.700641 0.617377 -v 0.076375 0.053999 0.207878 -vn -0.431804 -0.694211 0.575862 -v 0.072484 0.053999 0.207528 -vn -0.489615 -0.695576 0.525787 -v 0.072388 0.053999 0.207447 -vn -0.541804 -0.695275 0.472272 -v 0.071982 0.053999 0.207028 -vn -0.589062 -0.694866 0.412514 -v 0.071890 0.053999 0.206910 -vn -0.650122 -0.686888 0.324848 -v 0.071567 0.053999 0.206392 -vn -0.701168 -0.685704 0.195380 -v 0.071318 0.053999 0.205750 -vn 0.311219 -0.685976 -0.657707 -v 0.076177 0.053999 0.201642 -vn 0.414728 -0.691958 -0.590927 -v 0.076790 0.053999 0.202011 -vn 0.308075 -0.695350 0.649291 -v 0.076337 0.053999 0.207899 -vn 0.232718 -0.693402 0.681936 -v 0.075690 0.053999 0.208164 -vn 0.153781 -0.694677 0.702692 -v 0.075551 0.053999 0.208203 -vn 0.066020 -0.691781 0.719083 -v 0.074941 0.053999 0.208301 -vn -0.017869 -0.695782 0.718031 -v 0.074606 0.053999 0.208309 -vn -0.093494 -0.694580 0.713315 -v 0.074254 0.053999 0.208283 -vn -0.176936 -0.693536 0.698356 -v 0.073829 0.053999 0.208203 -vn -0.258034 -0.694471 0.671661 -v 0.073422 0.053999 0.208073 -vn -0.726138 -0.685475 0.053367 -v 0.071200 0.053999 0.205077 -vn -0.721458 -0.685981 -0.094495 -v 0.071222 0.053999 0.204338 -vn -0.413468 -0.691848 -0.591938 -v 0.072592 0.053999 0.202009 -vn -0.305780 -0.684878 -0.661393 -v 0.073217 0.053999 0.201635 -vn -0.000797 -0.684203 -0.729291 -v 0.074690 0.053999 0.201310 -vn -0.158162 -0.684495 -0.711654 -v 0.073927 0.053999 0.201395 -vn 0.635122 -0.695995 -0.334980 -v 0.077836 0.053999 0.203277 -vn 0.662344 -0.697335 -0.273905 -v 0.077890 0.053999 0.203394 -vn 0.687705 -0.696384 0.205208 -v 0.078050 0.053999 0.205790 -vn 0.685613 -0.695950 -0.213513 -v 0.078050 0.053999 0.203830 -vn 0.711860 -0.691182 0.124589 -v 0.078117 0.053999 0.205518 -vn 0.709818 -0.692097 -0.130996 -v 0.078105 0.053999 0.204045 -vn 0.124576 -0.000764 0.992210 -v 0.075125 0.061740 0.208283 -vn 0.245432 -0.000455 0.969414 -v 0.075551 0.061804 0.208203 -vn 0.245689 0.000000 0.969349 -v 0.075551 0.063756 0.208203 -vn 0.731061 -0.007193 0.682274 -v 0.077260 0.066658 0.207186 -vn 0.830274 -0.080086 0.551571 -v 0.077490 0.066983 0.206910 -vn 0.823755 -0.248856 0.509410 -v 0.077490 0.067211 0.206971 -vn -0.814662 -0.479044 0.326867 -v 0.071890 0.067330 0.207086 -vn -0.816677 -0.530603 0.226934 -v 0.071890 0.067359 0.207137 -vn -0.898583 -0.377253 0.224117 -v 0.071544 0.067843 0.206840 -vn -0.896716 -0.442606 -0.000052 -v 0.071544 0.067965 0.207793 -vn -0.812934 -0.582356 0.000000 -v 0.071890 0.067399 0.208153 -vn -0.808639 -0.588302 0.001911 -v 0.071890 0.067399 0.209577 -vn -0.736267 -0.676637 0.008532 -v 0.072119 0.067124 0.209724 -vn -0.419965 -0.019794 0.907324 -v 0.073228 0.066210 0.207991 -vn -0.482524 -0.006176 0.875861 -v 0.073043 0.066323 0.207899 -vn -0.473614 -0.004128 0.880723 -v 0.073043 0.066071 0.207899 -vn -0.727610 -0.478590 0.491462 -v 0.072215 0.067017 0.207294 -vn -0.721309 -0.564198 0.401739 -v 0.072183 0.067046 0.207277 -vn -0.706604 -0.416386 0.572130 -v 0.072183 0.067037 0.207267 -vn -0.730907 -0.680703 0.049180 -v 0.072249 0.066992 0.207325 -vn -0.695675 -0.717727 -0.030076 -v 0.072249 0.066991 0.207331 -vn -0.683192 -0.729018 0.042203 -v 0.072215 0.067023 0.207308 -vn -0.772555 -0.553623 0.310903 -v 0.072388 0.066862 0.207450 -vn -0.706872 -0.703345 0.075085 -v 0.072388 0.066863 0.207454 -vn -0.662044 -0.748954 -0.027658 -v 0.072352 0.066895 0.207431 -vn -0.576940 0.053424 0.815037 -v 0.072538 0.066733 0.207571 -vn -0.622804 -0.004593 0.782364 -v 0.072538 0.066725 0.207571 -vn -0.583916 0.033854 0.811108 -v 0.072577 0.066688 0.207601 -vn -0.645749 -0.751871 0.133038 -v 0.072697 0.066622 0.207692 -vn -0.598694 -0.800511 0.027356 -v 0.072697 0.066622 0.207697 -vn -0.586651 -0.809767 0.010879 -v 0.072656 0.066651 0.207677 -vn -0.645980 -0.550794 0.528522 -v 0.072822 0.066537 0.207773 -vn -0.642796 -0.347216 0.682828 -v 0.072822 0.066535 0.207771 -vn -0.581170 -0.154800 0.798923 -v 0.072844 0.066519 0.207784 -vn -0.549828 -0.834723 0.030454 -v 0.072844 0.066526 0.207795 -vn -0.527108 -0.849751 -0.008982 -v 0.072822 0.066540 0.207786 -vn -0.596468 -0.767504 0.234867 -v 0.072822 0.066539 0.207776 -vn -0.591014 -0.415084 0.691671 -v 0.073065 0.066395 0.207910 -vn -0.589237 -0.545997 0.595556 -v 0.073043 0.066409 0.207899 -vn -0.497025 -0.139930 0.856380 -v 0.073043 0.066406 0.207898 -vn -0.554195 -0.788894 0.265545 -v 0.073065 0.066398 0.207916 -vn -0.583964 -0.654048 0.480840 -v 0.073088 0.066385 0.207925 -vn -0.483173 -0.870880 0.090063 -v 0.073088 0.066388 0.207933 -vn -0.446208 -0.888875 0.103920 -v 0.073252 0.066308 0.208009 -vn -0.425842 -0.904746 0.009608 -v 0.073228 0.066319 0.208001 -vn -0.520875 -0.682479 0.512750 -v 0.073228 0.066319 0.207991 -vn -0.355448 0.052980 0.933193 -v 0.073348 0.066254 0.208043 -vn -0.393733 0.014177 0.919116 -v 0.073324 0.066267 0.208033 -vn -0.396492 -0.003213 0.918033 -v 0.073324 0.066251 0.208033 -vn -0.394202 -0.919024 0.000417 -v 0.073324 0.066277 0.208082 -vn -0.392265 -0.919826 0.006932 -v 0.073324 0.066277 0.208123 -vn -0.424435 -0.905458 0.000424 -v 0.073228 0.066319 0.208094 -vn -0.380099 -0.924924 -0.006425 -v 0.073348 0.066266 0.208068 -vn -0.372800 -0.927820 -0.013034 -v 0.073373 0.066256 0.208075 -vn -0.376650 -0.926352 0.002787 -v 0.073373 0.066256 0.208096 -vn -0.320239 -0.125480 0.938990 -v 0.073673 0.066142 0.208158 -vn -0.286398 0.038132 0.957352 -v 0.073622 0.066154 0.208144 -vn -0.306708 -0.049268 0.950528 -v 0.073622 0.066146 0.208144 -vn -0.376772 -0.920663 0.102088 -v 0.073471 0.066218 0.208102 -vn -0.363707 -0.931513 -0.000339 -v 0.073422 0.066237 0.208089 -vn -0.387780 -0.920733 0.043327 -v 0.073422 0.066237 0.208078 -vn -0.458703 -0.500758 0.734052 -v 0.073546 0.066185 0.208118 -vn -0.461688 -0.685263 0.563258 -v 0.073521 0.066195 0.208110 -vn -0.429362 -0.321377 0.844017 -v 0.073521 0.066193 0.208108 -vn -0.305220 -0.936249 0.174006 -v 0.073724 0.066136 0.208183 -vn -0.264708 -0.963592 -0.037681 -v 0.073724 0.066136 0.208188 -vn -0.285264 -0.958405 -0.009170 -v 0.073673 0.066150 0.208178 -vn -0.112317 0.020884 0.993453 -v 0.074254 0.066011 0.208283 -vn -0.115985 -0.029505 0.992813 -v 0.074254 0.066004 0.208283 -vn -0.085213 -0.262729 0.961099 -v 0.074471 0.065994 0.208304 -vn -0.050878 0.217914 0.974641 -v 0.074471 0.065998 0.208302 -vn -0.039542 -0.157372 0.986747 -v 0.074580 0.065995 0.208308 -vn 0.085216 -0.262746 0.961095 -v 0.074908 0.065994 0.208304 -vn 0.000000 0.000411 1.000000 -v 0.074690 0.065985 0.208310 -vn -0.000063 -0.012026 0.999928 -v 0.074690 0.065970 0.208310 -vn 0.171644 -0.471027 0.865258 -v 0.075179 0.066032 0.208276 -vn 0.160930 -0.525932 0.835163 -v 0.075125 0.066025 0.208282 -vn 0.101619 0.088662 0.990865 -v 0.075125 0.066019 0.208283 -vn 0.302572 -0.898248 0.318749 -v 0.075499 0.066094 0.208217 -vn 0.303659 -0.644927 0.701328 -v 0.075446 0.066080 0.208228 -vn 0.264973 -0.224193 0.937831 -v 0.075446 0.066077 0.208227 -vn 0.231686 -0.202083 0.951569 -v 0.075393 0.066066 0.208238 -vn 0.275891 -0.903097 0.329089 -v 0.075446 0.066082 0.208231 -vn 0.386773 -0.917468 0.093058 -v 0.075908 0.066218 0.208102 -vn 0.372339 -0.928093 0.002675 -v 0.075958 0.066237 0.208089 -vn 0.363449 -0.931608 0.003477 -v 0.075958 0.066237 0.208109 -vn 0.303033 -0.937913 0.168793 -v 0.075655 0.066136 0.208183 -vn 0.349074 -0.801603 0.485366 -v 0.075655 0.066134 0.208179 -vn 0.320049 -0.933925 0.159227 -v 0.075706 0.066150 0.208168 -vn 0.322399 -0.865476 0.383420 -v 0.075603 0.066121 0.208193 -vn 0.262654 -0.964888 0.001963 -v 0.075603 0.066122 0.208197 -vn 0.278710 -0.957477 0.074551 -v 0.075551 0.066108 0.208207 -vn 0.382352 -0.056591 0.922282 -v 0.075982 0.066238 0.208062 -vn 0.352166 0.033124 0.935351 -v 0.075982 0.066230 0.208063 -vn 0.354075 0.056614 0.933502 -v 0.076007 0.066242 0.208053 -vn 0.428683 -0.012196 0.903373 -v 0.076151 0.066307 0.207991 -vn 0.405456 0.028511 0.913670 -v 0.076151 0.066311 0.207991 -vn 0.363141 0.093833 0.926997 -v 0.076103 0.066285 0.208012 -vn 0.443461 -0.896292 0.001788 -v 0.076245 0.066364 0.207981 -vn 0.486597 -0.873606 0.006034 -v 0.076337 0.066411 0.207948 -vn 0.484247 -0.874930 0.001622 -v 0.076337 0.066411 0.208114 -vn 0.411483 -0.911267 0.016574 -v 0.076103 0.066298 0.208026 -vn 0.421059 -0.907032 0.001206 -v 0.076151 0.066319 0.208012 -vn 0.422662 -0.906285 0.002238 -v 0.076151 0.066319 0.208094 -vn 0.606849 -0.096337 0.788957 -v 0.076620 0.066570 0.207729 -vn 0.541981 -0.004473 0.840379 -v 0.076599 0.066553 0.207743 -vn 0.551198 -0.012803 0.834276 -v 0.076599 0.066545 0.207743 -vn 0.671481 -0.459549 0.581316 -v 0.076599 0.066564 0.207745 -vn 0.595346 -0.161432 0.787085 -v 0.076599 0.066561 0.207743 -vn 0.672444 -0.445520 0.591043 -v 0.076620 0.066577 0.207731 -vn 0.616500 -0.765262 0.185208 -v 0.076620 0.066580 0.207737 -vn 0.605353 -0.790224 0.095366 -v 0.076641 0.066594 0.207727 -vn 0.554864 -0.831876 -0.010364 -v 0.076641 0.066594 0.207738 -vn 0.447278 0.059399 0.892420 -v 0.076337 0.066397 0.207899 -vn 0.477485 -0.004127 0.878630 -v 0.076337 0.066393 0.207899 -vn 0.451123 0.067735 0.889887 -v 0.076382 0.066424 0.207873 -vn 0.551771 -0.833363 0.032491 -v 0.076599 0.066566 0.207799 -vn 0.574723 -0.818344 0.002696 -v 0.076683 0.066622 0.207760 -vn 0.579395 -0.815021 0.006470 -v 0.076683 0.066622 0.207803 -vn 0.702927 -0.330654 0.629732 -v 0.076861 0.066750 0.207557 -vn 0.553181 0.059782 0.830913 -v 0.076842 0.066733 0.207571 -vn 0.619176 -0.010406 0.785184 -v 0.076842 0.066725 0.207571 -vn 0.668971 -0.681104 0.297616 -v 0.076703 0.066636 0.207677 -vn 0.645289 -0.748420 0.153197 -v 0.076723 0.066651 0.207667 -vn 0.587381 -0.809202 0.013294 -v 0.076723 0.066651 0.207677 -vn 0.675525 -0.245296 0.695339 -v 0.076842 0.066737 0.207570 -vn 0.763799 -0.393007 0.512012 -v 0.076899 0.066781 0.207524 -vn 0.756654 -0.541623 0.366223 -v 0.076918 0.066799 0.207510 -vn 0.677039 -0.734771 0.041603 -v 0.076918 0.066800 0.207520 -vn 0.711241 -0.682105 0.169910 -v 0.076899 0.066784 0.207531 -vn 0.644119 -0.764908 0.005109 -v 0.076918 0.066800 0.207530 -vn 0.664917 0.017775 0.746706 -v 0.077062 0.066913 0.207384 -vn 0.708254 -0.113301 0.696806 -v 0.077062 0.066921 0.207383 -vn 0.665690 0.008683 0.746178 -v 0.077027 0.066882 0.207415 -vn 0.794528 -0.420644 0.437931 -v 0.077079 0.066940 0.207369 -vn 0.716394 -0.693197 0.079099 -v 0.077045 0.066910 0.207409 -vn 0.694796 -0.718969 0.018500 -v 0.077062 0.066926 0.207398 -vn 0.686237 -0.727364 0.004611 -v 0.077062 0.066926 0.207420 -vn 0.812133 -0.583470 0.002023 -v 0.077490 0.067399 0.207797 -vn 0.806349 -0.591385 0.008021 -v 0.077490 0.067399 0.207441 -vn 0.902231 -0.423763 0.080029 -v 0.077836 0.067939 0.207087 -vn 0.903133 -0.400683 0.154289 -v 0.077836 0.067898 0.206955 -vn 0.902333 0.087341 -0.422098 -v 0.077836 0.067896 0.203378 -vn 0.897695 0.166704 -0.407864 -v 0.077836 0.068482 0.203559 -vn 0.957898 0.084246 -0.274472 -v 0.078050 0.068027 0.203986 -vn 0.567968 0.544474 -0.617220 -v 0.076682 0.070559 0.203280 -vn 0.469315 0.588739 -0.658126 -v 0.076337 0.070727 0.203147 -vn 0.469254 0.659149 -0.587642 -v 0.076337 0.071169 0.203591 -vn -0.732737 0.129283 -0.668119 -v 0.072119 0.067936 0.202526 -vn -0.798342 0.091887 -0.595153 -v 0.071890 0.067714 0.202766 -vn -0.803943 0.180225 -0.566740 -v 0.071890 0.068355 0.202915 -vn -0.999993 0.002849 -0.002473 -v 0.071190 0.069144 0.206027 -vn -0.999996 0.002734 -0.000658 -v 0.071190 0.069274 0.206274 -vn -0.990015 0.127300 -0.060543 -v 0.071221 0.069673 0.206031 -vn -0.999994 0.002994 -0.001577 -v 0.071190 0.069381 0.206550 -vn -0.999992 0.003838 -0.000627 -v 0.071190 0.069458 0.206862 -vn -0.989963 0.137619 -0.032146 -v 0.071221 0.069881 0.206614 -vn 0.896806 0.000377 -0.442424 -v 0.077836 0.059886 0.203277 -vn 0.469595 0.000366 -0.882882 -v 0.076337 0.065404 0.201722 -vn 0.474783 0.035633 -0.879381 -v 0.076337 0.067033 0.201723 -vn 0.573033 0.022833 -0.819214 -v 0.076682 0.066863 0.201933 -vn -0.896927 0.000677 -0.442178 -v 0.071544 0.059886 0.203277 -vn -0.568521 -0.000057 -0.822669 -v 0.072697 0.063646 0.201933 -vn -0.675733 -0.000294 -0.737147 -v 0.072388 0.063500 0.202173 -vn -0.657399 0.006753 -0.753512 -v 0.072388 0.066668 0.202173 -vn -0.990560 -0.000003 -0.137080 -v 0.071221 0.064906 0.204346 -vn -0.958651 -0.000015 -0.284586 -v 0.071330 0.065323 0.203830 -vn -0.958701 -0.000400 -0.284416 -v 0.071330 0.059661 0.203830 -vn -0.470626 -0.000861 0.882332 -v 0.073043 0.062047 0.207899 -vn 0.533208 0.448870 -0.717081 -v 0.077422 0.071686 0.210310 -vn 0.567716 0.406730 -0.715730 -v 0.077489 0.071600 0.210310 -vn 0.798170 0.602422 -0.003510 -v 0.077490 0.071599 0.209142 -vn 0.645665 -0.261873 -0.717314 -v 0.077910 0.068128 0.210310 -vn 0.627914 -0.309787 -0.713972 -v 0.077836 0.067965 0.210310 -vn 0.895884 -0.444256 -0.005308 -v 0.077836 0.067965 0.209273 -vn 0.094330 -0.595586 -0.797734 -v 0.075150 0.066030 0.210310 -vn 0.099445 -0.969713 0.223085 -v 0.075125 0.066026 0.210308 -vn 0.241475 -0.970407 0.000186 -v 0.075551 0.066107 0.210265 -vn 0.177287 -0.669773 -0.721092 -v 0.075563 0.066110 0.210310 -vn 0.375826 -0.926531 0.017170 -v 0.075958 0.066237 0.210196 -vn 0.228961 -0.647569 -0.726795 -v 0.075884 0.066209 0.210310 -vn 0.475366 -0.879756 0.007479 -v 0.076337 0.066411 0.210104 -vn 0.306632 -0.616626 -0.725085 -v 0.076273 0.066378 0.210310 -vn 0.660409 -0.750881 0.006168 -v 0.076991 0.066862 0.209864 -vn 0.438974 -0.534071 -0.722544 -v 0.076906 0.066790 0.210310 -vn 0.380589 -0.577270 -0.722435 -v 0.076636 0.066590 0.210310 -vn 0.733005 -0.680222 0.001473 -v 0.077260 0.067124 0.209724 -vn 0.554196 -0.419691 -0.718837 -v 0.077490 0.067399 0.210310 -vn 0.497925 -0.481225 -0.721452 -v 0.077217 0.067078 0.210310 -vn 0.867978 -0.496488 -0.010679 -v 0.077721 0.067750 0.210310 -vn 0.589766 -0.371741 -0.716927 -v 0.077677 0.067676 0.210310 -vn 0.990616 -0.136667 -0.001173 -v 0.078159 0.069035 0.208696 -vn 0.693170 -0.098825 -0.713967 -v 0.078159 0.069035 0.210310 -vn 0.683001 -0.144990 -0.715883 -v 0.078112 0.068768 0.210310 -vn 0.958556 0.284893 -0.002567 -v 0.078050 0.070479 0.207910 -vn 0.686895 0.084221 -0.721860 -v 0.078164 0.069922 0.210310 -vn 0.990467 0.137750 0.000264 -v 0.078159 0.069964 0.208191 -vn 0.693678 0.004350 -0.720272 -v 0.078190 0.069499 0.210310 -vn 0.621771 0.301810 -0.722711 -v 0.077829 0.071047 0.210310 -vn 0.652316 0.235395 -0.720467 -v 0.077992 0.070658 0.210310 -vn 0.675063 0.160300 -0.720135 -v 0.078088 0.070335 0.210310 -vn 0.906596 0.421980 -0.004212 -v 0.077836 0.071033 0.207608 -vn 0.864864 0.501388 -0.024905 -v 0.077721 0.071249 0.210310 -vn -0.566807 0.823850 0.001065 -v 0.072697 0.072376 0.208794 -vn -0.307108 0.620948 -0.721185 -v 0.073157 0.072646 0.210310 -vn -0.469474 0.882944 0.002085 -v 0.073043 0.072587 0.208701 -vn -0.239108 0.650822 -0.720596 -v 0.073466 0.072778 0.210310 -vn -0.361283 0.932455 0.001312 -v 0.073422 0.072761 0.208623 -vn -0.162353 0.672985 -0.721618 -v 0.073868 0.072901 0.210310 -vn -0.245660 0.969355 0.001168 -v 0.073828 0.072891 0.208565 -vn -0.084728 0.688866 -0.719920 -v 0.074285 0.072976 0.210310 -vn -0.124865 0.992174 0.000339 -v 0.074254 0.072971 0.208528 -vn -0.010422 0.694451 -0.719465 -v 0.074619 0.072998 0.210310 -vn -0.000067 1.000000 -0.000411 -v 0.074690 0.072999 0.208516 -vn 0.069316 0.690136 -0.720353 -v 0.075039 0.072982 0.210310 -vn 0.124386 0.992234 -0.000472 -v 0.075125 0.072971 0.208528 -vn 0.148273 0.678905 -0.719099 -v 0.075457 0.072914 0.210310 -vn 0.245690 0.969348 -0.000757 -v 0.075551 0.072891 0.208565 -vn 0.220694 0.659244 -0.718813 -v 0.075783 0.072824 0.210310 -vn 0.361708 0.932291 -0.000999 -v 0.075957 0.072761 0.208623 -vn 0.294260 0.628606 -0.719906 -v 0.076173 0.072669 0.210310 -vn 0.469691 0.882830 -0.001223 -v 0.076337 0.072587 0.208701 -vn 0.365118 0.591811 -0.718643 -v 0.076545 0.072467 0.210310 -vn 0.568441 0.822723 -0.001609 -v 0.076682 0.072376 0.208794 -vn 0.426518 0.549507 -0.718418 -v 0.076821 0.072276 0.210310 -vn 0.675467 0.737384 -0.002914 -v 0.076991 0.072136 0.208902 -vn 0.486118 0.492604 -0.721824 -v 0.077138 0.072000 0.210310 -vn -0.799799 0.600255 -0.003960 -v 0.071890 0.071599 0.209142 -vn -0.497081 0.483627 -0.720427 -v 0.072200 0.071959 0.210310 -vn -0.675117 0.737705 -0.002838 -v 0.072388 0.072136 0.208902 -vn -0.442002 0.536698 -0.718742 -v 0.072450 0.072188 0.210310 -vn -0.374484 0.582502 -0.721424 -v 0.072788 0.072437 0.210310 -vn -0.624205 0.295033 -0.723412 -v 0.071527 0.070998 0.210310 -vn -0.871206 0.490412 -0.022248 -v 0.071659 0.071249 0.210310 -vn -0.590092 0.368379 -0.718393 -v 0.071684 0.071293 0.210310 -vn -0.547147 0.425046 -0.721087 -v 0.071921 0.071641 0.210310 -vn -0.958605 0.284733 -0.002027 -v 0.071330 0.070479 0.207910 -vn -0.990736 0.135788 -0.001739 -v 0.071221 0.069964 0.208191 -vn -0.680145 0.142923 -0.719010 -v 0.071260 0.070199 0.210310 -vn -0.691551 0.068596 -0.719063 -v 0.071209 0.069867 0.210310 -vn -0.999999 -0.000710 -0.000982 -v 0.071190 0.069499 0.208444 -vn -0.693188 -0.011131 -0.720671 -v 0.071190 0.069443 0.210310 -vn -0.674445 -0.160548 -0.720658 -v 0.071283 0.068694 0.210310 -vn -0.958782 -0.284138 -0.001749 -v 0.071330 0.068519 0.208974 -vn -0.652387 -0.237824 -0.719604 -v 0.071406 0.068289 0.210310 -vn -0.895805 -0.444417 -0.005282 -v 0.071544 0.067965 0.209273 -vn -0.576016 -0.385359 -0.720905 -v 0.071742 0.067612 0.210310 -vn -0.865338 -0.501044 -0.012061 -v 0.071659 0.067749 0.210310 -vn -0.622688 -0.325630 -0.711495 -v 0.071575 0.067903 0.210310 -vn -0.635435 -0.294122 -0.713943 -v 0.071544 0.067965 0.210310 -vn -0.214545 -0.645636 -0.732887 -v 0.073567 0.066184 0.210310 -vn -0.260863 -0.618137 -0.741523 -v 0.073254 0.066307 0.210310 -vn -0.472204 -0.881483 0.003425 -v 0.073043 0.066411 0.210104 -vn 0.124525 -0.992216 -0.000318 -v 0.075125 0.066026 0.209018 -vn 0.025675 -0.699419 -0.714251 -v 0.074728 0.065999 0.210310 -vn 0.000470 -0.999999 -0.001412 -v 0.074690 0.065999 0.209036 -vn -0.009272 -0.999928 -0.007652 -v 0.074690 0.065999 0.210310 -vn -0.057317 -0.696159 -0.715596 -v 0.074392 0.066012 0.210310 -vn 0.733597 -0.000032 0.679585 -v 0.077260 0.062618 0.207186 -vn 0.656751 -0.000065 0.754108 -v 0.076991 0.062408 0.207447 -vn 0.568586 0.000051 0.822624 -v 0.076683 0.062216 0.207688 -vn 0.469452 -0.000583 0.882958 -v 0.076337 0.062047 0.207899 -vn 0.812601 0.000471 0.582820 -v 0.077490 0.062839 0.206910 -vn 0.896463 0.000634 0.443119 -v 0.077836 0.063294 0.206344 -vn -0.990547 -0.000284 0.137171 -v 0.071221 0.064155 0.205275 -vn -0.958894 -0.000747 0.283763 -v 0.071330 0.063740 0.205790 -vn -0.896749 -0.000064 0.442540 -v 0.071544 0.063294 0.206344 -vn -0.812803 0.000169 0.582538 -v 0.071890 0.062839 0.206910 -vn -0.733518 -0.000341 0.679670 -v 0.072119 0.062618 0.207186 -vn 0.362504 -0.001106 0.931981 -v 0.075958 0.061908 0.208073 -vn -0.797007 0.000008 -0.603970 -v 0.071890 0.063173 0.202710 -vn -0.810384 -0.003794 -0.585887 -v 0.071890 0.066231 0.202711 -vn -0.734361 -0.000774 -0.678759 -v 0.072119 0.066455 0.202435 -vn -0.469784 -0.000013 -0.882781 -v 0.073043 0.063775 0.201722 -vn -0.470200 -0.000309 -0.882560 -v 0.073043 0.060516 0.201722 -vn -0.568031 -0.000560 -0.823007 -v 0.072697 0.060431 0.201933 -vn -0.675866 0.000213 -0.737024 -v 0.072388 0.060333 0.202173 -vn -0.796893 0.000478 -0.604121 -v 0.071890 0.060115 0.202710 -vn -0.999988 0.000345 -0.004970 -v 0.071190 0.059265 0.204810 -vn -0.990476 -0.000655 -0.137685 -v 0.071221 0.059453 0.204346 -vn -1.000000 0.000000 -0.000001 -v 0.071190 0.064531 0.204810 -vn -0.361290 -0.000138 -0.932454 -v 0.073422 0.060587 0.201548 -vn 0.366010 0.048035 -0.929371 -v 0.075957 0.067172 0.201552 -vn 0.361889 0.001417 -0.932220 -v 0.075957 0.065528 0.201548 -vn 0.248404 0.058219 -0.966905 -v 0.075551 0.067275 0.201425 -vn 0.245862 0.002373 -0.969302 -v 0.075551 0.065621 0.201418 -vn 0.125372 0.064466 -0.990013 -v 0.075125 0.067338 0.201347 -vn 0.124351 0.003088 -0.992233 -v 0.075125 0.065678 0.201338 -vn 0.000567 0.066090 -0.997814 -v 0.074690 0.067359 0.201321 -vn 0.000120 0.003190 -0.999995 -v 0.074690 0.065697 0.201310 -vn -0.124053 0.062760 -0.990289 -v 0.074254 0.067338 0.201347 -vn -0.124151 0.002589 -0.992260 -v 0.074254 0.065678 0.201338 -vn -0.246550 0.054607 -0.967591 -v 0.073828 0.067275 0.201425 -vn -0.245681 0.001621 -0.969349 -v 0.073828 0.065621 0.201418 -vn -0.363487 0.042676 -0.930621 -v 0.073422 0.067172 0.201552 -vn -0.361732 0.000689 -0.932282 -v 0.073422 0.065528 0.201548 -vn -0.471749 0.029009 -0.881256 -v 0.073043 0.067033 0.201723 -vn -0.469704 0.000097 -0.882824 -v 0.073043 0.065404 0.201722 -vn -0.569962 0.016194 -0.821512 -v 0.072697 0.066863 0.201933 -vn 0.361629 -0.000056 -0.932322 -v 0.075957 0.063881 0.201548 -vn 0.245650 -0.000073 -0.969359 -v 0.075551 0.063960 0.201418 -vn 0.124260 -0.000066 -0.992250 -v 0.075125 0.064009 0.201338 -vn 0.000004 -0.000064 -1.000000 -v 0.074690 0.064026 0.201310 -vn -0.124260 -0.000073 -0.992250 -v 0.074254 0.064009 0.201338 -vn -0.245664 -0.000064 -0.969355 -v 0.073828 0.063960 0.201418 -vn -0.361638 -0.000034 -0.932319 -v 0.073422 0.063881 0.201548 -vn 0.469795 -0.000024 -0.882776 -v 0.076337 0.063775 0.201722 -vn 0.568540 -0.000032 -0.822655 -v 0.076682 0.063646 0.201933 -vn 0.674369 -0.001868 -0.738392 -v 0.076991 0.063500 0.202173 -vn 0.360881 -0.000751 -0.932612 -v 0.075957 0.060587 0.201548 -vn 0.246096 -0.000743 -0.969245 -v 0.075551 0.060640 0.201418 -vn 0.123485 -0.001243 -0.992346 -v 0.075125 0.060673 0.201338 -vn 0.000727 -0.001095 -0.999999 -v 0.074690 0.060684 0.201310 -vn -0.124166 0.000108 -0.992262 -v 0.074254 0.060673 0.201338 -vn -0.245937 -0.000084 -0.969286 -v 0.073828 0.060640 0.201418 -vn 0.797294 -0.001035 -0.603591 -v 0.077490 0.063173 0.202710 -vn 0.896614 -0.000008 -0.442814 -v 0.077836 0.065772 0.203277 -vn 0.470106 -0.000109 -0.882610 -v 0.076337 0.060516 0.201722 -vn 0.568269 -0.000450 -0.822843 -v 0.076682 0.060431 0.201933 -vn 0.675526 0.000566 -0.737336 -v 0.076991 0.060333 0.202173 -vn 0.797381 0.001090 -0.603476 -v 0.077490 0.060115 0.202710 -vn 0.958606 0.000321 -0.284734 -v 0.078050 0.059661 0.203830 -vn 0.958647 -0.000033 -0.284597 -v 0.078050 0.065323 0.203830 -vn 0.990626 0.000442 -0.136602 -v 0.078159 0.059453 0.204346 -vn 0.990559 -0.000008 -0.137087 -v 0.078159 0.064906 0.204346 -vn 0.999946 -0.000912 0.010306 -v 0.078190 0.059265 0.204810 -vn 1.000000 -0.000001 -0.000001 -v 0.078190 0.064531 0.204810 -vn 0.990559 -0.000029 0.137085 -v 0.078159 0.064155 0.205275 -vn -0.807218 0.589983 -0.017842 -v 0.071890 0.071599 0.207298 -vn -0.895210 0.441562 -0.060191 -v 0.071544 0.070995 0.206761 -vn -0.896641 0.442700 -0.007146 -v 0.071544 0.071033 0.207608 -vn -0.957832 0.286223 -0.025176 -v 0.071330 0.070470 0.207056 -vn -0.990385 0.138204 -0.006170 -v 0.071221 0.069964 0.207352 -vn -0.999999 0.001438 0.000524 -v 0.071190 0.069499 0.207627 -vn -0.990482 -0.137640 -0.000584 -v 0.071221 0.069035 0.208696 -vn -0.687044 -0.092058 -0.720761 -v 0.071222 0.069025 0.210310 -vn -0.957713 0.276764 -0.078657 -v 0.071330 0.070343 0.206346 -vn -0.957724 0.257686 -0.127919 -v 0.071330 0.070115 0.205760 -vn -0.895395 0.423760 -0.136732 -v 0.071544 0.070835 0.206062 -vn -0.895386 0.396307 -0.203038 -v 0.071544 0.070588 0.205469 -vn -0.810378 0.553472 -0.192240 -v 0.071890 0.071335 0.205774 -vn -0.798027 0.531088 -0.284778 -v 0.071890 0.071071 0.205170 -vn -0.656573 0.220479 -0.721319 -v 0.071369 0.070605 0.210310 -vn -0.957672 0.232648 -0.169529 -v 0.071330 0.069813 0.205263 -vn -0.989940 0.096238 -0.103713 -v 0.071221 0.069027 0.205148 -vn -0.990021 0.113195 -0.083939 -v 0.071221 0.069383 0.205548 -vn -0.999989 0.002702 -0.003898 -v 0.071190 0.068642 0.205426 -vn -0.999993 0.003113 -0.002189 -v 0.071190 0.068995 0.205805 -vn -0.991107 -0.103129 0.084094 -v 0.071221 0.068605 0.206060 -vn -0.955855 0.034314 -0.291829 -v 0.071330 0.067425 0.203856 -vn -0.899206 0.167664 -0.404125 -v 0.071544 0.068482 0.203559 -vn -0.909896 0.091394 -0.404643 -v 0.071544 0.067896 0.203378 -vn -0.852398 0.146200 -0.502039 -v 0.071699 0.068128 0.203143 -vn -0.854066 0.050135 -0.517743 -v 0.071699 0.067480 0.203020 -vn -0.799474 0.327090 -0.503838 -v 0.071890 0.069461 0.203425 -vn -0.814329 0.246080 -0.525655 -v 0.071890 0.068935 0.203138 -vn -0.905895 0.026321 -0.422683 -v 0.071544 0.067237 0.203285 -vn -0.896659 0.001632 -0.442720 -v 0.071544 0.066508 0.203277 -vn -0.958916 0.007924 -0.283579 -v 0.071330 0.066739 0.203830 -vn -0.990530 0.000495 -0.137296 -v 0.071221 0.066270 0.204346 -vn -1.000000 -0.000003 0.000006 -v 0.071190 0.065847 0.204810 -vn -0.676715 0.482403 -0.556187 -v 0.072388 0.070367 0.203432 -vn -0.676224 0.415204 -0.608545 -v 0.072388 0.069885 0.203061 -vn -0.810273 0.013472 -0.585898 -v 0.071890 0.066996 0.202710 -vn -0.896638 0.000008 -0.442765 -v 0.071544 0.065772 0.203277 -vn -0.739075 0.672808 -0.033117 -v 0.072119 0.071872 0.207151 -vn -0.674181 0.738566 -0.000672 -v 0.072388 0.072136 0.207953 -vn -0.570135 0.821509 -0.008355 -v 0.072697 0.072377 0.207833 -vn -0.471782 0.881623 -0.012733 -v 0.073043 0.072588 0.207728 -vn -0.363477 0.931448 -0.017038 -v 0.073422 0.072762 0.207641 -vn -0.247113 0.968767 -0.020659 -v 0.073828 0.072892 0.207576 -vn -0.125134 0.991875 -0.022931 -v 0.074254 0.072973 0.207536 -vn -0.000243 0.999726 -0.023416 -v 0.074690 0.073000 0.207522 -vn 0.124627 0.991961 -0.021934 -v 0.075125 0.072973 0.207536 -vn 0.246499 0.968962 -0.018726 -v 0.075551 0.072892 0.207576 -vn 0.362748 0.931777 -0.014340 -v 0.075957 0.072762 0.207641 -vn 0.470957 0.882104 -0.009582 -v 0.076337 0.072588 0.207728 -vn 0.569372 0.822063 -0.005361 -v 0.076682 0.072377 0.207833 -vn 0.674639 0.738148 0.000553 -v 0.076991 0.072136 0.207953 -vn 0.657293 0.751744 -0.053351 -v 0.076991 0.072128 0.207015 -vn 0.568208 0.819928 -0.069698 -v 0.076682 0.072360 0.206892 -vn 0.468874 0.879123 -0.085439 -v 0.076337 0.072563 0.206786 -vn 0.360572 0.927436 -0.099245 -v 0.075957 0.072729 0.206700 -vn 0.244701 0.963335 -0.110031 -v 0.075551 0.072853 0.206636 -vn 0.123541 0.985435 -0.116861 -v 0.075125 0.072929 0.206597 -vn -0.000418 0.992870 -0.119204 -v 0.074690 0.072955 0.206583 -vn -0.124334 0.985336 -0.116847 -v 0.074254 0.072929 0.206597 -vn -0.245398 0.963153 -0.110076 -v 0.073828 0.072853 0.206636 -vn -0.361130 0.927193 -0.099495 -v 0.073422 0.072729 0.206700 -vn -0.469337 0.878808 -0.086128 -v 0.073043 0.072563 0.206786 -vn -0.568689 0.819465 -0.071206 -v 0.072697 0.072360 0.206892 -vn -0.657717 0.751127 -0.056710 -v 0.072388 0.072128 0.207015 -vn 0.655639 0.737795 -0.160612 -v 0.076991 0.072015 0.206201 -vn 0.567588 0.802090 -0.185729 -v 0.076682 0.072234 0.206082 -vn 0.468871 0.858361 -0.208272 -v 0.076337 0.072426 0.205978 -vn 0.360790 0.904564 -0.227146 -v 0.075957 0.072584 0.205892 -vn 0.244959 0.939002 -0.241393 -v 0.075551 0.072702 0.205828 -vn 0.123738 0.960255 -0.250198 -v 0.075125 0.072775 0.205789 -vn -0.000325 0.967445 -0.253081 -v 0.074690 0.072800 0.205776 -vn -0.124358 0.960266 -0.249847 -v 0.074254 0.072775 0.205789 -vn -0.245484 0.939043 -0.240699 -v 0.073828 0.072702 0.205828 -vn -0.361165 0.904671 -0.226120 -v 0.073422 0.072584 0.205892 -vn -0.469060 0.858583 -0.206924 -v 0.073043 0.072426 0.205978 -vn -0.567595 0.802475 -0.184035 -v 0.072697 0.072234 0.206082 -vn -0.655423 0.738433 -0.158550 -v 0.072388 0.072015 0.206201 -vn -0.732125 0.668313 -0.131722 -v 0.072119 0.071775 0.206332 -vn -0.808308 0.579896 -0.101780 -v 0.071890 0.071522 0.206470 -vn 0.802243 0.586512 -0.111403 -v 0.077490 0.071522 0.206470 -vn 0.732593 0.667344 -0.134010 -v 0.077260 0.071775 0.206332 -vn 0.737389 0.674893 -0.027862 -v 0.077260 0.071872 0.207151 -vn 0.661451 0.700167 -0.268792 -v 0.076991 0.071807 0.205501 -vn 0.567764 0.768771 -0.294338 -v 0.076682 0.072018 0.205380 -vn 0.469037 0.822868 -0.320769 -v 0.076337 0.072203 0.205273 -vn 0.360958 0.867324 -0.342722 -v 0.075957 0.072355 0.205185 -vn 0.245121 0.900492 -0.359207 -v 0.075551 0.072469 0.205119 -vn 0.123897 0.920981 -0.369383 -v 0.075125 0.072539 0.205078 -vn -0.000190 0.927931 -0.372753 -v 0.074690 0.072563 0.205064 -vn -0.124254 0.921040 -0.369117 -v 0.074254 0.072539 0.205078 -vn -0.245430 0.900618 -0.358681 -v 0.073828 0.072469 0.205119 -vn -0.361179 0.867535 -0.341954 -v 0.073422 0.072355 0.205185 -vn -0.469156 0.823184 -0.319783 -v 0.073043 0.072203 0.205273 -vn -0.567778 0.769211 -0.293161 -v 0.072697 0.072018 0.205380 -vn -0.655741 0.707592 -0.263283 -v 0.072388 0.071807 0.205501 -vn -0.732256 0.639207 -0.234978 -v 0.072119 0.071577 0.205634 -vn 0.674555 0.651088 -0.347937 -v 0.076991 0.071528 0.204887 -vn 0.567833 0.724913 -0.389957 -v 0.076682 0.071733 0.204760 -vn 0.469114 0.776754 -0.420221 -v 0.076337 0.071912 0.204648 -vn 0.361051 0.819406 -0.445214 -v 0.075957 0.072060 0.204556 -vn 0.245231 0.851264 -0.463908 -v 0.075551 0.072171 0.204487 -vn 0.124009 0.870963 -0.475443 -v 0.075125 0.072239 0.204444 -vn -0.000078 0.877660 -0.479283 -v 0.074690 0.072262 0.204429 -vn -0.124153 0.871058 -0.475230 -v 0.074254 0.072239 0.204444 -vn -0.245357 0.851456 -0.463490 -v 0.073828 0.072171 0.204487 -vn -0.361140 0.819698 -0.444604 -v 0.073422 0.072060 0.204556 -vn -0.469163 0.777143 -0.419447 -v 0.073043 0.071912 0.204648 -vn -0.567839 0.725400 -0.389042 -v 0.072697 0.071733 0.204760 -vn -0.671482 0.652171 -0.351832 -v 0.072388 0.071528 0.204887 -vn 0.797015 0.533433 -0.283224 -v 0.077490 0.071071 0.205170 -vn 0.728688 0.637446 -0.250352 -v 0.077260 0.071577 0.205634 -vn 0.812248 0.549993 -0.194324 -v 0.077490 0.071335 0.205774 -vn 0.795764 0.605352 -0.017566 -v 0.077490 0.071599 0.207298 -vn 0.856609 0.515855 -0.010716 -v 0.077681 0.071317 0.207452 -vn 0.851400 0.516338 -0.092267 -v 0.077681 0.071260 0.206614 -vn 0.907414 0.416429 -0.056448 -v 0.077836 0.070995 0.206761 -vn 0.896848 0.419918 -0.139039 -v 0.077836 0.070835 0.206062 -vn 0.957519 0.287152 -0.026479 -v 0.078050 0.070470 0.207056 -vn 0.895177 0.397568 -0.201492 -v 0.077836 0.070588 0.205469 -vn 0.957109 0.279462 -0.076443 -v 0.078050 0.070343 0.206346 -vn 0.957532 0.259035 -0.126626 -v 0.078050 0.070115 0.205760 -vn 0.989460 0.141594 -0.030344 -v 0.078159 0.069881 0.206614 -vn 0.989816 0.128976 -0.060240 -v 0.078159 0.069673 0.206031 -vn 0.999983 0.005774 0.000753 -v 0.078190 0.069458 0.206862 -vn 0.999994 0.003236 -0.001377 -v 0.078190 0.069381 0.206550 -vn 0.674393 0.603078 -0.426018 -v 0.076991 0.071191 0.204342 -vn 0.567880 0.672473 -0.474649 -v 0.076682 0.071391 0.204208 -vn 0.469181 0.721940 -0.508597 -v 0.076337 0.071566 0.204090 -vn 0.361145 0.762708 -0.536517 -v 0.075957 0.071710 0.203992 -vn 0.245331 0.793199 -0.557359 -v 0.075551 0.071818 0.203919 -vn 0.124107 0.812071 -0.570209 -v 0.075125 0.071884 0.203874 -vn 0.000022 0.818503 -0.574502 -v 0.074690 0.071907 0.203859 -vn -0.124065 0.812194 -0.570042 -v 0.074254 0.071884 0.203874 -vn -0.245296 0.793438 -0.557033 -v 0.073828 0.071818 0.203919 -vn -0.361114 0.763057 -0.536042 -v 0.073422 0.071710 0.203992 -vn -0.469159 0.722390 -0.507980 -v 0.073043 0.071566 0.204090 -vn -0.567872 0.673000 -0.473912 -v 0.072697 0.071391 0.204208 -vn 0.361228 0.697924 -0.618399 -v 0.075957 0.071310 0.203487 -vn 0.361315 0.625387 -0.691623 -v 0.075957 0.070865 0.203037 -vn 0.245425 0.726972 -0.641309 -v 0.075551 0.071416 0.203410 -vn 0.245531 0.652900 -0.716545 -v 0.075551 0.070968 0.202955 -vn 0.124205 0.744978 -0.655424 -v 0.075125 0.071481 0.203363 -vn 0.124300 0.669972 -0.731906 -v 0.075125 0.071032 0.202905 -vn 0.000113 0.751128 -0.660157 -v 0.074690 0.071503 0.203346 -vn 0.000205 0.675821 -0.737066 -v 0.074690 0.071054 0.202888 -vn -0.123987 0.745126 -0.655297 -v 0.074254 0.071481 0.203363 -vn -0.123917 0.670136 -0.731821 -v 0.074254 0.071032 0.202905 -vn -0.245241 0.727261 -0.641053 -v 0.073828 0.071416 0.203410 -vn -0.245196 0.653215 -0.716373 -v 0.073828 0.070968 0.202955 -vn -0.361085 0.698336 -0.618017 -v 0.073422 0.071310 0.203487 -vn -0.361061 0.625838 -0.691348 -v 0.073422 0.070865 0.203037 -vn -0.469161 0.659661 -0.587142 -v 0.073043 0.071169 0.203591 -vn -0.469152 0.589303 -0.657738 -v 0.073043 0.070727 0.203147 -vn -0.567888 0.612791 -0.549537 -v 0.072697 0.070998 0.203716 -vn -0.567909 0.545113 -0.616710 -v 0.072697 0.070559 0.203280 -vn -0.675767 0.545979 -0.495222 -v 0.072388 0.070803 0.203858 -vn -0.795392 0.386350 -0.466996 -v 0.071890 0.069938 0.203772 -vn -0.894827 0.220715 -0.388032 -v 0.071544 0.069009 0.203813 -vn -0.956519 0.082639 -0.279717 -v 0.071330 0.068027 0.203986 -vn -0.989998 0.006426 -0.140932 -v 0.071221 0.066952 0.204345 -vn -0.567894 0.470713 -0.675223 -v 0.072697 0.070074 0.202899 -vn -0.469119 0.512056 -0.719532 -v 0.073043 0.070239 0.202757 -vn -0.361011 0.546343 -0.755765 -v 0.073422 0.070375 0.202641 -vn -0.245124 0.572085 -0.782709 -v 0.073828 0.070476 0.202554 -vn -0.123838 0.588007 -0.799320 -v 0.074254 0.070539 0.202500 -vn 0.000292 0.593352 -0.804943 -v 0.074690 0.070560 0.202482 -vn 0.124391 0.587826 -0.799367 -v 0.075125 0.070539 0.202500 -vn 0.245607 0.571728 -0.782818 -v 0.075551 0.070476 0.202554 -vn 0.361381 0.545837 -0.755954 -v 0.075957 0.070375 0.202641 -vn 0.469357 0.511420 -0.719828 -v 0.076337 0.070239 0.202757 -vn 0.567971 0.469980 -0.675669 -v 0.076682 0.070074 0.202899 -vn 0.670492 0.417926 -0.613007 -v 0.076991 0.069885 0.203061 -vn 0.567918 0.612200 -0.550164 -v 0.076682 0.070998 0.203716 -vn 0.672831 0.484533 -0.559040 -v 0.076991 0.070367 0.203432 -vn 0.795670 0.387224 -0.465797 -v 0.077490 0.069938 0.203772 -vn 0.798903 0.327067 -0.504759 -v 0.077490 0.069461 0.203425 -vn 0.808568 0.244331 -0.535275 -v 0.077490 0.068935 0.203138 -vn 0.798008 0.175022 -0.576672 -v 0.077490 0.068355 0.202915 -vn 0.731104 0.302845 -0.611368 -v 0.077260 0.069152 0.202936 -vn 0.732511 0.217591 -0.645044 -v 0.077260 0.068573 0.202696 -vn 0.655853 0.345273 -0.671300 -v 0.076991 0.069356 0.202746 -vn 0.655766 0.259497 -0.708966 -v 0.076991 0.068777 0.202491 -vn 0.567972 0.388481 -0.725596 -v 0.076682 0.069543 0.202573 -vn 0.568007 0.299126 -0.766741 -v 0.076682 0.068963 0.202305 -vn 0.469407 0.427058 -0.772838 -v 0.076337 0.069706 0.202422 -vn 0.469525 0.334793 -0.816982 -v 0.076337 0.069125 0.202142 -vn 0.361462 0.459227 -0.811453 -v 0.075957 0.069840 0.202297 -vn 0.361594 0.364672 -0.858058 -v 0.075957 0.069258 0.202009 -vn 0.245708 0.483490 -0.840158 -v 0.075551 0.069940 0.202205 -vn 0.245830 0.387246 -0.888599 -v 0.075551 0.069357 0.201910 -vn 0.124493 0.498603 -0.857844 -v 0.075125 0.070001 0.202147 -vn 0.124614 0.401331 -0.907417 -v 0.075125 0.069418 0.201849 -vn 0.000385 0.503806 -0.863817 -v 0.074690 0.070022 0.202128 -vn 0.000497 0.406206 -0.913781 -v 0.074690 0.069439 0.201829 -vn -0.123749 0.498810 -0.857831 -v 0.074254 0.070001 0.202147 -vn -0.123673 0.401549 -0.907449 -v 0.074254 0.069418 0.201849 -vn -0.245069 0.483891 -0.840114 -v 0.073828 0.069940 0.202205 -vn -0.245010 0.387666 -0.888642 -v 0.073828 0.069357 0.201910 -vn -0.360963 0.459816 -0.811342 -v 0.073422 0.069840 0.202297 -vn -0.360933 0.365305 -0.858067 -v 0.073422 0.069258 0.202009 -vn -0.469096 0.427811 -0.772610 -v 0.073043 0.069706 0.202422 -vn -0.469113 0.335647 -0.816868 -v 0.073043 0.069125 0.202142 -vn -0.567874 0.389371 -0.725196 -v 0.072697 0.069543 0.202573 -vn -0.567892 0.300174 -0.766416 -v 0.072697 0.068963 0.202305 -vn -0.662745 0.349471 -0.662298 -v 0.072388 0.069356 0.202746 -vn -0.655944 0.260709 -0.708356 -v 0.072388 0.068777 0.202491 -vn -0.730076 0.316402 -0.605705 -v 0.072119 0.069152 0.202936 -vn -0.732911 0.219002 -0.644112 -v 0.072119 0.068573 0.202696 -vn 0.796407 0.092498 -0.597646 -v 0.077490 0.067714 0.202766 -vn 0.731682 0.126889 -0.669732 -v 0.077260 0.067936 0.202526 -vn 0.655540 0.165073 -0.736898 -v 0.076991 0.068143 0.202302 -vn 0.568099 0.201510 -0.797908 -v 0.076682 0.068330 0.202101 -vn 0.469607 0.234114 -0.851270 -v 0.076337 0.068493 0.201925 -vn 0.361644 0.261525 -0.894885 -v 0.075957 0.068625 0.201782 -vn 0.245927 0.282430 -0.927229 -v 0.075551 0.068724 0.201676 -vn 0.124756 0.295537 -0.947150 -v 0.075125 0.068785 0.201611 -vn 0.000615 0.300072 -0.953916 -v 0.074690 0.068805 0.201589 -vn -0.123568 0.295778 -0.947231 -v 0.074254 0.068785 0.201611 -vn -0.244889 0.282957 -0.927343 -v 0.073828 0.068724 0.201676 -vn -0.360863 0.262279 -0.894979 -v 0.073422 0.068625 0.201782 -vn -0.469099 0.235024 -0.851299 -v 0.073043 0.068493 0.201925 -vn -0.567842 0.202805 -0.797763 -v 0.072697 0.068330 0.202101 -vn -0.655852 0.167075 -0.736169 -v 0.072388 0.068143 0.202302 -vn 0.895640 0.221602 -0.385645 -v 0.077836 0.069009 0.203813 -vn 0.957914 0.128599 -0.256637 -v 0.078050 0.068560 0.204200 -vn 0.850187 0.135211 -0.508822 -v 0.077681 0.068128 0.203143 -vn 0.856984 0.059790 -0.511862 -v 0.077681 0.067480 0.203020 -vn 0.807079 0.014446 -0.590267 -v 0.077490 0.066996 0.202710 -vn 0.736432 0.044396 -0.675054 -v 0.077260 0.067228 0.202441 -vn 0.657590 0.068855 -0.750223 -v 0.076991 0.067443 0.202193 -vn 0.567599 0.096030 -0.817685 -v 0.076682 0.067635 0.201971 -vn 0.468788 0.123406 -0.874648 -v 0.076337 0.067800 0.201780 -vn 0.361621 0.148213 -0.920469 -v 0.075957 0.067934 0.201625 -vn 0.246300 0.167860 -0.954547 -v 0.075551 0.068034 0.201510 -vn 0.125001 0.180269 -0.975642 -v 0.075125 0.068095 0.201439 -vn 0.000767 0.184569 -0.982819 -v 0.074690 0.068116 0.201415 -vn -0.123462 0.180617 -0.975774 -v 0.074254 0.068095 0.201439 -vn -0.244963 0.168604 -0.954760 -v 0.073828 0.068034 0.201510 -vn -0.360817 0.149280 -0.920612 -v 0.073422 0.067934 0.201625 -vn -0.468486 0.124418 -0.874666 -v 0.073043 0.067800 0.201780 -vn -0.567313 0.095946 -0.817894 -v 0.072697 0.067635 0.201971 -vn -0.656469 0.066367 -0.751428 -v 0.072388 0.067443 0.202193 -vn -0.734321 0.039485 -0.677653 -v 0.072119 0.067228 0.202441 -vn 0.957826 0.035374 -0.285164 -v 0.078050 0.067425 0.203856 -vn 0.990113 0.027259 -0.137596 -v 0.078159 0.067585 0.204404 -vn 0.990276 0.005320 -0.139014 -v 0.078159 0.066952 0.204345 -vn 0.999977 -0.000595 -0.006783 -v 0.078190 0.067159 0.204816 -vn 1.000000 -0.000038 -0.000050 -v 0.078190 0.066505 0.204810 -vn 0.903102 0.027192 -0.428565 -v 0.077836 0.067237 0.203285 -vn 0.958366 0.004116 -0.285514 -v 0.078050 0.066739 0.203830 -vn 0.896776 0.000803 -0.442484 -v 0.077836 0.066508 0.203277 -vn 0.812929 0.000583 -0.582362 -v 0.077490 0.066231 0.202711 -vn 0.734781 0.004024 -0.678293 -v 0.077260 0.066455 0.202435 -vn 0.659414 0.011678 -0.751690 -v 0.076991 0.066668 0.202173 -vn 0.990141 0.053322 -0.129528 -v 0.078159 0.068132 0.204571 -vn 0.999979 0.001586 -0.006323 -v 0.078190 0.067733 0.204920 -vn 0.991038 -0.003843 0.133522 -v 0.078159 0.066695 0.205275 -vn 0.999996 0.002576 -0.001065 -v 0.078190 0.069274 0.206274 -vn 0.999996 0.002238 -0.001436 -v 0.078190 0.069144 0.206027 -vn 0.795492 0.494399 -0.350375 -v 0.077490 0.070745 0.204641 -vn 0.895396 0.362394 -0.258723 -v 0.077836 0.070274 0.204956 -vn 0.957739 0.233282 -0.168273 -v 0.078050 0.069813 0.205263 -vn 0.990011 0.113615 -0.083481 -v 0.078159 0.069383 0.205548 -vn 0.999994 0.002759 -0.001909 -v 0.078190 0.068995 0.205805 -vn 1.000000 0.000000 -0.000001 -v 0.078190 0.069499 0.208444 -vn 0.990557 -0.137097 0.000395 -v 0.078159 0.069035 0.207903 -vn 0.959742 -0.280719 0.009650 -v 0.078050 0.068520 0.207439 -vn 0.958644 -0.284607 -0.000087 -v 0.078050 0.068519 0.208207 -vn 0.958184 -0.286134 -0.003207 -v 0.078050 0.068519 0.208974 -vn 0.666039 -0.201931 -0.718064 -v 0.078051 0.068524 0.210310 -vn 0.896434 -0.443177 0.000963 -v 0.077836 0.067965 0.207793 -vn 0.961612 -0.271141 0.042248 -v 0.078050 0.068501 0.207078 -vn 0.960440 -0.263547 0.089986 -v 0.078050 0.068427 0.206789 -vn 0.898346 -0.438788 0.020962 -v 0.077836 0.067965 0.207423 -vn 0.812927 -0.582365 -0.000002 -v 0.077490 0.067399 0.208153 -vn 0.809843 -0.586630 -0.004461 -v 0.077490 0.067399 0.209577 -vn 0.245699 -0.969346 0.000002 -v 0.075551 0.066107 0.208968 -vn 0.361630 -0.932322 0.000000 -v 0.075958 0.066237 0.208887 -vn 0.470115 -0.882604 0.000964 -v 0.076337 0.066411 0.208777 -vn 0.900328 -0.375706 0.219669 -v 0.077836 0.067843 0.206840 -vn 0.818394 -0.568390 0.084643 -v 0.077490 0.067397 0.207267 -vn 0.733402 -0.679795 0.000434 -v 0.077260 0.067124 0.207630 -vn 0.733610 -0.679571 0.000000 -v 0.077260 0.067124 0.208328 -vn 0.733091 -0.679963 0.015110 -v 0.077260 0.067124 0.207455 -vn 0.735701 -0.668339 0.109854 -v 0.077260 0.067121 0.207284 -vn 0.819779 -0.531329 0.213666 -v 0.077490 0.067359 0.207137 -vn 0.749918 -0.592066 0.295095 -v 0.077260 0.067110 0.207254 -vn 0.814351 -0.480338 0.325742 -v 0.077490 0.067330 0.207086 -vn 0.744524 -0.580842 0.329101 -v 0.077147 0.067007 0.207309 -vn 0.718686 -0.282122 0.635529 -v 0.077147 0.067001 0.207305 -vn 0.728114 -0.623433 0.284922 -v 0.077164 0.067021 0.207300 -vn 0.736627 -0.457681 0.497905 -v 0.077164 0.067017 0.207294 -vn 0.723801 -0.559046 0.404449 -v 0.077197 0.067046 0.207277 -vn 0.683333 -0.728892 0.042092 -v 0.077164 0.067023 0.207308 -vn 0.725360 -0.656330 0.207566 -v 0.077197 0.067053 0.207289 -vn 0.687858 -0.725820 -0.005980 -v 0.077131 0.066991 0.207353 -vn 0.700369 -0.713340 0.025076 -v 0.077131 0.066991 0.207374 -vn 0.719786 -0.685885 0.107098 -v 0.077079 0.066942 0.207376 -vn 0.711262 -0.701868 0.038579 -v 0.077097 0.066958 0.207365 -vn 0.762681 -0.627698 0.155923 -v 0.077097 0.066957 0.207355 -vn 0.687166 -0.725816 -0.031513 -v 0.077131 0.066991 0.207331 -vn 0.687307 -0.726176 0.016658 -v 0.077097 0.066958 0.207376 -vn 0.644441 -0.764282 -0.023874 -v 0.076991 0.066862 0.207465 -vn 0.649315 -0.759938 -0.029734 -v 0.076991 0.066862 0.207459 -vn 0.659004 -0.751643 -0.027316 -v 0.077027 0.066894 0.207443 -vn 0.657328 -0.753041 -0.029148 -v 0.077027 0.066895 0.207431 -vn 0.790947 -0.505815 0.344317 -v 0.077045 0.066908 0.207401 -vn 0.743466 -0.650650 0.154635 -v 0.077062 0.066926 0.207388 -vn 0.700779 -0.709426 0.074998 -v 0.076991 0.066863 0.207454 -vn 0.687410 -0.722945 0.069409 -v 0.077027 0.066895 0.207426 -vn 0.748530 -0.614371 0.249501 -v 0.077027 0.066894 0.207421 -vn 0.782051 -0.370484 0.501137 -v 0.077027 0.066890 0.207416 -vn 0.769118 -0.554817 0.317232 -v 0.076991 0.066862 0.207450 -vn 0.739108 -0.250833 0.625141 -v 0.076991 0.066859 0.207447 -vn 0.766934 -0.470877 0.435990 -v 0.077009 0.066877 0.207434 -vn 0.651341 -0.006420 0.758758 -v 0.076991 0.066852 0.207447 -vn 0.731872 -0.148276 0.665115 -v 0.077009 0.066871 0.207431 -vn 0.779367 -0.511414 0.361997 -v 0.077131 0.066991 0.207320 -vn 0.786394 -0.220899 0.576878 -v 0.077097 0.066953 0.207350 -vn 0.727181 -0.180584 0.662267 -v 0.077131 0.066988 0.207319 -vn 0.683368 0.010265 0.730002 -v 0.077097 0.066949 0.207349 -vn 0.650979 -0.005061 0.759079 -v 0.077131 0.066984 0.207319 -vn 0.750019 -0.509451 0.421819 -v 0.077260 0.067095 0.207231 -vn 0.746822 -0.093391 0.658434 -v 0.077079 0.066933 0.207367 -vn 0.680705 -0.002078 0.732554 -v 0.077062 0.066904 0.207384 -vn 0.658636 0.059453 0.750109 -v 0.077097 0.066945 0.207350 -vn 0.678847 -0.006749 0.734248 -v 0.077062 0.066888 0.207384 -vn 0.689069 -0.002035 0.724693 -v 0.077131 0.066967 0.207319 -vn 0.714244 -0.101237 0.692536 -v 0.077027 0.066887 0.207415 -vn 0.788927 -0.435016 0.433998 -v 0.077062 0.066924 0.207385 -vn 0.710161 -0.177309 0.681347 -v 0.077197 0.067013 0.207255 -vn 0.730401 -0.416708 0.541173 -v 0.077197 0.067037 0.207267 -vn 0.743327 -0.231979 0.627416 -v 0.077164 0.067006 0.207287 -vn 0.705573 -0.039858 0.707516 -v 0.077197 0.066981 0.207252 -vn 0.739145 -0.093019 0.667092 -v 0.077147 0.066987 0.207302 -vn 0.705197 -0.017810 0.708788 -v 0.077131 0.066900 0.207319 -vn 0.660777 -0.002745 0.750577 -v 0.076991 0.066744 0.207447 -vn 0.697972 -0.683105 0.214947 -v 0.076842 0.066739 0.207573 -vn 0.695892 -0.662960 0.276077 -v 0.076861 0.066755 0.207561 -vn 0.615175 -0.788385 -0.003073 -v 0.076842 0.066739 0.207584 -vn 0.620446 -0.784167 -0.011362 -v 0.076880 0.066769 0.207573 -vn 0.743317 -0.278583 0.608170 -v 0.076880 0.066762 0.207539 -vn 0.609789 0.041775 0.791462 -v 0.076880 0.066759 0.207539 -vn 0.637867 -0.770034 0.013166 -v 0.076918 0.066800 0.207594 -vn 0.611185 -0.791464 0.006246 -v 0.076842 0.066739 0.207594 -vn 0.612726 -0.790100 0.017543 -v 0.076842 0.066739 0.207589 -vn 0.593491 -0.804807 0.007343 -v 0.076763 0.066680 0.207678 -vn 0.616482 -0.787369 0.000160 -v 0.076842 0.066739 0.207637 -vn 0.616597 -0.786834 0.026469 -v 0.076842 0.066739 0.207722 -vn 0.668086 -0.744069 0.004763 -v 0.076991 0.066862 0.207636 -vn 0.660539 -0.750780 0.004226 -v 0.076991 0.066862 0.207808 -vn 0.595412 -0.803393 0.006672 -v 0.076763 0.066680 0.207657 -vn 0.610829 -0.790608 0.042738 -v 0.076743 0.066665 0.207657 -vn 0.597308 -0.801784 -0.019133 -v 0.076763 0.066679 0.207647 -vn 0.658178 -0.743892 0.115870 -v 0.076783 0.066695 0.207624 -vn 0.600091 -0.799863 0.010483 -v 0.076803 0.066710 0.207614 -vn 0.588012 -0.808346 0.028636 -v 0.076683 0.066622 0.207697 -vn 0.657610 -0.734834 0.166040 -v 0.076803 0.066710 0.207609 -vn 0.712498 -0.462773 0.527436 -v 0.076783 0.066693 0.207617 -vn 0.724461 -0.593764 0.350143 -v 0.076803 0.066708 0.207606 -vn 0.655926 -0.122097 0.744885 -v 0.076783 0.066686 0.207615 -vn 0.750786 -0.388384 0.534302 -v 0.076803 0.066704 0.207600 -vn 0.653548 -0.756885 -0.000120 -v 0.076991 0.066862 0.207551 -vn 0.584578 0.035174 0.810575 -v 0.076803 0.066688 0.207601 -vn 0.548035 0.116756 0.828267 -v 0.076803 0.066696 0.207600 -vn 0.622303 -0.024950 0.782379 -v 0.076803 0.066701 0.207599 -vn 0.605053 -0.039260 0.795217 -v 0.076723 0.066641 0.207658 -vn 0.710000 -0.467001 0.527078 -v 0.076723 0.066648 0.207660 -vn 0.574036 0.006527 0.818804 -v 0.076703 0.066623 0.207673 -vn 0.646995 -0.255109 0.718552 -v 0.076703 0.066631 0.207673 -vn 0.559435 0.021677 0.828591 -v 0.076683 0.066605 0.207688 -vn 0.573446 0.013931 0.819125 -v 0.076763 0.066668 0.207630 -vn 0.671015 -0.285758 0.684165 -v 0.076763 0.066676 0.207630 -vn 0.649653 -0.148572 0.745572 -v 0.076743 0.066659 0.207643 -vn 0.678650 -0.707831 0.195983 -v 0.076763 0.066680 0.207635 -vn 0.706247 -0.619593 0.342520 -v 0.076743 0.066664 0.207647 -vn 0.569564 -0.006268 0.821923 -v 0.076683 0.066597 0.207688 -vn 0.560588 0.042064 0.827026 -v 0.076723 0.066632 0.207659 -vn 0.635956 -0.771721 -0.002681 -v 0.076918 0.066800 0.207552 -vn 0.678081 -0.720107 0.147148 -v 0.076880 0.066770 0.207550 -vn 0.589032 0.017430 0.807922 -v 0.076783 0.066678 0.207615 -vn 0.511418 -0.859148 -0.017778 -v 0.076514 0.066512 0.207816 -vn 0.524894 -0.851154 0.004758 -v 0.076514 0.066512 0.207837 -vn 0.523220 -0.851687 0.029492 -v 0.076514 0.066512 0.207878 -vn 0.572710 -0.819747 0.004320 -v 0.076683 0.066622 0.207971 -vn 0.549483 -0.814249 0.187265 -v 0.076382 0.066435 0.207880 -vn 0.494788 -0.868828 -0.017943 -v 0.076426 0.066460 0.207862 -vn 0.502106 -0.863346 0.050235 -v 0.076382 0.066436 0.207884 -vn 0.500744 -0.865012 0.031768 -v 0.076426 0.066460 0.207872 -vn 0.492324 -0.870136 0.021922 -v 0.076382 0.066436 0.207889 -vn 0.580881 -0.786070 0.211358 -v 0.076426 0.066461 0.207852 -vn 0.506922 -0.861980 -0.004607 -v 0.076426 0.066461 0.207857 -vn 0.607746 -0.686977 0.398381 -v 0.076382 0.066434 0.207876 -vn 0.604728 -0.541479 0.584041 -v 0.076337 0.066409 0.207899 -vn 0.564871 -0.789311 0.240643 -v 0.076337 0.066410 0.207902 -vn 0.499966 -0.864503 0.051656 -v 0.076337 0.066411 0.207907 -vn 0.519174 -0.854183 0.028800 -v 0.076471 0.066487 0.207833 -vn 0.576434 -0.793002 0.197159 -v 0.076471 0.066486 0.207828 -vn 0.530586 -0.847631 -0.000504 -v 0.076514 0.066513 0.207804 -vn 0.499199 -0.864445 -0.059462 -v 0.076514 0.066512 0.207810 -vn 0.533015 -0.845682 0.026783 -v 0.076536 0.066526 0.207795 -vn 0.527354 -0.849596 -0.009133 -v 0.076557 0.066539 0.207798 -vn 0.537543 -0.843203 -0.007441 -v 0.076557 0.066540 0.207786 -vn 0.544767 -0.838569 -0.005635 -v 0.076599 0.066566 0.207778 -vn 0.540757 -0.841117 -0.010223 -v 0.076599 0.066566 0.207757 -vn 0.472624 0.024564 0.880922 -v 0.076426 0.066455 0.207848 -vn 0.438865 0.109426 0.891865 -v 0.076426 0.066451 0.207849 -vn 0.612451 -0.290516 0.735190 -v 0.076471 0.066482 0.207823 -vn 0.517797 -0.067849 0.852809 -v 0.076382 0.066429 0.207873 -vn 0.569859 -0.821742 -0.001012 -v 0.076683 0.066622 0.207718 -vn 0.656687 -0.754163 0.000000 -v 0.076991 0.066862 0.208493 -vn 0.568568 -0.822636 0.000000 -v 0.076683 0.066622 0.208645 -vn 0.570617 -0.821208 0.003758 -v 0.076683 0.066622 0.209992 -vn 0.688763 -0.583802 0.429861 -v 0.076683 0.066620 0.207689 -vn 0.629056 -0.763944 0.143797 -v 0.076683 0.066622 0.207692 -vn 0.699537 -0.467936 0.540078 -v 0.076641 0.066590 0.207717 -vn 0.674766 -0.662452 0.325345 -v 0.076641 0.066592 0.207719 -vn 0.533382 0.057570 0.843913 -v 0.076641 0.066579 0.207715 -vn 0.535440 0.044244 0.843413 -v 0.076683 0.066614 0.207687 -vn 0.547795 0.030598 0.836053 -v 0.076641 0.066584 0.207715 -vn 0.640385 -0.197903 0.742120 -v 0.076683 0.066618 0.207687 -vn 0.642050 -0.705566 0.299915 -v 0.076599 0.066566 0.207747 -vn 0.573532 -0.815769 0.074717 -v 0.076599 0.066566 0.207752 -vn 0.662086 -0.540690 0.518938 -v 0.076557 0.066537 0.207773 -vn 0.610632 -0.759392 0.224615 -v 0.076557 0.066539 0.207776 -vn 0.646904 -0.583934 0.490445 -v 0.076536 0.066525 0.207786 -vn 0.600284 -0.160403 0.783537 -v 0.076536 0.066519 0.207784 -vn 0.655185 -0.340584 0.674341 -v 0.076557 0.066535 0.207771 -vn 0.601157 -0.155015 0.783952 -v 0.076557 0.066531 0.207770 -vn 0.550206 -0.030003 0.834490 -v 0.076557 0.066528 0.207770 -vn 0.659410 -0.218656 0.719283 -v 0.076641 0.066587 0.207715 -vn 0.567671 -0.002560 0.823252 -v 0.076683 0.066581 0.207688 -vn 0.476221 -0.010249 0.879266 -v 0.076337 0.066386 0.207899 -vn 0.480985 0.029259 0.876241 -v 0.076426 0.066446 0.207849 -vn 0.536963 -0.056650 0.841702 -v 0.076471 0.066479 0.207823 -vn 0.596983 -0.002019 0.802251 -v 0.076763 0.066660 0.207630 -vn 0.594317 -0.004685 0.804217 -v 0.076763 0.066652 0.207630 -vn 0.669374 -0.044158 0.741612 -v 0.076955 0.066821 0.207478 -vn 0.726712 -0.190436 0.660018 -v 0.076955 0.066825 0.207479 -vn 0.690398 -0.136190 0.710495 -v 0.076936 0.066810 0.207494 -vn 0.769648 -0.387948 0.507088 -v 0.076955 0.066828 0.207480 -vn 0.752998 -0.578109 0.314298 -v 0.076955 0.066830 0.207483 -vn 0.670574 -0.023975 0.741455 -v 0.076936 0.066802 0.207494 -vn 0.648625 -0.014523 0.760970 -v 0.076918 0.066767 0.207510 -vn 0.647178 0.026845 0.761866 -v 0.076991 0.066843 0.207447 -vn 0.669789 -0.114751 0.733631 -v 0.076918 0.066796 0.207509 -vn 0.565255 0.092309 0.819735 -v 0.076918 0.066791 0.207509 -vn 0.618627 0.033082 0.784988 -v 0.076918 0.066782 0.207510 -vn 0.608103 0.022166 0.793549 -v 0.076880 0.066745 0.207541 -vn 0.624666 -0.012905 0.780786 -v 0.076880 0.066729 0.207540 -vn 0.650181 -0.756951 0.065500 -v 0.076899 0.066785 0.207540 -vn 0.742460 -0.550104 0.382281 -v 0.076880 0.066767 0.207544 -vn 0.674563 -0.106785 0.730453 -v 0.076861 0.066743 0.207555 -vn 0.562256 0.126452 0.817238 -v 0.076880 0.066754 0.207540 -vn 0.658223 -0.000228 0.752823 -v 0.076991 0.066810 0.207447 -vn 0.640457 -0.007808 0.767954 -v 0.076918 0.066734 0.207510 -vn 0.811042 -0.463752 0.356573 -v 0.077097 0.066956 0.207352 -vn 0.721551 -0.690368 0.052504 -v 0.077131 0.066992 0.207325 -vn 0.623027 -0.019846 0.781949 -v 0.076842 0.066595 0.207571 -vn 0.573595 -0.006289 0.819115 -v 0.076683 0.066324 0.207688 -vn 0.663789 -0.005651 0.747898 -v 0.076991 0.066613 0.207447 -vn 0.656677 0.000025 0.754172 -v 0.076991 0.066350 0.207447 -vn 0.699431 -0.025056 0.714261 -v 0.077260 0.066928 0.207186 -vn 0.520066 -0.004853 0.854112 -v 0.076514 0.066495 0.207797 -vn 0.510987 -0.014967 0.859458 -v 0.076514 0.066502 0.207797 -vn 0.596686 -0.284022 0.750532 -v 0.076514 0.066510 0.207797 -vn 0.619616 -0.000377 0.784905 -v 0.076842 0.066660 0.207571 -vn 0.738754 -0.215532 0.638583 -v 0.077260 0.067053 0.207198 -vn 0.746583 -0.402512 0.529715 -v 0.077260 0.067076 0.207212 -vn 0.380507 -0.924774 -0.002819 -v 0.076031 0.066266 0.208068 -vn 0.393719 -0.919230 -0.001172 -v 0.076055 0.066277 0.208061 -vn 0.393957 -0.919129 0.000384 -v 0.076055 0.066277 0.208082 -vn 0.389890 -0.920720 0.016153 -v 0.076055 0.066277 0.208123 -vn 0.375916 -0.926628 0.006963 -v 0.076007 0.066256 0.208096 -vn 0.373457 -0.927573 -0.011784 -v 0.076007 0.066256 0.208075 -vn 0.386768 -0.922027 0.016662 -v 0.076031 0.066267 0.208058 -vn 0.419846 -0.902465 0.096366 -v 0.076055 0.066277 0.208041 -vn 0.418167 -0.907225 0.045597 -v 0.076079 0.066287 0.208033 -vn 0.417793 -0.908515 0.007095 -v 0.076151 0.066319 0.208176 -vn 0.358050 -0.933665 0.008376 -v 0.075958 0.066237 0.208232 -vn 0.362035 -0.932153 0.004560 -v 0.075958 0.066237 0.208150 -vn 0.477936 -0.878393 -0.001481 -v 0.076337 0.066411 0.207928 -vn 0.482602 -0.875801 0.008262 -v 0.076337 0.066411 0.207917 -vn 0.478431 -0.875857 0.063068 -v 0.076314 0.066399 0.207925 -vn 0.567137 -0.781899 0.258825 -v 0.076314 0.066398 0.207916 -vn 0.399804 0.068679 0.914024 -v 0.076198 0.066331 0.207968 -vn 0.404441 0.028614 0.914116 -v 0.076245 0.066359 0.207946 -vn 0.500294 -0.174501 0.848089 -v 0.076198 0.066336 0.207967 -vn 0.534407 -0.482680 0.693852 -v 0.076245 0.066363 0.207946 -vn 0.574547 -0.574965 0.582505 -v 0.076198 0.066338 0.207969 -vn 0.542799 -0.452676 0.707427 -v 0.076268 0.066372 0.207935 -vn 0.508747 -0.833381 0.215991 -v 0.076268 0.066376 0.207941 -vn 0.486111 -0.865202 0.122968 -v 0.076245 0.066364 0.207949 -vn 0.604980 -0.415384 0.679305 -v 0.076314 0.066395 0.207910 -vn 0.516574 -0.138959 0.844892 -v 0.076337 0.066406 0.207898 -vn 0.616789 -0.413614 0.669698 -v 0.076382 0.066432 0.207874 -vn 0.612737 -0.419636 0.669671 -v 0.076426 0.066459 0.207849 -vn 0.638586 -0.598908 0.483236 -v 0.076471 0.066485 0.207825 -vn 0.627472 -0.712130 0.314881 -v 0.076514 0.066513 0.207800 -vn 0.477083 -0.858756 0.186894 -v 0.076198 0.066342 0.207975 -vn 0.531182 -0.729924 0.430182 -v 0.076198 0.066340 0.207972 -vn 0.446051 -0.894982 -0.006765 -v 0.076245 0.066364 0.207960 -vn 0.451163 -0.892380 -0.010434 -v 0.076291 0.066387 0.207944 -vn 0.495728 -0.861525 0.109675 -v 0.076291 0.066388 0.207933 -vn 0.577878 -0.654243 0.487876 -v 0.076291 0.066385 0.207925 -vn 0.492337 -0.095945 0.865101 -v 0.076268 0.066366 0.207934 -vn 0.557358 -0.269586 0.785287 -v 0.076291 0.066380 0.207922 -vn 0.447014 0.038707 0.893689 -v 0.076291 0.066376 0.207922 -vn 0.438974 0.054493 0.896846 -v 0.076291 0.066372 0.207922 -vn 0.438036 0.070818 0.896164 -v 0.076337 0.066402 0.207898 -vn 0.443238 -0.011987 0.896324 -v 0.076245 0.066351 0.207946 -vn 0.443939 -0.004275 0.896047 -v 0.076245 0.066343 0.207946 -vn 0.446036 -0.008291 0.894977 -v 0.076245 0.066328 0.207946 -vn 0.366761 -0.930262 -0.009929 -v 0.075982 0.066247 0.208082 -vn 0.391331 -0.918661 0.054061 -v 0.076007 0.066257 0.208065 -vn 0.454848 -0.862678 0.221134 -v 0.076031 0.066266 0.208048 -vn 0.482548 -0.522200 0.703175 -v 0.076055 0.066275 0.208033 -vn 0.507081 -0.665755 0.547394 -v 0.076079 0.066286 0.208024 -vn 0.495240 -0.808344 0.318303 -v 0.076103 0.066297 0.208016 -vn 0.460110 -0.879464 0.121828 -v 0.076127 0.066308 0.208009 -vn 0.439858 -0.897844 0.020019 -v 0.076151 0.066319 0.208001 -vn 0.538235 -0.684118 0.492226 -v 0.076151 0.066319 0.207991 -vn 0.544906 -0.540253 0.641252 -v 0.076127 0.066306 0.208001 -vn 0.431570 -0.096151 0.896940 -v 0.076151 0.066315 0.207990 -vn 0.375557 0.067835 0.924314 -v 0.076103 0.066289 0.208011 -vn 0.403456 -0.000240 0.914999 -v 0.076103 0.066277 0.208012 -vn 0.420647 0.003440 0.907218 -v 0.076151 0.066304 0.207991 -vn 0.394284 0.002541 0.918985 -v 0.076055 0.066259 0.208033 -vn 0.392551 -0.002733 0.919726 -v 0.076055 0.066251 0.208033 -vn 0.405881 -0.906313 0.117719 -v 0.075982 0.066247 0.208071 -vn 0.487362 -0.764076 0.422690 -v 0.076007 0.066255 0.208056 -vn 0.487910 -0.370321 0.790447 -v 0.076031 0.066263 0.208042 -vn 0.378989 0.004879 0.925388 -v 0.076055 0.066267 0.208033 -vn 0.458566 -0.162811 0.873619 -v 0.076079 0.066280 0.208022 -vn 0.516730 -0.378672 0.767852 -v 0.076103 0.066293 0.208012 -vn 0.398392 -0.001647 0.917214 -v 0.076055 0.066263 0.208033 -vn 0.357905 0.058789 0.931905 -v 0.076031 0.066254 0.208043 -vn 0.380728 -0.013322 0.924591 -v 0.076007 0.066227 0.208053 -vn 0.343355 0.011475 0.939136 -v 0.075958 0.066218 0.208073 -vn 0.349730 0.000259 0.936851 -v 0.075958 0.066203 0.208073 -vn 0.354929 -0.000697 0.934893 -v 0.075958 0.066172 0.208073 -vn 0.393848 -0.011310 0.919106 -v 0.076055 0.066220 0.208033 -vn 0.473731 -0.003443 0.880663 -v 0.076337 0.066323 0.207899 -vn 0.525001 -0.008602 0.851058 -v 0.076514 0.066447 0.207797 -vn 0.518987 0.000062 0.854782 -v 0.076514 0.066479 0.207797 -vn 0.429552 -0.879184 0.206204 -v 0.075908 0.066216 0.208094 -vn 0.451594 -0.752653 0.479141 -v 0.075958 0.066237 0.208074 -vn 0.382024 -0.922940 0.047320 -v 0.075958 0.066237 0.208078 -vn 0.490079 -0.602039 0.630374 -v 0.075982 0.066245 0.208064 -vn 0.284733 -0.958561 -0.009415 -v 0.075706 0.066150 0.208178 -vn 0.312999 -0.949750 0.002592 -v 0.075757 0.066166 0.208178 -vn 0.273848 -0.961767 0.003251 -v 0.075655 0.066135 0.208199 -vn 0.309440 -0.947549 0.079992 -v 0.075757 0.066166 0.208198 -vn 0.255270 -0.966791 0.012366 -v 0.075551 0.066107 0.208239 -vn 0.334179 -0.942463 0.009410 -v 0.075858 0.066200 0.208134 -vn 0.308163 -0.951323 -0.004531 -v 0.075757 0.066166 0.208168 -vn 0.342669 -0.938784 0.035530 -v 0.075858 0.066201 0.208123 -vn 0.368593 -0.909083 0.194185 -v 0.075858 0.066200 0.208119 -vn 0.410999 -0.707826 0.574510 -v 0.075833 0.066190 0.208122 -vn 0.416480 -0.819667 0.393307 -v 0.075858 0.066199 0.208115 -vn 0.444076 -0.510568 0.736286 -v 0.075833 0.066185 0.208118 -vn 0.467089 -0.697195 0.543826 -v 0.075858 0.066195 0.208110 -vn 0.287460 0.019080 0.957603 -v 0.075757 0.066158 0.208143 -vn 0.389506 -0.247039 0.887275 -v 0.075808 0.066174 0.208127 -vn 0.393468 -0.321986 0.861109 -v 0.075808 0.066177 0.208128 -vn 0.417027 -0.582694 0.697536 -v 0.075808 0.066180 0.208129 -vn 0.399004 -0.832309 0.384781 -v 0.075808 0.066182 0.208132 -vn 0.349016 -0.929944 0.115727 -v 0.075808 0.066183 0.208135 -vn 0.359850 -0.272343 0.892377 -v 0.075757 0.066161 0.208143 -vn 0.410315 -0.679008 0.608760 -v 0.075757 0.066164 0.208145 -vn 0.370907 -0.898360 0.235325 -v 0.075757 0.066165 0.208148 -vn 0.317763 -0.947837 0.025132 -v 0.075757 0.066166 0.208157 -vn 0.228832 0.021302 0.973233 -v 0.075551 0.066096 0.208203 -vn 0.308492 -0.168010 0.936272 -v 0.075603 0.066112 0.208189 -vn 0.292947 -0.188024 0.937459 -v 0.075603 0.066116 0.208190 -vn 0.302818 -0.121188 0.945312 -v 0.075603 0.066109 0.208189 -vn 0.241673 -0.011225 0.970293 -v 0.075551 0.066088 0.208203 -vn 0.291811 -0.059006 0.954654 -v 0.075603 0.066105 0.208188 -vn 0.238264 -0.056503 0.969555 -v 0.075499 0.066088 0.208214 -vn 0.263304 -0.141285 0.954311 -v 0.075551 0.066104 0.208202 -vn 0.339267 -0.713043 0.613570 -v 0.075551 0.066107 0.208203 -vn 0.321691 -0.466818 0.823769 -v 0.075603 0.066119 0.208191 -vn 0.364508 -0.111668 0.924480 -v 0.075808 0.066171 0.208126 -vn 0.288946 0.040848 0.956473 -v 0.075757 0.066154 0.208144 -vn 0.308135 -0.019347 0.951146 -v 0.075757 0.066146 0.208144 -vn 0.319608 -0.122335 0.939620 -v 0.075706 0.066142 0.208158 -vn 0.357873 -0.883878 0.301141 -v 0.075706 0.066149 0.208165 -vn 0.369839 -0.626165 0.686394 -v 0.075655 0.066132 0.208177 -vn 0.399194 -0.762387 0.509323 -v 0.075706 0.066148 0.208161 -vn 0.377424 -0.487667 0.787231 -v 0.075655 0.066130 0.208175 -vn 0.394206 -0.481578 0.782741 -v 0.075706 0.066146 0.208159 -vn 0.352116 -0.278172 0.893663 -v 0.075655 0.066127 0.208174 -vn 0.303786 -0.084919 0.948948 -v 0.075655 0.066124 0.208173 -vn 0.239305 -0.005949 0.970926 -v 0.075551 0.066073 0.208203 -vn 0.243029 -0.003433 0.970013 -v 0.075551 0.065951 0.208203 -vn 0.263519 -0.963874 -0.038788 -v 0.075655 0.066136 0.208188 -vn 0.292506 -0.955498 0.038268 -v 0.075706 0.066151 0.208173 -vn 0.436618 -0.316418 0.842166 -v 0.075858 0.066193 0.208108 -vn 0.471894 -0.528548 0.705658 -v 0.075908 0.066215 0.208090 -vn 0.421559 -0.009887 0.906747 -v 0.076151 0.066210 0.207991 -vn 0.360310 -0.002306 0.932830 -v 0.075958 0.065863 0.208073 -vn 0.474899 -0.006247 0.880018 -v 0.076337 0.066071 0.207899 -vn 0.469819 0.000000 0.882763 -v 0.076337 0.065568 0.207899 -vn 0.329022 0.027226 0.943930 -v 0.075858 0.066189 0.208108 -vn 0.324822 0.014830 0.945659 -v 0.075808 0.066167 0.208126 -vn 0.355018 -0.006384 0.934838 -v 0.075958 0.066110 0.208073 -vn 0.409113 -0.205736 0.888988 -v 0.075958 0.066234 0.208072 -vn 0.342130 -0.013476 0.939556 -v 0.075908 0.066212 0.208090 -vn 0.131522 -0.990594 -0.037753 -v 0.075125 0.066026 0.208288 -vn 0.146687 -0.978164 0.147238 -v 0.075125 0.066027 0.208285 -vn 0.186076 -0.978837 0.085171 -v 0.075340 0.066060 0.208270 -vn 0.177693 -0.946620 0.268952 -v 0.075233 0.066042 0.208273 -vn 0.172886 -0.871915 0.458121 -v 0.075179 0.066034 0.208278 -vn 0.242383 -0.967616 -0.070501 -v 0.075551 0.066107 0.208213 -vn 0.242362 -0.969647 -0.032336 -v 0.075551 0.066107 0.208219 -vn 0.236562 -0.963468 0.125574 -v 0.075446 0.066082 0.208235 -vn 0.242704 -0.929086 0.279096 -v 0.075393 0.066071 0.208243 -vn 0.268852 -0.661613 0.699990 -v 0.075393 0.066069 0.208240 -vn 0.224305 -0.338889 0.913697 -v 0.075340 0.066057 0.208249 -vn 0.155440 0.088607 0.983863 -v 0.075340 0.066054 0.208249 -vn 0.252056 -0.963374 0.091535 -v 0.075499 0.066094 0.208222 -vn 0.221638 -0.061644 0.973179 -v 0.075393 0.066063 0.208238 -vn 0.162196 0.098462 0.981834 -v 0.075340 0.066049 0.208249 -vn 0.196846 -0.980366 -0.011576 -v 0.075340 0.066060 0.208260 -vn 0.208546 -0.948123 0.239940 -v 0.075287 0.066050 0.208262 -vn 0.209019 -0.976557 0.051457 -v 0.075340 0.066060 0.208255 -vn 0.240296 -0.662860 0.709136 -v 0.075287 0.066049 0.208259 -vn 0.250063 -0.857983 0.448702 -v 0.075340 0.066060 0.208251 -vn 0.191435 -0.129714 0.972896 -v 0.075287 0.066046 0.208258 -vn 0.162784 -0.033546 0.986091 -v 0.075233 0.066030 0.208268 -vn 0.147213 0.042043 0.988211 -v 0.075233 0.066035 0.208267 -vn 0.195906 -0.334629 0.921761 -v 0.075233 0.066038 0.208267 -vn 0.116035 -0.029467 0.992808 -v 0.075125 0.066004 0.208283 -vn 0.159020 -0.050639 0.985976 -v 0.075179 0.066020 0.208276 -vn 0.112231 0.020810 0.993464 -v 0.075125 0.066011 0.208283 -vn 0.139801 -0.005726 0.990163 -v 0.075179 0.066028 0.208275 -vn 0.118832 -0.003404 0.992909 -v 0.075125 0.065974 0.208283 -vn 0.211226 -0.124536 0.969471 -v 0.075340 0.066045 0.208250 -vn 0.210332 -0.793824 0.570617 -v 0.075233 0.066041 0.208269 -vn 0.176709 -0.980858 0.081804 -v 0.075287 0.066051 0.208267 -vn 0.315127 -0.503772 0.804306 -v 0.075499 0.066092 0.208215 -vn 0.221874 -0.023244 0.974798 -v 0.075446 0.066073 0.208227 -vn 0.251869 -0.967749 0.004836 -v 0.075551 0.066107 0.208320 -vn 0.132636 -0.991139 0.007202 -v 0.075125 0.066026 0.208374 -vn 0.140746 -0.990034 -0.004802 -v 0.075125 0.066026 0.208293 -vn 0.095235 -0.993791 0.057538 -v 0.075017 0.066014 0.208302 -vn 0.111892 -0.978739 0.171904 -v 0.075017 0.066014 0.208297 -vn 0.097270 -0.038437 0.994516 -v 0.075017 0.066009 0.208293 -vn 0.135532 -0.624507 0.769169 -v 0.075017 0.066013 0.208293 -vn 0.001843 0.054840 0.998493 -v 0.074690 0.065993 0.208310 -vn 0.038365 -0.156627 0.986912 -v 0.074799 0.065995 0.208308 -vn 0.002020 -0.068145 0.997673 -v 0.074690 0.065995 0.208310 -vn 0.043961 -0.516095 0.855403 -v 0.074799 0.065999 0.208309 -vn 0.000001 -0.783060 0.621946 -v 0.074690 0.065998 0.208311 -vn 0.050646 -0.940014 0.337356 -v 0.074799 0.066001 0.208311 -vn 0.071635 -0.945970 0.316244 -v 0.074908 0.066005 0.208306 -vn 0.094294 -0.615323 0.782615 -v 0.074908 0.066004 0.208303 -vn 0.073014 -0.048488 0.996152 -v 0.074908 0.066001 0.208302 -vn 0.052469 0.219065 0.974299 -v 0.074908 0.065998 0.208302 -vn 0.420309 -0.001402 0.907380 -v 0.076151 0.066272 0.207991 -vn 0.568832 -0.000841 0.822454 -v 0.076683 0.066453 0.207688 -vn 0.900373 -0.317313 0.297726 -v 0.077836 0.067703 0.206648 -vn -0.567181 -0.823483 0.013475 -v 0.072697 0.066622 0.209992 -vn -0.568567 -0.822637 0.000000 -v 0.072697 0.066622 0.208645 -vn -0.656683 -0.754167 0.000000 -v 0.072388 0.066862 0.208493 -vn -0.661903 -0.749578 0.004245 -v 0.072388 0.066862 0.207808 -vn -0.733610 -0.679571 0.000000 -v 0.072119 0.067124 0.207630 -vn -0.124376 -0.992234 -0.001800 -v 0.074254 0.066026 0.209018 -vn -0.151966 -0.988010 0.027260 -v 0.074182 0.066036 0.210230 -vn -0.246079 -0.969250 -0.000572 -v 0.073828 0.066107 0.208968 -vn -0.254378 -0.965947 0.047309 -v 0.073828 0.066107 0.210265 -vn -0.360743 -0.932664 0.001555 -v 0.073422 0.066237 0.208887 -vn -0.390385 -0.918517 0.062659 -v 0.073422 0.066237 0.210196 -vn -0.471748 -0.881731 0.002262 -v 0.073043 0.066411 0.208777 -vn -0.099503 -0.993305 0.058686 -v 0.074362 0.066014 0.208302 -vn -0.114332 -0.978445 0.171969 -v 0.074362 0.066014 0.208297 -vn -0.089943 -0.617825 0.781155 -v 0.074471 0.066004 0.208303 -vn -0.045158 -0.515446 0.855731 -v 0.074580 0.065999 0.208309 -vn -0.073886 -0.952535 0.295326 -v 0.074471 0.066005 0.208306 -vn -0.043073 -0.944955 0.324352 -v 0.074580 0.066001 0.208311 -vn 0.000762 -0.999838 0.018008 -v 0.074690 0.065999 0.208392 -vn -0.128045 -0.991699 0.011717 -v 0.074254 0.066026 0.208374 -vn -0.164716 -0.527380 0.833510 -v 0.074254 0.066025 0.208282 -vn -0.178486 -0.872832 0.454210 -v 0.074200 0.066034 0.208278 -vn -0.181235 -0.473304 0.862054 -v 0.074200 0.066032 0.208276 -vn -0.194025 -0.980258 0.038075 -v 0.074039 0.066060 0.208270 -vn -0.149153 -0.978044 0.145543 -v 0.074254 0.066027 0.208285 -vn -0.134487 -0.625183 0.768804 -v 0.074362 0.066013 0.208293 -vn -0.131752 -0.991228 -0.010378 -v 0.074254 0.066026 0.208293 -vn -0.133518 -0.990417 -0.035313 -v 0.074254 0.066026 0.208288 -vn -0.070817 -0.047271 0.996369 -v 0.074471 0.066001 0.208302 -vn -0.098547 -0.039219 0.994359 -v 0.074362 0.066009 0.208293 -vn -0.103902 0.090331 0.990477 -v 0.074254 0.066019 0.208283 -vn -0.139365 0.001621 0.990240 -v 0.074200 0.066028 0.208275 -vn -0.158914 -0.050665 0.985992 -v 0.074200 0.066020 0.208276 -vn -0.174858 -0.981492 0.078087 -v 0.074092 0.066051 0.208267 -vn -0.176457 -0.948475 0.263169 -v 0.074146 0.066042 0.208273 -vn -0.205835 -0.949630 0.236295 -v 0.074092 0.066050 0.208262 -vn -0.210623 -0.796207 0.567179 -v 0.074146 0.066041 0.208269 -vn -0.240884 -0.661605 0.710108 -v 0.074092 0.066049 0.208259 -vn -0.198545 -0.327591 0.923723 -v 0.074146 0.066038 0.208267 -vn -0.190268 -0.124000 0.973870 -v 0.074092 0.066046 0.208258 -vn -0.150031 0.044474 0.987680 -v 0.074146 0.066035 0.208267 -vn -0.162778 -0.033491 0.986094 -v 0.074146 0.066030 0.208268 -vn -0.242354 -0.969649 -0.032341 -v 0.073828 0.066107 0.208219 -vn -0.238309 -0.968459 -0.072774 -v 0.073828 0.066107 0.208213 -vn -0.248525 -0.964893 0.084949 -v 0.073880 0.066094 0.208222 -vn -0.268472 -0.960280 0.076060 -v 0.073828 0.066108 0.208207 -vn -0.300662 -0.899267 0.317681 -v 0.073880 0.066094 0.208217 -vn -0.246999 -0.968986 0.007593 -v 0.073828 0.066107 0.208239 -vn -0.232003 -0.964887 0.123157 -v 0.073933 0.066082 0.208235 -vn -0.241709 -0.931205 0.272825 -v 0.073986 0.066071 0.208243 -vn -0.271120 -0.907043 0.322130 -v 0.073933 0.066082 0.208231 -vn -0.272817 -0.663356 0.696800 -v 0.073986 0.066069 0.208240 -vn -0.305540 -0.643332 0.701975 -v 0.073933 0.066080 0.208228 -vn -0.234761 -0.198317 0.951608 -v 0.073986 0.066066 0.208238 -vn -0.265117 -0.217214 0.939431 -v 0.073933 0.066077 0.208227 -vn -0.220558 -0.055845 0.973774 -v 0.073986 0.066063 0.208238 -vn -0.194463 -0.980824 -0.012989 -v 0.074039 0.066060 0.208260 -vn -0.202502 -0.977998 0.050133 -v 0.074039 0.066060 0.208255 -vn -0.246929 -0.860892 0.444850 -v 0.074039 0.066060 0.208251 -vn -0.230630 -0.335383 0.913416 -v 0.074039 0.066057 0.208249 -vn -0.163354 0.089802 0.982472 -v 0.074039 0.066054 0.208249 -vn -0.164272 0.100327 0.981300 -v 0.074039 0.066049 0.208249 -vn -0.248625 -0.968557 0.009075 -v 0.073828 0.066107 0.208320 -vn -0.211218 -0.124497 0.969478 -v 0.074039 0.066045 0.208250 -vn -0.223039 -0.022158 0.974558 -v 0.073933 0.066073 0.208227 -vn -0.248559 -0.010546 0.968559 -v 0.073828 0.066073 0.208203 -vn -0.237941 -0.053233 0.969820 -v 0.073880 0.066088 0.208214 -vn -0.273865 -0.961763 0.003275 -v 0.073724 0.066135 0.208199 -vn -0.264716 -0.964316 0.004489 -v 0.073776 0.066122 0.208197 -vn -0.321957 -0.716017 0.619405 -v 0.073828 0.066107 0.208203 -vn -0.316151 -0.499987 0.806264 -v 0.073880 0.066092 0.208215 -vn -0.322401 -0.863378 0.388118 -v 0.073776 0.066121 0.208193 -vn -0.313194 -0.469930 0.825273 -v 0.073776 0.066119 0.208191 -vn -0.254981 -0.143269 0.956274 -v 0.073828 0.066104 0.208202 -vn -0.357458 -0.933924 0.003089 -v 0.073422 0.066237 0.208150 -vn -0.313003 -0.949749 0.002589 -v 0.073622 0.066166 0.208178 -vn -0.313996 -0.948765 0.035370 -v 0.073622 0.066166 0.208198 -vn -0.293366 -0.954992 0.043900 -v 0.073673 0.066151 0.208173 -vn -0.324430 -0.932807 0.156894 -v 0.073673 0.066150 0.208168 -vn -0.348539 -0.799935 0.488493 -v 0.073724 0.066134 0.208179 -vn -0.369129 -0.627466 0.685588 -v 0.073724 0.066132 0.208177 -vn -0.280248 -0.189563 0.941024 -v 0.073776 0.066116 0.208190 -vn -0.300088 -0.169886 0.938662 -v 0.073776 0.066112 0.208189 -vn -0.228818 0.021302 0.973236 -v 0.073828 0.066096 0.208203 -vn -0.357509 -0.881101 0.309593 -v 0.073673 0.066149 0.208165 -vn -0.377009 -0.490461 0.785692 -v 0.073724 0.066130 0.208175 -vn -0.299198 -0.122849 0.946250 -v 0.073776 0.066109 0.208189 -vn -0.241658 -0.011225 0.970297 -v 0.073828 0.066088 0.208203 -vn -0.313849 -0.949455 -0.005786 -v 0.073622 0.066166 0.208168 -vn -0.329887 -0.943549 0.029825 -v 0.073622 0.066166 0.208157 -vn -0.391891 -0.769137 0.504826 -v 0.073673 0.066148 0.208161 -vn -0.351774 -0.281194 0.892852 -v 0.073724 0.066127 0.208174 -vn -0.291189 -0.059646 0.954804 -v 0.073776 0.066105 0.208188 -vn -0.350665 -0.928909 0.119002 -v 0.073571 0.066183 0.208135 -vn -0.403254 -0.830970 0.383242 -v 0.073571 0.066182 0.208132 -vn -0.408193 -0.679093 0.610091 -v 0.073622 0.066164 0.208145 -vn -0.353366 -0.274408 0.894334 -v 0.073622 0.066161 0.208143 -vn -0.277369 0.019081 0.960574 -v 0.073622 0.066158 0.208143 -vn -0.396966 -0.327764 0.857315 -v 0.073571 0.066177 0.208128 -vn -0.415709 -0.576614 0.703350 -v 0.073571 0.066180 0.208129 -vn -0.429206 -0.706927 0.562171 -v 0.073546 0.066190 0.208122 -vn -0.327967 0.026404 0.944320 -v 0.073521 0.066189 0.208108 -vn -0.324891 0.014894 0.945634 -v 0.073571 0.066167 0.208126 -vn -0.364738 -0.111774 0.924377 -v 0.073571 0.066171 0.208126 -vn -0.396746 -0.249733 0.883304 -v 0.073571 0.066174 0.208127 -vn -0.333163 -0.942659 0.019883 -v 0.073521 0.066200 0.208134 -vn -0.361096 -0.932525 0.002501 -v 0.073422 0.066237 0.208109 -vn -0.345147 -0.937828 0.036783 -v 0.073521 0.066201 0.208123 -vn -0.379677 -0.906576 0.184296 -v 0.073521 0.066200 0.208119 -vn -0.375890 -0.896009 0.236377 -v 0.073622 0.066165 0.208148 -vn -0.392829 -0.483469 0.782268 -v 0.073673 0.066146 0.208159 -vn -0.304073 -0.086793 0.948687 -v 0.073724 0.066124 0.208173 -vn -0.397572 -0.915298 0.064543 -v 0.073373 0.066257 0.208065 -vn -0.386759 -0.921766 0.027665 -v 0.073348 0.066267 0.208058 -vn -0.484789 -0.756863 0.438336 -v 0.073373 0.066255 0.208056 -vn -0.369158 -0.929317 -0.009642 -v 0.073397 0.066247 0.208082 -vn -0.392581 -0.911957 0.119227 -v 0.073397 0.066247 0.208071 -vn -0.452689 -0.605521 0.654536 -v 0.073397 0.066245 0.208064 -vn -0.379084 -0.071803 0.922572 -v 0.073397 0.066238 0.208062 -vn -0.416348 -0.207805 0.885139 -v 0.073422 0.066234 0.208072 -vn -0.474254 -0.735763 0.483462 -v 0.073422 0.066237 0.208074 -vn -0.349235 0.059011 0.935175 -v 0.073373 0.066242 0.208053 -vn -0.459189 -0.857687 0.231340 -v 0.073348 0.066266 0.208048 -vn -0.395542 -0.918445 0.002372 -v 0.073324 0.066277 0.208061 -vn -0.440175 -0.892912 0.094623 -v 0.073324 0.066277 0.208041 -vn -0.411906 -0.910499 0.036386 -v 0.073300 0.066287 0.208033 -vn -0.520774 -0.675982 0.521385 -v 0.073300 0.066286 0.208024 -vn -0.491114 -0.821269 0.290387 -v 0.073276 0.066297 0.208016 -vn -0.509125 -0.351554 0.785622 -v 0.073276 0.066293 0.208012 -vn -0.542501 -0.522304 0.657945 -v 0.073252 0.066306 0.208001 -vn -0.423912 -0.905697 0.003418 -v 0.073228 0.066319 0.208012 -vn -0.407440 -0.913134 0.013388 -v 0.073276 0.066298 0.208026 -vn -0.401909 -0.007506 0.915649 -v 0.073276 0.066277 0.208012 -vn -0.428296 -0.107001 0.897281 -v 0.073300 0.066280 0.208022 -vn -0.372217 0.086969 0.924062 -v 0.073276 0.066285 0.208012 -vn -0.376501 0.072645 0.923564 -v 0.073276 0.066289 0.208011 -vn -0.408776 -0.094699 0.907708 -v 0.073228 0.066315 0.207990 -vn -0.353956 0.026854 0.934877 -v 0.073397 0.066230 0.208063 -vn -0.380677 -0.018764 0.924518 -v 0.073373 0.066227 0.208053 -vn -0.394593 -0.023276 0.918561 -v 0.073324 0.066220 0.208033 -vn -0.424753 -0.003526 0.905303 -v 0.073228 0.066272 0.207991 -vn -0.450018 -0.230448 0.862773 -v 0.073373 0.066251 0.208052 -vn -0.483006 -0.384439 0.786710 -v 0.073348 0.066263 0.208042 -vn -0.529525 -0.513674 0.675087 -v 0.073324 0.066275 0.208033 -vn -0.508674 -0.834255 0.212768 -v 0.073111 0.066376 0.207941 -vn -0.558099 -0.459690 0.690804 -v 0.073134 0.066363 0.207946 -vn -0.511784 -0.851791 0.111936 -v 0.073134 0.066364 0.207949 -vn -0.500391 -0.183228 0.846190 -v 0.073181 0.066336 0.207967 -vn -0.429831 -0.017221 0.902745 -v 0.073228 0.066307 0.207991 -vn -0.393065 0.025031 0.919170 -v 0.073228 0.066311 0.207991 -vn -0.564489 -0.590323 0.576950 -v 0.073181 0.066338 0.207969 -vn -0.528483 -0.721230 0.447810 -v 0.073181 0.066340 0.207972 -vn -0.453966 -0.891005 -0.005068 -v 0.073134 0.066364 0.207960 -vn -0.448943 -0.893290 -0.021966 -v 0.073088 0.066387 0.207944 -vn -0.478417 -0.878131 -0.001555 -v 0.073043 0.066411 0.207928 -vn -0.470284 -0.882063 0.028255 -v 0.073065 0.066399 0.207925 -vn -0.473992 -0.880524 0.003048 -v 0.073043 0.066411 0.207917 -vn -0.495203 -0.866872 0.057511 -v 0.073043 0.066411 0.207907 -vn -0.559171 -0.448659 0.697161 -v 0.073111 0.066372 0.207935 -vn -0.421657 0.004750 0.906743 -v 0.073228 0.066304 0.207991 -vn -0.395298 0.069677 0.915906 -v 0.073181 0.066331 0.207968 -vn -0.424541 0.020385 0.905179 -v 0.073134 0.066359 0.207946 -vn -0.444428 0.039703 0.894934 -v 0.073088 0.066376 0.207922 -vn -0.548493 -0.251358 0.797480 -v 0.073088 0.066380 0.207922 -vn -0.482233 -0.080330 0.872352 -v 0.073111 0.066366 0.207934 -vn -0.439426 0.052424 0.896748 -v 0.073088 0.066372 0.207922 -vn -0.444035 -0.004162 0.896000 -v 0.073134 0.066343 0.207946 -vn -0.446988 -0.006358 0.894517 -v 0.073134 0.066351 0.207946 -vn -0.428651 0.068031 0.900905 -v 0.073043 0.066402 0.207898 -vn -0.447669 0.056330 0.892424 -v 0.073043 0.066397 0.207899 -vn -0.477664 -0.003795 0.878534 -v 0.073043 0.066393 0.207899 -vn -0.524611 -0.851218 0.014533 -v 0.072865 0.066512 0.207878 -vn -0.479475 -0.877554 0.001562 -v 0.073043 0.066411 0.207948 -vn -0.481854 -0.876241 0.004303 -v 0.073043 0.066411 0.208114 -vn -0.441079 -0.897448 0.006091 -v 0.073134 0.066364 0.207981 -vn -0.485261 -0.851859 0.197122 -v 0.073181 0.066342 0.207975 -vn -0.420271 -0.907393 0.003195 -v 0.073228 0.066319 0.208176 -vn -0.353866 -0.935273 0.006509 -v 0.073422 0.066237 0.208232 -vn -0.346459 0.010059 0.938011 -v 0.073422 0.066218 0.208073 -vn -0.342026 -0.017627 0.939525 -v 0.073471 0.066212 0.208090 -vn -0.466900 -0.530183 0.707750 -v 0.073471 0.066215 0.208090 -vn -0.433345 -0.873377 0.222315 -v 0.073471 0.066216 0.208094 -vn -0.425875 -0.819995 0.382411 -v 0.073521 0.066199 0.208115 -vn -0.352609 0.000270 0.935771 -v 0.073422 0.066203 0.208073 -vn -0.360234 -0.002149 0.932860 -v 0.073422 0.066172 0.208073 -vn -0.363267 -0.009450 0.931637 -v 0.073422 0.066110 0.208073 -vn -0.245692 0.000000 0.969348 -v 0.073828 0.065951 0.208203 -vn -0.361629 0.000000 0.932322 -v 0.073422 0.065863 0.208073 -vn -0.447201 -0.020665 0.894195 -v 0.073134 0.066328 0.207946 -vn -0.481057 -0.012200 0.876604 -v 0.073043 0.066386 0.207899 -vn -0.572657 -0.819765 0.007048 -v 0.072697 0.066622 0.207971 -vn -0.137071 -0.665236 -0.733943 -v 0.073976 0.066073 0.210310 -vn -0.495189 -0.868471 0.023361 -v 0.072997 0.066436 0.207889 -vn -0.505817 -0.860920 0.054460 -v 0.072997 0.066436 0.207884 -vn -0.558340 -0.792956 0.243877 -v 0.073043 0.066410 0.207902 -vn -0.551405 -0.812075 0.191017 -v 0.072997 0.066435 0.207880 -vn -0.503087 -0.864096 -0.015542 -v 0.072953 0.066460 0.207862 -vn -0.606291 -0.686242 0.401850 -v 0.072997 0.066434 0.207876 -vn -0.520460 -0.853876 -0.004273 -v 0.072953 0.066461 0.207857 -vn -0.612151 -0.418615 0.670844 -v 0.072997 0.066432 0.207874 -vn -0.589547 -0.778307 0.216036 -v 0.072953 0.066461 0.207852 -vn -0.516944 -0.074198 0.852798 -v 0.072997 0.066429 0.207873 -vn -0.520020 -0.854146 0.003720 -v 0.072865 0.066512 0.207837 -vn -0.512132 -0.858730 -0.017402 -v 0.072865 0.066512 0.207816 -vn -0.524234 -0.850776 0.036876 -v 0.072909 0.066487 0.207833 -vn -0.580585 -0.788216 0.204050 -v 0.072909 0.066486 0.207828 -vn -0.600274 -0.421574 0.679666 -v 0.072953 0.066459 0.207849 -vn -0.457449 0.022134 0.888960 -v 0.072953 0.066455 0.207848 -vn -0.448144 0.067098 0.891440 -v 0.072997 0.066424 0.207873 -vn -0.503104 -0.863591 0.033135 -v 0.072953 0.066460 0.207872 -vn -0.481522 0.013782 0.876326 -v 0.072953 0.066446 0.207849 -vn -0.430498 0.107269 0.896195 -v 0.072953 0.066451 0.207849 -vn -0.609542 -0.297356 0.734873 -v 0.072909 0.066482 0.207823 -vn -0.634045 -0.600916 0.486710 -v 0.072909 0.066485 0.207825 -vn -0.544851 -0.838533 0.000635 -v 0.072865 0.066513 0.207804 -vn -0.509735 -0.858485 -0.056340 -v 0.072865 0.066512 0.207810 -vn -0.526833 -0.849729 -0.020217 -v 0.072822 0.066539 0.207798 -vn -0.537666 -0.056076 0.841291 -v 0.072909 0.066479 0.207823 -vn -0.605408 -0.713908 0.351876 -v 0.072865 0.066513 0.207800 -vn -0.604742 -0.324553 0.727291 -v 0.072865 0.066510 0.207797 -vn -0.653336 -0.581241 0.485089 -v 0.072844 0.066525 0.207786 -vn -0.575757 -0.817620 0.000893 -v 0.072697 0.066622 0.207760 -vn -0.548072 -0.836413 -0.005565 -v 0.072780 0.066566 0.207778 -vn -0.551561 -0.834001 0.014955 -v 0.072780 0.066566 0.207799 -vn -0.520066 -0.004853 0.854112 -v 0.072865 0.066495 0.207797 -vn -0.515072 -0.008041 0.857109 -v 0.072865 0.066502 0.207797 -vn -0.593259 -0.157527 0.789449 -v 0.072822 0.066531 0.207770 -vn -0.548974 -0.032024 0.835226 -v 0.072822 0.066528 0.207770 -vn -0.553708 -0.832690 -0.005904 -v 0.072738 0.066594 0.207738 -vn -0.579967 -0.807748 0.105746 -v 0.072738 0.066594 0.207727 -vn -0.623479 -0.755816 0.200039 -v 0.072759 0.066580 0.207737 -vn -0.553673 -0.832717 -0.005281 -v 0.072780 0.066566 0.207757 -vn -0.591105 -0.803810 0.066965 -v 0.072780 0.066566 0.207752 -vn -0.658687 -0.688268 0.304005 -v 0.072780 0.066566 0.207747 -vn -0.675662 -0.460251 0.575891 -v 0.072780 0.066564 0.207745 -vn -0.617664 -0.169154 0.768036 -v 0.072780 0.066561 0.207743 -vn -0.676459 -0.438308 0.591853 -v 0.072759 0.066577 0.207731 -vn -0.590311 -0.091751 0.801944 -v 0.072759 0.066570 0.207729 -vn -0.686377 -0.476339 0.549534 -v 0.072738 0.066590 0.207717 -vn -0.648825 -0.223096 0.727499 -v 0.072738 0.066587 0.207715 -vn -0.646092 -0.686437 0.333720 -v 0.072738 0.066592 0.207719 -vn -0.581418 -0.813575 0.007047 -v 0.072697 0.066622 0.207718 -vn -0.532938 0.056801 0.844246 -v 0.072738 0.066579 0.207715 -vn -0.542991 0.029049 0.839236 -v 0.072738 0.066584 0.207715 -vn -0.644422 -0.201586 0.737620 -v 0.072697 0.066618 0.207687 -vn -0.701906 -0.564415 0.434469 -v 0.072697 0.066620 0.207689 -vn -0.680804 -0.666507 0.303769 -v 0.072676 0.066636 0.207677 -vn -0.520302 0.001239 0.853981 -v 0.072865 0.066479 0.207797 -vn -0.551229 -0.012836 0.834255 -v 0.072780 0.066545 0.207743 -vn -0.545144 0.001272 0.838342 -v 0.072780 0.066553 0.207743 -vn 0.440934 -0.205747 0.873639 -v 0.076007 0.066251 0.208052 -vn -0.718413 -0.455503 0.525738 -v 0.072656 0.066648 0.207660 -vn -0.594393 -0.028095 0.803684 -v 0.072656 0.066641 0.207658 -vn -0.670347 -0.244249 0.700698 -v 0.072676 0.066631 0.207673 -vn -0.566335 0.014850 0.824041 -v 0.072676 0.066623 0.207673 -vn -0.549309 0.038956 0.834711 -v 0.072697 0.066614 0.207687 -vn -0.560794 0.024212 0.827601 -v 0.072697 0.066605 0.207688 -vn -0.689423 -0.282261 0.667102 -v 0.072616 0.066676 0.207630 -vn -0.641081 -0.136288 0.755276 -v 0.072636 0.066659 0.207643 -vn -0.711310 -0.615676 0.339090 -v 0.072636 0.066664 0.207647 -vn -0.560589 0.042064 0.827026 -v 0.072656 0.066632 0.207659 -vn -0.576500 0.021094 0.816825 -v 0.072616 0.066668 0.207630 -vn -0.650018 -0.105646 0.752539 -v 0.072596 0.066686 0.207615 -vn -0.675847 -0.712331 0.189249 -v 0.072616 0.066680 0.207635 -vn -0.646997 -0.752956 0.120218 -v 0.072596 0.066695 0.207624 -vn -0.721696 -0.477728 0.500929 -v 0.072596 0.066693 0.207617 -vn -0.634368 -0.773014 0.005186 -v 0.072538 0.066739 0.207584 -vn -0.690705 -0.624261 0.365001 -v 0.072577 0.066708 0.207606 -vn -0.619207 -0.784962 0.020443 -v 0.072538 0.066739 0.207589 -vn -0.653527 -0.737208 0.171543 -v 0.072577 0.066710 0.207609 -vn -0.594029 -0.009015 0.804393 -v 0.072616 0.066652 0.207630 -vn -0.596846 -0.002148 0.802353 -v 0.072616 0.066660 0.207630 -vn -0.590997 0.020071 0.806424 -v 0.072596 0.066678 0.207615 -vn -0.718667 -0.411112 0.560807 -v 0.072577 0.066704 0.207600 -vn -0.569564 -0.006268 0.821923 -v 0.072697 0.066597 0.207688 -vn -0.571793 -0.004465 0.820386 -v 0.072697 0.066581 0.207688 -vn -0.587379 -0.808808 -0.028548 -v 0.072616 0.066679 0.207647 -vn -0.595433 -0.803377 0.006667 -v 0.072616 0.066680 0.207657 -vn -0.612400 -0.790548 -0.000879 -v 0.072538 0.066739 0.207637 -vn -0.637113 -0.770766 -0.002645 -v 0.072462 0.066800 0.207552 -vn -0.633601 -0.773659 -0.001287 -v 0.072462 0.066800 0.207530 -vn -0.640647 -0.766778 0.040298 -v 0.072480 0.066785 0.207540 -vn -0.639115 -0.769087 0.006052 -v 0.072462 0.066800 0.207594 -vn -0.620388 -0.784145 -0.015326 -v 0.072499 0.066769 0.207573 -vn -0.608823 -0.793292 0.004758 -v 0.072538 0.066739 0.207594 -vn -0.600001 -0.799928 0.010691 -v 0.072577 0.066710 0.207614 -vn -0.592772 -0.805273 0.012545 -v 0.072616 0.066680 0.207678 -vn -0.617299 -0.786623 0.012904 -v 0.072538 0.066739 0.207722 -vn -0.668551 -0.743649 0.005084 -v 0.072388 0.066862 0.207636 -vn -0.666084 -0.735313 0.125085 -v 0.072499 0.066770 0.207550 -vn -0.745385 -0.547698 0.380036 -v 0.072499 0.066767 0.207544 -vn -0.706212 -0.663118 0.248072 -v 0.072518 0.066755 0.207561 -vn -0.720685 -0.326566 0.611529 -v 0.072518 0.066750 0.207557 -vn -0.686044 -0.232401 0.689445 -v 0.072538 0.066737 0.207570 -vn -0.520506 0.127220 0.844327 -v 0.072577 0.066696 0.207600 -vn -0.524438 -0.019654 0.851222 -v 0.072865 0.066447 0.207797 -vn -0.635468 -0.760779 0.131893 -v 0.072656 0.066651 0.207667 -vn -0.762591 -0.379347 0.523976 -v 0.072480 0.066781 0.207524 -vn -0.666978 -0.121071 0.735175 -v 0.072462 0.066796 0.207509 -vn -0.607463 0.042625 0.793203 -v 0.072499 0.066759 0.207539 -vn -0.561332 0.126198 0.817912 -v 0.072499 0.066754 0.207540 -vn -0.663710 -0.088310 0.742759 -v 0.072518 0.066743 0.207555 -vn -0.737141 -0.262841 0.622525 -v 0.072499 0.066762 0.207539 -vn -0.744537 -0.544879 0.385709 -v 0.072462 0.066799 0.207510 -vn -0.690870 -0.714870 0.107975 -v 0.072425 0.066831 0.207486 -vn -0.744649 -0.586659 0.318322 -v 0.072425 0.066830 0.207483 -vn -0.650921 -0.758868 -0.020510 -v 0.072388 0.066862 0.207465 -vn -0.659654 -0.751104 -0.026451 -v 0.072388 0.066862 0.207459 -vn -0.581265 0.086362 0.809118 -v 0.072462 0.066791 0.207509 -vn -0.684736 -0.137982 0.715610 -v 0.072443 0.066810 0.207494 -vn -0.658327 -0.020828 0.752444 -v 0.072443 0.066802 0.207494 -vn -0.676288 -0.049685 0.734959 -v 0.072425 0.066821 0.207478 -vn -0.718087 -0.191969 0.668953 -v 0.072425 0.066825 0.207479 -vn -0.755324 -0.398497 0.520274 -v 0.072425 0.066828 0.207480 -vn -0.760121 -0.255773 0.597324 -v 0.072388 0.066859 0.207447 -vn -0.654045 0.000026 0.756456 -v 0.072388 0.066852 0.207447 -vn -0.624135 -0.001601 0.781315 -v 0.072538 0.066660 0.207571 -vn -0.619571 -0.001189 0.784940 -v 0.072538 0.066692 0.207571 -vn -0.642003 -0.017738 0.766497 -v 0.072462 0.066734 0.207510 -vn -0.626391 -0.016154 0.779342 -v 0.072499 0.066729 0.207540 -vn -0.608613 0.021828 0.793167 -v 0.072499 0.066745 0.207541 -vn -0.620464 0.035367 0.783437 -v 0.072462 0.066782 0.207510 -vn -0.647678 -0.014176 0.761783 -v 0.072462 0.066767 0.207510 -vn -0.644128 0.028025 0.764404 -v 0.072388 0.066843 0.207447 -vn -0.625793 -0.039963 0.778965 -v 0.072538 0.066595 0.207571 -vn -0.615912 -0.032914 0.787127 -v 0.072577 0.066701 0.207599 -vn -0.709542 -0.676872 0.195947 -v 0.072538 0.066739 0.207573 -vn -0.662238 -0.002465 0.749289 -v 0.072388 0.066810 0.207447 -vn -0.669046 -0.005077 0.743204 -v 0.072388 0.066744 0.207447 -vn -0.597189 -0.801679 0.026000 -v 0.072636 0.066665 0.207657 -vn -0.578216 -0.003341 0.815877 -v 0.072697 0.066453 0.207688 -vn -0.572480 -0.004179 0.819908 -v 0.072697 0.066324 0.207688 -vn -0.653542 -0.756890 -0.000129 -v 0.072388 0.066862 0.207551 -vn -0.662051 -0.748392 0.039967 -v 0.072462 0.066800 0.207520 -vn -0.707107 -0.686518 0.169388 -v 0.072480 0.066784 0.207531 -vn -0.680251 -0.732978 0.001112 -v 0.072317 0.066926 0.207420 -vn -0.660361 -0.750481 -0.026483 -v 0.072352 0.066894 0.207443 -vn -0.696318 -0.715481 0.056826 -v 0.072352 0.066895 0.207426 -vn -0.756880 -0.608862 0.237527 -v 0.072352 0.066894 0.207421 -vn -0.775607 -0.479598 0.410389 -v 0.072370 0.066877 0.207434 -vn -0.779431 -0.354768 0.516359 -v 0.072352 0.066890 0.207416 -vn -0.722382 -0.133690 0.678447 -v 0.072370 0.066871 0.207431 -vn -0.788870 -0.435971 0.433145 -v 0.072317 0.066924 0.207385 -vn -0.792291 -0.493964 0.358154 -v 0.072335 0.066908 0.207401 -vn -0.742828 -0.648909 0.164693 -v 0.072317 0.066926 0.207388 -vn -0.703701 -0.706376 0.076403 -v 0.072335 0.066910 0.207409 -vn -0.726547 -0.677820 0.112647 -v 0.072300 0.066942 0.207376 -vn -0.681337 -0.731923 0.008365 -v 0.072317 0.066926 0.207398 -vn -0.685662 -0.727918 0.001882 -v 0.072283 0.066958 0.207376 -vn -0.700587 -0.713304 0.019370 -v 0.072249 0.066991 0.207374 -vn -0.727785 -0.089167 0.679984 -v 0.072300 0.066933 0.207367 -vn -0.737835 -0.123654 0.663558 -v 0.072317 0.066921 0.207383 -vn -0.796917 -0.412651 0.441182 -v 0.072300 0.066940 0.207369 -vn -0.783468 -0.502397 0.365753 -v 0.072249 0.066991 0.207320 -vn -0.778724 -0.226134 0.585195 -v 0.072283 0.066953 0.207350 -vn -0.801462 -0.474286 0.364297 -v 0.072283 0.066956 0.207352 -vn -0.680812 -0.015313 0.732298 -v 0.072317 0.066888 0.207384 -vn -0.663382 0.012804 0.748171 -v 0.072352 0.066882 0.207415 -vn -0.680712 -0.002061 0.732548 -v 0.072317 0.066904 0.207384 -vn -0.667616 0.023894 0.744122 -v 0.072317 0.066913 0.207384 -vn -0.747081 -0.644332 0.163420 -v 0.072283 0.066957 0.207355 -vn -0.694315 -0.718654 0.038260 -v 0.072283 0.066958 0.207365 -vn -0.692209 -0.721692 -0.002797 -v 0.072249 0.066991 0.207353 -vn -0.754001 -0.572949 0.321266 -v 0.072232 0.067007 0.207309 -vn -0.715946 -0.636791 0.286213 -v 0.072215 0.067021 0.207300 -vn -0.703774 -0.694785 0.148247 -v 0.072183 0.067053 0.207289 -vn -0.658196 0.058676 0.750556 -v 0.072283 0.066945 0.207350 -vn -0.687120 -0.021065 0.726238 -v 0.072249 0.066984 0.207319 -vn -0.692455 0.005068 0.721443 -v 0.072249 0.066967 0.207319 -vn -0.718599 -0.073079 0.691574 -v 0.072232 0.066987 0.207302 -vn -0.701611 -0.049564 0.710834 -v 0.072183 0.066981 0.207252 -vn -0.678821 0.009397 0.734244 -v 0.072283 0.066949 0.207349 -vn -0.730203 -0.183598 0.658100 -v 0.072249 0.066988 0.207319 -vn -0.747625 -0.290168 0.597377 -v 0.072232 0.067001 0.207305 -vn -0.725684 -0.218659 0.652359 -v 0.072215 0.067006 0.207287 -vn -0.751939 -0.501214 0.428221 -v 0.072119 0.067095 0.207231 -vn -0.755287 -0.590320 0.284716 -v 0.072119 0.067110 0.207254 -vn -0.760603 -0.637045 0.125129 -v 0.072119 0.067121 0.207284 -vn -0.721122 -0.205148 0.661738 -v 0.072119 0.067053 0.207198 -vn -0.727627 -0.053164 0.683909 -v 0.072119 0.066928 0.207186 -vn -0.708256 -0.036499 0.705012 -v 0.072249 0.066900 0.207319 -vn -0.707021 -0.098829 0.700253 -v 0.072352 0.066887 0.207415 -vn -0.990644 -0.136468 0.001166 -v 0.071221 0.069035 0.207903 -vn -0.658398 -0.752636 0.007166 -v 0.072388 0.066862 0.209864 -vn -0.733610 -0.679571 0.000000 -v 0.072119 0.067124 0.208328 -vn -0.812932 -0.582359 0.000003 -v 0.071890 0.067399 0.207797 -vn -0.898014 -0.439658 0.016494 -v 0.071544 0.067965 0.207423 -vn -0.958767 -0.284128 0.006092 -v 0.071330 0.068520 0.207439 -vn -0.960425 -0.275438 0.041447 -v 0.071330 0.068501 0.207078 -vn -0.737947 -0.674803 0.008637 -v 0.072119 0.067124 0.207455 -vn -0.814338 -0.574845 0.080044 -v 0.071890 0.067397 0.207267 -vn -0.898607 -0.408481 0.160152 -v 0.071544 0.067898 0.206955 -vn -0.903136 -0.305681 0.301503 -v 0.071544 0.067703 0.206648 -vn -0.818601 -0.254064 0.515115 -v 0.071890 0.067211 0.206971 -vn -0.825727 -0.396032 0.401662 -v 0.071890 0.067295 0.207041 -vn -0.811433 -0.584408 0.006608 -v 0.071890 0.067399 0.207441 -vn -0.900850 -0.425927 0.084004 -v 0.071544 0.067939 0.207087 -vn -0.960071 -0.263103 0.095083 -v 0.071330 0.068427 0.206789 -vn -0.958606 -0.284735 0.000156 -v 0.071330 0.068519 0.208207 -vn -0.990864 -0.134389 0.011350 -v 0.071221 0.069026 0.207120 -vn -0.991016 -0.129508 0.033378 -v 0.071221 0.068968 0.206796 -vn -0.990985 -0.123430 0.052085 -v 0.071221 0.068874 0.206517 -vn -0.960168 -0.241557 0.140455 -v 0.071330 0.068314 0.206548 -vn -0.990993 -0.115214 0.068246 -v 0.071221 0.068751 0.206274 -vn -0.364957 -0.568191 -0.737540 -v 0.072882 0.066502 0.210310 -vn -0.423099 -0.536139 -0.730439 -v 0.072533 0.066743 0.210310 -vn -0.477173 -0.494841 -0.726250 -v 0.072279 0.066962 0.210310 -vn -0.531069 -0.434464 -0.727466 -v 0.071992 0.067269 0.210310 -vn 0.990335 0.138477 -0.007818 -v 0.078159 0.069964 0.207352 -vn 1.000000 0.000769 -0.000434 -v 0.078190 0.069499 0.207627 -vn 0.991548 -0.128951 0.014306 -v 0.078159 0.069026 0.207120 -vn 0.991368 -0.127163 0.031911 -v 0.078159 0.068968 0.206796 -vn 0.991157 -0.122570 0.050833 -v 0.078159 0.068874 0.206517 -vn 0.991024 -0.115359 0.067560 -v 0.078159 0.068751 0.206274 -vn 0.991063 -0.102926 0.084860 -v 0.078159 0.068605 0.206060 -vn 0.991041 -0.082014 0.105410 -v 0.078159 0.068253 0.205707 -vn 0.959845 -0.243073 0.140046 -v 0.078050 0.068314 0.206548 -vn 0.959550 -0.216957 0.179423 -v 0.078050 0.068172 0.206343 -vn 0.959366 -0.187520 0.210837 -v 0.078050 0.068004 0.206170 -vn 0.959876 -0.149233 0.237421 -v 0.078050 0.067814 0.206027 -vn 0.902794 -0.230377 0.363166 -v 0.077836 0.067527 0.206501 -vn 0.905038 -0.134853 0.403387 -v 0.077836 0.067318 0.206398 -vn 0.901508 -0.048432 0.430044 -v 0.077836 0.067068 0.206347 -vn 0.960708 -0.107630 0.255845 -v 0.078050 0.067599 0.205914 -vn 0.673583 0.547465 -0.496556 -v 0.076991 0.070803 0.203858 -vn 0.795593 0.444136 -0.412038 -v 0.077490 0.070366 0.204177 -vn 0.895519 0.321091 -0.308133 -v 0.077836 0.069905 0.204512 -vn 0.957843 0.202819 -0.203474 -v 0.078050 0.069451 0.204841 -vn 0.990122 0.096083 -0.102109 -v 0.078159 0.069027 0.205148 -vn 0.999989 0.003112 -0.003501 -v 0.078190 0.068642 0.205426 -vn 0.991143 -0.049628 0.123176 -v 0.078159 0.067824 0.205450 -vn 0.956919 -0.050748 0.285886 -v 0.078050 0.067358 0.205834 -vn 0.890965 -0.001787 0.454069 -v 0.077836 0.066779 0.206344 -vn 0.896456 -0.001490 0.443131 -v 0.077836 0.066199 0.206344 -vn 0.812917 -0.000010 0.582379 -v 0.077490 0.065601 0.206910 -vn 0.812917 0.000001 0.582380 -v 0.077490 0.065049 0.206910 -vn 0.896663 0.000000 0.442713 -v 0.077836 0.064456 0.206344 -vn 0.958649 0.000000 0.284591 -v 0.078050 0.064957 0.205790 -vn 0.958578 -0.000414 0.284829 -v 0.078050 0.066175 0.205790 -vn 0.992342 -0.021635 0.121615 -v 0.078159 0.067310 0.205299 -vn 0.999986 0.002535 -0.004646 -v 0.078190 0.068222 0.205130 -vn 0.990147 0.076084 -0.117558 -v 0.078159 0.068610 0.204822 -vn 0.957900 0.167909 -0.232881 -v 0.078050 0.069033 0.204487 -vn 0.895600 0.274052 -0.350424 -v 0.077836 0.069482 0.204132 -vn 0.810533 -0.004363 0.585677 -v 0.077490 0.066706 0.206910 -vn 0.733635 -0.000029 0.679543 -v 0.077260 0.066389 0.207186 -vn 0.656686 -0.000004 0.754164 -v 0.076991 0.066087 0.207447 -vn 0.733611 -0.000009 0.679570 -v 0.077260 0.065850 0.207186 -vn 0.812873 -0.000004 0.582441 -v 0.077490 0.066154 0.206910 -vn 0.812790 -0.000146 0.582557 -v 0.077490 0.066430 0.206910 -vn 0.656698 -0.000002 0.754154 -v 0.076991 0.065562 0.207447 -vn 0.568567 0.000000 0.822637 -v 0.076683 0.065297 0.207688 -vn 0.568567 0.000000 0.822637 -v 0.076683 0.065811 0.207688 -vn 0.469819 0.000000 0.882763 -v 0.076337 0.065065 0.207899 -vn 0.733606 0.000000 0.679576 -v 0.077260 0.064773 0.207186 -vn 0.656699 0.000000 0.754153 -v 0.076991 0.064511 0.207447 -vn 0.568567 0.000000 0.822637 -v 0.076683 0.064270 0.207688 -vn 0.469819 0.000000 0.882763 -v 0.076337 0.064059 0.207899 -vn 0.361630 0.000000 0.932322 -v 0.075958 0.063885 0.208073 -vn 0.361630 0.000000 0.932322 -v 0.075958 0.064874 0.208073 -vn 0.960562 -0.013794 0.277725 -v 0.078050 0.066784 0.205790 -vn 0.896662 0.000011 0.442716 -v 0.077836 0.065618 0.206344 -vn 0.812917 0.000000 0.582380 -v 0.077490 0.063944 0.206910 -vn 0.990566 -0.000027 -0.137034 -v 0.078159 0.066270 0.204346 -vn 1.000000 -0.000000 0.000006 -v 0.078190 0.065847 0.204810 -vn 0.990559 0.000000 0.137086 -v 0.078159 0.065425 0.205275 -vn 0.245690 0.000000 0.969349 -v 0.075551 0.065707 0.208203 -vn 0.245690 0.000000 0.969349 -v 0.075551 0.064731 0.208203 -vn 0.124273 0.000000 0.992248 -v 0.075125 0.064643 0.208283 -vn 0.124273 0.000000 0.992248 -v 0.075125 0.063675 0.208283 -vn 0.000001 0.000000 1.000000 -v 0.074690 0.063648 0.208310 -vn 0.000139 -0.000205 1.000000 -v 0.074690 0.061718 0.208310 -vn -0.124271 0.000002 0.992248 -v 0.074254 0.061740 0.208283 -vn -0.118770 -0.003366 0.992916 -v 0.074254 0.065974 0.208283 -vn -0.124272 0.000000 0.992248 -v 0.074254 0.065853 0.208283 -vn -0.245692 0.000000 0.969348 -v 0.073828 0.065707 0.208203 -vn -0.361629 0.000000 0.932322 -v 0.073422 0.064874 0.208073 -vn -0.572770 -0.819713 0.002205 -v 0.072697 0.066622 0.207803 -vn -0.663602 -0.004186 0.748074 -v 0.072388 0.066613 0.207447 -vn -0.656678 -0.000007 0.754171 -v 0.072388 0.066350 0.207447 -vn -0.568566 0.000000 0.822637 -v 0.072697 0.065811 0.207688 -vn 0.124273 0.000000 0.992248 -v 0.075125 0.065853 0.208283 -vn 0.124273 0.000000 0.992248 -v 0.075125 0.065611 0.208283 -vn 0.000001 0.000000 1.000000 -v 0.074690 0.065578 0.208310 -vn 0.000001 0.000000 1.000000 -v 0.074690 0.064613 0.208310 -vn -0.124272 0.000000 0.992248 -v 0.074254 0.064643 0.208283 -vn -0.124272 0.000000 0.992248 -v 0.074254 0.063675 0.208283 -vn -0.245692 0.000000 0.969348 -v 0.073828 0.063756 0.208203 -vn -0.245693 0.000001 0.969348 -v 0.073828 0.061804 0.208203 -vn -0.361557 0.000087 0.932350 -v 0.073422 0.061908 0.208073 -vn -0.469820 0.000000 0.882762 -v 0.073043 0.065568 0.207899 -vn -0.568566 0.000000 0.822637 -v 0.072697 0.065297 0.207688 -vn -0.469820 0.000000 0.882762 -v 0.073043 0.065065 0.207899 -vn -0.568566 0.000000 0.822637 -v 0.072697 0.064270 0.207688 -vn -0.657210 -0.000639 0.753707 -v 0.072388 0.062408 0.207447 -vn -0.656694 0.000000 0.754157 -v 0.072388 0.064511 0.207447 -vn -0.656694 0.000000 0.754157 -v 0.072388 0.065562 0.207447 -vn -0.656689 -0.000004 0.754161 -v 0.072388 0.066087 0.207447 -vn -0.000051 -0.000197 1.000000 -v 0.074690 0.065940 0.208310 -vn 0.000001 0.000000 1.000000 -v 0.074690 0.065819 0.208310 -vn -0.124272 0.000000 0.992248 -v 0.074254 0.065611 0.208283 -vn -0.245692 0.000000 0.969348 -v 0.073828 0.064731 0.208203 -vn -0.361629 0.000000 0.932322 -v 0.073422 0.063885 0.208073 -vn -0.469820 0.000000 0.882762 -v 0.073043 0.064059 0.207899 -vn -0.568362 -0.000586 0.822779 -v 0.072697 0.062216 0.207688 -vn -0.991259 -0.080951 0.104174 -v 0.071221 0.068253 0.205707 -vn -0.962193 -0.142617 0.232046 -v 0.071330 0.067814 0.206027 -vn -0.961404 -0.181752 0.206565 -v 0.071330 0.068004 0.206170 -vn -0.908155 -0.133055 0.396927 -v 0.071544 0.067318 0.206398 -vn -0.910145 -0.219911 0.351106 -v 0.071544 0.067527 0.206501 -vn -0.797428 -0.006687 0.603377 -v 0.071890 0.066706 0.206910 -vn -0.779517 -0.070957 0.622349 -v 0.071890 0.066983 0.206910 -vn -0.733583 0.000170 0.679600 -v 0.072119 0.066658 0.207186 -vn -0.674826 -0.176341 0.716598 -v 0.072183 0.067013 0.207255 -vn -0.763357 -0.389755 0.515147 -v 0.072119 0.067076 0.207212 -vn -0.960467 -0.214076 0.177975 -v 0.071330 0.068172 0.206343 -vn -0.999985 0.001969 -0.005084 -v 0.071190 0.068222 0.205130 -vn -0.991338 -0.053431 0.119972 -v 0.071221 0.067824 0.205450 -vn -0.965988 -0.058781 0.251817 -v 0.071330 0.067358 0.205834 -vn -0.964657 -0.104069 0.242088 -v 0.071330 0.067599 0.205914 -vn -0.895303 -0.008980 0.445368 -v 0.071544 0.066779 0.206344 -vn -0.895446 -0.048579 0.442512 -v 0.071544 0.067068 0.206347 -vn -0.812873 -0.000145 0.582440 -v 0.071890 0.066154 0.206910 -vn -0.811492 -0.002851 0.584357 -v 0.071890 0.066430 0.206910 -vn -0.733606 -0.000005 0.679575 -v 0.072119 0.065850 0.207186 -vn -0.733621 -0.000028 0.679559 -v 0.072119 0.066389 0.207186 -vn -0.733606 0.000000 0.679576 -v 0.072119 0.064773 0.207186 -vn -0.812920 0.000002 0.582375 -v 0.071890 0.065601 0.206910 -vn -0.896683 -0.000052 0.442674 -v 0.071544 0.066199 0.206344 -vn -0.959328 -0.009786 0.282125 -v 0.071330 0.066784 0.205790 -vn -0.991360 -0.020403 0.129571 -v 0.071221 0.067310 0.205299 -vn -0.999975 0.000877 -0.007047 -v 0.071190 0.067733 0.204920 -vn -0.989801 0.076254 -0.120327 -v 0.071221 0.068610 0.204822 -vn -0.957550 0.202531 -0.205131 -v 0.071330 0.069451 0.204841 -vn -0.895335 0.361564 -0.260090 -v 0.071544 0.070274 0.204956 -vn 0.618249 0.000229 0.785982 -v 0.076842 0.066692 0.207571 -vn 0.686430 -0.720216 0.100516 -v 0.076955 0.066831 0.207486 -vn -0.990560 0.000000 0.137079 -v 0.071221 0.065425 0.205275 -vn -0.958649 0.000000 0.284591 -v 0.071330 0.064957 0.205790 -vn -0.896663 0.000000 0.442714 -v 0.071544 0.064456 0.206344 -vn -0.812919 0.000000 0.582376 -v 0.071890 0.063944 0.206910 -vn -0.812919 0.000000 0.582376 -v 0.071890 0.065049 0.206910 -vn -0.896662 0.000005 0.442716 -v 0.071544 0.065618 0.206344 -vn -0.958644 0.000035 0.284607 -v 0.071330 0.066175 0.205790 -vn -0.990657 -0.002155 0.136360 -v 0.071221 0.066695 0.205275 -vn -1.000000 0.000338 -0.000185 -v 0.071190 0.066505 0.204810 -vn -0.999980 -0.000067 -0.006371 -v 0.071190 0.067159 0.204816 -vn -0.989043 0.025683 -0.145375 -v 0.071221 0.067585 0.204404 -vn -0.989548 0.052946 -0.134133 -v 0.071221 0.068132 0.204571 -vn -0.957043 0.127957 -0.260183 -v 0.071330 0.068560 0.204200 -vn -0.957365 0.167650 -0.235257 -v 0.071330 0.069033 0.204487 -vn -0.895078 0.273441 -0.352230 -v 0.071544 0.069482 0.204132 -vn -0.895226 0.320464 -0.309634 -v 0.071544 0.069905 0.204512 -vn -0.795435 0.443290 -0.413252 -v 0.071890 0.070366 0.204177 -vn -0.795470 0.493513 -0.351673 -v 0.071890 0.070745 0.204641 -vn -0.674853 0.602633 -0.425918 -v 0.072388 0.071191 0.204342 -vn 0.958666 0.000176 0.284534 -v 0.078050 0.063740 0.205790 -vn 0.815634 -0.414933 0.403201 -v 0.077490 0.067295 0.207041 -vn 0.696273 -0.053193 -0.715803 -v 0.078175 0.069185 0.210310 -vn 0.396214 -0.686263 0.609966 -v 0.076710 0.065999 0.215310 -vn 0.396212 -0.686260 -0.609969 -v 0.076710 0.065999 0.210310 -vn 0.868397 -0.495788 0.009042 -v 0.077721 0.067750 0.215310 -vn 0.792402 -0.000000 0.609999 -v 0.078731 0.069499 0.215310 -vn 0.792406 -0.000002 -0.609995 -v 0.078731 0.069499 0.210310 -vn -0.396205 -0.686246 0.609991 -v 0.072669 0.065999 0.215310 -vn -0.396201 -0.686239 -0.610001 -v 0.072669 0.065999 0.210310 -vn -0.009948 -0.999914 0.008594 -v 0.074690 0.065999 0.215310 -vn -0.792396 -0.000001 0.610007 -v 0.070648 0.069499 0.215310 -vn -0.792401 -0.000002 -0.610001 -v 0.070648 0.069499 0.210310 -vn -0.865612 -0.500629 0.009270 -v 0.071659 0.067749 0.215310 -vn -0.396210 0.686253 -0.609979 -v 0.072669 0.072999 0.210310 -vn 0.396191 0.686228 -0.610019 -v 0.076710 0.072999 0.210310 -vn -0.578917 -0.385290 0.718615 -v 0.071742 0.067612 0.215310 -vn -0.142226 -0.677016 0.722095 -v 0.073976 0.066073 0.215310 -vn -0.064521 -0.691181 0.719796 -v 0.074392 0.066012 0.215310 -vn -0.216624 -0.658911 0.720355 -v 0.073567 0.066184 0.215310 -vn -0.289060 -0.632092 0.718961 -v 0.073254 0.066307 0.215310 -vn -0.351395 -0.601338 0.717576 -v 0.072882 0.066502 0.215310 -vn -0.476024 -0.509475 0.716824 -v 0.072279 0.066962 0.215310 -vn -0.513121 -0.476452 0.713933 -v 0.072119 0.067124 0.215310 -vn -0.544401 -0.433698 0.718007 -v 0.071992 0.067270 0.215310 -vn -0.397978 -0.576055 0.713985 -v 0.072697 0.066622 0.215310 -vn -0.435571 -0.545208 0.716258 -v 0.072533 0.066743 0.215310 -vn 0.026734 -0.699117 0.714508 -v 0.074727 0.065999 0.215310 -vn 0.500765 -0.480221 0.720154 -v 0.077217 0.067077 0.215310 -vn 0.443417 -0.535457 0.718795 -v 0.076905 0.066790 0.215310 -vn 0.591250 -0.373565 0.714754 -v 0.077677 0.067676 0.215310 -vn 0.553634 -0.420509 0.718792 -v 0.077489 0.067398 0.215310 -vn 0.382839 -0.580057 0.719005 -v 0.076635 0.066590 0.215310 -vn 0.313714 -0.618755 0.720227 -v 0.076272 0.066377 0.215310 -vn 0.239167 -0.651077 0.720346 -v 0.075884 0.066209 0.215310 -vn 0.169875 -0.672407 0.720424 -v 0.075563 0.066110 0.215310 -vn 0.091335 -0.686937 0.720955 -v 0.075150 0.066030 0.215310 -vn -0.626007 -0.305889 0.717319 -v 0.071575 0.067903 0.215310 -vn -0.649423 -0.240816 0.721289 -v 0.071406 0.068289 0.215310 -vn -0.675088 -0.163401 0.719414 -v 0.071283 0.068694 0.215310 -vn -0.686717 -0.086142 0.721803 -v 0.071222 0.069025 0.215310 -vn -0.689800 -0.015015 0.723844 -v 0.071190 0.069443 0.215310 -vn -0.690796 0.069773 0.719675 -v 0.071209 0.069867 0.215310 -vn -0.682652 0.136047 0.717967 -v 0.071260 0.070199 0.215310 -vn -0.674298 0.188913 0.713887 -v 0.071330 0.070479 0.215310 -vn -0.656397 0.234721 0.716972 -v 0.071369 0.070606 0.215310 -vn -0.639728 0.281254 0.715293 -v 0.071527 0.070999 0.215310 -vn -0.627008 0.316959 0.711616 -v 0.071544 0.071033 0.215310 -vn -0.869117 0.494550 0.007440 -v 0.071659 0.071249 0.215310 -vn -0.081720 0.688618 0.720505 -v 0.074286 0.072976 0.215310 -vn -0.001200 0.999846 0.017488 -v 0.074690 0.072999 0.215310 -vn -0.396217 0.686268 0.609958 -v 0.072669 0.072999 0.215310 -vn -0.587484 0.374329 0.717454 -v 0.071685 0.071294 0.215310 -vn -0.548811 0.421217 0.722068 -v 0.071922 0.071641 0.215310 -vn -0.497007 0.485607 0.719145 -v 0.072201 0.071960 0.215310 -vn -0.441569 0.536636 0.719054 -v 0.072450 0.072188 0.215310 -vn -0.376625 0.581948 0.720757 -v 0.072788 0.072438 0.215310 -vn -0.306987 0.622774 0.719660 -v 0.073157 0.072646 0.215310 -vn -0.241254 0.651118 0.719612 -v 0.073467 0.072778 0.215310 -vn -0.188677 0.674272 0.713973 -v 0.073828 0.072891 0.215310 -vn -0.144989 0.684003 0.714926 -v 0.073868 0.072901 0.215310 -vn 0.862750 0.505428 0.014329 -v 0.077721 0.071249 0.215310 -vn 0.396198 0.686252 0.609988 -v 0.076710 0.072999 0.215310 -vn 0.567844 0.407516 0.715181 -v 0.077489 0.071600 0.215310 -vn 0.532612 0.449255 0.717283 -v 0.077423 0.071686 0.215310 -vn 0.074672 0.688344 0.721531 -v 0.075040 0.072982 0.215310 -vn 0.144891 0.677125 0.721463 -v 0.075457 0.072914 0.215310 -vn 0.365994 0.589183 0.720355 -v 0.076545 0.072467 0.215310 -vn 0.423883 0.549113 0.720277 -v 0.076821 0.072275 0.215310 -vn 0.485996 0.491903 0.722384 -v 0.077138 0.072000 0.215310 -vn 0.221853 0.657731 0.719841 -v 0.075783 0.072824 0.215310 -vn 0.292648 0.628242 0.720881 -v 0.076173 0.072669 0.215310 -vn 0.000000 1.000000 0.000000 -v 0.074689 0.072999 0.212490 -vn -0.000418 1.000000 0.000018 -v 0.074686 0.072999 0.212431 -vn -0.000797 1.000000 0.000017 -v 0.074681 0.072999 0.212216 -vn -0.000981 1.000000 0.000013 -v 0.074680 0.072999 0.212098 -vn -0.000327 1.000000 -0.000017 -v 0.074683 0.072999 0.211354 -vn 0.000000 1.000000 -0.000002 -v 0.074690 0.072999 0.211285 -vn 0.000000 1.000000 0.000000 -v 0.074689 0.072999 0.212488 -vn -0.000126 1.000000 -0.000018 -v 0.074686 0.072999 0.211311 -vn 0.000000 1.000000 0.000000 -v 0.074688 0.072999 0.211291 -vn 0.000000 1.000000 0.000000 -v 0.074691 0.072999 0.212483 -vn 0.000000 -1.000000 0.000000 -v 0.074691 0.072999 0.211287 -vn 0.000000 1.000000 0.000000 -v 0.074691 0.072999 0.211289 -vn 0.000090 1.000000 -0.000018 -v 0.074694 0.072999 0.211311 -vn 0.000350 1.000000 -0.000019 -v 0.074696 0.072999 0.211354 -vn 0.001214 0.999999 0.000018 -v 0.074700 0.072999 0.212044 -vn 0.000650 1.000000 0.000021 -v 0.074695 0.072999 0.212379 -vn 0.000099 1.000000 0.000018 -v 0.074692 0.072999 0.212462 -vn 0.000000 1.000000 0.000000 -v 0.074689 0.072999 0.212485 -vn -0.000000 1.000000 0.000002 -v 0.074688 0.072999 0.212483 -vn -0.000241 1.000000 0.000019 -v 0.074688 0.072999 0.212479 -vn 0.676082 0.162210 0.718750 -v 0.078088 0.070335 0.215310 -vn 0.688444 0.083022 0.720522 -v 0.078164 0.069922 0.215310 -vn 0.691316 0.000114 0.722552 -v 0.078190 0.069499 0.215310 -vn 0.628807 0.300216 0.717267 -v 0.077829 0.071047 0.215310 -vn 0.654757 0.233991 0.718708 -v 0.077992 0.070658 0.215310 -vn 0.686740 -0.062084 0.724247 -v 0.078175 0.069185 0.215310 -vn 0.682139 -0.136876 0.718298 -v 0.078112 0.068768 0.215310 -vn 0.666032 -0.201961 0.718062 -v 0.078051 0.068524 0.215310 -vn 0.646180 -0.262002 0.716803 -v 0.077910 0.068128 0.215310 -vn 0.627938 -0.309917 0.713895 -v 0.077836 0.067965 0.215310 -vn -0.001449 0.999999 -0.000007 -v 0.074688 0.072999 0.211888 -vn 0.000151 1.000000 -0.000019 -v 0.074691 0.072999 0.211299 -vn 0.001891 0.999998 -0.000011 -v 0.074693 0.072999 0.211888 -vn -0.618739 -0.362608 0.696906 -v 0.071638 0.067784 0.217310 -vn -0.580109 -0.427030 0.693628 -v 0.071890 0.067399 0.217310 -vn 0.043441 0.714423 0.698364 -v 0.074945 0.072990 0.217310 -vn 0.359905 0.627660 0.690298 -v 0.076378 0.072565 0.217310 -vn 0.266780 0.668374 0.694338 -v 0.075957 0.072761 0.217310 -vn -0.651309 -0.301908 0.696167 -v 0.071544 0.067965 0.217310 -vn 0.473994 0.551192 0.686671 -v 0.076972 0.072153 0.217310 -vn 0.192919 0.695697 0.691945 -v 0.075691 0.072853 0.217310 -vn 0.110882 0.710909 0.694488 -v 0.075125 0.072972 0.217310 -vn 0.700184 0.146788 0.698710 -v 0.078116 0.070216 0.217310 -vn 0.686477 0.206056 0.697345 -v 0.078050 0.070479 0.217310 -vn -0.543086 -0.464177 0.699712 -v 0.072070 0.067179 0.217310 -vn 0.664410 0.267121 0.698001 -v 0.077921 0.070843 0.217310 -vn 0.638727 0.326781 0.696593 -v 0.077836 0.071033 0.217310 -vn 0.601997 0.389201 0.697225 -v 0.077585 0.071465 0.217310 -vn 0.571769 0.421968 0.703579 -v 0.077490 0.071599 0.217310 -vn 0.547215 0.465588 0.695546 -v 0.077456 0.071644 0.217310 -vn 0.685541 -0.212409 0.696359 -v 0.078050 0.068519 0.217310 -vn 0.710188 -0.130383 0.691834 -v 0.078105 0.068734 0.217310 -vn 0.420225 -0.582848 0.695484 -v 0.076789 0.066699 0.217310 -vn 0.478868 -0.534393 0.696498 -v 0.076991 0.066862 0.217310 -vn -0.508223 -0.506293 0.696690 -v 0.072119 0.067124 0.217310 -vn 0.536214 -0.479233 0.694845 -v 0.077311 0.067180 0.217310 -vn 0.725561 -0.016113 0.687969 -v 0.078190 0.069499 0.217310 -vn 0.713210 0.085081 0.695768 -v 0.078159 0.069964 0.217310 -vn -0.487980 0.525603 0.696863 -v 0.072388 0.072136 0.217310 -vn -0.541452 0.470890 0.696486 -v 0.071983 0.071718 0.217310 -vn -0.589631 0.412016 0.694679 -v 0.071890 0.071599 0.217310 -vn -0.688647 -0.221301 0.690500 -v 0.071369 0.068394 0.217310 -vn 0.592895 -0.409394 0.693450 -v 0.077544 0.067473 0.217310 -vn 0.634967 -0.333331 0.696927 -v 0.077836 0.067965 0.217310 -vn 0.661557 -0.274286 0.697932 -v 0.077890 0.068083 0.217310 -vn -0.017263 0.718068 0.695759 -v 0.074604 0.072998 0.217310 -vn -0.094177 0.713112 0.694696 -v 0.074254 0.072972 0.217310 -vn -0.193845 0.697889 0.689474 -v 0.073828 0.072891 0.217310 -vn 0.352840 -0.624751 0.696556 -v 0.076337 0.066411 0.217310 -vn -0.449738 -0.559911 0.695870 -v 0.072591 0.066698 0.217310 -vn -0.389974 -0.602471 0.696383 -v 0.072697 0.066622 0.217310 -vn -0.330425 0.647358 0.686839 -v 0.073082 0.072608 0.217310 -vn -0.430449 0.575535 0.695322 -v 0.072485 0.072217 0.217310 -vn -0.245240 -0.675755 0.695135 -v 0.073422 0.066237 0.217310 -vn -0.166568 -0.701938 0.692487 -v 0.073927 0.066083 0.217310 -vn -0.085367 -0.714752 0.694148 -v 0.074254 0.066026 0.217310 -vn 0.083811 -0.714190 0.694917 -v 0.075125 0.066026 0.217310 -vn 0.172670 -0.702146 0.690779 -v 0.075421 0.066076 0.217310 -vn 0.278909 -0.664255 0.693523 -v 0.076175 0.066330 0.217310 -vn -0.648424 0.326320 0.687794 -v 0.071568 0.071082 0.217310 -vn -0.698790 0.195601 0.688064 -v 0.071318 0.070440 0.217310 -vn -0.721245 -0.091463 0.686615 -v 0.071221 0.069029 0.217310 -vn -0.725296 0.051038 0.686542 -v 0.071200 0.069767 0.217310 -vn -0.318907 -0.644277 0.695130 -v 0.073216 0.066324 0.217310 -vn -0.000246 -0.720435 0.693522 -v 0.074690 0.065999 0.217310 -# 2951 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 6//6 5//5 7//7 -f 6//6 7//7 8//8 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 2//2 -f 2//2 12//12 13//13 -f 2//2 13//13 3//3 -f 14//14 15//15 16//16 -f 16//16 15//15 17//17 -f 16//16 17//17 4//4 -f 4//4 17//17 18//18 -f 4//4 18//18 5//5 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 24//24 25//25 26//26 -f 26//26 25//25 27//27 -f 26//26 27//27 28//28 -f 7//7 29//29 8//8 -f 8//8 29//29 30//30 -f 8//8 30//30 9//9 -f 9//9 30//30 31//31 -f 9//9 31//31 10//10 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 34//34 35//35 36//36 -f 27//27 37//37 28//28 -f 28//28 37//37 38//38 -f 28//28 38//38 19//19 -f 19//19 38//38 39//39 -f 19//19 39//39 20//20 -f 40//40 41//41 42//42 -f 42//42 41//41 43//43 -f 42//42 43//43 44//44 -f 44//44 43//43 45//45 -f 44//44 45//45 24//24 -f 24//24 45//45 46//46 -f 24//24 46//46 25//25 -f 3//3 47//47 1//1 -f 1//1 47//47 48//48 -f 1//1 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 40//40 -f 40//40 50//50 51//51 -f 40//40 51//51 41//41 -f 35//35 52//52 36//36 -f 36//36 52//52 53//53 -f 36//36 53//53 14//14 -f 14//14 53//53 54//54 -f 14//14 54//54 15//15 -f 22//22 55//55 23//23 -f 23//23 55//55 56//56 -f 23//23 56//56 32//32 -f 32//32 56//56 57//57 -f 32//32 57//57 33//33 -f 58//58 59//59 60//60 -f 60//60 59//59 61//61 -f 60//60 61//61 62//62 -f 62//62 61//61 63//63 -f 62//62 63//63 64//64 -f 63//63 22//22 64//64 -f 64//64 22//22 65//65 -f 64//64 65//65 66//66 -f 66//66 65//65 67//67 -f 66//66 67//67 68//68 -f 68//68 67//67 69//69 -f 68//68 69//69 70//70 -f 70//70 69//69 71//71 -f 70//70 71//71 72//72 -f 72//72 71//71 73//73 -f 72//72 73//73 74//74 -f 74//74 73//73 25//25 -f 74//74 25//25 75//75 -f 75//75 25//25 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 82//82 80//80 83//83 -f 82//82 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 85//85 51//51 86//86 -f 86//86 51//51 87//87 -f 86//86 87//87 88//88 -f 88//88 87//87 89//89 -f 88//88 89//89 90//90 -f 90//90 89//89 91//91 -f 90//90 91//91 92//92 -f 92//92 91//91 93//93 -f 93//93 91//91 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 12//12 -f 97//97 12//12 98//98 -f 98//98 12//12 99//99 -f 98//98 99//99 100//100 -f 100//100 99//99 101//101 -f 100//100 101//101 102//102 -f 102//102 101//101 103//103 -f 104//104 105//105 106//106 -f 104//104 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 5//5 -f 5//5 110//110 111//111 -f 5//5 111//111 112//112 -f 112//112 111//111 113//113 -f 112//112 113//113 114//114 -f 114//114 113//113 102//102 -f 114//114 102//102 103//103 -f 105//105 104//104 115//115 -f 115//115 104//104 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 118//118 52//52 119//119 -f 119//119 52//52 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 59//59 -f 123//123 59//59 58//58 -f 124//124 125//125 126//126 -f 124//124 127//127 125//125 -f 125//125 127//127 128//128 -f 125//125 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 131//131 -f 131//131 130//130 132//132 -f 131//131 132//132 133//133 -f 134//134 135//135 136//136 -f 136//136 135//135 131//131 -f 136//136 131//131 137//137 -f 137//137 131//131 133//133 -f 134//134 138//138 135//135 -f 135//135 138//138 139//139 -f 135//135 139//139 140//140 -f 141//141 142//142 143//143 -f 143//143 142//142 140//140 -f 143//143 140//140 144//144 -f 144//144 140//140 139//139 -f 141//141 145//145 142//142 -f 142//142 145//145 146//146 -f 142//142 146//146 147//147 -f 148//148 149//149 150//150 -f 150//150 149//149 147//147 -f 150//150 147//147 151//151 -f 151//151 147//147 146//146 -f 148//148 152//152 149//149 -f 149//149 152//152 153//153 -f 149//149 153//153 154//154 -f 153//153 155//155 154//154 -f 154//154 155//155 156//156 -f 154//154 156//156 157//157 -f 156//156 158//158 157//157 -f 157//157 158//158 159//159 -f 157//157 159//159 160//160 -f 160//160 159//159 161//161 -f 160//160 161//161 162//162 -f 162//162 161//161 163//163 -f 162//162 163//163 164//164 -f 164//164 165//165 162//162 -f 162//162 165//165 166//166 -f 162//162 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 172//172 173//173 174//174 -f 174//174 173//173 169//169 -f 174//174 169//169 175//175 -f 175//175 169//169 171//171 -f 172//172 176//176 173//173 -f 173//173 176//176 177//177 -f 173//173 177//177 178//178 -f 179//179 180//180 181//181 -f 181//181 180//180 178//178 -f 181//181 178//178 182//182 -f 182//182 178//178 177//177 -f 179//179 183//183 180//180 -f 180//180 183//183 184//184 -f 180//180 184//184 185//185 -f 184//184 186//186 185//185 -f 185//185 186//186 187//187 -f 185//185 187//187 188//188 -f 187//187 189//189 188//188 -f 188//188 189//189 190//190 -f 188//188 190//190 126//126 -f 126//126 190//190 191//191 -f 126//126 191//191 124//124 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 194//194 195//195 196//196 -f 196//196 195//195 197//197 -f 196//196 197//197 198//198 -f 198//198 197//197 199//199 -f 198//198 199//199 200//200 -f 200//200 199//199 97//97 -f 200//200 97//97 201//201 -f 201//201 97//97 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 204//204 206//206 205//205 -f 205//205 206//206 207//207 -f 205//205 207//207 208//208 -f 208//208 207//207 209//209 -f 208//208 209//209 210//210 -f 210//210 209//209 211//211 -f 210//210 211//211 212//212 -f 212//212 211//211 213//213 -f 212//212 213//213 214//214 -f 214//214 213//213 215//215 -f 214//214 215//215 216//216 -f 215//215 110//110 216//216 -f 216//216 110//110 217//217 -f 216//216 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 220//220 219//219 221//221 -f 220//220 221//221 222//222 -f 222//222 221//221 223//223 -f 222//222 223//223 224//224 -f 224//224 223//223 225//225 -f 224//224 225//225 226//226 -f 226//226 225//225 227//227 -f 226//226 227//227 228//228 -f 227//227 229//229 228//228 -f 228//228 229//229 230//230 -f 228//228 230//230 231//231 -f 231//231 230//230 232//232 -f 231//231 232//232 233//233 -f 233//233 232//232 119//119 -f 233//233 119//119 234//234 -f 119//119 235//235 234//234 -f 234//234 235//235 236//236 -f 234//234 236//236 237//237 -f 237//237 236//236 238//238 -f 237//237 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 241//241 -f 240//240 242//242 241//241 -f 241//241 242//242 243//243 -f 241//241 243//243 244//244 -f 244//244 243//243 245//245 -f 244//244 245//245 246//246 -f 246//246 245//245 247//247 -f 246//246 247//247 248//248 -f 248//248 247//247 249//249 -f 248//248 249//249 250//250 -f 250//250 249//249 64//64 -f 250//250 64//64 251//251 -f 64//64 252//252 251//251 -f 251//251 252//252 253//253 -f 251//251 253//253 254//254 -f 254//254 253//253 255//255 -f 254//254 255//255 256//256 -f 256//256 255//255 257//257 -f 256//256 257//257 258//258 -f 258//258 257//257 259//259 -f 258//258 259//259 260//260 -f 259//259 261//261 260//260 -f 260//260 261//261 262//262 -f 260//260 262//262 263//263 -f 263//263 262//262 264//264 -f 263//263 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 267//267 -f 266//266 75//75 267//267 -f 267//267 75//75 268//268 -f 267//267 268//268 269//269 -f 269//269 268//268 270//270 -f 269//269 270//270 271//271 -f 271//271 270//270 272//272 -f 271//271 272//272 273//273 -f 273//273 272//272 274//274 -f 273//273 274//274 275//275 -f 275//275 274//274 276//276 -f 275//275 276//276 277//277 -f 277//277 276//276 278//278 -f 277//277 278//278 279//279 -f 278//278 280//280 279//279 -f 279//279 280//280 281//281 -f 279//279 281//281 282//282 -f 282//282 281//281 283//283 -f 282//282 283//283 284//284 -f 284//284 283//283 86//86 -f 284//284 86//86 285//285 -f 86//86 286//286 285//285 -f 285//285 286//286 287//287 -f 285//285 287//287 288//288 -f 288//288 287//287 289//289 -f 288//288 289//289 290//290 -f 290//290 289//289 291//291 -f 290//290 291//291 192//192 -f 192//192 291//291 292//292 -f 192//192 292//292 193//193 -f 241//241 293//293 239//239 -f 239//239 293//293 294//294 -f 239//239 294//294 237//237 -f 237//237 294//294 295//295 -f 237//237 295//295 234//234 -f 234//234 295//295 296//296 -f 234//234 296//296 233//233 -f 233//233 296//296 297//297 -f 233//233 297//297 231//231 -f 231//231 297//297 298//298 -f 231//231 298//298 228//228 -f 228//228 298//298 299//299 -f 228//228 299//299 226//226 -f 226//226 299//299 300//300 -f 226//226 300//300 224//224 -f 224//224 300//300 301//301 -f 224//224 301//301 222//222 -f 301//301 302//302 222//222 -f 222//222 302//302 303//303 -f 222//222 303//303 220//220 -f 220//220 303//303 304//304 -f 220//220 304//304 218//218 -f 218//218 304//304 305//305 -f 218//218 305//305 216//216 -f 305//305 306//306 216//216 -f 216//216 306//306 307//307 -f 216//216 307//307 214//214 -f 214//214 307//307 308//308 -f 214//214 308//308 212//212 -f 212//212 308//308 309//309 -f 212//212 309//309 210//210 -f 210//210 309//309 310//310 -f 210//210 310//310 208//208 -f 310//310 311//311 208//208 -f 208//208 311//311 312//312 -f 208//208 312//312 205//205 -f 205//205 312//312 313//313 -f 205//205 313//313 203//203 -f 203//203 313//313 314//314 -f 203//203 314//314 201//201 -f 201//201 314//314 315//315 -f 201//201 315//315 200//200 -f 200//200 315//315 316//316 -f 200//200 316//316 198//198 -f 316//316 317//317 198//198 -f 198//198 317//317 318//318 -f 198//198 318//318 196//196 -f 196//196 318//318 319//319 -f 196//196 319//319 194//194 -f 194//194 319//319 320//320 -f 194//194 320//320 192//192 -f 320//320 321//321 192//192 -f 192//192 321//321 322//322 -f 192//192 322//322 290//290 -f 290//290 322//322 323//323 -f 290//290 323//323 288//288 -f 288//288 323//323 285//285 -f 323//323 324//324 285//285 -f 285//285 324//324 325//325 -f 285//285 325//325 284//284 -f 284//284 325//325 326//326 -f 284//284 326//326 282//282 -f 282//282 326//326 327//327 -f 282//282 327//327 279//279 -f 279//279 327//327 328//328 -f 279//279 328//328 277//277 -f 329//329 267//267 269//269 -f 328//328 330//330 277//277 -f 277//277 330//330 331//331 -f 277//277 331//331 275//275 -f 275//275 331//331 332//332 -f 275//275 332//332 273//273 -f 273//273 332//332 333//333 -f 273//273 333//333 271//271 -f 271//271 333//333 334//334 -f 271//271 334//334 269//269 -f 269//269 334//334 335//335 -f 269//269 335//335 329//329 -f 329//329 336//336 267//267 -f 267//267 336//336 337//337 -f 267//267 337//337 265//265 -f 265//265 337//337 338//338 -f 265//265 338//338 263//263 -f 263//263 338//338 339//339 -f 263//263 339//339 260//260 -f 260//260 339//339 340//340 -f 260//260 340//340 258//258 -f 258//258 340//340 341//341 -f 258//258 341//341 256//256 -f 256//256 341//341 342//342 -f 256//256 342//342 254//254 -f 254//254 342//342 343//343 -f 254//254 343//343 251//251 -f 343//343 344//344 251//251 -f 251//251 344//344 345//345 -f 251//251 345//345 250//250 -f 250//250 345//345 346//346 -f 250//250 346//346 248//248 -f 248//248 346//346 347//347 -f 248//248 347//347 246//246 -f 246//246 347//347 348//348 -f 246//246 348//348 244//244 -f 244//244 348//348 349//349 -f 244//244 349//349 241//241 -f 241//241 349//349 350//350 -f 241//241 350//350 293//293 -f 346//346 345//345 351//351 -f 341//341 340//340 352//352 -f 336//336 329//329 353//353 -f 332//332 331//331 354//354 -f 326//326 325//325 355//355 -f 319//319 318//318 356//356 -f 314//314 313//313 357//357 -f 309//309 308//308 358//358 -f 304//304 303//303 359//359 -f 299//299 298//298 360//360 -f 361//361 362//362 363//363 -f 364//364 365//365 366//366 -f 367//367 364//364 368//368 -f 369//369 367//367 370//370 -f 371//371 369//369 372//372 -f 373//373 371//371 374//374 -f 375//375 373//373 376//376 -f 377//377 375//375 378//378 -f 379//379 377//377 380//380 -f 381//381 379//379 382//382 -f 383//383 381//381 384//384 -f 385//385 383//383 386//386 -f 387//387 385//385 388//388 -f 389//389 387//387 390//390 -f 391//391 389//389 392//392 -f 393//393 391//391 394//394 -f 395//395 393//393 396//396 -f 397//397 395//395 398//398 -f 399//399 397//397 400//400 -f 401//401 399//399 402//402 -f 403//403 401//401 404//404 -f 405//405 403//403 406//406 -f 407//407 405//405 408//408 -f 409//409 407//407 410//410 -f 411//411 409//409 412//412 -f 413//413 411//411 414//414 -f 415//415 413//413 416//416 -f 417//417 415//415 418//418 -f 419//419 417//417 420//420 -f 421//421 419//419 422//422 -f 423//423 421//421 424//424 -f 425//425 423//423 426//426 -f 427//427 362//362 428//428 -f 428//428 362//362 361//361 -f 428//428 361//361 429//429 -f 366//366 365//365 430//430 -f 431//431 363//363 432//432 -f 432//432 363//363 362//362 -f 432//432 362//362 433//433 -f 433//433 362//362 427//427 -f 433//433 427//427 425//425 -f 434//434 366//366 435//435 -f 435//435 366//366 430//430 -f 435//435 430//430 436//436 -f 437//437 434//434 438//438 -f 438//438 434//434 435//435 -f 438//438 435//435 439//439 -f 439//439 435//435 436//436 -f 439//439 436//436 440//440 -f 297//297 296//296 431//431 -f 431//431 296//296 440//440 -f 431//431 440//440 363//363 -f 363//363 440//440 436//436 -f 363//363 436//436 361//361 -f 361//361 436//436 430//430 -f 361//361 430//430 429//429 -f 429//429 430//430 365//365 -f 425//425 426//426 433//433 -f 433//433 426//426 441//441 -f 433//433 441//441 432//432 -f 432//432 441//441 360//360 -f 432//432 360//360 431//431 -f 431//431 360//360 298//298 -f 431//431 298//298 297//297 -f 423//423 424//424 426//426 -f 426//426 424//424 442//442 -f 426//426 442//442 441//441 -f 441//441 442//442 443//443 -f 441//441 443//443 360//360 -f 360//360 443//443 300//300 -f 360//360 300//300 299//299 -f 444//444 302//302 301//301 -f 421//421 422//422 424//424 -f 424//424 422//422 445//445 -f 424//424 445//445 442//442 -f 442//442 445//445 444//444 -f 442//442 444//444 443//443 -f 443//443 444//444 301//301 -f 443//443 301//301 300//300 -f 419//419 420//420 422//422 -f 422//422 420//420 446//446 -f 422//422 446//446 445//445 -f 445//445 446//446 359//359 -f 445//445 359//359 444//444 -f 444//444 359//359 303//303 -f 444//444 303//303 302//302 -f 417//417 418//418 420//420 -f 420//420 418//418 447//447 -f 420//420 447//447 446//446 -f 446//446 447//447 448//448 -f 446//446 448//448 359//359 -f 359//359 448//448 305//305 -f 359//359 305//305 304//304 -f 449//449 307//307 306//306 -f 415//415 416//416 418//418 -f 418//418 416//416 450//450 -f 418//418 450//450 447//447 -f 447//447 450//450 449//449 -f 447//447 449//449 448//448 -f 448//448 449//449 306//306 -f 448//448 306//306 305//305 -f 413//413 414//414 416//416 -f 416//416 414//414 451//451 -f 416//416 451//451 450//450 -f 450//450 451//451 358//358 -f 450//450 358//358 449//449 -f 449//449 358//358 308//308 -f 449//449 308//308 307//307 -f 411//411 412//412 414//414 -f 414//414 412//412 452//452 -f 414//414 452//452 451//451 -f 451//451 452//452 453//453 -f 451//451 453//453 358//358 -f 358//358 453//453 310//310 -f 358//358 310//310 309//309 -f 454//454 312//312 311//311 -f 409//409 410//410 412//412 -f 412//412 410//410 455//455 -f 412//412 455//455 452//452 -f 452//452 455//455 454//454 -f 452//452 454//454 453//453 -f 453//453 454//454 311//311 -f 453//453 311//311 310//310 -f 407//407 408//408 410//410 -f 410//410 408//408 456//456 -f 410//410 456//456 455//455 -f 455//455 456//456 357//357 -f 455//455 357//357 454//454 -f 454//454 357//357 313//313 -f 454//454 313//313 312//312 -f 405//405 406//406 408//408 -f 408//408 406//406 457//457 -f 408//408 457//457 456//456 -f 456//456 457//457 458//458 -f 456//456 458//458 357//357 -f 357//357 458//458 315//315 -f 357//357 315//315 314//314 -f 459//459 317//317 316//316 -f 403//403 404//404 406//406 -f 406//406 404//404 460//460 -f 406//406 460//460 457//457 -f 457//457 460//460 459//459 -f 457//457 459//459 458//458 -f 458//458 459//459 316//316 -f 458//458 316//316 315//315 -f 401//401 402//402 404//404 -f 404//404 402//402 461//461 -f 404//404 461//461 460//460 -f 460//460 461//461 356//356 -f 460//460 356//356 459//459 -f 459//459 356//356 318//318 -f 459//459 318//318 317//317 -f 399//399 400//400 402//402 -f 402//402 400//400 462//462 -f 402//402 462//462 461//461 -f 461//461 462//462 463//463 -f 461//461 463//463 356//356 -f 356//356 463//463 320//320 -f 356//356 320//320 319//319 -f 464//464 322//322 321//321 -f 397//397 398//398 400//400 -f 400//400 398//398 465//465 -f 400//400 465//465 462//462 -f 462//462 465//465 464//464 -f 462//462 464//464 463//463 -f 463//463 464//464 321//321 -f 463//463 321//321 320//320 -f 466//466 324//324 323//323 -f 395//395 396//396 398//398 -f 398//398 396//396 467//467 -f 398//398 467//467 465//465 -f 465//465 467//467 466//466 -f 465//465 466//466 464//464 -f 464//464 466//466 323//323 -f 464//464 323//323 322//322 -f 393//393 394//394 396//396 -f 396//396 394//394 468//468 -f 396//396 468//468 467//467 -f 467//467 468//468 355//355 -f 467//467 355//355 466//466 -f 466//466 355//355 325//325 -f 466//466 325//325 324//324 -f 391//391 392//392 394//394 -f 394//394 392//392 469//469 -f 394//394 469//469 468//468 -f 468//468 469//469 470//470 -f 468//468 470//470 355//355 -f 355//355 470//470 327//327 -f 355//355 327//327 326//326 -f 471//471 330//330 328//328 -f 389//389 390//390 392//392 -f 392//392 390//390 472//472 -f 392//392 472//472 469//469 -f 469//469 472//472 471//471 -f 469//469 471//471 470//470 -f 470//470 471//471 328//328 -f 470//470 328//328 327//327 -f 387//387 388//388 390//390 -f 390//390 388//388 473//473 -f 390//390 473//473 472//472 -f 472//472 473//473 354//354 -f 472//472 354//354 471//471 -f 471//471 354//354 331//331 -f 471//471 331//331 330//330 -f 385//385 386//386 388//388 -f 388//388 386//386 474//474 -f 388//388 474//474 473//473 -f 473//473 474//474 475//475 -f 473//473 475//475 354//354 -f 354//354 475//475 333//333 -f 354//354 333//333 332//332 -f 476//476 335//335 334//334 -f 383//383 384//384 386//386 -f 386//386 384//384 477//477 -f 386//386 477//477 474//474 -f 474//474 477//477 476//476 -f 474//474 476//476 475//475 -f 475//475 476//476 334//334 -f 475//475 334//334 333//333 -f 381//381 382//382 384//384 -f 384//384 382//382 478//478 -f 384//384 478//478 477//477 -f 477//477 478//478 353//353 -f 477//477 353//353 476//476 -f 476//476 353//353 329//329 -f 476//476 329//329 335//335 -f 379//379 380//380 382//382 -f 382//382 380//380 479//479 -f 382//382 479//479 478//478 -f 478//478 479//479 480//480 -f 478//478 480//480 353//353 -f 353//353 480//480 337//337 -f 353//353 337//337 336//336 -f 481//481 339//339 338//338 -f 377//377 378//378 380//380 -f 380//380 378//378 482//482 -f 380//380 482//482 479//479 -f 479//479 482//482 481//481 -f 479//479 481//481 480//480 -f 480//480 481//481 338//338 -f 480//480 338//338 337//337 -f 375//375 376//376 378//378 -f 378//378 376//376 483//483 -f 378//378 483//483 482//482 -f 482//482 483//483 352//352 -f 482//482 352//352 481//481 -f 481//481 352//352 340//340 -f 481//481 340//340 339//339 -f 373//373 374//374 376//376 -f 376//376 374//374 484//484 -f 376//376 484//484 483//483 -f 483//483 484//484 485//485 -f 483//483 485//485 352//352 -f 352//352 485//485 342//342 -f 352//352 342//342 341//341 -f 486//486 344//344 343//343 -f 371//371 372//372 374//374 -f 374//374 372//372 487//487 -f 374//374 487//487 484//484 -f 484//484 487//487 486//486 -f 484//484 486//486 485//485 -f 485//485 486//486 343//343 -f 485//485 343//343 342//342 -f 369//369 370//370 372//372 -f 372//372 370//370 488//488 -f 372//372 488//488 487//487 -f 487//487 488//488 351//351 -f 487//487 351//351 486//486 -f 486//486 351//351 345//345 -f 486//486 345//345 344//344 -f 367//367 368//368 370//370 -f 370//370 368//368 489//489 -f 370//370 489//489 488//488 -f 488//488 489//489 490//490 -f 488//488 490//490 351//351 -f 351//351 490//490 347//347 -f 351//351 347//347 346//346 -f 364//364 366//366 368//368 -f 368//368 366//366 434//434 -f 368//368 434//434 489//489 -f 489//489 434//434 437//437 -f 489//489 437//437 490//490 -f 490//490 437//437 348//348 -f 490//490 348//348 347//347 -f 296//296 295//295 440//440 -f 440//440 295//295 294//294 -f 440//440 294//294 439//439 -f 439//439 294//294 293//293 -f 439//439 293//293 438//438 -f 438//438 293//293 350//350 -f 438//438 350//350 437//437 -f 437//437 350//350 349//349 -f 437//437 349//349 348//348 -f 423//423 491//491 421//421 -f 421//421 491//491 492//492 -f 421//421 492//492 419//419 -f 419//419 492//492 493//493 -f 419//419 493//493 417//417 -f 417//417 493//493 494//494 -f 417//417 494//494 415//415 -f 415//415 494//494 495//495 -f 415//415 495//495 413//413 -f 413//413 495//495 496//496 -f 413//413 496//496 411//411 -f 411//411 496//496 497//497 -f 411//411 497//497 409//409 -f 409//409 497//497 498//498 -f 409//409 498//498 407//407 -f 407//407 498//498 499//499 -f 407//407 499//499 405//405 -f 369//369 500//500 367//367 -f 367//367 500//500 501//501 -f 367//367 501//501 364//364 -f 364//364 501//501 502//502 -f 364//364 502//502 365//365 -f 365//365 502//502 503//503 -f 365//365 503//503 429//429 -f 429//429 503//503 504//504 -f 429//429 504//504 428//428 -f 428//428 504//504 505//505 -f 428//428 505//505 427//427 -f 427//427 505//505 506//506 -f 427//427 506//506 425//425 -f 425//425 506//506 507//507 -f 425//425 507//507 423//423 -f 423//423 507//507 508//508 -f 423//423 508//508 491//491 -f 387//387 509//509 385//385 -f 385//385 509//509 510//510 -f 385//385 510//510 383//383 -f 383//383 510//510 511//511 -f 383//383 511//511 381//381 -f 381//381 511//511 512//512 -f 381//381 512//512 379//379 -f 379//379 512//512 513//513 -f 379//379 513//513 377//377 -f 377//377 513//513 514//514 -f 377//377 514//514 375//375 -f 375//375 514//514 515//515 -f 375//375 515//515 373//373 -f 373//373 515//515 516//516 -f 373//373 516//516 371//371 -f 371//371 516//516 517//517 -f 371//371 517//517 369//369 -f 369//369 517//517 518//518 -f 369//369 518//518 500//500 -f 499//499 519//519 405//405 -f 405//405 519//519 520//520 -f 405//405 520//520 403//403 -f 403//403 520//520 521//521 -f 403//403 521//521 401//401 -f 401//401 521//521 522//522 -f 401//401 522//522 399//399 -f 399//399 522//522 523//523 -f 399//399 523//523 397//397 -f 397//397 523//523 524//524 -f 397//397 524//524 395//395 -f 395//395 524//524 525//525 -f 395//395 525//525 393//393 -f 393//393 525//525 526//526 -f 393//393 526//526 391//391 -f 391//391 526//526 527//527 -f 391//391 527//527 389//389 -f 389//389 527//527 528//528 -f 389//389 528//528 387//387 -f 387//387 528//528 529//529 -f 387//387 529//529 509//509 -f 530//530 531//531 532//532 -f 532//532 531//531 533//533 -f 532//532 533//533 534//534 -f 534//534 533//533 535//535 -f 534//534 535//535 536//536 -f 536//536 535//535 537//537 -f 536//536 537//537 538//538 -f 530//530 539//539 531//531 -f 531//531 539//539 540//540 -f 531//531 540//540 541//541 -f 541//541 540//540 542//542 -f 541//541 542//542 543//543 -f 542//542 544//544 543//543 -f 543//543 544//544 545//545 -f 543//543 545//545 546//546 -f 546//546 545//545 547//547 -f 546//546 547//547 548//548 -f 548//548 547//547 549//549 -f 549//549 550//550 548//548 -f 548//548 550//550 551//551 -f 548//548 551//551 552//552 -f 552//552 551//551 553//553 -f 552//552 553//553 554//554 -f 554//554 553//553 555//555 -f 554//554 555//555 556//556 -f 556//556 555//555 557//557 -f 557//557 558//558 556//556 -f 556//556 558//558 559//559 -f 556//556 559//559 560//560 -f 560//560 559//559 561//561 -f 560//560 561//561 562//562 -f 562//562 561//561 563//563 -f 562//562 563//563 564//564 -f 564//564 563//563 565//565 -f 565//565 566//566 564//564 -f 564//564 566//566 567//567 -f 564//564 567//567 568//568 -f 568//568 567//567 569//569 -f 568//568 569//569 570//570 -f 570//570 569//569 571//571 -f 570//570 571//571 572//572 -f 572//572 571//571 573//573 -f 573//573 574//574 572//572 -f 572//572 574//574 575//575 -f 572//572 575//575 576//576 -f 576//576 575//575 577//577 -f 576//576 577//577 578//578 -f 577//577 579//579 578//578 -f 578//578 579//579 580//580 -f 578//578 580//580 581//581 -f 581//581 580//580 582//582 -f 581//581 582//582 583//583 -f 583//583 582//582 584//584 -f 584//584 585//585 583//583 -f 583//583 585//585 586//586 -f 583//583 586//586 587//587 -f 587//587 586//586 588//588 -f 587//587 588//588 589//589 -f 589//589 588//588 590//590 -f 589//589 590//590 591//591 -f 591//591 590//590 592//592 -f 592//592 593//593 591//591 -f 591//591 593//593 594//594 -f 591//591 594//594 595//595 -f 595//595 594//594 596//596 -f 595//595 596//596 597//597 -f 597//597 596//596 598//598 -f 597//597 598//598 599//599 -f 599//599 598//598 600//600 -f 600//600 601//601 599//599 -f 599//599 601//601 602//602 -f 599//599 602//602 603//603 -f 603//603 602//602 604//604 -f 603//603 604//604 605//605 -f 605//605 604//604 606//606 -f 605//605 606//606 607//607 -f 607//607 606//606 608//608 -f 608//608 609//609 607//607 -f 607//607 609//609 610//610 -f 607//607 610//610 611//611 -f 611//611 610//610 612//612 -f 611//611 612//612 613//613 -f 612//612 614//614 613//613 -f 613//613 614//614 615//615 -f 613//613 615//615 616//616 -f 616//616 615//615 617//617 -f 616//616 617//617 618//618 -f 618//618 617//617 619//619 -f 619//619 620//620 618//618 -f 618//618 620//620 621//621 -f 618//618 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 624//624 623//623 625//625 -f 624//624 625//625 626//626 -f 626//626 625//625 627//627 -f 627//627 628//628 626//626 -f 626//626 628//628 629//629 -f 626//626 629//629 630//630 -f 630//630 629//629 631//631 -f 630//630 631//631 632//632 -f 632//632 631//631 633//633 -f 632//632 633//633 537//537 -f 537//537 633//633 634//634 -f 537//537 634//634 538//538 -f 632//632 635//635 630//630 -f 630//630 635//635 636//636 -f 630//630 636//636 626//626 -f 626//626 636//636 637//637 -f 626//626 637//637 624//624 -f 624//624 637//637 638//638 -f 624//624 638//638 622//622 -f 622//622 638//638 639//639 -f 622//622 639//639 618//618 -f 618//618 639//639 640//640 -f 618//618 640//640 616//616 -f 616//616 640//640 641//641 -f 616//616 641//641 613//613 -f 613//613 641//641 642//642 -f 613//613 642//642 611//611 -f 611//611 642//642 643//643 -f 611//611 643//643 607//607 -f 607//607 643//643 644//644 -f 607//607 644//644 605//605 -f 605//605 644//644 645//645 -f 605//605 645//645 603//603 -f 603//603 645//645 646//646 -f 603//603 646//646 599//599 -f 599//599 646//646 647//647 -f 599//599 647//647 597//597 -f 597//597 647//647 648//648 -f 597//597 648//648 595//595 -f 595//595 648//648 649//649 -f 595//595 649//649 591//591 -f 591//591 649//649 650//650 -f 591//591 650//650 589//589 -f 589//589 650//650 651//651 -f 589//589 651//651 587//587 -f 587//587 651//651 652//652 -f 587//587 652//652 583//583 -f 583//583 652//652 653//653 -f 583//583 653//653 581//581 -f 581//581 653//653 654//654 -f 581//581 654//654 578//578 -f 578//578 654//654 655//655 -f 578//578 655//655 576//576 -f 576//576 655//655 656//656 -f 576//576 656//656 572//572 -f 572//572 656//656 657//657 -f 572//572 657//657 570//570 -f 570//570 657//657 658//658 -f 570//570 658//658 568//568 -f 568//568 658//658 659//659 -f 568//568 659//659 564//564 -f 564//564 659//659 660//660 -f 564//564 660//660 562//562 -f 562//562 660//660 661//661 -f 562//562 661//661 560//560 -f 560//560 661//661 662//662 -f 560//560 662//662 556//556 -f 556//556 662//662 663//663 -f 556//556 663//663 554//554 -f 554//554 663//663 664//664 -f 554//554 664//664 552//552 -f 552//552 664//664 665//665 -f 552//552 665//665 548//548 -f 548//548 665//665 666//666 -f 548//548 666//666 546//546 -f 546//546 666//666 667//667 -f 546//546 667//667 543//543 -f 543//543 667//667 668//668 -f 543//543 668//668 541//541 -f 541//541 668//668 669//669 -f 541//541 669//669 531//531 -f 531//531 669//669 670//670 -f 531//531 670//670 533//533 -f 533//533 670//670 671//671 -f 533//533 671//671 535//535 -f 535//535 671//671 672//672 -f 535//535 672//672 537//537 -f 537//537 672//672 673//673 -f 537//537 673//673 632//632 -f 632//632 673//673 635//635 -f 673//673 674//674 635//635 -f 635//635 674//674 675//675 -f 635//635 675//675 636//636 -f 636//636 675//675 676//676 -f 636//636 676//676 637//637 -f 637//637 676//676 677//677 -f 637//637 677//677 638//638 -f 638//638 677//677 678//678 -f 638//638 678//678 639//639 -f 639//639 678//678 679//679 -f 639//639 679//679 640//640 -f 640//640 679//679 680//680 -f 640//640 680//680 641//641 -f 641//641 680//680 681//681 -f 641//641 681//681 642//642 -f 642//642 681//681 682//682 -f 642//642 682//682 643//643 -f 643//643 682//682 683//683 -f 643//643 683//683 644//644 -f 644//644 683//683 684//684 -f 644//644 684//684 645//645 -f 645//645 684//684 685//685 -f 645//645 685//685 646//646 -f 646//646 685//685 686//686 -f 646//646 686//686 647//647 -f 647//647 686//686 687//687 -f 647//647 687//687 648//648 -f 648//648 687//687 688//688 -f 648//648 688//688 649//649 -f 649//649 688//688 689//689 -f 649//649 689//689 650//650 -f 650//650 689//689 690//690 -f 650//650 690//690 651//651 -f 651//651 690//690 691//691 -f 651//651 691//691 652//652 -f 652//652 691//691 692//692 -f 652//652 692//692 653//653 -f 653//653 692//692 693//693 -f 653//653 693//693 654//654 -f 654//654 693//693 694//694 -f 654//654 694//694 655//655 -f 655//655 694//694 695//695 -f 655//655 695//695 656//656 -f 656//656 695//695 696//696 -f 656//656 696//696 657//657 -f 657//657 696//696 697//697 -f 657//657 697//697 658//658 -f 658//658 697//697 698//698 -f 658//658 698//698 659//659 -f 659//659 698//698 699//699 -f 659//659 699//699 660//660 -f 660//660 699//699 700//700 -f 660//660 700//700 661//661 -f 661//661 700//700 701//701 -f 661//661 701//701 662//662 -f 662//662 701//701 702//702 -f 662//662 702//702 663//663 -f 663//663 702//702 703//703 -f 663//663 703//703 664//664 -f 664//664 703//703 704//704 -f 664//664 704//704 665//665 -f 665//665 704//704 705//705 -f 665//665 705//705 666//666 -f 666//666 705//705 706//706 -f 666//666 706//706 667//667 -f 667//667 706//706 707//707 -f 667//667 707//707 668//668 -f 668//668 707//707 708//708 -f 668//668 708//708 669//669 -f 669//669 708//708 709//709 -f 669//669 709//709 670//670 -f 670//670 709//709 710//710 -f 670//670 710//710 671//671 -f 671//671 710//710 711//711 -f 671//671 711//711 672//672 -f 672//672 711//711 712//712 -f 672//672 712//712 673//673 -f 673//673 712//712 674//674 -f 712//712 713//713 674//674 -f 674//674 713//713 714//714 -f 674//674 714//714 675//675 -f 675//675 714//714 715//715 -f 675//675 715//715 676//676 -f 676//676 715//715 716//716 -f 676//676 716//716 677//677 -f 677//677 716//716 717//717 -f 677//677 717//717 678//678 -f 678//678 717//717 718//718 -f 678//678 718//718 679//679 -f 679//679 718//718 719//719 -f 679//679 719//719 680//680 -f 680//680 719//719 720//720 -f 680//680 720//720 681//681 -f 681//681 720//720 721//721 -f 681//681 721//721 682//682 -f 682//682 721//721 722//722 -f 682//682 722//722 683//683 -f 683//683 722//722 723//723 -f 683//683 723//723 684//684 -f 684//684 723//723 724//724 -f 684//684 724//724 685//685 -f 685//685 724//724 725//725 -f 685//685 725//725 686//686 -f 686//686 725//725 726//726 -f 686//686 726//726 687//687 -f 687//687 726//726 727//727 -f 687//687 727//727 688//688 -f 688//688 727//727 728//728 -f 688//688 728//728 689//689 -f 689//689 728//728 729//729 -f 689//689 729//729 690//690 -f 690//690 729//729 730//730 -f 690//690 730//730 691//691 -f 691//691 730//730 731//731 -f 691//691 731//731 692//692 -f 692//692 731//731 732//732 -f 692//692 732//732 693//693 -f 693//693 732//732 733//733 -f 693//693 733//733 694//694 -f 694//694 733//733 734//734 -f 694//694 734//734 695//695 -f 695//695 734//734 735//735 -f 695//695 735//735 696//696 -f 696//696 735//735 736//736 -f 696//696 736//736 697//697 -f 697//697 736//736 737//737 -f 697//697 737//737 698//698 -f 698//698 737//737 738//738 -f 698//698 738//738 699//699 -f 699//699 738//738 739//739 -f 699//699 739//739 700//700 -f 700//700 739//739 740//740 -f 700//700 740//740 701//701 -f 701//701 740//740 741//741 -f 701//701 741//741 702//702 -f 702//702 741//741 742//742 -f 702//702 742//742 703//703 -f 703//703 742//742 743//743 -f 703//703 743//743 704//704 -f 704//704 743//743 744//744 -f 704//704 744//744 705//705 -f 705//705 744//744 745//745 -f 705//705 745//745 706//706 -f 706//706 745//745 746//746 -f 706//706 746//746 707//707 -f 707//707 746//746 747//747 -f 707//707 747//747 708//708 -f 708//708 747//747 748//748 -f 708//708 748//748 709//709 -f 709//709 748//748 749//749 -f 709//709 749//749 710//710 -f 710//710 749//749 750//750 -f 710//710 750//750 711//711 -f 711//711 750//750 751//751 -f 711//711 751//751 712//712 -f 712//712 751//751 713//713 -f 751//751 503//503 713//713 -f 713//713 503//503 502//502 -f 713//713 502//502 714//714 -f 714//714 502//502 501//501 -f 714//714 501//501 715//715 -f 715//715 501//501 500//500 -f 715//715 500//500 716//716 -f 716//716 500//500 518//518 -f 716//716 518//518 717//717 -f 717//717 518//518 517//517 -f 717//717 517//517 718//718 -f 718//718 517//517 516//516 -f 718//718 516//516 719//719 -f 719//719 516//516 515//515 -f 719//719 515//515 720//720 -f 720//720 515//515 514//514 -f 720//720 514//514 721//721 -f 721//721 514//514 513//513 -f 721//721 513//513 722//722 -f 722//722 513//513 512//512 -f 722//722 512//512 723//723 -f 723//723 512//512 511//511 -f 723//723 511//511 724//724 -f 724//724 511//511 510//510 -f 724//724 510//510 725//725 -f 725//725 510//510 509//509 -f 725//725 509//509 726//726 -f 726//726 509//509 529//529 -f 726//726 529//529 727//727 -f 727//727 529//529 528//528 -f 727//727 528//528 728//728 -f 728//728 528//528 527//527 -f 728//728 527//527 729//729 -f 729//729 527//527 526//526 -f 729//729 526//526 730//730 -f 730//730 526//526 525//525 -f 730//730 525//525 731//731 -f 731//731 525//525 524//524 -f 731//731 524//524 732//732 -f 732//732 524//524 523//523 -f 732//732 523//523 733//733 -f 733//733 523//523 522//522 -f 733//733 522//522 734//734 -f 734//734 522//522 521//521 -f 734//734 521//521 735//735 -f 735//735 521//521 520//520 -f 735//735 520//520 736//736 -f 736//736 520//520 519//519 -f 736//736 519//519 737//737 -f 737//737 519//519 499//499 -f 737//737 499//499 738//738 -f 738//738 499//499 498//498 -f 738//738 498//498 739//739 -f 739//739 498//498 497//497 -f 739//739 497//497 740//740 -f 740//740 497//497 496//496 -f 740//740 496//496 741//741 -f 741//741 496//496 495//495 -f 741//741 495//495 742//742 -f 742//742 495//495 494//494 -f 742//742 494//494 743//743 -f 743//743 494//494 493//493 -f 743//743 493//493 744//744 -f 744//744 493//493 492//492 -f 744//744 492//492 745//745 -f 745//745 492//492 491//491 -f 745//745 491//491 746//746 -f 746//746 491//491 508//508 -f 746//746 508//508 747//747 -f 747//747 508//508 507//507 -f 747//747 507//507 748//748 -f 748//748 507//507 506//506 -f 748//748 506//506 749//749 -f 749//749 506//506 505//505 -f 749//749 505//505 750//750 -f 750//750 505//505 504//504 -f 750//750 504//504 751//751 -f 751//751 504//504 503//503 -f 752//752 575//575 753//753 -f 753//753 575//575 574//574 -f 753//753 574//574 754//754 -f 754//754 574//574 573//573 -f 754//754 573//573 755//755 -f 755//755 573//573 571//571 -f 755//755 571//571 756//756 -f 571//571 569//569 756//756 -f 756//756 569//569 567//567 -f 756//756 567//567 757//757 -f 757//757 567//567 566//566 -f 757//757 566//566 758//758 -f 758//758 566//566 565//565 -f 758//758 565//565 759//759 -f 759//759 565//565 563//563 -f 759//759 563//563 760//760 -f 760//760 563//563 561//561 -f 760//760 561//561 761//761 -f 561//561 559//559 761//761 -f 761//761 559//559 558//558 -f 761//761 558//558 762//762 -f 762//762 558//558 557//557 -f 762//762 557//557 763//763 -f 763//763 557//557 555//555 -f 763//763 555//555 764//764 -f 764//764 555//555 553//553 -f 764//764 553//553 765//765 -f 553//553 551//551 765//765 -f 765//765 551//551 550//550 -f 765//765 550//550 766//766 -f 766//766 550//550 549//549 -f 766//766 549//549 767//767 -f 767//767 549//549 547//547 -f 767//767 547//547 768//768 -f 768//768 547//547 545//545 -f 768//768 545//545 769//769 -f 769//769 545//545 544//544 -f 769//769 544//544 770//770 -f 544//544 542//542 770//770 -f 770//770 542//542 540//540 -f 770//770 540//540 771//771 -f 771//771 540//540 539//539 -f 771//771 539//539 772//772 -f 772//772 539//539 530//530 -f 772//772 530//530 773//773 -f 773//773 530//530 532//532 -f 773//773 532//532 774//774 -f 532//532 534//534 774//774 -f 774//774 534//534 536//536 -f 774//774 536//536 775//775 -f 775//775 536//536 538//538 -f 775//775 538//538 776//776 -f 776//776 538//538 634//634 -f 776//776 634//634 777//777 -f 777//777 634//634 633//633 -f 777//777 633//633 778//778 -f 778//778 633//633 631//631 -f 778//778 631//631 779//779 -f 631//631 629//629 779//779 -f 779//779 629//629 628//628 -f 779//779 628//628 780//780 -f 780//780 628//628 627//627 -f 780//780 627//627 781//781 -f 781//781 627//627 625//625 -f 781//781 625//625 782//782 -f 782//782 625//625 623//623 -f 782//782 623//623 783//783 -f 623//623 621//621 783//783 -f 783//783 621//621 620//620 -f 783//783 620//620 784//784 -f 784//784 620//620 619//619 -f 784//784 619//619 785//785 -f 785//785 619//619 617//617 -f 785//785 617//617 786//786 -f 786//786 617//617 615//615 -f 786//786 615//615 787//787 -f 787//787 615//615 614//614 -f 787//787 614//614 788//788 -f 614//614 612//612 788//788 -f 788//788 612//612 610//610 -f 788//788 610//610 789//789 -f 789//789 610//610 609//609 -f 789//789 609//609 790//790 -f 790//790 609//609 608//608 -f 790//790 608//608 791//791 -f 791//791 608//608 606//606 -f 791//791 606//606 792//792 -f 606//606 604//604 792//792 -f 792//792 604//604 602//602 -f 792//792 602//602 793//793 -f 793//793 602//602 601//601 -f 793//793 601//601 794//794 -f 794//794 601//601 600//600 -f 794//794 600//600 795//795 -f 795//795 600//600 598//598 -f 795//795 598//598 796//796 -f 796//796 598//598 596//596 -f 796//796 596//596 797//797 -f 596//596 594//594 797//797 -f 797//797 594//594 593//593 -f 797//797 593//593 798//798 -f 798//798 593//593 592//592 -f 798//798 592//592 799//799 -f 799//799 592//592 590//590 -f 799//799 590//590 800//800 -f 800//800 590//590 588//588 -f 800//800 588//588 801//801 -f 588//588 586//586 801//801 -f 801//801 586//586 585//585 -f 801//801 585//585 802//802 -f 802//802 585//585 584//584 -f 802//802 584//584 803//803 -f 803//803 584//584 582//582 -f 803//803 582//582 804//804 -f 804//804 582//582 580//580 -f 804//804 580//580 805//805 -f 805//805 580//580 579//579 -f 805//805 579//579 752//752 -f 752//752 579//579 577//577 -f 752//752 577//577 575//575 -f 806//806 807//807 808//808 -f 808//808 807//807 809//809 -f 808//808 809//809 810//810 -f 810//810 809//809 811//811 -f 810//810 811//811 812//812 -f 812//812 811//811 813//813 -f 812//812 813//813 814//814 -f 814//814 813//813 815//815 -f 814//814 815//815 816//816 -f 816//816 815//815 817//817 -f 816//816 817//817 818//818 -f 818//818 817//817 819//819 -f 818//818 819//819 820//820 -f 820//820 819//819 821//821 -f 820//820 821//821 822//822 -f 822//822 821//821 823//823 -f 822//822 823//823 824//824 -f 824//824 823//823 825//825 -f 824//824 825//825 826//826 -f 826//826 825//825 827//827 -f 826//826 827//827 828//828 -f 828//828 827//827 829//829 -f 828//828 829//829 830//830 -f 830//830 829//829 831//831 -f 830//830 831//831 832//832 -f 832//832 831//831 833//833 -f 832//832 833//833 834//834 -f 834//834 833//833 835//835 -f 834//834 835//835 836//836 -f 836//836 835//835 837//837 -f 836//836 837//837 838//838 -f 838//838 837//837 839//839 -f 838//838 839//839 840//840 -f 840//840 839//839 841//841 -f 840//840 841//841 842//842 -f 842//842 841//841 843//843 -f 842//842 843//843 844//844 -f 844//844 843//843 845//845 -f 844//844 845//845 846//846 -f 846//846 845//845 847//847 -f 846//846 847//847 848//848 -f 848//848 847//847 849//849 -f 848//848 849//849 850//850 -f 850//850 849//849 851//851 -f 850//850 851//851 852//852 -f 852//852 851//851 853//853 -f 852//852 853//853 854//854 -f 854//854 853//853 855//855 -f 854//854 855//855 856//856 -f 856//856 855//855 857//857 -f 856//856 857//857 858//858 -f 858//858 857//857 859//859 -f 858//858 859//859 860//860 -f 860//860 859//859 861//861 -f 860//860 861//861 862//862 -f 862//862 861//861 863//863 -f 862//862 863//863 864//864 -f 864//864 863//863 865//865 -f 864//864 865//865 866//866 -f 866//866 865//865 867//867 -f 866//866 867//867 868//868 -f 868//868 867//867 869//869 -f 868//868 869//869 870//870 -f 870//870 869//869 871//871 -f 870//870 871//871 872//872 -f 872//872 871//871 873//873 -f 872//872 873//873 874//874 -f 874//874 873//873 875//875 -f 874//874 875//875 876//876 -f 876//876 875//875 877//877 -f 876//876 877//877 878//878 -f 878//878 877//877 879//879 -f 878//878 879//879 880//880 -f 880//880 879//879 881//881 -f 880//880 881//881 882//882 -f 882//882 881//881 883//883 -f 882//882 883//883 884//884 -f 884//884 883//883 885//885 -f 884//884 885//885 886//886 -f 886//886 885//885 887//887 -f 886//886 887//887 888//888 -f 888//888 887//887 889//889 -f 888//888 889//889 890//890 -f 890//890 889//889 891//891 -f 890//890 891//891 892//892 -f 892//892 891//891 893//893 -f 892//892 893//893 894//894 -f 894//894 893//893 895//895 -f 894//894 895//895 896//896 -f 896//896 895//895 897//897 -f 896//896 897//897 898//898 -f 898//898 897//897 899//899 -f 898//898 899//899 900//900 -f 900//900 899//899 901//901 -f 900//900 901//901 902//902 -f 902//902 901//901 903//903 -f 902//902 903//903 904//904 -f 904//904 903//903 905//905 -f 904//904 905//905 906//906 -f 906//906 905//905 907//907 -f 906//906 907//907 908//908 -f 908//908 907//907 909//909 -f 908//908 909//909 910//910 -f 910//910 909//909 911//911 -f 910//910 911//911 912//912 -f 912//912 911//911 913//913 -f 912//912 913//913 806//806 -f 806//806 913//913 807//807 -f 913//913 778//778 807//807 -f 807//807 778//778 779//779 -f 807//807 779//779 809//809 -f 809//809 779//779 780//780 -f 809//809 780//780 811//811 -f 811//811 780//780 781//781 -f 811//811 781//781 813//813 -f 813//813 781//781 782//782 -f 813//813 782//782 815//815 -f 815//815 782//782 783//783 -f 815//815 783//783 817//817 -f 817//817 783//783 784//784 -f 817//817 784//784 819//819 -f 819//819 784//784 785//785 -f 819//819 785//785 821//821 -f 821//821 785//785 786//786 -f 821//821 786//786 823//823 -f 823//823 786//786 787//787 -f 823//823 787//787 825//825 -f 825//825 787//787 788//788 -f 825//825 788//788 827//827 -f 827//827 788//788 789//789 -f 827//827 789//789 829//829 -f 829//829 789//789 790//790 -f 829//829 790//790 831//831 -f 831//831 790//790 791//791 -f 831//831 791//791 833//833 -f 833//833 791//791 792//792 -f 833//833 792//792 835//835 -f 835//835 792//792 793//793 -f 835//835 793//793 837//837 -f 837//837 793//793 794//794 -f 837//837 794//794 839//839 -f 839//839 794//794 795//795 -f 839//839 795//795 841//841 -f 841//841 795//795 796//796 -f 841//841 796//796 843//843 -f 843//843 796//796 797//797 -f 843//843 797//797 845//845 -f 845//845 797//797 798//798 -f 845//845 798//798 847//847 -f 847//847 798//798 799//799 -f 847//847 799//799 849//849 -f 849//849 799//799 800//800 -f 849//849 800//800 851//851 -f 851//851 800//800 801//801 -f 851//851 801//801 853//853 -f 853//853 801//801 802//802 -f 853//853 802//802 855//855 -f 855//855 802//802 803//803 -f 855//855 803//803 857//857 -f 857//857 803//803 804//804 -f 857//857 804//804 859//859 -f 859//859 804//804 805//805 -f 859//859 805//805 861//861 -f 861//861 805//805 752//752 -f 861//861 752//752 863//863 -f 863//863 752//752 753//753 -f 863//863 753//753 865//865 -f 865//865 753//753 754//754 -f 865//865 754//754 867//867 -f 867//867 754//754 755//755 -f 867//867 755//755 869//869 -f 869//869 755//755 756//756 -f 869//869 756//756 871//871 -f 871//871 756//756 757//757 -f 871//871 757//757 873//873 -f 873//873 757//757 758//758 -f 873//873 758//758 875//875 -f 875//875 758//758 759//759 -f 875//875 759//759 877//877 -f 877//877 759//759 760//760 -f 877//877 760//760 879//879 -f 879//879 760//760 761//761 -f 879//879 761//761 881//881 -f 881//881 761//761 762//762 -f 881//881 762//762 883//883 -f 883//883 762//762 763//763 -f 883//883 763//763 885//885 -f 885//885 763//763 764//764 -f 885//885 764//764 887//887 -f 887//887 764//764 765//765 -f 887//887 765//765 889//889 -f 889//889 765//765 766//766 -f 889//889 766//766 891//891 -f 891//891 766//766 767//767 -f 891//891 767//767 893//893 -f 893//893 767//767 768//768 -f 893//893 768//768 895//895 -f 895//895 768//768 769//769 -f 895//895 769//769 897//897 -f 897//897 769//769 770//770 -f 897//897 770//770 899//899 -f 899//899 770//770 771//771 -f 899//899 771//771 901//901 -f 901//901 771//771 772//772 -f 901//901 772//772 903//903 -f 903//903 772//772 773//773 -f 903//903 773//773 905//905 -f 905//905 773//773 774//774 -f 905//905 774//774 907//907 -f 907//907 774//774 775//775 -f 907//907 775//775 909//909 -f 909//909 775//775 776//776 -f 909//909 776//776 911//911 -f 911//911 776//776 777//777 -f 911//911 777//777 913//913 -f 913//913 777//777 778//778 -f 914//914 915//915 900//900 -f 916//916 917//917 892//892 -f 918//918 876//876 878//878 -f 919//919 920//920 844//844 -f 921//921 922//922 908//908 -f 892//892 894//894 916//916 -f 916//916 894//894 896//896 -f 916//916 896//896 915//915 -f 915//915 896//896 898//898 -f 915//915 898//898 900//900 -f 918//918 878//878 923//923 -f 876//876 918//918 874//874 -f 874//874 918//918 924//924 -f 874//874 924//924 872//872 -f 872//872 924//924 925//925 -f 872//872 925//925 870//870 -f 926//926 927//927 826//826 -f 928//928 822//822 927//927 -f 927//927 822//822 824//824 -f 927//927 824//824 826//826 -f 908//908 910//910 921//921 -f 921//921 910//910 912//912 -f 921//921 912//912 929//929 -f 929//929 912//912 806//806 -f 929//929 806//806 930//930 -f 900//900 902//902 914//914 -f 914//914 902//902 904//904 -f 914//914 904//904 922//922 -f 922//922 904//904 906//906 -f 922//922 906//906 908//908 -f 931//931 886//886 932//932 -f 932//932 886//886 888//888 -f 932//932 888//888 917//917 -f 917//917 888//888 890//890 -f 917//917 890//890 892//892 -f 878//878 880//880 923//923 -f 923//923 880//880 882//882 -f 923//923 882//882 931//931 -f 931//931 882//882 884//884 -f 931//931 884//884 886//886 -f 933//933 934//934 814//814 -f 935//935 936//936 836//836 -f 814//814 816//816 933//933 -f 933//933 816//816 818//818 -f 933//933 818//818 928//928 -f 928//928 818//818 820//820 -f 928//928 820//820 822//822 -f 806//806 808//808 930//930 -f 930//930 808//808 810//810 -f 930//930 810//810 934//934 -f 934//934 810//810 812//812 -f 934//934 812//812 814//814 -f 937//937 866//866 925//925 -f 925//925 866//866 868//868 -f 925//925 868//868 870//870 -f 938//938 860//860 939//939 -f 939//939 860//860 862//862 -f 939//939 862//862 937//937 -f 937//937 862//862 864//864 -f 937//937 864//864 866//866 -f 940//940 856//856 938//938 -f 938//938 856//856 858//858 -f 938//938 858//858 860//860 -f 941//941 852//852 940//940 -f 940//940 852//852 854//854 -f 940//940 854//854 856//856 -f 844//844 846//846 919//919 -f 919//919 846//846 848//848 -f 919//919 848//848 941//941 -f 941//941 848//848 850//850 -f 941//941 850//850 852//852 -f 836//836 838//838 935//935 -f 935//935 838//838 840//840 -f 935//935 840//840 920//920 -f 920//920 840//840 842//842 -f 920//920 842//842 844//844 -f 826//826 828//828 926//926 -f 926//926 828//828 830//830 -f 926//926 830//830 942//942 -f 942//942 830//830 832//832 -f 942//942 832//832 936//936 -f 936//936 832//832 834//834 -f 936//936 834//834 836//836 -f 182//182 943//943 181//181 -f 181//181 943//943 944//944 -f 181//181 944//944 179//179 -f 179//179 944//944 945//945 -f 179//179 945//945 183//183 -f 183//183 945//945 946//946 -f 183//183 946//946 184//184 -f 182//182 177//177 943//943 -f 943//943 177//177 176//176 -f 943//943 176//176 947//947 -f 947//947 176//176 172//172 -f 947//947 172//172 948//948 -f 948//948 172//172 174//174 -f 948//948 174//174 949//949 -f 949//949 174//174 175//175 -f 175//175 171//171 949//949 -f 949//949 171//171 170//170 -f 949//949 170//170 950//950 -f 950//950 170//170 168//168 -f 950//950 168//168 951//951 -f 951//951 168//168 166//166 -f 951//951 166//166 952//952 -f 952//952 166//166 165//165 -f 165//165 164//164 952//952 -f 952//952 164//164 163//163 -f 952//952 163//163 953//953 -f 953//953 163//163 161//161 -f 953//953 161//161 954//954 -f 954//954 161//161 159//159 -f 954//954 159//159 955//955 -f 159//159 158//158 955//955 -f 955//955 158//158 156//156 -f 955//955 156//156 956//956 -f 956//956 156//156 155//155 -f 155//155 153//153 956//956 -f 956//956 153//153 152//152 -f 956//956 152//152 957//957 -f 957//957 152//152 148//148 -f 957//957 148//148 958//958 -f 958//958 148//148 150//150 -f 958//958 150//150 959//959 -f 959//959 150//150 151//151 -f 151//151 146//146 959//959 -f 959//959 146//146 145//145 -f 959//959 145//145 960//960 -f 960//960 145//145 141//141 -f 960//960 141//141 961//961 -f 961//961 141//141 143//143 -f 961//961 143//143 962//962 -f 962//962 143//143 144//144 -f 144//144 139//139 962//962 -f 962//962 139//139 138//138 -f 962//962 138//138 963//963 -f 963//963 138//138 134//134 -f 963//963 134//134 964//964 -f 964//964 134//134 136//136 -f 964//964 136//136 965//965 -f 965//965 136//136 137//137 -f 137//137 133//133 965//965 -f 965//965 133//133 132//132 -f 965//965 132//132 966//966 -f 966//966 132//132 130//130 -f 966//966 130//130 967//967 -f 967//967 130//130 128//128 -f 967//967 128//128 968//968 -f 968//968 128//128 127//127 -f 127//127 124//124 968//968 -f 968//968 124//124 191//191 -f 968//968 191//191 969//969 -f 969//969 191//191 190//190 -f 969//969 190//190 970//970 -f 970//970 190//190 189//189 -f 970//970 189//189 971//971 -f 971//971 189//189 187//187 -f 971//971 187//187 946//946 -f 946//946 187//187 186//186 -f 946//946 186//186 184//184 -f 969//969 972//972 968//968 -f 968//968 972//972 973//973 -f 968//968 973//973 967//967 -f 967//967 973//973 974//974 -f 967//967 974//974 966//966 -f 966//966 974//974 975//975 -f 966//966 975//975 965//965 -f 965//965 975//975 976//976 -f 965//965 976//976 964//964 -f 964//964 976//976 977//977 -f 964//964 977//977 963//963 -f 963//963 977//977 978//978 -f 963//963 978//978 962//962 -f 962//962 978//978 979//979 -f 962//962 979//979 961//961 -f 961//961 979//979 980//980 -f 961//961 980//980 960//960 -f 960//960 980//980 981//981 -f 960//960 981//981 959//959 -f 959//959 981//981 982//982 -f 959//959 982//982 958//958 -f 958//958 982//982 983//983 -f 958//958 983//983 957//957 -f 957//957 983//983 984//984 -f 957//957 984//984 956//956 -f 956//956 984//984 985//985 -f 956//956 985//985 955//955 -f 955//955 985//985 986//986 -f 955//955 986//986 954//954 -f 954//954 986//986 987//987 -f 954//954 987//987 953//953 -f 953//953 987//987 988//988 -f 953//953 988//988 952//952 -f 952//952 988//988 989//989 -f 952//952 989//989 951//951 -f 951//951 989//989 990//990 -f 951//951 990//990 950//950 -f 950//950 990//990 991//991 -f 950//950 991//991 949//949 -f 949//949 991//991 992//992 -f 949//949 992//992 948//948 -f 948//948 992//992 993//993 -f 948//948 993//993 947//947 -f 947//947 993//993 994//994 -f 947//947 994//994 943//943 -f 943//943 994//994 995//995 -f 943//943 995//995 944//944 -f 944//944 995//995 996//996 -f 944//944 996//996 945//945 -f 945//945 996//996 997//997 -f 945//945 997//997 946//946 -f 946//946 997//997 998//998 -f 946//946 998//998 971//971 -f 971//971 998//998 999//999 -f 971//971 999//999 970//970 -f 970//970 999//999 1000//1000 -f 970//970 1000//1000 969//969 -f 969//969 1000//1000 972//972 -f 1000//1000 1001//1001 972//972 -f 972//972 1001//1001 1002//1002 -f 972//972 1002//1002 973//973 -f 973//973 1002//1002 1003//1003 -f 973//973 1003//1003 974//974 -f 974//974 1003//1003 1004//1004 -f 974//974 1004//1004 975//975 -f 975//975 1004//1004 1005//1005 -f 975//975 1005//1005 976//976 -f 976//976 1005//1005 1006//1006 -f 976//976 1006//1006 977//977 -f 977//977 1006//1006 1007//1007 -f 977//977 1007//1007 978//978 -f 978//978 1007//1007 1008//1008 -f 978//978 1008//1008 979//979 -f 979//979 1008//1008 1009//1009 -f 979//979 1009//1009 980//980 -f 980//980 1009//1009 1010//1010 -f 980//980 1010//1010 981//981 -f 981//981 1010//1010 1011//1011 -f 981//981 1011//1011 982//982 -f 982//982 1011//1011 1012//1012 -f 982//982 1012//1012 983//983 -f 983//983 1012//1012 1013//1013 -f 983//983 1013//1013 984//984 -f 984//984 1013//1013 1014//1014 -f 984//984 1014//1014 985//985 -f 985//985 1014//1014 1015//1015 -f 985//985 1015//1015 986//986 -f 986//986 1015//1015 1016//1016 -f 986//986 1016//1016 987//987 -f 987//987 1016//1016 1017//1017 -f 987//987 1017//1017 988//988 -f 988//988 1017//1017 1018//1018 -f 988//988 1018//1018 989//989 -f 989//989 1018//1018 1019//1019 -f 989//989 1019//1019 990//990 -f 990//990 1019//1019 1020//1020 -f 990//990 1020//1020 991//991 -f 991//991 1020//1020 1021//1021 -f 991//991 1021//1021 992//992 -f 992//992 1021//1021 1022//1022 -f 992//992 1022//1022 993//993 -f 993//993 1022//1022 1023//1023 -f 993//993 1023//1023 994//994 -f 994//994 1023//1023 1024//1024 -f 994//994 1024//1024 995//995 -f 995//995 1024//1024 1025//1025 -f 995//995 1025//1025 996//996 -f 996//996 1025//1025 1026//1026 -f 996//996 1026//1026 997//997 -f 997//997 1026//1026 1027//1027 -f 997//997 1027//1027 998//998 -f 998//998 1027//1027 1028//1028 -f 998//998 1028//1028 999//999 -f 999//999 1028//1028 1029//1029 -f 999//999 1029//1029 1000//1000 -f 1000//1000 1029//1029 1001//1001 -f 1029//1029 930//930 1001//1001 -f 1001//1001 930//930 934//934 -f 1001//1001 934//934 1002//1002 -f 1002//1002 934//934 933//933 -f 1002//1002 933//933 1003//1003 -f 1003//1003 933//933 928//928 -f 1003//1003 928//928 1004//1004 -f 1004//1004 928//928 927//927 -f 1004//1004 927//927 1005//1005 -f 1005//1005 927//927 926//926 -f 1005//1005 926//926 1006//1006 -f 1006//1006 926//926 942//942 -f 1006//1006 942//942 1007//1007 -f 1007//1007 942//942 936//936 -f 1007//1007 936//936 1008//1008 -f 1008//1008 936//936 935//935 -f 1008//1008 935//935 1009//1009 -f 1009//1009 935//935 920//920 -f 1009//1009 920//920 1010//1010 -f 1010//1010 920//920 919//919 -f 1010//1010 919//919 1011//1011 -f 1011//1011 919//919 941//941 -f 1011//1011 941//941 1012//1012 -f 1012//1012 941//941 940//940 -f 1012//1012 940//940 1013//1013 -f 1013//1013 940//940 938//938 -f 1013//1013 938//938 1014//1014 -f 1014//1014 938//938 939//939 -f 1014//1014 939//939 1015//1015 -f 1015//1015 939//939 937//937 -f 1015//1015 937//937 1016//1016 -f 1016//1016 937//937 925//925 -f 1016//1016 925//925 1017//1017 -f 1017//1017 925//925 924//924 -f 1017//1017 924//924 1018//1018 -f 1018//1018 924//924 918//918 -f 1018//1018 918//918 1019//1019 -f 1019//1019 918//918 923//923 -f 1019//1019 923//923 1020//1020 -f 1020//1020 923//923 931//931 -f 1020//1020 931//931 1021//1021 -f 1021//1021 931//931 932//932 -f 1021//1021 932//932 1022//1022 -f 1022//1022 932//932 917//917 -f 1022//1022 917//917 1023//1023 -f 1023//1023 917//917 916//916 -f 1023//1023 916//916 1024//1024 -f 1024//1024 916//916 915//915 -f 1024//1024 915//915 1025//1025 -f 1025//1025 915//915 914//914 -f 1025//1025 914//914 1026//1026 -f 1026//1026 914//914 922//922 -f 1026//1026 922//922 1027//1027 -f 1027//1027 922//922 921//921 -f 1027//1027 921//921 1028//1028 -f 1028//1028 921//921 929//929 -f 1028//1028 929//929 1029//1029 -f 1029//1029 929//929 930//930 -f 1030//1030 1//1 1031//1031 -f 1031//1031 1//1 49//49 -f 1031//1031 49//49 1032//1032 -f 1032//1032 49//49 40//40 -f 1032//1032 40//40 1033//1033 -f 1033//1033 40//40 42//42 -f 1033//1033 42//42 1034//1034 -f 1034//1034 42//42 44//44 -f 1034//1034 44//44 1035//1035 -f 1035//1035 44//44 24//24 -f 1035//1035 24//24 1036//1036 -f 1036//1036 24//24 26//26 -f 1036//1036 26//26 1037//1037 -f 1037//1037 26//26 28//28 -f 1037//1037 28//28 1038//1038 -f 1038//1038 28//28 19//19 -f 1038//1038 19//19 1039//1039 -f 1039//1039 19//19 21//21 -f 1039//1039 21//21 1040//1040 -f 1040//1040 21//21 23//23 -f 1040//1040 23//23 1041//1041 -f 1041//1041 23//23 32//32 -f 1041//1041 32//32 1042//1042 -f 1042//1042 32//32 34//34 -f 1042//1042 34//34 1043//1043 -f 1043//1043 34//34 36//36 -f 1043//1043 36//36 1044//1044 -f 1044//1044 36//36 14//14 -f 1044//1044 14//14 1045//1045 -f 1045//1045 14//14 16//16 -f 1045//1045 16//16 1046//1046 -f 1046//1046 16//16 4//4 -f 1046//1046 4//4 1047//1047 -f 1047//1047 4//4 6//6 -f 1047//1047 6//6 1048//1048 -f 1048//1048 6//6 8//8 -f 1048//1048 8//8 1049//1049 -f 1049//1049 8//8 9//9 -f 1049//1049 9//9 1050//1050 -f 1050//1050 9//9 11//11 -f 1050//1050 11//11 1051//1051 -f 1051//1051 11//11 2//2 -f 1051//1051 2//2 1030//1030 -f 1030//1030 2//2 1//1 -f 140//140 1036//1036 135//135 -f 135//135 1036//1036 1037//1037 -f 135//135 1037//1037 131//131 -f 131//131 1037//1037 1038//1038 -f 131//131 1038//1038 129//129 -f 129//129 1038//1038 1039//1039 -f 129//129 1039//1039 125//125 -f 125//125 1039//1039 1040//1040 -f 125//125 1040//1040 126//126 -f 126//126 1040//1040 1041//1041 -f 126//126 1041//1041 188//188 -f 188//188 1041//1041 1042//1042 -f 188//188 1042//1042 185//185 -f 185//185 1042//1042 1043//1043 -f 185//185 1043//1043 180//180 -f 180//180 1043//1043 1044//1044 -f 180//180 1044//1044 178//178 -f 178//178 1044//1044 1045//1045 -f 178//178 1045//1045 173//173 -f 1045//1045 1046//1046 173//173 -f 173//173 1046//1046 1047//1047 -f 173//173 1047//1047 169//169 -f 169//169 1047//1047 1048//1048 -f 169//169 1048//1048 167//167 -f 167//167 1048//1048 1049//1049 -f 167//167 1049//1049 162//162 -f 162//162 1049//1049 1050//1050 -f 162//162 1050//1050 160//160 -f 160//160 1050//1050 1051//1051 -f 160//160 1051//1051 157//157 -f 157//157 1051//1051 1030//1030 -f 157//157 1030//1030 154//154 -f 154//154 1030//1030 1031//1031 -f 154//154 1031//1031 149//149 -f 149//149 1031//1031 1032//1032 -f 149//149 1032//1032 147//147 -f 147//147 1032//1032 1033//1033 -f 147//147 1033//1033 142//142 -f 142//142 1033//1033 1034//1034 -f 142//142 1034//1034 140//140 -f 140//140 1034//1034 1035//1035 -f 140//140 1035//1035 1036//1036 -f 22//22 63//63 55//55 -f 55//55 63//63 61//61 -f 55//55 61//61 56//56 -f 56//56 61//61 59//59 -f 56//56 59//59 57//57 -f 57//57 59//59 122//122 -f 57//57 122//122 33//33 -f 33//33 122//122 120//120 -f 33//33 120//120 35//35 -f 35//35 120//120 52//52 -f 52//52 118//118 53//53 -f 53//53 118//118 116//116 -f 53//53 116//116 54//54 -f 54//54 116//116 104//104 -f 54//54 104//104 15//15 -f 15//15 104//104 107//107 -f 15//15 107//107 17//17 -f 17//17 107//107 109//109 -f 17//17 109//109 18//18 -f 18//18 109//109 5//5 -f 5//5 112//112 7//7 -f 7//7 112//112 114//114 -f 7//7 114//114 29//29 -f 29//29 114//114 103//103 -f 29//29 103//103 30//30 -f 30//30 103//103 101//101 -f 30//30 101//101 31//31 -f 31//31 101//101 99//99 -f 31//31 99//99 10//10 -f 10//10 99//99 12//12 -f 12//12 96//96 13//13 -f 13//13 96//96 94//94 -f 13//13 94//94 3//3 -f 3//3 94//94 91//91 -f 3//3 91//91 47//47 -f 47//47 91//91 89//89 -f 47//47 89//89 48//48 -f 48//48 89//89 87//87 -f 48//48 87//87 50//50 -f 50//50 87//87 51//51 -f 76//76 46//46 45//45 -f 46//46 76//76 25//25 -f 51//51 85//85 41//41 -f 41//41 85//85 83//83 -f 41//41 83//83 43//43 -f 43//43 83//83 80//80 -f 43//43 80//80 45//45 -f 45//45 80//80 78//78 -f 45//45 78//78 76//76 -f 25//25 73//73 27//27 -f 27//27 73//73 71//71 -f 27//27 71//71 37//37 -f 37//37 71//71 69//69 -f 37//37 69//69 38//38 -f 38//38 69//69 67//67 -f 38//38 67//67 39//39 -f 39//39 67//67 65//65 -f 39//39 65//65 20//20 -f 20//20 65//65 22//22 -f 84//84 86//86 283//283 -f 283//283 281//281 84//84 -f 84//84 281//281 280//280 -f 84//84 280//280 82//82 -f 82//82 280//280 278//278 -f 82//82 278//278 81//81 -f 278//278 276//276 81//81 -f 81//81 276//276 274//274 -f 81//81 274//274 79//79 -f 274//274 272//272 79//79 -f 79//79 272//272 270//270 -f 79//79 270//270 77//77 -f 77//77 270//270 268//268 -f 77//77 268//268 75//75 -f 286//286 86//86 88//88 -f 97//97 199//199 95//95 -f 95//95 199//199 197//197 -f 95//95 197//197 93//93 -f 93//93 197//197 195//195 -f 195//195 193//193 93//93 -f 93//93 193//193 292//292 -f 93//93 292//292 92//92 -f 92//92 292//292 291//291 -f 92//92 291//291 90//90 -f 90//90 291//291 289//289 -f 90//90 289//289 88//88 -f 88//88 289//289 287//287 -f 88//88 287//287 286//286 -f 202//202 97//97 98//98 -f 110//110 215//215 111//111 -f 111//111 215//215 213//213 -f 111//111 213//213 113//113 -f 213//213 211//211 113//113 -f 113//113 211//211 209//209 -f 113//113 209//209 102//102 -f 102//102 209//209 207//207 -f 102//102 207//207 100//100 -f 100//100 207//207 206//206 -f 100//100 206//206 98//98 -f 98//98 206//206 204//204 -f 98//98 204//204 202//202 -f 117//117 119//119 232//232 -f 232//232 230//230 117//117 -f 117//117 230//230 229//229 -f 117//117 229//229 115//115 -f 115//115 229//229 227//227 -f 115//115 227//227 105//105 -f 227//227 225//225 105//105 -f 105//105 225//225 223//223 -f 105//105 223//223 106//106 -f 223//223 221//221 106//106 -f 106//106 221//221 219//219 -f 106//106 219//219 108//108 -f 108//108 219//219 217//217 -f 108//108 217//217 110//110 -f 235//235 119//119 121//121 -f 64//64 249//249 62//62 -f 62//62 249//249 247//247 -f 62//62 247//247 60//60 -f 60//60 247//247 245//245 -f 245//245 243//243 60//60 -f 60//60 243//243 242//242 -f 60//60 242//242 58//58 -f 58//58 242//242 240//240 -f 58//58 240//240 123//123 -f 123//123 240//240 238//238 -f 123//123 238//238 121//121 -f 121//121 238//238 236//236 -f 121//121 236//236 235//235 -f 75//75 266//266 74//74 -f 74//74 266//266 72//72 -f 266//266 264//264 72//72 -f 72//72 264//264 262//262 -f 72//72 262//262 70//70 -f 262//262 261//261 70//70 -f 70//70 261//261 259//259 -f 70//70 259//259 68//68 -f 68//68 259//259 257//257 -f 257//257 255//255 68//68 -f 68//68 255//255 253//253 -f 68//68 253//253 66//66 -f 66//66 253//253 252//252 -f 66//66 252//252 64//64 -f 1052//1052 1053//1053 1054//1054 -f 1054//1054 1053//1053 1055//1055 -f 1054//1054 1055//1055 1056//1056 -f 1056//1056 1055//1055 1057//1057 -f 1056//1056 1057//1057 1058//1058 -f 1058//1058 1057//1057 1059//1059 -f 1058//1058 1059//1059 1060//1060 -f 1060//1060 1059//1059 1061//1061 -f 1060//1060 1061//1061 1062//1062 -f 1062//1062 1061//1061 1063//1063 -f 1062//1062 1063//1063 1064//1064 -f 1064//1064 1063//1063 1065//1065 -f 1064//1064 1065//1065 1066//1066 -f 1066//1066 1065//1065 1067//1067 -f 1066//1066 1067//1067 1068//1068 -f 1068//1068 1067//1067 1069//1069 -f 1068//1068 1069//1069 1070//1070 -f 1070//1070 1069//1069 1071//1071 -f 1070//1070 1071//1071 1072//1072 -f 1072//1072 1071//1071 1073//1073 -f 1072//1072 1073//1073 1074//1074 -f 1074//1074 1073//1073 1075//1075 -f 1074//1074 1075//1075 1076//1076 -f 1076//1076 1075//1075 1077//1077 -f 1076//1076 1077//1077 1078//1078 -f 1078//1078 1077//1077 1079//1079 -f 1078//1078 1079//1079 1080//1080 -f 1080//1080 1079//1079 1081//1081 -f 1080//1080 1081//1081 1082//1082 -f 1082//1082 1081//1081 1083//1083 -f 1082//1082 1083//1083 1084//1084 -f 1084//1084 1083//1083 1085//1085 -f 1084//1084 1085//1085 1086//1086 -f 1086//1086 1085//1085 1087//1087 -f 1086//1086 1087//1087 1088//1088 -f 1088//1088 1087//1087 1089//1089 -f 1088//1088 1089//1089 1090//1090 -f 1090//1090 1089//1089 1091//1091 -f 1090//1090 1091//1091 1092//1092 -f 1092//1092 1091//1091 1093//1093 -f 1092//1092 1093//1093 1094//1094 -f 1094//1094 1093//1093 1095//1095 -f 1094//1094 1095//1095 1096//1096 -f 1096//1096 1095//1095 1097//1097 -f 1096//1096 1097//1097 1098//1098 -f 1098//1098 1097//1097 1099//1099 -f 1098//1098 1099//1099 1100//1100 -f 1100//1100 1099//1099 1101//1101 -f 1100//1100 1101//1101 1102//1102 -f 1102//1102 1101//1101 1103//1103 -f 1102//1102 1103//1103 1104//1104 -f 1104//1104 1103//1103 1105//1105 -f 1104//1104 1105//1105 1106//1106 -f 1106//1106 1105//1105 1107//1107 -f 1106//1106 1107//1107 1108//1108 -f 1108//1108 1107//1107 1109//1109 -f 1108//1108 1109//1109 1110//1110 -f 1110//1110 1109//1109 1111//1111 -f 1110//1110 1111//1111 1112//1112 -f 1112//1112 1111//1111 1113//1113 -f 1112//1112 1113//1113 1114//1114 -f 1114//1114 1113//1113 1115//1115 -f 1114//1114 1115//1115 1116//1116 -f 1116//1116 1115//1115 1117//1117 -f 1116//1116 1117//1117 1118//1118 -f 1118//1118 1117//1117 1119//1119 -f 1118//1118 1119//1119 1052//1052 -f 1052//1052 1119//1119 1053//1053 -f 1071//1071 1120//1120 1073//1073 -f 1073//1073 1120//1120 1121//1121 -f 1073//1073 1121//1121 1075//1075 -f 1075//1075 1121//1121 1122//1122 -f 1075//1075 1122//1122 1077//1077 -f 1077//1077 1122//1122 1123//1123 -f 1077//1077 1123//1123 1079//1079 -f 1079//1079 1123//1123 1124//1124 -f 1079//1079 1124//1124 1081//1081 -f 1081//1081 1124//1124 1125//1125 -f 1081//1081 1125//1125 1083//1083 -f 1083//1083 1125//1125 1126//1126 -f 1083//1083 1126//1126 1085//1085 -f 1105//1105 1127//1127 1107//1107 -f 1107//1107 1127//1127 1128//1128 -f 1107//1107 1128//1128 1109//1109 -f 1109//1109 1128//1128 1129//1129 -f 1109//1109 1129//1129 1111//1111 -f 1111//1111 1129//1129 1130//1130 -f 1111//1111 1130//1130 1113//1113 -f 1113//1113 1130//1130 1131//1131 -f 1113//1113 1131//1131 1115//1115 -f 1115//1115 1131//1131 1132//1132 -f 1115//1115 1132//1132 1117//1117 -f 1117//1117 1132//1132 1133//1133 -f 1117//1117 1133//1133 1119//1119 -f 1119//1119 1133//1133 1134//1134 -f 1119//1119 1134//1134 1053//1053 -f 1053//1053 1134//1134 1135//1135 -f 1053//1053 1135//1135 1055//1055 -f 1126//1126 1136//1136 1085//1085 -f 1085//1085 1136//1136 1137//1137 -f 1085//1085 1137//1137 1087//1087 -f 1087//1087 1137//1137 1138//1138 -f 1087//1087 1138//1138 1089//1089 -f 1089//1089 1138//1138 1139//1139 -f 1089//1089 1139//1139 1091//1091 -f 1091//1091 1139//1139 1140//1140 -f 1091//1091 1140//1140 1093//1093 -f 1093//1093 1140//1140 1141//1141 -f 1093//1093 1141//1141 1095//1095 -f 1135//1135 1142//1142 1055//1055 -f 1055//1055 1142//1142 1143//1143 -f 1055//1055 1143//1143 1057//1057 -f 1057//1057 1143//1143 1144//1144 -f 1057//1057 1144//1144 1059//1059 -f 1059//1059 1144//1144 1145//1145 -f 1059//1059 1145//1145 1061//1061 -f 1061//1061 1145//1145 1146//1146 -f 1061//1061 1146//1146 1063//1063 -f 1063//1063 1146//1146 1147//1147 -f 1063//1063 1147//1147 1065//1065 -f 1065//1065 1147//1147 1148//1148 -f 1065//1065 1148//1148 1067//1067 -f 1141//1141 1149//1149 1095//1095 -f 1095//1095 1149//1149 1150//1150 -f 1095//1095 1150//1150 1097//1097 -f 1097//1097 1150//1150 1151//1151 -f 1097//1097 1151//1151 1099//1099 -f 1099//1099 1151//1151 1152//1152 -f 1099//1099 1152//1152 1101//1101 -f 1101//1101 1152//1152 1153//1153 -f 1101//1101 1153//1153 1103//1103 -f 1103//1103 1153//1153 1154//1154 -f 1103//1103 1154//1154 1105//1105 -f 1105//1105 1154//1154 1155//1155 -f 1105//1105 1155//1155 1127//1127 -f 1148//1148 1156//1156 1067//1067 -f 1067//1067 1156//1156 1157//1157 -f 1067//1067 1157//1157 1069//1069 -f 1069//1069 1157//1157 1158//1158 -f 1069//1069 1158//1158 1071//1071 -f 1071//1071 1158//1158 1159//1159 -f 1071//1071 1159//1159 1120//1120 -f 1086//1086 1160//1160 1084//1084 -f 1084//1084 1160//1160 1161//1161 -f 1084//1084 1161//1161 1082//1082 -f 1082//1082 1161//1161 1162//1162 -f 1082//1082 1162//1162 1080//1080 -f 1080//1080 1162//1162 1163//1163 -f 1080//1080 1163//1163 1078//1078 -f 1078//1078 1163//1163 1164//1164 -f 1078//1078 1164//1164 1076//1076 -f 1076//1076 1164//1164 1165//1165 -f 1076//1076 1165//1165 1074//1074 -f 1074//1074 1165//1165 1166//1166 -f 1074//1074 1166//1166 1072//1072 -f 1166//1166 1167//1167 1072//1072 -f 1072//1072 1167//1167 1168//1168 -f 1072//1072 1168//1168 1070//1070 -f 1070//1070 1168//1168 1169//1169 -f 1070//1070 1169//1169 1068//1068 -f 1056//1056 1170//1170 1054//1054 -f 1054//1054 1170//1170 1171//1171 -f 1054//1054 1171//1171 1052//1052 -f 1052//1052 1171//1171 1172//1172 -f 1052//1052 1172//1172 1118//1118 -f 1118//1118 1172//1172 1173//1173 -f 1118//1118 1173//1173 1116//1116 -f 1116//1116 1173//1173 1174//1174 -f 1116//1116 1174//1174 1114//1114 -f 1114//1114 1174//1174 1175//1175 -f 1114//1114 1175//1175 1112//1112 -f 1112//1112 1175//1175 1176//1176 -f 1112//1112 1176//1176 1110//1110 -f 1110//1110 1176//1176 1177//1177 -f 1110//1110 1177//1177 1108//1108 -f 1108//1108 1177//1177 1178//1178 -f 1108//1108 1178//1178 1106//1106 -f 1169//1169 1179//1179 1068//1068 -f 1068//1068 1179//1179 1180//1180 -f 1068//1068 1180//1180 1066//1066 -f 1066//1066 1180//1180 1181//1181 -f 1066//1066 1181//1181 1064//1064 -f 1064//1064 1181//1181 1182//1182 -f 1064//1064 1182//1182 1062//1062 -f 1062//1062 1182//1182 1183//1183 -f 1062//1062 1183//1183 1060//1060 -f 1060//1060 1183//1183 1184//1184 -f 1060//1060 1184//1184 1058//1058 -f 1058//1058 1184//1184 1185//1185 -f 1058//1058 1185//1185 1056//1056 -f 1056//1056 1185//1185 1186//1186 -f 1056//1056 1186//1186 1170//1170 -f 1096//1096 1187//1187 1094//1094 -f 1094//1094 1187//1187 1188//1188 -f 1094//1094 1188//1188 1092//1092 -f 1092//1092 1188//1188 1189//1189 -f 1092//1092 1189//1189 1090//1090 -f 1090//1090 1189//1189 1190//1190 -f 1090//1090 1190//1190 1088//1088 -f 1088//1088 1190//1190 1191//1191 -f 1088//1088 1191//1191 1086//1086 -f 1086//1086 1191//1191 1192//1192 -f 1086//1086 1192//1192 1160//1160 -f 1178//1178 1193//1193 1106//1106 -f 1106//1106 1193//1193 1194//1194 -f 1106//1106 1194//1194 1104//1104 -f 1104//1104 1194//1194 1195//1195 -f 1104//1104 1195//1195 1102//1102 -f 1102//1102 1195//1195 1196//1196 -f 1102//1102 1196//1196 1100//1100 -f 1100//1100 1196//1196 1197//1197 -f 1100//1100 1197//1197 1098//1098 -f 1098//1098 1197//1197 1198//1198 -f 1098//1098 1198//1198 1096//1096 -f 1096//1096 1198//1198 1199//1199 -f 1096//1096 1199//1199 1187//1187 -f 1157//1157 1169//1169 1158//1158 -f 1158//1158 1169//1169 1168//1168 -f 1158//1158 1168//1168 1159//1159 -f 1159//1159 1168//1168 1167//1167 -f 1159//1159 1167//1167 1120//1120 -f 1120//1120 1167//1167 1166//1166 -f 1120//1120 1166//1166 1121//1121 -f 1121//1121 1166//1166 1165//1165 -f 1121//1121 1165//1165 1122//1122 -f 1122//1122 1165//1165 1164//1164 -f 1122//1122 1164//1164 1123//1123 -f 1123//1123 1164//1164 1163//1163 -f 1123//1123 1163//1163 1124//1124 -f 1124//1124 1163//1163 1162//1162 -f 1124//1124 1162//1162 1125//1125 -f 1125//1125 1162//1162 1161//1161 -f 1125//1125 1161//1161 1126//1126 -f 1126//1126 1161//1161 1160//1160 -f 1126//1126 1160//1160 1136//1136 -f 1136//1136 1160//1160 1192//1192 -f 1136//1136 1192//1192 1137//1137 -f 1137//1137 1192//1192 1191//1191 -f 1137//1137 1191//1191 1138//1138 -f 1138//1138 1191//1191 1190//1190 -f 1138//1138 1190//1190 1139//1139 -f 1139//1139 1190//1190 1189//1189 -f 1139//1139 1189//1189 1140//1140 -f 1140//1140 1189//1189 1188//1188 -f 1140//1140 1188//1188 1141//1141 -f 1141//1141 1188//1188 1187//1187 -f 1141//1141 1187//1187 1149//1149 -f 1149//1149 1187//1187 1199//1199 -f 1149//1149 1199//1199 1150//1150 -f 1150//1150 1199//1199 1198//1198 -f 1150//1150 1198//1198 1151//1151 -f 1151//1151 1198//1198 1197//1197 -f 1151//1151 1197//1197 1152//1152 -f 1152//1152 1197//1197 1196//1196 -f 1152//1152 1196//1196 1153//1153 -f 1153//1153 1196//1196 1195//1195 -f 1153//1153 1195//1195 1154//1154 -f 1154//1154 1195//1195 1194//1194 -f 1154//1154 1194//1194 1155//1155 -f 1155//1155 1194//1194 1193//1193 -f 1155//1155 1193//1193 1127//1127 -f 1127//1127 1193//1193 1178//1178 -f 1127//1127 1178//1178 1128//1128 -f 1128//1128 1178//1178 1177//1177 -f 1128//1128 1177//1177 1129//1129 -f 1129//1129 1177//1177 1176//1176 -f 1129//1129 1176//1176 1130//1130 -f 1130//1130 1176//1176 1175//1175 -f 1130//1130 1175//1175 1131//1131 -f 1131//1131 1175//1175 1174//1174 -f 1131//1131 1174//1174 1132//1132 -f 1132//1132 1174//1174 1173//1173 -f 1132//1132 1173//1173 1133//1133 -f 1133//1133 1173//1173 1172//1172 -f 1133//1133 1172//1172 1134//1134 -f 1134//1134 1172//1172 1171//1171 -f 1134//1134 1171//1171 1135//1135 -f 1135//1135 1171//1171 1170//1170 -f 1135//1135 1170//1170 1142//1142 -f 1142//1142 1170//1170 1186//1186 -f 1142//1142 1186//1186 1143//1143 -f 1143//1143 1186//1186 1185//1185 -f 1143//1143 1185//1185 1144//1144 -f 1144//1144 1185//1185 1184//1184 -f 1144//1144 1184//1184 1145//1145 -f 1145//1145 1184//1184 1183//1183 -f 1145//1145 1183//1183 1146//1146 -f 1146//1146 1183//1183 1182//1182 -f 1146//1146 1182//1182 1147//1147 -f 1147//1147 1182//1182 1181//1181 -f 1147//1147 1181//1181 1148//1148 -f 1148//1148 1181//1181 1180//1180 -f 1148//1148 1180//1180 1156//1156 -f 1156//1156 1180//1180 1179//1179 -f 1156//1156 1179//1179 1157//1157 -f 1157//1157 1179//1179 1169//1169 -f 1200//1200 1201//1201 1183//1183 -f 1183//1183 1201//1201 1202//1202 -f 1183//1183 1202//1202 1203//1203 -f 1204//1204 1205//1205 1206//1206 -f 1203//1203 1207//1207 1183//1183 -f 1183//1183 1207//1207 1206//1206 -f 1183//1183 1206//1206 1208//1208 -f 1208//1208 1206//1206 1209//1209 -f 1183//1183 1210//1210 1211//1211 -f 1212//1212 1183//1183 1213//1213 -f 1213//1213 1183//1183 1214//1214 -f 1212//1212 1215//1215 1183//1183 -f 1183//1183 1215//1215 1216//1216 -f 1183//1183 1216//1216 1217//1217 -f 1217//1217 1218//1218 1183//1183 -f 1183//1183 1218//1218 1219//1219 -f 1183//1183 1219//1219 1220//1220 -f 1211//1211 1221//1221 1183//1183 -f 1183//1183 1221//1221 1222//1222 -f 1183//1183 1222//1222 1223//1223 -f 1223//1223 1224//1224 1183//1183 -f 1183//1183 1224//1224 1225//1225 -f 1183//1183 1225//1225 1226//1226 -f 1205//1205 1227//1227 1206//1206 -f 1206//1206 1227//1227 1228//1228 -f 1206//1206 1228//1228 1209//1209 -f 1220//1220 1229//1229 1183//1183 -f 1183//1183 1229//1229 1230//1230 -f 1183//1183 1230//1230 1231//1231 -f 1231//1231 1232//1232 1183//1183 -f 1183//1183 1232//1232 1233//1233 -f 1183//1183 1233//1233 1234//1234 -f 1234//1234 1235//1235 1183//1183 -f 1183//1183 1235//1235 1236//1236 -f 1183//1183 1236//1236 1210//1210 -f 1226//1226 1237//1237 1183//1183 -f 1183//1183 1237//1237 1238//1238 -f 1183//1183 1238//1238 1200//1200 -f 1206//1206 1239//1239 1204//1204 -f 1204//1204 1239//1239 1240//1240 -f 1204//1204 1240//1240 1241//1241 -f 1241//1241 1240//1240 1242//1242 -f 1214//1214 1243//1243 1213//1213 -f 1213//1213 1243//1243 1244//1244 -f 1213//1213 1244//1244 1245//1245 -f 1245//1245 1244//1244 1246//1246 -f 1245//1245 1246//1246 1247//1247 -f 1247//1247 1246//1246 1248//1248 -f 1247//1247 1248//1248 1169//1169 -f 1249//1249 1250//1250 1251//1251 -f 1252//1252 1253//1253 1254//1254 -f 1255//1255 1256//1256 1257//1257 -f 1258//1258 1259//1259 1260//1260 -f 1260//1260 1259//1259 1261//1261 -f 1262//1262 1263//1263 1264//1264 -f 1265//1265 1266//1266 1267//1267 -f 1268//1268 1269//1269 1270//1270 -f 1271//1271 1272//1272 1273//1273 -f 1274//1274 1275//1275 1276//1276 -f 1277//1277 1278//1278 1279//1279 -f 1280//1280 1281//1281 1282//1282 -f 1283//1283 1284//1284 1285//1285 -f 1286//1286 1287//1287 1288//1288 -f 1289//1289 1290//1290 1291//1291 -f 1292//1292 1293//1293 1294//1294 -f 1295//1295 1296//1296 1297//1297 -f 1298//1298 1299//1299 1300//1300 -f 1301//1301 1302//1302 1303//1303 -f 1304//1304 1305//1305 1306//1306 -f 1307//1307 1308//1308 1309//1309 -f 1310//1310 1311//1311 1312//1312 -f 1313//1313 1314//1314 1315//1315 -f 1316//1316 1317//1317 1318//1318 -f 1319//1319 1318//1318 1320//1320 -f 1321//1321 1322//1322 1323//1323 -f 1324//1324 1325//1325 1326//1326 -f 1327//1327 1328//1328 1329//1329 -f 1330//1330 1328//1328 1331//1331 -f 1332//1332 1333//1333 1334//1334 -f 1335//1335 1336//1336 1337//1337 -f 1338//1338 1339//1339 1340//1340 -f 1341//1341 1342//1342 1343//1343 -f 1344//1344 1345//1345 1346//1346 -f 1347//1347 1348//1348 1349//1349 -f 1350//1350 1351//1351 1352//1352 -f 1353//1353 1354//1354 1355//1355 -f 1356//1356 1357//1357 1358//1358 -f 1359//1359 1360//1360 1361//1361 -f 1362//1362 1363//1363 1364//1364 -f 1365//1365 1366//1366 1367//1367 -f 1368//1368 1369//1369 1370//1370 -f 1371//1371 1372//1372 1373//1373 -f 1369//1369 1368//1368 1374//1374 -f 1375//1375 1376//1376 1377//1377 -f 1378//1378 1377//1377 1379//1379 -f 1380//1380 1381//1381 1382//1382 -f 1381//1381 1380//1380 1383//1383 -f 1384//1384 1385//1385 1386//1386 -f 1387//1387 1388//1388 1389//1389 -f 1389//1389 1388//1388 1390//1390 -f 1391//1391 1392//1392 1393//1393 -f 1394//1394 1395//1395 1396//1396 -f 1397//1397 1398//1398 1399//1399 -f 1400//1400 1401//1401 1402//1402 -f 1403//1403 1404//1404 1405//1405 -f 1244//1244 1243//1243 1406//1406 -f 1407//1407 1408//1408 1409//1409 -f 1202//1202 1201//1201 1410//1410 -f 1411//1411 1412//1412 1413//1413 -f 1414//1414 1415//1415 1416//1416 -f 1221//1221 1211//1211 1417//1417 -f 1418//1418 1419//1419 1420//1420 -f 1421//1421 1422//1422 1423//1423 -f 1424//1424 1425//1425 1426//1426 -f 1424//1424 1426//1426 1427//1427 -f 1427//1427 1426//1426 1428//1428 -f 1427//1427 1428//1428 1429//1429 -f 1429//1429 1428//1428 1430//1430 -f 1429//1429 1430//1430 1431//1431 -f 1432//1432 1433//1433 1434//1434 -f 1435//1435 1436//1436 1437//1437 -f 1435//1435 1437//1437 1433//1433 -f 1422//1422 1438//1438 1423//1423 -f 1423//1423 1438//1438 1439//1439 -f 1440//1440 1441//1441 1442//1442 -f 1443//1443 1444//1444 1445//1445 -f 1445//1445 1444//1444 1446//1446 -f 1447//1447 1448//1448 1443//1443 -f 1443//1443 1448//1448 1449//1449 -f 1443//1443 1449//1449 1444//1444 -f 1443//1443 1450//1450 1447//1447 -f 1447//1447 1450//1450 1420//1420 -f 1447//1447 1420//1420 1451//1451 -f 1451//1451 1420//1420 1419//1419 -f 1452//1452 1453//1453 1454//1454 -f 1454//1454 1453//1453 1455//1455 -f 1454//1454 1455//1455 1456//1456 -f 1456//1456 1455//1455 1457//1457 -f 1456//1456 1457//1457 1458//1458 -f 1458//1458 1457//1457 1459//1459 -f 1458//1458 1459//1459 1460//1460 -f 1460//1460 1459//1459 1461//1461 -f 1460//1460 1461//1461 1462//1462 -f 1462//1462 1461//1461 1463//1463 -f 1462//1462 1463//1463 1464//1464 -f 1464//1464 1463//1463 1465//1465 -f 1464//1464 1465//1465 1466//1466 -f 1466//1466 1465//1465 1467//1467 -f 1466//1466 1467//1467 1468//1468 -f 1468//1468 1467//1467 1469//1469 -f 1468//1468 1469//1469 1470//1470 -f 1470//1470 1469//1469 1471//1471 -f 1470//1470 1471//1471 1472//1472 -f 1472//1472 1471//1471 1473//1473 -f 1472//1472 1473//1473 1474//1474 -f 1474//1474 1473//1473 1475//1475 -f 1476//1476 1477//1477 1478//1478 -f 1478//1478 1477//1477 1479//1479 -f 1478//1478 1479//1479 1452//1452 -f 1452//1452 1479//1479 1480//1480 -f 1452//1452 1480//1480 1453//1453 -f 1476//1476 1481//1481 1482//1482 -f 1482//1482 1483//1483 1476//1476 -f 1476//1476 1483//1483 1484//1484 -f 1476//1476 1484//1484 1477//1477 -f 1485//1485 1486//1486 1487//1487 -f 1487//1487 1486//1486 1488//1488 -f 1488//1488 1486//1486 1489//1489 -f 1488//1488 1489//1489 1490//1490 -f 1491//1491 1492//1492 1493//1493 -f 1493//1493 1492//1492 1494//1494 -f 1495//1495 1496//1496 1494//1494 -f 1496//1496 1497//1497 1494//1494 -f 1494//1494 1497//1497 1498//1498 -f 1494//1494 1498//1498 1493//1493 -f 1499//1499 1500//1500 1501//1501 -f 1502//1502 1503//1503 1504//1504 -f 1504//1504 1503//1503 1505//1505 -f 1504//1504 1505//1505 1506//1506 -f 1217//1217 1507//1507 1218//1218 -f 1218//1218 1507//1507 1508//1508 -f 1218//1218 1508//1508 1219//1219 -f 1219//1219 1508//1508 1509//1509 -f 1219//1219 1509//1509 1220//1220 -f 1220//1220 1509//1509 1510//1510 -f 1220//1220 1510//1510 1229//1229 -f 1511//1511 1216//1216 1215//1215 -f 1511//1511 1215//1215 1512//1512 -f 1513//1513 1237//1237 1514//1514 -f 1514//1514 1237//1237 1226//1226 -f 1514//1514 1226//1226 1515//1515 -f 1515//1515 1226//1226 1225//1225 -f 1515//1515 1225//1225 1516//1516 -f 1224//1224 1223//1223 1517//1517 -f 1229//1229 1510//1510 1230//1230 -f 1230//1230 1510//1510 1518//1518 -f 1230//1230 1518//1518 1231//1231 -f 1231//1231 1518//1518 1250//1250 -f 1231//1231 1250//1250 1232//1232 -f 1232//1232 1250//1250 1249//1249 -f 1232//1232 1249//1249 1233//1233 -f 1519//1519 1520//1520 1412//1412 -f 1412//1412 1520//1520 1521//1521 -f 1412//1412 1521//1521 1413//1413 -f 1522//1522 1523//1523 1411//1411 -f 1411//1411 1523//1523 1524//1524 -f 1411//1411 1524//1524 1412//1412 -f 1412//1412 1524//1524 1525//1525 -f 1412//1412 1525//1525 1519//1519 -f 1519//1519 1525//1525 1526//1526 -f 1238//1238 1527//1527 1528//1528 -f 1528//1528 1527//1527 1529//1529 -f 1528//1528 1529//1529 1414//1414 -f 1414//1414 1416//1416 1528//1528 -f 1528//1528 1416//1416 1200//1200 -f 1528//1528 1200//1200 1238//1238 -f 1242//1242 1240//1240 1530//1530 -f 1522//1522 1530//1530 1523//1523 -f 1523//1523 1530//1530 1240//1240 -f 1523//1523 1240//1240 1524//1524 -f 1524//1524 1240//1240 1239//1239 -f 1524//1524 1239//1239 1525//1525 -f 1525//1525 1239//1239 1206//1206 -f 1525//1525 1206//1206 1526//1526 -f 1526//1526 1206//1206 1207//1207 -f 1526//1526 1207//1207 1203//1203 -f 1531//1531 1532//1532 1533//1533 -f 1533//1533 1532//1532 1534//1534 -f 1533//1533 1534//1534 1535//1535 -f 1535//1535 1534//1534 1536//1536 -f 1535//1535 1536//1536 1537//1537 -f 1537//1537 1536//1536 1538//1538 -f 1537//1537 1538//1538 1539//1539 -f 1539//1539 1538//1538 1540//1540 -f 1539//1539 1540//1540 1541//1541 -f 1541//1541 1540//1540 1542//1542 -f 1541//1541 1542//1542 1543//1543 -f 1543//1543 1542//1542 1544//1544 -f 1543//1543 1544//1544 1545//1545 -f 1545//1545 1544//1544 1546//1546 -f 1545//1545 1546//1546 1547//1547 -f 1532//1532 1548//1548 1534//1534 -f 1534//1534 1548//1548 1549//1549 -f 1534//1534 1549//1549 1536//1536 -f 1536//1536 1549//1549 1550//1550 -f 1536//1536 1550//1550 1538//1538 -f 1538//1538 1550//1550 1551//1551 -f 1538//1538 1551//1551 1540//1540 -f 1540//1540 1551//1551 1552//1552 -f 1540//1540 1552//1552 1542//1542 -f 1542//1542 1552//1552 1553//1553 -f 1542//1542 1553//1553 1544//1544 -f 1544//1544 1553//1553 1554//1554 -f 1544//1544 1554//1554 1546//1546 -f 1555//1555 1407//1407 1556//1556 -f 1556//1556 1407//1407 1409//1409 -f 1556//1556 1409//1409 1557//1557 -f 1548//1548 1558//1558 1549//1549 -f 1549//1549 1558//1558 1559//1559 -f 1549//1549 1559//1559 1550//1550 -f 1550//1550 1559//1559 1560//1560 -f 1550//1550 1560//1560 1551//1551 -f 1551//1551 1560//1560 1561//1561 -f 1551//1551 1561//1561 1552//1552 -f 1552//1552 1561//1561 1562//1562 -f 1552//1552 1562//1562 1553//1553 -f 1553//1553 1562//1562 1563//1563 -f 1553//1553 1563//1563 1554//1554 -f 1564//1564 1565//1565 1406//1406 -f 1566//1566 1555//1555 1567//1567 -f 1567//1567 1555//1555 1556//1556 -f 1567//1567 1556//1556 1568//1568 -f 1568//1568 1556//1556 1557//1557 -f 1568//1568 1557//1557 1569//1569 -f 1243//1243 1214//1214 1406//1406 -f 1406//1406 1214//1214 1569//1569 -f 1406//1406 1569//1569 1564//1564 -f 1564//1564 1569//1569 1557//1557 -f 1227//1227 1566//1566 1228//1228 -f 1228//1228 1566//1566 1567//1567 -f 1228//1228 1567//1567 1209//1209 -f 1209//1209 1567//1567 1568//1568 -f 1209//1209 1568//1568 1208//1208 -f 1208//1208 1568//1568 1569//1569 -f 1208//1208 1569//1569 1183//1183 -f 1183//1183 1569//1569 1214//1214 -f 1570//1570 1571//1571 1572//1572 -f 1572//1572 1571//1571 1573//1573 -f 1572//1572 1573//1573 1574//1574 -f 1574//1574 1573//1573 1575//1575 -f 1574//1574 1575//1575 1576//1576 -f 1413//1413 1547//1547 1411//1411 -f 1411//1411 1547//1547 1546//1546 -f 1411//1411 1546//1546 1522//1522 -f 1522//1522 1546//1546 1554//1554 -f 1522//1522 1554//1554 1530//1530 -f 1530//1530 1554//1554 1563//1563 -f 1530//1530 1563//1563 1242//1242 -f 1242//1242 1563//1563 1562//1562 -f 1242//1242 1562//1562 1241//1241 -f 1241//1241 1562//1562 1561//1561 -f 1241//1241 1561//1561 1204//1204 -f 1204//1204 1561//1561 1560//1560 -f 1204//1204 1560//1560 1205//1205 -f 1205//1205 1560//1560 1559//1559 -f 1205//1205 1559//1559 1227//1227 -f 1227//1227 1559//1559 1558//1558 -f 1227//1227 1558//1558 1566//1566 -f 1566//1566 1558//1558 1548//1548 -f 1566//1566 1548//1548 1555//1555 -f 1555//1555 1548//1548 1532//1532 -f 1555//1555 1532//1532 1407//1407 -f 1407//1407 1532//1532 1531//1531 -f 1407//1407 1531//1531 1408//1408 -f 1403//1403 1405//1405 1401//1401 -f 1577//1577 1578//1578 1579//1579 -f 1579//1579 1578//1578 1580//1580 -f 1579//1579 1580//1580 1485//1485 -f 1485//1485 1580//1580 1581//1581 -f 1485//1485 1581//1581 1486//1486 -f 1486//1486 1581//1581 1582//1582 -f 1486//1486 1582//1582 1489//1489 -f 1489//1489 1582//1582 1583//1583 -f 1489//1489 1583//1583 1490//1490 -f 1490//1490 1583//1583 1584//1584 -f 1401//1401 1405//1405 1402//1402 -f 1402//1402 1405//1405 1585//1585 -f 1402//1402 1585//1585 1586//1586 -f 1586//1586 1585//1585 1587//1587 -f 1586//1586 1587//1587 1588//1588 -f 1588//1588 1587//1587 1589//1589 -f 1588//1588 1589//1589 1590//1590 -f 1487//1487 1591//1591 1485//1485 -f 1485//1485 1591//1591 1481//1481 -f 1485//1485 1481//1481 1579//1579 -f 1579//1579 1481//1481 1476//1476 -f 1579//1579 1476//1476 1577//1577 -f 1577//1577 1476//1476 1478//1478 -f 1592//1592 1593//1593 1594//1594 -f 1594//1594 1593//1593 1595//1595 -f 1594//1594 1595//1595 1596//1596 -f 1596//1596 1595//1595 1597//1597 -f 1598//1598 1599//1599 1600//1600 -f 1600//1600 1599//1599 1601//1601 -f 1600//1600 1601//1601 1602//1602 -f 1603//1603 1604//1604 1599//1599 -f 1599//1599 1604//1604 1399//1399 -f 1599//1599 1399//1399 1601//1601 -f 1601//1601 1399//1399 1398//1398 -f 1601//1601 1398//1398 1602//1602 -f 1605//1605 1606//1606 1607//1607 -f 1607//1607 1606//1606 1415//1415 -f 1607//1607 1415//1415 1608//1608 -f 1608//1608 1415//1415 1414//1414 -f 1608//1608 1414//1414 1609//1609 -f 1609//1609 1414//1414 1529//1529 -f 1610//1610 1611//1611 1603//1603 -f 1605//1605 1612//1612 1606//1606 -f 1606//1606 1612//1612 1613//1613 -f 1606//1606 1613//1613 1415//1415 -f 1415//1415 1613//1613 1410//1410 -f 1415//1415 1410//1410 1416//1416 -f 1416//1416 1410//1410 1201//1201 -f 1416//1416 1201//1201 1200//1200 -f 1614//1614 1577//1577 1615//1615 -f 1615//1615 1577//1577 1478//1478 -f 1615//1615 1478//1478 1616//1616 -f 1616//1616 1478//1478 1452//1452 -f 1616//1616 1452//1452 1617//1617 -f 1617//1617 1452//1452 1454//1454 -f 1617//1617 1454//1454 1618//1618 -f 1618//1618 1454//1454 1456//1456 -f 1618//1618 1456//1456 1619//1619 -f 1619//1619 1456//1456 1458//1458 -f 1619//1619 1458//1458 1620//1620 -f 1620//1620 1458//1458 1460//1460 -f 1620//1620 1460//1460 1621//1621 -f 1621//1621 1460//1460 1462//1462 -f 1621//1621 1462//1462 1622//1622 -f 1622//1622 1462//1462 1464//1464 -f 1622//1622 1464//1464 1623//1623 -f 1623//1623 1464//1464 1466//1466 -f 1623//1623 1466//1466 1624//1624 -f 1624//1624 1466//1466 1468//1468 -f 1624//1624 1468//1468 1625//1625 -f 1625//1625 1468//1468 1470//1470 -f 1625//1625 1470//1470 1626//1626 -f 1626//1626 1470//1470 1472//1472 -f 1626//1626 1472//1472 1627//1627 -f 1627//1627 1472//1472 1474//1474 -f 1627//1627 1474//1474 1420//1420 -f 1420//1420 1474//1474 1475//1475 -f 1420//1420 1475//1475 1418//1418 -f 1627//1627 1628//1628 1626//1626 -f 1626//1626 1628//1628 1629//1629 -f 1626//1626 1629//1629 1625//1625 -f 1625//1625 1629//1629 1630//1630 -f 1625//1625 1630//1630 1624//1624 -f 1624//1624 1630//1630 1631//1631 -f 1624//1624 1631//1631 1623//1623 -f 1623//1623 1631//1631 1632//1632 -f 1623//1623 1632//1632 1622//1622 -f 1622//1622 1632//1632 1633//1633 -f 1622//1622 1633//1633 1621//1621 -f 1621//1621 1633//1633 1634//1634 -f 1621//1621 1634//1634 1620//1620 -f 1620//1620 1634//1634 1635//1635 -f 1620//1620 1635//1635 1619//1619 -f 1619//1619 1635//1635 1636//1636 -f 1619//1619 1636//1636 1618//1618 -f 1618//1618 1636//1636 1637//1637 -f 1618//1618 1637//1637 1617//1617 -f 1617//1617 1637//1637 1638//1638 -f 1617//1617 1638//1638 1616//1616 -f 1616//1616 1638//1638 1639//1639 -f 1616//1616 1639//1639 1615//1615 -f 1615//1615 1639//1639 1640//1640 -f 1615//1615 1640//1640 1614//1614 -f 1628//1628 1641//1641 1629//1629 -f 1629//1629 1641//1641 1642//1642 -f 1629//1629 1642//1642 1630//1630 -f 1630//1630 1642//1642 1643//1643 -f 1630//1630 1643//1643 1631//1631 -f 1631//1631 1643//1643 1644//1644 -f 1631//1631 1644//1644 1632//1632 -f 1632//1632 1644//1644 1645//1645 -f 1632//1632 1645//1645 1633//1633 -f 1633//1633 1645//1645 1646//1646 -f 1633//1633 1646//1646 1634//1634 -f 1634//1634 1646//1646 1647//1647 -f 1634//1634 1647//1647 1635//1635 -f 1635//1635 1647//1647 1648//1648 -f 1635//1635 1648//1648 1636//1636 -f 1636//1636 1648//1648 1649//1649 -f 1636//1636 1649//1649 1637//1637 -f 1637//1637 1649//1649 1650//1650 -f 1637//1637 1650//1650 1638//1638 -f 1638//1638 1650//1650 1651//1651 -f 1638//1638 1651//1651 1639//1639 -f 1639//1639 1651//1651 1652//1652 -f 1639//1639 1652//1652 1640//1640 -f 1640//1640 1652//1652 1653//1653 -f 1640//1640 1653//1653 1614//1614 -f 1614//1614 1653//1653 1654//1654 -f 1614//1614 1654//1654 1577//1577 -f 1577//1577 1654//1654 1655//1655 -f 1577//1577 1655//1655 1578//1578 -f 1656//1656 1657//1657 1658//1658 -f 1641//1641 1659//1659 1642//1642 -f 1642//1642 1659//1659 1660//1660 -f 1642//1642 1660//1660 1643//1643 -f 1643//1643 1660//1660 1661//1661 -f 1643//1643 1661//1661 1644//1644 -f 1644//1644 1661//1661 1662//1662 -f 1644//1644 1662//1662 1645//1645 -f 1645//1645 1662//1662 1663//1663 -f 1645//1645 1663//1663 1646//1646 -f 1646//1646 1663//1663 1664//1664 -f 1646//1646 1664//1664 1647//1647 -f 1647//1647 1664//1664 1665//1665 -f 1647//1647 1665//1665 1648//1648 -f 1648//1648 1665//1665 1666//1666 -f 1648//1648 1666//1666 1649//1649 -f 1649//1649 1666//1666 1667//1667 -f 1649//1649 1667//1667 1650//1650 -f 1650//1650 1667//1667 1668//1668 -f 1650//1650 1668//1668 1651//1651 -f 1651//1651 1668//1668 1669//1669 -f 1651//1651 1669//1669 1652//1652 -f 1652//1652 1669//1669 1670//1670 -f 1652//1652 1670//1670 1653//1653 -f 1653//1653 1670//1670 1671//1671 -f 1653//1653 1671//1671 1654//1654 -f 1654//1654 1671//1671 1672//1672 -f 1654//1654 1672//1672 1655//1655 -f 1659//1659 1673//1673 1660//1660 -f 1660//1660 1673//1673 1674//1674 -f 1660//1660 1674//1674 1661//1661 -f 1661//1661 1674//1674 1675//1675 -f 1661//1661 1675//1675 1662//1662 -f 1662//1662 1675//1675 1676//1676 -f 1662//1662 1676//1676 1663//1663 -f 1663//1663 1676//1676 1677//1677 -f 1663//1663 1677//1677 1664//1664 -f 1664//1664 1677//1677 1678//1678 -f 1664//1664 1678//1678 1665//1665 -f 1665//1665 1678//1678 1679//1679 -f 1665//1665 1679//1679 1666//1666 -f 1666//1666 1679//1679 1680//1680 -f 1666//1666 1680//1680 1667//1667 -f 1667//1667 1680//1680 1681//1681 -f 1667//1667 1681//1681 1668//1668 -f 1668//1668 1681//1681 1682//1682 -f 1668//1668 1682//1682 1669//1669 -f 1669//1669 1682//1682 1683//1683 -f 1669//1669 1683//1683 1670//1670 -f 1670//1670 1683//1683 1684//1684 -f 1670//1670 1684//1684 1671//1671 -f 1671//1671 1684//1684 1685//1685 -f 1671//1671 1685//1685 1672//1672 -f 1686//1686 1687//1687 1688//1688 -f 1688//1688 1687//1687 1657//1657 -f 1689//1689 1690//1690 1691//1691 -f 1691//1691 1690//1690 1692//1692 -f 1657//1657 1656//1656 1688//1688 -f 1688//1688 1656//1656 1693//1693 -f 1688//1688 1693//1693 1686//1686 -f 1658//1658 1689//1689 1656//1656 -f 1656//1656 1689//1689 1691//1691 -f 1656//1656 1691//1691 1693//1693 -f 1693//1693 1691//1691 1692//1692 -f 1693//1693 1692//1692 1694//1694 -f 1695//1695 1696//1696 1697//1697 -f 1697//1697 1696//1696 1698//1698 -f 1697//1697 1698//1698 1699//1699 -f 1698//1698 1700//1700 1701//1701 -f 1445//1445 1694//1694 1443//1443 -f 1443//1443 1694//1694 1692//1692 -f 1443//1443 1692//1692 1450//1450 -f 1450//1450 1692//1692 1690//1690 -f 1450//1450 1690//1690 1420//1420 -f 1420//1420 1690//1690 1689//1689 -f 1420//1420 1689//1689 1627//1627 -f 1627//1627 1689//1689 1658//1658 -f 1627//1627 1658//1658 1628//1628 -f 1628//1628 1658//1658 1657//1657 -f 1628//1628 1657//1657 1641//1641 -f 1641//1641 1657//1657 1687//1687 -f 1641//1641 1687//1687 1659//1659 -f 1659//1659 1687//1687 1686//1686 -f 1659//1659 1686//1686 1673//1673 -f 1673//1673 1686//1686 1702//1702 -f 1673//1673 1702//1702 1674//1674 -f 1674//1674 1702//1702 1703//1703 -f 1674//1674 1703//1703 1675//1675 -f 1675//1675 1703//1703 1704//1704 -f 1675//1675 1704//1704 1676//1676 -f 1676//1676 1704//1704 1705//1705 -f 1676//1676 1705//1705 1677//1677 -f 1677//1677 1705//1705 1706//1706 -f 1677//1677 1706//1706 1678//1678 -f 1678//1678 1706//1706 1707//1707 -f 1678//1678 1707//1707 1679//1679 -f 1679//1679 1707//1707 1708//1708 -f 1679//1679 1708//1708 1680//1680 -f 1680//1680 1708//1708 1709//1709 -f 1680//1680 1709//1709 1681//1681 -f 1681//1681 1709//1709 1710//1710 -f 1681//1681 1710//1710 1682//1682 -f 1682//1682 1710//1710 1711//1711 -f 1682//1682 1711//1711 1683//1683 -f 1683//1683 1711//1711 1712//1712 -f 1683//1683 1712//1712 1684//1684 -f 1684//1684 1712//1712 1713//1713 -f 1684//1684 1713//1713 1685//1685 -f 1396//1396 1395//1395 1714//1714 -f 1714//1714 1395//1395 1715//1715 -f 1714//1714 1715//1715 1716//1716 -f 1716//1716 1715//1715 1717//1717 -f 1716//1716 1717//1717 1718//1718 -f 1718//1718 1717//1717 1719//1719 -f 1718//1718 1719//1719 1720//1720 -f 1720//1720 1719//1719 1721//1721 -f 1720//1720 1721//1721 1722//1722 -f 1722//1722 1721//1721 1723//1723 -f 1722//1722 1723//1723 1724//1724 -f 1724//1724 1723//1723 1725//1725 -f 1724//1724 1725//1725 1726//1726 -f 1726//1726 1725//1725 1727//1727 -f 1726//1726 1727//1727 1728//1728 -f 1728//1728 1727//1727 1729//1729 -f 1728//1728 1729//1729 1730//1730 -f 1730//1730 1729//1729 1731//1731 -f 1730//1730 1731//1731 1732//1732 -f 1732//1732 1731//1731 1610//1610 -f 1732//1732 1610//1610 1733//1733 -f 1733//1733 1610//1610 1603//1603 -f 1733//1733 1603//1603 1734//1734 -f 1734//1734 1603//1603 1599//1599 -f 1734//1734 1599//1599 1735//1735 -f 1735//1735 1599//1599 1598//1598 -f 1735//1735 1598//1598 1736//1736 -f 1611//1611 1610//1610 1737//1737 -f 1737//1737 1610//1610 1731//1731 -f 1737//1737 1731//1731 1738//1738 -f 1738//1738 1731//1731 1729//1729 -f 1738//1738 1729//1729 1739//1739 -f 1739//1739 1729//1729 1727//1727 -f 1739//1739 1727//1727 1740//1740 -f 1740//1740 1727//1727 1725//1725 -f 1740//1740 1725//1725 1741//1741 -f 1741//1741 1725//1725 1723//1723 -f 1741//1741 1723//1723 1742//1742 -f 1742//1742 1723//1723 1721//1721 -f 1742//1742 1721//1721 1743//1743 -f 1743//1743 1721//1721 1719//1719 -f 1743//1743 1719//1719 1744//1744 -f 1744//1744 1719//1719 1717//1717 -f 1744//1744 1717//1717 1745//1745 -f 1745//1745 1717//1717 1715//1715 -f 1745//1745 1715//1715 1746//1746 -f 1746//1746 1715//1715 1395//1395 -f 1746//1746 1395//1395 1747//1747 -f 1747//1747 1395//1395 1394//1394 -f 1747//1747 1394//1394 1748//1748 -f 1396//1396 1749//1749 1394//1394 -f 1394//1394 1749//1749 1750//1750 -f 1394//1394 1750//1750 1748//1748 -f 1748//1748 1750//1750 1751//1751 -f 1748//1748 1751//1751 1752//1752 -f 1753//1753 1754//1754 1755//1755 -f 1755//1755 1754//1754 1756//1756 -f 1755//1755 1756//1756 1757//1757 -f 1757//1757 1756//1756 1758//1758 -f 1757//1757 1758//1758 1759//1759 -f 1759//1759 1758//1758 1760//1760 -f 1759//1759 1760//1760 1761//1761 -f 1761//1761 1760//1760 1762//1762 -f 1761//1761 1762//1762 1763//1763 -f 1763//1763 1762//1762 1764//1764 -f 1763//1763 1764//1764 1765//1765 -f 1765//1765 1764//1764 1766//1766 -f 1765//1765 1766//1766 1767//1767 -f 1767//1767 1766//1766 1768//1768 -f 1767//1767 1768//1768 1769//1769 -f 1769//1769 1768//1768 1770//1770 -f 1769//1769 1770//1770 1771//1771 -f 1771//1771 1770//1770 1772//1772 -f 1771//1771 1772//1772 1773//1773 -f 1773//1773 1772//1772 1774//1774 -f 1773//1773 1774//1774 1775//1775 -f 1775//1775 1774//1774 1776//1776 -f 1775//1775 1776//1776 1777//1777 -f 1777//1777 1776//1776 1778//1778 -f 1777//1777 1778//1778 1779//1779 -f 1779//1779 1778//1778 1780//1780 -f 1779//1779 1780//1780 1781//1781 -f 1781//1781 1780//1780 1782//1782 -f 1781//1781 1782//1782 1783//1783 -f 1783//1783 1782//1782 1784//1784 -f 1754//1754 1785//1785 1756//1756 -f 1756//1756 1785//1785 1786//1786 -f 1756//1756 1786//1786 1758//1758 -f 1758//1758 1786//1786 1787//1787 -f 1758//1758 1787//1787 1760//1760 -f 1760//1760 1787//1787 1788//1788 -f 1760//1760 1788//1788 1762//1762 -f 1762//1762 1788//1788 1789//1789 -f 1762//1762 1789//1789 1764//1764 -f 1764//1764 1789//1789 1790//1790 -f 1764//1764 1790//1790 1766//1766 -f 1766//1766 1790//1790 1791//1791 -f 1766//1766 1791//1791 1768//1768 -f 1768//1768 1791//1791 1792//1792 -f 1768//1768 1792//1792 1770//1770 -f 1770//1770 1792//1792 1793//1793 -f 1770//1770 1793//1793 1772//1772 -f 1772//1772 1793//1793 1794//1794 -f 1772//1772 1794//1794 1774//1774 -f 1774//1774 1794//1794 1795//1795 -f 1774//1774 1795//1795 1776//1776 -f 1776//1776 1795//1795 1796//1796 -f 1776//1776 1796//1796 1778//1778 -f 1778//1778 1796//1796 1797//1797 -f 1778//1778 1797//1797 1780//1780 -f 1780//1780 1797//1797 1798//1798 -f 1780//1780 1798//1798 1782//1782 -f 1782//1782 1798//1798 1799//1799 -f 1782//1782 1799//1799 1784//1784 -f 1784//1784 1799//1799 1397//1397 -f 1397//1397 1399//1399 1784//1784 -f 1784//1784 1399//1399 1604//1604 -f 1784//1784 1604//1604 1783//1783 -f 1783//1783 1604//1604 1603//1603 -f 1783//1783 1603//1603 1781//1781 -f 1781//1781 1603//1603 1611//1611 -f 1781//1781 1611//1611 1779//1779 -f 1779//1779 1611//1611 1737//1737 -f 1779//1779 1737//1737 1777//1777 -f 1777//1777 1737//1737 1738//1738 -f 1777//1777 1738//1738 1775//1775 -f 1775//1775 1738//1738 1739//1739 -f 1775//1775 1739//1739 1773//1773 -f 1773//1773 1739//1739 1740//1740 -f 1773//1773 1740//1740 1771//1771 -f 1771//1771 1740//1740 1741//1741 -f 1771//1771 1741//1741 1769//1769 -f 1769//1769 1741//1741 1742//1742 -f 1769//1769 1742//1742 1767//1767 -f 1767//1767 1742//1742 1743//1743 -f 1767//1767 1743//1743 1765//1765 -f 1765//1765 1743//1743 1744//1744 -f 1765//1765 1744//1744 1763//1763 -f 1763//1763 1744//1744 1745//1745 -f 1763//1763 1745//1745 1761//1761 -f 1761//1761 1745//1745 1746//1746 -f 1761//1761 1746//1746 1759//1759 -f 1759//1759 1746//1746 1747//1747 -f 1759//1759 1747//1747 1757//1757 -f 1757//1757 1747//1747 1748//1748 -f 1757//1757 1748//1748 1755//1755 -f 1755//1755 1748//1748 1752//1752 -f 1755//1755 1752//1752 1753//1753 -f 1392//1392 1800//1800 1801//1801 -f 1753//1753 1802//1802 1754//1754 -f 1754//1754 1802//1802 1803//1803 -f 1754//1754 1803//1803 1785//1785 -f 1785//1785 1803//1803 1804//1804 -f 1785//1785 1804//1804 1786//1786 -f 1786//1786 1804//1804 1805//1805 -f 1786//1786 1805//1805 1787//1787 -f 1787//1787 1805//1805 1806//1806 -f 1787//1787 1806//1806 1788//1788 -f 1788//1788 1806//1806 1807//1807 -f 1788//1788 1807//1807 1789//1789 -f 1789//1789 1807//1807 1808//1808 -f 1789//1789 1808//1808 1790//1790 -f 1790//1790 1808//1808 1809//1809 -f 1790//1790 1809//1809 1791//1791 -f 1791//1791 1809//1809 1810//1810 -f 1791//1791 1810//1810 1792//1792 -f 1792//1792 1810//1810 1811//1811 -f 1792//1792 1811//1811 1793//1793 -f 1793//1793 1811//1811 1812//1812 -f 1793//1793 1812//1812 1794//1794 -f 1794//1794 1812//1812 1813//1813 -f 1794//1794 1813//1813 1795//1795 -f 1795//1795 1813//1813 1814//1814 -f 1795//1795 1814//1814 1796//1796 -f 1796//1796 1814//1814 1815//1815 -f 1796//1796 1815//1815 1797//1797 -f 1797//1797 1815//1815 1816//1816 -f 1797//1797 1816//1816 1798//1798 -f 1798//1798 1816//1816 1817//1817 -f 1798//1798 1817//1817 1799//1799 -f 1799//1799 1817//1817 1818//1818 -f 1799//1799 1818//1818 1397//1397 -f 1397//1397 1818//1818 1819//1819 -f 1397//1397 1819//1819 1398//1398 -f 1398//1398 1819//1819 1612//1612 -f 1398//1398 1612//1612 1602//1602 -f 1602//1602 1612//1612 1605//1605 -f 1602//1602 1605//1605 1600//1600 -f 1600//1600 1605//1605 1607//1607 -f 1600//1600 1607//1607 1598//1598 -f 1598//1598 1607//1607 1608//1608 -f 1598//1598 1608//1608 1736//1736 -f 1736//1736 1608//1608 1609//1609 -f 1391//1391 1393//1393 1820//1820 -f 1820//1820 1393//1393 1821//1821 -f 1820//1820 1821//1821 1822//1822 -f 1822//1822 1821//1821 1823//1823 -f 1822//1822 1823//1823 1824//1824 -f 1825//1825 1826//1826 1827//1827 -f 1827//1827 1826//1826 1565//1565 -f 1827//1827 1565//1565 1828//1828 -f 1828//1828 1565//1565 1564//1564 -f 1828//1828 1564//1564 1829//1829 -f 1829//1829 1564//1564 1557//1557 -f 1829//1829 1557//1557 1830//1830 -f 1830//1830 1557//1557 1409//1409 -f 1392//1392 1801//1801 1393//1393 -f 1393//1393 1801//1801 1831//1831 -f 1393//1393 1831//1831 1821//1821 -f 1821//1821 1831//1831 1832//1832 -f 1821//1821 1832//1832 1823//1823 -f 1823//1823 1832//1832 1833//1833 -f 1823//1823 1833//1833 1824//1824 -f 1698//1698 1701//1701 1699//1699 -f 1699//1699 1701//1701 1834//1834 -f 1699//1699 1834//1834 1835//1835 -f 1836//1836 1695//1695 1837//1837 -f 1837//1837 1695//1695 1697//1697 -f 1837//1837 1697//1697 1838//1838 -f 1838//1838 1697//1697 1699//1699 -f 1838//1838 1699//1699 1839//1839 -f 1839//1839 1699//1699 1835//1835 -f 1839//1839 1835//1835 1840//1840 -f 1802//1802 1825//1825 1803//1803 -f 1803//1803 1825//1825 1827//1827 -f 1803//1803 1827//1827 1804//1804 -f 1804//1804 1827//1827 1828//1828 -f 1804//1804 1828//1828 1805//1805 -f 1805//1805 1828//1828 1829//1829 -f 1805//1805 1829//1829 1806//1806 -f 1806//1806 1829//1829 1830//1830 -f 1806//1806 1830//1830 1807//1807 -f 1807//1807 1830//1830 1409//1409 -f 1807//1807 1409//1409 1808//1808 -f 1808//1808 1409//1409 1408//1408 -f 1808//1808 1408//1408 1809//1809 -f 1809//1809 1408//1408 1531//1531 -f 1809//1809 1531//1531 1810//1810 -f 1810//1810 1531//1531 1533//1533 -f 1810//1810 1533//1533 1811//1811 -f 1811//1811 1533//1533 1535//1535 -f 1811//1811 1535//1535 1812//1812 -f 1812//1812 1535//1535 1537//1537 -f 1812//1812 1537//1537 1813//1813 -f 1813//1813 1537//1537 1539//1539 -f 1813//1813 1539//1539 1814//1814 -f 1814//1814 1539//1539 1541//1541 -f 1814//1814 1541//1541 1815//1815 -f 1815//1815 1541//1541 1543//1543 -f 1815//1815 1543//1543 1816//1816 -f 1816//1816 1543//1543 1545//1545 -f 1816//1816 1545//1545 1817//1817 -f 1817//1817 1545//1545 1547//1547 -f 1817//1817 1547//1547 1818//1818 -f 1818//1818 1547//1547 1413//1413 -f 1818//1818 1413//1413 1819//1819 -f 1819//1819 1413//1413 1521//1521 -f 1819//1819 1521//1521 1612//1612 -f 1612//1612 1521//1521 1520//1520 -f 1612//1612 1520//1520 1613//1613 -f 1613//1613 1520//1520 1519//1519 -f 1613//1613 1519//1519 1410//1410 -f 1410//1410 1519//1519 1526//1526 -f 1410//1410 1526//1526 1202//1202 -f 1202//1202 1526//1526 1203//1203 -f 1841//1841 1440//1440 1842//1842 -f 1843//1843 1842//1842 1844//1844 -f 1844//1844 1842//1842 1440//1440 -f 1844//1844 1440//1440 1845//1845 -f 1845//1845 1440//1440 1442//1442 -f 1845//1845 1442//1442 1846//1846 -f 1846//1846 1421//1421 1845//1845 -f 1845//1845 1421//1421 1423//1423 -f 1845//1845 1423//1423 1844//1844 -f 1844//1844 1423//1423 1847//1847 -f 1844//1844 1847//1847 1843//1843 -f 1843//1843 1847//1847 1848//1848 -f 1849//1849 1848//1848 1850//1850 -f 1850//1850 1848//1848 1847//1847 -f 1850//1850 1847//1847 1851//1851 -f 1851//1851 1847//1847 1423//1423 -f 1851//1851 1423//1423 1852//1852 -f 1852//1852 1423//1423 1439//1439 -f 1852//1852 1439//1439 1436//1436 -f 1424//1424 1503//1503 1425//1425 -f 1425//1425 1503//1503 1502//1502 -f 1425//1425 1502//1502 1426//1426 -f 1426//1426 1502//1502 1853//1853 -f 1426//1426 1853//1853 1428//1428 -f 1428//1428 1853//1853 1854//1854 -f 1428//1428 1854//1854 1430//1430 -f 1430//1430 1854//1854 1855//1855 -f 1856//1856 1390//1390 1857//1857 -f 1857//1857 1390//1390 1388//1388 -f 1857//1857 1388//1388 1858//1858 -f 1858//1858 1388//1388 1387//1387 -f 1858//1858 1387//1387 1859//1859 -f 1860//1860 1861//1861 1862//1862 -f 1862//1862 1861//1861 1863//1863 -f 1862//1862 1863//1863 1864//1864 -f 1865//1865 1866//1866 1867//1867 -f 1867//1867 1866//1866 1868//1868 -f 1867//1867 1868//1868 1869//1869 -f 1870//1870 1871//1871 1872//1872 -f 1872//1872 1871//1871 1873//1873 -f 1874//1874 1383//1383 1875//1875 -f 1875//1875 1383//1383 1876//1876 -f 1875//1875 1876//1876 1877//1877 -f 1386//1386 1385//1385 1873//1873 -f 1873//1873 1385//1385 1878//1878 -f 1873//1873 1878//1878 1872//1872 -f 1879//1879 1880//1880 1881//1881 -f 1881//1881 1880//1880 1882//1882 -f 1881//1881 1882//1882 1386//1386 -f 1384//1384 1883//1883 1385//1385 -f 1385//1385 1883//1883 1884//1884 -f 1385//1385 1884//1884 1878//1878 -f 1880//1880 1885//1885 1882//1882 -f 1882//1882 1885//1885 1886//1886 -f 1882//1882 1886//1886 1386//1386 -f 1386//1386 1886//1886 1887//1887 -f 1386//1386 1887//1887 1384//1384 -f 1384//1384 1887//1887 1888//1888 -f 1384//1384 1888//1888 1883//1883 -f 1889//1889 1890//1890 1891//1891 -f 1891//1891 1890//1890 1892//1892 -f 1891//1891 1892//1892 1893//1893 -f 1894//1894 1895//1895 1896//1896 -f 1896//1896 1895//1895 1897//1897 -f 1897//1897 1898//1898 1896//1896 -f 1896//1896 1898//1898 1866//1866 -f 1896//1896 1866//1866 1894//1894 -f 1894//1894 1866//1866 1865//1865 -f 1894//1894 1865//1865 1870//1870 -f 1870//1870 1865//1865 1867//1867 -f 1870//1870 1867//1867 1871//1871 -f 1871//1871 1867//1867 1869//1869 -f 1871//1871 1869//1869 1899//1899 -f 1900//1900 1901//1901 1902//1902 -f 1902//1902 1901//1901 1903//1903 -f 1902//1902 1903//1903 1904//1904 -f 1885//1885 1889//1889 1886//1886 -f 1886//1886 1889//1889 1891//1891 -f 1886//1886 1891//1891 1887//1887 -f 1887//1887 1891//1891 1893//1893 -f 1887//1887 1893//1893 1888//1888 -f 1888//1888 1893//1893 1905//1905 -f 1888//1888 1905//1905 1883//1883 -f 1883//1883 1905//1905 1906//1906 -f 1883//1883 1906//1906 1884//1884 -f 1907//1907 1908//1908 1909//1909 -f 1907//1907 1909//1909 1910//1910 -f 1910//1910 1909//1909 1911//1911 -f 1910//1910 1911//1911 1912//1912 -f 1911//1911 1904//1904 1912//1912 -f 1912//1912 1904//1904 1903//1903 -f 1912//1912 1903//1903 1913//1913 -f 1914//1914 1915//1915 1916//1916 -f 1916//1916 1915//1915 1917//1917 -f 1377//1377 1378//1378 1375//1375 -f 1375//1375 1378//1378 1918//1918 -f 1375//1375 1918//1918 1919//1919 -f 1920//1920 1921//1921 1917//1917 -f 1917//1917 1921//1921 1922//1922 -f 1917//1917 1922//1922 1916//1916 -f 1923//1923 1924//1924 1925//1925 -f 1925//1925 1924//1924 1926//1926 -f 1925//1925 1926//1926 1927//1927 -f 1927//1927 1926//1926 1860//1860 -f 1373//1373 1372//1372 1928//1928 -f 1928//1928 1372//1372 1929//1929 -f 1928//1928 1929//1929 1930//1930 -f 1931//1931 1932//1932 1924//1924 -f 1933//1933 1373//1373 1923//1923 -f 1923//1923 1373//1373 1928//1928 -f 1923//1923 1928//1928 1924//1924 -f 1924//1924 1928//1928 1930//1930 -f 1924//1924 1930//1930 1931//1931 -f 1932//1932 1931//1931 1934//1934 -f 1934//1934 1931//1931 1935//1935 -f 1934//1934 1935//1935 1936//1936 -f 1936//1936 1935//1935 1937//1937 -f 1936//1936 1937//1937 1938//1938 -f 1938//1938 1914//1914 1936//1936 -f 1936//1936 1914//1914 1916//1916 -f 1936//1936 1916//1916 1934//1934 -f 1934//1934 1916//1916 1922//1922 -f 1934//1934 1922//1922 1932//1932 -f 1932//1932 1922//1922 1921//1921 -f 1932//1932 1921//1921 1924//1924 -f 1924//1924 1921//1921 1920//1920 -f 1924//1924 1920//1920 1926//1926 -f 1926//1926 1920//1920 1939//1939 -f 1940//1940 1370//1370 1941//1941 -f 1941//1941 1370//1370 1369//1369 -f 1941//1941 1369//1369 1942//1942 -f 1942//1942 1369//1369 1374//1374 -f 1943//1943 1944//1944 1945//1945 -f 1945//1945 1944//1944 1946//1946 -f 1945//1945 1946//1946 1947//1947 -f 1948//1948 1949//1949 1950//1950 -f 1950//1950 1949//1949 1951//1951 -f 1950//1950 1951//1951 1952//1952 -f 1947//1947 1953//1953 1945//1945 -f 1945//1945 1953//1953 1954//1954 -f 1945//1945 1954//1954 1943//1943 -f 1939//1939 1920//1920 1955//1955 -f 1955//1955 1920//1920 1917//1917 -f 1955//1955 1917//1917 1956//1956 -f 1956//1956 1917//1917 1915//1915 -f 1956//1956 1915//1915 1368//1368 -f 1368//1368 1915//1915 1914//1914 -f 1368//1368 1914//1914 1374//1374 -f 1374//1374 1914//1914 1938//1938 -f 1374//1374 1938//1938 1942//1942 -f 1942//1942 1938//1938 1937//1937 -f 1942//1942 1937//1937 1941//1941 -f 1941//1941 1937//1937 1957//1957 -f 1941//1941 1957//1957 1940//1940 -f 1958//1958 1365//1365 1959//1959 -f 1959//1959 1365//1365 1367//1367 -f 1959//1959 1367//1367 1960//1960 -f 1960//1960 1367//1367 1961//1961 -f 1962//1962 1963//1963 1964//1964 -f 1964//1964 1963//1963 1965//1965 -f 1964//1964 1965//1965 1966//1966 -f 1967//1967 1968//1968 1969//1969 -f 1970//1970 1962//1962 1971//1971 -f 1971//1971 1962//1962 1964//1964 -f 1971//1971 1964//1964 1972//1972 -f 1972//1972 1964//1964 1966//1966 -f 1968//1968 1967//1967 1959//1959 -f 1959//1959 1967//1967 1973//1973 -f 1959//1959 1973//1973 1958//1958 -f 1974//1974 1975//1975 1976//1976 -f 1976//1976 1975//1975 1977//1977 -f 1976//1976 1977//1977 1978//1978 -f 1978//1978 1977//1977 1979//1979 -f 1978//1978 1979//1979 1980//1980 -f 1980//1980 1979//1979 1981//1981 -f 1980//1980 1981//1981 1361//1361 -f 1982//1982 1983//1983 1984//1984 -f 1983//1983 1982//1982 1364//1364 -f 1364//1364 1982//1982 1985//1985 -f 1364//1364 1985//1985 1362//1362 -f 1967//1967 1974//1974 1973//1973 -f 1973//1973 1974//1974 1976//1976 -f 1973//1973 1976//1976 1958//1958 -f 1958//1958 1976//1976 1978//1978 -f 1958//1958 1978//1978 1365//1365 -f 1365//1365 1978//1978 1980//1980 -f 1365//1365 1980//1980 1366//1366 -f 1366//1366 1980//1980 1361//1361 -f 1366//1366 1361//1361 1986//1986 -f 1986//1986 1361//1361 1360//1360 -f 1360//1360 1933//1933 1986//1986 -f 1986//1986 1933//1933 1923//1923 -f 1986//1986 1923//1923 1366//1366 -f 1366//1366 1923//1923 1925//1925 -f 1366//1366 1925//1925 1367//1367 -f 1367//1367 1925//1925 1927//1927 -f 1367//1367 1927//1927 1961//1961 -f 1961//1961 1927//1927 1987//1987 -f 1961//1961 1987//1987 1988//1988 -f 1988//1988 1987//1987 1432//1432 -f 1988//1988 1432//1432 1989//1989 -f 1989//1989 1432//1432 1434//1434 -f 1989//1989 1434//1434 1431//1431 -f 1990//1990 1991//1991 1992//1992 -f 1992//1992 1991//1991 1993//1993 -f 1992//1992 1993//1993 1358//1358 -f 1994//1994 1995//1995 1996//1996 -f 1996//1996 1995//1995 1997//1997 -f 1356//1356 1358//1358 1998//1998 -f 1998//1998 1999//1999 2000//2000 -f 1999//1999 2001//2001 2000//2000 -f 2000//2000 2001//2001 2002//2002 -f 2000//2000 2002//2002 2003//2003 -f 1998//1998 2004//2004 1356//1356 -f 1356//1356 2004//2004 2005//2005 -f 1356//1356 2005//2005 1357//1357 -f 1355//1355 1354//1354 2006//2006 -f 1997//1997 2007//2007 1996//1996 -f 1996//1996 2007//2007 1353//1353 -f 1996//1996 1353//1353 1994//1994 -f 1994//1994 1353//1353 1355//1355 -f 1994//1994 1355//1355 2008//2008 -f 1363//1363 2009//2009 1364//1364 -f 1364//1364 2009//2009 2010//2010 -f 1364//1364 2010//2010 1983//1983 -f 1983//1983 2010//2010 2011//2011 -f 1983//1983 2011//2011 1984//1984 -f 2012//2012 1948//1948 1954//1954 -f 1954//1954 1948//1948 1950//1950 -f 1954//1954 1950//1950 1943//1943 -f 1943//1943 1950//1950 1952//1952 -f 1943//1943 1952//1952 1944//1944 -f 1998//1998 2000//2000 2004//2004 -f 2004//2004 2000//2000 2003//2003 -f 2004//2004 2003//2003 2005//2005 -f 2005//2005 2003//2003 2006//2006 -f 2005//2005 2006//2006 1357//1357 -f 1357//1357 2006//2006 1354//1354 -f 1357//1357 1354//1354 1358//1358 -f 1358//1358 1354//1354 1353//1353 -f 1358//1358 1353//1353 1992//1992 -f 1992//1992 1353//1353 2007//2007 -f 1992//1992 2007//2007 1990//1990 -f 1990//1990 2007//2007 1997//1997 -f 1990//1990 1997//1997 1946//1946 -f 1946//1946 1997//1997 1995//1995 -f 1946//1946 1995//1995 1947//1947 -f 1947//1947 1995//1995 1994//1994 -f 1947//1947 1994//1994 1953//1953 -f 1953//1953 1994//1994 2008//2008 -f 1953//1953 2008//2008 1954//1954 -f 1954//1954 2008//2008 2013//2013 -f 1954//1954 2013//2013 2012//2012 -f 2014//2014 2015//2015 2016//2016 -f 2016//2016 2015//2015 2017//2017 -f 2016//2016 2017//2017 2018//2018 -f 2019//2019 2020//2020 2014//2014 -f 2014//2014 2020//2020 2021//2021 -f 1376//1376 1375//1375 2022//2022 -f 2022//2022 1375//1375 1919//1919 -f 2022//2022 1919//1919 2023//2023 -f 2014//2014 2016//2016 2019//2019 -f 2019//2019 2016//2016 2024//2024 -f 2019//2019 2024//2024 2020//2020 -f 2020//2020 2024//2024 2025//2025 -f 2020//2020 2025//2025 2026//2026 -f 1379//1379 2027//2027 1378//1378 -f 1378//1378 2027//2027 2028//2028 -f 1378//1378 2028//2028 1918//1918 -f 1918//1918 2028//2028 2029//2029 -f 1918//1918 2029//2029 1919//1919 -f 1919//1919 2029//2029 2030//2030 -f 1919//1919 2030//2030 2023//2023 -f 1382//1382 2021//2021 2031//2031 -f 2031//2031 2021//2021 2020//2020 -f 2031//2031 2020//2020 2032//2032 -f 2032//2032 2020//2020 2026//2026 -f 2032//2032 1913//1913 2031//2031 -f 2031//2031 1913//1913 1903//1903 -f 2031//2031 1903//1903 1382//1382 -f 1382//1382 1903//1903 1901//1901 -f 1382//1382 1901//1901 1380//1380 -f 1380//1380 1901//1901 1900//1900 -f 1380//1380 1900//1900 1383//1383 -f 1383//1383 1900//1900 2033//2033 -f 1383//1383 2033//2033 1876//1876 -f 1876//1876 2033//2033 2034//2034 -f 1876//1876 2034//2034 1877//1877 -f 2035//2035 2036//2036 2037//2037 -f 2037//2037 2036//2036 2038//2038 -f 2037//2037 2038//2038 2039//2039 -f 2040//2040 2041//2041 2011//2011 -f 2011//2011 2041//2041 2042//2042 -f 2011//2011 2042//2042 1984//1984 -f 2026//2026 2043//2043 2032//2032 -f 2032//2032 2043//2043 2035//2035 -f 2032//2032 2035//2035 1913//1913 -f 1913//1913 2035//2035 2037//2037 -f 1913//1913 2037//2037 1912//1912 -f 1912//1912 2037//2037 2039//2039 -f 1912//1912 2039//2039 1910//1910 -f 1910//1910 2039//2039 2044//2044 -f 1910//1910 2044//2044 1907//1907 -f 1907//1907 2044//2044 2045//2045 -f 1907//1907 2045//2045 1908//1908 -f 2046//2046 2047//2047 2048//2048 -f 2048//2048 2047//2047 1352//1352 -f 2048//2048 1352//1352 2049//2049 -f 2049//2049 2050//2050 2048//2048 -f 2048//2048 2050//2050 2051//2051 -f 2048//2048 2051//2051 2046//2046 -f 2046//2046 2051//2051 2052//2052 -f 2046//2046 2052//2052 2047//2047 -f 2047//2047 2052//2052 2053//2053 -f 2047//2047 2053//2053 1352//1352 -f 1352//1352 2053//2053 2054//2054 -f 1352//1352 2054//2054 1350//1350 -f 2055//2055 2056//2056 2057//2057 -f 1431//1431 1430//1430 1989//1989 -f 1989//1989 1430//1430 1855//1855 -f 1989//1989 1855//1855 1988//1988 -f 1988//1988 1855//1855 1349//1349 -f 1988//1988 1349//1349 1961//1961 -f 1961//1961 1349//1349 1348//1348 -f 1961//1961 1348//1348 1960//1960 -f 1960//1960 1348//1348 2058//2058 -f 1960//1960 2058//2058 2059//2059 -f 2059//2059 2058//2058 2060//2060 -f 2059//2059 2060//2060 2061//2061 -f 2062//2062 2063//2063 2064//2064 -f 2064//2064 2063//2063 2065//2065 -f 2064//2064 2065//2065 2066//2066 -f 2067//2067 2068//2068 2069//2069 -f 1970//1970 1969//1969 1962//1962 -f 1962//1962 1969//1969 1968//1968 -f 1962//1962 1968//1968 1963//1963 -f 1963//1963 1968//1968 1959//1959 -f 1963//1963 1959//1959 1965//1965 -f 1965//1965 1959//1959 1960//1960 -f 1965//1965 1960//1960 1966//1966 -f 1966//1966 1960//1960 2059//2059 -f 1966//1966 2059//2059 1972//1972 -f 1972//1972 2059//2059 2061//2061 -f 1972//1972 2061//2061 1971//1971 -f 1971//1971 2061//2061 2070//2070 -f 1971//1971 2070//2070 1970//1970 -f 1970//1970 2070//2070 2071//2071 -f 1970//1970 2071//2071 1969//1969 -f 1969//1969 2071//2071 2072//2072 -f 1969//1969 2072//2072 1967//1967 -f 1967//1967 2072//2072 2073//2073 -f 1967//1967 2073//2073 1974//1974 -f 1974//1974 2073//2073 2074//2074 -f 1974//1974 2074//2074 1975//1975 -f 1975//1975 2074//2074 2075//2075 -f 1975//1975 2075//2075 1977//1977 -f 1977//1977 2075//2075 2002//2002 -f 1977//1977 2002//2002 1979//1979 -f 1979//1979 2002//2002 2001//2001 -f 1979//1979 2001//2001 1981//1981 -f 1981//1981 2001//2001 1999//1999 -f 1981//1981 1999//1999 1361//1361 -f 1361//1361 1999//1999 1998//1998 -f 1361//1361 1998//1998 1359//1359 -f 1359//1359 1998//1998 1358//1358 -f 1359//1359 1358//1358 1360//1360 -f 1360//1360 1358//1358 1993//1993 -f 1360//1360 1993//1993 1933//1933 -f 1933//1933 1993//1993 1991//1991 -f 1933//1933 1991//1991 1373//1373 -f 1373//1373 1991//1991 1990//1990 -f 1373//1373 1990//1990 1371//1371 -f 1371//1371 1990//1990 1946//1946 -f 1371//1371 1946//1946 1372//1372 -f 1372//1372 1946//1946 1944//1944 -f 1372//1372 1944//1944 1929//1929 -f 1929//1929 1944//1944 1952//1952 -f 1929//1929 1952//1952 1930//1930 -f 1930//1930 1952//1952 1951//1951 -f 1930//1930 1951//1951 1931//1931 -f 1931//1931 1951//1951 1949//1949 -f 1931//1931 1949//1949 1935//1935 -f 1935//1935 1949//1949 1948//1948 -f 1935//1935 1948//1948 1937//1937 -f 1937//1937 1948//1948 2012//2012 -f 1937//1937 2012//2012 1957//1957 -f 1957//1957 2012//2012 2013//2013 -f 1957//1957 2013//2013 1940//1940 -f 2076//2076 2077//2077 2078//2078 -f 2078//2078 2077//2077 2069//2069 -f 2078//2078 2069//2069 2079//2079 -f 2079//2079 2069//2069 2068//2068 -f 2079//2079 2068//2068 2080//2080 -f 2080//2080 2068//2068 2067//2067 -f 2080//2080 2067//2067 2081//2081 -f 2081//2081 2067//2067 2082//2082 -f 2081//2081 2082//2082 2083//2083 -f 2083//2083 2082//2082 2084//2084 -f 2084//2084 2082//2082 2085//2085 -f 2084//2084 2085//2085 2086//2086 -f 2067//2067 2087//2087 2082//2082 -f 2082//2082 2087//2087 2088//2088 -f 2082//2082 2088//2088 2085//2085 -f 2085//2085 2088//2088 2089//2089 -f 2050//2050 2090//2090 2051//2051 -f 2051//2051 2090//2090 2091//2091 -f 2051//2051 2091//2091 2052//2052 -f 2052//2052 2091//2091 2092//2092 -f 2052//2052 2092//2092 2053//2053 -f 2053//2053 2092//2092 2093//2093 -f 2053//2053 2093//2093 2054//2054 -f 2054//2054 2093//2093 2094//2094 -f 2054//2054 2094//2094 1350//1350 -f 1350//1350 2094//2094 2095//2095 -f 1350//1350 2095//2095 1351//1351 -f 1351//1351 2095//2095 2096//2096 -f 1347//1347 2097//2097 2098//2098 -f 2098//2098 2097//2097 2099//2099 -f 2098//2098 2099//2099 2100//2100 -f 2100//2100 2099//2099 2101//2101 -f 2100//2100 2101//2101 1345//1345 -f 2102//2102 2103//2103 1344//1344 -f 1344//1344 1346//1346 2102//2102 -f 2102//2102 1346//1346 2104//2104 -f 2102//2102 2104//2104 2105//2105 -f 2049//2049 1334//1334 2050//2050 -f 2050//2050 1334//1334 1333//1333 -f 2050//2050 1333//1333 2090//2090 -f 2090//2090 1333//1333 2106//2106 -f 2090//2090 2106//2106 2091//2091 -f 2091//2091 2106//2106 2107//2107 -f 2091//2091 2107//2107 2092//2092 -f 2092//2092 2107//2107 2108//2108 -f 2092//2092 2108//2108 2093//2093 -f 2093//2093 2108//2108 2109//2109 -f 2093//2093 2109//2109 2094//2094 -f 2094//2094 2109//2109 2110//2110 -f 2094//2094 2110//2110 2095//2095 -f 2095//2095 2110//2110 2111//2111 -f 2095//2095 2111//2111 2096//2096 -f 1345//1345 2101//2101 1346//1346 -f 1346//1346 2101//2101 2112//2112 -f 1346//1346 2112//2112 2104//2104 -f 2104//2104 2112//2112 2113//2113 -f 2104//2104 2113//2113 2105//2105 -f 1343//1343 1342//1342 2114//2114 -f 1341//1341 2115//2115 1342//1342 -f 1342//1342 2115//2115 2116//2116 -f 1342//1342 2116//2116 2114//2114 -f 2114//2114 2116//2116 2117//2117 -f 2114//2114 2117//2117 2118//2118 -f 1985//1985 2086//2086 1362//1362 -f 1362//1362 2086//2086 2085//2085 -f 1362//1362 2085//2085 1363//1363 -f 1363//1363 2085//2085 2089//2089 -f 1363//1363 2089//2089 2009//2009 -f 2009//2009 2089//2089 2119//2119 -f 2009//2009 2119//2119 2010//2010 -f 2010//2010 2119//2119 2120//2120 -f 2010//2010 2120//2120 2011//2011 -f 2011//2011 2120//2120 2121//2121 -f 2011//2011 2121//2121 2040//2040 -f 2122//2122 2123//2123 2124//2124 -f 2124//2124 2123//2123 2125//2125 -f 2126//2126 2127//2127 2128//2128 -f 2128//2128 2127//2127 2129//2129 -f 2128//2128 2129//2129 2130//2130 -f 2131//2131 2057//2057 2132//2132 -f 1352//1352 2055//2055 2049//2049 -f 2049//2049 2055//2055 2057//2057 -f 2049//2049 2057//2057 1334//1334 -f 1334//1334 2057//2057 2131//2131 -f 1334//1334 2131//2131 2133//2133 -f 2134//2134 2135//2135 2136//2136 -f 2136//2136 2135//2135 2137//2137 -f 2136//2136 2137//2137 2138//2138 -f 2139//2139 2140//2140 2141//2141 -f 2141//2141 2140//2140 2137//2137 -f 2141//2141 2137//2137 2142//2142 -f 2142//2142 2137//2137 2135//2135 -f 2142//2142 2135//2135 2143//2143 -f 2143//2143 2135//2135 2134//2134 -f 2143//2143 2134//2134 2144//2144 -f 2139//2139 2141//2141 2145//2145 -f 2145//2145 2141//2141 2142//2142 -f 2145//2145 2142//2142 2146//2146 -f 2146//2146 2142//2142 2143//2143 -f 2146//2146 2143//2143 2147//2147 -f 2147//2147 2143//2143 2144//2144 -f 2147//2147 2144//2144 2148//2148 -f 2149//2149 2150//2150 2151//2151 -f 2150//2150 2149//2149 2152//2152 -f 2152//2152 2149//2149 2153//2153 -f 2152//2152 2153//2153 2154//2154 -f 2155//2155 2156//2156 2157//2157 -f 2157//2157 2156//2156 2158//2158 -f 2157//2157 2158//2158 1338//1338 -f 2159//2159 2160//2160 2161//2161 -f 2161//2161 2160//2160 2162//2162 -f 1337//1337 1336//1336 2163//2163 -f 2163//2163 1336//1336 2164//2164 -f 2163//2163 2164//2164 2165//2165 -f 2165//2165 2164//2164 2166//2166 -f 2165//2165 2166//2166 2167//2167 -f 2167//2167 2166//2166 2168//2168 -f 2167//2167 2168//2168 2162//2162 -f 2162//2162 2168//2168 2169//2169 -f 2162//2162 2169//2169 2161//2161 -f 2161//2161 2169//2169 2170//2170 -f 2161//2161 2170//2170 2171//2171 -f 2172//2172 1335//1335 2173//2173 -f 2173//2173 1335//1335 1337//1337 -f 2173//2173 1337//1337 2148//2148 -f 2148//2148 1337//1337 2163//2163 -f 2148//2148 2163//2163 2147//2147 -f 2147//2147 2163//2163 2165//2165 -f 2147//2147 2165//2165 2146//2146 -f 2146//2146 2165//2165 2167//2167 -f 2146//2146 2167//2167 2145//2145 -f 2145//2145 2167//2167 2162//2162 -f 2145//2145 2162//2162 2139//2139 -f 2139//2139 2162//2162 2160//2160 -f 2139//2139 2160//2160 2140//2140 -f 2140//2140 2160//2160 2159//2159 -f 2140//2140 2159//2159 2137//2137 -f 2137//2137 2159//2159 2174//2174 -f 2137//2137 2174//2174 2138//2138 -f 2138//2138 2174//2174 2175//2175 -f 2176//2176 2177//2177 2178//2178 -f 2178//2178 2177//2177 2179//2179 -f 2178//2178 2179//2179 2036//2036 -f 2180//2180 2181//2181 2182//2182 -f 1341//1341 2183//2183 2115//2115 -f 2115//2115 2183//2183 2184//2184 -f 2115//2115 2184//2184 2116//2116 -f 2116//2116 2184//2184 2180//2180 -f 2116//2116 2180//2180 2117//2117 -f 2117//2117 2180//2180 2182//2182 -f 2117//2117 2182//2182 2118//2118 -f 2185//2185 2186//2186 2187//2187 -f 1324//1324 2188//2188 2189//2189 -f 2189//2189 2188//2188 2187//2187 -f 2187//2187 2186//2186 2189//2189 -f 2189//2189 2186//2186 1325//1325 -f 2189//2189 1325//1325 1324//1324 -f 2190//2190 2128//2128 2191//2191 -f 2191//2191 2128//2128 2130//2130 -f 2191//2191 2130//2130 2192//2192 -f 2192//2192 2130//2130 2193//2193 -f 2192//2192 2193//2193 2194//2194 -f 2194//2194 2193//2193 2195//2195 -f 2194//2194 2195//2195 2196//2196 -f 1331//1331 1328//1328 2197//2197 -f 2197//2197 1328//1328 1327//1327 -f 2197//2197 1327//1327 2190//2190 -f 1329//1329 1328//1328 2198//2198 -f 2198//2198 1328//1328 1330//1330 -f 2198//2198 1330//1330 2199//2199 -f 2190//2190 2191//2191 2197//2197 -f 2197//2197 2191//2191 2192//2192 -f 2197//2197 2192//2192 1331//1331 -f 1331//1331 2192//2192 2194//2194 -f 1331//1331 2194//2194 1330//1330 -f 1330//1330 2194//2194 2196//2196 -f 1330//1330 2196//2196 2199//2199 -f 2200//2200 2201//2201 2202//2202 -f 2202//2202 2201//2201 2203//2203 -f 2202//2202 2203//2203 2204//2204 -f 2204//2204 2203//2203 2205//2205 -f 2206//2206 2205//2205 2207//2207 -f 2207//2207 2205//2205 2203//2203 -f 2207//2207 2203//2203 2208//2208 -f 2208//2208 2203//2203 2201//2201 -f 2209//2209 2210//2210 2211//2211 -f 2211//2211 2210//2210 2212//2212 -f 2213//2213 2214//2214 2209//2209 -f 2209//2209 2214//2214 2206//2206 -f 2209//2209 2206//2206 2210//2210 -f 2210//2210 2206//2206 2207//2207 -f 2210//2210 2207//2207 2212//2212 -f 2212//2212 2207//2207 2208//2208 -f 2212//2212 2208//2208 2215//2215 -f 2215//2215 2208//2208 2201//2201 -f 2215//2215 2201//2201 2216//2216 -f 2216//2216 2201//2201 2200//2200 -f 1338//1338 1340//1340 2157//2157 -f 2157//2157 1340//1340 2217//2217 -f 2157//2157 2217//2217 2155//2155 -f 2155//2155 2217//2217 2218//2218 -f 2155//2155 2218//2218 2170//2170 -f 2172//2172 1339//1339 1335//1335 -f 1335//1335 1339//1339 1338//1338 -f 1335//1335 1338//1338 1336//1336 -f 1336//1336 1338//1338 2158//2158 -f 1336//1336 2158//2158 2164//2164 -f 2164//2164 2158//2158 2151//2151 -f 2164//2164 2151//2151 2166//2166 -f 2166//2166 2151//2151 2150//2150 -f 2166//2166 2150//2150 2168//2168 -f 2168//2168 2150//2150 2152//2152 -f 2168//2168 2152//2152 2169//2169 -f 2169//2169 2152//2152 2154//2154 -f 2169//2169 2154//2154 2170//2170 -f 2170//2170 2154//2154 2153//2153 -f 2170//2170 2153//2153 2155//2155 -f 2155//2155 2153//2153 2149//2149 -f 2155//2155 2149//2149 2156//2156 -f 2156//2156 2149//2149 2151//2151 -f 2156//2156 2151//2151 2158//2158 -f 2219//2219 2220//2220 2221//2221 -f 2221//2221 2220//2220 2222//2222 -f 2221//2221 2222//2222 2223//2223 -f 1321//1321 1326//1326 2224//2224 -f 2224//2224 1326//1326 1325//1325 -f 2224//2224 1325//1325 2225//2225 -f 2225//2225 1325//1325 2186//2186 -f 2225//2225 2186//2186 2223//2223 -f 2223//2223 2186//2186 2185//2185 -f 2223//2223 2185//2185 2221//2221 -f 2221//2221 2185//2185 2187//2187 -f 2221//2221 2187//2187 2219//2219 -f 2219//2219 2187//2187 2130//2130 -f 2219//2219 2130//2130 2056//2056 -f 2056//2056 2130//2130 2129//2129 -f 2056//2056 2129//2129 2057//2057 -f 2057//2057 2129//2129 2127//2127 -f 2057//2057 2127//2127 2132//2132 -f 2132//2132 2127//2127 2126//2126 -f 2226//2226 2227//2227 2228//2228 -f 2228//2228 2227//2227 2229//2229 -f 2228//2228 2229//2229 2230//2230 -f 2230//2230 2229//2229 2231//2231 -f 2232//2232 2231//2231 2229//2229 -f 2232//2232 2229//2229 2233//2233 -f 2233//2233 2229//2229 2227//2227 -f 2233//2233 2227//2227 2234//2234 -f 2234//2234 2227//2227 2235//2235 -f 2077//2077 2066//2066 2069//2069 -f 2069//2069 2066//2066 2065//2065 -f 2069//2069 2065//2065 2067//2067 -f 2067//2067 2065//2065 2063//2063 -f 2067//2067 2063//2063 2087//2087 -f 2087//2087 2063//2063 2062//2062 -f 2087//2087 2062//2062 2088//2088 -f 2088//2088 2062//2062 2236//2236 -f 2088//2088 2236//2236 2089//2089 -f 2089//2089 2236//2236 2176//2176 -f 2089//2089 2176//2176 2119//2119 -f 2119//2119 2176//2176 2178//2178 -f 2119//2119 2178//2178 2120//2120 -f 2120//2120 2178//2178 2036//2036 -f 2120//2120 2036//2036 2237//2237 -f 2237//2237 2036//2036 2035//2035 -f 1433//1433 1432//1432 1435//1435 -f 1435//1435 1432//1432 1987//1987 -f 1435//1435 1987//1987 1859//1859 -f 1859//1859 1987//1987 1927//1927 -f 1859//1859 1927//1927 1858//1858 -f 1858//1858 1927//1927 1860//1860 -f 1858//1858 1860//1860 1857//1857 -f 1857//1857 1860//1860 1862//1862 -f 1857//1857 1862//1862 1856//1856 -f 1856//1856 1862//1862 1864//1864 -f 1856//1856 1864//1864 2238//2238 -f 1501//1501 2239//2239 2240//2240 -f 2240//2240 2239//2239 2241//2241 -f 2240//2240 2241//2241 2242//2242 -f 2242//2242 2241//2241 2243//2243 -f 2244//2244 2245//2245 2246//2246 -f 2246//2246 2245//2245 2247//2247 -f 2246//2246 2247//2247 2248//2248 -f 2248//2248 2247//2247 2249//2249 -f 2248//2248 2249//2249 2250//2250 -f 2251//2251 2252//2252 2253//2253 -f 2254//2254 2253//2253 1320//1320 -f 2255//2255 2254//2254 2256//2256 -f 2255//2255 2256//2256 2257//2257 -f 2253//2253 2254//2254 2255//2255 -f 2253//2253 2255//2255 2251//2251 -f 2251//2251 2255//2255 2258//2258 -f 2258//2258 2255//2255 2257//2257 -f 2259//2259 2260//2260 2261//2261 -f 2262//2262 2260//2260 2263//2263 -f 2263//2263 2260//2260 2259//2259 -f 2263//2263 2259//2259 2264//2264 -f 2265//2265 2262//2262 2266//2266 -f 2266//2266 2262//2262 2263//2263 -f 2266//2266 2263//2263 2264//2264 -f 2253//2253 2264//2264 2267//2267 -f 2268//2268 2259//2259 2269//2269 -f 2269//2269 2259//2259 2270//2270 -f 2269//2269 2270//2270 2271//2271 -f 2262//2262 2272//2272 2273//2273 -f 2273//2273 2272//2272 2274//2274 -f 2273//2273 2274//2274 2275//2275 -f 2275//2275 2274//2274 2276//2276 -f 2275//2275 2276//2276 2277//2277 -f 2277//2277 2276//2276 2278//2278 -f 2277//2277 2278//2278 2279//2279 -f 2279//2279 2278//2278 2280//2280 -f 2281//2281 2282//2282 2283//2283 -f 2283//2283 2282//2282 2284//2284 -f 2283//2283 2284//2284 2285//2285 -f 1319//1319 2268//2268 1318//1318 -f 1318//1318 2268//2268 2269//2269 -f 1318//1318 2269//2269 1316//1316 -f 1316//1316 2269//2269 2271//2271 -f 1316//1316 2271//2271 1317//1317 -f 2286//2286 2287//2287 2288//2288 -f 2288//2288 2287//2287 2289//2289 -f 2288//2288 2289//2289 2290//2290 -f 2290//2290 2289//2289 2291//2291 -f 2290//2290 2291//2291 2292//2292 -f 2292//2292 2291//2291 2293//2293 -f 2292//2292 2293//2293 2294//2294 -f 2295//2295 2286//2286 2296//2296 -f 2296//2296 2286//2286 2288//2288 -f 2296//2296 2288//2288 2297//2297 -f 2297//2297 2288//2288 2290//2290 -f 2297//2297 2290//2290 2298//2298 -f 2298//2298 2290//2290 2292//2292 -f 2298//2298 2292//2292 2299//2299 -f 2299//2299 2292//2292 2294//2294 -f 2299//2299 2294//2294 2300//2300 -f 2301//2301 2262//2262 2258//2258 -f 2258//2258 2262//2262 2265//2265 -f 2258//2258 2265//2265 2251//2251 -f 2251//2251 2265//2265 2266//2266 -f 2251//2251 2266//2266 2252//2252 -f 2252//2252 2266//2266 2264//2264 -f 2252//2252 2264//2264 2253//2253 -f 1320//1320 2253//2253 2267//2267 -f 1320//1320 2267//2267 1319//1319 -f 1319//1319 2267//2267 2264//2264 -f 1319//1319 2264//2264 2268//2268 -f 2268//2268 2264//2264 2259//2259 -f 2259//2259 2261//2261 2270//2270 -f 2302//2302 2303//2303 2304//2304 -f 2304//2304 2303//2303 2305//2305 -f 2281//2281 2306//2306 2282//2282 -f 2282//2282 2306//2306 2307//2307 -f 2282//2282 2307//2307 2284//2284 -f 2284//2284 2307//2307 2308//2308 -f 2284//2284 2308//2308 2285//2285 -f 2285//2285 2308//2308 2309//2309 -f 1314//1314 1313//1313 2310//2310 -f 2310//2310 1313//1313 2311//2311 -f 2310//2310 2311//2311 2312//2312 -f 2313//2313 2314//2314 2315//2315 -f 2315//2315 2314//2314 2306//2306 -f 2315//2315 2306//2306 2286//2286 -f 2286//2286 2306//2306 2281//2281 -f 2286//2286 2281//2281 2287//2287 -f 2287//2287 2281//2281 2283//2283 -f 2287//2287 2283//2283 2289//2289 -f 2289//2289 2283//2283 2285//2285 -f 2289//2289 2285//2285 2291//2291 -f 2291//2291 2285//2285 2309//2309 -f 2291//2291 2309//2309 2293//2293 -f 2316//2316 2317//2317 2318//2318 -f 2318//2318 2317//2317 2319//2319 -f 2318//2318 2319//2319 2320//2320 -f 2320//2320 2319//2319 2321//2321 -f 2320//2320 2321//2321 2322//2322 -f 2317//2317 2323//2323 2319//2319 -f 2319//2319 2323//2323 2324//2324 -f 2319//2319 2324//2324 2321//2321 -f 2321//2321 2324//2324 2325//2325 -f 2321//2321 2325//2325 2322//2322 -f 2322//2322 2325//2325 2326//2326 -f 2316//2316 2327//2327 2317//2317 -f 2317//2317 2327//2327 2328//2328 -f 2317//2317 2328//2328 2323//2323 -f 2323//2323 2328//2328 2329//2329 -f 2323//2323 2329//2329 2324//2324 -f 2324//2324 2329//2329 2330//2330 -f 2324//2324 2330//2330 2325//2325 -f 2325//2325 2330//2330 2331//2331 -f 2325//2325 2331//2331 2326//2326 -f 2332//2332 2333//2333 2334//2334 -f 2334//2334 2333//2333 2335//2335 -f 2334//2334 2335//2335 1304//1304 -f 1305//1305 2336//2336 2337//2337 -f 2337//2337 2336//2336 2338//2338 -f 2337//2337 2338//2338 2339//2339 -f 2340//2340 2341//2341 1312//1312 -f 1312//1312 2341//2341 2342//2342 -f 1312//1312 2342//2342 1310//1310 -f 1310//1310 2342//2342 2343//2343 -f 2344//2344 2345//2345 2346//2346 -f 2346//2346 2345//2345 2347//2347 -f 1305//1305 1304//1304 2336//2336 -f 2336//2336 1304//1304 2335//2335 -f 2336//2336 2335//2335 2338//2338 -f 2338//2338 2335//2335 2333//2333 -f 2338//2338 2333//2333 2339//2339 -f 2328//2328 2348//2348 2329//2329 -f 2329//2329 2348//2348 2349//2349 -f 2329//2329 2349//2349 2330//2330 -f 2330//2330 2349//2349 2350//2350 -f 2330//2330 2350//2350 2331//2331 -f 2331//2331 2350//2350 2304//2304 -f 2331//2331 2304//2304 2326//2326 -f 2326//2326 2304//2304 2305//2305 -f 2326//2326 2305//2305 2322//2322 -f 2322//2322 2305//2305 2312//2312 -f 2322//2322 2312//2312 2320//2320 -f 2320//2320 2312//2312 2311//2311 -f 2320//2320 2311//2311 2318//2318 -f 2318//2318 2311//2311 1313//1313 -f 2318//2318 1313//1313 2316//2316 -f 2316//2316 1313//1313 1315//1315 -f 2316//2316 1315//1315 2327//2327 -f 1302//1302 1301//1301 2351//2351 -f 2351//2351 1301//1301 2352//2352 -f 2351//2351 2352//2352 2353//2353 -f 2344//2344 2313//2313 2345//2345 -f 2345//2345 2313//2313 1303//1303 -f 2345//2345 1303//1303 2354//2354 -f 2354//2354 1303//1303 1302//1302 -f 2354//2354 1302//1302 2355//2355 -f 2355//2355 1302//1302 2351//2351 -f 2355//2355 2351//2351 2356//2356 -f 2356//2356 2351//2351 2353//2353 -f 2356//2356 2353//2353 2357//2357 -f 2357//2357 2358//2358 2356//2356 -f 2356//2356 2358//2358 2359//2359 -f 2356//2356 2359//2359 2355//2355 -f 2355//2355 2359//2359 1309//1309 -f 2355//2355 1309//1309 2354//2354 -f 2354//2354 1309//1309 1308//1308 -f 2354//2354 1308//1308 2345//2345 -f 2345//2345 1308//1308 1307//1307 -f 2345//2345 1307//1307 2347//2347 -f 1295//1295 1297//1297 2360//2360 -f 2361//2361 2362//2362 2363//2363 -f 2363//2363 2362//2362 2364//2364 -f 2363//2363 2364//2364 2365//2365 -f 2365//2365 2364//2364 2366//2366 -f 2365//2365 2366//2366 2367//2367 -f 2367//2367 2366//2366 2368//2368 -f 1293//1293 1292//1292 2369//2369 -f 2369//2369 1292//1292 2370//2370 -f 2369//2369 2370//2370 1300//1300 -f 2371//2371 2372//2372 2373//2373 -f 2373//2373 2372//2372 2374//2374 -f 2373//2373 2374//2374 2375//2375 -f 1294//1294 2368//2368 1292//1292 -f 1292//1292 2368//2368 2366//2366 -f 1292//1292 2366//2366 2370//2370 -f 2370//2370 2366//2366 2364//2364 -f 2370//2370 2364//2364 1300//1300 -f 1300//1300 2364//2364 2362//2362 -f 1300//1300 2362//2362 1298//1298 -f 2376//2376 2360//2360 2377//2377 -f 2377//2377 2360//2360 1297//1297 -f 2377//2377 1297//1297 2378//2378 -f 2378//2378 1297//1297 2379//2379 -f 2378//2378 2379//2379 1262//1262 -f 2376//2376 2380//2380 2360//2360 -f 2360//2360 2380//2380 2381//2381 -f 2360//2360 2381//2381 1295//1295 -f 1295//1295 2381//2381 2382//2382 -f 1295//1295 2382//2382 1296//1296 -f 1296//1296 2382//2382 2372//2372 -f 1296//1296 2372//2372 1297//1297 -f 1297//1297 2372//2372 2371//2371 -f 1297//1297 2371//2371 2379//2379 -f 2383//2383 2384//2384 2385//2385 -f 2385//2385 2384//2384 2386//2386 -f 2387//2387 2388//2388 2389//2389 -f 2389//2389 2388//2388 2390//2390 -f 2389//2389 2390//2390 2391//2391 -f 2392//2392 2393//2393 2394//2394 -f 2394//2394 2393//2393 2395//2395 -f 2394//2394 2395//2395 2396//2396 -f 1291//1291 1290//1290 2383//2383 -f 2383//2383 1290//1290 2397//2397 -f 2383//2383 2397//2397 2384//2384 -f 2398//2398 2386//2386 2399//2399 -f 2399//2399 2386//2386 2384//2384 -f 2399//2399 2384//2384 2400//2400 -f 2400//2400 2384//2384 2397//2397 -f 2401//2401 2402//2402 1286//1286 -f 2402//2402 2401//2401 2403//2403 -f 1286//1286 1288//1288 2401//2401 -f 2401//2401 1288//1288 2404//2404 -f 2401//2401 2404//2404 2403//2403 -f 2403//2403 2404//2404 2405//2405 -f 2403//2403 2405//2405 2406//2406 -f 2398//2398 2387//2387 2386//2386 -f 2386//2386 2387//2387 2389//2389 -f 2386//2386 2389//2389 2385//2385 -f 2385//2385 2389//2389 2391//2391 -f 2385//2385 2391//2391 2383//2383 -f 2383//2383 2391//2391 2392//2392 -f 2383//2383 2392//2392 1291//1291 -f 1291//1291 2392//2392 2394//2394 -f 1291//1291 2394//2394 1289//1289 -f 1289//1289 2394//2394 2396//2396 -f 1288//1288 2407//2407 2404//2404 -f 2404//2404 2407//2407 2408//2408 -f 2404//2404 2408//2408 2409//2409 -f 2410//2410 2411//2411 2412//2412 -f 2412//2412 2411//2411 2413//2413 -f 2380//2380 2361//2361 2381//2381 -f 2381//2381 2361//2361 2363//2363 -f 2381//2381 2363//2363 2382//2382 -f 2382//2382 2363//2363 2365//2365 -f 2382//2382 2365//2365 2372//2372 -f 2372//2372 2365//2365 2367//2367 -f 2372//2372 2367//2367 2374//2374 -f 2374//2374 2367//2367 2368//2368 -f 2374//2374 2368//2368 2375//2375 -f 2375//2375 2368//2368 1294//1294 -f 2375//2375 1294//1294 2414//2414 -f 2414//2414 1294//1294 1293//1293 -f 2414//2414 1293//1293 2413//2413 -f 2413//2413 1293//1293 2369//2369 -f 2413//2413 2369//2369 2412//2412 -f 2412//2412 2369//2369 1300//1300 -f 2412//2412 1300//1300 2415//2415 -f 2415//2415 1300//1300 1299//1299 -f 2415//2415 1299//1299 2416//2416 -f 2357//2357 2417//2417 2358//2358 -f 2358//2358 2417//2417 2418//2418 -f 2358//2358 2418//2418 2359//2359 -f 2359//2359 2418//2418 2419//2419 -f 2359//2359 2419//2419 1309//1309 -f 1309//1309 2419//2419 2420//2420 -f 1309//1309 2420//2420 1307//1307 -f 1307//1307 2420//2420 2421//2421 -f 1307//1307 2421//2421 2347//2347 -f 2422//2422 2423//2423 2340//2340 -f 2340//2340 2423//2423 2424//2424 -f 2340//2340 2424//2424 2341//2341 -f 2341//2341 2424//2424 1306//1306 -f 2341//2341 1306//1306 2342//2342 -f 2342//2342 1306//1306 1305//1305 -f 2342//2342 1305//1305 2343//2343 -f 2343//2343 1305//1305 2337//2337 -f 2343//2343 2337//2337 1310//1310 -f 1310//1310 2337//2337 2339//2339 -f 1310//1310 2339//2339 1311//1311 -f 2328//2328 2332//2332 2348//2348 -f 2348//2348 2332//2332 2334//2334 -f 2348//2348 2334//2334 2349//2349 -f 2349//2349 2334//2334 1304//1304 -f 2349//2349 1304//1304 2350//2350 -f 2350//2350 1304//1304 1306//1306 -f 2350//2350 1306//1306 2304//2304 -f 2304//2304 1306//1306 2424//2424 -f 2304//2304 2424//2424 2425//2425 -f 2425//2425 2424//2424 2426//2426 -f 1262//1262 2379//2379 1263//1263 -f 1263//1263 2379//2379 2427//2427 -f 1263//1263 2427//2427 2428//2428 -f 2242//2242 2429//2429 2240//2240 -f 2240//2240 2429//2429 2250//2250 -f 2240//2240 2250//2250 1501//1501 -f 1501//1501 2250//2250 2249//2249 -f 1501//1501 2249//2249 1499//1499 -f 1499//1499 2249//2249 2247//2247 -f 1499//1499 2247//2247 2430//2430 -f 2430//2430 2247//2247 2245//2245 -f 2430//2430 2245//2245 1506//1506 -f 1506//1506 2245//2245 2244//2244 -f 1506//1506 2244//2244 1504//1504 -f 2431//2431 2432//2432 2433//2433 -f 2434//2434 2435//2435 2436//2436 -f 2436//2436 2435//2435 2437//2437 -f 2436//2436 2437//2437 2438//2438 -f 2438//2438 2437//2437 2439//2439 -f 2438//2438 2439//2439 2440//2440 -f 1287//1287 2434//2434 1288//1288 -f 1288//1288 2434//2434 2436//2436 -f 1288//1288 2436//2436 2407//2407 -f 2407//2407 2436//2436 2438//2438 -f 2407//2407 2438//2438 2408//2408 -f 2408//2408 2438//2438 2440//2440 -f 2408//2408 2440//2440 2409//2409 -f 2441//2441 2442//2442 2443//2443 -f 2443//2443 2442//2442 2444//2444 -f 2443//2443 2444//2444 2445//2445 -f 2445//2445 2444//2444 2446//2446 -f 2445//2445 2446//2446 2447//2447 -f 2432//2432 2431//2431 2448//2448 -f 2448//2448 2431//2431 2410//2410 -f 2448//2448 2410//2410 2441//2441 -f 1286//1286 2433//2433 1287//1287 -f 1287//1287 2433//2433 2432//2432 -f 1287//1287 2432//2432 2434//2434 -f 2434//2434 2432//2432 2448//2448 -f 2434//2434 2448//2448 2435//2435 -f 2435//2435 2448//2448 2441//2441 -f 2435//2435 2441//2441 2437//2437 -f 2437//2437 2441//2441 2443//2443 -f 2437//2437 2443//2443 2439//2439 -f 2439//2439 2443//2443 2445//2445 -f 2439//2439 2445//2445 2440//2440 -f 2440//2440 2445//2445 2447//2447 -f 2440//2440 2447//2447 2409//2409 -f 2409//2409 2447//2447 2428//2428 -f 2409//2409 2428//2428 2404//2404 -f 2404//2404 2428//2428 2427//2427 -f 2404//2404 2427//2427 2405//2405 -f 2405//2405 2427//2427 2399//2399 -f 2405//2405 2399//2399 2406//2406 -f 2406//2406 2399//2399 2400//2400 -f 2406//2406 2400//2400 2403//2403 -f 2403//2403 2400//2400 2397//2397 -f 2403//2403 2397//2397 2402//2402 -f 2402//2402 2397//2397 1290//1290 -f 2402//2402 1290//1290 1286//1286 -f 1286//1286 1290//1290 1289//1289 -f 1286//1286 1289//1289 2433//2433 -f 2433//2433 1289//1289 2396//2396 -f 2433//2433 2396//2396 2431//2431 -f 2431//2431 2396//2396 2395//2395 -f 2431//2431 2395//2395 2410//2410 -f 2410//2410 2395//2395 2393//2393 -f 2410//2410 2393//2393 2411//2411 -f 2411//2411 2393//2393 2392//2392 -f 2411//2411 2392//2392 2413//2413 -f 2413//2413 2392//2392 2391//2391 -f 2413//2413 2391//2391 2414//2414 -f 2414//2414 2391//2391 2390//2390 -f 2414//2414 2390//2390 2375//2375 -f 2375//2375 2390//2390 2388//2388 -f 2375//2375 2388//2388 2373//2373 -f 2373//2373 2388//2388 2387//2387 -f 2373//2373 2387//2387 2371//2371 -f 2371//2371 2387//2387 2398//2398 -f 2371//2371 2398//2398 2379//2379 -f 2379//2379 2398//2398 2399//2399 -f 2379//2379 2399//2399 2427//2427 -f 2449//2449 2450//2450 2451//2451 -f 2451//2451 2450//2450 2452//2452 -f 2451//2451 2452//2452 2453//2453 -f 2453//2453 2452//2452 2454//2454 -f 2453//2453 2454//2454 2455//2455 -f 2456//2456 2457//2457 2458//2458 -f 2458//2458 2457//2457 1283//1283 -f 2458//2458 1283//1283 2459//2459 -f 2459//2459 1283//1283 1285//1285 -f 2460//2460 2461//2461 2462//2462 -f 2462//2462 2461//2461 2455//2455 -f 2463//2463 2464//2464 1282//1282 -f 1281//1281 2465//2465 1282//1282 -f 1282//1282 2465//2465 2466//2466 -f 1282//1282 2466//2466 2463//2463 -f 2467//2467 2468//2468 2469//2469 -f 2470//2470 2467//2467 2471//2471 -f 2471//2471 2467//2467 2469//2469 -f 2471//2471 2469//2469 2472//2472 -f 2472//2472 2469//2469 2473//2473 -f 2474//2474 2475//2475 2476//2476 -f 1278//1278 1277//1277 2477//2477 -f 2477//2477 1277//1277 2478//2478 -f 2477//2477 2478//2478 2476//2476 -f 2476//2476 2475//2475 2477//2477 -f 2477//2477 2475//2475 2479//2479 -f 2477//2477 2479//2479 1278//1278 -f 1278//1278 2479//2479 2480//2480 -f 1278//1278 2480//2480 1279//1279 -f 2481//2481 2482//2482 2483//2483 -f 2483//2483 2482//2482 2484//2484 -f 2483//2483 2484//2484 2485//2485 -f 1285//1285 1280//1280 2459//2459 -f 2459//2459 1280//1280 1282//1282 -f 2459//2459 1282//1282 2458//2458 -f 2458//2458 1282//1282 2464//2464 -f 2458//2458 2464//2464 2456//2456 -f 2456//2456 2464//2464 2463//2463 -f 2456//2456 2463//2463 2486//2486 -f 2486//2486 2463//2463 2466//2466 -f 2486//2486 2466//2466 2487//2487 -f 2487//2487 2466//2466 2488//2488 -f 2474//2474 2473//2473 2475//2475 -f 2475//2475 2473//2473 2469//2469 -f 2475//2475 2469//2469 2479//2479 -f 2479//2479 2469//2469 2468//2468 -f 2479//2479 2468//2468 2480//2480 -f 2480//2480 2468//2468 2467//2467 -f 2480//2480 2467//2467 2460//2460 -f 2460//2460 2467//2467 2470//2470 -f 2460//2460 2470//2470 2461//2461 -f 1332//1332 2122//2122 1333//1333 -f 1333//1333 2122//2122 2124//2124 -f 1333//1333 2124//2124 2106//2106 -f 2106//2106 2124//2124 2125//2125 -f 2106//2106 2125//2125 2107//2107 -f 2107//2107 2125//2125 2489//2489 -f 2107//2107 2489//2489 2108//2108 -f 2108//2108 2489//2489 2113//2113 -f 2108//2108 2113//2113 2109//2109 -f 2109//2109 2113//2113 2112//2112 -f 2109//2109 2112//2112 2110//2110 -f 2110//2110 2112//2112 2101//2101 -f 2110//2110 2101//2101 2111//2111 -f 2111//2111 2101//2101 2099//2099 -f 2111//2111 2099//2099 2096//2096 -f 2096//2096 2099//2099 2097//2097 -f 2096//2096 2097//2097 1351//1351 -f 1351//1351 2097//2097 1347//1347 -f 1351//1351 1347//1347 1352//1352 -f 1352//1352 1347//1347 1349//1349 -f 1352//1352 1349//1349 2055//2055 -f 2055//2055 1349//1349 1855//1855 -f 2055//2055 1855//1855 2056//2056 -f 2056//2056 1855//1855 1854//1854 -f 2056//2056 1854//1854 2219//2219 -f 2219//2219 1854//1854 1853//1853 -f 2219//2219 1853//1853 2220//2220 -f 2220//2220 1853//1853 1502//1502 -f 2220//2220 1502//1502 2257//2257 -f 2257//2257 1502//1502 1504//1504 -f 2257//2257 1504//1504 2258//2258 -f 2258//2258 1504//1504 2244//2244 -f 2258//2258 2244//2244 2301//2301 -f 2301//2301 2244//2244 2246//2246 -f 2301//2301 2246//2246 2416//2416 -f 2416//2416 2246//2246 2248//2248 -f 2416//2416 2248//2248 2415//2415 -f 2415//2415 2248//2248 2250//2250 -f 2415//2415 2250//2250 2412//2412 -f 2412//2412 2250//2250 2429//2429 -f 2412//2412 2429//2429 2410//2410 -f 2490//2490 2491//2491 2492//2492 -f 2492//2492 2491//2491 2493//2493 -f 2492//2492 2493//2493 2494//2494 -f 2494//2494 2493//2493 2495//2495 -f 2496//2496 2497//2497 2498//2498 -f 2499//2499 2497//2497 2500//2500 -f 2500//2500 2497//2497 2496//2496 -f 2500//2500 2496//2496 2501//2501 -f 2502//2502 2503//2503 2504//2504 -f 2505//2505 2506//2506 2507//2507 -f 2507//2507 2506//2506 2508//2508 -f 2509//2509 2510//2510 2511//2511 -f 2503//2503 2508//2508 2504//2504 -f 2504//2504 2508//2508 2506//2506 -f 2504//2504 2506//2506 2512//2512 -f 2512//2512 2506//2506 2505//2505 -f 2481//2481 2513//2513 2514//2514 -f 2514//2514 2513//2513 2499//2499 -f 2515//2515 2516//2516 2517//2517 -f 2518//2518 2519//2519 2520//2520 -f 2521//2521 2522//2522 2517//2517 -f 2517//2517 2522//2522 2523//2523 -f 2517//2517 2523//2523 2524//2524 -f 2516//2516 2525//2525 2517//2517 -f 2517//2517 2525//2525 2526//2526 -f 2517//2517 2526//2526 2521//2521 -f 2521//2521 2526//2526 2527//2527 -f 2528//2528 2529//2529 2530//2530 -f 2530//2530 2529//2529 2531//2531 -f 2530//2530 2531//2531 2532//2532 -f 2532//2532 2531//2531 1274//1274 -f 2532//2532 1274//1274 2533//2533 -f 2533//2533 1274//1274 1276//1276 -f 2487//2487 2534//2534 2486//2486 -f 2486//2486 2534//2534 2449//2449 -f 2486//2486 2449//2449 2456//2456 -f 2456//2456 2449//2449 2451//2451 -f 2456//2456 2451//2451 2457//2457 -f 2457//2457 2451//2451 2453//2453 -f 2457//2457 2453//2453 1283//1283 -f 1283//1283 2453//2453 2455//2455 -f 1283//1283 2455//2455 1284//1284 -f 1284//1284 2455//2455 2461//2461 -f 1284//1284 2461//2461 1285//1285 -f 1285//1285 2461//2461 2470//2470 -f 1285//1285 2470//2470 1280//1280 -f 1280//1280 2470//2470 2471//2471 -f 1280//1280 2471//2471 1281//1281 -f 1281//1281 2471//2471 2472//2472 -f 1281//1281 2472//2472 2465//2465 -f 2465//2465 2472//2472 2473//2473 -f 2465//2465 2473//2473 2466//2466 -f 2466//2466 2473//2473 2474//2474 -f 2466//2466 2474//2474 2488//2488 -f 2488//2488 2474//2474 2476//2476 -f 2488//2488 2476//2476 2487//2487 -f 2535//2535 2498//2498 2490//2490 -f 2490//2490 2498//2498 2497//2497 -f 2490//2490 2497//2497 2491//2491 -f 2491//2491 2497//2497 2499//2499 -f 2491//2491 2499//2499 2493//2493 -f 2493//2493 2499//2499 2513//2513 -f 2493//2493 2513//2513 2495//2495 -f 2495//2495 2513//2513 2481//2481 -f 2495//2495 2481//2481 2494//2494 -f 2494//2494 2481//2481 2483//2483 -f 2494//2494 2483//2483 2492//2492 -f 2492//2492 2483//2483 2485//2485 -f 2492//2492 2485//2485 2490//2490 -f 2490//2490 2485//2485 2535//2535 -f 2536//2536 2537//2537 2538//2538 -f 2538//2538 2537//2537 2539//2539 -f 2539//2539 2540//2540 2538//2538 -f 2538//2538 2540//2540 2541//2541 -f 2538//2538 2541//2541 2536//2536 -f 2536//2536 2542//2542 2537//2537 -f 2537//2537 2542//2542 2543//2543 -f 2537//2537 2543//2543 2544//2544 -f 2544//2544 2543//2543 2545//2545 -f 2544//2544 2545//2545 2546//2546 -f 2547//2547 2548//2548 2549//2549 -f 2550//2550 2549//2549 2551//2551 -f 2551//2551 2549//2549 2548//2548 -f 2551//2551 2548//2548 2552//2552 -f 2552//2552 1272//1272 2551//2551 -f 2551//2551 1272//1272 1271//1271 -f 2551//2551 1271//1271 2550//2550 -f 2550//2550 1271//1271 2553//2553 -f 2550//2550 2553//2553 2554//2554 -f 2555//2555 2556//2556 2557//2557 -f 2557//2557 2556//2556 2558//2558 -f 2559//2559 2560//2560 2558//2558 -f 2558//2558 2560//2560 2561//2561 -f 2558//2558 2561//2561 2557//2557 -f 2557//2557 2561//2561 2562//2562 -f 2563//2563 2509//2509 1276//1276 -f 1276//1276 2509//2509 2511//2511 -f 1276//1276 2511//2511 2533//2533 -f 2533//2533 2511//2511 2564//2564 -f 2533//2533 2564//2564 2532//2532 -f 2532//2532 2564//2564 2565//2565 -f 2532//2532 2565//2565 2530//2530 -f 2530//2530 2565//2565 2522//2522 -f 2530//2530 2522//2522 2528//2528 -f 2562//2562 2566//2566 2557//2557 -f 2557//2557 2566//2566 2567//2567 -f 2557//2557 2567//2567 2555//2555 -f 2512//2512 2501//2501 2504//2504 -f 2504//2504 2501//2501 2496//2496 -f 2504//2504 2496//2496 2502//2502 -f 2502//2502 2496//2496 2498//2498 -f 2502//2502 2498//2498 2568//2568 -f 2568//2568 2498//2498 2535//2535 -f 2568//2568 2535//2535 1279//1279 -f 1279//1279 2535//2535 2485//2485 -f 1279//1279 2485//2485 1277//1277 -f 1277//1277 2485//2485 2484//2484 -f 1277//1277 2484//2484 2478//2478 -f 2478//2478 2484//2484 2482//2482 -f 2478//2478 2482//2482 2476//2476 -f 2476//2476 2482//2482 2481//2481 -f 2476//2476 2481//2481 2487//2487 -f 2487//2487 2481//2481 2514//2514 -f 2487//2487 2514//2514 2534//2534 -f 2534//2534 2514//2514 2569//2569 -f 2534//2534 2569//2569 2570//2570 -f 2518//2518 2571//2571 2519//2519 -f 2519//2519 2571//2571 2572//2572 -f 2519//2519 2572//2572 2520//2520 -f 2520//2520 2572//2572 2573//2573 -f 2574//2574 2575//2575 2527//2527 -f 2527//2527 2575//2575 2571//2571 -f 2527//2527 2571//2571 2521//2521 -f 2521//2521 2571//2571 2518//2518 -f 2521//2521 2518//2518 2522//2522 -f 2522//2522 2518//2518 2520//2520 -f 2522//2522 2520//2520 2528//2528 -f 2528//2528 2520//2520 2573//2573 -f 2528//2528 2573//2573 2529//2529 -f 1275//1275 1274//1274 2540//2540 -f 2540//2540 1274//1274 2531//2531 -f 2540//2540 2531//2531 2541//2541 -f 2541//2541 2531//2531 2529//2529 -f 2541//2541 2529//2529 2536//2536 -f 2536//2536 2529//2529 2573//2573 -f 2536//2536 2573//2573 2542//2542 -f 2542//2542 2573//2573 2572//2572 -f 2542//2542 2572//2572 2543//2543 -f 2543//2543 2572//2572 2571//2571 -f 2543//2543 2571//2571 2545//2545 -f 2545//2545 2571//2571 2575//2575 -f 2545//2545 2575//2575 2546//2546 -f 2576//2576 2577//2577 2578//2578 -f 2578//2578 2577//2577 2579//2579 -f 2578//2578 2579//2579 2580//2580 -f 2581//2581 2582//2582 2583//2583 -f 2583//2583 2582//2582 2584//2584 -f 1273//1273 2576//2576 1271//1271 -f 1271//1271 2576//2576 2578//2578 -f 1271//1271 2578//2578 2553//2553 -f 2553//2553 2578//2578 2580//2580 -f 2553//2553 2580//2580 2554//2554 -f 2554//2554 2580//2580 2562//2562 -f 2554//2554 2562//2562 2550//2550 -f 2550//2550 2562//2562 2561//2561 -f 2550//2550 2561//2561 2549//2549 -f 2549//2549 2561//2561 2560//2560 -f 2549//2549 2560//2560 2547//2547 -f 2547//2547 2560//2560 2559//2559 -f 2585//2585 2586//2586 2587//2587 -f 2587//2587 2586//2586 2574//2574 -f 2587//2587 2574//2574 2588//2588 -f 2589//2589 2590//2590 2591//2591 -f 2591//2591 2590//2590 2581//2581 -f 2591//2591 2581//2581 2585//2585 -f 2585//2585 2581//2581 2583//2583 -f 2585//2585 2583//2583 2586//2586 -f 2586//2586 2583//2583 2584//2584 -f 2586//2586 2584//2584 2574//2574 -f 2592//2592 2593//2593 1268//1268 -f 1268//1268 2593//2593 2594//2594 -f 1268//1268 2594//2594 1269//1269 -f 2595//2595 2596//2596 2597//2597 -f 2597//2597 2596//2596 2598//2598 -f 2599//2599 2600//2600 2601//2601 -f 2592//2592 1268//1268 2602//2602 -f 2602//2602 1268//1268 1270//1270 -f 2602//2602 1270//1270 2603//2603 -f 1266//1266 1265//1265 2604//2604 -f 2594//2594 2599//2599 1269//1269 -f 1269//1269 2599//2599 2601//2601 -f 1269//1269 2601//2601 1270//1270 -f 1270//1270 2601//2601 2604//2604 -f 1270//1270 2604//2604 2603//2603 -f 2603//2603 2604//2604 1265//1265 -f 2603//2603 1265//1265 2602//2602 -f 2605//2605 2606//2606 2607//2607 -f 2607//2607 2606//2606 2608//2608 -f 2607//2607 2608//2608 2609//2609 -f 2589//2589 2610//2610 2605//2605 -f 2605//2605 2610//2610 2611//2611 -f 2605//2605 2611//2611 2606//2606 -f 2606//2606 2611//2611 2612//2612 -f 2606//2606 2612//2612 2608//2608 -f 2608//2608 2612//2612 2613//2613 -f 2608//2608 2613//2613 2609//2609 -f 1255//1255 2614//2614 1256//1256 -f 1256//1256 2614//2614 2615//2615 -f 1256//1256 2615//2615 2616//2616 -f 2616//2616 2615//2615 2588//2588 -f 2617//2617 2618//2618 2609//2609 -f 2609//2609 2618//2618 2619//2619 -f 2609//2609 2619//2619 2607//2607 -f 2607//2607 2619//2619 2595//2595 -f 2607//2607 2595//2595 2605//2605 -f 2605//2605 2595//2595 2597//2597 -f 2605//2605 2597//2597 2589//2589 -f 2589//2589 2597//2597 2598//2598 -f 2589//2589 2598//2598 2590//2590 -f 2590//2590 2598//2598 2596//2596 -f 2590//2590 2596//2596 2581//2581 -f 2581//2581 2596//2596 2620//2620 -f 2581//2581 2620//2620 2582//2582 -f 1491//1491 1584//1584 1492//1492 -f 1492//1492 1584//1584 1583//1583 -f 1492//1492 1583//1583 2621//2621 -f 2621//2621 1583//1583 1582//1582 -f 2621//2621 1582//1582 1404//1404 -f 1404//1404 1582//1582 1581//1581 -f 1404//1404 1581//1581 1405//1405 -f 1405//1405 1581//1581 1580//1580 -f 1405//1405 1580//1580 1585//1585 -f 1585//1585 1580//1580 1578//1578 -f 1585//1585 1578//1578 1587//1587 -f 1587//1587 1578//1578 1655//1655 -f 1587//1587 1655//1655 1589//1589 -f 1589//1589 1655//1655 1672//1672 -f 1589//1589 1672//1672 1590//1590 -f 1590//1590 1672//1672 1685//1685 -f 2622//2622 1261//1261 2623//2623 -f 2623//2623 1261//1261 1259//1259 -f 2623//2623 1259//1259 2624//2624 -f 2624//2624 1259//1259 1258//1258 -f 2624//2624 1258//1258 2625//2625 -f 2625//2625 1258//1258 2626//2626 -f 2625//2625 2626//2626 2627//2627 -f 2574//2574 2527//2527 2588//2588 -f 2588//2588 2527//2527 2628//2628 -f 2588//2588 2628//2628 2616//2616 -f 2616//2616 2628//2628 2629//2629 -f 2616//2616 2629//2629 1256//1256 -f 1256//1256 2629//2629 2630//2630 -f 1256//1256 2630//2630 1257//1257 -f 2631//2631 2632//2632 2633//2633 -f 2239//2239 2622//2622 2241//2241 -f 2241//2241 2622//2622 2623//2623 -f 2241//2241 2623//2623 2243//2243 -f 2243//2243 2623//2623 2624//2624 -f 2243//2243 2624//2624 2634//2634 -f 2634//2634 2624//2624 2625//2625 -f 2634//2634 2625//2625 2635//2635 -f 2635//2635 2625//2625 2627//2627 -f 2635//2635 2627//2627 2636//2636 -f 1258//1258 2637//2637 2626//2626 -f 2626//2626 2637//2637 2638//2638 -f 2626//2626 2638//2638 2627//2627 -f 2627//2627 2638//2638 2639//2639 -f 2627//2627 2639//2639 2636//2636 -f 2636//2636 2639//2639 2640//2640 -f 2636//2636 2640//2640 2641//2641 -f 2641//2641 2640//2640 2642//2642 -f 1500//1500 2643//2643 1501//1501 -f 1501//1501 2643//2643 2644//2644 -f 1501//1501 2644//2644 2239//2239 -f 2239//2239 2644//2644 2645//2645 -f 2239//2239 2645//2645 2622//2622 -f 2622//2622 2645//2645 2646//2646 -f 2622//2622 2646//2646 1261//1261 -f 1261//1261 2646//2646 1495//1495 -f 1261//1261 1495//1495 1260//1260 -f 1260//1260 1495//1495 1494//1494 -f 1260//1260 1494//1494 1258//1258 -f 1258//1258 1494//1494 1492//1492 -f 1258//1258 1492//1492 2637//2637 -f 2637//2637 1492//1492 2621//2621 -f 2637//2637 2621//2621 2638//2638 -f 2638//2638 2621//2621 1404//1404 -f 2638//2638 1404//1404 2639//2639 -f 2639//2639 1404//1404 1403//1403 -f 2639//2639 1403//1403 2640//2640 -f 2640//2640 1403//1403 1401//1401 -f 2640//2640 1401//1401 2642//2642 -f 2642//2642 1401//1401 1400//1400 -f 1696//1696 2647//2647 1698//1698 -f 1698//1698 2647//2647 2648//2648 -f 1698//1698 2648//2648 1700//1700 -f 1700//1700 2648//2648 2649//2649 -f 1700//1700 2649//2649 1701//1701 -f 1701//1701 2649//2649 2650//2650 -f 1701//1701 2650//2650 1834//1834 -f 1834//1834 2650//2650 2651//2651 -f 1834//1834 2651//2651 1835//1835 -f 1835//1835 2651//2651 2652//2652 -f 1835//1835 2652//2652 1840//1840 -f 1840//1840 2652//2652 2653//2653 -f 1840//1840 2653//2653 2654//2654 -f 2647//2647 1841//1841 2648//2648 -f 2648//2648 1841//1841 1842//1842 -f 2648//2648 1842//1842 2649//2649 -f 2649//2649 1842//1842 1843//1843 -f 2649//2649 1843//1843 2650//2650 -f 2650//2650 1843//1843 1848//1848 -f 2650//2650 1848//1848 2651//2651 -f 2651//2651 1848//1848 1849//1849 -f 2651//2651 1849//1849 2652//2652 -f 2652//2652 1849//1849 2655//2655 -f 2652//2652 2655//2655 2653//2653 -f 2653//2653 2655//2655 2656//2656 -f 2653//2653 2656//2656 2654//2654 -f 2654//2654 2656//2656 2657//2657 -f 2654//2654 2657//2657 2658//2658 -f 1436//1436 1435//1435 1852//1852 -f 1852//1852 1435//1435 1859//1859 -f 1852//1852 1859//1859 1851//1851 -f 1851//1851 1859//1859 1387//1387 -f 1851//1851 1387//1387 1850//1850 -f 1850//1850 1387//1387 1389//1389 -f 1850//1850 1389//1389 1849//1849 -f 1849//1849 1389//1389 1390//1390 -f 1849//1849 1390//1390 2655//2655 -f 2655//2655 1390//1390 1856//1856 -f 2655//2655 1856//1856 2656//2656 -f 2656//2656 1856//1856 2238//2238 -f 2656//2656 2238//2238 2657//2657 -f 2657//2657 2238//2238 2659//2659 -f 2657//2657 2659//2659 2658//2658 -f 2660//2660 2661//2661 2662//2662 -f 2663//2663 1836//1836 2664//2664 -f 2664//2664 1836//1836 1837//1837 -f 2664//2664 1837//1837 2665//2665 -f 2665//2665 1837//1837 1838//1838 -f 2665//2665 1838//1838 2666//2666 -f 2666//2666 1838//1838 1839//1839 -f 2666//2666 1839//1839 2667//2667 -f 2667//2667 1839//1839 1840//1840 -f 2667//2667 1840//1840 2668//2668 -f 2668//2668 1840//1840 2654//2654 -f 2668//2668 2654//2654 2669//2669 -f 2669//2669 2654//2654 2658//2658 -f 2662//2662 2661//2661 2670//2670 -f 2670//2670 2661//2661 2671//2671 -f 2670//2670 2671//2671 2672//2672 -f 2672//2672 2671//2671 2673//2673 -f 2672//2672 2673//2673 2674//2674 -f 2675//2675 2676//2676 2677//2677 -f 2677//2677 2676//2676 1833//1833 -f 2677//2677 1833//1833 2678//2678 -f 2678//2678 1833//1833 1832//1832 -f 2678//2678 1832//1832 2679//2679 -f 2679//2679 1832//1832 1831//1831 -f 2679//2679 1831//1831 2680//2680 -f 2680//2680 1831//1831 1801//1801 -f 2680//2680 1801//1801 2681//2681 -f 2681//2681 1801//1801 1800//1800 -f 2681//2681 1800//1800 2682//2682 -f 2683//2683 1253//1253 2684//2684 -f 2684//2684 1253//1253 1252//1252 -f 2684//2684 1252//1252 2685//2685 -f 2686//2686 2687//2687 2684//2684 -f 2684//2684 2687//2687 2688//2688 -f 2684//2684 2688//2688 2683//2683 -f 2686//2686 2684//2684 2689//2689 -f 2689//2689 2684//2684 2685//2685 -f 2689//2689 2685//2685 2690//2690 -f 2690//2690 2685//2685 2691//2691 -f 2690//2690 2691//2691 2692//2692 -f 2693//2693 2686//2686 2694//2694 -f 2694//2694 2686//2686 2689//2689 -f 2694//2694 2689//2689 2695//2695 -f 2695//2695 2689//2689 2690//2690 -f 2695//2695 2690//2690 2696//2696 -f 2696//2696 2690//2690 2692//2692 -f 2696//2696 2692//2692 2697//2697 -f 2697//2697 2692//2692 2698//2698 -f 2697//2697 2698//2698 1251//1251 -f 2659//2659 2660//2660 2658//2658 -f 2658//2658 2660//2660 2662//2662 -f 2658//2658 2662//2662 2669//2669 -f 2669//2669 2662//2662 2670//2670 -f 2669//2669 2670//2670 2699//2699 -f 2699//2699 2670//2670 2672//2672 -f 2699//2699 2672//2672 2700//2700 -f 2700//2700 2672//2672 2674//2674 -f 2700//2700 2674//2674 2701//2701 -f 1751//1751 2682//2682 1752//1752 -f 1752//1752 2682//2682 1800//1800 -f 1752//1752 1800//1800 1753//1753 -f 1753//1753 1800//1800 1392//1392 -f 1753//1753 1392//1392 1802//1802 -f 1802//1802 1392//1392 1391//1391 -f 1802//1802 1391//1391 1825//1825 -f 1825//1825 1391//1391 1820//1820 -f 1825//1825 1820//1820 1826//1826 -f 1826//1826 1820//1820 1822//1822 -f 1826//1826 1822//1822 2702//2702 -f 2702//2702 1822//1822 1824//1824 -f 2702//2702 1824//1824 2703//2703 -f 2703//2703 1824//1824 1833//1833 -f 2703//2703 1833//1833 2704//2704 -f 2704//2704 1833//1833 2676//2676 -f 1749//1749 2663//2663 1750//1750 -f 1750//1750 2663//2663 2664//2664 -f 1750//1750 2664//2664 1751//1751 -f 1751//1751 2664//2664 2665//2665 -f 1751//1751 2665//2665 2682//2682 -f 2682//2682 2665//2665 2666//2666 -f 2682//2682 2666//2666 2681//2681 -f 2681//2681 2666//2666 2667//2667 -f 2681//2681 2667//2667 2680//2680 -f 2680//2680 2667//2667 2668//2668 -f 2680//2680 2668//2668 2679//2679 -f 2679//2679 2668//2668 2669//2669 -f 2679//2679 2669//2669 2678//2678 -f 2678//2678 2669//2669 2699//2699 -f 2678//2678 2699//2699 2677//2677 -f 2677//2677 2699//2699 2700//2700 -f 2677//2677 2700//2700 2675//2675 -f 2675//2675 2700//2700 2701//2701 -f 1251//1251 1250//1250 2697//2697 -f 2697//2697 1250//1250 1518//1518 -f 2697//2697 1518//1518 2696//2696 -f 2696//2696 1518//1518 1510//1510 -f 2696//2696 1510//1510 2695//2695 -f 2695//2695 1510//1510 1509//1509 -f 2695//2695 1509//1509 2694//2694 -f 2694//2694 1509//1509 1508//1508 -f 2694//2694 1508//1508 2693//2693 -f 2693//2693 1508//1508 1507//1507 -f 2693//2693 1507//1507 1511//1511 -f 1511//1511 1507//1507 1217//1217 -f 1511//1511 1217//1217 1216//1216 -f 2236//2236 2118//2118 2176//2176 -f 2176//2176 2118//2118 2182//2182 -f 2176//2176 2182//2182 2177//2177 -f 2177//2177 2182//2182 2705//2705 -f 2177//2177 2705//2705 2706//2706 -f 2706//2706 2705//2705 2707//2707 -f 2706//2706 2707//2707 2708//2708 -f 2708//2708 2707//2707 2709//2709 -f 2708//2708 2709//2709 2710//2710 -f 2710//2710 2709//2709 2711//2711 -f 2710//2710 2711//2711 1234//1234 -f 1234//1234 2711//2711 1235//1235 -f 2262//2262 2273//2273 2260//2260 -f 2260//2260 2273//2273 2275//2275 -f 2260//2260 2275//2275 2261//2261 -f 2261//2261 2275//2275 2277//2277 -f 2261//2261 2277//2277 2270//2270 -f 2270//2270 2277//2277 2279//2279 -f 2270//2270 2279//2279 2271//2271 -f 2271//2271 2279//2279 2280//2280 -f 2271//2271 2280//2280 1317//1317 -f 1317//1317 2280//2280 2302//2302 -f 1317//1317 2302//2302 2712//2712 -f 2712//2712 2302//2302 2304//2304 -f 2712//2712 2304//2304 2713//2713 -f 2713//2713 2304//2304 2425//2425 -f 2713//2713 2425//2425 2714//2714 -f 2714//2714 2425//2425 2426//2426 -f 2714//2714 2426//2426 2715//2715 -f 2462//2462 2716//2716 2460//2460 -f 2460//2460 2716//2716 2526//2526 -f 2460//2460 2526//2526 2480//2480 -f 2480//2480 2526//2526 2525//2525 -f 2480//2480 2525//2525 1279//1279 -f 1279//1279 2525//2525 2516//2516 -f 1279//1279 2516//2516 2568//2568 -f 2568//2568 2516//2516 2515//2515 -f 2568//2568 2515//2515 2502//2502 -f 2502//2502 2515//2515 2517//2517 -f 2502//2502 2517//2517 2503//2503 -f 2503//2503 2517//2517 2524//2524 -f 2503//2503 2524//2524 2508//2508 -f 2508//2508 2524//2524 2523//2523 -f 2508//2508 2523//2523 2507//2507 -f 2507//2507 2523//2523 2522//2522 -f 2507//2507 2522//2522 2505//2505 -f 2505//2505 2522//2522 2565//2565 -f 2505//2505 2565//2565 2512//2512 -f 2512//2512 2565//2565 2564//2564 -f 2512//2512 2564//2564 2501//2501 -f 2501//2501 2564//2564 2511//2511 -f 2501//2501 2511//2511 2500//2500 -f 2500//2500 2511//2511 2510//2510 -f 2500//2500 2510//2510 2499//2499 -f 2499//2499 2510//2510 2509//2509 -f 2499//2499 2509//2509 2514//2514 -f 2514//2514 2509//2509 2563//2563 -f 2514//2514 2563//2563 2569//2569 -f 2569//2569 2563//2563 2717//2717 -f 2569//2569 2717//2717 2570//2570 -f 2570//2570 2717//2717 2718//2718 -f 2570//2570 2718//2718 2719//2719 -f 2218//2218 2214//2214 2170//2170 -f 2170//2170 2214//2214 2213//2213 -f 2170//2170 2213//2213 2171//2171 -f 2171//2171 2213//2213 2720//2720 -f 2171//2171 2720//2720 2721//2721 -f 2721//2721 2720//2720 2722//2722 -f 2721//2721 2722//2722 2723//2723 -f 2723//2723 2722//2722 2724//2724 -f 2723//2723 2724//2724 2725//2725 -f 2725//2725 2724//2724 2726//2726 -f 2725//2725 2726//2726 2727//2727 -f 2727//2727 2726//2726 2728//2728 -f 2727//2727 2728//2728 1236//1236 -f 1236//1236 2728//2728 1210//1210 -f 2641//2641 1257//1257 2636//2636 -f 2636//2636 1257//1257 2630//2630 -f 2636//2636 2630//2630 2635//2635 -f 2635//2635 2630//2630 2629//2629 -f 2635//2635 2629//2629 2634//2634 -f 2634//2634 2629//2629 2628//2628 -f 2634//2634 2628//2628 2243//2243 -f 2243//2243 2628//2628 2527//2527 -f 2243//2243 2527//2527 2242//2242 -f 2242//2242 2527//2527 2526//2526 -f 2242//2242 2526//2526 2429//2429 -f 2429//2429 2526//2526 2716//2716 -f 2429//2429 2716//2716 2410//2410 -f 2410//2410 2716//2716 2462//2462 -f 2410//2410 2462//2462 2441//2441 -f 2441//2441 2462//2462 2455//2455 -f 2441//2441 2455//2455 2442//2442 -f 2442//2442 2455//2455 2454//2454 -f 2442//2442 2454//2454 2444//2444 -f 2444//2444 2454//2454 2452//2452 -f 2444//2444 2452//2452 2446//2446 -f 2446//2446 2452//2452 2450//2450 -f 2446//2446 2450//2450 2447//2447 -f 2447//2447 2450//2450 2449//2449 -f 2447//2447 2449//2449 2428//2428 -f 2428//2428 2449//2449 2534//2534 -f 2428//2428 2534//2534 1263//1263 -f 1263//1263 2534//2534 2570//2570 -f 1263//1263 2570//2570 1264//1264 -f 1264//1264 2570//2570 2719//2719 -f 1264//1264 2719//2719 2729//2729 -f 2729//2729 2719//2719 2730//2730 -f 2729//2729 2730//2730 2731//2731 -f 2731//2731 2730//2730 2732//2732 -f 2733//2733 2732//2732 2734//2734 -f 2734//2734 2732//2732 2730//2730 -f 2734//2734 2730//2730 2735//2735 -f 2735//2735 2730//2730 2719//2719 -f 2735//2735 2719//2719 2736//2736 -f 2736//2736 2719//2719 2718//2718 -f 2226//2226 1322//1322 2227//2227 -f 2227//2227 1322//1322 1321//1321 -f 2227//2227 1321//1321 2235//2235 -f 2235//2235 1321//1321 2224//2224 -f 2235//2235 2224//2224 2234//2234 -f 2234//2234 2224//2224 2225//2225 -f 2234//2234 2225//2225 2233//2233 -f 2233//2233 2225//2225 2223//2223 -f 2233//2233 2223//2223 2232//2232 -f 2232//2232 2223//2223 2222//2222 -f 2232//2232 2222//2222 2220//2220 -f 2232//2232 2220//2220 2231//2231 -f 2231//2231 2220//2220 2257//2257 -f 2231//2231 2257//2257 2230//2230 -f 2230//2230 2257//2257 2256//2256 -f 2230//2230 2256//2256 2254//2254 -f 2230//2230 2254//2254 2228//2228 -f 2228//2228 2254//2254 2226//2226 -f 2226//2226 2254//2254 1320//1320 -f 2226//2226 1320//1320 1322//1322 -f 1322//1322 1320//1320 1318//1318 -f 1322//1322 1318//1318 1323//1323 -f 1323//1323 1318//1318 1317//1317 -f 1323//1323 1317//1317 2737//2737 -f 2737//2737 1317//1317 2712//2712 -f 2737//2737 2712//2712 2738//2738 -f 2738//2738 2712//2712 2713//2713 -f 2738//2738 2713//2713 2739//2739 -f 2739//2739 2713//2713 2714//2714 -f 2739//2739 2714//2714 2740//2740 -f 2740//2740 2714//2714 2715//2715 -f 2740//2740 2715//2715 2741//2741 -f 2741//2741 2715//2715 2742//2742 -f 2741//2741 2742//2742 1417//1417 -f 1417//1417 2742//2742 2743//2743 -f 1417//1417 2743//2743 1221//1221 -f 1221//1221 2743//2743 1222//1222 -f 2744//2744 2745//2745 2746//2746 -f 2746//2746 2745//2745 2747//2747 -f 2746//2746 2747//2747 2748//2748 -f 2748//2748 2747//2747 2749//2749 -f 2748//2748 2749//2749 2750//2750 -f 2750//2750 2749//2749 2751//2751 -f 2750//2750 2751//2751 2618//2618 -f 2613//2613 2752//2752 2609//2609 -f 2609//2609 2752//2752 2753//2753 -f 2609//2609 2753//2753 2617//2617 -f 2617//2617 2753//2753 2633//2633 -f 2617//2617 2633//2633 2618//2618 -f 2618//2618 2633//2633 2632//2632 -f 2618//2618 2632//2632 2750//2750 -f 2750//2750 2632//2632 2631//2631 -f 2750//2750 2631//2631 2748//2748 -f 2748//2748 2631//2631 2754//2754 -f 2748//2748 2754//2754 2746//2746 -f 2746//2746 2754//2754 1597//1597 -f 2746//2746 1597//1597 2744//2744 -f 2744//2744 1597//1597 1595//1595 -f 2744//2744 1595//1595 2755//2755 -f 2755//2755 1595//1595 1593//1593 -f 2756//2756 2757//2757 2758//2758 -f 2758//2758 2757//2757 2759//2759 -f 2758//2758 2759//2759 2760//2760 -f 2760//2760 2759//2759 2761//2761 -f 2760//2760 2761//2761 2762//2762 -f 2762//2762 2761//2761 2763//2763 -f 2762//2762 2763//2763 2764//2764 -f 2755//2755 2756//2756 2744//2744 -f 2744//2744 2756//2756 2758//2758 -f 2744//2744 2758//2758 2745//2745 -f 2745//2745 2758//2758 2760//2760 -f 2745//2745 2760//2760 2747//2747 -f 2747//2747 2760//2760 2762//2762 -f 2747//2747 2762//2762 2749//2749 -f 2749//2749 2762//2762 2764//2764 -f 2749//2749 2764//2764 2751//2751 -f 2765//2765 2763//2763 2766//2766 -f 2766//2766 2763//2763 2761//2761 -f 2766//2766 2761//2761 2767//2767 -f 2767//2767 2761//2761 2759//2759 -f 2767//2767 2759//2759 2768//2768 -f 2768//2768 2759//2759 2757//2757 -f 2768//2768 2757//2757 2769//2769 -f 2769//2769 2757//2757 2756//2756 -f 2769//2769 2756//2756 2770//2770 -f 2770//2770 2756//2756 2755//2755 -f 2770//2770 2755//2755 2771//2771 -f 2771//2771 2755//2755 1593//1593 -f 2771//2771 1593//1593 2772//2772 -f 2772//2772 1593//1593 1592//1592 -f 2772//2772 1592//1592 2773//2773 -f 2183//2183 2175//2175 2184//2184 -f 2184//2184 2175//2175 2174//2174 -f 2184//2184 2174//2174 2180//2180 -f 2180//2180 2174//2174 2159//2159 -f 2180//2180 2159//2159 2181//2181 -f 2181//2181 2159//2159 2161//2161 -f 2181//2181 2161//2161 2182//2182 -f 2182//2182 2161//2161 2171//2171 -f 2182//2182 2171//2171 2705//2705 -f 2705//2705 2171//2171 2721//2721 -f 2705//2705 2721//2721 2707//2707 -f 2707//2707 2721//2721 2723//2723 -f 2707//2707 2723//2723 2709//2709 -f 2709//2709 2723//2723 2725//2725 -f 2709//2709 2725//2725 2711//2711 -f 2711//2711 2725//2725 2727//2727 -f 2711//2711 2727//2727 1235//1235 -f 1235//1235 2727//2727 1236//1236 -f 1223//1223 2733//2733 1517//1517 -f 1517//1517 2733//2733 2734//2734 -f 1517//1517 2734//2734 2765//2765 -f 2765//2765 2734//2734 2735//2735 -f 2765//2765 2735//2735 2763//2763 -f 2763//2763 2735//2735 2736//2736 -f 2763//2763 2736//2736 2764//2764 -f 2764//2764 2736//2736 2718//2718 -f 2764//2764 2718//2718 2751//2751 -f 2751//2751 2718//2718 2717//2717 -f 2751//2751 2717//2717 2618//2618 -f 2618//2618 2717//2717 2567//2567 -f 2618//2618 2567//2567 2619//2619 -f 2619//2619 2567//2567 2566//2566 -f 2619//2619 2566//2566 2595//2595 -f 2595//2595 2566//2566 2562//2562 -f 2595//2595 2562//2562 2596//2596 -f 2596//2596 2562//2562 2580//2580 -f 2596//2596 2580//2580 2620//2620 -f 2620//2620 2580//2580 2579//2579 -f 2620//2620 2579//2579 2582//2582 -f 2582//2582 2579//2579 2577//2577 -f 2582//2582 2577//2577 2584//2584 -f 2584//2584 2577//2577 2576//2576 -f 2584//2584 2576//2576 2574//2574 -f 2574//2574 2576//2576 1273//1273 -f 2574//2574 1273//1273 2575//2575 -f 2575//2575 1273//1273 1272//1272 -f 2575//2575 1272//1272 2546//2546 -f 2546//2546 1272//1272 2552//2552 -f 2546//2546 2552//2552 2544//2544 -f 2544//2544 2552//2552 2548//2548 -f 2544//2544 2548//2548 2537//2537 -f 2537//2537 2548//2548 2547//2547 -f 2537//2537 2547//2547 2539//2539 -f 2539//2539 2547//2547 2559//2559 -f 2539//2539 2559//2559 2540//2540 -f 2540//2540 2559//2559 2558//2558 -f 2540//2540 2558//2558 1275//1275 -f 1275//1275 2558//2558 2556//2556 -f 1275//1275 2556//2556 1276//1276 -f 1276//1276 2556//2556 2555//2555 -f 1276//1276 2555//2555 2563//2563 -f 2563//2563 2555//2555 2567//2567 -f 2563//2563 2567//2567 2717//2717 -f 2417//2417 2422//2422 2418//2418 -f 2418//2418 2422//2422 2340//2340 -f 2418//2418 2340//2340 2419//2419 -f 2419//2419 2340//2340 1312//1312 -f 2419//2419 1312//1312 2420//2420 -f 2420//2420 1312//1312 1311//1311 -f 2420//2420 1311//1311 2421//2421 -f 2421//2421 1311//1311 2339//2339 -f 2421//2421 2339//2339 2347//2347 -f 2347//2347 2339//2339 2333//2333 -f 2347//2347 2333//2333 2346//2346 -f 2346//2346 2333//2333 2332//2332 -f 2346//2346 2332//2332 2344//2344 -f 2344//2344 2332//2332 2328//2328 -f 2344//2344 2328//2328 2313//2313 -f 2313//2313 2328//2328 2327//2327 -f 2313//2313 2327//2327 2314//2314 -f 2314//2314 2327//2327 1315//1315 -f 2314//2314 1315//1315 2306//2306 -f 2306//2306 1315//1315 1314//1314 -f 2306//2306 1314//1314 2307//2307 -f 2307//2307 1314//1314 2310//2310 -f 2307//2307 2310//2310 2308//2308 -f 2308//2308 2310//2310 2312//2312 -f 2308//2308 2312//2312 2309//2309 -f 2309//2309 2312//2312 2305//2305 -f 2309//2309 2305//2305 2293//2293 -f 2293//2293 2305//2305 2303//2303 -f 2293//2293 2303//2303 2294//2294 -f 2294//2294 2303//2303 2302//2302 -f 2294//2294 2302//2302 2300//2300 -f 2300//2300 2302//2302 2280//2280 -f 2300//2300 2280//2280 2299//2299 -f 2299//2299 2280//2280 2278//2278 -f 2299//2299 2278//2278 2298//2298 -f 2298//2298 2278//2278 2276//2276 -f 2298//2298 2276//2276 2297//2297 -f 2297//2297 2276//2276 2274//2274 -f 2297//2297 2274//2274 2296//2296 -f 2296//2296 2274//2274 2272//2272 -f 2296//2296 2272//2272 2295//2295 -f 2295//2295 2272//2272 2262//2262 -f 2295//2295 2262//2262 2286//2286 -f 2286//2286 2262//2262 2301//2301 -f 2286//2286 2301//2301 2315//2315 -f 2315//2315 2301//2301 2416//2416 -f 2315//2315 2416//2416 2313//2313 -f 2313//2313 2416//2416 1299//1299 -f 2313//2313 1299//1299 1303//1303 -f 1303//1303 1299//1299 1298//1298 -f 1303//1303 1298//1298 1301//1301 -f 1301//1301 1298//1298 2362//2362 -f 1301//1301 2362//2362 2352//2352 -f 2352//2352 2362//2362 2361//2361 -f 2352//2352 2361//2361 2353//2353 -f 2353//2353 2361//2361 2380//2380 -f 2353//2353 2380//2380 2357//2357 -f 2357//2357 2380//2380 2376//2376 -f 2357//2357 2376//2376 2417//2417 -f 2417//2417 2376//2376 2377//2377 -f 2417//2417 2377//2377 2422//2422 -f 2422//2422 2377//2377 2378//2378 -f 2422//2422 2378//2378 2423//2423 -f 2423//2423 2378//2378 1262//1262 -f 2423//2423 1262//1262 2424//2424 -f 2424//2424 1262//1262 1264//1264 -f 2424//2424 1264//1264 2426//2426 -f 2426//2426 1264//1264 2729//2729 -f 2426//2426 2729//2729 2715//2715 -f 2715//2715 2729//2729 2731//2731 -f 2715//2715 2731//2731 2742//2742 -f 2742//2742 2731//2731 2732//2732 -f 2742//2742 2732//2732 2743//2743 -f 2743//2743 2732//2732 2733//2733 -f 2743//2743 2733//2733 1222//1222 -f 1222//1222 2733//2733 1223//1223 -f 1940//1940 2774//2774 1370//1370 -f 1370//1370 2774//2774 2029//2029 -f 1370//1370 2029//2029 1368//1368 -f 1368//1368 2029//2029 2028//2028 -f 1368//1368 2028//2028 1956//1956 -f 1956//1956 2028//2028 2027//2027 -f 1956//1956 2027//2027 1955//1955 -f 1955//1955 2027//2027 1379//1379 -f 1955//1955 1379//1379 1939//1939 -f 1939//1939 1379//1379 1377//1377 -f 1939//1939 1377//1377 2775//2775 -f 2775//2775 1377//1377 1376//1376 -f 2775//2775 1376//1376 2018//2018 -f 2018//2018 1376//1376 2022//2022 -f 2018//2018 2022//2022 2016//2016 -f 2016//2016 2022//2022 2023//2023 -f 2016//2016 2023//2023 2024//2024 -f 2024//2024 2023//2023 2030//2030 -f 2024//2024 2030//2030 2025//2025 -f 2025//2025 2030//2030 2029//2029 -f 2025//2025 2029//2029 2026//2026 -f 2026//2026 2029//2029 2774//2774 -f 2026//2026 2774//2774 2043//2043 -f 2043//2043 2774//2774 1940//1940 -f 2043//2043 1940//1940 2035//2035 -f 2035//2035 1940//1940 2013//2013 -f 2035//2035 2013//2013 2237//2237 -f 2237//2237 2013//2013 2008//2008 -f 2237//2237 2008//2008 2120//2120 -f 2120//2120 2008//2008 1355//1355 -f 2120//2120 1355//1355 2121//2121 -f 2121//2121 1355//1355 2006//2006 -f 2121//2121 2006//2006 2040//2040 -f 2040//2040 2006//2006 2003//2003 -f 2040//2040 2003//2003 2041//2041 -f 2041//2041 2003//2003 2002//2002 -f 2041//2041 2002//2002 2042//2042 -f 2042//2042 2002//2002 2075//2075 -f 2042//2042 2075//2075 1984//1984 -f 1984//1984 2075//2075 2074//2074 -f 1984//1984 2074//2074 1982//1982 -f 1982//1982 2074//2074 2073//2073 -f 1982//1982 2073//2073 1985//1985 -f 1985//1985 2073//2073 2072//2072 -f 1985//1985 2072//2072 2086//2086 -f 2086//2086 2072//2072 2071//2071 -f 2086//2086 2071//2071 2084//2084 -f 2084//2084 2071//2071 2070//2070 -f 2084//2084 2070//2070 2083//2083 -f 2083//2083 2070//2070 2061//2061 -f 2083//2083 2061//2061 2081//2081 -f 2081//2081 2061//2061 2060//2060 -f 2081//2081 2060//2060 2080//2080 -f 2080//2080 2060//2060 2058//2058 -f 2080//2080 2058//2058 2079//2079 -f 2079//2079 2058//2058 1348//1348 -f 2079//2079 1348//1348 2078//2078 -f 2078//2078 1348//1348 1347//1347 -f 2078//2078 1347//1347 2076//2076 -f 2076//2076 1347//1347 2098//2098 -f 2076//2076 2098//2098 2077//2077 -f 2077//2077 2098//2098 2100//2100 -f 2077//2077 2100//2100 2066//2066 -f 2066//2066 2100//2100 1345//1345 -f 2066//2066 1345//1345 2064//2064 -f 2064//2064 1345//1345 1344//1344 -f 2064//2064 1344//1344 2062//2062 -f 2062//2062 1344//1344 2103//2103 -f 2062//2062 2103//2103 2236//2236 -f 2236//2236 2103//2103 2102//2102 -f 2236//2236 2102//2102 2118//2118 -f 2118//2118 2102//2102 2105//2105 -f 2118//2118 2105//2105 2114//2114 -f 2114//2114 2105//2105 2113//2113 -f 2114//2114 2113//2113 1343//1343 -f 1343//1343 2113//2113 2489//2489 -f 1343//1343 2489//2489 1341//1341 -f 1341//1341 2489//2489 2125//2125 -f 1341//1341 2125//2125 2183//2183 -f 2183//2183 2125//2125 2123//2123 -f 2183//2183 2123//2123 2175//2175 -f 2175//2175 2123//2123 2122//2122 -f 2175//2175 2122//2122 2138//2138 -f 2138//2138 2122//2122 1332//1332 -f 2138//2138 1332//1332 2136//2136 -f 2136//2136 1332//1332 1334//1334 -f 2136//2136 1334//1334 2134//2134 -f 2134//2134 1334//1334 2133//2133 -f 2134//2134 2133//2133 2144//2144 -f 2144//2144 2133//2133 2131//2131 -f 2144//2144 2131//2131 2148//2148 -f 2148//2148 2131//2131 2132//2132 -f 2148//2148 2132//2132 2173//2173 -f 2173//2173 2132//2132 2126//2126 -f 2173//2173 2126//2126 2172//2172 -f 2172//2172 2126//2126 2128//2128 -f 2172//2172 2128//2128 1339//1339 -f 1339//1339 2128//2128 2190//2190 -f 1339//1339 2190//2190 1340//1340 -f 1340//1340 2190//2190 1327//1327 -f 1340//1340 1327//1327 2217//2217 -f 2217//2217 1327//1327 1329//1329 -f 2217//2217 1329//1329 2218//2218 -f 2218//2218 1329//1329 2198//2198 -f 2218//2218 2198//2198 2214//2214 -f 2214//2214 2198//2198 2199//2199 -f 2214//2214 2199//2199 2206//2206 -f 2206//2206 2199//2199 2196//2196 -f 2206//2206 2196//2196 2205//2205 -f 2205//2205 2196//2196 2195//2195 -f 2205//2205 2195//2195 2204//2204 -f 2204//2204 2195//2195 2193//2193 -f 2204//2204 2193//2193 2202//2202 -f 2202//2202 2193//2193 2130//2130 -f 2202//2202 2130//2130 2200//2200 -f 2200//2200 2130//2130 2187//2187 -f 2200//2200 2187//2187 2216//2216 -f 2216//2216 2187//2187 2188//2188 -f 2216//2216 2188//2188 2215//2215 -f 2215//2215 2188//2188 1324//1324 -f 2215//2215 1324//1324 2212//2212 -f 2212//2212 1324//1324 1326//1326 -f 2212//2212 1326//1326 2211//2211 -f 2211//2211 1326//1326 1321//1321 -f 2211//2211 1321//1321 2209//2209 -f 2209//2209 1321//1321 1323//1323 -f 2209//2209 1323//1323 2213//2213 -f 2213//2213 1323//1323 2737//2737 -f 2213//2213 2737//2737 2720//2720 -f 2720//2720 2737//2737 2738//2738 -f 2720//2720 2738//2738 2722//2722 -f 2722//2722 2738//2738 2739//2739 -f 2722//2722 2739//2739 2724//2724 -f 2724//2724 2739//2739 2740//2740 -f 2724//2724 2740//2740 2726//2726 -f 2726//2726 2740//2740 2741//2741 -f 2726//2726 2741//2741 2728//2728 -f 2728//2728 2741//2741 1417//1417 -f 2728//2728 1417//1417 1210//1210 -f 1210//1210 1417//1417 1211//1211 -f 2776//2776 1513//1513 2777//2777 -f 2777//2777 1513//1513 1514//1514 -f 2777//2777 1514//1514 2778//2778 -f 2778//2778 1514//1514 1515//1515 -f 2778//2778 1515//1515 2779//2779 -f 2779//2779 1515//1515 1516//1516 -f 2779//2779 2780//2780 2778//2778 -f 2778//2778 2780//2780 2781//2781 -f 2778//2778 2781//2781 2777//2777 -f 2777//2777 2781//2781 2782//2782 -f 2777//2777 2782//2782 2776//2776 -f 2776//2776 2782//2782 2783//2783 -f 2776//2776 2783//2783 2784//2784 -f 2784//2784 2783//2783 2785//2785 -f 2784//2784 2785//2785 2786//2786 -f 2786//2786 2785//2785 2787//2787 -f 2786//2786 2787//2787 2788//2788 -f 2788//2788 2787//2787 2789//2789 -f 2788//2788 2789//2789 2790//2790 -f 2790//2790 2789//2789 2791//2791 -f 2790//2790 2791//2791 2792//2792 -f 2792//2792 2791//2791 2793//2793 -f 2792//2792 2793//2793 2794//2794 -f 1225//1225 1224//1224 1516//1516 -f 1516//1516 1224//1224 1517//1517 -f 1516//1516 1517//1517 2779//2779 -f 2779//2779 1517//1517 2765//2765 -f 2779//2779 2765//2765 2780//2780 -f 2780//2780 2765//2765 2766//2766 -f 2780//2780 2766//2766 2781//2781 -f 2781//2781 2766//2766 2767//2767 -f 2781//2781 2767//2767 2782//2782 -f 2782//2782 2767//2767 2768//2768 -f 2782//2782 2768//2768 2783//2783 -f 2783//2783 2768//2768 2769//2769 -f 2783//2783 2769//2769 2785//2785 -f 2785//2785 2769//2769 2770//2770 -f 2785//2785 2770//2770 2787//2787 -f 2787//2787 2770//2770 2771//2771 -f 2787//2787 2771//2771 2789//2789 -f 2789//2789 2771//2771 2772//2772 -f 2789//2789 2772//2772 2791//2791 -f 2791//2791 2772//2772 2773//2773 -f 2791//2791 2773//2773 2793//2793 -f 1713//1713 2794//2794 1685//1685 -f 1685//1685 2794//2794 2793//2793 -f 1685//1685 2793//2793 1590//1590 -f 1590//1590 2793//2793 2773//2773 -f 1590//1590 2773//2773 1588//1588 -f 1588//1588 2773//2773 1592//1592 -f 1588//1588 1592//1592 1586//1586 -f 1586//1586 1592//1592 1594//1594 -f 1586//1586 1594//1594 1402//1402 -f 1402//1402 1594//1594 1596//1596 -f 1402//1402 1596//1596 1400//1400 -f 1400//1400 1596//1596 1597//1597 -f 1400//1400 1597//1597 2642//2642 -f 2642//2642 1597//1597 2754//2754 -f 2642//2642 2754//2754 2641//2641 -f 2641//2641 2754//2754 2631//2631 -f 2641//2641 2631//2631 1257//1257 -f 1257//1257 2631//2631 2633//2633 -f 1257//1257 2633//2633 1255//1255 -f 1255//1255 2633//2633 2753//2753 -f 1255//1255 2753//2753 2614//2614 -f 2614//2614 2753//2753 2752//2752 -f 2614//2614 2752//2752 1267//1267 -f 1267//1267 2752//2752 2613//2613 -f 1267//1267 2613//2613 1265//1265 -f 1265//1265 2613//2613 2612//2612 -f 1265//1265 2612//2612 2602//2602 -f 2602//2602 2612//2612 2611//2611 -f 2602//2602 2611//2611 2592//2592 -f 2592//2592 2611//2611 2610//2610 -f 2592//2592 2610//2610 2593//2593 -f 2593//2593 2610//2610 2589//2589 -f 2593//2593 2589//2589 2594//2594 -f 2594//2594 2589//2589 2591//2591 -f 2594//2594 2591//2591 2599//2599 -f 2599//2599 2591//2591 2585//2585 -f 2599//2599 2585//2585 2600//2600 -f 2600//2600 2585//2585 2587//2587 -f 2600//2600 2587//2587 2601//2601 -f 2601//2601 2587//2587 2588//2588 -f 2601//2601 2588//2588 2604//2604 -f 2604//2604 2588//2588 2615//2615 -f 2604//2604 2615//2615 1266//1266 -f 1266//1266 2615//2615 2614//2614 -f 1266//1266 2614//2614 1267//1267 -f 1215//1215 1212//1212 1512//1512 -f 1512//1512 1212//1212 1213//1213 -f 1512//1512 1213//1213 2795//2795 -f 2795//2795 1213//1213 1245//1245 -f 2795//2795 1245//1245 1576//1576 -f 1576//1576 1245//1245 1247//1247 -f 1576//1576 1247//1247 1574//1574 -f 1574//1574 1247//1247 1169//1169 -f 1574//1574 1169//1169 1572//1572 -f 1572//1572 1169//1169 1248//1248 -f 1572//1572 1248//1248 1570//1570 -f 1570//1570 1248//1248 1246//1246 -f 1234//1234 1233//1233 2710//2710 -f 2710//2710 1233//1233 1249//1249 -f 2710//2710 1249//1249 2708//2708 -f 2708//2708 1249//1249 1251//1251 -f 2708//2708 1251//1251 2706//2706 -f 2706//2706 1251//1251 2698//2698 -f 2706//2706 2698//2698 2177//2177 -f 2177//2177 2698//2698 2692//2692 -f 2177//2177 2692//2692 2179//2179 -f 2179//2179 2692//2692 2691//2691 -f 2179//2179 2691//2691 2036//2036 -f 2036//2036 2691//2691 2685//2685 -f 2036//2036 2685//2685 2038//2038 -f 2038//2038 2685//2685 1252//1252 -f 2038//2038 1252//1252 2039//2039 -f 2039//2039 1252//1252 1254//1254 -f 2039//2039 1254//1254 2044//2044 -f 2044//2044 1254//1254 2796//2796 -f 2044//2044 2796//2796 2045//2045 -f 2045//2045 2796//2796 1899//1899 -f 2045//2045 1899//1899 1908//1908 -f 1908//1908 1899//1899 1869//1869 -f 1908//1908 1869//1869 1909//1909 -f 1909//1909 1869//1869 1868//1868 -f 1909//1909 1868//1868 1911//1911 -f 1911//1911 1868//1868 1866//1866 -f 1911//1911 1866//1866 1904//1904 -f 1904//1904 1866//1866 1898//1898 -f 1904//1904 1898//1898 1902//1902 -f 1902//1902 1898//1898 1897//1897 -f 1902//1902 1897//1897 1900//1900 -f 1900//1900 1897//1897 1895//1895 -f 1900//1900 1895//1895 2033//2033 -f 2033//2033 1895//1895 1894//1894 -f 2033//2033 1894//1894 2034//2034 -f 2034//2034 1894//1894 1870//1870 -f 2034//2034 1870//1870 1877//1877 -f 1877//1877 1870//1870 1872//1872 -f 1877//1877 1872//1872 1875//1875 -f 1875//1875 1872//1872 1878//1878 -f 1875//1875 1878//1878 1874//1874 -f 1874//1874 1878//1878 1884//1884 -f 1874//1874 1884//1884 1383//1383 -f 1383//1383 1884//1884 1906//1906 -f 1383//1383 1906//1906 1381//1381 -f 1381//1381 1906//1906 1905//1905 -f 1381//1381 1905//1905 1382//1382 -f 1382//1382 1905//1905 1893//1893 -f 1382//1382 1893//1893 2021//2021 -f 2021//2021 1893//1893 1892//1892 -f 2021//2021 1892//1892 2014//2014 -f 2014//2014 1892//1892 1890//1890 -f 2014//2014 1890//1890 2015//2015 -f 2015//2015 1890//1890 1889//1889 -f 2015//2015 1889//1889 2017//2017 -f 2017//2017 1889//1889 1885//1885 -f 2017//2017 1885//1885 2018//2018 -f 2018//2018 1885//1885 1880//1880 -f 2018//2018 1880//1880 2775//2775 -f 2775//2775 1880//1880 1879//1879 -f 2775//2775 1879//1879 1939//1939 -f 1939//1939 1879//1879 1881//1881 -f 1939//1939 1881//1881 1926//1926 -f 1926//1926 1881//1881 1386//1386 -f 1926//1926 1386//1386 1860//1860 -f 1860//1860 1386//1386 1873//1873 -f 1860//1860 1873//1873 1861//1861 -f 1861//1861 1873//1873 1871//1871 -f 1861//1861 1871//1871 1863//1863 -f 1863//1863 1871//1871 1899//1899 -f 1863//1863 1899//1899 1864//1864 -f 1864//1864 1899//1899 2796//2796 -f 1864//1864 2796//2796 2238//2238 -f 2238//2238 2796//2796 1254//1254 -f 2238//2238 1254//1254 2659//2659 -f 2659//2659 1254//1254 1253//1253 -f 2659//2659 1253//1253 2660//2660 -f 2660//2660 1253//1253 2683//2683 -f 2660//2660 2683//2683 2661//2661 -f 2661//2661 2683//2683 2688//2688 -f 2661//2661 2688//2688 2671//2671 -f 2671//2671 2688//2688 2687//2687 -f 2671//2671 2687//2687 2673//2673 -f 2673//2673 2687//2687 2686//2686 -f 2673//2673 2686//2686 2674//2674 -f 2674//2674 2686//2686 2693//2693 -f 2674//2674 2693//2693 2701//2701 -f 2701//2701 2693//2693 1511//1511 -f 2701//2701 1511//1511 2675//2675 -f 2675//2675 1511//1511 1512//1512 -f 2675//2675 1512//1512 2676//2676 -f 2676//2676 1512//1512 2795//2795 -f 2676//2676 2795//2795 2704//2704 -f 2704//2704 2795//2795 1576//1576 -f 2704//2704 1576//1576 2703//2703 -f 2703//2703 1576//1576 1575//1575 -f 2703//2703 1575//1575 2702//2702 -f 2702//2702 1575//1575 1573//1573 -f 2702//2702 1573//1573 1826//1826 -f 1826//1826 1573//1573 1571//1571 -f 1826//1826 1571//1571 1565//1565 -f 1565//1565 1571//1571 1570//1570 -f 1565//1565 1570//1570 1406//1406 -f 1406//1406 1570//1570 1246//1246 -f 1406//1406 1246//1246 1244//1244 -f 1238//1238 1237//1237 1527//1527 -f 1527//1527 1237//1237 1513//1513 -f 1527//1527 1513//1513 1529//1529 -f 1529//1529 1513//1513 2776//2776 -f 1529//1529 2776//2776 1609//1609 -f 1609//1609 2776//2776 2784//2784 -f 1609//1609 2784//2784 1736//1736 -f 1736//1736 2784//2784 2786//2786 -f 1736//1736 2786//2786 1735//1735 -f 1735//1735 2786//2786 2788//2788 -f 1735//1735 2788//2788 1734//1734 -f 1734//1734 2788//2788 2790//2790 -f 1734//1734 2790//2790 1733//1733 -f 1733//1733 2790//2790 2792//2792 -f 1733//1733 2792//2792 1732//1732 -f 1732//1732 2792//2792 2794//2794 -f 1732//1732 2794//2794 1730//1730 -f 1730//1730 2794//2794 1713//1713 -f 1730//1730 1713//1713 1728//1728 -f 1728//1728 1713//1713 1712//1712 -f 1728//1728 1712//1712 1726//1726 -f 1726//1726 1712//1712 1711//1711 -f 1726//1726 1711//1711 1724//1724 -f 1724//1724 1711//1711 1710//1710 -f 1724//1724 1710//1710 1722//1722 -f 1722//1722 1710//1710 1709//1709 -f 1722//1722 1709//1709 1720//1720 -f 1720//1720 1709//1709 1708//1708 -f 1720//1720 1708//1708 1718//1718 -f 1718//1718 1708//1708 1707//1707 -f 1718//1718 1707//1707 1716//1716 -f 1716//1716 1707//1707 1706//1706 -f 1716//1716 1706//1706 1714//1714 -f 1714//1714 1706//1706 1705//1705 -f 1714//1714 1705//1705 1396//1396 -f 1396//1396 1705//1705 1704//1704 -f 1396//1396 1704//1704 1749//1749 -f 1749//1749 1704//1704 1703//1703 -f 1749//1749 1703//1703 2663//2663 -f 2663//2663 1703//1703 1702//1702 -f 2663//2663 1702//1702 1836//1836 -f 1836//1836 1702//1702 1686//1686 -f 1836//1836 1686//1686 1695//1695 -f 1695//1695 1686//1686 1693//1693 -f 1695//1695 1693//1693 1696//1696 -f 1696//1696 1693//1693 1694//1694 -f 1696//1696 1694//1694 2647//2647 -f 2647//2647 1694//1694 1445//1445 -f 2647//2647 1445//1445 1841//1841 -f 1841//1841 1445//1445 1446//1446 -f 1841//1841 1446//1446 1440//1440 -f 1440//1440 1446//1446 2797//2797 -f 1440//1440 2797//2797 1441//1441 -f 2798//2798 2799//2799 2800//2800 -f 2800//2800 2799//2799 1438//1438 -f 2800//2800 1438//1438 2801//2801 -f 2801//2801 1438//1438 2802//2802 -f 2803//2803 2804//2804 2805//2805 -f 2805//2805 2804//2804 1505//1505 -f 2805//2805 1505//1505 2798//2798 -f 2798//2798 1505//1505 2799//2799 -f 2806//2806 2807//2807 2808//2808 -f 2808//2808 2807//2807 1496//1496 -f 2808//2808 1496//1496 2803//2803 -f 2803//2803 1496//1496 2804//2804 -f 1505//1505 2804//2804 1506//1506 -f 1506//1506 2804//2804 2430//2430 -f 2646//2646 2804//2804 1495//1495 -f 1495//1495 2804//2804 1496//1496 -f 2643//2643 1500//1500 2804//2804 -f 2804//2804 1500//1500 1499//1499 -f 2804//2804 1499//1499 2430//2430 -f 2646//2646 2645//2645 2804//2804 -f 2804//2804 2645//2645 2644//2644 -f 2804//2804 2644//2644 2643//2643 -f 1424//1424 2799//2799 1503//1503 -f 1503//1503 2799//2799 1505//1505 -f 2799//2799 1437//1437 1436//1436 -f 1424//1424 1427//1427 2799//2799 -f 2799//2799 1427//1427 1429//1429 -f 2799//2799 1429//1429 1431//1431 -f 1431//1431 1434//1434 2799//2799 -f 2799//2799 1434//1434 1433//1433 -f 2799//2799 1433//1433 1437//1437 -f 2799//2799 1436//1436 1439//1439 -f 2799//2799 1439//1439 1438//1438 -f 1591//1591 2807//2807 1481//1481 -f 1481//1481 2807//2807 1482//1482 -f 1591//1591 1487//1487 2807//2807 -f 2807//2807 1487//1487 1488//1488 -f 2807//2807 1488//1488 1490//1490 -f 1490//1490 1584//1584 2807//2807 -f 2807//2807 1584//1584 1491//1491 -f 2807//2807 1491//1491 1493//1493 -f 1493//1493 1498//1498 2807//2807 -f 2807//2807 1498//1498 1497//1497 -f 2807//2807 1497//1497 1496//1496 -f 1482//1482 2809//2809 1483//1483 -f 1483//1483 2809//2809 1484//1484 -f 1418//1418 2810//2810 1419//1419 -f 1419//1419 2810//2810 1451//1451 -f 1418//1418 1475//1475 2810//2810 -f 2810//2810 1475//1475 1473//1473 -f 2810//2810 1473//1473 1471//1471 -f 1457//1457 1455//1455 2809//2809 -f 2809//2809 1455//1455 1453//1453 -f 2809//2809 1453//1453 1480//1480 -f 1480//1480 1479//1479 2809//2809 -f 2809//2809 1479//1479 1477//1477 -f 2809//2809 1477//1477 1484//1484 -f 1471//1471 1469//1469 2810//2810 -f 2810//2810 1469//1469 1467//1467 -f 2810//2810 1467//1467 1465//1465 -f 1465//1465 1463//1463 2810//2810 -f 2810//2810 1463//1463 1461//1461 -f 2810//2810 1461//1461 2809//2809 -f 2809//2809 1461//1461 1459//1459 -f 2809//2809 1459//1459 1457//1457 -f 2811//2811 2808//2808 2803//2803 -f 2812//2812 2803//2803 2813//2813 -f 2813//2813 2803//2803 2805//2805 -f 2812//2812 2814//2814 2803//2803 -f 2803//2803 2814//2814 2815//2815 -f 2803//2803 2815//2815 2816//2816 -f 2817//2817 2818//2818 2803//2803 -f 2803//2803 2818//2818 2819//2819 -f 2803//2803 2819//2819 2811//2811 -f 2816//2816 2820//2820 2803//2803 -f 2803//2803 2820//2820 2821//2821 -f 2803//2803 2821//2821 2817//2817 -f 2822//2822 2805//2805 2798//2798 -f 2798//2798 2823//2823 2824//2824 -f 2800//2800 2825//2825 2798//2798 -f 2798//2798 2825//2825 2826//2826 -f 2798//2798 2826//2826 2823//2823 -f 2824//2824 2827//2827 2798//2798 -f 2798//2798 2827//2827 2828//2828 -f 2798//2798 2828//2828 2829//2829 -f 2829//2829 2830//2830 2798//2798 -f 2798//2798 2830//2830 2831//2831 -f 2798//2798 2831//2831 2822//2822 -f 2808//2808 2832//2832 2806//2806 -f 2806//2806 2832//2832 2833//2833 -f 2806//2806 2833//2833 2834//2834 -f 2834//2834 2835//2835 2806//2806 -f 2806//2806 2835//2835 2836//2836 -f 2806//2806 2836//2836 2837//2837 -f 2837//2837 2838//2838 2806//2806 -f 2806//2806 2838//2838 2839//2839 -f 2806//2806 2839//2839 2840//2840 -f 2840//2840 2841//2841 2806//2806 -f 2806//2806 2841//2841 2842//2842 -f 2806//2806 2842//2842 2843//2843 -f 2844//2844 2845//2845 2846//2846 -f 2846//2846 2843//2843 2847//2847 -f 2847//2847 2848//2848 2846//2846 -f 2846//2846 2848//2848 2849//2849 -f 2846//2846 2849//2849 2850//2850 -f 2850//2850 2851//2851 2846//2846 -f 2846//2846 2851//2851 2852//2852 -f 2846//2846 2852//2852 2853//2853 -f 2853//2853 2854//2854 2846//2846 -f 2846//2846 2854//2854 2855//2855 -f 2846//2846 2855//2855 2844//2844 -f 2856//2856 2857//2857 2858//2858 -f 2858//2858 2857//2857 2859//2859 -f 2845//2845 2860//2860 2857//2857 -f 2857//2857 2860//2860 2861//2861 -f 2862//2862 2863//2863 2857//2857 -f 2857//2857 2863//2863 2864//2864 -f 2857//2857 2864//2864 2859//2859 -f 2861//2861 2865//2865 2857//2857 -f 2857//2857 2865//2865 2866//2866 -f 2857//2857 2866//2866 2862//2862 -f 2801//2801 2802//2802 2856//2856 -f 2856//2856 2802//2802 1451//1451 -f 2856//2856 1451//1451 2857//2857 -f 2857//2857 1451//1451 2810//2810 -f 2846//2846 2809//2809 2843//2843 -f 2843//2843 2809//2809 1482//1482 -f 2843//2843 1482//1482 2806//2806 -f 2806//2806 1482//1482 2807//2807 -f 2867//2867 2846//2846 2845//2845 -f 2867//2867 2845//2845 2857//2857 -f 2868//2868 2869//2869 2809//2809 -f 2809//2809 2869//2869 2870//2870 -f 2809//2809 2870//2870 2871//2871 -f 2809//2809 2872//2872 2810//2810 -f 2846//2846 2867//2867 2809//2809 -f 2809//2809 2867//2867 2873//2873 -f 2871//2871 2874//2874 2809//2809 -f 2809//2809 2874//2874 2875//2875 -f 2809//2809 2875//2875 2872//2872 -f 2876//2876 2873//2873 2857//2857 -f 2857//2857 2873//2873 2867//2867 -f 2810//2810 2872//2872 2857//2857 -f 2857//2857 2872//2872 2877//2877 -f 2857//2857 2877//2877 2878//2878 -f 2878//2878 2879//2879 2857//2857 -f 2857//2857 2879//2879 2880//2880 -f 2857//2857 2880//2880 2881//2881 -f 2881//2881 2882//2882 2857//2857 -f 2857//2857 2882//2882 2883//2883 -f 2857//2857 2883//2883 2876//2876 -f 2809//2809 2873//2873 2884//2884 -f 2884//2884 2885//2885 2809//2809 -f 2809//2809 2885//2885 2886//2886 -f 2809//2809 2886//2886 2868//2868 -f 1446//1446 1444//1444 2802//2802 -f 2802//2802 1444//1444 1449//1449 -f 2802//2802 1846//1846 1442//1442 -f 1449//1449 1448//1448 2802//2802 -f 2802//2802 1448//1448 1447//1447 -f 2802//2802 1447//1447 1451//1451 -f 1438//1438 1422//1422 2802//2802 -f 2802//2802 1422//1422 1421//1421 -f 2802//2802 1421//1421 1846//1846 -f 1442//1442 1441//1441 2802//2802 -f 2802//2802 1441//1441 2797//2797 -f 2802//2802 2797//2797 1446//1446 -f 2887//2887 2888//2888 2801//2801 -f 2801//2801 2888//2888 2889//2889 -f 2856//2856 2890//2890 2801//2801 -f 2801//2801 2890//2890 2891//2891 -f 2801//2801 2891//2891 2887//2887 -f 2889//2889 2892//2892 2801//2801 -f 2801//2801 2892//2892 2893//2893 -f 2801//2801 2893//2893 2894//2894 -f 2894//2894 2895//2895 2801//2801 -f 2801//2801 2895//2895 2896//2896 -f 2801//2801 2896//2896 2800//2800 -f 2871//2871 2897//2897 2874//2874 -f 2874//2874 2897//2897 2872//2872 -f 2874//2874 2872//2872 2875//2875 -f 2897//2897 2898//2898 2872//2872 -f 2882//2882 2881//2881 2899//2899 -f 2899//2899 2881//2881 2880//2880 -f 2899//2899 2880//2880 2879//2879 -f 2877//2877 2872//2872 2878//2878 -f 2878//2878 2872//2872 2898//2898 -f 2878//2878 2898//2898 2879//2879 -f 2879//2879 2898//2898 2897//2897 -f 2879//2879 2897//2897 2899//2899 -f 2899//2899 2897//2897 2883//2883 -f 2899//2899 2883//2883 2882//2882 -f 2876//2876 2885//2885 2884//2884 -f 2876//2876 2884//2884 2873//2873 -f 2871//2871 2870//2870 2897//2897 -f 2897//2897 2870//2870 2869//2869 -f 2897//2897 2869//2869 2868//2868 -f 2876//2876 2883//2883 2885//2885 -f 2885//2885 2883//2883 2897//2897 -f 2885//2885 2897//2897 2886//2886 -f 2886//2886 2897//2897 2868//2868 -f 2900//2900 2901//2901 2902//2902 -f 2903//2903 2904//2904 2901//2901 -f 2900//2900 2902//2902 2905//2905 -f 2903//2903 2901//2901 2906//2906 -f 2904//2904 2907//2907 2901//2901 -f 2901//2901 2907//2907 2908//2908 -f 2901//2901 2908//2908 2902//2902 -f 2909//2909 2910//2910 2911//2911 -f 2911//2911 2910//2910 2912//2912 -f 2911//2911 2912//2912 2913//2913 -f 2913//2913 2914//2914 2911//2911 -f 2911//2911 2914//2914 2915//2915 -f 2911//2911 2915//2915 2901//2901 -f 2901//2901 2915//2915 2916//2916 -f 2901//2901 2916//2916 2906//2906 -f 2911//2911 2917//2917 2918//2918 -f 2919//2919 2920//2920 2921//2921 -f 2921//2921 2920//2920 2922//2922 -f 2918//2918 2923//2923 2911//2911 -f 2911//2911 2923//2923 2924//2924 -f 2911//2911 2924//2924 2909//2909 -f 2925//2925 2926//2926 2905//2905 -f 2905//2905 2926//2926 2927//2927 -f 2905//2905 2927//2927 2928//2928 -f 2922//2922 2929//2929 2921//2921 -f 2921//2921 2929//2929 2930//2930 -f 2921//2921 2930//2930 2911//2911 -f 2911//2911 2930//2930 2931//2931 -f 2911//2911 2931//2931 2917//2917 -f 2902//2902 2932//2932 2905//2905 -f 2905//2905 2932//2932 2933//2933 -f 2905//2905 2933//2933 2934//2934 -f 2919//2919 2921//2921 2935//2935 -f 2935//2935 2921//2921 2936//2936 -f 2935//2935 2936//2936 2937//2937 -f 2934//2934 2938//2938 2905//2905 -f 2905//2905 2938//2938 2939//2939 -f 2905//2905 2939//2939 2925//2925 -f 2940//2940 2941//2941 2942//2942 -f 2943//2943 2944//2944 2937//2937 -f 2937//2937 2944//2944 2945//2945 -f 2937//2937 2945//2945 2935//2935 -f 2927//2927 2946//2946 2928//2928 -f 2928//2928 2946//2946 2947//2947 -f 2928//2928 2947//2947 2948//2948 -f 2948//2948 2947//2947 2949//2949 -f 2937//2937 2950//2950 2943//2943 -f 2943//2943 2950//2950 2940//2940 -f 2943//2943 2940//2940 2951//2951 -f 2951//2951 2940//2940 2942//2942 -f 2860//2860 2908//2908 2907//2907 -f 2853//2853 2938//2938 2934//2934 -f 2848//2848 2847//2847 2946//2946 -f 2946//2946 2847//2847 2843//2843 -f 2946//2946 2843//2843 2842//2842 -f 2946//2946 2927//2927 2848//2848 -f 2848//2848 2927//2927 2926//2926 -f 2848//2848 2926//2926 2849//2849 -f 2849//2849 2926//2926 2925//2925 -f 2849//2849 2925//2925 2850//2850 -f 2850//2850 2925//2925 2939//2939 -f 2850//2850 2939//2939 2851//2851 -f 2851//2851 2939//2939 2938//2938 -f 2851//2851 2938//2938 2852//2852 -f 2852//2852 2938//2938 2853//2853 -f 2844//2844 2855//2855 2934//2934 -f 2934//2934 2855//2855 2854//2854 -f 2934//2934 2854//2854 2853//2853 -f 2934//2934 2933//2933 2844//2844 -f 2844//2844 2933//2933 2932//2932 -f 2844//2844 2932//2932 2845//2845 -f 2845//2845 2932//2932 2860//2860 -f 2860//2860 2932//2932 2902//2902 -f 2860//2860 2902//2902 2908//2908 -f 2866//2866 2865//2865 2907//2907 -f 2907//2907 2865//2865 2861//2861 -f 2907//2907 2861//2861 2860//2860 -f 2907//2907 2904//2904 2866//2866 -f 2866//2866 2904//2904 2903//2903 -f 2866//2866 2903//2903 2862//2862 -f 2862//2862 2903//2903 2906//2906 -f 2862//2862 2906//2906 2863//2863 -f 2863//2863 2906//2906 2864//2864 -f 2864//2864 2906//2906 2859//2859 -f 2859//2859 2906//2906 2916//2916 -f 2859//2859 2916//2916 2858//2858 -f 2916//2916 2915//2915 2858//2858 -f 2858//2858 2915//2915 2914//2914 -f 2858//2858 2914//2914 2856//2856 -f 2856//2856 2914//2914 2913//2913 -f 2856//2856 2913//2913 2890//2890 -f 2890//2890 2913//2913 2912//2912 -f 2890//2890 2912//2912 2891//2891 -f 2891//2891 2912//2912 2910//2910 -f 2891//2891 2910//2910 2887//2887 -f 2887//2887 2910//2910 2909//2909 -f 2887//2887 2909//2909 2888//2888 -f 2909//2909 2924//2924 2888//2888 -f 2888//2888 2924//2924 2923//2923 -f 2888//2888 2923//2923 2889//2889 -f 2889//2889 2923//2923 2918//2918 -f 2889//2889 2918//2918 2892//2892 -f 2892//2892 2918//2918 2893//2893 -f 2893//2893 2918//2918 2917//2917 -f 2893//2893 2917//2917 2894//2894 -f 2894//2894 2917//2917 2895//2895 -f 2895//2895 2917//2917 2931//2931 -f 2895//2895 2931//2931 2896//2896 -f 2896//2896 2931//2931 2930//2930 -f 2896//2896 2930//2930 2800//2800 -f 2800//2800 2930//2930 2929//2929 -f 2800//2800 2929//2929 2825//2825 -f 2825//2825 2929//2929 2826//2826 -f 2826//2826 2929//2929 2922//2922 -f 2826//2826 2922//2922 2823//2823 -f 2823//2823 2922//2922 2920//2920 -f 2823//2823 2920//2920 2824//2824 -f 2824//2824 2920//2920 2919//2919 -f 2824//2824 2919//2919 2827//2827 -f 2827//2827 2919//2919 2935//2935 -f 2827//2827 2935//2935 2828//2828 -f 2828//2828 2935//2935 2945//2945 -f 2828//2828 2945//2945 2829//2829 -f 2829//2829 2945//2945 2944//2944 -f 2829//2829 2944//2944 2830//2830 -f 2830//2830 2944//2944 2943//2943 -f 2830//2830 2943//2943 2831//2831 -f 2831//2831 2943//2943 2822//2822 -f 2822//2822 2943//2943 2951//2951 -f 2822//2822 2951//2951 2805//2805 -f 2805//2805 2951//2951 2942//2942 -f 2805//2805 2942//2942 2813//2813 -f 2813//2813 2942//2942 2941//2941 -f 2813//2813 2941//2941 2812//2812 -f 2812//2812 2941//2941 2940//2940 -f 2812//2812 2940//2940 2814//2814 -f 2814//2814 2940//2940 2815//2815 -f 2815//2815 2940//2940 2950//2950 -f 2815//2815 2950//2950 2816//2816 -f 2816//2816 2950//2950 2937//2937 -f 2816//2816 2937//2937 2820//2820 -f 2820//2820 2937//2937 2821//2821 -f 2821//2821 2937//2937 2936//2936 -f 2821//2821 2936//2936 2817//2817 -f 2817//2817 2936//2936 2921//2921 -f 2817//2817 2921//2921 2818//2818 -f 2818//2818 2921//2921 2819//2819 -f 2819//2819 2921//2921 2911//2911 -f 2819//2819 2911//2911 2811//2811 -f 2811//2811 2911//2911 2901//2901 -f 2811//2811 2901//2901 2808//2808 -f 2808//2808 2901//2901 2900//2900 -f 2808//2808 2900//2900 2832//2832 -f 2900//2900 2905//2905 2832//2832 -f 2832//2832 2905//2905 2928//2928 -f 2832//2832 2928//2928 2833//2833 -f 2833//2833 2928//2928 2834//2834 -f 2834//2834 2928//2928 2948//2948 -f 2834//2834 2948//2948 2835//2835 -f 2835//2835 2948//2948 2949//2949 -f 2835//2835 2949//2949 2836//2836 -f 2947//2947 2838//2838 2949//2949 -f 2949//2949 2838//2838 2837//2837 -f 2949//2949 2837//2837 2836//2836 -f 2842//2842 2841//2841 2946//2946 -f 2946//2946 2841//2841 2840//2840 -f 2946//2946 2840//2840 2947//2947 -f 2947//2947 2840//2840 2839//2839 -f 2947//2947 2839//2839 2838//2838 -# 5902 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower.obj deleted file mode 100644 index 4ac8119c6..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower.obj +++ /dev/null @@ -1,5412 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mid_lower_osnovno.obj -# -# Vertices: 1322 -# Faces: 2752 -# -#### -vn 0.074336 -0.724742 -0.684999 -v 0.094790 0.072745 0.056000 -vn 0.535422 -0.719805 0.441820 -v 0.094790 0.072745 0.065031 -vn -0.577350 -0.577350 -0.577351 -v 0.090006 0.072745 0.056000 -vn -0.707107 -0.707107 0.000000 -v 0.090006 0.072745 0.063375 -vn 0.597122 -0.731386 0.329424 -v 0.093943 0.072745 0.066200 -vn 0.656118 -0.734674 0.172519 -v 0.093244 0.072745 0.067888 -vn -0.707107 -0.707107 -0.000000 -v 0.090006 0.072745 0.074200 -vn 0.690278 -0.722129 0.045244 -v 0.093006 0.072745 0.069700 -vn -0.707107 -0.707107 -0.000000 -v 0.090006 0.072745 0.091200 -vn 0.694702 -0.718166 0.040331 -v 0.093006 0.072745 0.102000 -vn -0.694702 -0.718166 0.040331 -v 0.090006 0.072745 0.102000 -vn 0.690277 0.722130 0.045244 -v 0.093006 0.108745 0.069700 -vn 0.657463 0.733948 0.170481 -v 0.093244 0.108745 0.067888 -vn -0.707107 0.707107 0.000000 -v 0.090006 0.108745 0.063375 -vn -0.707107 0.707107 -0.000000 -v 0.090006 0.108745 0.074200 -vn -0.707107 0.707107 -0.000000 -v 0.090006 0.108745 0.091200 -vn 0.694702 0.718166 0.040331 -v 0.093006 0.108745 0.102000 -vn -0.694702 0.718166 0.040331 -v 0.090006 0.108745 0.102000 -vn 0.072580 0.723866 -0.686112 -v 0.094790 0.108745 0.056000 -vn -0.577350 0.577350 -0.577350 -v 0.090006 0.108745 0.056000 -vn 0.531534 0.721252 0.444148 -v 0.094790 0.108745 0.065031 -vn 0.599151 0.727321 0.334698 -v 0.093943 0.108745 0.066200 -vn 0.720554 0.051157 -0.691509 -v 0.101006 0.098369 0.056000 -vn -0.637727 -0.000001 -0.770263 -v 0.098506 0.090865 0.056000 -vn -0.552290 -0.318864 -0.770260 -v 0.098305 0.091615 0.056000 -vn 0.318862 -0.552289 -0.770263 -v 0.096256 0.092164 0.056000 -vn 0.552289 -0.318862 -0.770262 -v 0.095707 0.091615 0.056000 -vn -0.707107 -0.000000 -0.707107 -v 0.090006 0.103463 0.056000 -vn 0.637730 -0.000001 -0.770260 -v 0.095506 0.090865 0.056000 -vn -0.707107 -0.000000 -0.707107 -v 0.090006 0.078027 0.056000 -vn -0.318866 -0.552287 -0.770262 -v 0.097756 0.082664 0.056000 -vn -0.318864 0.552288 -0.770262 -v 0.097756 0.089566 0.056000 -vn -0.552288 0.318864 -0.770262 -v 0.098305 0.090115 0.056000 -vn -0.552290 -0.318864 -0.770260 -v 0.098305 0.082115 0.056000 -vn 0.720554 -0.051157 -0.691509 -v 0.101006 0.083121 0.056000 -vn -0.639154 -0.001548 -0.769077 -v 0.098506 0.081365 0.056000 -vn 0.706757 -0.164780 -0.687998 -v 0.100637 0.080535 0.056000 -vn -0.554748 0.320305 -0.767892 -v 0.098305 0.080615 0.056000 -vn 0.552287 0.318863 -0.770264 -v 0.095707 0.090115 0.056000 -vn 0.318864 0.552290 -0.770261 -v 0.096256 0.089566 0.056000 -vn 0.552289 -0.318862 -0.770262 -v 0.095707 0.082115 0.056000 -vn 0.000001 0.637727 -0.770263 -v 0.097006 0.089365 0.056000 -vn 0.000001 -0.637727 -0.770263 -v 0.097006 0.082865 0.056000 -vn 0.318865 -0.552288 -0.770261 -v 0.096256 0.082664 0.056000 -vn 0.320201 -0.554695 -0.767974 -v 0.096256 0.101664 0.056000 -vn -0.707107 0.000000 -0.707107 -v 0.090006 0.108070 0.056000 -vn 0.554551 -0.319614 -0.768323 -v 0.095707 0.101115 0.056000 -vn 0.637729 0.000000 -0.770261 -v 0.095506 0.081365 0.056000 -vn 0.552363 0.318917 -0.770187 -v 0.095707 0.080615 0.056000 -vn 0.320886 0.552822 -0.769039 -v 0.096256 0.080066 0.056000 -vn 0.638702 0.001033 -0.769453 -v 0.095506 0.100365 0.056000 -vn 0.552289 0.318862 -0.770263 -v 0.095707 0.099615 0.056000 -vn 0.318865 0.552288 -0.770261 -v 0.096256 0.099066 0.056000 -vn 0.000001 -0.637730 -0.770260 -v 0.097006 0.092365 0.056000 -vn 0.000001 0.637727 -0.770262 -v 0.097006 0.098865 0.056000 -vn -0.318863 -0.552287 -0.770264 -v 0.097756 0.092164 0.056000 -vn -0.318866 0.552286 -0.770262 -v 0.097756 0.099066 0.056000 -vn -0.320233 0.554726 -0.767939 -v 0.097756 0.080066 0.056000 -vn 0.667162 -0.285026 -0.688226 -v 0.099824 0.078052 0.056000 -vn 0.000001 0.640499 -0.767959 -v 0.097006 0.079865 0.056000 -vn 0.296116 0.683790 -0.666894 -v 0.095983 0.108498 0.056000 -vn -0.001454 -0.639171 -0.769063 -v 0.097006 0.101865 0.056000 -vn 0.506165 0.532615 -0.678320 -v 0.096979 0.107796 0.056000 -vn -0.318901 -0.552368 -0.770189 -v 0.097756 0.101664 0.056000 -vn 0.605539 0.395813 -0.690402 -v 0.098592 0.105742 0.056000 -vn -0.552340 -0.318902 -0.770210 -v 0.098305 0.101115 0.056000 -vn 0.665822 0.283575 -0.690121 -v 0.099824 0.103438 0.056000 -vn -0.637727 0.000000 -0.770263 -v 0.098506 0.100365 0.056000 -vn 0.706333 0.163509 -0.688737 -v 0.100636 0.100955 0.056000 -vn -0.552290 0.318864 -0.770260 -v 0.098305 0.099615 0.056000 -vn 0.607357 -0.396575 -0.688364 -v 0.098592 0.075749 0.056000 -vn 0.507064 -0.534420 -0.676225 -v 0.096979 0.073694 0.056000 -vn 0.297211 -0.685828 -0.664309 -v 0.095983 0.072993 0.056000 -vn -0.769976 -0.319096 0.552553 -v 0.090006 0.101681 0.063008 -vn -1.000000 0.000000 0.000000 -v 0.090006 0.103463 0.063375 -vn -0.682753 0.571245 0.455552 -v 0.090006 0.106564 0.108235 -vn -0.682753 0.658292 0.317016 -v 0.090006 0.107755 0.106339 -vn -1.000000 0.000000 0.000000 -v 0.090006 0.108070 0.104825 -vn -0.737700 -0.669353 -0.088122 -v 0.090006 0.102831 0.106000 -vn -0.682753 0.317016 0.658292 -v 0.090006 0.103084 0.111010 -vn -1.000000 0.000000 0.000000 -v 0.090006 0.103463 0.104825 -vn -0.682753 0.455552 0.571245 -v 0.090006 0.104980 0.109818 -vn -0.770262 0.318865 -0.552287 -v 0.090006 0.079809 0.107992 -vn -0.682753 -0.317016 0.658292 -v 0.090006 0.078406 0.111010 -vn -0.737700 0.088122 -0.669353 -v 0.090006 0.080959 0.108300 -vn -0.682753 -0.162584 0.712331 -v 0.090006 0.080520 0.111749 -vn -0.770261 -0.552290 -0.318863 -v 0.090006 0.102523 0.107150 -vn -0.770263 -0.318864 -0.552287 -v 0.090006 0.101681 0.107992 -vn -0.682753 0.162584 0.712331 -v 0.090006 0.100970 0.111749 -vn -0.737700 -0.088122 -0.669353 -v 0.090006 0.100531 0.108300 -vn -0.694702 0.040331 0.718166 -v 0.090006 0.098745 0.112000 -vn -0.694702 -0.040331 0.718166 -v 0.090006 0.082745 0.112000 -vn -0.682754 -0.658292 0.317017 -v 0.090006 0.073736 0.106339 -vn -0.682753 -0.571245 0.455552 -v 0.090006 0.074927 0.108235 -vn -1.000000 0.000000 0.000000 -v 0.090006 0.078027 0.104825 -vn -0.682753 -0.455552 0.571245 -v 0.090006 0.076510 0.109818 -vn -0.770262 0.637727 0.000001 -v 0.090006 0.074095 0.099700 -vn -0.770262 0.552288 0.318865 -v 0.090006 0.074316 0.098875 -vn -0.770262 0.318864 0.552289 -v 0.090006 0.074920 0.098271 -vn -1.000000 -0.000000 -0.000000 -v 0.090006 0.078027 0.091200 -vn -0.770262 -0.000001 0.637727 -v 0.090006 0.075745 0.098050 -vn -0.770262 -0.318865 0.552288 -v 0.090006 0.076570 0.098271 -vn -0.770262 -0.552288 0.318865 -v 0.090006 0.077174 0.098875 -vn -0.770262 -0.637728 0.000001 -v 0.090006 0.077395 0.099700 -vn -0.770262 -0.552289 -0.318864 -v 0.090006 0.077174 0.100525 -vn -0.770262 -0.318865 -0.552288 -v 0.090006 0.076570 0.101129 -vn -0.770262 -0.000001 -0.637727 -v 0.090006 0.075745 0.101350 -vn -0.682753 -0.712331 0.162586 -v 0.090006 0.072996 0.104225 -vn -0.770262 0.318864 -0.552289 -v 0.090006 0.074920 0.101129 -vn -0.770262 0.552289 -0.318864 -v 0.090006 0.074316 0.100525 -vn -0.770261 0.552290 -0.318863 -v 0.090006 0.078968 0.107150 -vn -0.737700 0.669353 -0.088122 -v 0.090006 0.078659 0.106000 -vn -0.707107 0.707107 0.000000 -v 0.090006 0.078659 0.104825 -vn -0.707107 0.707107 -0.000000 -v 0.090006 0.078659 0.091200 -vn -1.000000 -0.000000 -0.000000 -v 0.090006 0.078027 0.074200 -vn -0.707107 0.707107 -0.000000 -v 0.090006 0.078659 0.074200 -vn -1.000000 0.000000 0.000000 -v 0.090006 0.078027 0.063375 -vn -0.729848 0.680317 0.067005 -v 0.090006 0.078659 0.065000 -vn -0.768400 -0.553014 0.322084 -v 0.090006 0.102523 0.063850 -vn -0.735758 -0.671781 0.085855 -v 0.090006 0.102831 0.065000 -vn -1.000000 0.000000 -0.000000 -v 0.090006 0.103463 0.074200 -vn -0.707107 -0.707107 -0.000000 -v 0.090006 0.102831 0.074200 -vn -1.000000 0.000000 -0.000000 -v 0.090006 0.103463 0.091200 -vn -0.707107 -0.707107 -0.000000 -v 0.090006 0.102831 0.091200 -vn -0.707107 -0.707107 0.000000 -v 0.090006 0.102831 0.104825 -vn -0.754220 0.606325 0.252037 -v 0.090006 0.078835 0.064120 -vn -0.754177 0.464871 0.463802 -v 0.090006 0.079333 0.063374 -vn -0.752597 0.253408 0.607768 -v 0.090006 0.080079 0.062875 -vn -0.728641 0.065546 0.681752 -v 0.090006 0.080959 0.062700 -vn -0.737701 -0.088124 0.669352 -v 0.090006 0.100531 0.062700 -vn -0.770262 0.000001 -0.637728 -v 0.090006 0.105745 0.101350 -vn -0.770262 0.318865 -0.552288 -v 0.090006 0.104920 0.101129 -vn -0.770262 0.552288 0.318865 -v 0.090006 0.104316 0.098875 -vn -0.770262 0.637728 0.000001 -v 0.090006 0.104095 0.099700 -vn -0.770262 0.552289 -0.318864 -v 0.090006 0.104316 0.100525 -vn -0.770262 -0.318864 -0.552289 -v 0.090006 0.106570 0.101129 -vn -0.770262 0.318865 0.552288 -v 0.090006 0.104920 0.098271 -vn -0.770262 0.000001 0.637727 -v 0.090006 0.105745 0.098050 -vn -1.000000 -0.000000 -0.000000 -v 0.090006 0.108070 0.091200 -vn -0.770262 -0.318864 0.552289 -v 0.090006 0.106570 0.098271 -vn -0.770262 -0.552288 0.318865 -v 0.090006 0.107174 0.098875 -vn -0.770262 -0.637727 0.000001 -v 0.090006 0.107395 0.099700 -vn -0.770262 -0.552289 -0.318864 -v 0.090006 0.107174 0.100525 -vn -0.770261 0.318863 0.552290 -v 0.090006 0.074920 0.081271 -vn -0.770262 -0.000001 0.637727 -v 0.090006 0.075745 0.081050 -vn -0.770261 -0.318863 0.552290 -v 0.090006 0.076570 0.081271 -vn -0.770262 -0.552288 -0.318865 -v 0.090006 0.077174 0.083525 -vn -0.770260 -0.637730 -0.000000 -v 0.090006 0.077395 0.082700 -vn -0.770263 -0.552287 0.318865 -v 0.090006 0.077174 0.081875 -vn -0.770261 0.318863 -0.552291 -v 0.090006 0.074920 0.084129 -vn -0.770262 -0.000001 -0.637728 -v 0.090006 0.075745 0.084350 -vn -0.770260 -0.318864 -0.552291 -v 0.090006 0.076570 0.084129 -vn -0.770262 0.552288 -0.318865 -v 0.090006 0.074316 0.083525 -vn -0.770261 0.637729 -0.000000 -v 0.090006 0.074095 0.082700 -vn -0.770263 0.552287 0.318865 -v 0.090006 0.074316 0.081875 -vn -0.770261 -0.318863 0.552290 -v 0.090006 0.106570 0.081271 -vn -0.770263 -0.552287 0.318865 -v 0.090006 0.107174 0.081875 -vn -1.000000 -0.000000 -0.000000 -v 0.090006 0.108070 0.074200 -vn -0.770260 -0.637730 -0.000000 -v 0.090006 0.107395 0.082700 -vn -0.770262 0.000001 0.637727 -v 0.090006 0.105745 0.081050 -vn -0.770261 0.318863 0.552290 -v 0.090006 0.104920 0.081271 -vn -0.770262 -0.552288 -0.318865 -v 0.090006 0.107174 0.083525 -vn -0.770261 -0.318863 -0.552291 -v 0.090006 0.106570 0.084129 -vn -0.770262 0.000001 -0.637728 -v 0.090006 0.105745 0.084350 -vn -0.770260 0.318864 -0.552291 -v 0.090006 0.104920 0.084129 -vn -0.770262 0.552288 -0.318865 -v 0.090006 0.104316 0.083525 -vn -0.770260 0.637730 -0.000000 -v 0.090006 0.104095 0.082700 -vn -0.770263 0.552287 0.318865 -v 0.090006 0.104316 0.081875 -vn -0.767262 -0.000001 0.641334 -v 0.090006 0.075745 0.064050 -vn -0.767153 -0.320625 0.555586 -v 0.090006 0.076570 0.064271 -vn -0.765771 -0.557131 -0.321248 -v 0.090006 0.077174 0.066525 -vn -0.766301 -0.642481 0.000312 -v 0.090006 0.077395 0.065700 -vn -0.766799 -0.555690 0.321291 -v 0.090006 0.077174 0.064875 -vn -0.765430 -0.321901 -0.557222 -v 0.090006 0.076570 0.067129 -vn -0.767799 0.003334 -0.640682 -v 0.090006 0.075745 0.067350 -vn -0.769911 0.319163 -0.552604 -v 0.090006 0.074920 0.067129 -vn -0.769936 0.552674 -0.318983 -v 0.090006 0.074316 0.066525 -vn -0.769996 0.638049 0.000073 -v 0.090006 0.074095 0.065700 -vn -0.770047 0.552492 0.319031 -v 0.090006 0.074316 0.064875 -vn -0.768573 0.321553 0.553082 -v 0.090006 0.074920 0.064271 -vn -0.767262 0.000000 0.641334 -v 0.090006 0.105745 0.064050 -vn -0.767154 -0.320624 0.555586 -v 0.090006 0.106570 0.064271 -vn -1.000000 0.000000 0.000000 -v 0.090006 0.108070 0.063375 -vn -0.769911 0.319164 -0.552604 -v 0.090006 0.104920 0.067129 -vn -0.769936 0.552674 -0.318983 -v 0.090006 0.104316 0.066525 -vn -0.769996 0.638049 0.000073 -v 0.090006 0.104095 0.065700 -vn -0.770047 0.552492 0.319031 -v 0.090006 0.104316 0.064875 -vn -0.768573 0.321554 0.553082 -v 0.090006 0.104920 0.064271 -vn -0.766799 -0.555690 0.321291 -v 0.090006 0.107174 0.064875 -vn -0.766302 -0.642481 0.000312 -v 0.090006 0.107395 0.065700 -vn -0.765771 -0.557131 -0.321248 -v 0.090006 0.107174 0.066525 -vn -0.765431 -0.321901 -0.557222 -v 0.090006 0.106570 0.067129 -vn -0.767799 0.003335 -0.640682 -v 0.090006 0.105745 0.067350 -vn -0.682753 0.712331 0.162584 -v 0.090006 0.108494 0.104225 -vn 0.694702 -0.040331 0.718166 -v 0.093006 0.082745 0.112000 -vn 0.694702 0.040331 0.718166 -v 0.093006 0.098745 0.112000 -vn 0.708133 0.705899 -0.015965 -v 0.093767 0.104316 0.066525 -vn 0.813312 0.433421 -0.388162 -v 0.093495 0.104920 0.067129 -vn 0.774726 0.590393 -0.226352 -v 0.093607 0.104573 0.066861 -vn 0.829538 -0.223237 -0.511891 -v 0.093432 0.106174 0.067293 -vn 0.835576 0.008511 -0.549309 -v 0.093412 0.105745 0.067350 -vn 0.834305 0.213754 -0.508177 -v 0.093432 0.105316 0.067293 -vn 0.770033 -0.597310 -0.224210 -v 0.093607 0.106918 0.066860 -vn 0.810276 -0.429575 -0.398647 -v 0.093495 0.106570 0.067129 -vn 0.668360 -0.713302 0.210938 -v 0.093943 0.107318 0.066200 -vn 0.724733 -0.688186 -0.034096 -v 0.093767 0.107174 0.066525 -vn 0.510597 -0.600029 0.615837 -v 0.094588 0.107338 0.065268 -vn 0.584171 -0.683295 0.438009 -v 0.094261 0.107395 0.065700 -vn 0.375081 -0.357523 0.855273 -v 0.095333 0.106864 0.064488 -vn 0.443316 -0.480260 0.756849 -v 0.094934 0.107174 0.064875 -vn 0.335275 -0.118122 0.934686 -v 0.095790 0.106192 0.064112 -vn 0.346145 -0.247840 0.904853 -v 0.095587 0.106570 0.064271 -vn 0.337075 0.116898 0.934192 -v 0.095790 0.105299 0.064111 -vn 0.326251 -0.000126 0.945283 -v 0.095873 0.105745 0.064050 -vn 0.461577 0.503386 0.730444 -v 0.094935 0.104317 0.064875 -vn 0.428038 0.441506 0.788579 -v 0.095056 0.104396 0.064750 -vn 0.374619 0.353410 0.857182 -v 0.095332 0.104625 0.064489 -vn 0.349405 0.243865 0.904680 -v 0.095587 0.104920 0.064271 -vn 0.675476 0.716650 0.173621 -v 0.093938 0.104176 0.066210 -vn 0.581052 0.679718 0.447618 -v 0.094261 0.104095 0.065700 -vn 0.516997 0.602216 0.608318 -v 0.094589 0.104153 0.065266 -vn 0.770261 -0.637728 0.000001 -v 0.093006 0.077395 0.099700 -vn 0.770262 -0.552289 -0.318864 -v 0.093006 0.077174 0.100525 -vn 0.770262 -0.318865 -0.552288 -v 0.093006 0.076570 0.101129 -vn 0.770262 -0.000001 -0.637727 -v 0.093006 0.075745 0.101350 -vn 0.770262 0.318864 -0.552289 -v 0.093006 0.074920 0.101129 -vn 0.770262 0.552288 -0.318864 -v 0.093006 0.074316 0.100525 -vn 0.770262 0.637727 0.000001 -v 0.093006 0.074095 0.099700 -vn 0.770261 0.552289 0.318865 -v 0.093006 0.074316 0.098875 -vn 0.770262 0.318864 0.552289 -v 0.093006 0.074920 0.098271 -vn 0.770262 -0.000001 0.637728 -v 0.093006 0.075745 0.098050 -vn 0.770261 -0.318865 0.552289 -v 0.093006 0.076570 0.098271 -vn 0.770261 -0.552289 0.318865 -v 0.093006 0.077174 0.098875 -vn 0.770262 -0.637728 0.000001 -v 0.093006 0.107395 0.099700 -vn 0.770262 -0.552289 -0.318864 -v 0.093006 0.107174 0.100525 -vn 0.770262 -0.318864 -0.552288 -v 0.093006 0.106570 0.101129 -vn 0.770262 0.000001 -0.637727 -v 0.093006 0.105745 0.101350 -vn 0.770262 0.318865 -0.552288 -v 0.093006 0.104920 0.101129 -vn 0.770262 0.552288 -0.318864 -v 0.093006 0.104316 0.100525 -vn 0.770262 0.637728 0.000001 -v 0.093006 0.104095 0.099700 -vn 0.770261 0.552289 0.318865 -v 0.093006 0.104316 0.098875 -vn 0.770262 0.318865 0.552288 -v 0.093006 0.104920 0.098271 -vn 0.770261 0.000001 0.637729 -v 0.093006 0.105745 0.098050 -vn 0.770261 -0.318864 0.552289 -v 0.093006 0.106570 0.098271 -vn 0.770261 -0.552289 0.318865 -v 0.093006 0.107174 0.098875 -vn 0.770265 -0.637724 0.000001 -v 0.093006 0.107395 0.082700 -vn 0.770263 -0.552286 -0.318865 -v 0.093006 0.107174 0.083525 -vn 0.770261 -0.318862 -0.552290 -v 0.093006 0.106570 0.084129 -vn 0.770262 0.000001 -0.637727 -v 0.093006 0.105745 0.084350 -vn 0.770261 0.318863 -0.552290 -v 0.093006 0.104920 0.084129 -vn 0.770264 0.552285 -0.318865 -v 0.093006 0.104316 0.083525 -vn 0.770265 0.637724 0.000001 -v 0.093006 0.104095 0.082700 -vn 0.770263 0.552287 0.318865 -v 0.093006 0.104316 0.081875 -vn 0.770261 0.318863 0.552290 -v 0.093006 0.104920 0.081271 -vn 0.770262 0.000001 0.637728 -v 0.093006 0.105745 0.081050 -vn 0.770261 -0.318863 0.552290 -v 0.093006 0.106570 0.081271 -vn 0.770263 -0.552287 0.318865 -v 0.093006 0.107174 0.081875 -vn 0.770262 -0.637727 0.000000 -v 0.093006 0.077395 0.082700 -vn 0.770263 -0.552286 -0.318865 -v 0.093006 0.077174 0.083525 -vn 0.770261 -0.318863 -0.552290 -v 0.093006 0.076570 0.084129 -vn 0.770262 -0.000001 -0.637727 -v 0.093006 0.075745 0.084350 -vn 0.770261 0.318862 -0.552290 -v 0.093006 0.074920 0.084129 -vn 0.770263 0.552286 -0.318865 -v 0.093006 0.074316 0.083525 -vn 0.770263 0.637727 0.000000 -v 0.093006 0.074095 0.082700 -vn 0.770263 0.552287 0.318865 -v 0.093006 0.074316 0.081875 -vn 0.770261 0.318863 0.552290 -v 0.093006 0.074920 0.081271 -vn 0.770262 -0.000001 0.637728 -v 0.093006 0.075745 0.081050 -vn 0.770261 -0.318863 0.552290 -v 0.093006 0.076570 0.081271 -vn 0.770263 -0.552287 0.318865 -v 0.093006 0.077174 0.081875 -vn 0.709303 0.704738 -0.015280 -v 0.093767 0.074316 0.066525 -vn 0.813483 0.433270 -0.387972 -v 0.093495 0.074920 0.067129 -vn 0.775182 0.589907 -0.226061 -v 0.093607 0.074573 0.066861 -vn 0.829446 -0.223267 -0.512026 -v 0.093432 0.076174 0.067293 -vn 0.835576 0.008492 -0.549309 -v 0.093412 0.075745 0.067350 -vn 0.834396 0.213721 -0.508042 -v 0.093432 0.075316 0.067293 -vn 0.769574 -0.597791 -0.224503 -v 0.093607 0.076918 0.066860 -vn 0.810102 -0.429728 -0.398834 -v 0.093495 0.076570 0.067129 -vn 0.668360 -0.713302 0.210938 -v 0.093943 0.077318 0.066200 -vn 0.724463 -0.688434 -0.034816 -v 0.093767 0.077174 0.066525 -vn 0.510546 -0.600910 0.615020 -v 0.094588 0.077338 0.065268 -vn 0.582947 -0.684268 0.438121 -v 0.094261 0.077395 0.065700 -vn 0.381609 -0.355485 0.853232 -v 0.095333 0.076864 0.064488 -vn 0.445792 -0.479194 0.756070 -v 0.094934 0.077174 0.064875 -vn 0.342228 -0.115236 0.932524 -v 0.095790 0.076192 0.064112 -vn 0.353210 -0.240527 0.904096 -v 0.095587 0.076570 0.064271 -vn 0.335255 0.118031 0.934705 -v 0.095790 0.075299 0.064111 -vn 0.328823 0.001001 0.944391 -v 0.095873 0.075745 0.064050 -vn 0.461994 0.503092 0.730384 -v 0.094935 0.074317 0.064875 -vn 0.427525 0.441589 0.788810 -v 0.095056 0.074396 0.064750 -vn 0.384070 0.350491 0.854194 -v 0.095332 0.074625 0.064489 -vn 0.346973 0.238782 0.906969 -v 0.095587 0.074920 0.064271 -vn 0.675332 0.716597 0.174403 -v 0.093938 0.074176 0.066210 -vn 0.581951 0.678963 0.447595 -v 0.094261 0.074095 0.065700 -vn 0.517154 0.601391 0.608999 -v 0.094589 0.074153 0.065266 -vn 0.434907 0.623293 0.649894 -v 0.095329 0.078716 0.064492 -vn 0.369797 0.551196 0.747953 -v 0.095661 0.078799 0.064212 -vn 0.005055 0.004825 0.999976 -v 0.099991 0.080951 0.062700 -vn 0.000172 0.000148 1.000000 -v 0.100006 0.080959 0.062700 -vn -0.657105 0.222222 0.720299 -v 0.098450 0.080959 0.062700 -vn 0.028109 0.036472 0.998939 -v 0.099628 0.080743 0.062710 -vn 0.072527 0.097439 0.992595 -v 0.099035 0.080406 0.062768 -vn -0.575194 0.479373 0.662837 -v 0.098305 0.080615 0.062726 -vn 0.115033 0.208486 0.971237 -v 0.098118 0.079898 0.062959 -vn 0.001411 0.873948 0.486017 -v 0.097006 0.079865 0.062977 -vn 0.242180 0.332215 0.911582 -v 0.097097 0.079375 0.063333 -vn -0.165077 0.857273 0.487682 -v 0.097396 0.079917 0.062950 -vn 0.234288 0.282892 0.930098 -v 0.097238 0.079444 0.063270 -vn -0.276291 0.788282 0.549795 -v 0.097756 0.080066 0.062881 -vn -0.501335 0.643596 0.578315 -v 0.098074 0.080313 0.062793 -vn 0.284762 0.801788 0.525401 -v 0.096233 0.080079 0.062875 -vn 0.190896 0.872046 0.450660 -v 0.096615 0.079917 0.062950 -vn 0.295318 0.458070 0.838427 -v 0.096343 0.079039 0.063734 -vn 0.526725 0.697493 0.485865 -v 0.094818 0.078659 0.065000 -vn 0.483693 0.661997 0.572539 -v 0.095057 0.078673 0.064749 -vn 0.653061 0.209520 0.727745 -v 0.095562 0.080959 0.062700 -vn 0.567031 0.456977 0.685309 -v 0.095707 0.080615 0.062726 -vn 0.436369 0.637522 0.634939 -v 0.095937 0.080313 0.062793 -vn 0.690278 0.722129 0.045244 -v 0.093006 0.078659 0.069700 -vn 0.657704 0.733789 0.170235 -v 0.093244 0.078659 0.067888 -vn 0.598943 0.727172 0.335393 -v 0.093943 0.078659 0.066200 -vn 0.737701 0.669352 -0.088122 -v 0.093006 0.078659 0.106000 -vn 0.737700 0.088122 -0.669353 -v 0.093006 0.080959 0.108300 -vn 0.770262 0.318865 -0.552287 -v 0.093006 0.079809 0.107992 -vn 0.770261 0.552290 -0.318863 -v 0.093006 0.078968 0.107150 -vn 0.737700 -0.088121 -0.669353 -v 0.093006 0.100531 0.108300 -vn 0.737700 -0.669353 -0.088122 -v 0.093006 0.102831 0.106000 -vn 0.770261 -0.552290 -0.318863 -v 0.093006 0.102523 0.107150 -vn 0.770263 -0.318864 -0.552287 -v 0.093006 0.101681 0.107992 -vn 0.524693 -0.701632 0.482090 -v 0.094818 0.102831 0.065000 -vn 0.597026 -0.731333 0.329714 -v 0.093943 0.102831 0.066200 -vn 0.656399 -0.734484 0.172261 -v 0.093244 0.102831 0.067888 -vn 0.690278 -0.722128 0.045244 -v 0.093006 0.102831 0.069700 -vn 0.462854 -0.634579 0.618931 -v 0.095125 0.102809 0.064682 -vn 0.396715 -0.585952 0.706596 -v 0.095661 0.102692 0.064212 -vn 0.348862 -0.553882 0.755983 -v 0.095854 0.102632 0.064064 -vn 0.000172 -0.000148 1.000000 -v 0.100006 0.100531 0.062700 -vn 0.005056 -0.004825 0.999976 -v 0.099991 0.100539 0.062700 -vn -0.666990 -0.171251 0.725118 -v 0.098496 0.100531 0.062700 -vn 0.030559 -0.039979 0.998733 -v 0.099628 0.100747 0.062710 -vn -0.558346 -0.487274 0.671427 -v 0.098305 0.101115 0.062775 -vn 0.068033 -0.138672 0.987999 -v 0.098730 0.101256 0.062817 -vn -0.413105 -0.689471 0.594957 -v 0.098065 0.101427 0.062882 -vn 0.117796 -0.217893 0.968838 -v 0.098196 0.101550 0.062938 -vn -0.303555 -0.785412 0.539427 -v 0.097756 0.101664 0.062999 -vn 0.147397 -0.251316 0.956616 -v 0.097953 0.101680 0.063008 -vn -0.232481 -0.820275 0.522591 -v 0.097718 0.101685 0.063011 -vn 0.166620 -0.277365 0.946206 -v 0.097861 0.101729 0.063037 -vn -0.133105 -0.869734 0.475233 -v 0.097381 0.101818 0.063094 -vn 0.220577 -0.350995 0.910027 -v 0.097238 0.102047 0.063270 -vn 0.018340 -0.895968 0.443739 -v 0.097006 0.101865 0.063127 -vn 0.331617 -0.368913 0.868293 -v 0.096522 0.102377 0.063629 -vn 0.161770 -0.893687 0.418514 -v 0.096629 0.101817 0.063093 -vn 0.311531 -0.440354 0.842043 -v 0.096168 0.102520 0.063846 -vn 0.270035 -0.854552 0.443647 -v 0.096285 0.101681 0.063008 -vn 0.677548 -0.189031 0.710771 -v 0.095515 0.100531 0.062700 -vn 0.572743 -0.485002 0.660862 -v 0.095707 0.101115 0.062775 -vn 0.410270 -0.699025 0.585699 -v 0.095946 0.101427 0.062882 -vn 0.720554 -0.051157 0.691509 -v 0.101006 0.083121 0.062700 -vn 0.706962 -0.160267 0.688854 -v 0.100637 0.080535 0.062700 -vn 0.692128 -0.241617 0.680132 -v 0.100006 0.078498 0.062700 -vn 0.701597 0.253470 0.665969 -v 0.100006 0.102993 0.062700 -vn 0.706471 0.158745 0.689709 -v 0.100636 0.100955 0.062700 -vn 0.720554 0.051157 0.691509 -v 0.101006 0.098369 0.062700 -vn -0.654994 -0.040935 0.754524 -v 0.098506 0.081365 0.062700 -vn 0.664138 0.068796 0.744438 -v 0.095506 0.100365 0.062700 -vn 0.552289 0.318862 0.770262 -v 0.095707 0.099615 0.062700 -vn 0.552289 -0.318862 0.770263 -v 0.095707 0.091615 0.062700 -vn 0.318862 -0.552289 0.770262 -v 0.096256 0.092164 0.062700 -vn 0.318865 0.552288 0.770261 -v 0.096256 0.099066 0.062700 -vn 0.000001 0.637727 0.770262 -v 0.097006 0.098865 0.062700 -vn 0.000001 -0.637730 0.770260 -v 0.097006 0.092365 0.062700 -vn -0.318866 0.552287 0.770262 -v 0.097756 0.099066 0.062700 -vn -0.318863 -0.552287 0.770264 -v 0.097756 0.092164 0.062700 -vn -0.552290 0.318864 0.770260 -v 0.098305 0.099615 0.062700 -vn -0.660475 0.063391 0.748168 -v 0.098506 0.100365 0.062700 -vn 0.552289 -0.318862 0.770262 -v 0.095707 0.082115 0.062700 -vn 0.652608 -0.037792 0.756753 -v 0.095506 0.081365 0.062700 -vn -0.552290 -0.318864 0.770260 -v 0.098305 0.091615 0.062700 -vn -0.637727 -0.000001 0.770262 -v 0.098506 0.090865 0.062700 -vn -0.552288 0.318864 0.770262 -v 0.098305 0.090115 0.062700 -vn -0.318865 0.552289 0.770262 -v 0.097756 0.089566 0.062700 -vn 0.637730 -0.000001 0.770260 -v 0.095506 0.090865 0.062700 -vn 0.552287 0.318863 0.770264 -v 0.095707 0.090115 0.062700 -vn 0.318865 -0.552288 0.770261 -v 0.096256 0.082664 0.062700 -vn -0.552290 -0.318864 0.770260 -v 0.098305 0.082115 0.062700 -vn -0.318866 -0.552286 0.770262 -v 0.097756 0.082664 0.062700 -vn 0.000001 -0.637727 0.770262 -v 0.097006 0.082865 0.062700 -vn 0.000001 0.637727 0.770263 -v 0.097006 0.089365 0.062700 -vn 0.318864 0.552290 0.770260 -v 0.096256 0.089566 0.062700 -vn 0.682753 -0.712331 0.162586 -v 0.093006 0.072996 0.104225 -vn 0.682754 -0.658292 0.317017 -v 0.093006 0.073736 0.106339 -vn 0.682753 -0.571245 0.455552 -v 0.093006 0.074927 0.108235 -vn 0.682753 -0.455552 0.571245 -v 0.093006 0.076510 0.109818 -vn 0.682753 -0.317016 0.658292 -v 0.093006 0.078406 0.111010 -vn 0.682753 -0.162584 0.712331 -v 0.093006 0.080520 0.111749 -vn 0.682753 0.162584 0.712331 -v 0.093006 0.100970 0.111749 -vn 0.682753 0.317016 0.658292 -v 0.093006 0.103084 0.111010 -vn 0.682753 0.455552 0.571245 -v 0.093006 0.104980 0.109818 -vn 0.682753 0.571245 0.455552 -v 0.093006 0.106564 0.108235 -vn 0.682753 0.658292 0.317016 -v 0.093006 0.107755 0.106339 -vn 0.682753 0.712331 0.162584 -v 0.093006 0.108494 0.104225 -vn 0.710493 0.463694 0.529328 -v 0.096979 0.107796 0.063388 -vn 0.672227 0.551101 0.494367 -v 0.096506 0.108206 0.063638 -vn 0.524024 0.707538 0.474120 -v 0.095056 0.108733 0.064750 -vn 0.554979 0.676713 0.483796 -v 0.095507 0.108658 0.064337 -vn 0.600000 0.631078 0.491671 -v 0.095983 0.108498 0.063971 -vn 0.718645 0.414552 0.558297 -v 0.097607 0.107083 0.063124 -vn 0.712928 0.389973 0.582799 -v 0.098214 0.106293 0.062933 -vn 0.695972 0.358674 0.622074 -v 0.098592 0.105742 0.062844 -vn 0.699334 0.321604 0.638359 -v 0.099257 0.104619 0.062740 -vn 0.721098 -0.412379 0.556742 -v 0.097605 0.074405 0.063125 -vn 0.709277 -0.470260 0.525149 -v 0.096979 0.073694 0.063388 -vn 0.696415 -0.365700 0.617470 -v 0.098592 0.075749 0.062844 -vn 0.711466 -0.386791 0.586693 -v 0.098194 0.075169 0.062939 -vn 0.697114 -0.290050 0.655670 -v 0.099824 0.078052 0.062702 -vn 0.700516 -0.326426 0.634606 -v 0.099256 0.076870 0.062740 -vn 0.525684 -0.704465 0.476850 -v 0.095057 0.072757 0.064749 -vn 0.671044 -0.550110 0.497070 -v 0.096506 0.073284 0.063638 -vn 0.600459 -0.631952 0.489985 -v 0.095983 0.072993 0.063971 -vn 0.556204 -0.675951 0.483454 -v 0.095510 0.072833 0.064334 -vn -0.074337 0.724742 -0.684999 -v 0.055216 0.108985 0.056000 -vn -0.535425 0.719803 0.441818 -v 0.055216 0.108985 0.065031 -vn 0.577350 0.577350 -0.577350 -v 0.060001 0.108985 0.056000 -vn 0.707107 0.707107 0.000000 -v 0.060001 0.108985 0.063375 -vn -0.597121 0.731386 0.329425 -v 0.056063 0.108985 0.066200 -vn -0.656118 0.734675 0.172518 -v 0.056762 0.108985 0.067888 -vn 0.707107 0.707107 0.000000 -v 0.060001 0.108985 0.074200 -vn -0.690278 0.722128 0.045243 -v 0.057001 0.108985 0.069700 -vn 0.707107 0.707107 0.000000 -v 0.060001 0.108985 0.091200 -vn -0.694702 0.718166 0.040331 -v 0.057001 0.108985 0.102000 -vn 0.694702 0.718166 0.040331 -v 0.060001 0.108985 0.102000 -vn -0.690277 -0.722129 0.045243 -v 0.057001 0.072985 0.069700 -vn -0.657463 -0.733947 0.170480 -v 0.056762 0.072985 0.067888 -vn 0.707107 -0.707107 0.000000 -v 0.060001 0.072985 0.063375 -vn 0.707107 -0.707107 0.000000 -v 0.060001 0.072985 0.074200 -vn 0.707107 -0.707107 0.000000 -v 0.060001 0.072985 0.091200 -vn -0.694702 -0.718166 0.040331 -v 0.057001 0.072985 0.102000 -vn 0.694702 -0.718166 0.040331 -v 0.060001 0.072985 0.102000 -vn -0.072580 -0.723866 -0.686113 -v 0.055216 0.072985 0.056000 -vn 0.577350 -0.577350 -0.577350 -v 0.060001 0.072985 0.056000 -vn -0.531539 -0.721249 0.444146 -v 0.055216 0.072985 0.065031 -vn -0.599150 -0.727321 0.334699 -v 0.056063 0.072985 0.066200 -vn -0.720554 -0.051157 -0.691509 -v 0.049001 0.083361 0.056000 -vn 0.637728 -0.000001 -0.770261 -v 0.051501 0.090865 0.056000 -vn 0.552286 0.318864 -0.770263 -v 0.051701 0.090115 0.056000 -vn -0.318864 0.552289 -0.770261 -v 0.053751 0.089566 0.056000 -vn -0.552288 0.318863 -0.770263 -v 0.054300 0.090115 0.056000 -vn 0.707107 0.000000 -0.707107 -v 0.060001 0.078267 0.056000 -vn -0.637728 -0.000001 -0.770261 -v 0.054501 0.090865 0.056000 -vn 0.707107 0.000000 -0.707106 -v 0.060001 0.103703 0.056000 -vn 0.318865 0.552288 -0.770262 -v 0.052251 0.099066 0.056000 -vn 0.318862 -0.552289 -0.770263 -v 0.052251 0.092164 0.056000 -vn 0.552288 -0.318864 -0.770262 -v 0.051701 0.091615 0.056000 -vn 0.552289 0.318864 -0.770262 -v 0.051701 0.099615 0.056000 -vn -0.720554 0.051157 -0.691509 -v 0.049001 0.098609 0.056000 -vn 0.639155 0.001548 -0.769076 -v 0.051501 0.100365 0.056000 -vn -0.706757 0.164780 -0.687999 -v 0.049370 0.101195 0.056000 -vn 0.554746 -0.320305 -0.767894 -v 0.051701 0.101115 0.056000 -vn -0.552290 -0.318863 -0.770261 -v 0.054300 0.091615 0.056000 -vn -0.318862 -0.552288 -0.770263 -v 0.053751 0.092164 0.056000 -vn -0.552289 0.318863 -0.770262 -v 0.054300 0.099615 0.056000 -vn 0.000000 -0.637730 -0.770260 -v 0.053001 0.092365 0.056000 -vn 0.000000 0.637727 -0.770263 -v 0.053001 0.098865 0.056000 -vn -0.318866 0.552287 -0.770262 -v 0.053751 0.099066 0.056000 -vn -0.320199 0.554695 -0.767976 -v 0.053751 0.080066 0.056000 -vn 0.707107 0.000000 -0.707107 -v 0.060001 0.073660 0.056000 -vn -0.554552 0.319615 -0.768322 -v 0.054300 0.080615 0.056000 -vn -0.637728 0.000000 -0.770262 -v 0.054501 0.100365 0.056000 -vn -0.552364 -0.318918 -0.770186 -v 0.054300 0.101115 0.056000 -vn -0.320889 -0.552821 -0.769038 -v 0.053751 0.101664 0.056000 -vn -0.638701 -0.001033 -0.769455 -v 0.054501 0.081365 0.056000 -vn -0.552290 -0.318863 -0.770261 -v 0.054300 0.082115 0.056000 -vn -0.318866 -0.552287 -0.770262 -v 0.053751 0.082664 0.056000 -vn 0.000000 0.637727 -0.770263 -v 0.053001 0.089365 0.056000 -vn 0.000000 -0.637727 -0.770263 -v 0.053001 0.082865 0.056000 -vn 0.318864 0.552290 -0.770260 -v 0.052251 0.089566 0.056000 -vn 0.318865 -0.552288 -0.770261 -v 0.052251 0.082664 0.056000 -vn 0.320235 -0.554728 -0.767936 -v 0.052251 0.101664 0.056000 -vn -0.667162 0.285026 -0.688226 -v 0.050182 0.103678 0.056000 -vn 0.000000 -0.640495 -0.767962 -v 0.053001 0.101865 0.056000 -vn -0.296117 -0.683789 -0.666894 -v 0.054023 0.073233 0.056000 -vn 0.001456 0.639174 -0.769061 -v 0.053001 0.079865 0.056000 -vn -0.506165 -0.532614 -0.678321 -v 0.053027 0.073934 0.056000 -vn 0.318898 0.552370 -0.770189 -v 0.052251 0.080066 0.056000 -vn -0.605539 -0.395813 -0.690401 -v 0.051414 0.075989 0.056000 -vn 0.552338 0.318901 -0.770211 -v 0.051701 0.080615 0.056000 -vn -0.665822 -0.283574 -0.690121 -v 0.050182 0.078292 0.056000 -vn 0.637728 0.000000 -0.770262 -v 0.051501 0.081365 0.056000 -vn -0.706333 -0.163509 -0.688737 -v 0.049370 0.080775 0.056000 -vn 0.552288 -0.318864 -0.770262 -v 0.051701 0.082115 0.056000 -vn -0.607357 0.396576 -0.688364 -v 0.051414 0.105982 0.056000 -vn -0.507064 0.534420 -0.676226 -v 0.053027 0.108036 0.056000 -vn -0.297212 0.685827 -0.664308 -v 0.054023 0.108738 0.056000 -vn 0.769976 0.319096 0.552553 -v 0.060001 0.080049 0.063008 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.078267 0.063375 -vn 0.682753 -0.571245 0.455552 -v 0.060001 0.075167 0.108235 -vn 0.682753 -0.658292 0.317016 -v 0.060001 0.073976 0.106339 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.073660 0.104825 -vn 0.737700 0.669353 -0.088122 -v 0.060001 0.078899 0.106000 -vn 0.682753 -0.317016 0.658292 -v 0.060001 0.078646 0.111010 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.078267 0.104825 -vn 0.682753 -0.455552 0.571245 -v 0.060001 0.076750 0.109818 -vn 0.770262 -0.318865 -0.552287 -v 0.060001 0.101921 0.107992 -vn 0.682753 0.317016 0.658292 -v 0.060001 0.103324 0.111010 -vn 0.737700 -0.088122 -0.669353 -v 0.060001 0.100771 0.108300 -vn 0.682753 0.162585 0.712330 -v 0.060001 0.101210 0.111749 -vn 0.770261 0.552290 -0.318863 -v 0.060001 0.079208 0.107150 -vn 0.770263 0.318864 -0.552287 -v 0.060001 0.080049 0.107992 -vn 0.682753 -0.162584 0.712331 -v 0.060001 0.080760 0.111749 -vn 0.737700 0.088122 -0.669353 -v 0.060001 0.081199 0.108300 -vn 0.694702 -0.040331 0.718166 -v 0.060001 0.082985 0.112000 -vn 0.694702 0.040331 0.718166 -v 0.060001 0.098985 0.112000 -vn 0.682754 0.658292 0.317017 -v 0.060001 0.107995 0.106339 -vn 0.682753 0.571245 0.455552 -v 0.060001 0.106804 0.108235 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.103703 0.104825 -vn 0.682753 0.455552 0.571245 -v 0.060001 0.105220 0.109818 -vn 0.770262 -0.637727 0.000001 -v 0.060001 0.107635 0.099700 -vn 0.770262 -0.552288 0.318865 -v 0.060001 0.107414 0.098875 -vn 0.770262 -0.318865 0.552288 -v 0.060001 0.106810 0.098271 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.103703 0.091200 -vn 0.770262 -0.000001 0.637727 -v 0.060001 0.105985 0.098050 -vn 0.770262 0.318864 0.552289 -v 0.060001 0.105160 0.098271 -vn 0.770262 0.552288 0.318865 -v 0.060001 0.104556 0.098875 -vn 0.770262 0.637728 0.000001 -v 0.060001 0.104335 0.099700 -vn 0.770262 0.552289 -0.318864 -v 0.060001 0.104556 0.100525 -vn 0.770262 0.318864 -0.552289 -v 0.060001 0.105160 0.101129 -vn 0.770262 -0.000001 -0.637727 -v 0.060001 0.105985 0.101350 -vn 0.682753 0.712331 0.162586 -v 0.060001 0.108734 0.104225 -vn 0.770262 -0.318865 -0.552288 -v 0.060001 0.106810 0.101129 -vn 0.770262 -0.552289 -0.318864 -v 0.060001 0.107414 0.100525 -vn 0.770261 -0.552290 -0.318863 -v 0.060001 0.102763 0.107150 -vn 0.737700 -0.669353 -0.088122 -v 0.060001 0.103071 0.106000 -vn 0.707107 -0.707107 0.000000 -v 0.060001 0.103071 0.104825 -vn 0.707107 -0.707107 0.000000 -v 0.060001 0.103071 0.091200 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.103703 0.074200 -vn 0.707107 -0.707107 0.000000 -v 0.060001 0.103071 0.074200 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.103703 0.063375 -vn 0.729848 -0.680317 0.067005 -v 0.060001 0.103071 0.065000 -vn 0.768400 0.553013 0.322083 -v 0.060001 0.079208 0.063850 -vn 0.735758 0.671780 0.085855 -v 0.060001 0.078899 0.065000 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.078267 0.074200 -vn 0.707107 0.707107 0.000000 -v 0.060001 0.078899 0.074200 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.078267 0.091200 -vn 0.707107 0.707107 0.000000 -v 0.060001 0.078899 0.091200 -vn 0.707107 0.707107 0.000000 -v 0.060001 0.078899 0.104825 -vn 0.754220 -0.606325 0.252037 -v 0.060001 0.102896 0.064120 -vn 0.754177 -0.464871 0.463802 -v 0.060001 0.102397 0.063374 -vn 0.752597 -0.253408 0.607768 -v 0.060001 0.101651 0.062875 -vn 0.728641 -0.065546 0.681752 -v 0.060001 0.100771 0.062700 -vn 0.737701 0.088123 0.669352 -v 0.060001 0.081199 0.062700 -vn 0.770262 -0.000001 -0.637728 -v 0.060001 0.075985 0.101350 -vn 0.770262 -0.318865 -0.552288 -v 0.060001 0.076810 0.101129 -vn 0.770262 -0.552288 0.318865 -v 0.060001 0.077414 0.098875 -vn 0.770262 -0.637728 0.000001 -v 0.060001 0.077635 0.099700 -vn 0.770262 -0.552289 -0.318864 -v 0.060001 0.077414 0.100525 -vn 0.770262 0.318864 -0.552289 -v 0.060001 0.075160 0.101129 -vn 0.770262 -0.318865 0.552288 -v 0.060001 0.076810 0.098271 -vn 0.770262 -0.000001 0.637727 -v 0.060001 0.075985 0.098050 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.073660 0.091200 -vn 0.770262 0.318864 0.552289 -v 0.060001 0.075160 0.098271 -vn 0.770262 0.552288 0.318865 -v 0.060001 0.074556 0.098875 -vn 0.770262 0.637727 0.000001 -v 0.060001 0.074335 0.099700 -vn 0.770262 0.552289 -0.318864 -v 0.060001 0.074556 0.100525 -vn 0.770261 -0.318863 0.552290 -v 0.060001 0.106810 0.081271 -vn 0.770262 -0.000001 0.637727 -v 0.060001 0.105985 0.081050 -vn 0.770261 0.318863 0.552290 -v 0.060001 0.105160 0.081271 -vn 0.770263 0.552287 -0.318865 -v 0.060001 0.104556 0.083525 -vn 0.770262 0.637728 0.000000 -v 0.060001 0.104335 0.082700 -vn 0.770263 0.552287 0.318865 -v 0.060001 0.104556 0.081875 -vn 0.770261 -0.318863 -0.552290 -v 0.060001 0.106810 0.084129 -vn 0.770262 -0.000001 -0.637728 -v 0.060001 0.105985 0.084350 -vn 0.770261 0.318863 -0.552290 -v 0.060001 0.105160 0.084129 -vn 0.770263 -0.552287 -0.318865 -v 0.060001 0.107414 0.083525 -vn 0.770262 -0.637728 -0.000000 -v 0.060001 0.107635 0.082700 -vn 0.770263 -0.552287 0.318865 -v 0.060001 0.107414 0.081875 -vn 0.770261 0.318863 0.552290 -v 0.060001 0.075160 0.081271 -vn 0.770263 0.552287 0.318865 -v 0.060001 0.074556 0.081875 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.073660 0.074200 -vn 0.770262 0.637728 0.000000 -v 0.060001 0.074335 0.082700 -vn 0.770262 -0.000001 0.637727 -v 0.060001 0.075985 0.081050 -vn 0.770261 -0.318863 0.552290 -v 0.060001 0.076810 0.081271 -vn 0.770263 0.552287 -0.318865 -v 0.060001 0.074556 0.083525 -vn 0.770261 0.318863 -0.552290 -v 0.060001 0.075160 0.084129 -vn 0.770262 -0.000001 -0.637727 -v 0.060001 0.075985 0.084350 -vn 0.770261 -0.318863 -0.552290 -v 0.060001 0.076810 0.084129 -vn 0.770263 -0.552287 -0.318865 -v 0.060001 0.077414 0.083525 -vn 0.770262 -0.637728 -0.000000 -v 0.060001 0.077635 0.082700 -vn 0.770263 -0.552287 0.318865 -v 0.060001 0.077414 0.081875 -vn 0.767262 -0.000000 0.641334 -v 0.060001 0.105985 0.064050 -vn 0.767154 0.320624 0.555586 -v 0.060001 0.105160 0.064271 -vn 0.765771 0.557131 -0.321248 -v 0.060001 0.104556 0.066525 -vn 0.766301 0.642481 0.000312 -v 0.060001 0.104335 0.065700 -vn 0.766799 0.555690 0.321291 -v 0.060001 0.104556 0.064875 -vn 0.765431 0.321901 -0.557222 -v 0.060001 0.105160 0.067129 -vn 0.767799 -0.003335 -0.640682 -v 0.060001 0.105985 0.067350 -vn 0.769911 -0.319164 -0.552604 -v 0.060001 0.106810 0.067129 -vn 0.769936 -0.552674 -0.318983 -v 0.060001 0.107414 0.066525 -vn 0.769996 -0.638049 0.000072 -v 0.060001 0.107635 0.065700 -vn 0.770047 -0.552492 0.319031 -v 0.060001 0.107414 0.064875 -vn 0.768573 -0.321553 0.553082 -v 0.060001 0.106810 0.064271 -vn 0.767262 -0.000000 0.641334 -v 0.060001 0.075985 0.064050 -vn 0.767154 0.320624 0.555586 -v 0.060001 0.075160 0.064271 -vn 1.000000 0.000000 0.000000 -v 0.060001 0.073660 0.063375 -vn 0.769911 -0.319164 -0.552604 -v 0.060001 0.076810 0.067129 -vn 0.769936 -0.552674 -0.318983 -v 0.060001 0.077414 0.066525 -vn 0.769996 -0.638049 0.000072 -v 0.060001 0.077635 0.065700 -vn 0.770047 -0.552492 0.319031 -v 0.060001 0.077414 0.064875 -vn 0.768573 -0.321553 0.553082 -v 0.060001 0.076810 0.064271 -vn 0.766799 0.555690 0.321291 -v 0.060001 0.074556 0.064875 -vn 0.766302 0.642481 0.000312 -v 0.060001 0.074335 0.065700 -vn 0.765771 0.557131 -0.321248 -v 0.060001 0.074556 0.066525 -vn 0.765431 0.321901 -0.557222 -v 0.060001 0.075160 0.067129 -vn 0.767799 -0.003335 -0.640682 -v 0.060001 0.075985 0.067350 -vn 0.682753 -0.712331 0.162584 -v 0.060001 0.073236 0.104225 -vn -0.694702 0.040331 0.718166 -v 0.057001 0.098985 0.112000 -vn -0.694702 -0.040331 0.718166 -v 0.057001 0.082985 0.112000 -vn -0.708137 -0.705895 -0.015970 -v 0.056239 0.077414 0.066525 -vn -0.813307 -0.433420 -0.388173 -v 0.056511 0.076810 0.067129 -vn -0.774728 -0.590394 -0.226345 -v 0.056399 0.077157 0.066861 -vn -0.829544 0.223240 -0.511880 -v 0.056574 0.075556 0.067293 -vn -0.835576 -0.008510 -0.549309 -v 0.056594 0.075985 0.067350 -vn -0.834312 -0.213759 -0.508164 -v 0.056574 0.076414 0.067293 -vn -0.770032 0.597312 -0.224206 -v 0.056399 0.074812 0.066860 -vn -0.810272 0.429569 -0.398659 -v 0.056511 0.075160 0.067129 -vn -0.668359 0.713303 0.210939 -v 0.056063 0.074413 0.066200 -vn -0.724733 0.688186 -0.034096 -v 0.056239 0.074556 0.066525 -vn -0.510599 0.600029 0.615836 -v 0.055418 0.074393 0.065268 -vn -0.584170 0.683294 0.438011 -v 0.055745 0.074335 0.065700 -vn -0.375081 0.357523 0.855273 -v 0.054673 0.074866 0.064488 -vn -0.443318 0.480261 0.756848 -v 0.055072 0.074556 0.064875 -vn -0.335274 0.118123 0.934686 -v 0.054216 0.075539 0.064112 -vn -0.346147 0.247841 0.904852 -v 0.054419 0.075160 0.064271 -vn -0.337079 -0.116899 0.934191 -v 0.054216 0.076431 0.064111 -vn -0.326249 0.000126 0.945284 -v 0.054133 0.075985 0.064050 -vn -0.461588 -0.503385 0.730438 -v 0.055072 0.077414 0.064875 -vn -0.428040 -0.441511 0.788574 -v 0.054950 0.077334 0.064750 -vn -0.374617 -0.353411 0.857183 -v 0.054674 0.077106 0.064489 -vn -0.349405 -0.243864 0.904681 -v 0.054419 0.076810 0.064271 -vn -0.675474 -0.716652 0.173621 -v 0.056068 0.077554 0.066210 -vn -0.581051 -0.679716 0.447621 -v 0.055745 0.077635 0.065700 -vn -0.516997 -0.602215 0.608318 -v 0.055417 0.077577 0.065266 -vn -0.770262 0.637727 0.000001 -v 0.057001 0.104335 0.099700 -vn -0.770262 0.552289 -0.318864 -v 0.057001 0.104556 0.100525 -vn -0.770262 0.318864 -0.552288 -v 0.057001 0.105160 0.101129 -vn -0.770262 -0.000001 -0.637727 -v 0.057001 0.105985 0.101350 -vn -0.770262 -0.318865 -0.552288 -v 0.057001 0.106810 0.101129 -vn -0.770262 -0.552288 -0.318864 -v 0.057001 0.107414 0.100525 -vn -0.770262 -0.637727 0.000001 -v 0.057001 0.107635 0.099700 -vn -0.770262 -0.552288 0.318865 -v 0.057001 0.107414 0.098875 -vn -0.770261 -0.318865 0.552288 -v 0.057001 0.106810 0.098271 -vn -0.770262 -0.000001 0.637728 -v 0.057001 0.105985 0.098050 -vn -0.770262 0.318864 0.552289 -v 0.057001 0.105160 0.098271 -vn -0.770262 0.552288 0.318865 -v 0.057001 0.104556 0.098875 -vn -0.770262 0.637727 0.000001 -v 0.057001 0.074335 0.099700 -vn -0.770262 0.552289 -0.318864 -v 0.057001 0.074556 0.100525 -vn -0.770262 0.318864 -0.552288 -v 0.057001 0.075160 0.101129 -vn -0.770262 -0.000001 -0.637727 -v 0.057001 0.075985 0.101350 -vn -0.770262 -0.318865 -0.552288 -v 0.057001 0.076810 0.101129 -vn -0.770262 -0.552288 -0.318864 -v 0.057001 0.077414 0.100525 -vn -0.770262 -0.637727 0.000001 -v 0.057001 0.077635 0.099700 -vn -0.770262 -0.552288 0.318865 -v 0.057001 0.077414 0.098875 -vn -0.770262 -0.318865 0.552288 -v 0.057001 0.076810 0.098271 -vn -0.770261 -0.000001 0.637729 -v 0.057001 0.075985 0.098050 -vn -0.770261 0.318864 0.552289 -v 0.057001 0.075160 0.098271 -vn -0.770262 0.552288 0.318865 -v 0.057001 0.074556 0.098875 -vn -0.770262 0.637728 -0.000000 -v 0.057001 0.074335 0.082700 -vn -0.770263 0.552287 -0.318865 -v 0.057001 0.074556 0.083525 -vn -0.770261 0.318863 -0.552290 -v 0.057001 0.075160 0.084129 -vn -0.770262 -0.000001 -0.637727 -v 0.057001 0.075985 0.084350 -vn -0.770261 -0.318863 -0.552290 -v 0.057001 0.076810 0.084129 -vn -0.770263 -0.552287 -0.318865 -v 0.057001 0.077414 0.083525 -vn -0.770262 -0.637728 0.000000 -v 0.057001 0.077635 0.082700 -vn -0.770263 -0.552287 0.318865 -v 0.057001 0.077414 0.081875 -vn -0.770261 -0.318863 0.552290 -v 0.057001 0.076810 0.081271 -vn -0.770262 -0.000001 0.637728 -v 0.057001 0.075985 0.081050 -vn -0.770261 0.318863 0.552290 -v 0.057001 0.075160 0.081271 -vn -0.770263 0.552287 0.318865 -v 0.057001 0.074556 0.081875 -vn -0.770262 0.637728 -0.000000 -v 0.057001 0.104335 0.082700 -vn -0.770263 0.552286 -0.318865 -v 0.057001 0.104556 0.083525 -vn -0.770261 0.318863 -0.552290 -v 0.057001 0.105160 0.084129 -vn -0.770262 -0.000001 -0.637727 -v 0.057001 0.105985 0.084350 -vn -0.770261 -0.318863 -0.552290 -v 0.057001 0.106810 0.084129 -vn -0.770263 -0.552287 -0.318865 -v 0.057001 0.107414 0.083525 -vn -0.770262 -0.637728 0.000000 -v 0.057001 0.107635 0.082700 -vn -0.770263 -0.552287 0.318865 -v 0.057001 0.107414 0.081875 -vn -0.770261 -0.318863 0.552290 -v 0.057001 0.106810 0.081271 -vn -0.770262 -0.000001 0.637728 -v 0.057001 0.105985 0.081050 -vn -0.770261 0.318863 0.552290 -v 0.057001 0.105160 0.081271 -vn -0.770263 0.552287 0.318865 -v 0.057001 0.104556 0.081875 -vn -0.709306 -0.704735 -0.015285 -v 0.056239 0.107414 0.066525 -vn -0.813479 -0.433267 -0.387984 -v 0.056511 0.106810 0.067129 -vn -0.775183 -0.589908 -0.226054 -v 0.056399 0.107157 0.066861 -vn -0.829452 0.223270 -0.512015 -v 0.056574 0.105556 0.067293 -vn -0.835576 -0.008494 -0.549309 -v 0.056594 0.105985 0.067350 -vn -0.834402 -0.213726 -0.508031 -v 0.056574 0.106414 0.067293 -vn -0.769574 0.597793 -0.224499 -v 0.056399 0.104812 0.066860 -vn -0.810099 0.429723 -0.398846 -v 0.056511 0.105160 0.067129 -vn -0.668359 0.713303 0.210939 -v 0.056063 0.104413 0.066200 -vn -0.724463 0.688434 -0.034816 -v 0.056239 0.104556 0.066525 -vn -0.510548 0.600909 0.615019 -v 0.055418 0.104393 0.065268 -vn -0.582947 0.684267 0.438123 -v 0.055745 0.104335 0.065700 -vn -0.381609 0.355485 0.853232 -v 0.054673 0.104866 0.064488 -vn -0.445793 0.479195 0.756069 -v 0.055072 0.104556 0.064875 -vn -0.342227 0.115237 0.932524 -v 0.054216 0.105539 0.064112 -vn -0.353212 0.240528 0.904095 -v 0.054419 0.105160 0.064271 -vn -0.335257 -0.118033 0.934704 -v 0.054216 0.106431 0.064111 -vn -0.328820 -0.001002 0.944392 -v 0.054133 0.105985 0.064050 -vn -0.462006 -0.503090 0.730377 -v 0.055072 0.107414 0.064875 -vn -0.427528 -0.441593 0.788806 -v 0.054950 0.107334 0.064750 -vn -0.384067 -0.350491 0.854195 -v 0.054674 0.107106 0.064489 -vn -0.346972 -0.238781 0.906970 -v 0.054419 0.106810 0.064271 -vn -0.675330 -0.716599 0.174402 -v 0.056068 0.107554 0.066210 -vn -0.581951 -0.678962 0.447599 -v 0.055745 0.107635 0.065700 -vn -0.517154 -0.601391 0.609000 -v 0.055417 0.107577 0.065266 -vn -0.434904 -0.623295 0.649894 -v 0.054677 0.103014 0.064492 -vn -0.369796 -0.551195 0.747954 -v 0.054345 0.102932 0.064212 -vn -0.005055 -0.004825 0.999976 -v 0.050015 0.100779 0.062700 -vn -0.000172 -0.000148 1.000000 -v 0.050001 0.100771 0.062700 -vn 0.657105 -0.222218 0.720300 -v 0.051556 0.100771 0.062700 -vn -0.028109 -0.036473 0.998939 -v 0.050378 0.100987 0.062710 -vn -0.072528 -0.097438 0.992595 -v 0.050971 0.101324 0.062768 -vn 0.575189 -0.479374 0.662841 -v 0.051701 0.101115 0.062726 -vn -0.115033 -0.208486 0.971237 -v 0.051888 0.101832 0.062959 -vn -0.001412 -0.873949 0.486016 -v 0.053001 0.101865 0.062977 -vn -0.242180 -0.332217 0.911582 -v 0.052909 0.102355 0.063333 -vn 0.165087 -0.857272 0.487680 -v 0.052610 0.101814 0.062950 -vn -0.234288 -0.282891 0.930098 -v 0.052768 0.102287 0.063270 -vn 0.276294 -0.788282 0.549794 -v 0.052251 0.101664 0.062881 -vn 0.501330 -0.643600 0.578315 -v 0.051932 0.101418 0.062793 -vn -0.284760 -0.801789 0.525402 -v 0.053773 0.101651 0.062875 -vn -0.190902 -0.872046 0.450658 -v 0.053391 0.101814 0.062950 -vn -0.295319 -0.458069 0.838427 -v 0.053663 0.102691 0.063734 -vn -0.526724 -0.697493 0.485865 -v 0.055188 0.103071 0.065000 -vn -0.483696 -0.661996 0.572538 -v 0.054950 0.103057 0.064749 -vn -0.653056 -0.209522 0.727749 -v 0.054445 0.100771 0.062700 -vn -0.567033 -0.456980 0.685305 -v 0.054300 0.101115 0.062726 -vn -0.436370 -0.637520 0.634940 -v 0.054069 0.101418 0.062793 -vn -0.690278 -0.722128 0.045243 -v 0.057001 0.103071 0.069700 -vn -0.657704 -0.733788 0.170235 -v 0.056762 0.103071 0.067888 -vn -0.598942 -0.727172 0.335394 -v 0.056063 0.103071 0.066200 -vn -0.737701 -0.669352 -0.088122 -v 0.057001 0.103071 0.106000 -vn -0.737700 -0.088122 -0.669353 -v 0.057001 0.100771 0.108300 -vn -0.770262 -0.318865 -0.552287 -v 0.057001 0.101921 0.107992 -vn -0.770261 -0.552290 -0.318863 -v 0.057001 0.102763 0.107150 -vn -0.737700 0.088122 -0.669353 -v 0.057001 0.081199 0.108300 -vn -0.737700 0.669353 -0.088122 -v 0.057001 0.078899 0.106000 -vn -0.770261 0.552290 -0.318863 -v 0.057001 0.079208 0.107150 -vn -0.770263 0.318864 -0.552287 -v 0.057001 0.080049 0.107992 -vn -0.524691 0.701626 0.482100 -v 0.055188 0.078899 0.065000 -vn -0.597026 0.731333 0.329715 -v 0.056063 0.078899 0.066200 -vn -0.656399 0.734484 0.172260 -v 0.056762 0.078899 0.067888 -vn -0.690279 0.722128 0.045243 -v 0.057001 0.078899 0.069700 -vn -0.462852 0.634584 0.618927 -v 0.054881 0.078921 0.064682 -vn -0.396721 0.585950 0.706595 -v 0.054345 0.079039 0.064212 -vn -0.348866 0.553882 0.755981 -v 0.054152 0.079098 0.064064 -vn -0.000172 0.000148 1.000000 -v 0.050001 0.081199 0.062700 -vn -0.005056 0.004825 0.999976 -v 0.050015 0.081191 0.062700 -vn 0.666989 0.171243 0.725122 -v 0.051510 0.081199 0.062700 -vn -0.030559 0.039978 0.998733 -v 0.050378 0.080983 0.062710 -vn 0.558345 0.487275 0.671427 -v 0.051701 0.080615 0.062775 -vn -0.068033 0.138672 0.987999 -v 0.051276 0.080475 0.062817 -vn 0.413101 0.689473 0.594958 -v 0.051941 0.080304 0.062882 -vn -0.117797 0.217894 0.968838 -v 0.051810 0.080181 0.062938 -vn 0.303553 0.785414 0.539426 -v 0.052251 0.080066 0.062999 -vn -0.147398 0.251315 0.956616 -v 0.052053 0.080050 0.063008 -vn 0.232481 0.820275 0.522591 -v 0.052288 0.080045 0.063011 -vn -0.166620 0.277365 0.946206 -v 0.052145 0.080001 0.063037 -vn 0.133098 0.869734 0.475235 -v 0.052626 0.079913 0.063094 -vn -0.220581 0.350991 0.910027 -v 0.052768 0.079684 0.063270 -vn -0.018340 0.895968 0.443740 -v 0.053001 0.079865 0.063127 -vn -0.331615 0.368913 0.868294 -v 0.053485 0.079353 0.063629 -vn -0.161761 0.893688 0.418515 -v 0.053377 0.079913 0.063093 -vn -0.311529 0.440356 0.842043 -v 0.053838 0.079210 0.063846 -vn -0.270037 0.854551 0.443646 -v 0.053721 0.080049 0.063008 -vn -0.677547 0.189033 0.710772 -v 0.054491 0.081199 0.062700 -vn -0.572745 0.485002 0.660860 -v 0.054300 0.080615 0.062775 -vn -0.410270 0.699023 0.585700 -v 0.054060 0.080303 0.062882 -vn -0.720554 0.051157 0.691509 -v 0.049001 0.098609 0.062700 -vn -0.706961 0.160268 0.688854 -v 0.049370 0.101195 0.062700 -vn -0.692130 0.241615 0.680131 -v 0.050001 0.103233 0.062700 -vn -0.701599 -0.253469 0.665967 -v 0.050001 0.078738 0.062700 -vn -0.706471 -0.158746 0.689709 -v 0.049370 0.080775 0.062700 -vn -0.720554 -0.051157 0.691509 -v 0.049001 0.083361 0.062700 -vn 0.654995 0.040934 0.754524 -v 0.051501 0.100365 0.062700 -vn -0.664138 -0.068798 0.744438 -v 0.054501 0.081365 0.062700 -vn -0.552289 -0.318863 0.770262 -v 0.054300 0.082115 0.062700 -vn -0.552288 0.318863 0.770263 -v 0.054300 0.090115 0.062700 -vn -0.318864 0.552289 0.770261 -v 0.053751 0.089566 0.062700 -vn -0.318866 -0.552287 0.770262 -v 0.053751 0.082664 0.062700 -vn 0.000000 -0.637727 0.770263 -v 0.053001 0.082865 0.062700 -vn 0.000000 0.637727 0.770263 -v 0.053001 0.089365 0.062700 -vn 0.318865 -0.552288 0.770261 -v 0.052251 0.082664 0.062700 -vn 0.318864 0.552290 0.770260 -v 0.052251 0.089566 0.062700 -vn 0.552289 -0.318864 0.770262 -v 0.051701 0.082115 0.062700 -vn 0.660477 -0.063397 0.748165 -v 0.051501 0.081365 0.062700 -vn -0.552289 0.318863 0.770262 -v 0.054300 0.099615 0.062700 -vn -0.652608 0.037796 0.756752 -v 0.054501 0.100365 0.062700 -vn 0.552287 0.318864 0.770263 -v 0.051701 0.090115 0.062700 -vn 0.637728 -0.000001 0.770261 -v 0.051501 0.090865 0.062700 -vn 0.552289 -0.318864 0.770262 -v 0.051701 0.091615 0.062700 -vn 0.318862 -0.552289 0.770262 -v 0.052251 0.092164 0.062700 -vn -0.637728 -0.000001 0.770261 -v 0.054501 0.090865 0.062700 -vn -0.552289 -0.318863 0.770261 -v 0.054300 0.091615 0.062700 -vn -0.318866 0.552287 0.770262 -v 0.053751 0.099066 0.062700 -vn 0.552288 0.318864 0.770262 -v 0.051701 0.099615 0.062700 -vn 0.318865 0.552288 0.770261 -v 0.052251 0.099066 0.062700 -vn 0.000000 0.637727 0.770263 -v 0.053001 0.098865 0.062700 -vn 0.000000 -0.637730 0.770260 -v 0.053001 0.092365 0.062700 -vn -0.318862 -0.552288 0.770263 -v 0.053751 0.092164 0.062700 -vn -0.682753 0.712331 0.162586 -v 0.057001 0.108734 0.104225 -vn -0.682754 0.658292 0.317017 -v 0.057001 0.107995 0.106339 -vn -0.682753 0.571245 0.455552 -v 0.057001 0.106804 0.108235 -vn -0.682753 0.455552 0.571245 -v 0.057001 0.105220 0.109818 -vn -0.682753 0.317016 0.658292 -v 0.057001 0.103324 0.111010 -vn -0.682753 0.162585 0.712330 -v 0.057001 0.101210 0.111749 -vn -0.682753 -0.162584 0.712331 -v 0.057001 0.080760 0.111749 -vn -0.682753 -0.317016 0.658292 -v 0.057001 0.078646 0.111010 -vn -0.682753 -0.455552 0.571245 -v 0.057001 0.076750 0.109818 -vn -0.682753 -0.571245 0.455552 -v 0.057001 0.075167 0.108235 -vn -0.682753 -0.658292 0.317016 -v 0.057001 0.073976 0.106339 -vn -0.682753 -0.712331 0.162584 -v 0.057001 0.073236 0.104225 -vn -0.710497 -0.463691 0.529326 -v 0.053027 0.073934 0.063388 -vn -0.672228 -0.551100 0.494367 -v 0.053501 0.073524 0.063638 -vn -0.524026 -0.707538 0.474116 -v 0.054950 0.072997 0.064750 -vn -0.554978 -0.676713 0.483796 -v 0.054499 0.073072 0.064337 -vn -0.599997 -0.631080 0.491673 -v 0.054023 0.073233 0.063971 -vn -0.718644 -0.414553 0.558298 -v 0.052400 0.074648 0.063124 -vn -0.712926 -0.389975 0.582800 -v 0.051792 0.075437 0.062933 -vn -0.695971 -0.358676 0.622074 -v 0.051414 0.075989 0.062844 -vn -0.699335 -0.321603 0.638359 -v 0.050749 0.077112 0.062740 -vn -0.721097 0.412380 0.556742 -v 0.052402 0.107325 0.063125 -vn -0.709280 0.470258 0.525147 -v 0.053027 0.108036 0.063388 -vn -0.696415 0.365701 0.617470 -v 0.051414 0.105982 0.062844 -vn -0.711464 0.386792 0.586694 -v 0.051812 0.106562 0.062939 -vn -0.697116 0.290047 0.655669 -v 0.050182 0.103678 0.062702 -vn -0.700516 0.326425 0.634606 -v 0.050750 0.104860 0.062740 -vn -0.525686 0.704467 0.476845 -v 0.054949 0.108973 0.064749 -vn -0.671045 0.550110 0.497069 -v 0.053501 0.108446 0.063638 -vn -0.600458 0.631952 0.489986 -v 0.054023 0.108738 0.063971 -vn -0.556203 0.675951 0.483455 -v 0.054496 0.108898 0.064334 -vn -0.000000 0.637727 -0.770262 -v 0.097006 0.089265 0.055000 -vn 0.000000 0.637727 0.770262 -v 0.097006 0.089265 0.056000 -vn -0.318863 0.552290 -0.770261 -v 0.097806 0.089480 0.055000 -vn -0.318863 0.552290 0.770261 -v 0.097806 0.089480 0.056000 -vn -0.552287 0.318865 -0.770263 -v 0.098391 0.090065 0.055000 -vn -0.552287 0.318865 0.770263 -v 0.098391 0.090065 0.056000 -vn -0.637728 -0.000001 -0.770262 -v 0.098606 0.090865 0.055000 -vn -0.637728 -0.000001 0.770262 -v 0.098606 0.090865 0.056000 -vn -0.552287 -0.318866 -0.770262 -v 0.098391 0.091665 0.055000 -vn -0.552287 -0.318866 0.770262 -v 0.098391 0.091665 0.056000 -vn -0.318863 -0.552290 -0.770261 -v 0.097806 0.092251 0.055000 -vn -0.318863 -0.552290 0.770261 -v 0.097806 0.092251 0.056000 -vn 0.000000 -0.637727 -0.770262 -v 0.097006 0.092465 0.055000 -vn -0.000000 -0.637727 0.770262 -v 0.097006 0.092465 0.056000 -vn 0.318865 -0.552288 -0.770262 -v 0.096206 0.092251 0.055000 -vn 0.318865 -0.552288 0.770262 -v 0.096206 0.092251 0.056000 -vn 0.552288 -0.318865 -0.770262 -v 0.095620 0.091665 0.055000 -vn 0.552288 -0.318865 0.770262 -v 0.095620 0.091665 0.056000 -vn 0.637728 -0.000001 -0.770262 -v 0.095406 0.090865 0.055000 -vn 0.637728 -0.000001 0.770262 -v 0.095406 0.090865 0.056000 -vn 0.552289 0.318864 -0.770262 -v 0.095620 0.090065 0.055000 -vn 0.552289 0.318864 0.770262 -v 0.095620 0.090065 0.056000 -vn 0.318865 0.552288 -0.770262 -v 0.096206 0.089480 0.055000 -vn 0.318865 0.552288 0.770262 -v 0.096206 0.089480 0.056000 -vn -0.000000 0.637727 -0.770262 -v 0.097006 0.079765 0.055000 -vn 0.000000 0.637727 0.770262 -v 0.097006 0.079765 0.056000 -vn -0.318863 0.552290 -0.770261 -v 0.097806 0.079980 0.055000 -vn -0.318863 0.552290 0.770261 -v 0.097806 0.079980 0.056000 -vn -0.552287 0.318866 -0.770262 -v 0.098391 0.080565 0.055000 -vn -0.552287 0.318866 0.770262 -v 0.098391 0.080565 0.056000 -vn -0.637727 -0.000000 -0.770262 -v 0.098606 0.081365 0.055000 -vn -0.637727 0.000000 0.770262 -v 0.098606 0.081365 0.056000 -vn -0.552288 -0.318865 -0.770262 -v 0.098391 0.082165 0.055000 -vn -0.552288 -0.318865 0.770262 -v 0.098391 0.082165 0.056000 -vn -0.318865 -0.552288 -0.770262 -v 0.097806 0.082751 0.055000 -vn -0.318865 -0.552288 0.770262 -v 0.097806 0.082751 0.056000 -vn 0.000000 -0.637727 -0.770262 -v 0.097006 0.082965 0.055000 -vn -0.000000 -0.637727 0.770262 -v 0.097006 0.082965 0.056000 -vn 0.318866 -0.552287 -0.770262 -v 0.096206 0.082751 0.055000 -vn 0.318866 -0.552287 0.770262 -v 0.096206 0.082751 0.056000 -vn 0.552290 -0.318863 -0.770261 -v 0.095620 0.082165 0.055000 -vn 0.552290 -0.318863 0.770261 -v 0.095620 0.082165 0.056000 -vn 0.637727 0.000000 -0.770262 -v 0.095406 0.081365 0.055000 -vn 0.637727 -0.000000 0.770262 -v 0.095406 0.081365 0.056000 -vn 0.552288 0.318865 -0.770262 -v 0.095620 0.080565 0.055000 -vn 0.552288 0.318865 0.770262 -v 0.095620 0.080565 0.056000 -vn 0.318865 0.552288 -0.770262 -v 0.096206 0.079980 0.055000 -vn 0.318865 0.552288 0.770262 -v 0.096206 0.079980 0.056000 -vn -0.000000 0.637730 -0.770260 -v 0.097006 0.098765 0.055000 -vn 0.000000 0.637730 0.770260 -v 0.097006 0.098765 0.056000 -vn -0.318861 0.552289 -0.770263 -v 0.097806 0.098980 0.055000 -vn -0.318862 0.552289 0.770263 -v 0.097806 0.098980 0.056000 -vn -0.552288 0.318865 -0.770262 -v 0.098391 0.099565 0.055000 -vn -0.552288 0.318865 0.770262 -v 0.098391 0.099565 0.056000 -vn -0.637727 -0.000000 -0.770262 -v 0.098606 0.100365 0.055000 -vn -0.637727 0.000000 0.770262 -v 0.098606 0.100365 0.056000 -vn -0.552288 -0.318865 -0.770262 -v 0.098391 0.101165 0.055000 -vn -0.552288 -0.318865 0.770262 -v 0.098391 0.101165 0.056000 -vn -0.318862 -0.552289 -0.770263 -v 0.097806 0.101751 0.055000 -vn -0.318862 -0.552289 0.770263 -v 0.097806 0.101751 0.056000 -vn 0.000000 -0.637730 -0.770260 -v 0.097006 0.101965 0.055000 -vn -0.000000 -0.637730 0.770260 -v 0.097006 0.101965 0.056000 -vn 0.318863 -0.552287 -0.770263 -v 0.096206 0.101751 0.055000 -vn 0.318863 -0.552287 0.770263 -v 0.096206 0.101751 0.056000 -vn 0.552290 -0.318863 -0.770261 -v 0.095620 0.101165 0.055000 -vn 0.552290 -0.318863 0.770261 -v 0.095620 0.101165 0.056000 -vn 0.637727 0.000000 -0.770262 -v 0.095406 0.100365 0.055000 -vn 0.637727 -0.000000 0.770262 -v 0.095406 0.100365 0.056000 -vn 0.552290 0.318863 -0.770261 -v 0.095620 0.099565 0.055000 -vn 0.552290 0.318863 0.770261 -v 0.095620 0.099565 0.056000 -vn 0.318863 0.552287 -0.770263 -v 0.096206 0.098980 0.055000 -vn 0.318863 0.552287 0.770263 -v 0.096206 0.098980 0.056000 -vn -0.380741 -0.615386 0.690171 -v 0.059219 0.065238 0.056000 -vn -0.274934 -0.671886 0.687736 -v 0.063325 0.063116 0.056000 -vn -0.318864 0.552289 0.770261 -v 0.053801 0.079980 0.056000 -vn -0.552289 0.318863 0.770262 -v 0.076086 0.098125 0.056000 -vn -0.318863 0.552289 0.770262 -v 0.075628 0.097667 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.079003 0.094983 0.056000 -vn 0.000000 0.637728 0.770261 -v 0.075003 0.097500 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.071003 0.094983 0.056000 -vn 0.318863 0.552289 0.770262 -v 0.074378 0.097667 0.056000 -vn 0.552289 0.318863 0.770262 -v 0.073921 0.098125 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.071003 0.098133 0.056000 -vn 0.637728 -0.000000 0.770261 -v 0.073753 0.098750 0.056000 -vn 0.552289 -0.318863 0.770262 -v 0.073921 0.099375 0.056000 -vn 0.000000 0.707108 0.707106 -v 0.071003 0.119172 0.056000 -vn 0.318863 -0.552289 0.770262 -v 0.074378 0.099832 0.056000 -vn 0.000000 0.707107 0.707106 -v 0.079003 0.119172 0.056000 -vn -0.000000 -0.637728 0.770261 -v 0.075003 0.100000 0.056000 -vn -0.318863 -0.552289 0.770262 -v 0.075628 0.099832 0.056000 -vn -0.552289 -0.318863 0.770262 -v 0.076086 0.099375 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.079003 0.098133 0.056000 -vn -0.637728 0.000000 0.770261 -v 0.076253 0.098750 0.056000 -vn 0.318867 0.552288 0.770261 -v 0.074378 0.081667 0.056000 -vn 0.552289 0.318863 0.770262 -v 0.073921 0.082125 0.056000 -vn 0.000000 -0.707107 0.707106 -v 0.071003 0.062327 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.071003 0.083483 0.056000 -vn -0.318863 -0.552289 0.770262 -v 0.075628 0.083832 0.056000 -vn -0.552289 -0.318863 0.770262 -v 0.076086 0.083375 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.079003 0.083483 0.056000 -vn -0.637728 0.000000 0.770261 -v 0.076253 0.082750 0.056000 -vn 0.000000 -0.707108 0.707106 -v 0.079003 0.062327 0.056000 -vn -0.552289 0.318863 0.770262 -v 0.076086 0.082125 0.056000 -vn -0.318867 0.552288 0.770261 -v 0.075628 0.081667 0.056000 -vn 0.000000 0.637725 0.770264 -v 0.075003 0.081500 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.079003 0.086633 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.071003 0.086633 0.056000 -vn -0.000000 -0.637728 0.770261 -v 0.075003 0.084000 0.056000 -vn 0.637728 -0.000000 0.770261 -v 0.073753 0.082750 0.056000 -vn 0.552289 -0.318863 0.770262 -v 0.073921 0.083375 0.056000 -vn 0.318863 -0.552289 0.770262 -v 0.074378 0.083832 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.089829 0.083483 0.056000 -vn 0.707107 0.000001 0.707107 -v 0.103426 0.083483 0.056000 -vn 0.717113 -0.035871 0.696033 -v 0.103426 0.082965 0.056000 -vn 0.274935 -0.671884 0.687737 -v 0.086681 0.063116 0.056000 -vn 0.380741 -0.615386 0.690172 -v 0.090787 0.065238 0.056000 -vn 0.470755 -0.549593 0.690172 -v 0.094519 0.067966 0.056000 -vn 0.549594 -0.470754 0.690172 -v 0.097787 0.071234 0.056000 -vn 0.615385 -0.380741 0.690172 -v 0.100515 0.074966 0.056000 -vn 0.671886 -0.274933 0.687736 -v 0.102637 0.079072 0.056000 -vn 0.713737 -0.144619 0.685321 -v 0.103226 0.080979 0.056000 -vn 0.144620 -0.713738 0.685320 -v 0.084774 0.062527 0.056000 -vn 0.035869 -0.717113 0.696034 -v 0.082788 0.062327 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.053001 0.083483 0.056000 -vn -0.000000 -0.637727 0.770262 -v 0.053001 0.082965 0.056000 -vn -0.318865 -0.552288 0.770262 -v 0.053801 0.082751 0.056000 -vn -0.552289 -0.318864 0.770261 -v 0.054386 0.082165 0.056000 -vn -0.637727 0.000000 0.770262 -v 0.054601 0.081365 0.056000 -vn -0.552288 0.318865 0.770262 -v 0.054386 0.080565 0.056000 -vn -0.035869 -0.717113 0.696034 -v 0.067218 0.062327 0.056000 -vn -0.144618 -0.713738 0.685320 -v 0.065232 0.062527 0.056000 -vn 0.318864 0.552289 0.770261 -v 0.052201 0.079980 0.056000 -vn -0.615385 -0.380741 0.690172 -v 0.049491 0.074966 0.056000 -vn 0.000000 0.637727 0.770262 -v 0.053001 0.079765 0.056000 -vn -0.549593 -0.470755 0.690172 -v 0.052219 0.071234 0.056000 -vn -0.470755 -0.549593 0.690172 -v 0.055487 0.067966 0.056000 -vn 0.552288 0.318865 0.770262 -v 0.051615 0.080565 0.056000 -vn 0.637727 -0.000000 0.770262 -v 0.051401 0.081365 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.048991 0.083483 0.056000 -vn 0.552289 -0.318864 0.770261 -v 0.051615 0.082165 0.056000 -vn 0.318865 -0.552288 0.770262 -v 0.052201 0.082751 0.056000 -vn -0.671886 -0.274934 0.687736 -v 0.047369 0.079072 0.056000 -vn -0.713737 -0.144619 0.685321 -v 0.046780 0.080979 0.056000 -vn -0.713737 0.144619 0.685321 -v 0.046780 0.100521 0.056000 -vn -0.717113 0.035871 0.696033 -v 0.046581 0.098535 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.048991 0.098133 0.056000 -vn 0.552289 0.318864 0.770261 -v 0.051615 0.099565 0.056000 -vn 0.637727 -0.000000 0.770262 -v 0.051401 0.100365 0.056000 -vn -0.615385 0.380741 0.690172 -v 0.049491 0.106534 0.056000 -vn -0.671886 0.274934 0.687736 -v 0.047369 0.102428 0.056000 -vn 0.552289 -0.318864 0.770261 -v 0.051615 0.101165 0.056000 -vn 0.318862 -0.552288 0.770263 -v 0.052201 0.101751 0.056000 -vn -0.549593 0.470755 0.690172 -v 0.052219 0.110266 0.056000 -vn -0.000000 -0.637730 0.770260 -v 0.053001 0.101965 0.056000 -vn -0.470755 0.549594 0.690172 -v 0.055487 0.113534 0.056000 -vn -0.318862 -0.552288 0.770263 -v 0.053801 0.101751 0.056000 -vn -0.380741 0.615385 0.690172 -v 0.059219 0.116262 0.056000 -vn -0.552289 -0.318864 0.770261 -v 0.054386 0.101165 0.056000 -vn -0.637727 0.000000 0.770262 -v 0.054601 0.100365 0.056000 -vn -0.552289 0.318864 0.770261 -v 0.054386 0.099565 0.056000 -vn -0.318862 0.552288 0.770263 -v 0.053801 0.098980 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.053001 0.098133 0.056000 -vn 0.000000 0.637730 0.770260 -v 0.053001 0.098765 0.056000 -vn 0.318862 0.552288 0.770263 -v 0.052201 0.098980 0.056000 -vn -0.035871 0.717113 0.696033 -v 0.067218 0.119172 0.056000 -vn -0.144619 0.713737 0.685321 -v 0.065232 0.118973 0.056000 -vn -0.274933 0.671886 0.687736 -v 0.063325 0.118384 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.089829 0.098133 0.056000 -vn 0.707107 0.000000 0.707107 -v 0.103426 0.098133 0.056000 -vn 0.274932 0.671887 0.687736 -v 0.086681 0.118384 0.056000 -vn 0.144617 0.713737 0.685321 -v 0.084774 0.118973 0.056000 -vn 0.035871 0.717113 0.696033 -v 0.082788 0.119172 0.056000 -vn 0.380741 0.615385 0.690172 -v 0.090787 0.116262 0.056000 -vn 0.470755 0.549593 0.690172 -v 0.094519 0.113534 0.056000 -vn 0.549593 0.470755 0.690172 -v 0.097787 0.110266 0.056000 -vn 0.615385 0.380741 0.690172 -v 0.100515 0.106534 0.056000 -vn 0.671886 0.274933 0.687736 -v 0.102637 0.102428 0.056000 -vn 0.713737 0.144619 0.685321 -v 0.103226 0.100521 0.056000 -vn 0.717113 0.035871 0.696033 -v 0.103426 0.098535 0.056000 -vn -0.637725 0.000001 0.770264 -v 0.068253 0.090750 0.056000 -vn -0.552286 0.318869 0.770262 -v 0.068086 0.090125 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.071003 0.089383 0.056000 -vn -0.318864 -0.552290 0.770260 -v 0.053801 0.092251 0.056000 -vn 0.000000 -0.637725 0.770264 -v 0.067003 0.092000 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.071003 0.092233 0.056000 -vn -0.318866 -0.552291 0.770260 -v 0.067628 0.091832 0.056000 -vn -0.552286 -0.318868 0.770262 -v 0.068086 0.091375 0.056000 -vn -0.318865 0.552291 0.770260 -v 0.067628 0.089667 0.056000 -vn 0.000000 0.637725 0.770264 -v 0.067003 0.089500 0.056000 -vn -0.318864 0.552290 0.770261 -v 0.053801 0.089480 0.056000 -vn 0.318865 0.552291 0.770260 -v 0.066378 0.089667 0.056000 -vn -0.552287 0.318864 0.770262 -v 0.054386 0.090065 0.056000 -vn 0.552286 0.318865 0.770263 -v 0.065921 0.090125 0.056000 -vn -0.637728 -0.000001 0.770262 -v 0.054601 0.090865 0.056000 -vn 0.637729 0.000001 0.770261 -v 0.065753 0.090750 0.056000 -vn -0.552288 -0.318865 0.770262 -v 0.054386 0.091665 0.056000 -vn 0.552286 -0.318864 0.770263 -v 0.065921 0.091375 0.056000 -vn 0.318865 -0.552291 0.770260 -v 0.066378 0.091832 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.053001 0.094983 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.048991 0.094983 0.056000 -vn 0.318864 -0.552289 0.770261 -v 0.052201 0.092251 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.048991 0.092233 0.056000 -vn 0.552288 -0.318865 0.770262 -v 0.051615 0.091665 0.056000 -vn 0.637728 -0.000001 0.770262 -v 0.051401 0.090865 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.053001 0.086633 0.056000 -vn 0.000000 0.637727 0.770262 -v 0.053001 0.089265 0.056000 -vn 0.318864 0.552289 0.770261 -v 0.052201 0.089480 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.089829 0.094983 0.056000 -vn 0.707107 0.000000 0.707107 -v 0.103426 0.094983 0.056000 -vn 0.707107 0.000000 0.707107 -v 0.103426 0.092233 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.089829 0.092233 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.089829 0.089383 0.056000 -vn 0.707107 0.000000 0.707107 -v 0.103426 0.089383 0.056000 -vn 0.707107 0.000001 0.707107 -v 0.103426 0.086633 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.089829 0.086633 0.056000 -vn -0.637729 0.000001 0.770261 -v 0.084253 0.090750 0.056000 -vn -0.552286 0.318865 0.770263 -v 0.084086 0.090125 0.056000 -vn 0.637729 0.000001 0.770261 -v 0.081753 0.090750 0.056000 -vn 0.552286 -0.318864 0.770264 -v 0.081921 0.091375 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.079003 0.092233 0.056000 -vn -0.552286 -0.318864 0.770263 -v 0.084086 0.091375 0.056000 -vn -0.318865 0.552291 0.770260 -v 0.083628 0.089667 0.056000 -vn 0.000000 0.637725 0.770264 -v 0.083003 0.089500 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.079003 0.089383 0.056000 -vn 0.318866 0.552291 0.770260 -v 0.082378 0.089667 0.056000 -vn 0.552286 0.318865 0.770263 -v 0.081921 0.090125 0.056000 -vn 0.318865 -0.552291 0.770260 -v 0.082378 0.091832 0.056000 -vn 0.000000 -0.637725 0.770264 -v 0.083003 0.092000 0.056000 -vn -0.318866 -0.552291 0.770260 -v 0.083628 0.091832 0.056000 -vn -0.000000 -0.637727 0.770262 -v 0.053001 0.092465 0.056000 -vn 0.552288 0.318864 0.770262 -v 0.051615 0.090065 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.048991 0.089383 0.056000 -vn 0.000000 0.000000 1.000000 -v 0.048991 0.086633 0.056000 -vn -0.707107 0.000000 0.707107 -v 0.046581 0.098133 0.056000 -vn -0.707107 0.000000 0.707107 -v 0.046581 0.094983 0.056000 -vn -0.707107 0.000000 0.707107 -v 0.046581 0.092233 0.056000 -vn -0.707107 0.000000 0.707107 -v 0.046581 0.089383 0.056000 -vn -0.707107 0.000000 0.707107 -v 0.046581 0.086633 0.056000 -vn -0.707107 0.000000 0.707107 -v 0.046581 0.083483 0.056000 -vn -0.717113 -0.035871 0.696033 -v 0.046581 0.082965 0.056000 -vn -0.615385 0.380741 -0.690172 -v 0.049491 0.106534 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.048058 0.101683 0.052000 -vn -0.671886 0.274934 -0.687736 -v 0.047369 0.102428 0.052000 -vn 0.274932 0.671887 -0.687736 -v 0.086681 0.118384 0.052000 -vn 0.380741 0.615385 -0.690172 -v 0.090787 0.116262 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.088897 0.101683 0.052000 -vn -0.144619 0.713737 -0.685321 -v 0.065232 0.118973 0.052000 -vn -0.035871 0.717113 -0.696033 -v 0.067218 0.119172 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.071003 0.101683 0.052000 -vn -0.274933 0.671886 -0.687736 -v 0.063325 0.118384 0.052000 -vn -0.272352 -0.471728 -0.838628 -v 0.054733 0.103365 0.052000 -vn -0.380741 0.615385 -0.690172 -v 0.059219 0.116262 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.048058 0.095615 0.052000 -vn -0.717113 0.035871 -0.696033 -v 0.046581 0.098535 0.052000 -vn -0.713737 0.144619 -0.685321 -v 0.046780 0.100521 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.048058 0.084183 0.052000 -vn -0.671886 -0.274934 -0.687736 -v 0.047369 0.079072 0.052000 -vn -0.713737 -0.144619 -0.685321 -v 0.046780 0.080979 0.052000 -vn -0.272352 0.471728 -0.838628 -v 0.054733 0.078365 0.052000 -vn -0.470755 -0.549593 -0.690172 -v 0.055487 0.067966 0.052000 -vn 0.000000 0.707107 -0.707107 -v 0.053001 0.078365 0.052000 -vn -0.549593 -0.470755 -0.690172 -v 0.052219 0.071234 0.052000 -vn 0.272352 0.471728 -0.838628 -v 0.051268 0.078365 0.052000 -vn -0.615385 -0.380741 -0.690172 -v 0.049491 0.074966 0.052000 -vn 0.544705 -0.000000 -0.838628 -v 0.049536 0.081365 0.052000 -vn 0.000000 -0.707108 -0.707106 -v 0.071003 0.062327 0.052000 -vn -0.035869 -0.717113 -0.696034 -v 0.067218 0.062327 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.071003 0.084183 0.052000 -vn -0.144618 -0.713738 -0.685320 -v 0.065232 0.062527 0.052000 -vn -0.274934 -0.671885 -0.687737 -v 0.063325 0.063116 0.052000 -vn 0.380741 -0.615386 -0.690171 -v 0.090787 0.065238 0.052000 -vn 0.274935 -0.671884 -0.687737 -v 0.086681 0.063116 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.079003 0.084183 0.052000 -vn 0.144620 -0.713738 -0.685320 -v 0.084774 0.062527 0.052000 -vn 0.035869 -0.717113 -0.696034 -v 0.082788 0.062327 0.052000 -vn 0.000000 -0.707107 -0.707106 -v 0.079003 0.062327 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.088897 0.086115 0.052000 -vn 0.272352 -0.471728 -0.838628 -v 0.095274 0.084365 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.088897 0.084183 0.052000 -vn 0.544705 -0.000000 -0.838628 -v 0.093541 0.081365 0.052000 -vn 0.470755 -0.549593 -0.690172 -v 0.094519 0.067966 0.052000 -vn 0.272352 0.471728 -0.838628 -v 0.095274 0.078365 0.052000 -vn -0.544705 0.000000 -0.838628 -v 0.100470 0.081365 0.052000 -vn 0.671886 -0.274933 -0.687736 -v 0.102637 0.079072 0.052000 -vn -0.272352 0.471728 -0.838628 -v 0.098738 0.078365 0.052000 -vn 0.615385 -0.380741 -0.690172 -v 0.100515 0.074966 0.052000 -vn 0.549594 -0.470755 -0.690172 -v 0.097787 0.071234 0.052000 -vn -0.544705 0.000000 -0.838628 -v 0.100470 0.100365 0.052000 -vn 0.713737 0.144619 -0.685321 -v 0.103226 0.100521 0.052000 -vn -0.272352 0.471728 -0.838628 -v 0.098738 0.097365 0.052000 -vn 0.717113 0.035871 -0.696033 -v 0.103426 0.098535 0.052000 -vn 0.707107 0.000000 -0.707107 -v 0.103426 0.095615 0.052000 -vn 0.272352 0.471728 -0.838628 -v 0.095274 0.097365 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.088897 0.095615 0.052000 -vn 0.544705 -0.000000 -0.838628 -v 0.093541 0.100365 0.052000 -vn 0.272352 -0.471728 -0.838628 -v 0.095274 0.103365 0.052000 -vn 0.470755 0.549593 -0.690172 -v 0.094519 0.113534 0.052000 -vn 0.549593 0.470755 -0.690172 -v 0.097787 0.110266 0.052000 -vn -0.272352 -0.471728 -0.838628 -v 0.098738 0.103365 0.052000 -vn 0.615385 0.380741 -0.690172 -v 0.100515 0.106534 0.052000 -vn 0.671886 0.274933 -0.687736 -v 0.102637 0.102428 0.052000 -vn 0.707106 0.000001 -0.707107 -v 0.103426 0.086115 0.052000 -vn 0.707107 0.000001 -0.707106 -v 0.103426 0.084183 0.052000 -vn -0.272352 -0.471728 -0.838628 -v 0.098738 0.084365 0.052000 -vn 0.717113 -0.035871 -0.696033 -v 0.103426 0.082965 0.052000 -vn 0.713737 -0.144619 -0.685321 -v 0.103226 0.080979 0.052000 -vn 0.272352 -0.471728 -0.838628 -v 0.095274 0.093865 0.052000 -vn -0.272352 -0.471728 -0.838628 -v 0.098738 0.093865 0.052000 -vn 0.707107 0.000000 -0.707107 -v 0.103426 0.092933 0.052000 -vn -0.544705 -0.000000 -0.838628 -v 0.100470 0.090865 0.052000 -vn -0.272352 0.471728 -0.838628 -v 0.098738 0.087865 0.052000 -vn 0.707107 0.000000 -0.707107 -v 0.103426 0.088683 0.052000 -vn 0.272352 0.471728 -0.838628 -v 0.095274 0.087865 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.088897 0.088683 0.052000 -vn 0.544705 -0.000000 -0.838628 -v 0.093541 0.090865 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.088897 0.092933 0.052000 -vn 0.272352 0.471728 -0.838628 -v 0.051268 0.097365 0.052000 -vn 0.000000 0.707107 -0.707107 -v 0.053001 0.097365 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.053001 0.095615 0.052000 -vn -0.272352 0.471728 -0.838628 -v 0.054733 0.097365 0.052000 -vn 0.544705 -0.000000 -0.838628 -v 0.049536 0.100365 0.052000 -vn 0.272352 -0.471728 -0.838628 -v 0.051268 0.103365 0.052000 -vn 0.000000 -0.707107 -0.707107 -v 0.053001 0.103365 0.052000 -vn -0.549593 0.470755 -0.690172 -v 0.052219 0.110266 0.052000 -vn -0.470755 0.549593 -0.690172 -v 0.055487 0.113534 0.052000 -vn -0.272352 -0.471728 -0.838628 -v 0.054733 0.093865 0.052000 -vn 0.000000 -0.707107 -0.707107 -v 0.053001 0.093865 0.052000 -vn 0.272352 -0.471728 -0.838628 -v 0.051268 0.093865 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.048058 0.092933 0.052000 -vn 0.544705 -0.000000 -0.838628 -v 0.049536 0.090865 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.048058 0.088683 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.071003 0.088683 0.052000 -vn -0.272352 0.471728 -0.838628 -v 0.054733 0.087865 0.052000 -vn -0.544706 -0.000000 -0.838627 -v 0.056465 0.090865 0.052000 -vn 0.000000 -0.637725 -0.770264 -v 0.067003 0.092000 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.071003 0.092933 0.052000 -vn -0.318865 -0.552291 -0.770260 -v 0.067628 0.091832 0.052000 -vn -0.552286 -0.318868 -0.770262 -v 0.068086 0.091375 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.071003 0.095615 0.052000 -vn -0.544705 0.000000 -0.838628 -v 0.056465 0.100365 0.052000 -vn 0.318866 -0.552291 -0.770260 -v 0.066378 0.091832 0.052000 -vn 0.552286 -0.318864 -0.770264 -v 0.065921 0.091375 0.052000 -vn 0.637729 0.000001 -0.770261 -v 0.065753 0.090750 0.052000 -vn 0.552286 0.318865 -0.770263 -v 0.065921 0.090125 0.052000 -vn -0.637725 0.000001 -0.770264 -v 0.068253 0.090750 0.052000 -vn -0.552286 0.318869 -0.770262 -v 0.068086 0.090125 0.052000 -vn 0.318865 0.552291 -0.770260 -v 0.066378 0.089667 0.052000 -vn 0.000000 0.637725 -0.770264 -v 0.067003 0.089500 0.052000 -vn -0.318865 0.552291 -0.770260 -v 0.067628 0.089667 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.053001 0.086115 0.052000 -vn 0.000000 -0.707107 -0.707107 -v 0.053001 0.084365 0.052000 -vn 0.272352 -0.471728 -0.838628 -v 0.051268 0.084365 0.052000 -vn 0.272352 0.471728 -0.838628 -v 0.051268 0.087865 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.048058 0.086115 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.071003 0.086115 0.052000 -vn -0.272352 -0.471728 -0.838628 -v 0.054733 0.084365 0.052000 -vn -0.544705 0.000000 -0.838628 -v 0.056465 0.081365 0.052000 -vn -0.380741 -0.615386 -0.690172 -v 0.059219 0.065238 0.052000 -vn -0.717113 -0.035871 -0.696033 -v 0.046581 0.082965 0.052000 -vn -0.707107 0.000000 -0.707107 -v 0.046581 0.084183 0.052000 -vn -0.707107 0.000000 -0.707107 -v 0.046581 0.086115 0.052000 -vn -0.707107 0.000000 -0.707107 -v 0.046581 0.088683 0.052000 -vn -0.707107 0.000000 -0.707107 -v 0.046581 0.092933 0.052000 -vn -0.707107 0.000000 -0.707107 -v 0.046581 0.095615 0.052000 -vn 0.318867 0.552288 -0.770261 -v 0.074378 0.081667 0.052000 -vn 0.000000 0.637725 -0.770264 -v 0.075003 0.081500 0.052000 -vn 0.000000 -0.637728 -0.770261 -v 0.075003 0.084000 0.052000 -vn 0.318863 -0.552289 -0.770262 -v 0.074378 0.083832 0.052000 -vn -0.552289 -0.318863 -0.770262 -v 0.076086 0.083375 0.052000 -vn -0.318863 -0.552289 -0.770262 -v 0.075628 0.083832 0.052000 -vn -0.318867 0.552288 -0.770261 -v 0.075628 0.081667 0.052000 -vn -0.552289 0.318863 -0.770262 -v 0.076086 0.082125 0.052000 -vn -0.637728 -0.000000 -0.770261 -v 0.076253 0.082750 0.052000 -vn 0.552289 -0.318863 -0.770262 -v 0.073921 0.083375 0.052000 -vn 0.637728 0.000000 -0.770261 -v 0.073753 0.082750 0.052000 -vn 0.552289 0.318863 -0.770262 -v 0.073921 0.082125 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.079003 0.086115 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.079003 0.088683 0.052000 -vn 0.552289 -0.318863 -0.770262 -v 0.073921 0.099375 0.052000 -vn 0.637728 0.000000 -0.770261 -v 0.073753 0.098750 0.052000 -vn 0.552289 0.318863 -0.770262 -v 0.073921 0.098125 0.052000 -vn 0.318863 0.552289 -0.770262 -v 0.074378 0.097667 0.052000 -vn -0.000000 0.637728 -0.770261 -v 0.075003 0.097500 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.079003 0.095615 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.079003 0.092933 0.052000 -vn -0.318863 0.552289 -0.770262 -v 0.075628 0.097667 0.052000 -vn -0.552289 0.318863 -0.770262 -v 0.076086 0.098125 0.052000 -vn 0.000000 0.000000 -1.000000 -v 0.079003 0.101683 0.052000 -vn -0.637728 -0.000000 -0.770261 -v 0.076253 0.098750 0.052000 -vn -0.552289 -0.318863 -0.770262 -v 0.076086 0.099375 0.052000 -vn -0.318863 -0.552289 -0.770262 -v 0.075628 0.099832 0.052000 -vn 0.000000 -0.637728 -0.770261 -v 0.075003 0.100000 0.052000 -vn 0.318863 -0.552289 -0.770262 -v 0.074378 0.099832 0.052000 -vn 0.000000 0.707107 -0.707107 -v 0.071003 0.119172 0.052000 -vn 0.000000 0.707107 -0.707107 -v 0.079003 0.119172 0.052000 -vn 0.035871 0.717113 -0.696033 -v 0.082788 0.119172 0.052000 -vn 0.144617 0.713737 -0.685321 -v 0.084774 0.118973 0.052000 -vn 0.000000 -0.637725 -0.770264 -v 0.083003 0.092000 0.052000 -vn 0.318866 -0.552291 -0.770260 -v 0.082378 0.091832 0.052000 -vn 0.000000 0.637725 -0.770264 -v 0.083003 0.089500 0.052000 -vn -0.318865 0.552291 -0.770260 -v 0.083628 0.089667 0.052000 -vn 0.552286 -0.318864 -0.770263 -v 0.081921 0.091375 0.052000 -vn 0.000000 0.707107 -0.707107 -v 0.053001 0.087865 0.052000 -vn 0.637729 0.000001 -0.770261 -v 0.081753 0.090750 0.052000 -vn 0.552286 0.318865 -0.770263 -v 0.081921 0.090125 0.052000 -vn 0.318865 0.552291 -0.770260 -v 0.082378 0.089667 0.052000 -vn -0.552286 0.318865 -0.770263 -v 0.084086 0.090125 0.052000 -vn -0.637729 0.000001 -0.770261 -v 0.084253 0.090750 0.052000 -vn -0.552286 -0.318864 -0.770263 -v 0.084086 0.091375 0.052000 -vn -0.318865 -0.552291 -0.770260 -v 0.083628 0.091832 0.052000 -vn -0.000000 0.637727 -0.770262 -v 0.053001 0.089265 0.055000 -vn -0.318864 0.552289 -0.770261 -v 0.053801 0.089480 0.055000 -vn -0.552288 0.318864 -0.770262 -v 0.054386 0.090065 0.055000 -vn -0.637728 -0.000001 -0.770262 -v 0.054601 0.090865 0.055000 -vn -0.552288 -0.318865 -0.770262 -v 0.054386 0.091665 0.055000 -vn -0.318864 -0.552289 -0.770261 -v 0.053801 0.092251 0.055000 -vn 0.000000 -0.637727 -0.770262 -v 0.053001 0.092465 0.055000 -vn 0.318864 -0.552289 -0.770261 -v 0.052201 0.092251 0.055000 -vn 0.552288 -0.318865 -0.770262 -v 0.051615 0.091665 0.055000 -vn 0.637728 -0.000001 -0.770262 -v 0.051401 0.090865 0.055000 -vn 0.552288 0.318864 -0.770262 -v 0.051615 0.090065 0.055000 -vn 0.318864 0.552289 -0.770261 -v 0.052201 0.089480 0.055000 -vn -0.000000 0.637730 -0.770260 -v 0.053001 0.098765 0.055000 -vn -0.318862 0.552288 -0.770263 -v 0.053801 0.098980 0.055000 -vn -0.552289 0.318864 -0.770261 -v 0.054386 0.099565 0.055000 -vn -0.637727 -0.000000 -0.770262 -v 0.054601 0.100365 0.055000 -vn -0.552289 -0.318864 -0.770261 -v 0.054386 0.101165 0.055000 -vn -0.318862 -0.552288 -0.770263 -v 0.053801 0.101751 0.055000 -vn 0.000000 -0.637730 -0.770260 -v 0.053001 0.101965 0.055000 -vn 0.318862 -0.552288 -0.770263 -v 0.052201 0.101751 0.055000 -vn 0.552289 -0.318864 -0.770261 -v 0.051615 0.101165 0.055000 -vn 0.637727 0.000000 -0.770262 -v 0.051401 0.100365 0.055000 -vn 0.552289 0.318864 -0.770261 -v 0.051615 0.099565 0.055000 -vn 0.318862 0.552288 -0.770263 -v 0.052201 0.098980 0.055000 -vn -0.000000 0.637727 -0.770262 -v 0.053001 0.079765 0.055000 -vn -0.318864 0.552289 -0.770261 -v 0.053801 0.079980 0.055000 -vn -0.552288 0.318865 -0.770262 -v 0.054386 0.080565 0.055000 -vn -0.637727 -0.000000 -0.770262 -v 0.054601 0.081365 0.055000 -vn -0.552289 -0.318864 -0.770261 -v 0.054386 0.082165 0.055000 -vn -0.318865 -0.552288 -0.770262 -v 0.053801 0.082751 0.055000 -vn 0.000000 -0.637727 -0.770262 -v 0.053001 0.082965 0.055000 -vn 0.318865 -0.552288 -0.770262 -v 0.052201 0.082751 0.055000 -vn 0.552289 -0.318864 -0.770261 -v 0.051615 0.082165 0.055000 -vn 0.637727 0.000000 -0.770262 -v 0.051401 0.081365 0.055000 -vn 0.552288 0.318865 -0.770262 -v 0.051615 0.080565 0.055000 -vn 0.318864 0.552289 -0.770261 -v 0.052201 0.079980 0.055000 -vn 0.396203 -0.686244 -0.609994 -v 0.051268 0.084365 0.055000 -vn 0.792406 0.000000 -0.609994 -v 0.049536 0.081365 0.055000 -vn -0.396203 -0.686243 -0.609995 -v 0.054733 0.084365 0.055000 -vn 0.396203 0.686244 -0.609994 -v 0.051268 0.078365 0.055000 -vn -0.396203 0.686244 -0.609994 -v 0.054733 0.078365 0.055000 -vn -0.792406 -0.000000 -0.609994 -v 0.056465 0.081365 0.055000 -vn -0.396203 -0.686243 -0.609995 -v 0.054733 0.103365 0.055000 -vn 0.396203 -0.686244 -0.609994 -v 0.051268 0.103365 0.055000 -vn 0.396203 0.686243 -0.609995 -v 0.051268 0.097365 0.055000 -vn 0.792406 0.000000 -0.609994 -v 0.049536 0.100365 0.055000 -vn -0.396203 0.686244 -0.609994 -v 0.054733 0.097365 0.055000 -vn -0.792406 -0.000000 -0.609994 -v 0.056465 0.100365 0.055000 -vn 0.396203 -0.686244 -0.609995 -v 0.095274 0.103365 0.055000 -vn 0.792406 0.000000 -0.609994 -v 0.093541 0.100365 0.055000 -vn -0.396203 0.686244 -0.609995 -v 0.098738 0.097365 0.055000 -vn 0.396203 0.686244 -0.609994 -v 0.095274 0.097365 0.055000 -vn -0.792406 -0.000000 -0.609994 -v 0.100470 0.100365 0.055000 -vn -0.396203 -0.686244 -0.609994 -v 0.098738 0.103365 0.055000 -vn 0.396203 -0.686244 -0.609994 -v 0.095274 0.084365 0.055000 -vn 0.792406 0.000000 -0.609994 -v 0.093541 0.081365 0.055000 -vn 0.396203 0.686244 -0.609994 -v 0.095274 0.078365 0.055000 -vn -0.396203 0.686244 -0.609994 -v 0.098738 0.078365 0.055000 -vn -0.396203 -0.686244 -0.609994 -v 0.098738 0.084365 0.055000 -vn -0.792406 -0.000000 -0.609994 -v 0.100470 0.081365 0.055000 -vn 0.396203 0.686244 -0.609994 -v 0.095274 0.087865 0.055000 -vn -0.396203 -0.686244 -0.609994 -v 0.098738 0.093865 0.055000 -vn 0.396203 -0.686244 -0.609994 -v 0.095274 0.093865 0.055000 -vn 0.792406 -0.000000 -0.609994 -v 0.093541 0.090865 0.055000 -vn -0.396203 0.686244 -0.609994 -v 0.098738 0.087865 0.055000 -vn -0.792406 -0.000000 -0.609994 -v 0.100470 0.090865 0.055000 -vn 0.396203 -0.686244 -0.609994 -v 0.051268 0.093865 0.055000 -vn 0.792406 -0.000000 -0.609994 -v 0.049536 0.090865 0.055000 -vn -0.396203 0.686243 -0.609994 -v 0.054733 0.087865 0.055000 -vn 0.396203 0.686244 -0.609994 -v 0.051268 0.087865 0.055000 -vn -0.792406 -0.000000 -0.609994 -v 0.056465 0.090865 0.055000 -vn -0.396203 -0.686244 -0.609994 -v 0.054733 0.093865 0.055000 -# 1322 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 2//2 5//5 4//4 -f 4//4 5//5 6//6 -f 4//4 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 12//12 13//13 14//14 -f 14//14 15//15 12//12 -f 12//12 15//15 16//16 -f 12//12 16//16 17//17 -f 17//17 16//16 18//18 -f 19//19 20//20 21//21 -f 21//21 20//20 14//14 -f 21//21 14//14 22//22 -f 22//22 14//14 13//13 -f 23//23 24//24 25//25 -f 26//26 27//27 28//28 -f 28//28 27//27 29//29 -f 28//28 29//29 30//30 -f 31//31 32//32 33//33 -f 33//33 24//24 31//31 -f 31//31 24//24 23//23 -f 31//31 23//23 34//34 -f 34//34 23//23 35//35 -f 34//34 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 38//38 -f 29//29 39//39 30//30 -f 30//30 39//39 40//40 -f 30//30 40//40 41//41 -f 32//32 31//31 42//42 -f 42//42 31//31 43//43 -f 42//42 43//43 40//40 -f 40//40 43//43 44//44 -f 40//40 44//44 41//41 -f 20//20 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 28//28 -f 41//41 48//48 30//30 -f 30//30 48//48 49//49 -f 30//30 49//49 3//3 -f 3//3 49//49 50//50 -f 3//3 50//50 1//1 -f 47//47 51//51 28//28 -f 28//28 51//51 52//52 -f 28//28 52//52 26//26 -f 26//26 52//52 53//53 -f 26//26 53//53 54//54 -f 54//54 53//53 55//55 -f 54//54 55//55 56//56 -f 56//56 55//55 57//57 -f 38//38 37//37 58//58 -f 58//58 37//37 59//59 -f 58//58 59//59 60//60 -f 20//20 19//19 45//45 -f 45//45 19//19 61//61 -f 45//45 61//61 62//62 -f 62//62 61//61 63//63 -f 62//62 63//63 64//64 -f 64//64 63//63 65//65 -f 64//64 65//65 66//66 -f 66//66 65//65 67//67 -f 66//66 67//67 68//68 -f 68//68 67//67 69//69 -f 68//68 69//69 70//70 -f 70//70 69//69 23//23 -f 70//70 23//23 57//57 -f 57//57 23//23 25//25 -f 57//57 25//25 56//56 -f 59//59 71//71 60//60 -f 60//60 71//71 72//72 -f 60//60 72//72 50//50 -f 50//50 72//72 73//73 -f 50//50 73//73 1//1 -f 74//74 75//75 28//28 -f 76//76 77//77 78//78 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 76//76 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 79//79 87//87 80//80 -f 80//80 87//87 88//88 -f 80//80 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 85//85 -f 91//91 85//85 92//92 -f 92//92 85//85 86//86 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 84//84 -f 9//9 11//11 97//97 -f 97//97 98//98 9//9 -f 9//9 98//98 99//99 -f 9//9 99//99 100//100 -f 100//100 99//99 101//101 -f 100//100 101//101 102//102 -f 102//102 103//103 100//100 -f 100//100 103//103 104//104 -f 100//100 104//104 95//95 -f 104//104 105//105 95//95 -f 95//95 105//105 106//106 -f 95//95 106//106 93//93 -f 93//93 106//106 107//107 -f 93//93 107//107 108//108 -f 108//108 107//107 109//109 -f 108//108 109//109 11//11 -f 11//11 109//109 110//110 -f 11//11 110//110 97//97 -f 83//83 111//111 84//84 -f 84//84 111//111 112//112 -f 84//84 112//112 95//95 -f 95//95 112//112 113//113 -f 95//95 113//113 100//100 -f 100//100 113//113 114//114 -f 100//100 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 74//74 119//119 75//75 -f 75//75 119//119 120//120 -f 75//75 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 81//81 -f 81//81 124//124 125//125 -f 81//81 125//125 79//79 -f 118//118 126//126 117//117 -f 117//117 126//126 127//127 -f 117//117 127//127 30//30 -f 127//127 128//128 30//30 -f 30//30 128//128 129//129 -f 30//30 129//129 28//28 -f 28//28 129//129 130//130 -f 28//28 130//130 74//74 -f 131//131 132//132 81//81 -f 133//133 123//123 134//134 -f 134//134 123//123 81//81 -f 134//134 81//81 135//135 -f 135//135 81//81 132//132 -f 76//76 78//78 81//81 -f 81//81 78//78 136//136 -f 81//81 136//136 131//131 -f 133//133 137//137 123//123 -f 123//123 137//137 138//138 -f 123//123 138//138 139//139 -f 139//139 138//138 140//140 -f 140//140 141//141 139//139 -f 139//139 141//141 142//142 -f 139//139 142//142 78//78 -f 78//78 142//142 143//143 -f 78//78 143//143 136//136 -f 7//7 144//144 115//115 -f 115//115 144//144 145//145 -f 115//115 145//145 146//146 -f 147//147 100//100 148//148 -f 148//148 100//100 115//115 -f 148//148 115//115 149//149 -f 149//149 115//115 146//146 -f 150//150 9//9 151//151 -f 151//151 9//9 100//100 -f 151//151 100//100 152//152 -f 152//152 100//100 147//147 -f 150//150 153//153 9//9 -f 9//9 153//153 154//154 -f 9//9 154//154 7//7 -f 7//7 154//154 155//155 -f 7//7 155//155 144//144 -f 156//156 157//157 158//158 -f 158//158 157//157 159//159 -f 158//158 159//159 139//139 -f 156//156 158//158 160//160 -f 160//160 158//158 121//121 -f 160//160 121//121 161//161 -f 159//159 162//162 139//139 -f 139//139 162//162 163//163 -f 139//139 163//163 123//123 -f 123//123 163//163 164//164 -f 123//123 164//164 165//165 -f 165//165 166//166 123//123 -f 123//123 166//166 167//167 -f 123//123 167//167 121//121 -f 121//121 167//167 168//168 -f 121//121 168//168 161//161 -f 117//117 169//169 170//170 -f 171//171 115//115 172//172 -f 172//172 115//115 117//117 -f 172//172 117//117 173//173 -f 173//173 117//117 170//170 -f 171//171 174//174 115//115 -f 115//115 174//174 175//175 -f 115//115 175//175 7//7 -f 7//7 175//175 176//176 -f 176//176 177//177 7//7 -f 7//7 177//177 178//178 -f 7//7 178//178 4//4 -f 4//4 178//178 179//179 -f 4//4 179//179 180//180 -f 181//181 182//182 183//183 -f 184//184 185//185 121//121 -f 121//121 185//185 186//186 -f 121//121 186//186 75//75 -f 75//75 186//186 187//187 -f 75//75 187//187 188//188 -f 182//182 189//189 183//183 -f 183//183 189//189 190//190 -f 183//183 190//190 158//158 -f 190//190 191//191 158//158 -f 158//158 191//191 192//192 -f 158//158 192//192 121//121 -f 121//121 192//192 193//193 -f 121//121 193//193 184//184 -f 180//180 169//169 4//4 -f 4//4 169//169 117//117 -f 4//4 117//117 3//3 -f 3//3 117//117 30//30 -f 188//188 181//181 75//75 -f 75//75 181//181 183//183 -f 75//75 183//183 28//28 -f 28//28 183//183 46//46 -f 77//77 194//194 78//78 -f 78//78 194//194 18//18 -f 78//78 18//18 139//139 -f 139//139 18//18 16//16 -f 139//139 16//16 158//158 -f 158//158 16//16 15//15 -f 158//158 15//15 183//183 -f 183//183 15//15 14//14 -f 183//183 14//14 46//46 -f 46//46 14//14 20//20 -f 195//195 196//196 92//92 -f 92//92 196//196 91//91 -f 186//186 185//185 197//197 -f 184//184 198//198 185//185 -f 185//185 198//198 199//199 -f 185//185 199//199 197//197 -f 192//192 200//200 193//193 -f 193//193 200//200 201//201 -f 193//193 201//201 184//184 -f 184//184 201//201 202//202 -f 184//184 202//202 198//198 -f 191//191 203//203 192//192 -f 192//192 203//203 204//204 -f 192//192 204//204 200//200 -f 190//190 205//205 191//191 -f 191//191 205//205 206//206 -f 191//191 206//206 203//203 -f 189//189 207//207 190//190 -f 190//190 207//207 208//208 -f 190//190 208//208 205//205 -f 182//182 209//209 189//189 -f 189//189 209//209 210//210 -f 189//189 210//210 207//207 -f 181//181 211//211 182//182 -f 182//182 211//211 212//212 -f 182//182 212//212 209//209 -f 188//188 213//213 181//181 -f 181//181 213//213 214//214 -f 181//181 214//214 211//211 -f 187//187 215//215 188//188 -f 188//188 215//215 216//216 -f 216//216 217//217 188//188 -f 188//188 217//217 218//218 -f 188//188 218//218 213//213 -f 197//197 219//219 186//186 -f 186//186 219//219 220//220 -f 186//186 220//220 187//187 -f 187//187 220//220 221//221 -f 187//187 221//221 215//215 -f 104//104 222//222 105//105 -f 105//105 222//222 223//223 -f 105//105 223//223 106//106 -f 106//106 223//223 224//224 -f 106//106 224//224 107//107 -f 107//107 224//224 225//225 -f 107//107 225//225 109//109 -f 109//109 225//225 226//226 -f 109//109 226//226 110//110 -f 110//110 226//226 227//227 -f 110//110 227//227 97//97 -f 97//97 227//227 228//228 -f 97//97 228//228 98//98 -f 98//98 228//228 229//229 -f 98//98 229//229 99//99 -f 99//99 229//229 230//230 -f 99//99 230//230 101//101 -f 101//101 230//230 231//231 -f 101//101 231//231 102//102 -f 102//102 231//231 232//232 -f 102//102 232//232 103//103 -f 103//103 232//232 233//233 -f 103//103 233//233 104//104 -f 104//104 233//233 222//222 -f 142//142 234//234 143//143 -f 143//143 234//234 235//235 -f 143//143 235//235 136//136 -f 136//136 235//235 236//236 -f 136//136 236//236 131//131 -f 131//131 236//236 237//237 -f 131//131 237//237 132//132 -f 132//132 237//237 238//238 -f 132//132 238//238 135//135 -f 135//135 238//238 239//239 -f 135//135 239//239 134//134 -f 134//134 239//239 240//240 -f 134//134 240//240 133//133 -f 133//133 240//240 241//241 -f 133//133 241//241 137//137 -f 137//137 241//241 242//242 -f 137//137 242//242 138//138 -f 138//138 242//242 243//243 -f 138//138 243//243 140//140 -f 140//140 243//243 244//244 -f 140//140 244//244 141//141 -f 141//141 244//244 245//245 -f 141//141 245//245 142//142 -f 142//142 245//245 234//234 -f 159//159 246//246 162//162 -f 162//162 246//246 247//247 -f 162//162 247//247 163//163 -f 163//163 247//247 248//248 -f 163//163 248//248 164//164 -f 164//164 248//248 249//249 -f 164//164 249//249 165//165 -f 165//165 249//249 250//250 -f 165//165 250//250 166//166 -f 166//166 250//250 251//251 -f 166//166 251//251 167//167 -f 167//167 251//251 252//252 -f 167//167 252//252 168//168 -f 168//168 252//252 253//253 -f 168//168 253//253 161//161 -f 161//161 253//253 254//254 -f 161//161 254//254 160//160 -f 160//160 254//254 255//255 -f 160//160 255//255 156//156 -f 156//156 255//255 256//256 -f 156//156 256//256 157//157 -f 157//157 256//256 257//257 -f 157//157 257//257 159//159 -f 159//159 257//257 246//246 -f 148//148 258//258 147//147 -f 147//147 258//258 259//259 -f 147//147 259//259 152//152 -f 152//152 259//259 260//260 -f 152//152 260//260 151//151 -f 151//151 260//260 261//261 -f 151//151 261//261 150//150 -f 150//150 261//261 262//262 -f 150//150 262//262 153//153 -f 153//153 262//262 263//263 -f 153//153 263//263 154//154 -f 154//154 263//263 264//264 -f 154//154 264//264 155//155 -f 155//155 264//264 265//265 -f 155//155 265//265 144//144 -f 144//144 265//265 266//266 -f 144//144 266//266 145//145 -f 145//145 266//266 267//267 -f 145//145 267//267 146//146 -f 146//146 267//267 268//268 -f 146//146 268//268 149//149 -f 149//149 268//268 269//269 -f 149//149 269//269 148//148 -f 148//148 269//269 258//258 -f 178//178 177//177 270//270 -f 176//176 271//271 177//177 -f 177//177 271//271 272//272 -f 177//177 272//272 270//270 -f 174//174 273//273 175//175 -f 175//175 273//273 274//274 -f 175//175 274//274 176//176 -f 176//176 274//274 275//275 -f 176//176 275//275 271//271 -f 171//171 276//276 174//174 -f 174//174 276//276 277//277 -f 174//174 277//277 273//273 -f 172//172 278//278 171//171 -f 171//171 278//278 279//279 -f 171//171 279//279 276//276 -f 173//173 280//280 172//172 -f 172//172 280//280 281//281 -f 172//172 281//281 278//278 -f 170//170 282//282 173//173 -f 173//173 282//282 283//283 -f 173//173 283//283 280//280 -f 169//169 284//284 170//170 -f 170//170 284//284 285//285 -f 170//170 285//285 282//282 -f 180//180 286//286 169//169 -f 169//169 286//286 287//287 -f 169//169 287//287 284//284 -f 179//179 288//288 180//180 -f 180//180 288//288 289//289 -f 289//289 290//290 180//180 -f 180//180 290//290 291//291 -f 180//180 291//291 286//286 -f 270//270 292//292 178//178 -f 178//178 292//292 293//293 -f 178//178 293//293 179//179 -f 179//179 293//293 294//294 -f 179//179 294//294 288//288 -f 295//295 296//296 126//126 -f 297//297 298//298 299//299 -f 297//297 299//299 300//300 -f 300//300 299//299 301//301 -f 301//301 299//299 302//302 -f 301//301 302//302 303//303 -f 304//304 305//305 306//306 -f 306//306 305//305 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 303//303 -f 308//308 303//303 309//309 -f 309//309 303//303 302//302 -f 128//128 127//127 310//310 -f 310//310 127//127 305//305 -f 310//310 305//305 311//311 -f 311//311 305//305 304//304 -f 126//126 296//296 127//127 -f 127//127 296//296 312//312 -f 127//127 312//312 305//305 -f 118//118 313//313 126//126 -f 126//126 313//313 314//314 -f 126//126 314//314 295//295 -f 315//315 129//129 316//316 -f 316//316 129//129 128//128 -f 316//316 128//128 317//317 -f 317//317 128//128 310//310 -f 318//318 319//319 118//118 -f 118//118 319//319 320//320 -f 118//118 320//320 313//313 -f 118//118 116//116 318//318 -f 318//318 116//116 114//114 -f 318//318 114//114 321//321 -f 321//321 114//114 113//113 -f 321//321 113//113 112//112 -f 85//85 322//322 83//83 -f 83//83 322//322 323//323 -f 83//83 323//323 111//111 -f 111//111 323//323 324//324 -f 111//111 324//324 112//112 -f 112//112 324//324 321//321 -f 325//325 322//322 90//90 -f 90//90 322//322 85//85 -f 79//79 326//326 87//87 -f 87//87 326//326 327//327 -f 87//87 327//327 88//88 -f 88//88 327//327 328//328 -f 88//88 328//328 90//90 -f 90//90 328//328 325//325 -f 329//329 330//330 120//120 -f 120//120 330//330 331//331 -f 120//120 331//331 332//332 -f 79//79 125//125 326//326 -f 326//326 125//125 124//124 -f 326//326 124//124 332//332 -f 332//332 124//124 122//122 -f 332//332 122//122 120//120 -f 329//329 120//120 333//333 -f 333//333 120//120 119//119 -f 333//333 119//119 334//334 -f 334//334 119//119 335//335 -f 336//336 337//337 338//338 -f 338//338 337//337 339//339 -f 338//338 339//339 340//340 -f 340//340 339//339 341//341 -f 340//340 341//341 342//342 -f 342//342 341//341 343//343 -f 342//342 343//343 344//344 -f 344//344 343//343 345//345 -f 344//344 345//345 346//346 -f 346//346 345//345 347//347 -f 346//346 347//347 348//348 -f 348//348 347//347 349//349 -f 348//348 349//349 350//350 -f 350//350 349//349 351//351 -f 350//350 351//351 352//352 -f 352//352 351//351 353//353 -f 352//352 353//353 354//354 -f 130//130 355//355 74//74 -f 74//74 355//355 356//356 -f 356//356 357//357 74//74 -f 74//74 357//357 354//354 -f 74//74 354//354 119//119 -f 119//119 354//354 353//353 -f 119//119 353//353 335//335 -f 358//358 298//298 359//359 -f 359//359 298//298 360//360 -f 361//361 336//336 362//362 -f 362//362 336//336 363//363 -f 364//364 299//299 298//298 -f 355//355 130//130 365//365 -f 365//365 130//130 366//366 -f 367//367 368//368 130//130 -f 366//366 130//130 369//369 -f 369//369 130//130 368//368 -f 369//369 368//368 370//370 -f 370//370 368//368 371//371 -f 370//370 371//371 372//372 -f 372//372 371//371 373//373 -f 372//372 373//373 374//374 -f 374//374 373//373 363//363 -f 374//374 363//363 375//375 -f 375//375 363//363 336//336 -f 375//375 336//336 338//338 -f 376//376 129//129 377//377 -f 377//377 129//129 315//315 -f 373//373 378//378 363//363 -f 363//363 378//378 379//379 -f 363//363 379//379 358//358 -f 358//358 379//379 380//380 -f 358//358 380//380 381//381 -f 367//367 130//130 382//382 -f 382//382 130//130 129//129 -f 382//382 129//129 383//383 -f 383//383 129//129 376//376 -f 383//383 376//376 384//384 -f 364//364 298//298 385//385 -f 385//385 298//298 358//358 -f 385//385 358//358 386//386 -f 386//386 358//358 381//381 -f 386//386 381//381 387//387 -f 387//387 381//381 388//388 -f 387//387 388//388 384//384 -f 384//384 388//388 389//389 -f 384//384 389//389 383//383 -f 11//11 10//10 390//390 -f 11//11 390//390 108//108 -f 108//108 390//390 391//391 -f 108//108 391//391 93//93 -f 93//93 391//391 392//392 -f 93//93 392//392 94//94 -f 94//94 392//392 393//393 -f 94//94 393//393 96//96 -f 96//96 393//393 394//394 -f 96//96 394//394 84//84 -f 84//84 394//394 395//395 -f 84//84 395//395 86//86 -f 86//86 395//395 195//195 -f 86//86 195//195 92//92 -f 91//91 196//196 396//396 -f 91//91 396//396 89//89 -f 89//89 396//396 397//397 -f 89//89 397//397 80//80 -f 80//80 397//397 398//398 -f 80//80 398//398 82//82 -f 82//82 398//398 399//399 -f 82//82 399//399 76//76 -f 76//76 399//399 400//400 -f 76//76 400//400 77//77 -f 77//77 400//400 401//401 -f 77//77 401//401 194//194 -f 194//194 401//401 17//17 -f 194//194 17//17 18//18 -f 235//235 234//234 17//17 -f 269//269 318//318 258//258 -f 258//258 318//318 321//321 -f 258//258 321//321 259//259 -f 259//259 321//321 222//222 -f 222//222 233//233 259//259 -f 259//259 233//233 232//232 -f 259//259 232//232 260//260 -f 269//269 268//268 318//318 -f 318//318 268//268 267//267 -f 318//318 267//267 8//8 -f 8//8 267//267 266//266 -f 263//263 10//10 264//264 -f 264//264 10//10 8//8 -f 264//264 8//8 265//265 -f 265//265 8//8 266//266 -f 255//255 332//332 256//256 -f 256//256 332//332 12//12 -f 256//256 12//12 257//257 -f 257//257 12//12 246//246 -f 250//250 249//249 243//243 -f 260//260 232//232 261//261 -f 261//261 232//232 231//231 -f 261//261 231//231 262//262 -f 262//262 231//231 230//230 -f 262//262 230//230 263//263 -f 263//263 230//230 229//229 -f 263//263 229//229 10//10 -f 17//17 234//234 12//12 -f 234//234 245//245 12//12 -f 12//12 245//245 244//244 -f 12//12 244//244 246//246 -f 246//246 244//244 247//247 -f 243//243 249//249 244//244 -f 244//244 249//249 248//248 -f 244//244 248//248 247//247 -f 225//225 224//224 321//321 -f 321//321 224//224 223//223 -f 321//321 223//223 222//222 -f 392//392 324//324 393//393 -f 393//393 324//324 323//323 -f 235//235 17//17 236//236 -f 236//236 17//17 401//401 -f 236//236 401//401 237//237 -f 237//237 401//401 400//400 -f 237//237 400//400 399//399 -f 229//229 228//228 10//10 -f 10//10 228//228 227//227 -f 10//10 227//227 390//390 -f 390//390 227//227 226//226 -f 390//390 226//226 391//391 -f 391//391 226//226 225//225 -f 391//391 225//225 392//392 -f 392//392 225//225 321//321 -f 392//392 321//321 324//324 -f 238//238 237//237 326//326 -f 326//326 237//237 399//399 -f 326//326 399//399 327//327 -f 327//327 399//399 398//398 -f 327//327 398//398 328//328 -f 328//328 398//398 397//397 -f 328//328 397//397 325//325 -f 325//325 397//397 396//396 -f 255//255 254//254 332//332 -f 332//332 254//254 253//253 -f 332//332 253//253 252//252 -f 332//332 241//241 240//240 -f 332//332 240//240 326//326 -f 326//326 240//240 239//239 -f 326//326 239//239 238//238 -f 396//396 196//196 325//325 -f 325//325 196//196 195//195 -f 325//325 195//195 322//322 -f 322//322 195//195 395//395 -f 322//322 395//395 323//323 -f 323//323 395//395 394//394 -f 323//323 394//394 393//393 -f 241//241 332//332 242//242 -f 242//242 332//332 252//252 -f 242//242 252//252 243//243 -f 243//243 252//252 251//251 -f 243//243 251//251 250//250 -f 402//402 63//63 403//403 -f 403//403 63//63 61//61 -f 21//21 404//404 19//19 -f 19//19 404//404 405//405 -f 19//19 405//405 61//61 -f 61//61 405//405 406//406 -f 61//61 406//406 403//403 -f 363//363 23//23 69//69 -f 402//402 407//407 63//63 -f 63//63 407//407 408//408 -f 63//63 408//408 65//65 -f 408//408 409//409 65//65 -f 65//65 409//409 410//410 -f 65//65 410//410 67//67 -f 67//67 410//410 361//361 -f 67//67 361//361 69//69 -f 69//69 361//361 362//362 -f 69//69 362//362 363//363 -f 35//35 23//23 358//358 -f 358//358 23//23 363//363 -f 411//411 412//412 72//72 -f 71//71 413//413 72//72 -f 72//72 413//413 414//414 -f 72//72 414//414 411//411 -f 359//359 360//360 59//59 -f 59//59 360//360 415//415 -f 59//59 415//415 71//71 -f 71//71 415//415 416//416 -f 71//71 416//416 413//413 -f 59//59 37//37 359//359 -f 359//359 37//37 35//35 -f 359//359 35//35 358//358 -f 417//417 2//2 1//1 -f 73//73 72//72 412//412 -f 412//412 418//418 73//73 -f 73//73 418//418 419//419 -f 73//73 419//419 1//1 -f 1//1 419//419 420//420 -f 1//1 420//420 417//417 -f 337//337 336//336 361//361 -f 200//200 204//204 13//13 -f 197//197 331//331 219//219 -f 219//219 331//331 330//330 -f 219//219 330//330 220//220 -f 197//197 199//199 331//331 -f 331//331 199//199 198//198 -f 331//331 198//198 202//202 -f 200//200 13//13 201//201 -f 204//204 203//203 13//13 -f 13//13 203//203 206//206 -f 13//13 206//206 22//22 -f 220//220 330//330 221//221 -f 221//221 330//330 329//329 -f 221//221 329//329 215//215 -f 215//215 329//329 333//333 -f 215//215 333//333 216//216 -f 212//212 211//211 403//403 -f 212//212 403//403 209//209 -f 214//214 213//213 351//351 -f 213//213 218//218 351//351 -f 351//351 218//218 217//217 -f 351//351 217//217 353//353 -f 353//353 217//217 335//335 -f 216//216 333//333 217//217 -f 217//217 333//333 334//334 -f 217//217 334//334 335//335 -f 403//403 406//406 209//209 -f 209//209 406//406 405//405 -f 209//209 405//405 210//210 -f 210//210 405//405 404//404 -f 210//210 404//404 207//207 -f 207//207 404//404 21//21 -f 207//207 21//21 208//208 -f 208//208 21//21 22//22 -f 208//208 22//22 205//205 -f 205//205 22//22 206//206 -f 211//211 214//214 403//403 -f 403//403 214//214 351//351 -f 403//403 351//351 402//402 -f 402//402 351//351 407//407 -f 407//407 351//351 408//408 -f 408//408 351//351 349//349 -f 408//408 349//349 347//347 -f 347//347 345//345 408//408 -f 408//408 345//345 343//343 -f 408//408 343//343 409//409 -f 409//409 343//343 410//410 -f 410//410 343//343 341//341 -f 410//410 341//341 361//361 -f 361//361 341//341 339//339 -f 361//361 339//339 337//337 -f 12//12 332//332 13//13 -f 13//13 332//332 331//331 -f 13//13 331//331 201//201 -f 201//201 331//331 202//202 -f 5//5 292//292 6//6 -f 6//6 292//292 270//270 -f 270//270 272//272 6//6 -f 6//6 272//272 271//271 -f 6//6 271//271 275//275 -f 277//277 319//319 273//273 -f 273//273 319//319 274//274 -f 277//277 276//276 319//319 -f 319//319 276//276 279//279 -f 319//319 279//279 320//320 -f 282//282 285//285 312//312 -f 285//285 284//284 312//312 -f 312//312 284//284 287//287 -f 312//312 287//287 418//418 -f 290//290 289//289 417//417 -f 417//417 289//289 288//288 -f 417//417 288//288 2//2 -f 2//2 288//288 294//294 -f 2//2 294//294 5//5 -f 5//5 294//294 293//293 -f 5//5 293//293 292//292 -f 287//287 286//286 418//418 -f 418//418 286//286 291//291 -f 418//418 291//291 419//419 -f 419//419 291//291 290//290 -f 419//419 290//290 420//420 -f 420//420 290//290 417//417 -f 312//312 296//296 282//282 -f 282//282 296//296 295//295 -f 282//282 295//295 283//283 -f 283//283 295//295 314//314 -f 283//283 314//314 280//280 -f 280//280 314//314 313//313 -f 280//280 313//313 281//281 -f 281//281 313//313 320//320 -f 281//281 320//320 278//278 -f 278//278 320//320 279//279 -f 414//414 305//305 411//411 -f 411//411 305//305 312//312 -f 411//411 312//312 412//412 -f 412//412 312//312 418//418 -f 360//360 298//298 297//297 -f 413//413 303//303 414//414 -f 414//414 303//303 307//307 -f 414//414 307//307 305//305 -f 297//297 300//300 360//360 -f 360//360 300//300 301//301 -f 360//360 301//301 415//415 -f 415//415 301//301 303//303 -f 415//415 303//303 416//416 -f 416//416 303//303 413//413 -f 318//318 8//8 319//319 -f 319//319 8//8 6//6 -f 319//319 6//6 274//274 -f 274//274 6//6 275//275 -f 54//54 371//371 26//26 -f 26//26 371//371 368//368 -f 26//26 368//368 27//27 -f 27//27 368//368 367//367 -f 27//27 367//367 29//29 -f 29//29 367//367 382//382 -f 29//29 382//382 39//39 -f 39//39 382//382 383//383 -f 39//39 383//383 40//40 -f 40//40 383//383 389//389 -f 40//40 389//389 42//42 -f 42//42 389//389 388//388 -f 42//42 388//388 32//32 -f 32//32 388//388 381//381 -f 32//32 381//381 33//33 -f 33//33 381//381 380//380 -f 33//33 380//380 24//24 -f 24//24 380//380 379//379 -f 24//24 379//379 25//25 -f 25//25 379//379 378//378 -f 25//25 378//378 56//56 -f 56//56 378//378 373//373 -f 56//56 373//373 54//54 -f 54//54 373//373 371//371 -f 58//58 308//308 309//309 -f 58//58 309//309 38//38 -f 308//308 58//58 306//306 -f 306//306 58//58 60//60 -f 306//306 60//60 304//304 -f 304//304 60//60 311//311 -f 311//311 60//60 50//50 -f 311//311 50//50 310//310 -f 49//49 316//316 50//50 -f 50//50 316//316 317//317 -f 50//50 317//317 310//310 -f 309//309 302//302 38//38 -f 38//38 302//302 299//299 -f 38//38 299//299 36//36 -f 36//36 299//299 364//364 -f 36//36 364//364 34//34 -f 34//34 364//364 385//385 -f 34//34 385//385 31//31 -f 31//31 385//385 386//386 -f 31//31 386//386 43//43 -f 43//43 386//386 387//387 -f 43//43 387//387 44//44 -f 44//44 387//387 384//384 -f 44//44 384//384 41//41 -f 41//41 384//384 376//376 -f 41//41 376//376 48//48 -f 48//48 376//376 377//377 -f 48//48 377//377 49//49 -f 49//49 377//377 315//315 -f 49//49 315//315 316//316 -f 47//47 45//45 357//357 -f 348//348 350//350 62//62 -f 62//62 350//350 352//352 -f 62//62 352//352 45//45 -f 45//45 352//352 354//354 -f 45//45 354//354 357//357 -f 64//64 66//66 340//340 -f 340//340 342//342 64//64 -f 64//64 342//342 344//344 -f 64//64 344//344 62//62 -f 62//62 344//344 346//346 -f 62//62 346//346 348//348 -f 357//357 356//356 47//47 -f 47//47 356//356 355//355 -f 47//47 355//355 51//51 -f 51//51 355//355 365//365 -f 51//51 365//365 52//52 -f 52//52 365//365 366//366 -f 52//52 366//366 53//53 -f 53//53 366//366 369//369 -f 53//53 369//369 55//55 -f 55//55 369//369 370//370 -f 55//55 370//370 57//57 -f 57//57 370//370 372//372 -f 57//57 372//372 70//70 -f 70//70 372//372 374//374 -f 70//70 374//374 68//68 -f 68//68 374//374 375//375 -f 68//68 375//375 66//66 -f 66//66 375//375 338//338 -f 66//66 338//338 340//340 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 422//422 425//425 424//424 -f 424//424 425//425 426//426 -f 424//424 426//426 427//427 -f 427//427 426//426 428//428 -f 427//427 428//428 429//429 -f 429//429 428//428 430//430 -f 429//429 430//430 431//431 -f 432//432 433//433 434//434 -f 434//434 435//435 432//432 -f 432//432 435//435 436//436 -f 432//432 436//436 437//437 -f 437//437 436//436 438//438 -f 439//439 440//440 441//441 -f 441//441 440//440 434//434 -f 441//441 434//434 442//442 -f 442//442 434//434 433//433 -f 443//443 444//444 445//445 -f 446//446 447//447 448//448 -f 448//448 447//447 449//449 -f 448//448 449//449 450//450 -f 451//451 452//452 453//453 -f 453//453 444//444 451//451 -f 451//451 444//444 443//443 -f 451//451 443//443 454//454 -f 454//454 443//443 455//455 -f 454//454 455//455 456//456 -f 456//456 455//455 457//457 -f 456//456 457//457 458//458 -f 449//449 459//459 450//450 -f 450//450 459//459 460//460 -f 450//450 460//460 461//461 -f 452//452 451//451 462//462 -f 462//462 451//451 463//463 -f 462//462 463//463 460//460 -f 460//460 463//463 464//464 -f 460//460 464//464 461//461 -f 440//440 465//465 466//466 -f 466//466 465//465 467//467 -f 466//466 467//467 448//448 -f 461//461 468//468 450//450 -f 450//450 468//468 469//469 -f 450//450 469//469 423//423 -f 423//423 469//469 470//470 -f 423//423 470//470 421//421 -f 467//467 471//471 448//448 -f 448//448 471//471 472//472 -f 448//448 472//472 446//446 -f 446//446 472//472 473//473 -f 446//446 473//473 474//474 -f 474//474 473//473 475//475 -f 474//474 475//475 476//476 -f 476//476 475//475 477//477 -f 458//458 457//457 478//478 -f 478//478 457//457 479//479 -f 478//478 479//479 480//480 -f 440//440 439//439 465//465 -f 465//465 439//439 481//481 -f 465//465 481//481 482//482 -f 482//482 481//481 483//483 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 486//486 -f 486//486 485//485 487//487 -f 486//486 487//487 488//488 -f 488//488 487//487 489//489 -f 488//488 489//489 490//490 -f 490//490 489//489 443//443 -f 490//490 443//443 477//477 -f 477//477 443//443 445//445 -f 477//477 445//445 476//476 -f 479//479 491//491 480//480 -f 480//480 491//491 492//492 -f 480//480 492//492 470//470 -f 470//470 492//492 493//493 -f 470//470 493//493 421//421 -f 494//494 495//495 448//448 -f 496//496 497//497 498//498 -f 499//499 500//500 501//501 -f 501//501 500//500 502//502 -f 501//501 502//502 496//496 -f 503//503 504//504 505//505 -f 505//505 504//504 506//506 -f 499//499 507//507 500//500 -f 500//500 507//507 508//508 -f 500//500 508//508 509//509 -f 509//509 508//508 510//510 -f 509//509 510//510 511//511 -f 511//511 510//510 505//505 -f 511//511 505//505 512//512 -f 512//512 505//505 506//506 -f 513//513 514//514 515//515 -f 515//515 514//514 516//516 -f 515//515 516//516 504//504 -f 429//429 431//431 517//517 -f 517//517 518//518 429//429 -f 429//429 518//518 519//519 -f 429//429 519//519 520//520 -f 520//520 519//519 521//521 -f 520//520 521//521 522//522 -f 522//522 523//523 520//520 -f 520//520 523//523 524//524 -f 520//520 524//524 515//515 -f 524//524 525//525 515//515 -f 515//515 525//525 526//526 -f 515//515 526//526 513//513 -f 513//513 526//526 527//527 -f 513//513 527//527 528//528 -f 528//528 527//527 529//529 -f 528//528 529//529 431//431 -f 431//431 529//529 530//530 -f 431//431 530//530 517//517 -f 503//503 531//531 504//504 -f 504//504 531//531 532//532 -f 504//504 532//532 515//515 -f 515//515 532//532 533//533 -f 515//515 533//533 520//520 -f 520//520 533//533 534//534 -f 520//520 534//534 535//535 -f 535//535 534//534 536//536 -f 535//535 536//536 537//537 -f 537//537 536//536 538//538 -f 494//494 539//539 495//495 -f 495//495 539//539 540//540 -f 495//495 540//540 541//541 -f 541//541 540//540 542//542 -f 541//541 542//542 543//543 -f 543//543 542//542 544//544 -f 543//543 544//544 501//501 -f 501//501 544//544 545//545 -f 501//501 545//545 499//499 -f 538//538 546//546 537//537 -f 537//537 546//546 547//547 -f 537//537 547//547 450//450 -f 547//547 548//548 450//450 -f 450//450 548//548 549//549 -f 450//450 549//549 448//448 -f 448//448 549//549 550//550 -f 448//448 550//550 494//494 -f 551//551 552//552 501//501 -f 553//553 543//543 554//554 -f 554//554 543//543 501//501 -f 554//554 501//501 555//555 -f 555//555 501//501 552//552 -f 496//496 498//498 501//501 -f 501//501 498//498 556//556 -f 501//501 556//556 551//551 -f 553//553 557//557 543//543 -f 543//543 557//557 558//558 -f 543//543 558//558 559//559 -f 559//559 558//558 560//560 -f 560//560 561//561 559//559 -f 559//559 561//561 562//562 -f 559//559 562//562 498//498 -f 498//498 562//562 563//563 -f 498//498 563//563 556//556 -f 427//427 564//564 535//535 -f 535//535 564//564 565//565 -f 535//535 565//565 566//566 -f 567//567 520//520 568//568 -f 568//568 520//520 535//535 -f 568//568 535//535 569//569 -f 569//569 535//535 566//566 -f 570//570 429//429 571//571 -f 571//571 429//429 520//520 -f 571//571 520//520 572//572 -f 572//572 520//520 567//567 -f 570//570 573//573 429//429 -f 429//429 573//573 574//574 -f 429//429 574//574 427//427 -f 427//427 574//574 575//575 -f 427//427 575//575 564//564 -f 576//576 577//577 578//578 -f 578//578 577//577 579//579 -f 578//578 579//579 559//559 -f 576//576 578//578 580//580 -f 580//580 578//578 541//541 -f 580//580 541//541 581//581 -f 579//579 582//582 559//559 -f 559//559 582//582 583//583 -f 559//559 583//583 543//543 -f 543//543 583//583 584//584 -f 543//543 584//584 585//585 -f 585//585 586//586 543//543 -f 543//543 586//586 587//587 -f 543//543 587//587 541//541 -f 541//541 587//587 588//588 -f 541//541 588//588 581//581 -f 537//537 589//589 590//590 -f 591//591 535//535 592//592 -f 592//592 535//535 537//537 -f 592//592 537//537 593//593 -f 593//593 537//537 590//590 -f 591//591 594//594 535//535 -f 535//535 594//594 595//595 -f 535//535 595//595 427//427 -f 427//427 595//595 596//596 -f 596//596 597//597 427//427 -f 427//427 597//597 598//598 -f 427//427 598//598 424//424 -f 424//424 598//598 599//599 -f 424//424 599//599 600//600 -f 601//601 602//602 603//603 -f 604//604 605//605 541//541 -f 541//541 605//605 606//606 -f 541//541 606//606 495//495 -f 495//495 606//606 607//607 -f 495//495 607//607 608//608 -f 602//602 609//609 603//603 -f 603//603 609//609 610//610 -f 603//603 610//610 578//578 -f 610//610 611//611 578//578 -f 578//578 611//611 612//612 -f 578//578 612//612 541//541 -f 541//541 612//612 613//613 -f 541//541 613//613 604//604 -f 600//600 589//589 424//424 -f 424//424 589//589 537//537 -f 424//424 537//537 423//423 -f 423//423 537//537 450//450 -f 608//608 601//601 495//495 -f 495//495 601//601 603//603 -f 495//495 603//603 448//448 -f 448//448 603//603 466//466 -f 497//497 614//614 498//498 -f 498//498 614//614 438//438 -f 498//498 438//438 559//559 -f 559//559 438//438 436//436 -f 559//559 436//436 578//578 -f 578//578 436//436 435//435 -f 578//578 435//435 603//603 -f 603//603 435//435 434//434 -f 603//603 434//434 466//466 -f 466//466 434//434 440//440 -f 615//615 616//616 512//512 -f 512//512 616//616 511//511 -f 606//606 605//605 617//617 -f 604//604 618//618 605//605 -f 605//605 618//618 619//619 -f 605//605 619//619 617//617 -f 612//612 620//620 613//613 -f 613//613 620//620 621//621 -f 613//613 621//621 604//604 -f 604//604 621//621 622//622 -f 604//604 622//622 618//618 -f 611//611 623//623 612//612 -f 612//612 623//623 624//624 -f 612//612 624//624 620//620 -f 610//610 625//625 611//611 -f 611//611 625//625 626//626 -f 611//611 626//626 623//623 -f 609//609 627//627 610//610 -f 610//610 627//627 628//628 -f 610//610 628//628 625//625 -f 602//602 629//629 609//609 -f 609//609 629//629 630//630 -f 609//609 630//630 627//627 -f 601//601 631//631 602//602 -f 602//602 631//631 632//632 -f 602//602 632//632 629//629 -f 608//608 633//633 601//601 -f 601//601 633//633 634//634 -f 601//601 634//634 631//631 -f 607//607 635//635 608//608 -f 608//608 635//635 636//636 -f 636//636 637//637 608//608 -f 608//608 637//637 638//638 -f 608//608 638//638 633//633 -f 617//617 639//639 606//606 -f 606//606 639//639 640//640 -f 606//606 640//640 607//607 -f 607//607 640//640 641//641 -f 607//607 641//641 635//635 -f 524//524 642//642 525//525 -f 525//525 642//642 643//643 -f 525//525 643//643 526//526 -f 526//526 643//643 644//644 -f 526//526 644//644 527//527 -f 527//527 644//644 645//645 -f 527//527 645//645 529//529 -f 529//529 645//645 646//646 -f 529//529 646//646 530//530 -f 530//530 646//646 647//647 -f 530//530 647//647 517//517 -f 517//517 647//647 648//648 -f 517//517 648//648 518//518 -f 518//518 648//648 649//649 -f 518//518 649//649 519//519 -f 519//519 649//649 650//650 -f 519//519 650//650 521//521 -f 521//521 650//650 651//651 -f 521//521 651//651 522//522 -f 522//522 651//651 652//652 -f 522//522 652//652 523//523 -f 523//523 652//652 653//653 -f 523//523 653//653 524//524 -f 524//524 653//653 642//642 -f 562//562 654//654 563//563 -f 563//563 654//654 655//655 -f 563//563 655//655 556//556 -f 556//556 655//655 656//656 -f 556//556 656//656 551//551 -f 551//551 656//656 657//657 -f 551//551 657//657 552//552 -f 552//552 657//657 658//658 -f 552//552 658//658 555//555 -f 555//555 658//658 659//659 -f 555//555 659//659 554//554 -f 554//554 659//659 660//660 -f 554//554 660//660 553//553 -f 553//553 660//660 661//661 -f 553//553 661//661 557//557 -f 557//557 661//661 662//662 -f 557//557 662//662 558//558 -f 558//558 662//662 663//663 -f 558//558 663//663 560//560 -f 560//560 663//663 664//664 -f 560//560 664//664 561//561 -f 561//561 664//664 665//665 -f 561//561 665//665 562//562 -f 562//562 665//665 654//654 -f 579//579 666//666 582//582 -f 582//582 666//666 667//667 -f 582//582 667//667 583//583 -f 583//583 667//667 668//668 -f 583//583 668//668 584//584 -f 584//584 668//668 669//669 -f 584//584 669//669 585//585 -f 585//585 669//669 670//670 -f 585//585 670//670 586//586 -f 586//586 670//670 671//671 -f 586//586 671//671 587//587 -f 587//587 671//671 672//672 -f 587//587 672//672 588//588 -f 588//588 672//672 673//673 -f 588//588 673//673 581//581 -f 581//581 673//673 674//674 -f 581//581 674//674 580//580 -f 580//580 674//674 675//675 -f 580//580 675//675 576//576 -f 576//576 675//675 676//676 -f 576//576 676//676 577//577 -f 577//577 676//676 677//677 -f 577//577 677//677 579//579 -f 579//579 677//677 666//666 -f 568//568 678//678 567//567 -f 567//567 678//678 679//679 -f 567//567 679//679 572//572 -f 572//572 679//679 680//680 -f 572//572 680//680 571//571 -f 571//571 680//680 681//681 -f 571//571 681//681 570//570 -f 570//570 681//681 682//682 -f 570//570 682//682 573//573 -f 573//573 682//682 683//683 -f 573//573 683//683 574//574 -f 574//574 683//683 684//684 -f 574//574 684//684 575//575 -f 575//575 684//684 685//685 -f 575//575 685//685 564//564 -f 564//564 685//685 686//686 -f 564//564 686//686 565//565 -f 565//565 686//686 687//687 -f 565//565 687//687 566//566 -f 566//566 687//687 688//688 -f 566//566 688//688 569//569 -f 569//569 688//688 689//689 -f 569//569 689//689 568//568 -f 568//568 689//689 678//678 -f 598//598 597//597 690//690 -f 596//596 691//691 597//597 -f 597//597 691//691 692//692 -f 597//597 692//692 690//690 -f 594//594 693//693 595//595 -f 595//595 693//693 694//694 -f 595//595 694//694 596//596 -f 596//596 694//694 695//695 -f 596//596 695//695 691//691 -f 591//591 696//696 594//594 -f 594//594 696//696 697//697 -f 594//594 697//697 693//693 -f 592//592 698//698 591//591 -f 591//591 698//698 699//699 -f 591//591 699//699 696//696 -f 593//593 700//700 592//592 -f 592//592 700//700 701//701 -f 592//592 701//701 698//698 -f 590//590 702//702 593//593 -f 593//593 702//702 703//703 -f 593//593 703//703 700//700 -f 589//589 704//704 590//590 -f 590//590 704//704 705//705 -f 590//590 705//705 702//702 -f 600//600 706//706 589//589 -f 589//589 706//706 707//707 -f 589//589 707//707 704//704 -f 599//599 708//708 600//600 -f 600//600 708//708 709//709 -f 709//709 710//710 600//600 -f 600//600 710//710 711//711 -f 600//600 711//711 706//706 -f 690//690 712//712 598//598 -f 598//598 712//712 713//713 -f 598//598 713//713 599//599 -f 599//599 713//713 714//714 -f 599//599 714//714 708//708 -f 715//715 716//716 546//546 -f 717//717 718//718 719//719 -f 717//717 719//719 720//720 -f 720//720 719//719 721//721 -f 721//721 719//719 722//722 -f 721//721 722//722 723//723 -f 724//724 725//725 726//726 -f 726//726 725//725 727//727 -f 726//726 727//727 728//728 -f 728//728 727//727 723//723 -f 728//728 723//723 729//729 -f 729//729 723//723 722//722 -f 548//548 547//547 730//730 -f 730//730 547//547 725//725 -f 730//730 725//725 731//731 -f 731//731 725//725 724//724 -f 546//546 716//716 547//547 -f 547//547 716//716 732//732 -f 547//547 732//732 725//725 -f 538//538 733//733 546//546 -f 546//546 733//733 734//734 -f 546//546 734//734 715//715 -f 735//735 549//549 736//736 -f 736//736 549//549 548//548 -f 736//736 548//548 737//737 -f 737//737 548//548 730//730 -f 738//738 739//739 538//538 -f 538//538 739//739 740//740 -f 538//538 740//740 733//733 -f 538//538 536//536 738//738 -f 738//738 536//536 534//534 -f 738//738 534//534 741//741 -f 741//741 534//534 533//533 -f 741//741 533//533 532//532 -f 505//505 742//742 503//503 -f 503//503 742//742 743//743 -f 503//503 743//743 531//531 -f 531//531 743//743 744//744 -f 531//531 744//744 532//532 -f 532//532 744//744 741//741 -f 745//745 742//742 510//510 -f 510//510 742//742 505//505 -f 499//499 746//746 507//507 -f 507//507 746//746 747//747 -f 507//507 747//747 508//508 -f 508//508 747//747 748//748 -f 508//508 748//748 510//510 -f 510//510 748//748 745//745 -f 749//749 750//750 540//540 -f 540//540 750//750 751//751 -f 540//540 751//751 752//752 -f 499//499 545//545 746//746 -f 746//746 545//545 544//544 -f 746//746 544//544 752//752 -f 752//752 544//544 542//542 -f 752//752 542//542 540//540 -f 749//749 540//540 753//753 -f 753//753 540//540 539//539 -f 753//753 539//539 754//754 -f 754//754 539//539 755//755 -f 756//756 757//757 758//758 -f 758//758 757//757 759//759 -f 758//758 759//759 760//760 -f 760//760 759//759 761//761 -f 760//760 761//761 762//762 -f 762//762 761//761 763//763 -f 762//762 763//763 764//764 -f 764//764 763//763 765//765 -f 764//764 765//765 766//766 -f 766//766 765//765 767//767 -f 766//766 767//767 768//768 -f 768//768 767//767 769//769 -f 768//768 769//769 770//770 -f 770//770 769//769 771//771 -f 770//770 771//771 772//772 -f 772//772 771//771 773//773 -f 772//772 773//773 774//774 -f 550//550 775//775 494//494 -f 494//494 775//775 776//776 -f 776//776 777//777 494//494 -f 494//494 777//777 774//774 -f 494//494 774//774 539//539 -f 539//539 774//774 773//773 -f 539//539 773//773 755//755 -f 778//778 718//718 779//779 -f 779//779 718//718 780//780 -f 781//781 756//756 782//782 -f 782//782 756//756 783//783 -f 784//784 719//719 718//718 -f 775//775 550//550 785//785 -f 785//785 550//550 786//786 -f 787//787 788//788 550//550 -f 786//786 550//550 789//789 -f 789//789 550//550 788//788 -f 789//789 788//788 790//790 -f 790//790 788//788 791//791 -f 790//790 791//791 792//792 -f 792//792 791//791 793//793 -f 792//792 793//793 794//794 -f 794//794 793//793 783//783 -f 794//794 783//783 795//795 -f 795//795 783//783 756//756 -f 795//795 756//756 758//758 -f 796//796 549//549 797//797 -f 797//797 549//549 735//735 -f 793//793 798//798 783//783 -f 783//783 798//798 799//799 -f 783//783 799//799 778//778 -f 778//778 799//799 800//800 -f 778//778 800//800 801//801 -f 787//787 550//550 802//802 -f 802//802 550//550 549//549 -f 802//802 549//549 803//803 -f 803//803 549//549 796//796 -f 803//803 796//796 804//804 -f 784//784 718//718 805//805 -f 805//805 718//718 778//778 -f 805//805 778//778 806//806 -f 806//806 778//778 801//801 -f 806//806 801//801 807//807 -f 807//807 801//801 808//808 -f 807//807 808//808 804//804 -f 804//804 808//808 809//809 -f 804//804 809//809 803//803 -f 431//431 430//430 810//810 -f 431//431 810//810 528//528 -f 528//528 810//810 811//811 -f 528//528 811//811 513//513 -f 513//513 811//811 812//812 -f 513//513 812//812 514//514 -f 514//514 812//812 813//813 -f 514//514 813//813 516//516 -f 516//516 813//813 814//814 -f 516//516 814//814 504//504 -f 504//504 814//814 815//815 -f 504//504 815//815 506//506 -f 506//506 815//815 615//615 -f 506//506 615//615 512//512 -f 511//511 616//616 816//816 -f 511//511 816//816 509//509 -f 509//509 816//816 817//817 -f 509//509 817//817 500//500 -f 500//500 817//817 818//818 -f 500//500 818//818 502//502 -f 502//502 818//818 819//819 -f 502//502 819//819 496//496 -f 496//496 819//819 820//820 -f 496//496 820//820 497//497 -f 497//497 820//820 821//821 -f 497//497 821//821 614//614 -f 614//614 821//821 437//437 -f 614//614 437//437 438//438 -f 655//655 654//654 437//437 -f 689//689 738//738 678//678 -f 678//678 738//738 741//741 -f 678//678 741//741 679//679 -f 679//679 741//741 642//642 -f 642//642 653//653 679//679 -f 679//679 653//653 652//652 -f 679//679 652//652 680//680 -f 689//689 688//688 738//738 -f 738//738 688//688 687//687 -f 738//738 687//687 428//428 -f 428//428 687//687 686//686 -f 683//683 430//430 684//684 -f 684//684 430//430 428//428 -f 684//684 428//428 685//685 -f 685//685 428//428 686//686 -f 675//675 752//752 676//676 -f 676//676 752//752 432//432 -f 676//676 432//432 677//677 -f 677//677 432//432 666//666 -f 670//670 669//669 663//663 -f 680//680 652//652 681//681 -f 681//681 652//652 651//651 -f 681//681 651//651 682//682 -f 682//682 651//651 650//650 -f 682//682 650//650 683//683 -f 683//683 650//650 649//649 -f 683//683 649//649 430//430 -f 437//437 654//654 432//432 -f 654//654 665//665 432//432 -f 432//432 665//665 664//664 -f 432//432 664//664 666//666 -f 666//666 664//664 667//667 -f 663//663 669//669 664//664 -f 664//664 669//669 668//668 -f 664//664 668//668 667//667 -f 645//645 644//644 741//741 -f 741//741 644//644 643//643 -f 741//741 643//643 642//642 -f 812//812 744//744 813//813 -f 813//813 744//744 743//743 -f 655//655 437//437 656//656 -f 656//656 437//437 821//821 -f 656//656 821//821 657//657 -f 657//657 821//821 820//820 -f 657//657 820//820 819//819 -f 649//649 648//648 430//430 -f 430//430 648//648 647//647 -f 430//430 647//647 810//810 -f 810//810 647//647 646//646 -f 810//810 646//646 811//811 -f 811//811 646//646 645//645 -f 811//811 645//645 812//812 -f 812//812 645//645 741//741 -f 812//812 741//741 744//744 -f 658//658 657//657 746//746 -f 746//746 657//657 819//819 -f 746//746 819//819 747//747 -f 747//747 819//819 818//818 -f 747//747 818//818 748//748 -f 748//748 818//818 817//817 -f 748//748 817//817 745//745 -f 745//745 817//817 816//816 -f 675//675 674//674 752//752 -f 752//752 674//674 673//673 -f 752//752 673//673 672//672 -f 752//752 661//661 660//660 -f 752//752 660//660 746//746 -f 746//746 660//660 659//659 -f 746//746 659//659 658//658 -f 816//816 616//616 745//745 -f 745//745 616//616 615//615 -f 745//745 615//615 742//742 -f 742//742 615//615 815//815 -f 742//742 815//815 743//743 -f 743//743 815//815 814//814 -f 743//743 814//814 813//813 -f 661//661 752//752 662//662 -f 662//662 752//752 672//672 -f 662//662 672//672 663//663 -f 663//663 672//672 671//671 -f 663//663 671//671 670//670 -f 822//822 483//483 823//823 -f 823//823 483//483 481//481 -f 441//441 824//824 439//439 -f 439//439 824//824 825//825 -f 439//439 825//825 481//481 -f 481//481 825//825 826//826 -f 481//481 826//826 823//823 -f 783//783 443//443 489//489 -f 822//822 827//827 483//483 -f 483//483 827//827 828//828 -f 483//483 828//828 485//485 -f 828//828 829//829 485//485 -f 485//485 829//829 830//830 -f 485//485 830//830 487//487 -f 487//487 830//830 781//781 -f 487//487 781//781 489//489 -f 489//489 781//781 782//782 -f 489//489 782//782 783//783 -f 455//455 443//443 778//778 -f 778//778 443//443 783//783 -f 831//831 832//832 492//492 -f 491//491 833//833 492//492 -f 492//492 833//833 834//834 -f 492//492 834//834 831//831 -f 779//779 780//780 479//479 -f 479//479 780//780 835//835 -f 479//479 835//835 491//491 -f 491//491 835//835 836//836 -f 491//491 836//836 833//833 -f 479//479 457//457 779//779 -f 779//779 457//457 455//455 -f 779//779 455//455 778//778 -f 837//837 422//422 421//421 -f 493//493 492//492 832//832 -f 832//832 838//838 493//493 -f 493//493 838//838 839//839 -f 493//493 839//839 421//421 -f 421//421 839//839 840//840 -f 421//421 840//840 837//837 -f 757//757 756//756 781//781 -f 620//620 624//624 433//433 -f 617//617 751//751 639//639 -f 639//639 751//751 750//750 -f 639//639 750//750 640//640 -f 617//617 619//619 751//751 -f 751//751 619//619 618//618 -f 751//751 618//618 622//622 -f 620//620 433//433 621//621 -f 624//624 623//623 433//433 -f 433//433 623//623 626//626 -f 433//433 626//626 442//442 -f 640//640 750//750 641//641 -f 641//641 750//750 749//749 -f 641//641 749//749 635//635 -f 635//635 749//749 753//753 -f 635//635 753//753 636//636 -f 632//632 631//631 823//823 -f 632//632 823//823 629//629 -f 634//634 633//633 771//771 -f 633//633 638//638 771//771 -f 771//771 638//638 637//637 -f 771//771 637//637 773//773 -f 773//773 637//637 755//755 -f 636//636 753//753 637//637 -f 637//637 753//753 754//754 -f 637//637 754//754 755//755 -f 823//823 826//826 629//629 -f 629//629 826//826 825//825 -f 629//629 825//825 630//630 -f 630//630 825//825 824//824 -f 630//630 824//824 627//627 -f 627//627 824//824 441//441 -f 627//627 441//441 628//628 -f 628//628 441//441 442//442 -f 628//628 442//442 625//625 -f 625//625 442//442 626//626 -f 631//631 634//634 823//823 -f 823//823 634//634 771//771 -f 823//823 771//771 822//822 -f 822//822 771//771 827//827 -f 827//827 771//771 828//828 -f 828//828 771//771 769//769 -f 828//828 769//769 767//767 -f 767//767 765//765 828//828 -f 828//828 765//765 763//763 -f 828//828 763//763 829//829 -f 829//829 763//763 830//830 -f 830//830 763//763 761//761 -f 830//830 761//761 781//781 -f 781//781 761//761 759//759 -f 781//781 759//759 757//757 -f 432//432 752//752 433//433 -f 433//433 752//752 751//751 -f 433//433 751//751 621//621 -f 621//621 751//751 622//622 -f 425//425 712//712 426//426 -f 426//426 712//712 690//690 -f 690//690 692//692 426//426 -f 426//426 692//692 691//691 -f 426//426 691//691 695//695 -f 697//697 739//739 693//693 -f 693//693 739//739 694//694 -f 697//697 696//696 739//739 -f 739//739 696//696 699//699 -f 739//739 699//699 740//740 -f 702//702 705//705 732//732 -f 705//705 704//704 732//732 -f 732//732 704//704 707//707 -f 732//732 707//707 838//838 -f 710//710 709//709 837//837 -f 837//837 709//709 708//708 -f 837//837 708//708 422//422 -f 422//422 708//708 714//714 -f 422//422 714//714 425//425 -f 425//425 714//714 713//713 -f 425//425 713//713 712//712 -f 707//707 706//706 838//838 -f 838//838 706//706 711//711 -f 838//838 711//711 839//839 -f 839//839 711//711 710//710 -f 839//839 710//710 840//840 -f 840//840 710//710 837//837 -f 732//732 716//716 702//702 -f 702//702 716//716 715//715 -f 702//702 715//715 703//703 -f 703//703 715//715 734//734 -f 703//703 734//734 700//700 -f 700//700 734//734 733//733 -f 700//700 733//733 701//701 -f 701//701 733//733 740//740 -f 701//701 740//740 698//698 -f 698//698 740//740 699//699 -f 834//834 725//725 831//831 -f 831//831 725//725 732//732 -f 831//831 732//732 832//832 -f 832//832 732//732 838//838 -f 780//780 718//718 717//717 -f 833//833 723//723 834//834 -f 834//834 723//723 727//727 -f 834//834 727//727 725//725 -f 717//717 720//720 780//780 -f 780//780 720//720 721//721 -f 780//780 721//721 835//835 -f 835//835 721//721 723//723 -f 835//835 723//723 836//836 -f 836//836 723//723 833//833 -f 738//738 428//428 739//739 -f 739//739 428//428 426//426 -f 739//739 426//426 694//694 -f 694//694 426//426 695//695 -f 474//474 791//791 446//446 -f 446//446 791//791 788//788 -f 446//446 788//788 447//447 -f 447//447 788//788 787//787 -f 447//447 787//787 449//449 -f 449//449 787//787 802//802 -f 449//449 802//802 459//459 -f 459//459 802//802 803//803 -f 459//459 803//803 460//460 -f 460//460 803//803 809//809 -f 460//460 809//809 462//462 -f 462//462 809//809 808//808 -f 462//462 808//808 452//452 -f 452//452 808//808 801//801 -f 452//452 801//801 453//453 -f 453//453 801//801 800//800 -f 453//453 800//800 444//444 -f 444//444 800//800 799//799 -f 444//444 799//799 445//445 -f 445//445 799//799 798//798 -f 445//445 798//798 476//476 -f 476//476 798//798 793//793 -f 476//476 793//793 474//474 -f 474//474 793//793 791//791 -f 478//478 728//728 729//729 -f 478//478 729//729 458//458 -f 728//728 478//478 726//726 -f 726//726 478//478 480//480 -f 726//726 480//480 724//724 -f 724//724 480//480 731//731 -f 731//731 480//480 470//470 -f 731//731 470//470 730//730 -f 469//469 736//736 470//470 -f 470//470 736//736 737//737 -f 470//470 737//737 730//730 -f 729//729 722//722 458//458 -f 458//458 722//722 719//719 -f 458//458 719//719 456//456 -f 456//456 719//719 784//784 -f 456//456 784//784 454//454 -f 454//454 784//784 805//805 -f 454//454 805//805 451//451 -f 451//451 805//805 806//806 -f 451//451 806//806 463//463 -f 463//463 806//806 807//807 -f 463//463 807//807 464//464 -f 464//464 807//807 804//804 -f 464//464 804//804 461//461 -f 461//461 804//804 796//796 -f 461//461 796//796 468//468 -f 468//468 796//796 797//797 -f 468//468 797//797 469//469 -f 469//469 797//797 735//735 -f 469//469 735//735 736//736 -f 467//467 465//465 777//777 -f 768//768 770//770 482//482 -f 482//482 770//770 772//772 -f 482//482 772//772 465//465 -f 465//465 772//772 774//774 -f 465//465 774//774 777//777 -f 484//484 486//486 760//760 -f 760//760 762//762 484//484 -f 484//484 762//762 764//764 -f 484//484 764//764 482//482 -f 482//482 764//764 766//766 -f 482//482 766//766 768//768 -f 777//777 776//776 467//467 -f 467//467 776//776 775//775 -f 467//467 775//775 471//471 -f 471//471 775//775 785//785 -f 471//471 785//785 472//472 -f 472//472 785//785 786//786 -f 472//472 786//786 473//473 -f 473//473 786//786 789//789 -f 473//473 789//789 475//475 -f 475//475 789//789 790//790 -f 475//475 790//790 477//477 -f 477//477 790//790 792//792 -f 477//477 792//792 490//490 -f 490//490 792//792 794//794 -f 490//490 794//794 488//488 -f 488//488 794//794 795//795 -f 488//488 795//795 486//486 -f 486//486 795//795 758//758 -f 486//486 758//758 760//760 -f 841//841 842//842 843//843 -f 843//843 842//842 844//844 -f 843//843 844//844 845//845 -f 845//845 844//844 846//846 -f 845//845 846//846 847//847 -f 847//847 846//846 848//848 -f 847//847 848//848 849//849 -f 849//849 848//848 850//850 -f 849//849 850//850 851//851 -f 851//851 850//850 852//852 -f 851//851 852//852 853//853 -f 853//853 852//852 854//854 -f 853//853 854//854 855//855 -f 855//855 854//854 856//856 -f 855//855 856//856 857//857 -f 857//857 856//856 858//858 -f 857//857 858//858 859//859 -f 859//859 858//858 860//860 -f 859//859 860//860 861//861 -f 861//861 860//860 862//862 -f 861//861 862//862 863//863 -f 863//863 862//862 864//864 -f 863//863 864//864 841//841 -f 841//841 864//864 842//842 -f 865//865 866//866 867//867 -f 867//867 866//866 868//868 -f 867//867 868//868 869//869 -f 869//869 868//868 870//870 -f 869//869 870//870 871//871 -f 871//871 870//870 872//872 -f 871//871 872//872 873//873 -f 873//873 872//872 874//874 -f 873//873 874//874 875//875 -f 875//875 874//874 876//876 -f 875//875 876//876 877//877 -f 877//877 876//876 878//878 -f 877//877 878//878 879//879 -f 879//879 878//878 880//880 -f 879//879 880//880 881//881 -f 881//881 880//880 882//882 -f 881//881 882//882 883//883 -f 883//883 882//882 884//884 -f 883//883 884//884 885//885 -f 885//885 884//884 886//886 -f 885//885 886//886 887//887 -f 887//887 886//886 888//888 -f 887//887 888//888 865//865 -f 865//865 888//888 866//866 -f 889//889 890//890 891//891 -f 891//891 890//890 892//892 -f 891//891 892//892 893//893 -f 893//893 892//892 894//894 -f 893//893 894//894 895//895 -f 895//895 894//894 896//896 -f 895//895 896//896 897//897 -f 897//897 896//896 898//898 -f 897//897 898//898 899//899 -f 899//899 898//898 900//900 -f 899//899 900//900 901//901 -f 901//901 900//900 902//902 -f 901//901 902//902 903//903 -f 903//903 902//902 904//904 -f 903//903 904//904 905//905 -f 905//905 904//904 906//906 -f 905//905 906//906 907//907 -f 907//907 906//906 908//908 -f 907//907 908//908 909//909 -f 909//909 908//908 910//910 -f 909//909 910//910 911//911 -f 911//911 910//910 912//912 -f 911//911 912//912 889//889 -f 889//889 912//912 890//890 -f 913//913 914//914 915//915 -f 916//916 917//917 918//918 -f 918//918 917//917 919//919 -f 918//918 919//919 920//920 -f 921//921 922//922 923//923 -f 923//923 922//922 924//924 -f 924//924 925//925 926//926 -f 926//926 925//925 927//927 -f 926//926 927//927 928//928 -f 928//928 927//927 929//929 -f 929//929 930//930 928//928 -f 928//928 930//930 931//931 -f 928//928 931//931 932//932 -f 932//932 931//931 933//933 -f 934//934 935//935 936//936 -f 936//936 935//935 937//937 -f 938//938 939//939 940//940 -f 940//940 939//939 941//941 -f 940//940 941//941 942//942 -f 941//941 943//943 942//942 -f 942//942 943//943 944//944 -f 942//942 944//944 936//936 -f 936//936 944//944 945//945 -f 936//936 945//945 934//934 -f 946//946 947//947 948//948 -f 935//935 949//949 937//937 -f 937//937 949//949 950//950 -f 937//937 950//950 947//947 -f 947//947 950//950 951//951 -f 947//947 951//951 948//948 -f 884//884 882//882 952//952 -f 884//884 952//952 886//886 -f 953//953 874//874 954//954 -f 954//954 874//874 872//872 -f 882//882 880//880 952//952 -f 952//952 880//880 878//878 -f 952//952 878//878 953//953 -f 953//953 878//878 876//876 -f 953//953 876//876 874//874 -f 955//955 956//956 888//888 -f 888//888 956//956 957//957 -f 888//888 957//957 866//866 -f 866//866 957//957 958//958 -f 866//866 958//958 868//868 -f 868//868 958//958 959//959 -f 868//868 959//959 870//870 -f 870//870 959//959 960//960 -f 870//870 960//960 872//872 -f 872//872 960//960 961//961 -f 872//872 961//961 954//954 -f 888//888 886//886 955//955 -f 955//955 886//886 952//952 -f 955//955 952//952 962//962 -f 962//962 952//952 940//940 -f 962//962 940//940 963//963 -f 963//963 940//940 942//942 -f 964//964 965//965 966//966 -f 967//967 968//968 937//937 -f 937//937 968//968 936//936 -f 936//936 968//968 969//969 -f 936//936 969//969 970//970 -f 915//915 914//914 969//969 -f 969//969 914//914 971//971 -f 969//969 971//971 970//970 -f 972//972 973//973 974//974 -f 974//974 973//973 975//975 -f 974//974 975//975 915//915 -f 915//915 975//975 976//976 -f 915//915 976//976 913//913 -f 977//977 978//978 979//979 -f 979//979 978//978 980//980 -f 979//979 980//980 981//981 -f 972//972 977//977 973//973 -f 973//973 977//977 979//979 -f 973//973 979//979 982//982 -f 982//982 979//979 983//983 -f 984//984 985//985 986//986 -f 986//986 987//987 988//988 -f 988//988 989//989 986//986 -f 986//986 989//989 990//990 -f 986//986 990//990 984//984 -f 988//988 991//991 989//989 -f 989//989 991//991 992//992 -f 989//989 992//992 993//993 -f 993//993 992//992 994//994 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 924//924 926//926 923//923 -f 923//923 926//926 998//998 -f 923//923 998//998 999//999 -f 999//999 1000//1000 923//923 -f 923//923 1000//1000 1001//1001 -f 923//923 1001//1001 1002//1002 -f 1002//1002 1001//1001 1003//1003 -f 1002//1002 1003//1003 986//986 -f 986//986 1003//1003 1004//1004 -f 986//986 1004//1004 987//987 -f 926//926 1005//1005 998//998 -f 998//998 1005//1005 1006//1006 -f 998//998 1006//1006 996//996 -f 996//996 1006//1006 1007//1007 -f 996//996 1007//1007 997//997 -f 1008//1008 1009//1009 890//890 -f 890//890 912//912 1008//1008 -f 1008//1008 912//912 910//910 -f 1008//1008 910//910 908//908 -f 908//908 1010//1010 1008//1008 -f 1008//1008 1010//1010 1011//1011 -f 1008//1008 1011//1011 932//932 -f 932//932 1011//1011 1012//1012 -f 932//932 1012//1012 928//928 -f 908//908 906//906 1010//1010 -f 1010//1010 906//906 904//904 -f 1010//1010 904//904 1013//1013 -f 1013//1013 904//904 1014//1014 -f 1014//1014 904//904 1015//1015 -f 1015//1015 904//904 902//902 -f 1015//1015 902//902 1016//1016 -f 1016//1016 902//902 900//900 -f 1016//1016 900//900 1017//1017 -f 1017//1017 900//900 898//898 -f 1017//1017 898//898 1018//1018 -f 1018//1018 898//898 896//896 -f 1018//1018 896//896 1019//1019 -f 1019//1019 896//896 894//894 -f 1019//1019 894//894 1009//1009 -f 1009//1009 894//894 892//892 -f 1009//1009 892//892 890//890 -f 1020//1020 1021//1021 1022//1022 -f 1023//1023 1024//1024 1025//1025 -f 1025//1025 1024//1024 1026//1026 -f 1020//1020 1022//1022 1027//1027 -f 1021//1021 1028//1028 1022//1022 -f 1022//1022 1028//1028 1029//1029 -f 1022//1022 1029//1029 1030//1030 -f 1030//1030 1029//1029 1031//1031 -f 1030//1030 1031//1031 1032//1032 -f 1032//1032 1031//1031 1033//1033 -f 1032//1032 1033//1033 1034//1034 -f 1034//1034 1033//1033 1035//1035 -f 1034//1034 1035//1035 1036//1036 -f 1036//1036 1035//1035 1037//1037 -f 1036//1036 1037//1037 1023//1023 -f 1023//1023 1037//1037 1038//1038 -f 1023//1023 1038//1038 1024//1024 -f 1039//1039 1040//1040 1041//1041 -f 1041//1041 1040//1040 1042//1042 -f 1041//1041 1042//1042 1043//1043 -f 1043//1043 1042//1042 1044//1044 -f 1045//1045 1046//1046 1047//1047 -f 856//856 854//854 1048//1048 -f 1048//1048 854//854 1049//1049 -f 1049//1049 854//854 852//852 -f 1049//1049 852//852 1050//1050 -f 860//860 858//858 1051//1051 -f 860//860 1051//1051 862//862 -f 1052//1052 864//864 862//862 -f 1053//1053 844//844 1054//1054 -f 1054//1054 844//844 842//842 -f 1054//1054 842//842 1055//1055 -f 852//852 850//850 1050//1050 -f 1050//1050 850//850 848//848 -f 1050//1050 848//848 1053//1053 -f 1053//1053 848//848 846//846 -f 1053//1053 846//846 844//844 -f 953//953 1054//1054 952//952 -f 952//952 1054//1054 1055//1055 -f 952//952 1055//1055 940//940 -f 940//940 1055//1055 946//946 -f 940//940 946//946 938//938 -f 938//938 946//946 948//948 -f 1056//1056 1057//1057 1052//1052 -f 1058//1058 1059//1059 1060//1060 -f 862//862 1051//1051 1052//1052 -f 1052//1052 1051//1051 1061//1061 -f 1052//1052 1061//1061 1056//1056 -f 1057//1057 1062//1062 1052//1052 -f 1052//1052 1062//1062 1063//1063 -f 1052//1052 1063//1063 1064//1064 -f 1064//1064 1063//1063 1065//1065 -f 1064//1064 1065//1065 1066//1066 -f 1059//1059 1067//1067 1060//1060 -f 1060//1060 1067//1067 1068//1068 -f 1060//1060 1068//1068 1051//1051 -f 1051//1051 1068//1068 1069//1069 -f 1051//1051 1069//1069 1061//1061 -f 1049//1049 1009//1009 1048//1048 -f 1048//1048 1009//1009 1008//1008 -f 1048//1048 1008//1008 918//918 -f 918//918 1008//1008 932//932 -f 918//918 932//932 916//916 -f 916//916 932//932 933//933 -f 842//842 864//864 1055//1055 -f 1055//1055 864//864 1052//1052 -f 1055//1055 1052//1052 946//946 -f 946//946 1052//1052 1064//1064 -f 946//946 1064//1064 947//947 -f 947//947 1064//1064 1022//1022 -f 947//947 1022//1022 1046//1046 -f 1046//1046 1022//1022 1030//1030 -f 1066//1066 1058//1058 1064//1064 -f 1064//1064 1058//1058 1060//1060 -f 1064//1064 1060//1060 1022//1022 -f 1022//1022 1060//1060 1025//1025 -f 1022//1022 1025//1025 1027//1027 -f 1027//1027 1025//1025 1026//1026 -f 858//858 856//856 1051//1051 -f 1051//1051 856//856 1048//1048 -f 1051//1051 1048//1048 1060//1060 -f 1060//1060 1048//1048 918//918 -f 1060//1060 918//918 1025//1025 -f 1025//1025 918//918 920//920 -f 1025//1025 920//920 1023//1023 -f 1023//1023 920//920 1039//1039 -f 1023//1023 1039//1039 1070//1070 -f 1070//1070 1039//1039 1041//1041 -f 1046//1046 1045//1045 947//947 -f 947//947 1045//1045 964//964 -f 947//947 964//964 937//937 -f 937//937 964//964 966//966 -f 937//937 966//966 967//967 -f 1044//1044 1042//1042 1071//1071 -f 1071//1071 1042//1042 1072//1072 -f 1071//1071 1072//1072 1047//1047 -f 1047//1047 1072//1072 1073//1073 -f 1047//1047 1073//1073 1045//1045 -f 1045//1045 1073//1073 979//979 -f 1045//1045 979//979 964//964 -f 964//964 979//979 981//981 -f 964//964 981//981 965//965 -f 919//919 921//921 920//920 -f 920//920 921//921 923//923 -f 920//920 923//923 1039//1039 -f 1039//1039 923//923 1002//1002 -f 1039//1039 1002//1002 1040//1040 -f 1040//1040 1002//1002 986//986 -f 985//985 1074//1074 986//986 -f 986//986 1074//1074 1075//1075 -f 986//986 1075//1075 1040//1040 -f 1040//1040 1075//1075 1076//1076 -f 1040//1040 1076//1076 1042//1042 -f 1042//1042 1076//1076 1077//1077 -f 1042//1042 1077//1077 1072//1072 -f 1072//1072 1077//1077 1078//1078 -f 1072//1072 1078//1078 1073//1073 -f 1073//1073 1078//1078 1079//1079 -f 1073//1073 1079//1079 979//979 -f 979//979 1079//1079 1080//1080 -f 979//979 1080//1080 983//983 -f 1081//1081 1082//1082 1083//1083 -f 1084//1084 1085//1085 1086//1086 -f 1087//1087 1088//1088 1089//1089 -f 1087//1087 1089//1089 1090//1090 -f 1090//1090 1089//1089 1091//1091 -f 1090//1090 1091//1091 1092//1092 -f 1093//1093 1094//1094 1082//1082 -f 1082//1082 1094//1094 1095//1095 -f 1082//1082 1095//1095 1083//1083 -f 1096//1096 1097//1097 1098//1098 -f 1099//1099 1100//1100 1101//1101 -f 1101//1101 1100//1100 1102//1102 -f 1101//1101 1102//1102 1103//1103 -f 1103//1103 1102//1102 1104//1104 -f 1103//1103 1104//1104 1105//1105 -f 1106//1106 1107//1107 1108//1108 -f 1108//1108 1107//1107 1109//1109 -f 1108//1108 1109//1109 1110//1110 -f 1111//1111 1112//1112 1113//1113 -f 1112//1112 1114//1114 1113//1113 -f 1113//1113 1114//1114 1115//1115 -f 1113//1113 1115//1115 1116//1116 -f 1117//1117 1118//1118 1119//1119 -f 1119//1119 1118//1118 1120//1120 -f 1121//1121 1111//1111 1122//1122 -f 1123//1123 1124//1124 1125//1125 -f 1125//1125 1124//1124 1126//1126 -f 1125//1125 1126//1126 1122//1122 -f 1122//1122 1126//1126 1127//1127 -f 1122//1122 1127//1127 1121//1121 -f 1128//1128 1129//1129 1130//1130 -f 1130//1130 1129//1129 1131//1131 -f 1130//1130 1131//1131 1132//1132 -f 1133//1133 1134//1134 1135//1135 -f 1135//1135 1134//1134 1086//1086 -f 1135//1135 1086//1086 1136//1136 -f 1136//1136 1086//1086 1085//1085 -f 1085//1085 1137//1137 1136//1136 -f 1136//1136 1137//1137 1138//1138 -f 1136//1136 1138//1138 1139//1139 -f 1139//1139 1138//1138 1140//1140 -f 1139//1139 1140//1140 1128//1128 -f 1128//1128 1140//1140 1141//1141 -f 1128//1128 1141//1141 1129//1129 -f 1142//1142 1143//1143 1144//1144 -f 1144//1144 1143//1143 1145//1145 -f 1144//1144 1145//1145 1123//1123 -f 1123//1123 1145//1145 1146//1146 -f 1123//1123 1146//1146 1124//1124 -f 1147//1147 1132//1132 1148//1148 -f 1148//1148 1132//1132 1149//1149 -f 1148//1148 1149//1149 1150//1150 -f 1150//1150 1149//1149 1151//1151 -f 1149//1149 1152//1152 1151//1151 -f 1151//1151 1152//1152 1142//1142 -f 1151//1151 1142//1142 1153//1153 -f 1144//1144 1118//1118 1142//1142 -f 1142//1142 1118//1118 1117//1117 -f 1142//1142 1117//1117 1153//1153 -f 1153//1153 1117//1117 1154//1154 -f 1153//1153 1154//1154 1155//1155 -f 1155//1155 1154//1154 1156//1156 -f 1155//1155 1156//1156 1147//1147 -f 1147//1147 1156//1156 1134//1134 -f 1147//1147 1134//1134 1132//1132 -f 1132//1132 1134//1134 1133//1133 -f 1132//1132 1133//1133 1130//1130 -f 1157//1157 1158//1158 1159//1159 -f 1159//1159 1158//1158 1160//1160 -f 1157//1157 1093//1093 1161//1161 -f 1161//1161 1093//1093 1082//1082 -f 1161//1161 1082//1082 1162//1162 -f 1162//1162 1082//1082 1081//1081 -f 1162//1162 1081//1081 1163//1163 -f 1163//1163 1081//1081 1164//1164 -f 1163//1163 1164//1164 1091//1091 -f 1091//1091 1164//1164 1165//1165 -f 1091//1091 1165//1165 1092//1092 -f 1166//1166 1167//1167 1159//1159 -f 1159//1159 1167//1167 1168//1168 -f 1157//1157 1159//1159 1093//1093 -f 1093//1093 1159//1159 1168//1168 -f 1093//1093 1168//1168 1169//1169 -f 1169//1169 1168//1168 1170//1170 -f 1169//1169 1170//1170 1171//1171 -f 1172//1172 1173//1173 1174//1174 -f 1175//1175 1176//1176 1177//1177 -f 1177//1177 1176//1176 1178//1178 -f 1175//1175 1166//1166 1176//1176 -f 1176//1176 1166//1166 1159//1159 -f 1176//1176 1159//1159 1179//1179 -f 1179//1179 1159//1159 1160//1160 -f 1179//1179 1160//1160 1089//1089 -f 1089//1089 1160//1160 1180//1180 -f 1089//1089 1180//1180 1091//1091 -f 1175//1175 1181//1181 1166//1166 -f 1166//1166 1181//1181 1182//1182 -f 1166//1166 1182//1182 1174//1174 -f 1174//1174 1182//1182 1183//1183 -f 1174//1174 1183//1183 1184//1184 -f 1178//1178 1176//1176 1185//1185 -f 1185//1185 1176//1176 1172//1172 -f 1185//1185 1172//1172 1186//1186 -f 1184//1184 1187//1187 1174//1174 -f 1174//1174 1187//1187 1188//1188 -f 1174//1174 1188//1188 1172//1172 -f 1172//1172 1188//1188 1189//1189 -f 1172//1172 1189//1189 1186//1186 -f 1190//1190 1191//1191 1192//1192 -f 1170//1170 1193//1193 1171//1171 -f 1171//1171 1193//1193 1190//1190 -f 1171//1171 1190//1190 1194//1194 -f 1194//1194 1190//1190 1192//1192 -f 1194//1194 1192//1192 1096//1096 -f 1096//1096 1192//1192 1105//1105 -f 1096//1096 1105//1105 1097//1097 -f 1097//1097 1105//1105 1104//1104 -f 1190//1190 1195//1195 1108//1108 -f 1191//1191 1190//1190 1196//1196 -f 1196//1196 1190//1190 1108//1108 -f 1196//1196 1108//1108 1197//1197 -f 1197//1197 1108//1108 1110//1110 -f 1197//1197 1110//1110 1099//1099 -f 1099//1099 1110//1110 1198//1198 -f 1099//1099 1198//1198 1100//1100 -f 1098//1098 1199//1199 1096//1096 -f 1096//1096 1199//1199 1200//1200 -f 1096//1096 1200//1200 1194//1194 -f 1194//1194 1200//1200 1201//1201 -f 1194//1194 1201//1201 1171//1171 -f 1171//1171 1201//1201 1202//1202 -f 1171//1171 1202//1202 1169//1169 -f 1169//1169 1202//1202 1203//1203 -f 1169//1169 1203//1203 1093//1093 -f 1093//1093 1203//1203 1204//1204 -f 1093//1093 1204//1204 1094//1094 -f 1205//1205 1206//1206 1106//1106 -f 1108//1108 1207//1207 1208//1208 -f 1106//1106 1206//1206 1116//1116 -f 1113//1113 1209//1209 1210//1210 -f 1206//1206 1211//1211 1116//1116 -f 1116//1116 1211//1211 1212//1212 -f 1116//1116 1212//1212 1113//1113 -f 1113//1113 1212//1212 1213//1213 -f 1113//1113 1213//1213 1209//1209 -f 1208//1208 1214//1214 1108//1108 -f 1108//1108 1214//1214 1215//1215 -f 1108//1108 1215//1215 1106//1106 -f 1106//1106 1215//1215 1216//1216 -f 1106//1106 1216//1216 1205//1205 -f 1210//1210 1207//1207 1113//1113 -f 1113//1113 1207//1207 1108//1108 -f 1113//1113 1108//1108 1217//1217 -f 1217//1217 1108//1108 1195//1195 -f 1217//1217 1195//1195 1218//1218 -f 1219//1219 1220//1220 1089//1089 -f 1089//1089 1220//1220 1179//1179 -f 1179//1179 1220//1220 1221//1221 -f 1179//1179 1221//1221 1222//1222 -f 1222//1222 1223//1223 1179//1179 -f 1179//1179 1223//1223 1224//1224 -f 1179//1179 1224//1224 1176//1176 -f 1176//1176 1224//1224 1225//1225 -f 1176//1176 1225//1225 1172//1172 -f 1223//1223 1226//1226 1224//1224 -f 1224//1224 1226//1226 1227//1227 -f 1224//1224 1227//1227 1228//1228 -f 1228//1228 1227//1227 1229//1229 -f 1228//1228 1229//1229 1230//1230 -f 1230//1230 1231//1231 1228//1228 -f 1228//1228 1231//1231 1232//1232 -f 1228//1228 1232//1232 1089//1089 -f 1089//1089 1232//1232 1233//1233 -f 1089//1089 1233//1233 1219//1219 -f 1088//1088 1234//1234 1089//1089 -f 1089//1089 1234//1234 1235//1235 -f 1089//1089 1235//1235 1228//1228 -f 1228//1228 1235//1235 1236//1236 -f 1228//1228 1236//1236 1237//1237 -f 1225//1225 1238//1238 1239//1239 -f 1240//1240 1241//1241 1154//1154 -f 1239//1239 1242//1242 1225//1225 -f 1225//1225 1242//1242 1218//1218 -f 1225//1225 1218//1218 1172//1172 -f 1172//1172 1218//1218 1195//1195 -f 1172//1172 1195//1195 1173//1173 -f 1173//1173 1195//1195 1190//1190 -f 1173//1173 1190//1190 1243//1243 -f 1243//1243 1190//1190 1193//1193 -f 1242//1242 1244//1244 1218//1218 -f 1218//1218 1244//1244 1245//1245 -f 1218//1218 1245//1245 1246//1246 -f 1246//1246 1240//1240 1218//1218 -f 1218//1218 1240//1240 1154//1154 -f 1218//1218 1154//1154 1217//1217 -f 1217//1217 1154//1154 1117//1117 -f 1217//1217 1117//1117 1113//1113 -f 1113//1113 1117//1117 1119//1119 -f 1113//1113 1119//1119 1111//1111 -f 1111//1111 1119//1119 1120//1120 -f 1111//1111 1120//1120 1122//1122 -f 1241//1241 1247//1247 1154//1154 -f 1154//1154 1247//1247 1248//1248 -f 1154//1154 1248//1248 1156//1156 -f 1156//1156 1248//1248 1249//1249 -f 1156//1156 1249//1249 1250//1250 -f 1237//1237 1084//1084 1228//1228 -f 1228//1228 1084//1084 1086//1086 -f 1228//1228 1086//1086 1224//1224 -f 1224//1224 1086//1086 1134//1134 -f 1224//1224 1134//1134 1225//1225 -f 1225//1225 1134//1134 1156//1156 -f 1225//1225 1156//1156 1238//1238 -f 1238//1238 1156//1156 1250//1250 -f 1017//1017 1141//1141 1140//1140 -f 1017//1017 1140//1140 1016//1016 -f 1016//1016 1140//1140 1138//1138 -f 1016//1016 1138//1138 1015//1015 -f 1015//1015 1138//1138 1137//1137 -f 1015//1015 1137//1137 1014//1014 -f 1014//1014 1137//1137 1085//1085 -f 1014//1014 1085//1085 1013//1013 -f 1013//1013 1085//1085 1084//1084 -f 1013//1013 1084//1084 1010//1010 -f 1088//1088 1005//1005 1234//1234 -f 1234//1234 1005//1005 926//926 -f 1234//1234 926//926 1235//1235 -f 1235//1235 926//926 928//928 -f 1235//1235 928//928 1236//1236 -f 1236//1236 928//928 1012//1012 -f 1007//1007 1090//1090 1092//1092 -f 1007//1007 1092//1092 997//997 -f 997//997 1092//1092 1165//1165 -f 997//997 1165//1165 995//995 -f 995//995 1165//1165 1164//1164 -f 995//995 1164//1164 993//993 -f 993//993 1164//1164 1081//1081 -f 993//993 1081//1081 989//989 -f 989//989 1081//1081 1083//1083 -f 989//989 1083//1083 990//990 -f 1199//1199 1080//1080 1079//1079 -f 1199//1199 1079//1079 1200//1200 -f 1200//1200 1079//1079 1078//1078 -f 1200//1200 1078//1078 1201//1201 -f 1201//1201 1078//1078 1202//1202 -f 1202//1202 1078//1078 1077//1077 -f 1202//1202 1077//1077 1203//1203 -f 1203//1203 1077//1077 1076//1076 -f 1203//1203 1076//1076 1204//1204 -f 985//985 1094//1094 1074//1074 -f 1074//1074 1094//1094 1204//1204 -f 1074//1074 1204//1204 1075//1075 -f 1075//1075 1204//1204 1076//1076 -f 982//982 1097//1097 1104//1104 -f 982//982 1104//1104 973//973 -f 973//973 1104//1104 1102//1102 -f 973//973 1102//1102 975//975 -f 975//975 1102//1102 1100//1100 -f 975//975 1100//1100 976//976 -f 976//976 1100//1100 1198//1198 -f 976//976 1198//1198 913//913 -f 913//913 1198//1198 1110//1110 -f 913//913 1110//1110 914//914 -f 970//970 1107//1107 936//936 -f 936//936 1107//1107 1106//1106 -f 936//936 1106//1106 942//942 -f 942//942 1106//1106 1116//1116 -f 942//942 1116//1116 963//963 -f 963//963 1116//1116 1115//1115 -f 955//955 1112//1112 1111//1111 -f 955//955 1111//1111 956//956 -f 956//956 1111//1111 1121//1121 -f 956//956 1121//1121 957//957 -f 957//957 1121//1121 1127//1127 -f 957//957 1127//1127 958//958 -f 958//958 1127//1127 1126//1126 -f 958//958 1126//1126 959//959 -f 959//959 1126//1126 1124//1124 -f 959//959 1124//1124 960//960 -f 954//954 1145//1145 953//953 -f 953//953 1145//1145 1143//1143 -f 953//953 1143//1143 1054//1054 -f 1054//1054 1143//1143 1142//1142 -f 1054//1054 1142//1142 1053//1053 -f 1053//1053 1142//1142 1152//1152 -f 1053//1053 1152//1152 1050//1050 -f 1050//1050 1152//1152 1149//1149 -f 1050//1050 1149//1149 1049//1049 -f 1049//1049 1149//1149 1132//1132 -f 1049//1049 1132//1132 1009//1009 -f 1009//1009 1132//1132 1131//1131 -f 1009//1009 1131//1131 1019//1019 -f 1068//1068 1238//1238 1069//1069 -f 1069//1069 1238//1238 1250//1250 -f 1069//1069 1250//1250 1061//1061 -f 1061//1061 1250//1250 1249//1249 -f 1061//1061 1249//1249 1056//1056 -f 1056//1056 1249//1249 1248//1248 -f 1056//1056 1248//1248 1057//1057 -f 1057//1057 1248//1248 1247//1247 -f 1057//1057 1247//1247 1062//1062 -f 1062//1062 1247//1247 1241//1241 -f 1062//1062 1241//1241 1063//1063 -f 1063//1063 1241//1241 1240//1240 -f 1063//1063 1240//1240 1065//1065 -f 1065//1065 1240//1240 1246//1246 -f 1065//1065 1246//1246 1066//1066 -f 1066//1066 1246//1246 1245//1245 -f 1066//1066 1245//1245 1058//1058 -f 1058//1058 1245//1245 1244//1244 -f 1058//1058 1244//1244 1059//1059 -f 1059//1059 1244//1244 1242//1242 -f 1059//1059 1242//1242 1067//1067 -f 1067//1067 1242//1242 1239//1239 -f 1067//1067 1239//1239 1068//1068 -f 1068//1068 1239//1239 1238//1238 -f 948//948 1207//1207 938//938 -f 938//938 1207//1207 1210//1210 -f 938//938 1210//1210 939//939 -f 939//939 1210//1210 1209//1209 -f 939//939 1209//1209 941//941 -f 941//941 1209//1209 1213//1213 -f 941//941 1213//1213 943//943 -f 943//943 1213//1213 1212//1212 -f 943//943 1212//1212 944//944 -f 944//944 1212//1212 1211//1211 -f 944//944 1211//1211 945//945 -f 945//945 1211//1211 1206//1206 -f 945//945 1206//1206 934//934 -f 934//934 1206//1206 1205//1205 -f 934//934 1205//1205 935//935 -f 935//935 1205//1205 1216//1216 -f 935//935 1216//1216 949//949 -f 949//949 1216//1216 1215//1215 -f 949//949 1215//1215 950//950 -f 950//950 1215//1215 1214//1214 -f 950//950 1214//1214 951//951 -f 951//951 1214//1214 1208//1208 -f 951//951 1208//1208 948//948 -f 948//948 1208//1208 1207//1207 -f 1024//1024 1175//1175 1026//1026 -f 1026//1026 1175//1175 1177//1177 -f 1026//1026 1177//1177 1027//1027 -f 1027//1027 1177//1177 1178//1178 -f 1027//1027 1178//1178 1020//1020 -f 1020//1020 1178//1178 1185//1185 -f 1020//1020 1185//1185 1021//1021 -f 1021//1021 1185//1185 1186//1186 -f 1021//1021 1186//1186 1028//1028 -f 1028//1028 1186//1186 1189//1189 -f 1028//1028 1189//1189 1029//1029 -f 1029//1029 1189//1189 1188//1188 -f 1029//1029 1188//1188 1031//1031 -f 1031//1031 1188//1188 1187//1187 -f 1031//1031 1187//1187 1033//1033 -f 1033//1033 1187//1187 1184//1184 -f 1033//1033 1184//1184 1035//1035 -f 1035//1035 1184//1184 1183//1183 -f 1035//1035 1183//1183 1037//1037 -f 1037//1037 1183//1183 1182//1182 -f 1037//1037 1182//1182 1038//1038 -f 1038//1038 1182//1182 1181//1181 -f 1038//1038 1181//1181 1024//1024 -f 1024//1024 1181//1181 1175//1175 -f 929//929 1232//1232 930//930 -f 930//930 1232//1232 1231//1231 -f 930//930 1231//1231 931//931 -f 931//931 1231//1231 1230//1230 -f 931//931 1230//1230 933//933 -f 933//933 1230//1230 1229//1229 -f 933//933 1229//1229 916//916 -f 916//916 1229//1229 1227//1227 -f 916//916 1227//1227 917//917 -f 917//917 1227//1227 1226//1226 -f 917//917 1226//1226 919//919 -f 919//919 1226//1226 1223//1223 -f 919//919 1223//1223 921//921 -f 921//921 1223//1223 1222//1222 -f 921//921 1222//1222 922//922 -f 922//922 1222//1222 1221//1221 -f 922//922 1221//1221 924//924 -f 924//924 1221//1221 1220//1220 -f 924//924 1220//1220 925//925 -f 925//925 1220//1220 1219//1219 -f 925//925 1219//1219 927//927 -f 927//927 1219//1219 1233//1233 -f 927//927 1233//1233 929//929 -f 929//929 1233//1233 1232//1232 -f 1019//1019 1131//1131 1129//1129 -f 1019//1019 1129//1129 1018//1018 -f 1018//1018 1129//1129 1141//1141 -f 1018//1018 1141//1141 1017//1017 -f 960//960 1124//1124 1146//1146 -f 960//960 1146//1146 961//961 -f 961//961 1146//1146 1145//1145 -f 961//961 1145//1145 954//954 -f 1005//1005 1088//1088 1087//1087 -f 1005//1005 1087//1087 1006//1006 -f 1006//1006 1087//1087 1090//1090 -f 1006//1006 1090//1090 1007//1007 -f 1010//1010 1084//1084 1237//1237 -f 1010//1010 1237//1237 1011//1011 -f 1011//1011 1237//1237 1236//1236 -f 1011//1011 1236//1236 1012//1012 -f 990//990 1083//1083 1095//1095 -f 990//990 1095//1095 984//984 -f 984//984 1095//1095 1094//1094 -f 984//984 1094//1094 985//985 -f 1080//1080 1199//1199 1098//1098 -f 1080//1080 1098//1098 983//983 -f 983//983 1098//1098 1097//1097 -f 983//983 1097//1097 982//982 -f 914//914 1110//1110 1109//1109 -f 914//914 1109//1109 971//971 -f 971//971 1109//1109 1107//1107 -f 971//971 1107//1107 970//970 -f 963//963 1115//1115 1114//1114 -f 963//963 1114//1114 962//962 -f 962//962 1114//1114 1112//1112 -f 962//962 1112//1112 955//955 -f 1251//1251 1046//1046 1252//1252 -f 1252//1252 1046//1046 1030//1030 -f 1252//1252 1030//1030 1253//1253 -f 1253//1253 1030//1030 1032//1032 -f 1253//1253 1032//1032 1254//1254 -f 1254//1254 1032//1032 1034//1034 -f 1254//1254 1034//1034 1255//1255 -f 1255//1255 1034//1034 1036//1036 -f 1255//1255 1036//1036 1256//1256 -f 1256//1256 1036//1036 1023//1023 -f 1256//1256 1023//1023 1257//1257 -f 1257//1257 1023//1023 1070//1070 -f 1257//1257 1070//1070 1258//1258 -f 1258//1258 1070//1070 1041//1041 -f 1258//1258 1041//1041 1259//1259 -f 1259//1259 1041//1041 1043//1043 -f 1259//1259 1043//1043 1260//1260 -f 1260//1260 1043//1043 1044//1044 -f 1260//1260 1044//1044 1261//1261 -f 1261//1261 1044//1044 1071//1071 -f 1261//1261 1071//1071 1262//1262 -f 1262//1262 1071//1071 1047//1047 -f 1262//1262 1047//1047 1251//1251 -f 1251//1251 1047//1047 1046//1046 -f 1263//1263 1003//1003 1264//1264 -f 1264//1264 1003//1003 1001//1001 -f 1264//1264 1001//1001 1265//1265 -f 1265//1265 1001//1001 1000//1000 -f 1265//1265 1000//1000 1266//1266 -f 1266//1266 1000//1000 999//999 -f 1266//1266 999//999 1267//1267 -f 1267//1267 999//999 998//998 -f 1267//1267 998//998 1268//1268 -f 1268//1268 998//998 996//996 -f 1268//1268 996//996 1269//1269 -f 1269//1269 996//996 994//994 -f 1269//1269 994//994 1270//1270 -f 1270//1270 994//994 992//992 -f 1270//1270 992//992 1271//1271 -f 1271//1271 992//992 991//991 -f 1271//1271 991//991 1272//1272 -f 1272//1272 991//991 988//988 -f 1272//1272 988//988 1273//1273 -f 1273//1273 988//988 987//987 -f 1273//1273 987//987 1274//1274 -f 1274//1274 987//987 1004//1004 -f 1274//1274 1004//1004 1263//1263 -f 1263//1263 1004//1004 1003//1003 -f 1275//1275 974//974 1276//1276 -f 1276//1276 974//974 915//915 -f 1276//1276 915//915 1277//1277 -f 1277//1277 915//915 969//969 -f 1277//1277 969//969 1278//1278 -f 1278//1278 969//969 968//968 -f 1278//1278 968//968 1279//1279 -f 1279//1279 968//968 967//967 -f 1279//1279 967//967 1280//1280 -f 1280//1280 967//967 966//966 -f 1280//1280 966//966 1281//1281 -f 1281//1281 966//966 965//965 -f 1281//1281 965//965 1282//1282 -f 1282//1282 965//965 981//981 -f 1282//1282 981//981 1283//1283 -f 1283//1283 981//981 980//980 -f 1283//1283 980//980 1284//1284 -f 1284//1284 980//980 978//978 -f 1284//1284 978//978 1285//1285 -f 1285//1285 978//978 977//977 -f 1285//1285 977//977 1286//1286 -f 1286//1286 977//977 972//972 -f 1286//1286 972//972 1275//1275 -f 1275//1275 972//972 974//974 -f 1282//1282 1283//1283 1287//1287 -f 1287//1287 1283//1283 1288//1288 -f 1289//1289 1280//1280 1287//1287 -f 1287//1287 1280//1280 1281//1281 -f 1287//1287 1281//1281 1282//1282 -f 1283//1283 1284//1284 1288//1288 -f 1288//1288 1284//1284 1285//1285 -f 1288//1288 1285//1285 1290//1290 -f 1285//1285 1286//1286 1290//1290 -f 1290//1290 1286//1286 1275//1275 -f 1290//1290 1275//1275 1291//1291 -f 1275//1275 1276//1276 1291//1291 -f 1291//1291 1276//1276 1277//1277 -f 1291//1291 1277//1277 1292//1292 -f 1292//1292 1277//1277 1278//1278 -f 1292//1292 1278//1278 1289//1289 -f 1289//1289 1278//1278 1279//1279 -f 1289//1289 1279//1279 1280//1280 -f 1292//1292 1289//1289 1197//1197 -f 1197//1197 1289//1289 1196//1196 -f 1287//1287 1192//1192 1289//1289 -f 1289//1289 1192//1192 1191//1191 -f 1289//1289 1191//1191 1196//1196 -f 1287//1287 1288//1288 1192//1192 -f 1192//1192 1288//1288 1105//1105 -f 1288//1288 1290//1290 1105//1105 -f 1105//1105 1290//1290 1103//1103 -f 1291//1291 1099//1099 1290//1290 -f 1290//1290 1099//1099 1101//1101 -f 1290//1290 1101//1101 1103//1103 -f 1291//1291 1292//1292 1099//1099 -f 1099//1099 1292//1292 1197//1197 -f 1268//1268 1269//1269 1293//1293 -f 1293//1293 1269//1269 1294//1294 -f 1273//1273 1295//1295 1272//1272 -f 1272//1272 1295//1295 1296//1296 -f 1272//1272 1296//1296 1271//1271 -f 1271//1271 1296//1296 1294//1294 -f 1271//1271 1294//1294 1270//1270 -f 1270//1270 1294//1294 1269//1269 -f 1273//1273 1274//1274 1295//1295 -f 1295//1295 1274//1274 1263//1263 -f 1295//1295 1263//1263 1297//1297 -f 1263//1263 1264//1264 1297//1297 -f 1297//1297 1264//1264 1265//1265 -f 1297//1297 1265//1265 1298//1298 -f 1298//1298 1265//1265 1266//1266 -f 1298//1298 1266//1266 1293//1293 -f 1293//1293 1266//1266 1267//1267 -f 1293//1293 1267//1267 1268//1268 -f 1294//1294 1162//1162 1293//1293 -f 1293//1293 1162//1162 1163//1163 -f 1293//1293 1163//1163 1091//1091 -f 1294//1294 1296//1296 1162//1162 -f 1162//1162 1296//1296 1161//1161 -f 1296//1296 1295//1295 1161//1161 -f 1161//1161 1295//1295 1157//1157 -f 1297//1297 1160//1160 1295//1295 -f 1295//1295 1160//1160 1158//1158 -f 1295//1295 1158//1158 1157//1157 -f 1297//1297 1298//1298 1160//1160 -f 1160//1160 1298//1298 1180//1180 -f 1298//1298 1293//1293 1180//1180 -f 1180//1180 1293//1293 1091//1091 -f 903//903 905//905 1299//1299 -f 1299//1299 905//905 1300//1300 -f 889//889 1301//1301 911//911 -f 911//911 1301//1301 1302//1302 -f 911//911 1302//1302 909//909 -f 909//909 1302//1302 1300//1300 -f 909//909 1300//1300 907//907 -f 907//907 1300//1300 905//905 -f 889//889 891//891 1301//1301 -f 1301//1301 891//891 893//893 -f 1301//1301 893//893 1303//1303 -f 1303//1303 893//893 895//895 -f 1303//1303 895//895 1304//1304 -f 895//895 897//897 1304//1304 -f 1304//1304 897//897 899//899 -f 1304//1304 899//899 1299//1299 -f 1299//1299 899//899 901//901 -f 1299//1299 901//901 903//903 -f 1303//1303 1304//1304 1128//1128 -f 1128//1128 1304//1304 1139//1139 -f 1304//1304 1299//1299 1139//1139 -f 1139//1139 1299//1299 1136//1136 -f 1299//1299 1300//1300 1136//1136 -f 1136//1136 1300//1300 1135//1135 -f 1300//1300 1302//1302 1135//1135 -f 1135//1135 1302//1302 1133//1133 -f 1302//1302 1301//1301 1133//1133 -f 1133//1133 1301//1301 1130//1130 -f 1301//1301 1303//1303 1130//1130 -f 1130//1130 1303//1303 1128//1128 -f 877//877 879//879 1305//1305 -f 1305//1305 879//879 881//881 -f 1305//1305 881//881 1306//1306 -f 881//881 883//883 1306//1306 -f 1306//1306 883//883 885//885 -f 1306//1306 885//885 1307//1307 -f 1307//1307 885//885 887//887 -f 1307//1307 887//887 1308//1308 -f 877//877 1305//1305 875//875 -f 875//875 1305//1305 1309//1309 -f 875//875 1309//1309 873//873 -f 873//873 1309//1309 1310//1310 -f 873//873 1310//1310 871//871 -f 887//887 865//865 1308//1308 -f 1308//1308 865//865 867//867 -f 1308//1308 867//867 1310//1310 -f 1310//1310 867//867 869//869 -f 1310//1310 869//869 871//871 -f 1309//1309 1305//1305 1144//1144 -f 1144//1144 1305//1305 1118//1118 -f 1305//1305 1306//1306 1118//1118 -f 1118//1118 1306//1306 1120//1120 -f 1306//1306 1307//1307 1120//1120 -f 1120//1120 1307//1307 1122//1122 -f 1307//1307 1308//1308 1122//1122 -f 1122//1122 1308//1308 1125//1125 -f 1308//1308 1310//1310 1125//1125 -f 1125//1125 1310//1310 1123//1123 -f 1310//1310 1309//1309 1123//1123 -f 1123//1123 1309//1309 1144//1144 -f 863//863 841//841 1311//1311 -f 1312//1312 853//853 1313//1313 -f 1313//1313 853//853 855//855 -f 1313//1313 855//855 1314//1314 -f 1311//1311 841//841 1315//1315 -f 855//855 857//857 1314//1314 -f 1314//1314 857//857 859//859 -f 1314//1314 859//859 1311//1311 -f 1311//1311 859//859 861//861 -f 1311//1311 861//861 863//863 -f 841//841 843//843 1315//1315 -f 1315//1315 843//843 845//845 -f 1315//1315 845//845 1316//1316 -f 845//845 847//847 1316//1316 -f 1316//1316 847//847 849//849 -f 1316//1316 849//849 1312//1312 -f 1312//1312 849//849 851//851 -f 1312//1312 851//851 853//853 -f 1313//1313 1314//1314 1147//1147 -f 1147//1147 1314//1314 1155//1155 -f 1314//1314 1311//1311 1155//1155 -f 1155//1155 1311//1311 1153//1153 -f 1311//1311 1315//1315 1153//1153 -f 1153//1153 1315//1315 1151//1151 -f 1315//1315 1316//1316 1151//1151 -f 1151//1151 1316//1316 1150//1150 -f 1316//1316 1312//1312 1150//1150 -f 1150//1150 1312//1312 1148//1148 -f 1312//1312 1313//1313 1148//1148 -f 1148//1148 1313//1313 1147//1147 -f 1258//1258 1259//1259 1317//1317 -f 1317//1317 1259//1259 1318//1318 -f 1251//1251 1319//1319 1262//1262 -f 1262//1262 1319//1319 1320//1320 -f 1262//1262 1320//1320 1261//1261 -f 1261//1261 1320//1320 1318//1318 -f 1261//1261 1318//1318 1260//1260 -f 1260//1260 1318//1318 1259//1259 -f 1251//1251 1252//1252 1319//1319 -f 1319//1319 1252//1252 1253//1253 -f 1319//1319 1253//1253 1321//1321 -f 1253//1253 1254//1254 1321//1321 -f 1321//1321 1254//1254 1255//1255 -f 1321//1321 1255//1255 1322//1322 -f 1322//1322 1255//1255 1256//1256 -f 1322//1322 1256//1256 1317//1317 -f 1317//1317 1256//1256 1257//1257 -f 1317//1317 1257//1257 1258//1258 -f 1319//1319 1321//1321 1173//1173 -f 1173//1173 1321//1321 1174//1174 -f 1321//1321 1322//1322 1174//1174 -f 1174//1174 1322//1322 1166//1166 -f 1166//1166 1322//1322 1167//1167 -f 1167//1167 1322//1322 1317//1317 -f 1167//1167 1317//1317 1168//1168 -f 1317//1317 1318//1318 1168//1168 -f 1168//1168 1318//1318 1170//1170 -f 1318//1318 1320//1320 1170//1170 -f 1170//1170 1320//1320 1193//1193 -f 1193//1193 1320//1320 1243//1243 -f 1243//1243 1320//1320 1319//1319 -f 1243//1243 1319//1319 1173//1173 -# 2752 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower_motor.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower_motor.obj deleted file mode 100644 index e1e17fde7..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower_motor.obj +++ /dev/null @@ -1,9620 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mid_lower_motor.obj -# -# Vertices: 2376 -# Faces: 4852 -# -#### -vn 0.642870 -0.726791 -0.241854 -v 0.093753 0.087999 0.096000 -vn 0.897350 -0.438409 0.050598 -v 0.093753 0.087766 0.096314 -vn 0.660283 -0.751017 0.000000 -v 0.093753 0.087499 0.096000 -vn 0.897348 -0.418314 0.140641 -v 0.093753 0.087896 0.096927 -vn 0.640667 -0.562882 0.522217 -v 0.093753 0.088232 0.097107 -vn 0.660283 -0.676643 0.325854 -v 0.093753 0.087821 0.097410 -vn 0.642880 -0.762322 0.074629 -v 0.093753 0.088237 0.097119 -vn 0.897349 -0.324946 0.298622 -v 0.093753 0.088520 0.098007 -vn 0.640646 -0.301904 0.705993 -v 0.093753 0.088899 0.098035 -vn 0.642900 -0.666095 0.378150 -v 0.093753 0.088909 0.098044 -vn 0.640664 -0.442020 0.627828 -v 0.093753 0.088517 0.097606 -vn 0.642882 -0.730152 0.231476 -v 0.093753 0.088524 0.097616 -vn 0.897347 -0.379934 0.224541 -v 0.093753 0.088151 0.097500 -vn 0.660283 -0.468251 0.587169 -v 0.093753 0.088723 0.098541 -vn 0.642868 -0.306594 -0.701941 -v 0.093753 0.088909 0.093956 -vn 0.897349 -0.330954 -0.291950 -v 0.093753 0.088520 0.093993 -vn 0.660283 -0.468250 -0.587170 -v 0.093753 0.088723 0.093459 -vn 0.642888 -0.565523 -0.516603 -v 0.093753 0.088237 0.094881 -vn 0.897349 -0.421089 -0.132097 -v 0.093753 0.087896 0.095073 -vn 0.660283 -0.676643 -0.325855 -v 0.093753 0.087821 0.094590 -vn 0.640672 -0.659133 0.393805 -v 0.093753 0.088057 0.096559 -vn 0.642873 -0.761190 -0.085469 -v 0.093753 0.088059 0.096572 -vn 0.897350 -0.175389 0.404971 -v 0.093753 0.089529 0.098741 -vn 0.640627 0.011275 0.767769 -v 0.093753 0.089887 0.098611 -vn 0.642920 -0.454747 0.616327 -v 0.093753 0.089899 0.098615 -vn 0.640642 -0.148539 0.753335 -v 0.093753 0.089363 0.098375 -vn 0.642904 -0.572926 0.508360 -v 0.093753 0.089374 0.098382 -vn 0.897350 -0.255756 0.359656 -v 0.093753 0.088986 0.098427 -vn 0.660283 -0.167116 0.732187 -v 0.093753 0.090026 0.099169 -vn 0.642898 0.005542 -0.765932 -v 0.093753 0.089899 0.093385 -vn 0.897349 -0.183598 -0.401319 -v 0.093753 0.089529 0.093259 -vn 0.660284 -0.167116 -0.732187 -v 0.093753 0.090026 0.092831 -vn 0.640698 -0.733710 -0.226219 -v 0.093753 0.088532 0.094373 -vn 0.642847 -0.445919 -0.622819 -v 0.093753 0.088524 0.094384 -vn 0.897348 -0.384422 -0.216762 -v 0.093753 0.088151 0.094500 -vn 0.640659 -0.764727 -0.068909 -v 0.093753 0.088242 0.094870 -vn 0.640666 -0.762333 0.091627 -v 0.093753 0.088062 0.095416 -vn 0.642880 -0.660594 -0.387714 -v 0.093753 0.088059 0.095428 -vn 0.897350 -0.439348 -0.041663 -v 0.093753 0.087766 0.095686 -vn 0.640676 -0.726602 0.248162 -v 0.093753 0.087999 0.095987 -vn 0.640647 0.170735 0.748612 -v 0.093753 0.090449 0.098734 -vn 0.642899 -0.316601 0.697456 -v 0.093753 0.090462 0.098735 -vn 0.897347 -0.087355 0.432594 -v 0.093753 0.090125 0.098934 -vn 0.897347 0.004491 0.441302 -v 0.093753 0.090749 0.099000 -vn 0.640657 0.322679 0.696733 -v 0.093753 0.091024 0.098736 -vn 0.642891 -0.164635 0.748055 -v 0.093753 0.091037 0.098735 -vn 0.897346 0.096145 0.430727 -v 0.093753 0.091373 0.098934 -vn 0.660284 0.167116 0.732186 -v 0.093753 0.091472 0.099169 -vn 0.640650 0.460463 0.614444 -v 0.093753 0.091587 0.098619 -vn 0.897347 -0.004491 -0.441302 -v 0.093753 0.090749 0.093000 -vn 0.660283 0.167116 -0.732187 -v 0.093753 0.091472 0.092831 -vn 0.642898 -0.005542 0.765932 -v 0.093753 0.091599 0.098615 -vn 0.897349 0.183598 0.401319 -v 0.093753 0.091969 0.098741 -vn 0.660283 0.468252 0.587168 -v 0.093753 0.092776 0.098541 -vn 0.640662 -0.578188 -0.505223 -v 0.093753 0.089385 0.093612 -vn 0.642884 -0.153890 -0.750345 -v 0.093753 0.089374 0.093618 -vn 0.897347 -0.263026 -0.354380 -v 0.093753 0.088986 0.093573 -vn 0.640678 -0.670614 -0.373910 -v 0.093753 0.088919 0.093948 -vn 0.897348 0.175394 -0.404973 -v 0.093753 0.091969 0.093259 -vn 0.660283 0.468251 -0.587169 -v 0.093753 0.092776 0.093459 -vn 0.897347 0.087355 -0.432594 -v 0.093753 0.091373 0.093066 -vn 0.640647 -0.170735 -0.748612 -v 0.093753 0.091049 0.093266 -vn 0.642899 0.316601 -0.697456 -v 0.093753 0.091037 0.093265 -vn 0.640657 -0.322679 -0.696733 -v 0.093753 0.090475 0.093264 -vn 0.642891 0.164635 -0.748055 -v 0.093753 0.090462 0.093265 -vn 0.897346 -0.096145 -0.430727 -v 0.093753 0.090125 0.093066 -vn 0.640650 -0.460463 -0.614444 -v 0.093753 0.089912 0.093381 -vn 0.640662 0.578188 0.505223 -v 0.093753 0.092113 0.098388 -vn 0.642884 0.153890 0.750345 -v 0.093753 0.092124 0.098382 -vn 0.897347 0.263026 0.354380 -v 0.093753 0.092513 0.098427 -vn 0.640678 0.670614 0.373910 -v 0.093753 0.092580 0.098052 -vn 0.642869 0.306600 0.701937 -v 0.093753 0.092589 0.098044 -vn 0.897347 0.330960 0.291950 -v 0.093753 0.092979 0.098007 -vn 0.660284 0.676642 0.325854 -v 0.093753 0.093677 0.097410 -vn 0.642841 0.565686 0.516484 -v 0.093753 0.093261 0.097119 -vn 0.897350 0.421086 0.132098 -v 0.093753 0.093602 0.096927 -vn 0.660282 0.751018 0.000000 -v 0.093753 0.093999 0.096000 -vn 0.897347 0.255762 -0.359657 -v 0.093753 0.092513 0.093573 -vn 0.640687 0.148351 -0.753334 -v 0.093753 0.092135 0.093625 -vn 0.642860 0.572827 -0.508527 -v 0.093753 0.092124 0.093618 -vn 0.642872 0.454602 -0.616484 -v 0.093753 0.091599 0.093385 -vn 0.640677 -0.011477 -0.767725 -v 0.093753 0.091611 0.093389 -vn 0.640669 0.733695 0.226351 -v 0.093753 0.092966 0.097627 -vn 0.642879 0.445803 0.622870 -v 0.093753 0.092974 0.097616 -vn 0.897347 0.384427 0.216759 -v 0.093753 0.093347 0.097500 -vn 0.640704 0.764708 0.068703 -v 0.093753 0.093256 0.097130 -vn 0.642872 0.726791 0.241848 -v 0.093753 0.093499 0.096000 -vn 0.897345 0.438420 -0.050596 -v 0.093753 0.093733 0.095686 -vn 0.642862 0.666042 -0.378308 -v 0.093753 0.092589 0.093956 -vn 0.897349 0.324945 -0.298622 -v 0.093753 0.092979 0.093993 -vn 0.640684 0.301741 -0.706029 -v 0.093753 0.092599 0.093965 -vn 0.640666 0.762333 -0.091627 -v 0.093753 0.093436 0.096584 -vn 0.642881 0.660595 0.387709 -v 0.093753 0.093439 0.096572 -vn 0.897345 0.439358 0.041667 -v 0.093753 0.093733 0.096314 -vn 0.640678 0.726604 -0.248151 -v 0.093753 0.093499 0.096013 -vn 0.897348 0.418314 -0.140641 -v 0.093753 0.093602 0.095073 -vn 0.640713 0.562716 -0.522339 -v 0.093753 0.093267 0.094893 -vn 0.660283 0.676642 -0.325855 -v 0.093753 0.093677 0.094590 -vn 0.642832 0.762343 -0.074829 -v 0.093753 0.093261 0.094881 -vn 0.897351 0.379927 -0.224538 -v 0.093753 0.093347 0.094500 -vn 0.640663 0.442015 -0.627833 -v 0.093753 0.092982 0.094394 -vn 0.642882 0.730152 -0.231476 -v 0.093753 0.092974 0.094384 -vn 0.640685 0.659106 -0.393830 -v 0.093753 0.093442 0.095441 -vn 0.642862 0.761204 0.085425 -v 0.093753 0.093439 0.095428 -vn 0.760788 -0.144416 0.632728 -v 0.090753 0.089970 0.099412 -vn 0.665719 0.285560 -0.689401 -v 0.090753 0.089027 0.100157 -vn 0.760789 -0.404644 0.507408 -v 0.090753 0.088567 0.098736 -vn 0.665719 0.527644 -0.527646 -v 0.090753 0.087567 0.099182 -vn 0.760788 -0.584729 0.281590 -v 0.090753 0.087596 0.097519 -vn 0.665719 0.689401 -0.285560 -v 0.090753 0.086592 0.097722 -vn 0.760789 -0.649000 0.000000 -v 0.090753 0.087249 0.096000 -vn 0.665719 0.746202 0.000000 -v 0.090753 0.086249 0.096000 -vn 0.760788 -0.584729 -0.281590 -v 0.090753 0.087596 0.094481 -vn 0.665719 0.689401 0.285560 -v 0.090753 0.086592 0.094278 -vn 0.760789 -0.404644 -0.507408 -v 0.090753 0.088567 0.093264 -vn 0.665719 0.527645 0.527645 -v 0.090753 0.087567 0.092818 -vn 0.760788 -0.144416 -0.632728 -v 0.090753 0.089970 0.092588 -vn 0.665719 0.285560 0.689401 -v 0.090753 0.089027 0.091843 -vn 0.665719 0.000000 0.746202 -v 0.090753 0.090749 0.091500 -vn 0.760788 0.144416 -0.632728 -v 0.090753 0.091528 0.092588 -vn 0.665719 -0.285560 0.689401 -v 0.090753 0.092471 0.091843 -vn 0.760789 0.404644 -0.507408 -v 0.090753 0.092931 0.093264 -vn 0.665719 -0.527646 0.527644 -v 0.090753 0.093931 0.092818 -vn 0.760788 0.584729 -0.281590 -v 0.090753 0.093903 0.094481 -vn 0.665719 -0.689401 0.285560 -v 0.090753 0.094907 0.094278 -vn 0.760789 0.649000 0.000000 -v 0.090753 0.094249 0.096000 -vn 0.665718 -0.746203 0.000000 -v 0.090753 0.095249 0.096000 -vn 0.760788 0.584729 0.281590 -v 0.090753 0.093903 0.097519 -vn 0.665719 -0.689401 -0.285560 -v 0.090753 0.094907 0.097722 -vn 0.760789 0.404644 0.507408 -v 0.090753 0.092931 0.098736 -vn 0.665719 -0.527645 -0.527645 -v 0.090753 0.093931 0.099182 -vn 0.760788 0.144416 0.632728 -v 0.090753 0.091528 0.099412 -vn 0.665719 -0.285560 -0.689401 -v 0.090753 0.092471 0.100157 -vn 0.665718 -0.000000 -0.746203 -v 0.090753 0.090749 0.100500 -vn -0.301511 0.904534 -0.301511 -v 0.088003 0.108550 0.078700 -vn -0.301511 0.904534 0.301511 -v 0.088003 0.108550 0.069203 -vn -0.577350 0.577350 -0.577350 -v 0.088003 0.102536 0.078700 -vn -0.577350 0.577350 0.577350 -v 0.088003 0.102536 0.069203 -vn -0.577350 0.577350 0.577350 -v 0.088003 0.102536 0.086700 -vn -0.577350 0.577350 -0.577350 -v 0.088003 0.102536 0.096197 -vn -0.301511 0.904534 0.301511 -v 0.088003 0.108550 0.086700 -vn -0.301511 0.904534 -0.301511 -v 0.088003 0.108550 0.096197 -vn -0.770263 0.000000 0.637726 -v 0.088003 0.105750 0.081350 -vn -0.770260 -0.318865 0.552291 -v 0.088003 0.106425 0.081531 -vn -0.301512 0.904534 0.301511 -v 0.088003 0.108550 0.079700 -vn -0.687523 0.064936 0.723254 -v 0.088003 0.104756 0.079700 -vn -0.669120 0.260539 0.695987 -v 0.088003 0.104405 0.079763 -vn -0.770261 0.318866 0.552288 -v 0.088003 0.105075 0.081531 -vn -0.669125 0.488001 0.560469 -v 0.088003 0.104099 0.079946 -vn -0.770261 0.552288 0.318866 -v 0.088003 0.104581 0.082025 -vn -0.687521 0.605103 0.401455 -v 0.088003 0.103876 0.080224 -vn -0.770263 0.637726 -0.000000 -v 0.088003 0.104400 0.082700 -vn -0.614012 0.789297 0.000000 -v 0.088003 0.102536 0.082700 -vn -0.770260 0.552291 -0.318865 -v 0.088003 0.104581 0.083375 -vn -0.687526 0.605097 -0.401455 -v 0.088003 0.103876 0.085176 -vn -0.770262 0.318863 -0.552288 -v 0.088003 0.105075 0.083869 -vn -0.770263 -0.552286 0.318864 -v 0.088003 0.106919 0.082025 -vn -0.770260 -0.637730 -0.000001 -v 0.088003 0.107100 0.082700 -vn -0.301512 0.904534 -0.301512 -v 0.088003 0.108550 0.085700 -vn -0.770261 -0.552290 -0.318863 -v 0.088003 0.106919 0.083375 -vn -0.770261 -0.318863 -0.552290 -v 0.088003 0.106425 0.083869 -vn -0.687521 0.064936 -0.723255 -v 0.088003 0.104756 0.085700 -vn -0.770259 -0.000000 -0.637731 -v 0.088003 0.105750 0.084050 -vn -0.669121 0.260533 -0.695989 -v 0.088003 0.104405 0.085637 -vn -0.669119 0.488000 -0.560479 -v 0.088003 0.104099 0.085454 -vn 0.301511 0.904534 -0.301511 -v 0.076103 0.102536 0.067000 -vn 0.904534 0.301511 0.301511 -v 0.076103 0.102536 0.069600 -vn -0.301517 0.904531 0.301516 -v 0.085103 0.102536 0.069600 -vn -0.301512 0.904534 -0.301511 -v 0.085703 0.102536 0.096197 -vn 0.301511 0.904534 -0.301511 -v 0.074103 0.102536 0.078200 -vn 0.301511 0.904534 0.301511 -v 0.074103 0.102536 0.079200 -vn -0.301514 0.904533 0.301513 -v 0.085703 0.102536 0.069203 -vn -0.301518 0.904532 -0.301511 -v 0.085103 0.102536 0.074600 -vn -0.301518 0.904532 -0.301511 -v 0.085703 0.102536 0.078700 -vn -0.165770 0.986165 -0.000000 -v 0.085703 0.102536 0.082700 -vn -0.301512 0.904534 0.301510 -v 0.085703 0.102536 0.086700 -vn 0.904534 0.301511 -0.301511 -v 0.076103 0.102536 0.074600 -vn 0.301511 0.904534 0.301511 -v 0.076103 0.102536 0.077200 -vn -0.707107 0.683011 -0.183016 -v 0.085703 0.102536 0.065000 -vn 0.289898 0.849937 -0.439962 -v 0.074103 0.102536 0.065000 -vn -0.178904 0.983867 -0.000000 -v 0.085703 0.102536 0.065700 -vn 0.301511 0.904534 0.301511 -v 0.074103 0.102536 0.066000 -vn 0.577350 0.577350 0.577350 -v 0.071103 0.102536 0.066000 -vn 0.577350 0.577350 -0.577350 -v 0.071103 0.102536 0.067000 -vn 0.301511 0.904534 0.301512 -v 0.064303 0.102536 0.086700 -vn -0.737701 0.669352 0.088123 -v 0.088003 0.102536 0.106000 -vn -0.301512 0.904534 0.301512 -v 0.085703 0.102536 0.103200 -vn -0.577350 0.577350 0.577350 -v 0.088003 0.102536 0.103200 -vn 0.577350 0.577350 0.577350 -v 0.062003 0.102536 0.103200 -vn 0.737701 0.669352 0.088123 -v 0.062003 0.102536 0.106000 -vn 0.301511 0.904534 0.301511 -v 0.064303 0.102536 0.103200 -vn 0.577350 0.577350 0.577350 -v 0.071103 0.102536 0.077200 -vn 0.577350 0.577350 -0.577350 -v 0.071103 0.102536 0.078200 -vn 0.577350 0.577350 0.577350 -v 0.062003 0.102536 0.086700 -vn 0.577350 0.577350 -0.577350 -v 0.062003 0.102536 0.096197 -vn 0.301511 0.904534 -0.301511 -v 0.064303 0.102536 0.096197 -vn 0.178903 0.983867 -0.000000 -v 0.064303 0.102536 0.099700 -vn -0.178904 0.983867 -0.000000 -v 0.085703 0.102536 0.099700 -vn 0.165763 0.986166 0.000000 -v 0.064303 0.102536 0.082700 -vn 0.577350 0.577350 0.577350 -v 0.064303 0.102536 0.079200 -vn -0.770262 -0.318863 0.552289 -v 0.088003 0.106425 0.064531 -vn -0.770262 -0.552289 0.318862 -v 0.088003 0.106919 0.065025 -vn -0.685696 0.724383 -0.071347 -v 0.088003 0.108550 0.063414 -vn -0.770261 -0.637729 0.000000 -v 0.088003 0.107100 0.065700 -vn -0.301511 0.904534 -0.301511 -v 0.088003 0.108550 0.068693 -vn -0.665720 0.689400 -0.285560 -v 0.088003 0.108474 0.063032 -vn -0.490003 0.800288 -0.345596 -v 0.088003 0.108257 0.062707 -vn -0.770261 0.000000 0.637729 -v 0.088003 0.105750 0.064350 -vn -0.679085 0.095070 0.727877 -v 0.088003 0.104868 0.062707 -vn -0.770263 0.318864 0.552286 -v 0.088003 0.105075 0.064531 -vn -0.653609 0.375726 0.656982 -v 0.088003 0.104372 0.062839 -vn -0.770260 0.552290 0.318865 -v 0.088003 0.104581 0.065025 -vn -0.679087 0.579143 0.451038 -v 0.088003 0.104007 0.063200 -vn -0.770263 0.637726 -0.000000 -v 0.088003 0.104400 0.065700 -vn -0.608812 0.793315 -0.000000 -v 0.088003 0.102536 0.065700 -vn -0.770261 0.552288 -0.318866 -v 0.088003 0.104581 0.066375 -vn -0.679088 0.579144 -0.451034 -v 0.088003 0.104007 0.068200 -vn -0.770261 0.318866 -0.552288 -v 0.088003 0.105075 0.066869 -vn -0.653607 0.375726 -0.656985 -v 0.088003 0.104372 0.068561 -vn -0.770263 -0.000000 -0.637726 -v 0.088003 0.105750 0.067050 -vn -0.679087 0.095064 -0.727877 -v 0.088003 0.104868 0.068693 -vn -0.770260 -0.318865 -0.552291 -v 0.088003 0.106425 0.066869 -vn -0.770263 -0.552286 -0.318864 -v 0.088003 0.106919 0.066375 -vn -0.770262 -0.318862 0.552289 -v 0.088003 0.106425 0.098531 -vn -0.301511 0.904534 0.301511 -v 0.088003 0.108550 0.096707 -vn -0.770261 0.000000 0.637729 -v 0.088003 0.105750 0.098350 -vn -0.679087 0.095064 0.727876 -v 0.088003 0.104868 0.096707 -vn -0.770263 0.318864 0.552286 -v 0.088003 0.105075 0.098531 -vn -0.653606 0.375726 0.656985 -v 0.088003 0.104372 0.096839 -vn -0.770260 0.552290 0.318865 -v 0.088003 0.104581 0.099025 -vn -0.679087 0.579145 0.451034 -v 0.088003 0.104007 0.097200 -vn -0.770264 0.637725 -0.000001 -v 0.088003 0.104400 0.099700 -vn -0.608812 0.793315 -0.000000 -v 0.088003 0.102536 0.099700 -vn -0.770260 0.552290 -0.318866 -v 0.088003 0.104581 0.100375 -vn -0.679088 0.579144 -0.451034 -v 0.088003 0.104007 0.102200 -vn -0.770263 0.318864 -0.552286 -v 0.088003 0.105075 0.100869 -vn -0.653606 0.375726 -0.656985 -v 0.088003 0.104372 0.102561 -vn -0.770261 -0.000000 -0.637729 -v 0.088003 0.105750 0.101050 -vn -0.679087 0.095064 -0.727877 -v 0.088003 0.104868 0.102693 -vn -0.770262 -0.318862 -0.552289 -v 0.088003 0.106425 0.100869 -vn -0.770262 -0.552289 0.318862 -v 0.088003 0.106919 0.099025 -vn -0.770261 -0.637729 -0.000001 -v 0.088003 0.107100 0.099700 -vn -0.685696 0.724383 0.071349 -v 0.088003 0.108550 0.101986 -vn -0.770262 -0.552289 -0.318864 -v 0.088003 0.106919 0.100375 -vn -0.665720 0.689400 0.285561 -v 0.088003 0.108474 0.102368 -vn -0.490003 0.800289 0.345593 -v 0.088003 0.108257 0.102693 -vn -0.770262 0.318865 0.552288 -v 0.088003 0.101536 0.107732 -vn -0.041899 0.065065 0.997001 -v 0.088003 0.100536 0.108000 -vn -0.685696 0.071347 0.724383 -v 0.088003 0.102536 0.108000 -vn -0.770262 0.552288 0.318865 -v 0.088003 0.102268 0.107000 -vn -0.665719 0.285564 0.689400 -v 0.088003 0.102918 0.107924 -vn -0.685697 0.461768 0.562662 -v 0.088003 0.103243 0.107707 -vn -0.131339 0.557230 0.819905 -v 0.088003 0.107750 0.103200 -vn -0.770261 0.552290 -0.318865 -v 0.088003 0.102268 0.064000 -vn -0.538122 -0.110018 -0.835656 -v 0.088003 0.102536 0.065000 -vn -0.904534 -0.301512 -0.301512 -v 0.088003 0.102536 0.062200 -vn -0.770260 -0.552290 0.318865 -v 0.088003 0.099995 0.059525 -vn -0.770264 -0.637726 0.000000 -v 0.088003 0.100175 0.060200 -vn -0.685696 0.071347 -0.724383 -v 0.088003 0.102536 0.057400 -vn -0.770263 -0.318864 0.552286 -v 0.088003 0.099500 0.059031 -vn -0.770260 -0.552291 -0.318865 -v 0.088003 0.099995 0.060875 -vn -0.770263 -0.318864 -0.552286 -v 0.088003 0.099500 0.061369 -vn -0.770262 -0.000000 -0.637728 -v 0.088003 0.098825 0.061550 -vn -0.770263 0.318862 -0.552288 -v 0.088003 0.098150 0.061369 -vn -0.770263 0.552288 -0.318862 -v 0.088003 0.097656 0.060875 -vn -0.770262 -0.552289 -0.318863 -v 0.088003 0.084221 0.060875 -vn -0.770263 0.552288 -0.318862 -v 0.088003 0.081883 0.060875 -vn -0.770261 0.637729 0.000000 -v 0.088003 0.081702 0.060200 -vn -0.707107 -0.000000 -0.707107 -v 0.088003 0.079401 0.057400 -vn -0.770261 -0.000000 0.637729 -v 0.088003 0.098825 0.058850 -vn -0.770263 0.318862 0.552288 -v 0.088003 0.098150 0.059031 -vn -0.665719 0.285561 -0.689400 -v 0.088003 0.102918 0.057476 -vn -0.685696 0.461767 -0.562665 -v 0.088003 0.103243 0.057693 -vn -0.131339 0.557229 -0.819906 -v 0.088003 0.107750 0.062200 -vn -0.770261 -0.637729 0.000000 -v 0.088003 0.084402 0.060200 -vn -0.770261 0.637729 0.000000 -v 0.088003 0.097475 0.060200 -vn -0.770262 -0.552289 0.318863 -v 0.088003 0.084221 0.059525 -vn -0.737700 -0.088121 -0.669353 -v 0.088003 0.080964 0.063000 -vn -0.770261 -0.000000 -0.637729 -v 0.088003 0.083052 0.061550 -vn -0.770262 0.318862 -0.552289 -v 0.088003 0.082377 0.061369 -vn -0.770262 0.552289 0.318863 -v 0.088003 0.081883 0.059525 -vn -0.770262 0.318862 0.552289 -v 0.088003 0.082377 0.059031 -vn -0.770260 -0.000000 0.637730 -v 0.088003 0.083052 0.058850 -vn -0.770262 0.552289 0.318863 -v 0.088003 0.097656 0.059525 -vn -0.770261 -0.318863 0.552290 -v 0.088003 0.083727 0.059031 -vn -0.737699 0.088120 -0.669354 -v 0.088003 0.100536 0.063000 -vn -0.770263 0.318863 -0.552287 -v 0.088003 0.101536 0.063268 -vn -0.762539 -0.306261 -0.569858 -v 0.088003 0.079964 0.063268 -vn -0.737708 -0.509597 -0.442830 -v 0.088003 0.079366 0.063797 -vn -0.770262 -0.318863 -0.552289 -v 0.088003 0.083727 0.061369 -vn -0.707106 -0.707107 -0.000000 -v 0.088003 0.072950 0.074200 -vn -0.770261 0.637729 -0.000000 -v 0.088003 0.074400 0.065700 -vn -0.685696 -0.724383 -0.071347 -v 0.088003 0.072950 0.063414 -vn -0.770261 0.552291 0.318861 -v 0.088003 0.074581 0.065025 -vn -0.665721 -0.689401 -0.285554 -v 0.088003 0.073026 0.063032 -vn -0.770264 0.318863 0.552286 -v 0.088003 0.075075 0.064531 -vn -0.770260 -0.318866 -0.552290 -v 0.088003 0.076425 0.066869 -vn -0.770263 -0.000002 -0.637726 -v 0.088003 0.075750 0.067050 -vn -0.770261 0.318865 -0.552288 -v 0.088003 0.075075 0.066869 -vn -0.770262 0.552289 -0.318862 -v 0.088003 0.074581 0.066375 -vn -0.770262 -0.318864 0.552289 -v 0.088003 0.076425 0.064531 -vn -0.770263 -0.552288 0.318862 -v 0.088003 0.076919 0.065025 -vn -0.685696 -0.071347 -0.724383 -v 0.088003 0.078964 0.057400 -vn -0.665720 -0.285561 -0.689400 -v 0.088003 0.078581 0.057476 -vn -0.770261 -0.000002 0.637729 -v 0.088003 0.075750 0.064350 -vn -0.685696 -0.461767 -0.562665 -v 0.088003 0.078257 0.057693 -vn -0.685694 -0.562670 -0.461763 -v 0.088003 0.073243 0.062707 -vn -0.770263 -0.552286 -0.318864 -v 0.088003 0.076919 0.066375 -vn -0.707105 -0.707109 -0.000000 -v 0.088003 0.078964 0.074200 -vn -0.770261 -0.637729 0.000000 -v 0.088003 0.077100 0.065700 -vn -0.737700 -0.669353 -0.088121 -v 0.088003 0.078964 0.065000 -vn -0.745120 -0.608106 -0.273869 -v 0.088003 0.079232 0.064000 -vn -0.685695 -0.724383 0.071349 -v 0.088003 0.072950 0.101986 -vn -0.770260 0.637730 -0.000000 -v 0.088003 0.074400 0.082700 -vn -0.770262 0.552289 0.318862 -v 0.088003 0.074581 0.082025 -vn -0.770261 0.318865 0.552288 -v 0.088003 0.075075 0.081531 -vn -0.770261 -0.000002 -0.637729 -v 0.088003 0.075750 0.084050 -vn -0.770263 0.318863 -0.552287 -v 0.088003 0.075075 0.083869 -vn -0.770261 0.552291 -0.318861 -v 0.088003 0.074581 0.083375 -vn -0.770264 0.318863 0.552286 -v 0.088003 0.075075 0.098531 -vn -0.770260 -0.637730 -0.000000 -v 0.088003 0.077100 0.082700 -vn -0.770262 0.552290 0.318860 -v 0.088003 0.074581 0.099025 -vn -0.770261 -0.552290 -0.318863 -v 0.088003 0.076919 0.083375 -vn -0.770262 -0.318864 -0.552289 -v 0.088003 0.076425 0.083869 -vn -0.770263 -0.552287 0.318863 -v 0.088003 0.079232 0.107000 -vn -0.770262 -0.318863 -0.552289 -v 0.088003 0.076425 0.100869 -vn -0.770261 -0.000002 -0.637729 -v 0.088003 0.075750 0.101050 -vn -0.770263 -0.000002 0.637726 -v 0.088003 0.075750 0.081350 -vn -0.770264 0.318863 -0.552286 -v 0.088003 0.075075 0.100869 -vn -0.770261 0.552291 -0.318862 -v 0.088003 0.074581 0.100375 -vn -0.770261 0.637729 -0.000001 -v 0.088003 0.074400 0.099700 -vn -0.770260 -0.318866 0.552290 -v 0.088003 0.076425 0.081531 -vn -0.770263 -0.552286 0.318864 -v 0.088003 0.076919 0.082025 -vn -0.685696 -0.071347 0.724383 -v 0.088003 0.078964 0.108000 -vn -0.770261 -0.318864 0.552290 -v 0.088003 0.079964 0.107732 -vn -0.707107 0.000000 0.707107 -v 0.088003 0.079401 0.108000 -vn -0.041900 -0.065066 0.997001 -v 0.088003 0.080964 0.108000 -vn -0.665722 -0.689401 0.285555 -v 0.088003 0.073026 0.102368 -vn -0.685694 -0.562670 0.461763 -v 0.088003 0.073243 0.102693 -vn -0.685697 -0.461768 0.562662 -v 0.088003 0.078257 0.107707 -vn -0.665719 -0.285564 0.689400 -v 0.088003 0.078581 0.107924 -vn -0.770261 -0.000002 0.637729 -v 0.088003 0.075750 0.098350 -vn -0.770262 -0.318863 0.552289 -v 0.088003 0.076425 0.098531 -vn -0.770262 -0.552289 0.318863 -v 0.088003 0.076919 0.099025 -vn -0.737697 -0.669356 0.088121 -v 0.088003 0.078964 0.106000 -vn -0.770261 -0.637729 -0.000001 -v 0.088003 0.077100 0.099700 -vn -0.770262 -0.552289 -0.318864 -v 0.088003 0.076919 0.100375 -vn 0.770263 -0.552288 -0.318862 -v 0.090003 0.084221 0.060875 -vn 0.770261 -0.637728 0.000000 -v 0.090003 0.084402 0.060200 -vn 1.000000 0.000000 0.000000 -v 0.090003 0.090939 0.062950 -vn 0.753769 -0.251479 0.607117 -v 0.090003 0.079890 0.107886 -vn 0.031347 -0.048925 0.998310 -v 0.090003 0.080464 0.108000 -vn 0.707107 0.000000 0.707107 -v 0.090003 0.079401 0.108000 -vn 0.685696 -0.071347 -0.724383 -v 0.090003 0.078964 0.057400 -vn 0.707107 0.000000 -0.707107 -v 0.090003 0.079401 0.057400 -vn 1.000000 0.000000 -0.000000 -v 0.090003 0.079401 0.062950 -vn 0.707108 0.499999 0.499999 -v 0.090003 0.105750 0.105200 -vn 1.000000 0.000000 0.000000 -v 0.090003 0.105750 0.104525 -vn 0.707108 0.499999 0.499999 -v 0.090003 0.106425 0.104525 -vn 0.770263 0.318864 -0.552286 -v 0.090003 0.105075 0.100869 -vn 0.770261 0.000000 -0.637729 -v 0.090003 0.105750 0.101050 -vn 0.770262 -0.318862 -0.552289 -v 0.090003 0.106425 0.100869 -vn 0.707108 0.499999 0.499999 -v 0.090003 0.107825 0.103125 -vn 0.770262 -0.552289 -0.318863 -v 0.090003 0.106919 0.100375 -vn 0.770261 -0.637729 -0.000001 -v 0.090003 0.107100 0.099700 -vn 1.000000 0.000000 0.000000 -v 0.090003 0.107825 0.091200 -vn 0.770262 -0.552289 0.318862 -v 0.090003 0.106919 0.099025 -vn 0.770262 -0.318862 0.552289 -v 0.090003 0.106425 0.098531 -vn 1.000000 -0.000000 0.000001 -v 0.090003 0.105750 0.091200 -vn 0.770261 -0.000000 0.637729 -v 0.090003 0.105750 0.098350 -vn 0.707106 0.707107 0.000000 -v 0.090003 0.102534 0.091200 -vn 0.770263 0.318864 0.552286 -v 0.090003 0.105075 0.098531 -vn 0.770260 0.552291 0.318865 -v 0.090003 0.104581 0.099025 -vn 0.770264 0.637726 -0.000001 -v 0.090003 0.104400 0.099700 -vn 0.707107 0.707107 0.000000 -v 0.090003 0.102534 0.104525 -vn 0.770260 0.552290 -0.318866 -v 0.090003 0.104581 0.100375 -vn 0.707106 0.707107 0.000000 -v 0.090003 0.102534 0.074200 -vn 0.770264 0.637725 0.000000 -v 0.090003 0.104400 0.082700 -vn 0.770261 0.552288 0.318866 -v 0.090003 0.104581 0.082025 -vn 1.000000 0.000000 0.000000 -v 0.090003 0.107825 0.074200 -vn 0.770260 -0.318865 0.552291 -v 0.090003 0.106425 0.081531 -vn 1.000000 0.000000 0.000000 -v 0.090003 0.105750 0.074200 -vn 0.770263 -0.000000 0.637726 -v 0.090003 0.105750 0.081350 -vn 0.770261 0.318866 0.552288 -v 0.090003 0.105075 0.081531 -vn 0.770261 0.552290 -0.318864 -v 0.090003 0.104581 0.083375 -vn 0.770264 0.318864 -0.552286 -v 0.090003 0.105075 0.083869 -vn 0.770261 -0.000000 -0.637729 -v 0.090003 0.105750 0.084050 -vn 0.770263 -0.318862 -0.552288 -v 0.090003 0.106425 0.083869 -vn 0.770263 -0.552288 -0.318862 -v 0.090003 0.106919 0.083375 -vn 0.770262 -0.637727 0.000000 -v 0.090003 0.107100 0.082700 -vn 0.770263 -0.552286 0.318864 -v 0.090003 0.106919 0.082025 -vn 0.770262 -0.318862 0.552289 -v 0.090003 0.106425 0.064531 -vn 0.770261 -0.000000 0.637729 -v 0.090003 0.105750 0.064350 -vn 1.000000 0.000000 0.000000 -v 0.090003 0.105750 0.062950 -vn 0.770263 0.318864 0.552287 -v 0.090003 0.105075 0.064531 -vn 0.729849 0.680317 -0.067005 -v 0.090003 0.102534 0.064500 -vn 0.753767 0.607120 -0.251477 -v 0.090003 0.102420 0.063926 -vn 0.770260 0.552291 0.318865 -v 0.090003 0.104581 0.065025 -vn 0.753768 0.464669 -0.464669 -v 0.090003 0.102095 0.063439 -vn 0.753768 0.251476 -0.607120 -v 0.090003 0.101608 0.063114 -vn 0.770263 0.637726 0.000000 -v 0.090003 0.104400 0.065700 -vn 0.770261 0.552288 -0.318866 -v 0.090003 0.104581 0.066375 -vn 0.770261 0.318866 -0.552288 -v 0.090003 0.105075 0.066869 -vn 0.770263 0.000000 -0.637726 -v 0.090003 0.105750 0.067050 -vn 0.770260 -0.318865 -0.552291 -v 0.090003 0.106425 0.066869 -vn 0.770263 -0.552286 -0.318864 -v 0.090003 0.106919 0.066375 -vn 0.770261 -0.637729 -0.000000 -v 0.090003 0.107100 0.065700 -vn 1.000000 0.000000 0.000000 -v 0.090003 0.107825 0.062950 -vn 0.770262 -0.552289 0.318862 -v 0.090003 0.106919 0.065025 -vn 0.707107 -0.707107 0.000000 -v 0.090003 0.078964 0.091200 -vn 0.770262 -0.318863 0.552289 -v 0.090003 0.076425 0.098531 -vn 0.707106 -0.707107 0.000000 -v 0.090003 0.072950 0.091200 -vn 0.770261 -0.000002 0.637729 -v 0.090003 0.075750 0.098350 -vn 0.770264 0.318863 0.552287 -v 0.090003 0.075075 0.098531 -vn 0.770264 0.318863 -0.552287 -v 0.090003 0.075075 0.100869 -vn 0.770261 -0.000002 -0.637729 -v 0.090003 0.075750 0.101050 -vn 0.707106 -0.500000 0.500001 -v 0.090003 0.075075 0.104525 -vn 0.770262 -0.318863 -0.552289 -v 0.090003 0.076425 0.100869 -vn 0.770262 -0.552289 -0.318863 -v 0.090003 0.076919 0.100375 -vn 0.707107 -0.707107 0.000000 -v 0.090003 0.078964 0.104525 -vn 0.770261 -0.637729 -0.000001 -v 0.090003 0.077100 0.099700 -vn 0.770262 -0.552289 0.318862 -v 0.090003 0.076919 0.099025 -vn 0.753767 -0.607120 0.251477 -v 0.090003 0.079078 0.107074 -vn 0.685697 -0.461768 0.562663 -v 0.090003 0.078257 0.107707 -vn 0.729849 -0.680317 0.067005 -v 0.090003 0.078964 0.106500 -vn 0.770261 0.552291 0.318861 -v 0.090003 0.074581 0.099025 -vn 0.770261 0.637729 -0.000001 -v 0.090003 0.074400 0.099700 -vn 0.685696 -0.724383 0.071349 -v 0.090003 0.072950 0.101986 -vn 0.770261 0.552291 -0.318862 -v 0.090003 0.074581 0.100375 -vn 0.665722 -0.689401 0.285555 -v 0.090003 0.073026 0.102368 -vn 0.685695 -0.562671 0.461763 -v 0.090003 0.073243 0.102693 -vn 0.770263 -0.552286 0.318864 -v 0.090003 0.076919 0.082025 -vn 0.707106 -0.707107 0.000000 -v 0.090003 0.078964 0.074200 -vn 0.770261 -0.637728 0.000000 -v 0.090003 0.077100 0.082700 -vn 0.770263 -0.552288 -0.318862 -v 0.090003 0.076919 0.083375 -vn 0.770260 -0.318866 0.552290 -v 0.090003 0.076425 0.081531 -vn 0.770263 -0.000002 0.637726 -v 0.090003 0.075750 0.081350 -vn 0.707106 -0.707107 0.000000 -v 0.090003 0.072950 0.074200 -vn 0.770261 0.318865 0.552288 -v 0.090003 0.075075 0.081531 -vn 0.770262 0.552290 -0.318861 -v 0.090003 0.074581 0.083375 -vn 0.770262 0.637728 0.000000 -v 0.090003 0.074400 0.082700 -vn 0.770262 0.552289 0.318862 -v 0.090003 0.074581 0.082025 -vn 0.770264 0.318863 -0.552286 -v 0.090003 0.075075 0.083869 -vn 0.770261 -0.000002 -0.637729 -v 0.090003 0.075750 0.084050 -vn 0.770262 -0.318863 -0.552288 -v 0.090003 0.076425 0.083869 -vn 0.685696 -0.724383 -0.071347 -v 0.090003 0.072950 0.063414 -vn 0.770261 0.552291 0.318861 -v 0.090003 0.074581 0.065025 -vn 0.770261 0.637729 0.000000 -v 0.090003 0.074400 0.065700 -vn 0.685694 -0.562670 -0.461763 -v 0.090003 0.073243 0.062707 -vn 0.770261 -0.000002 0.637729 -v 0.090003 0.075750 0.064350 -vn 0.770264 0.318863 0.552286 -v 0.090003 0.075075 0.064531 -vn 0.770262 0.552289 -0.318862 -v 0.090003 0.074581 0.066375 -vn 0.770261 0.318865 -0.552288 -v 0.090003 0.075075 0.066869 -vn 0.770263 -0.000002 -0.637726 -v 0.090003 0.075750 0.067050 -vn 0.770260 -0.318866 -0.552290 -v 0.090003 0.076425 0.066869 -vn 0.770263 -0.552286 -0.318864 -v 0.090003 0.076919 0.066375 -vn 0.729849 -0.680317 -0.067005 -v 0.090003 0.078964 0.064500 -vn 0.770261 -0.637729 -0.000000 -v 0.090003 0.077100 0.065700 -vn 0.753767 -0.607120 -0.251477 -v 0.090003 0.079078 0.063926 -vn 0.770262 -0.552289 0.318862 -v 0.090003 0.076919 0.065025 -vn 0.770262 -0.318863 0.552289 -v 0.090003 0.076425 0.064531 -vn 0.753768 -0.464669 -0.464669 -v 0.090003 0.079403 0.063439 -vn 0.665721 -0.689401 -0.285554 -v 0.090003 0.073026 0.063032 -vn 0.729849 0.067005 -0.680317 -v 0.090003 0.101034 0.063000 -vn 0.707107 0.000000 -0.707107 -v 0.090003 0.090939 0.063000 -vn 0.729843 -0.067004 -0.680323 -v 0.090003 0.080464 0.063000 -vn 0.753768 -0.251476 -0.607120 -v 0.090003 0.079890 0.063114 -vn 0.729849 0.680317 0.067005 -v 0.090003 0.102534 0.106500 -vn 0.753767 0.607120 0.251477 -v 0.090003 0.102420 0.107074 -vn 0.031347 0.048924 0.998310 -v 0.090003 0.101034 0.108000 -vn 0.753769 0.251479 0.607117 -v 0.090003 0.101608 0.107886 -vn 0.685696 0.071347 0.724383 -v 0.090003 0.102536 0.108000 -vn 0.753766 0.464672 0.464667 -v 0.090003 0.102095 0.107561 -vn 0.665719 0.285564 0.689400 -v 0.090003 0.102918 0.107924 -vn 0.685697 0.461769 0.562662 -v 0.090003 0.103243 0.107707 -vn 0.685696 0.562666 -0.461766 -v 0.090003 0.108257 0.062707 -vn 0.707107 0.500000 -0.500000 -v 0.090003 0.105750 0.060200 -vn 0.770262 0.552289 0.318863 -v 0.090003 0.097656 0.059525 -vn 0.770261 0.637729 0.000000 -v 0.090003 0.097475 0.060200 -vn 0.770262 0.552289 -0.318862 -v 0.090003 0.097656 0.060875 -vn 0.770262 0.318862 -0.552289 -v 0.090003 0.098150 0.061369 -vn 0.770261 0.000000 -0.637729 -v 0.090003 0.098825 0.061550 -vn 0.770263 -0.318864 -0.552286 -v 0.090003 0.099500 0.061369 -vn 0.770260 -0.552291 -0.318865 -v 0.090003 0.099995 0.060875 -vn 0.770264 -0.637726 0.000000 -v 0.090003 0.100175 0.060200 -vn 0.685696 0.461767 -0.562665 -v 0.090003 0.103243 0.057693 -vn 0.770260 -0.552290 0.318865 -v 0.090003 0.099995 0.059525 -vn 0.665719 0.285561 -0.689400 -v 0.090003 0.102918 0.057476 -vn 0.685696 0.071347 -0.724383 -v 0.090003 0.102536 0.057400 -vn 0.770263 -0.318864 0.552286 -v 0.090003 0.099500 0.059031 -vn 0.770261 -0.000000 0.637729 -v 0.090003 0.098825 0.058850 -vn 0.707107 0.000000 -0.707107 -v 0.090003 0.090939 0.057400 -vn 0.770262 0.318862 0.552289 -v 0.090003 0.098150 0.059031 -vn 0.665719 -0.285561 -0.689400 -v 0.090003 0.078581 0.057476 -vn 0.685697 -0.461767 -0.562665 -v 0.090003 0.078257 0.057693 -vn 0.665719 -0.285564 0.689400 -v 0.090003 0.078581 0.107924 -vn 0.685696 -0.071347 0.724383 -v 0.090003 0.078964 0.108000 -vn 0.753766 -0.464672 0.464668 -v 0.090003 0.079403 0.107561 -vn 0.770263 -0.552288 0.318863 -v 0.090003 0.084221 0.059525 -vn 0.770263 -0.318862 0.552288 -v 0.090003 0.083727 0.059031 -vn 0.770261 0.000000 0.637728 -v 0.090003 0.083052 0.058850 -vn 0.770262 0.552289 -0.318862 -v 0.090003 0.081883 0.060875 -vn 0.770262 0.318862 -0.552289 -v 0.090003 0.082377 0.061369 -vn 0.770261 0.000000 -0.637728 -v 0.090003 0.083052 0.061550 -vn 0.770263 -0.318862 -0.552288 -v 0.090003 0.083727 0.061369 -vn 0.770262 0.318862 0.552289 -v 0.090003 0.082377 0.059031 -vn 0.770262 0.552289 0.318863 -v 0.090003 0.081883 0.059525 -vn 0.770261 0.637729 0.000000 -v 0.090003 0.081702 0.060200 -vn 0.665720 0.689400 -0.285560 -v 0.090003 0.108474 0.063032 -vn 0.685696 0.724383 -0.071347 -v 0.090003 0.108550 0.063414 -vn 0.707107 0.707107 0.000000 -v 0.090003 0.108550 0.074200 -vn 0.707107 0.707107 0.000000 -v 0.090003 0.108550 0.091200 -vn 0.685695 0.724383 0.071349 -v 0.090003 0.108550 0.101986 -vn 0.685697 0.562666 0.461766 -v 0.090003 0.108257 0.102693 -vn 0.665720 0.689400 0.285561 -v 0.090003 0.108474 0.102368 -vn 0.577350 0.577350 -0.577350 -v 0.062003 0.086250 0.063000 -vn 0.301511 0.301511 -0.904534 -v 0.062003 0.086250 0.057400 -vn 0.577350 -0.577350 -0.577350 -v 0.062003 0.095250 0.063000 -vn 0.301511 -0.301511 -0.904534 -v 0.062003 0.095250 0.057400 -vn 0.737700 -0.088121 -0.669353 -v 0.064303 0.080964 0.063000 -vn 0.122605 -0.023152 -0.992186 -v 0.064303 0.083052 0.063000 -vn 0.301512 0.301513 -0.904534 -v 0.064303 0.086250 0.063000 -vn 0.301512 -0.301511 -0.904534 -v 0.064303 0.095250 0.063000 -vn 0.122605 0.023152 -0.992186 -v 0.064303 0.098448 0.063000 -vn 0.737700 0.088121 -0.669353 -v 0.064303 0.100536 0.063000 -vn 0.262880 0.359049 -0.895532 -v 0.062003 0.102536 0.057400 -vn 0.665719 0.285561 -0.689400 -v 0.062003 0.102918 0.057476 -vn 0.577350 0.577350 -0.577350 -v 0.062003 0.102536 0.062200 -vn 0.685696 0.461767 -0.562665 -v 0.062003 0.103243 0.057693 -vn 0.131340 0.557226 -0.819908 -v 0.062003 0.107750 0.062200 -vn 0.770261 -0.000000 0.637729 -v 0.062003 0.098825 0.058850 -vn 0.301511 0.301511 -0.904534 -v 0.062003 0.095760 0.057400 -vn 0.301512 -0.301511 -0.904534 -v 0.062003 0.102026 0.057400 -vn 0.770264 -0.637726 0.000000 -v 0.062003 0.100175 0.060200 -vn 0.770260 -0.552290 0.318865 -v 0.062003 0.099995 0.059525 -vn 0.770263 -0.318864 0.552286 -v 0.062003 0.099500 0.059031 -vn 0.770262 0.318862 0.552289 -v 0.062003 0.098150 0.059031 -vn 0.770262 0.552289 0.318863 -v 0.062003 0.097656 0.059525 -vn 0.686227 0.724062 -0.069477 -v 0.062003 0.095760 0.061143 -vn 0.770261 0.637729 0.000000 -v 0.062003 0.097475 0.060200 -vn 0.666710 0.691422 -0.278270 -v 0.062003 0.095832 0.061517 -vn 0.770262 0.552289 -0.318863 -v 0.062003 0.097656 0.060875 -vn 0.684528 -0.725068 -0.075478 -v 0.062003 0.102026 0.061073 -vn 0.663555 -0.684657 -0.301561 -v 0.062003 0.101941 0.061476 -vn 0.770260 -0.552291 -0.318865 -v 0.062003 0.099995 0.060875 -vn 0.663556 -0.505023 -0.551947 -v 0.062003 0.101701 0.061810 -vn 0.770263 -0.318864 -0.552286 -v 0.062003 0.099500 0.061369 -vn 0.684528 -0.303806 -0.662664 -v 0.062003 0.101346 0.062020 -vn 0.770261 0.000000 -0.637729 -v 0.062003 0.098825 0.061550 -vn 0.633287 0.037442 -0.773011 -v 0.062003 0.098448 0.063000 -vn 0.770262 0.318862 -0.552289 -v 0.062003 0.098150 0.061369 -vn 0.686228 0.360538 -0.631747 -v 0.062003 0.096349 0.062055 -vn 0.666709 0.537538 -0.516287 -v 0.062003 0.096039 0.061836 -vn 0.770262 -0.552289 0.318863 -v 0.062003 0.084221 0.059525 -vn 0.301511 -0.301511 -0.904534 -v 0.062003 0.085740 0.057400 -vn 0.770261 -0.637729 0.000000 -v 0.062003 0.084402 0.060200 -vn 0.686227 -0.724062 -0.069477 -v 0.062003 0.085740 0.061143 -vn 0.770262 -0.552289 -0.318862 -v 0.062003 0.084221 0.060875 -vn 0.663553 0.505026 -0.551948 -v 0.062003 0.079799 0.061810 -vn 0.663557 0.684658 -0.301555 -v 0.062003 0.079559 0.061476 -vn 0.684528 0.725068 -0.075478 -v 0.062003 0.079474 0.061073 -vn 0.770262 -0.318862 0.552289 -v 0.062003 0.083727 0.059031 -vn 0.770261 -0.000000 0.637729 -v 0.062003 0.083052 0.058850 -vn 0.301511 0.301511 -0.904534 -v 0.062003 0.079474 0.057400 -vn 0.684529 0.303803 -0.662665 -v 0.062003 0.080154 0.062020 -vn 0.770261 0.637729 0.000000 -v 0.062003 0.081702 0.060200 -vn 0.770262 0.552289 0.318863 -v 0.062003 0.081883 0.059525 -vn 0.770262 0.318862 0.552289 -v 0.062003 0.082377 0.059031 -vn 0.770262 0.552289 -0.318862 -v 0.062003 0.081883 0.060875 -vn 0.770262 0.318862 -0.552289 -v 0.062003 0.082377 0.061369 -vn 0.633287 -0.037442 -0.773011 -v 0.062003 0.083052 0.063000 -vn 0.770261 0.000000 -0.637729 -v 0.062003 0.083052 0.061550 -vn 0.686228 -0.360538 -0.631747 -v 0.062003 0.085150 0.062055 -vn 0.770262 -0.318862 -0.552289 -v 0.062003 0.083727 0.061369 -vn 0.666709 -0.537538 -0.516287 -v 0.062003 0.085461 0.061836 -vn 0.666710 -0.691422 -0.278270 -v 0.062003 0.085668 0.061517 -vn 0.665719 -0.285561 -0.689400 -v 0.062003 0.078581 0.057476 -vn 0.262880 -0.359049 -0.895532 -v 0.062003 0.078964 0.057400 -vn 0.685697 -0.461767 -0.562665 -v 0.062003 0.078257 0.057693 -vn 0.577350 -0.577350 -0.577350 -v 0.062003 0.078964 0.062200 -vn 0.131341 -0.557223 -0.819910 -v 0.062003 0.073750 0.062200 -vn 0.301511 -0.904534 0.301511 -v 0.076103 0.078964 0.077200 -vn 0.904534 -0.301511 -0.301511 -v 0.076103 0.078964 0.074600 -vn -0.301510 -0.904535 -0.301511 -v 0.085103 0.078964 0.074600 -vn -0.301510 -0.904535 0.301511 -v 0.085103 0.078964 0.069600 -vn 0.301511 -0.904534 -0.301511 -v 0.064303 0.078964 0.096197 -vn 0.577350 -0.577350 -0.577350 -v 0.062003 0.078964 0.096197 -vn 0.577350 -0.577350 0.577350 -v 0.062003 0.078964 0.086700 -vn 0.577350 -0.577350 -0.577350 -v 0.071103 0.078964 0.067000 -vn 0.577350 -0.577350 0.577350 -v 0.071103 0.078964 0.066000 -vn 0.301512 -0.904534 -0.301512 -v 0.076103 0.078964 0.067000 -vn 0.301511 -0.904534 0.301511 -v 0.074103 0.078964 0.066000 -vn 0.178904 -0.983867 -0.000000 -v 0.064303 0.078964 0.099700 -vn 0.301512 -0.904534 0.301511 -v 0.064303 0.078964 0.103200 -vn 0.737700 -0.669353 0.088121 -v 0.062003 0.078964 0.106000 -vn 0.577350 -0.577350 0.577350 -v 0.062003 0.078964 0.103200 -vn 0.289898 -0.849937 -0.439961 -v 0.074103 0.078964 0.065000 -vn 0.904534 -0.301511 0.301511 -v 0.076103 0.078964 0.069600 -vn 0.577350 -0.577350 0.577350 -v 0.064303 0.078964 0.079200 -vn 0.301511 -0.904534 0.301511 -v 0.074103 0.078964 0.079200 -vn 0.165763 -0.986166 0.000000 -v 0.064303 0.078964 0.082700 -vn 0.301511 -0.904534 0.301512 -v 0.064303 0.078964 0.086700 -vn 0.301511 -0.904534 -0.301511 -v 0.074103 0.078964 0.078200 -vn 0.577350 -0.577350 -0.577350 -v 0.071103 0.078964 0.078200 -vn 0.577350 -0.577350 0.577350 -v 0.071103 0.078964 0.077200 -vn 0.301511 -0.904534 -0.301511 -v 0.071103 0.073964 0.078200 -vn 0.301511 -0.904534 0.301511 -v 0.071103 0.073964 0.077200 -vn -0.577350 -0.577350 -0.577350 -v 0.064303 0.078964 0.078700 -vn 0.577350 -0.577350 -0.577350 -v 0.062003 0.078964 0.078700 -vn -0.577350 -0.577350 0.577350 -v 0.064303 0.078964 0.069203 -vn 0.577350 -0.577350 0.577350 -v 0.062003 0.078964 0.069203 -vn 0.707107 0.000000 -0.707107 -v 0.064303 0.078964 0.062200 -vn 0.756532 0.598477 -0.263597 -v 0.064303 0.079559 0.061476 -vn 0.756537 0.441451 -0.482466 -v 0.064303 0.079799 0.061810 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.078964 0.057400 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.079474 0.057400 -vn 0.731171 0.678528 -0.070633 -v 0.064303 0.079474 0.061073 -vn 0.769938 -0.318698 -0.552835 -v 0.064303 0.079964 0.063268 -vn 0.731170 0.284303 -0.620130 -v 0.064303 0.080154 0.062020 -vn 0.178904 -0.983867 -0.000001 -v 0.064303 0.078964 0.065700 -vn 0.000001 -0.496440 0.868071 -v 0.064303 0.078376 0.064700 -vn 0.737700 -0.669353 -0.088121 -v 0.064303 0.078964 0.065000 -vn 0.904534 0.301511 0.301511 -v 0.064303 0.078964 0.064700 -vn 0.769934 -0.552839 -0.318700 -v 0.064303 0.079232 0.064000 -vn -0.000000 -0.496440 -0.868071 -v 0.064303 0.078376 0.066700 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.078964 0.066700 -vn 0.301511 0.904534 0.301511 -v 0.071103 0.107536 0.066000 -vn 0.301511 0.904534 -0.301511 -v 0.071103 0.107536 0.067000 -vn 0.301511 0.904534 -0.301511 -v 0.071103 0.107536 0.078200 -vn 0.301511 0.904534 0.301511 -v 0.071103 0.107536 0.077200 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.102536 0.066700 -vn -0.577350 0.577350 -0.577350 -v 0.065303 0.102536 0.066700 -vn 0.178903 0.983867 -0.000001 -v 0.064303 0.102536 0.065700 -vn -0.707107 0.683012 -0.183016 -v 0.065303 0.102536 0.065000 -vn 0.737701 0.669352 -0.088123 -v 0.064303 0.102536 0.065000 -vn 0.577350 0.577350 0.577350 -v 0.062003 0.102536 0.069203 -vn 0.577350 0.577350 -0.577350 -v 0.062003 0.102536 0.078700 -vn -0.577350 0.577350 0.577350 -v 0.064303 0.102536 0.069203 -vn -0.577350 0.577350 -0.577350 -v 0.064303 0.102536 0.078700 -vn 0.731172 -0.284305 -0.620128 -v 0.064303 0.101346 0.062020 -vn 0.756534 -0.441452 -0.482470 -v 0.064303 0.101701 0.061810 -vn 0.707107 -0.000000 -0.707107 -v 0.064303 0.102536 0.062200 -vn 0.770263 0.318863 -0.552287 -v 0.064303 0.101536 0.063268 -vn 0.770261 0.552290 -0.318864 -v 0.064303 0.102268 0.064000 -vn 0.904534 -0.301511 0.301511 -v 0.064303 0.102536 0.064700 -vn 0.000001 0.496440 0.868071 -v 0.064303 0.103124 0.064700 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.102026 0.057400 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.102536 0.057400 -vn 0.731171 -0.678528 -0.070633 -v 0.064303 0.102026 0.061073 -vn 0.756534 -0.598474 -0.263601 -v 0.064303 0.101941 0.061476 -vn -0.000000 0.496440 -0.868071 -v 0.064303 0.103124 0.066700 -vn 0.904534 0.301511 0.301511 -v 0.064303 0.107536 0.079200 -vn 0.000000 0.707107 -0.707107 -v 0.064303 0.107536 0.078700 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.108550 0.078700 -vn 0.577350 0.577350 0.577350 -v 0.064303 0.108550 0.079700 -vn 0.727799 0.061326 0.683043 -v 0.064303 0.104756 0.079700 -vn 0.749491 0.232093 0.619997 -v 0.064303 0.104405 0.079763 -vn 0.749484 0.434728 0.499285 -v 0.064303 0.104099 0.079946 -vn 0.727801 0.571458 0.379133 -v 0.064303 0.103876 0.080224 -vn 0.301511 -0.904534 -0.301511 -v 0.062003 0.072950 0.078700 -vn 0.301511 -0.904534 0.301511 -v 0.062003 0.072950 0.069203 -vn 0.301511 -0.904534 0.301511 -v 0.062003 0.072950 0.086700 -vn 0.301511 -0.904534 -0.301511 -v 0.062003 0.072950 0.096197 -vn 0.770261 0.000000 -0.637729 -v 0.062003 0.105750 0.084050 -vn 0.770262 -0.318862 -0.552289 -v 0.062003 0.106425 0.083869 -vn 0.301512 0.904534 -0.301511 -v 0.062003 0.108550 0.085700 -vn 0.770262 -0.552289 -0.318862 -v 0.062003 0.106919 0.083375 -vn 0.770261 -0.637729 -0.000000 -v 0.062003 0.107100 0.082700 -vn 0.301512 0.904534 0.301511 -v 0.062003 0.108550 0.079700 -vn 0.770263 -0.552286 0.318864 -v 0.062003 0.106919 0.082025 -vn 0.770260 -0.318865 0.552291 -v 0.062003 0.106425 0.081531 -vn 0.687522 0.064936 0.723254 -v 0.062003 0.104756 0.079700 -vn 0.770263 -0.000000 0.637726 -v 0.062003 0.105750 0.081350 -vn 0.669120 0.260539 0.695987 -v 0.062003 0.104405 0.079763 -vn 0.770261 0.318866 0.552288 -v 0.062003 0.105075 0.081531 -vn 0.687523 0.064936 -0.723254 -v 0.062003 0.104756 0.085700 -vn 0.669122 0.260532 -0.695987 -v 0.062003 0.104405 0.085637 -vn 0.770263 0.318864 -0.552286 -v 0.062003 0.105075 0.083869 -vn 0.669122 0.488002 -0.560473 -v 0.062003 0.104099 0.085454 -vn 0.770260 0.552291 -0.318865 -v 0.062003 0.104581 0.083375 -vn 0.687522 0.605104 -0.401450 -v 0.062003 0.103876 0.085176 -vn 0.770263 0.637726 0.000000 -v 0.062003 0.104400 0.082700 -vn 0.614012 0.789297 -0.000000 -v 0.062003 0.102536 0.082700 -vn 0.770261 0.552288 0.318866 -v 0.062003 0.104581 0.082025 -vn 0.687521 0.605103 0.401455 -v 0.062003 0.103876 0.080224 -vn 0.669125 0.488001 0.560469 -v 0.062003 0.104099 0.079946 -vn 0.301511 0.904534 0.301511 -v 0.062003 0.108550 0.069203 -vn 0.301511 0.904534 -0.301511 -v 0.062003 0.108550 0.078700 -vn 0.301511 0.904534 -0.301511 -v 0.062003 0.108550 0.096197 -vn 0.301511 0.904534 0.301511 -v 0.062003 0.108550 0.086700 -vn 0.770264 0.318863 0.552287 -v 0.062003 0.075075 0.098531 -vn 0.770261 0.552291 0.318861 -v 0.062003 0.074581 0.099025 -vn 0.301512 -0.904534 0.301511 -v 0.062003 0.072950 0.096707 -vn 0.770261 0.637729 -0.000001 -v 0.062003 0.074400 0.099700 -vn 0.685696 -0.724383 0.071349 -v 0.062003 0.072950 0.101986 -vn 0.770261 0.552291 -0.318862 -v 0.062003 0.074581 0.100375 -vn 0.666352 -0.689188 0.284595 -v 0.062003 0.073026 0.102368 -vn 0.770264 0.318863 -0.552286 -v 0.062003 0.075075 0.100869 -vn 0.770261 -0.000002 0.637729 -v 0.062003 0.075750 0.098350 -vn 0.679086 -0.095066 0.727877 -v 0.062003 0.076631 0.096707 -vn 0.770262 -0.318863 0.552289 -v 0.062003 0.076425 0.098531 -vn 0.653608 -0.375723 0.656985 -v 0.062003 0.077128 0.096839 -vn 0.770262 -0.552289 0.318862 -v 0.062003 0.076919 0.099025 -vn 0.679086 -0.579143 0.451038 -v 0.062003 0.077493 0.097200 -vn 0.770261 -0.637729 -0.000001 -v 0.062003 0.077100 0.099700 -vn 0.608812 -0.793315 -0.000001 -v 0.062003 0.078964 0.099700 -vn 0.770262 -0.552289 -0.318863 -v 0.062003 0.076919 0.100375 -vn 0.679087 -0.579143 -0.451038 -v 0.062003 0.077493 0.102200 -vn 0.770262 -0.318864 -0.552289 -v 0.062003 0.076425 0.100869 -vn 0.653608 -0.375723 -0.656985 -v 0.062003 0.077128 0.102561 -vn 0.770261 -0.000002 -0.637729 -v 0.062003 0.075750 0.101050 -vn 0.679086 -0.095066 -0.727877 -v 0.062003 0.076631 0.102693 -vn 0.490876 -0.799541 0.346085 -v 0.062003 0.073243 0.102693 -vn 0.770261 -0.318865 0.552290 -v 0.062003 0.079964 0.107732 -vn 0.041899 -0.065066 0.997001 -v 0.062003 0.080964 0.108000 -vn 0.685696 -0.071347 0.724383 -v 0.062003 0.078964 0.108000 -vn 0.770263 -0.552287 0.318863 -v 0.062003 0.079232 0.107000 -vn 0.665719 -0.285564 0.689400 -v 0.062003 0.078581 0.107924 -vn 0.685697 -0.461768 0.562662 -v 0.062003 0.078257 0.107707 -vn 0.131340 -0.557227 0.819907 -v 0.062003 0.073750 0.103200 -vn 0.301512 -0.904534 -0.301511 -v 0.062003 0.072950 0.085700 -vn 0.301511 -0.904534 0.301511 -v 0.062003 0.072950 0.079700 -vn 0.770261 0.637729 0.000000 -v 0.062003 0.074400 0.082700 -vn 0.770263 -0.000002 0.637726 -v 0.062003 0.075750 0.081350 -vn 0.770261 0.318865 0.552288 -v 0.062003 0.075075 0.081531 -vn 0.770262 0.552289 0.318862 -v 0.062003 0.074581 0.082025 -vn 0.770261 0.552291 -0.318861 -v 0.062003 0.074581 0.083375 -vn 0.770264 0.318863 -0.552287 -v 0.062003 0.075075 0.083869 -vn 0.687523 -0.064936 -0.723254 -v 0.062003 0.076744 0.085700 -vn 0.770261 -0.000002 -0.637729 -v 0.062003 0.075750 0.084050 -vn 0.669122 -0.260532 -0.695987 -v 0.062003 0.077095 0.085637 -vn 0.770262 -0.318863 -0.552289 -v 0.062003 0.076425 0.083869 -vn 0.687523 -0.064936 0.723254 -v 0.062003 0.076744 0.079700 -vn 0.669120 -0.260539 0.695987 -v 0.062003 0.077095 0.079763 -vn 0.770260 -0.318866 0.552290 -v 0.062003 0.076425 0.081531 -vn 0.669125 -0.488001 0.560469 -v 0.062003 0.077401 0.079946 -vn 0.770263 -0.552286 0.318864 -v 0.062003 0.076919 0.082025 -vn 0.687521 -0.605103 0.401455 -v 0.062003 0.077624 0.080224 -vn 0.770261 -0.637729 -0.000000 -v 0.062003 0.077100 0.082700 -vn 0.614012 -0.789297 0.000000 -v 0.062003 0.078964 0.082700 -vn 0.770262 -0.552289 -0.318862 -v 0.062003 0.076919 0.083375 -vn 0.687522 -0.605104 -0.401450 -v 0.062003 0.077624 0.085176 -vn 0.669122 -0.488002 -0.560473 -v 0.062003 0.077401 0.085454 -vn -0.577350 -0.577350 -0.577350 -v 0.065303 0.078964 0.066700 -vn -0.707107 -0.683013 -0.183011 -v 0.065303 0.078964 0.065000 -vn 0.770264 0.318863 0.552286 -v 0.062003 0.075075 0.064531 -vn 0.770261 0.552291 0.318861 -v 0.062003 0.074581 0.065025 -vn 0.685696 -0.724383 -0.071347 -v 0.062003 0.072950 0.063414 -vn 0.770261 0.637729 0.000000 -v 0.062003 0.074400 0.065700 -vn 0.301511 -0.904534 -0.301511 -v 0.062003 0.072950 0.068693 -vn 0.770262 0.552289 -0.318862 -v 0.062003 0.074581 0.066375 -vn 0.770261 0.318865 -0.552288 -v 0.062003 0.075075 0.066869 -vn 0.679086 -0.095066 -0.727877 -v 0.062003 0.076631 0.068693 -vn 0.770263 -0.000002 -0.637726 -v 0.062003 0.075750 0.067050 -vn 0.653608 -0.375723 -0.656985 -v 0.062003 0.077128 0.068561 -vn 0.770260 -0.318866 -0.552290 -v 0.062003 0.076425 0.066869 -vn 0.679087 -0.579143 -0.451038 -v 0.062003 0.077493 0.068200 -vn 0.770263 -0.552286 -0.318864 -v 0.062003 0.076919 0.066375 -vn 0.608812 -0.793315 -0.000001 -v 0.062003 0.078964 0.065700 -vn 0.770261 -0.637729 -0.000000 -v 0.062003 0.077100 0.065700 -vn 0.679085 -0.579141 0.451041 -v 0.062003 0.077493 0.063200 -vn 0.770262 -0.552289 0.318862 -v 0.062003 0.076919 0.065025 -vn 0.653610 -0.375723 0.656982 -v 0.062003 0.077128 0.062839 -vn 0.770262 -0.318863 0.552289 -v 0.062003 0.076425 0.064531 -vn 0.679085 -0.095071 0.727877 -v 0.062003 0.076631 0.062707 -vn 0.770261 -0.000002 0.637729 -v 0.062003 0.075750 0.064350 -vn 0.490001 -0.800287 -0.345600 -v 0.062003 0.073243 0.062707 -vn 0.665721 -0.689401 -0.285554 -v 0.062003 0.073026 0.063032 -vn 0.770260 -0.318865 -0.552290 -v 0.062003 0.106425 0.066869 -vn 0.770263 -0.552286 -0.318864 -v 0.062003 0.106919 0.066375 -vn 0.301511 0.904534 -0.301511 -v 0.062003 0.108550 0.068693 -vn 0.770261 -0.637729 -0.000000 -v 0.062003 0.107100 0.065700 -vn 0.685696 0.724383 -0.071347 -v 0.062003 0.108550 0.063414 -vn 0.770262 -0.552289 0.318862 -v 0.062003 0.106919 0.065025 -vn 0.665720 0.689400 -0.285560 -v 0.062003 0.108474 0.063032 -vn 0.770262 -0.318862 0.552289 -v 0.062003 0.106425 0.064531 -vn 0.770263 0.000000 -0.637726 -v 0.062003 0.105750 0.067050 -vn 0.679087 0.095064 -0.727876 -v 0.062003 0.104868 0.068693 -vn 0.770261 0.318866 -0.552288 -v 0.062003 0.105075 0.066869 -vn 0.653606 0.375726 -0.656985 -v 0.062003 0.104372 0.068561 -vn 0.770261 0.552288 -0.318866 -v 0.062003 0.104581 0.066375 -vn 0.679088 0.579144 -0.451034 -v 0.062003 0.104007 0.068200 -vn 0.770263 0.637726 0.000000 -v 0.062003 0.104400 0.065700 -vn 0.608812 0.793315 -0.000001 -v 0.062003 0.102536 0.065700 -vn 0.770260 0.552291 0.318865 -v 0.062003 0.104581 0.065025 -vn 0.679086 0.579143 0.451038 -v 0.062003 0.104007 0.063200 -vn 0.770263 0.318864 0.552286 -v 0.062003 0.105075 0.064531 -vn 0.653609 0.375726 0.656982 -v 0.062003 0.104372 0.062839 -vn 0.770261 -0.000000 0.637729 -v 0.062003 0.105750 0.064350 -vn 0.679085 0.095070 0.727877 -v 0.062003 0.104868 0.062707 -vn 0.490004 0.800286 -0.345600 -v 0.062003 0.108257 0.062707 -vn 0.770262 -0.318863 -0.552289 -v 0.062003 0.106425 0.100869 -vn 0.770262 -0.552289 -0.318863 -v 0.062003 0.106919 0.100375 -vn 0.685696 0.724383 0.071349 -v 0.062003 0.108550 0.101986 -vn 0.770261 -0.637729 -0.000001 -v 0.062003 0.107100 0.099700 -vn 0.301511 0.904534 0.301511 -v 0.062003 0.108550 0.096707 -vn 0.770262 -0.552289 0.318862 -v 0.062003 0.106919 0.099025 -vn 0.770262 -0.318862 0.552289 -v 0.062003 0.106425 0.098531 -vn 0.679087 0.095064 0.727876 -v 0.062003 0.104868 0.096707 -vn 0.770261 -0.000000 0.637729 -v 0.062003 0.105750 0.098350 -vn 0.653606 0.375726 0.656985 -v 0.062003 0.104372 0.096839 -vn 0.770263 0.318864 0.552286 -v 0.062003 0.105075 0.098531 -vn 0.679087 0.579145 0.451034 -v 0.062003 0.104007 0.097200 -vn 0.770260 0.552291 0.318865 -v 0.062003 0.104581 0.099025 -vn 0.608812 0.793315 -0.000001 -v 0.062003 0.102536 0.099700 -vn 0.770264 0.637726 -0.000001 -v 0.062003 0.104400 0.099700 -vn 0.679088 0.579144 -0.451034 -v 0.062003 0.104007 0.102200 -vn 0.770260 0.552290 -0.318866 -v 0.062003 0.104581 0.100375 -vn 0.653606 0.375726 -0.656985 -v 0.062003 0.104372 0.102561 -vn 0.770263 0.318864 -0.552286 -v 0.062003 0.105075 0.100869 -vn 0.679087 0.095064 -0.727876 -v 0.062003 0.104868 0.102693 -vn 0.770261 0.000000 -0.637729 -v 0.062003 0.105750 0.101050 -vn 0.490002 0.800289 0.345593 -v 0.062003 0.108257 0.102693 -vn 0.665720 0.689400 0.285561 -v 0.062003 0.108474 0.102368 -vn 0.131339 0.557230 0.819905 -v 0.062003 0.107750 0.103200 -vn 0.770261 0.552289 0.318865 -v 0.062003 0.102268 0.107000 -vn 0.685697 0.461769 0.562662 -v 0.062003 0.103243 0.107707 -vn 0.665719 0.285564 0.689400 -v 0.062003 0.102918 0.107924 -vn 0.770261 0.318865 0.552289 -v 0.062003 0.101536 0.107732 -vn 0.685696 0.071347 0.724383 -v 0.062003 0.102536 0.108000 -vn 0.041899 0.065066 0.997001 -v 0.062003 0.100536 0.108000 -vn -0.765145 0.077608 0.639163 -v 0.057753 0.091112 0.098978 -vn -0.663167 0.231291 0.711838 -v 0.057753 0.091986 0.099804 -vn -0.765146 0.365752 0.529883 -v 0.057753 0.092454 0.098469 -vn -0.663167 0.500825 0.556223 -v 0.057753 0.093426 0.098973 -vn -0.765145 0.570108 0.299216 -v 0.057753 0.093406 0.097394 -vn -0.663167 0.683763 0.304430 -v 0.057753 0.094404 0.097627 -vn -0.765146 0.643856 0.000000 -v 0.057753 0.093750 0.096000 -vn -0.663167 0.748471 -0.000000 -v 0.057753 0.094750 0.096000 -vn -0.765145 0.570108 -0.299216 -v 0.057753 0.093406 0.094606 -vn -0.663167 0.683763 -0.304430 -v 0.057753 0.094404 0.094373 -vn -0.765146 0.365754 -0.529883 -v 0.057753 0.092454 0.093531 -vn -0.663167 0.500826 -0.556222 -v 0.057753 0.093426 0.093027 -vn -0.765147 0.077608 -0.639162 -v 0.057753 0.091112 0.093022 -vn -0.663167 0.231291 -0.711839 -v 0.057753 0.091986 0.092196 -vn -0.663167 -0.078237 -0.744371 -v 0.057753 0.090332 0.092022 -vn -0.765145 -0.228315 -0.602018 -v 0.057753 0.089686 0.093195 -vn -0.663167 -0.374236 -0.648195 -v 0.057753 0.088750 0.092536 -vn -0.765147 -0.481933 -0.426955 -v 0.057753 0.088504 0.094011 -vn -0.663167 -0.605525 -0.439941 -v 0.057753 0.087514 0.093649 -vn -0.750018 -0.631469 -0.196775 -v 0.057753 0.087837 0.095282 -vn -0.673532 -0.713972 -0.191306 -v 0.057753 0.086837 0.095168 -vn -0.735272 -0.677772 0.000000 -v 0.057753 0.087750 0.096000 -vn -0.684321 -0.729181 0.000000 -v 0.057753 0.086750 0.096000 -vn -0.750018 -0.631469 0.196775 -v 0.057753 0.087837 0.096718 -vn -0.673532 -0.713972 0.191306 -v 0.057753 0.086837 0.096832 -vn -0.765146 -0.481934 0.426956 -v 0.057753 0.088504 0.097989 -vn -0.663167 -0.605525 0.439941 -v 0.057753 0.087514 0.098351 -vn -0.765146 -0.228314 0.602017 -v 0.057753 0.089686 0.098805 -vn -0.663167 -0.374236 0.648195 -v 0.057753 0.088750 0.099464 -vn -0.663167 -0.078236 0.744372 -v 0.057753 0.090332 0.099978 -vn -0.757035 0.201904 -0.621396 -v 0.058253 0.091986 0.092196 -vn -0.671869 -0.061164 0.738141 -v 0.058253 0.091287 0.089522 -vn -0.757034 -0.068297 -0.649796 -v 0.058253 0.090332 0.092022 -vn -0.671868 0.181825 0.718006 -v 0.058253 0.089154 0.089699 -vn -0.757035 -0.326688 -0.565839 -v 0.058253 0.088750 0.092536 -vn -0.671869 0.405108 0.620064 -v 0.058253 0.087195 0.090558 -vn -0.757034 -0.528591 -0.384045 -v 0.058253 0.087514 0.093649 -vn -0.671868 0.584493 0.454930 -v 0.058253 0.085621 0.092008 -vn -0.744073 -0.645334 -0.172915 -v 0.058253 0.086837 0.095168 -vn -0.671869 0.700539 0.240495 -v 0.058253 0.084602 0.093889 -vn -0.731407 -0.681942 -0.000000 -v 0.058253 0.086750 0.096000 -vn -0.671868 0.740671 -0.000000 -v 0.058253 0.084250 0.096000 -vn -0.744073 -0.645334 0.172915 -v 0.058253 0.086837 0.096832 -vn -0.671869 0.700539 -0.240496 -v 0.058253 0.084602 0.098111 -vn -0.757034 -0.528591 0.384045 -v 0.058253 0.087514 0.098351 -vn -0.671869 0.584493 -0.454929 -v 0.058253 0.085621 0.099992 -vn -0.757035 -0.326688 0.565839 -v 0.058253 0.088750 0.099464 -vn -0.671868 0.405108 -0.620065 -v 0.058253 0.087195 0.101442 -vn -0.757035 -0.068295 0.649795 -v 0.058253 0.090332 0.099978 -vn -0.757034 0.596888 0.265751 -v 0.058253 0.094404 0.097627 -vn -0.671869 -0.730569 -0.121910 -v 0.058253 0.097161 0.097070 -vn -0.757035 0.653375 0.000000 -v 0.058253 0.094750 0.096000 -vn -0.671869 -0.730569 0.121910 -v 0.058253 0.097161 0.094930 -vn -0.757034 0.596888 -0.265751 -v 0.058253 0.094404 0.094373 -vn -0.671868 -0.651400 0.352520 -v 0.058253 0.096467 0.092906 -vn -0.757034 0.437194 -0.485551 -v 0.058253 0.093426 0.093027 -vn -0.671869 -0.501642 0.544929 -v 0.058253 0.095152 0.091218 -vn -0.671868 -0.297525 0.678286 -v 0.058253 0.093361 0.090047 -vn -0.671869 0.181823 -0.718006 -v 0.058253 0.089154 0.102301 -vn -0.671869 -0.061163 -0.738141 -v 0.058253 0.091287 0.102478 -vn -0.757034 0.201905 0.621397 -v 0.058253 0.091986 0.099804 -vn -0.671868 -0.297523 -0.678287 -v 0.058253 0.093361 0.101953 -vn -0.757035 0.437193 0.485552 -v 0.058253 0.093426 0.098973 -vn -0.671869 -0.501642 -0.544929 -v 0.058253 0.095152 0.100782 -vn -0.671868 -0.651400 -0.352520 -v 0.058253 0.096467 0.099094 -vn -0.577350 0.577350 0.577350 -v 0.060003 0.089295 0.105200 -vn -0.301511 0.301511 0.904534 -v 0.060003 0.089295 0.108000 -vn -0.577350 -0.577350 0.577350 -v 0.060003 0.091232 0.105200 -vn -0.301511 -0.301512 0.904534 -v 0.060003 0.091232 0.108000 -vn -0.685696 0.724383 -0.071347 -v 0.060003 0.108550 0.063414 -vn -0.665720 0.689400 -0.285560 -v 0.060003 0.108474 0.063032 -vn -0.685696 0.562665 -0.461767 -v 0.060003 0.108257 0.062707 -vn -0.685697 0.461767 -0.562665 -v 0.060003 0.103243 0.057693 -vn 0.546918 0.773460 0.320376 -v 0.064303 0.108257 0.062707 -vn 0.630263 0.297107 -0.717284 -v 0.064303 0.107750 0.062200 -vn -0.665719 0.285561 -0.689400 -v 0.060003 0.102918 0.057476 -vn -0.685696 0.071347 -0.724383 -v 0.060003 0.102536 0.057400 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.086250 0.057400 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.085740 0.057400 -vn -0.685696 -0.071347 -0.724383 -v 0.060003 0.078964 0.057400 -vn -0.707107 0.000000 -0.707107 -v 0.060003 0.083795 0.057400 -vn -0.707107 0.000000 -0.707107 -v 0.060003 0.090845 0.057400 -vn -0.707104 0.000000 -0.707109 -v 0.060003 0.100182 0.057400 -vn -0.707107 0.000000 -0.707107 -v 0.060003 0.102295 0.057400 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.095760 0.057400 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.095250 0.057400 -vn -0.665719 -0.285561 -0.689400 -v 0.060003 0.078581 0.057476 -vn -0.685697 -0.461767 -0.562665 -v 0.060003 0.078257 0.057693 -vn -0.685694 -0.562670 -0.461764 -v 0.060003 0.073243 0.062707 -vn 0.630263 -0.297104 -0.717285 -v 0.064303 0.073750 0.062200 -vn 0.546918 -0.773461 0.320373 -v 0.064303 0.073243 0.062707 -vn -0.665721 -0.689401 -0.285554 -v 0.060003 0.073026 0.063032 -vn -0.685696 -0.724383 -0.071347 -v 0.060003 0.072950 0.063414 -vn -0.685695 -0.724383 0.071349 -v 0.060003 0.072950 0.101986 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.072950 0.078700 -vn 0.577350 -0.577350 0.577350 -v 0.064303 0.072950 0.079700 -vn -0.707107 -0.707106 0.000000 -v 0.060003 0.072950 0.074250 -vn -0.707107 -0.707107 0.000000 -v 0.060003 0.072950 0.064300 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.072950 0.068693 -vn 0.577350 -0.577350 0.577350 -v 0.064303 0.072950 0.069203 -vn -0.707106 -0.707107 0.000000 -v 0.060003 0.072950 0.091200 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.072950 0.085700 -vn 0.577350 -0.577350 0.577350 -v 0.064303 0.072950 0.086700 -vn 0.577350 -0.577350 -0.577350 -v 0.064303 0.072950 0.096197 -vn 0.577350 -0.577350 0.577350 -v 0.064303 0.072950 0.096707 -vn -0.683679 -0.696291 0.218543 -v 0.060003 0.073026 0.102368 -vn -0.685611 -0.635291 0.355447 -v 0.060003 0.073041 0.102404 -vn -0.687733 -0.556719 0.465926 -v 0.060003 0.073243 0.102693 -vn -0.685697 -0.461768 0.562663 -v 0.060003 0.078257 0.107707 -vn 0.546918 -0.773459 -0.320377 -v 0.064303 0.073243 0.102693 -vn 0.630263 -0.297109 0.717284 -v 0.064303 0.073750 0.103200 -vn -0.665719 -0.285564 0.689400 -v 0.060003 0.078581 0.107924 -vn -0.685696 -0.071347 0.724383 -v 0.060003 0.078964 0.108000 -vn 0.128917 -0.096454 0.986953 -v 0.091753 0.080464 0.108000 -vn 0.128916 0.096454 0.986953 -v 0.091753 0.101034 0.108000 -vn -0.707107 -0.000000 0.707107 -v 0.060003 0.083795 0.108000 -vn -0.095840 -0.678874 0.727973 -v 0.059853 0.091232 0.108000 -vn -0.094249 0.090010 0.991471 -v 0.059853 0.093632 0.108000 -vn -0.039550 0.062571 0.997257 -v 0.060003 0.093632 0.108000 -vn -0.707107 0.000000 0.707107 -v 0.060003 0.100182 0.108000 -vn -0.707107 0.000000 0.707107 -v 0.060003 0.102295 0.108000 -vn -0.685696 0.071347 0.724383 -v 0.060003 0.102536 0.108000 -vn -0.041899 -0.065065 0.997001 -v 0.060003 0.086895 0.108000 -vn -0.089389 -0.097189 0.991244 -v 0.059853 0.086895 0.108000 -vn -0.094249 0.679793 0.727323 -v 0.059853 0.089295 0.108000 -vn -0.665719 0.285564 0.689400 -v 0.060003 0.102918 0.107924 -vn -0.685697 0.461769 0.562662 -v 0.060003 0.103243 0.107707 -vn -0.685696 0.562666 0.461766 -v 0.060003 0.108257 0.102693 -vn 0.630262 0.297111 0.717283 -v 0.064303 0.107750 0.103200 -vn 0.546918 0.773458 -0.320380 -v 0.064303 0.108257 0.102693 -vn -0.665720 0.689400 0.285561 -v 0.060003 0.108474 0.102368 -vn -0.685695 0.724383 0.071349 -v 0.060003 0.108550 0.101986 -vn 0.577350 0.577350 0.577350 -v 0.064303 0.108550 0.069203 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.108550 0.068693 -vn -0.707107 0.707107 0.000000 -v 0.060003 0.108550 0.091200 -vn -0.707108 0.707106 0.000000 -v 0.060003 0.108550 0.074250 -vn -0.707107 0.707107 0.000000 -v 0.060003 0.108550 0.064300 -vn 0.577350 0.577350 0.577350 -v 0.064303 0.108550 0.086700 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.108550 0.085700 -vn 0.577350 0.577350 0.577350 -v 0.064303 0.108550 0.096707 -vn 0.577350 0.577350 -0.577350 -v 0.064303 0.108550 0.096197 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.102295 0.062900 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.078695 0.062900 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.078695 0.064300 -vn -0.906149 -0.297002 0.301137 -v 0.060003 0.078257 0.102693 -vn -0.707107 -0.707107 0.000000 -v 0.060003 0.078257 0.102400 -vn -0.770261 0.637729 -0.000000 -v 0.060003 0.074400 0.082700 -vn -0.770260 0.552290 -0.318866 -v 0.060003 0.104581 0.100375 -vn -0.770264 0.637725 -0.000001 -v 0.060003 0.104400 0.099700 -vn -0.707107 0.707107 0.000000 -v 0.060003 0.103243 0.102400 -vn -0.770262 -0.552289 -0.318862 -v 0.060003 0.084221 0.060875 -vn -0.770262 -0.318862 -0.552289 -v 0.060003 0.083727 0.061369 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.083795 0.062900 -vn -0.770261 -0.000000 -0.637729 -v 0.060003 0.083052 0.061550 -vn -0.770262 0.318862 -0.552289 -v 0.060003 0.082377 0.061369 -vn -0.770262 0.552289 -0.318862 -v 0.060003 0.081883 0.060875 -vn -0.770261 0.637729 0.000000 -v 0.060003 0.081702 0.060200 -vn -0.770262 0.552289 0.318863 -v 0.060003 0.081883 0.059525 -vn -0.770262 0.318862 0.552289 -v 0.060003 0.082377 0.059031 -vn -0.770261 0.000000 0.637729 -v 0.060003 0.083052 0.058850 -vn -0.770262 -0.318862 0.552289 -v 0.060003 0.083727 0.059031 -vn -0.770262 -0.552289 0.318863 -v 0.060003 0.084221 0.059525 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.090845 0.062900 -vn -0.770261 -0.637729 0.000000 -v 0.060003 0.084402 0.060200 -vn -0.770261 -0.552288 -0.318865 -v 0.060003 0.099995 0.105925 -vn -0.770261 -0.318865 -0.552288 -v 0.060003 0.099464 0.106456 -vn -0.770263 0.000000 -0.637727 -v 0.060003 0.098739 0.106650 -vn -0.770261 0.318865 -0.552288 -v 0.060003 0.098014 0.106456 -vn -0.763903 0.322639 0.558888 -v 0.060003 0.094932 0.107652 -vn -0.760730 0.560698 0.326969 -v 0.060003 0.095884 0.106700 -vn -0.770263 0.552289 -0.318862 -v 0.060003 0.097484 0.105925 -vn -0.770261 -0.318865 0.552288 -v 0.060003 0.099464 0.103944 -vn -0.707107 0.000000 0.707107 -v 0.060003 0.100182 0.102693 -vn -0.770263 0.000000 0.637727 -v 0.060003 0.098739 0.103750 -vn -0.685705 0.084244 0.722988 -v 0.060003 0.098739 0.102693 -vn -0.770261 0.318865 0.552288 -v 0.060003 0.098014 0.103944 -vn -0.667078 0.372494 0.645179 -v 0.060003 0.097486 0.103029 -vn -0.770263 0.552289 0.318862 -v 0.060003 0.097484 0.104475 -vn -0.667078 0.645179 0.372494 -v 0.060003 0.096568 0.103946 -vn -0.770260 0.637730 0.000000 -v 0.060003 0.097289 0.105200 -vn -0.685705 0.722988 0.084244 -v 0.060003 0.096232 0.105200 -vn -0.731202 0.677511 0.079511 -v 0.060003 0.096232 0.105400 -vn -0.770261 -0.552288 0.318865 -v 0.060003 0.099995 0.104475 -vn -0.770263 -0.637727 0.000000 -v 0.060003 0.100189 0.105200 -vn -0.707107 0.000000 0.707107 -v 0.060003 0.102295 0.102693 -vn -0.770262 0.552289 0.318862 -v 0.060003 0.097484 0.064975 -vn -0.770260 0.318866 0.552290 -v 0.060003 0.098014 0.064444 -vn -0.876729 0.297319 -0.378085 -v 0.060003 0.096749 0.065700 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.090845 0.064300 -vn -0.707107 0.000000 -0.707107 -v 0.060003 0.090845 0.065700 -vn -0.707109 0.000455 -0.707105 -v 0.060003 0.100182 0.067691 -vn -0.770261 -0.552288 -0.318865 -v 0.060003 0.099995 0.066425 -vn -0.770263 -0.318862 -0.552289 -v 0.060003 0.099464 0.066956 -vn -0.684690 0.086679 -0.723661 -v 0.060003 0.098739 0.067690 -vn -0.770260 0.000000 -0.637730 -v 0.060003 0.098739 0.067150 -vn -0.664953 0.373443 -0.646821 -v 0.060003 0.097744 0.067423 -vn -0.770263 0.318862 -0.552289 -v 0.060003 0.098014 0.066956 -vn -0.664954 0.646821 -0.373443 -v 0.060003 0.097016 0.066695 -vn -0.770263 0.552289 -0.318862 -v 0.060003 0.097484 0.066425 -vn -0.770260 0.637730 0.000000 -v 0.060003 0.097289 0.065700 -vn -0.770263 -0.637727 0.000000 -v 0.060003 0.100189 0.065700 -vn -0.707105 0.000453 -0.707108 -v 0.060003 0.102295 0.067692 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.102295 0.064300 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.100182 0.062900 -vn -0.770263 0.000000 0.637727 -v 0.060003 0.098739 0.064250 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.100182 0.064300 -vn -0.770261 -0.318865 0.552288 -v 0.060003 0.099464 0.064444 -vn -0.770261 -0.552288 0.318865 -v 0.060003 0.099995 0.064975 -vn -0.770263 0.000000 0.637727 -v 0.060003 0.081739 0.064250 -vn -0.770261 0.318865 0.552288 -v 0.060003 0.081014 0.064444 -vn -0.770261 0.552288 0.318865 -v 0.060003 0.080484 0.064975 -vn -0.707107 0.000000 -0.707107 -v 0.060003 0.083795 0.065700 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.083795 0.064300 -vn -0.770261 -0.552288 0.318865 -v 0.060003 0.082995 0.064975 -vn -0.876492 -0.297401 -0.378568 -v 0.060003 0.083729 0.065700 -vn -0.770263 -0.637727 0.000000 -v 0.060003 0.083189 0.065700 -vn -0.663437 -0.646491 -0.376698 -v 0.060003 0.083463 0.066695 -vn -0.770261 -0.552288 -0.318865 -v 0.060003 0.082995 0.066425 -vn -0.663436 -0.376702 -0.646489 -v 0.060003 0.082734 0.067423 -vn -0.770263 -0.318862 -0.552289 -v 0.060003 0.082464 0.066956 -vn -0.684304 -0.087156 -0.723969 -v 0.060003 0.081739 0.067690 -vn -0.770260 0.000000 -0.637730 -v 0.060003 0.081739 0.067150 -vn -0.707107 -0.000588 -0.707106 -v 0.060003 0.078695 0.067693 -vn -0.770263 0.318862 -0.552289 -v 0.060003 0.081014 0.066956 -vn -0.770261 0.552288 -0.318865 -v 0.060003 0.080484 0.066425 -vn -0.770263 0.637727 0.000000 -v 0.060003 0.080289 0.065700 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.107825 0.102400 -vn -0.904534 0.301511 0.301511 -v 0.060003 0.103243 0.102693 -vn -0.707107 0.707107 0.000000 -v 0.060003 0.103243 0.091200 -vn -0.770260 0.552291 0.318865 -v 0.060003 0.104581 0.099025 -vn -0.770263 0.318864 0.552286 -v 0.060003 0.105075 0.098531 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.107825 0.091200 -vn -0.770261 0.000000 0.637729 -v 0.060003 0.105750 0.098350 -vn -0.770262 -0.318862 0.552289 -v 0.060003 0.106425 0.098531 -vn -0.770262 -0.552289 0.318862 -v 0.060003 0.106919 0.099025 -vn -0.770261 -0.637729 -0.000001 -v 0.060003 0.107100 0.099700 -vn -0.770262 -0.552289 -0.318864 -v 0.060003 0.106919 0.100375 -vn -0.770262 -0.318862 -0.552289 -v 0.060003 0.106425 0.100869 -vn -0.770261 -0.000000 -0.637729 -v 0.060003 0.105750 0.101050 -vn -0.770263 0.318864 -0.552286 -v 0.060003 0.105075 0.100869 -vn -0.770261 0.552288 0.318866 -v 0.060003 0.104581 0.082025 -vn -0.770261 0.318866 0.552288 -v 0.060003 0.105075 0.081531 -vn -0.707107 0.707107 0.000000 -v 0.060003 0.103243 0.074250 -vn -0.770263 0.000000 0.637726 -v 0.060003 0.105750 0.081350 -vn -0.770260 -0.318865 0.552291 -v 0.060003 0.106425 0.081531 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.107825 0.074250 -vn -0.770262 -0.552289 -0.318862 -v 0.060003 0.106919 0.083375 -vn -0.770261 -0.637729 0.000000 -v 0.060003 0.107100 0.082700 -vn -0.770263 -0.552286 0.318864 -v 0.060003 0.106919 0.082025 -vn -0.770263 0.637726 -0.000000 -v 0.060003 0.104400 0.082700 -vn -0.770260 0.552291 -0.318865 -v 0.060003 0.104581 0.083375 -vn -0.770262 -0.318862 -0.552289 -v 0.060003 0.106425 0.083869 -vn -0.770261 -0.000000 -0.637729 -v 0.060003 0.105750 0.084050 -vn -0.770263 0.318864 -0.552286 -v 0.060003 0.105075 0.083869 -vn -0.770260 0.552291 0.318865 -v 0.060003 0.104581 0.065025 -vn -0.770263 0.318864 0.552286 -v 0.060003 0.105075 0.064531 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.107825 0.064300 -vn -0.770261 0.000000 0.637729 -v 0.060003 0.105750 0.064350 -vn -0.770262 -0.318862 0.552289 -v 0.060003 0.106425 0.064531 -vn -0.770262 -0.552289 0.318862 -v 0.060003 0.106919 0.065025 -vn -0.770261 -0.637729 0.000000 -v 0.060003 0.107100 0.065700 -vn -0.770263 -0.552286 -0.318864 -v 0.060003 0.106919 0.066375 -vn -0.770260 -0.318865 -0.552291 -v 0.060003 0.106425 0.066869 -vn -0.770263 -0.000000 -0.637726 -v 0.060003 0.105750 0.067050 -vn -0.904460 0.301719 -0.301527 -v 0.060003 0.103243 0.067693 -vn -0.770261 0.318866 -0.552288 -v 0.060003 0.105075 0.066869 -vn -0.770261 0.552288 -0.318866 -v 0.060003 0.104581 0.066375 -vn -0.770263 0.637726 -0.000000 -v 0.060003 0.104400 0.065700 -vn -0.707107 -0.707107 0.000000 -v 0.060003 0.078257 0.074250 -vn -0.770263 -0.000002 -0.637726 -v 0.060003 0.075750 0.067050 -vn -0.770261 0.318865 -0.552288 -v 0.060003 0.075075 0.066869 -vn -0.770262 0.552289 -0.318862 -v 0.060003 0.074581 0.066375 -vn -0.770261 0.637729 -0.000000 -v 0.060003 0.074400 0.065700 -vn -0.770261 0.552291 0.318861 -v 0.060003 0.074581 0.065025 -vn -0.770264 0.318863 0.552287 -v 0.060003 0.075075 0.064531 -vn -0.770261 -0.000002 0.637729 -v 0.060003 0.075750 0.064350 -vn -0.904436 -0.301784 -0.301532 -v 0.060003 0.078257 0.067693 -vn -0.770262 -0.552289 0.318863 -v 0.060003 0.076919 0.065025 -vn -0.770262 -0.318863 0.552289 -v 0.060003 0.076425 0.064531 -vn -0.770261 -0.637729 0.000000 -v 0.060003 0.077100 0.065700 -vn -0.770263 -0.552286 -0.318864 -v 0.060003 0.076919 0.066375 -vn -0.770260 -0.318866 -0.552290 -v 0.060003 0.076425 0.066869 -vn -0.770262 -0.318863 -0.552289 -v 0.060003 0.076425 0.083869 -vn -0.770261 -0.000002 -0.637729 -v 0.060003 0.075750 0.084050 -vn -0.707107 -0.707107 0.000000 -v 0.060003 0.078257 0.091200 -vn -0.770262 0.552289 0.318862 -v 0.060003 0.074581 0.082025 -vn -0.770261 0.318865 0.552288 -v 0.060003 0.075075 0.081531 -vn -0.770263 -0.000002 0.637726 -v 0.060003 0.075750 0.081350 -vn -0.770260 -0.318866 0.552290 -v 0.060003 0.076425 0.081531 -vn -0.770264 0.318863 -0.552287 -v 0.060003 0.075075 0.083869 -vn -0.770261 0.552291 -0.318861 -v 0.060003 0.074581 0.083375 -vn -0.770263 -0.552286 0.318864 -v 0.060003 0.076919 0.082025 -vn -0.770261 -0.637729 0.000000 -v 0.060003 0.077100 0.082700 -vn -0.770262 -0.552289 -0.318862 -v 0.060003 0.076919 0.083375 -vn -0.770261 -0.000002 0.637729 -v 0.060003 0.075750 0.098350 -vn -0.770262 -0.318863 0.552289 -v 0.060003 0.076425 0.098531 -vn -0.770264 0.318863 0.552287 -v 0.060003 0.075075 0.098531 -vn -0.770264 0.318863 -0.552286 -v 0.060003 0.075075 0.100869 -vn -0.770261 0.552291 -0.318862 -v 0.060003 0.074581 0.100375 -vn -0.770261 0.637729 -0.000001 -v 0.060003 0.074400 0.099700 -vn -0.770261 0.552291 0.318861 -v 0.060003 0.074581 0.099025 -vn -0.770262 -0.552289 0.318862 -v 0.060003 0.076919 0.099025 -vn -0.770261 -0.637729 -0.000001 -v 0.060003 0.077100 0.099700 -vn -0.770262 -0.552289 -0.318864 -v 0.060003 0.076919 0.100375 -vn -0.770262 -0.318863 -0.552289 -v 0.060003 0.076425 0.100869 -vn -0.770261 -0.000002 -0.637729 -v 0.060003 0.075750 0.101050 -vn -0.770263 0.637727 0.000000 -v 0.060003 0.080289 0.105200 -vn -0.770261 0.552288 0.318865 -v 0.060003 0.080484 0.104475 -vn -0.707107 0.009776 0.707039 -v 0.060003 0.078695 0.102687 -vn -0.770261 0.318865 0.552288 -v 0.060003 0.081014 0.103944 -vn -0.684452 -0.079162 0.724748 -v 0.060003 0.081739 0.102645 -vn -0.770263 0.000000 0.637727 -v 0.060003 0.081739 0.103750 -vn -0.667290 -0.372355 0.645039 -v 0.060003 0.083017 0.102987 -vn -0.770261 -0.318865 0.552288 -v 0.060003 0.082464 0.103944 -vn -0.667226 -0.645054 0.372444 -v 0.060003 0.083952 0.103922 -vn -0.770261 0.552288 -0.318865 -v 0.060003 0.080484 0.105925 -vn -0.770261 0.318865 -0.552288 -v 0.060003 0.081014 0.106456 -vn -0.770263 0.000000 -0.637727 -v 0.060003 0.081739 0.106650 -vn -0.770261 -0.318865 -0.552288 -v 0.060003 0.082464 0.106456 -vn -0.770261 -0.552288 0.318865 -v 0.060003 0.082995 0.104475 -vn -0.770263 -0.637727 0.000000 -v 0.060003 0.083189 0.105200 -vn -0.770261 -0.552288 -0.318865 -v 0.060003 0.082995 0.105925 -vn -0.764197 -0.321824 0.558957 -v 0.060003 0.085595 0.107652 -vn -0.685783 -0.722937 0.084054 -v 0.060003 0.084295 0.105200 -vn -0.731203 -0.677510 0.079513 -v 0.060003 0.084295 0.105400 -vn -0.760728 -0.560699 0.326970 -v 0.060003 0.084643 0.106700 -vn -0.770261 -0.318865 0.552288 -v 0.060003 0.082464 0.064444 -vn -1.000000 0.000000 0.000000 -v 0.060003 0.107825 0.062900 -vn -0.770263 -0.318864 -0.552286 -v 0.060003 0.099500 0.061369 -vn -0.770261 -0.000000 -0.637729 -v 0.060003 0.098825 0.061550 -vn -0.770262 0.318862 -0.552289 -v 0.060003 0.098150 0.061369 -vn -0.770262 0.552289 -0.318862 -v 0.060003 0.097656 0.060875 -vn -0.770261 0.637729 0.000000 -v 0.060003 0.097475 0.060200 -vn -0.770262 0.552289 0.318863 -v 0.060003 0.097656 0.059525 -vn -0.770262 0.318862 0.552289 -v 0.060003 0.098150 0.059031 -vn -0.770261 0.000000 0.637729 -v 0.060003 0.098825 0.058850 -vn -0.770263 -0.318864 0.552286 -v 0.060003 0.099500 0.059031 -vn -0.770260 -0.552290 0.318865 -v 0.060003 0.099995 0.059525 -vn -0.770264 -0.637725 0.000000 -v 0.060003 0.100175 0.060200 -vn -0.770260 -0.552291 -0.318865 -v 0.060003 0.099995 0.060875 -vn -0.653228 0.757161 -0.000000 -v 0.061003 0.097289 0.105200 -vn -0.653226 0.655723 -0.378580 -v 0.061003 0.097484 0.105925 -vn -0.653227 0.378582 -0.655721 -v 0.061003 0.098014 0.106456 -vn -0.653226 0.000000 -0.757163 -v 0.061003 0.098739 0.106650 -vn -0.653227 -0.378582 -0.655721 -v 0.061003 0.099464 0.106456 -vn -0.653227 -0.655721 -0.378582 -v 0.061003 0.099995 0.105925 -vn -0.653226 -0.757163 0.000000 -v 0.061003 0.100189 0.105200 -vn -0.653227 -0.655721 0.378582 -v 0.061003 0.099995 0.104475 -vn -0.653227 -0.378582 0.655721 -v 0.061003 0.099464 0.103944 -vn -0.653226 0.000000 0.757163 -v 0.061003 0.098739 0.103750 -vn -0.653227 0.378582 0.655721 -v 0.061003 0.098014 0.103944 -vn -0.653226 0.655723 0.378579 -v 0.061003 0.097484 0.104475 -vn -1.000000 0.000000 0.000000 -v 0.061003 0.098739 0.105200 -vn -0.653226 0.757163 0.000000 -v 0.061003 0.080289 0.105200 -vn -0.653227 0.655721 -0.378582 -v 0.061003 0.080484 0.105925 -vn -0.653227 0.378582 -0.655721 -v 0.061003 0.081014 0.106456 -vn -0.653226 0.000000 -0.757163 -v 0.061003 0.081739 0.106650 -vn -0.653227 -0.378582 -0.655721 -v 0.061003 0.082464 0.106456 -vn -0.653227 -0.655721 -0.378582 -v 0.061003 0.082995 0.105925 -vn -0.653226 -0.757163 0.000000 -v 0.061003 0.083189 0.105200 -vn -0.653227 -0.655721 0.378582 -v 0.061003 0.082995 0.104475 -vn -0.653227 -0.378582 0.655721 -v 0.061003 0.082464 0.103944 -vn -0.653226 0.000000 0.757163 -v 0.061003 0.081739 0.103750 -vn -0.653227 0.378582 0.655721 -v 0.061003 0.081014 0.103944 -vn -0.653227 0.655721 0.378582 -v 0.061003 0.080484 0.104475 -vn -1.000000 0.000000 0.000000 -v 0.061003 0.081739 0.105200 -vn -0.653228 0.757161 -0.000000 -v 0.061003 0.097289 0.065700 -vn -0.653226 0.655723 -0.378580 -v 0.061003 0.097484 0.066425 -vn -0.653226 0.378579 -0.655723 -v 0.061003 0.098014 0.066956 -vn -0.653228 0.000000 -0.757161 -v 0.061003 0.098739 0.067150 -vn -0.653226 -0.378580 -0.655723 -v 0.061003 0.099464 0.066956 -vn -0.653227 -0.655721 -0.378582 -v 0.061003 0.099995 0.066425 -vn -0.653226 -0.757163 0.000000 -v 0.061003 0.100189 0.065700 -vn -0.653227 -0.655721 0.378582 -v 0.061003 0.099995 0.064975 -vn -0.653227 -0.378582 0.655721 -v 0.061003 0.099464 0.064444 -vn -0.653226 0.000000 0.757163 -v 0.061003 0.098739 0.064250 -vn -0.653227 0.378582 0.655721 -v 0.061003 0.098014 0.064444 -vn -0.653226 0.655723 0.378579 -v 0.061003 0.097484 0.064975 -vn -1.000000 0.000000 0.000000 -v 0.061003 0.098739 0.065700 -vn -0.653226 0.757163 0.000000 -v 0.061003 0.080289 0.065700 -vn -0.653227 0.655721 -0.378582 -v 0.061003 0.080484 0.066425 -vn -0.653226 0.378579 -0.655723 -v 0.061003 0.081014 0.066956 -vn -0.653228 0.000000 -0.757161 -v 0.061003 0.081739 0.067150 -vn -0.653226 -0.378580 -0.655723 -v 0.061003 0.082464 0.066956 -vn -0.653227 -0.655721 -0.378582 -v 0.061003 0.082995 0.066425 -vn -0.653226 -0.757163 0.000000 -v 0.061003 0.083189 0.065700 -vn -0.653227 -0.655721 0.378582 -v 0.061003 0.082995 0.064975 -vn -0.653227 -0.378582 0.655721 -v 0.061003 0.082464 0.064444 -vn -0.653226 0.000000 0.757163 -v 0.061003 0.081739 0.064250 -vn -0.653227 0.378582 0.655721 -v 0.061003 0.081014 0.064444 -vn -0.653227 0.655721 0.378582 -v 0.061003 0.080484 0.064975 -vn -1.000000 0.000000 0.000000 -v 0.061003 0.081739 0.065700 -vn -0.130962 0.989242 0.065191 -v 0.058253 0.096232 0.105200 -vn -0.137413 0.956763 0.256363 -v 0.058253 0.096318 0.104551 -vn -0.131949 0.858453 0.495628 -v 0.058253 0.096568 0.103946 -vn -0.137412 0.700400 0.700399 -v 0.058253 0.096966 0.103427 -vn -0.131954 0.495628 0.858453 -v 0.058253 0.097486 0.103029 -vn -0.137413 0.256362 0.956763 -v 0.058253 0.098090 0.102778 -vn -0.129779 0.063344 0.989518 -v 0.058253 0.098739 0.102693 -vn -0.088336 0.704340 0.704345 -v 0.058253 0.103243 0.102693 -vn -0.067517 0.705756 -0.705231 -v 0.058253 0.103243 0.067693 -vn -0.129858 0.063759 -0.989481 -v 0.058253 0.098739 0.067690 -vn -0.135448 0.256435 -0.957024 -v 0.058253 0.098224 0.067622 -vn -0.131954 0.495628 -0.858453 -v 0.058253 0.097744 0.067423 -vn -0.135447 0.700591 -0.700590 -v 0.058253 0.097332 0.067107 -vn -0.131954 0.858451 -0.495631 -v 0.058253 0.097016 0.066695 -vn -0.126543 0.960862 -0.246438 -v 0.058253 0.096817 0.066215 -vn -0.091000 0.657835 -0.747644 -v 0.058253 0.096749 0.065700 -vn -0.090608 -0.649670 -0.754797 -v 0.058253 0.083729 0.065700 -vn -0.092396 -0.954203 -0.284535 -v 0.058253 0.083635 0.066304 -vn -0.086707 -0.472199 -0.877217 -v 0.058253 0.082734 0.067423 -vn -0.105652 -0.628650 -0.770478 -v 0.058253 0.082906 0.067312 -vn -0.105654 -0.770404 -0.628741 -v 0.058253 0.083351 0.066867 -vn -0.070660 -0.883515 -0.463042 -v 0.058253 0.083463 0.066695 -vn -0.102781 -0.279450 -0.954643 -v 0.058253 0.082343 0.067596 -vn -0.098757 -0.077443 -0.992094 -v 0.058253 0.081739 0.067690 -vn -0.089884 -0.703442 -0.705046 -v 0.058253 0.078257 0.067693 -vn -0.067578 -0.700636 0.710311 -v 0.058253 0.078257 0.102693 -vn -0.086164 -0.052403 0.994902 -v 0.058253 0.081739 0.102645 -vn -0.104782 -0.251208 0.962245 -v 0.058253 0.082377 0.102726 -vn -0.098614 -0.434170 0.895417 -v 0.058253 0.083000 0.102977 -vn -0.097078 -0.550787 0.828981 -v 0.058253 0.083017 0.102987 -vn -0.104657 -0.700623 0.705815 -v 0.058253 0.083536 0.103383 -vn -0.098839 -0.859745 0.501068 -v 0.058253 0.083947 0.103914 -vn -0.104380 -0.960184 0.259135 -v 0.058253 0.084206 0.104534 -vn -0.098210 -0.992986 0.065833 -v 0.058253 0.084295 0.105200 -vn -0.120572 -0.991164 0.055285 -v 0.058253 0.084295 0.105400 -vn -0.376480 0.656148 0.654013 -v 0.058553 0.089295 0.107652 -vn -0.650837 0.658413 0.378025 -v 0.057601 0.089295 0.106700 -vn -0.725479 0.682211 0.090931 -v 0.057253 0.089295 0.105400 -vn -0.904534 0.301511 0.301511 -v 0.057253 0.089295 0.105200 -vn -0.904534 -0.301511 0.301511 -v 0.057253 0.091232 0.105200 -vn -0.725479 -0.682211 0.090931 -v 0.057253 0.091232 0.105400 -vn -0.375554 -0.655352 0.655343 -v 0.058553 0.091232 0.107652 -vn -0.650837 -0.658414 0.378025 -v 0.057601 0.091232 0.106700 -vn -0.133355 0.989952 0.047027 -v 0.058253 0.096232 0.105400 -vn -0.746099 0.525437 0.408965 -v 0.057253 0.085621 0.092008 -vn -0.904534 0.301511 -0.301511 -v 0.057253 0.088750 0.087500 -vn -0.904534 0.301511 0.301511 -v 0.057253 0.088750 0.085300 -vn -0.746099 0.364177 -0.557415 -v 0.057253 0.087195 0.101442 -vn -0.746099 0.525438 -0.408965 -v 0.057253 0.085621 0.099992 -vn -0.995955 -0.077643 0.045226 -v 0.057253 0.084811 0.103411 -vn -0.746099 0.629759 0.216196 -v 0.057253 0.084602 0.093889 -vn -0.990256 -0.098512 -0.098427 -v 0.057253 0.079257 0.068692 -vn -0.746099 0.665835 0.000000 -v 0.057253 0.084250 0.096000 -vn -0.990469 -0.100628 0.094050 -v 0.057253 0.079257 0.101679 -vn -0.746099 0.629758 -0.216197 -v 0.057253 0.084602 0.098111 -vn -0.999902 -0.000740 0.013961 -v 0.057253 0.081732 0.101645 -vn -0.996093 -0.020070 0.086002 -v 0.057253 0.082626 0.101757 -vn -0.995955 -0.044327 0.078159 -v 0.057253 0.083493 0.102107 -vn -0.995955 -0.063167 0.063901 -v 0.057253 0.084239 0.102672 -vn -0.989952 -0.133357 0.047026 -v 0.057253 0.085295 0.105400 -vn -0.994201 -0.106344 0.015970 -v 0.057253 0.085295 0.105200 -vn -0.995955 -0.086748 0.023423 -v 0.057253 0.085172 0.104273 -vn -0.746099 -0.450958 -0.489871 -v 0.057253 0.095152 0.100782 -vn -0.746099 -0.267462 -0.609754 -v 0.057253 0.093361 0.101953 -vn -0.746099 -0.054983 -0.663562 -v 0.057253 0.091287 0.102478 -vn -0.746099 0.163452 -0.645461 -v 0.057253 0.089154 0.102301 -vn -0.995677 -0.033726 -0.086543 -v 0.057253 0.082647 0.068549 -vn -0.996244 -0.050758 -0.070154 -v 0.057253 0.083492 0.068122 -vn -0.904534 -0.301512 0.301512 -v 0.057253 0.092750 0.085300 -vn -0.996219 -0.070159 -0.051246 -v 0.057253 0.084161 0.067453 -vn -0.992210 -0.009225 -0.124232 -v 0.057253 0.081739 0.068690 -vn -0.746099 -0.267463 0.609754 -v 0.057253 0.093361 0.090047 -vn -0.746099 -0.450958 0.489871 -v 0.057253 0.095152 0.091218 -vn -0.904534 -0.301511 -0.301511 -v 0.057253 0.092750 0.087500 -vn -0.999999 0.000799 -0.001343 -v 0.057253 0.095921 0.066700 -vn -0.999999 -0.000739 -0.001363 -v 0.057253 0.084557 0.066700 -vn -0.992649 0.103969 -0.061950 -v 0.057253 0.096150 0.067195 -vn -0.992797 0.084717 -0.084717 -v 0.057253 0.096625 0.067814 -vn -0.992797 0.059904 -0.103756 -v 0.057253 0.097244 0.068289 -vn -0.992797 0.031016 -0.115728 -v 0.057253 0.097965 0.068588 -vn -0.990261 0.098446 0.098446 -v 0.057253 0.102243 0.101693 -vn -0.990258 0.098495 -0.098432 -v 0.057253 0.102243 0.068692 -vn -0.746099 -0.656754 0.109593 -v 0.057253 0.097161 0.094930 -vn -0.746099 -0.585584 0.316902 -v 0.057253 0.096467 0.092906 -vn -0.746098 0.364177 0.557415 -v 0.057253 0.087195 0.090558 -vn -0.746099 0.163453 0.645460 -v 0.057253 0.089154 0.089699 -vn -0.746099 -0.054984 0.663561 -v 0.057253 0.091287 0.089522 -vn -0.992102 0.007940 -0.125182 -v 0.057253 0.098739 0.068690 -vn -0.746099 -0.656754 -0.109593 -v 0.057253 0.097161 0.097070 -vn -0.746099 -0.585584 -0.316902 -v 0.057253 0.096467 0.099094 -vn -0.992105 0.007891 0.125162 -v 0.057253 0.098739 0.101693 -vn -0.992797 0.031008 0.115724 -v 0.057253 0.097832 0.101812 -vn -0.990193 0.132044 0.045621 -v 0.057253 0.095232 0.105400 -vn -0.992797 0.084717 0.084717 -v 0.057253 0.096259 0.102720 -vn -0.992797 0.059904 0.103755 -v 0.057253 0.096986 0.102163 -vn -0.992105 0.125162 0.007891 -v 0.057253 0.095232 0.105200 -vn -0.992797 0.115726 0.031009 -v 0.057253 0.095352 0.104292 -vn -0.992797 0.103756 0.059904 -v 0.057253 0.095702 0.103446 -vn -0.865265 -0.492610 0.093011 -v 0.057387 0.084795 0.105400 -vn -0.952821 -0.293337 0.078008 -v 0.057329 0.084912 0.105200 -vn -0.848140 -0.529072 0.027222 -v 0.057387 0.084795 0.105200 -vn -0.710433 -0.698115 0.088997 -v 0.057546 0.084587 0.105200 -vn -0.499306 -0.861199 0.095023 -v 0.057753 0.084428 0.105400 -vn -0.315557 -0.944005 0.096326 -v 0.057870 0.084371 0.105200 -vn -0.529124 -0.846819 0.054090 -v 0.057753 0.084428 0.105200 -vn -0.929789 -0.355739 0.094568 -v 0.057329 0.084802 0.104373 -vn -0.391490 -0.236238 0.889341 -v 0.057870 0.082396 0.102652 -vn -0.335046 -0.042508 0.941242 -v 0.057922 0.081739 0.102588 -vn -0.827579 -0.032852 0.560387 -v 0.057405 0.081736 0.102175 -vn -0.622005 -0.038931 0.782045 -v 0.057628 0.081738 0.102426 -vn -0.711124 -0.173137 0.681415 -v 0.057546 0.082450 0.102442 -vn -0.992293 -0.007030 0.123716 -v 0.057255 0.081732 0.101703 -vn -0.940989 -0.019889 0.337851 -v 0.057329 0.081735 0.102027 -vn -0.930226 -0.085517 0.356885 -v 0.057329 0.082531 0.102128 -vn -0.387188 -0.453999 0.802478 -v 0.057870 0.083037 0.102911 -vn -0.388085 -0.648339 0.655017 -v 0.057870 0.083589 0.103329 -vn -0.388580 -0.796192 0.463770 -v 0.057870 0.084013 0.103876 -vn -0.384958 -0.892540 0.234902 -v 0.057870 0.084280 0.104514 -vn -0.715373 -0.344704 0.607800 -v 0.057546 0.083144 0.102723 -vn -0.715371 -0.491229 0.496930 -v 0.057546 0.083742 0.103174 -vn -0.715371 -0.603784 0.351696 -v 0.057546 0.084200 0.103766 -vn -0.717895 -0.673158 0.177442 -v 0.057546 0.084489 0.104458 -vn -0.929612 -0.181809 0.320573 -v 0.057329 0.083304 0.102440 -vn -0.929611 -0.259091 0.262098 -v 0.057329 0.083970 0.102944 -vn -0.929613 -0.318451 0.185495 -v 0.057329 0.084481 0.103603 -vn -0.288402 -0.672832 0.681265 -v 0.058058 0.078276 0.102673 -vn -0.580248 -0.573146 0.578633 -v 0.057753 0.078391 0.102557 -vn -0.791979 -0.429236 0.434196 -v 0.057538 0.078558 0.102388 -vn -0.918185 -0.275896 0.284286 -v 0.057387 0.078757 0.102186 -vn -0.324843 -0.667375 -0.670140 -v 0.057994 0.078291 0.067727 -vn -0.630351 -0.549336 -0.548533 -v 0.057753 0.078391 0.067827 -vn -0.882038 -0.332935 -0.333413 -v 0.057387 0.078757 0.068192 -vn -0.324355 -0.074885 -0.942967 -v 0.057868 0.081739 0.067767 -vn -0.529902 -0.064744 -0.845584 -v 0.057753 0.081739 0.067824 -vn -0.712984 -0.060000 -0.698609 -v 0.057543 0.081739 0.067986 -vn -0.898792 -0.039149 -0.436623 -v 0.057387 0.081739 0.068190 -vn -0.296420 -0.620315 -0.726185 -v 0.057986 0.083765 0.065736 -vn -0.910265 -0.282078 -0.303068 -v 0.057386 0.084180 0.066202 -vn -0.798510 -0.361639 -0.481248 -v 0.057493 0.084053 0.066050 -vn -0.724470 -0.653242 -0.220040 -v 0.057543 0.083918 0.066394 -vn -0.630417 -0.490467 -0.601678 -v 0.057753 0.083859 0.065834 -vn -0.995262 -0.059583 -0.076830 -v 0.057253 0.084553 0.066695 -vn -0.960932 -0.188350 -0.202818 -v 0.057299 0.084336 0.066400 -vn -0.912560 -0.367807 -0.178751 -v 0.057326 0.084230 0.066494 -vn -0.932563 -0.292194 -0.212011 -v 0.057326 0.083857 0.067233 -vn -0.932458 -0.211775 -0.292699 -v 0.057326 0.083271 0.067818 -vn -0.936091 -0.118181 -0.331311 -v 0.057326 0.082533 0.068191 -vn -0.720394 -0.202712 -0.663280 -v 0.057543 0.082433 0.067878 -vn -0.382015 -0.270414 -0.883709 -v 0.057868 0.082367 0.067670 -vn -0.486768 -0.556137 -0.673623 -v 0.057866 0.083806 0.065778 -vn -0.393864 -0.876397 -0.277128 -v 0.057868 0.083709 0.066328 -vn -0.385818 -0.745235 -0.543847 -v 0.057868 0.083414 0.066912 -vn -0.383299 -0.547681 -0.743725 -v 0.057868 0.082951 0.067375 -vn -0.720473 -0.406508 -0.561846 -v 0.057543 0.083079 0.067552 -vn -0.720474 -0.561781 -0.406596 -v 0.057543 0.083591 0.067040 -vn -0.326302 0.627351 -0.707077 -v 0.057986 0.096713 0.065736 -vn -0.600059 0.511454 -0.615097 -v 0.057753 0.096620 0.065834 -vn -0.798199 0.398417 -0.451820 -v 0.057493 0.096426 0.066050 -vn -0.902721 0.261460 -0.341663 -v 0.057386 0.096299 0.066202 -vn -0.965643 0.153729 -0.209524 -v 0.057299 0.096142 0.066400 -vn -0.994915 0.072460 -0.069953 -v 0.057253 0.095925 0.066695 -vn -0.501737 0.212167 -0.838597 -v 0.057753 0.098190 0.067752 -vn -0.446955 0.057508 -0.892706 -v 0.057753 0.098739 0.067824 -vn -0.900236 0.028412 -0.434475 -v 0.057387 0.098739 0.068190 -vn -0.875015 0.421832 -0.237499 -v 0.057387 0.096583 0.066945 -vn -0.840138 0.521906 -0.147586 -v 0.057387 0.096334 0.066344 -vn -0.511007 0.833259 -0.211071 -v 0.057753 0.096688 0.066250 -vn -0.875348 0.341881 -0.341881 -v 0.057387 0.096979 0.067461 -vn -0.875349 0.241747 -0.418716 -v 0.057387 0.097494 0.067856 -vn -0.879324 0.114294 -0.462305 -v 0.057387 0.098095 0.068105 -vn -0.710416 0.039223 -0.702688 -v 0.057543 0.098739 0.067986 -vn -0.509552 0.430221 -0.745162 -v 0.057753 0.097677 0.067539 -vn -0.509550 0.608424 -0.608423 -v 0.057753 0.097237 0.067202 -vn -0.509552 0.745162 -0.430222 -v 0.057753 0.096900 0.066762 -vn -0.288299 0.677258 -0.676909 -v 0.058057 0.103223 0.067712 -vn -0.611452 0.560317 -0.558723 -v 0.057753 0.103109 0.067827 -vn -0.882456 0.335743 -0.329466 -v 0.057387 0.102743 0.068193 -vn -0.326349 0.668331 0.668454 -v 0.057994 0.103209 0.102659 -vn -0.630730 0.548797 0.548636 -v 0.057753 0.103109 0.102559 -vn -0.882034 0.333178 0.333179 -v 0.057387 0.102743 0.102193 -vn -0.870302 0.031949 0.491481 -v 0.057387 0.098739 0.102193 -vn -0.505087 0.055006 0.861314 -v 0.057753 0.098739 0.102559 -vn -0.870302 0.491482 0.031950 -v 0.057387 0.095732 0.105200 -vn -0.875349 0.467018 0.125137 -v 0.057387 0.095835 0.104422 -vn -0.503996 0.861830 0.056903 -v 0.057753 0.096098 0.105200 -vn -0.509549 0.831122 0.222701 -v 0.057753 0.096188 0.104516 -vn -0.509551 0.745164 0.430220 -v 0.057753 0.096452 0.103879 -vn -0.509551 0.608425 0.608422 -v 0.057753 0.096872 0.103332 -vn -0.509550 0.430220 0.745164 -v 0.057753 0.097419 0.102913 -vn -0.509549 0.222697 0.831123 -v 0.057753 0.098056 0.102649 -vn -0.875351 0.418713 0.241743 -v 0.057387 0.096135 0.103696 -vn -0.875348 0.341881 0.341882 -v 0.057387 0.096613 0.103074 -vn -0.875348 0.241746 0.418717 -v 0.057387 0.097236 0.102596 -vn -0.875349 0.125137 0.467017 -v 0.057387 0.097961 0.102295 -vn -0.863203 0.501708 0.056301 -v 0.057387 0.095732 0.105400 -vn -0.500643 0.863743 0.057477 -v 0.057753 0.096098 0.105400 -vn -0.383963 -0.022088 0.923084 -v 0.058629 0.086142 0.107694 -vn -0.556299 -0.103275 0.824540 -v 0.058555 0.086096 0.107653 -vn -0.763292 -0.081261 0.640922 -v 0.057699 0.085569 0.106856 -vn -0.874749 -0.148328 0.461318 -v 0.057603 0.085510 0.106703 -vn -0.966841 -0.127448 0.221304 -v 0.057291 0.085318 0.105842 -vn -0.322506 -0.180471 0.929204 -v 0.058772 0.085973 0.107741 -vn -0.182515 -0.334180 0.924668 -v 0.058932 0.085814 0.107741 -vn -0.637523 -0.376059 0.672417 -v 0.057881 0.085215 0.106972 -vn -0.825639 -0.485904 0.286736 -v 0.057432 0.084833 0.105901 -vn -0.475944 -0.827157 0.298811 -v 0.057792 0.084474 0.105901 -vn -0.129557 -0.962498 0.238355 -v 0.058276 0.084332 0.105842 -vn -0.185670 -0.875883 0.445370 -v 0.058469 0.084645 0.106703 -vn -0.365179 -0.644607 0.671659 -v 0.058174 0.084922 0.106972 -vn -0.080015 -0.755855 0.649832 -v 0.058527 0.084740 0.106856 -vn -0.141557 -0.560079 0.816256 -v 0.059055 0.085597 0.107653 -vn -0.018246 -0.382750 0.923672 -v 0.059100 0.085671 0.107694 -vn -0.962043 0.133773 0.237861 -v 0.057291 0.095209 0.105842 -vn -0.875923 0.185608 0.445318 -v 0.057603 0.095017 0.106703 -vn -0.756052 0.082932 0.649236 -v 0.057699 0.094958 0.106856 -vn -0.560201 0.141417 0.816196 -v 0.058555 0.094431 0.107653 -vn -0.383621 0.021330 0.923244 -v 0.058629 0.094385 0.107694 -vn -0.180467 0.322504 0.929205 -v 0.058932 0.094713 0.107741 -vn -0.334177 0.182517 0.924669 -v 0.058772 0.094553 0.107741 -vn -0.018596 0.382960 0.923578 -v 0.059100 0.094856 0.107694 -vn -0.103419 0.556169 0.824610 -v 0.059055 0.094930 0.107653 -vn -0.078355 0.763109 0.641502 -v 0.058527 0.095786 0.106856 -vn -0.376057 0.637524 0.672416 -v 0.058174 0.095604 0.106972 -vn -0.148391 0.874716 0.461359 -v 0.058469 0.095882 0.106703 -vn -0.123230 0.967279 0.221779 -v 0.058276 0.096194 0.105842 -vn -0.485904 0.825641 0.286731 -v 0.057792 0.096053 0.105901 -vn -0.827160 0.475942 0.298806 -v 0.057432 0.095694 0.105901 -vn -0.644607 0.365178 0.671660 -v 0.057881 0.095311 0.106972 -vn -0.577350 -0.577350 0.577350 -v 0.058253 0.092750 0.085300 -vn -0.577350 -0.577350 -0.577350 -v 0.058253 0.092750 0.087500 -vn -0.577350 0.577350 -0.577350 -v 0.058253 0.088750 0.087500 -vn -0.577350 0.577350 0.577350 -v 0.058253 0.088750 0.085300 -vn -0.668697 -0.709868 -0.221205 -v 0.056253 0.087837 0.095282 -vn -0.680955 -0.732325 0.000000 -v 0.056253 0.087750 0.096000 -vn -0.770263 0.637727 0.000000 -v 0.056253 0.089750 0.096000 -vn -0.668697 -0.709868 0.221206 -v 0.056253 0.087837 0.096718 -vn -0.770261 0.552288 -0.318865 -v 0.056253 0.089884 0.096500 -vn -0.656999 -0.564296 0.499922 -v 0.056253 0.088504 0.097989 -vn -0.770261 0.318866 -0.552288 -v 0.056253 0.090250 0.096866 -vn -0.656999 -0.267333 0.704901 -v 0.056253 0.089686 0.098805 -vn -0.770263 0.000001 -0.637726 -v 0.056253 0.090750 0.097000 -vn -0.657000 0.090871 0.748394 -v 0.056253 0.091112 0.098978 -vn -0.770261 -0.318865 -0.552288 -v 0.056253 0.091250 0.096866 -vn -0.656999 0.428260 0.620441 -v 0.056253 0.092454 0.098469 -vn -0.770262 -0.552288 -0.318865 -v 0.056253 0.091616 0.096500 -vn -0.657000 0.667537 0.350350 -v 0.056253 0.093406 0.097394 -vn -0.770263 -0.637727 0.000000 -v 0.056253 0.091750 0.096000 -vn -0.656999 0.753892 -0.000000 -v 0.056253 0.093750 0.096000 -vn -0.770262 -0.552288 0.318865 -v 0.056253 0.091616 0.095500 -vn -0.657000 0.667537 -0.350350 -v 0.056253 0.093406 0.094606 -vn -0.770262 -0.318865 0.552288 -v 0.056253 0.091250 0.095134 -vn -0.656999 0.428261 -0.620439 -v 0.056253 0.092454 0.093531 -vn -0.770263 0.000001 0.637726 -v 0.056253 0.090750 0.095000 -vn -0.656998 0.090871 -0.748395 -v 0.056253 0.091112 0.093022 -vn -0.770261 0.318866 0.552288 -v 0.056253 0.090250 0.095134 -vn -0.657000 -0.267333 -0.704900 -v 0.056253 0.089686 0.093195 -vn -0.770261 0.552288 0.318865 -v 0.056253 0.089884 0.095500 -vn -0.656998 -0.564296 -0.499923 -v 0.056253 0.088504 0.094011 -vn -0.653226 -0.757163 0.000000 -v 0.057753 0.091750 0.096000 -vn -0.653227 -0.655721 -0.378582 -v 0.057753 0.091616 0.096500 -vn -0.653227 -0.378582 -0.655721 -v 0.057753 0.091250 0.096866 -vn -0.653226 0.000001 -0.757163 -v 0.057753 0.090750 0.097000 -vn -0.653227 0.378583 -0.655720 -v 0.057753 0.090250 0.096866 -vn -0.653227 0.655721 -0.378582 -v 0.057753 0.089884 0.096500 -vn -0.653226 0.757163 0.000000 -v 0.057753 0.089750 0.096000 -vn -0.653227 0.655721 0.378582 -v 0.057753 0.089884 0.095500 -vn -0.653227 0.378583 0.655720 -v 0.057753 0.090250 0.095134 -vn -0.653226 0.000001 0.757163 -v 0.057753 0.090750 0.095000 -vn -0.653227 -0.378582 0.655721 -v 0.057753 0.091250 0.095134 -vn -0.653227 -0.655721 0.378582 -v 0.057753 0.091616 0.095500 -vn -1.000000 0.000000 0.000000 -v 0.057753 0.090750 0.096000 -vn 0.258204 -0.522850 -0.812378 -v 0.069103 0.078964 0.065000 -vn 0.258203 0.522847 -0.812380 -v 0.069103 0.102536 0.065000 -vn 0.737450 0.532867 -0.414994 -v 0.064303 0.104007 0.102200 -vn 0.769741 0.316908 -0.554137 -v 0.064303 0.104372 0.102561 -vn 0.737451 0.087468 -0.669713 -v 0.064303 0.104868 0.102693 -vn 0.737451 0.087468 0.669713 -v 0.064303 0.104868 0.096707 -vn 0.769741 0.316908 0.554137 -v 0.064303 0.104372 0.096839 -vn 0.737450 0.532867 0.414994 -v 0.064303 0.104007 0.097200 -vn -0.301511 -0.904534 0.301511 -v 0.065303 0.102536 0.064700 -vn 0.297108 -0.630262 -0.717284 -v 0.066303 0.102536 0.062200 -vn -0.679087 0.579143 0.451038 -v 0.064303 0.104007 0.063200 -vn 0.301511 0.301511 -0.904534 -v 0.064303 0.107536 0.062200 -vn 0.297108 0.630263 -0.717284 -v 0.066303 0.107536 0.062200 -vn 0.000000 0.707107 0.707107 -v 0.064303 0.107536 0.062707 -vn -0.679085 0.095070 0.727877 -v 0.064303 0.104868 0.062707 -vn -0.653609 0.375726 0.656982 -v 0.064303 0.104372 0.062839 -vn -0.679088 0.579144 -0.451034 -v 0.064303 0.104007 0.068200 -vn -0.653606 0.375726 -0.656985 -v 0.064303 0.104372 0.068561 -vn -0.679087 0.095064 -0.727876 -v 0.064303 0.104868 0.068693 -vn -0.000000 0.707107 -0.707107 -v 0.064303 0.107536 0.068693 -vn 0.000000 0.707107 0.707107 -v 0.064303 0.107536 0.069203 -vn -0.301511 0.904534 0.301511 -v 0.065303 0.078964 0.064700 -vn 0.297108 0.630263 -0.717284 -v 0.066303 0.078964 0.062200 -vn -0.679085 -0.579141 0.451041 -v 0.064303 0.077493 0.063200 -vn -0.653610 -0.375723 0.656982 -v 0.064303 0.077128 0.062839 -vn -0.679085 -0.095071 0.727877 -v 0.064303 0.076631 0.062707 -vn -0.000000 -0.707107 0.707107 -v 0.064303 0.073964 0.062707 -vn 0.301511 -0.301511 -0.904534 -v 0.064303 0.073964 0.062200 -vn 0.297108 -0.630263 -0.717284 -v 0.066303 0.073964 0.062200 -vn -0.679086 -0.095066 -0.727877 -v 0.064303 0.076631 0.068693 -vn -0.653608 -0.375723 -0.656985 -v 0.064303 0.077128 0.068561 -vn -0.679087 -0.579143 -0.451038 -v 0.064303 0.077493 0.068200 -vn 0.000000 -0.707107 0.707107 -v 0.064303 0.073964 0.069203 -vn 0.000000 -0.707107 -0.707107 -v 0.064303 0.073964 0.068693 -vn 0.737451 -0.532864 -0.414996 -v 0.064303 0.077493 0.102200 -vn 0.737452 -0.087469 -0.669712 -v 0.064303 0.076631 0.102693 -vn 0.769740 -0.316907 -0.554140 -v 0.064303 0.077128 0.102561 -vn 0.737451 -0.532864 0.414995 -v 0.064303 0.077493 0.097200 -vn 0.769740 -0.316907 0.554140 -v 0.064303 0.077128 0.096839 -vn 0.737452 -0.087469 0.669712 -v 0.064303 0.076631 0.096707 -vn 0.727802 0.571463 -0.379123 -v 0.064303 0.103876 0.085176 -vn 0.749487 0.434731 -0.499279 -v 0.064303 0.104099 0.085454 -vn 0.749489 0.232088 -0.620001 -v 0.064303 0.104405 0.085637 -vn 0.727799 0.061326 -0.683043 -v 0.064303 0.104756 0.085700 -vn 0.727799 -0.061326 -0.683043 -v 0.064303 0.076744 0.085700 -vn 0.749489 -0.232088 -0.620002 -v 0.064303 0.077095 0.085637 -vn 0.749487 -0.434731 -0.499278 -v 0.064303 0.077401 0.085454 -vn 0.727802 -0.571463 -0.379123 -v 0.064303 0.077624 0.085176 -vn 0.727799 -0.061326 0.683043 -v 0.064303 0.076744 0.079700 -vn 0.000000 -0.707107 -0.707107 -v 0.064303 0.073964 0.078700 -vn 0.727801 -0.571458 0.379133 -v 0.064303 0.077624 0.080224 -vn 0.749484 -0.434728 0.499285 -v 0.064303 0.077401 0.079946 -vn 0.749491 -0.232093 0.619997 -v 0.064303 0.077095 0.079763 -vn 0.904534 -0.301511 0.301511 -v 0.064303 0.073964 0.079200 -vn -0.577350 0.577350 -0.577350 -v 0.064303 0.107536 0.066700 -vn -0.577350 0.577350 0.577350 -v 0.064303 0.107536 0.064700 -vn -0.301511 0.904534 0.301511 -v 0.065303 0.107536 0.064700 -vn -0.301511 0.904534 -0.301511 -v 0.065303 0.107536 0.066700 -vn 0.577350 0.577350 0.577350 -v 0.074103 0.107536 0.079200 -vn 0.577350 0.577350 -0.577350 -v 0.074103 0.107536 0.078200 -vn 0.577350 0.577350 0.577350 -v 0.074103 0.107536 0.066000 -vn 0.577350 0.577350 -0.577350 -v 0.074103 0.107536 0.065000 -vn 0.227458 0.804186 -0.549133 -v 0.069103 0.107536 0.065000 -vn 0.577350 0.577350 0.577350 -v 0.076103 0.107536 0.077200 -vn 0.577350 0.577350 -0.577350 -v 0.076103 0.107536 0.067000 -vn 0.904534 0.301511 0.301511 -v 0.076103 0.103036 0.067500 -vn 0.904534 0.301511 -0.301511 -v 0.076103 0.103036 0.076700 -vn 0.577350 0.577350 -0.577350 -v 0.076103 0.101536 0.074600 -vn 0.577350 0.577350 0.577350 -v 0.076103 0.101536 0.069600 -vn 0.904534 -0.301511 0.301511 -v 0.076103 0.107036 0.067500 -vn 0.904534 -0.301511 -0.301511 -v 0.076103 0.107036 0.076700 -vn 0.577350 -0.577350 0.577350 -v 0.071103 0.107036 0.067500 -vn 0.577350 -0.577350 -0.577350 -v 0.071103 0.107036 0.076700 -vn 0.577350 0.577350 -0.577350 -v 0.071103 0.103036 0.076700 -vn 0.577350 0.577350 0.577350 -v 0.071103 0.103036 0.067500 -vn -0.577350 0.577350 0.577350 -v 0.085103 0.101536 0.069600 -vn -0.577350 0.577350 -0.577350 -v 0.085103 0.101536 0.074600 -vn -0.577350 -0.577350 0.577350 -v 0.064303 0.073964 0.064700 -vn 0.227458 -0.804186 -0.549133 -v 0.069103 0.073964 0.065000 -vn 0.577350 -0.577350 -0.577350 -v 0.074103 0.073964 0.065000 -vn 0.577350 -0.577350 0.577350 -v 0.074103 0.073964 0.066000 -vn 0.301511 -0.904534 0.301511 -v 0.071103 0.073964 0.066000 -vn 0.301511 -0.904534 -0.301511 -v 0.071103 0.073964 0.067000 -vn 0.577350 -0.577350 -0.577350 -v 0.074103 0.073964 0.078200 -vn 0.577350 -0.577350 0.577350 -v 0.074103 0.073964 0.079200 -vn -0.577350 -0.577350 -0.577350 -v 0.064303 0.073964 0.066700 -vn -0.301511 -0.904534 -0.301511 -v 0.065303 0.073964 0.066700 -vn -0.301511 -0.904534 0.301511 -v 0.065303 0.073964 0.064700 -vn 0.577350 -0.577350 -0.577350 -v 0.076103 0.073964 0.067000 -vn 0.577350 -0.577350 0.577350 -v 0.076103 0.073964 0.077200 -vn 0.904534 -0.301511 -0.301511 -v 0.076103 0.078464 0.076700 -vn 0.904534 0.301511 -0.301511 -v 0.076103 0.074464 0.076700 -vn 0.904534 0.301511 0.301511 -v 0.076103 0.074464 0.067500 -vn 0.904534 -0.301511 0.301511 -v 0.076103 0.078464 0.067500 -vn 0.577350 -0.577350 0.577350 -v 0.076103 0.079964 0.069600 -vn 0.577350 -0.577350 -0.577350 -v 0.076103 0.079964 0.074600 -vn 0.577350 0.577350 -0.577350 -v 0.071103 0.074464 0.076700 -vn 0.577350 0.577350 0.577350 -v 0.071103 0.074464 0.067500 -vn 0.577350 -0.577350 0.577350 -v 0.071103 0.078464 0.067500 -vn 0.577350 -0.577350 -0.577350 -v 0.071103 0.078464 0.076700 -vn -0.577350 -0.577350 -0.577350 -v 0.085103 0.079964 0.074600 -vn -0.577350 -0.577350 0.577350 -v 0.085103 0.079964 0.069600 -vn 0.729253 -0.339148 -0.594280 -v 0.064303 0.085150 0.062055 -vn 0.752512 -0.474975 -0.456207 -v 0.064303 0.085461 0.061836 -vn 0.752512 -0.610955 -0.245885 -v 0.064303 0.085668 0.061517 -vn 0.729251 -0.681118 -0.065356 -v 0.064303 0.085740 0.061143 -vn 0.729251 0.681118 -0.065356 -v 0.064303 0.095760 0.061143 -vn 0.752512 0.610955 -0.245885 -v 0.064303 0.095832 0.061517 -vn 0.752513 0.474978 -0.456201 -v 0.064303 0.096039 0.061836 -vn 0.729250 0.339155 -0.594280 -v 0.064303 0.096349 0.062055 -vn -0.577350 0.577350 -0.577350 -v 0.085703 0.108550 0.078700 -vn -0.577350 0.577350 0.577350 -v 0.085703 0.108550 0.079700 -vn -0.577350 0.577350 -0.577350 -v 0.085703 0.108550 0.068693 -vn -0.577350 0.577350 0.577350 -v 0.085703 0.108550 0.069203 -vn -0.577350 0.577350 -0.577350 -v 0.085703 0.108550 0.085700 -vn -0.577350 0.577350 0.577350 -v 0.085703 0.108550 0.086700 -vn -0.577350 0.577350 -0.577350 -v 0.085703 0.108550 0.096197 -vn -0.577350 0.577350 0.577350 -v 0.085703 0.108550 0.096707 -vn -0.546918 0.773458 -0.320380 -v 0.085703 0.108257 0.102693 -vn -0.630262 0.297111 0.717283 -v 0.085703 0.107750 0.103200 -vn -0.546918 0.773458 0.320379 -v 0.085703 0.108257 0.062707 -vn -0.630262 0.297110 -0.717283 -v 0.085703 0.107750 0.062200 -vn -0.737450 0.532867 -0.414994 -v 0.085703 0.104007 0.102200 -vn -0.737451 0.087468 -0.669713 -v 0.085703 0.104868 0.102693 -vn -0.769741 0.316908 -0.554137 -v 0.085703 0.104372 0.102561 -vn -0.737450 0.532867 0.414994 -v 0.085703 0.104007 0.097200 -vn -0.769742 0.316908 0.554137 -v 0.085703 0.104372 0.096839 -vn -0.737451 0.087468 0.669713 -v 0.085703 0.104868 0.096707 -vn -0.737452 0.532864 0.414995 -v 0.085703 0.104007 0.063200 -vn -0.769738 0.316911 0.554139 -v 0.085703 0.104372 0.062839 -vn -0.737453 0.087472 0.669710 -v 0.085703 0.104868 0.062707 -vn -0.577350 -0.577350 -0.577350 -v 0.085703 0.102536 0.062200 -vn -0.737451 0.087468 -0.669713 -v 0.085703 0.104868 0.068693 -vn -0.769741 0.316908 -0.554137 -v 0.085703 0.104372 0.068561 -vn -0.737450 0.532867 -0.414994 -v 0.085703 0.104007 0.068200 -vn -0.727799 0.061326 -0.683043 -v 0.085703 0.104756 0.085700 -vn -0.749489 0.232088 -0.620001 -v 0.085703 0.104405 0.085637 -vn -0.749490 0.434717 -0.499286 -v 0.085703 0.104099 0.085454 -vn -0.727797 0.571460 -0.379137 -v 0.085703 0.103876 0.085176 -vn -0.727799 0.061326 0.683043 -v 0.085703 0.104756 0.079700 -vn -0.727801 0.571458 0.379133 -v 0.085703 0.103876 0.080224 -vn -0.749484 0.434728 0.499285 -v 0.085703 0.104099 0.079946 -vn -0.749491 0.232093 0.619997 -v 0.085703 0.104405 0.079763 -vn 0.128917 0.096454 -0.986953 -v 0.091753 0.101034 0.063000 -vn 0.128478 0.379511 -0.916223 -v 0.091753 0.101608 0.063114 -vn 0.128476 0.701246 -0.701247 -v 0.091753 0.102095 0.063439 -vn 0.128475 0.916223 -0.379512 -v 0.091753 0.102420 0.063926 -vn 0.128916 0.986953 -0.096455 -v 0.091753 0.102534 0.064500 -vn 0.128917 0.986953 0.096455 -v 0.091753 0.102534 0.106500 -vn 0.128476 0.916224 0.379511 -v 0.091753 0.102420 0.107074 -vn 0.128475 0.701250 0.701243 -v 0.091753 0.102095 0.107561 -vn 0.128477 0.379515 0.916222 -v 0.091753 0.101608 0.107886 -vn 0.128478 -0.379515 0.916221 -v 0.091753 0.079890 0.107886 -vn 0.128476 -0.701250 0.701243 -v 0.091753 0.079403 0.107561 -vn 0.128475 -0.916223 0.379512 -v 0.091753 0.079078 0.107074 -vn 0.128916 -0.986953 0.096455 -v 0.091753 0.078964 0.106500 -vn 0.128917 -0.986953 -0.096455 -v 0.091753 0.078964 0.064500 -vn 0.128476 -0.916224 -0.379511 -v 0.091753 0.079078 0.063926 -vn 0.128475 -0.701247 -0.701247 -v 0.091753 0.079403 0.063439 -vn 0.128477 -0.379510 -0.916224 -v 0.091753 0.079890 0.063114 -vn 0.128916 -0.096454 -0.986953 -v 0.091753 0.080464 0.063000 -vn 0.989212 0.103586 -0.103587 -v 0.092753 0.101388 0.064146 -vn 0.989211 0.135343 -0.056062 -v 0.092753 0.101496 0.064309 -vn 0.990257 0.138488 -0.014547 -v 0.092753 0.101534 0.064500 -vn 0.753767 -0.464670 0.464669 -v 0.092753 0.093931 0.092818 -vn 0.904534 -0.301511 -0.301511 -v 0.092753 0.096534 0.076000 -vn 0.753766 -0.607120 0.251478 -v 0.092753 0.094907 0.094278 -vn 0.753768 -0.657141 0.000000 -v 0.092753 0.095249 0.096000 -vn 0.989211 0.135344 0.056062 -v 0.092753 0.101496 0.106691 -vn 0.753766 -0.464670 -0.464670 -v 0.092753 0.093931 0.099182 -vn 0.990257 0.138489 0.014548 -v 0.092753 0.101534 0.106500 -vn 0.753767 -0.607120 -0.251478 -v 0.092753 0.094907 0.097722 -vn 0.989212 -0.056058 -0.135342 -v 0.092753 0.080273 0.064038 -vn 0.990257 -0.014547 -0.138488 -v 0.092753 0.080464 0.064000 -vn 0.989212 -0.103588 -0.103587 -v 0.092753 0.080111 0.064146 -vn 0.904534 0.301511 0.301511 -v 0.092753 0.084534 0.070000 -vn 0.904534 -0.301511 0.301512 -v 0.092753 0.096534 0.070000 -vn 0.990257 0.014547 -0.138488 -v 0.092753 0.101034 0.064000 -vn 0.989212 0.056060 -0.135342 -v 0.092753 0.101226 0.064038 -vn 0.904534 0.301511 -0.301511 -v 0.092753 0.084534 0.076000 -vn 0.753766 0.464670 0.464670 -v 0.092753 0.087567 0.092818 -vn 0.753767 0.607120 0.251478 -v 0.092753 0.086592 0.094278 -vn 0.990257 -0.014548 0.138488 -v 0.092753 0.080464 0.107000 -vn 0.989211 -0.056060 0.135344 -v 0.092753 0.080273 0.106962 -vn 0.753767 0.464669 -0.464670 -v 0.092753 0.087567 0.099182 -vn 0.753767 0.251478 -0.607120 -v 0.092753 0.089027 0.100157 -vn 0.753768 0.000000 -0.657141 -v 0.092753 0.090749 0.100500 -vn 0.990257 0.014547 0.138488 -v 0.092753 0.101034 0.107000 -vn 0.753767 -0.251478 -0.607119 -v 0.092753 0.092471 0.100157 -vn 0.989211 0.056064 0.135343 -v 0.092753 0.101226 0.106962 -vn 0.989212 0.103584 0.103586 -v 0.092753 0.101388 0.106854 -vn 0.753768 -0.251478 0.607119 -v 0.092753 0.092471 0.091843 -vn 0.753767 0.000000 0.657142 -v 0.092753 0.090749 0.091500 -vn 0.753767 0.251478 0.607119 -v 0.092753 0.089027 0.091843 -vn 0.990257 -0.138488 0.014547 -v 0.092753 0.079964 0.106500 -vn 0.990257 -0.138489 -0.014548 -v 0.092753 0.079964 0.064500 -vn 0.989212 -0.135344 -0.056059 -v 0.092753 0.080002 0.064309 -vn 0.989212 -0.103587 0.103585 -v 0.092753 0.080111 0.106854 -vn 0.989212 -0.135343 0.056060 -v 0.092753 0.080002 0.106691 -vn 0.753767 0.607120 -0.251478 -v 0.092753 0.086592 0.097722 -vn 0.753767 0.657142 0.000000 -v 0.092753 0.086249 0.096000 -vn 0.491660 0.866654 -0.084741 -v 0.092253 0.102400 0.064500 -vn 0.486553 0.807149 -0.334332 -v 0.092253 0.102296 0.063977 -vn 0.858057 0.510973 -0.051426 -v 0.092619 0.102034 0.064500 -vn 0.852052 0.483611 -0.200318 -v 0.092619 0.101958 0.064117 -vn 0.852052 0.370141 -0.370138 -v 0.092619 0.101741 0.063793 -vn 0.852049 0.200317 -0.483617 -v 0.092619 0.101417 0.063576 -vn 0.858058 0.051421 -0.510972 -v 0.092619 0.101034 0.063500 -vn 0.486551 0.617764 -0.617767 -v 0.092253 0.102000 0.063534 -vn 0.486550 0.334328 -0.807152 -v 0.092253 0.101557 0.063238 -vn 0.491659 0.084741 -0.866655 -v 0.092253 0.101034 0.063134 -vn 0.858058 0.510971 0.051424 -v 0.092619 0.102034 0.106500 -vn 0.491659 0.866655 0.084741 -v 0.092253 0.102400 0.106500 -vn 0.858058 -0.051420 -0.510971 -v 0.092619 0.080464 0.063500 -vn 0.491658 -0.084740 -0.866655 -v 0.092253 0.080464 0.063134 -vn 0.491659 0.084741 0.866654 -v 0.092253 0.101034 0.107866 -vn 0.486554 0.334332 0.807148 -v 0.092253 0.101557 0.107762 -vn 0.858057 0.051425 0.510973 -v 0.092619 0.101034 0.107500 -vn 0.852051 0.200322 0.483612 -v 0.092619 0.101417 0.107424 -vn 0.852052 0.370139 0.370141 -v 0.092619 0.101741 0.107207 -vn 0.852052 0.483611 0.200321 -v 0.092619 0.101958 0.106883 -vn 0.486553 0.617766 0.617763 -v 0.092253 0.102000 0.107466 -vn 0.486551 0.807150 0.334331 -v 0.092253 0.102296 0.107023 -vn 0.486550 -0.334328 -0.807152 -v 0.092253 0.079941 0.063238 -vn 0.852049 -0.200317 -0.483617 -v 0.092619 0.080081 0.063576 -vn 0.852049 -0.370146 -0.370141 -v 0.092619 0.079757 0.063793 -vn 0.852052 -0.483611 -0.200317 -v 0.092619 0.079540 0.064117 -vn 0.858058 -0.510971 -0.051425 -v 0.092619 0.079464 0.064500 -vn 0.486551 -0.617764 -0.617766 -v 0.092253 0.079498 0.063534 -vn 0.486552 -0.807149 -0.334332 -v 0.092253 0.079202 0.063977 -vn 0.491659 -0.866655 -0.084741 -v 0.092253 0.079098 0.064500 -vn 0.858058 -0.051424 0.510971 -v 0.092619 0.080464 0.107500 -vn 0.491659 -0.084741 0.866655 -v 0.092253 0.080464 0.107866 -vn 0.858057 -0.510972 0.051425 -v 0.092619 0.079464 0.106500 -vn 0.491659 -0.866654 0.084741 -v 0.092253 0.079098 0.106500 -vn 0.486551 -0.807150 0.334331 -v 0.092253 0.079202 0.107023 -vn 0.852051 -0.483613 0.200317 -v 0.092619 0.079540 0.106883 -vn 0.852050 -0.370143 0.370142 -v 0.092619 0.079757 0.107207 -vn 0.852051 -0.200320 0.483612 -v 0.092619 0.080081 0.107424 -vn 0.486550 -0.617767 0.617765 -v 0.092253 0.079498 0.107466 -vn 0.486552 -0.334333 0.807149 -v 0.092253 0.079941 0.107762 -vn 0.364736 -0.838902 0.403994 -v 0.092003 0.087596 0.097519 -vn 0.364739 -0.580537 0.727971 -v 0.092003 0.088567 0.098736 -vn 0.364738 -0.207191 0.907765 -v 0.092003 0.089970 0.099412 -vn 0.364738 0.207191 0.907765 -v 0.092003 0.091528 0.099412 -vn 0.364739 0.580538 0.727971 -v 0.092003 0.092931 0.098736 -vn 0.364741 0.838900 0.403993 -v 0.092003 0.093903 0.097519 -vn 0.364736 0.931111 -0.000001 -v 0.092003 0.094249 0.096000 -vn 0.364739 0.838902 -0.403992 -v 0.092003 0.093903 0.094481 -vn 0.364739 0.580537 -0.727971 -v 0.092003 0.092931 0.093264 -vn 0.364738 0.207191 -0.907765 -v 0.092003 0.091528 0.092588 -vn 0.364738 -0.207191 -0.907765 -v 0.092003 0.089970 0.092588 -vn 0.364739 -0.580537 -0.727972 -v 0.092003 0.088567 0.093264 -vn 0.364734 -0.838903 -0.403993 -v 0.092003 0.087596 0.094481 -vn 0.364735 -0.931111 0.000000 -v 0.092003 0.087249 0.096000 -vn 0.403292 -0.824451 0.397034 -v 0.092253 0.087821 0.097410 -vn 0.403296 -0.570536 0.715430 -v 0.092253 0.088723 0.098541 -vn 0.403294 -0.203621 0.892128 -v 0.092253 0.090026 0.099169 -vn 0.403294 0.203621 0.892128 -v 0.092253 0.091472 0.099169 -vn 0.403296 0.570537 0.715430 -v 0.092253 0.092776 0.098541 -vn 0.403299 0.824448 0.397034 -v 0.092253 0.093677 0.097410 -vn 0.403293 0.915071 -0.000000 -v 0.092253 0.093999 0.096000 -vn 0.403295 0.824449 -0.397036 -v 0.092253 0.093677 0.094590 -vn 0.403296 0.570536 -0.715430 -v 0.092253 0.092776 0.093459 -vn 0.403294 0.203621 -0.892128 -v 0.092253 0.091472 0.092831 -vn 0.403294 -0.203621 -0.892128 -v 0.092253 0.090026 0.092831 -vn 0.403296 -0.570535 -0.715432 -v 0.092253 0.088723 0.093459 -vn 0.403290 -0.824451 -0.397036 -v 0.092253 0.087821 0.094590 -vn 0.403291 -0.915072 0.000000 -v 0.092253 0.087499 0.096000 -vn 0.784916 -0.133177 0.605121 -v 0.097753 0.091037 0.098735 -vn 0.580607 0.177374 0.794628 -v 0.097753 0.091373 0.098934 -vn 0.788212 0.258624 0.558423 -v 0.097753 0.091024 0.098736 -vn 0.580607 0.008285 0.814142 -v 0.097753 0.090749 0.099000 -vn 0.784904 -0.256115 0.564208 -v 0.097753 0.090462 0.098735 -vn 0.788226 0.136837 0.599980 -v 0.097753 0.090449 0.098734 -vn 0.580607 -0.161158 0.798075 -v 0.097753 0.090125 0.098934 -vn 0.784873 -0.367900 0.498622 -v 0.097753 0.089899 0.098615 -vn 0.788255 0.009036 0.615282 -v 0.097753 0.089887 0.098611 -vn 0.580605 -0.323573 0.747126 -v 0.097753 0.089529 0.098741 -vn 0.784897 -0.463479 0.411247 -v 0.097753 0.089374 0.098382 -vn 0.788234 -0.119044 0.603752 -v 0.097753 0.089363 0.098375 -vn 0.580606 -0.471840 0.663524 -v 0.097753 0.088986 0.098427 -vn 0.784903 -0.538840 0.305906 -v 0.097753 0.088909 0.098044 -vn 0.788227 -0.241961 0.565821 -v 0.097753 0.088899 0.098035 -vn 0.580606 -0.599485 0.550921 -v 0.097753 0.088520 0.098007 -vn 0.784929 -0.590616 0.187240 -v 0.097753 0.088524 0.097616 -vn 0.788200 -0.354284 0.503212 -v 0.097753 0.088517 0.097606 -vn 0.580607 -0.700925 0.414246 -v 0.097753 0.088151 0.097500 -vn 0.784932 -0.616635 0.060367 -v 0.097753 0.088237 0.097119 -vn 0.788197 -0.451162 0.418568 -v 0.097753 0.088232 0.097107 -vn 0.580607 -0.771735 0.259464 -v 0.097753 0.087896 0.096927 -vn 0.784943 -0.615699 -0.069132 -v 0.097753 0.088059 0.096572 -vn 0.788188 -0.528321 0.315651 -v 0.097753 0.088057 0.096559 -vn 0.580606 -0.808816 0.093348 -v 0.097753 0.087766 0.096314 -vn 0.784946 -0.587869 -0.195625 -v 0.097753 0.087999 0.096000 -vn 0.788184 -0.582408 0.198915 -v 0.097753 0.087999 0.095987 -vn 0.580606 -0.810549 -0.076863 -v 0.097753 0.087766 0.095686 -vn 0.784933 -0.534346 -0.313616 -v 0.097753 0.088059 0.095428 -vn 0.788198 -0.611024 0.073441 -v 0.097753 0.088062 0.095416 -vn 0.580606 -0.776856 -0.243703 -v 0.097753 0.087896 0.095073 -vn 0.784920 -0.457460 -0.417888 -v 0.097753 0.088237 0.094881 -vn 0.788206 -0.612928 -0.055230 -v 0.097753 0.088242 0.094870 -vn 0.580606 -0.709209 -0.399898 -v 0.097753 0.088151 0.094500 -vn 0.784980 -0.360650 -0.503724 -v 0.097753 0.088524 0.094384 -vn 0.788150 -0.588162 -0.181343 -v 0.097753 0.088532 0.094373 -vn 0.580606 -0.610569 -0.538612 -v 0.097753 0.088520 0.093993 -vn 0.784950 -0.247988 -0.567764 -v 0.097753 0.088909 0.093956 -vn 0.788180 -0.537537 -0.299710 -v 0.097753 0.088919 0.093948 -vn 0.580607 -0.485247 -0.653782 -v 0.097753 0.088986 0.093573 -vn 0.784926 -0.124483 -0.606956 -v 0.097753 0.089374 0.093618 -vn 0.788203 -0.463421 -0.404939 -v 0.097753 0.089385 0.093612 -vn 0.580606 -0.338716 -0.740384 -v 0.097753 0.089529 0.093259 -vn 0.784906 0.004482 -0.619599 -v 0.097753 0.089899 0.093385 -vn 0.788222 -0.369045 -0.492455 -v 0.097753 0.089912 0.093381 -vn 0.580607 -0.177374 -0.794628 -v 0.097753 0.090125 0.093066 -vn 0.784916 0.133177 -0.605121 -v 0.097753 0.090462 0.093265 -vn 0.788212 -0.258624 -0.558423 -v 0.097753 0.090475 0.093264 -vn 0.580607 -0.008285 -0.814142 -v 0.097753 0.090749 0.093000 -vn 0.784904 0.256115 -0.564208 -v 0.097753 0.091037 0.093265 -vn 0.788226 -0.136837 -0.599980 -v 0.097753 0.091049 0.093266 -vn 0.580607 0.161158 -0.798075 -v 0.097753 0.091373 0.093066 -vn 0.784944 0.367710 -0.498651 -v 0.097753 0.091599 0.093385 -vn 0.788182 -0.009200 -0.615374 -v 0.097753 0.091611 0.093389 -vn 0.580606 0.323579 -0.747123 -v 0.097753 0.091969 0.093259 -vn 0.784961 0.463315 -0.411309 -v 0.097753 0.092124 0.093618 -vn 0.788167 0.118916 -0.603865 -v 0.097753 0.092135 0.093625 -vn 0.580607 0.471846 -0.663519 -v 0.097753 0.092513 0.093573 -vn 0.784958 0.538714 -0.305987 -v 0.097753 0.092589 0.093956 -vn 0.788172 0.241868 -0.565938 -v 0.097753 0.092599 0.093965 -vn 0.580606 0.599485 -0.550922 -v 0.097753 0.092979 0.093993 -vn 0.784929 0.590616 -0.187240 -v 0.097753 0.092974 0.094384 -vn 0.788203 0.354278 -0.503213 -v 0.097753 0.092982 0.094394 -vn 0.580605 0.700925 -0.414248 -v 0.097753 0.093347 0.094500 -vn 0.785002 0.616531 -0.060517 -v 0.097753 0.093261 0.094881 -vn 0.788128 0.451115 -0.418747 -v 0.097753 0.093267 0.094893 -vn 0.580607 0.771735 -0.259464 -v 0.097753 0.093602 0.095073 -vn 0.784958 0.615684 0.069094 -v 0.097753 0.093439 0.095428 -vn 0.788170 0.528328 -0.315688 -v 0.097753 0.093442 0.095441 -vn 0.580608 0.808815 -0.093342 -v 0.097753 0.093733 0.095686 -vn 0.784944 0.587874 0.195621 -v 0.097753 0.093499 0.096000 -vn 0.788180 0.582415 -0.198908 -v 0.097753 0.093499 0.096013 -vn 0.580608 0.810547 0.076869 -v 0.097753 0.093733 0.096314 -vn 0.784931 0.534350 0.313614 -v 0.097753 0.093439 0.096572 -vn 0.788198 0.611024 -0.073441 -v 0.097753 0.093436 0.096584 -vn 0.580606 0.776855 0.243706 -v 0.097753 0.093602 0.096927 -vn 0.784990 0.457504 0.417710 -v 0.097753 0.093261 0.097119 -vn 0.788141 0.613026 0.055075 -v 0.097753 0.093256 0.097130 -vn 0.580607 0.709213 0.399890 -v 0.097753 0.093347 0.097500 -vn 0.784934 0.360604 0.503829 -v 0.097753 0.092974 0.097616 -vn 0.788194 0.588078 0.181427 -v 0.097753 0.092966 0.097627 -vn 0.580607 0.610573 0.538605 -v 0.097753 0.092979 0.098007 -vn 0.784947 0.247995 0.567764 -v 0.097753 0.092589 0.098044 -vn 0.788180 0.537537 0.299710 -v 0.097753 0.092580 0.098052 -vn 0.580607 0.485247 0.653782 -v 0.097753 0.092513 0.098427 -vn 0.784926 0.124483 0.606956 -v 0.097753 0.092124 0.098382 -vn 0.788203 0.463421 0.404939 -v 0.097753 0.092113 0.098388 -vn 0.580606 0.338716 0.740384 -v 0.097753 0.091969 0.098741 -vn 0.784906 -0.004482 0.619599 -v 0.097753 0.091599 0.098615 -vn 0.788222 0.369045 0.492455 -v 0.097753 0.091587 0.098619 -vn 0.770263 0.637726 -0.000000 -v 0.097753 0.089749 0.096000 -vn 0.653226 0.757163 0.000000 -v 0.093753 0.089749 0.096000 -vn 0.770261 0.552289 -0.318865 -v 0.097753 0.089883 0.096500 -vn 0.653227 0.655721 -0.378582 -v 0.093753 0.089883 0.096500 -vn 0.770263 0.318864 -0.552287 -v 0.097753 0.090249 0.096866 -vn 0.653227 0.378582 -0.655721 -v 0.093753 0.090249 0.096866 -vn 0.770265 -0.000000 -0.637724 -v 0.097753 0.090749 0.097000 -vn 0.653226 0.000000 -0.757163 -v 0.093753 0.090749 0.097000 -vn 0.770262 -0.318865 -0.552288 -v 0.097753 0.091249 0.096866 -vn 0.653227 -0.378582 -0.655721 -v 0.093753 0.091249 0.096866 -vn 0.770261 -0.552289 -0.318865 -v 0.097753 0.091615 0.096500 -vn 0.653227 -0.655721 -0.378582 -v 0.093753 0.091615 0.096500 -vn 0.770260 -0.637730 0.000000 -v 0.097753 0.091749 0.096000 -vn 0.653226 -0.757163 -0.000000 -v 0.093753 0.091749 0.096000 -vn 0.770261 -0.552289 0.318865 -v 0.097753 0.091615 0.095500 -vn 0.653227 -0.655721 0.378582 -v 0.093753 0.091615 0.095500 -vn 0.770263 -0.318864 0.552287 -v 0.097753 0.091249 0.095134 -vn 0.653227 -0.378582 0.655721 -v 0.093753 0.091249 0.095134 -vn 0.770265 0.000000 0.637724 -v 0.097753 0.090749 0.095000 -vn 0.653226 -0.000000 0.757163 -v 0.093753 0.090749 0.095000 -vn 0.770263 0.318864 0.552286 -v 0.097753 0.090249 0.095134 -vn 0.653227 0.378582 0.655721 -v 0.093753 0.090249 0.095134 -vn 0.770260 0.552290 0.318866 -v 0.097753 0.089883 0.095500 -vn 0.653227 0.655721 0.378582 -v 0.093753 0.089883 0.095500 -vn 1.000000 0.000000 0.000000 -v 0.093753 0.090749 0.096000 -vn 0.577350 0.577350 0.577350 -v 0.092503 0.084534 0.070000 -vn 0.577350 0.577350 -0.577350 -v 0.092503 0.084534 0.076000 -vn 0.577350 -0.577350 -0.577350 -v 0.092503 0.096534 0.076000 -vn 0.577351 -0.577350 0.577350 -v 0.092503 0.096534 0.070000 -vn -0.770264 0.388027 -0.506092 -v 0.092753 0.087295 0.089119 -vn -0.770258 0.589091 -0.244284 -v 0.092753 0.087093 0.088856 -vn -1.000000 -0.000001 -0.000000 -v 0.092753 0.085990 0.090581 -vn -0.688983 -0.456671 0.562809 -v 0.092753 0.083347 0.105122 -vn -0.688983 -0.357807 0.630299 -v 0.092753 0.084950 0.106216 -vn -1.000000 -0.000001 0.000000 -v 0.092753 0.087057 0.104923 -vn -0.739079 0.236136 -0.630874 -v 0.092753 0.092151 0.092254 -vn -0.739079 0.397588 -0.543770 -v 0.092753 0.093110 0.092771 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.094025 0.092130 -vn -0.739077 0.529552 -0.416340 -v 0.092753 0.093894 0.093528 -vn -0.739079 0.622240 -0.258031 -v 0.092753 0.094444 0.094468 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.095802 0.096417 -vn -0.739079 0.668781 -0.080581 -v 0.092753 0.094720 0.095521 -vn -0.739078 -0.126034 -0.661725 -v 0.092753 0.090001 0.092071 -vn -1.000000 0.000000 -0.000000 -v 0.092753 0.090277 0.088804 -vn -0.739079 -0.299890 -0.603181 -v 0.092753 0.088968 0.092418 -vn -0.739078 -0.451507 -0.499905 -v 0.092753 0.088068 0.093032 -vn -0.739078 -0.569636 -0.359553 -v 0.092753 0.087367 0.093865 -vn -1.000000 -0.000000 0.000000 -v 0.092753 0.081826 0.092308 -vn -0.770257 0.589092 -0.244284 -v 0.092753 0.082765 0.093187 -vn -0.770263 0.632304 0.082981 -v 0.092753 0.082722 0.092858 -vn -0.770262 -0.082984 0.632305 -v 0.092753 0.083440 0.092306 -vn -0.770256 0.244282 0.589094 -v 0.092753 0.083111 0.092350 -vn -0.770265 0.506092 0.388024 -v 0.092753 0.082848 0.092552 -vn -0.770261 -0.388024 0.506098 -v 0.092753 0.083747 0.092433 -vn -0.770262 -0.589088 0.244280 -v 0.092753 0.083949 0.092696 -vn -0.770260 -0.632307 -0.082992 -v 0.092753 0.083992 0.093025 -vn -0.739078 -0.645519 -0.192532 -v 0.092753 0.086916 0.094857 -vn -0.770261 -0.506098 -0.388024 -v 0.092753 0.083865 0.093331 -vn -0.770262 -0.244280 -0.589087 -v 0.092753 0.083602 0.093533 -vn -1.000000 -0.000001 -0.000000 -v 0.092753 0.083553 0.096472 -vn -0.739077 -0.673527 -0.011234 -v 0.092753 0.086750 0.095933 -vn -0.770260 0.082988 -0.632307 -v 0.092753 0.083274 0.093577 -vn -0.770265 0.388024 -0.506092 -v 0.092753 0.082967 0.093450 -vn -0.739078 -0.319840 0.592846 -v 0.092753 0.088850 0.099520 -vn -0.739080 -0.467927 0.484567 -v 0.092753 0.087971 0.098877 -vn -1.000000 -0.000002 -0.000000 -v 0.092753 0.085330 0.100759 -vn -0.732374 -0.580451 0.355956 -v 0.092753 0.087297 0.098021 -vn -0.732375 -0.662013 0.159264 -v 0.092753 0.086880 0.097015 -vn -1.000000 -0.000001 0.000000 -v 0.092753 0.086168 0.102780 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.090333 0.101053 -vn -0.739079 -0.148033 0.657152 -v 0.092753 0.089870 0.099902 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.094619 0.099275 -vn -0.739078 0.613290 0.278638 -v 0.092753 0.094391 0.097655 -vn -0.739078 0.515373 0.433767 -v 0.092753 0.093809 0.098576 -vn -0.739080 0.379229 0.556728 -v 0.092753 0.093001 0.099306 -vn -0.739077 0.214964 0.638400 -v 0.092753 0.092026 0.099791 -vn -0.739079 0.034756 0.672721 -v 0.092753 0.090956 0.099995 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.096640 0.098437 -vn -0.739078 0.665723 0.102843 -v 0.092753 0.094702 0.096611 -vn -0.770260 0.506095 0.388032 -v 0.092753 0.097630 0.092546 -vn -0.770259 0.244286 0.589088 -v 0.092753 0.097894 0.092344 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.096168 0.091241 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.097946 0.095528 -vn -0.770262 -0.244280 -0.589087 -v 0.092753 0.098384 0.093528 -vn -0.770261 0.082991 -0.632305 -v 0.092753 0.098056 0.093571 -vn -0.770262 -0.506097 -0.388024 -v 0.092753 0.098647 0.093325 -vn -0.688984 0.723366 -0.045198 -v 0.092753 0.102474 0.095267 -vn -0.770261 -0.632306 -0.082992 -v 0.092753 0.098774 0.093019 -vn -0.688984 0.706061 -0.163642 -v 0.092753 0.102193 0.093348 -vn -0.770263 -0.589087 0.244279 -v 0.092753 0.098731 0.092690 -vn -0.688983 0.669497 -0.277624 -v 0.092753 0.101601 0.091500 -vn -0.770262 -0.388024 0.506097 -v 0.092753 0.098529 0.092427 -vn -0.688984 0.614670 -0.384034 -v 0.092753 0.100712 0.089775 -vn -0.770264 -0.082984 0.632303 -v 0.092753 0.098222 0.092300 -vn -0.688984 0.543077 -0.479968 -v 0.092753 0.099551 0.088221 -vn -0.770262 0.388024 -0.506097 -v 0.092753 0.097749 0.093444 -vn -0.770260 0.589087 -0.244287 -v 0.092753 0.097547 0.093181 -vn -0.770266 0.632299 0.082990 -v 0.092753 0.097504 0.092852 -vn -0.688984 0.657693 0.304534 -v 0.092753 0.101409 0.100936 -vn -0.688984 0.698847 0.192129 -v 0.092753 0.102076 0.099114 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.099672 0.099692 -vn -0.688983 0.720940 0.074481 -v 0.092753 0.102434 0.097207 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.098784 0.097549 -vn -0.770261 -0.632306 -0.082992 -v 0.092753 0.094449 0.103473 -vn -0.770260 -0.506101 -0.388022 -v 0.092753 0.094322 0.103780 -vn -0.688984 0.433482 0.580857 -v 0.092753 0.097775 0.105415 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.091221 0.103196 -vn -0.770262 0.589087 -0.244280 -v 0.092753 0.093222 0.103635 -vn -0.770260 0.632307 0.082988 -v 0.092753 0.093178 0.103306 -vn -0.770262 0.388024 -0.506097 -v 0.092753 0.093424 0.103898 -vn -0.688984 0.104779 0.717163 -v 0.092753 0.092447 0.107624 -vn -0.770261 0.082992 -0.632306 -v 0.092753 0.093730 0.104025 -vn -0.770265 0.506092 0.388024 -v 0.092753 0.093305 0.103000 -vn -0.770257 0.244284 0.589092 -v 0.092753 0.093568 0.102798 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.095508 0.101419 -vn -0.770264 -0.244282 -0.589083 -v 0.092753 0.094059 0.103982 -vn -0.688984 0.221390 0.690136 -v 0.092753 0.094338 0.107186 -vn -0.688984 0.331963 0.644284 -v 0.092753 0.096130 0.106443 -vn -0.770264 -0.082983 0.632303 -v 0.092753 0.093897 0.102755 -vn -0.770262 -0.388024 0.506097 -v 0.092753 0.094203 0.102881 -vn -0.770263 -0.589087 0.244279 -v 0.092753 0.094405 0.103144 -vn -0.688983 0.598598 0.408634 -v 0.092753 0.100451 0.102623 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.097529 0.100581 -vn -0.688984 0.523175 0.501586 -v 0.092753 0.099229 0.104130 -vn -0.688984 -0.249183 0.680595 -v 0.092753 0.086710 0.107031 -vn -0.688984 -0.133762 0.712326 -v 0.092753 0.088581 0.107546 -vn -0.688984 -0.014693 0.724628 -v 0.092753 0.090511 0.107745 -vn -0.688985 -0.706060 0.163643 -v 0.092753 0.079305 0.098652 -vn -0.688983 -0.669497 0.277624 -v 0.092753 0.079898 0.100500 -vn -1.000000 -0.000001 0.000000 -v 0.092753 0.082221 0.102048 -vn -0.688984 -0.698847 -0.192129 -v 0.092753 0.079422 0.092886 -vn -0.688984 -0.720940 -0.074482 -v 0.092753 0.079064 0.094793 -vn -1.000000 0.000000 0.000000 -v 0.092753 0.080444 0.097761 -vn -0.688983 -0.723367 0.045199 -v 0.092753 0.079025 0.096733 -vn -0.688983 -0.598599 -0.408633 -v 0.092753 0.081047 0.089377 -vn -1.000000 -0.000001 -0.000000 -v 0.092753 0.084701 0.087472 -vn -0.688984 -0.523176 -0.501586 -v 0.092753 0.082269 0.087870 -vn -0.688983 -0.433482 -0.580858 -v 0.092753 0.083723 0.086585 -vn -1.000000 0.000000 -0.000003 -v 0.092753 0.088988 0.085695 -vn -0.688982 -0.104777 -0.717165 -v 0.092753 0.089051 0.084376 -vn -0.688982 -0.221391 -0.690137 -v 0.092753 0.087161 0.084814 -vn -0.688988 -0.331960 -0.644281 -v 0.092753 0.085369 0.085557 -vn -1.000000 0.000000 -0.000001 -v 0.092753 0.091009 0.084857 -vn -0.688984 0.014691 -0.724628 -v 0.092753 0.090987 0.084255 -vn -0.688983 0.133761 -0.712328 -v 0.092753 0.092917 0.084454 -vn -1.000000 -0.000000 -0.000001 -v 0.092753 0.094441 0.087077 -vn -0.688982 0.249182 -0.680597 -v 0.092753 0.094788 0.084969 -vn -0.688984 0.357805 -0.630299 -v 0.092753 0.096549 0.085784 -vn -0.688984 0.456669 -0.562809 -v 0.092753 0.098151 0.086878 -vn -1.000000 -0.000000 -0.000001 -v 0.092753 0.092298 0.087966 -vn -0.688984 -0.657693 -0.304534 -v 0.092753 0.080089 0.091064 -vn -0.770263 0.244279 0.589087 -v 0.092753 0.087439 0.088018 -vn -0.770263 0.506096 0.388023 -v 0.092753 0.087176 0.088220 -vn -0.770265 0.632301 0.082983 -v 0.092753 0.087049 0.088527 -vn -0.770261 -0.632306 -0.082992 -v 0.092753 0.088320 0.088694 -vn -0.770262 -0.506097 -0.388024 -v 0.092753 0.088193 0.089000 -vn -0.770263 -0.244279 -0.589087 -v 0.092753 0.087930 0.089202 -vn -0.770261 0.082992 -0.632306 -v 0.092753 0.087601 0.089245 -vn -0.770261 -0.082992 0.632306 -v 0.092753 0.087768 0.087975 -vn -0.770260 -0.388021 0.506101 -v 0.092753 0.088075 0.088102 -vn -0.770264 -0.589083 0.244282 -v 0.092753 0.088277 0.088365 -vn -0.770260 -0.506101 -0.388022 -v 0.092753 0.094316 0.088998 -vn -0.770264 -0.244282 -0.589083 -v 0.092753 0.094053 0.089200 -vn -0.770261 0.082992 -0.632306 -v 0.092753 0.093724 0.089243 -vn -0.770262 0.388024 -0.506097 -v 0.092753 0.093418 0.089116 -vn -0.770263 0.589087 -0.244279 -v 0.092753 0.093216 0.088853 -vn -0.770261 0.632306 0.082992 -v 0.092753 0.093172 0.088524 -vn -0.770262 0.506096 0.388024 -v 0.092753 0.093299 0.088218 -vn -0.770259 0.244286 0.589088 -v 0.092753 0.093562 0.088016 -vn -0.739079 0.057170 -0.671189 -v 0.092753 0.091089 0.092014 -vn -0.770264 -0.082984 0.632303 -v 0.092753 0.093891 0.087972 -vn -0.770262 -0.388024 0.506097 -v 0.092753 0.094198 0.088099 -vn -0.770263 -0.589087 0.244279 -v 0.092753 0.094400 0.088362 -vn -0.770261 -0.632306 -0.082992 -v 0.092753 0.094443 0.088691 -vn -0.770260 0.388022 -0.506101 -v 0.092753 0.082969 0.099573 -vn -0.770264 0.589083 -0.244282 -v 0.092753 0.082767 0.099310 -vn -0.770261 0.632306 0.082992 -v 0.092753 0.082724 0.098981 -vn -0.770260 0.506101 0.388022 -v 0.092753 0.082851 0.098675 -vn -0.770264 0.244282 0.589083 -v 0.092753 0.083114 0.098472 -vn -0.770261 -0.082992 0.632306 -v 0.092753 0.083443 0.098429 -vn -0.770259 -0.632308 -0.082990 -v 0.092753 0.083995 0.099148 -vn -0.770260 -0.589090 0.244280 -v 0.092753 0.083951 0.098819 -vn -0.770262 -0.388024 0.506097 -v 0.092753 0.083749 0.098556 -vn -0.770260 -0.506099 -0.388025 -v 0.092753 0.083868 0.099454 -vn -0.770261 -0.244281 -0.589088 -v 0.092753 0.083605 0.099656 -vn -0.770261 0.082991 -0.632305 -v 0.092753 0.083276 0.099700 -vn -1.000000 -0.000001 0.000000 -v 0.092753 0.083059 0.104069 -vn -0.770264 0.589083 -0.244282 -v 0.092753 0.097550 0.099304 -vn -0.770261 0.632306 0.082992 -v 0.092753 0.097506 0.098975 -vn -0.770262 0.506097 0.388024 -v 0.092753 0.097633 0.098669 -vn -0.770262 0.244280 0.589087 -v 0.092753 0.097896 0.098467 -vn -0.770261 -0.082991 0.632305 -v 0.092753 0.098225 0.098423 -vn -0.770261 -0.632306 -0.082992 -v 0.092753 0.098777 0.099142 -vn -0.770264 -0.589083 0.244282 -v 0.092753 0.098733 0.098813 -vn -0.770260 -0.388022 0.506101 -v 0.092753 0.098531 0.098550 -vn -0.770260 -0.506101 -0.388022 -v 0.092753 0.098650 0.099448 -vn -0.770264 -0.244282 -0.589083 -v 0.092753 0.098387 0.099650 -vn -0.770261 0.082992 -0.632306 -v 0.092753 0.098058 0.099694 -vn -0.770260 0.388022 -0.506101 -v 0.092753 0.097752 0.099567 -vn -0.770259 0.589088 -0.244286 -v 0.092753 0.087099 0.103638 -vn -0.770266 0.632299 0.082990 -v 0.092753 0.087055 0.103309 -vn -0.770264 -0.589083 0.244282 -v 0.092753 0.088283 0.103147 -vn -0.770261 -0.632306 -0.082992 -v 0.092753 0.088326 0.103476 -vn -0.770257 0.506100 0.388029 -v 0.092753 0.087182 0.103002 -vn -0.770264 0.244282 0.589083 -v 0.092753 0.087445 0.102800 -vn -0.770261 -0.082992 0.632306 -v 0.092753 0.087774 0.102757 -vn -0.770260 -0.388021 0.506101 -v 0.092753 0.088080 0.102884 -vn -0.770262 -0.506097 -0.388024 -v 0.092753 0.088199 0.103782 -vn -0.770262 -0.244280 -0.589087 -v 0.092753 0.087936 0.103984 -vn -0.770260 0.082988 -0.632307 -v 0.092753 0.087607 0.104028 -vn -0.770263 0.388021 -0.506096 -v 0.092753 0.087301 0.103901 -vn -0.688984 -0.614669 0.384035 -v 0.092753 0.080786 0.102225 -vn -0.688984 -0.543076 0.479968 -v 0.092753 0.081947 0.103779 -vn 0.770261 -0.632306 -0.082992 -v 0.094753 0.088320 0.088694 -vn 0.770264 -0.589083 0.244282 -v 0.094753 0.088277 0.088365 -vn 1.000000 -0.000000 0.000000 -v 0.094753 0.090277 0.088804 -vn 0.770265 -0.589084 0.244280 -v 0.094753 0.083951 0.098819 -vn 1.000000 0.000001 0.000000 -v 0.094753 0.083553 0.096472 -vn 1.000000 0.000002 0.000000 -v 0.094753 0.085330 0.100759 -vn 0.688983 -0.723367 0.045199 -v 0.094753 0.079025 0.096733 -vn 0.688984 -0.720939 -0.074482 -v 0.094753 0.079064 0.094793 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.080444 0.097761 -vn 0.688985 0.249183 -0.680593 -v 0.094753 0.094788 0.084969 -vn 0.688984 0.357807 -0.630298 -v 0.094753 0.096549 0.085784 -vn 1.000000 0.000000 0.000001 -v 0.094753 0.094441 0.087077 -vn 0.688984 0.456669 -0.562809 -v 0.094753 0.098151 0.086878 -vn 0.688984 0.543077 -0.479968 -v 0.094753 0.099551 0.088221 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.096168 0.091241 -vn 0.739079 -0.529551 0.416339 -v 0.094753 0.087605 0.098472 -vn 0.739078 -0.397587 0.543771 -v 0.094753 0.088388 0.099229 -vn 0.739078 0.451507 0.499906 -v 0.094753 0.093430 0.098968 -vn 0.739079 0.569635 0.359553 -v 0.094753 0.094132 0.098135 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.094619 0.099275 -vn 0.739078 0.467927 -0.484569 -v 0.094753 0.093528 0.093123 -vn 0.739078 0.319841 -0.592845 -v 0.094753 0.092648 0.092480 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.094025 0.092130 -vn 0.730865 0.576875 -0.364762 -v 0.094753 0.094201 0.093979 -vn 0.722796 0.638353 -0.264710 -v 0.094753 0.094444 0.094468 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.095802 0.096417 -vn 0.730865 0.665719 -0.150513 -v 0.094753 0.094618 0.094985 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.096640 0.098437 -vn 0.739079 0.645518 0.192531 -v 0.094753 0.094582 0.097143 -vn 0.739078 0.673526 0.011233 -v 0.094753 0.094749 0.096067 -vn 0.739079 0.299890 0.603181 -v 0.094753 0.092530 0.099582 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.090333 0.101053 -vn 0.739078 0.126034 0.661725 -v 0.094753 0.091498 0.099929 -vn 1.000000 0.000001 -0.000000 -v 0.094753 0.086168 0.102780 -vn 0.739079 -0.236136 0.630874 -v 0.094753 0.089347 0.099746 -vn 0.739079 -0.057170 0.671189 -v 0.094753 0.090410 0.099986 -vn 0.739078 -0.665723 -0.102841 -v 0.094753 0.086796 0.095389 -vn 0.739080 -0.668781 0.080581 -v 0.094753 0.086778 0.096478 -vn 0.739079 -0.622241 0.258029 -v 0.094753 0.087054 0.097532 -vn 0.770262 -0.632305 -0.082992 -v 0.094753 0.083992 0.093025 -vn 0.770264 -0.589086 0.244279 -v 0.094753 0.083949 0.092696 -vn 1.000000 0.000001 -0.000000 -v 0.094753 0.085990 0.090581 -vn 0.770263 -0.388023 0.506096 -v 0.094753 0.083747 0.092433 -vn 0.770266 -0.082985 0.632301 -v 0.094753 0.083440 0.092306 -vn 0.770259 0.244283 0.589090 -v 0.094753 0.083111 0.092350 -vn 1.000000 0.000000 -0.000000 -v 0.094753 0.081826 0.092308 -vn 0.770265 0.506092 0.388024 -v 0.094753 0.082848 0.092552 -vn 0.770265 0.388024 -0.506092 -v 0.094753 0.082967 0.093450 -vn 0.770257 0.589092 -0.244284 -v 0.094753 0.082765 0.093187 -vn 0.770263 0.632304 0.082981 -v 0.094753 0.082722 0.092858 -vn 0.770260 0.082988 -0.632307 -v 0.094753 0.083274 0.093577 -vn 0.770263 -0.244279 -0.589087 -v 0.094753 0.083602 0.093533 -vn 0.770263 -0.506096 -0.388023 -v 0.094753 0.083865 0.093331 -vn 0.739081 -0.613287 -0.278637 -v 0.094753 0.087107 0.094345 -vn 0.739078 -0.515371 -0.433770 -v 0.094753 0.087689 0.093424 -vn 0.739079 0.148033 -0.657152 -v 0.094753 0.091628 0.092098 -vn 0.739078 -0.034754 -0.672722 -v 0.094753 0.090543 0.092005 -vn 0.739079 -0.214964 -0.638398 -v 0.094753 0.089473 0.092209 -vn 0.739079 -0.379233 -0.556727 -v 0.094753 0.088497 0.092694 -vn 0.770259 0.244286 0.589088 -v 0.094753 0.097894 0.092344 -vn 0.770260 0.506094 0.388032 -v 0.094753 0.097630 0.092546 -vn 0.770264 -0.082984 0.632303 -v 0.094753 0.098222 0.092300 -vn 0.770262 -0.388024 0.506097 -v 0.094753 0.098529 0.092427 -vn 0.688984 0.614670 -0.384034 -v 0.094753 0.100712 0.089775 -vn 0.770263 -0.589087 0.244279 -v 0.094753 0.098731 0.092690 -vn 0.688983 0.669497 -0.277624 -v 0.094753 0.101601 0.091500 -vn 0.770261 -0.632306 -0.082992 -v 0.094753 0.098774 0.093019 -vn 0.688984 0.706061 -0.163642 -v 0.094753 0.102193 0.093348 -vn 0.770262 -0.506097 -0.388024 -v 0.094753 0.098647 0.093325 -vn 0.688984 0.723366 -0.045198 -v 0.094753 0.102474 0.095267 -vn 0.770262 -0.244280 -0.589087 -v 0.094753 0.098384 0.093528 -vn 0.770266 0.632299 0.082990 -v 0.094753 0.097504 0.092852 -vn 0.770260 0.589087 -0.244287 -v 0.094753 0.097547 0.093181 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.097946 0.095528 -vn 0.770262 0.388024 -0.506097 -v 0.094753 0.097749 0.093444 -vn 0.770261 0.082991 -0.632305 -v 0.094753 0.098056 0.093571 -vn 0.688984 0.133761 -0.712326 -v 0.094753 0.092917 0.084454 -vn 1.000000 -0.000001 0.000001 -v 0.094753 0.091009 0.084857 -vn 0.688984 0.014691 -0.724627 -v 0.094753 0.090987 0.084255 -vn 1.000000 -0.000000 0.000003 -v 0.094753 0.088988 0.085695 -vn 0.688986 -0.104777 -0.717161 -v 0.094753 0.089051 0.084376 -vn 1.000000 0.000001 -0.000000 -v 0.094753 0.084701 0.087472 -vn 0.688983 -0.331962 -0.644285 -v 0.094753 0.085369 0.085557 -vn 0.688987 -0.221391 -0.690133 -v 0.094753 0.087161 0.084814 -vn 0.688984 -0.598598 -0.408633 -v 0.094753 0.081047 0.089377 -vn 0.688984 -0.523175 -0.501586 -v 0.094753 0.082269 0.087870 -vn 0.688984 -0.433480 -0.580858 -v 0.094753 0.083723 0.086585 -vn 0.688984 -0.657693 -0.304534 -v 0.094753 0.080089 0.091064 -vn 0.688984 -0.698847 -0.192128 -v 0.094753 0.079422 0.092886 -vn 0.688984 -0.456669 0.562809 -v 0.094753 0.083347 0.105122 -vn 0.688984 -0.543076 0.479968 -v 0.094753 0.081947 0.103779 -vn 1.000000 0.000001 -0.000000 -v 0.094753 0.083059 0.104069 -vn 0.688984 -0.614669 0.384035 -v 0.094753 0.080786 0.102225 -vn 1.000000 0.000001 -0.000000 -v 0.094753 0.082221 0.102048 -vn 0.688983 -0.669497 0.277624 -v 0.094753 0.079898 0.100500 -vn 0.688985 -0.706060 0.163643 -v 0.094753 0.079305 0.098652 -vn 0.770260 0.632307 0.082988 -v 0.094753 0.093178 0.103306 -vn 0.770262 0.589087 -0.244280 -v 0.094753 0.093222 0.103635 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.091221 0.103196 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.095508 0.101419 -vn 0.770263 -0.589087 0.244279 -v 0.094753 0.094405 0.103144 -vn 0.770262 -0.388024 0.506097 -v 0.094753 0.094203 0.102881 -vn 0.688984 0.104779 0.717163 -v 0.094753 0.092447 0.107624 -vn 0.688984 -0.014693 0.724628 -v 0.094753 0.090511 0.107745 -vn 1.000000 0.000001 -0.000000 -v 0.094753 0.087057 0.104923 -vn 0.688984 -0.133762 0.712326 -v 0.094753 0.088581 0.107546 -vn 0.688983 -0.249181 0.680596 -v 0.094753 0.086710 0.107031 -vn 0.770264 -0.082983 0.632303 -v 0.094753 0.093897 0.102755 -vn 0.770257 0.244284 0.589092 -v 0.094753 0.093568 0.102798 -vn 0.770265 0.506092 0.388024 -v 0.094753 0.093305 0.103000 -vn 0.770262 0.388024 -0.506097 -v 0.094753 0.093424 0.103898 -vn 0.770261 0.082992 -0.632306 -v 0.094753 0.093730 0.104025 -vn 0.688984 0.221390 0.690136 -v 0.094753 0.094338 0.107186 -vn 0.770264 -0.244282 -0.589083 -v 0.094753 0.094059 0.103982 -vn 0.688984 0.331963 0.644284 -v 0.094753 0.096130 0.106443 -vn 0.770260 -0.506102 -0.388022 -v 0.094753 0.094322 0.103780 -vn 0.688984 0.433482 0.580857 -v 0.094753 0.097775 0.105415 -vn 0.770261 -0.632306 -0.082992 -v 0.094753 0.094449 0.103473 -vn 0.688984 0.657693 0.304534 -v 0.094753 0.101409 0.100936 -vn 0.688983 0.598598 0.408634 -v 0.094753 0.100451 0.102623 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.099672 0.099692 -vn 0.688984 0.523175 0.501586 -v 0.094753 0.099229 0.104130 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.097529 0.100581 -vn 1.000000 0.000000 0.000000 -v 0.094753 0.098784 0.097549 -vn 0.688983 0.720940 0.074481 -v 0.094753 0.102434 0.097207 -vn 0.688984 0.698847 0.192128 -v 0.094753 0.102076 0.099114 -vn 0.770261 -0.632306 -0.082992 -v 0.094753 0.098777 0.099142 -vn 0.770264 -0.589083 0.244282 -v 0.094753 0.098733 0.098813 -vn 0.770260 -0.388022 0.506102 -v 0.094753 0.098531 0.098550 -vn 0.770261 -0.082991 0.632305 -v 0.094753 0.098225 0.098423 -vn 0.770262 0.244280 0.589087 -v 0.094753 0.097896 0.098467 -vn 0.770262 0.506097 0.388024 -v 0.094753 0.097633 0.098669 -vn 0.770261 0.632306 0.082992 -v 0.094753 0.097506 0.098975 -vn 0.770264 0.589083 -0.244282 -v 0.094753 0.097550 0.099304 -vn 0.770260 0.388022 -0.506102 -v 0.094753 0.097752 0.099567 -vn 0.770261 0.082992 -0.632306 -v 0.094753 0.098058 0.099694 -vn 0.770264 -0.244282 -0.589083 -v 0.094753 0.098387 0.099650 -vn 0.770260 -0.506102 -0.388022 -v 0.094753 0.098650 0.099448 -vn 0.770264 -0.589083 0.244282 -v 0.094753 0.088283 0.103147 -vn 0.770260 -0.388021 0.506101 -v 0.094753 0.088080 0.102884 -vn 0.770263 0.388021 -0.506096 -v 0.094753 0.087301 0.103901 -vn 0.770259 0.589088 -0.244286 -v 0.094753 0.087099 0.103638 -vn 0.770266 0.632299 0.082990 -v 0.094753 0.087055 0.103309 -vn 0.770261 -0.082992 0.632306 -v 0.094753 0.087774 0.102757 -vn 0.770264 0.244282 0.589083 -v 0.094753 0.087445 0.102800 -vn 0.770257 0.506100 0.388029 -v 0.094753 0.087182 0.103002 -vn 0.770260 0.082988 -0.632307 -v 0.094753 0.087607 0.104028 -vn 0.770262 -0.244280 -0.589087 -v 0.094753 0.087936 0.103984 -vn 0.770262 -0.506097 -0.388024 -v 0.094753 0.088199 0.103782 -vn 0.770261 -0.632306 -0.082992 -v 0.094753 0.088326 0.103476 -vn 0.770262 0.082992 -0.632304 -v 0.094753 0.083276 0.099700 -vn 0.770264 -0.244280 -0.589085 -v 0.094753 0.083605 0.099656 -vn 0.770262 -0.388024 0.506097 -v 0.094753 0.083749 0.098556 -vn 0.770261 -0.082992 0.632306 -v 0.094753 0.083443 0.098429 -vn 0.770264 0.244282 0.589083 -v 0.094753 0.083114 0.098472 -vn 0.770263 -0.506096 -0.388023 -v 0.094753 0.083868 0.099454 -vn 0.770264 -0.632303 -0.082991 -v 0.094753 0.083995 0.099148 -vn 0.770260 0.506102 0.388022 -v 0.094753 0.082851 0.098675 -vn 0.688985 -0.357804 0.630298 -v 0.094753 0.084950 0.106216 -vn 0.770261 0.632306 0.082992 -v 0.094753 0.082724 0.098981 -vn 0.770264 0.589083 -0.244282 -v 0.094753 0.082767 0.099310 -vn 0.770260 0.388021 -0.506101 -v 0.094753 0.082969 0.099573 -vn 0.770263 -0.589087 0.244279 -v 0.094753 0.094400 0.088362 -vn 0.770262 -0.388024 0.506097 -v 0.094753 0.094198 0.088099 -vn 0.770261 0.632306 0.082992 -v 0.094753 0.093172 0.088524 -vn 0.770263 0.589087 -0.244279 -v 0.094753 0.093216 0.088853 -vn 1.000000 0.000000 0.000001 -v 0.094753 0.092298 0.087966 -vn 0.770261 -0.632306 -0.082992 -v 0.094753 0.094443 0.088691 -vn 0.770264 -0.082984 0.632303 -v 0.094753 0.093891 0.087972 -vn 0.770259 0.244286 0.589088 -v 0.094753 0.093562 0.088016 -vn 0.770262 0.506096 0.388024 -v 0.094753 0.093299 0.088218 -vn 0.770262 0.388024 -0.506097 -v 0.094753 0.093418 0.089116 -vn 0.770261 0.082992 -0.632306 -v 0.094753 0.093724 0.089243 -vn 0.770264 -0.244282 -0.589083 -v 0.094753 0.094053 0.089200 -vn 0.770260 -0.506102 -0.388022 -v 0.094753 0.094316 0.088998 -vn 0.770260 -0.388021 0.506101 -v 0.094753 0.088075 0.088102 -vn 0.770263 0.632304 0.082984 -v 0.094753 0.087049 0.088527 -vn 0.770257 0.589092 -0.244284 -v 0.094753 0.087093 0.088856 -vn 0.770264 0.388027 -0.506092 -v 0.094753 0.087295 0.089119 -vn 0.770261 -0.082992 0.632306 -v 0.094753 0.087768 0.087975 -vn 0.770262 0.244280 0.589087 -v 0.094753 0.087439 0.088018 -vn 0.770261 0.506098 0.388025 -v 0.094753 0.087176 0.088220 -vn 0.770261 0.082992 -0.632306 -v 0.094753 0.087601 0.089245 -vn 0.770263 -0.244279 -0.589087 -v 0.094753 0.087930 0.089202 -vn 0.770262 -0.506097 -0.388024 -v 0.094753 0.088193 0.089000 -vn -0.671868 -0.466685 0.575151 -v 0.094753 0.092431 0.093927 -vn -0.680299 -0.605006 0.413716 -v 0.094753 0.093013 0.094585 -vn -0.744239 -0.565082 0.356077 -v 0.091753 0.093013 0.094585 -vn -0.688555 -0.669871 0.277785 -v 0.094753 0.093215 0.094977 -vn -0.744241 -0.651238 0.148306 -v 0.091753 0.093350 0.095397 -vn -0.680297 -0.720239 0.135836 -v 0.094753 0.093350 0.095397 -vn -0.746099 -0.662310 -0.068424 -v 0.091753 0.093405 0.096274 -vn -0.671869 -0.736749 -0.076115 -v 0.094753 0.093405 0.096274 -vn -0.746099 -0.604207 -0.279768 -v 0.091753 0.093172 0.097122 -vn -0.671868 -0.672116 -0.311212 -v 0.094753 0.093172 0.097122 -vn -0.746099 -0.480628 -0.460796 -v 0.091753 0.092676 0.097848 -vn -0.671868 -0.534647 -0.512587 -v 0.094753 0.092676 0.097848 -vn -0.746098 -0.304967 -0.591889 -v 0.091753 0.091972 0.098373 -vn -0.671869 -0.339243 -0.658412 -v 0.094753 0.091972 0.098373 -vn -0.746099 -0.096259 -0.658840 -v 0.091753 0.091135 0.098642 -vn -0.671868 -0.107078 -0.732890 -v 0.094753 0.091135 0.098642 -vn -0.746100 0.122884 -0.654396 -v 0.091753 0.090256 0.098624 -vn -0.671868 0.136696 -0.727948 -v 0.094753 0.090256 0.098624 -vn -0.746098 0.328710 -0.579040 -v 0.091753 0.089431 0.098322 -vn -0.671869 0.365654 -0.644119 -v 0.094753 0.089431 0.098322 -vn -0.746099 0.498911 -0.440936 -v 0.091753 0.088749 0.097768 -vn -0.671869 0.554985 -0.490494 -v 0.094753 0.088749 0.097768 -vn -0.746099 0.615050 -0.255047 -v 0.091753 0.088283 0.097023 -vn -0.671868 0.684178 -0.283713 -v 0.094753 0.088283 0.097023 -vn -0.746098 0.664540 -0.041522 -v 0.091753 0.088084 0.096166 -vn -0.671869 0.739228 -0.046189 -v 0.094753 0.088084 0.096166 -vn -0.746099 0.642015 0.176502 -v 0.091753 0.088175 0.095292 -vn -0.671868 0.714173 0.196340 -v 0.094753 0.088175 0.095292 -vn -0.746099 0.549917 0.375403 -v 0.091753 0.088544 0.094495 -vn -0.671868 0.611724 0.417596 -v 0.094753 0.088544 0.094495 -vn -0.746099 0.398227 0.533622 -v 0.091753 0.089152 0.093860 -vn -0.671869 0.442985 0.593597 -v 0.094753 0.089152 0.093860 -vn -0.746098 0.203387 0.634013 -v 0.091753 0.089934 0.093458 -vn -0.671869 0.226245 0.705269 -v 0.094753 0.089934 0.093458 -vn -0.746100 -0.013496 0.665697 -v 0.091753 0.090803 0.093331 -vn -0.671868 -0.015013 0.740519 -v 0.094753 0.090803 0.093331 -vn -0.746098 -0.228919 0.625247 -v 0.091753 0.091667 0.093493 -vn -0.671869 -0.254647 0.695519 -v 0.094753 0.091667 0.093493 -vn -0.746099 -0.419532 0.517038 -v 0.091753 0.092431 0.093927 -vn 0.684798 0.615933 -0.389459 -v 0.097753 0.094201 0.093979 -vn 0.770263 -0.589086 0.244278 -v 0.097753 0.091673 0.095617 -vn 0.770261 -0.388024 0.506098 -v 0.097753 0.091358 0.095206 -vn 0.677704 -0.730055 0.087963 -v 0.097753 0.086778 0.096478 -vn 0.770260 0.632307 0.082992 -v 0.097753 0.089758 0.095870 -vn 0.770263 0.589087 -0.244278 -v 0.097753 0.089825 0.096383 -vn 0.770263 -0.082989 0.632304 -v 0.097753 0.090879 0.095008 -vn 0.677705 0.349144 -0.647159 -v 0.097753 0.092648 0.092480 -vn 0.677705 0.510797 -0.528964 -v 0.097753 0.093528 0.093123 -vn 0.770261 0.244283 0.589087 -v 0.097753 0.090366 0.095076 -vn 0.677705 -0.037938 -0.734355 -v 0.097753 0.090543 0.092005 -vn 0.677704 0.161595 -0.717359 -v 0.097753 0.091628 0.092098 -vn 0.770262 0.506098 0.388022 -v 0.097753 0.089956 0.095392 -vn 0.677704 -0.413977 -0.607733 -v 0.097753 0.088497 0.092694 -vn 0.677704 -0.234659 -0.696888 -v 0.097753 0.089473 0.092209 -vn 0.677706 -0.726713 -0.112262 -v 0.097753 0.086796 0.095389 -vn 0.677703 -0.669478 -0.304166 -v 0.097753 0.087107 0.094345 -vn 0.677706 -0.562587 -0.473509 -v 0.097753 0.087689 0.093424 -vn 0.770260 0.082992 -0.632307 -v 0.097753 0.090619 0.096991 -vn 0.770265 -0.244280 -0.589084 -v 0.097753 0.091132 0.096924 -vn 0.677705 0.137580 0.722349 -v 0.097753 0.091498 0.099929 -vn 0.692063 0.666781 -0.276498 -v 0.097753 0.094444 0.094468 -vn 0.684798 0.710793 -0.160704 -v 0.097753 0.094618 0.094985 -vn 0.770261 -0.632306 -0.082994 -v 0.097753 0.091741 0.096130 -vn 0.770262 0.388022 -0.506098 -v 0.097753 0.090141 0.096794 -vn 0.677704 -0.578067 0.454483 -v 0.097753 0.087605 0.098472 -vn 0.677704 -0.679249 0.281669 -v 0.097753 0.087054 0.097532 -vn 0.677704 -0.062407 0.732682 -v 0.097753 0.090410 0.099986 -vn 0.677704 -0.257770 0.688674 -v 0.097753 0.089347 0.099746 -vn 0.677705 -0.434013 0.593590 -v 0.097753 0.088388 0.099229 -vn 0.770260 -0.506101 -0.388022 -v 0.097753 0.091543 0.096608 -vn 0.677705 0.492872 0.545704 -v 0.097753 0.093430 0.098968 -vn 0.677704 0.327366 0.658444 -v 0.097753 0.092530 0.099582 -vn 0.677705 0.735232 0.012262 -v 0.097753 0.094749 0.096067 -vn 0.677704 0.704660 0.210171 -v 0.097753 0.094582 0.097143 -vn 0.677704 0.621824 0.392494 -v 0.097753 0.094132 0.098135 -vn -0.770263 0.589087 -0.244278 -v 0.094753 0.089825 0.096383 -vn -0.770260 0.632307 0.082992 -v 0.094753 0.089758 0.095870 -vn -0.770261 0.244283 0.589087 -v 0.094753 0.090366 0.095076 -vn -0.770262 0.506098 0.388022 -v 0.094753 0.089956 0.095392 -vn -0.770264 -0.589086 0.244278 -v 0.094753 0.091673 0.095617 -vn -0.770261 -0.632306 -0.082994 -v 0.094753 0.091741 0.096130 -vn -0.770260 0.082992 -0.632307 -v 0.094753 0.090619 0.096991 -vn -0.770265 -0.244280 -0.589084 -v 0.094753 0.091132 0.096924 -vn -0.770260 -0.506101 -0.388022 -v 0.094753 0.091543 0.096608 -vn -0.770261 -0.388024 0.506098 -v 0.094753 0.091358 0.095206 -vn -0.770262 -0.082989 0.632304 -v 0.094753 0.090879 0.095008 -vn -0.770262 0.388022 -0.506098 -v 0.094753 0.090141 0.096794 -vn -0.914877 -0.393942 0.088371 -v 0.091753 0.087460 0.096863 -vn -0.911925 -0.182689 -0.367448 -v 0.091753 0.089235 0.092956 -vn -0.911925 -0.275049 -0.304533 -v 0.091753 0.088470 0.093477 -vn -0.911924 -0.347013 -0.219034 -v 0.091753 0.087874 0.094185 -vn -0.911925 -0.393238 -0.117286 -v 0.091753 0.087491 0.095028 -vn -0.911925 -0.410300 -0.006843 -v 0.091753 0.087350 0.095943 -vn -0.911925 0.322594 -0.253626 -v 0.091753 0.093422 0.093899 -vn -0.911925 0.242202 -0.331255 -v 0.091753 0.092756 0.093255 -vn -0.911926 0.143848 -0.384316 -v 0.091753 0.091941 0.092816 -vn -0.911925 0.034828 -0.408876 -v 0.091753 0.091038 0.092612 -vn -0.911925 -0.076777 -0.403111 -v 0.091753 0.090113 0.092660 -vn -0.911926 0.231020 0.339147 -v 0.091753 0.092663 0.098810 -vn -0.911925 0.313955 0.264243 -v 0.091753 0.093350 0.098189 -vn -0.911925 0.373606 0.169743 -v 0.091753 0.093845 0.097406 -vn -0.911925 0.405547 0.062650 -v 0.091753 0.094109 0.096519 -vn -0.911926 0.407407 -0.049090 -v 0.091753 0.094125 0.095593 -vn -0.911926 0.379056 -0.157187 -v 0.091753 0.093890 0.094698 -vn -0.917946 -0.366447 0.151958 -v 0.091753 0.087608 0.097302 -vn -0.914878 -0.340874 0.216341 -v 0.091753 0.087815 0.097718 -vn -0.911926 -0.285051 0.295190 -v 0.091753 0.088387 0.098446 -vn -0.911926 -0.194840 0.361150 -v 0.091753 0.089135 0.098992 -vn -0.911925 -0.090179 0.400325 -v 0.091753 0.090002 0.099317 -vn -0.911926 0.021174 0.409808 -v 0.091753 0.090925 0.099395 -vn -0.911925 0.130952 0.388901 -v 0.091753 0.091834 0.099222 -vn -0.350979 -0.864963 0.358682 -v 0.092353 0.087054 0.097532 -vn -0.374026 -0.904465 0.205057 -v 0.092353 0.086880 0.097015 -vn -0.371426 -0.928334 -0.015484 -v 0.092353 0.086750 0.095933 -vn -0.371426 -0.889731 -0.265371 -v 0.092353 0.086916 0.094857 -vn -0.371425 -0.785139 -0.495580 -v 0.092353 0.087367 0.093865 -vn -0.371426 -0.622320 -0.689029 -v 0.092353 0.088068 0.093032 -vn -0.371425 -0.413346 -0.831378 -v 0.092353 0.088968 0.092418 -vn -0.371425 -0.173714 -0.912067 -v 0.092353 0.090001 0.092071 -vn -0.371427 0.078798 -0.925113 -v 0.092353 0.091089 0.092014 -vn -0.371427 0.325470 -0.869546 -v 0.092353 0.092151 0.092254 -vn -0.371426 0.548004 -0.749489 -v 0.092353 0.093110 0.092771 -vn -0.371426 0.729891 -0.573848 -v 0.092353 0.093894 0.093528 -vn -0.371428 0.857645 -0.355649 -v 0.092353 0.094444 0.094468 -vn -0.371427 0.921795 -0.111067 -v 0.092353 0.094720 0.095521 -vn -0.371425 0.917578 0.141751 -v 0.092353 0.094702 0.096611 -vn -0.371425 0.845309 0.384052 -v 0.092353 0.094391 0.097655 -vn -0.371427 0.710348 0.597870 -v 0.092353 0.093809 0.098576 -vn -0.371427 0.522701 0.767350 -v 0.092353 0.093001 0.099306 -vn -0.371426 0.296288 0.879918 -v 0.092353 0.092026 0.099791 -vn -0.371427 0.047905 0.927225 -v 0.092353 0.090956 0.099995 -vn -0.371426 -0.204037 0.905766 -v 0.092353 0.089870 0.099902 -vn -0.371427 -0.440841 0.817130 -v 0.092353 0.088850 0.099520 -vn -0.371427 -0.644954 0.667890 -v 0.092353 0.087971 0.098877 -vn -0.374026 -0.784159 0.495176 -v 0.092353 0.087297 0.098021 -# 2376 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 6//6 5//5 7//7 -f 8//8 9//9 10//10 -f 11//11 12//12 13//13 -f 13//13 12//12 8//8 -f 7//7 13//13 6//6 -f 6//6 13//13 8//8 -f 6//6 8//8 14//14 -f 14//14 8//8 10//10 -f 15//15 16//16 17//17 -f 18//18 19//19 20//20 -f 21//21 22//22 2//2 -f 2//2 22//22 4//4 -f 2//2 4//4 3//3 -f 3//3 4//4 6//6 -f 23//23 24//24 25//25 -f 17//17 16//16 20//20 -f 20//20 19//19 3//3 -f 26//26 27//27 28//28 -f 28//28 27//27 23//23 -f 10//10 28//28 14//14 -f 14//14 28//28 23//23 -f 14//14 23//23 29//29 -f 29//29 23//23 25//25 -f 30//30 31//31 32//32 -f 32//32 31//31 17//17 -f 33//33 34//34 16//16 -f 16//16 34//34 35//35 -f 16//16 35//35 20//20 -f 20//20 35//35 36//36 -f 20//20 36//36 18//18 -f 37//37 38//38 19//19 -f 19//19 38//38 39//39 -f 19//19 39//39 3//3 -f 3//3 39//39 40//40 -f 3//3 40//40 1//1 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 45//45 46//46 44//44 -f 44//44 46//46 47//47 -f 25//25 43//43 29//29 -f 29//29 43//43 44//44 -f 29//29 44//44 48//48 -f 48//48 44//44 47//47 -f 48//48 47//47 49//49 -f 50//50 32//32 51//51 -f 49//49 52//52 48//48 -f 48//48 52//52 53//53 -f 48//48 53//53 54//54 -f 55//55 56//56 31//31 -f 31//31 56//56 57//57 -f 31//31 57//57 17//17 -f 17//17 57//57 58//58 -f 17//17 58//58 15//15 -f 59//59 51//51 60//60 -f 61//61 62//62 63//63 -f 64//64 65//65 50//50 -f 50//50 65//65 66//66 -f 50//50 66//66 32//32 -f 32//32 66//66 67//67 -f 32//32 67//67 30//30 -f 68//68 69//69 53//53 -f 53//53 69//69 70//70 -f 53//53 70//70 54//54 -f 54//54 70//70 71//71 -f 71//71 72//72 54//54 -f 54//54 72//72 73//73 -f 54//54 73//73 74//74 -f 75//75 76//76 74//74 -f 74//74 76//76 77//77 -f 78//78 79//79 80//80 -f 63//63 50//50 61//61 -f 61//61 50//50 51//51 -f 61//61 51//51 81//81 -f 81//81 51//51 59//59 -f 81//81 59//59 82//82 -f 83//83 84//84 73//73 -f 73//73 84//84 85//85 -f 73//73 85//85 74//74 -f 74//74 85//85 86//86 -f 74//74 86//86 75//75 -f 87//87 88//88 77//77 -f 80//80 59//59 78//78 -f 78//78 59//59 60//60 -f 78//78 60//60 89//89 -f 89//89 60//60 90//90 -f 89//89 90//90 91//91 -f 92//92 93//93 76//76 -f 76//76 93//93 94//94 -f 76//76 94//94 77//77 -f 77//77 94//94 95//95 -f 77//77 95//95 87//87 -f 96//96 97//97 98//98 -f 98//98 97//97 99//99 -f 98//98 99//99 100//100 -f 101//101 102//102 100//100 -f 100//100 102//102 90//90 -f 100//100 90//90 98//98 -f 98//98 90//90 60//60 -f 103//103 104//104 88//88 -f 88//88 104//104 96//96 -f 88//88 96//96 77//77 -f 77//77 96//96 98//98 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 116//116 118//118 117//117 -f 117//117 118//118 119//119 -f 117//117 119//119 120//120 -f 120//120 119//119 121//121 -f 120//120 121//121 122//122 -f 122//122 121//121 123//123 -f 122//122 123//123 124//124 -f 124//124 123//123 125//125 -f 124//124 125//125 126//126 -f 126//126 125//125 127//127 -f 126//126 127//127 128//128 -f 128//128 127//127 129//129 -f 128//128 129//129 130//130 -f 130//130 129//129 131//131 -f 130//130 131//131 132//132 -f 132//132 131//131 133//133 -f 132//132 133//133 105//105 -f 105//105 133//133 134//134 -f 105//105 134//134 106//106 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 139//139 140//140 141//141 -f 141//141 140//140 142//142 -f 143//143 144//144 145//145 -f 145//145 146//146 143//143 -f 143//143 146//146 147//147 -f 143//143 147//147 148//148 -f 148//148 147//147 149//149 -f 148//148 149//149 150//150 -f 150//150 149//149 151//151 -f 150//150 151//151 152//152 -f 152//152 151//151 153//153 -f 152//152 153//153 154//154 -f 154//154 153//153 155//155 -f 154//154 155//155 156//156 -f 144//144 157//157 145//145 -f 145//145 157//157 158//158 -f 145//145 158//158 159//159 -f 158//158 160//160 159//159 -f 159//159 160//160 161//161 -f 159//159 161//161 162//162 -f 162//162 161//161 163//163 -f 162//162 163//163 164//164 -f 164//164 163//163 156//156 -f 164//164 156//156 165//165 -f 165//165 156//156 155//155 -f 166//166 167//167 168//168 -f 169//169 170//170 171//171 -f 137//137 138//138 172//172 -f 168//168 173//173 174//174 -f 174//174 173//173 175//175 -f 175//175 173//173 176//176 -f 176//176 173//173 177//177 -f 176//176 177//177 178//178 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 172//172 -f 182//182 183//183 184//184 -f 185//185 186//186 187//187 -f 187//187 186//186 188//188 -f 184//184 166//166 182//182 -f 182//182 166//166 168//168 -f 182//182 168//168 172//172 -f 172//172 168//168 174//174 -f 172//172 174//174 137//137 -f 189//189 190//190 191//191 -f 191//191 190//190 186//186 -f 192//192 193//193 178//178 -f 178//178 193//193 170//170 -f 178//178 170//170 176//176 -f 176//176 170//170 169//169 -f 176//176 169//169 139//139 -f 139//139 169//169 140//140 -f 194//194 195//195 185//185 -f 185//185 195//195 196//196 -f 185//185 196//196 186//186 -f 186//186 196//196 197//197 -f 186//186 197//197 191//191 -f 187//187 198//198 185//185 -f 185//185 198//198 169//169 -f 185//185 169//169 199//199 -f 199//199 169//169 171//171 -f 199//199 171//171 200//200 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 203//203 206//206 201//201 -f 201//201 206//206 207//207 -f 201//201 207//207 208//208 -f 208//208 207//207 209//209 -f 208//208 209//209 210//210 -f 210//210 209//209 211//211 -f 210//210 211//211 212//212 -f 212//212 211//211 213//213 -f 212//212 213//213 214//214 -f 214//214 213//213 215//215 -f 214//214 215//215 216//216 -f 216//216 215//215 217//217 -f 216//216 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 220//220 219//219 221//221 -f 220//220 221//221 222//222 -f 222//222 221//221 205//205 -f 222//222 205//205 223//223 -f 223//223 205//205 204//204 -f 224//224 225//225 226//226 -f 226//226 225//225 227//227 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 230//230 -f 230//230 229//229 231//231 -f 230//230 231//231 232//232 -f 232//232 231//231 233//233 -f 232//232 233//233 234//234 -f 234//234 233//233 235//235 -f 234//234 235//235 236//236 -f 236//236 235//235 237//237 -f 236//236 237//237 238//238 -f 238//238 237//237 239//239 -f 238//238 239//239 240//240 -f 224//224 241//241 225//225 -f 225//225 241//241 242//242 -f 225//225 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 240//240 -f 245//245 240//240 246//246 -f 246//246 240//240 239//239 -f 247//247 248//248 249//249 -f 247//247 249//249 250//250 -f 249//249 251//251 250//250 -f 250//250 251//251 252//252 -f 250//250 252//252 186//186 -f 186//186 252//252 253//253 -f 186//186 253//253 188//188 -f 254//254 255//255 256//256 -f 256//256 257//257 258//258 -f 259//259 260//260 257//257 -f 258//258 261//261 256//256 -f 256//256 261//261 262//262 -f 256//256 262//262 263//263 -f 264//264 265//265 266//266 -f 267//267 268//268 269//269 -f 260//260 259//259 270//270 -f 270//270 259//259 269//269 -f 270//270 269//269 271//271 -f 272//272 259//259 273//273 -f 273//273 259//259 257//257 -f 273//273 257//257 274//274 -f 274//274 257//257 256//256 -f 266//266 265//265 275//275 -f 275//275 265//265 276//276 -f 275//275 276//276 277//277 -f 278//278 279//279 280//280 -f 268//268 281//281 269//269 -f 269//269 281//281 282//282 -f 269//269 282//282 283//283 -f 271//271 269//269 284//284 -f 284//284 269//269 283//283 -f 284//284 283//283 276//276 -f 276//276 283//283 285//285 -f 276//276 285//285 277//277 -f 278//278 286//286 256//256 -f 256//256 286//286 287//287 -f 256//256 287//287 254//254 -f 278//278 280//280 288//288 -f 288//288 280//280 267//267 -f 288//288 267//267 289//289 -f 279//279 278//278 290//290 -f 290//290 278//278 256//256 -f 290//290 256//256 266//266 -f 266//266 256//256 263//263 -f 266//266 263//263 264//264 -f 291//291 292//292 293//293 -f 293//293 292//292 294//294 -f 293//293 294//294 295//295 -f 295//295 294//294 296//296 -f 297//297 298//298 291//291 -f 298//298 299//299 291//291 -f 291//291 299//299 300//300 -f 291//291 300//300 292//292 -f 267//267 269//269 289//289 -f 289//289 269//269 301//301 -f 289//289 301//301 302//302 -f 269//269 303//303 301//301 -f 301//301 303//303 304//304 -f 301//301 304//304 305//305 -f 305//305 304//304 306//306 -f 305//305 306//306 296//296 -f 296//296 306//306 307//307 -f 296//296 307//307 295//295 -f 308//308 309//309 310//310 -f 310//310 309//309 311//311 -f 310//310 311//311 302//302 -f 302//302 311//311 312//312 -f 302//302 312//312 289//289 -f 313//313 314//314 291//291 -f 291//291 314//314 315//315 -f 291//291 315//315 316//316 -f 317//317 318//318 313//313 -f 313//313 318//318 319//319 -f 313//313 319//319 314//314 -f 320//320 321//321 322//322 -f 322//322 321//321 323//323 -f 322//322 323//323 313//313 -f 313//313 323//323 324//324 -f 313//313 324//324 317//317 -f 325//325 326//326 327//327 -f 316//316 328//328 291//291 -f 291//291 328//328 309//309 -f 291//291 309//309 297//297 -f 297//297 309//309 308//308 -f 329//329 330//330 313//313 -f 313//313 330//330 331//331 -f 313//313 331//331 322//322 -f 328//328 332//332 309//309 -f 309//309 332//332 333//333 -f 309//309 333//333 321//321 -f 325//325 334//334 335//335 -f 335//335 334//334 336//336 -f 335//335 336//336 337//337 -f 313//313 338//338 329//329 -f 329//329 338//338 339//339 -f 329//329 339//339 327//327 -f 327//327 339//339 340//340 -f 327//327 340//340 325//325 -f 325//325 340//340 341//341 -f 325//325 341//341 334//334 -f 320//320 342//342 321//321 -f 321//321 342//342 343//343 -f 321//321 343//343 309//309 -f 309//309 343//343 344//344 -f 309//309 344//344 345//345 -f 345//345 344//344 346//346 -f 345//345 346//346 325//325 -f 325//325 346//346 347//347 -f 325//325 347//347 326//326 -f 348//348 349//349 350//350 -f 351//351 352//352 353//353 -f 354//354 355//355 356//356 -f 357//357 358//358 359//359 -f 360//360 361//361 358//358 -f 358//358 361//361 359//359 -f 359//359 361//361 362//362 -f 359//359 362//362 363//363 -f 362//362 364//364 363//363 -f 363//363 364//364 365//365 -f 363//363 365//365 366//366 -f 365//365 367//367 366//366 -f 366//366 367//367 368//368 -f 366//366 368//368 369//369 -f 369//369 368//368 370//370 -f 369//369 370//370 371//371 -f 371//371 370//370 372//372 -f 372//372 373//373 371//371 -f 371//371 373//373 374//374 -f 371//371 374//374 375//375 -f 375//375 374//374 376//376 -f 371//371 377//377 378//378 -f 378//378 377//377 379//379 -f 380//380 381//381 382//382 -f 382//382 381//381 383//383 -f 382//382 383//383 377//377 -f 377//377 383//383 384//384 -f 377//377 384//384 379//379 -f 378//378 385//385 371//371 -f 371//371 385//385 386//386 -f 371//371 386//386 369//369 -f 369//369 386//386 387//387 -f 369//369 387//387 366//366 -f 366//366 387//387 388//388 -f 388//388 389//389 366//366 -f 366//366 389//389 390//390 -f 366//366 390//390 380//380 -f 380//380 390//390 391//391 -f 380//380 391//391 381//381 -f 392//392 393//393 394//394 -f 394//394 393//393 395//395 -f 396//396 397//397 398//398 -f 398//398 397//397 399//399 -f 398//398 399//399 395//395 -f 395//395 399//399 400//400 -f 395//395 400//400 394//394 -f 398//398 401//401 396//396 -f 396//396 401//401 402//402 -f 396//396 402//402 377//377 -f 377//377 402//402 403//403 -f 377//377 403//403 382//382 -f 382//382 403//403 404//404 -f 382//382 404//404 380//380 -f 380//380 404//404 405//405 -f 405//405 406//406 380//380 -f 380//380 406//406 407//407 -f 380//380 407//407 408//408 -f 408//408 407//407 409//409 -f 410//410 411//411 412//412 -f 412//412 411//411 413//413 -f 412//412 413//413 414//414 -f 415//415 416//416 417//417 -f 418//418 419//419 420//420 -f 420//420 419//419 421//421 -f 420//420 421//421 410//410 -f 410//410 421//421 422//422 -f 410//410 422//422 411//411 -f 423//423 424//424 425//425 -f 425//425 424//424 417//417 -f 425//425 417//417 420//420 -f 420//420 417//417 416//416 -f 420//420 416//416 418//418 -f 414//414 426//426 412//412 -f 412//412 426//426 427//427 -f 412//412 427//427 428//428 -f 428//428 427//427 429//429 -f 428//428 429//429 430//430 -f 430//430 429//429 415//415 -f 430//430 415//415 431//431 -f 431//431 415//415 417//417 -f 432//432 433//433 434//434 -f 434//434 433//433 410//410 -f 434//434 410//410 435//435 -f 436//436 437//437 438//438 -f 438//438 437//437 439//439 -f 440//440 412//412 441//441 -f 441//441 412//412 438//438 -f 441//441 438//438 442//442 -f 442//442 438//438 439//439 -f 440//440 443//443 412//412 -f 412//412 443//443 444//444 -f 412//412 444//444 410//410 -f 410//410 444//444 445//445 -f 410//410 445//445 435//435 -f 446//446 447//447 448//448 -f 449//449 450//450 451//451 -f 446//446 448//448 438//438 -f 438//438 448//448 452//452 -f 438//438 452//452 453//453 -f 453//453 454//454 438//438 -f 438//438 454//454 433//433 -f 438//438 433//433 436//436 -f 436//436 433//433 432//432 -f 454//454 455//455 433//433 -f 433//433 455//455 456//456 -f 433//433 456//456 457//457 -f 457//457 456//456 458//458 -f 457//457 458//458 459//459 -f 459//459 458//458 460//460 -f 461//461 356//356 460//460 -f 460//460 356//356 462//462 -f 460//460 462//462 459//459 -f 447//447 446//446 451//451 -f 451//451 446//446 463//463 -f 451//451 463//463 449//449 -f 464//464 465//465 350//350 -f 350//350 465//465 466//466 -f 350//350 466//466 356//356 -f 356//356 466//466 467//467 -f 356//356 467//467 462//462 -f 376//376 360//360 375//375 -f 375//375 360//360 358//358 -f 375//375 358//358 468//468 -f 468//468 358//358 357//357 -f 468//468 357//357 469//469 -f 470//470 471//471 472//472 -f 472//472 471//471 473//473 -f 472//472 473//473 474//474 -f 474//474 473//473 469//469 -f 474//474 469//469 475//475 -f 475//475 469//469 357//357 -f 409//409 392//392 408//408 -f 408//408 392//392 394//394 -f 408//408 394//394 476//476 -f 476//476 394//394 477//477 -f 478//478 479//479 350//350 -f 350//350 479//479 480//480 -f 350//350 480//480 481//481 -f 400//400 464//464 394//394 -f 394//394 464//464 350//350 -f 394//394 350//350 482//482 -f 482//482 350//350 481//481 -f 482//482 483//483 394//394 -f 394//394 483//483 484//484 -f 394//394 484//484 477//477 -f 477//477 484//484 485//485 -f 477//477 485//485 486//486 -f 486//486 485//485 487//487 -f 486//486 487//487 488//488 -f 488//488 487//487 489//489 -f 487//487 490//490 489//489 -f 489//489 490//490 491//491 -f 489//489 491//491 492//492 -f 492//492 491//491 493//493 -f 492//492 493//493 478//478 -f 494//494 354//354 495//495 -f 495//495 354//354 356//356 -f 495//495 356//356 449//449 -f 449//449 356//356 461//461 -f 449//449 461//461 450//450 -f 496//496 424//424 497//497 -f 497//497 424//424 423//423 -f 497//497 423//423 353//353 -f 353//353 423//423 498//498 -f 353//353 498//498 351//351 -f 478//478 350//350 492//492 -f 492//492 350//350 349//349 -f 492//492 349//349 499//499 -f 499//499 500//500 492//492 -f 492//492 500//500 501//501 -f 492//492 501//501 355//355 -f 502//502 503//503 356//356 -f 356//356 503//503 504//504 -f 356//356 504//504 350//350 -f 350//350 504//504 505//505 -f 350//350 505//505 348//348 -f 501//501 506//506 355//355 -f 355//355 506//506 507//507 -f 355//355 507//507 356//356 -f 356//356 507//507 508//508 -f 356//356 508//508 502//502 -f 476//476 509//509 408//408 -f 408//408 509//509 510//510 -f 408//408 510//510 380//380 -f 380//380 510//510 511//511 -f 380//380 511//511 366//366 -f 366//366 511//511 512//512 -f 366//366 512//512 363//363 -f 363//363 512//512 513//513 -f 363//363 513//513 514//514 -f 514//514 513//513 515//515 -f 516//516 517//517 518//518 -f 518//518 517//517 519//519 -f 278//278 520//520 521//521 -f 516//516 518//518 522//522 -f 522//522 518//518 523//523 -f 521//521 522//522 278//278 -f 278//278 522//522 523//523 -f 278//278 523//523 286//286 -f 286//286 523//523 524//524 -f 286//286 524//524 525//525 -f 526//526 527//527 528//528 -f 528//528 527//527 529//529 -f 528//528 529//529 530//530 -f 531//531 532//532 533//533 -f 534//534 535//535 533//533 -f 533//533 535//535 536//536 -f 533//533 536//536 531//531 -f 531//531 537//537 532//532 -f 532//532 537//537 538//538 -f 532//532 538//538 539//539 -f 539//539 538//538 540//540 -f 539//539 540//540 541//541 -f 541//541 540//540 542//542 -f 533//533 543//543 534//534 -f 534//534 543//543 544//544 -f 534//534 544//544 545//545 -f 545//545 544//544 546//546 -f 545//545 546//546 547//547 -f 547//547 546//546 548//548 -f 547//547 548//548 549//549 -f 549//549 548//548 550//550 -f 549//549 550//550 551//551 -f 551//551 550//550 552//552 -f 551//551 552//552 542//542 -f 542//542 552//552 553//553 -f 542//542 553//553 541//541 -f 554//554 555//555 556//556 -f 556//556 555//555 557//557 -f 556//556 557//557 558//558 -f 559//559 560//560 561//561 -f 554//554 562//562 555//555 -f 555//555 562//562 563//563 -f 555//555 563//563 564//564 -f 565//565 559//559 566//566 -f 566//566 559//559 561//561 -f 566//566 561//561 567//567 -f 567//567 561//561 564//564 -f 567//567 564//564 568//568 -f 568//568 564//564 563//563 -f 566//566 569//569 565//565 -f 565//565 569//569 570//570 -f 565//565 570//570 571//571 -f 571//571 570//570 572//572 -f 571//571 572//572 573//573 -f 573//573 572//572 574//574 -f 573//573 574//574 575//575 -f 575//575 574//574 558//558 -f 575//575 558//558 576//576 -f 576//576 558//558 557//557 -f 577//577 578//578 579//579 -f 579//579 578//578 580//580 -f 579//579 580//580 581//581 -f 582//582 583//583 584//584 -f 584//584 585//585 311//311 -f 586//586 587//587 588//588 -f 589//589 590//590 591//591 -f 591//591 590//590 592//592 -f 593//593 345//345 594//594 -f 594//594 345//345 595//595 -f 594//594 595//595 596//596 -f 592//592 597//597 591//591 -f 591//591 597//597 311//311 -f 591//591 311//311 598//598 -f 598//598 311//311 585//585 -f 599//599 600//600 601//601 -f 601//601 600//600 602//602 -f 603//603 604//604 605//605 -f 593//593 586//586 345//345 -f 345//345 586//586 584//584 -f 345//345 584//584 309//309 -f 309//309 584//584 311//311 -f 588//588 602//602 586//586 -f 586//586 602//602 600//600 -f 586//586 600//600 584//584 -f 584//584 600//600 603//603 -f 584//584 603//603 582//582 -f 582//582 603//603 605//605 -f 604//604 606//606 605//605 -f 605//605 606//606 607//607 -f 608//608 609//609 610//610 -f 610//610 609//609 611//611 -f 612//612 613//613 614//614 -f 615//615 616//616 612//612 -f 612//612 616//616 617//617 -f 612//612 617//617 613//613 -f 618//618 619//619 520//520 -f 520//520 619//619 521//521 -f 620//620 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 624//624 623//623 612//612 -f 624//624 612//612 618//618 -f 618//618 612//612 614//614 -f 618//618 614//614 619//619 -f 625//625 620//620 626//626 -f 183//183 627//627 184//184 -f 184//184 627//627 628//628 -f 629//629 193//193 630//630 -f 630//630 193//193 192//192 -f 631//631 632//632 633//633 -f 633//633 632//632 634//634 -f 633//633 634//634 635//635 -f 636//636 637//637 638//638 -f 638//638 637//637 639//639 -f 525//525 524//524 640//640 -f 640//640 641//641 642//642 -f 525//525 640//640 643//643 -f 643//643 640//640 642//642 -f 643//643 642//642 644//644 -f 644//644 642//642 645//645 -f 644//644 645//645 635//635 -f 635//635 645//645 646//646 -f 635//635 646//646 633//633 -f 647//647 648//648 649//649 -f 649//649 648//648 642//642 -f 649//649 642//642 650//650 -f 650//650 642//642 641//641 -f 651//651 631//631 633//633 -f 652//652 653//653 654//654 -f 654//654 655//655 652//652 -f 652//652 655//655 656//656 -f 652//652 656//656 200//200 -f 200//200 656//656 657//657 -f 657//657 658//658 200//200 -f 200//200 658//658 659//659 -f 200//200 659//659 199//199 -f 660//660 661//661 609//609 -f 609//609 661//661 611//611 -f 588//588 587//587 662//662 -f 662//662 587//587 663//663 -f 664//664 665//665 666//666 -f 665//665 667//667 666//666 -f 666//666 667//667 668//668 -f 666//666 668//668 669//669 -f 668//668 670//670 669//669 -f 669//669 670//670 671//671 -f 669//669 671//671 672//672 -f 672//672 671//671 673//673 -f 672//672 673//673 674//674 -f 674//674 673//673 675//675 -f 666//666 676//676 664//664 -f 664//664 676//676 677//677 -f 664//664 677//677 678//678 -f 678//678 677//677 679//679 -f 678//678 679//679 680//680 -f 680//680 679//679 681//681 -f 680//680 681//681 682//682 -f 682//682 681//681 683//683 -f 682//682 683//683 684//684 -f 684//684 683//683 685//685 -f 684//684 685//685 675//675 -f 675//675 685//685 686//686 -f 675//675 686//686 674//674 -f 636//636 687//687 637//637 -f 637//637 687//687 688//688 -f 689//689 195//195 690//690 -f 690//690 195//195 194//194 -f 691//691 692//692 693//693 -f 693//693 692//692 694//694 -f 693//693 694//694 695//695 -f 695//695 694//694 696//696 -f 695//695 696//696 697//697 -f 697//697 696//696 698//698 -f 691//691 693//693 699//699 -f 699//699 693//693 700//700 -f 699//699 700//700 701//701 -f 701//701 700//700 702//702 -f 701//701 702//702 703//703 -f 703//703 702//702 704//704 -f 703//703 704//704 705//705 -f 705//705 704//704 706//706 -f 705//705 706//706 707//707 -f 707//707 706//706 708//708 -f 707//707 708//708 709//709 -f 709//709 708//708 710//710 -f 709//709 710//710 711//711 -f 711//711 710//710 712//712 -f 711//711 712//712 698//698 -f 698//698 712//712 713//713 -f 698//698 713//713 697//697 -f 714//714 715//715 716//716 -f 714//714 716//716 717//717 -f 716//716 718//718 717//717 -f 717//717 718//718 719//719 -f 717//717 719//719 595//595 -f 595//595 719//719 720//720 -f 595//595 720//720 596//596 -f 721//721 722//722 723//723 -f 724//724 725//725 722//722 -f 722//722 725//725 726//726 -f 722//722 726//726 723//723 -f 723//723 727//727 721//721 -f 721//721 727//727 728//728 -f 721//721 728//728 729//729 -f 729//729 728//728 730//730 -f 729//729 730//730 731//731 -f 731//731 730//730 732//732 -f 722//722 733//733 724//724 -f 724//724 733//733 734//734 -f 724//724 734//734 735//735 -f 735//735 734//734 736//736 -f 735//735 736//736 737//737 -f 737//737 736//736 738//738 -f 737//737 738//738 739//739 -f 739//739 738//738 740//740 -f 739//739 740//740 741//741 -f 741//741 740//740 742//742 -f 741//741 742//742 732//732 -f 732//732 742//742 743//743 -f 732//732 743//743 731//731 -f 744//744 626//626 745//745 -f 745//745 626//626 620//620 -f 745//745 620//620 622//622 -f 746//746 747//747 748//748 -f 748//748 747//747 749//749 -f 748//748 749//749 750//750 -f 749//749 751//751 750//750 -f 750//750 751//751 752//752 -f 750//750 752//752 753//753 -f 753//753 752//752 754//754 -f 753//753 754//754 755//755 -f 755//755 754//754 756//756 -f 755//755 756//756 757//757 -f 757//757 756//756 758//758 -f 757//757 758//758 759//759 -f 759//759 758//758 760//760 -f 759//759 760//760 761//761 -f 761//761 760//760 762//762 -f 761//761 762//762 763//763 -f 763//763 762//762 764//764 -f 763//763 764//764 765//765 -f 765//765 764//764 766//766 -f 765//765 766//766 767//767 -f 767//767 766//766 746//746 -f 767//767 746//746 768//768 -f 768//768 746//746 748//748 -f 769//769 770//770 771//771 -f 771//771 770//770 772//772 -f 771//771 772//772 773//773 -f 773//773 772//772 774//774 -f 773//773 774//774 775//775 -f 775//775 774//774 776//776 -f 769//769 771//771 777//777 -f 777//777 771//771 778//778 -f 777//777 778//778 779//779 -f 779//779 778//778 780//780 -f 779//779 780//780 781//781 -f 781//781 780//780 782//782 -f 781//781 782//782 783//783 -f 783//783 782//782 784//784 -f 783//783 784//784 785//785 -f 785//785 784//784 786//786 -f 785//785 786//786 787//787 -f 787//787 786//786 788//788 -f 787//787 788//788 789//789 -f 789//789 788//788 790//790 -f 789//789 790//790 776//776 -f 776//776 790//790 791//791 -f 776//776 791//791 775//775 -f 792//792 793//793 794//794 -f 794//794 793//793 795//795 -f 794//794 795//795 796//796 -f 795//795 797//797 796//796 -f 796//796 797//797 798//798 -f 796//796 798//798 799//799 -f 799//799 798//798 800//800 -f 799//799 800//800 801//801 -f 801//801 800//800 802//802 -f 801//801 802//802 803//803 -f 803//803 802//802 804//804 -f 803//803 804//804 805//805 -f 805//805 804//804 806//806 -f 805//805 806//806 807//807 -f 807//807 806//806 808//808 -f 807//807 808//808 809//809 -f 809//809 808//808 810//810 -f 809//809 810//810 811//811 -f 811//811 810//810 812//812 -f 811//811 812//812 813//813 -f 813//813 812//812 792//792 -f 813//813 792//792 814//814 -f 814//814 792//792 794//794 -f 190//190 189//189 815//815 -f 190//190 815//815 816//816 -f 815//815 817//817 816//816 -f 816//816 817//817 818//818 -f 816//816 818//818 819//819 -f 819//819 818//818 820//820 -f 819//819 820//820 821//821 -f 822//822 823//823 824//824 -f 824//824 823//823 825//825 -f 824//824 825//825 826//826 -f 826//826 825//825 827//827 -f 826//826 827//827 828//828 -f 828//828 827//827 829//829 -f 828//828 829//829 830//830 -f 830//830 829//829 831//831 -f 830//830 831//831 832//832 -f 832//832 831//831 833//833 -f 832//832 833//833 834//834 -f 833//833 835//835 834//834 -f 834//834 835//835 836//836 -f 834//834 836//836 837//837 -f 837//837 836//836 838//838 -f 837//837 838//838 839//839 -f 839//839 838//838 840//840 -f 839//839 840//840 841//841 -f 841//841 840//840 842//842 -f 841//841 842//842 843//843 -f 843//843 842//842 844//844 -f 843//843 844//844 845//845 -f 845//845 844//844 846//846 -f 845//845 846//846 847//847 -f 847//847 846//846 848//848 -f 847//847 848//848 849//849 -f 849//849 848//848 850//850 -f 849//849 850//850 822//822 -f 822//822 850//850 851//851 -f 822//822 851//851 823//823 -f 852//852 853//853 854//854 -f 854//854 853//853 855//855 -f 854//854 855//855 856//856 -f 856//856 855//855 857//857 -f 856//856 857//857 858//858 -f 858//858 857//857 859//859 -f 858//858 859//859 860//860 -f 860//860 859//859 861//861 -f 860//860 861//861 862//862 -f 862//862 861//861 863//863 -f 862//862 863//863 864//864 -f 864//864 863//863 865//865 -f 864//864 865//865 866//866 -f 866//866 865//865 867//867 -f 866//866 867//867 868//868 -f 868//868 867//867 869//869 -f 868//868 869//869 870//870 -f 871//871 872//872 873//873 -f 873//873 872//872 874//874 -f 873//873 874//874 875//875 -f 875//875 874//874 876//876 -f 875//875 876//876 877//877 -f 877//877 876//876 878//878 -f 877//877 878//878 852//852 -f 852//852 878//878 879//879 -f 852//852 879//879 853//853 -f 869//869 880//880 870//870 -f 870//870 880//880 881//881 -f 870//870 881//881 882//882 -f 882//882 881//881 883//883 -f 882//882 883//883 884//884 -f 884//884 883//883 885//885 -f 884//884 885//885 871//871 -f 871//871 885//885 886//886 -f 871//871 886//886 872//872 -f 887//887 888//888 889//889 -f 889//889 888//888 890//890 -f 891//891 773//773 775//775 -f 891//891 775//775 892//892 -f 892//892 775//775 791//791 -f 892//892 791//791 893//893 -f 530//530 529//529 894//894 -f 895//895 896//896 791//791 -f 791//791 896//896 530//530 -f 791//791 530//530 893//893 -f 893//893 530//530 894//894 -f 894//894 529//529 527//527 -f 894//894 527//527 897//897 -f 897//897 527//527 526//526 -f 897//897 526//526 898//898 -f 517//517 899//899 900//900 -f 616//616 615//615 578//578 -f 648//648 647//647 526//526 -f 526//526 647//647 533//533 -f 616//616 578//578 564//564 -f 564//564 578//578 901//901 -f 564//564 901//901 555//555 -f 555//555 901//901 902//902 -f 555//555 902//902 903//903 -f 532//532 903//903 533//533 -f 533//533 903//903 904//904 -f 904//904 905//905 533//533 -f 533//533 905//905 898//898 -f 533//533 898//898 526//526 -f 906//906 907//907 532//532 -f 532//532 907//907 519//519 -f 532//532 519//519 903//903 -f 903//903 519//519 517//517 -f 903//903 517//517 555//555 -f 555//555 517//517 900//900 -f 901//901 578//578 577//577 -f 901//901 577//577 908//908 -f 908//908 577//577 579//579 -f 908//908 579//579 909//909 -f 909//909 579//579 910//910 -f 910//910 579//579 581//581 -f 910//910 581//581 767//767 -f 767//767 581//581 911//911 -f 767//767 911//911 912//912 -f 910//910 767//767 768//768 -f 910//910 768//768 913//913 -f 913//913 768//768 748//748 -f 913//913 748//748 914//914 -f 693//693 695//695 915//915 -f 916//916 917//917 660//660 -f 660//660 917//917 722//722 -f 750//750 918//918 748//748 -f 748//748 918//918 919//919 -f 748//748 919//919 914//914 -f 920//920 921//921 750//750 -f 750//750 921//921 661//661 -f 750//750 661//661 918//918 -f 918//918 661//661 660//660 -f 918//918 660//660 922//922 -f 922//922 660//660 722//722 -f 923//923 924//924 721//721 -f 721//721 924//924 662//662 -f 663//663 925//925 926//926 -f 926//926 693//693 663//663 -f 663//663 693//693 915//915 -f 663//663 915//915 662//662 -f 662//662 915//915 922//922 -f 662//662 922//922 721//721 -f 721//721 922//922 722//722 -f 695//695 697//697 915//915 -f 915//915 697//697 927//927 -f 927//927 697//697 928//928 -f 928//928 697//697 713//713 -f 928//928 713//713 929//929 -f 720//720 719//719 930//930 -f 931//931 932//932 713//713 -f 713//713 932//932 720//720 -f 713//713 720//720 929//929 -f 929//929 720//720 930//930 -f 930//930 719//719 718//718 -f 930//930 718//718 933//933 -f 933//933 718//718 716//716 -f 933//933 716//716 934//934 -f 352//352 935//935 936//936 -f 937//937 934//934 716//716 -f 821//821 938//938 248//248 -f 248//248 938//938 890//890 -f 248//248 890//890 888//888 -f 334//334 497//497 336//336 -f 336//336 497//497 353//353 -f 336//336 353//353 337//337 -f 939//939 938//938 940//940 -f 940//940 938//938 821//821 -f 940//940 821//821 941//941 -f 941//941 821//821 820//820 -f 941//941 820//820 942//942 -f 942//942 820//820 943//943 -f 470//470 472//472 249//249 -f 249//249 248//248 470//470 -f 470//470 248//248 715//715 -f 470//470 715//715 936//936 -f 936//936 715//715 337//337 -f 936//936 337//337 352//352 -f 352//352 337//337 353//353 -f 716//716 715//715 937//937 -f 937//937 715//715 248//248 -f 937//937 248//248 944//944 -f 944//944 248//248 888//888 -f 944//944 888//888 945//945 -f 945//945 888//888 946//946 -f 943//943 820//820 818//818 -f 943//943 818//818 947//947 -f 947//947 818//818 817//817 -f 947//947 817//817 948//948 -f 948//948 817//817 949//949 -f 949//949 817//817 815//815 -f 949//949 815//815 813//813 -f 813//813 815//815 950//950 -f 813//813 950//950 951//951 -f 949//949 813//813 814//814 -f 949//949 814//814 952//952 -f 952//952 814//814 794//794 -f 952//952 794//794 953//953 -f 687//687 954//954 955//955 -f 953//953 794//794 956//956 -f 956//956 794//794 796//796 -f 957//957 771//771 958//958 -f 958//958 771//771 773//773 -f 958//958 773//773 891//891 -f 959//959 960//960 690//690 -f 690//690 960//960 666//666 -f 961//961 962//962 796//796 -f 796//796 962//962 689//689 -f 796//796 689//689 956//956 -f 956//956 689//689 690//690 -f 956//956 690//690 957//957 -f 957//957 690//690 666//666 -f 957//957 666//666 669//669 -f 655//655 654//654 669//669 -f 669//669 654//654 688//688 -f 669//669 688//688 957//957 -f 957//957 688//688 687//687 -f 957//957 687//687 771//771 -f 771//771 687//687 955//955 -f 898//898 905//905 963//963 -f 910//910 913//913 964//964 -f 914//914 919//919 965//965 -f 966//966 967//967 928//928 -f 968//968 918//918 922//922 -f 969//969 970//970 971//971 -f 972//972 973//973 974//974 -f 974//974 973//973 975//975 -f 974//974 975//975 964//964 -f 964//964 975//975 976//976 -f 964//964 976//976 977//977 -f 977//977 978//978 908//908 -f 908//908 978//978 979//979 -f 908//908 979//979 901//901 -f 901//901 979//979 980//980 -f 901//901 980//980 902//902 -f 980//980 981//981 902//902 -f 902//902 981//981 982//982 -f 902//902 982//982 903//903 -f 903//903 982//982 983//983 -f 903//903 983//983 984//984 -f 984//984 983//983 985//985 -f 986//986 987//987 941//941 -f 941//941 987//987 988//988 -f 941//941 988//988 989//989 -f 940//940 941//941 990//990 -f 990//990 941//941 989//989 -f 990//990 989//989 991//991 -f 991//991 989//989 992//992 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 997//997 996//996 998//998 -f 997//997 998//998 999//999 -f 999//999 998//998 1000//1000 -f 999//999 1000//1000 1001//1001 -f 1001//1001 1000//1000 1002//1002 -f 1001//1001 1002//1002 992//992 -f 992//992 1002//1002 1003//1003 -f 992//992 1003//1003 991//991 -f 993//993 1004//1004 994//994 -f 994//994 1004//1004 1005//1005 -f 994//994 1005//1005 1006//1006 -f 986//986 941//941 1005//1005 -f 1005//1005 941//941 942//942 -f 1005//1005 942//942 1006//1006 -f 1007//1007 1008//1008 1009//1009 -f 1009//1009 1008//1008 1010//1010 -f 1009//1009 1010//1010 1011//1011 -f 1012//1012 1013//1013 1014//1014 -f 1012//1012 1014//1014 1015//1015 -f 1015//1015 1014//1014 1016//1016 -f 1015//1015 1016//1016 1017//1017 -f 1017//1017 1016//1016 1018//1018 -f 1017//1017 1018//1018 1019//1019 -f 1019//1019 1018//1018 1020//1020 -f 1019//1019 1020//1020 1009//1009 -f 1009//1009 1020//1020 1021//1021 -f 1009//1009 1021//1021 1007//1007 -f 1013//1013 1012//1012 1022//1022 -f 1022//1022 1012//1012 1023//1023 -f 1022//1022 1023//1023 1024//1024 -f 1025//1025 1026//1026 1027//1027 -f 1027//1027 1026//1026 1028//1028 -f 1027//1027 1028//1028 1029//1029 -f 1030//1030 965//965 1031//1031 -f 1031//1031 965//965 1032//1032 -f 1033//1033 1034//1034 1035//1035 -f 1033//1033 1035//1035 1036//1036 -f 1036//1036 1035//1035 1037//1037 -f 1036//1036 1037//1037 1038//1038 -f 1038//1038 1037//1037 1039//1039 -f 1038//1038 1039//1039 1040//1040 -f 1040//1040 1039//1039 1041//1041 -f 1040//1040 1041//1041 1042//1042 -f 1042//1042 1041//1041 1043//1043 -f 1042//1042 1043//1043 1044//1044 -f 1043//1043 1045//1045 1044//1044 -f 1044//1044 1045//1045 1046//1046 -f 1044//1044 1046//1046 965//965 -f 965//965 1046//1046 1047//1047 -f 965//965 1047//1047 1032//1032 -f 1048//1048 971//971 949//949 -f 949//949 971//971 1049//1049 -f 942//942 943//943 1006//1006 -f 1006//1006 943//943 947//947 -f 1006//1006 947//947 1049//1049 -f 1049//1049 947//947 948//948 -f 1049//1049 948//948 949//949 -f 971//971 970//970 1050//1050 -f 970//970 1051//1051 1050//1050 -f 1050//1050 1051//1051 1052//1052 -f 1050//1050 1052//1052 1053//1053 -f 1053//1053 1052//1052 1054//1054 -f 1053//1053 1054//1054 1055//1055 -f 1055//1055 1056//1056 1053//1053 -f 1053//1053 1056//1056 1057//1057 -f 1053//1053 1057//1057 1048//1048 -f 1048//1048 1057//1057 1058//1058 -f 1058//1058 1059//1059 1048//1048 -f 1048//1048 1059//1059 1060//1060 -f 1048//1048 1060//1060 971//971 -f 971//971 1060//1060 1061//1061 -f 971//971 1061//1061 969//969 -f 1062//1062 1063//1063 1064//1064 -f 1065//1065 1066//1066 1067//1067 -f 1065//1065 1067//1067 1063//1063 -f 1068//1068 1053//1053 1069//1069 -f 1069//1069 1053//1053 1067//1067 -f 1069//1069 1067//1067 1070//1070 -f 1070//1070 1067//1067 1066//1066 -f 1062//1062 1064//1064 1071//1071 -f 1071//1071 1064//1064 1050//1050 -f 1071//1071 1050//1050 1072//1072 -f 1068//1068 1073//1073 1053//1053 -f 1053//1053 1073//1073 1074//1074 -f 1053//1053 1074//1074 1050//1050 -f 1050//1050 1074//1074 1075//1075 -f 1050//1050 1075//1075 1072//1072 -f 1076//1076 1077//1077 1024//1024 -f 1078//1078 1079//1079 1080//1080 -f 1080//1080 1081//1081 1078//1078 -f 1078//1078 1081//1081 1082//1082 -f 1078//1078 1082//1082 1067//1067 -f 1082//1082 1083//1083 1067//1067 -f 1067//1067 1083//1083 1084//1084 -f 1067//1067 1084//1084 1085//1085 -f 1063//1063 1067//1067 1064//1064 -f 1064//1064 1067//1067 1085//1085 -f 1064//1064 1085//1085 1086//1086 -f 1086//1086 1085//1085 1087//1087 -f 1086//1086 1087//1087 1023//1023 -f 1023//1023 1087//1087 1088//1088 -f 1023//1023 1088//1088 1024//1024 -f 1024//1024 1088//1088 1089//1089 -f 1024//1024 1089//1089 1076//1076 -f 918//918 1090//1090 1091//1091 -f 1091//1091 1092//1092 918//918 -f 918//918 1092//1092 1093//1093 -f 918//918 1093//1093 919//919 -f 919//919 1093//1093 1094//1094 -f 919//919 1094//1094 1095//1095 -f 1095//1095 1096//1096 919//919 -f 919//919 1096//1096 1097//1097 -f 919//919 1097//1097 965//965 -f 1098//1098 1044//1044 1099//1099 -f 1099//1099 1044//1044 965//965 -f 1099//1099 965//965 1100//1100 -f 1100//1100 965//965 1097//1097 -f 1099//1099 1101//1101 1098//1098 -f 1098//1098 1101//1101 1102//1102 -f 1098//1098 1102//1102 1090//1090 -f 1090//1090 1102//1102 1103//1103 -f 1090//1090 1103//1103 1091//1091 -f 1104//1104 1105//1105 1106//1106 -f 968//968 1107//1107 918//918 -f 918//918 1107//1107 1108//1108 -f 918//918 1108//1108 1090//1090 -f 1090//1090 1108//1108 1109//1109 -f 1090//1090 1109//1109 1110//1110 -f 1105//1105 1111//1111 922//922 -f 922//922 1111//1111 1112//1112 -f 922//922 1112//1112 968//968 -f 1110//1110 1113//1113 1090//1090 -f 1090//1090 1113//1113 1114//1114 -f 1090//1090 1114//1114 1106//1106 -f 1106//1106 1114//1114 1115//1115 -f 1106//1106 1115//1115 1104//1104 -f 1106//1106 1116//1116 1117//1117 -f 1105//1105 922//922 1106//1106 -f 1106//1106 922//922 1118//1118 -f 1106//1106 1118//1118 1116//1116 -f 1119//1119 1120//1120 915//915 -f 915//915 1120//1120 1121//1121 -f 915//915 1121//1121 922//922 -f 922//922 1121//1121 1122//1122 -f 922//922 1122//1122 1118//1118 -f 1117//1117 1123//1123 1106//1106 -f 1106//1106 1123//1123 1124//1124 -f 1106//1106 1124//1124 967//967 -f 967//967 1124//1124 1125//1125 -f 1125//1125 1126//1126 967//967 -f 967//967 1126//1126 1127//1127 -f 967//967 1127//1127 928//928 -f 928//928 1127//1127 1119//1119 -f 928//928 1119//1119 927//927 -f 927//927 1119//1119 915//915 -f 1128//1128 1129//1129 1130//1130 -f 1130//1130 1129//1129 1131//1131 -f 1130//1130 1131//1131 1132//1132 -f 1132//1132 1131//1131 1133//1133 -f 1132//1132 1133//1133 1134//1134 -f 1134//1134 1133//1133 1135//1135 -f 1134//1134 1135//1135 1136//1136 -f 1137//1137 933//933 1138//1138 -f 1138//1138 933//933 934//934 -f 1138//1138 934//934 1139//1139 -f 1139//1139 934//934 937//937 -f 1139//1139 937//937 1140//1140 -f 928//928 929//929 966//966 -f 966//966 929//929 930//930 -f 966//966 930//930 1130//1130 -f 1130//1130 930//930 933//933 -f 1130//1130 933//933 1128//1128 -f 1128//1128 933//933 1137//1137 -f 1135//1135 1141//1141 1136//1136 -f 1136//1136 1141//1141 1142//1142 -f 1136//1136 1142//1142 937//937 -f 937//937 1142//1142 1143//1143 -f 937//937 1143//1143 1140//1140 -f 937//937 944//944 1144//1144 -f 1145//1145 1136//1136 1146//1146 -f 1146//1146 1136//1136 937//937 -f 1146//1146 937//937 1147//1147 -f 1147//1147 937//937 1144//1144 -f 913//913 914//914 964//964 -f 964//964 914//914 965//965 -f 964//964 965//965 974//974 -f 974//974 965//965 1030//1030 -f 974//974 1030//1030 1034//1034 -f 1034//1034 1030//1030 1148//1148 -f 1034//1034 1148//1148 1035//1035 -f 977//977 908//908 964//964 -f 964//964 908//908 909//909 -f 964//964 909//909 910//910 -f 897//897 898//898 894//894 -f 894//894 898//898 963//963 -f 894//894 963//963 893//893 -f 949//949 952//952 1048//1048 -f 1048//1048 952//952 953//953 -f 1048//1048 953//953 1053//1053 -f 1053//1053 953//953 956//956 -f 1053//1053 956//956 1067//1067 -f 1067//1067 956//956 957//957 -f 1067//1067 957//957 1078//1078 -f 1078//1078 957//957 958//958 -f 1078//1078 958//958 1149//1149 -f 1149//1149 958//958 891//891 -f 1149//1149 891//891 892//892 -f 1033//1033 1011//1011 1034//1034 -f 1034//1034 1011//1011 1010//1010 -f 1034//1034 1010//1010 974//974 -f 974//974 1010//1010 984//984 -f 974//974 984//984 972//972 -f 972//972 984//984 985//985 -f 1077//1077 1079//1079 1024//1024 -f 1024//1024 1079//1079 1078//1078 -f 1024//1024 1078//1078 963//963 -f 963//963 1078//1078 1149//1149 -f 963//963 1149//1149 893//893 -f 893//893 1149//1149 892//892 -f 1150//1150 1151//1151 1025//1025 -f 1152//1152 1153//1153 984//984 -f 984//984 1153//1153 1154//1154 -f 984//984 1154//1154 903//903 -f 1154//1154 1155//1155 903//903 -f 903//903 1155//1155 1156//1156 -f 903//903 1156//1156 904//904 -f 904//904 1156//1156 1157//1157 -f 904//904 1157//1157 1158//1158 -f 1008//1008 1026//1026 1010//1010 -f 1010//1010 1026//1026 1025//1025 -f 1010//1010 1025//1025 984//984 -f 984//984 1025//1025 1151//1151 -f 984//984 1151//1151 1152//1152 -f 1158//1158 1159//1159 904//904 -f 904//904 1159//1159 1160//1160 -f 904//904 1160//1160 1025//1025 -f 1025//1025 1160//1160 1161//1161 -f 1025//1025 1161//1161 1150//1150 -f 1029//1029 1022//1022 1027//1027 -f 1027//1027 1022//1022 1024//1024 -f 1027//1027 1024//1024 1025//1025 -f 1025//1025 1024//1024 963//963 -f 1025//1025 963//963 904//904 -f 904//904 963//963 905//905 -f 540//540 1154//1154 542//542 -f 542//542 1154//1154 1153//1153 -f 542//542 1153//1153 551//551 -f 551//551 1153//1153 1152//1152 -f 551//551 1152//1152 549//549 -f 549//549 1152//1152 1151//1151 -f 549//549 1151//1151 547//547 -f 547//547 1151//1151 1150//1150 -f 547//547 1150//1150 545//545 -f 545//545 1150//1150 1161//1161 -f 545//545 1161//1161 534//534 -f 534//534 1161//1161 1160//1160 -f 534//534 1160//1160 535//535 -f 535//535 1160//1160 1159//1159 -f 535//535 1159//1159 536//536 -f 536//536 1159//1159 1158//1158 -f 536//536 1158//1158 531//531 -f 531//531 1158//1158 1157//1157 -f 531//531 1157//1157 537//537 -f 537//537 1157//1157 1156//1156 -f 537//537 1156//1156 538//538 -f 538//538 1156//1156 1155//1155 -f 538//538 1155//1155 540//540 -f 540//540 1155//1155 1154//1154 -f 566//566 978//978 569//569 -f 569//569 978//978 977//977 -f 569//569 977//977 570//570 -f 570//570 977//977 976//976 -f 570//570 976//976 572//572 -f 572//572 976//976 975//975 -f 572//572 975//975 574//574 -f 574//574 975//975 973//973 -f 574//574 973//973 558//558 -f 558//558 973//973 972//972 -f 558//558 972//972 556//556 -f 556//556 972//972 985//985 -f 556//556 985//985 554//554 -f 554//554 985//985 983//983 -f 554//554 983//983 562//562 -f 562//562 983//983 982//982 -f 562//562 982//982 563//563 -f 563//563 982//982 981//981 -f 563//563 981//981 568//568 -f 568//568 981//981 980//980 -f 568//568 980//980 567//567 -f 567//567 980//980 979//979 -f 567//567 979//979 566//566 -f 566//566 979//979 978//978 -f 682//682 1071//1071 680//680 -f 680//680 1071//1071 1072//1072 -f 680//680 1072//1072 678//678 -f 678//678 1072//1072 1075//1075 -f 678//678 1075//1075 664//664 -f 664//664 1075//1075 1074//1074 -f 664//664 1074//1074 665//665 -f 665//665 1074//1074 1073//1073 -f 665//665 1073//1073 667//667 -f 667//667 1073//1073 1068//1068 -f 667//667 1068//1068 668//668 -f 668//668 1068//1068 1069//1069 -f 668//668 1069//1069 670//670 -f 670//670 1069//1069 1070//1070 -f 670//670 1070//1070 671//671 -f 671//671 1070//1070 1066//1066 -f 671//671 1066//1066 673//673 -f 673//673 1066//1066 1065//1065 -f 673//673 1065//1065 675//675 -f 675//675 1065//1065 1063//1063 -f 675//675 1063//1063 684//684 -f 684//684 1063//1063 1062//1062 -f 684//684 1062//1062 682//682 -f 682//682 1062//1062 1071//1071 -f 723//723 968//968 727//727 -f 727//727 968//968 1112//1112 -f 727//727 1112//1112 728//728 -f 728//728 1112//1112 1111//1111 -f 728//728 1111//1111 730//730 -f 730//730 1111//1111 1105//1105 -f 730//730 1105//1105 732//732 -f 732//732 1105//1105 1104//1104 -f 732//732 1104//1104 741//741 -f 741//741 1104//1104 1115//1115 -f 741//741 1115//1115 739//739 -f 739//739 1115//1115 1114//1114 -f 739//739 1114//1114 737//737 -f 737//737 1114//1114 1113//1113 -f 737//737 1113//1113 735//735 -f 735//735 1113//1113 1110//1110 -f 735//735 1110//1110 724//724 -f 724//724 1110//1110 1109//1109 -f 724//724 1109//1109 725//725 -f 725//725 1109//1109 1108//1108 -f 725//725 1108//1108 726//726 -f 726//726 1108//1108 1107//1107 -f 726//726 1107//1107 723//723 -f 723//723 1107//1107 968//968 -f 783//783 1089//1089 781//781 -f 781//781 1089//1089 1088//1088 -f 781//781 1088//1088 779//779 -f 779//779 1088//1088 1087//1087 -f 779//779 1087//1087 777//777 -f 777//777 1087//1087 1085//1085 -f 777//777 1085//1085 769//769 -f 769//769 1085//1085 1084//1084 -f 769//769 1084//1084 770//770 -f 770//770 1084//1084 1083//1083 -f 770//770 1083//1083 772//772 -f 772//772 1083//1083 1082//1082 -f 772//772 1082//1082 774//774 -f 774//774 1082//1082 1081//1081 -f 774//774 1081//1081 776//776 -f 776//776 1081//1081 1080//1080 -f 776//776 1080//1080 789//789 -f 789//789 1080//1080 1079//1079 -f 789//789 1079//1079 787//787 -f 787//787 1079//1079 1077//1077 -f 787//787 1077//1077 785//785 -f 785//785 1077//1077 1076//1076 -f 785//785 1076//1076 783//783 -f 783//783 1076//1076 1089//1089 -f 749//749 1094//1094 751//751 -f 751//751 1094//1094 1093//1093 -f 751//751 1093//1093 752//752 -f 752//752 1093//1093 1092//1092 -f 752//752 1092//1092 754//754 -f 754//754 1092//1092 1091//1091 -f 754//754 1091//1091 756//756 -f 756//756 1091//1091 1103//1103 -f 756//756 1103//1103 758//758 -f 758//758 1103//1103 1102//1102 -f 758//758 1102//1102 760//760 -f 760//760 1102//1102 1101//1101 -f 760//760 1101//1101 762//762 -f 762//762 1101//1101 1099//1099 -f 762//762 1099//1099 764//764 -f 764//764 1099//1099 1100//1100 -f 764//764 1100//1100 766//766 -f 766//766 1100//1100 1097//1097 -f 766//766 1097//1097 746//746 -f 746//746 1097//1097 1096//1096 -f 746//746 1096//1096 747//747 -f 747//747 1096//1096 1095//1095 -f 747//747 1095//1095 749//749 -f 749//749 1095//1095 1094//1094 -f 694//694 1121//1121 696//696 -f 696//696 1121//1121 1120//1120 -f 696//696 1120//1120 698//698 -f 698//698 1120//1120 1119//1119 -f 698//698 1119//1119 711//711 -f 711//711 1119//1119 1127//1127 -f 711//711 1127//1127 709//709 -f 709//709 1127//1127 1126//1126 -f 709//709 1126//1126 707//707 -f 707//707 1126//1126 1125//1125 -f 707//707 1125//1125 705//705 -f 705//705 1125//1125 1124//1124 -f 705//705 1124//1124 703//703 -f 703//703 1124//1124 1123//1123 -f 703//703 1123//1123 701//701 -f 701//701 1123//1123 1117//1117 -f 701//701 1117//1117 699//699 -f 699//699 1117//1117 1116//1116 -f 699//699 1116//1116 691//691 -f 691//691 1116//1116 1118//1118 -f 691//691 1118//1118 692//692 -f 692//692 1118//1118 1122//1122 -f 692//692 1122//1122 694//694 -f 694//694 1122//1122 1121//1121 -f 806//806 970//970 808//808 -f 808//808 970//970 969//969 -f 808//808 969//969 810//810 -f 810//810 969//969 1061//1061 -f 810//810 1061//1061 812//812 -f 812//812 1061//1061 1060//1060 -f 812//812 1060//1060 792//792 -f 792//792 1060//1060 1059//1059 -f 792//792 1059//1059 793//793 -f 793//793 1059//1059 1058//1058 -f 793//793 1058//1058 795//795 -f 795//795 1058//1058 1057//1057 -f 795//795 1057//1057 797//797 -f 797//797 1057//1057 1056//1056 -f 797//797 1056//1056 798//798 -f 798//798 1056//1056 1055//1055 -f 798//798 1055//1055 800//800 -f 800//800 1055//1055 1054//1054 -f 800//800 1054//1054 802//802 -f 802//802 1054//1054 1052//1052 -f 802//802 1052//1052 804//804 -f 804//804 1052//1052 1051//1051 -f 804//804 1051//1051 806//806 -f 806//806 1051//1051 970//970 -f 1162//1162 1001//1001 1163//1163 -f 1163//1163 1001//1001 992//992 -f 1163//1163 992//992 1164//1164 -f 1164//1164 992//992 989//989 -f 1164//1164 989//989 1165//1165 -f 1165//1165 989//989 988//988 -f 1165//1165 988//988 1166//1166 -f 1166//1166 988//988 987//987 -f 1166//1166 987//987 1167//1167 -f 1167//1167 987//987 986//986 -f 1167//1167 986//986 1168//1168 -f 1168//1168 986//986 1005//1005 -f 1168//1168 1005//1005 1169//1169 -f 1169//1169 1005//1005 1004//1004 -f 1169//1169 1004//1004 1170//1170 -f 1170//1170 1004//1004 993//993 -f 1170//1170 993//993 1171//1171 -f 1171//1171 993//993 995//995 -f 1171//1171 995//995 1172//1172 -f 1172//1172 995//995 997//997 -f 1172//1172 997//997 1173//1173 -f 1173//1173 997//997 999//999 -f 1173//1173 999//999 1162//1162 -f 1162//1162 999//999 1001//1001 -f 1172//1172 1173//1173 1174//1174 -f 1174//1174 1173//1173 1162//1162 -f 1174//1174 1162//1162 1163//1163 -f 1169//1169 1170//1170 1174//1174 -f 1174//1174 1170//1170 1171//1171 -f 1174//1174 1171//1171 1172//1172 -f 1166//1166 1167//1167 1174//1174 -f 1174//1174 1167//1167 1168//1168 -f 1174//1174 1168//1168 1169//1169 -f 1163//1163 1164//1164 1174//1174 -f 1174//1174 1164//1164 1165//1165 -f 1174//1174 1165//1165 1166//1166 -f 1175//1175 1128//1128 1176//1176 -f 1176//1176 1128//1128 1137//1137 -f 1176//1176 1137//1137 1177//1177 -f 1177//1177 1137//1137 1138//1138 -f 1177//1177 1138//1138 1178//1178 -f 1178//1178 1138//1138 1139//1139 -f 1178//1178 1139//1139 1179//1179 -f 1179//1179 1139//1139 1140//1140 -f 1179//1179 1140//1140 1180//1180 -f 1180//1180 1140//1140 1143//1143 -f 1180//1180 1143//1143 1181//1181 -f 1181//1181 1143//1143 1142//1142 -f 1181//1181 1142//1142 1182//1182 -f 1182//1182 1142//1142 1141//1141 -f 1182//1182 1141//1141 1183//1183 -f 1183//1183 1141//1141 1135//1135 -f 1183//1183 1135//1135 1184//1184 -f 1184//1184 1135//1135 1133//1133 -f 1184//1184 1133//1133 1185//1185 -f 1185//1185 1133//1133 1131//1131 -f 1185//1185 1131//1131 1186//1186 -f 1186//1186 1131//1131 1129//1129 -f 1186//1186 1129//1129 1175//1175 -f 1175//1175 1129//1129 1128//1128 -f 1185//1185 1186//1186 1187//1187 -f 1187//1187 1186//1186 1175//1175 -f 1187//1187 1175//1175 1176//1176 -f 1182//1182 1183//1183 1187//1187 -f 1187//1187 1183//1183 1184//1184 -f 1187//1187 1184//1184 1185//1185 -f 1179//1179 1180//1180 1187//1187 -f 1187//1187 1180//1180 1181//1181 -f 1187//1187 1181//1181 1182//1182 -f 1176//1176 1177//1177 1187//1187 -f 1187//1187 1177//1177 1178//1178 -f 1187//1187 1178//1178 1179//1179 -f 1188//1188 1021//1021 1189//1189 -f 1189//1189 1021//1021 1020//1020 -f 1189//1189 1020//1020 1190//1190 -f 1190//1190 1020//1020 1018//1018 -f 1190//1190 1018//1018 1191//1191 -f 1191//1191 1018//1018 1016//1016 -f 1191//1191 1016//1016 1192//1192 -f 1192//1192 1016//1016 1014//1014 -f 1192//1192 1014//1014 1193//1193 -f 1193//1193 1014//1014 1013//1013 -f 1193//1193 1013//1013 1194//1194 -f 1194//1194 1013//1013 1022//1022 -f 1194//1194 1022//1022 1195//1195 -f 1195//1195 1022//1022 1029//1029 -f 1195//1195 1029//1029 1196//1196 -f 1196//1196 1029//1029 1028//1028 -f 1196//1196 1028//1028 1197//1197 -f 1197//1197 1028//1028 1026//1026 -f 1197//1197 1026//1026 1198//1198 -f 1198//1198 1026//1026 1008//1008 -f 1198//1198 1008//1008 1199//1199 -f 1199//1199 1008//1008 1007//1007 -f 1199//1199 1007//1007 1188//1188 -f 1188//1188 1007//1007 1021//1021 -f 1198//1198 1199//1199 1200//1200 -f 1200//1200 1199//1199 1188//1188 -f 1200//1200 1188//1188 1189//1189 -f 1195//1195 1196//1196 1200//1200 -f 1200//1200 1196//1196 1197//1197 -f 1200//1200 1197//1197 1198//1198 -f 1192//1192 1193//1193 1200//1200 -f 1200//1200 1193//1193 1194//1194 -f 1200//1200 1194//1194 1195//1195 -f 1189//1189 1190//1190 1200//1200 -f 1200//1200 1190//1190 1191//1191 -f 1200//1200 1191//1191 1192//1192 -f 1201//1201 1047//1047 1202//1202 -f 1202//1202 1047//1047 1046//1046 -f 1202//1202 1046//1046 1203//1203 -f 1203//1203 1046//1046 1045//1045 -f 1203//1203 1045//1045 1204//1204 -f 1204//1204 1045//1045 1043//1043 -f 1204//1204 1043//1043 1205//1205 -f 1205//1205 1043//1043 1041//1041 -f 1205//1205 1041//1041 1206//1206 -f 1206//1206 1041//1041 1039//1039 -f 1206//1206 1039//1039 1207//1207 -f 1207//1207 1039//1039 1037//1037 -f 1207//1207 1037//1037 1208//1208 -f 1208//1208 1037//1037 1035//1035 -f 1208//1208 1035//1035 1209//1209 -f 1209//1209 1035//1035 1148//1148 -f 1209//1209 1148//1148 1210//1210 -f 1210//1210 1148//1148 1030//1030 -f 1210//1210 1030//1030 1211//1211 -f 1211//1211 1030//1030 1031//1031 -f 1211//1211 1031//1031 1212//1212 -f 1212//1212 1031//1031 1032//1032 -f 1212//1212 1032//1032 1201//1201 -f 1201//1201 1032//1032 1047//1047 -f 1211//1211 1212//1212 1213//1213 -f 1213//1213 1212//1212 1201//1201 -f 1213//1213 1201//1201 1202//1202 -f 1208//1208 1209//1209 1213//1213 -f 1213//1213 1209//1209 1210//1210 -f 1213//1213 1210//1210 1211//1211 -f 1205//1205 1206//1206 1213//1213 -f 1213//1213 1206//1206 1207//1207 -f 1213//1213 1207//1207 1208//1208 -f 1202//1202 1203//1203 1213//1213 -f 1213//1213 1203//1203 1204//1204 -f 1213//1213 1204//1204 1205//1205 -f 1214//1214 1002//1002 1215//1215 -f 1215//1215 1002//1002 1000//1000 -f 1215//1215 1000//1000 1216//1216 -f 1216//1216 1000//1000 1217//1217 -f 1217//1217 1000//1000 998//998 -f 1217//1217 998//998 1218//1218 -f 1218//1218 998//998 1219//1219 -f 1219//1219 998//998 996//996 -f 1219//1219 996//996 1220//1220 -f 1220//1220 996//996 994//994 -f 1220//1220 994//994 1221//1221 -f 1221//1221 994//994 1006//1006 -f 1221//1221 1006//1006 1049//1049 -f 1049//1049 971//971 1221//1221 -f 1221//1221 971//971 1050//1050 -f 1221//1221 1050//1050 1222//1222 -f 1222//1222 1050//1050 1064//1064 -f 1222//1222 1064//1064 1086//1086 -f 1222//1222 1086//1086 1023//1023 -f 1222//1222 1023//1023 1223//1223 -f 1223//1223 1023//1023 1012//1012 -f 1223//1223 1012//1012 1015//1015 -f 1223//1223 1015//1015 1224//1224 -f 1224//1224 1015//1015 1017//1017 -f 1224//1224 1017//1017 1225//1225 -f 1225//1225 1017//1017 1226//1226 -f 1226//1226 1017//1017 1019//1019 -f 1226//1226 1019//1019 1227//1227 -f 1227//1227 1019//1019 1228//1228 -f 1228//1228 1019//1019 1009//1009 -f 1228//1228 1009//1009 1229//1229 -f 1033//1033 1036//1036 1230//1230 -f 1033//1033 1230//1230 1011//1011 -f 1011//1011 1230//1230 1229//1229 -f 1011//1011 1229//1229 1009//1009 -f 1230//1230 1036//1036 1231//1231 -f 1231//1231 1036//1036 1038//1038 -f 1232//1232 1233//1233 1040//1040 -f 1040//1040 1233//1233 1234//1234 -f 1040//1040 1234//1234 1038//1038 -f 1038//1038 1234//1234 1235//1235 -f 1038//1038 1235//1235 1231//1231 -f 1232//1232 1040//1040 1236//1236 -f 1236//1236 1040//1040 1042//1042 -f 1236//1236 1042//1042 1237//1237 -f 1098//1098 1238//1238 1044//1044 -f 1044//1044 1238//1238 1237//1237 -f 1044//1044 1237//1237 1042//1042 -f 1098//1098 1090//1090 1238//1238 -f 1238//1238 1090//1090 1106//1106 -f 1238//1238 1106//1106 1239//1239 -f 1239//1239 1106//1106 967//967 -f 1239//1239 967//967 966//966 -f 1132//1132 1240//1240 1130//1130 -f 1130//1130 1240//1240 1239//1239 -f 1130//1130 1239//1239 966//966 -f 1240//1240 1132//1132 1241//1241 -f 1241//1241 1132//1132 1134//1134 -f 1241//1241 1134//1134 1242//1242 -f 1242//1242 1134//1134 1243//1243 -f 1243//1243 1134//1134 1244//1244 -f 1244//1244 1134//1134 1136//1136 -f 1244//1244 1136//1136 1245//1245 -f 1245//1245 1136//1136 1246//1246 -f 1246//1246 1136//1136 1145//1145 -f 1246//1246 1145//1145 1247//1247 -f 1248//1248 1247//1247 1146//1146 -f 1146//1146 1247//1247 1145//1145 -f 946//946 888//888 887//887 -f 1249//1249 946//946 1250//1250 -f 1250//1250 946//946 887//887 -f 1250//1250 887//887 1251//1251 -f 1251//1251 887//887 1252//1252 -f 1253//1253 1252//1252 889//889 -f 889//889 1252//1252 887//887 -f 1254//1254 1253//1253 889//889 -f 889//889 890//890 938//938 -f 938//938 1255//1255 889//889 -f 889//889 1255//1255 1256//1256 -f 889//889 1256//1256 1254//1254 -f 1003//1003 1002//1002 1257//1257 -f 1257//1257 1002//1002 1214//1214 -f 1258//1258 1259//1259 1260//1260 -f 1261//1261 1262//1262 1252//1252 -f 1252//1252 1262//1262 1263//1263 -f 1264//1264 1265//1265 1266//1266 -f 1266//1266 1265//1265 1267//1267 -f 1266//1266 1267//1267 1268//1268 -f 1268//1268 1267//1267 1269//1269 -f 1269//1269 1270//1270 1268//1268 -f 1268//1268 1270//1270 1271//1271 -f 1268//1268 1271//1271 1262//1262 -f 1262//1262 1271//1271 1272//1272 -f 1262//1262 1272//1272 1263//1263 -f 1273//1273 1251//1251 1274//1274 -f 1274//1274 1251//1251 1252//1252 -f 1274//1274 1252//1252 1275//1275 -f 1275//1275 1252//1252 1263//1263 -f 1276//1276 1277//1277 1253//1253 -f 1253//1253 1277//1277 1278//1278 -f 1253//1253 1278//1278 1252//1252 -f 1252//1252 1278//1278 1279//1279 -f 1252//1252 1279//1279 1261//1261 -f 1280//1280 1260//1260 1281//1281 -f 1281//1281 1260//1260 1282//1282 -f 1281//1281 1282//1282 1283//1283 -f 1264//1264 1258//1258 1265//1265 -f 1265//1265 1258//1258 1260//1260 -f 1265//1265 1260//1260 1284//1284 -f 1284//1284 1260//1260 1280//1280 -f 1285//1285 1286//1286 1287//1287 -f 1288//1288 1289//1289 1290//1290 -f 1290//1290 1289//1289 1283//1283 -f 1290//1290 1283//1283 1291//1291 -f 1291//1291 1283//1283 1282//1282 -f 1291//1291 1282//1282 1292//1292 -f 1292//1292 1282//1282 1293//1293 -f 1294//1294 1295//1295 1296//1296 -f 1296//1296 1295//1295 1297//1297 -f 1258//1258 1298//1298 1259//1259 -f 1259//1259 1298//1298 1299//1299 -f 1259//1259 1299//1299 1287//1287 -f 1287//1287 1299//1299 1300//1300 -f 1287//1287 1300//1300 1285//1285 -f 1286//1286 1297//1297 1287//1287 -f 1287//1287 1297//1297 1295//1295 -f 1287//1287 1295//1295 1282//1282 -f 1282//1282 1295//1295 1301//1301 -f 1282//1282 1301//1301 1293//1293 -f 1296//1296 1302//1302 1294//1294 -f 1294//1294 1302//1302 1303//1303 -f 1294//1294 1303//1303 1304//1304 -f 1304//1304 1303//1303 1305//1305 -f 1253//1253 1254//1254 1306//1306 -f 1276//1276 1307//1307 1303//1303 -f 1303//1303 1307//1307 1308//1308 -f 1303//1303 1308//1308 1305//1305 -f 1306//1306 1309//1309 1253//1253 -f 1253//1253 1309//1309 1310//1310 -f 1253//1253 1310//1310 1276//1276 -f 1276//1276 1310//1310 1311//1311 -f 1276//1276 1311//1311 1307//1307 -f 1273//1273 1274//1274 1312//1312 -f 1312//1312 1274//1274 1313//1313 -f 1313//1313 1314//1314 1312//1312 -f 1312//1312 1314//1314 1315//1315 -f 1312//1312 1315//1315 1316//1316 -f 1247//1247 1248//1248 1317//1317 -f 1317//1317 1248//1248 1316//1316 -f 1317//1317 1316//1316 1318//1318 -f 1318//1318 1316//1316 1315//1315 -f 1314//1314 1313//1313 1319//1319 -f 1320//1320 1321//1321 1240//1240 -f 1322//1322 1323//1323 1324//1324 -f 1324//1324 1323//1323 1321//1321 -f 1325//1325 1326//1326 1327//1327 -f 1327//1327 1326//1326 1322//1322 -f 1270//1270 1269//1269 1325//1325 -f 1240//1240 1241//1241 1320//1320 -f 1320//1320 1241//1241 1242//1242 -f 1320//1320 1242//1242 1328//1328 -f 1328//1328 1242//1242 1243//1243 -f 1328//1328 1243//1243 1329//1329 -f 1243//1243 1244//1244 1329//1329 -f 1329//1329 1244//1244 1245//1245 -f 1329//1329 1245//1245 1330//1330 -f 1330//1330 1245//1245 1246//1246 -f 1330//1330 1246//1246 1331//1331 -f 1246//1246 1247//1247 1331//1331 -f 1331//1331 1247//1247 1317//1317 -f 1331//1331 1317//1317 1318//1318 -f 1321//1321 1320//1320 1324//1324 -f 1324//1324 1320//1320 1328//1328 -f 1324//1324 1328//1328 1332//1332 -f 1332//1332 1328//1328 1329//1329 -f 1332//1332 1329//1329 1333//1333 -f 1333//1333 1329//1329 1330//1330 -f 1333//1333 1330//1330 1334//1334 -f 1334//1334 1330//1330 1331//1331 -f 1334//1334 1331//1331 1335//1335 -f 1335//1335 1331//1331 1318//1318 -f 1335//1335 1318//1318 1315//1315 -f 1322//1322 1324//1324 1327//1327 -f 1327//1327 1324//1324 1332//1332 -f 1327//1327 1332//1332 1336//1336 -f 1336//1336 1332//1332 1333//1333 -f 1336//1336 1333//1333 1337//1337 -f 1337//1337 1333//1333 1334//1334 -f 1337//1337 1334//1334 1338//1338 -f 1338//1338 1334//1334 1335//1335 -f 1338//1338 1335//1335 1319//1319 -f 1319//1319 1335//1335 1315//1315 -f 1319//1319 1315//1315 1314//1314 -f 1325//1325 1327//1327 1270//1270 -f 1270//1270 1327//1327 1336//1336 -f 1270//1270 1336//1336 1271//1271 -f 1271//1271 1336//1336 1337//1337 -f 1271//1271 1337//1337 1272//1272 -f 1272//1272 1337//1337 1338//1338 -f 1272//1272 1338//1338 1263//1263 -f 1263//1263 1338//1338 1319//1319 -f 1263//1263 1319//1319 1275//1275 -f 1275//1275 1319//1319 1313//1313 -f 1275//1275 1313//1313 1274//1274 -f 1239//1239 1240//1240 1339//1339 -f 1339//1339 1240//1240 1321//1321 -f 1339//1339 1321//1321 1340//1340 -f 1340//1340 1321//1321 1323//1323 -f 1340//1340 1323//1323 1341//1341 -f 1341//1341 1323//1323 1342//1342 -f 1323//1323 1322//1322 1342//1342 -f 1342//1342 1322//1322 1326//1326 -f 1342//1342 1326//1326 1267//1267 -f 1267//1267 1326//1326 1325//1325 -f 1267//1267 1325//1325 1269//1269 -f 1238//1238 1239//1239 1343//1343 -f 1343//1343 1239//1239 1339//1339 -f 1343//1343 1339//1339 1344//1344 -f 1339//1339 1340//1340 1344//1344 -f 1344//1344 1340//1340 1341//1341 -f 1344//1344 1341//1341 1345//1345 -f 1341//1341 1342//1342 1345//1345 -f 1345//1345 1342//1342 1267//1267 -f 1345//1345 1267//1267 1265//1265 -f 1237//1237 1238//1238 1346//1346 -f 1346//1346 1238//1238 1343//1343 -f 1346//1346 1343//1343 1347//1347 -f 1347//1347 1343//1343 1344//1344 -f 1347//1347 1344//1344 1348//1348 -f 1348//1348 1344//1344 1349//1349 -f 1344//1344 1345//1345 1349//1349 -f 1349//1349 1345//1345 1265//1265 -f 1349//1349 1265//1265 1284//1284 -f 1350//1350 1230//1230 1231//1231 -f 1351//1351 1352//1352 1353//1353 -f 1353//1353 1352//1352 1354//1354 -f 1283//1283 1289//1289 1355//1355 -f 1356//1356 1357//1357 1355//1355 -f 1355//1355 1357//1357 1358//1358 -f 1355//1355 1358//1358 1283//1283 -f 1283//1283 1358//1358 1359//1359 -f 1283//1283 1359//1359 1281//1281 -f 1281//1281 1359//1359 1360//1360 -f 1281//1281 1360//1360 1280//1280 -f 1347//1347 1348//1348 1361//1361 -f 1361//1361 1348//1348 1349//1349 -f 1362//1362 1346//1346 1347//1347 -f 1363//1363 1350//1350 1364//1364 -f 1364//1364 1350//1350 1231//1231 -f 1364//1364 1231//1231 1365//1365 -f 1365//1365 1231//1231 1235//1235 -f 1237//1237 1346//1346 1236//1236 -f 1236//1236 1346//1346 1362//1362 -f 1236//1236 1362//1362 1232//1232 -f 1232//1232 1362//1362 1366//1366 -f 1232//1232 1366//1366 1233//1233 -f 1233//1233 1366//1366 1365//1365 -f 1233//1233 1365//1365 1234//1234 -f 1234//1234 1365//1365 1235//1235 -f 1347//1347 1361//1361 1362//1362 -f 1362//1362 1361//1361 1367//1367 -f 1362//1362 1367//1367 1366//1366 -f 1366//1366 1367//1367 1368//1368 -f 1366//1366 1368//1368 1365//1365 -f 1365//1365 1368//1368 1353//1353 -f 1365//1365 1353//1353 1364//1364 -f 1364//1364 1353//1353 1354//1354 -f 1364//1364 1354//1354 1363//1363 -f 1284//1284 1280//1280 1349//1349 -f 1349//1349 1280//1280 1360//1360 -f 1349//1349 1360//1360 1361//1361 -f 1361//1361 1360//1360 1359//1359 -f 1361//1361 1359//1359 1367//1367 -f 1367//1367 1359//1359 1358//1358 -f 1367//1367 1358//1358 1368//1368 -f 1368//1368 1358//1358 1357//1357 -f 1368//1368 1357//1357 1353//1353 -f 1353//1353 1357//1357 1356//1356 -f 1353//1353 1356//1356 1351//1351 -f 1230//1230 1350//1350 1229//1229 -f 1229//1229 1350//1350 1363//1363 -f 1229//1229 1363//1363 1369//1369 -f 1369//1369 1363//1363 1354//1354 -f 1369//1369 1354//1354 1370//1370 -f 1370//1370 1354//1354 1371//1371 -f 1371//1371 1354//1354 1352//1352 -f 1371//1371 1352//1352 1372//1372 -f 1355//1355 1289//1289 1288//1288 -f 1352//1352 1351//1351 1372//1372 -f 1372//1372 1351//1351 1356//1356 -f 1372//1372 1356//1356 1373//1373 -f 1373//1373 1356//1356 1355//1355 -f 1373//1373 1355//1355 1374//1374 -f 1374//1374 1355//1355 1288//1288 -f 1374//1374 1288//1288 1290//1290 -f 1375//1375 1376//1376 1223//1223 -f 1293//1293 1301//1301 1377//1377 -f 1374//1374 1378//1378 1373//1373 -f 1373//1373 1378//1378 1379//1379 -f 1373//1373 1379//1379 1372//1372 -f 1372//1372 1379//1379 1371//1371 -f 1380//1380 1370//1370 1371//1371 -f 1228//1228 1229//1229 1369//1369 -f 1374//1374 1290//1290 1378//1378 -f 1378//1378 1290//1290 1291//1291 -f 1378//1378 1291//1291 1381//1381 -f 1381//1381 1291//1291 1292//1292 -f 1381//1381 1292//1292 1382//1382 -f 1382//1382 1292//1292 1293//1293 -f 1382//1382 1293//1293 1383//1383 -f 1383//1383 1293//1293 1377//1377 -f 1383//1383 1377//1377 1384//1384 -f 1223//1223 1224//1224 1375//1375 -f 1375//1375 1224//1224 1225//1225 -f 1375//1375 1225//1225 1385//1385 -f 1385//1385 1225//1225 1226//1226 -f 1385//1385 1226//1226 1386//1386 -f 1386//1386 1226//1226 1227//1227 -f 1386//1386 1227//1227 1387//1387 -f 1387//1387 1227//1227 1228//1228 -f 1387//1387 1228//1228 1380//1380 -f 1380//1380 1228//1228 1369//1369 -f 1380//1380 1369//1369 1370//1370 -f 1371//1371 1379//1379 1380//1380 -f 1380//1380 1379//1379 1378//1378 -f 1380//1380 1378//1378 1387//1387 -f 1387//1387 1378//1378 1381//1381 -f 1387//1387 1381//1381 1386//1386 -f 1386//1386 1381//1381 1382//1382 -f 1386//1386 1382//1382 1385//1385 -f 1385//1385 1382//1382 1383//1383 -f 1385//1385 1383//1383 1375//1375 -f 1375//1375 1383//1383 1384//1384 -f 1375//1375 1384//1384 1376//1376 -f 1222//1222 1223//1223 1388//1388 -f 1388//1388 1223//1223 1376//1376 -f 1388//1388 1376//1376 1389//1389 -f 1389//1389 1376//1376 1384//1384 -f 1389//1389 1384//1384 1390//1390 -f 1384//1384 1377//1377 1390//1390 -f 1390//1390 1377//1377 1301//1301 -f 1390//1390 1301//1301 1295//1295 -f 1221//1221 1222//1222 1391//1391 -f 1391//1391 1222//1222 1388//1388 -f 1391//1391 1388//1388 1392//1392 -f 1388//1388 1389//1389 1392//1392 -f 1392//1392 1389//1389 1390//1390 -f 1392//1392 1390//1390 1393//1393 -f 1393//1393 1390//1390 1295//1295 -f 1393//1393 1295//1295 1294//1294 -f 1294//1294 1304//1304 1394//1394 -f 1294//1294 1394//1394 1393//1393 -f 1393//1393 1394//1394 1395//1395 -f 1393//1393 1395//1395 1392//1392 -f 1392//1392 1395//1395 1391//1391 -f 1391//1391 1395//1395 1220//1220 -f 1391//1391 1220//1220 1221//1221 -f 1309//1309 1396//1396 1397//1397 -f 1396//1396 1398//1398 1399//1399 -f 1398//1398 1214//1214 1215//1215 -f 1398//1398 1215//1215 1399//1399 -f 1399//1399 1215//1215 1216//1216 -f 1399//1399 1216//1216 1400//1400 -f 1400//1400 1216//1216 1217//1217 -f 1400//1400 1217//1217 1401//1401 -f 1401//1401 1217//1217 1218//1218 -f 1401//1401 1218//1218 1402//1402 -f 1402//1402 1218//1218 1219//1219 -f 1402//1402 1219//1219 1403//1403 -f 1403//1403 1219//1219 1220//1220 -f 1403//1403 1220//1220 1395//1395 -f 1396//1396 1399//1399 1397//1397 -f 1397//1397 1399//1399 1400//1400 -f 1397//1397 1400//1400 1404//1404 -f 1404//1404 1400//1400 1401//1401 -f 1404//1404 1401//1401 1405//1405 -f 1405//1405 1401//1401 1402//1402 -f 1405//1405 1402//1402 1406//1406 -f 1406//1406 1402//1402 1403//1403 -f 1406//1406 1403//1403 1407//1407 -f 1407//1407 1403//1403 1395//1395 -f 1407//1407 1395//1395 1394//1394 -f 1309//1309 1397//1397 1310//1310 -f 1310//1310 1397//1397 1404//1404 -f 1310//1310 1404//1404 1311//1311 -f 1311//1311 1404//1404 1405//1405 -f 1311//1311 1405//1405 1307//1307 -f 1307//1307 1405//1405 1406//1406 -f 1307//1307 1406//1406 1308//1308 -f 1308//1308 1406//1406 1407//1407 -f 1308//1308 1407//1407 1305//1305 -f 1305//1305 1407//1407 1394//1394 -f 1305//1305 1394//1394 1304//1304 -f 1309//1309 1306//1306 1408//1408 -f 1309//1309 1408//1408 1396//1396 -f 1396//1396 1408//1408 1409//1409 -f 1396//1396 1409//1409 1398//1398 -f 1398//1398 1409//1409 1257//1257 -f 1398//1398 1257//1257 1214//1214 -f 945//945 946//946 1410//1410 -f 1410//1410 946//946 1249//1249 -f 1410//1410 1249//1249 1411//1411 -f 1411//1411 1249//1249 1412//1412 -f 1412//1412 1249//1249 1250//1250 -f 1412//1412 1250//1250 1413//1413 -f 1413//1413 1250//1250 1414//1414 -f 1414//1414 1250//1250 1251//1251 -f 1414//1414 1251//1251 1273//1273 -f 945//945 1415//1415 1416//1416 -f 1410//1410 1415//1415 945//945 -f 1411//1411 1412//1412 1417//1417 -f 1413//1413 1414//1414 1418//1418 -f 1414//1414 1273//1273 1418//1418 -f 1418//1418 1273//1273 1312//1312 -f 1418//1418 1312//1312 1419//1419 -f 1419//1419 1312//1312 1316//1316 -f 1420//1420 1421//1421 1422//1422 -f 1412//1412 1413//1413 1417//1417 -f 1417//1417 1413//1413 1418//1418 -f 1417//1417 1418//1418 1422//1422 -f 1422//1422 1418//1418 1419//1419 -f 1422//1422 1419//1419 1420//1420 -f 1420//1420 1419//1419 1316//1316 -f 1420//1420 1316//1316 1248//1248 -f 1423//1423 1424//1424 1416//1416 -f 1416//1416 1424//1424 1425//1425 -f 1416//1416 1425//1425 945//945 -f 1410//1410 1411//1411 1415//1415 -f 1415//1415 1411//1411 1417//1417 -f 1415//1415 1417//1417 1416//1416 -f 1416//1416 1417//1417 1422//1422 -f 1416//1416 1422//1422 1423//1423 -f 1423//1423 1422//1422 1421//1421 -f 1248//1248 1146//1146 1420//1420 -f 1420//1420 1146//1146 1147//1147 -f 1420//1420 1147//1147 1421//1421 -f 1421//1421 1147//1147 1423//1423 -f 1423//1423 1147//1147 1144//1144 -f 1423//1423 1144//1144 1424//1424 -f 944//944 945//945 1144//1144 -f 1144//1144 945//945 1425//1425 -f 1144//1144 1425//1425 1424//1424 -f 1306//1306 1254//1254 1426//1426 -f 1426//1426 1254//1254 1256//1256 -f 1426//1426 1256//1256 1427//1427 -f 1427//1427 1256//1256 1428//1428 -f 1428//1428 1256//1256 1255//1255 -f 1428//1428 1255//1255 1429//1429 -f 938//938 939//939 1255//1255 -f 1255//1255 939//939 1430//1430 -f 1255//1255 1430//1430 1429//1429 -f 939//939 1431//1431 1432//1432 -f 1433//1433 1431//1431 939//939 -f 1434//1434 1435//1435 1436//1436 -f 1437//1437 1438//1438 1439//1439 -f 1438//1438 1257//1257 1439//1439 -f 1439//1439 1257//1257 1409//1409 -f 1439//1439 1409//1409 1440//1440 -f 1440//1440 1409//1409 1408//1408 -f 1426//1426 1427//1427 1441//1441 -f 1435//1435 1437//1437 1436//1436 -f 1436//1436 1437//1437 1439//1439 -f 1436//1436 1439//1439 1441//1441 -f 1441//1441 1439//1439 1440//1440 -f 1441//1441 1440//1440 1426//1426 -f 1426//1426 1440//1440 1408//1408 -f 1426//1426 1408//1408 1306//1306 -f 1428//1428 1429//1429 1432//1432 -f 1432//1432 1429//1429 1430//1430 -f 1432//1432 1430//1430 939//939 -f 1433//1433 1434//1434 1431//1431 -f 1431//1431 1434//1434 1436//1436 -f 1431//1431 1436//1436 1432//1432 -f 1432//1432 1436//1436 1441//1441 -f 1432//1432 1441//1441 1428//1428 -f 1428//1428 1441//1441 1427//1427 -f 939//939 940//940 1433//1433 -f 1433//1433 940//940 990//990 -f 1433//1433 990//990 1434//1434 -f 1434//1434 990//990 1435//1435 -f 1435//1435 990//990 991//991 -f 1435//1435 991//991 1437//1437 -f 1437//1437 991//991 1438//1438 -f 1438//1438 991//991 1003//1003 -f 1438//1438 1003//1003 1257//1257 -f 863//863 1266//1266 865//865 -f 865//865 1266//1266 1268//1268 -f 865//865 1268//1268 867//867 -f 867//867 1268//1268 1262//1262 -f 867//867 1262//1262 869//869 -f 869//869 1262//1262 1261//1261 -f 869//869 1261//1261 880//880 -f 880//880 1261//1261 1279//1279 -f 880//880 1279//1279 881//881 -f 881//881 1279//1279 1278//1278 -f 881//881 1278//1278 883//883 -f 883//883 1278//1278 1277//1277 -f 883//883 1277//1277 885//885 -f 885//885 1277//1277 1276//1276 -f 885//885 1276//1276 886//886 -f 886//886 1276//1276 1303//1303 -f 886//886 1303//1303 872//872 -f 872//872 1303//1303 1302//1302 -f 872//872 1302//1302 874//874 -f 874//874 1302//1302 1296//1296 -f 874//874 1296//1296 876//876 -f 876//876 1296//1296 1297//1297 -f 876//876 1297//1297 878//878 -f 878//878 1297//1297 1286//1286 -f 878//878 1286//1286 879//879 -f 879//879 1286//1286 1285//1285 -f 879//879 1285//1285 853//853 -f 853//853 1285//1285 1300//1300 -f 853//853 1300//1300 855//855 -f 855//855 1300//1300 1299//1299 -f 855//855 1299//1299 857//857 -f 857//857 1299//1299 1298//1298 -f 857//857 1298//1298 859//859 -f 859//859 1298//1298 1258//1258 -f 859//859 1258//1258 861//861 -f 861//861 1258//1258 1264//1264 -f 861//861 1264//1264 863//863 -f 863//863 1264//1264 1266//1266 -f 1442//1442 1443//1443 1282//1282 -f 1282//1282 1443//1443 1287//1287 -f 1443//1443 1444//1444 1287//1287 -f 1287//1287 1444//1444 1259//1259 -f 1444//1444 1445//1445 1259//1259 -f 1259//1259 1445//1445 1260//1260 -f 1445//1445 1442//1442 1260//1260 -f 1260//1260 1442//1442 1282//1282 -f 1445//1445 1444//1444 1442//1442 -f 1442//1442 1444//1444 1443//1443 -f 846//846 844//844 862//862 -f 862//862 844//844 860//860 -f 844//844 842//842 860//860 -f 860//860 842//842 840//840 -f 860//860 840//840 858//858 -f 858//858 840//840 838//838 -f 858//858 838//838 856//856 -f 856//856 838//838 836//836 -f 856//856 836//836 854//854 -f 854//854 836//836 835//835 -f 854//854 835//835 852//852 -f 852//852 835//835 833//833 -f 852//852 833//833 877//877 -f 877//877 833//833 831//831 -f 877//877 831//831 875//875 -f 875//875 831//831 829//829 -f 875//875 829//829 873//873 -f 873//873 829//829 827//827 -f 873//873 827//827 871//871 -f 871//871 827//827 825//825 -f 871//871 825//825 884//884 -f 884//884 825//825 823//823 -f 884//884 823//823 882//882 -f 882//882 823//823 851//851 -f 882//882 851//851 870//870 -f 870//870 851//851 850//850 -f 870//870 850//850 868//868 -f 868//868 850//850 848//848 -f 868//868 848//848 866//866 -f 866//866 848//848 846//846 -f 866//866 846//846 864//864 -f 864//864 846//846 862//862 -f 1446//1446 1447//1447 1448//1448 -f 1448//1448 1447//1447 1449//1449 -f 1448//1448 1449//1449 1450//1450 -f 1450//1450 1449//1449 1451//1451 -f 1450//1450 1451//1451 1452//1452 -f 1452//1452 1451//1451 1453//1453 -f 1452//1452 1453//1453 1454//1454 -f 1454//1454 1453//1453 1455//1455 -f 1454//1454 1455//1455 1456//1456 -f 1456//1456 1455//1455 1457//1457 -f 1456//1456 1457//1457 1458//1458 -f 1458//1458 1457//1457 1459//1459 -f 1458//1458 1459//1459 1460//1460 -f 1460//1460 1459//1459 1461//1461 -f 1460//1460 1461//1461 1462//1462 -f 1462//1462 1461//1461 1463//1463 -f 1462//1462 1463//1463 1464//1464 -f 1464//1464 1463//1463 1465//1465 -f 1464//1464 1465//1465 1466//1466 -f 1466//1466 1465//1465 1467//1467 -f 1466//1466 1467//1467 1468//1468 -f 1468//1468 1467//1467 1469//1469 -f 1468//1468 1469//1469 1470//1470 -f 1470//1470 1469//1469 1471//1471 -f 1470//1470 1471//1471 1448//1448 -f 1448//1448 1471//1471 1446//1446 -f 1449//1449 1447//1447 843//843 -f 843//843 1447//1447 841//841 -f 1447//1447 1446//1446 841//841 -f 841//841 1446//1446 1471//1471 -f 841//841 1471//1471 839//839 -f 839//839 1471//1471 1469//1469 -f 839//839 1469//1469 837//837 -f 837//837 1469//1469 1467//1467 -f 837//837 1467//1467 834//834 -f 834//834 1467//1467 1465//1465 -f 834//834 1465//1465 832//832 -f 832//832 1465//1465 1463//1463 -f 832//832 1463//1463 830//830 -f 830//830 1463//1463 1461//1461 -f 830//830 1461//1461 828//828 -f 828//828 1461//1461 1459//1459 -f 828//828 1459//1459 826//826 -f 826//826 1459//1459 1457//1457 -f 826//826 1457//1457 824//824 -f 824//824 1457//1457 1455//1455 -f 824//824 1455//1455 822//822 -f 822//822 1455//1455 1453//1453 -f 822//822 1453//1453 849//849 -f 849//849 1453//1453 1451//1451 -f 849//849 1451//1451 847//847 -f 847//847 1451//1451 1449//1449 -f 847//847 1449//1449 845//845 -f 845//845 1449//1449 843//843 -f 1460//1460 1472//1472 1458//1458 -f 1458//1458 1472//1472 1473//1473 -f 1458//1458 1473//1473 1456//1456 -f 1456//1456 1473//1473 1474//1474 -f 1456//1456 1474//1474 1454//1454 -f 1454//1454 1474//1474 1475//1475 -f 1454//1454 1475//1475 1452//1452 -f 1452//1452 1475//1475 1476//1476 -f 1452//1452 1476//1476 1450//1450 -f 1450//1450 1476//1476 1477//1477 -f 1450//1450 1477//1477 1448//1448 -f 1448//1448 1477//1477 1478//1478 -f 1448//1448 1478//1478 1470//1470 -f 1470//1470 1478//1478 1479//1479 -f 1470//1470 1479//1479 1468//1468 -f 1468//1468 1479//1479 1480//1480 -f 1468//1468 1480//1480 1466//1466 -f 1466//1466 1480//1480 1481//1481 -f 1466//1466 1481//1481 1464//1464 -f 1464//1464 1481//1481 1482//1482 -f 1464//1464 1482//1482 1462//1462 -f 1462//1462 1482//1482 1483//1483 -f 1462//1462 1483//1483 1460//1460 -f 1460//1460 1483//1483 1472//1472 -f 1480//1480 1479//1479 1484//1484 -f 1484//1484 1479//1479 1478//1478 -f 1484//1484 1478//1478 1477//1477 -f 1483//1483 1482//1482 1484//1484 -f 1484//1484 1482//1482 1481//1481 -f 1484//1484 1481//1481 1480//1480 -f 1474//1474 1473//1473 1484//1484 -f 1484//1484 1473//1473 1472//1472 -f 1484//1484 1472//1472 1483//1483 -f 1477//1477 1476//1476 1484//1484 -f 1484//1484 1476//1476 1475//1475 -f 1484//1484 1475//1475 1474//1474 -f 597//597 1485//1485 624//624 -f 624//624 1485//1485 745//745 -f 624//624 745//745 622//622 -f 311//311 597//597 312//312 -f 312//312 597//597 624//624 -f 312//312 624//624 289//289 -f 289//289 624//624 618//618 -f 289//289 618//618 288//288 -f 288//288 618//618 520//520 -f 288//288 520//520 278//278 -f 179//179 255//255 254//254 -f 286//286 525//525 643//643 -f 635//635 634//634 644//644 -f 644//644 634//634 1486//1486 -f 644//644 1486//1486 180//180 -f 286//286 643//643 287//287 -f 287//287 643//643 644//644 -f 287//287 644//644 254//254 -f 254//254 644//644 180//180 -f 254//254 180//180 179//179 -f 337//337 715//715 714//714 -f 337//337 714//714 335//335 -f 335//335 714//714 717//717 -f 335//335 717//717 325//325 -f 325//325 717//717 595//595 -f 325//325 595//595 345//345 -f 186//186 190//190 816//816 -f 186//186 816//816 250//250 -f 250//250 816//816 819//819 -f 250//250 819//819 247//247 -f 247//247 819//819 821//821 -f 247//247 821//821 248//248 -f 1487//1487 197//197 807//807 -f 807//807 197//197 805//805 -f 1487//1487 807//807 1488//1488 -f 1488//1488 807//807 809//809 -f 1488//1488 809//809 1489//1489 -f 1489//1489 809//809 811//811 -f 951//951 1489//1489 813//813 -f 813//813 1489//1489 811//811 -f 191//191 950//950 189//189 -f 189//189 950//950 815//815 -f 191//191 197//197 1487//1487 -f 951//951 950//950 1489//1489 -f 1489//1489 950//950 191//191 -f 1489//1489 191//191 1488//1488 -f 1488//1488 191//191 1487//1487 -f 1490//1490 799//799 1491//1491 -f 1491//1491 799//799 801//801 -f 1491//1491 801//801 1492//1492 -f 1492//1492 801//801 803//803 -f 197//197 1492//1492 805//805 -f 805//805 1492//1492 803//803 -f 962//962 196//196 689//689 -f 689//689 196//196 195//195 -f 1490//1490 961//961 799//799 -f 799//799 961//961 796//796 -f 197//197 196//196 1492//1492 -f 1492//1492 196//196 1491//1491 -f 1491//1491 196//196 1490//1490 -f 1490//1490 196//196 962//962 -f 1490//1490 962//962 961//961 -f 645//645 642//642 1493//1493 -f 1493//1493 642//642 1494//1494 -f 1493//1493 1494//1494 634//634 -f 634//634 1494//1494 1486//1486 -f 1495//1495 786//786 646//646 -f 646//646 786//786 784//784 -f 646//646 784//784 633//633 -f 530//530 896//896 528//528 -f 528//528 896//896 1496//1496 -f 528//528 1496//1496 642//642 -f 642//642 1496//1496 1497//1497 -f 642//642 1497//1497 1494//1494 -f 895//895 791//791 1498//1498 -f 1498//1498 791//791 790//790 -f 1498//1498 790//790 1499//1499 -f 1499//1499 790//790 1500//1500 -f 1500//1500 790//790 788//788 -f 1500//1500 788//788 1495//1495 -f 1495//1495 788//788 786//786 -f 896//896 895//895 1496//1496 -f 1496//1496 895//895 1498//1498 -f 1501//1501 782//782 1502//1502 -f 1502//1502 782//782 780//780 -f 1502//1502 780//780 1503//1503 -f 1503//1503 780//780 778//778 -f 1503//1503 778//778 1504//1504 -f 1504//1504 778//778 771//771 -f 1504//1504 771//771 955//955 -f 954//954 687//687 1505//1505 -f 1505//1505 687//687 636//636 -f 1505//1505 636//636 638//638 -f 633//633 784//784 651//651 -f 651//651 784//784 782//782 -f 651//651 782//782 1501//1501 -f 955//955 954//954 1504//1504 -f 1504//1504 954//954 1505//1505 -f 745//745 1485//1485 1506//1506 -f 1506//1506 1485//1485 1507//1507 -f 1506//1506 1507//1507 623//623 -f 623//623 1507//1507 612//612 -f 620//620 759//759 621//621 -f 621//621 759//759 761//761 -f 621//621 761//761 1508//1508 -f 1508//1508 761//761 1509//1509 -f 1509//1509 761//761 763//763 -f 1509//1509 763//763 1510//1510 -f 1510//1510 763//763 765//765 -f 1510//1510 765//765 1511//1511 -f 1511//1511 765//765 767//767 -f 1511//1511 767//767 912//912 -f 1512//1512 911//911 581//581 -f 1507//1507 1513//1513 612//612 -f 612//612 1513//1513 1512//1512 -f 612//612 1512//1512 580//580 -f 580//580 1512//1512 581//581 -f 912//912 911//911 1511//1511 -f 1511//1511 911//911 1512//1512 -f 1514//1514 753//753 1515//1515 -f 1515//1515 753//753 755//755 -f 1515//1515 755//755 1516//1516 -f 1516//1516 755//755 757//757 -f 1516//1516 757//757 625//625 -f 625//625 757//757 759//759 -f 625//625 759//759 620//620 -f 610//610 611//611 1517//1517 -f 1517//1517 611//611 661//661 -f 1517//1517 661//661 921//921 -f 920//920 750//750 1518//1518 -f 1518//1518 750//750 753//753 -f 1518//1518 753//753 1514//1514 -f 921//921 920//920 1517//1517 -f 1517//1517 920//920 1518//1518 -f 593//593 1519//1519 706//706 -f 706//706 1519//1519 708//708 -f 932//932 594//594 720//720 -f 720//720 594//594 596//596 -f 1520//1520 931//931 712//712 -f 712//712 931//931 713//713 -f 1520//1520 712//712 1521//1521 -f 1521//1521 712//712 710//710 -f 1521//1521 710//710 1519//1519 -f 1519//1519 710//710 708//708 -f 593//593 594//594 1519//1519 -f 1519//1519 594//594 1521//1521 -f 1521//1521 594//594 1520//1520 -f 1520//1520 594//594 932//932 -f 1520//1520 932//932 931//931 -f 1522//1522 704//704 1523//1523 -f 1523//1523 704//704 702//702 -f 1523//1523 702//702 1524//1524 -f 1524//1524 702//702 700//700 -f 926//926 1524//1524 693//693 -f 693//693 1524//1524 700//700 -f 586//586 925//925 587//587 -f 587//587 925//925 663//663 -f 1522//1522 593//593 704//704 -f 704//704 593//593 706//706 -f 586//586 593//593 1522//1522 -f 926//926 925//925 1524//1524 -f 1524//1524 925//925 586//586 -f 1524//1524 586//586 1523//1523 -f 1523//1523 586//586 1522//1522 -f 1525//1525 681//681 1526//1526 -f 1526//1526 681//681 679//679 -f 1526//1526 679//679 1527//1527 -f 1527//1527 679//679 677//677 -f 1527//1527 677//677 1528//1528 -f 1528//1528 677//677 676//676 -f 960//960 1528//1528 666//666 -f 666//666 1528//1528 676//676 -f 185//185 959//959 194//194 -f 194//194 959//959 690//690 -f 1525//1525 199//199 681//681 -f 681//681 199//199 683//683 -f 1526//1526 185//185 1525//1525 -f 1525//1525 185//185 199//199 -f 960//960 959//959 1528//1528 -f 1528//1528 959//959 185//185 -f 1528//1528 185//185 1527//1527 -f 1527//1527 185//185 1526//1526 -f 656//656 655//655 672//672 -f 672//672 655//655 669//669 -f 656//656 672//672 657//657 -f 657//657 672//672 674//674 -f 657//657 674//674 658//658 -f 658//658 674//674 686//686 -f 658//658 686//686 659//659 -f 659//659 686//686 685//685 -f 199//199 659//659 683//683 -f 683//683 659//659 685//685 -f 639//639 637//637 653//653 -f 653//653 637//637 688//688 -f 653//653 688//688 654//654 -f 1529//1529 729//729 1530//1530 -f 1530//1530 729//729 731//731 -f 1530//1530 731//731 1531//1531 -f 1531//1531 731//731 743//743 -f 1531//1531 743//743 1532//1532 -f 1532//1532 743//743 742//742 -f 601//601 1532//1532 740//740 -f 740//740 1532//1532 742//742 -f 924//924 602//602 662//662 -f 662//662 602//602 588//588 -f 1529//1529 923//923 729//729 -f 729//729 923//923 721//721 -f 924//924 923//923 602//602 -f 602//602 923//923 1529//1529 -f 602//602 1529//1529 1530//1530 -f 1530//1530 1531//1531 602//602 -f 602//602 1531//1531 1532//1532 -f 602//602 1532//1532 601//601 -f 917//917 1533//1533 722//722 -f 722//722 1533//1533 733//733 -f 916//916 660//660 1534//1534 -f 1534//1534 660//660 609//609 -f 1534//1534 609//609 608//608 -f 1535//1535 601//601 738//738 -f 738//738 601//601 740//740 -f 1535//1535 738//738 1536//1536 -f 1536//1536 738//738 736//736 -f 1536//1536 736//736 1537//1537 -f 1537//1537 736//736 734//734 -f 1537//1537 734//734 1533//1533 -f 1533//1533 734//734 733//733 -f 1536//1536 599//599 1535//1535 -f 1535//1535 599//599 601//601 -f 916//916 1534//1534 917//917 -f 917//917 1534//1534 1538//1538 -f 917//917 1538//1538 1533//1533 -f 1533//1533 1538//1538 599//599 -f 1533//1533 599//599 1537//1537 -f 1537//1537 599//599 1536//1536 -f 1539//1539 651//651 1501//1501 -f 1501//1501 1502//1502 1539//1539 -f 1539//1539 1502//1502 1503//1503 -f 1539//1539 1503//1503 1504//1504 -f 639//639 653//653 638//638 -f 638//638 653//653 1505//1505 -f 1540//1540 1498//1498 1499//1499 -f 1499//1499 1500//1500 1540//1540 -f 1540//1540 1500//1500 1495//1495 -f 1540//1540 1495//1495 646//646 -f 1541//1541 1540//1540 1493//1493 -f 1493//1493 1540//1540 646//646 -f 1493//1493 646//646 645//645 -f 632//632 1542//1542 634//634 -f 634//634 1542//1542 1541//1541 -f 634//634 1541//1541 1493//1493 -f 1539//1539 1542//1542 651//651 -f 651//651 1542//1542 632//632 -f 651//651 632//632 631//631 -f 1543//1543 652//652 171//171 -f 171//171 652//652 200//200 -f 1544//1544 1543//1543 170//170 -f 170//170 1543//1543 171//171 -f 629//629 1544//1544 193//193 -f 193//193 1544//1544 170//170 -f 1545//1545 627//627 182//182 -f 182//182 627//627 183//183 -f 1546//1546 1545//1545 180//180 -f 180//180 1545//1545 182//182 -f 1547//1547 1546//1546 1486//1486 -f 1486//1486 1546//1546 180//180 -f 1497//1497 1547//1547 1494//1494 -f 1494//1494 1547//1547 1486//1486 -f 1547//1547 1497//1497 1541//1541 -f 1540//1540 1541//1541 1498//1498 -f 1498//1498 1541//1541 1497//1497 -f 1498//1498 1497//1497 1496//1496 -f 1548//1548 1549//1549 628//628 -f 652//652 1543//1543 629//629 -f 629//629 1543//1543 1544//1544 -f 627//627 1545//1545 1546//1546 -f 1548//1548 1504//1504 630//630 -f 630//630 1504//1504 1505//1505 -f 630//630 1505//1505 629//629 -f 629//629 1505//1505 653//653 -f 629//629 653//653 652//652 -f 1546//1546 1547//1547 627//627 -f 627//627 1547//1547 1541//1541 -f 627//627 1541//1541 628//628 -f 628//628 1541//1541 1542//1542 -f 628//628 1542//1542 1548//1548 -f 1548//1548 1542//1542 1539//1539 -f 1548//1548 1539//1539 1504//1504 -f 177//177 1550//1550 1551//1551 -f 1552//1552 1553//1553 177//177 -f 177//177 1553//1553 167//167 -f 177//177 167//167 1550//1550 -f 1550//1550 167//167 166//166 -f 1550//1550 166//166 1554//1554 -f 1554//1554 166//166 1549//1549 -f 1554//1554 1549//1549 1555//1555 -f 1555//1555 1549//1549 1548//1548 -f 1555//1555 1548//1548 1551//1551 -f 1551//1551 1548//1548 178//178 -f 1551//1551 178//178 177//177 -f 1549//1549 166//166 628//628 -f 628//628 166//166 184//184 -f 178//178 1548//1548 192//192 -f 192//192 1548//1548 630//630 -f 1554//1554 1555//1555 1556//1556 -f 1556//1556 1555//1555 1557//1557 -f 1555//1555 1551//1551 1557//1557 -f 1557//1557 1551//1551 1558//1558 -f 1551//1551 1550//1550 1558//1558 -f 1558//1558 1550//1550 1559//1559 -f 1550//1550 1554//1554 1559//1559 -f 1559//1559 1554//1554 1556//1556 -f 1557//1557 1558//1558 1556//1556 -f 1556//1556 1558//1558 1559//1559 -f 1553//1553 1560//1560 167//167 -f 167//167 1560//1560 168//168 -f 1560//1560 1561//1561 168//168 -f 168//168 1561//1561 173//173 -f 1561//1561 1552//1552 173//173 -f 173//173 1552//1552 177//177 -f 1561//1561 1560//1560 1552//1552 -f 1552//1552 1560//1560 1553//1553 -f 1562//1562 621//621 1508//1508 -f 1508//1508 1509//1509 1562//1562 -f 1562//1562 1509//1509 1510//1510 -f 1562//1562 1510//1510 1511//1511 -f 1534//1534 608//608 1517//1517 -f 1517//1517 608//608 610//610 -f 1563//1563 1513//1513 1485//1485 -f 1485//1485 1513//1513 1507//1507 -f 1564//1564 1563//1563 597//597 -f 597//597 1563//1563 1485//1485 -f 1565//1565 1564//1564 592//592 -f 592//592 1564//1564 597//597 -f 1566//1566 1565//1565 590//590 -f 590//590 1565//1565 592//592 -f 1566//1566 590//590 1567//1567 -f 1567//1567 590//590 589//589 -f 1568//1568 606//606 603//603 -f 603//603 606//606 604//604 -f 1569//1569 1568//1568 600//600 -f 600//600 1568//1568 603//603 -f 1538//1538 1569//1569 599//599 -f 599//599 1569//1569 600//600 -f 1516//1516 625//625 1570//1570 -f 1515//1515 1516//1516 1514//1514 -f 1514//1514 1516//1516 1570//1570 -f 1514//1514 1570//1570 1518//1518 -f 1571//1571 1570//1570 744//744 -f 744//744 1570//1570 625//625 -f 744//744 625//625 626//626 -f 1506//1506 1572//1572 745//745 -f 745//745 1572//1572 1571//1571 -f 745//745 1571//1571 744//744 -f 1562//1562 1572//1572 621//621 -f 621//621 1572//1572 1506//1506 -f 621//621 1506//1506 623//623 -f 1564//1564 1565//1565 1563//1563 -f 1563//1563 1565//1565 1566//1566 -f 1511//1511 1512//1512 1513//1513 -f 1573//1573 1574//1574 1567//1567 -f 1567//1567 1574//1574 607//607 -f 1567//1567 1518//1518 1571//1571 -f 1571//1571 1518//1518 1570//1570 -f 1566//1566 1567//1567 1563//1563 -f 1563//1563 1567//1567 1571//1571 -f 1563//1563 1571//1571 1513//1513 -f 1513//1513 1571//1571 1572//1572 -f 1513//1513 1572//1572 1511//1511 -f 1511//1511 1572//1572 1562//1562 -f 1568//1568 1569//1569 606//606 -f 606//606 1569//1569 1538//1538 -f 606//606 1538//1538 607//607 -f 607//607 1538//1538 1534//1534 -f 607//607 1534//1534 1567//1567 -f 1567//1567 1534//1534 1517//1517 -f 1567//1567 1517//1517 1518//1518 -f 1574//1574 582//582 607//607 -f 607//607 582//582 605//605 -f 591//591 1573//1573 589//589 -f 589//589 1573//1573 1567//1567 -f 583//583 582//582 1575//1575 -f 1575//1575 582//582 1576//1576 -f 1576//1576 582//582 1574//1574 -f 1576//1576 1574//1574 1577//1577 -f 1577//1577 1574//1574 1573//1573 -f 1577//1577 1573//1573 1578//1578 -f 1578//1578 1573//1573 591//591 -f 1578//1578 591//591 598//598 -f 1579//1579 1580//1580 598//598 -f 598//598 1580//1580 583//583 -f 598//598 583//583 1578//1578 -f 1578//1578 583//583 1575//1575 -f 1576//1576 1577//1577 1581//1581 -f 1581//1581 1577//1577 1582//1582 -f 1577//1577 1578//1578 1582//1582 -f 1582//1582 1578//1578 1583//1583 -f 1578//1578 1575//1575 1583//1583 -f 1583//1583 1575//1575 1584//1584 -f 1575//1575 1576//1576 1584//1584 -f 1584//1584 1576//1576 1581//1581 -f 1582//1582 1583//1583 1581//1581 -f 1581//1581 1583//1583 1584//1584 -f 1580//1580 1585//1585 583//583 -f 583//583 1585//1585 584//584 -f 1585//1585 1586//1586 584//584 -f 584//584 1586//1586 585//585 -f 1586//1586 1579//1579 585//585 -f 585//585 1579//1579 598//598 -f 1586//1586 1585//1585 1579//1579 -f 1579//1579 1585//1585 1580//1580 -f 617//617 616//616 561//561 -f 561//561 616//616 564//564 -f 617//617 561//561 613//613 -f 613//613 561//561 560//560 -f 613//613 560//560 614//614 -f 614//614 560//560 559//559 -f 614//614 559//559 619//619 -f 619//619 559//559 565//565 -f 521//521 619//619 571//571 -f 571//571 619//619 565//565 -f 578//578 615//615 580//580 -f 580//580 615//615 612//612 -f 1587//1587 573//573 1588//1588 -f 1588//1588 573//573 575//575 -f 1588//1588 575//575 1589//1589 -f 1589//1589 575//575 576//576 -f 1589//1589 576//576 1590//1590 -f 1590//1590 576//576 557//557 -f 900//900 1590//1590 555//555 -f 555//555 1590//1590 557//557 -f 522//522 899//899 516//516 -f 516//516 899//899 517//517 -f 1587//1587 521//521 573//573 -f 573//573 521//521 571//571 -f 1588//1588 522//522 1587//1587 -f 1587//1587 522//522 521//521 -f 900//900 899//899 1590//1590 -f 1590//1590 899//899 522//522 -f 1590//1590 522//522 1589//1589 -f 1589//1589 522//522 1588//1588 -f 648//648 526//526 642//642 -f 642//642 526//526 528//528 -f 647//647 649//649 533//533 -f 533//533 649//649 543//543 -f 640//640 524//524 548//548 -f 548//548 524//524 550//550 -f 640//640 548//548 641//641 -f 641//641 548//548 546//546 -f 641//641 546//546 650//650 -f 650//650 546//546 544//544 -f 650//650 544//544 649//649 -f 649//649 544//544 543//543 -f 1591//1591 539//539 1592//1592 -f 1592//1592 539//539 541//541 -f 1592//1592 541//541 1593//1593 -f 1593//1593 541//541 553//553 -f 1593//1593 553//553 1594//1594 -f 1594//1594 553//553 552//552 -f 524//524 1594//1594 550//550 -f 550//550 1594//1594 552//552 -f 907//907 523//523 519//519 -f 519//519 523//523 518//518 -f 1591//1591 906//906 539//539 -f 539//539 906//906 532//532 -f 1592//1592 523//523 1591//1591 -f 1591//1591 523//523 907//907 -f 1591//1591 907//907 906//906 -f 1592//1592 1593//1593 523//523 -f 523//523 1593//1593 1594//1594 -f 523//523 1594//1594 524//524 -f 476//476 207//207 206//206 -f 476//476 206//206 509//509 -f 509//509 206//206 203//203 -f 509//509 203//203 510//510 -f 225//225 243//243 513//513 -f 510//510 203//203 511//511 -f 511//511 203//203 205//205 -f 1595//1595 1596//1596 135//135 -f 135//135 1596//1596 145//145 -f 1597//1597 1598//1598 205//205 -f 205//205 1598//1598 136//136 -f 205//205 136//136 511//511 -f 511//511 136//136 135//135 -f 511//511 135//135 512//512 -f 512//512 135//135 145//145 -f 1599//1599 1600//1600 159//159 -f 159//159 1600//1600 141//141 -f 142//142 1601//1601 1602//1602 -f 1602//1602 225//225 142//142 -f 142//142 225//225 513//513 -f 142//142 513//513 141//141 -f 141//141 513//513 512//512 -f 141//141 512//512 159//159 -f 159//159 512//512 145//145 -f 513//513 243//243 245//245 -f 513//513 245//245 515//515 -f 515//515 245//245 246//246 -f 515//515 246//246 514//514 -f 1603//1603 1604//1604 246//246 -f 246//246 1604//1604 253//253 -f 252//252 475//475 253//253 -f 253//253 475//475 357//357 -f 253//253 357//357 359//359 -f 359//359 363//363 253//253 -f 253//253 363//363 514//514 -f 253//253 514//514 246//246 -f 475//475 252//252 251//251 -f 475//475 251//251 474//474 -f 474//474 251//251 249//249 -f 474//474 249//249 472//472 -f 497//497 334//334 341//341 -f 497//497 341//341 496//496 -f 496//496 341//341 340//340 -f 496//496 340//340 424//424 -f 424//424 340//340 417//417 -f 417//417 340//340 339//339 -f 417//417 339//339 431//431 -f 431//431 339//339 338//338 -f 431//431 338//338 430//430 -f 430//430 338//338 313//313 -f 430//430 313//313 428//428 -f 291//291 293//293 446//446 -f 446//446 438//438 291//291 -f 291//291 438//438 412//412 -f 291//291 412//412 313//313 -f 313//313 412//412 428//428 -f 446//446 293//293 295//295 -f 446//446 295//295 463//463 -f 463//463 295//295 307//307 -f 463//463 307//307 449//449 -f 495//495 449//449 306//306 -f 306//306 449//449 307//307 -f 495//495 306//306 304//304 -f 495//495 304//304 494//494 -f 494//494 304//304 303//303 -f 494//494 303//303 354//354 -f 354//354 303//303 355//355 -f 355//355 303//303 269//269 -f 355//355 269//269 492//492 -f 492//492 269//269 259//259 -f 492//492 259//259 489//489 -f 489//489 259//259 272//272 -f 489//489 272//272 488//488 -f 488//488 272//272 273//273 -f 488//488 273//273 486//486 -f 1605//1605 207//207 1606//1606 -f 1606//1606 207//207 274//274 -f 486//486 273//273 477//477 -f 477//477 273//273 274//274 -f 477//477 274//274 476//476 -f 476//476 274//274 207//207 -f 258//258 485//485 261//261 -f 261//261 485//485 484//484 -f 261//261 484//484 262//262 -f 262//262 484//484 483//483 -f 262//262 483//483 263//263 -f 263//263 483//483 482//482 -f 263//263 482//482 264//264 -f 264//264 482//482 481//481 -f 264//264 481//481 265//265 -f 265//265 481//481 480//480 -f 265//265 480//480 276//276 -f 276//276 480//480 479//479 -f 276//276 479//479 284//284 -f 284//284 479//479 478//478 -f 284//284 478//478 271//271 -f 271//271 478//478 493//493 -f 271//271 493//493 270//270 -f 270//270 493//493 491//491 -f 270//270 491//491 260//260 -f 260//260 491//491 490//490 -f 260//260 490//490 257//257 -f 257//257 490//490 487//487 -f 257//257 487//487 258//258 -f 258//258 487//487 485//485 -f 275//275 349//349 266//266 -f 266//266 349//349 348//348 -f 266//266 348//348 290//290 -f 290//290 348//348 505//505 -f 290//290 505//505 279//279 -f 279//279 505//505 504//504 -f 279//279 504//504 280//280 -f 280//280 504//504 503//503 -f 280//280 503//503 267//267 -f 267//267 503//503 502//502 -f 267//267 502//502 268//268 -f 268//268 502//502 508//508 -f 268//268 508//508 281//281 -f 281//281 508//508 507//507 -f 281//281 507//507 282//282 -f 282//282 507//507 506//506 -f 282//282 506//506 283//283 -f 283//283 506//506 501//501 -f 283//283 501//501 285//285 -f 285//285 501//501 500//500 -f 285//285 500//500 277//277 -f 277//277 500//500 499//499 -f 277//277 499//499 275//275 -f 275//275 499//499 349//349 -f 158//158 390//390 160//160 -f 160//160 390//390 389//389 -f 160//160 389//389 161//161 -f 161//161 389//389 388//388 -f 161//161 388//388 163//163 -f 163//163 388//388 387//387 -f 163//163 387//387 156//156 -f 156//156 387//387 386//386 -f 156//156 386//386 154//154 -f 154//154 386//386 385//385 -f 154//154 385//385 152//152 -f 152//152 385//385 378//378 -f 152//152 378//378 150//150 -f 150//150 378//378 379//379 -f 150//150 379//379 148//148 -f 148//148 379//379 384//384 -f 148//148 384//384 143//143 -f 143//143 384//384 383//383 -f 143//143 383//383 144//144 -f 144//144 383//383 381//381 -f 144//144 381//381 157//157 -f 157//157 381//381 391//391 -f 157//157 391//391 158//158 -f 158//158 391//391 390//390 -f 321//321 434//434 323//323 -f 323//323 434//434 435//435 -f 323//323 435//435 324//324 -f 324//324 435//435 445//445 -f 324//324 445//445 317//317 -f 317//317 445//445 444//444 -f 317//317 444//444 318//318 -f 318//318 444//444 443//443 -f 318//318 443//443 319//319 -f 319//319 443//443 440//440 -f 319//319 440//440 314//314 -f 314//314 440//440 441//441 -f 314//314 441//441 315//315 -f 315//315 441//441 442//442 -f 315//315 442//442 316//316 -f 316//316 442//442 439//439 -f 316//316 439//439 328//328 -f 328//328 439//439 437//437 -f 328//328 437//437 332//332 -f 332//332 437//437 436//436 -f 332//332 436//436 333//333 -f 333//333 436//436 432//432 -f 333//333 432//432 321//321 -f 321//321 432//432 434//434 -f 204//204 407//407 223//223 -f 223//223 407//407 406//406 -f 223//223 406//406 222//222 -f 222//222 406//406 405//405 -f 222//222 405//405 220//220 -f 220//220 405//405 404//404 -f 220//220 404//404 218//218 -f 218//218 404//404 403//403 -f 218//218 403//403 216//216 -f 216//216 403//403 402//402 -f 216//216 402//402 214//214 -f 214//214 402//402 401//401 -f 214//214 401//401 212//212 -f 212//212 401//401 398//398 -f 212//212 398//398 210//210 -f 210//210 398//398 395//395 -f 210//210 395//395 208//208 -f 208//208 395//395 393//393 -f 208//208 393//393 201//201 -f 201//201 393//393 392//392 -f 201//201 392//392 202//202 -f 202//202 392//392 409//409 -f 202//202 409//409 204//204 -f 204//204 409//409 407//407 -f 310//310 458//458 308//308 -f 308//308 458//458 456//456 -f 308//308 456//456 297//297 -f 297//297 456//456 455//455 -f 297//297 455//455 298//298 -f 298//298 455//455 454//454 -f 298//298 454//454 299//299 -f 299//299 454//454 453//453 -f 299//299 453//453 300//300 -f 300//300 453//453 452//452 -f 300//300 452//452 292//292 -f 292//292 452//452 448//448 -f 292//292 448//448 294//294 -f 294//294 448//448 447//447 -f 294//294 447//447 296//296 -f 296//296 447//447 451//451 -f 296//296 451//451 305//305 -f 305//305 451//451 450//450 -f 305//305 450//450 301//301 -f 301//301 450//450 461//461 -f 301//301 461//461 302//302 -f 302//302 461//461 460//460 -f 302//302 460//460 310//310 -f 310//310 460//460 458//458 -f 346//346 421//421 347//347 -f 347//347 421//421 419//419 -f 347//347 419//419 326//326 -f 326//326 419//419 418//418 -f 326//326 418//418 327//327 -f 327//327 418//418 416//416 -f 327//327 416//416 329//329 -f 329//329 416//416 415//415 -f 329//329 415//415 330//330 -f 330//330 415//415 429//429 -f 330//330 429//429 331//331 -f 331//331 429//429 427//427 -f 331//331 427//427 322//322 -f 322//322 427//427 426//426 -f 322//322 426//426 320//320 -f 320//320 426//426 414//414 -f 320//320 414//414 342//342 -f 342//342 414//414 413//413 -f 342//342 413//413 343//343 -f 343//343 413//413 411//411 -f 343//343 411//411 344//344 -f 344//344 411//411 422//422 -f 344//344 422//422 346//346 -f 346//346 422//422 421//421 -f 242//242 365//365 244//244 -f 244//244 365//365 364//364 -f 244//244 364//364 240//240 -f 240//240 364//364 362//362 -f 240//240 362//362 238//238 -f 238//238 362//362 361//361 -f 238//238 361//361 236//236 -f 236//236 361//361 360//360 -f 236//236 360//360 234//234 -f 234//234 360//360 376//376 -f 234//234 376//376 232//232 -f 232//232 376//376 374//374 -f 232//232 374//374 230//230 -f 230//230 374//374 373//373 -f 230//230 373//373 228//228 -f 228//228 373//373 372//372 -f 228//228 372//372 226//226 -f 226//226 372//372 370//370 -f 226//226 370//370 224//224 -f 224//224 370//370 368//368 -f 224//224 368//368 241//241 -f 241//241 368//368 367//367 -f 241//241 367//367 242//242 -f 242//242 367//367 365//365 -f 198//198 1607//1607 233//233 -f 233//233 1607//1607 235//235 -f 1604//1604 187//187 253//253 -f 253//253 187//187 188//188 -f 1608//1608 1603//1603 239//239 -f 239//239 1603//1603 246//246 -f 1608//1608 239//239 1609//1609 -f 1609//1609 239//239 237//237 -f 1609//1609 237//237 1607//1607 -f 1607//1607 237//237 235//235 -f 198//198 187//187 1607//1607 -f 1607//1607 187//187 1609//1609 -f 1609//1609 187//187 1608//1608 -f 1608//1608 187//187 1604//1604 -f 1608//1608 1604//1604 1603//1603 -f 1610//1610 231//231 1611//1611 -f 1611//1611 231//231 229//229 -f 1611//1611 229//229 1612//1612 -f 1612//1612 229//229 227//227 -f 1602//1602 1612//1612 225//225 -f 225//225 1612//1612 227//227 -f 169//169 1601//1601 140//140 -f 140//140 1601//1601 142//142 -f 1610//1610 198//198 231//231 -f 231//231 198//198 233//233 -f 169//169 198//198 1610//1610 -f 1602//1602 1601//1601 1612//1612 -f 1612//1612 1601//1601 169//169 -f 1612//1612 169//169 1611//1611 -f 1611//1611 169//169 1610//1610 -f 1613//1613 181//181 213//213 -f 213//213 181//181 215//215 -f 1613//1613 213//213 1614//1614 -f 1614//1614 213//213 211//211 -f 1614//1614 211//211 1615//1615 -f 1615//1615 211//211 209//209 -f 1605//1605 1615//1615 207//207 -f 207//207 1615//1615 209//209 -f 1616//1616 1606//1606 256//256 -f 256//256 1606//1606 274//274 -f 1616//1616 256//256 179//179 -f 179//179 256//256 255//255 -f 181//181 1613//1613 179//179 -f 179//179 1613//1613 1616//1616 -f 1605//1605 1606//1606 1615//1615 -f 1615//1615 1606//1606 1616//1616 -f 1615//1615 1616//1616 1614//1614 -f 1614//1614 1616//1616 1613//1613 -f 1617//1617 221//221 1618//1618 -f 1618//1618 221//221 219//219 -f 1618//1618 219//219 1619//1619 -f 1619//1619 219//219 217//217 -f 181//181 1619//1619 215//215 -f 215//215 1619//1619 217//217 -f 1598//1598 172//172 136//136 -f 136//136 172//172 138//138 -f 1617//1617 1597//1597 221//221 -f 221//221 1597//1597 205//205 -f 181//181 172//172 1619//1619 -f 1619//1619 172//172 1618//1618 -f 1618//1618 172//172 1617//1617 -f 1617//1617 172//172 1598//1598 -f 1617//1617 1598//1598 1597//1597 -f 1620//1620 162//162 1621//1621 -f 1621//1621 162//162 164//164 -f 1621//1621 164//164 1622//1622 -f 1622//1622 164//164 165//165 -f 1622//1622 165//165 1623//1623 -f 1623//1623 165//165 155//155 -f 175//175 1623//1623 153//153 -f 153//153 1623//1623 155//155 -f 1600//1600 176//176 141//141 -f 141//141 176//176 139//139 -f 1620//1620 1599//1599 162//162 -f 162//162 1599//1599 159//159 -f 1600//1600 1599//1599 176//176 -f 176//176 1599//1599 1620//1620 -f 176//176 1620//1620 1621//1621 -f 1621//1621 1622//1622 176//176 -f 176//176 1622//1622 1623//1623 -f 176//176 1623//1623 175//175 -f 1596//1596 1624//1624 145//145 -f 145//145 1624//1624 146//146 -f 174//174 1595//1595 137//137 -f 137//137 1595//1595 135//135 -f 1625//1625 175//175 151//151 -f 151//151 175//175 153//153 -f 1625//1625 151//151 1626//1626 -f 1626//1626 151//151 149//149 -f 1626//1626 149//149 1627//1627 -f 1627//1627 149//149 147//147 -f 1627//1627 147//147 1624//1624 -f 1624//1624 147//147 146//146 -f 1626//1626 174//174 1625//1625 -f 1625//1625 174//174 175//175 -f 1596//1596 1595//1595 1624//1624 -f 1624//1624 1595//1595 174//174 -f 1624//1624 174//174 1627//1627 -f 1627//1627 174//174 1626//1626 -f 1628//1628 464//464 400//400 -f 1628//1628 400//400 1629//1629 -f 1629//1629 400//400 399//399 -f 1629//1629 399//399 1630//1630 -f 1630//1630 399//399 397//397 -f 1630//1630 397//397 1631//1631 -f 1631//1631 397//397 396//396 -f 1631//1631 396//396 1632//1632 -f 396//396 377//377 1632//1632 -f 1632//1632 377//377 371//371 -f 1632//1632 371//371 1633//1633 -f 1633//1633 371//371 375//375 -f 1633//1633 375//375 468//468 -f 1633//1633 468//468 469//469 -f 1633//1633 469//469 1634//1634 -f 1634//1634 469//469 473//473 -f 1634//1634 473//473 1635//1635 -f 1635//1635 473//473 471//471 -f 1635//1635 471//471 1636//1636 -f 1636//1636 471//471 470//470 -f 1636//1636 470//470 936//936 -f 935//935 352//352 351//351 -f 935//935 351//351 1637//1637 -f 1637//1637 351//351 498//498 -f 1637//1637 498//498 1638//1638 -f 1638//1638 498//498 423//423 -f 1638//1638 423//423 1639//1639 -f 1639//1639 423//423 425//425 -f 1639//1639 425//425 1640//1640 -f 425//425 420//420 1640//1640 -f 1640//1640 420//420 410//410 -f 1640//1640 410//410 1641//1641 -f 1641//1641 410//410 433//433 -f 1641//1641 433//433 457//457 -f 1641//1641 457//457 459//459 -f 1641//1641 459//459 1642//1642 -f 1642//1642 459//459 462//462 -f 1642//1642 462//462 1643//1643 -f 1643//1643 462//462 467//467 -f 1643//1643 467//467 1644//1644 -f 1644//1644 467//467 466//466 -f 1644//1644 466//466 1645//1645 -f 464//464 1628//1628 465//465 -f 465//465 1628//1628 1645//1645 -f 465//465 1645//1645 466//466 -f 1646//1646 1647//1647 1648//1648 -f 1649//1649 1650//1650 1651//1651 -f 1651//1651 1650//1650 1652//1652 -f 1653//1653 1654//1654 1655//1655 -f 1655//1655 1654//1654 1656//1656 -f 1657//1657 1658//1658 1659//1659 -f 1659//1659 1658//1658 1660//1660 -f 1660//1660 1658//1658 1661//1661 -f 1661//1661 1658//1658 1662//1662 -f 1661//1661 1662//1662 1663//1663 -f 1663//1663 1646//1646 1661//1661 -f 1661//1661 1646//1646 1648//1648 -f 1661//1661 1648//1648 1650//1650 -f 1650//1650 1648//1648 1655//1655 -f 1650//1650 1655//1655 1652//1652 -f 1652//1652 1655//1655 1656//1656 -f 1664//1664 1665//1665 1666//1666 -f 1667//1667 1668//1668 1669//1669 -f 1669//1669 1670//1670 1667//1667 -f 1667//1667 1670//1670 1671//1671 -f 1667//1667 1671//1671 1672//1672 -f 1672//1672 1671//1671 1673//1673 -f 1672//1672 1673//1673 1674//1674 -f 1674//1674 1673//1673 1654//1654 -f 1674//1674 1654//1654 1675//1675 -f 1675//1675 1654//1654 1653//1653 -f 1649//1649 1676//1676 1650//1650 -f 1650//1650 1676//1676 1677//1677 -f 1650//1650 1677//1677 1664//1664 -f 1664//1664 1677//1677 1678//1678 -f 1664//1664 1678//1678 1665//1665 -f 1666//1666 1679//1679 1664//1664 -f 1664//1664 1679//1679 1680//1680 -f 1664//1664 1680//1680 1660//1660 -f 1660//1660 1680//1680 1681//1681 -f 1660//1660 1681//1681 1659//1659 -f 1668//1668 1682//1682 1669//1669 -f 1669//1669 1682//1682 1683//1683 -f 1669//1669 1683//1683 1684//1684 -f 1684//1684 1683//1683 1679//1679 -f 1684//1684 1679//1679 1685//1685 -f 1685//1685 1679//1679 1666//1666 -f 1632//1632 1686//1686 1687//1687 -f 1686//1686 1688//1688 1689//1689 -f 1688//1688 1648//1648 1647//1647 -f 1688//1688 1647//1647 1689//1689 -f 1689//1689 1647//1647 1646//1646 -f 1689//1689 1646//1646 1690//1690 -f 1690//1690 1646//1646 1663//1663 -f 1690//1690 1663//1663 1691//1691 -f 1691//1691 1663//1663 1662//1662 -f 1691//1691 1662//1662 1692//1692 -f 1686//1686 1689//1689 1687//1687 -f 1687//1687 1689//1689 1690//1690 -f 1687//1687 1690//1690 1693//1693 -f 1693//1693 1690//1690 1691//1691 -f 1693//1693 1691//1691 1694//1694 -f 1694//1694 1691//1691 1692//1692 -f 1694//1694 1692//1692 1695//1695 -f 1632//1632 1687//1687 1631//1631 -f 1631//1631 1687//1687 1693//1693 -f 1631//1631 1693//1693 1630//1630 -f 1630//1630 1693//1693 1694//1694 -f 1630//1630 1694//1694 1629//1629 -f 1629//1629 1694//1694 1695//1695 -f 1629//1629 1695//1695 1628//1628 -f 1655//1655 1648//1648 1688//1688 -f 1655//1655 1688//1688 1696//1696 -f 1696//1696 1688//1688 1686//1686 -f 1696//1696 1686//1686 1697//1697 -f 1697//1697 1686//1686 1632//1632 -f 1697//1697 1632//1632 1633//1633 -f 1662//1662 1658//1658 1698//1698 -f 1662//1662 1698//1698 1692//1692 -f 1692//1692 1698//1698 1699//1699 -f 1692//1692 1699//1699 1695//1695 -f 1695//1695 1699//1699 1645//1645 -f 1695//1695 1645//1645 1628//1628 -f 936//936 1700//1700 1701//1701 -f 1700//1700 1702//1702 1703//1703 -f 1702//1702 1672//1672 1674//1674 -f 1702//1702 1674//1674 1703//1703 -f 1703//1703 1674//1674 1675//1675 -f 1703//1703 1675//1675 1704//1704 -f 1704//1704 1675//1675 1653//1653 -f 1704//1704 1653//1653 1705//1705 -f 1705//1705 1653//1653 1655//1655 -f 1705//1705 1655//1655 1696//1696 -f 1700//1700 1703//1703 1701//1701 -f 1701//1701 1703//1703 1704//1704 -f 1701//1701 1704//1704 1706//1706 -f 1706//1706 1704//1704 1705//1705 -f 1706//1706 1705//1705 1707//1707 -f 1707//1707 1705//1705 1696//1696 -f 1707//1707 1696//1696 1697//1697 -f 936//936 1701//1701 1636//1636 -f 1636//1636 1701//1701 1706//1706 -f 1636//1636 1706//1706 1635//1635 -f 1635//1635 1706//1706 1707//1707 -f 1635//1635 1707//1707 1634//1634 -f 1634//1634 1707//1707 1697//1697 -f 1634//1634 1697//1697 1633//1633 -f 1645//1645 1699//1699 1708//1708 -f 1699//1699 1698//1698 1709//1709 -f 1698//1698 1658//1658 1657//1657 -f 1698//1698 1657//1657 1709//1709 -f 1709//1709 1657//1657 1659//1659 -f 1709//1709 1659//1659 1710//1710 -f 1710//1710 1659//1659 1681//1681 -f 1710//1710 1681//1681 1711//1711 -f 1711//1711 1681//1681 1680//1680 -f 1711//1711 1680//1680 1712//1712 -f 1699//1699 1709//1709 1708//1708 -f 1708//1708 1709//1709 1710//1710 -f 1708//1708 1710//1710 1713//1713 -f 1713//1713 1710//1710 1711//1711 -f 1713//1713 1711//1711 1714//1714 -f 1714//1714 1711//1711 1712//1712 -f 1714//1714 1712//1712 1715//1715 -f 1645//1645 1708//1708 1644//1644 -f 1644//1644 1708//1708 1713//1713 -f 1644//1644 1713//1713 1643//1643 -f 1643//1643 1713//1713 1714//1714 -f 1643//1643 1714//1714 1642//1642 -f 1642//1642 1714//1714 1715//1715 -f 1642//1642 1715//1715 1641//1641 -f 1667//1667 1672//1672 1702//1702 -f 1667//1667 1702//1702 1716//1716 -f 1716//1716 1702//1702 1700//1700 -f 1716//1716 1700//1700 1717//1717 -f 1717//1717 1700//1700 936//936 -f 1717//1717 936//936 935//935 -f 1680//1680 1679//1679 1718//1718 -f 1680//1680 1718//1718 1712//1712 -f 1712//1712 1718//1718 1719//1719 -f 1712//1712 1719//1719 1715//1715 -f 1715//1715 1719//1719 1640//1640 -f 1715//1715 1640//1640 1641//1641 -f 1640//1640 1719//1719 1720//1720 -f 1719//1719 1718//1718 1721//1721 -f 1718//1718 1679//1679 1683//1683 -f 1718//1718 1683//1683 1721//1721 -f 1721//1721 1683//1683 1682//1682 -f 1721//1721 1682//1682 1722//1722 -f 1722//1722 1682//1682 1668//1668 -f 1722//1722 1668//1668 1723//1723 -f 1723//1723 1668//1668 1667//1667 -f 1723//1723 1667//1667 1716//1716 -f 1719//1719 1721//1721 1720//1720 -f 1720//1720 1721//1721 1722//1722 -f 1720//1720 1722//1722 1724//1724 -f 1724//1724 1722//1722 1723//1723 -f 1724//1724 1723//1723 1725//1725 -f 1725//1725 1723//1723 1716//1716 -f 1725//1725 1716//1716 1717//1717 -f 1640//1640 1720//1720 1639//1639 -f 1639//1639 1720//1720 1724//1724 -f 1639//1639 1724//1724 1638//1638 -f 1638//1638 1724//1724 1725//1725 -f 1638//1638 1725//1725 1637//1637 -f 1637//1637 1725//1725 1717//1717 -f 1637//1637 1717//1717 935//935 -f 127//127 1652//1652 129//129 -f 129//129 1652//1652 1656//1656 -f 129//129 1656//1656 131//131 -f 131//131 1656//1656 1654//1654 -f 131//131 1654//1654 133//133 -f 133//133 1654//1654 1673//1673 -f 133//133 1673//1673 134//134 -f 134//134 1673//1673 1671//1671 -f 134//134 1671//1671 106//106 -f 106//106 1671//1671 1670//1670 -f 106//106 1670//1670 108//108 -f 108//108 1670//1670 1669//1669 -f 108//108 1669//1669 110//110 -f 110//110 1669//1669 1684//1684 -f 110//110 1684//1684 112//112 -f 112//112 1684//1684 1685//1685 -f 112//112 1685//1685 114//114 -f 114//114 1685//1685 1666//1666 -f 114//114 1666//1666 116//116 -f 116//116 1666//1666 1665//1665 -f 116//116 1665//1665 118//118 -f 118//118 1665//1665 1678//1678 -f 118//118 1678//1678 119//119 -f 119//119 1678//1678 1677//1677 -f 119//119 1677//1677 121//121 -f 121//121 1677//1677 1676//1676 -f 121//121 1676//1676 123//123 -f 123//123 1676//1676 1649//1649 -f 123//123 1649//1649 125//125 -f 125//125 1649//1649 1651//1651 -f 125//125 1651//1651 127//127 -f 127//127 1651//1651 1652//1652 -f 111//111 1726//1726 109//109 -f 109//109 1726//1726 1727//1727 -f 109//109 1727//1727 107//107 -f 107//107 1727//1727 1728//1728 -f 107//107 1728//1728 105//105 -f 105//105 1728//1728 1729//1729 -f 105//105 1729//1729 132//132 -f 132//132 1729//1729 1730//1730 -f 132//132 1730//1730 130//130 -f 130//130 1730//1730 1731//1731 -f 130//130 1731//1731 128//128 -f 128//128 1731//1731 1732//1732 -f 128//128 1732//1732 126//126 -f 126//126 1732//1732 1733//1733 -f 126//126 1733//1733 124//124 -f 124//124 1733//1733 1734//1734 -f 124//124 1734//1734 122//122 -f 122//122 1734//1734 1735//1735 -f 122//122 1735//1735 120//120 -f 120//120 1735//1735 1736//1736 -f 120//120 1736//1736 117//117 -f 117//117 1736//1736 1737//1737 -f 117//117 1737//1737 115//115 -f 115//115 1737//1737 1738//1738 -f 115//115 1738//1738 113//113 -f 113//113 1738//1738 1739//1739 -f 113//113 1739//1739 111//111 -f 111//111 1739//1739 1726//1726 -f 1739//1739 1740//1740 1726//1726 -f 1726//1726 1740//1740 1741//1741 -f 1726//1726 1741//1741 1727//1727 -f 1727//1727 1741//1741 1742//1742 -f 1727//1727 1742//1742 1728//1728 -f 1728//1728 1742//1742 1743//1743 -f 1728//1728 1743//1743 1729//1729 -f 1729//1729 1743//1743 1744//1744 -f 1729//1729 1744//1744 1730//1730 -f 1730//1730 1744//1744 1745//1745 -f 1730//1730 1745//1745 1731//1731 -f 1731//1731 1745//1745 1746//1746 -f 1731//1731 1746//1746 1732//1732 -f 1732//1732 1746//1746 1747//1747 -f 1732//1732 1747//1747 1733//1733 -f 1733//1733 1747//1747 1748//1748 -f 1733//1733 1748//1748 1734//1734 -f 1734//1734 1748//1748 1749//1749 -f 1734//1734 1749//1749 1735//1735 -f 1735//1735 1749//1749 1750//1750 -f 1735//1735 1750//1750 1736//1736 -f 1736//1736 1750//1750 1751//1751 -f 1736//1736 1751//1751 1737//1737 -f 1737//1737 1751//1751 1752//1752 -f 1737//1737 1752//1752 1738//1738 -f 1738//1738 1752//1752 1753//1753 -f 1738//1738 1753//1753 1739//1739 -f 1739//1739 1753//1753 1740//1740 -f 1753//1753 6//6 1740//1740 -f 1740//1740 6//6 14//14 -f 1740//1740 14//14 1741//1741 -f 1741//1741 14//14 29//29 -f 1741//1741 29//29 1742//1742 -f 1742//1742 29//29 48//48 -f 1742//1742 48//48 1743//1743 -f 1743//1743 48//48 54//54 -f 1743//1743 54//54 1744//1744 -f 1744//1744 54//54 74//74 -f 1744//1744 74//74 1745//1745 -f 1745//1745 74//74 77//77 -f 1745//1745 77//77 1746//1746 -f 1746//1746 77//77 98//98 -f 1746//1746 98//98 1747//1747 -f 1747//1747 98//98 60//60 -f 1747//1747 60//60 1748//1748 -f 1748//1748 60//60 51//51 -f 1748//1748 51//51 1749//1749 -f 1749//1749 51//51 32//32 -f 1749//1749 32//32 1750//1750 -f 1750//1750 32//32 17//17 -f 1750//1750 17//17 1751//1751 -f 1751//1751 17//17 20//20 -f 1751//1751 20//20 1752//1752 -f 1752//1752 20//20 3//3 -f 1752//1752 3//3 1753//1753 -f 1753//1753 3//3 6//6 -f 1754//1754 1755//1755 46//46 -f 46//46 1755//1755 47//47 -f 46//46 45//45 1754//1754 -f 1754//1754 45//45 1756//1756 -f 1757//1757 1756//1756 44//44 -f 44//44 1756//1756 45//45 -f 1758//1758 1757//1757 42//42 -f 42//42 1757//1757 44//44 -f 42//42 41//41 1758//1758 -f 1758//1758 41//41 1759//1759 -f 1760//1760 1759//1759 43//43 -f 43//43 1759//1759 41//41 -f 1761//1761 1760//1760 25//25 -f 25//25 1760//1760 43//43 -f 25//25 24//24 1761//1761 -f 1761//1761 24//24 1762//1762 -f 1763//1763 1762//1762 23//23 -f 23//23 1762//1762 24//24 -f 1764//1764 1763//1763 27//27 -f 27//27 1763//1763 23//23 -f 27//27 26//26 1764//1764 -f 1764//1764 26//26 1765//1765 -f 1766//1766 1765//1765 28//28 -f 28//28 1765//1765 26//26 -f 1767//1767 1766//1766 10//10 -f 10//10 1766//1766 28//28 -f 10//10 9//9 1767//1767 -f 1767//1767 9//9 1768//1768 -f 1769//1769 1768//1768 8//8 -f 8//8 1768//1768 9//9 -f 1770//1770 1769//1769 12//12 -f 12//12 1769//1769 8//8 -f 12//12 11//11 1770//1770 -f 1770//1770 11//11 1771//1771 -f 1772//1772 1771//1771 13//13 -f 13//13 1771//1771 11//11 -f 1773//1773 1772//1772 7//7 -f 7//7 1772//1772 13//13 -f 7//7 5//5 1773//1773 -f 1773//1773 5//5 1774//1774 -f 1775//1775 1774//1774 4//4 -f 4//4 1774//1774 5//5 -f 1776//1776 1775//1775 22//22 -f 22//22 1775//1775 4//4 -f 22//22 21//21 1776//1776 -f 1776//1776 21//21 1777//1777 -f 1778//1778 1777//1777 2//2 -f 2//2 1777//1777 21//21 -f 1779//1779 1778//1778 1//1 -f 1//1 1778//1778 2//2 -f 1//1 40//40 1779//1779 -f 1779//1779 40//40 1780//1780 -f 1781//1781 1780//1780 39//39 -f 39//39 1780//1780 40//40 -f 1782//1782 1781//1781 38//38 -f 38//38 1781//1781 39//39 -f 38//38 37//37 1782//1782 -f 1782//1782 37//37 1783//1783 -f 1784//1784 1783//1783 19//19 -f 19//19 1783//1783 37//37 -f 1785//1785 1784//1784 18//18 -f 18//18 1784//1784 19//19 -f 18//18 36//36 1785//1785 -f 1785//1785 36//36 1786//1786 -f 1787//1787 1786//1786 35//35 -f 35//35 1786//1786 36//36 -f 1788//1788 1787//1787 34//34 -f 34//34 1787//1787 35//35 -f 34//34 33//33 1788//1788 -f 1788//1788 33//33 1789//1789 -f 1790//1790 1789//1789 16//16 -f 16//16 1789//1789 33//33 -f 1791//1791 1790//1790 15//15 -f 15//15 1790//1790 16//16 -f 15//15 58//58 1791//1791 -f 1791//1791 58//58 1792//1792 -f 1793//1793 1792//1792 57//57 -f 57//57 1792//1792 58//58 -f 1794//1794 1793//1793 56//56 -f 56//56 1793//1793 57//57 -f 56//56 55//55 1794//1794 -f 1794//1794 55//55 1795//1795 -f 1796//1796 1795//1795 31//31 -f 31//31 1795//1795 55//55 -f 1797//1797 1796//1796 30//30 -f 30//30 1796//1796 31//31 -f 30//30 67//67 1797//1797 -f 1797//1797 67//67 1798//1798 -f 1799//1799 1798//1798 66//66 -f 66//66 1798//1798 67//67 -f 1800//1800 1799//1799 65//65 -f 65//65 1799//1799 66//66 -f 65//65 64//64 1800//1800 -f 1800//1800 64//64 1801//1801 -f 1802//1802 1801//1801 50//50 -f 50//50 1801//1801 64//64 -f 1803//1803 1802//1802 63//63 -f 63//63 1802//1802 50//50 -f 63//63 62//62 1803//1803 -f 1803//1803 62//62 1804//1804 -f 1805//1805 1804//1804 61//61 -f 61//61 1804//1804 62//62 -f 1806//1806 1805//1805 81//81 -f 81//81 1805//1805 61//61 -f 81//81 82//82 1806//1806 -f 1806//1806 82//82 1807//1807 -f 1808//1808 1807//1807 59//59 -f 59//59 1807//1807 82//82 -f 1809//1809 1808//1808 80//80 -f 80//80 1808//1808 59//59 -f 80//80 79//79 1809//1809 -f 1809//1809 79//79 1810//1810 -f 1811//1811 1810//1810 78//78 -f 78//78 1810//1810 79//79 -f 1812//1812 1811//1811 89//89 -f 89//89 1811//1811 78//78 -f 89//89 91//91 1812//1812 -f 1812//1812 91//91 1813//1813 -f 1814//1814 1813//1813 90//90 -f 90//90 1813//1813 91//91 -f 1815//1815 1814//1814 102//102 -f 102//102 1814//1814 90//90 -f 102//102 101//101 1815//1815 -f 1815//1815 101//101 1816//1816 -f 1817//1817 1816//1816 100//100 -f 100//100 1816//1816 101//101 -f 1818//1818 1817//1817 99//99 -f 99//99 1817//1817 100//100 -f 99//99 97//97 1818//1818 -f 1818//1818 97//97 1819//1819 -f 1820//1820 1819//1819 96//96 -f 96//96 1819//1819 97//97 -f 1821//1821 1820//1820 104//104 -f 104//104 1820//1820 96//96 -f 104//104 103//103 1821//1821 -f 1821//1821 103//103 1822//1822 -f 1823//1823 1822//1822 88//88 -f 88//88 1822//1822 103//103 -f 1824//1824 1823//1823 87//87 -f 87//87 1823//1823 88//88 -f 87//87 95//95 1824//1824 -f 1824//1824 95//95 1825//1825 -f 1826//1826 1825//1825 94//94 -f 94//94 1825//1825 95//95 -f 1827//1827 1826//1826 93//93 -f 93//93 1826//1826 94//94 -f 93//93 92//92 1827//1827 -f 1827//1827 92//92 1828//1828 -f 1829//1829 1828//1828 76//76 -f 76//76 1828//1828 92//92 -f 1830//1830 1829//1829 75//75 -f 75//75 1829//1829 76//76 -f 75//75 86//86 1830//1830 -f 1830//1830 86//86 1831//1831 -f 1832//1832 1831//1831 85//85 -f 85//85 1831//1831 86//86 -f 1833//1833 1832//1832 84//84 -f 84//84 1832//1832 85//85 -f 84//84 83//83 1833//1833 -f 1833//1833 83//83 1834//1834 -f 1835//1835 1834//1834 73//73 -f 73//73 1834//1834 83//83 -f 1836//1836 1835//1835 72//72 -f 72//72 1835//1835 73//73 -f 72//72 71//71 1836//1836 -f 1836//1836 71//71 1837//1837 -f 1838//1838 1837//1837 70//70 -f 70//70 1837//1837 71//71 -f 1839//1839 1838//1838 69//69 -f 69//69 1838//1838 70//70 -f 69//69 68//68 1839//1839 -f 1839//1839 68//68 1840//1840 -f 1841//1841 1840//1840 53//53 -f 53//53 1840//1840 68//68 -f 1842//1842 1841//1841 52//52 -f 52//52 1841//1841 53//53 -f 52//52 49//49 1842//1842 -f 1842//1842 49//49 1843//1843 -f 1755//1755 1843//1843 47//47 -f 47//47 1843//1843 49//49 -f 1844//1844 1845//1845 1846//1846 -f 1846//1846 1845//1845 1847//1847 -f 1846//1846 1847//1847 1848//1848 -f 1848//1848 1847//1847 1849//1849 -f 1848//1848 1849//1849 1850//1850 -f 1850//1850 1849//1849 1851//1851 -f 1850//1850 1851//1851 1852//1852 -f 1852//1852 1851//1851 1853//1853 -f 1852//1852 1853//1853 1854//1854 -f 1854//1854 1853//1853 1855//1855 -f 1854//1854 1855//1855 1856//1856 -f 1856//1856 1855//1855 1857//1857 -f 1856//1856 1857//1857 1858//1858 -f 1858//1858 1857//1857 1859//1859 -f 1858//1858 1859//1859 1860//1860 -f 1860//1860 1859//1859 1861//1861 -f 1860//1860 1861//1861 1862//1862 -f 1862//1862 1861//1861 1863//1863 -f 1862//1862 1863//1863 1864//1864 -f 1864//1864 1863//1863 1865//1865 -f 1864//1864 1865//1865 1866//1866 -f 1866//1866 1865//1865 1867//1867 -f 1866//1866 1867//1867 1844//1844 -f 1844//1844 1867//1867 1845//1845 -f 1782//1782 1783//1783 1864//1864 -f 1782//1782 1864//1864 1781//1781 -f 1786//1786 1862//1862 1785//1785 -f 1785//1785 1862//1862 1864//1864 -f 1785//1785 1864//1864 1784//1784 -f 1784//1784 1864//1864 1783//1783 -f 1758//1758 1759//1759 1846//1846 -f 1777//1777 1778//1778 1866//1866 -f 1866//1866 1778//1778 1779//1779 -f 1866//1866 1779//1779 1864//1864 -f 1864//1864 1779//1779 1780//1780 -f 1864//1864 1780//1780 1781//1781 -f 1789//1789 1790//1790 1791//1791 -f 1771//1771 1866//1866 1770//1770 -f 1770//1770 1866//1866 1844//1844 -f 1770//1770 1844//1844 1769//1769 -f 1787//1787 1788//1788 1786//1786 -f 1786//1786 1788//1788 1789//1789 -f 1786//1786 1789//1789 1862//1862 -f 1862//1862 1789//1789 1791//1791 -f 1862//1862 1791//1791 1792//1792 -f 1758//1758 1846//1846 1757//1757 -f 1766//1766 1767//1767 1844//1844 -f 1844//1844 1767//1767 1768//1768 -f 1844//1844 1768//1768 1769//1769 -f 1771//1771 1772//1772 1866//1866 -f 1866//1866 1772//1772 1773//1773 -f 1866//1866 1773//1773 1774//1774 -f 1774//1774 1775//1775 1866//1866 -f 1866//1866 1775//1775 1776//1776 -f 1866//1866 1776//1776 1777//1777 -f 1795//1795 1860//1860 1794//1794 -f 1794//1794 1860//1860 1862//1862 -f 1794//1794 1862//1862 1793//1793 -f 1793//1793 1862//1862 1792//1792 -f 1795//1795 1796//1796 1860//1860 -f 1860//1860 1796//1796 1797//1797 -f 1860//1860 1797//1797 1798//1798 -f 1833//1833 1834//1834 1850//1850 -f 1759//1759 1760//1760 1846//1846 -f 1846//1846 1760//1760 1761//1761 -f 1846//1846 1761//1761 1762//1762 -f 1762//1762 1763//1763 1846//1846 -f 1846//1846 1763//1763 1764//1764 -f 1846//1846 1764//1764 1844//1844 -f 1844//1844 1764//1764 1765//1765 -f 1844//1844 1765//1765 1766//1766 -f 1801//1801 1858//1858 1800//1800 -f 1800//1800 1858//1858 1860//1860 -f 1800//1800 1860//1860 1799//1799 -f 1799//1799 1860//1860 1798//1798 -f 1801//1801 1802//1802 1858//1858 -f 1858//1858 1802//1802 1803//1803 -f 1858//1858 1803//1803 1804//1804 -f 1827//1827 1828//1828 1852//1852 -f 1840//1840 1848//1848 1839//1839 -f 1839//1839 1848//1848 1850//1850 -f 1839//1839 1850//1850 1838//1838 -f 1838//1838 1850//1850 1837//1837 -f 1804//1804 1805//1805 1858//1858 -f 1858//1858 1805//1805 1806//1806 -f 1858//1858 1806//1806 1807//1807 -f 1810//1810 1856//1856 1809//1809 -f 1809//1809 1856//1856 1858//1858 -f 1809//1809 1858//1858 1808//1808 -f 1808//1808 1858//1858 1807//1807 -f 1856//1856 1816//1816 1817//1817 -f 1833//1833 1850//1850 1832//1832 -f 1834//1834 1835//1835 1850//1850 -f 1850//1850 1835//1835 1836//1836 -f 1850//1850 1836//1836 1837//1837 -f 1840//1840 1841//1841 1848//1848 -f 1848//1848 1841//1841 1842//1842 -f 1848//1848 1842//1842 1843//1843 -f 1843//1843 1755//1755 1848//1848 -f 1848//1848 1755//1755 1754//1754 -f 1848//1848 1754//1754 1846//1846 -f 1846//1846 1754//1754 1756//1756 -f 1846//1846 1756//1756 1757//1757 -f 1810//1810 1811//1811 1856//1856 -f 1856//1856 1811//1811 1812//1812 -f 1856//1856 1812//1812 1813//1813 -f 1813//1813 1814//1814 1856//1856 -f 1856//1856 1814//1814 1815//1815 -f 1856//1856 1815//1815 1816//1816 -f 1817//1817 1818//1818 1856//1856 -f 1856//1856 1818//1818 1819//1819 -f 1856//1856 1819//1819 1820//1820 -f 1856//1856 1824//1824 1854//1854 -f 1854//1854 1824//1824 1825//1825 -f 1854//1854 1825//1825 1852//1852 -f 1852//1852 1825//1825 1826//1826 -f 1852//1852 1826//1826 1827//1827 -f 1828//1828 1829//1829 1852//1852 -f 1852//1852 1829//1829 1830//1830 -f 1852//1852 1830//1830 1850//1850 -f 1850//1850 1830//1830 1831//1831 -f 1850//1850 1831//1831 1832//1832 -f 1823//1823 1824//1824 1822//1822 -f 1822//1822 1824//1824 1856//1856 -f 1822//1822 1856//1856 1821//1821 -f 1821//1821 1856//1856 1820//1820 -f 1861//1861 1859//1859 1868//1868 -f 1868//1868 1859//1859 1857//1857 -f 1868//1868 1857//1857 1855//1855 -f 1867//1867 1865//1865 1868//1868 -f 1868//1868 1865//1865 1863//1863 -f 1868//1868 1863//1863 1861//1861 -f 1849//1849 1847//1847 1868//1868 -f 1868//1868 1847//1847 1845//1845 -f 1868//1868 1845//1845 1867//1867 -f 1855//1855 1853//1853 1868//1868 -f 1868//1868 1853//1853 1851//1851 -f 1868//1868 1851//1851 1849//1849 -f 1869//1869 1870//1870 1660//1660 -f 1660//1660 1870//1870 1664//1664 -f 1870//1870 1871//1871 1664//1664 -f 1664//1664 1871//1871 1650//1650 -f 1871//1871 1872//1872 1650//1650 -f 1650//1650 1872//1872 1661//1661 -f 1872//1872 1869//1869 1661//1661 -f 1661//1661 1869//1869 1660//1660 -f 1872//1872 1871//1871 1869//1869 -f 1869//1869 1871//1871 1870//1870 -f 1873//1873 1874//1874 1875//1875 -f 1876//1876 1877//1877 1878//1878 -f 1879//1879 1880//1880 1881//1881 -f 1880//1880 1882//1882 1881//1881 -f 1881//1881 1882//1882 1883//1883 -f 1881//1881 1883//1883 1884//1884 -f 1884//1884 1883//1883 1885//1885 -f 1886//1886 1887//1887 1888//1888 -f 1888//1888 1887//1887 1875//1875 -f 1888//1888 1875//1875 1889//1889 -f 1889//1889 1875//1875 1890//1890 -f 1891//1891 1892//1892 1893//1893 -f 1894//1894 1875//1875 1895//1895 -f 1895//1895 1875//1875 1891//1891 -f 1895//1895 1891//1891 1896//1896 -f 1896//1896 1891//1891 1893//1893 -f 1894//1894 1897//1897 1875//1875 -f 1875//1875 1897//1897 1898//1898 -f 1875//1875 1898//1898 1890//1890 -f 1890//1890 1898//1898 1899//1899 -f 1890//1890 1899//1899 1900//1900 -f 1900//1900 1899//1899 1901//1901 -f 1902//1902 1903//1903 1901//1901 -f 1901//1901 1903//1903 1904//1904 -f 1901//1901 1904//1904 1900//1900 -f 1902//1902 1905//1905 1903//1903 -f 1903//1903 1905//1905 1906//1906 -f 1903//1903 1906//1906 1892//1892 -f 1907//1907 1908//1908 1909//1909 -f 1909//1909 1908//1908 1910//1910 -f 1909//1909 1910//1910 1903//1903 -f 1903//1903 1910//1910 1911//1911 -f 1903//1903 1911//1911 1904//1904 -f 1912//1912 1913//1913 1914//1914 -f 1915//1915 1916//1916 1917//1917 -f 1917//1917 1918//1918 1915//1915 -f 1915//1915 1918//1918 1919//1919 -f 1915//1915 1919//1919 1913//1913 -f 1913//1913 1919//1919 1920//1920 -f 1913//1913 1920//1920 1914//1914 -f 1915//1915 1921//1921 1916//1916 -f 1916//1916 1921//1921 1884//1884 -f 1916//1916 1884//1884 1922//1922 -f 1922//1922 1884//1884 1885//1885 -f 1923//1923 1924//1924 1925//1925 -f 1926//1926 1927//1927 1928//1928 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1935//1935 -f 1935//1935 1934//1934 1936//1936 -f 1935//1935 1936//1936 1937//1937 -f 1937//1937 1936//1936 1938//1938 -f 1928//1928 1939//1939 1926//1926 -f 1926//1926 1939//1939 1940//1940 -f 1926//1926 1940//1940 1925//1925 -f 1925//1925 1940//1940 1941//1941 -f 1925//1925 1941//1941 1923//1923 -f 1942//1942 1943//1943 1944//1944 -f 1944//1944 1943//1943 1945//1945 -f 1944//1944 1945//1945 1946//1946 -f 1946//1946 1945//1945 1930//1930 -f 1946//1946 1930//1930 1926//1926 -f 1926//1926 1930//1930 1929//1929 -f 1926//1926 1929//1929 1927//1927 -f 1947//1947 1948//1948 1949//1949 -f 1950//1950 1951//1951 1952//1952 -f 1951//1951 1950//1950 1953//1953 -f 1953//1953 1950//1950 1954//1954 -f 1953//1953 1954//1954 1955//1955 -f 1952//1952 1956//1956 1950//1950 -f 1950//1950 1956//1956 1957//1957 -f 1950//1950 1957//1957 1958//1958 -f 1955//1955 1954//1954 1959//1959 -f 1959//1959 1954//1954 1960//1960 -f 1959//1959 1960//1960 1948//1948 -f 1948//1948 1960//1960 1961//1961 -f 1948//1948 1961//1961 1949//1949 -f 1957//1957 1962//1962 1958//1958 -f 1958//1958 1962//1962 1963//1963 -f 1958//1958 1963//1963 1964//1964 -f 1942//1942 1944//1944 1965//1965 -f 1965//1965 1944//1944 1966//1966 -f 1965//1965 1966//1966 1967//1967 -f 1967//1967 1966//1966 1958//1958 -f 1967//1967 1958//1958 1949//1949 -f 1949//1949 1958//1958 1964//1964 -f 1949//1949 1964//1964 1947//1947 -f 1877//1877 1968//1968 1878//1878 -f 1878//1878 1968//1968 1969//1969 -f 1878//1878 1969//1969 1950//1950 -f 1950//1950 1969//1969 1970//1970 -f 1950//1950 1970//1970 1954//1954 -f 1971//1971 1972//1972 1973//1973 -f 1891//1891 1974//1974 1975//1975 -f 1892//1892 1891//1891 1903//1903 -f 1903//1903 1891//1891 1975//1975 -f 1903//1903 1975//1975 1976//1976 -f 1976//1976 1975//1975 1977//1977 -f 1976//1976 1977//1977 1971//1971 -f 1978//1978 1979//1979 1980//1980 -f 1980//1980 1979//1979 1981//1981 -f 1982//1982 1983//1983 1984//1984 -f 1982//1982 1984//1984 1979//1979 -f 1979//1979 1984//1984 1985//1985 -f 1979//1979 1985//1985 1981//1981 -f 1986//1986 1987//1987 1983//1983 -f 1988//1988 1989//1989 1990//1990 -f 1990//1990 1989//1989 1991//1991 -f 1991//1991 1989//1989 1992//1992 -f 1992//1992 1989//1989 1925//1925 -f 1992//1992 1925//1925 1938//1938 -f 1938//1938 1925//1925 1924//1924 -f 1938//1938 1924//1924 1937//1937 -f 1983//1983 1982//1982 1986//1986 -f 1986//1986 1982//1982 1887//1887 -f 1986//1986 1887//1887 1993//1993 -f 1874//1874 1979//1979 1875//1875 -f 1875//1875 1979//1979 1978//1978 -f 1875//1875 1978//1978 1891//1891 -f 1891//1891 1978//1978 1994//1994 -f 1891//1891 1994//1994 1974//1974 -f 1995//1995 1982//1982 1996//1996 -f 1996//1996 1982//1982 1979//1979 -f 1996//1996 1979//1979 1997//1997 -f 1997//1997 1979//1979 1874//1874 -f 1998//1998 1999//1999 1887//1887 -f 1887//1887 1999//1999 2000//2000 -f 1887//1887 2000//2000 1875//1875 -f 1875//1875 2000//2000 2001//2001 -f 1875//1875 2001//2001 1873//1873 -f 1995//1995 2002//2002 1982//1982 -f 1982//1982 2002//2002 2003//2003 -f 1982//1982 2003//2003 1887//1887 -f 1887//1887 2003//2003 2004//2004 -f 1887//1887 2004//2004 1998//1998 -f 2005//2005 2006//2006 1881//1881 -f 1881//1881 2006//2006 2007//2007 -f 1881//1881 2007//2007 2008//2008 -f 2009//2009 2010//2010 1993//1993 -f 1993//1993 2010//2010 2011//2011 -f 1993//1993 2011//2011 2012//2012 -f 1886//1886 2013//2013 1887//1887 -f 1887//1887 2013//2013 1879//1879 -f 1887//1887 1879//1879 1993//1993 -f 1993//1993 1879//1879 1881//1881 -f 1993//1993 1881//1881 2009//2009 -f 2009//2009 1881//1881 2008//2008 -f 1987//1987 1986//1986 1988//1988 -f 1988//1988 1986//1986 1993//1993 -f 1988//1988 1993//1993 1989//1989 -f 1989//1989 1993//1993 2012//2012 -f 1989//1989 2012//2012 2014//2014 -f 2014//2014 2015//2015 1989//1989 -f 1989//1989 2015//2015 2016//2016 -f 1989//1989 2016//2016 1925//1925 -f 1925//1925 2016//2016 2017//2017 -f 1925//1925 2017//2017 2005//2005 -f 1971//1971 1973//1973 1976//1976 -f 1976//1976 1973//1973 2018//2018 -f 1976//1976 2018//2018 2019//2019 -f 2019//2019 2020//2020 1976//1976 -f 1976//1976 2020//2020 2021//2021 -f 1976//1976 2021//2021 1903//1903 -f 1903//1903 2021//2021 2022//2022 -f 1903//1903 2022//2022 2023//2023 -f 2024//2024 1909//1909 2025//2025 -f 2025//2025 1909//1909 1903//1903 -f 2025//2025 1903//1903 2026//2026 -f 2026//2026 1903//1903 2023//2023 -f 2024//2024 2027//2027 1909//1909 -f 1909//1909 2027//2027 2028//2028 -f 1909//1909 2028//2028 1973//1973 -f 1973//1973 2028//2028 2029//2029 -f 1973//1973 2029//2029 2018//2018 -f 1973//1973 2030//2030 1909//1909 -f 1909//1909 2030//2030 1912//1912 -f 1909//1909 1912//1912 1907//1907 -f 1907//1907 1912//1912 1914//1914 -f 2031//2031 2032//2032 1921//1921 -f 1921//1921 2032//2032 2033//2033 -f 1921//1921 2033//2033 2034//2034 -f 2005//2005 1881//1881 1925//1925 -f 1925//1925 1881//1881 1884//1884 -f 1925//1925 1884//1884 1926//1926 -f 1926//1926 1884//1884 1921//1921 -f 1926//1926 1921//1921 1946//1946 -f 1946//1946 1921//1921 2034//2034 -f 1946//1946 2034//2034 2035//2035 -f 2036//2036 1944//1944 2037//2037 -f 2037//2037 1944//1944 1946//1946 -f 2037//2037 1946//1946 2038//2038 -f 2038//2038 1946//1946 2035//2035 -f 2036//2036 2039//2039 1944//1944 -f 1944//1944 2039//2039 2040//2040 -f 1944//1944 2040//2040 1966//1966 -f 1966//1966 2040//2040 2041//2041 -f 1966//1966 2041//2041 2042//2042 -f 1912//1912 2043//2043 2044//2044 -f 2045//2045 2046//2046 1950//1950 -f 2044//2044 2047//2047 1912//1912 -f 1912//1912 2047//2047 2048//2048 -f 1912//1912 2048//2048 1913//1913 -f 1913//1913 2048//2048 2049//2049 -f 1913//1913 2049//2049 2050//2050 -f 2050//2050 2045//2045 1913//1913 -f 1913//1913 2045//2045 1950//1950 -f 1913//1913 1950//1950 1915//1915 -f 1915//1915 1950//1950 1958//1958 -f 1915//1915 1958//1958 1921//1921 -f 1921//1921 1958//1958 1966//1966 -f 1921//1921 1966//1966 2031//2031 -f 2031//2031 1966//1966 2042//2042 -f 2046//2046 2051//2051 1950//1950 -f 1950//1950 2051//2051 2052//2052 -f 1950//1950 2052//2052 1878//1878 -f 1878//1878 2052//2052 2053//2053 -f 1878//1878 2053//2053 2054//2054 -f 1972//1972 2055//2055 1973//1973 -f 1973//1973 2055//2055 2056//2056 -f 1973//1973 2056//2056 2030//2030 -f 2030//2030 2056//2056 1876//1876 -f 2030//2030 1876//1876 1912//1912 -f 1912//1912 1876//1876 1878//1878 -f 1912//1912 1878//1878 2043//2043 -f 2043//2043 1878//1878 2054//2054 -f 2057//2057 2058//2058 2059//2059 -f 2060//2060 2061//2061 2062//2062 -f 2063//2063 2064//2064 2065//2065 -f 2066//2066 2067//2067 2068//2068 -f 2069//2069 2070//2070 2071//2071 -f 2072//2072 2073//2073 2062//2062 -f 2074//2074 2075//2075 2076//2076 -f 2077//2077 2078//2078 2079//2079 -f 2077//2077 2079//2079 2080//2080 -f 2080//2080 2079//2079 2081//2081 -f 2081//2081 2079//2079 2082//2082 -f 2081//2081 2082//2082 2083//2083 -f 2076//2076 2075//2075 2084//2084 -f 2084//2084 2075//2075 2085//2085 -f 2084//2084 2085//2085 2082//2082 -f 2082//2082 2085//2085 2086//2086 -f 2082//2082 2086//2086 2083//2083 -f 2074//2074 2076//2076 2087//2087 -f 2087//2087 2076//2076 2088//2088 -f 2087//2087 2088//2088 2089//2089 -f 2062//2062 2073//2073 2090//2090 -f 2090//2090 2073//2073 2091//2091 -f 2090//2090 2091//2091 2088//2088 -f 2088//2088 2091//2091 2092//2092 -f 2088//2088 2092//2092 2089//2089 -f 2061//2061 2093//2093 2094//2094 -f 2061//2061 2094//2094 2062//2062 -f 2062//2062 2094//2094 2095//2095 -f 2062//2062 2095//2095 2072//2072 -f 2096//2096 2097//2097 2098//2098 -f 2098//2098 2097//2097 2099//2099 -f 2099//2099 2100//2100 2098//2098 -f 2098//2098 2100//2100 2101//2101 -f 2098//2098 2101//2101 2102//2102 -f 2102//2102 2101//2101 2103//2103 -f 2104//2104 2061//2061 2105//2105 -f 2105//2105 2061//2061 2102//2102 -f 2105//2105 2102//2102 2106//2106 -f 2106//2106 2102//2102 2103//2103 -f 2104//2104 2107//2107 2061//2061 -f 2061//2061 2107//2107 2108//2108 -f 2061//2061 2108//2108 2093//2093 -f 2093//2093 2108//2108 2109//2109 -f 2093//2093 2109//2109 2110//2110 -f 2110//2110 2109//2109 2096//2096 -f 2110//2110 2096//2096 2111//2111 -f 2111//2111 2096//2096 2098//2098 -f 2112//2112 2113//2113 2059//2059 -f 2059//2059 2113//2113 2114//2114 -f 2059//2059 2114//2114 2098//2098 -f 2098//2098 2114//2114 2115//2115 -f 2098//2098 2115//2115 2111//2111 -f 2071//2071 2116//2116 2117//2117 -f 2116//2116 2071//2071 2118//2118 -f 2118//2118 2071//2071 2070//2070 -f 2118//2118 2070//2070 2119//2119 -f 2119//2119 2070//2070 2120//2120 -f 2119//2119 2120//2120 2121//2121 -f 2121//2121 2120//2120 2122//2122 -f 2121//2121 2122//2122 2123//2123 -f 2123//2123 2122//2122 2124//2124 -f 2123//2123 2124//2124 2125//2125 -f 2125//2125 2124//2124 2126//2126 -f 2125//2125 2126//2126 2127//2127 -f 2117//2117 2128//2128 2071//2071 -f 2071//2071 2128//2128 2129//2129 -f 2071//2071 2129//2129 2130//2130 -f 2130//2130 2129//2129 2131//2131 -f 2130//2130 2131//2131 2132//2132 -f 2133//2133 2134//2134 2135//2135 -f 2135//2135 2134//2134 2136//2136 -f 2135//2135 2136//2136 2137//2137 -f 2138//2138 2139//2139 2136//2136 -f 2136//2136 2139//2139 2140//2140 -f 2136//2136 2140//2140 2137//2137 -f 2141//2141 2142//2142 2138//2138 -f 2138//2138 2142//2142 2143//2143 -f 2138//2138 2143//2143 2139//2139 -f 2138//2138 2098//2098 2141//2141 -f 2141//2141 2098//2098 2102//2102 -f 2141//2141 2102//2102 2144//2144 -f 2144//2144 2102//2102 2145//2145 -f 2146//2146 2147//2147 2148//2148 -f 2148//2148 2147//2147 2149//2149 -f 2148//2148 2149//2149 2150//2150 -f 2150//2150 2149//2149 2151//2151 -f 2150//2150 2151//2151 2065//2065 -f 2065//2065 2151//2151 2152//2152 -f 2065//2065 2152//2152 2063//2063 -f 2153//2153 2154//2154 2155//2155 -f 2156//2156 2157//2157 2158//2158 -f 2154//2154 2159//2159 2155//2155 -f 2155//2155 2159//2159 2160//2160 -f 2155//2155 2160//2160 2161//2161 -f 2161//2161 2160//2160 2162//2162 -f 2161//2161 2162//2162 2163//2163 -f 2158//2158 2164//2164 2156//2156 -f 2156//2156 2164//2164 2165//2165 -f 2156//2156 2165//2165 2155//2155 -f 2155//2155 2165//2165 2166//2166 -f 2155//2155 2166//2166 2153//2153 -f 2154//2154 2167//2167 2159//2159 -f 2159//2159 2167//2167 2168//2168 -f 2159//2159 2168//2168 2169//2169 -f 2169//2169 2168//2168 2170//2170 -f 2169//2169 2170//2170 2171//2171 -f 2171//2171 2170//2170 2172//2172 -f 2171//2171 2172//2172 2173//2173 -f 2173//2173 2172//2172 2174//2174 -f 2175//2175 2176//2176 2177//2177 -f 2177//2177 2176//2176 2178//2178 -f 2177//2177 2178//2178 2179//2179 -f 2179//2179 2178//2178 2173//2173 -f 2179//2179 2173//2173 2156//2156 -f 2156//2156 2173//2173 2174//2174 -f 2156//2156 2174//2174 2157//2157 -f 2132//2132 2127//2127 2130//2130 -f 2130//2130 2127//2127 2126//2126 -f 2130//2130 2126//2126 2180//2180 -f 2180//2180 2126//2126 2181//2181 -f 2180//2180 2181//2181 2177//2177 -f 2177//2177 2181//2181 2182//2182 -f 2177//2177 2182//2182 2175//2175 -f 2177//2177 2183//2183 2184//2184 -f 2177//2177 2184//2184 2180//2180 -f 2180//2180 2184//2184 2185//2185 -f 2180//2180 2185//2185 2186//2186 -f 2187//2187 2188//2188 2084//2084 -f 2084//2084 2188//2188 2189//2189 -f 2084//2084 2189//2189 2190//2190 -f 2190//2190 2191//2191 2179//2179 -f 2191//2191 2192//2192 2179//2179 -f 2179//2179 2192//2192 2193//2193 -f 2179//2179 2193//2193 2177//2177 -f 2177//2177 2193//2193 2194//2194 -f 2177//2177 2194//2194 2183//2183 -f 2088//2088 2195//2195 2196//2196 -f 2197//2197 2161//2161 2198//2198 -f 2198//2198 2161//2161 2090//2090 -f 2198//2198 2090//2090 2199//2199 -f 2196//2196 2200//2200 2088//2088 -f 2088//2088 2200//2200 2201//2201 -f 2088//2088 2201//2201 2090//2090 -f 2090//2090 2201//2201 2202//2202 -f 2090//2090 2202//2202 2199//2199 -f 2197//2197 2203//2203 2161//2161 -f 2161//2161 2203//2203 2204//2204 -f 2161//2161 2204//2204 2155//2155 -f 2155//2155 2204//2204 2205//2205 -f 2155//2155 2205//2205 2206//2206 -f 2190//2190 2179//2179 2084//2084 -f 2084//2084 2179//2179 2156//2156 -f 2084//2084 2156//2156 2076//2076 -f 2076//2076 2156//2156 2155//2155 -f 2076//2076 2155//2155 2088//2088 -f 2088//2088 2155//2155 2206//2206 -f 2088//2088 2206//2206 2195//2195 -f 2186//2186 2187//2187 2180//2180 -f 2180//2180 2187//2187 2084//2084 -f 2180//2180 2084//2084 2130//2130 -f 2130//2130 2084//2084 2082//2082 -f 2130//2130 2082//2082 2071//2071 -f 2071//2071 2082//2082 2079//2079 -f 2207//2207 2208//2208 2062//2062 -f 2060//2060 2209//2209 2061//2061 -f 2061//2061 2209//2209 2210//2210 -f 2061//2061 2210//2210 2211//2211 -f 2208//2208 2212//2212 2062//2062 -f 2062//2062 2212//2212 2213//2213 -f 2062//2062 2213//2213 2060//2060 -f 2145//2145 2102//2102 2064//2064 -f 2064//2064 2102//2102 2061//2061 -f 2064//2064 2061//2061 2065//2065 -f 2065//2065 2061//2061 2211//2211 -f 2065//2065 2211//2211 2214//2214 -f 2163//2163 2215//2215 2161//2161 -f 2161//2161 2215//2215 2146//2146 -f 2161//2161 2146//2146 2090//2090 -f 2090//2090 2146//2146 2148//2148 -f 2090//2090 2148//2148 2062//2062 -f 2062//2062 2148//2148 2150//2150 -f 2062//2062 2150//2150 2207//2207 -f 2214//2214 2216//2216 2065//2065 -f 2065//2065 2216//2216 2217//2217 -f 2065//2065 2217//2217 2150//2150 -f 2150//2150 2217//2217 2218//2218 -f 2150//2150 2218//2218 2207//2207 -f 2068//2068 2219//2219 2220//2220 -f 2221//2221 2222//2222 2223//2223 -f 2067//2067 2069//2069 2068//2068 -f 2068//2068 2069//2069 2071//2071 -f 2068//2068 2071//2071 2219//2219 -f 2219//2219 2071//2071 2224//2224 -f 2220//2220 2225//2225 2068//2068 -f 2068//2068 2225//2225 2226//2226 -f 2068//2068 2226//2226 2223//2223 -f 2223//2223 2226//2226 2227//2227 -f 2223//2223 2227//2227 2221//2221 -f 2112//2112 2059//2059 2078//2078 -f 2078//2078 2059//2059 2223//2223 -f 2078//2078 2223//2223 2079//2079 -f 2079//2079 2223//2223 2222//2222 -f 2079//2079 2222//2222 2228//2228 -f 2228//2228 2229//2229 2079//2079 -f 2079//2079 2229//2229 2230//2230 -f 2079//2079 2230//2230 2071//2071 -f 2071//2071 2230//2230 2231//2231 -f 2071//2071 2231//2231 2224//2224 -f 2066//2066 2068//2068 2133//2133 -f 2133//2133 2068//2068 2223//2223 -f 2133//2133 2223//2223 2134//2134 -f 2134//2134 2223//2223 2059//2059 -f 2134//2134 2059//2059 2136//2136 -f 2136//2136 2059//2059 2058//2058 -f 2136//2136 2058//2058 2232//2232 -f 2138//2138 2233//2233 2098//2098 -f 2098//2098 2233//2233 2234//2234 -f 2098//2098 2234//2234 2235//2235 -f 2232//2232 2236//2236 2136//2136 -f 2136//2136 2236//2236 2237//2237 -f 2136//2136 2237//2237 2138//2138 -f 2138//2138 2237//2237 2238//2238 -f 2138//2138 2238//2238 2233//2233 -f 2235//2235 2239//2239 2098//2098 -f 2098//2098 2239//2239 2240//2240 -f 2098//2098 2240//2240 2059//2059 -f 2059//2059 2240//2240 2241//2241 -f 2059//2059 2241//2241 2057//2057 -f 1972//1972 2149//2149 2055//2055 -f 2055//2055 2149//2149 2147//2147 -f 2055//2055 2147//2147 2056//2056 -f 2056//2056 2147//2147 2146//2146 -f 2056//2056 2146//2146 1876//1876 -f 1876//1876 2146//2146 2215//2215 -f 1876//1876 2215//2215 1877//1877 -f 1877//1877 2215//2215 2163//2163 -f 1877//1877 2163//2163 1968//1968 -f 1968//1968 2163//2163 2162//2162 -f 1968//1968 2162//2162 1969//1969 -f 1969//1969 2162//2162 2160//2160 -f 1969//1969 2160//2160 1970//1970 -f 1970//1970 2160//2160 2159//2159 -f 1970//1970 2159//2159 1954//1954 -f 1954//1954 2159//2159 2169//2169 -f 1954//1954 2169//2169 1960//1960 -f 1960//1960 2169//2169 2171//2171 -f 1960//1960 2171//2171 1961//1961 -f 1961//1961 2171//2171 2173//2173 -f 1961//1961 2173//2173 1949//1949 -f 1949//1949 2173//2173 2178//2178 -f 1949//1949 2178//2178 1967//1967 -f 1967//1967 2178//2178 2176//2176 -f 1967//1967 2176//2176 1965//1965 -f 1965//1965 2176//2176 2175//2175 -f 1965//1965 2175//2175 1942//1942 -f 1942//1942 2175//2175 2182//2182 -f 1942//1942 2182//2182 1943//1943 -f 1943//1943 2182//2182 2181//2181 -f 1943//1943 2181//2181 1945//1945 -f 1945//1945 2181//2181 2126//2126 -f 1945//1945 2126//2126 1930//1930 -f 1930//1930 2126//2126 2124//2124 -f 1930//1930 2124//2124 1932//1932 -f 1932//1932 2124//2124 2122//2122 -f 1932//1932 2122//2122 1934//1934 -f 1934//1934 2122//2122 2120//2120 -f 1934//1934 2120//2120 1936//1936 -f 1936//1936 2120//2120 2070//2070 -f 1936//1936 2070//2070 1938//1938 -f 1938//1938 2070//2070 2069//2069 -f 1938//1938 2069//2069 1992//1992 -f 1992//1992 2069//2069 2067//2067 -f 1992//1992 2067//2067 1991//1991 -f 1991//1991 2067//2067 2066//2066 -f 1991//1991 2066//2066 1990//1990 -f 1990//1990 2066//2066 2133//2133 -f 1990//1990 2133//2133 1988//1988 -f 1988//1988 2133//2133 2135//2135 -f 1988//1988 2135//2135 1987//1987 -f 1987//1987 2135//2135 2137//2137 -f 1987//1987 2137//2137 1983//1983 -f 1983//1983 2137//2137 2140//2140 -f 1983//1983 2140//2140 1984//1984 -f 1984//1984 2140//2140 2139//2139 -f 1984//1984 2139//2139 1985//1985 -f 1985//1985 2139//2139 2143//2143 -f 1985//1985 2143//2143 1981//1981 -f 1981//1981 2143//2143 2142//2142 -f 1981//1981 2142//2142 1980//1980 -f 1980//1980 2142//2142 2141//2141 -f 1980//1980 2141//2141 1978//1978 -f 1978//1978 2141//2141 2144//2144 -f 1978//1978 2144//2144 1994//1994 -f 1994//1994 2144//2144 2145//2145 -f 1994//1994 2145//2145 1974//1974 -f 1974//1974 2145//2145 2064//2064 -f 1974//1974 2064//2064 1975//1975 -f 1975//1975 2064//2064 2063//2063 -f 1975//1975 2063//2063 1977//1977 -f 1977//1977 2063//2063 2152//2152 -f 1977//1977 2152//2152 1971//1971 -f 1971//1971 2152//2152 2151//2151 -f 1971//1971 2151//2151 1972//1972 -f 1972//1972 2151//2151 2149//2149 -f 2242//2242 2243//2243 2244//2244 -f 2244//2244 2243//2243 2245//2245 -f 2244//2244 2245//2245 2246//2246 -f 2246//2246 2245//2245 2247//2247 -f 2246//2246 2247//2247 2248//2248 -f 2248//2248 2247//2247 2249//2249 -f 2248//2248 2249//2249 2250//2250 -f 2250//2250 2249//2249 2251//2251 -f 2250//2250 2251//2251 2252//2252 -f 2252//2252 2251//2251 2253//2253 -f 2252//2252 2253//2253 2254//2254 -f 2254//2254 2253//2253 2255//2255 -f 2254//2254 2255//2255 2256//2256 -f 2256//2256 2255//2255 2257//2257 -f 2256//2256 2257//2257 2258//2258 -f 2258//2258 2257//2257 2259//2259 -f 2258//2258 2259//2259 2260//2260 -f 2260//2260 2259//2259 2261//2261 -f 2260//2260 2261//2261 2262//2262 -f 2262//2262 2261//2261 2263//2263 -f 2262//2262 2263//2263 2264//2264 -f 2264//2264 2263//2263 2265//2265 -f 2264//2264 2265//2265 2266//2266 -f 2266//2266 2265//2265 2267//2267 -f 2266//2266 2267//2267 2268//2268 -f 2268//2268 2267//2267 2269//2269 -f 2268//2268 2269//2269 2270//2270 -f 2270//2270 2269//2269 2271//2271 -f 2270//2270 2271//2271 2272//2272 -f 2272//2272 2271//2271 2273//2273 -f 2272//2272 2273//2273 2274//2274 -f 2274//2274 2273//2273 2275//2275 -f 2274//2274 2275//2275 2276//2276 -f 2276//2276 2275//2275 2277//2277 -f 2276//2276 2277//2277 2278//2278 -f 2278//2278 2277//2277 2279//2279 -f 2278//2278 2279//2279 2280//2280 -f 2280//2280 2279//2279 2242//2242 -f 2280//2280 2242//2242 2244//2244 -f 2154//2154 1951//1951 2167//2167 -f 2167//2167 1951//1951 1953//1953 -f 2167//2167 1953//1953 2168//2168 -f 2168//2168 1953//1953 1955//1955 -f 2168//2168 1955//1955 2170//2170 -f 2170//2170 1955//1955 1959//1959 -f 2170//2170 1959//1959 2172//2172 -f 2172//2172 1959//1959 1948//1948 -f 2172//2172 1948//1948 2174//2174 -f 2174//2174 1948//1948 1947//1947 -f 2174//2174 1947//1947 2157//2157 -f 2157//2157 1947//1947 1964//1964 -f 2157//2157 1964//1964 2158//2158 -f 2158//2158 1964//1964 1963//1963 -f 2158//2158 1963//1963 2164//2164 -f 2164//2164 1963//1963 1962//1962 -f 2164//2164 1962//1962 2165//2165 -f 2165//2165 1962//1962 1957//1957 -f 2165//2165 1957//1957 2166//2166 -f 2166//2166 1957//1957 1956//1956 -f 2166//2166 1956//1956 2153//2153 -f 2153//2153 1956//1956 1952//1952 -f 2153//2153 1952//1952 2154//2154 -f 2154//2154 1952//1952 1951//1951 -f 2190//2190 2031//2031 2191//2191 -f 2191//2191 2031//2031 2042//2042 -f 2191//2191 2042//2042 2192//2192 -f 2192//2192 2042//2042 2041//2041 -f 2192//2192 2041//2041 2193//2193 -f 2193//2193 2041//2041 2040//2040 -f 2193//2193 2040//2040 2194//2194 -f 2194//2194 2040//2040 2039//2039 -f 2194//2194 2039//2039 2183//2183 -f 2183//2183 2039//2039 2036//2036 -f 2183//2183 2036//2036 2184//2184 -f 2184//2184 2036//2036 2037//2037 -f 2184//2184 2037//2037 2185//2185 -f 2185//2185 2037//2037 2038//2038 -f 2185//2185 2038//2038 2186//2186 -f 2186//2186 2038//2038 2035//2035 -f 2186//2186 2035//2035 2187//2187 -f 2187//2187 2035//2035 2034//2034 -f 2187//2187 2034//2034 2188//2188 -f 2188//2188 2034//2034 2033//2033 -f 2188//2188 2033//2033 2189//2189 -f 2189//2189 2033//2033 2032//2032 -f 2189//2189 2032//2032 2190//2190 -f 2190//2190 2032//2032 2031//2031 -f 2129//2129 1940//1940 2131//2131 -f 2131//2131 1940//1940 1939//1939 -f 2131//2131 1939//1939 2132//2132 -f 2132//2132 1939//1939 1928//1928 -f 2132//2132 1928//1928 2127//2127 -f 2127//2127 1928//1928 1927//1927 -f 2127//2127 1927//1927 2125//2125 -f 2125//2125 1927//1927 1929//1929 -f 2125//2125 1929//1929 2123//2123 -f 2123//2123 1929//1929 1931//1931 -f 2123//2123 1931//1931 2121//2121 -f 2121//2121 1931//1931 1933//1933 -f 2121//2121 1933//1933 2119//2119 -f 2119//2119 1933//1933 1935//1935 -f 2119//2119 1935//1935 2118//2118 -f 2118//2118 1935//1935 1937//1937 -f 2118//2118 1937//1937 2116//2116 -f 2116//2116 1937//1937 1924//1924 -f 2116//2116 1924//1924 2117//2117 -f 2117//2117 1924//1924 1923//1923 -f 2117//2117 1923//1923 2128//2128 -f 2128//2128 1923//1923 1941//1941 -f 2128//2128 1941//1941 2129//2129 -f 2129//2129 1941//1941 1940//1940 -f 2222//2222 2009//2009 2228//2228 -f 2228//2228 2009//2009 2008//2008 -f 2228//2228 2008//2008 2229//2229 -f 2229//2229 2008//2008 2007//2007 -f 2229//2229 2007//2007 2230//2230 -f 2230//2230 2007//2007 2006//2006 -f 2230//2230 2006//2006 2231//2231 -f 2231//2231 2006//2006 2005//2005 -f 2231//2231 2005//2005 2224//2224 -f 2224//2224 2005//2005 2017//2017 -f 2224//2224 2017//2017 2219//2219 -f 2219//2219 2017//2017 2016//2016 -f 2219//2219 2016//2016 2220//2220 -f 2220//2220 2016//2016 2015//2015 -f 2220//2220 2015//2015 2225//2225 -f 2225//2225 2015//2015 2014//2014 -f 2225//2225 2014//2014 2226//2226 -f 2226//2226 2014//2014 2012//2012 -f 2226//2226 2012//2012 2227//2227 -f 2227//2227 2012//2012 2011//2011 -f 2227//2227 2011//2011 2221//2221 -f 2221//2221 2011//2011 2010//2010 -f 2221//2221 2010//2010 2222//2222 -f 2222//2222 2010//2010 2009//2009 -f 2234//2234 1874//1874 2235//2235 -f 2235//2235 1874//1874 1873//1873 -f 2235//2235 1873//1873 2239//2239 -f 2239//2239 1873//1873 2001//2001 -f 2239//2239 2001//2001 2240//2240 -f 2240//2240 2001//2001 2000//2000 -f 2240//2240 2000//2000 2241//2241 -f 2241//2241 2000//2000 1999//1999 -f 2241//2241 1999//1999 2057//2057 -f 2057//2057 1999//1999 1998//1998 -f 2057//2057 1998//1998 2058//2058 -f 2058//2058 1998//1998 2004//2004 -f 2058//2058 2004//2004 2232//2232 -f 2232//2232 2004//2004 2003//2003 -f 2232//2232 2003//2003 2236//2236 -f 2236//2236 2003//2003 2002//2002 -f 2236//2236 2002//2002 2237//2237 -f 2237//2237 2002//2002 1995//1995 -f 2237//2237 1995//1995 2238//2238 -f 2238//2238 1995//1995 1996//1996 -f 2238//2238 1996//1996 2233//2233 -f 2233//2233 1996//1996 1997//1997 -f 2233//2233 1997//1997 2234//2234 -f 2234//2234 1997//1997 1874//1874 -f 2105//2105 1892//1892 2104//2104 -f 2104//2104 1892//1892 1906//1906 -f 2104//2104 1906//1906 2107//2107 -f 2107//2107 1906//1906 1905//1905 -f 2107//2107 1905//1905 2108//2108 -f 2108//2108 1905//1905 1902//1902 -f 2108//2108 1902//1902 2109//2109 -f 2109//2109 1902//1902 1901//1901 -f 2109//2109 1901//1901 2096//2096 -f 2096//2096 1901//1901 1899//1899 -f 2096//2096 1899//1899 2097//2097 -f 2097//2097 1899//1899 1898//1898 -f 2097//2097 1898//1898 2099//2099 -f 2099//2099 1898//1898 1897//1897 -f 2099//2099 1897//1897 2100//2100 -f 2100//2100 1897//1897 1894//1894 -f 2100//2100 1894//1894 2101//2101 -f 2101//2101 1894//1894 1895//1895 -f 2101//2101 1895//1895 2103//2103 -f 2103//2103 1895//1895 1896//1896 -f 2103//2103 1896//1896 2106//2106 -f 2106//2106 1896//1896 1893//1893 -f 2106//2106 1893//1893 2105//2105 -f 2105//2105 1893//1893 1892//1892 -f 2217//2217 2019//2019 2218//2218 -f 2218//2218 2019//2019 2018//2018 -f 2218//2218 2018//2018 2207//2207 -f 2207//2207 2018//2018 2029//2029 -f 2207//2207 2029//2029 2208//2208 -f 2208//2208 2029//2029 2028//2028 -f 2208//2208 2028//2028 2212//2212 -f 2212//2212 2028//2028 2027//2027 -f 2212//2212 2027//2027 2213//2213 -f 2213//2213 2027//2027 2024//2024 -f 2213//2213 2024//2024 2060//2060 -f 2060//2060 2024//2024 2025//2025 -f 2060//2060 2025//2025 2209//2209 -f 2209//2209 2025//2025 2026//2026 -f 2209//2209 2026//2026 2210//2210 -f 2210//2210 2026//2026 2023//2023 -f 2210//2210 2023//2023 2211//2211 -f 2211//2211 2023//2023 2022//2022 -f 2211//2211 2022//2022 2214//2214 -f 2214//2214 2022//2022 2021//2021 -f 2214//2214 2021//2021 2216//2216 -f 2216//2216 2021//2021 2020//2020 -f 2216//2216 2020//2020 2217//2217 -f 2217//2217 2020//2020 2019//2019 -f 2198//2198 2043//2043 2197//2197 -f 2197//2197 2043//2043 2054//2054 -f 2197//2197 2054//2054 2203//2203 -f 2203//2203 2054//2054 2053//2053 -f 2203//2203 2053//2053 2204//2204 -f 2204//2204 2053//2053 2052//2052 -f 2204//2204 2052//2052 2205//2205 -f 2205//2205 2052//2052 2051//2051 -f 2205//2205 2051//2051 2206//2206 -f 2206//2206 2051//2051 2046//2046 -f 2206//2206 2046//2046 2195//2195 -f 2195//2195 2046//2046 2045//2045 -f 2195//2195 2045//2045 2196//2196 -f 2196//2196 2045//2045 2050//2050 -f 2196//2196 2050//2050 2200//2200 -f 2200//2200 2050//2050 2049//2049 -f 2200//2200 2049//2049 2201//2201 -f 2201//2201 2049//2049 2048//2048 -f 2201//2201 2048//2048 2202//2202 -f 2202//2202 2048//2048 2047//2047 -f 2202//2202 2047//2047 2199//2199 -f 2199//2199 2047//2047 2044//2044 -f 2199//2199 2044//2044 2198//2198 -f 2198//2198 2044//2044 2043//2043 -f 2281//2281 2282//2282 2283//2283 -f 2284//2284 2285//2285 2286//2286 -f 2287//2287 2288//2288 2283//2283 -f 2283//2283 2288//2288 2289//2289 -f 2283//2283 2289//2289 2281//2281 -f 2290//2290 2291//2291 2287//2287 -f 2287//2287 2291//2291 2292//2292 -f 2287//2287 2292//2292 2288//2288 -f 2293//2293 2294//2294 2290//2290 -f 2290//2290 2294//2294 2295//2295 -f 2290//2290 2295//2295 2291//2291 -f 2284//2284 2296//2296 2285//2285 -f 2285//2285 2296//2296 2297//2297 -f 2285//2285 2297//2297 2293//2293 -f 2293//2293 2297//2297 2298//2298 -f 2293//2293 2298//2298 2294//2294 -f 2299//2299 2300//2300 2301//2301 -f 2281//2281 2302//2302 2282//2282 -f 2282//2282 2302//2302 2303//2303 -f 2282//2282 2303//2303 2304//2304 -f 2305//2305 2306//2306 2286//2286 -f 2286//2286 2306//2306 2307//2307 -f 2286//2286 2307//2307 2284//2284 -f 2301//2301 2308//2308 2299//2299 -f 2299//2299 2308//2308 2309//2309 -f 2299//2299 2309//2309 2305//2305 -f 2305//2305 2309//2309 2310//2310 -f 2305//2305 2310//2310 2306//2306 -f 2311//2311 2312//2312 2300//2300 -f 2300//2300 2312//2312 2313//2313 -f 2300//2300 2313//2313 2301//2301 -f 2303//2303 2314//2314 2304//2304 -f 2304//2304 2314//2314 2315//2315 -f 2304//2304 2315//2315 2311//2311 -f 2311//2311 2315//2315 2316//2316 -f 2311//2311 2316//2316 2312//2312 -f 2317//2317 2318//2318 2267//2267 -f 2319//2319 2273//2273 2320//2320 -f 2320//2320 2273//2273 2271//2271 -f 2320//2320 2271//2271 2318//2318 -f 2318//2318 2271//2271 2269//2269 -f 2318//2318 2269//2269 2267//2267 -f 2247//2247 2321//2321 2322//2322 -f 2323//2323 2257//2257 2324//2324 -f 2324//2324 2257//2257 2255//2255 -f 2324//2324 2255//2255 2325//2325 -f 2326//2326 2279//2279 2327//2327 -f 2327//2327 2279//2279 2277//2277 -f 2327//2327 2277//2277 2319//2319 -f 2319//2319 2277//2277 2275//2275 -f 2319//2319 2275//2275 2273//2273 -f 2255//2255 2253//2253 2325//2325 -f 2325//2325 2253//2253 2251//2251 -f 2325//2325 2251//2251 2322//2322 -f 2322//2322 2251//2251 2249//2249 -f 2322//2322 2249//2249 2247//2247 -f 2267//2267 2265//2265 2317//2317 -f 2317//2317 2265//2265 2263//2263 -f 2317//2317 2263//2263 2328//2328 -f 2328//2328 2263//2263 2261//2261 -f 2328//2328 2261//2261 2323//2323 -f 2323//2323 2261//2261 2259//2259 -f 2323//2323 2259//2259 2257//2257 -f 2247//2247 2245//2245 2321//2321 -f 2321//2321 2245//2245 2243//2243 -f 2321//2321 2243//2243 2326//2326 -f 2326//2326 2243//2243 2242//2242 -f 2326//2326 2242//2242 2279//2279 -f 2303//2303 2302//2302 2081//2081 -f 2081//2081 2302//2302 2080//2080 -f 2302//2302 2281//2281 2080//2080 -f 2080//2080 2281//2281 2289//2289 -f 2080//2080 2289//2289 2077//2077 -f 2077//2077 2289//2289 2288//2288 -f 2077//2077 2288//2288 2078//2078 -f 2078//2078 2288//2288 2292//2292 -f 2078//2078 2292//2292 2112//2112 -f 2112//2112 2292//2292 2291//2291 -f 2112//2112 2291//2291 2113//2113 -f 2113//2113 2291//2291 2295//2295 -f 2113//2113 2295//2295 2114//2114 -f 2114//2114 2295//2295 2294//2294 -f 2114//2114 2294//2294 2115//2115 -f 2115//2115 2294//2294 2298//2298 -f 2115//2115 2298//2298 2111//2111 -f 2111//2111 2298//2298 2297//2297 -f 2111//2111 2297//2297 2110//2110 -f 2110//2110 2297//2297 2296//2296 -f 2110//2110 2296//2296 2093//2093 -f 2093//2093 2296//2296 2284//2284 -f 2093//2093 2284//2284 2094//2094 -f 2094//2094 2284//2284 2307//2307 -f 2094//2094 2307//2307 2095//2095 -f 2095//2095 2307//2307 2306//2306 -f 2095//2095 2306//2306 2072//2072 -f 2072//2072 2306//2306 2310//2310 -f 2072//2072 2310//2310 2073//2073 -f 2073//2073 2310//2310 2309//2309 -f 2073//2073 2309//2309 2091//2091 -f 2091//2091 2309//2309 2308//2308 -f 2091//2091 2308//2308 2092//2092 -f 2092//2092 2308//2308 2301//2301 -f 2092//2092 2301//2301 2089//2089 -f 2089//2089 2301//2301 2313//2313 -f 2089//2089 2313//2313 2087//2087 -f 2087//2087 2313//2313 2312//2312 -f 2087//2087 2312//2312 2074//2074 -f 2074//2074 2312//2312 2316//2316 -f 2074//2074 2316//2316 2075//2075 -f 2075//2075 2316//2316 2315//2315 -f 2075//2075 2315//2315 2085//2085 -f 2085//2085 2315//2315 2314//2314 -f 2085//2085 2314//2314 2086//2086 -f 2086//2086 2314//2314 2303//2303 -f 2086//2086 2303//2303 2083//2083 -f 2083//2083 2303//2303 2081//2081 -f 2286//2286 2317//2317 2305//2305 -f 2305//2305 2317//2317 2328//2328 -f 2305//2305 2328//2328 2299//2299 -f 2299//2299 2328//2328 2323//2323 -f 2299//2299 2323//2323 2300//2300 -f 2300//2300 2323//2323 2324//2324 -f 2300//2300 2324//2324 2311//2311 -f 2311//2311 2324//2324 2325//2325 -f 2311//2311 2325//2325 2304//2304 -f 2304//2304 2325//2325 2322//2322 -f 2304//2304 2322//2322 2282//2282 -f 2282//2282 2322//2322 2321//2321 -f 2282//2282 2321//2321 2283//2283 -f 2283//2283 2321//2321 2326//2326 -f 2283//2283 2326//2326 2287//2287 -f 2287//2287 2326//2326 2327//2327 -f 2287//2287 2327//2327 2290//2290 -f 2290//2290 2327//2327 2319//2319 -f 2290//2290 2319//2319 2293//2293 -f 2293//2293 2319//2319 2320//2320 -f 2293//2293 2320//2320 2285//2285 -f 2285//2285 2320//2320 2318//2318 -f 2285//2285 2318//2318 2286//2286 -f 2286//2286 2318//2318 2317//2317 -f 2329//2329 2264//2264 2266//2266 -f 2274//2274 2330//2330 2272//2272 -f 2272//2272 2330//2330 2331//2331 -f 2272//2272 2331//2331 2270//2270 -f 2270//2270 2331//2331 2332//2332 -f 2270//2270 2332//2332 2268//2268 -f 2268//2268 2332//2332 2333//2333 -f 2268//2268 2333//2333 2266//2266 -f 2266//2266 2333//2333 2334//2334 -f 2266//2266 2334//2334 2329//2329 -f 2244//2244 2335//2335 2280//2280 -f 2280//2280 2335//2335 2336//2336 -f 2280//2280 2336//2336 2278//2278 -f 2278//2278 2336//2336 2337//2337 -f 2278//2278 2337//2337 2276//2276 -f 2276//2276 2337//2337 2338//2338 -f 2276//2276 2338//2338 2274//2274 -f 2274//2274 2338//2338 2339//2339 -f 2274//2274 2339//2339 2330//2330 -f 2254//2254 2340//2340 2252//2252 -f 2252//2252 2340//2340 2341//2341 -f 2252//2252 2341//2341 2250//2250 -f 2250//2250 2341//2341 2342//2342 -f 2250//2250 2342//2342 2248//2248 -f 2248//2248 2342//2342 2343//2343 -f 2248//2248 2343//2343 2246//2246 -f 2246//2246 2343//2343 2344//2344 -f 2246//2246 2344//2344 2244//2244 -f 2244//2244 2344//2344 2345//2345 -f 2244//2244 2345//2345 2335//2335 -f 2329//2329 2346//2346 2264//2264 -f 2264//2264 2346//2346 2347//2347 -f 2264//2264 2347//2347 2262//2262 -f 2262//2262 2347//2347 2348//2348 -f 2262//2262 2348//2348 2260//2260 -f 2260//2260 2348//2348 2349//2349 -f 2260//2260 2349//2349 2258//2258 -f 2258//2258 2349//2349 2350//2350 -f 2258//2258 2350//2350 2256//2256 -f 2256//2256 2350//2350 2351//2351 -f 2256//2256 2351//2351 2254//2254 -f 2254//2254 2351//2351 2352//2352 -f 2254//2254 2352//2352 2340//2340 -f 2353//2353 2354//2354 1911//1911 -f 1911//1911 2354//2354 2355//2355 -f 1911//1911 2355//2355 1904//1904 -f 1904//1904 2355//2355 2356//2356 -f 1904//1904 2356//2356 1900//1900 -f 1900//1900 2356//2356 2357//2357 -f 1900//1900 2357//2357 1890//1890 -f 1890//1890 2357//2357 2358//2358 -f 1890//1890 2358//2358 1889//1889 -f 1889//1889 2358//2358 2359//2359 -f 1889//1889 2359//2359 1888//1888 -f 1888//1888 2359//2359 2360//2360 -f 1888//1888 2360//2360 1886//1886 -f 1886//1886 2360//2360 2361//2361 -f 1886//1886 2361//2361 2013//2013 -f 2013//2013 2361//2361 2362//2362 -f 2013//2013 2362//2362 1879//1879 -f 1879//1879 2362//2362 2363//2363 -f 1879//1879 2363//2363 1880//1880 -f 1880//1880 2363//2363 2364//2364 -f 1880//1880 2364//2364 1882//1882 -f 1882//1882 2364//2364 2365//2365 -f 1882//1882 2365//2365 1883//1883 -f 1883//1883 2365//2365 2366//2366 -f 1883//1883 2366//2366 1885//1885 -f 1885//1885 2366//2366 2367//2367 -f 1885//1885 2367//2367 1922//1922 -f 1922//1922 2367//2367 2368//2368 -f 1922//1922 2368//2368 1916//1916 -f 1916//1916 2368//2368 2369//2369 -f 1916//1916 2369//2369 1917//1917 -f 1917//1917 2369//2369 2370//2370 -f 1917//1917 2370//2370 1918//1918 -f 1918//1918 2370//2370 2371//2371 -f 1918//1918 2371//2371 1919//1919 -f 1919//1919 2371//2371 2372//2372 -f 1919//1919 2372//2372 1920//1920 -f 1920//1920 2372//2372 2373//2373 -f 1920//1920 2373//2373 1914//1914 -f 1914//1914 2373//2373 2374//2374 -f 1914//1914 2374//2374 1907//1907 -f 1907//1907 2374//2374 2375//2375 -f 1907//1907 2375//2375 1908//1908 -f 1908//1908 2375//2375 2376//2376 -f 1908//1908 2376//2376 1910//1910 -f 1910//1910 2376//2376 2353//2353 -f 1910//1910 2353//2353 1911//1911 -f 2347//2347 2346//2346 2353//2353 -f 2353//2353 2346//2346 2354//2354 -f 2346//2346 2329//2329 2354//2354 -f 2354//2354 2329//2329 2334//2334 -f 2354//2354 2334//2334 2355//2355 -f 2355//2355 2334//2334 2333//2333 -f 2355//2355 2333//2333 2356//2356 -f 2356//2356 2333//2333 2332//2332 -f 2356//2356 2332//2332 2357//2357 -f 2357//2357 2332//2332 2331//2331 -f 2357//2357 2331//2331 2358//2358 -f 2358//2358 2331//2331 2330//2330 -f 2358//2358 2330//2330 2359//2359 -f 2359//2359 2330//2330 2339//2339 -f 2359//2359 2339//2339 2360//2360 -f 2360//2360 2339//2339 2338//2338 -f 2360//2360 2338//2338 2361//2361 -f 2361//2361 2338//2338 2337//2337 -f 2361//2361 2337//2337 2362//2362 -f 2362//2362 2337//2337 2336//2336 -f 2362//2362 2336//2336 2363//2363 -f 2363//2363 2336//2336 2335//2335 -f 2363//2363 2335//2335 2364//2364 -f 2364//2364 2335//2335 2345//2345 -f 2364//2364 2345//2345 2365//2365 -f 2365//2365 2345//2345 2344//2344 -f 2365//2365 2344//2344 2366//2366 -f 2366//2366 2344//2344 2343//2343 -f 2366//2366 2343//2343 2367//2367 -f 2367//2367 2343//2343 2342//2342 -f 2367//2367 2342//2342 2368//2368 -f 2368//2368 2342//2342 2341//2341 -f 2368//2368 2341//2341 2369//2369 -f 2369//2369 2341//2341 2340//2340 -f 2369//2369 2340//2340 2370//2370 -f 2370//2370 2340//2340 2352//2352 -f 2370//2370 2352//2352 2371//2371 -f 2371//2371 2352//2352 2351//2351 -f 2371//2371 2351//2351 2372//2372 -f 2372//2372 2351//2351 2350//2350 -f 2372//2372 2350//2350 2373//2373 -f 2373//2373 2350//2350 2349//2349 -f 2373//2373 2349//2349 2374//2374 -f 2374//2374 2349//2349 2348//2348 -f 2374//2374 2348//2348 2375//2375 -f 2375//2375 2348//2348 2347//2347 -f 2375//2375 2347//2347 2376//2376 -f 2376//2376 2347//2347 2353//2353 -# 4852 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower_white.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower_white.obj deleted file mode 100644 index d8a717b59..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_lower_white.obj +++ /dev/null @@ -1,22324 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mid_lower_belo.obj -# -# Vertices: 5577 -# Faces: 11154 -# -#### -vn 0.606857 0.058087 0.792686 -v 0.052523 0.090370 0.091918 -vn 0.677745 0.128041 0.724063 -v 0.052523 0.090224 0.091934 -vn 0.875242 0.063742 0.479467 -v 0.052540 0.090215 0.091868 -vn 0.616363 0.726591 -0.303583 -v 0.052523 0.086926 0.097482 -vn 0.700361 0.637682 -0.320712 -v 0.052523 0.087115 0.097897 -vn 0.875361 0.429015 -0.222911 -v 0.052540 0.087056 0.097928 -vn 0.613425 -0.088965 -0.784726 -v 0.052523 0.091129 0.100082 -vn 0.703264 -0.131849 -0.698596 -v 0.052523 0.091534 0.100024 -vn 0.875368 -0.092181 -0.474588 -v 0.052540 0.091547 0.100089 -vn 0.614358 -0.772146 0.162344 -v 0.052523 0.094779 0.095245 -vn 0.702588 -0.683944 0.196444 -v 0.052523 0.094679 0.094832 -vn 0.875359 -0.463613 0.137151 -v 0.052540 0.094743 0.094813 -vn -0.777958 0.493352 0.389082 -v 0.052773 0.087475 0.093390 -vn -0.778690 0.435200 0.451932 -v 0.052773 0.087836 0.092993 -vn -0.392478 0.640048 0.660530 -v 0.052718 0.087807 0.092963 -vn -0.955153 0.028798 0.294710 -v 0.052801 0.090221 0.091910 -vn -0.955149 0.005684 0.296072 -v 0.052801 0.090748 0.091876 -vn -0.777977 0.003396 0.628283 -v 0.052773 0.090748 0.091813 -vn -0.954069 0.050369 0.295323 -v 0.052801 0.090194 0.091913 -vn -0.778531 0.079249 0.622583 -v 0.052773 0.090213 0.091848 -vn -0.947764 0.100589 0.302698 -v 0.052801 0.089474 0.092078 -vn -0.954734 0.070789 0.288915 -v 0.052801 0.089702 0.092011 -vn -0.778191 0.156675 0.608170 -v 0.052773 0.089686 0.091950 -vn -0.947514 0.207942 0.242851 -v 0.052801 0.088177 0.092776 -vn -0.954861 0.172152 0.242082 -v 0.052801 0.088281 0.092695 -vn -0.777832 0.373645 0.505338 -v 0.052773 0.088244 0.092645 -vn -0.951946 0.299586 0.063625 -v 0.052801 0.086691 0.095265 -vn -0.955209 0.284521 0.081388 -v 0.052801 0.086795 0.094828 -vn -0.778034 0.602757 0.177053 -v 0.052773 0.086735 0.094810 -vn -0.955264 0.295265 0.017005 -v 0.052801 0.086627 0.095869 -vn -0.955218 0.293357 0.038744 -v 0.052801 0.086678 0.095343 -vn -0.777773 0.620982 0.097214 -v 0.052773 0.086616 0.095333 -vn -0.955155 0.280911 -0.093635 -v 0.052801 0.086879 0.097425 -vn -0.955117 0.287261 -0.072342 -v 0.052801 0.086728 0.096919 -vn -0.777971 0.611782 -0.143120 -v 0.052773 0.086668 0.096933 -vn -0.952052 0.236280 -0.194341 -v 0.052801 0.087644 0.098714 -vn -0.955004 0.241399 -0.172318 -v 0.052801 0.087367 0.098361 -vn -0.778055 0.514218 -0.360846 -v 0.052773 0.087316 0.098396 -vn -0.955040 0.197433 -0.221178 -v 0.052801 0.088077 0.099141 -vn -0.954976 0.214317 -0.205157 -v 0.052801 0.087697 0.098774 -vn -0.777770 0.463178 -0.424899 -v 0.052773 0.087651 0.098816 -vn -0.955050 0.101726 -0.278446 -v 0.052801 0.089451 0.099915 -vn -0.954883 0.123525 -0.270073 -v 0.052801 0.088961 0.099716 -vn -0.777958 0.269548 -0.567560 -v 0.052773 0.088934 0.099773 -vn -0.952005 -0.004500 -0.306050 -v 0.052801 0.090935 0.100120 -vn -0.954936 0.016288 -0.296363 -v 0.052801 0.090486 0.100116 -vn -0.778030 0.038486 -0.627048 -v 0.052773 0.090482 0.100178 -vn -0.954845 -0.050232 -0.292827 -v 0.052801 0.091539 0.100048 -vn -0.954946 -0.026839 -0.295564 -v 0.052801 0.091015 0.100116 -vn -0.777775 -0.043413 -0.627042 -v 0.052773 0.091019 0.100178 -vn -0.954942 -0.154654 -0.253315 -v 0.052801 0.093000 0.099456 -vn -0.954900 -0.134159 -0.264892 -v 0.052801 0.092540 0.099715 -vn -0.777968 -0.275669 -0.564599 -v 0.052773 0.092567 0.099772 -vn -0.951879 -0.242600 -0.187274 -v 0.052801 0.094086 0.098423 -vn -0.955018 -0.221317 -0.197381 -v 0.052801 0.093803 0.098772 -vn -0.778045 -0.466235 -0.421036 -v 0.052773 0.093849 0.098814 -vn -0.955005 -0.259548 -0.143532 -v 0.052801 0.094406 0.097907 -vn -0.955156 -0.247551 -0.162467 -v 0.052801 0.094132 0.098359 -vn -0.777763 -0.517320 -0.357022 -v 0.052773 0.094184 0.098394 -vn -0.955104 -0.293896 -0.037444 -v 0.052801 0.094855 0.096395 -vn -0.955198 -0.289927 -0.059495 -v 0.052801 0.094770 0.096917 -vn -0.777964 -0.613305 -0.136490 -v 0.052773 0.094831 0.096931 -vn -0.952001 -0.297389 0.072484 -v 0.052801 0.094725 0.094902 -vn -0.955243 -0.291515 0.050288 -v 0.052801 0.094820 0.095341 -vn -0.778044 -0.619873 0.102007 -v 0.052773 0.094882 0.095331 -vn -0.955169 -0.273589 0.113139 -v 0.052801 0.094520 0.094329 -vn -0.955050 -0.281722 0.092261 -v 0.052801 0.094703 0.094825 -vn -0.777758 -0.601681 0.181859 -v 0.052773 0.094763 0.094808 -vn -0.955146 -0.212472 0.206279 -v 0.052801 0.093618 0.093036 -vn -0.954943 -0.227941 0.190072 -v 0.052801 0.093973 0.093428 -vn -0.777962 -0.489105 0.394401 -v 0.052773 0.094022 0.093389 -vn -0.952153 -0.128172 0.277445 -v 0.052801 0.092369 0.092207 -vn -0.954887 -0.143027 0.260259 -v 0.052801 0.092772 0.092406 -vn -0.778033 -0.306737 0.548249 -v 0.052773 0.092803 0.092351 -vn -0.955325 -0.082414 0.283836 -v 0.052801 0.091794 0.092010 -vn -0.955270 -0.103625 0.276987 -v 0.052801 0.092296 0.092177 -vn -0.777778 -0.232951 0.583776 -v 0.052773 0.092319 0.092119 -vn -0.954545 -0.040432 0.295313 -v 0.052801 0.091275 0.091909 -vn -0.947325 -0.060935 0.314422 -v 0.052801 0.091666 0.091979 -vn -0.777847 -0.162120 0.607182 -v 0.052773 0.091810 0.091950 -vn -0.955610 -0.181140 0.232374 -v 0.052801 0.093215 0.092694 -vn -0.954118 -0.198937 0.223792 -v 0.052801 0.093598 0.093018 -vn -0.778545 -0.437333 0.450120 -v 0.052773 0.093661 0.092992 -vn -0.954786 -0.255400 0.152166 -v 0.052801 0.094275 0.093861 -vn -0.947268 -0.284020 0.148376 -v 0.052801 0.094465 0.094209 -vn -0.777853 -0.575789 0.251816 -v 0.052773 0.094577 0.094304 -vn -0.955180 -0.295996 0.004277 -v 0.052801 0.094871 0.095867 -vn -0.954118 -0.298981 -0.016420 -v 0.052801 0.094857 0.096369 -vn -0.778533 -0.624606 -0.061276 -v 0.052773 0.094917 0.096401 -vn -0.955406 -0.275790 -0.105548 -v 0.052801 0.094620 0.097423 -vn -0.947615 -0.292604 -0.128093 -v 0.052801 0.094466 0.097788 -vn -0.777845 -0.555885 -0.293170 -v 0.052773 0.094462 0.097936 -vn -0.954872 -0.188539 -0.229505 -v 0.052801 0.093424 0.099140 -vn -0.954150 -0.173597 -0.243850 -v 0.052801 0.093022 0.099441 -vn -0.778531 -0.341526 -0.526545 -v 0.052773 0.093034 0.099508 -vn -0.954642 -0.091251 -0.283431 -v 0.052801 0.092050 0.099914 -vn -0.947410 -0.081722 -0.309413 -v 0.052801 0.091668 0.100021 -vn -0.777846 -0.117380 -0.617396 -v 0.052773 0.091551 0.100109 -vn -0.954752 0.061394 -0.290997 -v 0.052801 0.089962 0.100048 -vn -0.953997 0.082987 -0.288103 -v 0.052801 0.089476 0.099923 -vn -0.778530 0.198724 -0.595315 -v 0.052773 0.089431 0.099974 -vn -0.954612 0.164314 -0.248427 -v 0.052801 0.088500 0.099457 -vn -0.947270 0.191540 -0.256888 -v 0.052801 0.088179 0.099225 -vn -0.777848 0.409511 -0.476710 -v 0.052773 0.088036 0.099189 -vn -0.955033 0.265120 -0.132753 -v 0.052801 0.087093 0.097909 -vn -0.954009 0.276925 -0.114798 -v 0.052801 0.086888 0.097450 -vn -0.778525 0.589346 -0.215801 -v 0.052773 0.086820 0.097447 -vn -0.955804 0.293003 -0.024250 -v 0.052801 0.086644 0.096397 -vn -0.947682 0.318999 -0.011798 -v 0.052801 0.086625 0.096001 -vn -0.777838 0.628046 0.022947 -v 0.052773 0.086564 0.095867 -vn -0.954975 0.269113 0.124905 -v 0.052801 0.086977 0.094332 -vn -0.954124 0.262247 0.144478 -v 0.052801 0.087208 0.093886 -vn -0.778520 0.536180 0.326219 -v 0.052773 0.087168 0.093831 -vn -0.954934 0.204179 0.215435 -v 0.052801 0.087879 0.093038 -vn -0.948411 0.235781 0.211955 -v 0.052801 0.087642 0.093287 -vn -0.955038 0.235593 0.179996 -v 0.052801 0.087524 0.093429 -vn -0.954960 0.249152 0.161169 -v 0.052801 0.087222 0.093863 -vn -0.777751 0.311190 0.546135 -v 0.052773 0.088694 0.092352 -vn -0.955044 0.152449 0.254263 -v 0.052801 0.088724 0.092407 -vn -0.952009 0.136833 0.273779 -v 0.052801 0.088794 0.092369 -vn -0.778046 0.237380 0.581632 -v 0.052773 0.089177 0.092120 -vn -0.955191 0.113171 0.273501 -v 0.052801 0.089200 0.092178 -vn -0.392471 -0.117364 0.912246 -v 0.052718 0.091289 0.091806 -vn -0.392513 0.000253 0.919746 -v 0.052718 0.090748 0.091771 -vn 0.086274 0.596102 0.798260 -v 0.052651 0.088213 0.092603 -vn -0.392490 0.550320 0.736953 -v 0.052718 0.088219 0.092612 -vn 0.544985 0.411641 0.730440 -v 0.052586 0.088679 0.092326 -vn 0.086304 0.489127 0.867932 -v 0.052651 0.088668 0.092307 -vn -0.392478 0.451568 0.801279 -v 0.052718 0.088673 0.092316 -vn 0.875362 0.180858 0.448366 -v 0.052540 0.089185 0.092138 -vn 0.544972 0.314860 0.777090 -v 0.052586 0.089166 0.092092 -vn 0.086313 0.374124 0.923353 -v 0.052651 0.089157 0.092071 -vn -0.392481 0.345396 0.852444 -v 0.052718 0.089161 0.092081 -vn 0.875219 -0.121026 0.468341 -v 0.052540 0.091805 0.091970 -vn 0.875210 -0.063697 0.479530 -v 0.052540 0.091281 0.091868 -vn 0.544943 -0.106992 0.831619 -v 0.052586 0.091287 0.091817 -vn -0.948566 -0.018217 0.316055 -v 0.052801 0.090933 0.091880 -vn -0.778672 -0.081989 0.622051 -v 0.052773 0.091283 0.091847 -vn -0.392493 -0.233053 0.889739 -v 0.052718 0.091821 0.091909 -vn 0.086309 -0.252436 0.963757 -v 0.052651 0.091823 0.091899 -vn 0.086296 -0.373608 0.923564 -v 0.052651 0.092339 0.092070 -vn 0.544960 -0.314429 0.777273 -v 0.052586 0.092331 0.092091 -vn 0.544952 -0.411249 0.730686 -v 0.052586 0.092817 0.092325 -vn 0.875332 -0.238750 0.420466 -v 0.052540 0.092793 0.092369 -vn 0.875583 -0.288322 0.387589 -v 0.052540 0.093240 0.092660 -vn -0.392489 -0.451118 0.801526 -v 0.052718 0.092823 0.092315 -vn -0.392473 -0.549911 0.737267 -v 0.052718 0.093277 0.092610 -vn 0.086311 -0.595656 0.798589 -v 0.052651 0.093284 0.092602 -vn 0.086329 -0.692888 0.715858 -v 0.052651 0.093698 0.092954 -vn 0.544967 -0.583130 0.602470 -v 0.052586 0.093682 0.092970 -vn 0.544966 -0.655389 0.522951 -v 0.052586 0.094045 0.093370 -vn 0.875365 -0.378712 0.300523 -v 0.052540 0.094006 0.093401 -vn 0.875374 -0.413939 0.249751 -v 0.052540 0.094311 0.093839 -vn -0.947578 -0.174713 0.267528 -v 0.052801 0.093020 0.092557 -vn -0.778191 -0.377803 0.501681 -v 0.052773 0.093252 0.092644 -vn -0.392506 -0.639671 0.660879 -v 0.052718 0.093690 0.092962 -vn 0.086309 -0.778740 0.621381 -v 0.052651 0.094063 0.093356 -vn 0.544967 -0.716879 0.434850 -v 0.052586 0.094355 0.093813 -vn 0.875296 -0.441375 0.197596 -v 0.052540 0.094559 0.094312 -vn 0.701612 -0.637119 0.319091 -v 0.052523 0.094498 0.094339 -vn 0.609961 -0.741604 0.279233 -v 0.052523 0.094572 0.094518 -vn -0.948394 -0.259167 0.182708 -v 0.052801 0.094085 0.093575 -vn -0.778677 -0.537455 0.323736 -v 0.052773 0.094329 0.093829 -vn -0.392497 -0.786387 0.477013 -v 0.052718 0.094365 0.093807 -vn -0.392481 -0.840937 0.372538 -v 0.052718 0.094615 0.094287 -vn 0.086338 -0.910886 0.403526 -v 0.052651 0.094625 0.094283 -vn 0.086296 -0.955012 0.283733 -v 0.052651 0.094813 0.094793 -vn 0.544964 -0.803737 0.238792 -v 0.052586 0.094791 0.094799 -vn 0.544969 -0.827671 0.134048 -v 0.052586 0.094912 0.095326 -vn 0.875182 -0.477873 0.075460 -v 0.052540 0.094862 0.095334 -vn 0.875230 -0.483395 0.017402 -v 0.052540 0.094913 0.095865 -vn -0.392521 -0.907913 0.147043 -v 0.052718 0.094923 0.095324 -vn -0.392498 -0.919272 0.029736 -v 0.052718 0.094975 0.095863 -vn 0.086311 -0.995748 0.032209 -v 0.052651 0.094986 0.095863 -vn 0.086282 -0.991693 -0.095397 -v 0.052651 0.094969 0.096406 -vn 0.544956 -0.834613 -0.080278 -v 0.052586 0.094947 0.096404 -vn 0.544945 -0.817502 -0.186349 -v 0.052586 0.094861 0.096937 -vn 0.875233 -0.471163 -0.109420 -v 0.052540 0.094811 0.096926 -vn 0.875252 -0.454453 -0.165549 -v 0.052540 0.094660 0.097438 -vn -0.392471 -0.896761 -0.204415 -v 0.052718 0.094872 0.096940 -vn -0.392479 -0.863255 -0.317413 -v 0.052718 0.094718 0.097459 -vn 0.086289 -0.935063 -0.343819 -v 0.052651 0.094728 0.097463 -vn 0.086288 -0.883420 -0.460568 -v 0.052651 0.094508 0.097960 -vn 0.544937 -0.743500 -0.387622 -v 0.052586 0.094488 0.097949 -vn 0.544959 -0.687818 -0.479506 -v 0.052586 0.094208 0.098412 -vn 0.875361 -0.395590 -0.277942 -v 0.052540 0.094167 0.098383 -vn 0.875841 -0.357493 -0.324193 -v 0.052540 0.093834 0.098800 -vn -0.392490 -0.754506 -0.525997 -v 0.052718 0.094218 0.098418 -vn -0.392499 -0.681045 -0.618161 -v 0.052718 0.093880 0.098842 -vn 0.086301 -0.737703 -0.669587 -v 0.052651 0.093888 0.098849 -vn 0.086280 -0.646018 -0.758430 -v 0.052651 0.093498 0.099227 -vn 0.544956 -0.543694 -0.638295 -v 0.052586 0.093484 0.099210 -vn 0.544945 -0.457609 -0.702587 -v 0.052586 0.093051 0.099534 -vn 0.875365 -0.262917 -0.405722 -v 0.052540 0.093023 0.099491 -vn 0.875271 -0.208657 -0.436306 -v 0.052540 0.092558 0.099753 -vn -0.392503 -0.596405 -0.700174 -v 0.052718 0.093491 0.099219 -vn 0.086331 -0.543732 -0.834807 -v 0.052651 0.093063 0.099552 -vn 0.544956 -0.364006 -0.755330 -v 0.052586 0.092580 0.099799 -vn 0.875269 -0.154357 -0.458344 -v 0.052540 0.092063 0.099954 -vn 0.693503 -0.259167 -0.672225 -v 0.052523 0.092042 0.099891 -vn 0.610466 -0.207872 -0.764278 -v 0.052523 0.091872 0.099943 -vn -0.392499 -0.399293 -0.828559 -v 0.052718 0.092585 0.099809 -vn -0.392504 -0.290064 -0.872813 -v 0.052718 0.092083 0.100013 -vn 0.086284 -0.314193 -0.945430 -v 0.052651 0.092086 0.100023 -vn 0.086301 -0.190719 -0.977844 -v 0.052651 0.091561 0.100161 -vn 0.544973 -0.160509 -0.822947 -v 0.052586 0.091556 0.100139 -vn 0.544940 -0.053952 -0.836738 -v 0.052586 0.091021 0.100208 -vn 0.875185 -0.029174 -0.482908 -v 0.052540 0.091017 0.100158 -vn 0.875208 0.029127 -0.482870 -v 0.052540 0.090483 0.100158 -vn -0.392504 -0.059183 -0.917844 -v 0.052718 0.091021 0.100220 -vn -0.392505 0.058671 -0.917877 -v 0.052718 0.090479 0.100220 -vn 0.086278 0.063554 -0.994242 -v 0.052651 0.090479 0.100231 -vn 0.086254 0.190174 -0.977954 -v 0.052651 0.089940 0.100162 -vn 0.544968 0.160054 -0.823039 -v 0.052586 0.089944 0.100139 -vn 0.544990 0.263979 -0.795802 -v 0.052586 0.089421 0.100002 -vn 0.875261 0.154108 -0.458442 -v 0.052540 0.089437 0.099955 -vn 0.875301 0.208563 -0.436290 -v 0.052540 0.088942 0.099754 -vn -0.947666 0.041073 -0.316609 -v 0.052801 0.090197 0.100087 -vn -0.778180 0.122719 -0.615935 -v 0.052773 0.089950 0.100110 -vn -0.392523 0.289578 -0.872966 -v 0.052718 0.089418 0.100013 -vn -0.392462 0.398841 -0.828794 -v 0.052718 0.088916 0.099810 -vn 0.086307 0.432016 -0.897727 -v 0.052651 0.088911 0.099820 -vn 0.086305 0.543267 -0.835112 -v 0.052651 0.088437 0.099554 -vn 0.544942 0.457221 -0.702842 -v 0.052586 0.088450 0.099535 -vn 0.544970 0.543331 -0.638592 -v 0.052586 0.088016 0.099212 -vn 0.875372 0.314540 -0.367135 -v 0.052540 0.088049 0.099173 -vn 0.875834 0.357352 -0.324366 -v 0.052540 0.087666 0.098802 -vn -0.392497 0.501543 -0.770974 -v 0.052718 0.088443 0.099545 -vn 0.086319 0.645597 -0.758785 -v 0.052651 0.088002 0.099229 -vn 0.544940 0.620551 -0.563877 -v 0.052586 0.087628 0.098836 -vn 0.875362 0.395434 -0.278162 -v 0.052540 0.087333 0.098385 -vn 0.689794 0.581136 -0.431815 -v 0.052523 0.087387 0.098347 -vn 0.609224 0.676370 -0.413970 -v 0.052523 0.087264 0.098159 -vn -0.392483 0.680704 -0.618545 -v 0.052718 0.087620 0.098844 -vn -0.392511 0.754207 -0.526410 -v 0.052718 0.087282 0.098420 -vn 0.086319 0.816951 -0.570211 -v 0.052651 0.087273 0.098426 -vn 0.086310 0.883163 -0.461057 -v 0.052651 0.086991 0.097962 -vn 0.544965 0.743270 -0.388024 -v 0.052586 0.087011 0.097952 -vn 0.544966 0.786786 -0.289793 -v 0.052586 0.086792 0.097457 -vn 0.875202 0.454516 -0.165640 -v 0.052540 0.086839 0.097440 -vn 0.875250 0.471120 -0.109470 -v 0.052540 0.086687 0.096928 -vn -0.947547 0.273606 -0.165208 -v 0.052801 0.087209 0.098116 -vn -0.778176 0.558074 -0.288090 -v 0.052773 0.087038 0.097938 -vn -0.392482 0.863077 -0.317894 -v 0.052718 0.086781 0.097461 -vn -0.392494 0.896637 -0.204915 -v 0.052718 0.086627 0.096942 -vn 0.086333 0.971226 -0.221960 -v 0.052651 0.086616 0.096945 -vn 0.086334 0.991636 -0.095941 -v 0.052651 0.086529 0.096408 -vn 0.544958 0.834567 -0.080743 -v 0.052586 0.086552 0.096406 -vn 0.544962 0.838037 0.026642 -v 0.052586 0.086534 0.095866 -vn 0.875201 0.483449 0.017356 -v 0.052540 0.086585 0.095868 -vn 0.875219 0.477815 0.075401 -v 0.052540 0.086636 0.095336 -vn -0.948386 0.312799 -0.052154 -v 0.052801 0.086691 0.096738 -vn -0.778683 0.624686 -0.058482 -v 0.052773 0.086582 0.096403 -vn -0.392457 0.919306 0.029223 -v 0.052718 0.086523 0.095866 -vn -0.392479 0.908012 0.146545 -v 0.052718 0.086575 0.095326 -vn 0.086319 0.983542 0.158729 -v 0.052651 0.086564 0.095325 -vn 0.086282 0.955171 0.283202 -v 0.052651 0.086685 0.094795 -vn 0.544947 0.803882 0.238343 -v 0.052586 0.086706 0.094801 -vn 0.544994 0.766777 0.339168 -v 0.052586 0.086893 0.094294 -vn 0.875301 0.441478 0.197344 -v 0.052540 0.086939 0.094315 -vn 0.875408 0.413939 0.249631 -v 0.052540 0.087186 0.093841 -vn -0.947567 0.299791 0.110646 -v 0.052801 0.086887 0.094552 -vn -0.778195 0.573168 0.256694 -v 0.052773 0.086920 0.094306 -vn -0.392512 0.841132 0.372063 -v 0.052718 0.086882 0.094289 -vn -0.392480 0.786659 0.476579 -v 0.052718 0.087133 0.093809 -vn 0.086287 0.852095 0.516226 -v 0.052651 0.087123 0.093803 -vn 0.086277 0.779088 0.620949 -v 0.052651 0.087434 0.093358 -vn 0.544937 0.655693 0.522601 -v 0.052586 0.087451 0.093372 -vn 0.544966 0.583471 0.602141 -v 0.052586 0.087815 0.092972 -vn 0.875371 0.335363 0.348220 -v 0.052540 0.087850 0.093008 -vn 0.875553 0.288473 0.387544 -v 0.052540 0.088256 0.092662 -vn -0.392480 0.719257 0.573261 -v 0.052718 0.087442 0.093364 -vn 0.086328 0.693287 0.715473 -v 0.052651 0.087799 0.092955 -vn 0.544955 0.501679 0.671820 -v 0.052586 0.088226 0.092621 -vn 0.875328 0.238988 0.420339 -v 0.052540 0.088704 0.092370 -vn 0.709792 0.374528 0.596593 -v 0.052523 0.088736 0.092428 -vn 0.609532 0.348150 0.712223 -v 0.052523 0.088921 0.092330 -vn 0.086321 0.000272 0.996267 -v 0.052651 0.090748 0.091761 -vn 0.544968 0.000235 0.838457 -v 0.052586 0.090748 0.091783 -vn 0.875690 0.001069 0.482873 -v 0.052540 0.090748 0.091834 -vn 0.611785 -0.060057 0.788741 -v 0.052523 0.091126 0.091917 -vn 0.703360 0.001455 0.710833 -v 0.052523 0.090748 0.091900 -vn 0.609537 -0.347742 0.712419 -v 0.052523 0.092576 0.092329 -vn 0.701329 -0.258612 0.664272 -v 0.052523 0.092287 0.092199 -vn 0.875566 -0.179960 0.448329 -v 0.052540 0.092312 0.092138 -vn 0.544956 -0.212452 0.811102 -v 0.052586 0.091818 0.091921 -vn 0.086311 -0.127130 0.988124 -v 0.052651 0.091290 0.091795 -vn 0.613791 -0.235324 0.753581 -v 0.052523 0.091870 0.092056 -vn 0.648761 -0.160500 0.743874 -v 0.052523 0.091788 0.092034 -vn 0.672002 -0.124976 0.729927 -v 0.052523 0.091272 0.091934 -vn 0.608904 -0.586646 0.533931 -v 0.052523 0.093778 0.093237 -vn 0.694817 -0.487471 0.528773 -v 0.052523 0.093601 0.093054 -vn 0.875424 -0.334993 0.348443 -v 0.052540 0.093647 0.093006 -vn 0.544958 -0.501305 0.672096 -v 0.052586 0.093270 0.092620 -vn 0.086257 -0.488652 0.868204 -v 0.052651 0.092829 0.092305 -vn -0.392493 -0.344919 0.852632 -v 0.052718 0.092335 0.092080 -vn 0.619232 -0.492123 0.611855 -v 0.052523 0.093219 0.092727 -vn 0.626137 -0.443295 0.641437 -v 0.052523 0.093200 0.092714 -vn 0.686887 -0.376678 0.621531 -v 0.052523 0.092760 0.092427 -vn 0.635862 -0.678400 0.368040 -v 0.052523 0.094255 0.093874 -vn 0.618446 -0.655720 0.433077 -v 0.052523 0.094234 0.093841 -vn 0.697015 -0.569799 0.435315 -v 0.052523 0.093954 0.093443 -vn -0.392494 -0.718935 0.573656 -v 0.052718 0.094054 0.093363 -vn 0.086287 -0.851811 0.516694 -v 0.052651 0.094374 0.093801 -vn 0.544954 -0.766610 0.339608 -v 0.052586 0.094605 0.094292 -vn 0.611078 -0.780096 -0.134289 -v 0.052523 0.094780 0.096752 -vn 0.703229 -0.708005 -0.064800 -v 0.052523 0.094830 0.096393 -vn 0.875676 -0.480779 -0.045210 -v 0.052540 0.094896 0.096399 -vn 0.544968 -0.838018 0.027104 -v 0.052586 0.094964 0.095864 -vn 0.086265 -0.983457 0.159280 -v 0.052651 0.094934 0.095322 -vn -0.392507 -0.881661 0.261940 -v 0.052718 0.094803 0.094796 -vn 0.608683 -0.793240 -0.016567 -v 0.052523 0.094849 0.095999 -vn 0.670121 -0.739972 0.058138 -v 0.052523 0.094847 0.095867 -vn 0.657666 -0.748458 0.085365 -v 0.052523 0.094796 0.095345 -vn 0.609223 -0.676598 -0.413598 -v 0.052523 0.094236 0.098157 -vn 0.700124 -0.638334 -0.319932 -v 0.052523 0.094385 0.097895 -vn 0.875521 -0.429089 -0.222140 -v 0.052540 0.094444 0.097926 -vn 0.544962 -0.786951 -0.289353 -v 0.052586 0.094707 0.097455 -vn 0.086321 -0.971350 -0.221420 -v 0.052651 0.094883 0.096942 -vn -0.392494 -0.915529 -0.088062 -v 0.052718 0.094958 0.096405 -vn -0.778205 -0.627769 0.017413 -v 0.052773 0.094934 0.095865 -vn -0.947587 -0.318063 0.030231 -v 0.052801 0.094857 0.095629 -vn 0.615330 -0.727118 -0.304415 -v 0.052523 0.094573 0.097480 -vn 0.642303 -0.729921 -0.233800 -v 0.052523 0.094597 0.097415 -vn 0.676185 -0.711292 -0.191932 -v 0.052523 0.094747 0.096911 -vn 0.609014 -0.476085 -0.634386 -v 0.052523 0.093221 0.099271 -vn 0.692456 -0.482500 -0.536375 -v 0.052523 0.093408 0.099121 -vn 0.875384 -0.314768 -0.366911 -v 0.052540 0.093451 0.099172 -vn 0.544958 -0.620854 -0.563525 -v 0.052586 0.093872 0.098834 -vn 0.086290 -0.817272 -0.569755 -v 0.052651 0.094227 0.098424 -vn -0.392486 -0.815574 -0.425198 -v 0.052718 0.094499 0.097955 -vn -0.778672 -0.588209 -0.218357 -v 0.052773 0.094679 0.097445 -vn -0.948344 -0.304626 -0.088579 -v 0.052801 0.094725 0.097096 -vn 0.620250 -0.562860 -0.546332 -v 0.052523 0.093780 0.098761 -vn 0.622185 -0.597075 -0.506347 -v 0.052523 0.093785 0.098756 -vn 0.689793 -0.581377 -0.431494 -v 0.052523 0.094113 0.098345 -vn 0.641364 -0.298937 -0.706604 -v 0.052523 0.092529 0.099693 -vn 0.617409 -0.370091 -0.694146 -v 0.052523 0.092578 0.099670 -vn 0.698819 -0.379456 -0.606354 -v 0.052523 0.092987 0.099436 -vn -0.947607 -0.221939 -0.229748 -v 0.052801 0.093600 0.098980 -vn -0.778176 -0.405047 -0.479978 -v 0.052773 0.093464 0.099187 -vn -0.392456 -0.501984 -0.770708 -v 0.052718 0.093057 0.099543 -vn 0.086286 -0.432514 -0.897489 -v 0.052651 0.092590 0.099819 -vn 0.544973 -0.264425 -0.795666 -v 0.052586 0.092079 0.100002 -vn 0.610466 0.207439 -0.764395 -v 0.052523 0.089628 0.099944 -vn 0.702900 0.130555 -0.699205 -v 0.052523 0.089967 0.100025 -vn 0.875634 0.091092 -0.474307 -v 0.052540 0.089954 0.100090 -vn 0.544970 0.053483 -0.836748 -v 0.052586 0.090480 0.100208 -vn 0.086285 -0.064113 -0.994205 -v 0.052651 0.091022 0.100231 -vn -0.392507 -0.176067 -0.902740 -v 0.052718 0.091559 0.100150 -vn -0.778677 -0.196022 -0.596019 -v 0.052773 0.092070 0.099973 -vn -0.948408 -0.120472 -0.293273 -v 0.052801 0.092371 0.099792 -vn 0.610471 0.090788 -0.786818 -v 0.052523 0.090372 0.100083 -vn 0.662764 0.013765 -0.748702 -v 0.052523 0.090488 0.100092 -vn 0.662741 -0.014175 -0.748714 -v 0.052523 0.091013 0.100091 -vn 0.609019 0.475735 -0.634644 -v 0.052523 0.088279 0.099273 -vn 0.698653 0.378819 -0.606944 -v 0.052523 0.088513 0.099437 -vn 0.875479 0.262289 -0.405883 -v 0.052540 0.088477 0.099492 -vn 0.544947 0.363591 -0.755536 -v 0.052586 0.088921 0.099800 -vn 0.086329 0.313668 -0.945600 -v 0.052651 0.089414 0.100024 -vn -0.392514 0.175568 -0.902834 -v 0.052718 0.089942 0.100151 -vn 0.616772 0.370591 -0.694445 -v 0.052523 0.088923 0.099671 -vn 0.636293 0.305953 -0.708183 -v 0.052523 0.088971 0.099694 -vn 0.680064 0.256494 -0.686822 -v 0.052523 0.089458 0.099891 -vn 0.622203 0.596746 -0.506713 -v 0.052523 0.087715 0.098757 -vn 0.620269 0.562556 -0.546624 -v 0.052523 0.087720 0.098763 -vn 0.692492 0.482124 -0.536666 -v 0.052523 0.088092 0.099123 -vn -0.948470 0.153955 -0.276952 -v 0.052801 0.088796 0.099632 -vn -0.778689 0.343760 -0.524855 -v 0.052773 0.088466 0.099510 -vn -0.392482 0.596021 -0.700512 -v 0.052718 0.088009 0.099221 -vn 0.086301 0.737329 -0.669999 -v 0.052651 0.087612 0.098851 -vn 0.544975 0.687543 -0.479882 -v 0.052586 0.087291 0.098414 -vn 0.612556 0.790293 -0.014597 -v 0.052523 0.086649 0.096001 -vn 0.703142 0.707818 -0.067711 -v 0.052523 0.086668 0.096395 -vn 0.875717 0.480499 -0.047329 -v 0.052540 0.086602 0.096401 -vn 0.544946 0.817398 -0.186802 -v 0.052586 0.086638 0.096939 -vn 0.086323 0.934870 -0.344336 -v 0.052651 0.086771 0.097465 -vn -0.392478 0.815340 -0.425654 -v 0.052718 0.087001 0.097957 -vn 0.604936 0.785172 -0.132501 -v 0.052523 0.086719 0.096754 -vn 0.685567 0.701334 -0.195268 -v 0.052523 0.086752 0.096913 -vn 0.646944 0.727546 -0.228343 -v 0.052523 0.086902 0.097417 -vn 0.609952 0.741766 0.278822 -v 0.052523 0.086926 0.094520 -vn 0.702264 0.684599 0.195319 -v 0.052523 0.086818 0.094835 -vn 0.875578 0.463490 0.136161 -v 0.052540 0.086755 0.094816 -vn 0.544969 0.827746 0.133586 -v 0.052586 0.086586 0.095328 -vn 0.086311 0.995765 0.031657 -v 0.052651 0.086512 0.095865 -vn -0.392471 0.915490 -0.088575 -v 0.052718 0.086540 0.096407 -vn 0.612161 0.773559 0.163905 -v 0.052523 0.086719 0.095248 -vn 0.655589 0.750101 0.086897 -v 0.052523 0.086702 0.095347 -vn 0.667507 0.742486 0.056115 -v 0.052523 0.086651 0.095870 -vn 0.608912 0.586939 0.533600 -v 0.052523 0.087718 0.093239 -vn 0.696881 0.570347 0.434812 -v 0.052523 0.087543 0.093445 -vn 0.875453 0.378909 0.300017 -v 0.052540 0.087491 0.093403 -vn 0.544937 0.717139 0.434460 -v 0.052586 0.087142 0.093815 -vn 0.086314 0.911113 0.403017 -v 0.052651 0.086872 0.094285 -vn -0.392499 0.881811 0.261447 -v 0.052718 0.086695 0.094798 -vn 0.618100 0.655910 0.433285 -v 0.052523 0.087263 0.093843 -vn 0.630841 0.678678 0.376079 -v 0.052523 0.087242 0.093876 -vn 0.683605 0.656819 0.318233 -v 0.052523 0.087000 0.094341 -vn 0.630742 0.434887 0.642681 -v 0.052523 0.088296 0.092715 -vn 0.619396 0.492148 0.611669 -v 0.052523 0.088277 0.092729 -vn 0.694890 0.487867 0.528312 -v 0.052523 0.087896 0.093056 -vn 0.701609 0.259555 0.663609 -v 0.052523 0.089209 0.092200 -vn 0.875184 0.121092 0.468390 -v 0.052540 0.089691 0.091970 -vn 0.652394 0.156943 0.741452 -v 0.052523 0.089708 0.092034 -vn 0.615332 0.234114 0.752700 -v 0.052523 0.089626 0.092057 -vn -0.392498 0.233548 0.889607 -v 0.052718 0.089675 0.091910 -vn 0.086322 0.252979 0.963613 -v 0.052651 0.089673 0.091899 -vn 0.544978 0.212905 0.810969 -v 0.052586 0.089678 0.091921 -vn -0.392491 0.117871 0.912172 -v 0.052718 0.090207 0.091806 -vn 0.086312 0.127676 0.988053 -v 0.052651 0.090206 0.091795 -vn 0.544962 0.107452 0.831547 -v 0.052586 0.090209 0.091818 -vn -0.715388 0.698711 -0.004815 -v 0.052453 0.086649 0.096001 -vn -0.715801 0.685539 0.132908 -v 0.052453 0.086719 0.095248 -vn -0.714980 0.653082 0.249574 -v 0.052453 0.086926 0.094520 -vn -0.717942 0.590200 0.369084 -v 0.052453 0.087263 0.093843 -vn -0.714875 0.517122 0.470679 -v 0.052453 0.087718 0.093239 -vn -0.720746 0.415098 0.555175 -v 0.052453 0.088277 0.092729 -vn -0.715062 0.310661 0.626240 -v 0.052453 0.088921 0.092330 -vn -0.716255 0.194948 0.670055 -v 0.052453 0.089626 0.092057 -vn -0.715309 0.060867 0.696152 -v 0.052453 0.090370 0.091918 -vn -0.715236 -0.059917 0.696310 -v 0.052453 0.091126 0.091917 -vn -0.716097 -0.195534 0.670053 -v 0.052453 0.091870 0.092056 -vn -0.714933 -0.309332 0.627044 -v 0.052453 0.092576 0.092329 -vn -0.719149 -0.420280 0.553344 -v 0.052453 0.093219 0.092727 -vn -0.714874 -0.516859 0.470970 -v 0.052453 0.093778 0.093237 -vn -0.718899 -0.591241 0.365539 -v 0.052453 0.094234 0.093841 -vn -0.715098 -0.652454 0.250876 -v 0.052453 0.094572 0.094518 -vn -0.715872 -0.685474 0.132866 -v 0.052453 0.094779 0.095245 -vn -0.715433 -0.698669 -0.004105 -v 0.052453 0.094849 0.095999 -vn -0.715127 -0.687858 -0.124278 -v 0.052453 0.094780 0.096752 -vn -0.716505 -0.648842 -0.256172 -v 0.052453 0.094573 0.097480 -vn -0.714908 -0.595500 -0.366450 -v 0.052453 0.094236 0.098157 -vn -0.720867 -0.511848 -0.467293 -v 0.052453 0.093780 0.098761 -vn -0.714889 -0.420696 -0.558524 -v 0.052453 0.093221 0.099271 -vn -0.717648 -0.311944 -0.622634 -v 0.052453 0.092578 0.099670 -vn -0.715154 -0.188935 -0.672947 -v 0.052453 0.091872 0.099943 -vn -0.715589 -0.069286 -0.695077 -v 0.052453 0.091129 0.100082 -vn -0.715583 0.068905 -0.695121 -v 0.052453 0.090372 0.100083 -vn -0.715040 0.187694 -0.673416 -v 0.052453 0.089628 0.099944 -vn -0.717092 0.314218 -0.622131 -v 0.052453 0.088923 0.099671 -vn -0.714883 0.420392 -0.558760 -v 0.052453 0.088279 0.099273 -vn -0.720864 0.511587 -0.467584 -v 0.052453 0.087720 0.098763 -vn -0.714910 0.595298 -0.366776 -v 0.052453 0.087264 0.098159 -vn -0.716812 0.649018 -0.254868 -v 0.052453 0.086926 0.097482 -vn -0.715219 0.687558 -0.125403 -v 0.052453 0.086719 0.096754 -vn -0.990996 0.011019 -0.133436 -v 0.052453 0.091148 0.091166 -vn -0.990996 -0.000038 -0.133891 -v 0.052453 0.090748 0.091150 -vn -0.990996 0.132074 0.022002 -v 0.052453 0.095533 0.096797 -vn -0.990998 0.133423 0.011017 -v 0.052453 0.095583 0.096399 -vn -0.990996 0.129800 0.032832 -v 0.052453 0.095451 0.097189 -vn -0.990997 0.126643 0.043436 -v 0.052453 0.095337 0.097574 -vn -0.990996 0.133892 -0.000036 -v 0.052453 0.095599 0.095999 -vn -0.990995 0.133436 -0.011094 -v 0.052453 0.095582 0.095598 -vn -0.990996 0.122631 0.053751 -v 0.052453 0.095191 0.097947 -vn -0.990996 0.117770 0.063692 -v 0.052453 0.095015 0.098307 -vn -0.990997 0.112063 -0.073259 -v 0.052453 0.094809 0.093346 -vn -0.990998 0.105627 -0.082260 -v 0.052453 0.094576 0.093020 -vn -0.990997 0.082265 0.105633 -v 0.052453 0.093729 0.099826 -vn -0.990995 0.090712 0.098485 -v 0.052453 0.094035 0.099567 -vn -0.990997 -0.132049 0.022074 -v 0.052453 0.085966 0.096800 -vn -0.990997 -0.129776 0.032902 -v 0.052453 0.086048 0.097192 -vn -0.990996 0.022003 -0.132074 -v 0.052453 0.091546 0.091216 -vn -0.990996 0.032832 -0.129800 -v 0.052453 0.091938 0.091298 -vn -0.990997 0.098527 0.090649 -v 0.052453 0.094318 0.099284 -vn -0.990996 0.105680 0.082207 -v 0.052453 0.094577 0.098978 -vn -0.990998 0.112100 0.073193 -v 0.052453 0.094810 0.098652 -vn -0.990995 -0.133435 0.011093 -v 0.052453 0.085916 0.096402 -vn -0.990996 -0.133891 0.000038 -v 0.052453 0.085899 0.096001 -vn -0.990997 0.043436 -0.126643 -v 0.052453 0.092323 0.091412 -vn -0.990997 0.053746 -0.122621 -v 0.052453 0.092696 0.091558 -vn -0.990996 0.073200 -0.112109 -v 0.052453 0.093401 0.091939 -vn -0.990996 0.063691 -0.117769 -v 0.052453 0.093056 0.091734 -vn -0.990997 0.098479 -0.090706 -v 0.052453 0.094316 0.092714 -vn -0.990997 0.090650 -0.098527 -v 0.052453 0.094033 0.092431 -vn -0.990998 0.082200 -0.105673 -v 0.052453 0.093727 0.092172 -vn -0.990996 0.132063 -0.022075 -v 0.052453 0.095533 0.095200 -vn -0.990997 0.129776 -0.032903 -v 0.052453 0.095450 0.094808 -vn -0.990997 0.073260 0.112063 -v 0.052453 0.093403 0.100060 -vn -0.990997 0.063756 0.117732 -v 0.052453 0.093059 0.100265 -vn -0.990998 -0.011018 0.133423 -v 0.052453 0.090350 0.100834 -vn -0.990996 0.000036 0.133892 -v 0.052453 0.090751 0.100850 -vn -0.990997 -0.021999 0.132061 -v 0.052453 0.089952 0.100784 -vn -0.990996 -0.032832 0.129800 -v 0.052453 0.089560 0.100702 -vn -0.990996 -0.133435 -0.011019 -v 0.052453 0.085916 0.095601 -vn -0.990996 -0.132073 -0.022003 -v 0.052453 0.085965 0.095203 -vn -0.990996 -0.129800 -0.032832 -v 0.052453 0.086047 0.094811 -vn -0.990997 -0.126643 -0.043436 -v 0.052453 0.086162 0.094426 -vn -0.990997 -0.082265 -0.105633 -v 0.052453 0.087769 0.092173 -vn -0.990997 -0.090706 -0.098478 -v 0.052453 0.087463 0.092433 -vn -0.990996 -0.073264 -0.112072 -v 0.052453 0.088095 0.091940 -vn -0.990996 -0.063758 -0.117738 -v 0.052453 0.088440 0.091735 -vn -0.990997 0.126617 -0.043506 -v 0.052453 0.095336 0.094424 -vn -0.990997 0.122590 -0.053813 -v 0.052453 0.095190 0.094051 -vn -0.990997 0.117727 -0.063753 -v 0.052453 0.095014 0.093690 -vn -0.990997 0.053814 0.122590 -v 0.052453 0.092699 0.100441 -vn -0.990997 0.043508 0.126621 -v 0.052453 0.092325 0.100587 -vn -0.990995 0.011094 0.133436 -v 0.052453 0.091151 0.100833 -vn -0.990996 0.022074 0.132061 -v 0.052453 0.091549 0.100784 -vn -0.990997 0.032903 0.129776 -v 0.052453 0.091941 0.100701 -vn -0.990997 -0.073198 0.112106 -v 0.052453 0.088098 0.100061 -vn -0.990997 -0.122621 -0.053745 -v 0.052453 0.086307 0.094053 -vn -0.990996 -0.117774 -0.063694 -v 0.052453 0.086483 0.093693 -vn -0.990997 -0.098528 -0.090649 -v 0.052453 0.087180 0.092716 -vn -0.990995 -0.105686 -0.082212 -v 0.052453 0.086921 0.093022 -vn -0.990995 -0.112115 -0.073204 -v 0.052453 0.086688 0.093348 -vn -0.990998 -0.053814 -0.122588 -v 0.052453 0.088800 0.091559 -vn -0.990997 -0.043508 -0.126617 -v 0.052453 0.089173 0.091413 -vn -0.990995 -0.011093 -0.133435 -v 0.052453 0.090347 0.091167 -vn -0.990997 -0.022074 -0.132051 -v 0.052453 0.089950 0.091216 -vn -0.990996 -0.032904 -0.129788 -v 0.052453 0.089557 0.091299 -vn -0.990995 -0.063695 0.117775 -v 0.052453 0.088442 0.100266 -vn -0.990996 -0.053751 0.122631 -v 0.052453 0.088802 0.100442 -vn -0.990997 -0.043436 0.126643 -v 0.052453 0.089176 0.100588 -vn -0.990996 -0.112072 0.073264 -v 0.052453 0.086690 0.098654 -vn -0.990996 -0.105633 0.082266 -v 0.052453 0.086923 0.098980 -vn -0.990996 -0.098484 0.090712 -v 0.052453 0.087182 0.099286 -vn -0.990997 -0.090649 0.098527 -v 0.052453 0.087465 0.099569 -vn -0.990995 -0.082213 0.105686 -v 0.052453 0.087771 0.099828 -vn -0.990996 -0.126622 0.043508 -v 0.052453 0.086162 0.097576 -vn -0.990997 -0.122589 0.053815 -v 0.052453 0.086308 0.097949 -vn -0.990995 -0.117743 0.063760 -v 0.052453 0.086484 0.098310 -vn -0.863076 -0.041846 -0.503338 -v 0.052473 0.090341 0.091092 -vn -0.863072 -0.083271 -0.498170 -v 0.052473 0.089937 0.091142 -vn -0.863071 -0.124126 -0.489593 -v 0.052473 0.089539 0.091226 -vn -0.863069 -0.164135 -0.477672 -v 0.052473 0.089149 0.091342 -vn -0.863069 -0.203020 -0.462487 -v 0.052473 0.088770 0.091490 -vn -0.863073 -0.240516 -0.444137 -v 0.052473 0.088404 0.091669 -vn -0.863069 -0.276372 -0.422765 -v 0.052473 0.088054 0.091878 -vn -0.863077 -0.310333 -0.398488 -v 0.052473 0.087723 0.092114 -vn -0.863079 -0.342178 -0.371495 -v 0.052473 0.087413 0.092377 -vn -0.863072 -0.371696 -0.341980 -v 0.052473 0.087125 0.092665 -vn -0.863083 -0.398653 -0.310103 -v 0.052473 0.086862 0.092976 -vn -0.863082 -0.422899 -0.276126 -v 0.052473 0.086625 0.093307 -vn -0.863077 -0.444264 -0.240266 -v 0.052473 0.086417 0.093657 -vn -0.863077 -0.462588 -0.202755 -v 0.052473 0.086238 0.094023 -vn -0.863070 -0.477764 -0.163865 -v 0.052473 0.086091 0.094402 -vn -0.863074 -0.489658 -0.123853 -v 0.052473 0.085975 0.094792 -vn -0.863074 -0.498212 -0.082997 -v 0.052473 0.085891 0.095191 -vn -0.863071 -0.503369 -0.041569 -v 0.052473 0.085841 0.095595 -vn -0.863072 -0.505080 0.000142 -v 0.052473 0.085824 0.096001 -vn -0.863076 -0.503338 0.041846 -v 0.052473 0.085841 0.096408 -vn -0.863073 -0.498168 0.083271 -v 0.052473 0.085892 0.096812 -vn -0.863077 -0.489583 0.124125 -v 0.052473 0.085975 0.097210 -vn -0.863074 -0.477666 0.164131 -v 0.052473 0.086091 0.097600 -vn -0.863069 -0.462488 0.203020 -v 0.052473 0.086240 0.097980 -vn -0.863079 -0.444128 0.240511 -v 0.052473 0.086418 0.098345 -vn -0.863069 -0.422766 0.276371 -v 0.052473 0.086627 0.098695 -vn -0.863077 -0.398487 0.310333 -v 0.052473 0.086863 0.099026 -vn -0.863087 -0.371483 0.342171 -v 0.052473 0.087127 0.099337 -vn -0.863072 -0.341981 0.371693 -v 0.052473 0.087415 0.099624 -vn -0.863082 -0.310105 0.398654 -v 0.052473 0.087725 0.099887 -vn -0.863073 -0.276135 0.422912 -v 0.052473 0.088057 0.100124 -vn -0.863078 -0.240265 0.444263 -v 0.052473 0.088406 0.100332 -vn -0.863088 -0.202747 0.462572 -v 0.052473 0.088772 0.100511 -vn -0.863069 -0.163869 0.477765 -v 0.052473 0.089151 0.100659 -vn -0.863073 -0.123853 0.489658 -v 0.052473 0.089541 0.100775 -vn -0.863079 -0.082994 0.498203 -v 0.052473 0.089940 0.100858 -vn -0.863077 -0.041568 0.503358 -v 0.052473 0.090344 0.100908 -vn -0.863073 0.000141 0.505080 -v 0.052473 0.090751 0.100925 -vn -0.863076 0.041848 0.503337 -v 0.052473 0.091157 0.100908 -vn -0.863085 0.083270 0.498148 -v 0.052473 0.091561 0.100858 -vn -0.863076 0.124123 0.489585 -v 0.052473 0.091959 0.100774 -vn -0.863090 0.164125 0.477638 -v 0.052473 0.092350 0.100658 -vn -0.863068 0.203016 0.462490 -v 0.052473 0.092729 0.100510 -vn -0.863084 0.240508 0.444120 -v 0.052473 0.093094 0.100331 -vn -0.863073 0.276370 0.422758 -v 0.052473 0.093444 0.100122 -vn -0.863078 0.310334 0.398485 -v 0.052473 0.093775 0.099886 -vn -0.863075 0.342181 0.371503 -v 0.052473 0.094086 0.099623 -vn -0.863072 0.371693 0.341981 -v 0.052473 0.094374 0.099335 -vn -0.863085 0.398649 0.310101 -v 0.052473 0.094637 0.099024 -vn -0.863076 0.422908 0.276132 -v 0.052473 0.094873 0.098693 -vn -0.863072 0.444271 0.240270 -v 0.052473 0.095081 0.098343 -vn -0.863081 0.462582 0.202753 -v 0.052473 0.095260 0.097977 -vn -0.863064 0.477773 0.163874 -v 0.052473 0.095408 0.097598 -vn -0.863074 0.489658 0.123853 -v 0.052473 0.095524 0.097208 -vn -0.863074 0.498212 0.082997 -v 0.052473 0.095607 0.096809 -vn -0.863078 0.503357 0.041565 -v 0.052473 0.095657 0.096405 -vn -0.863073 0.505080 -0.000141 -v 0.052473 0.095674 0.095999 -vn -0.863076 0.503337 -0.041848 -v 0.052473 0.095657 0.095592 -vn -0.863084 0.498149 -0.083269 -v 0.052473 0.095607 0.095188 -vn -0.863076 0.489585 -0.124123 -v 0.052473 0.095523 0.094790 -vn -0.863087 0.477644 -0.164128 -v 0.052473 0.095407 0.094400 -vn -0.863069 0.462490 -0.203017 -v 0.052473 0.095259 0.094020 -vn -0.863078 0.444129 -0.240513 -v 0.052473 0.095080 0.093655 -vn -0.863074 0.422757 -0.276370 -v 0.052473 0.094871 0.093305 -vn -0.863070 0.398496 -0.310341 -v 0.052473 0.094635 0.092974 -vn -0.863068 0.371512 -0.342188 -v 0.052473 0.094372 0.092663 -vn -0.863071 0.341981 -0.371695 -v 0.052473 0.094084 0.092376 -vn -0.863077 0.310110 -0.398660 -v 0.052473 0.093773 0.092113 -vn -0.863086 0.276119 -0.422897 -v 0.052473 0.093442 0.091876 -vn -0.863072 0.240271 -0.444271 -v 0.052473 0.093092 0.091668 -vn -0.863071 0.202763 -0.462596 -v 0.052473 0.092726 0.091489 -vn -0.863080 0.163859 -0.477748 -v 0.052473 0.092347 0.091341 -vn -0.863073 0.123853 -0.489658 -v 0.052473 0.091957 0.091225 -vn -0.863074 0.082997 -0.498212 -v 0.052473 0.091558 0.091142 -vn -0.863072 0.041567 -0.503367 -v 0.052473 0.091154 0.091092 -vn -0.863072 -0.000142 -0.505081 -v 0.052473 0.090748 0.091075 -vn -0.497071 -0.071894 -0.864726 -v 0.052528 0.090337 0.091037 -vn -0.497049 -0.143055 -0.855849 -v 0.052528 0.089928 0.091088 -vn -0.497082 -0.213244 -0.841093 -v 0.052528 0.089525 0.091173 -vn -0.497066 -0.281975 -0.820619 -v 0.052528 0.089131 0.091290 -vn -0.497056 -0.348782 -0.794536 -v 0.052528 0.088747 0.091440 -vn -0.497064 -0.413198 -0.763017 -v 0.052528 0.088378 0.091621 -vn -0.497076 -0.474791 -0.726285 -v 0.052528 0.088024 0.091832 -vn -0.497083 -0.533143 -0.684592 -v 0.052528 0.087689 0.092071 -vn -0.497065 -0.587864 -0.638234 -v 0.052528 0.087375 0.092337 -vn -0.497050 -0.638567 -0.587514 -v 0.052528 0.087084 0.092628 -vn -0.497079 -0.684891 -0.532763 -v 0.052528 0.086818 0.092942 -vn -0.497058 -0.726554 -0.474397 -v 0.052528 0.086579 0.093277 -vn -0.497089 -0.763235 -0.412765 -v 0.052528 0.086369 0.093631 -vn -0.497043 -0.794735 -0.348345 -v 0.052528 0.086188 0.094001 -vn -0.497078 -0.820772 -0.281509 -v 0.052528 0.086039 0.094384 -vn -0.497072 -0.841216 -0.212778 -v 0.052528 0.085921 0.094779 -vn -0.497088 -0.855906 -0.142581 -v 0.052528 0.085837 0.095182 -vn -0.497059 -0.864773 -0.071416 -v 0.052528 0.085786 0.095590 -vn -0.497091 -0.867698 0.000246 -v 0.052528 0.085769 0.096001 -vn -0.497071 -0.864726 0.071894 -v 0.052528 0.085786 0.096413 -vn -0.497049 -0.855849 0.143056 -v 0.052528 0.085837 0.096821 -vn -0.497072 -0.841098 0.213245 -v 0.052528 0.085922 0.097224 -vn -0.497075 -0.820614 0.281975 -v 0.052528 0.086040 0.097618 -vn -0.497056 -0.794536 0.348781 -v 0.052528 0.086189 0.098002 -vn -0.497077 -0.763009 0.413197 -v 0.052528 0.086370 0.098371 -vn -0.497076 -0.726284 0.474792 -v 0.052528 0.086581 0.098725 -vn -0.497060 -0.684604 0.533150 -v 0.052528 0.086820 0.099060 -vn -0.497085 -0.638222 0.587860 -v 0.052528 0.087086 0.099374 -vn -0.497081 -0.587502 0.638555 -v 0.052528 0.087377 0.099665 -vn -0.497080 -0.532765 0.684889 -v 0.052528 0.087692 0.099931 -vn -0.497068 -0.474394 0.726549 -v 0.052528 0.088027 0.100170 -vn -0.497087 -0.412769 0.763234 -v 0.052528 0.088380 0.100380 -vn -0.497068 -0.348337 0.794723 -v 0.052528 0.088750 0.100561 -vn -0.497079 -0.281512 0.820770 -v 0.052528 0.089133 0.100711 -vn -0.497070 -0.212774 0.841218 -v 0.052528 0.089528 0.100828 -vn -0.497050 -0.142589 0.855926 -v 0.052528 0.089931 0.100912 -vn -0.497057 -0.071412 0.864774 -v 0.052528 0.090339 0.100963 -vn -0.497053 0.000242 0.867720 -v 0.052528 0.090751 0.100980 -vn -0.497071 0.071894 0.864726 -v 0.052528 0.091162 0.100963 -vn -0.497075 0.143056 0.855834 -v 0.052528 0.091570 0.100912 -vn -0.497072 0.213247 0.841098 -v 0.052528 0.091973 0.100827 -vn -0.497064 0.281975 0.820620 -v 0.052528 0.092367 0.100710 -vn -0.497058 0.348778 0.794536 -v 0.052528 0.092751 0.100560 -vn -0.497077 0.413197 0.763009 -v 0.052528 0.093121 0.100379 -vn -0.497075 0.474797 0.726281 -v 0.052528 0.093474 0.100168 -vn -0.497060 0.533155 0.684600 -v 0.052528 0.093809 0.099929 -vn -0.497063 0.587865 0.638234 -v 0.052528 0.094123 0.099663 -vn -0.497053 0.638561 0.587518 -v 0.052528 0.094414 0.099372 -vn -0.497080 0.684889 0.532765 -v 0.052528 0.094680 0.099058 -vn -0.497069 0.726550 0.474392 -v 0.052528 0.094919 0.098723 -vn -0.497093 0.763233 0.412764 -v 0.052528 0.095130 0.098369 -vn -0.497072 0.794722 0.348333 -v 0.052528 0.095310 0.097999 -vn -0.497070 0.820775 0.281514 -v 0.052528 0.095460 0.097616 -vn -0.497060 0.841224 0.212778 -v 0.052528 0.095577 0.097221 -vn -0.497044 0.855930 0.142591 -v 0.052528 0.095661 0.096818 -vn -0.497061 0.864771 0.071416 -v 0.052528 0.095712 0.096410 -vn -0.497092 0.867698 -0.000246 -v 0.052528 0.095729 0.095999 -vn -0.497071 0.864726 -0.071894 -v 0.052528 0.095712 0.095587 -vn -0.497076 0.855833 -0.143055 -v 0.052528 0.095661 0.095179 -vn -0.497081 0.841093 -0.213245 -v 0.052528 0.095576 0.094776 -vn -0.497056 0.820625 -0.281975 -v 0.052528 0.095459 0.094382 -vn -0.497057 0.794536 -0.348779 -v 0.052528 0.095309 0.093998 -vn -0.497064 0.763017 -0.413198 -v 0.052528 0.095128 0.093629 -vn -0.497076 0.726281 -0.474796 -v 0.052528 0.094917 0.093275 -vn -0.497067 0.684597 -0.533152 -v 0.052528 0.094678 0.092940 -vn -0.497046 0.638247 -0.587866 -v 0.052528 0.094412 0.092626 -vn -0.497077 0.587505 -0.638556 -v 0.052528 0.094121 0.092335 -vn -0.497058 0.532772 -0.684899 -v 0.052528 0.093807 0.092069 -vn -0.497058 0.474393 -0.726557 -v 0.052528 0.093472 0.091830 -vn -0.497095 0.412759 -0.763234 -v 0.052528 0.093118 0.091620 -vn -0.497045 0.348345 -0.794734 -v 0.052528 0.092748 0.091439 -vn -0.497057 0.281514 -0.820783 -v 0.052528 0.092365 0.091289 -vn -0.497064 0.212777 -0.841221 -v 0.052528 0.091970 0.091172 -vn -0.497081 0.142584 -0.855909 -v 0.052528 0.091567 0.091088 -vn -0.497061 0.071416 -0.864771 -v 0.052528 0.091159 0.091037 -vn -0.497092 -0.000246 -0.867698 -v 0.052528 0.090748 0.091020 -vn -0.130089 -0.082153 -0.988093 -v 0.052603 0.090335 0.091017 -vn -0.130075 -0.163463 -0.977937 -v 0.052603 0.089925 0.091068 -vn -0.130108 -0.243665 -0.961093 -v 0.052603 0.089520 0.091153 -vn -0.130101 -0.322206 -0.937687 -v 0.052603 0.089124 0.091271 -vn -0.130095 -0.398538 -0.907878 -v 0.052603 0.088739 0.091422 -vn -0.130087 -0.472142 -0.871871 -v 0.052603 0.088368 0.091603 -vn -0.130103 -0.542526 -0.829903 -v 0.052603 0.088013 0.091815 -vn -0.130106 -0.609210 -0.782263 -v 0.052603 0.087677 0.092055 -vn -0.130081 -0.671732 -0.729284 -v 0.052603 0.087362 0.092322 -vn -0.130079 -0.729658 -0.671326 -v 0.052603 0.087070 0.092615 -vn -0.130085 -0.782606 -0.608774 -v 0.052603 0.086803 0.092930 -vn -0.130056 -0.830205 -0.542075 -v 0.052603 0.086563 0.093266 -vn -0.130102 -0.872132 -0.471656 -v 0.052603 0.086351 0.093621 -vn -0.130060 -0.908105 -0.398033 -v 0.052603 0.086170 0.093993 -vn -0.130111 -0.937868 -0.321674 -v 0.052603 0.086020 0.094378 -vn -0.130099 -0.961228 -0.243136 -v 0.052603 0.085902 0.094774 -vn -0.130111 -0.978022 -0.162926 -v 0.052603 0.085817 0.095178 -vn -0.130085 -0.988139 -0.081604 -v 0.052603 0.085766 0.095588 -vn -0.130119 -0.991498 0.000281 -v 0.052603 0.085749 0.096001 -vn -0.130089 -0.988093 0.082153 -v 0.052603 0.085766 0.096414 -vn -0.130075 -0.977936 0.163465 -v 0.052603 0.085818 0.096824 -vn -0.130097 -0.961095 0.243662 -v 0.052603 0.085902 0.097229 -vn -0.130100 -0.937688 0.322204 -v 0.052603 0.086021 0.097625 -vn -0.130095 -0.907878 0.398538 -v 0.052603 0.086171 0.098010 -vn -0.130087 -0.871871 0.472142 -v 0.052603 0.086352 0.098381 -vn -0.130103 -0.829900 0.542531 -v 0.052603 0.086564 0.098736 -vn -0.130079 -0.782268 0.609210 -v 0.052603 0.086804 0.099072 -vn -0.130079 -0.729286 0.671730 -v 0.052603 0.087071 0.099387 -vn -0.130111 -0.671320 0.729658 -v 0.052603 0.087364 0.099680 -vn -0.130087 -0.608776 0.782604 -v 0.052603 0.087679 0.099947 -vn -0.130092 -0.542070 0.830203 -v 0.052603 0.088016 0.100187 -vn -0.130104 -0.471659 0.872130 -v 0.052603 0.088371 0.100398 -vn -0.130060 -0.398033 0.908105 -v 0.052603 0.088742 0.100579 -vn -0.130111 -0.321674 0.937868 -v 0.052603 0.089127 0.100730 -vn -0.130099 -0.243127 0.961230 -v 0.052603 0.089523 0.100847 -vn -0.130069 -0.162931 0.978026 -v 0.052603 0.089928 0.100932 -vn -0.130082 -0.081600 0.988140 -v 0.052603 0.090338 0.100983 -vn -0.130077 0.000277 0.991504 -v 0.052603 0.090751 0.101000 -vn -0.130086 0.082148 0.988094 -v 0.052603 0.091163 0.100983 -vn -0.130075 0.163465 0.977936 -v 0.052603 0.091573 0.100932 -vn -0.130097 0.243671 0.961093 -v 0.052603 0.091978 0.100847 -vn -0.130060 0.322203 0.937694 -v 0.052603 0.092374 0.100729 -vn -0.130092 0.398533 0.907881 -v 0.052603 0.092759 0.100578 -vn -0.130087 0.472142 0.871871 -v 0.052603 0.093130 0.100397 -vn -0.130103 0.542537 0.829896 -v 0.052603 0.093485 0.100185 -vn -0.130079 0.609215 0.782264 -v 0.052603 0.093821 0.099945 -vn -0.130079 0.671730 0.729286 -v 0.052603 0.094137 0.099678 -vn -0.130082 0.729655 0.671328 -v 0.052603 0.094429 0.099385 -vn -0.130086 0.782602 0.608779 -v 0.052603 0.094696 0.099070 -vn -0.130092 0.830203 0.542070 -v 0.052603 0.094936 0.098734 -vn -0.130124 0.872128 0.471657 -v 0.052603 0.095147 0.098379 -vn -0.130079 0.908103 0.398030 -v 0.052603 0.095329 0.098007 -vn -0.130112 0.937869 0.321672 -v 0.052603 0.095479 0.097622 -vn -0.130089 0.961231 0.243128 -v 0.052603 0.095596 0.097226 -vn -0.130061 0.978027 0.162931 -v 0.052603 0.095681 0.096822 -vn -0.130081 0.988139 0.081610 -v 0.052603 0.095732 0.096412 -vn -0.130119 0.991498 -0.000281 -v 0.052603 0.095749 0.095999 -vn -0.130089 0.988093 -0.082153 -v 0.052603 0.095732 0.095586 -vn -0.130075 0.977937 -0.163463 -v 0.052603 0.095681 0.095176 -vn -0.130107 0.961091 -0.243673 -v 0.052603 0.095596 0.094771 -vn -0.130061 0.937693 -0.322204 -v 0.052603 0.095478 0.094375 -vn -0.130092 0.907881 -0.398533 -v 0.052603 0.095327 0.093990 -vn -0.130087 0.871871 -0.472142 -v 0.052603 0.095146 0.093619 -vn -0.130103 0.829899 -0.542532 -v 0.052603 0.094934 0.093264 -vn -0.130106 0.782258 -0.609216 -v 0.052603 0.094694 0.092928 -vn -0.130081 0.729293 -0.671723 -v 0.052603 0.094427 0.092613 -vn -0.130110 0.671325 -0.729654 -v 0.052603 0.094135 0.092320 -vn -0.130087 0.608771 -0.782608 -v 0.052603 0.093819 0.092053 -vn -0.130056 0.542075 -0.830205 -v 0.052603 0.093483 0.091813 -vn -0.130122 0.471654 -0.872130 -v 0.052603 0.093128 0.091602 -vn -0.130079 0.398030 -0.908103 -v 0.052603 0.092756 0.091421 -vn -0.130071 0.321677 -0.937873 -v 0.052603 0.092371 0.091270 -vn -0.130086 0.243133 -0.961231 -v 0.052603 0.091975 0.091153 -vn -0.130103 0.162926 -0.978023 -v 0.052603 0.091571 0.091068 -vn -0.130084 0.081605 -0.988139 -v 0.052603 0.091161 0.091017 -vn -0.130119 -0.000281 -0.991498 -v 0.052603 0.090748 0.091000 -vn 0.130079 -0.988140 -0.081599 -v 0.056303 0.085766 0.095588 -vn 0.130113 -0.991499 0.000275 -v 0.056303 0.085749 0.096001 -vn 0.130080 -0.988094 0.082155 -v 0.056303 0.085766 0.096414 -vn 0.130070 -0.977937 0.163468 -v 0.056303 0.085818 0.096824 -vn 0.130092 -0.961096 0.243661 -v 0.056303 0.085902 0.097229 -vn 0.130094 -0.937689 0.322204 -v 0.056303 0.086021 0.097625 -vn 0.130088 -0.907879 0.398538 -v 0.056303 0.086171 0.098010 -vn 0.130081 -0.871871 0.472144 -v 0.056303 0.086352 0.098381 -vn 0.130096 -0.829903 0.542528 -v 0.056303 0.086564 0.098736 -vn 0.130072 -0.782267 0.609212 -v 0.056303 0.086804 0.099072 -vn 0.130075 -0.729285 0.671732 -v 0.056303 0.087071 0.099387 -vn 0.130105 -0.671325 0.729655 -v 0.056303 0.087364 0.099680 -vn 0.130080 -0.608775 0.782606 -v 0.056303 0.087679 0.099947 -vn 0.130087 -0.542070 0.830204 -v 0.056303 0.088016 0.100187 -vn 0.130096 -0.471664 0.872129 -v 0.056303 0.088371 0.100398 -vn 0.130055 -0.398026 0.908109 -v 0.056303 0.088742 0.100579 -vn 0.130107 -0.321680 0.937867 -v 0.056303 0.089127 0.100730 -vn 0.130091 -0.243129 0.961231 -v 0.056303 0.089523 0.100847 -vn 0.130062 -0.162927 0.978028 -v 0.056303 0.089928 0.100932 -vn 0.130076 -0.081602 0.988140 -v 0.056303 0.090338 0.100983 -vn 0.130071 0.000279 0.991505 -v 0.056303 0.090751 0.101000 -vn 0.130080 0.082146 0.988095 -v 0.056303 0.091163 0.100983 -vn 0.130070 0.163468 0.977937 -v 0.056303 0.091573 0.100932 -vn 0.130090 0.243665 0.961095 -v 0.056303 0.091978 0.100847 -vn 0.130054 0.322209 0.937692 -v 0.056303 0.092374 0.100729 -vn 0.130088 0.398530 0.907883 -v 0.056303 0.092759 0.100578 -vn 0.130081 0.472144 0.871871 -v 0.056303 0.093130 0.100397 -vn 0.130096 0.542534 0.829899 -v 0.056303 0.093485 0.100185 -vn 0.130072 0.609218 0.782263 -v 0.056303 0.093821 0.099945 -vn 0.130073 0.671730 0.729287 -v 0.056303 0.094137 0.099678 -vn 0.130076 0.729656 0.671329 -v 0.056303 0.094429 0.099385 -vn 0.130080 0.782603 0.608779 -v 0.056303 0.094696 0.099070 -vn 0.130088 0.830204 0.542068 -v 0.056303 0.094936 0.098734 -vn 0.130117 0.872126 0.471663 -v 0.056303 0.095147 0.098379 -vn 0.130072 0.908107 0.398024 -v 0.056303 0.095329 0.098007 -vn 0.130106 0.937868 0.321677 -v 0.056303 0.095479 0.097622 -vn 0.130079 0.961233 0.243128 -v 0.056303 0.095596 0.097226 -vn 0.130055 0.978029 0.162927 -v 0.056303 0.095681 0.096822 -vn 0.130079 0.988139 0.081608 -v 0.056303 0.095732 0.096412 -vn 0.130113 0.991499 -0.000275 -v 0.056303 0.095749 0.095999 -vn 0.130080 0.988094 -0.082155 -v 0.056303 0.095732 0.095586 -vn 0.130070 0.977937 -0.163467 -v 0.056303 0.095681 0.095176 -vn 0.130100 0.961094 -0.243666 -v 0.056303 0.095596 0.094771 -vn 0.130054 0.937692 -0.322212 -v 0.056303 0.095478 0.094375 -vn 0.130088 0.907883 -0.398530 -v 0.056303 0.095327 0.093990 -vn 0.130081 0.871871 -0.472144 -v 0.056303 0.095146 0.093619 -vn 0.130098 0.829900 -0.542532 -v 0.056303 0.094934 0.093264 -vn 0.130098 0.782261 -0.609215 -v 0.056303 0.094694 0.092928 -vn 0.130075 0.729289 -0.671727 -v 0.056303 0.094427 0.092613 -vn 0.130105 0.671329 -0.729651 -v 0.056303 0.094135 0.092320 -vn 0.130078 0.608772 -0.782609 -v 0.056303 0.093819 0.092053 -vn 0.130053 0.542068 -0.830210 -v 0.056303 0.093483 0.091813 -vn 0.130117 0.471663 -0.872126 -v 0.056303 0.093128 0.091602 -vn 0.130069 0.398027 -0.908106 -v 0.056303 0.092756 0.091421 -vn 0.130066 0.321676 -0.937874 -v 0.056303 0.092371 0.091270 -vn 0.130082 0.243133 -0.961231 -v 0.056303 0.091975 0.091153 -vn 0.130097 0.162929 -0.978023 -v 0.056303 0.091571 0.091068 -vn 0.130079 0.081600 -0.988140 -v 0.056303 0.091161 0.091017 -vn 0.130113 -0.000275 -0.991499 -v 0.056303 0.090748 0.091000 -vn 0.130080 -0.082155 -0.988094 -v 0.056303 0.090335 0.091017 -vn 0.130070 -0.163467 -0.977937 -v 0.056303 0.089925 0.091068 -vn 0.130103 -0.243661 -0.961094 -v 0.056303 0.089520 0.091153 -vn 0.130094 -0.322206 -0.937688 -v 0.056303 0.089124 0.091271 -vn 0.130088 -0.398538 -0.907879 -v 0.056303 0.088739 0.091422 -vn 0.130081 -0.472144 -0.871871 -v 0.056303 0.088368 0.091603 -vn 0.130098 -0.542526 -0.829904 -v 0.056303 0.088013 0.091815 -vn 0.130098 -0.609209 -0.782265 -v 0.056303 0.087677 0.092055 -vn 0.130073 -0.671735 -0.729283 -v 0.056303 0.087362 0.092322 -vn 0.130073 -0.729659 -0.671326 -v 0.056303 0.087070 0.092615 -vn 0.130078 -0.782605 -0.608777 -v 0.056303 0.086803 0.092930 -vn 0.130051 -0.830209 -0.542070 -v 0.056303 0.086563 0.093266 -vn 0.130096 -0.872129 -0.471664 -v 0.056303 0.086351 0.093621 -vn 0.130055 -0.908109 -0.398026 -v 0.056303 0.086170 0.093993 -vn 0.130107 -0.937867 -0.321680 -v 0.056303 0.086020 0.094378 -vn 0.130093 -0.961229 -0.243134 -v 0.056303 0.085902 0.094774 -vn 0.130104 -0.978022 -0.162930 -v 0.056303 0.085817 0.095178 -vn 0.497082 -0.071893 -0.864720 -v 0.056378 0.090337 0.091037 -vn 0.497056 -0.143061 -0.855844 -v 0.056378 0.089928 0.091088 -vn 0.497089 -0.213238 -0.841090 -v 0.056378 0.089525 0.091173 -vn 0.497075 -0.281974 -0.820614 -v 0.056378 0.089131 0.091290 -vn 0.497066 -0.348781 -0.794529 -v 0.056378 0.088747 0.091440 -vn 0.497073 -0.413196 -0.763012 -v 0.056378 0.088378 0.091621 -vn 0.497084 -0.474788 -0.726281 -v 0.056378 0.088024 0.091832 -vn 0.497094 -0.533137 -0.684589 -v 0.056378 0.087689 0.092071 -vn 0.497074 -0.587861 -0.638229 -v 0.056378 0.087375 0.092337 -vn 0.497060 -0.638567 -0.587507 -v 0.056378 0.087084 0.092628 -vn 0.497091 -0.684882 -0.532763 -v 0.056378 0.086818 0.092942 -vn 0.497066 -0.726554 -0.474389 -v 0.056378 0.086579 0.093277 -vn 0.497097 -0.763227 -0.412770 -v 0.056378 0.086369 0.093631 -vn 0.497051 -0.794734 -0.348335 -v 0.056378 0.086188 0.094001 -vn 0.497085 -0.820767 -0.281512 -v 0.056378 0.086039 0.094384 -vn 0.497082 -0.841211 -0.212774 -v 0.056378 0.085921 0.094779 -vn 0.497097 -0.855899 -0.142586 -v 0.056378 0.085837 0.095182 -vn 0.497067 -0.864769 -0.071409 -v 0.056378 0.085786 0.095590 -vn 0.497101 -0.867693 0.000241 -v 0.056378 0.085769 0.096001 -vn 0.497082 -0.864720 0.071893 -v 0.056378 0.085786 0.096413 -vn 0.497056 -0.855844 0.143061 -v 0.056378 0.085837 0.096821 -vn 0.497080 -0.841094 0.213242 -v 0.056378 0.085922 0.097224 -vn 0.497083 -0.820610 0.281971 -v 0.056378 0.086040 0.097618 -vn 0.497067 -0.794529 0.348782 -v 0.056378 0.086189 0.098002 -vn 0.497086 -0.763006 0.413192 -v 0.056378 0.086370 0.098371 -vn 0.497084 -0.726281 0.474788 -v 0.056378 0.086581 0.098725 -vn 0.497072 -0.684596 0.533149 -v 0.056378 0.086820 0.099060 -vn 0.497091 -0.638221 0.587856 -v 0.056378 0.087086 0.099374 -vn 0.497089 -0.587499 0.638552 -v 0.056378 0.087377 0.099665 -vn 0.497091 -0.532763 0.684883 -v 0.056378 0.087692 0.099931 -vn 0.497076 -0.474388 0.726547 -v 0.056378 0.088027 0.100170 -vn 0.497100 -0.412770 0.763225 -v 0.056378 0.088380 0.100380 -vn 0.497076 -0.348332 0.794721 -v 0.056378 0.088750 0.100561 -vn 0.497085 -0.281512 0.820767 -v 0.056378 0.089133 0.100711 -vn 0.497082 -0.212774 0.841211 -v 0.056378 0.089528 0.100828 -vn 0.497059 -0.142585 0.855921 -v 0.056378 0.089931 0.100912 -vn 0.497065 -0.071413 0.864770 -v 0.056378 0.090339 0.100963 -vn 0.497063 0.000245 0.867715 -v 0.056378 0.090751 0.100980 -vn 0.497082 0.071892 0.864720 -v 0.056378 0.091162 0.100963 -vn 0.497083 0.143055 0.855829 -v 0.056378 0.091570 0.100912 -vn 0.497082 0.213245 0.841092 -v 0.056378 0.091973 0.100827 -vn 0.497073 0.281973 0.820615 -v 0.056378 0.092367 0.100710 -vn 0.497065 0.348779 0.794531 -v 0.056378 0.092751 0.100560 -vn 0.497086 0.413192 0.763006 -v 0.056378 0.093121 0.100379 -vn 0.497084 0.474793 0.726277 -v 0.056378 0.093474 0.100168 -vn 0.497071 0.533153 0.684594 -v 0.056378 0.093809 0.099929 -vn 0.497071 0.587861 0.638231 -v 0.056378 0.094123 0.099663 -vn 0.497063 0.638560 0.587511 -v 0.056378 0.094414 0.099372 -vn 0.497089 0.684882 0.532765 -v 0.056378 0.094680 0.099058 -vn 0.497075 0.726549 0.474386 -v 0.056378 0.094919 0.098723 -vn 0.497104 0.763225 0.412765 -v 0.056378 0.095130 0.098369 -vn 0.497080 0.794719 0.348329 -v 0.056378 0.095310 0.097999 -vn 0.497077 0.820771 0.281513 -v 0.056378 0.095460 0.097616 -vn 0.497073 0.841216 0.212778 -v 0.056378 0.095577 0.097221 -vn 0.497053 0.855925 0.142586 -v 0.056378 0.095661 0.096818 -vn 0.497067 0.864768 0.071414 -v 0.056378 0.095712 0.096410 -vn 0.497101 0.867693 -0.000241 -v 0.056378 0.095729 0.095999 -vn 0.497084 0.864719 -0.071896 -v 0.056378 0.095712 0.095587 -vn 0.497083 0.855829 -0.143055 -v 0.056378 0.095661 0.095179 -vn 0.497091 0.841088 -0.213241 -v 0.056378 0.095576 0.094776 -vn 0.497065 0.820619 -0.281976 -v 0.056378 0.095459 0.094382 -vn 0.497064 0.794532 -0.348778 -v 0.056378 0.095309 0.093998 -vn 0.497073 0.763012 -0.413196 -v 0.056378 0.095128 0.093629 -vn 0.497083 0.726279 -0.474792 -v 0.056378 0.094917 0.093275 -vn 0.497077 0.684594 -0.533147 -v 0.056378 0.094678 0.092940 -vn 0.497055 0.638239 -0.587867 -v 0.056378 0.094412 0.092626 -vn 0.497086 0.587505 -0.638548 -v 0.056378 0.094121 0.092335 -vn 0.497072 0.532766 -0.684894 -v 0.056378 0.093807 0.092069 -vn 0.497065 0.474388 -0.726556 -v 0.056378 0.093472 0.091830 -vn 0.497101 0.412766 -0.763227 -v 0.056378 0.093118 0.091620 -vn 0.497058 0.348336 -0.794730 -v 0.056378 0.092748 0.091439 -vn 0.497065 0.281513 -0.820778 -v 0.056378 0.092365 0.091289 -vn 0.497071 0.212774 -0.841218 -v 0.056378 0.091970 0.091172 -vn 0.497091 0.142587 -0.855903 -v 0.056378 0.091567 0.091088 -vn 0.497069 0.071410 -0.864767 -v 0.056378 0.091159 0.091037 -vn 0.497101 -0.000241 -0.867693 -v 0.056378 0.090748 0.091020 -vn 0.863074 -0.041845 -0.503342 -v 0.056433 0.090341 0.091092 -vn 0.863070 -0.083271 -0.498173 -v 0.056433 0.089937 0.091142 -vn 0.863068 -0.124128 -0.489597 -v 0.056433 0.089539 0.091226 -vn 0.863068 -0.164136 -0.477675 -v 0.056433 0.089149 0.091342 -vn 0.863066 -0.203023 -0.462492 -v 0.056433 0.088770 0.091490 -vn 0.863069 -0.240518 -0.444143 -v 0.056433 0.088404 0.091669 -vn 0.863066 -0.276376 -0.422767 -v 0.056433 0.088054 0.091878 -vn 0.863074 -0.310335 -0.398492 -v 0.056433 0.087723 0.092114 -vn 0.863077 -0.342179 -0.371499 -v 0.056433 0.087413 0.092377 -vn 0.863068 -0.371702 -0.341981 -v 0.056433 0.087125 0.092665 -vn 0.863079 -0.398657 -0.310109 -v 0.056433 0.086862 0.092976 -vn 0.863080 -0.422902 -0.276129 -v 0.056433 0.086625 0.093307 -vn 0.863076 -0.444267 -0.240266 -v 0.056433 0.086417 0.093657 -vn 0.863075 -0.462590 -0.202758 -v 0.056433 0.086238 0.094023 -vn 0.863067 -0.477769 -0.163865 -v 0.056433 0.086091 0.094402 -vn 0.863070 -0.489663 -0.123855 -v 0.056433 0.085975 0.094792 -vn 0.863071 -0.498217 -0.082998 -v 0.056433 0.085891 0.095191 -vn 0.863069 -0.503373 -0.041569 -v 0.056433 0.085841 0.095595 -vn 0.863069 -0.505086 0.000143 -v 0.056433 0.085824 0.096001 -vn 0.863074 -0.503342 0.041845 -v 0.056433 0.085841 0.096408 -vn 0.863071 -0.498171 0.083272 -v 0.056433 0.085892 0.096812 -vn 0.863073 -0.489589 0.124126 -v 0.056433 0.085975 0.097210 -vn 0.863072 -0.477670 0.164132 -v 0.056433 0.086091 0.097600 -vn 0.863066 -0.462492 0.203024 -v 0.056433 0.086240 0.097980 -vn 0.863075 -0.444135 0.240511 -v 0.056433 0.086418 0.098345 -vn 0.863067 -0.422768 0.276376 -v 0.056433 0.086627 0.098695 -vn 0.863073 -0.398491 0.310337 -v 0.056433 0.086863 0.099026 -vn 0.863085 -0.371489 0.342170 -v 0.056433 0.087127 0.099337 -vn 0.863069 -0.341981 0.371700 -v 0.056433 0.087415 0.099624 -vn 0.863079 -0.310111 0.398656 -v 0.056433 0.087725 0.099887 -vn 0.863071 -0.276136 0.422916 -v 0.056433 0.088057 0.100124 -vn 0.863074 -0.240267 0.444270 -v 0.056433 0.088406 0.100332 -vn 0.863087 -0.202753 0.462572 -v 0.056433 0.088772 0.100511 -vn 0.863068 -0.163866 0.477768 -v 0.056433 0.089151 0.100659 -vn 0.863070 -0.123854 0.489663 -v 0.056433 0.089541 0.100775 -vn 0.863077 -0.082997 0.498206 -v 0.056433 0.089940 0.100858 -vn 0.863075 -0.041569 0.503363 -v 0.056433 0.090344 0.100908 -vn 0.863069 0.000143 0.505086 -v 0.056433 0.090751 0.100925 -vn 0.863073 0.041849 0.503343 -v 0.056433 0.091157 0.100908 -vn 0.863083 0.083267 0.498151 -v 0.056433 0.091561 0.100858 -vn 0.863073 0.124129 0.489588 -v 0.056433 0.091959 0.100774 -vn 0.863088 0.164120 0.477643 -v 0.056433 0.092350 0.100658 -vn 0.863066 0.203023 0.462491 -v 0.056433 0.092729 0.100510 -vn 0.863081 0.240506 0.444127 -v 0.056433 0.093094 0.100331 -vn 0.863071 0.276374 0.422760 -v 0.056433 0.093444 0.100122 -vn 0.863074 0.310337 0.398490 -v 0.056433 0.093775 0.099886 -vn 0.863072 0.342184 0.371506 -v 0.056433 0.094086 0.099623 -vn 0.863069 0.371699 0.341982 -v 0.056433 0.094374 0.099335 -vn 0.863082 0.398650 0.310107 -v 0.056433 0.094637 0.099024 -vn 0.863074 0.422911 0.276133 -v 0.056433 0.094873 0.098693 -vn 0.863069 0.444277 0.240271 -v 0.056433 0.095081 0.098343 -vn 0.863079 0.462583 0.202758 -v 0.056433 0.095260 0.097977 -vn 0.863062 0.477777 0.163870 -v 0.056433 0.095408 0.097598 -vn 0.863070 0.489664 0.123856 -v 0.056433 0.095524 0.097208 -vn 0.863071 0.498216 0.082997 -v 0.056433 0.095607 0.096809 -vn 0.863075 0.503362 0.041568 -v 0.056433 0.095657 0.096405 -vn 0.863069 0.505086 -0.000143 -v 0.056433 0.095674 0.095999 -vn 0.863073 0.503343 -0.041849 -v 0.056433 0.095657 0.095592 -vn 0.863082 0.498153 -0.083267 -v 0.056433 0.095607 0.095188 -vn 0.863073 0.489588 -0.124127 -v 0.056433 0.095523 0.094790 -vn 0.863084 0.477649 -0.164124 -v 0.056433 0.095407 0.094400 -vn 0.863067 0.462491 -0.203022 -v 0.056433 0.095259 0.094020 -vn 0.863075 0.444134 -0.240513 -v 0.056433 0.095080 0.093655 -vn 0.863071 0.422760 -0.276372 -v 0.056433 0.094871 0.093305 -vn 0.863067 0.398499 -0.310344 -v 0.056433 0.094635 0.092974 -vn 0.863065 0.371515 -0.342193 -v 0.056433 0.094372 0.092663 -vn 0.863068 0.341984 -0.371699 -v 0.056433 0.094084 0.092376 -vn 0.863073 0.310113 -0.398666 -v 0.056433 0.093773 0.092113 -vn 0.863083 0.276125 -0.422898 -v 0.056433 0.093442 0.091876 -vn 0.863070 0.240270 -0.444274 -v 0.056433 0.093092 0.091668 -vn 0.863069 0.202764 -0.462601 -v 0.056433 0.092726 0.091489 -vn 0.863077 0.163863 -0.477752 -v 0.056433 0.092347 0.091341 -vn 0.863071 0.123852 -0.489663 -v 0.056433 0.091957 0.091225 -vn 0.863071 0.082998 -0.498217 -v 0.056433 0.091558 0.091142 -vn 0.863070 0.041568 -0.503371 -v 0.056433 0.091154 0.091092 -vn 0.863069 -0.000143 -0.505086 -v 0.056433 0.090748 0.091075 -vn 0.990992 -0.011096 -0.133459 -v 0.056453 0.090347 0.091167 -vn 0.990994 -0.022076 -0.132075 -v 0.056453 0.089950 0.091216 -vn 0.990992 -0.032912 -0.129810 -v 0.056453 0.089557 0.091299 -vn 0.990994 -0.043515 -0.126640 -v 0.056453 0.089173 0.091413 -vn 0.990994 -0.053822 -0.122610 -v 0.056453 0.088800 0.091559 -vn 0.990993 -0.063769 -0.117758 -v 0.056453 0.088440 0.091735 -vn 0.990992 -0.073278 -0.112092 -v 0.056453 0.088095 0.091940 -vn 0.990993 -0.082280 -0.105652 -v 0.056453 0.087769 0.092173 -vn 0.990994 -0.090722 -0.098496 -v 0.056453 0.087463 0.092433 -vn 0.990994 -0.098544 -0.090666 -v 0.056453 0.087180 0.092716 -vn 0.990992 -0.105704 -0.082225 -v 0.056453 0.086921 0.093022 -vn 0.990992 -0.112135 -0.073217 -v 0.056453 0.086688 0.093348 -vn 0.990992 -0.117796 -0.063705 -v 0.056453 0.086483 0.093693 -vn 0.990994 -0.122643 -0.053756 -v 0.056453 0.086307 0.094053 -vn 0.990994 -0.126665 -0.043444 -v 0.056453 0.086162 0.094426 -vn 0.990993 -0.129822 -0.032838 -v 0.056453 0.086047 0.094811 -vn 0.990993 -0.132097 -0.022006 -v 0.056453 0.085965 0.095203 -vn 0.990993 -0.133459 -0.011021 -v 0.056453 0.085916 0.095601 -vn 0.990993 -0.133914 0.000037 -v 0.056453 0.085899 0.096001 -vn 0.990992 -0.133459 0.011097 -v 0.056453 0.085916 0.096402 -vn 0.990994 -0.132073 0.022076 -v 0.056453 0.085966 0.096800 -vn 0.990994 -0.129798 0.032907 -v 0.056453 0.086048 0.097192 -vn 0.990993 -0.126644 0.043517 -v 0.056453 0.086162 0.097576 -vn 0.990994 -0.122611 0.053822 -v 0.056453 0.086308 0.097949 -vn 0.990992 -0.117762 0.063773 -v 0.056453 0.086484 0.098310 -vn 0.990992 -0.112092 0.073278 -v 0.056453 0.086690 0.098654 -vn 0.990993 -0.105652 0.082280 -v 0.056453 0.086923 0.098980 -vn 0.990992 -0.098501 0.090729 -v 0.056453 0.087182 0.099286 -vn 0.990994 -0.090666 0.098543 -v 0.056453 0.087465 0.099569 -vn 0.990992 -0.082226 0.105705 -v 0.056453 0.087771 0.099828 -vn 0.990993 -0.073212 0.112125 -v 0.056453 0.088098 0.100061 -vn 0.990992 -0.063705 0.117796 -v 0.056453 0.088442 0.100266 -vn 0.990992 -0.053760 0.122653 -v 0.056453 0.088802 0.100442 -vn 0.990994 -0.043445 0.126665 -v 0.056453 0.089176 0.100588 -vn 0.990993 -0.032836 0.129823 -v 0.056453 0.089560 0.100702 -vn 0.990994 -0.022004 0.132085 -v 0.056453 0.089952 0.100784 -vn 0.990995 -0.011021 0.133445 -v 0.056453 0.090350 0.100834 -vn 0.990993 0.000037 0.133914 -v 0.056453 0.090751 0.100850 -vn 0.990992 0.011097 0.133459 -v 0.056453 0.091151 0.100833 -vn 0.990993 0.022079 0.132084 -v 0.056453 0.091549 0.100784 -vn 0.990994 0.032908 0.129800 -v 0.056453 0.091941 0.100701 -vn 0.990993 0.043516 0.126643 -v 0.056453 0.092325 0.100587 -vn 0.990994 0.053822 0.122612 -v 0.056453 0.092699 0.100441 -vn 0.990993 0.063768 0.117752 -v 0.056453 0.093059 0.100265 -vn 0.990994 0.073272 0.112083 -v 0.056453 0.093403 0.100060 -vn 0.990993 0.082279 0.105651 -v 0.056453 0.093729 0.099826 -vn 0.990992 0.090729 0.098502 -v 0.056453 0.094035 0.099567 -vn 0.990994 0.098544 0.090666 -v 0.056453 0.094318 0.099284 -vn 0.990993 0.105700 0.082221 -v 0.056453 0.094577 0.098978 -vn 0.990994 0.112119 0.073208 -v 0.056453 0.094810 0.098652 -vn 0.990993 0.117790 0.063703 -v 0.056453 0.095015 0.098307 -vn 0.990992 0.122653 0.053760 -v 0.056453 0.095191 0.097947 -vn 0.990994 0.126665 0.043445 -v 0.056453 0.095337 0.097574 -vn 0.990993 0.129822 0.032838 -v 0.056453 0.095451 0.097189 -vn 0.990992 0.132098 0.022005 -v 0.056453 0.095533 0.096797 -vn 0.990995 0.133446 0.011021 -v 0.056453 0.095583 0.096399 -vn 0.990993 0.133914 -0.000037 -v 0.056453 0.095599 0.095999 -vn 0.990992 0.133459 -0.011096 -v 0.056453 0.095582 0.095598 -vn 0.990992 0.132087 -0.022080 -v 0.056453 0.095533 0.095200 -vn 0.990994 0.129800 -0.032908 -v 0.056453 0.095450 0.094808 -vn 0.990994 0.126639 -0.043514 -v 0.056453 0.095336 0.094424 -vn 0.990994 0.122611 -0.053823 -v 0.056453 0.095190 0.094051 -vn 0.990994 0.117748 -0.063764 -v 0.056453 0.095014 0.093690 -vn 0.990994 0.112083 -0.073272 -v 0.056453 0.094809 0.093346 -vn 0.990994 0.105646 -0.082274 -v 0.056453 0.094576 0.093020 -vn 0.990993 0.098496 -0.090722 -v 0.056453 0.094316 0.092714 -vn 0.990994 0.090666 -0.098545 -v 0.056453 0.094033 0.092431 -vn 0.990995 0.082215 -0.105691 -v 0.056453 0.093727 0.092172 -vn 0.990993 0.073212 -0.112129 -v 0.056453 0.093401 0.091939 -vn 0.990993 0.063702 -0.117790 -v 0.056453 0.093056 0.091734 -vn 0.990994 0.053756 -0.122643 -v 0.056453 0.092696 0.091558 -vn 0.990994 0.043444 -0.126665 -v 0.056453 0.092323 0.091412 -vn 0.990993 0.032838 -0.129822 -v 0.056453 0.091938 0.091298 -vn 0.990993 0.022006 -0.132097 -v 0.056453 0.091546 0.091216 -vn 0.990993 0.011021 -0.133460 -v 0.056453 0.091148 0.091166 -vn 0.990993 -0.000037 -0.133914 -v 0.056453 0.090748 0.091150 -vn 0.715219 -0.687628 -0.125020 -v 0.056453 0.094780 0.096752 -vn 0.715390 -0.698711 -0.004427 -v 0.056453 0.094849 0.095999 -vn 0.715807 -0.685460 0.133288 -v 0.056453 0.094779 0.095245 -vn 0.716823 -0.649157 -0.254481 -v 0.056453 0.094573 0.097480 -vn 0.714908 -0.595500 -0.366450 -v 0.056453 0.094236 0.098157 -vn 0.714983 -0.652940 0.249937 -v 0.056453 0.094572 0.094518 -vn 0.718897 0.591442 0.365217 -v 0.056453 0.087263 0.093843 -vn 0.714875 0.517122 0.470679 -v 0.056453 0.087718 0.093239 -vn 0.715127 0.687789 -0.124663 -v 0.056453 0.086719 0.096754 -vn 0.715431 0.698669 -0.004493 -v 0.056453 0.086649 0.096001 -vn 0.716495 0.648702 -0.256555 -v 0.056453 0.086926 0.097482 -vn 0.717653 0.311586 -0.622807 -v 0.056453 0.088923 0.099671 -vn 0.714883 0.420392 -0.558760 -v 0.056453 0.088279 0.099273 -vn 0.715589 -0.069287 -0.695077 -v 0.056453 0.091129 0.100082 -vn 0.720867 -0.511848 -0.467293 -v 0.056453 0.093780 0.098761 -vn 0.715237 0.060304 0.696276 -v 0.056453 0.090370 0.091918 -vn 0.715308 -0.060481 0.696187 -v 0.056453 0.091126 0.091917 -vn 0.714910 0.595298 -0.366776 -v 0.056453 0.087264 0.098159 -vn 0.720864 0.511587 -0.467584 -v 0.056453 0.087720 0.098763 -vn 0.715583 0.068906 -0.695121 -v 0.056453 0.090372 0.100083 -vn 0.715049 -0.188073 -0.673301 -v 0.056453 0.091872 0.099943 -vn 0.714889 -0.420696 -0.558524 -v 0.056453 0.093221 0.099271 -vn 0.717944 -0.589997 0.369405 -v 0.056453 0.094234 0.093841 -vn 0.714874 -0.516859 0.470970 -v 0.056453 0.093778 0.093237 -vn 0.720740 -0.414796 0.555409 -v 0.056453 0.093219 0.092727 -vn 0.715054 -0.310309 0.626423 -v 0.056453 0.092576 0.092329 -vn 0.715146 0.188557 -0.673062 -v 0.056453 0.089628 0.099944 -vn 0.716261 -0.194561 0.670161 -v 0.056453 0.091870 0.092056 -vn 0.716092 0.195919 0.669947 -v 0.056453 0.089626 0.092057 -vn 0.715095 0.652596 0.250513 -v 0.056453 0.086926 0.094520 -vn 0.715866 0.685553 0.132485 -v 0.056453 0.086719 0.095248 -vn 0.717087 -0.314571 -0.621958 -v 0.056453 0.092578 0.099670 -vn 0.714941 0.309685 0.626861 -v 0.056453 0.088921 0.092330 -vn 0.719156 0.420577 0.553109 -v 0.056453 0.088277 0.092729 -vn -0.657669 0.748501 0.084957 -v 0.056383 0.086702 0.095347 -vn -0.670123 0.740002 0.057725 -v 0.056383 0.086651 0.095870 -vn -0.701620 0.637289 0.318735 -v 0.056383 0.087000 0.094341 -vn -0.609952 0.741766 0.278822 -v 0.056383 0.086926 0.094520 -vn -0.702608 0.684036 0.196054 -v 0.056383 0.086818 0.094835 -vn -0.614348 0.772243 0.161917 -v 0.056383 0.086719 0.095248 -vn -0.635873 0.678592 0.367667 -v 0.056383 0.087242 0.093876 -vn -0.618451 0.655952 0.432719 -v 0.056383 0.087263 0.093843 -vn -0.697014 0.570042 0.434998 -v 0.056383 0.087543 0.093445 -vn -0.608912 0.586939 0.533600 -v 0.056383 0.087718 0.093239 -vn -0.694803 0.487777 0.528509 -v 0.056383 0.087896 0.093056 -vn -0.619241 0.492432 0.611598 -v 0.056383 0.088277 0.092729 -vn -0.609532 0.348150 0.712223 -v 0.056383 0.088921 0.092330 -vn -0.686835 0.377054 0.621360 -v 0.056383 0.088736 0.092428 -vn -0.626120 0.443627 0.641225 -v 0.056383 0.088296 0.092715 -vn -0.701309 0.258983 0.664149 -v 0.056383 0.089209 0.092200 -vn -0.613783 0.235764 0.753449 -v 0.056383 0.089626 0.092057 -vn -0.611782 0.060496 0.788710 -v 0.056383 0.090370 0.091918 -vn -0.671997 0.125385 0.729862 -v 0.056383 0.090224 0.091934 -vn -0.648784 0.160919 0.743764 -v 0.056383 0.089708 0.092034 -vn -0.703355 -0.001063 0.710837 -v 0.056383 0.090748 0.091900 -vn -0.606863 -0.057647 0.792713 -v 0.056383 0.091126 0.091917 -vn -0.652373 -0.156522 0.741560 -v 0.056383 0.091788 0.092034 -vn -0.677752 -0.127639 0.724128 -v 0.056383 0.091272 0.091934 -vn -0.709847 -0.374167 0.596755 -v 0.056383 0.092760 0.092427 -vn -0.609537 -0.347742 0.712418 -v 0.056383 0.092576 0.092329 -vn -0.701621 -0.259188 0.663740 -v 0.056383 0.092287 0.092199 -vn -0.615339 -0.233674 0.752831 -v 0.056383 0.091870 0.092056 -vn -0.630761 -0.434550 0.642889 -v 0.056383 0.093200 0.092714 -vn -0.619387 -0.491840 0.611926 -v 0.056383 0.093219 0.092727 -vn -0.694896 -0.487566 0.528583 -v 0.056383 0.093601 0.093054 -vn -0.608904 -0.586646 0.533931 -v 0.056383 0.093778 0.093237 -vn -0.696874 -0.570109 0.435134 -v 0.056383 0.093954 0.093443 -vn -0.618096 -0.655677 0.433642 -v 0.056383 0.094234 0.093841 -vn -0.609961 -0.741604 0.279233 -v 0.056383 0.094572 0.094518 -vn -0.683594 -0.656652 0.318601 -v 0.056383 0.094498 0.094339 -vn -0.630831 -0.678481 0.376452 -v 0.056383 0.094255 0.093874 -vn -0.702236 -0.684516 0.195712 -v 0.056383 0.094679 0.094832 -vn -0.612171 -0.773461 0.164333 -v 0.056383 0.094779 0.095245 -vn -0.612555 -0.790301 -0.014158 -v 0.056383 0.094849 0.095999 -vn -0.667498 -0.742463 0.056529 -v 0.056383 0.094847 0.095867 -vn -0.655580 -0.750061 0.087307 -v 0.056383 0.094796 0.095345 -vn -0.703123 -0.707874 -0.067321 -v 0.056383 0.094830 0.096393 -vn -0.604934 -0.785248 -0.132062 -v 0.056383 0.094780 0.096752 -vn -0.646901 -0.727717 -0.227920 -v 0.056383 0.094597 0.097415 -vn -0.685565 -0.701443 -0.194880 -v 0.056383 0.094747 0.096911 -vn -0.700363 -0.637856 -0.320361 -v 0.056383 0.094385 0.097895 -vn -0.616367 -0.726773 -0.303138 -v 0.056383 0.094573 0.097480 -vn -0.620286 -0.562893 -0.546257 -v 0.056383 0.093780 0.098761 -vn -0.622185 -0.597074 -0.506347 -v 0.056383 0.093785 0.098756 -vn -0.689789 -0.581380 -0.431495 -v 0.056383 0.094113 0.098345 -vn -0.609223 -0.676598 -0.413598 -v 0.056383 0.094236 0.098157 -vn -0.692480 -0.482435 -0.536403 -v 0.056383 0.093408 0.099121 -vn -0.609014 -0.476085 -0.634386 -v 0.056383 0.093221 0.099271 -vn -0.698624 -0.379163 -0.606762 -v 0.056383 0.092987 0.099436 -vn -0.616769 -0.370996 -0.694232 -v 0.056383 0.092578 0.099670 -vn -0.610466 -0.207872 -0.764278 -v 0.056383 0.091872 0.099943 -vn -0.680030 -0.256899 -0.686704 -v 0.056383 0.092042 0.099891 -vn -0.636313 -0.306352 -0.707994 -v 0.056383 0.092529 0.099693 -vn -0.702860 -0.130946 -0.699172 -v 0.056383 0.091534 0.100024 -vn -0.610470 -0.091219 -0.786769 -v 0.056383 0.091129 0.100082 -vn -0.613424 0.088538 -0.784776 -v 0.056383 0.090372 0.100083 -vn -0.662756 0.013768 -0.748708 -v 0.056383 0.090488 0.100092 -vn -0.662734 -0.014179 -0.748721 -v 0.056383 0.091013 0.100091 -vn -0.703294 0.131459 -0.698639 -v 0.056383 0.089967 0.100025 -vn -0.610466 0.207439 -0.764395 -v 0.056383 0.089628 0.099944 -vn -0.641349 0.298532 -0.706788 -v 0.056383 0.088971 0.099694 -vn -0.693545 0.258775 -0.672333 -v 0.056383 0.089458 0.099891 -vn -0.698839 0.379117 -0.606543 -v 0.056383 0.088513 0.099437 -vn -0.617414 0.369684 -0.694359 -v 0.056383 0.088923 0.099671 -vn -0.622202 0.596747 -0.506713 -v 0.056383 0.087715 0.098757 -vn -0.620233 0.562523 -0.546699 -v 0.056383 0.087720 0.098763 -vn -0.692461 0.482194 -0.536645 -v 0.056383 0.088092 0.099123 -vn -0.609019 0.475735 -0.634643 -v 0.056383 0.088279 0.099273 -vn -0.689790 0.581139 -0.431818 -v 0.056383 0.087387 0.098347 -vn -0.609224 0.676370 -0.413970 -v 0.056383 0.087264 0.098159 -vn -0.700114 0.638166 -0.320288 -v 0.056383 0.087115 0.097897 -vn -0.615327 0.726934 -0.304859 -v 0.056383 0.086926 0.097482 -vn -0.676190 0.711179 -0.192330 -v 0.056383 0.086752 0.096913 -vn -0.642348 0.729747 -0.234219 -v 0.056383 0.086902 0.097417 -vn -0.608683 0.793231 -0.017008 -v 0.056383 0.086649 0.096001 -vn -0.703239 0.707958 -0.065191 -v 0.056383 0.086668 0.096395 -vn -0.611081 0.780019 -0.134725 -v 0.056383 0.086719 0.096754 -vn 0.951033 0.137018 0.277059 -v 0.056105 0.088794 0.092369 -vn 0.955044 0.152450 0.254263 -v 0.056105 0.088724 0.092407 -vn 0.777825 0.310826 0.546238 -v 0.056133 0.088694 0.092352 -vn 0.949931 0.312374 -0.007371 -v 0.056105 0.086625 0.096001 -vn 0.955326 0.294276 -0.027470 -v 0.056105 0.086644 0.096397 -vn 0.778044 0.625342 -0.059964 -v 0.056133 0.086582 0.096403 -vn 0.949931 0.188998 -0.248820 -v 0.056105 0.088179 0.099225 -vn 0.955221 0.161571 -0.247886 -v 0.056105 0.088500 0.099457 -vn 0.778048 0.343008 -0.526295 -v 0.056133 0.088466 0.099510 -vn 0.950083 -0.076157 -0.302560 -v 0.056105 0.091668 0.100021 -vn 0.954878 -0.092612 -0.282189 -v 0.056105 0.092050 0.099914 -vn 0.778036 -0.197612 -0.596331 -v 0.056133 0.092070 0.099973 -vn 0.949921 -0.284671 -0.128891 -v 0.056105 0.094466 0.097788 -vn 0.955173 -0.277462 -0.103249 -v 0.056105 0.094620 0.097423 -vn 0.778032 -0.589444 -0.217308 -v 0.056133 0.094679 0.097445 -vn 0.949830 -0.278624 0.142100 -v 0.056105 0.094465 0.094209 -vn 0.955666 -0.251561 0.153031 -v 0.056105 0.094275 0.093861 -vn 0.778036 -0.537405 0.325355 -v 0.056133 0.094329 0.093829 -vn 0.948457 -0.018845 0.316345 -v 0.056105 0.090933 0.091880 -vn 0.954803 0.005883 0.297180 -v 0.056105 0.090748 0.091876 -vn 0.777977 0.003400 0.628284 -v 0.056133 0.090748 0.091813 -vn -0.875352 0.463701 0.136892 -v 0.056366 0.086755 0.094816 -vn -0.875301 0.441477 0.197347 -v 0.056366 0.086939 0.094315 -vn -0.545000 0.766770 0.339173 -v 0.056320 0.086893 0.094294 -vn -0.875217 0.121290 0.468277 -v 0.056366 0.089691 0.091970 -vn -0.875552 0.180221 0.448250 -v 0.056366 0.089185 0.092138 -vn -0.875584 0.288534 0.387428 -v 0.056366 0.088256 0.092662 -vn -0.875187 0.477906 0.075192 -v 0.056366 0.086636 0.095336 -vn -0.875227 0.471112 -0.109684 -v 0.056366 0.086687 0.096928 -vn -0.875361 0.395436 -0.278161 -v 0.056366 0.087333 0.098385 -vn -0.875358 0.262701 -0.405878 -v 0.056366 0.088477 0.099492 -vn -0.875263 0.208418 -0.436436 -v 0.056366 0.088942 0.099754 -vn -0.875374 0.091915 -0.474628 -v 0.056366 0.089954 0.100090 -vn -0.875180 0.028904 -0.482934 -v 0.056366 0.090483 0.100158 -vn -0.875269 -0.154357 -0.458343 -v 0.056366 0.092063 0.099954 -vn -0.875367 -0.314750 -0.366967 -v 0.056366 0.093451 0.099172 -vn -0.875826 -0.357546 -0.324175 -v 0.056366 0.093834 0.098800 -vn -0.875364 -0.429134 -0.222669 -v 0.056366 0.094444 0.097926 -vn -0.875217 -0.454585 -0.165374 -v 0.056366 0.094660 0.097438 -vn -0.875204 -0.483432 0.017625 -v 0.056366 0.094913 0.095865 -vn -0.875296 -0.441376 0.197596 -v 0.056366 0.094559 0.094312 -vn -0.875372 -0.335168 0.348405 -v 0.056366 0.093647 0.093006 -vn -0.875551 -0.288260 0.387707 -v 0.056366 0.093240 0.092660 -vn -0.875375 -0.180600 0.448444 -v 0.056366 0.092312 0.092138 -vn -0.875187 -0.120828 0.468453 -v 0.056366 0.091805 0.091970 -vn -0.875235 -0.063475 0.479515 -v 0.056366 0.091281 0.091868 -vn -0.875410 -0.413796 0.249858 -v 0.056366 0.094311 0.093839 -vn -0.875214 -0.477781 0.075671 -v 0.056366 0.094862 0.095334 -vn -0.875255 -0.471173 -0.109202 -v 0.056366 0.094811 0.096926 -vn -0.875309 -0.208803 -0.436160 -v 0.056366 0.092558 0.099753 -vn -0.875213 -0.029393 -0.482844 -v 0.056366 0.091017 0.100158 -vn -0.875849 0.357301 -0.324383 -v 0.056366 0.087666 0.098802 -vn -0.875238 0.454383 -0.165817 -v 0.056366 0.086839 0.097440 -vn -0.875228 0.483408 0.017136 -v 0.056366 0.086585 0.095868 -vn -0.875370 0.414084 0.249523 -v 0.056366 0.087186 0.093841 -vn -0.875366 0.378876 0.300311 -v 0.056366 0.087491 0.093403 -vn -0.875328 0.238988 0.420340 -v 0.056366 0.088704 0.092370 -vn -0.875217 0.063961 0.479483 -v 0.056366 0.090215 0.091868 -vn -0.086302 0.852094 0.516224 -v 0.056255 0.087123 0.093803 -vn -0.544943 0.717138 0.434454 -v 0.056320 0.087142 0.093815 -vn 0.392478 0.719258 0.573262 -v 0.056188 0.087442 0.093364 -vn -0.086290 0.779090 0.620945 -v 0.056255 0.087434 0.093358 -vn -0.544944 0.655690 0.522596 -v 0.056320 0.087451 0.093372 -vn 0.778032 -0.080695 0.623020 -v 0.056133 0.091283 0.091847 -vn 0.392509 0.000258 0.919748 -v 0.056188 0.090748 0.091771 -vn 0.392467 -0.117369 0.912247 -v 0.056188 0.091289 0.091806 -vn -0.086335 0.000271 0.996266 -v 0.056255 0.090748 0.091761 -vn -0.086326 -0.127129 0.988122 -v 0.056255 0.091290 0.091795 -vn -0.544975 0.000233 0.838452 -v 0.056320 0.090748 0.091783 -vn 0.778051 0.436771 0.451518 -v 0.056133 0.087836 0.092993 -vn 0.392474 0.640048 0.660532 -v 0.056188 0.087807 0.092963 -vn -0.086340 0.693281 0.715477 -v 0.056255 0.087799 0.092955 -vn -0.544973 0.583466 0.602140 -v 0.056320 0.087815 0.092972 -vn -0.875423 0.335188 0.348257 -v 0.056366 0.087850 0.093008 -vn 0.777854 -0.233252 0.583555 -v 0.056133 0.092319 0.092119 -vn 0.777791 -0.162490 0.607155 -v 0.056133 0.091810 0.091950 -vn 0.392490 -0.233051 0.889741 -v 0.056188 0.091821 0.091909 -vn -0.544961 -0.212452 0.811099 -v 0.056320 0.091818 0.091921 -vn -0.544967 -0.314428 0.777268 -v 0.056320 0.092331 0.092091 -vn -0.086308 -0.373609 0.923562 -v 0.056255 0.092339 0.092070 -vn -0.086270 -0.488646 0.868206 -v 0.056255 0.092829 0.092305 -vn 0.392484 -0.451118 0.801529 -v 0.056188 0.092823 0.092315 -vn 0.392474 -0.549914 0.737265 -v 0.056188 0.093277 0.092610 -vn 0.778061 -0.377670 0.501983 -v 0.056133 0.093252 0.092644 -vn 0.778473 -0.437548 0.450034 -v 0.056133 0.093661 0.092992 -vn -0.544960 -0.411245 0.730682 -v 0.056320 0.092817 0.092325 -vn -0.086326 -0.595657 0.798587 -v 0.056255 0.093284 0.092602 -vn 0.392502 -0.639670 0.660882 -v 0.056188 0.093690 0.092962 -vn 0.777963 -0.489105 0.394398 -v 0.056133 0.094022 0.093389 -vn 0.954954 -0.227932 0.190025 -v 0.056105 0.093973 0.093428 -vn 0.948661 -0.258999 0.181554 -v 0.056105 0.094085 0.093575 -vn -0.544975 -0.583127 0.602466 -v 0.056320 0.093682 0.092970 -vn -0.544974 -0.655385 0.522948 -v 0.056320 0.094045 0.093370 -vn -0.086320 -0.778740 0.621380 -v 0.056255 0.094063 0.093356 -vn -0.086301 -0.851807 0.516697 -v 0.056255 0.094374 0.093801 -vn 0.392496 -0.786387 0.477015 -v 0.056188 0.094365 0.093807 -vn 0.392477 -0.840940 0.372536 -v 0.056188 0.094615 0.094287 -vn 0.777798 -0.575997 0.251512 -v 0.056133 0.094577 0.094304 -vn 0.777832 -0.601699 0.181481 -v 0.056133 0.094763 0.094808 -vn -0.544963 -0.766604 0.339607 -v 0.056320 0.094605 0.094292 -vn -0.544971 -0.803732 0.238791 -v 0.056320 0.094791 0.094799 -vn -0.086305 -0.955011 0.283734 -v 0.056255 0.094813 0.094793 -vn -0.086281 -0.983455 0.159285 -v 0.056255 0.094934 0.095322 -vn 0.392520 -0.907913 0.147046 -v 0.056188 0.094923 0.095324 -vn 0.392497 -0.919272 0.029735 -v 0.056188 0.094975 0.095863 -vn 0.778076 -0.627921 0.017710 -v 0.056133 0.094934 0.095865 -vn 0.778462 -0.624671 -0.061502 -v 0.056133 0.094917 0.096401 -vn -0.875585 -0.463403 0.136415 -v 0.056366 0.094743 0.094813 -vn -0.544975 -0.827667 0.134047 -v 0.056320 0.094912 0.095326 -vn -0.086328 -0.995746 0.032204 -v 0.056255 0.094986 0.095863 -vn 0.392489 -0.915531 -0.088061 -v 0.056188 0.094958 0.096405 -vn 0.777965 -0.613303 -0.136490 -v 0.056133 0.094831 0.096931 -vn 0.955198 -0.289927 -0.059495 -v 0.056105 0.094770 0.096917 -vn 0.948344 -0.304626 -0.088579 -v 0.056105 0.094725 0.097096 -vn -0.875744 -0.480477 -0.047062 -v 0.056366 0.094896 0.096399 -vn -0.544964 -0.834607 -0.080277 -v 0.056320 0.094947 0.096404 -vn -0.544954 -0.817497 -0.186346 -v 0.056320 0.094861 0.096937 -vn -0.086333 -0.971348 -0.221424 -v 0.056255 0.094883 0.096942 -vn -0.086303 -0.935063 -0.343816 -v 0.056255 0.094728 0.097463 -vn 0.392476 -0.863256 -0.317414 -v 0.056188 0.094718 0.097459 -vn 0.392482 -0.815576 -0.425199 -v 0.056188 0.094499 0.097955 -vn 0.777790 -0.555776 -0.293524 -v 0.056133 0.094462 0.097936 -vn 0.777838 -0.517036 -0.357270 -v 0.056133 0.094184 0.098394 -vn -0.544945 -0.743497 -0.387617 -v 0.056320 0.094488 0.097949 -vn -0.544968 -0.687812 -0.479504 -v 0.056320 0.094208 0.098412 -vn -0.086300 -0.817272 -0.569753 -v 0.056255 0.094227 0.098424 -vn -0.086314 -0.737701 -0.669588 -v 0.056255 0.093888 0.098849 -vn 0.392495 -0.681046 -0.618162 -v 0.056188 0.093880 0.098842 -vn 0.392502 -0.596408 -0.700171 -v 0.056188 0.093491 0.099219 -vn 0.778048 -0.405369 -0.479915 -v 0.056133 0.093464 0.099187 -vn 0.778460 -0.341392 -0.526737 -v 0.056133 0.093034 0.099508 -vn -0.875361 -0.395590 -0.277943 -v 0.056366 0.094167 0.098383 -vn -0.544967 -0.620850 -0.563522 -v 0.056320 0.093872 0.098834 -vn -0.086297 -0.646021 -0.758426 -v 0.056255 0.093498 0.099227 -vn 0.392453 -0.501980 -0.770712 -v 0.056188 0.093057 0.099543 -vn 0.777968 -0.275669 -0.564598 -v 0.056133 0.092567 0.099772 -vn 0.955480 -0.134482 -0.262627 -v 0.056105 0.092540 0.099715 -vn 0.948372 -0.120608 -0.293334 -v 0.056105 0.092371 0.099792 -vn -0.875487 -0.262503 -0.405728 -v 0.056366 0.093023 0.099491 -vn -0.544952 -0.457608 -0.702582 -v 0.056320 0.093051 0.099534 -vn -0.544964 -0.364004 -0.755325 -v 0.056320 0.092580 0.099799 -vn -0.086295 -0.432517 -0.897487 -v 0.056255 0.092590 0.099819 -vn -0.086296 -0.314194 -0.945429 -v 0.056255 0.092086 0.100023 -vn 0.392501 -0.290065 -0.872815 -v 0.056188 0.092083 0.100013 -vn 0.392505 -0.176068 -0.902740 -v 0.056188 0.091559 0.100150 -vn 0.777789 -0.117034 -0.617533 -v 0.056133 0.091551 0.100109 -vn 0.777850 -0.043046 -0.626974 -v 0.056133 0.091019 0.100178 -vn -0.875628 -0.091360 -0.474267 -v 0.056366 0.091547 0.100089 -vn -0.544980 -0.160506 -0.822943 -v 0.056320 0.091556 0.100139 -vn -0.544949 -0.053957 -0.836732 -v 0.056320 0.091021 0.100208 -vn -0.086295 -0.064114 -0.994205 -v 0.056255 0.091022 0.100231 -vn -0.086289 0.063555 -0.994241 -v 0.056255 0.090479 0.100231 -vn 0.392498 0.058672 -0.917880 -v 0.056188 0.090479 0.100220 -vn 0.392513 0.175568 -0.902834 -v 0.056188 0.089942 0.100151 -vn 0.778051 0.122468 -0.616148 -v 0.056133 0.089950 0.100110 -vn 0.778459 0.198957 -0.595330 -v 0.056133 0.089431 0.099974 -vn -0.544977 0.053485 -0.836744 -v 0.056320 0.090480 0.100208 -vn -0.086267 0.190168 -0.977954 -v 0.056255 0.089940 0.100162 -vn 0.392521 0.289574 -0.872969 -v 0.056188 0.089418 0.100013 -vn 0.777959 0.269550 -0.567558 -v 0.056133 0.088934 0.099773 -vn 0.954811 0.123472 -0.270353 -v 0.056105 0.088961 0.099716 -vn 0.948560 0.154384 -0.276405 -v 0.056105 0.088796 0.099632 -vn -0.875260 0.154106 -0.458444 -v 0.056366 0.089437 0.099955 -vn -0.544999 0.263982 -0.795795 -v 0.056320 0.089421 0.100002 -vn -0.544953 0.363586 -0.755534 -v 0.056320 0.088921 0.099800 -vn -0.086322 0.432014 -0.897726 -v 0.056255 0.088911 0.099820 -vn -0.086317 0.543266 -0.835112 -v 0.056255 0.088437 0.099554 -vn 0.392493 0.501541 -0.770977 -v 0.056188 0.088443 0.099545 -vn 0.392479 0.596022 -0.700512 -v 0.056188 0.088009 0.099221 -vn 0.777792 0.409835 -0.476524 -v 0.056133 0.088036 0.099189 -vn 0.777843 0.463359 -0.424569 -v 0.056133 0.087651 0.098816 -vn -0.875390 0.314558 -0.367077 -v 0.056366 0.088049 0.099173 -vn -0.544976 0.543332 -0.638586 -v 0.056320 0.088016 0.099212 -vn -0.544948 0.620543 -0.563877 -v 0.056320 0.087628 0.098836 -vn -0.086314 0.737326 -0.670000 -v 0.056255 0.087612 0.098851 -vn -0.086328 0.816951 -0.570210 -v 0.056255 0.087273 0.098426 -vn 0.392504 0.754207 -0.526415 -v 0.056188 0.087282 0.098420 -vn 0.392473 0.815344 -0.425653 -v 0.056188 0.087001 0.097957 -vn 0.778049 0.558084 -0.288415 -v 0.056133 0.087038 0.097938 -vn 0.778451 0.589507 -0.215627 -v 0.056133 0.086820 0.097447 -vn -0.544985 0.687540 -0.479876 -v 0.056320 0.087291 0.098414 -vn -0.086323 0.883161 -0.461058 -v 0.056255 0.086991 0.097962 -vn 0.392481 0.863077 -0.317894 -v 0.056188 0.086781 0.097461 -vn 0.777970 0.611783 -0.143122 -v 0.056133 0.086668 0.096933 -vn 0.955117 0.287260 -0.072339 -v 0.056105 0.086728 0.096919 -vn 0.948386 0.312799 -0.052154 -v 0.056105 0.086691 0.096738 -vn -0.875517 0.428972 -0.222382 -v 0.056366 0.087056 0.097928 -vn -0.544974 0.786782 -0.289789 -v 0.056320 0.086792 0.097457 -vn -0.544953 0.817393 -0.186803 -v 0.056320 0.086638 0.096939 -vn -0.086347 0.971225 -0.221959 -v 0.056255 0.086616 0.096945 -vn -0.086348 0.991635 -0.095939 -v 0.056255 0.086529 0.096408 -vn 0.392466 0.915492 -0.088575 -v 0.056188 0.086540 0.096407 -vn 0.392455 0.919307 0.029225 -v 0.056188 0.086523 0.095866 -vn 0.777781 0.628103 0.023318 -v 0.056133 0.086564 0.095867 -vn 0.777846 0.620836 0.097557 -v 0.056133 0.086616 0.095333 -vn -0.875650 0.480801 -0.045484 -v 0.056366 0.086602 0.096401 -vn -0.544968 0.838034 0.026641 -v 0.056320 0.086534 0.095866 -vn -0.544978 0.827740 0.133587 -v 0.056320 0.086586 0.095328 -vn -0.086329 0.983540 0.158731 -v 0.056255 0.086564 0.095325 -vn -0.086293 0.955172 0.283198 -v 0.056255 0.086685 0.094795 -vn 0.392494 0.881813 0.261447 -v 0.056188 0.086695 0.094798 -vn 0.392510 0.841134 0.372061 -v 0.056188 0.086882 0.094289 -vn 0.778067 0.573432 0.256493 -v 0.056133 0.086920 0.094306 -vn 0.778449 0.536140 0.326452 -v 0.056133 0.087168 0.093831 -vn -0.544955 0.803878 0.238337 -v 0.056320 0.086706 0.094801 -vn -0.086329 0.911110 0.403021 -v 0.056255 0.086872 0.094285 -vn 0.392475 0.786659 0.476582 -v 0.056188 0.087133 0.093809 -vn 0.777958 0.493351 0.389084 -v 0.056133 0.087475 0.093390 -vn 0.955038 0.235594 0.179996 -v 0.056105 0.087524 0.093429 -vn 0.948326 0.236114 0.211962 -v 0.056105 0.087642 0.093287 -vn 0.954947 -0.038608 0.294255 -v 0.056105 0.091275 0.091909 -vn 0.949929 -0.062323 0.306188 -v 0.056105 0.091666 0.091979 -vn 0.947606 -0.174604 0.267500 -v 0.056105 0.093020 0.092557 -vn 0.954761 -0.142314 0.261110 -v 0.056105 0.092772 0.092406 -vn 0.778418 -0.305758 0.548249 -v 0.056133 0.092803 0.092351 -vn 0.392485 -0.344920 0.852635 -v 0.056188 0.092335 0.092080 -vn -0.086324 -0.252437 0.963755 -v 0.056255 0.091823 0.091899 -vn -0.544949 -0.106988 0.831615 -v 0.056320 0.091287 0.091817 -vn -0.875689 -0.000800 0.482874 -v 0.056366 0.090748 0.091834 -vn 0.951178 -0.131410 0.279271 -v 0.056105 0.092369 0.092207 -vn 0.954890 -0.104189 0.278082 -v 0.056105 0.092296 0.092177 -vn 0.954914 -0.081795 0.285391 -v 0.056105 0.091794 0.092010 -vn 0.955146 -0.212473 0.206279 -v 0.056105 0.093618 0.093036 -vn 0.954083 -0.199944 0.223041 -v 0.056105 0.093598 0.093018 -vn 0.954932 -0.181015 0.235241 -v 0.056105 0.093215 0.092694 -vn -0.875332 -0.238751 0.420466 -v 0.056366 0.092793 0.092369 -vn -0.544967 -0.501302 0.672092 -v 0.056320 0.093270 0.092620 -vn -0.086342 -0.692889 0.715856 -v 0.056255 0.093698 0.092954 -vn 0.392486 -0.718939 0.573657 -v 0.056188 0.094054 0.093363 -vn 0.947587 -0.318063 0.030231 -v 0.056105 0.094857 0.095629 -vn 0.955055 -0.291948 0.051356 -v 0.056105 0.094820 0.095341 -vn 0.778427 -0.619265 0.102775 -v 0.056133 0.094882 0.095331 -vn 0.392499 -0.881664 0.261941 -v 0.056188 0.094803 0.094796 -vn -0.086350 -0.910887 0.403520 -v 0.056255 0.094625 0.094283 -vn -0.544975 -0.716875 0.434846 -v 0.056320 0.094355 0.093813 -vn -0.875452 -0.378744 0.300229 -v 0.056366 0.094006 0.093401 -vn 0.951140 -0.300360 0.071529 -v 0.056105 0.094725 0.094902 -vn 0.955053 -0.281716 0.092253 -v 0.056105 0.094703 0.094825 -vn 0.955169 -0.273589 0.113139 -v 0.056105 0.094520 0.094329 -vn 0.955103 -0.293897 -0.037446 -v 0.056105 0.094855 0.096395 -vn 0.954237 -0.298580 -0.016811 -v 0.056105 0.094857 0.096369 -vn 0.955243 -0.295786 0.004600 -v 0.056105 0.094871 0.095867 -vn -0.544973 -0.838015 0.027103 -v 0.056320 0.094964 0.095864 -vn -0.086295 -0.991692 -0.095392 -v 0.056255 0.094969 0.096406 -vn 0.392465 -0.896763 -0.204418 -v 0.056188 0.094872 0.096940 -vn 0.947586 -0.222019 -0.229756 -v 0.056105 0.093600 0.098980 -vn 0.955705 -0.221389 -0.193946 -v 0.056105 0.093803 0.098772 -vn 0.778429 -0.466456 -0.420079 -v 0.056133 0.093849 0.098814 -vn 0.392484 -0.754508 -0.525999 -v 0.056188 0.094218 0.098418 -vn -0.086300 -0.883419 -0.460568 -v 0.056255 0.094508 0.097960 -vn -0.544967 -0.786946 -0.289355 -v 0.056320 0.094707 0.097455 -vn 0.951214 -0.242619 -0.190599 -v 0.056105 0.094086 0.098423 -vn 0.955156 -0.247552 -0.162466 -v 0.056105 0.094132 0.098359 -vn 0.954998 -0.259558 -0.143557 -v 0.056105 0.094406 0.097907 -vn 0.955324 -0.153728 -0.252436 -v 0.056105 0.093000 0.099456 -vn 0.954376 -0.172454 -0.243775 -v 0.056105 0.093022 0.099441 -vn 0.954885 -0.188808 -0.229228 -v 0.056105 0.093424 0.099140 -vn -0.544961 -0.543691 -0.638292 -v 0.056320 0.093484 0.099210 -vn -0.086346 -0.543726 -0.834809 -v 0.056255 0.093063 0.099552 -vn 0.392491 -0.399297 -0.828561 -v 0.056188 0.092585 0.099809 -vn 0.947770 0.041659 -0.316222 -v 0.056105 0.090197 0.100087 -vn 0.954646 0.015338 -0.297347 -v 0.056105 0.090486 0.100116 -vn 0.778415 0.037604 -0.626623 -v 0.056133 0.090482 0.100178 -vn 0.392497 -0.059183 -0.917847 -v 0.056188 0.091021 0.100220 -vn -0.086317 -0.190717 -0.977843 -v 0.056255 0.091561 0.100161 -vn -0.544981 -0.264423 -0.795661 -v 0.056320 0.092079 0.100002 -vn 0.951091 -0.003065 -0.308897 -v 0.056105 0.090935 0.100120 -vn 0.955220 -0.027514 -0.294616 -v 0.056105 0.091015 0.100116 -vn 0.955211 -0.050057 -0.291660 -v 0.056105 0.091539 0.100048 -vn 0.955049 0.101728 -0.278446 -v 0.056105 0.089451 0.099915 -vn 0.954239 0.082795 -0.287354 -v 0.056105 0.089476 0.099923 -vn 0.955143 0.060545 -0.289888 -v 0.056105 0.089962 0.100048 -vn -0.544976 0.160051 -0.823034 -v 0.056320 0.089944 0.100139 -vn -0.086344 0.313673 -0.945597 -v 0.056255 0.089414 0.100024 -vn 0.392459 0.398848 -0.828792 -v 0.056188 0.088916 0.099810 -vn 0.947614 0.273357 -0.165242 -v 0.056105 0.087209 0.098116 -vn 0.955069 0.240404 -0.173349 -v 0.056105 0.087367 0.098361 -vn 0.778441 0.513332 -0.361277 -v 0.056133 0.087316 0.098396 -vn 0.392480 0.680707 -0.618545 -v 0.056188 0.087620 0.098844 -vn -0.086334 0.645597 -0.758782 -v 0.056255 0.088002 0.099229 -vn -0.544950 0.457216 -0.702839 -v 0.056320 0.088450 0.099535 -vn 0.951268 0.239575 -0.194146 -v 0.056105 0.087644 0.098714 -vn 0.954907 0.214386 -0.205406 -v 0.056105 0.087697 0.098774 -vn 0.955040 0.197431 -0.221178 -v 0.056105 0.088077 0.099141 -vn 0.955156 0.280909 -0.093636 -v 0.056105 0.086879 0.097425 -vn 0.954129 0.276732 -0.114271 -v 0.056105 0.086888 0.097450 -vn 0.955096 0.264791 -0.132953 -v 0.056105 0.087093 0.097909 -vn -0.544974 0.743265 -0.388022 -v 0.056320 0.087011 0.097952 -vn -0.086337 0.934869 -0.344335 -v 0.056255 0.086771 0.097465 -vn 0.392491 0.896638 -0.204917 -v 0.056188 0.086627 0.096942 -vn 0.947567 0.299791 0.110646 -v 0.056105 0.086887 0.094552 -vn 0.955701 0.283625 0.078688 -v 0.056105 0.086795 0.094828 -vn 0.778418 0.602540 0.176100 -v 0.056133 0.086735 0.094810 -vn 0.392473 0.908014 0.146545 -v 0.056188 0.086575 0.095326 -vn -0.086326 0.995764 0.031655 -v 0.056255 0.086512 0.095865 -vn -0.544963 0.834563 -0.080742 -v 0.056320 0.086552 0.096406 -vn 0.951327 0.300903 0.066598 -v 0.056105 0.086691 0.095265 -vn 0.955218 0.293356 0.038745 -v 0.056105 0.086678 0.095343 -vn 0.955264 0.295265 0.017004 -v 0.056105 0.086627 0.095869 -vn 0.955022 0.249044 0.160969 -v 0.056105 0.087222 0.093863 -vn 0.954288 0.261538 0.144681 -v 0.056105 0.087208 0.093886 -vn 0.955038 0.269064 0.124524 -v 0.056105 0.086977 0.094332 -vn 0.954971 0.205569 0.213945 -v 0.056105 0.087879 0.093038 -vn 0.777778 0.373390 0.505610 -v 0.056133 0.088244 0.092645 -vn 0.954934 0.172141 0.241803 -v 0.056105 0.088281 0.092695 -vn 0.949988 0.200304 0.239586 -v 0.056105 0.088177 0.092776 -vn -0.544963 0.501678 0.671814 -v 0.056320 0.088226 0.092621 -vn -0.086284 0.596106 0.798256 -v 0.056255 0.088213 0.092603 -vn 0.392483 0.550323 0.736955 -v 0.056188 0.088219 0.092612 -vn -0.544995 0.411635 0.730437 -v 0.056320 0.088679 0.092326 -vn -0.086317 0.489125 0.867932 -v 0.056255 0.088668 0.092307 -vn 0.392475 0.451568 0.801280 -v 0.056188 0.088673 0.092316 -vn -0.544980 0.314860 0.777085 -v 0.056320 0.089166 0.092092 -vn -0.086328 0.374124 0.923352 -v 0.056255 0.089157 0.092071 -vn 0.392480 0.345395 0.852445 -v 0.056188 0.089161 0.092081 -vn 0.778428 0.237995 0.580868 -v 0.056133 0.089177 0.092120 -vn 0.954688 0.114996 0.274493 -v 0.056105 0.089200 0.092178 -vn 0.778063 0.156995 0.608252 -v 0.056133 0.089686 0.091950 -vn 0.954908 0.070972 0.288294 -v 0.056105 0.089702 0.092011 -vn 0.947667 0.100071 0.303172 -v 0.056105 0.089474 0.092078 -vn -0.544985 0.212903 0.810965 -v 0.056320 0.089678 0.091921 -vn -0.086335 0.252978 0.963612 -v 0.056255 0.089673 0.091899 -vn 0.392494 0.233550 0.889608 -v 0.056188 0.089675 0.091910 -vn 0.778458 0.079042 0.622700 -v 0.056133 0.090213 0.091848 -vn 0.954983 0.029372 0.295203 -v 0.056105 0.090221 0.091910 -vn 0.954244 0.050061 0.294809 -v 0.056105 0.090194 0.091913 -vn -0.544970 0.107453 0.831542 -v 0.056320 0.090209 0.091818 -vn -0.086325 0.127677 0.988052 -v 0.056255 0.090206 0.091795 -vn 0.392488 0.117869 0.912173 -v 0.056188 0.090207 0.091806 -vn 0.650248 0.739993 0.172012 -v 0.056039 0.087067 0.095291 -vn 0.651406 0.751224 0.106456 -v 0.056039 0.087059 0.095331 -vn 0.653780 0.717041 -0.241709 -v 0.056039 0.087239 0.097319 -vn 0.652644 0.737881 -0.172012 -v 0.056039 0.087067 0.096711 -vn 0.652356 0.750387 -0.106539 -v 0.056039 0.087060 0.096671 -vn 0.660075 0.751199 -0.000621 -v 0.056039 0.086999 0.096001 -vn 0.651928 0.661295 -0.371050 -v 0.056039 0.087531 0.097924 -vn 0.651933 0.695267 -0.302633 -v 0.056039 0.087268 0.097395 -vn 0.654390 0.480787 -0.583624 -v 0.056039 0.088412 0.098933 -vn 0.652202 0.536585 -0.535452 -v 0.056039 0.088036 0.098589 -vn 0.652715 0.583020 -0.483788 -v 0.056039 0.087926 0.098468 -vn 0.651735 0.626385 -0.427649 -v 0.056039 0.087595 0.098028 -vn 0.652648 0.239399 -0.718846 -v 0.056039 0.089591 0.099567 -vn 0.651651 0.305988 -0.694062 -v 0.056039 0.089192 0.099412 -vn 0.652170 0.369022 -0.662192 -v 0.056039 0.088973 0.099303 -vn 0.652355 0.431252 -0.623261 -v 0.056039 0.088575 0.099055 -vn 0.652022 -0.035577 -0.757365 -v 0.056039 0.090918 0.099746 -vn 0.651677 0.034194 -0.757726 -v 0.056039 0.090572 0.099746 -vn 0.652065 0.104538 -0.750922 -v 0.056039 0.090247 0.099716 -vn 0.650666 0.176146 -0.738652 -v 0.056039 0.089866 0.099645 -vn 0.652012 -0.306404 -0.693540 -v 0.056039 0.092224 0.099448 -vn 0.652706 -0.240608 -0.718389 -v 0.056039 0.091977 0.099543 -vn 0.653414 -0.174322 -0.736656 -v 0.056039 0.091585 0.099656 -vn 0.649879 -0.104211 -0.752859 -v 0.056039 0.091284 0.099712 -vn 0.652057 -0.536144 -0.536070 -v 0.056039 0.093341 0.098710 -vn 0.651561 -0.485544 -0.582851 -v 0.056039 0.093206 0.098833 -vn 0.652153 -0.428398 -0.625437 -v 0.056039 0.092816 0.099129 -vn 0.648766 -0.369962 -0.665004 -v 0.056039 0.092625 0.099247 -vn 0.649400 -0.585234 -0.485573 -v 0.056039 0.093697 0.098317 -vn 0.651788 -0.625086 -0.429466 -v 0.056039 0.093784 0.098203 -vn 0.651025 -0.664422 -0.367028 -v 0.056039 0.094083 0.097717 -vn 0.650769 -0.752512 -0.101122 -v 0.056039 0.094482 0.096355 -vn 0.651842 -0.737793 -0.175396 -v 0.056039 0.094364 0.096997 -vn 0.652016 -0.719726 -0.238471 -v 0.056039 0.094348 0.097055 -vn 0.652570 -0.692944 -0.306562 -v 0.056039 0.094128 0.097626 -vn 0.653114 -0.736895 0.174436 -v 0.056039 0.094364 0.095001 -vn 0.652491 -0.750807 0.102684 -v 0.056039 0.094482 0.095642 -vn 0.651732 -0.757484 0.038261 -v 0.056039 0.094484 0.095663 -vn 0.651197 -0.757978 -0.037570 -v 0.056039 0.094484 0.096335 -vn 0.653269 -0.663374 0.364931 -v 0.056039 0.094082 0.094281 -vn 0.655190 -0.690030 0.307544 -v 0.056039 0.094127 0.094372 -vn 0.652687 -0.718859 0.239253 -v 0.056039 0.094347 0.094942 -vn 0.652227 -0.427127 0.626229 -v 0.056039 0.092814 0.092870 -vn 0.651773 -0.486670 0.581674 -v 0.056039 0.093204 0.093165 -vn 0.653366 -0.534767 0.535851 -v 0.056039 0.093340 0.093289 -vn 0.652008 -0.583623 0.484013 -v 0.056039 0.093696 0.093681 -vn 0.651822 -0.625494 0.428818 -v 0.056039 0.093782 0.093795 -vn 0.654069 -0.171047 0.736842 -v 0.056039 0.091583 0.092344 -vn 0.651738 -0.241121 0.719095 -v 0.056039 0.091975 0.092456 -vn 0.652659 -0.306356 0.692952 -v 0.056039 0.092222 0.092551 -vn 0.651805 -0.369169 0.662468 -v 0.056039 0.092623 0.092752 -vn 0.652477 0.105469 0.750433 -v 0.056039 0.090245 0.092284 -vn 0.651267 0.036248 0.757982 -v 0.056039 0.090570 0.092254 -vn 0.652366 -0.035611 0.757068 -v 0.056039 0.090916 0.092254 -vn 0.652664 -0.106468 0.750129 -v 0.056039 0.091282 0.092288 -vn 0.651132 0.430273 0.625213 -v 0.056039 0.088573 0.092946 -vn 0.652177 0.368240 0.662620 -v 0.056039 0.088971 0.092698 -vn 0.651467 0.308015 0.693338 -v 0.056039 0.089190 0.092589 -vn 0.652264 0.240567 0.718804 -v 0.056039 0.089589 0.092434 -vn 0.651276 0.173196 0.738812 -v 0.056039 0.089864 0.092356 -vn 0.650834 0.627921 0.426768 -v 0.056039 0.087594 0.093973 -vn 0.652174 0.582325 0.485352 -v 0.056039 0.087924 0.093534 -vn 0.652099 0.537248 0.534913 -v 0.056039 0.088034 0.093413 -vn 0.652722 0.483903 0.582917 -v 0.056039 0.088410 0.093069 -vn 0.652048 0.718630 0.241672 -v 0.056039 0.087238 0.094683 -vn 0.651614 0.695070 0.303771 -v 0.056039 0.087267 0.094607 -vn 0.651838 0.662126 0.369724 -v 0.056039 0.087529 0.094078 -vn -0.047251 0.966320 0.252969 -v 0.054601 0.087101 0.095132 -vn -0.018624 0.985453 0.168926 -v 0.054601 0.087067 0.095291 -vn -0.044196 0.993858 0.101452 -v 0.054601 0.087018 0.095626 -vn -0.046931 0.695915 0.716589 -v 0.054601 0.088053 0.093394 -vn -0.042598 0.744276 0.666512 -v 0.054601 0.088034 0.093413 -vn -0.045904 0.794975 0.604904 -v 0.054601 0.087730 0.093776 -vn -0.002243 0.847873 0.530194 -v 0.054601 0.087594 0.093973 -vn -0.042137 0.879370 0.474271 -v 0.054601 0.087460 0.094199 -vn -0.042063 0.916658 0.397454 -v 0.054601 0.087267 0.094607 -vn -0.046731 0.942564 0.330741 -v 0.054601 0.087249 0.094653 -vn -0.045871 0.288459 0.956393 -v 0.054601 0.089757 0.092384 -vn -0.046030 0.366374 0.929328 -v 0.054601 0.089284 0.092548 -vn -0.030245 0.438659 0.898144 -v 0.054601 0.089190 0.092589 -vn -0.044374 0.502625 0.863365 -v 0.054601 0.088837 0.092774 -vn -0.030136 0.571769 0.819861 -v 0.054601 0.088573 0.092946 -vn -0.046935 0.635494 0.770678 -v 0.054601 0.088424 0.093058 -vn -0.045975 -0.102765 0.993643 -v 0.054601 0.091248 0.092283 -vn -0.045956 -0.020424 0.998735 -v 0.054601 0.090748 0.092250 -vn -0.015721 0.066819 0.997641 -v 0.054601 0.090570 0.092254 -vn -0.043403 0.133112 0.990150 -v 0.054601 0.090248 0.092284 -vn -0.035667 0.215228 0.975912 -v 0.054601 0.089864 0.092356 -vn -0.046156 -0.602093 0.797091 -v 0.054601 0.093072 0.093056 -vn -0.045803 -0.534233 0.844095 -v 0.054601 0.092659 0.092773 -vn -0.041416 -0.472490 0.880363 -v 0.054601 0.092623 0.092752 -vn -0.046091 -0.403246 0.913930 -v 0.054601 0.092212 0.092547 -vn -0.029718 -0.326340 0.944785 -v 0.054601 0.091975 0.092456 -vn -0.048481 -0.250388 0.966931 -v 0.054601 0.091739 0.092383 -vn -0.043648 -0.171725 0.984178 -v 0.054601 0.091282 0.092288 -vn -0.047078 -0.862575 0.503735 -v 0.054601 0.094037 0.094197 -vn -0.046765 -0.818837 0.572118 -v 0.054601 0.093768 0.093775 -vn -0.029506 -0.769216 0.638308 -v 0.054601 0.093696 0.093681 -vn -0.046468 -0.723331 0.688936 -v 0.054601 0.093444 0.093392 -vn -0.030876 -0.663706 0.747356 -v 0.054601 0.093204 0.093165 -vn -0.047750 -0.944765 -0.324252 -v 0.054601 0.094331 0.097110 -vn -0.038597 -0.966710 -0.252948 -v 0.054601 0.094348 0.097055 -vn -0.046112 -0.982846 -0.178573 -v 0.054601 0.094447 0.096623 -vn -0.028486 -0.994799 -0.097796 -v 0.054601 0.094482 0.096355 -vn -0.047449 -0.998739 -0.016418 -v 0.054601 0.094497 0.096124 -vn -0.044969 -0.996953 0.063736 -v 0.054601 0.094482 0.095642 -vn -0.048518 -0.989889 0.133285 -v 0.054601 0.094480 0.095624 -vn -0.049100 -0.976337 0.210607 -v 0.054601 0.094397 0.095130 -vn -0.015698 -0.953477 0.301058 -v 0.054601 0.094347 0.094942 -vn -0.047825 -0.932523 0.357930 -v 0.054601 0.094248 0.094651 -vn -0.037180 -0.898497 0.437402 -v 0.054601 0.094082 0.094281 -vn -0.046137 -0.690390 -0.721964 -v 0.054601 0.093265 0.098780 -vn -0.046533 -0.747309 -0.662845 -v 0.054601 0.093614 0.098420 -vn -0.024412 -0.799998 -0.599506 -v 0.054601 0.093697 0.098317 -vn -0.044091 -0.839704 -0.541252 -v 0.054601 0.093911 0.098017 -vn -0.031738 -0.881628 -0.470877 -v 0.054601 0.094083 0.097717 -vn -0.047621 -0.915840 -0.398710 -v 0.054601 0.094151 0.097578 -vn -0.045874 0.175970 -0.983326 -v 0.054601 0.090003 0.099675 -vn -0.045803 0.094046 -0.994514 -v 0.054601 0.090500 0.099742 -vn -0.036015 0.019072 -0.999169 -v 0.054601 0.090572 0.099746 -vn -0.045029 -0.055858 -0.997423 -v 0.054601 0.091001 0.099742 -vn -0.029454 -0.137563 -0.990055 -v 0.054601 0.091284 0.099712 -vn -0.047494 -0.217363 -0.974935 -v 0.054601 0.091497 0.099675 -vn -0.045763 -0.327106 -0.943879 -v 0.054601 0.091980 0.099542 -vn -0.045988 -0.434112 -0.899684 -v 0.054601 0.092441 0.099346 -vn -0.008909 -0.513580 -0.857995 -v 0.054601 0.092625 0.099247 -vn -0.042564 -0.568258 -0.821749 -v 0.054601 0.092872 0.099091 -vn -0.038760 -0.635384 -0.771223 -v 0.054601 0.093206 0.098833 -vn -0.046418 0.541305 -0.839544 -v 0.054601 0.088628 0.099092 -vn -0.046229 0.470680 -0.881092 -v 0.054601 0.089059 0.099347 -vn -0.022633 0.394490 -0.918621 -v 0.054601 0.089192 0.099412 -vn -0.044721 0.331230 -0.942490 -v 0.054601 0.089520 0.099543 -vn -0.033001 0.251819 -0.967211 -v 0.054601 0.089866 0.099645 -vn -0.046688 0.897640 -0.438250 -v 0.054601 0.087348 0.097579 -vn -0.046071 0.858629 -0.510523 -v 0.054601 0.087589 0.098019 -vn -0.046277 0.821769 -0.567939 -v 0.054601 0.087595 0.098028 -vn -0.047612 0.774448 -0.630843 -v 0.054601 0.087886 0.098422 -vn -0.008107 0.712575 -0.701550 -v 0.054601 0.088036 0.098589 -vn -0.045262 0.667840 -0.742927 -v 0.054601 0.088234 0.098782 -vn -0.040376 0.601056 -0.798186 -v 0.054601 0.088575 0.099055 -vn -0.034274 0.999235 0.018849 -v 0.054601 0.086999 0.096001 -vn -0.047952 0.997099 -0.059107 -v 0.054601 0.087001 0.096126 -vn -0.047642 0.989177 -0.138778 -v 0.054601 0.087052 0.096625 -vn -0.036235 0.975243 -0.218148 -v 0.054601 0.087067 0.096711 -vn -0.048723 0.957379 -0.284695 -v 0.054601 0.087168 0.097112 -vn -0.029387 0.930734 -0.364514 -v 0.054601 0.087268 0.097395 -vn -0.000662 0.382638 0.923898 -v 0.054453 0.089279 0.092535 -vn 0.000656 0.273149 0.961971 -v 0.054453 0.089754 0.092370 -vn 0.045870 0.288461 0.956392 -v 0.054305 0.089757 0.092384 -vn -0.000406 0.716984 0.697090 -v 0.054453 0.088043 0.093384 -vn 0.000506 0.628095 0.778136 -v 0.054453 0.088416 0.093047 -vn 0.046856 0.635537 0.770647 -v 0.054305 0.088424 0.093058 -vn -0.000558 0.970386 0.241560 -v 0.054453 0.087087 0.095128 -vn 0.000580 0.935098 0.354388 -v 0.054453 0.087236 0.094648 -vn 0.046672 0.942579 0.330707 -v 0.054305 0.087249 0.094653 -vn -0.000668 0.987305 -0.158834 -v 0.054453 0.087038 0.096627 -vn 0.000632 0.999064 -0.043247 -v 0.054453 0.086987 0.096127 -vn 0.047953 0.997099 -0.059106 -v 0.054305 0.087001 0.096126 -vn -0.000207 0.843434 -0.537233 -v 0.054453 0.087577 0.098026 -vn 0.000473 0.902566 -0.430551 -v 0.054453 0.087335 0.097585 -vn 0.046688 0.897640 -0.438249 -v 0.054305 0.087348 0.097579 -vn -0.000590 0.459765 -0.888041 -v 0.054453 0.089052 0.099360 -vn 0.000637 0.560470 -0.828175 -v 0.054453 0.088620 0.099104 -vn 0.046418 0.541305 -0.839544 -v 0.054305 0.088628 0.099092 -vn -0.000656 0.073399 -0.997302 -v 0.054453 0.090499 0.099756 -vn 0.000604 0.189147 -0.981949 -v 0.054453 0.090000 0.099689 -vn 0.045875 0.175972 -0.983326 -v 0.054305 0.090003 0.099675 -vn -0.000619 -0.757487 -0.652849 -v 0.054453 0.093624 0.098429 -vn 0.000663 -0.676466 -0.736473 -v 0.054453 0.093275 0.098791 -vn 0.046137 -0.690390 -0.721964 -v 0.054305 0.093265 0.098780 -vn -0.000615 -0.953468 -0.301495 -v 0.054453 0.094344 0.097114 -vn 0.000572 -0.911460 -0.411388 -v 0.054453 0.094164 0.097583 -vn 0.047737 -0.915802 -0.398783 -v 0.054305 0.094151 0.097578 -vn -0.000644 -0.810391 0.585889 -v 0.054453 0.093779 0.093766 -vn 0.000667 -0.872797 0.488084 -v 0.054453 0.094049 0.094190 -vn 0.047076 -0.862574 0.503736 -v 0.054305 0.094037 0.094197 -vn -0.000535 -0.513166 0.858289 -v 0.054453 0.092666 0.092761 -vn 0.000540 -0.611361 0.791351 -v 0.054453 0.093081 0.093045 -vn 0.046156 -0.602093 0.797091 -v 0.054305 0.093072 0.093056 -vn 0.041653 -0.172099 0.984199 -v 0.054305 0.091282 0.092288 -vn 0.045973 -0.102763 0.993643 -v 0.054305 0.091248 0.092283 -vn 0.000479 -0.129366 0.991597 -v 0.054453 0.091250 0.092269 -vn -0.000522 -0.010116 0.999949 -v 0.054453 0.090748 0.092236 -vn 0.001072 -0.255425 0.966828 -v 0.054453 0.091743 0.092369 -vn 0.003854 -0.394105 0.919057 -v 0.054453 0.092218 0.092534 -vn 0.001016 -0.719433 0.694561 -v 0.054453 0.093454 0.093383 -vn -0.001884 -0.932309 0.361658 -v 0.054453 0.094261 0.094646 -vn -0.000491 -0.975052 0.221977 -v 0.054453 0.094410 0.095126 -vn 0.000314 -0.994736 0.102471 -v 0.054453 0.094494 0.095622 -vn 0.000796 -0.999720 -0.023652 -v 0.054453 0.094511 0.096125 -vn 0.003304 -0.985487 -0.169721 -v 0.054453 0.094461 0.096625 -vn 0.000438 -0.842774 -0.538267 -v 0.054453 0.093922 0.098024 -vn -0.002457 -0.568464 -0.822704 -v 0.054453 0.092880 0.099103 -vn -0.000457 -0.442050 -0.896990 -v 0.054453 0.092448 0.099359 -vn -0.000350 -0.328449 -0.944522 -v 0.054453 0.091985 0.099555 -vn 0.000439 -0.209447 -0.977820 -v 0.054453 0.091500 0.099688 -vn 0.002740 -0.063984 -0.997947 -v 0.054453 0.091002 0.099756 -vn -0.000144 0.327603 -0.944815 -v 0.054453 0.089515 0.099556 -vn -0.003022 0.668043 -0.744117 -v 0.054453 0.088225 0.098792 -vn -0.000657 0.769767 -0.638325 -v 0.054453 0.087875 0.098431 -vn 0.002173 0.955745 -0.294187 -v 0.054453 0.087154 0.097116 -vn -0.000724 0.995087 0.098999 -v 0.054453 0.087004 0.095624 -vn -0.003582 0.879004 0.476800 -v 0.054453 0.087448 0.094192 -vn -0.000935 0.799771 0.600305 -v 0.054453 0.087718 0.093768 -vn 0.001592 0.508296 0.861181 -v 0.054453 0.088830 0.092762 -vn -0.001305 0.135039 0.990839 -v 0.054453 0.090246 0.092270 -vn 0.045472 -0.249260 0.967368 -v 0.054305 0.091739 0.092383 -vn 0.046812 -0.533699 0.844378 -v 0.054305 0.092659 0.092773 -vn 0.043683 -0.474110 0.879381 -v 0.054305 0.092623 0.092752 -vn 0.042020 -0.396131 0.917232 -v 0.054305 0.092212 0.092547 -vn 0.001062 -0.337661 0.941267 -v 0.054305 0.091975 0.092456 -vn 0.046844 -0.818804 0.572158 -v 0.054305 0.093768 0.093775 -vn 0.035035 -0.772796 0.633687 -v 0.054305 0.093696 0.093681 -vn 0.043259 -0.717462 0.695253 -v 0.054305 0.093444 0.093392 -vn 0.016717 -0.669065 0.743016 -v 0.054305 0.093204 0.093165 -vn 0.029518 -0.956392 0.290590 -v 0.054305 0.094347 0.094942 -vn 0.045048 -0.928961 0.367426 -v 0.054305 0.094248 0.094651 -vn 0.031798 -0.900039 0.434647 -v 0.054305 0.094082 0.094281 -vn 0.047056 -0.998766 -0.015899 -v 0.054305 0.094497 0.096124 -vn 0.044489 -0.997011 0.063173 -v 0.054305 0.094482 0.095642 -vn 0.048520 -0.989890 0.133283 -v 0.054305 0.094480 0.095624 -vn 0.048941 -0.976369 0.210495 -v 0.054305 0.094397 0.095130 -vn 0.047751 -0.944765 -0.324251 -v 0.054305 0.094331 0.097110 -vn 0.040667 -0.966133 -0.254820 -v 0.054305 0.094348 0.097055 -vn 0.042515 -0.984380 -0.170846 -v 0.054305 0.094447 0.096623 -vn 0.004183 -0.994146 -0.107967 -v 0.054305 0.094482 0.096355 -vn 0.046533 -0.747309 -0.662845 -v 0.054305 0.093614 0.098420 -vn 0.032926 -0.796542 -0.603686 -v 0.054305 0.093697 0.098317 -vn 0.043621 -0.843961 -0.534628 -v 0.054305 0.093911 0.098017 -vn 0.020455 -0.878828 -0.476701 -v 0.054305 0.094083 0.097717 -vn 0.031144 -0.504373 -0.862924 -v 0.054305 0.092625 0.099247 -vn 0.046175 -0.574837 -0.816964 -v 0.054305 0.092872 0.099091 -vn 0.035861 -0.632826 -0.773463 -v 0.054305 0.093206 0.098833 -vn 0.046215 -0.217141 -0.975046 -v 0.054305 0.091497 0.099675 -vn 0.045882 -0.296921 -0.953799 -v 0.054305 0.091977 0.099543 -vn 0.045737 -0.359180 -0.932147 -v 0.054305 0.091980 0.099542 -vn 0.048517 -0.435477 -0.898892 -v 0.054305 0.092441 0.099346 -vn 0.045804 0.094044 -0.994514 -v 0.054305 0.090500 0.099742 -vn 0.039565 0.021249 -0.998991 -v 0.054305 0.090572 0.099746 -vn 0.043215 -0.063759 -0.997029 -v 0.054305 0.091001 0.099742 -vn 0.008176 -0.127395 -0.991818 -v 0.054305 0.091284 0.099712 -vn 0.046765 0.470361 -0.881234 -v 0.054305 0.089059 0.099347 -vn 0.032915 0.400776 -0.915585 -v 0.054305 0.089192 0.099412 -vn 0.043816 0.323645 -0.945163 -v 0.054305 0.089520 0.099543 -vn 0.023123 0.257194 -0.966083 -v 0.054305 0.089866 0.099645 -vn 0.028507 0.720232 -0.693147 -v 0.054305 0.088036 0.098589 -vn 0.045060 0.661173 -0.748879 -v 0.054305 0.088234 0.098782 -vn 0.036871 0.602392 -0.797348 -v 0.054305 0.088575 0.099055 -vn 0.046401 0.858513 -0.510688 -v 0.054305 0.087589 0.098019 -vn 0.046247 0.822339 -0.567115 -v 0.054305 0.087595 0.098028 -vn 0.047011 0.774062 -0.631362 -v 0.054305 0.087886 0.098422 -vn 0.047600 0.989183 -0.138751 -v 0.054305 0.087052 0.096625 -vn 0.037920 0.976294 -0.213099 -v 0.054305 0.087067 0.096711 -vn 0.043125 0.954840 -0.293976 -v 0.054305 0.087168 0.097112 -vn 0.010438 0.934152 -0.356724 -v 0.054305 0.087268 0.097395 -vn 0.047252 0.966320 0.252967 -v 0.054305 0.087101 0.095132 -vn 0.031080 0.983958 0.175671 -v 0.054305 0.087067 0.095291 -vn 0.044975 0.994592 0.093615 -v 0.054305 0.087018 0.095626 -vn 0.026619 0.999360 0.023903 -v 0.054305 0.086999 0.096001 -vn 0.028117 0.841910 0.538885 -v 0.054305 0.087594 0.093973 -vn 0.046047 0.882931 0.467240 -v 0.054305 0.087460 0.094199 -vn 0.040327 0.916048 0.399036 -v 0.054305 0.087267 0.094607 -vn 0.046931 0.695915 0.716589 -v 0.054305 0.088053 0.093394 -vn 0.043324 0.743707 0.667100 -v 0.054305 0.088034 0.093413 -vn 0.046453 0.795394 0.604310 -v 0.054305 0.087730 0.093776 -vn 0.046029 0.366372 0.929329 -v 0.054305 0.089284 0.092548 -vn 0.036401 0.435492 0.899457 -v 0.054305 0.089190 0.092589 -vn 0.044881 0.509854 0.859089 -v 0.054305 0.088837 0.092774 -vn 0.015438 0.564466 0.825312 -v 0.054305 0.088573 0.092946 -vn 0.047302 -0.019568 0.998689 -v 0.054305 0.090748 0.092250 -vn 0.031593 0.058299 0.997799 -v 0.054305 0.090570 0.092254 -vn 0.044758 0.140903 0.989011 -v 0.054305 0.090248 0.092284 -vn 0.029555 0.211063 0.977026 -v 0.054305 0.089864 0.092356 -vn -0.659349 0.751834 -0.001957 -v 0.052867 0.086999 0.096001 -vn -0.651406 0.751224 0.106456 -v 0.052867 0.087059 0.095331 -vn -0.651183 0.739545 0.170394 -v 0.052867 0.087067 0.095291 -vn -0.652218 0.718276 0.242262 -v 0.052867 0.087238 0.094683 -vn -0.651586 0.695080 0.303808 -v 0.052867 0.087267 0.094607 -vn -0.651867 0.662121 0.369682 -v 0.052867 0.087529 0.094078 -vn -0.650853 0.627890 0.426785 -v 0.052867 0.087594 0.093973 -vn -0.651857 0.582176 0.485956 -v 0.052867 0.087924 0.093534 -vn -0.651341 0.537866 0.535215 -v 0.052867 0.088034 0.093413 -vn -0.652417 0.484705 0.582592 -v 0.052867 0.088410 0.093069 -vn -0.651884 0.429004 0.625301 -v 0.052867 0.088573 0.092946 -vn -0.653457 0.366822 0.662145 -v 0.052867 0.088971 0.092698 -vn -0.651437 0.309546 0.692684 -v 0.052867 0.089190 0.092589 -vn -0.652053 0.241328 0.718740 -v 0.052867 0.089589 0.092434 -vn -0.651582 0.173356 0.738504 -v 0.052867 0.089864 0.092356 -vn -0.652162 0.104241 0.750878 -v 0.052867 0.090245 0.092284 -vn -0.650533 0.036682 0.758592 -v 0.052867 0.090570 0.092254 -vn -0.652619 -0.034434 0.756903 -v 0.052867 0.090916 0.092254 -vn -0.651851 -0.105136 0.751024 -v 0.052867 0.091282 0.092288 -vn -0.651992 -0.173469 0.738116 -v 0.052867 0.091583 0.092344 -vn -0.649286 -0.240788 0.721421 -v 0.052867 0.091975 0.092456 -vn -0.652714 -0.306025 0.693046 -v 0.052867 0.092222 0.092551 -vn -0.652184 -0.369078 0.662146 -v 0.052867 0.092623 0.092752 -vn -0.652084 -0.428108 0.625707 -v 0.052867 0.092814 0.092870 -vn -0.648809 -0.485720 0.585767 -v 0.052867 0.093204 0.093165 -vn -0.651815 -0.535646 0.536862 -v 0.052867 0.093340 0.093289 -vn -0.651272 -0.584774 0.483615 -v 0.052867 0.093696 0.093681 -vn -0.652493 -0.624469 0.429292 -v 0.052867 0.093782 0.093795 -vn -0.651619 -0.663760 0.367173 -v 0.052867 0.094082 0.094281 -vn -0.651796 -0.692997 0.308088 -v 0.052867 0.094127 0.094372 -vn -0.650852 -0.720751 0.238557 -v 0.052867 0.094347 0.094942 -vn -0.652657 -0.737393 0.174042 -v 0.052867 0.094364 0.095001 -vn -0.652491 -0.750808 0.102684 -v 0.052867 0.094482 0.095642 -vn -0.651731 -0.757484 0.038261 -v 0.052867 0.094484 0.095663 -vn -0.651196 -0.757979 -0.037572 -v 0.052867 0.094484 0.096335 -vn -0.650768 -0.752513 -0.101120 -v 0.052867 0.094482 0.096355 -vn -0.651842 -0.737793 -0.175396 -v 0.052867 0.094364 0.096997 -vn -0.651850 -0.719687 -0.239044 -v 0.052867 0.094348 0.097055 -vn -0.652089 -0.693669 -0.305948 -v 0.052867 0.094128 0.097626 -vn -0.651139 -0.664429 -0.366815 -v 0.052867 0.094083 0.097717 -vn -0.651787 -0.625086 -0.429466 -v 0.052867 0.093784 0.098203 -vn -0.651290 -0.585409 -0.482822 -v 0.052867 0.093697 0.098317 -vn -0.652258 -0.535295 -0.536674 -v 0.052867 0.093341 0.098710 -vn -0.651838 -0.484947 -0.583039 -v 0.052867 0.093206 0.098833 -vn -0.652841 -0.428372 -0.624737 -v 0.052867 0.092816 0.099129 -vn -0.652098 -0.370087 -0.661667 -v 0.052867 0.092625 0.099247 -vn -0.652933 -0.305645 -0.693008 -v 0.052867 0.092224 0.099448 -vn -0.651865 -0.241625 -0.718811 -v 0.052867 0.091977 0.099543 -vn -0.652571 -0.174533 -0.737353 -v 0.052867 0.091585 0.099656 -vn -0.651462 -0.104628 -0.751432 -v 0.052867 0.091284 0.099712 -vn -0.653209 -0.033955 -0.756416 -v 0.052867 0.090918 0.099746 -vn -0.651894 0.033409 -0.757573 -v 0.052867 0.090572 0.099746 -vn -0.652253 0.103829 -0.750856 -v 0.052867 0.090247 0.099716 -vn -0.651271 0.174856 -0.738425 -v 0.052867 0.089866 0.099645 -vn -0.652265 0.240299 -0.718893 -v 0.052867 0.089591 0.099567 -vn -0.651409 0.306912 -0.693882 -v 0.052867 0.089192 0.099412 -vn -0.652614 0.367934 -0.662359 -v 0.052867 0.088973 0.099303 -vn -0.651739 0.429710 -0.624969 -v 0.052867 0.088575 0.099055 -vn -0.652151 0.483105 -0.584216 -v 0.052867 0.088412 0.098933 -vn -0.650937 0.538087 -0.535484 -v 0.052867 0.088036 0.098589 -vn -0.652374 0.582600 -0.484753 -v 0.052867 0.087926 0.098468 -vn -0.652008 0.626467 -0.427112 -v 0.052867 0.087595 0.098028 -vn -0.652225 0.661291 -0.370537 -v 0.052867 0.087531 0.097924 -vn -0.650927 0.695569 -0.304103 -v 0.052867 0.087268 0.097395 -vn -0.651521 0.718778 -0.242649 -v 0.052867 0.087239 0.097319 -vn -0.651263 0.739398 -0.170726 -v 0.052867 0.087067 0.096711 -vn -0.652130 0.750673 -0.105908 -v 0.052867 0.087060 0.096671 -vn 0.327045 -0.943593 0.051715 -v 0.053900 0.088350 0.096075 -vn 0.327252 -0.937194 0.120717 -v 0.053900 0.088378 0.096369 -vn -0.689521 -0.724265 0.001030 -v 0.052453 0.088349 0.096001 -vn -0.689458 -0.713423 0.125197 -v 0.052453 0.088386 0.096417 -vn 0.330860 -0.925612 0.183777 -v 0.053900 0.088386 0.096417 -vn 0.327453 -0.910682 0.251859 -v 0.053900 0.088441 0.096657 -vn -0.689924 -0.680092 0.247951 -v 0.052453 0.088494 0.096821 -vn 0.333275 -0.887631 0.317868 -v 0.053900 0.088494 0.096821 -vn 0.327469 -0.863314 0.383997 -v 0.053900 0.088539 0.096936 -vn -0.689651 -0.627024 0.362245 -v 0.052453 0.088671 0.097201 -vn 0.326588 -0.818404 0.472816 -v 0.053900 0.088671 0.097201 -vn 0.327463 -0.763908 0.556070 -v 0.053900 0.088834 0.097447 -vn -0.689924 -0.554523 0.465305 -v 0.052453 0.088911 0.097543 -vn 0.330858 -0.621519 0.710103 -v 0.053900 0.089207 0.097839 -vn -0.689611 -0.464913 0.555241 -v 0.052453 0.089207 0.097839 -vn 0.330175 -0.674871 0.659950 -v 0.053900 0.089027 0.097671 -vn 0.340485 -0.713704 0.612124 -v 0.053900 0.088911 0.097543 -vn 0.327553 -0.572807 0.751399 -v 0.053900 0.089245 0.097870 -vn 0.327348 -0.515866 0.791660 -v 0.053900 0.089486 0.098041 -vn -0.689675 -0.362398 0.626910 -v 0.052453 0.089550 0.098079 -vn 0.332740 -0.331868 0.882693 -v 0.053900 0.089929 0.098255 -vn -0.689386 -0.246534 0.681152 -v 0.052453 0.089929 0.098255 -vn 0.327448 -0.396869 0.857481 -v 0.053900 0.089747 0.098181 -vn 0.331919 -0.458221 0.824539 -v 0.053900 0.089550 0.098079 -vn 0.326458 -0.266946 0.906733 -v 0.053900 0.090022 0.098287 -vn 0.327142 -0.200286 0.923506 -v 0.053900 0.090309 0.098359 -vn -0.689175 -0.126600 0.713449 -v 0.052453 0.090333 0.098364 -vn 0.329670 -0.139451 0.933740 -v 0.053900 0.090333 0.098364 -vn 0.327458 -0.069913 0.942276 -v 0.053900 0.090602 0.098395 -vn -0.689958 0.000201 0.723850 -v 0.052453 0.090750 0.098400 -vn 0.329659 0.139988 0.933664 -v 0.053900 0.091167 0.098363 -vn -0.689655 0.126218 0.713053 -v 0.052453 0.091167 0.098363 -vn 0.327450 0.070438 0.942240 -v 0.053900 0.090898 0.098395 -vn 0.333446 0.000259 0.942769 -v 0.053900 0.090750 0.098400 -vn 0.328016 0.200028 0.923252 -v 0.053900 0.091191 0.098359 -vn 0.327423 0.268100 0.906045 -v 0.053900 0.091477 0.098287 -vn -0.689832 0.247431 0.680375 -v 0.052453 0.091571 0.098255 -vn 0.331927 0.458675 0.824283 -v 0.053900 0.091950 0.098078 -vn -0.689524 0.363026 0.626713 -v 0.052453 0.091950 0.098078 -vn 0.329622 0.394486 0.857747 -v 0.053900 0.091753 0.098180 -vn 0.337683 0.335230 0.879540 -v 0.053900 0.091571 0.098255 -vn 0.327047 0.516553 0.791336 -v 0.053900 0.092013 0.098040 -vn 0.327251 0.573128 0.751287 -v 0.053900 0.092254 0.097869 -vn -0.689458 0.465132 0.555248 -v 0.052453 0.092292 0.097838 -vn 0.330858 0.621943 0.709733 -v 0.053900 0.092292 0.097838 -vn 0.327457 0.673455 0.662745 -v 0.053900 0.092473 0.097670 -vn -0.689922 0.554781 0.465000 -v 0.052453 0.092588 0.097542 -vn 0.333275 0.719106 0.609766 -v 0.053900 0.092588 0.097542 -vn 0.327463 0.764218 0.555642 -v 0.053900 0.092665 0.097446 -vn -0.689653 0.627225 0.361895 -v 0.052453 0.092828 0.097199 -vn 0.326581 0.818674 0.472354 -v 0.053900 0.092828 0.097199 -vn 0.327456 0.863524 0.383534 -v 0.053900 0.092960 0.096935 -vn -0.689923 0.680229 0.247577 -v 0.052453 0.093005 0.096820 -vn 0.330860 0.925720 0.183233 -v 0.053900 0.093113 0.096416 -vn -0.689612 0.713309 0.125002 -v 0.052453 0.093113 0.096416 -vn 0.330176 0.908970 0.254475 -v 0.053900 0.093058 0.096656 -vn 0.340482 0.886967 0.312028 -v 0.053900 0.093005 0.096820 -vn 0.327553 0.937130 0.120398 -v 0.053900 0.093121 0.096367 -vn 0.327332 0.943536 0.050917 -v 0.053900 0.093148 0.096073 -vn -0.689676 0.724118 0.000393 -v 0.052453 0.093149 0.095999 -vn 0.332751 0.930367 -0.153928 -v 0.053900 0.093113 0.095583 -vn -0.689387 0.713162 -0.127069 -v 0.052453 0.093113 0.095583 -vn 0.327450 0.941034 -0.085040 -v 0.053900 0.093139 0.095778 -vn 0.331907 0.943186 -0.015432 -v 0.053900 0.093149 0.095999 -vn 0.326474 0.918727 -0.222162 -v 0.053900 0.093093 0.095486 -vn 0.327145 0.899922 -0.288300 -v 0.053900 0.093012 0.095202 -vn -0.689175 0.681166 -0.247084 -v 0.052453 0.093004 0.095179 -vn 0.329670 0.878370 -0.346097 -v 0.053900 0.093004 0.095179 -vn 0.327449 0.850996 -0.410589 -v 0.053900 0.092897 0.094930 -vn -0.689957 0.626772 -0.362101 -v 0.052453 0.092827 0.094799 -vn 0.329665 0.738622 -0.588012 -v 0.053900 0.092587 0.094457 -vn -0.689658 0.554413 -0.465831 -v 0.052453 0.092587 0.094457 -vn 0.327470 0.780778 -0.532118 -v 0.053900 0.092749 0.094674 -vn 0.333452 0.816331 -0.471607 -v 0.053900 0.092827 0.094799 -vn 0.328012 0.699590 -0.634809 -v 0.053900 0.092571 0.094438 -vn 0.327422 0.650628 -0.685184 -v 0.053900 0.092366 0.094226 -vn -0.689829 0.465512 -0.554468 -v 0.052453 0.092291 0.094161 -vn 0.331907 0.484496 -0.809383 -v 0.053900 0.091949 0.093921 -vn -0.689523 0.361238 -0.627746 -v 0.052453 0.091949 0.093921 -vn 0.329616 0.545591 -0.770509 -v 0.053900 0.092135 0.094041 -vn 0.337692 0.594092 -0.730081 -v 0.053900 0.092291 0.094161 -vn 0.327024 0.427016 -0.843038 -v 0.053900 0.091884 0.093885 -vn 0.327248 0.364086 -0.871981 -v 0.053900 0.091616 0.093762 -vn -0.689455 0.248288 -0.680445 -v 0.052453 0.091569 0.093745 -vn 0.330854 0.303682 -0.893484 -v 0.053900 0.091569 0.093745 -vn 0.327441 0.237210 -0.914611 -v 0.053900 0.091334 0.093672 -vn -0.689927 0.125310 -0.712951 -v 0.052453 0.091165 0.093636 -vn 0.333261 0.168530 -0.927650 -v 0.053900 0.091165 0.093636 -vn 0.327455 0.099113 -0.939654 -v 0.053900 0.091043 0.093618 -vn -0.689650 -0.000201 -0.724143 -v 0.052453 0.090748 0.093600 -vn 0.326582 -0.000265 -0.945169 -v 0.053900 0.090748 0.093600 -vn 0.327455 -0.099633 -0.939599 -v 0.053900 0.090454 0.093618 -vn -0.689928 -0.125703 -0.712880 -v 0.052453 0.090332 0.093637 -vn 0.330859 -0.304207 -0.893303 -v 0.053900 0.089928 0.093745 -vn -0.689610 -0.248392 -0.680249 -v 0.052453 0.089928 0.093745 -vn 0.330167 -0.234087 -0.914436 -v 0.053900 0.090163 0.093673 -vn 0.340466 -0.173257 -0.924156 -v 0.053900 0.090332 0.093637 -vn 0.327556 -0.364325 -0.871765 -v 0.053900 0.089882 0.093762 -vn 0.327357 -0.427664 -0.842580 -v 0.053900 0.089613 0.093886 -vn -0.689674 -0.361721 -0.627301 -v 0.052453 0.089549 0.093922 -vn 0.332749 -0.598504 -0.728746 -v 0.053900 0.089206 0.094162 -vn -0.689387 -0.466626 -0.554080 -v 0.052453 0.089206 0.094162 -vn 0.327453 -0.544168 -0.772435 -v 0.053900 0.089362 0.094042 -vn 0.331928 -0.484952 -0.809101 -v 0.053900 0.089549 0.093922 -vn 0.326469 -0.651773 -0.684550 -v 0.053900 0.089132 0.094227 -vn 0.327143 -0.699627 -0.635216 -v 0.053900 0.088926 0.094439 -vn -0.689175 -0.554564 -0.466366 -v 0.052453 0.088910 0.094458 -vn 0.329669 -0.738912 -0.587646 -v 0.053900 0.088910 0.094458 -vn 0.327457 -0.781079 -0.531685 -v 0.053900 0.088748 0.094675 -vn -0.689956 -0.626975 -0.361749 -v 0.052453 0.088670 0.094801 -vn 0.329661 -0.878565 -0.345611 -v 0.053900 0.088494 0.095180 -vn -0.689654 -0.680633 -0.247217 -v 0.052453 0.088494 0.095180 -vn 0.330718 -0.848370 -0.413394 -v 0.053900 0.088600 0.094931 -vn 0.343376 -0.816366 -0.464369 -v 0.053900 0.088670 0.094801 -vn 0.328020 -0.899572 -0.288398 -v 0.053900 0.088485 0.095203 -vn 0.327420 -0.918707 -0.220847 -v 0.053900 0.088405 0.095487 -vn -0.689834 -0.712935 -0.125910 -v 0.052453 0.088386 0.095584 -vn 0.337679 -0.929319 -0.149462 -v 0.053900 0.088386 0.095584 -vn 0.329622 -0.940073 -0.087252 -v 0.053900 0.088359 0.095779 -vn 0.331926 -0.943188 -0.014889 -v 0.053900 0.088349 0.096001 -vn -0.329669 -0.738912 -0.587646 -v 0.055006 0.088910 0.094458 -vn -0.327457 -0.781079 -0.531685 -v 0.055006 0.088748 0.094675 -vn -0.550722 -0.694603 -0.462852 -v 0.054887 0.088828 0.094727 -vn -0.333443 -0.816602 -0.471145 -v 0.055006 0.088670 0.094801 -vn -0.327443 -0.851229 -0.410109 -v 0.055006 0.088600 0.094931 -vn -0.550707 -0.748357 -0.369707 -v 0.054887 0.088686 0.094973 -vn -0.329670 -0.139451 0.933740 -v 0.055006 0.090333 0.098364 -vn -0.327458 -0.069913 0.942276 -v 0.055006 0.090602 0.098395 -vn -0.550710 -0.053544 0.832978 -v 0.054887 0.090608 0.098300 -vn -0.333446 0.000259 0.942769 -v 0.055006 0.090750 0.098400 -vn -0.327450 0.070438 0.942240 -v 0.055006 0.090898 0.098395 -vn -0.550710 0.053999 0.832948 -v 0.054887 0.090892 0.098300 -vn -0.329670 0.878370 -0.346097 -v 0.055006 0.093004 0.095179 -vn -0.330723 0.848135 -0.413871 -v 0.055006 0.092897 0.094930 -vn -0.548178 0.748256 -0.373650 -v 0.054887 0.092812 0.094972 -vn 0.550261 -0.695581 -0.461931 -v 0.054020 0.088828 0.094727 -vn 0.549055 -0.634075 -0.544506 -v 0.054020 0.088998 0.094501 -vn 0.376903 -0.703571 -0.602439 -v 0.054155 0.089052 0.094547 -vn 0.549882 -0.101078 -0.829103 -v 0.054020 0.090465 0.093713 -vn 0.549050 -0.788753 -0.276429 -v 0.054020 0.088575 0.095235 -vn 0.550339 -0.834449 0.028671 -v 0.054020 0.088445 0.096072 -vn 0.550881 -0.803065 0.227194 -v 0.054020 0.088533 0.096631 -vn 0.550425 -0.767507 0.328580 -v 0.054020 0.088627 0.096899 -vn 0.549902 -0.521801 0.652175 -v 0.054020 0.089305 0.097796 -vn 0.550957 -0.349047 0.758032 -v 0.054020 0.089786 0.098094 -vn 0.550486 -0.249918 0.796559 -v 0.054020 0.090051 0.098197 -vn 0.550709 -0.053545 0.832978 -v 0.054020 0.090608 0.098300 -vn 0.550707 0.053997 0.832950 -v 0.054020 0.090892 0.098300 -vn 0.549059 0.154981 0.821289 -v 0.054020 0.091173 0.098265 -vn 0.550333 0.442054 0.708324 -v 0.054020 0.091963 0.097959 -vn 0.550891 0.598283 0.581873 -v 0.054020 0.092404 0.097604 -vn 0.550432 0.668312 0.500385 -v 0.054020 0.092589 0.097388 -vn 0.549890 0.825707 0.125815 -v 0.054020 0.093027 0.096353 -vn 0.550960 0.830996 -0.076737 -v 0.054020 0.093044 0.095787 -vn 0.550494 0.814794 -0.181845 -v 0.054020 0.093000 0.095506 -vn 0.550712 0.748147 -0.370126 -v 0.054020 0.092812 0.094972 -vn 0.550714 0.694352 -0.463238 -v 0.054020 0.092670 0.094726 -vn 0.549052 0.633777 -0.544857 -v 0.054020 0.092499 0.094500 -vn 0.550345 0.392387 -0.736989 -v 0.054020 0.091839 0.093969 -vn 0.550887 0.204769 -0.809069 -v 0.054020 0.091311 0.093765 -vn 0.550427 0.099195 -0.828970 -v 0.054020 0.091032 0.093713 -vn 0.549902 0.563763 -0.616262 -v 0.054020 0.092301 0.094296 -vn 0.549886 0.768562 0.327014 -v 0.054020 0.092872 0.096898 -vn 0.549905 0.251818 0.796362 -v 0.054020 0.091448 0.098196 -vn 0.549893 -0.667480 0.502084 -v 0.054020 0.088910 0.097389 -vn 0.549895 -0.815585 -0.180101 -v 0.054020 0.088498 0.095508 -vn 0.550484 -0.564877 -0.614720 -v 0.054020 0.089196 0.094297 -vn 0.550977 -0.481949 -0.681285 -v 0.054020 0.089417 0.094119 -vn 0.549897 -0.303903 -0.777982 -v 0.054020 0.089916 0.093851 -vn 0.192035 -0.661363 -0.725067 -v 0.054301 0.089273 0.094381 -vn 0.376889 -0.624203 -0.684343 -v 0.054155 0.089244 0.094349 -vn 0.192031 0.120333 -0.973984 -v 0.054301 0.091018 0.093826 -vn 0.192039 -0.000270 -0.981387 -v 0.054301 0.090749 0.093809 -vn 0.376888 -0.000252 -0.926259 -v 0.054155 0.090749 0.093766 -vn 0.376887 0.771990 -0.511847 -v 0.054155 0.092611 0.094765 -vn 0.376901 0.829030 -0.413103 -v 0.054155 0.092749 0.095004 -vn 0.192038 0.878381 -0.437685 -v 0.054301 0.092710 0.095023 -vn 0.192042 0.925507 -0.326431 -v 0.054301 0.092815 0.095271 -vn -0.000000 0.943059 -0.332625 -v 0.054453 0.092801 0.095276 -vn 0.376895 0.057284 0.924483 -v 0.054155 0.090887 0.098230 -vn 0.376884 -0.056771 0.924519 -v 0.054155 0.090612 0.098230 -vn 0.192029 -0.060148 0.979544 -v 0.054301 0.090615 0.098187 -vn 0.192022 -0.180064 0.964730 -v 0.054301 0.090347 0.098153 -vn 0.000001 -0.183476 0.983024 -v 0.054453 0.090350 0.098139 -vn 0.548173 -0.748466 -0.373236 -v 0.054020 0.088686 0.094973 -vn 0.376902 -0.829262 -0.412636 -v 0.054155 0.088749 0.095005 -vn 0.376905 -0.772267 -0.511416 -v 0.054155 0.088886 0.094766 -vn 0.192028 -0.818237 -0.541861 -v 0.054301 0.088923 0.094790 -vn 0.192026 -0.745451 -0.638302 -v 0.054301 0.089085 0.094575 -vn -0.000001 -0.759586 -0.650407 -v 0.054453 0.089096 0.094585 -vn -0.000001 -0.577996 -0.816039 -v 0.054453 0.089491 0.094224 -vn 0.192020 -0.567239 -0.800855 -v 0.054301 0.089483 0.094212 -vn 0.376892 -0.535377 -0.755860 -v 0.054155 0.089458 0.094177 -vn 0.376900 0.703229 -0.602840 -v 0.054155 0.092445 0.094546 -vn 0.192034 0.817938 -0.542310 -v 0.054301 0.092575 0.094789 -vn 0.000001 0.895040 -0.445986 -v 0.054453 0.092697 0.095030 -vn -0.192041 0.925509 -0.326426 -v 0.054605 0.092815 0.095271 -vn 0.376895 0.170462 0.910435 -v 0.054155 0.091160 0.098196 -vn 0.192034 0.060693 0.979510 -v 0.054301 0.090885 0.098186 -vn 0.000002 -0.061284 0.998120 -v 0.054453 0.090616 0.098172 -vn -0.192028 -0.180062 0.964730 -v 0.054605 0.090347 0.098153 -vn 0.376891 -0.873691 -0.307598 -v 0.054155 0.088642 0.095258 -vn 0.192028 -0.878622 -0.437206 -v 0.054301 0.088788 0.095024 -vn 0.000000 -0.833755 -0.552135 -v 0.054453 0.088935 0.094799 -vn -0.192030 -0.745452 -0.638300 -v 0.054605 0.089085 0.094575 -vn -0.192047 -0.464527 -0.864484 -v 0.054605 0.089712 0.094070 -vn -0.000000 -0.473338 -0.880881 -v 0.054453 0.089719 0.094083 -vn 0.192041 -0.464534 -0.864482 -v 0.054301 0.089712 0.094070 -vn 0.376894 -0.438438 -0.815918 -v 0.054155 0.089692 0.094032 -vn 0.550341 -0.392802 -0.736771 -v 0.054020 0.089658 0.093970 -vn 0.549109 0.484294 -0.681130 -v 0.054020 0.092080 0.094118 -vn 0.376884 0.623831 -0.684685 -v 0.054155 0.092254 0.094349 -vn 0.192032 0.745094 -0.638717 -v 0.054301 0.092412 0.094574 -vn 0.000001 0.833450 -0.552595 -v 0.054453 0.092563 0.094798 -vn -0.192044 0.878380 -0.437684 -v 0.054605 0.092710 0.095023 -vn -0.376893 0.873519 -0.308086 -v 0.054751 0.092856 0.095257 -vn 0.549123 0.347738 0.759962 -v 0.054020 0.091713 0.098094 -vn 0.376886 0.281041 0.882594 -v 0.054155 0.091427 0.098129 -vn 0.192024 0.180605 0.964629 -v 0.054301 0.091152 0.098153 -vn -0.000000 0.061840 0.998086 -v 0.054453 0.090884 0.098172 -vn -0.192034 -0.060148 0.979543 -v 0.054605 0.090615 0.098187 -vn -0.376890 -0.169944 0.910534 -v 0.054751 0.090339 0.098196 -vn 0.549123 -0.832015 -0.078836 -v 0.054020 0.088454 0.095788 -vn 0.376880 -0.904873 -0.197906 -v 0.054155 0.088567 0.095523 -vn 0.192030 -0.925692 -0.325912 -v 0.054301 0.088683 0.095272 -vn 0.000002 -0.895285 -0.445493 -v 0.054453 0.088801 0.095031 -vn -0.192032 -0.818236 -0.541861 -v 0.054605 0.088923 0.094790 -vn -0.376902 -0.703569 -0.602441 -v 0.054751 0.089052 0.094547 -vn -0.376902 -0.334844 -0.863611 -v 0.054751 0.089942 0.093917 -vn -0.192040 -0.354776 -0.915016 -v 0.054605 0.089957 0.093957 -vn 0.000001 -0.361503 -0.932371 -v 0.054453 0.089963 0.093971 -vn 0.192035 -0.354773 -0.915018 -v 0.054301 0.089957 0.093957 -vn 0.376897 -0.334845 -0.863613 -v 0.054155 0.089942 0.093917 -vn -0.376898 0.225674 -0.898343 -v 0.054751 0.091293 0.093833 -vn -0.376902 0.113576 -0.919264 -v 0.054751 0.091023 0.093783 -vn -0.192036 0.120335 -0.973982 -v 0.054605 0.091018 0.093826 -vn 0.376896 0.534958 -0.756155 -v 0.054155 0.092039 0.094176 -vn 0.192027 0.660961 -0.725436 -v 0.054301 0.092225 0.094381 -vn -0.000001 0.759224 -0.650829 -v 0.054453 0.092401 0.094584 -vn -0.192040 0.817937 -0.542309 -v 0.054605 0.092575 0.094789 -vn -0.376901 0.829034 -0.413097 -v 0.054751 0.092749 0.095004 -vn -0.549048 0.788599 -0.276873 -v 0.054887 0.092923 0.095233 -vn -0.376902 0.922278 -0.085725 -v 0.054751 0.092974 0.095793 -vn -0.376882 0.904761 -0.198414 -v 0.054751 0.092931 0.095521 -vn -0.192026 0.958610 -0.210222 -v 0.054605 0.092889 0.095531 -vn 0.376895 0.387369 0.841365 -v 0.054155 0.091683 0.098029 -vn 0.192039 0.297777 0.935120 -v 0.054301 0.091414 0.098087 -vn 0.000000 0.184030 0.982921 -v 0.054453 0.091150 0.098139 -vn -0.192039 0.060689 0.979509 -v 0.054605 0.090885 0.098186 -vn -0.376887 -0.056768 0.924518 -v 0.054751 0.090612 0.098230 -vn -0.549050 -0.154515 0.821383 -v 0.054887 0.090326 0.098266 -vn -0.376889 -0.386903 0.841582 -v 0.054751 0.089816 0.098030 -vn -0.376897 -0.280550 0.882746 -v 0.054751 0.090072 0.098129 -vn -0.192030 -0.297248 0.935290 -v 0.054605 0.090086 0.098088 -vn 0.376883 -0.922333 -0.085211 -v 0.054155 0.088524 0.095794 -vn 0.192020 -0.958729 -0.209684 -v 0.054301 0.088609 0.095532 -vn 0.000001 -0.943246 -0.332094 -v 0.054453 0.088697 0.095277 -vn -0.192035 -0.878621 -0.437204 -v 0.054605 0.088788 0.095024 -vn -0.376908 -0.772266 -0.511416 -v 0.054751 0.088886 0.094766 -vn -0.549058 -0.634073 -0.544506 -v 0.054887 0.088998 0.094501 -vn -0.376894 -0.535375 -0.755860 -v 0.054751 0.089458 0.094177 -vn -0.376895 -0.624204 -0.684339 -v 0.054751 0.089244 0.094349 -vn -0.192035 -0.661358 -0.725071 -v 0.054605 0.089273 0.094381 -vn -0.550883 -0.205220 -0.808958 -v 0.054887 0.090186 0.093765 -vn -0.376904 -0.226176 -0.898214 -v 0.054751 0.090204 0.093833 -vn -0.192042 -0.239637 -0.951680 -v 0.054605 0.090214 0.093876 -vn -0.000003 -0.244180 -0.969730 -v 0.054453 0.090218 0.093890 -vn 0.192042 -0.239637 -0.951680 -v 0.054301 0.090214 0.093876 -vn 0.376900 -0.226177 -0.898215 -v 0.054155 0.090204 0.093833 -vn 0.548659 -0.202814 -0.811074 -v 0.054020 0.090186 0.093765 -vn -0.549889 0.100619 -0.829155 -v 0.054887 0.091032 0.093713 -vn -0.548659 0.202360 -0.811186 -v 0.054887 0.091311 0.093765 -vn -0.549897 0.303465 -0.778153 -v 0.054887 0.091581 0.093851 -vn -0.331907 0.484496 -0.809383 -v 0.055006 0.091949 0.093921 -vn -0.327334 0.427187 -0.842831 -v 0.055006 0.091884 0.093885 -vn -0.550345 0.392391 -0.736987 -v 0.054887 0.091839 0.093969 -vn -0.376907 0.334363 -0.863796 -v 0.054751 0.091556 0.093917 -vn -0.192026 0.239108 -0.951816 -v 0.054605 0.091283 0.093875 -vn 0.000002 0.122613 -0.992455 -v 0.054453 0.091016 0.093840 -vn -0.550489 0.564535 -0.615030 -v 0.054887 0.092301 0.094296 -vn -0.550968 0.481572 -0.681559 -v 0.054887 0.092080 0.094118 -vn -0.376894 0.534959 -0.756155 -v 0.054751 0.092039 0.094176 -vn -0.376898 0.437976 -0.816165 -v 0.054751 0.091806 0.094031 -vn -0.192027 0.464042 -0.864749 -v 0.054605 0.091785 0.094070 -vn -0.192034 0.354265 -0.915215 -v 0.054605 0.091540 0.093957 -vn -0.000003 0.360985 -0.932571 -v 0.054453 0.091535 0.093971 -vn 0.000001 0.243643 -0.969865 -v 0.054453 0.091279 0.093890 -vn 0.192019 0.239114 -0.951816 -v 0.054301 0.091283 0.093875 -vn 0.376896 0.113574 -0.919266 -v 0.054155 0.091023 0.093783 -vn 0.547684 -0.000231 -0.836685 -v 0.054020 0.090749 0.093695 -vn 0.376897 0.225676 -0.898342 -v 0.054155 0.091293 0.093833 -vn 0.192035 0.354259 -0.915218 -v 0.054301 0.091540 0.093957 -vn -0.000000 0.472844 -0.881146 -v 0.054453 0.091778 0.094083 -vn -0.192037 0.566802 -0.801160 -v 0.054605 0.092014 0.094212 -vn -0.376889 0.623825 -0.684687 -v 0.054751 0.092254 0.094349 -vn -0.549050 0.633779 -0.544856 -v 0.054887 0.092499 0.094500 -vn -0.328015 0.699587 -0.634811 -v 0.055006 0.092571 0.094438 -vn -0.329665 0.738622 -0.588012 -v 0.055006 0.092587 0.094457 -vn 0.549900 0.303466 -0.778151 -v 0.054020 0.091581 0.093851 -vn 0.376901 0.334360 -0.863799 -v 0.054155 0.091556 0.093917 -vn 0.376895 0.437978 -0.816165 -v 0.054155 0.091806 0.094031 -vn 0.192025 0.464047 -0.864747 -v 0.054301 0.091785 0.094070 -vn 0.192030 0.566800 -0.801163 -v 0.054301 0.092014 0.094212 -vn 0.000002 0.577549 -0.816356 -v 0.054453 0.092006 0.094224 -vn -0.000001 0.673493 -0.739194 -v 0.054453 0.092215 0.094392 -vn -0.192029 0.660958 -0.725437 -v 0.054605 0.092225 0.094381 -vn -0.192036 0.745094 -0.638716 -v 0.054605 0.092412 0.094574 -vn -0.376901 0.703233 -0.602834 -v 0.054751 0.092445 0.094546 -vn -0.376886 0.771986 -0.511854 -v 0.054751 0.092611 0.094765 -vn -0.550255 0.695325 -0.462323 -v 0.054887 0.092670 0.094726 -vn -0.549905 0.815478 -0.180557 -v 0.054887 0.093000 0.095506 -vn -0.549106 0.831981 -0.079306 -v 0.054887 0.093044 0.095787 -vn -0.550332 0.834469 0.028209 -v 0.054887 0.093053 0.096070 -vn -0.330860 0.925720 0.183233 -v 0.055006 0.093113 0.096416 -vn -0.327551 0.937131 0.120401 -v 0.055006 0.093121 0.096367 -vn -0.549893 0.825705 0.125814 -v 0.054887 0.093027 0.096353 -vn -0.376913 0.925817 0.028268 -v 0.054751 0.092982 0.096068 -vn -0.192052 0.977174 -0.090812 -v 0.054605 0.092930 0.095797 -vn 0.000002 0.976789 -0.214203 -v 0.054453 0.092875 0.095534 -vn 0.549046 0.788602 -0.276867 -v 0.054020 0.092923 0.095233 -vn 0.376886 0.873522 -0.308086 -v 0.054155 0.092856 0.095257 -vn 0.376881 0.904762 -0.198408 -v 0.054155 0.092931 0.095521 -vn 0.192019 0.958614 -0.210211 -v 0.054301 0.092889 0.095531 -vn 0.192040 0.977176 -0.090823 -v 0.054301 0.092930 0.095797 -vn 0.000003 0.995709 -0.092543 -v 0.054453 0.092916 0.095799 -vn 0.000001 0.999534 0.030511 -v 0.054453 0.092924 0.096066 -vn -0.192034 0.980931 0.029943 -v 0.054605 0.092939 0.096067 -vn -0.192036 0.969815 0.150272 -v 0.054605 0.092914 0.096335 -vn -0.376904 0.915329 0.141830 -v 0.054751 0.092957 0.096342 -vn -0.376900 0.890965 0.253234 -v 0.054751 0.092898 0.096611 -vn -0.550890 0.803185 0.226746 -v 0.054887 0.092966 0.096630 -vn -0.550422 0.767692 0.328154 -v 0.054887 0.092872 0.096898 -vn 0.376903 0.922277 -0.085728 -v 0.054155 0.092974 0.095793 -vn 0.376908 0.925819 0.028264 -v 0.054155 0.092982 0.096068 -vn 0.192031 0.980932 0.029948 -v 0.054301 0.092939 0.096067 -vn 0.192034 0.969816 0.150267 -v 0.054301 0.092914 0.096335 -vn -0.000000 0.988208 0.153120 -v 0.054453 0.092899 0.096333 -vn -0.000002 0.961901 0.273399 -v 0.054453 0.092842 0.096595 -vn -0.192025 0.944001 0.268305 -v 0.054605 0.092856 0.096599 -vn -0.192043 0.903871 0.382279 -v 0.054605 0.092767 0.096853 -vn -0.376905 0.853093 0.360797 -v 0.054751 0.092807 0.096870 -vn -0.376906 0.802285 0.462905 -v 0.054751 0.092684 0.097117 -vn -0.547685 0.724706 0.418142 -v 0.054887 0.092745 0.097152 -vn -0.549897 0.667756 0.501712 -v 0.054887 0.092589 0.097388 -vn -0.327464 0.764218 0.555642 -v 0.055006 0.092665 0.097446 -vn 0.550331 0.834470 0.028207 -v 0.054020 0.093053 0.096070 -vn 0.376900 0.915331 0.141832 -v 0.054155 0.092957 0.096342 -vn 0.192024 0.944000 0.268312 -v 0.054301 0.092856 0.096599 -vn -0.000002 0.921013 0.389531 -v 0.054453 0.092753 0.096848 -vn -0.192042 0.850041 0.490459 -v 0.054605 0.092647 0.097095 -vn -0.376903 0.739319 0.557989 -v 0.054751 0.092532 0.097346 -vn -0.548661 0.601326 0.580842 -v 0.054887 0.092404 0.097604 -vn 0.376896 0.890966 0.253236 -v 0.054155 0.092898 0.096611 -vn 0.192041 0.903873 0.382275 -v 0.054301 0.092767 0.096853 -vn 0.000001 0.866165 0.499758 -v 0.054453 0.092634 0.097087 -vn -0.192032 0.783332 0.591197 -v 0.054605 0.092498 0.097320 -vn -0.376892 0.665154 0.644611 -v 0.054751 0.092353 0.097555 -vn -0.549902 0.522165 0.651883 -v 0.054887 0.092195 0.097795 -vn 0.548663 0.803816 0.229889 -v 0.054020 0.092966 0.096630 -vn 0.376903 0.853095 0.360796 -v 0.054155 0.092807 0.096870 -vn 0.192039 0.850042 0.490458 -v 0.054301 0.092647 0.097095 -vn -0.000001 0.798187 0.602410 -v 0.054453 0.092486 0.097311 -vn -0.192033 0.704744 0.682979 -v 0.054605 0.092322 0.097525 -vn -0.376891 0.580896 0.721466 -v 0.054751 0.092150 0.097740 -vn -0.550336 0.442057 0.708319 -v 0.054887 0.091963 0.097959 -vn -0.327354 0.516284 0.791385 -v 0.055006 0.092013 0.098040 -vn -0.331927 0.458675 0.824283 -v 0.055006 0.091950 0.098078 -vn 0.547685 0.724706 0.418141 -v 0.054020 0.092745 0.097152 -vn 0.376901 0.802286 0.462906 -v 0.054155 0.092684 0.097117 -vn 0.376898 0.739322 0.557988 -v 0.054155 0.092532 0.097346 -vn 0.192032 0.783331 0.591200 -v 0.054301 0.092498 0.097320 -vn 0.192035 0.704743 0.682979 -v 0.054301 0.092322 0.097525 -vn -0.000004 0.718105 0.695935 -v 0.054453 0.092312 0.097514 -vn 0.000004 0.627144 0.778904 -v 0.054453 0.092114 0.097695 -vn -0.192045 0.615465 0.764409 -v 0.054605 0.092123 0.097706 -vn -0.192039 0.516863 0.834250 -v 0.054605 0.091903 0.097862 -vn -0.376893 0.487833 0.787382 -v 0.054751 0.091926 0.097899 -vn -0.376904 0.387364 0.841364 -v 0.054751 0.091683 0.098029 -vn -0.550973 0.349460 0.757831 -v 0.054887 0.091713 0.098094 -vn -0.550489 0.250369 0.796415 -v 0.054887 0.091448 0.098196 -vn 0.376887 0.665153 0.644615 -v 0.054155 0.092353 0.097555 -vn 0.192033 0.615468 0.764410 -v 0.054301 0.092123 0.097706 -vn 0.000003 0.526669 0.850071 -v 0.054453 0.091895 0.097850 -vn -0.192038 0.410428 0.891443 -v 0.054605 0.091665 0.097990 -vn -0.376895 0.281044 0.882590 -v 0.054751 0.091427 0.098129 -vn -0.549056 0.154979 0.821291 -v 0.054887 0.091173 0.098265 -vn -0.328020 0.200032 0.923250 -v 0.055006 0.091191 0.098359 -vn -0.329659 0.139988 0.933664 -v 0.055006 0.091167 0.098363 -vn -0.549895 -0.251372 0.796510 -v 0.054887 0.090051 0.098197 -vn -0.549104 -0.347314 0.760170 -v 0.054887 0.089786 0.098094 -vn -0.550333 -0.441662 0.708567 -v 0.054887 0.089536 0.097960 -vn -0.330858 -0.621519 0.710103 -v 0.055006 0.089207 0.097839 -vn -0.327555 -0.572805 0.751400 -v 0.055006 0.089245 0.097870 -vn -0.549900 -0.521804 0.652174 -v 0.054887 0.089305 0.097796 -vn -0.376907 -0.487393 0.787648 -v 0.054751 0.089574 0.097900 -vn -0.192047 -0.409938 0.891666 -v 0.054605 0.089834 0.097990 -vn -0.000002 -0.302892 0.953025 -v 0.054453 0.090090 0.098074 -vn 0.549052 -0.154513 0.821381 -v 0.054020 0.090326 0.098266 -vn 0.376887 -0.169946 0.910536 -v 0.054155 0.090339 0.098196 -vn 0.376896 -0.280546 0.882747 -v 0.054155 0.090072 0.098129 -vn 0.192027 -0.297251 0.935290 -v 0.054301 0.090086 0.098088 -vn 0.192040 -0.409936 0.891669 -v 0.054301 0.089834 0.097990 -vn 0.000001 -0.417715 0.908578 -v 0.054453 0.089840 0.097977 -vn -0.000000 -0.526198 0.850362 -v 0.054453 0.089604 0.097850 -vn -0.192044 -0.516403 0.834534 -v 0.054605 0.089596 0.097863 -vn -0.192037 -0.615044 0.764750 -v 0.054605 0.089376 0.097707 -vn -0.376903 -0.580491 0.721786 -v 0.054751 0.089349 0.097741 -vn -0.376901 -0.664790 0.644980 -v 0.054751 0.089146 0.097556 -vn -0.550889 -0.597962 0.582205 -v 0.054887 0.089095 0.097605 -vn -0.550427 -0.668034 0.500760 -v 0.054887 0.088910 0.097389 -vn 0.376892 -0.386907 0.841579 -v 0.054155 0.089816 0.098030 -vn 0.376899 -0.487392 0.787652 -v 0.054155 0.089574 0.097900 -vn 0.192042 -0.516402 0.834535 -v 0.054301 0.089596 0.097863 -vn 0.192035 -0.615045 0.764750 -v 0.054301 0.089376 0.097707 -vn 0.000000 -0.626707 0.779255 -v 0.054453 0.089385 0.097696 -vn -0.000001 -0.717716 0.696336 -v 0.054453 0.089187 0.097515 -vn -0.192033 -0.704359 0.683375 -v 0.054605 0.089177 0.097525 -vn -0.192033 -0.782997 0.591642 -v 0.054605 0.089001 0.097321 -vn -0.376895 -0.739014 0.558399 -v 0.054751 0.088967 0.097347 -vn -0.376886 -0.802034 0.463356 -v 0.054751 0.088815 0.097118 -vn -0.547696 -0.724469 0.418537 -v 0.054887 0.088753 0.097153 -vn -0.549893 -0.768376 0.327438 -v 0.054887 0.088627 0.096899 -vn -0.327469 -0.863314 0.383997 -v 0.055006 0.088539 0.096936 -vn 0.550337 -0.441661 0.708565 -v 0.054020 0.089536 0.097960 -vn 0.376897 -0.580493 0.721787 -v 0.054155 0.089349 0.097741 -vn 0.192032 -0.704360 0.683375 -v 0.054301 0.089177 0.097525 -vn -0.000004 -0.797847 0.602859 -v 0.054453 0.089013 0.097312 -vn -0.192031 -0.849769 0.490934 -v 0.054605 0.088852 0.097096 -vn -0.376883 -0.852897 0.361284 -v 0.054751 0.088692 0.096871 -vn -0.548649 -0.803694 0.230346 -v 0.054887 0.088533 0.096631 -vn 0.376897 -0.664790 0.644983 -v 0.054155 0.089146 0.097556 -vn 0.192038 -0.782995 0.591643 -v 0.054301 0.089001 0.097321 -vn 0.000000 -0.865885 0.500243 -v 0.054453 0.088865 0.097089 -vn -0.192040 -0.903659 0.382782 -v 0.054605 0.088732 0.096854 -vn -0.376887 -0.890829 0.253730 -v 0.054751 0.088600 0.096612 -vn -0.549902 -0.825630 0.126265 -v 0.054887 0.088472 0.096354 -vn 0.548660 -0.601004 0.581177 -v 0.054020 0.089095 0.097605 -vn 0.376886 -0.739017 0.558400 -v 0.054155 0.088967 0.097347 -vn 0.192027 -0.849772 0.490932 -v 0.054301 0.088852 0.097096 -vn -0.000002 -0.920800 0.390036 -v 0.054453 0.088745 0.096849 -vn -0.192054 -0.943849 0.268821 -v 0.054605 0.088642 0.096600 -vn -0.376903 -0.915252 0.142328 -v 0.054751 0.088542 0.096343 -vn -0.550341 -0.834447 0.028676 -v 0.054887 0.088445 0.096072 -vn -0.327352 -0.943500 0.051461 -v 0.055006 0.088350 0.096075 -vn -0.331926 -0.943188 -0.014889 -v 0.055006 0.088349 0.096001 -vn 0.547694 -0.724468 0.418543 -v 0.054020 0.088753 0.097153 -vn 0.376884 -0.802035 0.463356 -v 0.054155 0.088815 0.097118 -vn 0.376885 -0.852896 0.361284 -v 0.054155 0.088692 0.096871 -vn 0.192036 -0.903660 0.382780 -v 0.054301 0.088732 0.096854 -vn 0.192048 -0.943848 0.268829 -v 0.054301 0.088642 0.096600 -vn 0.000002 -0.961751 0.273925 -v 0.054453 0.088656 0.096596 -vn 0.000006 -0.988122 0.153669 -v 0.054453 0.088599 0.096334 -vn -0.192039 -0.969731 0.150804 -v 0.054605 0.088585 0.096337 -vn -0.192033 -0.980915 0.030499 -v 0.054605 0.088560 0.096068 -vn -0.376899 -0.925807 0.028781 -v 0.054751 0.088516 0.096069 -vn -0.376891 -0.922330 -0.085210 -v 0.054751 0.088524 0.095794 -vn -0.550974 -0.831029 -0.076278 -v 0.054887 0.088454 0.095788 -vn -0.550483 -0.814905 -0.181381 -v 0.054887 0.088498 0.095508 -vn 0.376883 -0.890832 0.253726 -v 0.054155 0.088600 0.096612 -vn 0.192028 -0.969734 0.150800 -v 0.054301 0.088585 0.096337 -vn -0.000004 -0.999517 0.031072 -v 0.054453 0.088574 0.096068 -vn -0.192039 -0.977226 -0.090275 -v 0.054605 0.088568 0.095798 -vn -0.376883 -0.904872 -0.197902 -v 0.054751 0.088567 0.095523 -vn -0.549047 -0.788755 -0.276429 -v 0.054887 0.088575 0.095235 -vn -0.328022 -0.899572 -0.288396 -v 0.055006 0.088485 0.095203 -vn -0.329661 -0.878565 -0.345611 -v 0.055006 0.088494 0.095180 -vn -0.549893 -0.564113 -0.615950 -v 0.054887 0.089196 0.094297 -vn -0.549123 -0.484658 -0.680860 -v 0.054887 0.089417 0.094119 -vn -0.550340 -0.392804 -0.736770 -v 0.054887 0.089658 0.093970 -vn -0.330859 -0.304207 -0.893303 -v 0.055006 0.089928 0.093745 -vn -0.327558 -0.364327 -0.871764 -v 0.055006 0.089882 0.093762 -vn -0.549894 -0.303904 -0.777984 -v 0.054887 0.089916 0.093851 -vn -0.376893 -0.438440 -0.815918 -v 0.054751 0.089692 0.094032 -vn -0.192024 -0.567246 -0.800849 -v 0.054605 0.089483 0.094212 -vn -0.000001 -0.673901 -0.738821 -v 0.054453 0.089283 0.094392 -vn 0.000001 -0.000277 -1.000000 -v 0.054453 0.090749 0.093824 -vn -0.192041 -0.000272 -0.981387 -v 0.054605 0.090749 0.093809 -vn -0.376893 -0.000257 -0.926257 -v 0.054751 0.090749 0.093766 -vn -0.547684 -0.000229 -0.836685 -v 0.054887 0.090749 0.093695 -vn -0.327456 0.099111 -0.939654 -v 0.055006 0.091043 0.093618 -vn -0.326581 -0.000261 -0.945169 -v 0.055006 0.090748 0.093600 -vn -0.327550 0.363820 -0.871978 -v 0.055006 0.091616 0.093762 -vn -0.330854 0.303682 -0.893484 -v 0.055006 0.091569 0.093745 -vn -0.330160 0.233584 -0.914567 -v 0.055006 0.091334 0.093672 -vn -0.340474 0.172759 -0.924247 -v 0.055006 0.091165 0.093636 -vn -0.327425 0.650630 -0.685181 -v 0.055006 0.092366 0.094226 -vn -0.332751 0.598102 -0.729075 -v 0.055006 0.092291 0.094161 -vn -0.327445 0.543735 -0.772743 -v 0.055006 0.092135 0.094041 -vn -0.327470 0.780778 -0.532118 -v 0.055006 0.092749 0.094674 -vn -0.343381 0.816100 -0.464834 -v 0.055006 0.092827 0.094799 -vn -0.328028 0.899404 -0.288912 -v 0.055006 0.093012 0.095202 -vn -0.327424 0.918583 -0.221356 -v 0.055006 0.093093 0.095486 -vn -0.327330 0.943537 0.050914 -v 0.055006 0.093148 0.096073 -vn -0.331907 0.943186 -0.015432 -v 0.055006 0.093149 0.095999 -vn -0.329617 0.940027 -0.087759 -v 0.055006 0.093139 0.095778 -vn -0.337686 0.929237 -0.149958 -v 0.055006 0.093113 0.095583 -vn -0.326580 0.818673 0.472356 -v 0.055006 0.092828 0.097199 -vn -0.327455 0.863526 0.383532 -v 0.055006 0.092960 0.096935 -vn -0.333270 0.887803 0.317391 -v 0.055006 0.093005 0.096820 -vn -0.327458 0.910819 0.251357 -v 0.055006 0.093058 0.096656 -vn -0.327550 0.573265 0.751052 -v 0.055006 0.092254 0.097869 -vn -0.330858 0.621943 0.709733 -v 0.055006 0.092292 0.097838 -vn -0.330177 0.675230 0.659582 -v 0.055006 0.092473 0.097670 -vn -0.340490 0.714042 0.611727 -v 0.055006 0.092588 0.097542 -vn -0.327426 0.268096 0.906045 -v 0.055006 0.091477 0.098287 -vn -0.332753 0.332361 0.882503 -v 0.055006 0.091571 0.098255 -vn -0.327456 0.397342 0.857258 -v 0.055006 0.091753 0.098180 -vn -0.376898 0.170459 0.910435 -v 0.054751 0.091160 0.098196 -vn -0.192039 0.297774 0.935121 -v 0.054605 0.091414 0.098087 -vn -0.000005 0.418204 0.908353 -v 0.054453 0.091659 0.097977 -vn 0.192030 0.516862 0.834253 -v 0.054301 0.091903 0.097862 -vn 0.376894 0.580897 0.721464 -v 0.054155 0.092150 0.097740 -vn -0.376893 0.057283 0.924484 -v 0.054751 0.090887 0.098230 -vn -0.192028 0.180611 0.964627 -v 0.054605 0.091152 0.098153 -vn -0.000001 0.303422 0.952856 -v 0.054453 0.091409 0.098073 -vn 0.192043 0.410429 0.891441 -v 0.054301 0.091665 0.097990 -vn 0.376894 0.487831 0.787383 -v 0.054155 0.091926 0.097899 -vn 0.549897 0.522170 0.651883 -v 0.054020 0.092195 0.097795 -vn -0.328027 -0.199501 0.923362 -v 0.055006 0.090309 0.098359 -vn -0.327409 -0.267567 0.906207 -v 0.055006 0.090022 0.098287 -vn -0.327349 -0.515867 0.791659 -v 0.055006 0.089486 0.098041 -vn -0.331919 -0.458221 0.824538 -v 0.055006 0.089550 0.098079 -vn -0.329615 -0.394010 0.857969 -v 0.055006 0.089747 0.098181 -vn -0.337676 -0.334743 0.879729 -v 0.055006 0.089929 0.098255 -vn -0.326587 -0.818406 0.472814 -v 0.055006 0.088671 0.097201 -vn -0.327461 -0.763907 0.556072 -v 0.055006 0.088834 0.097447 -vn -0.333272 -0.718768 0.610166 -v 0.055006 0.088911 0.097543 -vn -0.327456 -0.673094 0.663111 -v 0.055006 0.089027 0.097671 -vn -0.327552 -0.937060 0.120950 -v 0.055006 0.088378 0.096369 -vn -0.330860 -0.925612 0.183777 -v 0.055006 0.088386 0.096417 -vn -0.330173 -0.908830 0.254979 -v 0.055006 0.088441 0.096657 -vn -0.340492 -0.886797 0.312500 -v 0.055006 0.088494 0.096821 -vn -0.327422 -0.918706 -0.220849 -v 0.055006 0.088405 0.095487 -vn -0.332750 -0.930450 -0.153428 -v 0.055006 0.088386 0.095584 -vn -0.327456 -0.941077 -0.084535 -v 0.055006 0.088359 0.095779 -vn -0.376893 -0.873691 -0.307598 -v 0.054751 0.088642 0.095258 -vn -0.192026 -0.958729 -0.209676 -v 0.054605 0.088609 0.095532 -vn -0.000002 -0.995760 -0.091986 -v 0.054453 0.088582 0.095800 -vn 0.192035 -0.980914 0.030497 -v 0.054301 0.088560 0.096068 -vn 0.376902 -0.915252 0.142334 -v 0.054155 0.088542 0.096343 -vn -0.376905 -0.829261 -0.412638 -v 0.054751 0.088749 0.095005 -vn -0.192037 -0.925690 -0.325914 -v 0.054605 0.088683 0.095272 -vn 0.000002 -0.976909 -0.213656 -v 0.054453 0.088623 0.095535 -vn 0.192041 -0.977227 -0.090270 -v 0.054301 0.088568 0.095798 -vn 0.376895 -0.925809 0.028781 -v 0.054155 0.088516 0.096069 -vn 0.549901 -0.825630 0.126271 -v 0.054020 0.088472 0.096354 -vn -0.328026 -0.699897 -0.634463 -v 0.055006 0.088926 0.094439 -vn -0.327419 -0.651005 -0.684828 -v 0.055006 0.089132 0.094227 -vn -0.327359 -0.427661 -0.842581 -v 0.055006 0.089613 0.093886 -vn -0.331928 -0.484952 -0.809101 -v 0.055006 0.089549 0.093922 -vn -0.329621 -0.546020 -0.770203 -v 0.055006 0.089362 0.094042 -vn -0.337685 -0.594499 -0.729753 -v 0.055006 0.089206 0.094162 -vn -0.327453 -0.237707 -0.914478 -v 0.055006 0.090163 0.093673 -vn -0.550418 -0.099656 -0.828920 -v 0.054887 0.090465 0.093713 -vn -0.327453 -0.099636 -0.939600 -v 0.055006 0.090454 0.093618 -vn -0.333263 -0.169035 -0.927557 -v 0.055006 0.090332 0.093637 -vn 0.376897 -0.114083 -0.919203 -v 0.054155 0.090474 0.093783 -vn 0.192049 -0.120880 -0.973912 -v 0.054301 0.090479 0.093826 -vn -0.000003 -0.123167 -0.992386 -v 0.054453 0.090481 0.093841 -vn -0.192047 -0.120877 -0.973913 -v 0.054605 0.090479 0.093826 -vn -0.376902 -0.114081 -0.919201 -v 0.054751 0.090474 0.093783 -vn 0.689614 -0.713237 0.125403 -v 0.056453 0.088386 0.096417 -vn 0.689672 -0.724122 0.000795 -v 0.056453 0.088349 0.096001 -vn 0.689924 -0.680092 0.247951 -v 0.056453 0.088494 0.096821 -vn 0.689652 -0.627024 0.362245 -v 0.056453 0.088671 0.097201 -vn 0.689924 -0.554523 0.465305 -v 0.056453 0.088911 0.097543 -vn 0.689611 -0.464913 0.555241 -v 0.056453 0.089207 0.097839 -vn 0.689675 -0.362398 0.626910 -v 0.056453 0.089550 0.098079 -vn 0.689829 -0.247050 0.680516 -v 0.056453 0.089929 0.098255 -vn 0.689656 -0.125818 0.713123 -v 0.056453 0.090333 0.098364 -vn 0.689958 0.000201 0.723850 -v 0.056453 0.090750 0.098400 -vn 0.689655 0.126218 0.713053 -v 0.056453 0.091167 0.098363 -vn 0.689832 0.247431 0.680375 -v 0.056453 0.091571 0.098255 -vn 0.689676 0.362749 0.626706 -v 0.056453 0.091950 0.098078 -vn 0.689614 0.465218 0.554982 -v 0.056453 0.092292 0.097838 -vn 0.689922 0.554781 0.465000 -v 0.056453 0.092588 0.097542 -vn 0.689652 0.627226 0.361895 -v 0.056453 0.092828 0.097199 -vn 0.689923 0.680229 0.247577 -v 0.056453 0.093005 0.096820 -vn 0.689612 0.713309 0.125002 -v 0.056453 0.093113 0.096416 -vn 0.689676 0.724118 0.000393 -v 0.056453 0.093149 0.095999 -vn 0.689831 0.712868 -0.126303 -v 0.056453 0.093113 0.095583 -vn 0.689656 0.680492 -0.247598 -v 0.056453 0.093004 0.095179 -vn 0.689957 0.626772 -0.362101 -v 0.056453 0.092827 0.094799 -vn 0.689658 0.554413 -0.465831 -v 0.056453 0.092587 0.094457 -vn 0.689829 0.465512 -0.554468 -v 0.056453 0.092291 0.094161 -vn 0.689675 0.361370 -0.627504 -v 0.056453 0.091949 0.093921 -vn 0.689611 0.248015 -0.680386 -v 0.056453 0.091569 0.093745 -vn 0.689927 0.125310 -0.712951 -v 0.056453 0.091165 0.093636 -vn 0.689650 -0.000201 -0.724143 -v 0.056453 0.090748 0.093600 -vn 0.689928 -0.125703 -0.712880 -v 0.056453 0.090332 0.093637 -vn 0.689610 -0.248392 -0.680249 -v 0.056453 0.089928 0.093745 -vn 0.689674 -0.361721 -0.627301 -v 0.056453 0.089549 0.093922 -vn 0.689831 -0.465817 -0.554209 -v 0.056453 0.089206 0.094162 -vn 0.689655 -0.554672 -0.465526 -v 0.056453 0.088910 0.094458 -vn 0.689957 -0.626975 -0.361749 -v 0.056453 0.088670 0.094801 -vn 0.689654 -0.680633 -0.247217 -v 0.056453 0.088494 0.095180 -vn 0.689834 -0.712935 -0.125910 -v 0.056453 0.088386 0.095584 -vn 0.995629 -0.052633 -0.077152 -v 0.056453 0.091679 0.097363 -vn 0.995630 -0.063541 -0.068442 -v 0.056453 0.091872 0.097209 -vn 0.995630 -0.073031 -0.058208 -v 0.056453 0.092039 0.097028 -vn 0.995629 -0.080895 -0.046674 -v 0.056453 0.092178 0.096825 -vn 0.995630 -0.086939 -0.034094 -v 0.056453 0.092285 0.096602 -vn 0.995629 -0.091064 -0.020757 -v 0.056453 0.092358 0.096367 -vn 0.995630 -0.040495 0.084146 -v 0.056453 0.091465 0.094513 -vn 0.995630 -0.027501 0.089246 -v 0.056453 0.091235 0.094423 -vn 0.995630 -0.013893 0.092348 -v 0.056453 0.090995 0.094368 -vn 0.995629 0.000026 0.093396 -v 0.056453 0.090749 0.094350 -vn 0.995630 0.013944 0.092342 -v 0.056453 0.090503 0.094368 -vn 0.995629 0.027555 0.089239 -v 0.056453 0.090262 0.094423 -vn 0.995630 0.040495 -0.084147 -v 0.056453 0.090034 0.097487 -vn 0.995628 0.027504 -0.089261 -v 0.056453 0.090263 0.097577 -vn 0.995630 0.013894 -0.092347 -v 0.056453 0.090504 0.097632 -vn 0.995629 -0.000028 -0.093395 -v 0.056453 0.090750 0.097650 -vn 0.995630 -0.013945 -0.092344 -v 0.056453 0.090996 0.097631 -vn 0.995629 -0.027553 -0.089239 -v 0.056453 0.091236 0.097577 -vn 0.995629 -0.040546 -0.084133 -v 0.056453 0.091465 0.097486 -vn 0.995631 -0.093120 -0.006954 -v 0.056453 0.092395 0.096123 -vn 0.995629 -0.093135 0.007007 -v 0.056453 0.092395 0.095876 -vn 0.995630 -0.091042 0.020805 -v 0.056453 0.092358 0.095632 -vn 0.995630 -0.086924 0.034143 -v 0.056453 0.092285 0.095397 -vn 0.995629 -0.080868 0.046719 -v 0.056453 0.092178 0.095175 -vn 0.995629 -0.073003 0.058250 -v 0.056453 0.092039 0.094971 -vn 0.995629 -0.063507 0.068484 -v 0.056453 0.091871 0.094790 -vn 0.995630 -0.052587 0.077178 -v 0.056453 0.091678 0.094636 -vn 0.995629 0.040546 0.084134 -v 0.056453 0.090033 0.094514 -vn 0.995630 0.052629 0.077148 -v 0.056453 0.089819 0.094637 -vn 0.995629 0.063542 0.068443 -v 0.056453 0.089627 0.094791 -vn 0.995630 0.073030 0.058207 -v 0.056453 0.089459 0.094972 -vn 0.995629 0.080896 0.046675 -v 0.056453 0.089320 0.095175 -vn 0.995629 0.086949 0.034097 -v 0.056453 0.089213 0.095398 -vn 0.995630 0.091052 0.020756 -v 0.056453 0.089140 0.095633 -vn 0.995519 0.094158 0.008742 -v 0.056453 0.089104 0.095877 -vn 0.995854 0.090964 -0.000026 -v 0.056453 0.089099 0.096000 -vn 0.995518 0.094161 -0.008798 -v 0.056453 0.089104 0.096124 -vn 0.995630 0.091042 -0.020805 -v 0.056453 0.089141 0.096368 -vn 0.995629 0.086928 -0.034145 -v 0.056453 0.089213 0.096603 -vn 0.995631 0.080858 -0.046712 -v 0.056453 0.089320 0.096825 -vn 0.995630 0.072998 -0.058247 -v 0.056453 0.089459 0.097029 -vn 0.995629 0.063507 -0.068484 -v 0.056453 0.089627 0.097210 -vn 0.995630 0.052584 -0.077171 -v 0.056453 0.089820 0.097364 -vn 0.080546 0.485722 0.870394 -v 0.056303 0.090046 0.094675 -vn 0.094964 0.563731 0.820481 -v 0.056303 0.089904 0.094761 -vn 0.383333 0.523536 0.760898 -v 0.056360 0.089897 0.094751 -vn 0.087409 0.810274 0.579496 -v 0.056303 0.089555 0.095093 -vn 0.093778 0.860942 0.499984 -v 0.056303 0.089450 0.095250 -vn 0.384389 0.800755 0.459388 -v 0.056360 0.089440 0.095245 -vn 0.094861 0.979128 0.179747 -v 0.056303 0.089284 0.095678 -vn 0.098323 0.991006 0.090777 -v 0.056303 0.089253 0.095888 -vn 0.380447 0.921806 0.074393 -v 0.056360 0.089242 0.095887 -vn 0.073266 0.997312 -0.000264 -v 0.056303 0.089249 0.096000 -vn 0.097728 0.990939 -0.092136 -v 0.056303 0.089253 0.096113 -vn 0.381004 0.921473 -0.075651 -v 0.056360 0.089242 0.096113 -vn 0.074647 0.900961 -0.427431 -v 0.056303 0.089388 0.096630 -vn 0.096544 0.856053 -0.507792 -v 0.056303 0.089450 0.096750 -vn 0.381927 0.797559 -0.466939 -v 0.056360 0.089440 0.096756 -vn 0.078717 0.631077 -0.771716 -v 0.056303 0.089778 0.097144 -vn 0.095401 0.556102 -0.825621 -v 0.056303 0.089905 0.097240 -vn 0.382976 0.516732 -0.765714 -v 0.056360 0.089898 0.097249 -vn 0.084951 0.240722 -0.966869 -v 0.056303 0.090348 0.097445 -vn 0.094225 0.148858 -0.984359 -v 0.056303 0.090526 0.097483 -vn 0.384011 0.134620 -0.913462 -v 0.056360 0.090524 0.097495 -vn 0.073915 -0.728505 -0.681041 -v 0.056303 0.091838 0.097031 -vn 0.096970 -0.786653 -0.609732 -v 0.056303 0.091922 0.096935 -vn 0.381645 -0.726361 -0.571617 -v 0.056360 0.091931 0.096942 -vn 0.077051 -0.949727 -0.303450 -v 0.056303 0.092171 0.096479 -vn 0.095755 -0.972126 -0.214014 -v 0.056303 0.092212 0.096333 -vn 0.382638 -0.901794 -0.200887 -v 0.056360 0.092223 0.096336 -vn 0.082706 -0.987833 0.131703 -v 0.056303 0.092240 0.095837 -vn 0.094590 -0.970212 0.223028 -v 0.056303 0.092211 0.095666 -vn 0.383682 -0.899527 0.208901 -v 0.056360 0.092223 0.095663 -vn 0.089912 -0.836812 0.540057 -v 0.056303 0.092034 0.095226 -vn 0.093410 -0.781255 0.617183 -v 0.056303 0.091922 0.095064 -vn 0.384765 -0.720365 0.577088 -v 0.056360 0.091931 0.095057 -vn 0.097146 -0.527575 0.843936 -v 0.056303 0.091591 0.094758 -vn 0.098318 -0.448888 0.888163 -v 0.056303 0.091400 0.094648 -vn 0.380562 -0.406699 0.830523 -v 0.056360 0.091405 0.094638 -vn 0.927562 0.372520 0.029273 -v 0.056442 0.089161 0.095881 -vn 0.927143 -0.110346 0.358092 -v 0.056442 0.091218 0.094478 -vn 0.927145 -0.055744 0.370533 -v 0.056442 0.090986 0.094425 -vn 0.927146 0.000103 0.374701 -v 0.056442 0.090749 0.094407 -vn 0.927149 0.055945 0.370492 -v 0.056442 0.090511 0.094425 -vn 0.927141 0.110549 0.358034 -v 0.056442 0.090279 0.094478 -vn 0.711773 -0.206852 0.671261 -v 0.056409 0.091204 0.094525 -vn 0.711750 -0.104492 0.694618 -v 0.056409 0.090979 0.094473 -vn 0.711773 0.000192 0.702410 -v 0.056409 0.090749 0.094456 -vn 0.711777 0.104880 0.694531 -v 0.056409 0.090519 0.094473 -vn 0.711772 0.207224 0.671147 -v 0.056409 0.090294 0.094525 -vn 0.381301 -0.266471 0.885213 -v 0.056360 0.091194 0.094556 -vn 0.382459 -0.135089 0.914044 -v 0.056360 0.090974 0.094505 -vn 0.927143 -0.254791 0.274751 -v 0.056442 0.091832 0.094832 -vn 0.927138 -0.292903 0.233715 -v 0.056442 0.091994 0.095007 -vn 0.711765 -0.477619 0.515045 -v 0.056409 0.091799 0.094868 -vn 0.711780 -0.549041 0.438091 -v 0.056409 0.091956 0.095037 -vn 0.380858 -0.624800 0.681596 -v 0.056360 0.091777 0.094892 -vn 0.927138 -0.348780 0.136998 -v 0.056442 0.092231 0.095418 -vn 0.927136 -0.365307 0.083487 -v 0.056442 0.092302 0.095645 -vn 0.711794 -0.653766 0.256785 -v 0.056409 0.092186 0.095436 -vn 0.711778 -0.684751 0.156488 -v 0.056409 0.092254 0.095656 -vn 0.380392 -0.858808 0.343150 -v 0.056360 0.092156 0.095447 -vn 0.927141 -0.373673 -0.027899 -v 0.056442 0.092337 0.096119 -vn 0.927138 -0.365350 -0.083281 -v 0.056442 0.092302 0.096354 -vn 0.711754 -0.700480 -0.052290 -v 0.056409 0.092289 0.096115 -vn 0.711797 -0.684818 -0.156108 -v 0.056409 0.092254 0.096343 -vn 0.380415 -0.922595 -0.064059 -v 0.056360 0.092256 0.096113 -vn 0.927145 -0.324553 -0.187263 -v 0.056442 0.092129 0.096796 -vn 0.927135 -0.293040 -0.233555 -v 0.056442 0.091995 0.096993 -vn 0.711773 -0.608400 -0.351040 -v 0.056409 0.092086 0.096772 -vn 0.711760 -0.549302 -0.437796 -v 0.056409 0.091957 0.096962 -vn 0.381614 -0.802198 -0.459184 -v 0.056360 0.092058 0.096755 -vn 0.927138 -0.211173 -0.309550 -v 0.056442 0.091647 0.097316 -vn 0.927138 -0.162680 -0.337566 -v 0.056442 0.091441 0.097435 -vn 0.711768 -0.395850 -0.580250 -v 0.056409 0.091619 0.097275 -vn 0.711787 -0.304936 -0.632751 -v 0.056409 0.091419 0.097391 -vn 0.385138 -0.520488 -0.762077 -v 0.056360 0.091601 0.097249 -vn 0.381088 -0.406039 -0.830604 -v 0.056360 0.091405 0.097362 -vn 0.927145 -0.000102 -0.374702 -v 0.056442 0.090750 0.097593 -vn 0.927144 0.055745 -0.370534 -v 0.056442 0.090512 0.097575 -vn 0.711772 -0.000195 -0.702410 -v 0.056409 0.090750 0.097544 -vn 0.711750 0.104492 -0.694617 -v 0.056409 0.090519 0.097527 -vn 0.380509 -0.005711 -0.924760 -v 0.056360 0.090750 0.097511 -vn 0.927137 0.162492 -0.337658 -v 0.056442 0.090059 0.097435 -vn 0.927140 0.210996 -0.309664 -v 0.056442 0.089852 0.097316 -vn 0.711763 0.304590 -0.632944 -v 0.056409 0.090080 0.097391 -vn 0.711761 0.395529 -0.580477 -v 0.056409 0.089880 0.097276 -vn 0.380324 0.396431 -0.835581 -v 0.056360 0.090094 0.097362 -vn 0.927133 0.292913 -0.233723 -v 0.056442 0.089504 0.096993 -vn 0.927141 0.324458 -0.187447 -v 0.056442 0.089370 0.096797 -vn 0.711741 0.549068 -0.438120 -v 0.056409 0.089542 0.096963 -vn 0.711763 0.608218 -0.351375 -v 0.056409 0.089412 0.096772 -vn 0.381042 0.720283 -0.579655 -v 0.056360 0.089568 0.096943 -vn 0.927136 0.365307 -0.083487 -v 0.056442 0.089197 0.096355 -vn 0.927550 0.372533 -0.029483 -v 0.056442 0.089161 0.096119 -vn 0.711747 0.684780 -0.156503 -v 0.056409 0.089244 0.096344 -vn 0.711769 0.700436 -0.052682 -v 0.056409 0.089210 0.096116 -vn 0.383618 0.899951 -0.207186 -v 0.056360 0.089276 0.096337 -vn 0.927140 0.348851 0.136801 -v 0.056442 0.089266 0.095419 -vn 0.927134 0.324577 0.187274 -v 0.056442 0.089370 0.095204 -vn 0.711779 0.653919 0.256438 -v 0.056409 0.089312 0.095436 -vn 0.711783 0.608394 0.351030 -v 0.056409 0.089412 0.095228 -vn 0.380680 0.862846 0.332535 -v 0.056360 0.089342 0.095448 -vn 0.927143 0.254941 0.274610 -v 0.056442 0.089666 0.094833 -vn 0.927137 0.211178 0.309550 -v 0.056442 0.089852 0.094684 -vn 0.711757 0.477915 0.514780 -v 0.056409 0.089699 0.094869 -vn 0.711791 0.395830 0.580234 -v 0.056409 0.089879 0.094725 -vn 0.380299 0.633143 0.674169 -v 0.056360 0.089721 0.094892 -vn 0.379993 -0.006747 0.924965 -v 0.056360 0.090749 0.094489 -vn 0.382244 0.142875 0.912949 -v 0.056360 0.090523 0.094506 -vn 0.380628 0.277011 0.882262 -v 0.056360 0.090303 0.094556 -vn 0.090770 -0.194859 0.976622 -v 0.056303 0.090991 0.094520 -vn 0.097324 -0.278215 0.955575 -v 0.056303 0.091191 0.094567 -vn 0.073392 -0.365977 0.927725 -v 0.056303 0.091304 0.094606 -vn 0.711776 -0.304586 0.632931 -v 0.056409 0.091419 0.094609 -vn 0.927137 -0.162492 0.337659 -v 0.056442 0.091440 0.094565 -vn 0.098213 -0.590158 0.801291 -v 0.056303 0.091594 0.094760 -vn 0.384993 -0.520297 0.762281 -v 0.056360 0.091600 0.094751 -vn 0.711765 -0.395519 0.580479 -v 0.056409 0.091619 0.094724 -vn 0.927135 -0.211004 0.309675 -v 0.056442 0.091646 0.094684 -vn 0.098333 -0.660931 0.743976 -v 0.056303 0.091769 0.094900 -vn 0.046612 -0.736944 0.674345 -v 0.056303 0.091838 0.094968 -vn 0.098229 -0.877632 0.469162 -v 0.056303 0.092048 0.095250 -vn 0.381048 -0.802760 0.458672 -v 0.056360 0.092058 0.095244 -vn 0.711754 -0.608221 0.351388 -v 0.056409 0.092086 0.095228 -vn 0.927132 -0.324477 0.187459 -v 0.056442 0.092128 0.095203 -vn 0.098258 -0.916793 0.387087 -v 0.056303 0.092145 0.095452 -vn 0.061005 -0.953098 0.296451 -v 0.056303 0.092170 0.095521 -vn 0.098300 -0.994105 0.045734 -v 0.056303 0.092245 0.095887 -vn 0.379813 -0.922915 0.063009 -v 0.056360 0.092256 0.095887 -vn 0.711758 -0.700446 0.052685 -v 0.056409 0.092289 0.095884 -vn 0.927149 -0.373637 0.028101 -v 0.056442 0.092337 0.095881 -vn 0.098240 -0.994135 -0.045225 -v 0.056303 0.092245 0.096112 -vn 0.074823 -0.987815 -0.136467 -v 0.056303 0.092240 0.096162 -vn 0.098291 -0.917000 -0.386586 -v 0.056303 0.092146 0.096548 -vn 0.379860 -0.858605 -0.344244 -v 0.056360 0.092156 0.096552 -vn 0.711758 -0.653942 -0.256438 -v 0.056409 0.092187 0.096564 -vn 0.927136 -0.348858 -0.136806 -v 0.056442 0.092232 0.096581 -vn 0.098201 -0.877905 -0.468657 -v 0.056303 0.092048 0.096750 -vn 0.087140 -0.835987 -0.541786 -v 0.056303 0.092035 0.096773 -vn 0.098330 -0.661357 -0.743598 -v 0.056303 0.091770 0.097099 -vn 0.380455 -0.624225 -0.682346 -v 0.056360 0.091777 0.097108 -vn 0.711759 -0.477913 -0.514779 -v 0.056409 0.091800 0.097131 -vn 0.927144 -0.254939 -0.274608 -v 0.056442 0.091833 0.097167 -vn 0.098196 -0.590809 -0.800814 -v 0.056303 0.091594 0.097239 -vn 0.092436 -0.193820 -0.976673 -v 0.056303 0.090992 0.097480 -vn 0.093003 -0.287153 -0.953359 -v 0.056303 0.091192 0.097433 -vn 0.385087 -0.273504 -0.881421 -v 0.056360 0.091195 0.097444 -vn 0.711770 -0.207221 -0.671150 -v 0.056409 0.091205 0.097475 -vn 0.927142 -0.110543 -0.358034 -v 0.056442 0.091219 0.097522 -vn 0.041711 -0.355808 -0.933628 -v 0.056303 0.091305 0.097393 -vn 0.098095 -0.449601 -0.887827 -v 0.056303 0.091400 0.097351 -vn 0.096908 -0.528047 -0.843668 -v 0.056303 0.091591 0.097241 -vn 0.098249 -0.114748 -0.988524 -v 0.056303 0.090973 0.097483 -vn 0.381967 -0.134644 -0.914315 -v 0.056360 0.090975 0.097494 -vn 0.711753 -0.104887 -0.694555 -v 0.056409 0.090980 0.097527 -vn 0.927136 -0.055953 -0.370523 -v 0.056442 0.090987 0.097575 -vn 0.098330 -0.024105 -0.994862 -v 0.056303 0.090750 0.097500 -vn 0.056331 0.075390 -0.995562 -v 0.056303 0.090668 0.097498 -vn 0.098210 0.321793 -0.941703 -v 0.056303 0.090307 0.097433 -vn 0.380009 0.278043 -0.882205 -v 0.056360 0.090304 0.097444 -vn 0.711780 0.206850 -0.671254 -v 0.056409 0.090294 0.097475 -vn 0.927141 0.110349 -0.358096 -v 0.056442 0.090280 0.097522 -vn 0.098282 0.406404 -0.908392 -v 0.056303 0.090099 0.097352 -vn 0.070308 0.491029 -0.868301 -v 0.056303 0.090047 0.097325 -vn 0.098289 0.695773 -0.711505 -v 0.056303 0.089729 0.097100 -vn 0.379760 0.634086 -0.673586 -v 0.056360 0.089721 0.097108 -vn 0.711763 0.477621 -0.515045 -v 0.056409 0.089699 0.097132 -vn 0.927144 0.254791 -0.274748 -v 0.056442 0.089666 0.097168 -vn 0.098244 0.757854 -0.644985 -v 0.056303 0.089577 0.096936 -vn 0.083294 0.812242 -0.577344 -v 0.056303 0.089555 0.096908 -vn 0.098336 0.934268 -0.342744 -v 0.056303 0.089353 0.096548 -vn 0.380250 0.863370 -0.331666 -v 0.056360 0.089342 0.096553 -vn 0.711764 0.653791 -0.256807 -v 0.056409 0.089312 0.096564 -vn 0.927136 0.348782 -0.137001 -v 0.056442 0.089267 0.096582 -vn 0.098190 0.961674 -0.256013 -v 0.056303 0.089287 0.096334 -vn 0.094029 0.979318 -0.179150 -v 0.056303 0.089284 0.096323 -vn 0.711777 0.700456 0.052296 -v 0.056409 0.089210 0.095885 -vn 0.098231 0.961744 0.255733 -v 0.056303 0.089287 0.095667 -vn 0.383252 0.900062 0.207379 -v 0.056360 0.089276 0.095664 -vn 0.711765 0.684852 0.156105 -v 0.056409 0.089244 0.095657 -vn 0.927141 0.365341 0.083279 -v 0.056442 0.089196 0.095646 -vn 0.098316 0.934460 0.342227 -v 0.056303 0.089353 0.095452 -vn 0.051473 0.898089 0.436792 -v 0.056303 0.089388 0.095371 -vn 0.098288 0.758133 0.644650 -v 0.056303 0.089576 0.095065 -vn 0.380451 0.719899 0.580520 -v 0.056360 0.089567 0.095058 -vn 0.711763 0.549296 0.437799 -v 0.056409 0.089542 0.095038 -vn 0.927135 0.293037 0.233558 -v 0.056442 0.089504 0.095007 -vn 0.098287 0.696179 0.711108 -v 0.056303 0.089729 0.094901 -vn 0.065767 0.626488 0.776651 -v 0.056303 0.089778 0.094857 -vn 0.098229 0.406966 0.908146 -v 0.056303 0.090098 0.094649 -vn 0.379735 0.395548 0.836267 -v 0.056360 0.090093 0.094638 -vn 0.711788 0.304931 0.632752 -v 0.056409 0.090079 0.094609 -vn 0.927137 0.162677 0.337569 -v 0.056442 0.090058 0.094565 -vn 0.098224 0.322311 0.941524 -v 0.056303 0.090307 0.094567 -vn 0.098240 -0.114109 0.988599 -v 0.056303 0.090972 0.094517 -vn 0.098273 -0.023513 0.994882 -v 0.056303 0.090749 0.094500 -vn 0.075726 0.066654 0.994898 -v 0.056303 0.090668 0.094502 -vn 0.096140 0.157918 0.982761 -v 0.056303 0.090525 0.094517 -vn 0.079140 0.237227 0.968225 -v 0.056303 0.090347 0.094555 -vn -0.098322 0.990955 -0.091325 -v 0.052603 0.089253 0.096113 -vn -0.073266 0.997312 -0.000264 -v 0.052603 0.089249 0.096000 -vn -0.097728 0.990990 0.091589 -v 0.052603 0.089253 0.095888 -vn -0.094048 0.979370 0.178853 -v 0.052603 0.089284 0.095678 -vn -0.098234 0.961745 0.255729 -v 0.052603 0.089287 0.095667 -vn -0.098319 0.934458 0.342230 -v 0.052603 0.089353 0.095452 -vn -0.074644 0.901197 0.426934 -v 0.052603 0.089388 0.095371 -vn -0.096542 0.856340 0.507308 -v 0.052603 0.089450 0.095250 -vn -0.083290 0.812506 0.576972 -v 0.052603 0.089555 0.095093 -vn -0.098292 0.758137 0.644646 -v 0.052603 0.089576 0.095065 -vn -0.098291 0.696175 0.711112 -v 0.052603 0.089729 0.094901 -vn -0.078703 0.631506 0.771366 -v 0.052603 0.089778 0.094857 -vn -0.095355 0.556564 0.825315 -v 0.052603 0.089904 0.094761 -vn -0.070308 0.491538 0.868014 -v 0.052603 0.090046 0.094675 -vn -0.098227 0.406964 0.908147 -v 0.052603 0.090098 0.094649 -vn -0.098223 0.322313 0.941524 -v 0.052603 0.090307 0.094567 -vn -0.084957 0.241262 0.966734 -v 0.052603 0.090347 0.094555 -vn -0.094170 0.149415 0.984280 -v 0.052603 0.090525 0.094517 -vn -0.056334 0.075952 0.995519 -v 0.052603 0.090668 0.094502 -vn -0.098268 -0.023520 0.994882 -v 0.052603 0.090749 0.094500 -vn -0.098235 -0.114101 0.988600 -v 0.052603 0.090972 0.094517 -vn -0.092408 -0.193203 0.976798 -v 0.052603 0.090991 0.094520 -vn -0.092980 -0.286630 0.953519 -v 0.052603 0.091191 0.094567 -vn -0.041658 -0.355293 0.933826 -v 0.052603 0.091304 0.094606 -vn -0.098123 -0.449133 0.888061 -v 0.052603 0.091400 0.094648 -vn -0.096930 -0.527351 0.844101 -v 0.052603 0.091591 0.094758 -vn -0.098214 -0.590157 0.801292 -v 0.052603 0.091594 0.094760 -vn -0.098335 -0.660933 0.743975 -v 0.052603 0.091769 0.094900 -vn -0.073894 -0.728120 0.681455 -v 0.052603 0.091838 0.094968 -vn -0.096964 -0.786320 0.610163 -v 0.052603 0.091922 0.095064 -vn -0.087181 -0.835673 0.542265 -v 0.052603 0.092034 0.095226 -vn -0.098233 -0.877629 0.469166 -v 0.052603 0.092048 0.095250 -vn -0.098262 -0.916794 0.387082 -v 0.052603 0.092145 0.095452 -vn -0.077042 -0.949555 0.303989 -v 0.052603 0.092170 0.095521 -vn -0.095781 -0.972003 0.214561 -v 0.052603 0.092211 0.095666 -vn -0.074851 -0.987742 0.136981 -v 0.052603 0.092240 0.095837 -vn -0.098306 -0.994104 0.045742 -v 0.052603 0.092245 0.095887 -vn -0.098245 -0.994134 -0.045232 -v 0.052603 0.092245 0.096112 -vn -0.082676 -0.987904 -0.131190 -v 0.052603 0.092240 0.096162 -vn -0.094566 -0.970341 -0.222475 -v 0.052603 0.092212 0.096333 -vn -0.061034 -0.953261 -0.295920 -v 0.052603 0.092171 0.096479 -vn -0.098293 -0.917001 -0.386584 -v 0.052603 0.092146 0.096548 -vn -0.098203 -0.877904 -0.468659 -v 0.052603 0.092048 0.096750 -vn -0.089881 -0.837129 -0.539571 -v 0.052603 0.092035 0.096773 -vn -0.093423 -0.781590 -0.616757 -v 0.052603 0.091922 0.096935 -vn -0.046652 -0.737319 -0.673932 -v 0.052603 0.091838 0.097031 -vn -0.098329 -0.661356 -0.743599 -v 0.052603 0.091770 0.097099 -vn -0.098196 -0.590810 -0.800813 -v 0.052603 0.091594 0.097239 -vn -0.097125 -0.528271 -0.843502 -v 0.052603 0.091591 0.097241 -vn -0.098289 -0.449356 -0.887929 -v 0.052603 0.091400 0.097351 -vn -0.073421 -0.366481 -0.927524 -v 0.052603 0.091305 0.097393 -vn -0.097345 -0.278748 -0.955418 -v 0.052603 0.091192 0.097433 -vn -0.090801 -0.195472 -0.976497 -v 0.052603 0.090992 0.097480 -vn -0.098250 -0.114749 -0.988524 -v 0.052603 0.090973 0.097483 -vn -0.098331 -0.024104 -0.994862 -v 0.052603 0.090750 0.097500 -vn -0.075753 0.066079 -0.994935 -v 0.052603 0.090668 0.097498 -vn -0.096195 0.157381 -0.982842 -v 0.052603 0.090526 0.097483 -vn -0.079112 0.236672 -0.968363 -v 0.052603 0.090348 0.097445 -vn -0.098205 0.321798 -0.941701 -v 0.052603 0.090307 0.097433 -vn -0.098278 0.406399 -0.908395 -v 0.052603 0.090099 0.097352 -vn -0.080565 0.485201 -0.870683 -v 0.052603 0.090047 0.097325 -vn -0.095011 0.563283 -0.820783 -v 0.052603 0.089905 0.097240 -vn -0.065762 0.626048 -0.777007 -v 0.052603 0.089778 0.097144 -vn -0.098289 0.695773 -0.711505 -v 0.052603 0.089729 0.097100 -vn -0.098244 0.757853 -0.644986 -v 0.052603 0.089577 0.096936 -vn -0.087407 0.810012 -0.579862 -v 0.052603 0.089555 0.096908 -vn -0.093777 0.860658 -0.500473 -v 0.052603 0.089450 0.096750 -vn -0.051470 0.897847 -0.437289 -v 0.052603 0.089388 0.096630 -vn -0.098339 0.934266 -0.342748 -v 0.052603 0.089353 0.096548 -vn -0.098193 0.961674 -0.256009 -v 0.052603 0.089287 0.096334 -vn -0.094841 0.979076 -0.180042 -v 0.052603 0.089284 0.096323 -vn -0.380466 -0.005190 0.924781 -v 0.052546 0.090749 0.094489 -vn -0.381925 -0.134136 0.914407 -v 0.052546 0.090974 0.094505 -vn -0.385082 -0.273017 0.881574 -v 0.052546 0.091194 0.094556 -vn -0.381106 -0.405575 0.830823 -v 0.052546 0.091405 0.094638 -vn -0.385157 -0.520055 0.762363 -v 0.052546 0.091600 0.094751 -vn -0.380458 -0.623843 0.682694 -v 0.052546 0.091777 0.094892 -vn -0.381654 -0.726034 0.572028 -v 0.052546 0.091931 0.095057 -vn -0.381648 -0.801933 0.459618 -v 0.052546 0.092058 0.095244 -vn -0.379883 -0.858405 0.344717 -v 0.052546 0.092156 0.095447 -vn -0.382639 -0.901680 0.201397 -v 0.052546 0.092223 0.095663 -vn -0.380413 -0.922560 0.064563 -v 0.052546 0.092256 0.095887 -vn -0.379800 -0.922954 -0.062507 -v 0.052546 0.092256 0.096113 -vn -0.383684 -0.899647 -0.208377 -v 0.052546 0.092223 0.096336 -vn -0.380365 -0.859004 -0.342688 -v 0.052546 0.092156 0.096552 -vn -0.381004 -0.803030 -0.458234 -v 0.052546 0.092058 0.096755 -vn -0.384748 -0.720694 -0.576688 -v 0.052546 0.091931 0.096942 -vn -0.380852 -0.625182 -0.681248 -v 0.052546 0.091777 0.097108 -vn -0.384972 -0.520731 -0.761995 -v 0.052546 0.091601 0.097249 -vn -0.380546 -0.407164 -0.830303 -v 0.052546 0.091405 0.097362 -vn -0.381305 -0.266961 -0.885064 -v 0.052546 0.091195 0.097444 -vn -0.382502 -0.135596 -0.913951 -v 0.052546 0.090975 0.097494 -vn -0.380042 -0.007276 -0.924941 -v 0.052546 0.090750 0.097511 -vn -0.382275 0.142384 -0.913013 -v 0.052546 0.090524 0.097495 -vn -0.380635 0.276515 -0.882415 -v 0.052546 0.090304 0.097444 -vn -0.379755 0.395062 -0.836488 -v 0.052546 0.090094 0.097362 -vn -0.383321 0.523128 -0.761185 -v 0.052546 0.089898 0.097249 -vn -0.380300 0.632759 -0.674529 -v 0.052546 0.089721 0.097108 -vn -0.380413 0.719604 -0.580909 -v 0.052546 0.089568 0.096943 -vn -0.384356 0.800513 -0.459837 -v 0.052546 0.089440 0.096756 -vn -0.380679 0.862659 -0.333021 -v 0.052546 0.089342 0.096553 -vn -0.383215 0.899965 -0.207867 -v 0.052546 0.089276 0.096337 -vn -0.380456 0.921761 -0.074898 -v 0.052546 0.089242 0.096113 -vn -0.380995 0.921518 0.075153 -v 0.052546 0.089242 0.095887 -vn -0.383647 0.900053 0.206686 -v 0.052546 0.089276 0.095664 -vn -0.380243 0.863555 0.331191 -v 0.052546 0.089342 0.095448 -vn -0.381964 0.797805 0.466488 -v 0.052546 0.089440 0.095245 -vn -0.381079 0.720582 0.579258 -v 0.052546 0.089567 0.095058 -vn -0.379753 0.634458 0.673239 -v 0.052546 0.089721 0.094892 -vn -0.382985 0.517163 0.765418 -v 0.052546 0.089897 0.094751 -vn -0.380314 0.396904 0.835361 -v 0.052546 0.090093 0.094638 -vn -0.380010 0.278531 0.882050 -v 0.052546 0.090303 0.094556 -vn -0.383980 0.135135 0.913399 -v 0.052546 0.090523 0.094506 -vn -0.711796 0.104879 0.694512 -v 0.052497 0.090519 0.094473 -vn -0.711787 0.207216 0.671134 -v 0.052497 0.090294 0.094525 -vn -0.711803 0.304926 0.632737 -v 0.052497 0.090079 0.094609 -vn -0.711814 0.395822 0.580211 -v 0.052497 0.089879 0.094725 -vn -0.711779 0.477896 0.514767 -v 0.052497 0.089699 0.094869 -vn -0.711777 0.549282 0.437793 -v 0.052497 0.089542 0.095038 -vn -0.711803 0.608378 0.351017 -v 0.052497 0.089412 0.095228 -vn -0.711801 0.653899 0.256428 -v 0.052497 0.089312 0.095436 -vn -0.711787 0.684829 0.156105 -v 0.052497 0.089244 0.095657 -vn -0.711797 0.700437 0.052290 -v 0.052497 0.089210 0.095885 -vn -0.711787 0.700417 -0.052682 -v 0.052497 0.089210 0.096116 -vn -0.711766 0.684762 -0.156493 -v 0.052497 0.089244 0.096344 -vn -0.711783 0.653772 -0.256802 -v 0.052497 0.089312 0.096564 -vn -0.711782 0.608199 -0.351369 -v 0.052497 0.089412 0.096772 -vn -0.711763 0.549057 -0.438099 -v 0.052497 0.089542 0.096963 -vn -0.711783 0.477603 -0.515033 -v 0.052497 0.089699 0.097132 -vn -0.711776 0.395521 -0.580463 -v 0.052497 0.089880 0.097276 -vn -0.711782 0.304585 -0.632925 -v 0.052497 0.090080 0.097391 -vn -0.711804 0.206834 -0.671234 -v 0.052497 0.090294 0.097475 -vn -0.711772 0.104497 -0.694594 -v 0.052497 0.090519 0.097527 -vn -0.711790 -0.000203 -0.702392 -v 0.052497 0.090750 0.097544 -vn -0.711772 -0.104878 -0.694537 -v 0.052497 0.090980 0.097527 -vn -0.711787 -0.207216 -0.671134 -v 0.052497 0.091205 0.097475 -vn -0.711805 -0.304932 -0.632732 -v 0.052497 0.091419 0.097391 -vn -0.711792 -0.395836 -0.580230 -v 0.052497 0.091619 0.097275 -vn -0.711779 -0.477899 -0.514766 -v 0.052497 0.091800 0.097131 -vn -0.711778 -0.549286 -0.437786 -v 0.052497 0.091957 0.096962 -vn -0.711793 -0.608385 -0.351025 -v 0.052497 0.092086 0.096772 -vn -0.711774 -0.653923 -0.256442 -v 0.052497 0.092187 0.096564 -vn -0.711817 -0.684801 -0.156090 -v 0.052497 0.092254 0.096343 -vn -0.711781 -0.700452 -0.052295 -v 0.052497 0.092289 0.096115 -vn -0.711776 -0.700429 0.052683 -v 0.052497 0.092289 0.095884 -vn -0.711789 -0.684741 0.156484 -v 0.052497 0.092254 0.095656 -vn -0.711814 -0.653744 0.256788 -v 0.052497 0.092186 0.095436 -vn -0.711775 -0.608209 0.351367 -v 0.052497 0.092086 0.095228 -vn -0.711803 -0.549018 0.438082 -v 0.052497 0.091956 0.095037 -vn -0.711785 -0.477606 0.515029 -v 0.052497 0.091799 0.094868 -vn -0.711780 -0.395513 0.580464 -v 0.052497 0.091619 0.094724 -vn -0.711796 -0.304575 0.632914 -v 0.052497 0.091419 0.094609 -vn -0.711798 -0.206841 0.671238 -v 0.052497 0.091204 0.094525 -vn -0.711772 -0.104497 0.694595 -v 0.052497 0.090979 0.094473 -vn -0.711792 0.000195 0.702391 -v 0.052497 0.090749 0.094456 -vn -0.927159 0.055945 0.370468 -v 0.052464 0.090511 0.094425 -vn -0.927151 0.110540 0.358011 -v 0.052464 0.090279 0.094478 -vn -0.927147 0.162666 0.337547 -v 0.052464 0.090058 0.094565 -vn -0.927146 0.211163 0.309533 -v 0.052464 0.089852 0.094684 -vn -0.927153 0.254928 0.274590 -v 0.052464 0.089666 0.094833 -vn -0.927145 0.293017 0.233543 -v 0.052464 0.089504 0.095007 -vn -0.927143 0.324557 0.187265 -v 0.052464 0.089370 0.095204 -vn -0.927150 0.348829 0.136791 -v 0.052464 0.089266 0.095419 -vn -0.927150 0.365318 0.083276 -v 0.052464 0.089196 0.095646 -vn -0.927572 0.372498 0.029267 -v 0.052464 0.089161 0.095881 -vn -0.927561 0.372507 -0.029478 -v 0.052464 0.089161 0.096119 -vn -0.927146 0.365283 -0.083482 -v 0.052464 0.089197 0.096355 -vn -0.927146 0.348761 -0.136990 -v 0.052464 0.089267 0.096582 -vn -0.927152 0.324433 -0.187438 -v 0.052464 0.089370 0.096797 -vn -0.927141 0.292900 -0.233706 -v 0.052464 0.089504 0.096993 -vn -0.927152 0.254774 -0.274734 -v 0.052464 0.089666 0.097168 -vn -0.927151 0.210980 -0.309642 -v 0.052464 0.089852 0.097316 -vn -0.927146 0.162484 -0.337638 -v 0.052464 0.090059 0.097435 -vn -0.927150 0.110344 -0.358075 -v 0.052464 0.090280 0.097522 -vn -0.927154 0.055740 -0.370512 -v 0.052464 0.090512 0.097575 -vn -0.927155 -0.000104 -0.374678 -v 0.052464 0.090750 0.097593 -vn -0.927146 -0.055946 -0.370500 -v 0.052464 0.090987 0.097575 -vn -0.927151 -0.110538 -0.358012 -v 0.052464 0.091219 0.097522 -vn -0.927148 -0.162669 -0.337545 -v 0.052464 0.091441 0.097435 -vn -0.927147 -0.211160 -0.309532 -v 0.052464 0.091647 0.097316 -vn -0.927154 -0.254925 -0.274588 -v 0.052464 0.091833 0.097167 -vn -0.927145 -0.293019 -0.233544 -v 0.052464 0.091995 0.096993 -vn -0.927155 -0.324535 -0.187247 -v 0.052464 0.092129 0.096796 -vn -0.927146 -0.348835 -0.136799 -v 0.052464 0.092232 0.096581 -vn -0.927147 -0.365327 -0.083278 -v 0.052464 0.092302 0.096354 -vn -0.927149 -0.373652 -0.027897 -v 0.052464 0.092337 0.096119 -vn -0.927158 -0.373614 0.028104 -v 0.052464 0.092337 0.095881 -vn -0.927147 -0.365281 0.083477 -v 0.052464 0.092302 0.095645 -vn -0.927147 -0.348757 0.136990 -v 0.052464 0.092231 0.095418 -vn -0.927141 -0.324459 0.187445 -v 0.052464 0.092128 0.095203 -vn -0.927146 -0.292887 0.233702 -v 0.052464 0.091994 0.095007 -vn -0.927152 -0.254772 0.274735 -v 0.052464 0.091832 0.094832 -vn -0.927146 -0.210991 0.309651 -v 0.052464 0.091646 0.094684 -vn -0.927146 -0.162483 0.337638 -v 0.052464 0.091440 0.094565 -vn -0.927151 -0.110339 0.358072 -v 0.052464 0.091218 0.094478 -vn -0.927154 -0.055740 0.370512 -v 0.052464 0.090986 0.094425 -vn -0.927155 0.000102 0.374679 -v 0.052464 0.090749 0.094407 -vn -0.995854 0.090964 -0.000026 -v 0.052453 0.089099 0.096000 -vn -0.995518 0.094161 -0.008797 -v 0.052453 0.089104 0.096124 -vn -0.995630 0.091042 -0.020807 -v 0.052453 0.089141 0.096368 -vn -0.995629 0.086930 -0.034143 -v 0.052453 0.089213 0.096603 -vn -0.995630 0.080858 -0.046714 -v 0.052453 0.089320 0.096825 -vn -0.995630 0.072996 -0.058247 -v 0.052453 0.089459 0.097029 -vn -0.995629 0.063509 -0.068482 -v 0.052453 0.089627 0.097210 -vn -0.995630 0.052584 -0.077173 -v 0.052453 0.089820 0.097364 -vn -0.995630 0.040492 -0.084146 -v 0.052453 0.090034 0.097487 -vn -0.995628 0.027507 -0.089260 -v 0.052453 0.090263 0.097577 -vn -0.995630 0.013892 -0.092348 -v 0.052453 0.090504 0.097632 -vn -0.995629 -0.000026 -0.093394 -v 0.052453 0.090750 0.097650 -vn -0.995630 -0.013946 -0.092343 -v 0.052453 0.090996 0.097631 -vn -0.995629 -0.027553 -0.089239 -v 0.052453 0.091236 0.097577 -vn -0.995629 -0.040546 -0.084133 -v 0.052453 0.091465 0.097486 -vn -0.995629 -0.052633 -0.077152 -v 0.052453 0.091679 0.097363 -vn -0.995630 -0.063541 -0.068443 -v 0.052453 0.091872 0.097209 -vn -0.995630 -0.073032 -0.058207 -v 0.052453 0.092039 0.097028 -vn -0.995629 -0.080895 -0.046676 -v 0.052453 0.092178 0.096825 -vn -0.995630 -0.086940 -0.034092 -v 0.052453 0.092285 0.096602 -vn -0.995629 -0.091063 -0.020760 -v 0.052453 0.092358 0.096367 -vn -0.995631 -0.093120 -0.006950 -v 0.052453 0.092395 0.096123 -vn -0.995629 -0.093135 0.007004 -v 0.052453 0.092395 0.095876 -vn -0.995630 -0.091042 0.020806 -v 0.052453 0.092358 0.095632 -vn -0.995630 -0.086924 0.034143 -v 0.052453 0.092285 0.095397 -vn -0.995629 -0.080867 0.046719 -v 0.052453 0.092178 0.095175 -vn -0.995629 -0.073002 0.058250 -v 0.052453 0.092039 0.094971 -vn -0.995629 -0.063508 0.068483 -v 0.052453 0.091871 0.094790 -vn -0.995629 -0.052588 0.077179 -v 0.052453 0.091678 0.094636 -vn -0.995630 -0.040494 0.084147 -v 0.052453 0.091465 0.094513 -vn -0.995630 -0.027501 0.089245 -v 0.052453 0.091235 0.094423 -vn -0.995630 -0.013892 0.092348 -v 0.052453 0.090995 0.094368 -vn -0.995629 0.000025 0.093395 -v 0.052453 0.090749 0.094350 -vn -0.995630 0.013945 0.092342 -v 0.052453 0.090503 0.094368 -vn -0.995629 0.027554 0.089239 -v 0.052453 0.090262 0.094423 -vn -0.995629 0.040545 0.084135 -v 0.052453 0.090033 0.094514 -vn -0.995630 0.052630 0.077148 -v 0.052453 0.089819 0.094637 -vn -0.995629 0.063542 0.068444 -v 0.052453 0.089627 0.094791 -vn -0.995630 0.073031 0.058206 -v 0.052453 0.089459 0.094972 -vn -0.995629 0.080896 0.046675 -v 0.052453 0.089320 0.095175 -vn -0.995629 0.086949 0.034098 -v 0.052453 0.089213 0.095398 -vn -0.995630 0.091053 0.020755 -v 0.052453 0.089140 0.095633 -vn -0.995519 0.094157 0.008742 -v 0.052453 0.089104 0.095877 -vn -0.402955 0.692819 0.598021 -v 0.054448 0.087894 0.096786 -vn -0.503259 0.810660 -0.299267 -v 0.054448 0.087966 0.097011 -vn -0.000221 0.938252 -0.345953 -v 0.054453 0.087967 0.097010 -vn 0.440433 -0.057864 -0.895919 -v 0.054459 0.088355 0.097744 -vn 0.502485 0.739616 -0.447747 -v 0.054458 0.088224 0.097548 -vn 0.000515 0.855431 -0.517917 -v 0.054453 0.088226 0.097547 -vn 0.404998 -0.892372 -0.199119 -v 0.054459 0.088343 0.097755 -vn 0.166807 -0.976602 -0.135733 -v 0.054455 0.088342 0.097756 -vn 0.496378 -0.742771 0.449332 -v 0.054458 0.088210 0.097557 -vn -0.000173 -0.855464 0.517863 -v 0.054453 0.088208 0.097557 -vn 0.862963 -0.432379 0.261423 -v 0.054462 0.088213 0.097555 -vn 0.723215 -0.649785 -0.233965 -v 0.054462 0.088346 0.097752 -vn 0.999973 -0.006371 0.003663 -v 0.054463 0.088217 0.097552 -vn 0.951109 -0.253947 -0.175790 -v 0.054463 0.088349 0.097749 -vn 0.869319 0.422615 -0.256284 -v 0.054462 0.088221 0.097549 -vn 0.650254 -0.248566 -0.717903 -v 0.054462 0.088353 0.097746 -vn -0.502879 0.738951 -0.448401 -v 0.054448 0.088224 0.097548 -vn -0.191249 0.063644 -0.979476 -v 0.054450 0.088356 0.097743 -vn 0.127070 0.048128 -0.990726 -v 0.054455 0.088356 0.097742 -vn -0.999971 -0.006721 0.003667 -v 0.054443 0.088217 0.097552 -vn -0.694559 -0.292094 -0.657471 -v 0.054444 0.088351 0.097747 -vn -0.869073 0.422760 -0.256877 -v 0.054444 0.088221 0.097549 -vn -0.549044 -0.117366 -0.827512 -v 0.054446 0.088354 0.097744 -vn -0.395136 0.011014 -0.918557 -v 0.054448 0.088355 0.097743 -vn -0.496306 -0.742586 0.449717 -v 0.054448 0.088210 0.097557 -vn -0.638657 -0.728752 -0.247059 -v 0.054445 0.088345 0.097753 -vn -0.862788 -0.432491 0.261818 -v 0.054444 0.088213 0.097555 -vn -0.948126 -0.279300 -0.151817 -v 0.054443 0.088349 0.097749 -vn -0.044458 -0.990610 -0.129285 -v 0.054453 0.088342 0.097756 -vn -0.298461 -0.936853 -0.182283 -v 0.054448 0.088342 0.097755 -vn -0.356332 -0.422860 0.833197 -v 0.054448 0.087877 0.096789 -vn -0.144899 -0.518047 0.842989 -v 0.054451 0.087876 0.096789 -vn -0.496941 -0.814034 0.300662 -v 0.054448 0.087949 0.097016 -vn 0.000211 -0.938098 0.346369 -v 0.054453 0.087948 0.097017 -vn -0.862730 -0.474362 0.175152 -v 0.054444 0.087953 0.097015 -vn -0.702410 -0.236121 0.671466 -v 0.054444 0.087881 0.096788 -vn -0.999974 -0.006693 0.002644 -v 0.054443 0.087957 0.097014 -vn -0.951080 -0.020759 0.308247 -v 0.054443 0.087885 0.096788 -vn -0.869040 0.464147 -0.171282 -v 0.054444 0.087962 0.097012 -vn -0.634086 0.422433 0.647677 -v 0.054444 0.087890 0.096787 -vn 0.503248 0.810919 -0.298584 -v 0.054458 0.087966 0.097011 -vn 0.193727 0.805452 0.560105 -v 0.054456 0.087895 0.096786 -vn -0.103684 0.816272 0.568287 -v 0.054451 0.087895 0.096786 -vn 0.999972 -0.006878 0.002904 -v 0.054463 0.087957 0.097014 -vn 0.693124 0.332571 0.639513 -v 0.054462 0.087889 0.096787 -vn 0.869232 0.464071 -0.170509 -v 0.054462 0.087962 0.097012 -vn 0.549469 0.574902 0.606277 -v 0.054460 0.087893 0.096787 -vn 0.394079 0.725194 0.564620 -v 0.054458 0.087894 0.096786 -vn 0.496676 -0.814248 0.300523 -v 0.054458 0.087949 0.097016 -vn 0.642164 -0.258940 0.721510 -v 0.054461 0.087880 0.096788 -vn 0.862989 -0.473934 0.175033 -v 0.054462 0.087953 0.097015 -vn 0.948059 -0.055471 0.313220 -v 0.054463 0.087885 0.096788 -vn 0.049538 -0.513897 0.856421 -v 0.054453 0.087875 0.096789 -vn 0.305512 -0.437731 0.845608 -v 0.054458 0.087877 0.096789 -vn 0.000001 0.900847 -0.434137 -v 0.054453 0.088083 0.097285 -vn -0.503653 0.778244 -0.375060 -v 0.054448 0.088081 0.097286 -vn -0.869507 0.444949 -0.214425 -v 0.054444 0.088078 0.097287 -vn -0.999967 -0.007265 0.003500 -v 0.054443 0.088074 0.097289 -vn -0.862205 -0.456334 0.219913 -v 0.054444 0.088069 0.097292 -vn -0.496073 -0.782189 0.376951 -v 0.054448 0.088066 0.097293 -vn -0.000002 -0.900848 0.434134 -v 0.054453 0.088065 0.097294 -vn 0.496075 -0.782187 0.376953 -v 0.054458 0.088066 0.097293 -vn 0.862375 -0.456070 0.219793 -v 0.054462 0.088069 0.097292 -vn 0.999968 -0.007248 0.003488 -v 0.054463 0.088074 0.097289 -vn 0.869683 0.444671 -0.214287 -v 0.054462 0.088078 0.097287 -vn 0.503652 0.778246 -0.375057 -v 0.054458 0.088081 0.097286 -vn -0.402767 0.428486 -0.808813 -v 0.054448 0.092151 0.098608 -vn -0.503173 -0.472152 -0.723802 -v 0.054448 0.092354 0.098489 -vn -0.000225 -0.546097 -0.837722 -v 0.054453 0.092353 0.098488 -vn 0.446859 -0.854778 0.263956 -v 0.054459 0.092982 0.097946 -vn 0.502825 -0.600956 -0.621303 -v 0.054458 0.092820 0.098117 -vn 0.000507 -0.695291 -0.718728 -v 0.054453 0.092819 0.098116 -vn 0.405137 0.004059 0.914247 -v 0.054459 0.092995 0.097955 -vn 0.166053 0.085329 0.982418 -v 0.054455 0.092997 0.097956 -vn 0.497115 0.603048 0.623867 -v 0.054458 0.092832 0.098129 -vn -0.000169 0.695255 0.718764 -v 0.054453 0.092833 0.098130 -vn 0.862943 0.351100 0.363399 -v 0.054462 0.092829 0.098127 -vn 0.724049 -0.083164 0.684717 -v 0.054462 0.092992 0.097953 -vn 0.999972 0.004964 0.005529 -v 0.054463 0.092826 0.098123 -vn 0.951669 -0.108649 0.287267 -v 0.054463 0.092989 0.097951 -vn 0.869218 -0.344125 -0.355017 -v 0.054462 0.092822 0.098120 -vn 0.659744 -0.629710 0.410126 -v 0.054462 0.092985 0.097948 -vn -0.503214 -0.601439 -0.620521 -v 0.054448 0.092820 0.098117 -vn -0.190678 -0.969133 0.156279 -v 0.054450 0.092981 0.097946 -vn 0.126769 -0.976731 0.172994 -v 0.054455 0.092980 0.097945 -vn -0.999972 0.004769 0.005806 -v 0.054443 0.092826 0.098123 -vn -0.705846 -0.550762 0.445469 -v 0.054444 0.092986 0.097949 -vn -0.869009 -0.344594 -0.355076 -v 0.054444 0.092822 0.098120 -vn -0.548955 -0.780766 0.298416 -v 0.054446 0.092983 0.097947 -vn -0.395392 -0.897940 0.193309 -v 0.054448 0.092981 0.097946 -vn -0.497046 0.603383 0.623597 -v 0.054448 0.092832 0.098129 -vn -0.604868 -0.073574 0.792920 -v 0.054445 0.092993 0.097954 -vn -0.862685 0.351427 0.363694 -v 0.054444 0.092829 0.098127 -vn -0.944684 -0.059399 0.322560 -v 0.054443 0.092990 0.097952 -vn -0.046106 0.094196 0.994486 -v 0.054453 0.092997 0.097956 -vn -0.298515 0.031040 0.953900 -v 0.054448 0.092996 0.097956 -vn -0.348624 0.907677 0.233631 -v 0.054448 0.092157 0.098625 -vn -0.145444 0.937060 0.317434 -v 0.054451 0.092158 0.098626 -vn -0.496997 0.474218 0.726712 -v 0.054448 0.092363 0.098503 -vn 0.000208 0.546454 0.837489 -v 0.054453 0.092364 0.098505 -vn -0.862679 0.276265 0.423630 -v 0.054444 0.092361 0.098500 -vn -0.671726 0.735872 0.085301 -v 0.054444 0.092156 0.098621 -vn -0.999973 0.004035 0.006141 -v 0.054443 0.092358 0.098496 -vn -0.948862 0.312695 -0.043380 -v 0.054443 0.092154 0.098617 -vn -0.869210 -0.270129 -0.414132 -v 0.054444 0.092356 0.098492 -vn -0.633683 0.537759 -0.556113 -v 0.054444 0.092152 0.098612 -vn 0.503167 -0.471539 -0.724205 -v 0.054458 0.092354 0.098489 -vn 0.192393 0.367064 -0.910082 -v 0.054456 0.092151 0.098608 -vn -0.103075 0.372417 -0.922324 -v 0.054451 0.092151 0.098607 -vn 0.999972 0.004401 0.006119 -v 0.054463 0.092358 0.098496 -vn 0.693548 0.549076 -0.466376 -v 0.054462 0.092153 0.098613 -vn 0.869401 -0.269357 -0.414233 -v 0.054462 0.092356 0.098492 -vn 0.548878 0.463885 -0.695373 -v 0.054460 0.092152 0.098610 -vn 0.395102 0.388237 -0.832566 -v 0.054458 0.092151 0.098608 -vn 0.496734 0.474137 0.726946 -v 0.054458 0.092363 0.098503 -vn 0.641356 0.761730 0.091815 -v 0.054461 0.092156 0.098622 -vn 0.862895 0.276202 0.423230 -v 0.054462 0.092361 0.098500 -vn 0.948108 0.317567 -0.015567 -v 0.054463 0.092154 0.098617 -vn 0.048558 0.949314 0.310555 -v 0.054453 0.092158 0.098626 -vn 0.305580 0.921737 0.238793 -v 0.054458 0.092157 0.098625 -vn -0.000004 -0.623721 -0.781647 -v 0.054453 0.092595 0.098314 -vn -0.503849 -0.538741 -0.675199 -v 0.054448 0.092596 0.098315 -vn -0.869589 -0.307983 -0.385955 -v 0.054444 0.092598 0.098318 -vn -0.999965 0.005203 0.006523 -v 0.054443 0.092602 0.098322 -vn -0.862224 0.315932 0.395926 -v 0.054444 0.092605 0.098325 -vn -0.496396 0.541440 0.678553 -v 0.054448 0.092607 0.098328 -vn 0.000002 0.623692 0.781670 -v 0.054453 0.092608 0.098329 -vn 0.496396 0.541443 0.678550 -v 0.054458 0.092607 0.098328 -vn 0.862394 0.315754 0.395697 -v 0.054462 0.092605 0.098325 -vn 0.999965 0.005191 0.006506 -v 0.054463 0.092602 0.098322 -vn 0.869764 -0.307788 -0.385716 -v 0.054462 0.092598 0.098318 -vn 0.503855 -0.538735 -0.675200 -v 0.054458 0.092596 0.098315 -vn -0.409265 -0.356524 -0.839877 -v 0.054448 0.093663 0.096530 -vn -0.503320 -0.860191 -0.082100 -v 0.054448 0.093696 0.096297 -vn -0.000225 -0.995442 -0.095373 -v 0.054453 0.093694 0.096297 -vn 0.447164 -0.327056 0.832513 -v 0.054459 0.093663 0.095468 -vn 0.502934 -0.860381 0.082477 -v 0.054458 0.093695 0.095701 -vn 0.000509 -0.995436 0.095433 -v 0.054453 0.093694 0.095701 -vn 0.397909 0.723682 0.563872 -v 0.054459 0.093678 0.095463 -vn 0.165917 0.821622 0.545353 -v 0.054455 0.093680 0.095462 -vn 0.496852 0.863903 -0.082516 -v 0.054458 0.093713 0.095699 -vn -0.000165 0.995435 -0.095437 -v 0.054453 0.093714 0.095699 -vn 0.863016 0.502885 -0.048061 -v 0.054462 0.093709 0.095700 -vn 0.693017 0.506023 0.513487 -v 0.054462 0.093675 0.095464 -vn 0.999973 0.007305 -0.000555 -v 0.054463 0.093704 0.095700 -vn 0.949470 0.165500 0.266676 -v 0.054463 0.093671 0.095465 -vn 0.869327 -0.491933 0.047666 -v 0.054462 0.093699 0.095701 -vn 0.657983 -0.072299 0.749554 -v 0.054462 0.093666 0.095467 -vn -0.503324 -0.860067 0.083359 -v 0.054448 0.093695 0.095701 -vn -0.191593 -0.482746 0.854546 -v 0.054450 0.093662 0.095468 -vn 0.127033 -0.473149 0.871776 -v 0.054455 0.093661 0.095469 -vn -0.999973 0.007331 -0.000087 -v 0.054443 0.093704 0.095700 -vn -0.706652 0.005059 0.707543 -v 0.054444 0.093667 0.095467 -vn -0.869119 -0.492269 0.048004 -v 0.054444 0.093699 0.095701 -vn -0.548006 -0.253560 0.797118 -v 0.054446 0.093664 0.095468 -vn -0.394684 -0.408945 0.822793 -v 0.054448 0.093662 0.095468 -vn -0.496790 0.863899 -0.082940 -v 0.054448 0.093713 0.095699 -vn -0.604304 0.574129 0.552442 -v 0.054445 0.093676 0.095464 -vn -0.862714 0.503407 -0.048018 -v 0.054444 0.093709 0.095700 -vn -0.944680 0.215285 0.247449 -v 0.054443 0.093672 0.095465 -vn -0.044985 0.836240 0.546515 -v 0.054453 0.093680 0.095462 -vn -0.298928 0.764968 0.570496 -v 0.054448 0.093679 0.095463 -vn -0.349792 0.748211 -0.563761 -v 0.054448 0.093679 0.096536 -vn -0.144727 0.832496 -0.534793 -v 0.054451 0.093680 0.096536 -vn -0.497062 0.863801 0.082327 -v 0.054448 0.093713 0.096299 -vn 0.000211 0.995482 0.094946 -v 0.054453 0.093714 0.096299 -vn -0.862676 0.503462 0.048132 -v 0.054444 0.093709 0.096299 -vn -0.672930 0.524885 -0.521211 -v 0.054444 0.093676 0.096534 -vn -0.999970 0.007693 0.000597 -v 0.054443 0.093704 0.096298 -vn -0.949388 0.165480 -0.266982 -v 0.054443 0.093671 0.096533 -vn -0.869171 -0.492258 -0.047169 -v 0.054444 0.093699 0.096298 -vn -0.643328 -0.084284 -0.760937 -v 0.054444 0.093667 0.096531 -vn 0.503314 -0.860124 -0.082840 -v 0.054458 0.093696 0.096297 -vn 0.191196 -0.481575 -0.855295 -v 0.054456 0.093662 0.096530 -vn -0.102681 -0.489338 -0.866028 -v 0.054451 0.093661 0.096530 -vn 0.999970 0.007681 0.000118 -v 0.054463 0.093704 0.096298 -vn 0.707151 0.004719 -0.707047 -v 0.054462 0.093668 0.096532 -vn 0.869401 -0.491799 -0.047703 -v 0.054462 0.093699 0.096298 -vn 0.548197 -0.254168 -0.796792 -v 0.054460 0.093664 0.096531 -vn 0.394992 -0.410168 -0.822036 -v 0.054458 0.093663 0.096530 -vn 0.496796 0.863933 0.082545 -v 0.054458 0.093713 0.096299 -vn 0.609106 0.570894 -0.550517 -v 0.054461 0.093676 0.096535 -vn 0.862809 0.503274 0.047699 -v 0.054462 0.093709 0.096299 -vn 0.944513 0.215484 -0.247915 -v 0.054463 0.093672 0.096533 -vn 0.049663 0.834420 -0.548887 -v 0.054453 0.093681 0.096536 -vn 0.306846 0.761162 -0.571383 -v 0.054458 0.093679 0.096536 -vn -0.000000 -1.000000 0.000278 -v 0.054453 0.093709 0.095999 -vn -0.503527 -0.863979 0.000237 -v 0.054448 0.093710 0.095999 -vn -0.869519 -0.493900 0.000136 -v 0.054444 0.093714 0.095999 -vn -0.999964 0.008495 -0.000003 -v 0.054443 0.093719 0.095999 -vn -0.862227 0.506523 -0.000138 -v 0.054444 0.093724 0.095999 -vn -0.496349 0.868123 -0.000235 -v 0.054448 0.093728 0.095999 -vn -0.000000 1.000000 -0.000271 -v 0.054453 0.093729 0.095999 -vn 0.496348 0.868123 -0.000238 -v 0.054458 0.093728 0.095999 -vn 0.862398 0.506231 -0.000143 -v 0.054462 0.093724 0.095999 -vn 0.999964 0.008473 -0.000006 -v 0.054463 0.093719 0.095999 -vn 0.869696 -0.493588 0.000136 -v 0.054462 0.093714 0.095999 -vn 0.503528 -0.863979 0.000241 -v 0.054458 0.093710 0.095999 -vn -0.408708 -0.878903 -0.245942 -v 0.054448 0.092980 0.094053 -vn -0.503121 -0.600586 0.621422 -v 0.054448 0.092819 0.093882 -vn -0.000217 -0.695236 0.718782 -v 0.054453 0.092818 0.093883 -vn 0.446706 0.447150 0.774927 -v 0.054459 0.092150 0.093390 -vn 0.502856 -0.472009 0.724115 -v 0.054458 0.092352 0.093510 -vn 0.000508 -0.545975 0.837801 -v 0.054453 0.092352 0.093511 -vn 0.397206 0.892365 -0.214269 -v 0.054459 0.092156 0.093375 -vn 0.166992 0.938822 -0.301208 -v 0.054455 0.092156 0.093373 -vn 0.497342 0.473968 -0.726639 -v 0.054458 0.092362 0.093496 -vn -0.000164 0.546035 -0.837763 -v 0.054453 0.092363 0.093495 -vn 0.862896 0.276087 -0.423304 -v 0.054462 0.092360 0.093499 -vn 0.693984 0.715959 -0.076080 -v 0.054462 0.092155 0.093378 -vn 0.999972 0.004222 -0.006215 -v 0.054463 0.092357 0.093503 -vn 0.949448 0.311748 0.036904 -v 0.054463 0.092153 0.093383 -vn 0.869301 -0.269463 0.414373 -v 0.054462 0.092354 0.093507 -vn 0.658403 0.540634 0.523660 -v 0.054462 0.092151 0.093387 -vn -0.503244 -0.471130 0.724419 -v 0.054448 0.092352 0.093510 -vn -0.192038 0.367443 0.910004 -v 0.054450 0.092149 0.093392 -vn 0.127150 0.386528 0.913471 -v 0.054455 0.092149 0.093392 -vn -0.999972 0.004606 -0.005944 -v 0.054443 0.092357 0.093503 -vn -0.705400 0.557229 0.438071 -v 0.054444 0.092152 0.093386 -vn -0.869093 -0.269414 0.414841 -v 0.054444 0.092354 0.093507 -vn -0.548678 0.464532 0.695099 -v 0.054446 0.092150 0.093389 -vn -0.394642 0.388775 0.832533 -v 0.054448 0.092150 0.093391 -vn -0.497280 0.473632 -0.726902 -v 0.054448 0.092362 0.093496 -vn -0.605473 0.788919 -0.104924 -v 0.054445 0.092155 0.093377 -vn -0.862596 0.276449 -0.423680 -v 0.054444 0.092360 0.093499 -vn -0.944720 0.327585 -0.013900 -v 0.054443 0.092153 0.093381 -vn -0.045074 0.948347 -0.314018 -v 0.054453 0.092156 0.093373 -vn -0.298133 0.923316 -0.242084 -v 0.054448 0.092156 0.093374 -vn -0.350531 0.026234 -0.936184 -v 0.054448 0.092995 0.094043 -vn -0.143823 0.100481 -0.984489 -v 0.054451 0.092996 0.094042 -vn -0.496855 0.602993 -0.624127 -v 0.054448 0.092831 0.093869 -vn 0.000215 0.694925 -0.719082 -v 0.054453 0.092832 0.093868 -vn -0.862725 0.351491 -0.363538 -v 0.054444 0.092828 0.093872 -vn -0.669857 -0.081730 -0.737979 -v 0.054444 0.092992 0.094045 -vn -0.999972 0.005130 -0.005511 -v 0.054443 0.092825 0.093876 -vn -0.949472 -0.105427 -0.295616 -v 0.054443 0.092987 0.094048 -vn -0.869125 -0.343855 0.355508 -v 0.054444 0.092821 0.093879 -vn -0.643623 -0.647426 -0.408153 -v 0.054444 0.092984 0.094050 -vn 0.503109 -0.601114 0.620921 -v 0.054458 0.092819 0.093882 -vn 0.192373 -0.968985 -0.155115 -v 0.054456 0.092979 0.094053 -vn -0.103011 -0.982207 -0.157030 -v 0.054451 0.092979 0.094053 -vn 0.999972 0.004747 -0.005800 -v 0.054463 0.092825 0.093876 -vn 0.703722 -0.552728 -0.446393 -v 0.054462 0.092985 0.094050 -vn 0.869355 -0.343982 0.354821 -v 0.054462 0.092821 0.093879 -vn 0.549289 -0.781010 -0.297160 -v 0.054460 0.092982 0.094052 -vn 0.393667 -0.898582 -0.193847 -v 0.054458 0.092980 0.094053 -vn 0.496586 0.603245 -0.624098 -v 0.054458 0.092831 0.093869 -vn 0.607708 -0.074868 -0.790624 -v 0.054461 0.092992 0.094045 -vn 0.862860 0.351031 -0.363662 -v 0.054462 0.092828 0.093872 -vn 0.944684 -0.059401 -0.322558 -v 0.054463 0.092989 0.094047 -vn 0.049852 0.091390 -0.994567 -v 0.054453 0.092996 0.094042 -vn 0.306089 0.028139 -0.951587 -v 0.054458 0.092995 0.094043 -vn -0.000002 -0.623262 0.782013 -v 0.054453 0.092594 0.093685 -vn -0.503387 -0.538545 0.675700 -v 0.054448 0.092595 0.093684 -vn -0.869587 -0.307770 0.386129 -v 0.054444 0.092597 0.093681 -vn -0.999965 0.005184 -0.006499 -v 0.054443 0.092600 0.093677 -vn -0.862237 0.315688 -0.396091 -v 0.054444 0.092603 0.093674 -vn -0.496398 0.541063 -0.678851 -v 0.054448 0.092606 0.093671 -vn 0.000005 0.623260 -0.782014 -v 0.054453 0.092606 0.093670 -vn 0.496394 0.541061 -0.678856 -v 0.054458 0.092606 0.093671 -vn 0.862408 0.315504 -0.395865 -v 0.054462 0.092603 0.093674 -vn 0.999966 0.005170 -0.006482 -v 0.054463 0.092600 0.093677 -vn 0.869765 -0.307578 0.385883 -v 0.054462 0.092597 0.093681 -vn 0.503389 -0.538541 0.675702 -v 0.054458 0.092595 0.093684 -vn -0.408910 -0.739698 0.534452 -v 0.054448 0.090618 0.093042 -vn -0.503103 0.111358 0.857022 -v 0.054448 0.090383 0.093061 -vn -0.000228 0.128527 0.991706 -v 0.054453 0.090383 0.093063 -vn 0.446828 0.884615 0.133425 -v 0.054459 0.089582 0.093278 -vn 0.502789 0.271865 0.820544 -v 0.054458 0.089802 0.093194 -vn 0.000507 0.314618 0.949218 -v 0.054453 0.089803 0.093195 -vn 0.404266 0.393229 -0.825796 -v 0.054459 0.089574 0.093264 -vn 0.167185 0.349338 -0.921961 -v 0.054455 0.089573 0.093262 -vn 0.496778 -0.272714 -0.823917 -v 0.054458 0.089797 0.093178 -vn -0.000166 -0.314527 -0.949249 -v 0.054453 0.089796 0.093176 -vn 0.862792 -0.158751 -0.479988 -v 0.054462 0.089798 0.093181 -vn 0.724588 0.371359 -0.580573 -v 0.054462 0.089576 0.093267 -vn 0.999972 -0.002064 -0.007137 -v 0.054463 0.089799 0.093186 -vn 0.951742 0.222322 -0.211566 -v 0.054463 0.089578 0.093271 -vn 0.869250 0.155992 0.469117 -v 0.054462 0.089801 0.093191 -vn 0.659429 0.745566 -0.096359 -v 0.054462 0.089580 0.093275 -vn -0.503179 0.272641 0.820047 -v 0.054448 0.089802 0.093194 -vn -0.192538 0.940469 0.280084 -v 0.054450 0.089583 0.093279 -vn 0.126422 0.955190 0.267637 -v 0.054455 0.089583 0.093279 -vn -0.999972 -0.001772 -0.007300 -v 0.054443 0.089799 0.093186 -vn -0.706218 0.689058 -0.162653 -v 0.054444 0.089580 0.093274 -vn -0.869040 0.156393 0.469373 -v 0.054444 0.089801 0.093191 -vn -0.548641 0.833084 0.070457 -v 0.054446 0.089582 0.093277 -vn -0.393789 0.893639 0.215267 -v 0.054448 0.089582 0.093278 -vn -0.496718 -0.273132 -0.823814 -v 0.054448 0.089797 0.093178 -vn -0.605810 0.409502 -0.682131 -v 0.054445 0.089575 0.093266 -vn -0.862530 -0.158920 -0.480403 -v 0.054444 0.089798 0.093181 -vn -0.944649 0.193424 -0.265000 -v 0.054443 0.089577 0.093270 -vn -0.045662 0.346109 -0.937083 -v 0.054453 0.089573 0.093262 -vn -0.298309 0.386562 -0.872686 -v 0.054448 0.089573 0.093263 -vn -0.349220 -0.716127 -0.604324 -v 0.054448 0.090619 0.093024 -vn -0.144880 -0.706801 -0.692417 -v 0.054451 0.090619 0.093023 -vn -0.497005 -0.111977 -0.860493 -v 0.054448 0.090381 0.093044 -vn 0.000204 -0.128936 -0.991653 -v 0.054453 0.090381 0.093043 -vn -0.862556 -0.065116 -0.501754 -v 0.054444 0.090382 0.093048 -vn -0.672080 -0.625764 -0.395888 -v 0.054444 0.090619 0.093028 -vn -0.999972 -0.001110 -0.007446 -v 0.054443 0.090382 0.093053 -vn -0.949443 -0.296957 -0.101852 -v 0.054443 0.090619 0.093033 -vn -0.869214 0.063555 0.490335 -v 0.054444 0.090383 0.093058 -vn -0.642978 -0.723340 0.251710 -v 0.054444 0.090618 0.093037 -vn 0.503102 0.110627 0.857117 -v 0.054458 0.090383 0.093061 -vn 0.191542 -0.726027 0.660452 -v 0.054456 0.090618 0.093042 -vn -0.102720 -0.735518 0.669673 -v 0.054451 0.090618 0.093043 -vn 0.999972 -0.001572 -0.007329 -v 0.054463 0.090382 0.093053 -vn 0.706698 -0.690812 0.152829 -v 0.054462 0.090618 0.093036 -vn 0.869442 0.062930 0.490010 -v 0.054462 0.090383 0.093058 -vn 0.548949 -0.719505 0.425403 -v 0.054460 0.090618 0.093040 -vn 0.394147 -0.711110 0.582212 -v 0.054458 0.090618 0.093042 -vn 0.496750 -0.111795 -0.860663 -v 0.054458 0.090381 0.093044 -vn 0.609991 -0.663078 -0.433865 -v 0.054461 0.090619 0.093027 -vn 0.862687 -0.065496 -0.501479 -v 0.054462 0.090382 0.093048 -vn 0.944564 -0.289574 -0.154745 -v 0.054463 0.090619 0.093032 -vn 0.048406 -0.720573 -0.691687 -v 0.054453 0.090619 0.093023 -vn 0.306631 -0.726497 -0.614963 -v 0.054458 0.090619 0.093024 -vn -0.000004 0.222797 0.974865 -v 0.054453 0.090090 0.093114 -vn -0.503487 0.192488 0.842288 -v 0.054448 0.090089 0.093113 -vn -0.869337 0.110098 0.481800 -v 0.054444 0.090089 0.093110 -vn -0.999964 -0.001900 -0.008318 -v 0.054443 0.090087 0.093105 -vn -0.862328 -0.112800 -0.493626 -v 0.054444 0.090086 0.093100 -vn -0.496253 -0.193427 -0.846356 -v 0.054448 0.090086 0.093096 -vn -0.000000 -0.222791 -0.974866 -v 0.054453 0.090085 0.093095 -vn 0.496254 -0.193432 -0.846355 -v 0.054458 0.090086 0.093096 -vn 0.862499 -0.112731 -0.493344 -v 0.054462 0.090086 0.093100 -vn 0.999964 -0.001899 -0.008297 -v 0.054463 0.090087 0.093105 -vn 0.869513 0.110036 0.481498 -v 0.054462 0.090089 0.093110 -vn 0.503493 0.192488 0.842284 -v 0.054458 0.090089 0.093113 -vn -0.402704 -0.035594 0.914638 -v 0.054448 0.088354 0.094258 -vn -0.503628 0.739223 0.447111 -v 0.054448 0.088224 0.094454 -vn -0.000219 0.855471 0.517850 -v 0.054453 0.088225 0.094455 -vn 0.441522 0.663833 -0.603643 -v 0.054459 0.087893 0.095215 -vn 0.502651 0.811111 0.299066 -v 0.054458 0.087965 0.094991 -vn 0.000506 0.938274 0.345893 -v 0.054453 0.087966 0.094991 -vn 0.404811 -0.400704 -0.821928 -v 0.054459 0.087877 0.095213 -vn 0.167555 -0.502615 -0.848117 -v 0.054455 0.087875 0.095213 -vn 0.496630 -0.814274 -0.300527 -v 0.054458 0.087949 0.094985 -vn -0.000172 -0.938271 -0.345902 -v 0.054453 0.087947 0.094985 -vn 0.862905 -0.474065 -0.175093 -v 0.054462 0.087952 0.094986 -vn 0.723746 -0.222200 -0.653313 -v 0.054462 0.087881 0.095213 -vn 0.999973 -0.006838 -0.002692 -v 0.054463 0.087957 0.094988 -vn 0.951121 -0.020728 -0.308123 -v 0.054463 0.087885 0.095214 -vn 0.869392 0.463753 0.170557 -v 0.054462 0.087962 0.094990 -vn 0.649368 0.406554 -0.642678 -v 0.054462 0.087890 0.095215 -vn -0.503039 0.811208 0.298151 -v 0.054448 0.087965 0.094991 -vn -0.192076 0.805938 -0.559973 -v 0.054450 0.087895 0.095215 -vn 0.126423 0.804753 -0.579991 -v 0.054455 0.087895 0.095215 -vn -0.999971 -0.007059 -0.002962 -v 0.054443 0.087957 0.094988 -vn -0.694889 0.331803 -0.637993 -v 0.054444 0.087888 0.095214 -vn -0.869146 0.464309 0.170299 -v 0.054444 0.087962 0.094990 -vn -0.548423 0.574402 -0.607697 -v 0.054446 0.087892 0.095215 -vn -0.393715 0.725330 -0.564699 -v 0.054448 0.087894 0.095215 -vn -0.496562 -0.814457 -0.300143 -v 0.054448 0.087949 0.094985 -vn -0.639219 -0.261386 -0.723240 -v 0.054445 0.087880 0.095213 -vn -0.862728 -0.474443 -0.174938 -v 0.054444 0.087952 0.094986 -vn -0.948148 -0.055382 -0.312966 -v 0.054443 0.087885 0.095214 -vn -0.044416 -0.516685 -0.855023 -v 0.054453 0.087875 0.095213 -vn -0.298188 -0.441559 -0.846233 -v 0.054448 0.087876 0.095213 -vn -0.349412 -0.918934 0.182953 -v 0.054448 0.088342 0.094246 -vn -0.144298 -0.982113 0.120967 -v 0.054451 0.088341 0.094245 -vn -0.497143 -0.742503 -0.448930 -v 0.054448 0.088209 0.094445 -vn 0.000202 -0.855706 -0.517462 -v 0.054453 0.088208 0.094444 -vn -0.862607 -0.432810 -0.261887 -v 0.054444 0.088212 0.094447 -vn -0.670873 -0.700550 0.243227 -v 0.054444 0.088344 0.094249 -vn -0.999973 -0.006308 -0.003783 -v 0.054443 0.088216 0.094449 -vn -0.948881 -0.262893 0.174680 -v 0.054443 0.088348 0.094252 -vn -0.869134 0.423164 0.256004 -v 0.054444 0.088220 0.094452 -vn -0.633238 -0.243334 0.734710 -v 0.054444 0.088352 0.094256 -vn 0.503614 0.738847 0.447747 -v 0.054458 0.088224 0.094454 -vn 0.192357 0.063451 0.979272 -v 0.054456 0.088355 0.094259 -vn -0.103271 0.065713 0.992480 -v 0.054451 0.088355 0.094259 -vn 0.999972 -0.006629 -0.003603 -v 0.054463 0.088216 0.094449 -vn 0.693645 -0.292411 0.658296 -v 0.054462 0.088350 0.094255 -vn 0.869327 0.422509 0.256429 -v 0.054462 0.088220 0.094452 -vn 0.548565 -0.116177 0.827997 -v 0.054460 0.088353 0.094257 -vn 0.394124 0.011812 0.918982 -v 0.054458 0.088354 0.094258 -vn 0.496888 -0.742526 -0.449175 -v 0.054458 0.088209 0.094445 -vn 0.641328 -0.726067 0.248042 -v 0.054461 0.088344 0.094248 -vn 0.862821 -0.432583 -0.261556 -v 0.054462 0.088212 0.094447 -vn 0.948115 -0.279374 0.151748 -v 0.054463 0.088348 0.094252 -vn 0.048417 -0.990087 0.131845 -v 0.054453 0.088341 0.094245 -vn 0.306172 -0.933898 0.184646 -v 0.054458 0.088342 0.094246 -vn 0.000003 0.901090 0.433632 -v 0.054453 0.088082 0.094716 -vn -0.503655 0.778455 0.374620 -v 0.054448 0.088081 0.094716 -vn -0.869507 0.445070 0.214174 -v 0.054444 0.088077 0.094714 -vn -0.999967 -0.007341 -0.003532 -v 0.054443 0.088073 0.094712 -vn -0.862402 -0.456152 -0.219517 -v 0.054444 0.088068 0.094710 -vn -0.496459 -0.782201 -0.376418 -v 0.054448 0.088065 0.094708 -vn -0.000003 -0.901089 -0.433635 -v 0.054453 0.088064 0.094708 -vn 0.496463 -0.782199 -0.376417 -v 0.054458 0.088065 0.094708 -vn 0.862573 -0.455888 -0.219395 -v 0.054462 0.088068 0.094710 -vn 0.999967 -0.007322 -0.003525 -v 0.054463 0.088073 0.094712 -vn 0.869684 0.444790 0.214039 -v 0.054462 0.088077 0.094714 -vn 0.503653 0.778456 0.374619 -v 0.054458 0.088081 0.094716 -vn -0.403206 0.899354 -0.169077 -v 0.054448 0.089584 0.098722 -vn -0.503236 0.271503 -0.820390 -v 0.054448 0.089804 0.098806 -vn -0.000224 0.314459 -0.949271 -v 0.054453 0.089804 0.098805 -vn 0.446541 -0.739353 -0.503942 -v 0.054459 0.090619 0.098959 -vn 0.502799 0.111064 -0.857239 -v 0.054458 0.090385 0.098939 -vn 0.000507 0.128428 -0.991719 -v 0.054453 0.090385 0.098938 -vn 0.404612 -0.712578 0.573169 -v 0.054459 0.090621 0.098975 -vn 0.166997 -0.715080 0.678802 -v 0.054455 0.090621 0.098977 -vn 0.496676 -0.111812 0.860704 -v 0.054458 0.090383 0.098956 -vn -0.000173 -0.128462 0.991714 -v 0.054453 0.090383 0.098957 -vn 0.863025 -0.065167 0.500941 -v 0.054462 0.090383 0.098952 -vn 0.724577 -0.586511 0.361929 -v 0.054462 0.090621 0.098972 -vn 0.999972 -0.001235 0.007352 -v 0.054463 0.090384 0.098947 -vn 0.951694 -0.292274 0.094100 -v 0.054463 0.090620 0.098967 -vn 0.869203 0.062997 -0.490426 -v 0.054462 0.090384 0.098942 -vn 0.659509 -0.713405 -0.236858 -v 0.054462 0.090620 0.098963 -vn -0.503188 0.110154 -0.857128 -v 0.054448 0.090385 0.098939 -vn -0.191195 -0.726317 -0.660233 -v 0.054450 0.090619 0.098958 -vn 0.126614 -0.744337 -0.655692 -v 0.054455 0.090619 0.098957 -vn -0.999971 -0.001324 0.007564 -v 0.054443 0.090384 0.098947 -vn -0.693811 -0.696836 -0.181787 -v 0.054444 0.090620 0.098964 -vn -0.868994 0.062750 -0.490828 -v 0.054444 0.090384 0.098942 -vn -0.549114 -0.720052 -0.424263 -v 0.054446 0.090620 0.098960 -vn -0.395149 -0.710918 -0.581767 -v 0.054448 0.090619 0.098958 -vn -0.496602 -0.111396 0.860800 -v 0.054448 0.090383 0.098956 -vn -0.638055 -0.647996 0.415917 -v 0.054445 0.090621 0.098973 -vn -0.862850 -0.064936 0.501272 -v 0.054444 0.090383 0.098952 -vn -0.948128 -0.292830 0.123710 -v 0.054443 0.090620 0.098967 -vn -0.045929 -0.718237 0.694282 -v 0.054453 0.090621 0.098977 -vn -0.298393 -0.726678 0.618790 -v 0.054448 0.090621 0.098976 -vn -0.355915 0.387671 0.850315 -v 0.054448 0.089575 0.098737 -vn -0.144960 0.336475 0.930468 -v 0.054451 0.089574 0.098738 -vn -0.496368 -0.272605 0.824200 -v 0.054448 0.089798 0.098823 -vn 0.000208 -0.314071 0.949399 -v 0.054453 0.089798 0.098824 -vn -0.862496 -0.158939 0.480456 -v 0.054444 0.089799 0.098819 -vn -0.703226 0.376946 0.602814 -v 0.054444 0.089577 0.098734 -vn -0.999973 -0.002163 0.007047 -v 0.054443 0.089801 0.098815 -vn -0.951077 0.228117 0.208362 -v 0.054443 0.089579 0.098730 -vn -0.869226 0.155365 -0.469370 -v 0.054444 0.089803 0.098810 -vn -0.634197 0.769645 0.073761 -v 0.054444 0.089582 0.098726 -vn 0.503229 0.272197 -0.820164 -v 0.054458 0.089804 0.098806 -vn 0.191901 0.940561 -0.280211 -v 0.054456 0.089584 0.098722 -vn -0.102741 0.953260 -0.284149 -v 0.054451 0.089585 0.098721 -vn 0.999971 -0.002076 0.007353 -v 0.054463 0.089801 0.098815 -vn 0.695556 0.705046 0.138244 -v 0.054462 0.089581 0.098727 -vn 0.869418 0.155928 -0.468827 -v 0.054462 0.089803 0.098810 -vn 0.548416 0.833213 -0.070684 -v 0.054460 0.089583 0.098724 -vn 0.394615 0.893058 -0.216164 -v 0.054458 0.089584 0.098722 -vn 0.496107 -0.272834 0.824281 -v 0.054458 0.089798 0.098823 -vn 0.642521 0.402525 0.652027 -v 0.054461 0.089577 0.098735 -vn 0.862754 -0.158761 0.480052 -v 0.054462 0.089799 0.098819 -vn 0.948063 0.210284 0.238655 -v 0.054463 0.089579 0.098730 -vn 0.048456 0.348666 0.935994 -v 0.054453 0.089574 0.098739 -vn 0.305476 0.388066 0.869534 -v 0.054458 0.089575 0.098737 -vn -0.000003 0.222255 -0.974989 -v 0.054453 0.090091 0.098886 -vn -0.504023 0.191934 -0.842094 -v 0.054448 0.090091 0.098887 -vn -0.869518 0.109780 -0.481546 -v 0.054444 0.090090 0.098891 -vn -0.999965 -0.001849 0.008109 -v 0.054443 0.090089 0.098896 -vn -0.862271 -0.112560 0.493780 -v 0.054444 0.090088 0.098901 -vn -0.496156 -0.192962 0.846520 -v 0.054448 0.090087 0.098904 -vn 0.000001 -0.222261 0.974987 -v 0.054453 0.090087 0.098905 -vn 0.496159 -0.192963 0.846518 -v 0.054458 0.090087 0.098904 -vn 0.862440 -0.112495 0.493500 -v 0.054462 0.090088 0.098901 -vn 0.999966 -0.001845 0.008088 -v 0.054463 0.090089 0.098896 -vn 0.869694 0.109713 -0.481244 -v 0.054462 0.090090 0.098891 -vn 0.504028 0.191942 -0.842089 -v 0.054458 0.090091 0.098887 -vn 0.248027 -0.000248 -0.968753 -v 0.054643 0.087779 0.095230 -vn 0.240808 -0.059597 -0.968741 -v 0.054638 0.087733 0.095230 -vn 0.000000 -0.004310 -0.999991 -v 0.054453 0.087779 0.095207 -vn -0.219607 0.114981 -0.968789 -v 0.054285 0.087867 0.095230 -vn -0.185624 0.164224 -0.968800 -v 0.054311 0.087905 0.095230 -vn -0.056885 -0.468241 0.881768 -v 0.054409 0.087413 0.096704 -vn -0.029874 -0.245947 0.968823 -v 0.054430 0.087591 0.096772 -vn -0.087940 -0.231625 0.968822 -v 0.054386 0.087602 0.096772 -vn 0.000000 -0.003750 0.999993 -v 0.054453 0.087779 0.096795 -vn 0.029880 -0.245950 0.968822 -v 0.054476 0.087591 0.096772 -vn 0.041812 0.261496 0.964298 -v 0.054476 0.087968 0.096772 -vn -0.041799 0.261486 0.964302 -v 0.054430 0.087968 0.096772 -vn 0.140890 0.204392 0.968697 -v 0.054561 0.087936 0.096772 -vn 0.268065 0.388647 0.881530 -v 0.054663 0.088083 0.096704 -vn 0.167347 0.441505 0.881515 -v 0.054584 0.088124 0.096704 -vn 0.056891 -0.468241 0.881768 -v 0.054498 0.087413 0.096704 -vn 0.080559 -0.663169 0.744121 -v 0.054517 0.087257 0.096595 -vn 0.087940 -0.231629 0.968821 -v 0.054520 0.087602 0.096772 -vn 0.167356 -0.441018 0.881757 -v 0.054584 0.087434 0.096704 -vn 0.236974 -0.624609 0.744115 -v 0.054640 0.087287 0.096595 -vn 0.292888 -0.772086 0.564004 -v 0.054685 0.087168 0.096452 -vn 0.140896 -0.203851 0.968810 -v 0.054561 0.087623 0.096772 -vn 0.268088 -0.388151 0.881741 -v 0.054663 0.087476 0.096704 -vn 0.379600 -0.549762 0.744088 -v 0.054752 0.087346 0.096595 -vn 0.469181 -0.679567 0.563966 -v 0.054824 0.087242 0.096452 -vn 0.531812 -0.770339 0.351787 -v 0.054875 0.087168 0.096283 -vn 0.185663 -0.164169 0.968802 -v 0.054595 0.087653 0.096772 -vn 0.353245 -0.312697 0.881725 -v 0.054729 0.087535 0.096704 -vn 0.500189 -0.442930 0.744059 -v 0.054847 0.087430 0.096595 -vn 0.618210 -0.547543 0.563926 -v 0.054942 0.087346 0.096452 -vn 0.700720 -0.620701 0.351742 -v 0.055009 0.087287 0.096283 -vn 0.743149 -0.658345 0.119628 -v 0.055043 0.087256 0.096097 -vn 0.219625 -0.114993 0.968784 -v 0.054621 0.087691 0.096772 -vn 0.417875 -0.219058 0.881699 -v 0.054780 0.087608 0.096704 -vn 0.591706 -0.310335 0.744027 -v 0.054919 0.087535 0.096595 -vn 0.731323 -0.383671 0.563882 -v 0.055032 0.087476 0.096452 -vn 0.828928 -0.434956 0.351697 -v 0.055110 0.087434 0.096282 -vn 0.879116 -0.461366 0.119570 -v 0.055151 0.087413 0.096097 -vn 0.879115 -0.461433 -0.119316 -v 0.055151 0.087413 0.095905 -vn 0.240804 -0.059116 0.968772 -v 0.054638 0.087734 0.096772 -vn -0.240806 -0.059094 0.968773 -v 0.054269 0.087734 0.096772 -vn -0.219625 -0.114997 0.968783 -v 0.054285 0.087691 0.096772 -vn -0.417873 -0.219069 0.881698 -v 0.054126 0.087608 0.096704 -vn -0.353245 -0.312700 0.881724 -v 0.054177 0.087535 0.096704 -vn -0.500184 -0.442926 0.744064 -v 0.054059 0.087430 0.096595 -vn -0.379600 -0.549753 0.744094 -v 0.054154 0.087346 0.096595 -vn -0.469183 -0.679566 0.563966 -v 0.054082 0.087242 0.096452 -vn -0.292873 -0.772092 0.564003 -v 0.054221 0.087168 0.096452 -vn -0.331971 -0.875226 0.351816 -v 0.054190 0.087085 0.096283 -vn -0.112829 -0.929236 0.351838 -v 0.054364 0.087042 0.096283 -vn -0.119678 -0.985568 0.119720 -v 0.054358 0.086997 0.096097 -vn 0.119683 -0.985567 0.119725 -v 0.054548 0.086997 0.096097 -vn -0.119684 -0.985633 -0.119178 -v 0.054358 0.086997 0.095905 -vn -0.352081 -0.928285 0.119695 -v 0.054174 0.087042 0.096097 -vn -0.531807 -0.770346 0.351778 -v 0.054031 0.087168 0.096283 -vn -0.618218 -0.547536 0.563925 -v 0.053964 0.087346 0.096452 -vn -0.591707 -0.310340 0.744024 -v 0.053987 0.087535 0.096595 -vn -0.458217 -0.112701 0.881667 -v 0.054095 0.087691 0.096704 -vn -0.248025 0.000311 0.968754 -v 0.054263 0.087779 0.096772 -vn 0.352054 0.928359 0.119192 -v 0.054733 0.088516 0.096096 -vn 0.352058 0.928292 -0.119700 -v 0.054733 0.088516 0.095905 -vn 0.119667 0.985571 -0.119708 -v 0.054548 0.088562 0.095905 -vn 0.458217 -0.112720 0.881664 -v 0.054811 0.087691 0.096704 -vn 0.648828 -0.159716 0.743985 -v 0.054964 0.087653 0.096595 -vn 0.801926 -0.197505 0.563832 -v 0.055087 0.087623 0.096452 -vn 0.908960 -0.223938 0.351630 -v 0.055174 0.087602 0.096282 -vn 0.963990 -0.237573 0.119509 -v 0.055218 0.087591 0.096097 -vn 0.963990 -0.237639 -0.119381 -v 0.055218 0.087590 0.095905 -vn 0.908958 -0.224137 -0.351508 -v 0.055174 0.087601 0.095719 -vn 0.248013 0.000311 0.968757 -v 0.054643 0.087779 0.096772 -vn 0.119679 -0.985634 -0.119173 -v 0.054548 0.086997 0.095905 -vn 0.352077 -0.928352 -0.119179 -v 0.054733 0.087042 0.095905 -vn -0.112841 -0.929435 -0.351310 -v 0.054364 0.087042 0.095719 -vn -0.352074 -0.928353 -0.119183 -v 0.054174 0.087042 0.095905 -vn -0.563995 -0.817061 0.119669 -v 0.054005 0.087130 0.096097 -vn -0.700722 -0.620697 0.351745 -v 0.053897 0.087287 0.096283 -vn -0.731322 -0.383669 0.563884 -v 0.053874 0.087476 0.096452 -vn -0.648828 -0.159728 0.743982 -v 0.053942 0.087653 0.096595 -vn -0.471919 0.000227 0.881642 -v 0.054084 0.087779 0.096704 -vn -0.240820 0.059588 0.968739 -v 0.054269 0.087825 0.096772 -vn 0.471931 0.000233 0.881635 -v 0.054822 0.087779 0.096704 -vn 0.668247 0.000197 0.743939 -v 0.054980 0.087779 0.096595 -vn 0.825925 0.000159 0.563781 -v 0.055106 0.087779 0.096452 -vn 0.936161 0.000100 0.351573 -v 0.055195 0.087779 0.096282 -vn 0.992841 0.000036 0.119446 -v 0.055241 0.087779 0.096097 -vn 0.992840 -0.000033 -0.119449 -v 0.055241 0.087779 0.095905 -vn 0.936159 -0.000101 -0.351578 -v 0.055195 0.087779 0.095719 -vn 0.825926 -0.000163 -0.563778 -v 0.055106 0.087779 0.095550 -vn 0.240823 0.059619 0.968736 -v 0.054638 0.087825 0.096772 -vn 0.331974 -0.875424 -0.351320 -v 0.054716 0.087085 0.095719 -vn 0.531808 -0.770540 -0.351352 -v 0.054875 0.087168 0.095719 -vn -0.099558 -0.820064 -0.563545 -v 0.054374 0.087130 0.095550 -vn -0.331971 -0.875425 -0.351320 -v 0.054190 0.087085 0.095719 -vn -0.563998 -0.817126 -0.119215 -v 0.054005 0.087130 0.095905 -vn -0.743150 -0.658345 0.119627 -v 0.053863 0.087256 0.096097 -vn -0.828927 -0.434959 0.351698 -v 0.053796 0.087434 0.096282 -vn -0.801924 -0.197506 0.563835 -v 0.053819 0.087623 0.096452 -vn -0.668248 0.000199 0.743939 -v 0.053927 0.087779 0.096595 -vn -0.458207 0.113202 0.881608 -v 0.054095 0.087868 0.096704 -vn -0.219603 0.115532 0.968724 -v 0.054285 0.087868 0.096772 -vn -0.112845 0.929236 -0.351834 -v 0.054364 0.088516 0.095719 -vn -0.099533 0.819746 -0.564012 -v 0.054374 0.088428 0.095550 -vn -0.292872 0.772101 -0.563991 -v 0.054221 0.088390 0.095550 -vn 0.458201 0.113201 0.881611 -v 0.054811 0.087868 0.096704 -vn 0.648841 0.160124 0.743886 -v 0.054964 0.087905 0.096595 -vn 0.801922 0.197820 0.563727 -v 0.055087 0.087936 0.096452 -vn 0.908961 0.224132 0.351505 -v 0.055174 0.087957 0.096282 -vn 0.963992 0.237632 0.119375 -v 0.055218 0.087968 0.096096 -vn 0.963990 0.237572 -0.119510 -v 0.055218 0.087968 0.095905 -vn 0.908957 0.223942 -0.351635 -v 0.055174 0.087957 0.095719 -vn 0.801927 0.197488 -0.563837 -v 0.055087 0.087935 0.095550 -vn 0.648834 0.159720 -0.743978 -v 0.054964 0.087905 0.095406 -vn 0.219611 0.115517 0.968724 -v 0.054621 0.087868 0.096772 -vn 0.469190 -0.679880 -0.563581 -v 0.054824 0.087241 0.095550 -vn 0.618212 -0.547853 -0.563623 -v 0.054942 0.087346 0.095550 -vn -0.080551 -0.663585 -0.743751 -v 0.054390 0.087256 0.095407 -vn -0.292887 -0.772412 -0.563557 -v 0.054221 0.087168 0.095550 -vn -0.531803 -0.770544 -0.351351 -v 0.054031 0.087168 0.095719 -vn -0.743150 -0.658411 -0.119260 -v 0.053863 0.087256 0.095905 -vn -0.879116 -0.461365 0.119570 -v 0.053755 0.087413 0.096097 -vn -0.908961 -0.223934 0.351631 -v 0.053732 0.087602 0.096282 -vn -0.825929 0.000161 0.563774 -v 0.053800 0.087779 0.096452 -vn -0.648835 0.160131 0.743890 -v 0.053942 0.087905 0.096595 -vn -0.417874 0.219564 0.881574 -v 0.054126 0.087951 0.096704 -vn -0.185639 0.164760 0.968706 -v 0.054311 0.087905 0.096772 -vn -0.236971 0.624616 -0.744110 -v 0.054266 0.088271 0.095406 -vn -0.379620 0.549746 -0.744089 -v 0.054154 0.088212 0.095406 -vn 0.417863 0.219569 0.881578 -v 0.054780 0.087951 0.096704 -vn 0.591713 0.310751 0.743848 -v 0.054919 0.088024 0.096595 -vn 0.731325 0.383981 0.563668 -v 0.055032 0.088083 0.096452 -vn 0.828923 0.435157 0.351461 -v 0.055110 0.088124 0.096282 -vn 0.879119 0.461426 0.119316 -v 0.055151 0.088145 0.096096 -vn 0.879118 0.461361 -0.119574 -v 0.055151 0.088145 0.095905 -vn 0.828928 0.434960 -0.351693 -v 0.055110 0.088124 0.095719 -vn 0.731317 0.383678 -0.563885 -v 0.055032 0.088083 0.095550 -vn 0.591703 0.310338 -0.744029 -v 0.054919 0.088024 0.095406 -vn 0.417862 0.219101 -0.881695 -v 0.054780 0.087950 0.095298 -vn 0.185621 0.164770 0.968708 -v 0.054595 0.087905 0.096772 -vn 0.500199 -0.443338 -0.743809 -v 0.054847 0.087430 0.095407 -vn 0.591710 -0.310750 -0.743851 -v 0.054919 0.087534 0.095407 -vn -0.056902 -0.468712 -0.881516 -v 0.054409 0.087413 0.095298 -vn -0.236971 -0.625029 -0.743763 -v 0.054266 0.087287 0.095407 -vn -0.469184 -0.679884 -0.563582 -v 0.054082 0.087241 0.095550 -vn -0.700725 -0.620889 -0.351400 -v 0.053897 0.087287 0.095719 -vn -0.879115 -0.461434 -0.119315 -v 0.053755 0.087413 0.095905 -vn -0.963990 -0.237573 0.119511 -v 0.053688 0.087591 0.096097 -vn -0.936159 0.000097 0.351577 -v 0.053711 0.087779 0.096282 -vn -0.801926 0.197820 0.563722 -v 0.053819 0.087936 0.096452 -vn -0.591709 0.310759 0.743848 -v 0.053987 0.088024 0.096595 -vn -0.353229 0.313191 0.881556 -v 0.054177 0.088024 0.096704 -vn -0.140880 0.204399 0.968697 -v 0.054345 0.087936 0.096772 -vn -0.268104 0.388129 -0.881746 -v 0.054243 0.088083 0.095298 -vn -0.353246 0.312712 -0.881719 -v 0.054177 0.088024 0.095298 -vn 0.417865 -0.219566 -0.881578 -v 0.054780 0.087607 0.095298 -vn 0.458226 -0.113172 -0.881602 -v 0.054811 0.087691 0.095298 -vn -0.029853 -0.246484 -0.968687 -v 0.054430 0.087590 0.095230 -vn -0.167361 -0.441500 -0.881515 -v 0.054322 0.087434 0.095298 -vn -0.379612 -0.550163 -0.743785 -v 0.054154 0.087346 0.095407 -vn -0.618217 -0.547846 -0.563625 -v 0.053964 0.087346 0.095550 -vn -0.828927 -0.435159 -0.351449 -v 0.053796 0.087434 0.095719 -vn -0.963990 -0.237640 -0.119380 -v 0.053688 0.087590 0.095905 -vn -0.992841 0.000034 0.119445 -v 0.053665 0.087779 0.096097 -vn -0.908957 0.224135 0.351513 -v 0.053732 0.087957 0.096282 -vn -0.731326 0.383974 0.563672 -v 0.053874 0.088083 0.096452 -vn -0.500190 0.443340 0.743814 -v 0.054059 0.088128 0.096595 -vn -0.268075 0.388642 0.881529 -v 0.054243 0.088083 0.096704 -vn -0.087978 0.232166 0.968689 -v 0.054386 0.087957 0.096772 -vn 0.292883 0.772408 0.563565 -v 0.054685 0.088390 0.096452 -vn 0.331963 0.875423 0.351335 -v 0.054716 0.088473 0.096282 -vn 0.112845 0.929435 0.351306 -v 0.054543 0.088516 0.096282 -vn 0.119668 0.985636 0.119167 -v 0.054548 0.088562 0.096096 -vn -0.119666 0.985637 0.119164 -v 0.054358 0.088562 0.096096 -vn -0.119671 0.985570 -0.119712 -v 0.054358 0.088562 0.095905 -vn -0.352059 0.928292 -0.119705 -v 0.054174 0.088516 0.095905 -vn -0.331969 0.875228 -0.351813 -v 0.054190 0.088473 0.095719 -vn -0.531795 0.770348 -0.351794 -v 0.054031 0.088390 0.095719 -vn -0.469187 0.679564 -0.563965 -v 0.054082 0.088317 0.095550 -vn -0.618212 0.547535 -0.563932 -v 0.053964 0.088212 0.095550 -vn -0.500194 0.442924 -0.744059 -v 0.054059 0.088128 0.095406 -vn -0.591700 0.310354 -0.744024 -v 0.053987 0.088024 0.095406 -vn -0.417864 0.219089 -0.881697 -v 0.054126 0.087950 0.095298 -vn -0.458216 0.112672 -0.881671 -v 0.054095 0.087867 0.095298 -vn -0.240821 0.059028 -0.968773 -v 0.054269 0.087824 0.095230 -vn -0.248019 -0.000241 -0.968755 -v 0.054263 0.087779 0.095230 -vn -0.140888 0.203847 -0.968812 -v 0.054345 0.087935 0.095230 -vn -0.167341 0.441015 -0.881761 -v 0.054322 0.088124 0.095298 -vn -0.087925 0.231632 -0.968822 -v 0.054386 0.087957 0.095230 -vn -0.080545 0.663180 -0.744113 -v 0.054390 0.088302 0.095406 -vn -0.056882 0.468233 -0.881772 -v 0.054409 0.088145 0.095298 -vn -0.041729 0.260956 -0.964449 -v 0.054430 0.087968 0.095230 -vn 0.041740 0.260962 -0.964446 -v 0.054476 0.087968 0.095230 -vn 0.056886 0.468228 -0.881775 -v 0.054498 0.088145 0.095298 -vn 0.080542 0.663178 -0.744116 -v 0.054517 0.088302 0.095406 -vn 0.099541 0.819752 -0.564002 -v 0.054532 0.088428 0.095550 -vn 0.112845 0.929232 -0.351844 -v 0.054543 0.088516 0.095719 -vn 0.331963 0.875229 -0.351817 -v 0.054716 0.088473 0.095719 -vn 0.292867 0.772107 -0.563985 -v 0.054685 0.088390 0.095550 -vn 0.236973 0.624607 -0.744117 -v 0.054640 0.088271 0.095406 -vn 0.167342 0.441016 -0.881761 -v 0.054584 0.088124 0.095298 -vn 0.087917 0.231639 -0.968821 -v 0.054520 0.087957 0.095230 -vn 0.353239 0.313182 0.881555 -v 0.054729 0.088024 0.096704 -vn 0.379591 0.550174 0.743788 -v 0.054752 0.088213 0.096595 -vn 0.500190 0.443340 0.743814 -v 0.054847 0.088128 0.096595 -vn 0.469172 0.679883 0.563592 -v 0.054824 0.088317 0.096452 -vn 0.618218 0.547847 0.563622 -v 0.054942 0.088213 0.096452 -vn 0.531796 0.770543 0.351365 -v 0.054875 0.088390 0.096282 -vn 0.700724 0.620889 0.351401 -v 0.055009 0.088272 0.096282 -vn 0.563998 0.817125 0.119218 -v 0.054901 0.088428 0.096096 -vn 0.743149 0.658412 0.119263 -v 0.055043 0.088302 0.096096 -vn 0.563996 0.817060 -0.119672 -v 0.054901 0.088428 0.095905 -vn 0.743151 0.658343 -0.119627 -v 0.055043 0.088302 0.095905 -vn 0.531801 0.770344 -0.351792 -v 0.054875 0.088390 0.095719 -vn 0.700727 0.620687 -0.351752 -v 0.055009 0.088271 0.095719 -vn 0.469193 0.679555 -0.563972 -v 0.054824 0.088317 0.095550 -vn 0.618211 0.547545 -0.563923 -v 0.054942 0.088212 0.095550 -vn 0.379618 0.549754 -0.744084 -v 0.054752 0.088212 0.095406 -vn 0.500192 0.442927 -0.744059 -v 0.054847 0.088128 0.095406 -vn 0.268091 0.388133 -0.881748 -v 0.054663 0.088083 0.095298 -vn 0.353254 0.312694 -0.881722 -v 0.054729 0.088024 0.095298 -vn 0.140897 0.203843 -0.968812 -v 0.054561 0.087935 0.095230 -vn 0.185624 0.164233 -0.968799 -v 0.054595 0.087905 0.095230 -vn 0.219592 0.114990 -0.968791 -v 0.054621 0.087867 0.095230 -vn 0.240816 0.059029 -0.968774 -v 0.054638 0.087824 0.095230 -vn 0.458216 0.112681 -0.881669 -v 0.054811 0.087867 0.095298 -vn 0.471930 -0.000264 -0.881636 -v 0.054822 0.087779 0.095298 -vn 0.668249 -0.000221 -0.743937 -v 0.054980 0.087779 0.095407 -vn 0.648835 -0.160125 -0.743891 -v 0.054964 0.087653 0.095407 -vn 0.801927 -0.197812 -0.563722 -v 0.055087 0.087623 0.095550 -vn 0.731318 -0.383987 -0.563674 -v 0.055032 0.087475 0.095550 -vn 0.828929 -0.435157 -0.351447 -v 0.055110 0.087434 0.095719 -vn 0.700721 -0.620893 -0.351401 -v 0.055009 0.087287 0.095719 -vn 0.743150 -0.658411 -0.119260 -v 0.055043 0.087256 0.095905 -vn 0.563997 -0.817126 -0.119217 -v 0.054901 0.087130 0.095905 -vn 0.564000 -0.817058 0.119665 -v 0.054901 0.087130 0.096097 -vn 0.352068 -0.928289 0.119695 -v 0.054733 0.087042 0.096097 -vn 0.331966 -0.875230 0.351811 -v 0.054716 0.087085 0.096283 -vn 0.112831 -0.929240 0.351828 -v 0.054543 0.087042 0.096283 -vn 0.099547 -0.819754 0.563999 -v 0.054532 0.087131 0.096452 -vn -0.099554 -0.819752 0.564000 -v 0.054374 0.087131 0.096452 -vn -0.080562 -0.663175 0.744116 -v 0.054390 0.087257 0.096595 -vn -0.236971 -0.624613 0.744112 -v 0.054266 0.087287 0.096595 -vn -0.167364 -0.441017 0.881756 -v 0.054322 0.087434 0.096704 -vn -0.268091 -0.388153 0.881739 -v 0.054243 0.087476 0.096704 -vn -0.140897 -0.203851 0.968810 -v 0.054345 0.087623 0.096772 -vn -0.185673 -0.164170 0.968800 -v 0.054311 0.087653 0.096772 -vn 0.219608 -0.115537 -0.968723 -v 0.054621 0.087691 0.095230 -vn 0.353249 -0.313189 -0.881549 -v 0.054729 0.087534 0.095298 -vn 0.185675 -0.164704 -0.968709 -v 0.054595 0.087653 0.095230 -vn 0.379611 -0.550167 -0.743783 -v 0.054752 0.087346 0.095407 -vn 0.268086 -0.388635 -0.881528 -v 0.054663 0.087475 0.095298 -vn 0.140881 -0.204388 -0.968699 -v 0.054561 0.087623 0.095230 -vn 0.292886 -0.772413 -0.563557 -v 0.054685 0.087168 0.095550 -vn 0.236967 -0.625027 -0.743766 -v 0.054640 0.087287 0.095407 -vn 0.167361 -0.441510 -0.881510 -v 0.054584 0.087434 0.095298 -vn 0.087888 -0.232181 -0.968694 -v 0.054520 0.087601 0.095230 -vn 0.112835 -0.929433 -0.351316 -v 0.054543 0.087042 0.095719 -vn 0.099561 -0.820067 -0.563541 -v 0.054532 0.087130 0.095550 -vn 0.080554 -0.663582 -0.743754 -v 0.054517 0.087256 0.095407 -vn 0.056904 -0.468723 -0.881511 -v 0.054498 0.087413 0.095298 -vn 0.029840 -0.246471 -0.968691 -v 0.054476 0.087590 0.095230 -vn -0.087881 -0.232203 -0.968689 -v 0.054386 0.087601 0.095230 -vn -0.268087 -0.388636 -0.881528 -v 0.054243 0.087475 0.095298 -vn -0.500193 -0.443337 -0.743814 -v 0.054059 0.087430 0.095407 -vn -0.731321 -0.383985 -0.563672 -v 0.053874 0.087475 0.095550 -vn -0.908956 -0.224136 -0.351514 -v 0.053732 0.087601 0.095719 -vn -0.992840 -0.000029 -0.119450 -v 0.053665 0.087779 0.095905 -vn -0.963992 0.237634 0.119375 -v 0.053688 0.087968 0.096096 -vn -0.828927 0.435152 0.351458 -v 0.053796 0.088124 0.096282 -vn -0.618216 0.547842 0.563629 -v 0.053964 0.088213 0.096452 -vn -0.379593 0.550171 0.743788 -v 0.054154 0.088213 0.096595 -vn -0.167345 0.441506 0.881515 -v 0.054322 0.088124 0.096704 -vn -0.140881 -0.204390 -0.968699 -v 0.054345 0.087623 0.095230 -vn -0.353250 -0.313198 -0.881545 -v 0.054177 0.087534 0.095298 -vn -0.591706 -0.310750 -0.743854 -v 0.053987 0.087534 0.095407 -vn -0.801926 -0.197810 -0.563724 -v 0.053819 0.087623 0.095550 -vn -0.936158 -0.000099 -0.351579 -v 0.053711 0.087779 0.095719 -vn -0.963991 0.237568 -0.119510 -v 0.053688 0.087968 0.095905 -vn -0.879118 0.461427 0.119318 -v 0.053755 0.088145 0.096096 -vn -0.700723 0.620892 0.351398 -v 0.053897 0.088272 0.096282 -vn -0.469171 0.679884 0.563592 -v 0.054082 0.088317 0.096452 -vn -0.236953 0.625038 0.743761 -v 0.054266 0.088272 0.096595 -vn -0.056876 0.468744 0.881501 -v 0.054409 0.088146 0.096704 -vn 0.087966 0.232175 0.968688 -v 0.054520 0.087957 0.096772 -vn 0.056878 0.468736 0.881505 -v 0.054498 0.088146 0.096704 -vn -0.080550 0.663575 0.743760 -v 0.054390 0.088302 0.096595 -vn -0.292879 0.772405 0.563571 -v 0.054221 0.088390 0.096452 -vn -0.531793 0.770545 0.351363 -v 0.054031 0.088390 0.096282 -vn -0.743151 0.658409 0.119264 -v 0.053863 0.088302 0.096096 -vn -0.879116 0.461365 -0.119574 -v 0.053755 0.088145 0.095905 -vn -0.908955 0.223941 -0.351642 -v 0.053732 0.087957 0.095719 -vn -0.825928 -0.000165 -0.563776 -v 0.053800 0.087779 0.095550 -vn -0.648837 -0.160135 -0.743887 -v 0.053942 0.087653 0.095407 -vn -0.417875 -0.219566 -0.881573 -v 0.054126 0.087607 0.095298 -vn -0.185665 -0.164705 -0.968711 -v 0.054311 0.087653 0.095230 -vn -0.668252 -0.000216 -0.743935 -v 0.053927 0.087779 0.095407 -vn -0.458219 -0.113174 -0.881605 -v 0.054095 0.087691 0.095298 -vn -0.219617 -0.115518 -0.968723 -v 0.054285 0.087691 0.095230 -vn 0.236950 0.625032 0.743768 -v 0.054640 0.088272 0.096595 -vn 0.080549 0.663576 0.743760 -v 0.054517 0.088302 0.096595 -vn 0.099560 0.820055 0.563558 -v 0.054532 0.088428 0.096452 -vn -0.099559 0.820054 0.563560 -v 0.054374 0.088428 0.096452 -vn -0.112843 0.929434 0.351310 -v 0.054364 0.088516 0.096282 -vn -0.331967 0.875420 0.351336 -v 0.054190 0.088473 0.096282 -vn -0.352063 0.928356 0.119192 -v 0.054174 0.088516 0.096096 -vn -0.563994 0.817128 0.119219 -v 0.054005 0.088428 0.096096 -vn -0.563995 0.817061 -0.119672 -v 0.054005 0.088428 0.095905 -vn -0.743153 0.658341 -0.119628 -v 0.053863 0.088302 0.095905 -vn -0.700728 0.620689 -0.351746 -v 0.053897 0.088271 0.095719 -vn -0.828929 0.434956 -0.351694 -v 0.053796 0.088124 0.095719 -vn -0.731319 0.383672 -0.563887 -v 0.053874 0.088083 0.095550 -vn -0.801930 0.197491 -0.563831 -v 0.053819 0.087935 0.095550 -vn -0.648830 0.159717 -0.743982 -v 0.053942 0.087905 0.095406 -vn -0.471929 -0.000253 -0.881637 -v 0.054084 0.087779 0.095298 -vn -0.240803 -0.059598 -0.968742 -v 0.054269 0.087733 0.095230 -vn 0.248020 -0.757558 -0.603815 -v 0.054643 0.088295 0.097842 -vn 0.240807 -0.794560 -0.557393 -v 0.054638 0.088267 0.097878 -vn 0.000001 -0.784509 -0.620118 -v 0.054453 0.088277 0.097828 -vn -0.219611 -0.685749 -0.693916 -v 0.054285 0.088350 0.097773 -vn -0.185635 -0.655058 -0.732419 -v 0.054311 0.088374 0.097744 -vn -0.056906 0.397443 0.915861 -v 0.054409 0.089220 0.099047 -vn -0.029919 0.604130 0.796324 -v 0.054430 0.089383 0.098951 -vn -0.087939 0.613038 0.785144 -v 0.054386 0.089390 0.098942 -vn 0.000001 0.779483 0.626423 -v 0.054453 0.089519 0.098817 -vn 0.029920 0.604131 0.796323 -v 0.054476 0.089383 0.098951 -vn 0.041861 0.916948 0.396804 -v 0.054476 0.089618 0.098656 -vn -0.041844 0.916944 0.396816 -v 0.054430 0.089618 0.098656 -vn 0.140820 0.884808 0.444168 -v 0.054561 0.089598 0.098681 -vn 0.268062 0.931527 0.245765 -v 0.054663 0.089637 0.098523 -vn 0.167342 0.964472 0.204427 -v 0.054584 0.089663 0.098491 -vn 0.056899 0.397449 0.915859 -v 0.054498 0.089220 0.099047 -vn 0.080541 0.168287 0.982442 -v 0.054517 0.089037 0.099102 -vn 0.087950 0.613037 0.785144 -v 0.054520 0.089390 0.098942 -vn 0.167368 0.414437 0.894556 -v 0.054584 0.089233 0.099031 -vn 0.236957 0.192325 0.952293 -v 0.054640 0.089056 0.099078 -vn 0.292880 -0.040457 0.955293 -v 0.054685 0.088870 0.099081 -vn 0.140851 0.630341 0.763434 -v 0.054561 0.089403 0.098925 -vn 0.268080 0.447369 0.853226 -v 0.054663 0.089259 0.098998 -vn 0.379613 0.238991 0.893743 -v 0.054752 0.089093 0.099032 -vn 0.469185 0.017230 0.882932 -v 0.054824 0.088916 0.099024 -vn 0.531797 -0.205272 0.821618 -v 0.054875 0.088737 0.098976 -vn 0.185629 0.655061 0.732418 -v 0.054595 0.089422 0.098902 -vn 0.353242 0.494388 0.794230 -v 0.054729 0.089295 0.098952 -vn 0.500197 0.305571 0.810203 -v 0.054847 0.089145 0.098966 -vn 0.618214 0.099506 0.779686 -v 0.054942 0.088981 0.098943 -vn 0.700728 -0.111979 0.704585 -v 0.055009 0.088811 0.098883 -vn 0.743150 -0.316940 0.589303 -v 0.055043 0.088647 0.098791 -vn 0.219600 0.685746 0.693922 -v 0.054621 0.089446 0.098872 -vn 0.417880 0.552753 0.721000 -v 0.054780 0.089341 0.098895 -vn 0.591705 0.388213 0.706523 -v 0.054919 0.089210 0.098884 -vn 0.731322 0.201638 0.651545 -v 0.055032 0.089061 0.098841 -vn 0.828929 0.003774 0.559342 -v 0.055110 0.088903 0.098768 -vn 0.879114 -0.194168 0.435266 -v 0.055151 0.088745 0.098669 -vn 0.879119 -0.380976 0.286369 -v 0.055151 0.088595 0.098549 -vn 0.240807 0.720600 0.650191 -v 0.054638 0.089473 0.098839 -vn -0.240815 0.720603 0.650184 -v 0.054269 0.089473 0.098839 -vn -0.219611 0.685753 0.693912 -v 0.054285 0.089446 0.098872 -vn -0.417881 0.552749 0.721002 -v 0.054126 0.089341 0.098895 -vn -0.353242 0.494389 0.794229 -v 0.054177 0.089295 0.098952 -vn -0.500200 0.305570 0.810202 -v 0.054059 0.089145 0.098966 -vn -0.379617 0.238991 0.893741 -v 0.054154 0.089093 0.099032 -vn -0.469179 0.017224 0.882935 -v 0.054082 0.088916 0.099024 -vn -0.292888 -0.040465 0.955290 -v 0.054221 0.088870 0.099081 -vn -0.331961 -0.270628 0.903638 -v 0.054190 0.088686 0.099041 -vn -0.112851 -0.304294 0.945870 -v 0.054364 0.088659 0.099074 -vn -0.119677 -0.520886 0.845196 -v 0.054358 0.088485 0.098994 -vn 0.119674 -0.520888 0.845195 -v 0.054548 0.088485 0.098994 -vn -0.119674 -0.707711 0.696293 -v 0.054358 0.088335 0.098875 -vn -0.352070 -0.485185 0.800401 -v 0.054174 0.088514 0.098959 -vn -0.531793 -0.205269 0.821621 -v 0.054031 0.088737 0.098976 -vn -0.618212 0.099519 0.779686 -v 0.053964 0.088981 0.098943 -vn -0.591703 0.388206 0.706530 -v 0.053987 0.089210 0.098884 -vn -0.458217 0.619046 0.637823 -v 0.054095 0.089393 0.098830 -vn -0.248006 0.757584 0.603787 -v 0.054263 0.089501 0.098803 -vn 0.352072 0.671998 -0.651509 -v 0.054733 0.089432 0.097806 -vn 0.352060 0.485197 -0.800399 -v 0.054733 0.089283 0.097687 -vn 0.119674 0.520887 -0.845195 -v 0.054548 0.089311 0.097651 -vn 0.458225 0.619034 0.637830 -v 0.054811 0.089393 0.098830 -vn 0.648831 0.482089 0.588735 -v 0.054964 0.089284 0.098792 -vn 0.801927 0.317681 0.505956 -v 0.055087 0.089153 0.098726 -vn 0.908958 0.135294 0.394324 -v 0.055174 0.089007 0.098637 -vn 0.963989 -0.054690 0.260257 -v 0.055218 0.088855 0.098530 -vn 0.963991 -0.241497 0.111359 -v 0.055218 0.088706 0.098410 -vn 0.908959 -0.414564 -0.043931 -v 0.055174 0.088567 0.098286 -vn 0.248000 0.757587 0.603787 -v 0.054643 0.089501 0.098803 -vn 0.119672 -0.707710 0.696294 -v 0.054548 0.088335 0.098875 -vn 0.352070 -0.672005 0.651503 -v 0.054733 0.088364 0.098839 -vn -0.112839 -0.854167 0.507608 -v 0.054364 0.088219 0.098723 -vn -0.352075 -0.672007 0.651498 -v 0.054174 0.088364 0.098839 -vn -0.564005 -0.415871 0.713407 -v 0.054005 0.088569 0.098889 -vn -0.700732 -0.111989 0.704580 -v 0.053897 0.088811 0.098883 -vn -0.731325 0.201646 0.651538 -v 0.053874 0.089061 0.098841 -vn -0.648834 0.482082 0.588738 -v 0.053942 0.089284 0.098792 -vn -0.471922 0.689438 0.549514 -v 0.054084 0.089448 0.098761 -vn -0.240802 0.794555 0.557402 -v 0.054269 0.089529 0.098767 -vn 0.471930 0.689435 0.549510 -v 0.054822 0.089448 0.098761 -vn 0.668250 0.581755 0.463685 -v 0.054980 0.089363 0.098693 -vn 0.825925 0.440874 0.351393 -v 0.055106 0.089251 0.098604 -vn 0.936161 0.274931 0.219125 -v 0.055195 0.089118 0.098498 -vn 0.992841 0.093409 0.074447 -v 0.055241 0.088973 0.098382 -vn 0.992841 -0.093409 -0.074447 -v 0.055241 0.088823 0.098263 -vn 0.936161 -0.274929 -0.219126 -v 0.055195 0.088678 0.098147 -vn 0.825926 -0.440874 -0.351391 -v 0.055106 0.088545 0.098041 -vn 0.240805 0.794566 0.557384 -v 0.054638 0.089529 0.098767 -vn 0.331972 -0.820494 0.465386 -v 0.054716 0.088245 0.098690 -vn 0.531805 -0.755126 0.383365 -v 0.054875 0.088297 0.098625 -vn -0.099538 -0.951902 0.289784 -v 0.054374 0.088141 0.098549 -vn -0.331966 -0.820496 0.465387 -v 0.054190 0.088245 0.098690 -vn -0.563994 -0.602675 0.564530 -v 0.054005 0.088419 0.098770 -vn -0.743147 -0.316938 0.589308 -v 0.053863 0.088647 0.098791 -vn -0.828929 0.003774 0.559341 -v 0.053796 0.088903 0.098768 -vn -0.801925 0.317679 0.505961 -v 0.053819 0.089153 0.098726 -vn -0.668250 0.581753 0.463686 -v 0.053927 0.089363 0.098693 -vn -0.458205 0.759848 0.461172 -v 0.054095 0.089503 0.098692 -vn -0.219613 0.829390 0.513695 -v 0.054285 0.089556 0.098734 -vn -0.112836 0.304290 -0.945873 -v 0.054364 0.089137 0.097571 -vn -0.099555 0.070149 -0.992556 -v 0.054374 0.088950 0.097534 -vn -0.292880 0.040446 -0.955293 -v 0.054221 0.088926 0.097564 -vn 0.458201 0.759853 0.461168 -v 0.054811 0.089503 0.098692 -vn 0.648833 0.681435 0.338618 -v 0.054964 0.089441 0.098594 -vn 0.801929 0.564068 0.196817 -v 0.055087 0.089348 0.098481 -vn 0.908957 0.414571 0.043922 -v 0.055174 0.089229 0.098359 -vn 0.963991 0.241496 -0.111359 -v 0.055218 0.089090 0.098235 -vn 0.963990 0.054690 -0.260254 -v 0.055218 0.088941 0.098115 -vn 0.908959 -0.135300 -0.394318 -v 0.055174 0.088789 0.098008 -vn 0.801931 -0.317678 -0.505952 -v 0.055087 0.088643 0.097919 -vn 0.648836 -0.482079 -0.588737 -v 0.054964 0.088512 0.097854 -vn 0.219618 0.829390 0.513693 -v 0.054621 0.089556 0.098734 -vn 0.469189 -0.864523 0.180170 -v 0.054824 0.088210 0.098462 -vn 0.618208 -0.782241 0.076925 -v 0.054942 0.088275 0.098380 -vn -0.080541 -0.995228 0.055092 -v 0.054390 0.088108 0.098361 -vn -0.292874 -0.922203 0.252521 -v 0.054221 0.088165 0.098519 -vn -0.531801 -0.755127 0.383368 -v 0.054031 0.088297 0.098625 -vn -0.743147 -0.503757 0.440411 -v 0.053863 0.088497 0.098672 -vn -0.879113 -0.194166 0.435271 -v 0.053755 0.088745 0.098669 -vn -0.908956 0.135298 0.394327 -v 0.053732 0.089007 0.098637 -vn -0.825929 0.440872 0.351388 -v 0.053800 0.089251 0.098604 -vn -0.648830 0.681443 0.338607 -v 0.053942 0.089441 0.098594 -vn -0.417878 0.826137 0.377989 -v 0.054126 0.089555 0.098627 -vn -0.185651 0.860067 0.475204 -v 0.054311 0.089579 0.098705 -vn -0.236955 -0.192328 -0.952293 -v 0.054266 0.088740 0.097567 -vn -0.379626 -0.238984 -0.893740 -v 0.054154 0.088703 0.097613 -vn 0.417870 0.826143 0.377984 -v 0.054780 0.089555 0.098627 -vn 0.591690 0.775334 0.220818 -v 0.054919 0.089515 0.098502 -vn 0.731323 0.680105 0.051223 -v 0.055032 0.089440 0.098366 -vn 0.828928 0.546090 -0.121097 -v 0.055110 0.089333 0.098228 -vn 0.879117 0.380983 -0.286367 -v 0.055151 0.089201 0.098096 -vn 0.879114 0.194175 -0.435264 -v 0.055151 0.089051 0.097976 -vn 0.828926 -0.003771 -0.559346 -v 0.055110 0.088893 0.097877 -vn 0.731318 -0.201655 -0.651544 -v 0.055032 0.088735 0.097804 -vn 0.591704 -0.388198 -0.706533 -v 0.054919 0.088586 0.097761 -vn 0.417866 -0.552734 -0.721023 -v 0.054780 0.088455 0.097750 -vn 0.185648 0.860069 0.475202 -v 0.054595 0.089579 0.098705 -vn 0.500200 -0.857949 -0.117145 -v 0.054847 0.088216 0.098225 -vn 0.591700 -0.775324 -0.220827 -v 0.054919 0.088281 0.098143 -vn -0.056891 -0.981441 -0.183131 -v 0.054409 0.088120 0.098171 -vn -0.236958 -0.971200 0.024933 -v 0.054266 0.088126 0.098337 -vn -0.469185 -0.864526 0.180166 -v 0.054082 0.088210 0.098462 -vn -0.700721 -0.661857 0.266337 -v 0.053897 0.088371 0.098532 -vn -0.879117 -0.380983 0.286366 -v 0.053755 0.088595 0.098549 -vn -0.963990 -0.054686 0.260254 -v 0.053688 0.088855 0.098530 -vn -0.936160 0.274933 0.219127 -v 0.053711 0.089118 0.098498 -vn -0.801927 0.564070 0.196822 -v 0.053819 0.089348 0.098481 -vn -0.591697 0.775330 0.220813 -v 0.053987 0.089515 0.098502 -vn -0.353252 0.884495 0.304765 -v 0.054177 0.089600 0.098569 -vn -0.140815 0.884816 0.444153 -v 0.054345 0.089598 0.098681 -vn -0.268082 -0.447371 -0.853224 -v 0.054243 0.088538 0.097647 -vn -0.353243 -0.494385 -0.794231 -v 0.054177 0.088501 0.097693 -vn 0.417870 -0.826142 -0.377987 -v 0.054780 0.088241 0.098018 -vn 0.458206 -0.759850 -0.461168 -v 0.054811 0.088293 0.097953 -vn -0.029881 -0.911031 -0.411253 -v 0.054430 0.088178 0.097990 -vn -0.167351 -0.964472 -0.204420 -v 0.054322 0.088133 0.098154 -vn -0.379594 -0.924543 -0.033595 -v 0.054154 0.088163 0.098291 -vn -0.618209 -0.782240 0.076928 -v 0.053964 0.088275 0.098380 -vn -0.828925 -0.546092 0.121103 -v 0.053796 0.088463 0.098417 -vn -0.963991 -0.241497 0.111360 -v 0.053688 0.088706 0.098410 -vn -0.992841 0.093406 0.074448 -v 0.053665 0.088973 0.098382 -vn -0.908956 0.414572 0.043923 -v 0.053732 0.089229 0.098359 -vn -0.731319 0.680109 0.051228 -v 0.053874 0.089440 0.098366 -vn -0.500195 0.857951 0.117151 -v 0.054059 0.089580 0.098420 -vn -0.268071 0.931524 0.245767 -v 0.054243 0.089637 0.098523 -vn -0.087968 0.902109 0.422446 -v 0.054386 0.089612 0.098664 -vn 0.292883 0.922200 -0.252522 -v 0.054685 0.089632 0.098126 -vn 0.331974 0.820492 -0.465388 -v 0.054716 0.089551 0.097955 -vn 0.112834 0.854163 -0.507617 -v 0.054543 0.089578 0.097922 -vn 0.119672 0.707711 -0.696293 -v 0.054548 0.089461 0.097770 -vn -0.119675 0.707712 -0.696292 -v 0.054358 0.089461 0.097770 -vn -0.119672 0.520890 -0.845194 -v 0.054358 0.089311 0.097651 -vn -0.352063 0.485193 -0.800400 -v 0.054174 0.089283 0.097687 -vn -0.331959 0.270624 -0.903640 -v 0.054190 0.089111 0.097604 -vn -0.531800 0.205260 -0.821618 -v 0.054031 0.089059 0.097669 -vn -0.469182 -0.017229 -0.882933 -v 0.054082 0.088880 0.097621 -vn -0.618211 -0.099518 -0.779687 -v 0.053964 0.088815 0.097703 -vn -0.500200 -0.305564 -0.810204 -v 0.054059 0.088651 0.097679 -vn -0.591698 -0.388192 -0.706541 -v 0.053987 0.088586 0.097761 -vn -0.417869 -0.552739 -0.721017 -v 0.054126 0.088455 0.097750 -vn -0.458217 -0.619066 -0.637805 -v 0.054095 0.088403 0.097815 -vn -0.240813 -0.720604 -0.650184 -v 0.054269 0.088324 0.097806 -vn -0.248013 -0.757557 -0.603819 -v 0.054263 0.088295 0.097842 -vn -0.140852 -0.630344 -0.763431 -v 0.054345 0.088393 0.097720 -vn -0.167332 -0.414421 -0.894570 -v 0.054322 0.088563 0.097615 -vn -0.087943 -0.613029 -0.785151 -v 0.054386 0.088406 0.097703 -vn -0.080543 -0.168301 -0.982440 -v 0.054390 0.088759 0.097543 -vn -0.056905 -0.397448 -0.915859 -v 0.054409 0.088577 0.097598 -vn -0.041782 -0.591347 -0.805334 -v 0.054430 0.088413 0.097695 -vn 0.041783 -0.591350 -0.805332 -v 0.054476 0.088413 0.097695 -vn 0.056900 -0.397453 -0.915857 -v 0.054498 0.088577 0.097598 -vn 0.080545 -0.168295 -0.982441 -v 0.054517 0.088759 0.097543 -vn 0.099553 0.070144 -0.992557 -v 0.054532 0.088950 0.097534 -vn 0.112834 0.304296 -0.945871 -v 0.054543 0.089137 0.097571 -vn 0.331957 0.270632 -0.903639 -v 0.054716 0.089111 0.097604 -vn 0.292884 0.040435 -0.955293 -v 0.054685 0.088926 0.097564 -vn 0.236961 -0.192326 -0.952292 -v 0.054640 0.088740 0.097567 -vn 0.167343 -0.414424 -0.894566 -v 0.054584 0.088563 0.097615 -vn 0.087947 -0.613031 -0.785149 -v 0.054520 0.088406 0.097703 -vn 0.353265 0.884484 0.304781 -v 0.054729 0.089600 0.098569 -vn 0.379617 0.924533 0.033607 -v 0.054752 0.089633 0.098354 -vn 0.500201 0.857949 0.117143 -v 0.054847 0.089580 0.098420 -vn 0.469191 0.864524 -0.180164 -v 0.054824 0.089586 0.098183 -vn 0.618200 0.782248 -0.076919 -v 0.054942 0.089521 0.098265 -vn 0.531804 0.755126 -0.383366 -v 0.054875 0.089499 0.098020 -vn 0.700724 0.661854 -0.266337 -v 0.055009 0.089425 0.098113 -vn 0.563994 0.602685 -0.564519 -v 0.054901 0.089377 0.097875 -vn 0.743147 0.503760 -0.440406 -v 0.055043 0.089299 0.097973 -vn 0.563999 0.415870 -0.713413 -v 0.054901 0.089227 0.097756 -vn 0.743156 0.316933 -0.589298 -v 0.055043 0.089149 0.097854 -vn 0.531808 0.205251 -0.821616 -v 0.054875 0.089059 0.097669 -vn 0.700723 0.111987 -0.704589 -v 0.055009 0.088985 0.097762 -vn 0.469185 -0.017228 -0.882932 -v 0.054824 0.088880 0.097621 -vn 0.618209 -0.099505 -0.779690 -v 0.054942 0.088815 0.097703 -vn 0.379614 -0.238981 -0.893746 -v 0.054752 0.088703 0.097613 -vn 0.500201 -0.305569 -0.810201 -v 0.054847 0.088651 0.097679 -vn 0.268073 -0.447366 -0.853230 -v 0.054663 0.088538 0.097647 -vn 0.353249 -0.494390 -0.794226 -v 0.054729 0.088501 0.097693 -vn 0.140857 -0.630342 -0.763432 -v 0.054561 0.088393 0.097720 -vn 0.185631 -0.655055 -0.732424 -v 0.054595 0.088374 0.097744 -vn 0.219598 -0.685748 -0.693921 -v 0.054621 0.088350 0.097773 -vn 0.240810 -0.720602 -0.650187 -v 0.054638 0.088324 0.097806 -vn 0.458216 -0.619062 -0.637809 -v 0.054811 0.088403 0.097815 -vn 0.471929 -0.689451 -0.549491 -v 0.054822 0.088348 0.097884 -vn 0.668252 -0.581764 -0.463671 -v 0.054980 0.088433 0.097952 -vn 0.648832 -0.681435 -0.338620 -v 0.054964 0.088355 0.098051 -vn 0.801928 -0.564068 -0.196823 -v 0.055087 0.088448 0.098164 -vn 0.731317 -0.680111 -0.051233 -v 0.055032 0.088356 0.098279 -vn 0.828925 -0.546094 0.121096 -v 0.055110 0.088463 0.098417 -vn 0.700717 -0.661860 0.266340 -v 0.055009 0.088371 0.098532 -vn 0.743144 -0.503759 0.440413 -v 0.055043 0.088497 0.098672 -vn 0.563998 -0.602676 0.564524 -v 0.054901 0.088419 0.098770 -vn 0.563997 -0.415869 0.713414 -v 0.054901 0.088569 0.098889 -vn 0.352073 -0.485182 0.800402 -v 0.054733 0.088514 0.098959 -vn 0.331964 -0.270638 0.903634 -v 0.054716 0.088686 0.099041 -vn 0.112848 -0.304290 0.945871 -v 0.054543 0.088659 0.099074 -vn 0.099558 -0.070147 0.992556 -v 0.054532 0.088846 0.099111 -vn -0.099553 -0.070147 0.992557 -v 0.054374 0.088846 0.099111 -vn -0.080540 0.168296 0.982441 -v 0.054390 0.089037 0.099102 -vn -0.236954 0.192335 0.952292 -v 0.054266 0.089056 0.099078 -vn -0.167364 0.414423 0.894563 -v 0.054322 0.089233 0.099031 -vn -0.268079 0.447369 0.853226 -v 0.054243 0.089259 0.098998 -vn -0.140855 0.630347 0.763428 -v 0.054345 0.089403 0.098925 -vn -0.185627 0.655059 0.732421 -v 0.054311 0.089422 0.098902 -vn 0.219609 -0.829415 -0.513657 -v 0.054621 0.088240 0.097911 -vn 0.353254 -0.884487 -0.304787 -v 0.054729 0.088196 0.098076 -vn 0.185655 -0.860071 -0.475195 -v 0.054595 0.088217 0.097941 -vn 0.379597 -0.924542 -0.033599 -v 0.054752 0.088163 0.098291 -vn 0.268063 -0.931526 -0.245766 -v 0.054663 0.088159 0.098122 -vn 0.140912 -0.884785 -0.444183 -v 0.054561 0.088198 0.097964 -vn 0.292878 -0.922202 0.252521 -v 0.054685 0.088165 0.098519 -vn 0.236939 -0.971205 0.024929 -v 0.054640 0.088126 0.098337 -vn 0.167351 -0.964473 -0.204417 -v 0.054584 0.088133 0.098154 -vn 0.087959 -0.902105 -0.422456 -v 0.054520 0.088184 0.097981 -vn 0.112832 -0.854166 0.507612 -v 0.054543 0.088219 0.098723 -vn 0.099536 -0.951905 0.289776 -v 0.054532 0.088141 0.098549 -vn 0.080550 -0.995227 0.055094 -v 0.054517 0.088108 0.098361 -vn 0.056895 -0.981442 -0.183126 -v 0.054498 0.088120 0.098171 -vn 0.029879 -0.911030 -0.411257 -v 0.054476 0.088178 0.097990 -vn -0.087948 -0.902108 -0.422453 -v 0.054386 0.088184 0.097981 -vn -0.268074 -0.931524 -0.245764 -v 0.054243 0.088159 0.098122 -vn -0.500190 -0.857955 -0.117149 -v 0.054059 0.088216 0.098225 -vn -0.731320 -0.680107 -0.051244 -v 0.053874 0.088356 0.098279 -vn -0.908957 -0.414568 -0.043938 -v 0.053732 0.088567 0.098286 -vn -0.992841 -0.093406 -0.074448 -v 0.053665 0.088823 0.098263 -vn -0.963990 0.241499 -0.111359 -v 0.053688 0.089090 0.098235 -vn -0.828928 0.546088 -0.121103 -v 0.053796 0.089333 0.098228 -vn -0.618211 0.782240 -0.076917 -v 0.053964 0.089521 0.098265 -vn -0.379607 0.924537 0.033611 -v 0.054154 0.089633 0.098354 -vn -0.167352 0.964469 0.204433 -v 0.054322 0.089663 0.098491 -vn -0.140911 -0.884782 -0.444191 -v 0.054345 0.088198 0.097964 -vn -0.353247 -0.884492 -0.304778 -v 0.054177 0.088196 0.098076 -vn -0.591704 -0.775320 -0.220831 -v 0.053987 0.088281 0.098143 -vn -0.801927 -0.564069 -0.196824 -v 0.053819 0.088448 0.098164 -vn -0.936160 -0.274932 -0.219128 -v 0.053711 0.088678 0.098147 -vn -0.963990 0.054686 -0.260254 -v 0.053688 0.088941 0.098115 -vn -0.879117 0.380987 -0.286361 -v 0.053755 0.089201 0.098096 -vn -0.700726 0.661855 -0.266328 -v 0.053897 0.089425 0.098113 -vn -0.469185 0.864526 -0.180166 -v 0.054082 0.089586 0.098183 -vn -0.236957 0.971200 -0.024941 -v 0.054266 0.089670 0.098308 -vn -0.056892 0.981441 0.183131 -v 0.054409 0.089676 0.098474 -vn 0.087948 0.902114 0.422440 -v 0.054520 0.089612 0.098664 -vn 0.056901 0.981440 0.183136 -v 0.054498 0.089676 0.098474 -vn -0.080541 0.995228 -0.055088 -v 0.054390 0.089689 0.098284 -vn -0.292879 0.922202 -0.252519 -v 0.054221 0.089632 0.098126 -vn -0.531801 0.755127 -0.383368 -v 0.054031 0.089499 0.098020 -vn -0.743147 0.503757 -0.440411 -v 0.053863 0.089299 0.097973 -vn -0.879115 0.194171 -0.435264 -v 0.053755 0.089051 0.097976 -vn -0.908959 -0.135300 -0.394320 -v 0.053732 0.088789 0.098008 -vn -0.825929 -0.440872 -0.351388 -v 0.053800 0.088545 0.098041 -vn -0.648830 -0.681443 -0.338607 -v 0.053942 0.088355 0.098051 -vn -0.417878 -0.826137 -0.377989 -v 0.054126 0.088241 0.098018 -vn -0.185658 -0.860069 -0.475197 -v 0.054311 0.088217 0.097941 -vn -0.668253 -0.581758 -0.463675 -v 0.053927 0.088433 0.097952 -vn -0.458209 -0.759848 -0.461167 -v 0.054095 0.088293 0.097953 -vn -0.219613 -0.829412 -0.513660 -v 0.054285 0.088240 0.097911 -vn 0.236942 0.971204 -0.024935 -v 0.054640 0.089670 0.098308 -vn 0.080547 0.995227 -0.055089 -v 0.054517 0.089689 0.098284 -vn 0.099541 0.951902 -0.289784 -v 0.054532 0.089655 0.098096 -vn -0.099542 0.951900 -0.289788 -v 0.054374 0.089655 0.098096 -vn -0.112841 0.854163 -0.507615 -v 0.054364 0.089578 0.097922 -vn -0.331967 0.820493 -0.465391 -v 0.054190 0.089551 0.097955 -vn -0.352070 0.672004 -0.651504 -v 0.054174 0.089432 0.097806 -vn -0.563997 0.602681 -0.564521 -v 0.054005 0.089377 0.097875 -vn -0.564003 0.415868 -0.713410 -v 0.054005 0.089227 0.097756 -vn -0.743152 0.316940 -0.589300 -v 0.053863 0.089149 0.097854 -vn -0.700726 0.111987 -0.704586 -v 0.053897 0.088985 0.097762 -vn -0.828926 -0.003773 -0.559345 -v 0.053796 0.088893 0.097877 -vn -0.731319 -0.201653 -0.651544 -v 0.053874 0.088735 0.097804 -vn -0.801931 -0.317680 -0.505950 -v 0.053819 0.088643 0.097919 -vn -0.648835 -0.482082 -0.588736 -v 0.053942 0.088512 0.097854 -vn -0.471929 -0.689449 -0.549494 -v 0.054084 0.088348 0.097884 -vn -0.240800 -0.794556 -0.557401 -v 0.054269 0.088267 0.097878 -vn 0.248013 -0.944401 0.215863 -v 0.054643 0.090659 0.099067 -vn 0.240802 -0.931175 0.273729 -v 0.054638 0.090669 0.099111 -vn 0.000001 -0.973960 0.226722 -v 0.054453 0.090637 0.099072 -vn -0.219622 -0.970085 0.103450 -v 0.054285 0.090640 0.098981 -vn -0.185677 -0.981041 0.055516 -v 0.054311 0.090631 0.098944 -vn -0.056870 0.963852 0.260298 -v 0.054409 0.092178 0.099096 -vn -0.029908 0.999260 0.024190 -v 0.054430 0.092204 0.098907 -vn -0.087991 0.996069 0.010233 -v 0.054386 0.092202 0.098897 -vn 0.000001 0.975759 -0.218846 -v 0.054453 0.092185 0.098718 -vn 0.029905 0.999260 0.024186 -v 0.054476 0.092204 0.098907 -vn 0.041772 0.881942 -0.469503 -v 0.054476 0.092120 0.098540 -vn -0.041774 0.881941 -0.469505 -v 0.054430 0.092120 0.098540 -vn 0.140933 0.898939 -0.414786 -v 0.054561 0.092128 0.098571 -vn 0.268083 0.772956 -0.575040 -v 0.054663 0.092029 0.098443 -vn 0.167326 0.761165 -0.626602 -v 0.054584 0.092019 0.098402 -vn 0.056872 0.963851 0.260303 -v 0.054498 0.092178 0.099096 -vn 0.080551 0.873037 0.480955 -v 0.054517 0.092107 0.099272 -vn 0.087985 0.996069 0.010220 -v 0.054520 0.092202 0.098897 -vn 0.167330 0.957788 0.233756 -v 0.054584 0.092173 0.099075 -vn 0.236964 0.864444 0.443379 -v 0.054640 0.092100 0.099243 -vn 0.292893 0.721662 0.627230 -v 0.054685 0.091987 0.099390 -vn 0.140897 0.989881 -0.016865 -v 0.054561 0.092197 0.098876 -vn 0.268082 0.946010 0.182203 -v 0.054663 0.092164 0.099035 -vn 0.379607 0.847762 0.370402 -v 0.054752 0.092087 0.099185 -vn 0.469177 0.701044 0.537039 -v 0.054824 0.091970 0.099319 -vn 0.531807 0.514390 0.672744 -v 0.054875 0.091821 0.099428 -vn 0.185614 0.981056 -0.055464 -v 0.054595 0.092190 0.098846 -vn 0.353240 0.929202 0.108654 -v 0.054729 0.092151 0.098977 -vn 0.500189 0.823964 0.266259 -v 0.054847 0.092068 0.099103 -vn 0.618206 0.671629 0.408333 -v 0.054942 0.091947 0.099217 -vn 0.700722 0.481043 0.526865 -v 0.055009 0.091795 0.099313 -vn 0.743148 0.263128 0.615219 -v 0.055043 0.091621 0.099384 -vn 0.219590 0.970090 -0.103465 -v 0.054621 0.092182 0.098810 -vn 0.417862 0.908344 0.017383 -v 0.054780 0.092134 0.098906 -vn 0.591703 0.794430 0.137001 -v 0.054919 0.092045 0.099001 -vn 0.731322 0.635123 0.248571 -v 0.055032 0.091918 0.099091 -vn 0.828926 0.439664 0.345799 -v 0.055110 0.091762 0.099169 -vn 0.879114 0.219242 0.423192 -v 0.055151 0.091586 0.099231 -vn 0.879114 -0.013642 0.476416 -v 0.055151 0.091399 0.099274 -vn 0.240811 0.957625 -0.158001 -v 0.054638 0.092173 0.098768 -vn -0.240815 0.957623 -0.158007 -v 0.054269 0.092173 0.098768 -vn -0.219599 0.970087 -0.103477 -v 0.054285 0.092182 0.098810 -vn -0.417866 0.908342 0.017385 -v 0.054126 0.092134 0.098906 -vn -0.353243 0.929200 0.108664 -v 0.054177 0.092151 0.098977 -vn -0.500183 0.823968 0.266259 -v 0.054059 0.092068 0.099103 -vn -0.379613 0.847761 0.370398 -v 0.054154 0.092087 0.099185 -vn -0.469171 0.701048 0.537038 -v 0.054082 0.091970 0.099319 -vn -0.292891 0.721656 0.627238 -v 0.054221 0.091987 0.099390 -vn -0.331968 0.537761 0.774991 -v 0.054190 0.091840 0.099509 -vn -0.112846 0.549789 0.827646 -v 0.054364 0.091850 0.099551 -vn -0.119674 0.336021 0.934221 -v 0.054358 0.091678 0.099637 -vn 0.119675 0.336021 0.934220 -v 0.054548 0.091678 0.099637 -vn -0.119674 0.103141 0.987441 -v 0.054358 0.091492 0.099679 -vn -0.352077 0.323255 0.878378 -v 0.054174 0.091668 0.099592 -vn -0.531801 0.514386 0.672751 -v 0.054031 0.091821 0.099428 -vn -0.618211 0.671631 0.408322 -v 0.053964 0.091947 0.099217 -vn -0.591697 0.794433 0.137007 -v 0.053987 0.092045 0.099001 -vn -0.458210 0.884641 -0.086336 -v 0.054095 0.092116 0.098825 -vn -0.248015 0.944418 -0.215787 -v 0.054263 0.092162 0.098724 -vn 0.352064 -0.090383 -0.931602 -v 0.054733 0.091340 0.098156 -vn 0.352074 -0.323268 -0.878375 -v 0.054733 0.091153 0.098198 -vn 0.119674 -0.336026 -0.934219 -v 0.054548 0.091143 0.098154 -vn 0.458213 0.884641 -0.086325 -v 0.054811 0.092116 0.098825 -vn 0.648836 0.760865 -0.009841 -v 0.054964 0.092018 0.098886 -vn 0.801929 0.593641 0.067081 -v 0.055087 0.091885 0.098947 -vn 0.908957 0.392652 0.140076 -v 0.055174 0.091725 0.099006 -vn 0.963991 0.169378 0.205021 -v 0.055218 0.091546 0.099058 -vn 0.963990 -0.063505 0.258243 -v 0.055218 0.091360 0.099101 -vn 0.908957 -0.292821 0.296736 -v 0.055174 0.091176 0.099131 -vn 0.248021 0.944414 -0.215794 -v 0.054643 0.092162 0.098724 -vn 0.119678 0.103137 0.987441 -v 0.054548 0.091492 0.099679 -vn 0.352058 0.090368 0.931606 -v 0.054733 0.091482 0.099635 -vn -0.112855 -0.135680 0.984304 -v 0.054364 0.091301 0.099677 -vn -0.352073 0.090370 0.931600 -v 0.054174 0.091482 0.099635 -vn -0.564003 0.298484 0.769940 -v 0.054005 0.091649 0.099506 -vn -0.700727 0.481039 0.526862 -v 0.053897 0.091795 0.099313 -vn -0.731327 0.635117 0.248570 -v 0.053874 0.091918 0.099091 -vn -0.648837 0.760864 -0.009840 -v 0.053942 0.092018 0.098886 -vn -0.471923 0.859483 -0.196413 -v 0.054084 0.092096 0.098739 -vn -0.240802 0.931204 -0.273631 -v 0.054269 0.092152 0.098679 -vn 0.471927 0.859478 -0.196422 -v 0.054822 0.092096 0.098739 -vn 0.668250 0.725237 -0.165748 -v 0.054980 0.091990 0.098763 -vn 0.825927 0.549607 -0.125604 -v 0.055106 0.091851 0.098795 -vn 0.936159 0.342740 -0.078332 -v 0.055195 0.091685 0.098833 -vn 0.992841 0.116441 -0.026609 -v 0.055241 0.091504 0.098874 -vn 0.992840 -0.116447 0.026610 -v 0.055241 0.091318 0.098917 -vn 0.936161 -0.342735 0.078333 -v 0.055195 0.091136 0.098958 -vn 0.825923 -0.549611 0.125614 -v 0.055106 0.090971 0.098996 -vn 0.240815 0.931197 -0.273642 -v 0.054638 0.092152 0.098679 -vn 0.331970 -0.147712 0.931653 -v 0.054716 0.091291 0.099635 -vn 0.531795 -0.171087 0.829412 -v 0.054875 0.091272 0.099554 -vn -0.099557 -0.366934 0.924904 -v 0.054374 0.091116 0.099628 -vn -0.331971 -0.147715 0.931652 -v 0.054190 0.091291 0.099635 -vn -0.563992 0.065609 0.823170 -v 0.054005 0.091462 0.099549 -vn -0.743149 0.263128 0.615219 -v 0.053863 0.091621 0.099384 -vn -0.828924 0.439670 0.345798 -v 0.053796 0.091762 0.099169 -vn -0.801929 0.593641 0.067084 -v 0.053819 0.091885 0.098947 -vn -0.668255 0.725234 -0.165743 -v 0.053927 0.091990 0.098763 -vn -0.458213 0.834315 -0.306529 -v 0.054095 0.092077 0.098653 -vn -0.219574 0.918714 -0.328255 -v 0.054285 0.092143 0.098637 -vn -0.112842 -0.549794 -0.827643 -v 0.054364 0.090972 0.098240 -vn -0.099557 -0.732270 -0.673698 -v 0.054374 0.090827 0.098363 -vn -0.292874 -0.721659 -0.627242 -v 0.054221 0.090835 0.098400 -vn 0.458211 0.834317 -0.306526 -v 0.054811 0.092077 0.098653 -vn 0.648835 0.689608 -0.321642 -v 0.054964 0.091962 0.098640 -vn 0.801930 0.505572 -0.318285 -v 0.055087 0.091816 0.098642 -vn 0.908957 0.292824 -0.296734 -v 0.055174 0.091646 0.098659 -vn 0.963991 0.063506 -0.258242 -v 0.055218 0.091462 0.098690 -vn 0.963990 -0.169377 -0.205024 -v 0.055218 0.091276 0.098733 -vn 0.908958 -0.392648 -0.140080 -v 0.055174 0.091097 0.098785 -vn 0.801926 -0.593644 -0.067092 -v 0.055087 0.090936 0.098843 -vn 0.648826 -0.760873 0.009848 -v 0.054964 0.090803 0.098905 -vn 0.219571 0.918718 -0.328246 -v 0.054621 0.092143 0.098637 -vn 0.469182 -0.398172 0.788243 -v 0.054824 0.091091 0.099520 -vn 0.618214 -0.427581 0.659535 -v 0.054942 0.091068 0.099418 -vn -0.080558 -0.577452 0.812440 -v 0.054390 0.090948 0.099537 -vn -0.292879 -0.377554 0.878450 -v 0.054221 0.091107 0.099591 -vn -0.531792 -0.171078 0.829415 -v 0.054031 0.091272 0.099554 -vn -0.743150 0.030246 0.668441 -v 0.053863 0.091434 0.099426 -vn -0.879113 0.219242 0.423194 -v 0.053755 0.091586 0.099231 -vn -0.908956 0.392656 0.140074 -v 0.053732 0.091725 0.099006 -vn -0.825928 0.549606 -0.125606 -v 0.053800 0.091851 0.098795 -vn -0.648836 0.689600 -0.321656 -v 0.053942 0.091962 0.098640 -vn -0.417863 0.810601 -0.410264 -v 0.054126 0.092058 0.098572 -vn -0.185640 0.907756 -0.376188 -v 0.054311 0.092134 0.098601 -vn -0.236961 -0.864448 -0.443373 -v 0.054266 0.090722 0.098548 -vn -0.379588 -0.847776 -0.370391 -v 0.054154 0.090735 0.098605 -vn 0.417857 0.810606 -0.410261 -v 0.054780 0.092058 0.098572 -vn 0.591698 0.656054 -0.468495 -v 0.054919 0.091936 0.098524 -vn 0.731320 0.464099 -0.499784 -v 0.055032 0.091783 0.098499 -vn 0.828928 0.245807 -0.502451 -v 0.055110 0.091608 0.098496 -vn 0.879114 0.013642 -0.476416 -v 0.055151 0.091423 0.098517 -vn 0.879114 -0.219242 -0.423192 -v 0.055151 0.091236 0.098560 -vn 0.828926 -0.439664 -0.345799 -v 0.055110 0.091059 0.098622 -vn 0.731323 -0.635116 -0.248582 -v 0.055032 0.090903 0.098700 -vn 0.591706 -0.794429 -0.136991 -v 0.054919 0.090777 0.098789 -vn 0.417870 -0.908341 -0.017381 -v 0.054780 0.090687 0.098885 -vn 0.185624 0.907760 -0.376186 -v 0.054595 0.092134 0.098601 -vn 0.500187 -0.626509 0.597745 -v 0.054847 0.090909 0.099368 -vn 0.591713 -0.656052 0.468478 -v 0.054919 0.090886 0.099266 -vn -0.056888 -0.755102 0.653135 -v 0.054409 0.090807 0.099409 -vn -0.236974 -0.586042 0.774854 -v 0.054266 0.090941 0.099508 -vn -0.469182 -0.398180 0.788239 -v 0.054082 0.091091 0.099520 -vn -0.700727 -0.204429 0.683513 -v 0.053897 0.091246 0.099438 -vn -0.879114 -0.013642 0.476417 -v 0.053755 0.091399 0.099274 -vn -0.963991 0.169379 0.205018 -v 0.053688 0.091546 0.099058 -vn -0.936159 0.342740 -0.078332 -v 0.053711 0.091685 0.098833 -vn -0.801926 0.505578 -0.318285 -v 0.053819 0.091816 0.098642 -vn -0.591697 0.656054 -0.468495 -v 0.053987 0.091936 0.098524 -vn -0.353265 0.789763 -0.501476 -v 0.054177 0.092042 0.098500 -vn -0.140939 0.898945 -0.414770 -v 0.054345 0.092128 0.098571 -vn -0.268082 -0.946009 -0.182208 -v 0.054243 0.090658 0.098756 -vn -0.353241 -0.929201 -0.108655 -v 0.054177 0.090671 0.098813 -vn 0.417857 -0.810622 0.410229 -v 0.054780 0.090764 0.099219 -vn 0.458217 -0.834311 0.306532 -v 0.054811 0.090745 0.099138 -vn -0.029901 -0.889549 0.455861 -v 0.054430 0.090701 0.099251 -vn -0.167354 -0.761170 0.626589 -v 0.054322 0.090802 0.099388 -vn -0.379602 -0.602716 0.701880 -v 0.054154 0.090928 0.099450 -vn -0.618215 -0.427585 0.659531 -v 0.053964 0.091068 0.099418 -vn -0.828927 -0.245807 0.502453 -v 0.053796 0.091213 0.099294 -vn -0.963990 -0.063505 0.258244 -v 0.053688 0.091360 0.099101 -vn -0.992841 0.116443 -0.026608 -v 0.053665 0.091504 0.098874 -vn -0.908957 0.292828 -0.296732 -v 0.053732 0.091646 0.098659 -vn -0.731319 0.464104 -0.499781 -v 0.053874 0.091783 0.098499 -vn -0.500196 0.626517 -0.597729 -v 0.054059 0.091912 0.098423 -vn -0.268081 0.772948 -0.575051 -v 0.054243 0.092029 0.098443 -vn -0.087964 0.892749 -0.441884 -v 0.054386 0.092123 0.098550 -vn 0.292887 0.377562 -0.878444 -v 0.054685 0.091714 0.098199 -vn 0.331969 0.147716 -0.931653 -v 0.054716 0.091531 0.098156 -vn 0.112839 0.135677 -0.984306 -v 0.054543 0.091521 0.098114 -vn 0.119671 -0.103136 -0.987442 -v 0.054548 0.091330 0.098111 -vn -0.119673 -0.103136 -0.987442 -v 0.054358 0.091330 0.098111 -vn -0.119674 -0.336025 -0.934219 -v 0.054358 0.091143 0.098154 -vn -0.352080 -0.323261 -0.878375 -v 0.054174 0.091153 0.098198 -vn -0.331969 -0.537758 -0.774992 -v 0.054190 0.090982 0.098281 -vn -0.531807 -0.514380 -0.672751 -v 0.054031 0.091000 0.098362 -vn -0.469186 -0.701036 -0.537041 -v 0.054082 0.090851 0.098472 -vn -0.618227 -0.671617 -0.408320 -v 0.053964 0.090875 0.098573 -vn -0.500193 -0.823967 -0.266243 -v 0.054059 0.090754 0.098687 -vn -0.591709 -0.794425 -0.137000 -v 0.053987 0.090777 0.098789 -vn -0.417867 -0.908342 -0.017385 -v 0.054126 0.090687 0.098885 -vn -0.458215 -0.884642 0.086300 -v 0.054095 0.090706 0.098966 -vn -0.240803 -0.957637 0.157943 -v 0.054269 0.090649 0.099023 -vn -0.248020 -0.944401 0.215855 -v 0.054263 0.090659 0.099067 -vn -0.140836 -0.989890 0.016813 -v 0.054345 0.090624 0.098915 -vn -0.167363 -0.957785 -0.233745 -v 0.054322 0.090649 0.098716 -vn -0.087925 -0.996074 -0.010269 -v 0.054386 0.090620 0.098894 -vn -0.080571 -0.873031 -0.480962 -v 0.054390 0.090715 0.098518 -vn -0.056905 -0.963855 -0.260280 -v 0.054409 0.090644 0.098695 -vn -0.041774 -0.998334 -0.039791 -v 0.054430 0.090617 0.098883 -vn 0.041778 -0.998334 -0.039792 -v 0.054476 0.090617 0.098883 -vn 0.056908 -0.963855 -0.260278 -v 0.054498 0.090644 0.098695 -vn 0.080565 -0.873034 -0.480958 -v 0.054517 0.090715 0.098518 -vn 0.099554 -0.732266 -0.673703 -v 0.054532 0.090827 0.098363 -vn 0.112841 -0.549793 -0.827644 -v 0.054543 0.090972 0.098240 -vn 0.331971 -0.537752 -0.774995 -v 0.054716 0.090982 0.098281 -vn 0.292884 -0.721659 -0.627237 -v 0.054685 0.090835 0.098400 -vn 0.236969 -0.864447 -0.443371 -v 0.054640 0.090722 0.098548 -vn 0.167357 -0.957788 -0.233737 -v 0.054584 0.090649 0.098716 -vn 0.087933 -0.996073 -0.010274 -v 0.054520 0.090620 0.098894 -vn 0.353268 0.789756 -0.501485 -v 0.054729 0.092042 0.098500 -vn 0.379621 0.602709 -0.701875 -v 0.054752 0.091894 0.098341 -vn 0.500192 0.626513 -0.597737 -v 0.054847 0.091912 0.098423 -vn 0.469180 0.398176 -0.788242 -v 0.054824 0.091731 0.098271 -vn 0.618203 0.427591 -0.659538 -v 0.054942 0.091754 0.098372 -vn 0.531805 0.171087 -0.829405 -v 0.054875 0.091549 0.098237 -vn 0.700725 0.204427 -0.683516 -v 0.055009 0.091576 0.098353 -vn 0.564002 -0.065604 -0.823164 -v 0.054901 0.091360 0.098242 -vn 0.743148 -0.030245 -0.668443 -v 0.055043 0.091388 0.098364 -vn 0.564010 -0.298487 -0.769934 -v 0.054901 0.091173 0.098284 -vn 0.743148 -0.263128 -0.615219 -v 0.055043 0.091201 0.098407 -vn 0.531809 -0.514380 -0.672750 -v 0.054875 0.091000 0.098362 -vn 0.700724 -0.481039 -0.526865 -v 0.055009 0.091027 0.098478 -vn 0.469185 -0.701041 -0.537036 -v 0.054824 0.090851 0.098472 -vn 0.618220 -0.671618 -0.408330 -v 0.054942 0.090875 0.098573 -vn 0.379589 -0.847769 -0.370405 -v 0.054752 0.090735 0.098605 -vn 0.500195 -0.823965 -0.266245 -v 0.054847 0.090754 0.098687 -vn 0.268074 -0.946013 -0.182199 -v 0.054663 0.090658 0.098756 -vn 0.353246 -0.929200 -0.108653 -v 0.054729 0.090671 0.098813 -vn 0.140841 -0.989890 0.016803 -v 0.054561 0.090624 0.098915 -vn 0.185662 -0.981045 0.055509 -v 0.054595 0.090631 0.098944 -vn 0.219625 -0.970083 0.103461 -v 0.054621 0.090640 0.098981 -vn 0.240801 -0.957641 0.157917 -v 0.054638 0.090649 0.099023 -vn 0.458221 -0.884640 0.086287 -v 0.054811 0.090706 0.098966 -vn 0.471936 -0.859475 0.196415 -v 0.054822 0.090725 0.099052 -vn 0.668250 -0.725237 0.165748 -v 0.054980 0.090831 0.099028 -vn 0.648845 -0.689603 0.321632 -v 0.054964 0.090860 0.099151 -vn 0.801927 -0.505571 0.318294 -v 0.055087 0.091006 0.099148 -vn 0.731324 -0.464093 0.499783 -v 0.055032 0.091039 0.099292 -vn 0.828928 -0.245807 0.502451 -v 0.055110 0.091213 0.099294 -vn 0.700725 -0.204427 0.683516 -v 0.055009 0.091246 0.099438 -vn 0.743148 0.030245 0.668443 -v 0.055043 0.091434 0.099426 -vn 0.564000 0.065606 0.823164 -v 0.054901 0.091462 0.099549 -vn 0.564007 0.298487 0.769936 -v 0.054901 0.091649 0.099506 -vn 0.352069 0.323259 0.878380 -v 0.054733 0.091668 0.099592 -vn 0.331971 0.537754 0.774994 -v 0.054716 0.091840 0.099509 -vn 0.112841 0.549785 0.827649 -v 0.054543 0.091850 0.099551 -vn 0.099565 0.732280 0.673687 -v 0.054532 0.091995 0.099427 -vn -0.099566 0.732275 0.673691 -v 0.054374 0.091995 0.099427 -vn -0.080543 0.873039 0.480953 -v 0.054390 0.092107 0.099272 -vn -0.236969 0.864443 0.443377 -v 0.054266 0.092100 0.099243 -vn -0.167329 0.957791 0.233746 -v 0.054322 0.092173 0.099075 -vn -0.268084 0.946009 0.182201 -v 0.054243 0.092164 0.099035 -vn -0.140888 0.989882 -0.016855 -v 0.054345 0.092197 0.098876 -vn -0.185610 0.981057 -0.055471 -v 0.054311 0.092190 0.098846 -vn 0.219611 -0.918726 0.328198 -v 0.054621 0.090679 0.099153 -vn 0.353229 -0.789760 0.501507 -v 0.054729 0.090780 0.099291 -vn 0.185694 -0.907771 0.376124 -v 0.054595 0.090687 0.099190 -vn 0.379597 -0.602718 0.701881 -v 0.054752 0.090928 0.099450 -vn 0.268087 -0.772943 0.575055 -v 0.054663 0.090793 0.099348 -vn 0.140892 -0.898931 0.414817 -v 0.054561 0.090694 0.099220 -vn 0.292886 -0.377556 0.878447 -v 0.054685 0.091107 0.099591 -vn 0.236967 -0.586041 0.774856 -v 0.054640 0.090941 0.099508 -vn 0.167353 -0.761168 0.626591 -v 0.054584 0.090802 0.099388 -vn 0.087913 -0.892736 0.441920 -v 0.054520 0.090699 0.099240 -vn 0.112854 -0.135672 0.984305 -v 0.054543 0.091301 0.099677 -vn 0.099557 -0.366940 0.924902 -v 0.054532 0.091116 0.099628 -vn 0.080564 -0.577448 0.812443 -v 0.054517 0.090948 0.099537 -vn 0.056889 -0.755104 0.653132 -v 0.054498 0.090807 0.099409 -vn 0.029906 -0.889547 0.455863 -v 0.054476 0.090701 0.099251 -vn -0.087924 -0.892734 0.441923 -v 0.054386 0.090699 0.099240 -vn -0.268086 -0.772944 0.575054 -v 0.054243 0.090793 0.099348 -vn -0.500184 -0.626511 0.597746 -v 0.054059 0.090909 0.099368 -vn -0.731324 -0.464095 0.499781 -v 0.053874 0.091039 0.099292 -vn -0.908956 -0.292829 0.296733 -v 0.053732 0.091176 0.099131 -vn -0.992840 -0.116450 0.026607 -v 0.053665 0.091318 0.098917 -vn -0.963990 0.063506 -0.258243 -v 0.053688 0.091462 0.098690 -vn -0.828927 0.245807 -0.502453 -v 0.053796 0.091608 0.098496 -vn -0.618209 0.427590 -0.659533 -v 0.053964 0.091754 0.098372 -vn -0.379608 0.602713 -0.701880 -v 0.054154 0.091894 0.098341 -vn -0.167343 0.761161 -0.626603 -v 0.054322 0.092019 0.098402 -vn -0.140880 -0.898928 0.414827 -v 0.054345 0.090694 0.099220 -vn -0.353234 -0.789752 0.501516 -v 0.054177 0.090780 0.099291 -vn -0.591708 -0.656053 0.468483 -v 0.053987 0.090886 0.099266 -vn -0.801929 -0.505570 0.318291 -v 0.053819 0.091006 0.099148 -vn -0.936160 -0.342737 0.078332 -v 0.053711 0.091136 0.098958 -vn -0.963991 -0.169379 -0.205020 -v 0.053688 0.091276 0.098733 -vn -0.879114 0.013642 -0.476417 -v 0.053755 0.091423 0.098517 -vn -0.700725 0.204431 -0.683514 -v 0.053897 0.091576 0.098353 -vn -0.469178 0.398173 -0.788245 -v 0.054082 0.091731 0.098271 -vn -0.236965 0.586039 -0.774859 -v 0.054266 0.091881 0.098283 -vn -0.056909 0.755102 -0.653133 -v 0.054409 0.092015 0.098382 -vn 0.087983 0.892746 -0.441886 -v 0.054520 0.092123 0.098550 -vn 0.056920 0.755095 -0.653140 -v 0.054498 0.092015 0.098382 -vn -0.080548 0.577443 -0.812448 -v 0.054390 0.091874 0.098253 -vn -0.292885 0.377567 -0.878443 -v 0.054221 0.091714 0.098199 -vn -0.531802 0.171089 -0.829406 -v 0.054031 0.091549 0.098237 -vn -0.743150 -0.030246 -0.668442 -v 0.053863 0.091388 0.098364 -vn -0.879113 -0.219242 -0.423194 -v 0.053755 0.091236 0.098560 -vn -0.908959 -0.392648 -0.140077 -v 0.053732 0.091097 0.098785 -vn -0.825927 -0.549605 0.125616 -v 0.053800 0.090971 0.098996 -vn -0.648840 -0.689604 0.321640 -v 0.053942 0.090860 0.099151 -vn -0.417868 -0.810617 0.410226 -v 0.054126 0.090764 0.099219 -vn -0.185684 -0.907777 0.376115 -v 0.054311 0.090687 0.099190 -vn -0.668252 -0.725236 0.165747 -v 0.053927 0.090831 0.099028 -vn -0.458217 -0.834313 0.306528 -v 0.054095 0.090745 0.099138 -vn -0.219620 -0.918730 0.328179 -v 0.054285 0.090679 0.099153 -vn 0.236951 0.586041 -0.774861 -v 0.054640 0.091881 0.098283 -vn 0.080552 0.577450 -0.812443 -v 0.054517 0.091874 0.098253 -vn 0.099561 0.366945 -0.924899 -v 0.054532 0.091706 0.098162 -vn -0.099558 0.366950 -0.924898 -v 0.054374 0.091706 0.098162 -vn -0.112840 0.135675 -0.984307 -v 0.054364 0.091521 0.098114 -vn -0.331969 0.147716 -0.931653 -v 0.054190 0.091531 0.098156 -vn -0.352069 -0.090386 -0.931600 -v 0.054174 0.091340 0.098156 -vn -0.563997 -0.065611 -0.823166 -v 0.054005 0.091360 0.098242 -vn -0.564008 -0.298482 -0.769937 -v 0.054005 0.091173 0.098284 -vn -0.743149 -0.263128 -0.615219 -v 0.053863 0.091201 0.098407 -vn -0.700727 -0.481039 -0.526862 -v 0.053897 0.091027 0.098478 -vn -0.828923 -0.439668 -0.345801 -v 0.053796 0.091059 0.098622 -vn -0.731323 -0.635118 -0.248580 -v 0.053874 0.090903 0.098700 -vn -0.801922 -0.593649 -0.067092 -v 0.053819 0.090936 0.098843 -vn -0.648832 -0.760868 0.009835 -v 0.053942 0.090803 0.098905 -vn -0.471925 -0.859480 0.196421 -v 0.054084 0.090725 0.099052 -vn -0.240805 -0.931175 0.273726 -v 0.054269 0.090669 0.099111 -vn 0.248031 -0.420082 0.872933 -v 0.054643 0.093091 0.097983 -vn 0.240830 -0.366616 0.898663 -v 0.054638 0.093132 0.098002 -vn 0.000001 -0.429984 0.902836 -v 0.054453 0.093081 0.098003 -vn -0.219631 -0.523931 0.822957 -v 0.054285 0.093012 0.097944 -vn -0.185652 -0.568290 0.801611 -v 0.054311 0.092978 0.097928 -vn -0.056897 0.804464 -0.591271 -v 0.054409 0.094060 0.096813 -vn -0.029904 0.641944 -0.766168 -v 0.054430 0.093930 0.096675 -vn -0.087978 0.629046 -0.772373 -v 0.054386 0.093920 0.096670 -vn 0.000000 0.437276 -0.899327 -v 0.054453 0.093770 0.096572 -vn 0.029907 0.641944 -0.766168 -v 0.054476 0.093930 0.096675 -vn 0.041758 0.182790 -0.982265 -v 0.054476 0.093590 0.096511 -vn -0.041756 0.182798 -0.982263 -v 0.054430 0.093590 0.096511 -vn 0.140909 0.236149 -0.961446 -v 0.054561 0.093619 0.096525 -vn 0.268083 0.032326 -0.962853 -v 0.054663 0.093457 0.096523 -vn 0.167351 -0.015319 -0.985778 -v 0.054584 0.093419 0.096505 -vn 0.056891 0.804460 -0.591276 -v 0.054498 0.094060 0.096813 -vn 0.080538 0.920362 -0.382683 -v 0.054517 0.094154 0.096979 -vn 0.087971 0.629043 -0.772377 -v 0.054520 0.093920 0.096670 -vn 0.167344 0.779923 -0.603088 -v 0.054584 0.094041 0.096804 -vn 0.236946 0.885628 -0.399398 -v 0.054640 0.094127 0.096966 -vn 0.292875 0.940346 -0.173128 -v 0.054685 0.094172 0.097146 -vn 0.140946 0.603958 -0.784454 -v 0.054561 0.093901 0.096661 -vn 0.268071 0.732290 -0.626011 -v 0.054663 0.094004 0.096786 -vn 0.379607 0.818159 -0.431872 -v 0.054752 0.094074 0.096940 -vn 0.469176 0.856971 -0.213247 -v 0.054824 0.094106 0.097115 -vn 0.531800 0.846693 0.017290 -v 0.054875 0.094098 0.097299 -vn 0.185662 0.568285 -0.801612 -v 0.054595 0.093873 0.096648 -vn 0.353246 0.664290 -0.658739 -v 0.054729 0.093951 0.096760 -vn 0.500206 0.721884 -0.478202 -v 0.054847 0.093998 0.096904 -vn 0.618221 0.737988 -0.270510 -v 0.054942 0.094011 0.097069 -vn 0.700724 0.711842 -0.047607 -v 0.055009 0.093991 0.097248 -vn 0.743149 0.645055 0.177860 -v 0.055043 0.093938 0.097428 -vn 0.219578 0.523968 -0.822947 -v 0.054621 0.093839 0.096631 -vn 0.417868 0.579945 -0.699322 -v 0.054780 0.093885 0.096729 -vn 0.591716 0.602421 -0.535688 -v 0.054919 0.093904 0.096858 -vn 0.731322 0.590335 -0.341573 -v 0.055032 0.093895 0.097013 -vn 0.828924 0.544485 -0.128143 -v 0.055110 0.093858 0.097184 -vn 0.879116 0.467556 0.092449 -v 0.055151 0.093797 0.097360 -vn 0.879116 0.363963 0.307710 -v 0.055151 0.093714 0.097533 -vn 0.240825 0.473535 -0.847212 -v 0.054638 0.093801 0.096613 -vn -0.240826 0.473541 -0.847208 -v 0.054269 0.093801 0.096613 -vn -0.219593 0.523945 -0.822959 -v 0.054285 0.093839 0.096631 -vn -0.417873 0.579934 -0.699328 -v 0.054126 0.093885 0.096729 -vn -0.353231 0.664303 -0.658733 -v 0.054177 0.093951 0.096760 -vn -0.500204 0.721886 -0.478201 -v 0.054059 0.093998 0.096904 -vn -0.379611 0.818160 -0.431868 -v 0.054154 0.094074 0.096940 -vn -0.469171 0.856972 -0.213253 -v 0.054082 0.094106 0.097115 -vn -0.292874 0.940347 -0.173124 -v 0.054221 0.094172 0.097146 -vn -0.331955 0.941205 0.062761 -v 0.054190 0.094173 0.097335 -vn -0.112845 0.989867 0.086195 -v 0.054364 0.094212 0.097354 -vn -0.119666 0.939915 0.319749 -v 0.054358 0.094172 0.097541 -vn 0.119667 0.939913 0.319756 -v 0.054548 0.094172 0.097541 -vn -0.119677 0.836315 0.535028 -v 0.054358 0.094089 0.097713 -vn -0.352061 0.888301 0.294914 -v 0.054174 0.094131 0.097521 -vn -0.531803 0.846691 0.017297 -v 0.054031 0.094098 0.097299 -vn -0.618230 0.737979 -0.270514 -v 0.053964 0.094011 0.097069 -vn -0.591721 0.602424 -0.535679 -v 0.053987 0.093904 0.096858 -vn -0.458214 0.484067 -0.745465 -v 0.054095 0.093810 0.096693 -vn -0.248015 0.420108 -0.872925 -v 0.054263 0.093760 0.096593 -vn 0.352058 -0.784711 -0.510180 -v 0.054733 0.092803 0.096882 -vn 0.352070 -0.888296 -0.294917 -v 0.054733 0.092720 0.097055 -vn 0.119676 -0.939909 -0.319763 -v 0.054548 0.092679 0.097035 -vn 0.458218 0.484071 -0.745461 -v 0.054811 0.093810 0.096693 -vn 0.648832 0.466695 -0.601010 -v 0.054964 0.093797 0.096807 -vn 0.801924 0.422587 -0.422301 -v 0.055087 0.093762 0.096949 -vn 0.908958 0.354330 -0.219649 -v 0.055174 0.093708 0.097111 -vn 0.963991 0.265896 -0.004597 -v 0.055218 0.093637 0.097283 -vn 0.963991 0.162305 0.210663 -v 0.055218 0.093554 0.097456 -vn 0.908959 0.049425 0.413945 -v 0.055174 0.093463 0.097619 -vn 0.248021 0.420112 -0.872921 -v 0.054643 0.093760 0.096593 -vn 0.119677 0.836320 0.535020 -v 0.054548 0.094089 0.097713 -vn 0.352068 0.784708 0.510179 -v 0.054733 0.094048 0.097694 -vn -0.112836 0.684958 0.719792 -v 0.054364 0.093967 0.097861 -vn -0.352071 0.784701 0.510187 -v 0.054174 0.094048 0.097694 -vn -0.563998 0.788067 0.246691 -v 0.054005 0.094051 0.097483 -vn -0.700724 0.711842 -0.047610 -v 0.053897 0.093991 0.097248 -vn -0.731321 0.590337 -0.341574 -v 0.053874 0.093895 0.097013 -vn -0.648835 0.466700 -0.601003 -v 0.053942 0.093797 0.096807 -vn -0.471932 0.382306 -0.794432 -v 0.054084 0.093730 0.096654 -vn -0.240817 0.366634 -0.898658 -v 0.054269 0.093719 0.096573 -vn 0.471934 0.382304 -0.794432 -v 0.054822 0.093730 0.096654 -vn 0.668253 0.322591 -0.670353 -v 0.054980 0.093683 0.096752 -vn 0.825923 0.244466 -0.508023 -v 0.055106 0.093621 0.096881 -vn 0.936162 0.152451 -0.316794 -v 0.055195 0.093547 0.097034 -vn 0.992841 0.051792 -0.107633 -v 0.055241 0.093467 0.097202 -vn 0.992840 -0.051795 0.107636 -v 0.055241 0.093384 0.097374 -vn 0.936159 -0.152455 0.316803 -v 0.055195 0.093303 0.097542 -vn 0.825925 -0.244471 0.508017 -v 0.055106 0.093230 0.097694 -vn 0.240823 0.366617 -0.898664 -v 0.054638 0.093719 0.096573 -vn 0.331961 0.636294 0.696371 -v 0.054716 0.093929 0.097843 -vn 0.531803 0.541782 0.650890 -v 0.054875 0.093854 0.097807 -vn -0.099544 0.494336 0.863552 -v 0.054374 0.093814 0.097976 -vn -0.331957 0.636299 0.696368 -v 0.054190 0.093929 0.097843 -vn -0.563996 0.684476 0.461954 -v 0.054005 0.093968 0.097655 -vn -0.743147 0.645057 0.177861 -v 0.053863 0.093938 0.097428 -vn -0.828920 0.544490 -0.128148 -v 0.053796 0.093858 0.097184 -vn -0.801919 0.422591 -0.422307 -v 0.053819 0.093762 0.096949 -vn -0.668252 0.322598 -0.670350 -v 0.053927 0.093683 0.096752 -vn -0.458215 0.280534 -0.843410 -v 0.054095 0.093651 0.096616 -vn -0.219620 0.316232 -0.922911 -v 0.054285 0.093680 0.096555 -vn -0.112840 -0.989869 -0.086182 -v 0.054364 0.092639 0.097222 -vn -0.099546 -0.983280 0.152484 -v 0.054374 0.092645 0.097413 -vn -0.292873 -0.940343 0.173147 -v 0.054221 0.092679 0.097429 -vn 0.458212 0.280530 -0.843412 -v 0.054811 0.093651 0.096616 -vn 0.648835 0.178495 -0.739698 -v 0.054964 0.093570 0.096698 -vn 0.801926 0.066368 -0.593726 -v 0.055087 0.093480 0.096814 -vn 0.908961 -0.049419 -0.413942 -v 0.055174 0.093387 0.096957 -vn 0.963990 -0.162307 -0.210665 -v 0.055218 0.093297 0.097120 -vn 0.963990 -0.265898 0.004597 -v 0.055218 0.093214 0.097292 -vn 0.908959 -0.354332 0.219642 -v 0.055174 0.093143 0.097465 -vn 0.801930 -0.422577 0.422300 -v 0.055087 0.093089 0.097626 -vn 0.648832 -0.466698 0.601007 -v 0.054964 0.093054 0.097769 -vn 0.219623 0.316229 -0.922911 -v 0.054621 0.093680 0.096555 -vn 0.469186 0.368010 0.802766 -v 0.054824 0.093714 0.097928 -vn 0.618210 0.249051 0.745514 -v 0.054942 0.093620 0.097882 -vn -0.080542 0.275161 0.958018 -v 0.054390 0.093639 0.098050 -vn -0.292872 0.451396 0.842892 -v 0.054221 0.093780 0.097959 -vn -0.531800 0.541787 0.650888 -v 0.054031 0.093854 0.097807 -vn -0.743150 0.541462 0.393126 -v 0.053863 0.093855 0.097601 -vn -0.879116 0.467554 0.092452 -v 0.053755 0.093797 0.097360 -vn -0.908958 0.354328 -0.219652 -v 0.053732 0.093708 0.097111 -vn -0.825928 0.244461 -0.508017 -v 0.053800 0.093621 0.096881 -vn -0.648833 0.178478 -0.739704 -v 0.053942 0.093570 0.096698 -vn -0.417878 0.184658 -0.889539 -v 0.054126 0.093576 0.096580 -vn -0.185652 0.271881 -0.944253 -v 0.054311 0.093646 0.096539 -vn -0.236970 -0.885617 0.399409 -v 0.054266 0.092724 0.097610 -vn -0.379613 -0.818155 0.431876 -v 0.054154 0.092777 0.097636 -vn 0.417869 0.184665 -0.889542 -v 0.054780 0.093576 0.096580 -vn 0.591702 0.042755 -0.805022 -v 0.054919 0.093463 0.096646 -vn 0.731313 -0.101389 -0.674464 -v 0.055032 0.093347 0.096750 -vn 0.828928 -0.239572 -0.505455 -v 0.055110 0.093237 0.096885 -vn 0.879118 -0.363966 -0.307702 -v 0.055151 0.093137 0.097043 -vn 0.879117 -0.467555 -0.092447 -v 0.055151 0.093054 0.097215 -vn 0.828929 -0.544477 0.128146 -v 0.055110 0.092992 0.097392 -vn 0.731320 -0.590341 0.341567 -v 0.055032 0.092956 0.097563 -vn 0.591699 -0.602430 0.535697 -v 0.054919 0.092947 0.097717 -vn 0.417868 -0.579937 0.699328 -v 0.054780 0.092966 0.097847 -vn 0.185649 0.271881 -0.944254 -v 0.054595 0.093646 0.096539 -vn 0.500186 0.076714 0.862513 -v 0.054847 0.093482 0.097975 -vn 0.591698 -0.042761 0.805025 -v 0.054919 0.093388 0.097930 -vn -0.056885 0.039851 0.997585 -v 0.054409 0.093451 0.098080 -vn -0.236963 0.240424 0.941300 -v 0.054266 0.093611 0.098037 -vn -0.469185 0.368009 0.802767 -v 0.054082 0.093714 0.097928 -vn -0.700724 0.406937 0.585993 -v 0.053897 0.093747 0.097755 -vn -0.879116 0.363963 0.307711 -v 0.053755 0.093714 0.097533 -vn -0.963992 0.265893 -0.004598 -v 0.053688 0.093637 0.097283 -vn -0.936161 0.152452 -0.316799 -v 0.053711 0.093547 0.097034 -vn -0.801927 0.066364 -0.593725 -v 0.053819 0.093480 0.096814 -vn -0.591704 0.042757 -0.805021 -v 0.053987 0.093463 0.096646 -vn -0.353251 0.100308 -0.930135 -v 0.054177 0.093510 0.096548 -vn -0.140909 0.236151 -0.961446 -v 0.054345 0.093619 0.096525 -vn -0.268103 -0.732278 0.626011 -v 0.054243 0.092847 0.097790 -vn -0.353246 -0.664306 0.658722 -v 0.054177 0.092900 0.097815 -vn 0.417858 -0.184664 0.889547 -v 0.054780 0.093275 0.097996 -vn 0.458210 -0.280535 0.843412 -v 0.054811 0.093200 0.097960 -vn -0.029891 -0.198210 0.979704 -v 0.054430 0.093261 0.098064 -vn -0.167351 0.015311 0.985778 -v 0.054322 0.093431 0.098071 -vn -0.379611 0.172954 0.908836 -v 0.054154 0.093558 0.098011 -vn -0.618212 0.249042 0.745514 -v 0.053964 0.093620 0.097882 -vn -0.828926 0.239573 0.505456 -v 0.053796 0.093614 0.097691 -vn -0.963991 0.162306 0.210662 -v 0.053688 0.093554 0.097456 -vn -0.992841 0.051795 -0.107631 -v 0.053665 0.093467 0.097202 -vn -0.908957 -0.049411 -0.413951 -v 0.053732 0.093387 0.096957 -vn -0.731317 -0.101378 -0.674462 -v 0.053874 0.093347 0.096750 -vn -0.500193 -0.076693 -0.862511 -v 0.054059 0.093368 0.096601 -vn -0.268090 0.032327 -0.962851 -v 0.054243 0.093457 0.096523 -vn -0.087953 0.211116 -0.973496 -v 0.054386 0.093600 0.096516 -vn 0.292878 -0.451396 -0.842890 -v 0.054685 0.093070 0.096617 -vn 0.331956 -0.636296 -0.696371 -v 0.054716 0.092922 0.096733 -vn 0.112843 -0.684964 -0.719785 -v 0.054543 0.092883 0.096715 -vn 0.119667 -0.836316 -0.535029 -v 0.054548 0.092762 0.096862 -vn -0.119670 -0.836318 -0.535024 -v 0.054358 0.092762 0.096862 -vn -0.119680 -0.939907 -0.319768 -v 0.054358 0.092679 0.097035 -vn -0.352071 -0.888295 -0.294921 -v 0.054174 0.092720 0.097055 -vn -0.331966 -0.941201 -0.062770 -v 0.054190 0.092678 0.097241 -vn -0.531801 -0.846693 -0.017291 -v 0.054031 0.092753 0.097277 -vn -0.469183 -0.856962 0.213269 -v 0.054082 0.092745 0.097461 -vn -0.618210 -0.737994 0.270519 -v 0.053964 0.092839 0.097506 -vn -0.500182 -0.721905 0.478195 -v 0.054059 0.092853 0.097672 -vn -0.591696 -0.602438 0.535690 -v 0.053987 0.092947 0.097717 -vn -0.417865 -0.579940 0.699327 -v 0.054126 0.092966 0.097847 -vn -0.458214 -0.484061 0.745470 -v 0.054095 0.093041 0.097883 -vn -0.240828 -0.473531 0.847213 -v 0.054269 0.093050 0.097963 -vn -0.248031 -0.420082 0.872933 -v 0.054263 0.093091 0.097983 -vn -0.140881 -0.604024 0.784416 -v 0.054345 0.092950 0.097915 -vn -0.167342 -0.779925 0.603087 -v 0.054322 0.092810 0.097772 -vn -0.087924 -0.629062 0.772367 -v 0.054386 0.092931 0.097906 -vn -0.080549 -0.920359 0.382689 -v 0.054390 0.092697 0.097597 -vn -0.056864 -0.804454 0.591287 -v 0.054409 0.092790 0.097763 -vn -0.041774 -0.653581 0.755703 -v 0.054430 0.092921 0.097901 -vn 0.041770 -0.653570 0.755713 -v 0.054476 0.092921 0.097901 -vn 0.056871 -0.804459 0.591280 -v 0.054498 0.092790 0.097763 -vn 0.080550 -0.920356 0.382696 -v 0.054517 0.092697 0.097597 -vn 0.099547 -0.983281 0.152478 -v 0.054532 0.092645 0.097413 -vn 0.112841 -0.989868 -0.086183 -v 0.054543 0.092639 0.097222 -vn 0.331962 -0.941202 -0.062776 -v 0.054716 0.092678 0.097241 -vn 0.292876 -0.940342 0.173148 -v 0.054685 0.092679 0.097429 -vn 0.236968 -0.885615 0.399414 -v 0.054640 0.092724 0.097610 -vn 0.167337 -0.779928 0.603085 -v 0.054584 0.092810 0.097772 -vn 0.087939 -0.629059 0.772368 -v 0.054520 0.092931 0.097906 -vn 0.353253 0.100315 -0.930134 -v 0.054729 0.093510 0.096548 -vn 0.379607 -0.172962 -0.908836 -v 0.054752 0.093293 0.096564 -vn 0.500201 -0.076697 -0.862506 -v 0.054847 0.093368 0.096601 -vn 0.469178 -0.368016 -0.802767 -v 0.054824 0.093136 0.096648 -vn 0.618215 -0.249045 -0.745511 -v 0.054942 0.093231 0.096694 -vn 0.531801 -0.541782 -0.650892 -v 0.054875 0.092997 0.096769 -vn 0.700729 -0.406930 -0.585993 -v 0.055009 0.093104 0.096821 -vn 0.564000 -0.684480 -0.461943 -v 0.054901 0.092882 0.096920 -vn 0.743151 -0.541462 -0.393122 -v 0.055043 0.092996 0.096975 -vn 0.563998 -0.788067 -0.246691 -v 0.054901 0.092799 0.097093 -vn 0.743151 -0.645052 -0.177861 -v 0.055043 0.092913 0.097147 -vn 0.531805 -0.846690 -0.017287 -v 0.054875 0.092753 0.097277 -vn 0.700728 -0.711838 0.047610 -v 0.055009 0.092860 0.097328 -vn 0.469187 -0.856959 0.213273 -v 0.054824 0.092745 0.097461 -vn 0.618210 -0.737998 0.270510 -v 0.054942 0.092839 0.097506 -vn 0.379613 -0.818159 0.431868 -v 0.054752 0.092777 0.097636 -vn 0.500186 -0.721907 0.478189 -v 0.054847 0.092853 0.097672 -vn 0.268094 -0.732277 0.626015 -v 0.054663 0.092847 0.097790 -vn 0.353246 -0.664301 0.658728 -v 0.054729 0.092900 0.097815 -vn 0.140877 -0.604032 0.784410 -v 0.054561 0.092950 0.097915 -vn 0.185653 -0.568288 0.801612 -v 0.054595 0.092978 0.097928 -vn 0.219617 -0.523941 0.822954 -v 0.054621 0.093012 0.097944 -vn 0.240824 -0.473533 0.847213 -v 0.054638 0.093050 0.097963 -vn 0.458215 -0.484076 0.745459 -v 0.054811 0.093041 0.097883 -vn 0.471927 -0.382299 0.794439 -v 0.054822 0.093121 0.097921 -vn 0.668244 -0.322595 0.670360 -v 0.054980 0.093168 0.097823 -vn 0.648835 -0.178495 0.739698 -v 0.054964 0.093281 0.097878 -vn 0.801927 -0.066365 0.593724 -v 0.055087 0.093371 0.097762 -vn 0.731318 0.101394 0.674457 -v 0.055032 0.093503 0.097826 -vn 0.828926 0.239573 0.505456 -v 0.055110 0.093614 0.097691 -vn 0.700723 0.406938 0.585994 -v 0.055009 0.093747 0.097755 -vn 0.743149 0.541462 0.393126 -v 0.055043 0.093855 0.097601 -vn 0.563998 0.684475 0.461953 -v 0.054901 0.093968 0.097655 -vn 0.563996 0.788068 0.246692 -v 0.054901 0.094051 0.097483 -vn 0.352057 0.888300 0.294922 -v 0.054733 0.094131 0.097521 -vn 0.331965 0.941202 0.062760 -v 0.054716 0.094173 0.097335 -vn 0.112837 0.989868 0.086196 -v 0.054543 0.094212 0.097354 -vn 0.099563 0.983279 -0.152478 -v 0.054532 0.094205 0.097163 -vn -0.099561 0.983281 -0.152468 -v 0.054374 0.094205 0.097163 -vn -0.080530 0.920358 -0.382696 -v 0.054390 0.094154 0.096979 -vn -0.236954 0.885624 -0.399403 -v 0.054266 0.094127 0.096966 -vn -0.167336 0.779926 -0.603088 -v 0.054322 0.094041 0.096804 -vn -0.268074 0.732278 -0.626024 -v 0.054243 0.094004 0.096786 -vn -0.140961 0.603968 -0.784444 -v 0.054345 0.093901 0.096661 -vn -0.185648 0.568300 -0.801605 -v 0.054311 0.093873 0.096648 -vn 0.219628 -0.316227 0.922911 -v 0.054621 0.093171 0.098021 -vn 0.353256 -0.100312 0.930133 -v 0.054729 0.093341 0.098027 -vn 0.185653 -0.271879 0.944254 -v 0.054595 0.093205 0.098037 -vn 0.379608 0.172959 0.908836 -v 0.054752 0.093558 0.098011 -vn 0.268086 -0.032322 0.962853 -v 0.054663 0.093394 0.098053 -vn 0.140894 -0.236146 0.961449 -v 0.054561 0.093232 0.098050 -vn 0.292876 0.451396 0.842891 -v 0.054685 0.093780 0.097959 -vn 0.236959 0.240423 0.941301 -v 0.054640 0.093611 0.098037 -vn 0.167348 0.015313 0.985779 -v 0.054584 0.093431 0.098071 -vn 0.087944 -0.211103 0.973499 -v 0.054520 0.093251 0.098060 -vn 0.112829 0.684955 0.719796 -v 0.054543 0.093967 0.097861 -vn 0.099547 0.494338 0.863551 -v 0.054532 0.093814 0.097976 -vn 0.080545 0.275160 0.958018 -v 0.054517 0.093639 0.098050 -vn 0.056888 0.039852 0.997585 -v 0.054498 0.093451 0.098080 -vn 0.029892 -0.198210 0.979704 -v 0.054476 0.093261 0.098064 -vn -0.087943 -0.211101 0.973500 -v 0.054386 0.093251 0.098060 -vn -0.268091 -0.032321 0.962851 -v 0.054243 0.093394 0.098053 -vn -0.500184 0.076718 0.862514 -v 0.054059 0.093482 0.097975 -vn -0.731319 0.101391 0.674457 -v 0.053874 0.093503 0.097826 -vn -0.908957 0.049422 0.413951 -v 0.053732 0.093463 0.097619 -vn -0.992840 -0.051797 0.107634 -v 0.053665 0.093384 0.097374 -vn -0.963990 -0.162310 -0.210663 -v 0.053688 0.093297 0.097120 -vn -0.828927 -0.239574 -0.505455 -v 0.053796 0.093237 0.096885 -vn -0.618216 -0.249044 -0.745511 -v 0.053964 0.093231 0.096694 -vn -0.379609 -0.172957 -0.908836 -v 0.054154 0.093293 0.096564 -vn -0.167350 -0.015321 -0.985778 -v 0.054322 0.093419 0.096505 -vn -0.140893 -0.236144 0.961450 -v 0.054345 0.093232 0.098050 -vn -0.353245 -0.100305 0.930138 -v 0.054177 0.093341 0.098027 -vn -0.591697 -0.042760 0.805025 -v 0.053987 0.093388 0.097930 -vn -0.801927 -0.066366 0.593724 -v 0.053819 0.093371 0.097762 -vn -0.936158 -0.152459 0.316805 -v 0.053711 0.093303 0.097542 -vn -0.963991 -0.265897 0.004598 -v 0.053688 0.093214 0.097292 -vn -0.879117 -0.363967 -0.307704 -v 0.053755 0.093137 0.097043 -vn -0.700732 -0.406926 -0.585992 -v 0.053897 0.093104 0.096821 -vn -0.469180 -0.368015 -0.802767 -v 0.054082 0.093136 0.096648 -vn -0.236963 -0.240421 -0.941300 -v 0.054266 0.093239 0.096539 -vn -0.056885 -0.039847 -0.997585 -v 0.054409 0.093400 0.096496 -vn 0.087958 0.211118 -0.973495 -v 0.054520 0.093600 0.096516 -vn 0.056885 -0.039846 -0.997585 -v 0.054498 0.093400 0.096496 -vn -0.080550 -0.275159 -0.958018 -v 0.054390 0.093212 0.096526 -vn -0.292874 -0.451396 -0.842892 -v 0.054221 0.093070 0.096617 -vn -0.531795 -0.541788 -0.650892 -v 0.054031 0.092997 0.096769 -vn -0.743154 -0.541459 -0.393121 -v 0.053863 0.092996 0.096975 -vn -0.879117 -0.467555 -0.092446 -v 0.053755 0.093054 0.097215 -vn -0.908957 -0.354332 0.219648 -v 0.053732 0.093143 0.097465 -vn -0.825929 -0.244468 0.508013 -v 0.053800 0.093230 0.097694 -vn -0.648833 -0.178483 0.739702 -v 0.053942 0.093281 0.097878 -vn -0.417872 -0.184668 0.889540 -v 0.054126 0.093275 0.097996 -vn -0.185655 -0.271879 0.944253 -v 0.054311 0.093205 0.098037 -vn -0.668246 -0.322599 0.670356 -v 0.053927 0.093168 0.097823 -vn -0.458210 -0.280530 0.843414 -v 0.054095 0.093200 0.097960 -vn -0.219625 -0.316229 0.922911 -v 0.054285 0.093171 0.098021 -vn 0.236961 -0.240420 -0.941301 -v 0.054640 0.093239 0.096539 -vn 0.080552 -0.275160 -0.958018 -v 0.054517 0.093212 0.096526 -vn 0.099558 -0.494337 -0.863550 -v 0.054532 0.093036 0.096600 -vn -0.099557 -0.494337 -0.863551 -v 0.054374 0.093036 0.096600 -vn -0.112843 -0.684963 -0.719787 -v 0.054364 0.092883 0.096715 -vn -0.331960 -0.636295 -0.696370 -v 0.054190 0.092922 0.096733 -vn -0.352062 -0.784710 -0.510179 -v 0.054174 0.092803 0.096882 -vn -0.563994 -0.684484 -0.461945 -v 0.054005 0.092882 0.096920 -vn -0.563999 -0.788067 -0.246690 -v 0.054005 0.092799 0.097093 -vn -0.743150 -0.645054 -0.177858 -v 0.053863 0.092913 0.097147 -vn -0.700730 -0.711837 0.047603 -v 0.053897 0.092860 0.097328 -vn -0.828930 -0.544476 0.128146 -v 0.053796 0.092992 0.097392 -vn -0.731323 -0.590334 0.341573 -v 0.053874 0.092956 0.097563 -vn -0.801929 -0.422579 0.422299 -v 0.053819 0.093089 0.097626 -vn -0.648833 -0.466699 0.601005 -v 0.053942 0.093054 0.097769 -vn -0.471922 -0.382312 0.794435 -v 0.054084 0.093121 0.097921 -vn -0.240824 -0.366633 0.898657 -v 0.054269 0.093132 0.098002 -vn 0.248013 0.420618 0.872680 -v 0.054643 0.093759 0.095405 -vn 0.240827 0.474031 0.846934 -v 0.054638 0.093800 0.095385 -vn 0.000001 0.437771 0.899086 -v 0.054453 0.093769 0.095426 -vn -0.219602 0.316712 0.922750 -v 0.054285 0.093680 0.095443 -vn -0.185659 0.272434 0.944092 -v 0.054311 0.093646 0.095460 -vn -0.056869 0.039295 -0.997608 -v 0.054409 0.093449 0.093918 -vn -0.029904 -0.198765 -0.979591 -v 0.054430 0.093260 0.093934 -vn -0.087992 -0.211680 -0.973370 -v 0.054386 0.093250 0.093939 -vn -0.000001 -0.430484 -0.902598 -v 0.054453 0.093080 0.093995 -vn 0.029901 -0.198770 -0.979590 -v 0.054476 0.093260 0.093934 -vn 0.041739 -0.654002 -0.755340 -v 0.054476 0.092920 0.094098 -vn -0.041746 -0.654002 -0.755340 -v 0.054430 0.092920 0.094098 -vn 0.140918 -0.604433 -0.784094 -v 0.054561 0.092949 0.094084 -vn 0.268072 -0.732634 -0.625608 -v 0.054663 0.092846 0.094209 -vn 0.167346 -0.780261 -0.602650 -v 0.054584 0.092809 0.094227 -vn 0.056874 0.039301 -0.997608 -v 0.054498 0.093449 0.093918 -vn 0.080554 0.274629 -0.958170 -v 0.054517 0.093638 0.093948 -vn 0.087989 -0.211692 -0.973368 -v 0.054520 0.093250 0.093939 -vn 0.167341 0.014769 -0.985789 -v 0.054584 0.093430 0.093927 -vn 0.236959 0.239908 -0.941432 -v 0.054640 0.093610 0.093961 -vn 0.292879 0.450920 -0.843145 -v 0.054685 0.093779 0.094039 -vn 0.140922 -0.236718 -0.961304 -v 0.054561 0.093231 0.093948 -vn 0.268087 -0.032874 -0.962834 -v 0.054663 0.093393 0.093945 -vn 0.379598 0.172469 -0.908934 -v 0.054752 0.093557 0.093987 -vn 0.469168 0.367577 -0.802975 -v 0.054824 0.093713 0.094071 -vn 0.531801 0.541419 -0.651194 -v 0.054875 0.093853 0.094192 -vn 0.185623 -0.272383 -0.944114 -v 0.054595 0.093203 0.093961 -vn 0.353241 -0.100854 -0.930080 -v 0.054729 0.093340 0.093971 -vn 0.500186 0.076229 -0.862556 -v 0.054847 0.093481 0.094024 -vn 0.618213 0.248643 -0.745647 -v 0.054942 0.093619 0.094116 -vn 0.700726 0.406611 -0.586217 -v 0.055009 0.093746 0.094243 -vn 0.743149 0.541244 -0.393426 -v 0.055043 0.093854 0.094397 -vn 0.219588 -0.316705 -0.922756 -v 0.054621 0.093170 0.093978 -vn 0.417868 -0.185173 -0.889437 -v 0.054780 0.093274 0.094003 -vn 0.591704 -0.043216 -0.804996 -v 0.054919 0.093387 0.094069 -vn 0.731324 0.101011 -0.674509 -v 0.055032 0.093502 0.094172 -vn 0.828928 0.239288 -0.505588 -v 0.055110 0.093613 0.094307 -vn 0.879116 0.363795 -0.307910 -v 0.055151 0.093713 0.094465 -vn 0.879116 0.467504 -0.092707 -v 0.055151 0.093796 0.094638 -vn 0.240806 -0.367133 -0.898458 -v 0.054638 0.093131 0.093996 -vn -0.240820 -0.367138 -0.898452 -v 0.054269 0.093131 0.093996 -vn -0.219597 -0.316726 -0.922747 -v 0.054285 0.093170 0.093978 -vn -0.417875 -0.185173 -0.889433 -v 0.054126 0.093274 0.094003 -vn -0.353240 -0.100837 -0.930082 -v 0.054177 0.093340 0.093971 -vn -0.500184 0.076220 -0.862558 -v 0.054059 0.093481 0.094024 -vn -0.379591 0.172465 -0.908937 -v 0.054154 0.093557 0.093987 -vn -0.469163 0.367576 -0.802978 -v 0.054082 0.093713 0.094071 -vn -0.292871 0.450924 -0.843145 -v 0.054221 0.093779 0.094039 -vn -0.331957 0.635900 -0.696732 -v 0.054190 0.093928 0.094156 -vn -0.112842 0.684557 -0.720172 -v 0.054364 0.093966 0.094137 -vn -0.119664 0.836023 -0.535487 -v 0.054358 0.094088 0.094285 -vn 0.119665 0.836025 -0.535483 -v 0.054548 0.094088 0.094285 -vn -0.119669 0.939734 -0.320281 -v 0.054358 0.094171 0.094457 -vn -0.352065 0.784423 -0.510619 -v 0.054174 0.094047 0.094304 -vn -0.531800 0.541424 -0.651190 -v 0.054031 0.093853 0.094192 -vn -0.618221 0.248632 -0.745644 -v 0.053964 0.093619 0.094116 -vn -0.591697 -0.043205 -0.805002 -v 0.053987 0.093387 0.094069 -vn -0.458196 -0.280991 -0.843268 -v 0.054095 0.093199 0.094039 -vn -0.248013 -0.420555 -0.872710 -v 0.054263 0.093090 0.094016 -vn 0.352063 -0.888135 0.295411 -v 0.054733 0.092719 0.094944 -vn 0.352061 -0.784429 0.510612 -v 0.054733 0.092802 0.095117 -vn 0.119673 -0.836022 0.535486 -v 0.054548 0.092761 0.095137 -vn 0.458213 -0.280981 -0.843262 -v 0.054811 0.093199 0.094039 -vn 0.648828 -0.178910 -0.739604 -v 0.054964 0.093280 0.094121 -vn 0.801929 -0.066698 -0.593684 -v 0.055087 0.093370 0.094236 -vn 0.908958 0.049196 -0.413976 -v 0.055174 0.093462 0.094380 -vn 0.963990 0.162192 -0.210755 -v 0.055218 0.093553 0.094543 -vn 0.963990 0.265900 0.004451 -v 0.055218 0.093636 0.094715 -vn 0.908959 0.354451 0.219447 -v 0.055174 0.093707 0.094887 -vn 0.248016 -0.420570 -0.872702 -v 0.054643 0.093090 0.094016 -vn 0.119673 0.939733 -0.320280 -v 0.054548 0.094171 0.094457 -vn 0.352056 0.888140 -0.295404 -v 0.054733 0.094130 0.094477 -vn -0.112847 0.989819 -0.086741 -v 0.054364 0.094211 0.094644 -vn -0.352069 0.888136 -0.295400 -v 0.054174 0.094130 0.094477 -vn -0.563999 0.684222 -0.462327 -v 0.054005 0.093967 0.094343 -vn -0.700730 0.406610 -0.586214 -v 0.053897 0.093746 0.094243 -vn -0.731326 0.101012 -0.674506 -v 0.053874 0.093502 0.094172 -vn -0.648835 -0.178906 -0.739599 -v 0.053942 0.093280 0.094121 -vn -0.471923 -0.382756 -0.794221 -v 0.054084 0.093119 0.094077 -vn -0.240801 -0.474013 -0.846951 -v 0.054269 0.093049 0.094036 -vn 0.471931 -0.382751 -0.794219 -v 0.054822 0.093119 0.094077 -vn 0.668251 -0.322982 -0.670166 -v 0.054980 0.093167 0.094175 -vn 0.825924 -0.244760 -0.507880 -v 0.055106 0.093229 0.094304 -vn 0.936160 -0.152631 -0.316716 -v 0.055195 0.093302 0.094457 -vn 0.992841 -0.051860 -0.107600 -v 0.055241 0.093383 0.094624 -vn 0.992840 0.051860 0.107604 -v 0.055241 0.093466 0.094797 -vn 0.936161 0.152630 0.316711 -v 0.055195 0.093547 0.094964 -vn 0.825925 0.244754 0.507881 -v 0.055106 0.093620 0.095117 -vn 0.240812 -0.474012 -0.846949 -v 0.054638 0.093049 0.094036 -vn 0.331966 0.941165 -0.063295 -v 0.054716 0.094172 0.094663 -vn 0.531796 0.846686 -0.017757 -v 0.054875 0.094097 0.094699 -vn -0.099551 0.983365 0.151928 -v 0.054374 0.094205 0.094835 -vn -0.331966 0.941165 -0.063295 -v 0.054190 0.094172 0.094663 -vn -0.563991 0.787936 -0.247126 -v 0.054005 0.094051 0.094515 -vn -0.743150 0.541242 -0.393427 -v 0.053863 0.093854 0.094397 -vn -0.828927 0.239287 -0.505590 -v 0.053796 0.093613 0.094307 -vn -0.801931 -0.066700 -0.593681 -v 0.053819 0.093370 0.094236 -vn -0.668259 -0.322980 -0.670159 -v 0.053927 0.093167 0.094175 -vn -0.458223 -0.484498 -0.745180 -v 0.054095 0.093040 0.094116 -vn -0.219592 -0.524426 -0.822652 -v 0.054285 0.093010 0.094054 -vn -0.112840 -0.684560 0.720170 -v 0.054364 0.092883 0.095284 -vn -0.099556 -0.493852 0.863828 -v 0.054374 0.093036 0.095399 -vn -0.292887 -0.450927 0.843138 -v 0.054221 0.093070 0.095382 -vn 0.458217 -0.484502 -0.745181 -v 0.054811 0.093040 0.094116 -vn 0.648835 -0.467026 -0.600749 -v 0.054964 0.093053 0.094230 -vn 0.801925 -0.422813 -0.422072 -v 0.055087 0.093088 0.094372 -vn 0.908958 -0.354455 -0.219447 -v 0.055174 0.093142 0.094534 -vn 0.963991 -0.265899 -0.004448 -v 0.055218 0.093213 0.094706 -vn 0.963991 -0.162193 0.210750 -v 0.055218 0.093296 0.094879 -vn 0.908958 -0.049195 0.413976 -v 0.055174 0.093387 0.095041 -vn 0.801926 0.066694 0.593689 -v 0.055087 0.093480 0.095185 -vn 0.648832 0.178912 0.739600 -v 0.054964 0.093569 0.095301 -vn 0.219581 -0.524428 -0.822654 -v 0.054621 0.093010 0.094054 -vn 0.469181 0.857083 0.212786 -v 0.054824 0.094105 0.094883 -vn 0.618208 0.738150 0.270100 -v 0.054942 0.094011 0.094929 -vn -0.080549 0.920568 0.382187 -v 0.054390 0.094154 0.095019 -vn -0.292879 0.940438 0.172619 -v 0.054221 0.094171 0.094852 -vn -0.531795 0.846687 -0.017763 -v 0.054031 0.094097 0.094699 -vn -0.743151 0.644953 -0.178219 -v 0.053863 0.093937 0.094570 -vn -0.879115 0.363796 -0.307913 -v 0.053755 0.093713 0.094465 -vn -0.908955 0.049193 -0.413982 -v 0.053732 0.093462 0.094380 -vn -0.825924 -0.244757 -0.507881 -v 0.053800 0.093229 0.094304 -vn -0.648834 -0.467031 -0.600747 -v 0.053942 0.093053 0.094230 -vn -0.417874 -0.580316 -0.699010 -v 0.054126 0.092965 0.094152 -vn -0.185634 -0.568739 -0.801296 -v 0.054311 0.092976 0.094071 -vn -0.236969 -0.239905 0.941430 -v 0.054266 0.093239 0.095460 -vn -0.379621 -0.172462 0.908925 -v 0.054154 0.093292 0.095434 -vn 0.417871 -0.580320 -0.699008 -v 0.054780 0.092965 0.094152 -vn 0.591702 -0.602728 -0.535358 -v 0.054919 0.092946 0.094281 -vn 0.731317 -0.590531 -0.341245 -v 0.055032 0.092955 0.094436 -vn 0.828928 -0.544552 -0.127834 -v 0.055110 0.092992 0.094607 -vn 0.879116 -0.467506 0.092702 -v 0.055151 0.093053 0.094783 -vn 0.879117 -0.363793 0.307908 -v 0.055151 0.093136 0.094956 -vn 0.828928 -0.239281 0.505591 -v 0.055110 0.093236 0.095114 -vn 0.731323 -0.101011 0.674510 -v 0.055032 0.093347 0.095249 -vn 0.591705 0.043204 0.804996 -v 0.054919 0.093462 0.095352 -vn 0.417869 0.185183 0.889434 -v 0.054780 0.093575 0.095418 -vn 0.185626 -0.568741 -0.801297 -v 0.054595 0.092976 0.094071 -vn 0.500186 0.722170 0.477791 -v 0.054847 0.093997 0.095094 -vn 0.591702 0.602728 0.535358 -v 0.054919 0.093903 0.095140 -vn -0.056876 0.804793 0.590825 -v 0.054409 0.094060 0.095185 -vn -0.236969 0.885836 0.398923 -v 0.054266 0.094126 0.095032 -vn -0.469182 0.857081 0.212791 -v 0.054082 0.094105 0.094883 -vn -0.700727 0.711866 0.047208 -v 0.053897 0.093990 0.094751 -vn -0.879116 0.467506 -0.092705 -v 0.053755 0.093796 0.094638 -vn -0.963990 0.162190 -0.210755 -v 0.053688 0.093553 0.094543 -vn -0.936158 -0.152630 -0.316720 -v 0.053711 0.093302 0.094457 -vn -0.801924 -0.422812 -0.422076 -v 0.053819 0.093088 0.094372 -vn -0.591701 -0.602730 -0.535356 -v 0.053987 0.092946 0.094281 -vn -0.353244 -0.664668 -0.658358 -v 0.054177 0.092899 0.094183 -vn -0.140919 -0.604424 -0.784100 -v 0.054345 0.092949 0.094084 -vn -0.268089 0.032874 0.962833 -v 0.054243 0.093456 0.095476 -vn -0.353251 0.100840 0.930078 -v 0.054177 0.093509 0.095450 -vn 0.417872 0.580322 0.699006 -v 0.054780 0.093884 0.095270 -vn 0.458205 0.484500 0.745190 -v 0.054811 0.093809 0.095306 -vn -0.029860 0.642380 0.765805 -v 0.054430 0.093929 0.095323 -vn -0.167329 0.780275 0.602637 -v 0.054322 0.094041 0.095194 -vn -0.379604 0.818406 0.431407 -v 0.054154 0.094073 0.095058 -vn -0.618210 0.738147 0.270102 -v 0.053964 0.094011 0.094929 -vn -0.828927 0.544554 0.127836 -v 0.053796 0.093858 0.094814 -vn -0.963990 0.265901 0.004449 -v 0.053688 0.093636 0.094715 -vn -0.992841 -0.051858 -0.107599 -v 0.053665 0.093383 0.094624 -vn -0.908957 -0.354457 -0.219449 -v 0.053732 0.093142 0.094534 -vn -0.731318 -0.590531 -0.341245 -v 0.053874 0.092955 0.094436 -vn -0.500191 -0.722166 -0.477793 -v 0.054059 0.092852 0.094327 -vn -0.268081 -0.732637 -0.625601 -v 0.054243 0.092846 0.094209 -vn -0.087929 -0.629480 -0.772025 -v 0.054386 0.092930 0.094093 -vn 0.292885 -0.940438 -0.172612 -v 0.054685 0.092678 0.094570 -vn 0.331966 -0.941165 0.063295 -v 0.054716 0.092677 0.094758 -vn 0.112846 -0.989819 0.086748 -v 0.054543 0.092639 0.094777 -vn 0.119673 -0.939733 0.320280 -v 0.054548 0.092678 0.094964 -vn -0.119671 -0.939733 0.320283 -v 0.054358 0.092678 0.094964 -vn -0.119672 -0.836023 0.535485 -v 0.054358 0.092761 0.095137 -vn -0.352067 -0.784425 0.510614 -v 0.054174 0.092802 0.095117 -vn -0.331967 -0.635906 0.696722 -v 0.054190 0.092922 0.095266 -vn -0.531793 -0.541423 0.651197 -v 0.054031 0.092997 0.095230 -vn -0.469173 -0.367571 0.802975 -v 0.054082 0.093136 0.095350 -vn -0.618213 -0.248626 0.745653 -v 0.053964 0.093230 0.095305 -vn -0.500185 -0.076230 0.862557 -v 0.054059 0.093368 0.095398 -vn -0.591704 0.043205 0.804997 -v 0.053987 0.093462 0.095352 -vn -0.417867 0.185167 0.889438 -v 0.054126 0.093575 0.095418 -vn -0.458216 0.281017 0.843248 -v 0.054095 0.093650 0.095382 -vn -0.240792 0.367088 0.898479 -v 0.054269 0.093718 0.095425 -vn -0.248022 0.420622 0.872675 -v 0.054263 0.093759 0.095405 -vn -0.140922 0.236708 0.961307 -v 0.054345 0.093618 0.095473 -vn -0.167349 -0.014767 0.985787 -v 0.054322 0.093419 0.095494 -vn -0.087926 0.211671 0.973378 -v 0.054386 0.093599 0.095482 -vn -0.080546 -0.274631 0.958170 -v 0.054390 0.093212 0.095473 -vn -0.056860 -0.039282 0.997609 -v 0.054409 0.093400 0.095503 -vn -0.041694 0.183330 0.982167 -v 0.054430 0.093589 0.095487 -vn 0.041705 0.183333 0.982166 -v 0.054476 0.093589 0.095487 -vn 0.056871 -0.039282 0.997608 -v 0.054498 0.093400 0.095503 -vn 0.080551 -0.274627 0.958171 -v 0.054517 0.093212 0.095473 -vn 0.099556 -0.493851 0.863828 -v 0.054532 0.093036 0.095399 -vn 0.112838 -0.684563 0.720167 -v 0.054543 0.092883 0.095284 -vn 0.331962 -0.635912 0.696718 -v 0.054716 0.092922 0.095266 -vn 0.292889 -0.450918 0.843143 -v 0.054685 0.093070 0.095382 -vn 0.236966 -0.239907 0.941431 -v 0.054640 0.093239 0.095460 -vn 0.167333 -0.014773 0.985790 -v 0.054584 0.093419 0.095494 -vn 0.087914 0.211664 0.973380 -v 0.054520 0.093599 0.095482 -vn 0.353251 -0.664663 -0.658360 -v 0.054729 0.092899 0.094183 -vn 0.379613 -0.818397 -0.431417 -v 0.054752 0.092776 0.094363 -vn 0.500196 -0.722165 -0.477789 -v 0.054847 0.092852 0.094327 -vn 0.469182 -0.857082 -0.212789 -v 0.054824 0.092744 0.094538 -vn 0.618206 -0.738151 -0.270100 -v 0.054942 0.092839 0.094492 -vn 0.531798 -0.846685 0.017761 -v 0.054875 0.092752 0.094722 -vn 0.700726 -0.711867 -0.047208 -v 0.055009 0.092859 0.094671 -vn 0.564000 -0.787931 0.247121 -v 0.054901 0.092799 0.094906 -vn 0.743148 -0.644958 0.178214 -v 0.055043 0.092912 0.094851 -vn 0.563996 -0.684227 0.462322 -v 0.054901 0.092882 0.095078 -vn 0.743149 -0.541247 0.393421 -v 0.055043 0.092995 0.095024 -vn 0.531804 -0.541411 0.651198 -v 0.054875 0.092997 0.095230 -vn 0.700723 -0.406611 0.586221 -v 0.055009 0.093103 0.095178 -vn 0.469178 -0.367571 0.802972 -v 0.054824 0.093136 0.095350 -vn 0.618209 -0.248633 0.745653 -v 0.054942 0.093230 0.095305 -vn 0.379613 -0.172467 0.908928 -v 0.054752 0.093292 0.095434 -vn 0.500196 -0.076228 0.862550 -v 0.054847 0.093368 0.095398 -vn 0.268095 0.032874 0.962832 -v 0.054663 0.093456 0.095476 -vn 0.353246 0.100840 0.930080 -v 0.054729 0.093509 0.095450 -vn 0.140922 0.236718 0.961304 -v 0.054561 0.093618 0.095473 -vn 0.185655 0.272436 0.944093 -v 0.054595 0.093646 0.095460 -vn 0.219605 0.316711 0.922750 -v 0.054621 0.093680 0.095443 -vn 0.240795 0.367071 0.898486 -v 0.054638 0.093718 0.095425 -vn 0.458214 0.280997 0.843256 -v 0.054811 0.093650 0.095382 -vn 0.471936 0.382756 0.794213 -v 0.054822 0.093730 0.095344 -vn 0.668247 0.322971 0.670176 -v 0.054980 0.093683 0.095246 -vn 0.648834 0.467026 0.600751 -v 0.054964 0.093796 0.095191 -vn 0.801922 0.422820 0.422072 -v 0.055087 0.093761 0.095049 -vn 0.731319 0.590533 0.341238 -v 0.055032 0.093894 0.094985 -vn 0.828926 0.544554 0.127837 -v 0.055110 0.093858 0.094814 -vn 0.700727 0.711866 0.047204 -v 0.055009 0.093990 0.094751 -vn 0.743148 0.644956 -0.178219 -v 0.055043 0.093937 0.094570 -vn 0.563998 0.787932 -0.247124 -v 0.054901 0.094051 0.094515 -vn 0.564001 0.684219 -0.462328 -v 0.054901 0.093967 0.094343 -vn 0.352059 0.784426 -0.510618 -v 0.054733 0.094047 0.094304 -vn 0.331966 0.635899 -0.696729 -v 0.054716 0.093928 0.094156 -vn 0.112835 0.684561 -0.720170 -v 0.054543 0.093966 0.094137 -vn 0.099563 0.493849 -0.863829 -v 0.054532 0.093813 0.094023 -vn -0.099566 0.493854 -0.863826 -v 0.054374 0.093813 0.094023 -vn -0.080547 0.274630 -0.958171 -v 0.054390 0.093638 0.093948 -vn -0.236971 0.239908 -0.941429 -v 0.054266 0.093610 0.093961 -vn -0.167346 0.014759 -0.985788 -v 0.054322 0.093430 0.093927 -vn -0.268091 -0.032873 -0.962833 -v 0.054243 0.093393 0.093945 -vn -0.140922 -0.236710 -0.961306 -v 0.054345 0.093231 0.093948 -vn -0.185609 -0.272383 -0.944117 -v 0.054311 0.093203 0.093961 -vn 0.219622 0.524372 0.822679 -v 0.054621 0.093839 0.095367 -vn 0.353269 0.664649 0.658364 -v 0.054729 0.093950 0.095238 -vn 0.185626 0.568741 0.801297 -v 0.054595 0.093873 0.095350 -vn 0.379609 0.818404 0.431408 -v 0.054752 0.094073 0.095058 -vn 0.268077 0.732639 0.625599 -v 0.054663 0.094003 0.095212 -vn 0.140918 0.604433 0.784094 -v 0.054561 0.093900 0.095337 -vn 0.292887 0.940436 0.172618 -v 0.054685 0.094171 0.094852 -vn 0.236961 0.885840 0.398920 -v 0.054640 0.094126 0.095032 -vn 0.167329 0.780270 0.602645 -v 0.054584 0.094041 0.095194 -vn 0.087943 0.629477 0.772026 -v 0.054520 0.093919 0.095328 -vn 0.112846 0.989819 -0.086748 -v 0.054543 0.094211 0.094644 -vn 0.099550 0.983365 0.151933 -v 0.054532 0.094205 0.094835 -vn 0.080553 0.920569 0.382182 -v 0.054517 0.094154 0.095019 -vn 0.056874 0.804793 0.590825 -v 0.054498 0.094060 0.095185 -vn 0.029857 0.642376 0.765808 -v 0.054476 0.093929 0.095323 -vn -0.087929 0.629480 0.772025 -v 0.054386 0.093919 0.095328 -vn -0.268082 0.732642 0.625594 -v 0.054243 0.094003 0.095212 -vn -0.500187 0.722172 0.477787 -v 0.054059 0.093997 0.095094 -vn -0.731320 0.590532 0.341239 -v 0.053874 0.093894 0.094985 -vn -0.908956 0.354455 0.219453 -v 0.053732 0.093707 0.094887 -vn -0.992840 0.051856 0.107605 -v 0.053665 0.093466 0.094797 -vn -0.963990 -0.265901 -0.004446 -v 0.053688 0.093213 0.094706 -vn -0.828927 -0.544553 -0.127832 -v 0.053796 0.092992 0.094607 -vn -0.618212 -0.738147 -0.270100 -v 0.053964 0.092839 0.094492 -vn -0.379610 -0.818396 -0.431421 -v 0.054154 0.092776 0.094363 -vn -0.167347 -0.780262 -0.602649 -v 0.054322 0.092809 0.094227 -vn -0.140919 0.604424 0.784100 -v 0.054345 0.093900 0.095337 -vn -0.353254 0.664651 0.658370 -v 0.054177 0.093950 0.095238 -vn -0.591701 0.602729 0.535358 -v 0.053987 0.093903 0.095140 -vn -0.801924 0.422816 0.422072 -v 0.053819 0.093761 0.095049 -vn -0.936161 0.152629 0.316714 -v 0.053711 0.093547 0.094964 -vn -0.963992 -0.162189 0.210748 -v 0.053688 0.093296 0.094879 -vn -0.879116 -0.467506 0.092700 -v 0.053755 0.093053 0.094783 -vn -0.700728 -0.711865 -0.047214 -v 0.053897 0.092859 0.094671 -vn -0.469183 -0.857080 -0.212793 -v 0.054082 0.092744 0.094538 -vn -0.236970 -0.885835 -0.398925 -v 0.054266 0.092723 0.094389 -vn -0.056894 -0.804779 -0.590842 -v 0.054409 0.092789 0.094236 -vn 0.087946 -0.629472 -0.772030 -v 0.054520 0.092930 0.094093 -vn 0.056895 -0.804783 -0.590836 -v 0.054498 0.092789 0.094236 -vn -0.080549 -0.920570 -0.382181 -v 0.054390 0.092696 0.094402 -vn -0.292877 -0.940441 -0.172611 -v 0.054221 0.092678 0.094570 -vn -0.531794 -0.846687 0.017769 -v 0.054031 0.092752 0.094722 -vn -0.743151 -0.644955 0.178214 -v 0.053863 0.092912 0.094851 -vn -0.879116 -0.363796 0.307908 -v 0.053755 0.093136 0.094956 -vn -0.908958 -0.049190 0.413975 -v 0.053732 0.093387 0.095041 -vn -0.825928 0.244757 0.507876 -v 0.053800 0.093620 0.095117 -vn -0.648830 0.467034 0.600749 -v 0.053942 0.093796 0.095191 -vn -0.417881 0.580316 0.699006 -v 0.054126 0.093884 0.095270 -vn -0.185642 0.568738 0.801295 -v 0.054311 0.093873 0.095350 -vn -0.668248 0.322967 0.670177 -v 0.053927 0.093683 0.095246 -vn -0.458210 0.484497 0.745189 -v 0.054095 0.093809 0.095306 -vn -0.219612 0.524383 0.822674 -v 0.054285 0.093839 0.095367 -vn 0.236960 -0.885839 -0.398923 -v 0.054640 0.092723 0.094389 -vn 0.080556 -0.920570 -0.382180 -v 0.054517 0.092696 0.094402 -vn 0.099550 -0.983366 -0.151928 -v 0.054532 0.092644 0.094586 -vn -0.099551 -0.983366 -0.151923 -v 0.054374 0.092644 0.094586 -vn -0.112847 -0.989819 0.086741 -v 0.054364 0.092639 0.094777 -vn -0.331967 -0.941165 0.063295 -v 0.054190 0.092677 0.094758 -vn -0.352071 -0.888134 0.295405 -v 0.054174 0.092719 0.094944 -vn -0.563995 -0.787935 0.247119 -v 0.054005 0.092799 0.094906 -vn -0.563994 -0.684226 0.462326 -v 0.054005 0.092882 0.095078 -vn -0.743151 -0.541245 0.393422 -v 0.053863 0.092995 0.095024 -vn -0.700731 -0.406606 0.586215 -v 0.053897 0.093103 0.095178 -vn -0.828923 -0.239285 0.505598 -v 0.053796 0.093236 0.095114 -vn -0.731329 -0.101008 0.674504 -v 0.053874 0.093347 0.095249 -vn -0.801920 0.066694 0.593697 -v 0.053819 0.093480 0.095185 -vn -0.648837 0.178904 0.739597 -v 0.053942 0.093569 0.095301 -vn -0.471928 0.382752 0.794220 -v 0.054084 0.093730 0.095344 -vn -0.240825 0.474002 0.846950 -v 0.054269 0.093800 0.095385 -vn 0.247999 0.944527 0.215326 -v 0.054643 0.092161 0.093276 -vn 0.240804 0.957723 0.157415 -v 0.054638 0.092171 0.093231 -vn 0.000002 0.975880 0.218308 -v 0.054453 0.092183 0.093281 -vn -0.219625 0.918922 0.327638 -v 0.054285 0.092141 0.093362 -vn -0.185637 0.907973 0.375664 -v 0.054311 0.092133 0.093398 -vn -0.056862 -0.755470 -0.652711 -v 0.054409 0.090805 0.092591 -vn -0.029872 -0.889808 -0.455356 -v 0.054430 0.090700 0.092749 -vn -0.087936 -0.892988 -0.441407 -v 0.054386 0.090697 0.092760 -vn -0.000001 -0.974082 -0.226196 -v 0.054453 0.090635 0.092928 -vn 0.029876 -0.889808 -0.455357 -v 0.054476 0.090700 0.092749 -vn 0.041762 -0.998312 0.040364 -v 0.054476 0.090616 0.093117 -vn -0.041757 -0.998313 0.040353 -v 0.054430 0.090616 0.093117 -vn 0.140945 -0.989883 -0.016337 -v 0.054561 0.090623 0.093085 -vn 0.268100 -0.945904 0.182722 -v 0.054663 0.090656 0.093244 -vn 0.167338 -0.957657 0.234288 -v 0.054584 0.090647 0.093284 -vn 0.056870 -0.755467 -0.652714 -v 0.054498 0.090805 0.092591 -vn 0.080546 -0.577897 -0.812125 -v 0.054517 0.090946 0.092463 -vn 0.087937 -0.892987 -0.441408 -v 0.054520 0.090697 0.092760 -vn 0.167334 -0.761516 -0.626173 -v 0.054584 0.090800 0.092612 -vn 0.236955 -0.586463 -0.774541 -v 0.054640 0.090939 0.092492 -vn 0.292869 -0.378037 -0.878246 -v 0.054685 0.091105 0.092408 -vn 0.140896 -0.899167 -0.414302 -v 0.054561 0.090692 0.092780 -vn 0.268089 -0.773267 -0.574618 -v 0.054663 0.090791 0.092652 -vn 0.379612 -0.603109 -0.701537 -v 0.054752 0.090926 0.092550 -vn 0.469182 -0.398608 -0.788023 -v 0.054824 0.091089 0.092480 -vn 0.531804 -0.171541 -0.829312 -v 0.054875 0.091271 0.092446 -vn 0.185645 -0.907974 -0.375658 -v 0.054595 0.090686 0.092810 -vn 0.353251 -0.790036 -0.501056 -v 0.054729 0.090778 0.092709 -vn 0.500204 -0.626850 -0.597374 -v 0.054847 0.090907 0.092632 -vn 0.618217 -0.427949 -0.659293 -v 0.054942 0.091066 0.092582 -vn 0.700732 -0.204806 -0.683395 -v 0.055009 0.091244 0.092562 -vn 0.743153 0.029865 -0.668455 -v 0.055043 0.091432 0.092573 -vn 0.219610 -0.918919 -0.327656 -v 0.054621 0.090677 0.092847 -vn 0.417885 -0.810845 -0.409760 -v 0.054780 0.090762 0.092781 -vn 0.591703 -0.656316 -0.468122 -v 0.054919 0.090884 0.092734 -vn 0.731319 -0.464368 -0.499535 -v 0.055032 0.091037 0.092708 -vn 0.828931 -0.246077 -0.502313 -v 0.055110 0.091211 0.092705 -vn 0.879116 -0.013912 -0.476406 -v 0.055151 0.091397 0.092726 -vn 0.879118 0.218996 -0.423310 -v 0.055151 0.091584 0.092768 -vn 0.240827 -0.931331 -0.273177 -v 0.054638 0.090668 0.092889 -vn -0.240821 -0.931330 -0.273184 -v 0.054269 0.090668 0.092889 -vn -0.219625 -0.918922 -0.327638 -v 0.054285 0.090677 0.092847 -vn -0.417895 -0.810840 -0.409758 -v 0.054126 0.090762 0.092781 -vn -0.353251 -0.790036 -0.501055 -v 0.054177 0.090778 0.092709 -vn -0.500209 -0.626847 -0.597373 -v 0.054059 0.090907 0.092632 -vn -0.379614 -0.603108 -0.701537 -v 0.054154 0.090926 0.092550 -vn -0.469180 -0.398608 -0.788024 -v 0.054082 0.091089 0.092480 -vn -0.292869 -0.378039 -0.878245 -v 0.054221 0.091105 0.092408 -vn -0.331968 -0.148230 -0.931571 -v 0.054190 0.091289 0.092365 -vn -0.112844 -0.136240 -0.984228 -v 0.054364 0.091299 0.092323 -vn -0.119677 0.102591 -0.987498 -v 0.054358 0.091490 0.092320 -vn 0.119678 0.102592 -0.987498 -v 0.054548 0.091490 0.092320 -vn -0.119680 0.335515 -0.934402 -v 0.054358 0.091676 0.092363 -vn -0.352076 0.089868 -0.931647 -v 0.054174 0.091480 0.092364 -vn -0.531801 -0.171539 -0.829314 -v 0.054031 0.091271 0.092446 -vn -0.618215 -0.427960 -0.659288 -v 0.053964 0.091066 0.092582 -vn -0.591695 -0.656316 -0.468131 -v 0.053987 0.090884 0.092734 -vn -0.458215 -0.834487 -0.306056 -v 0.054095 0.090743 0.092862 -vn -0.248013 -0.944527 -0.215310 -v 0.054263 0.090658 0.092933 -vn 0.352056 -0.322786 0.878559 -v 0.054733 0.091152 0.093802 -vn 0.352068 -0.089866 0.931650 -v 0.054733 0.091339 0.093844 -vn 0.119677 -0.102595 0.987498 -v 0.054548 0.091329 0.093888 -vn 0.458217 -0.834487 -0.306053 -v 0.054811 0.090743 0.092862 -vn 0.648823 -0.689800 -0.321257 -v 0.054964 0.090858 0.092849 -vn 0.801925 -0.505753 -0.318009 -v 0.055087 0.091004 0.092852 -vn 0.908959 -0.292976 -0.296578 -v 0.055174 0.091174 0.092868 -vn 0.963990 -0.063652 -0.258210 -v 0.055218 0.091358 0.092899 -vn 0.963988 0.169270 -0.205122 -v 0.055218 0.091544 0.092942 -vn 0.908959 0.392569 -0.140296 -v 0.055174 0.091723 0.092994 -vn 0.248011 -0.944523 -0.215331 -v 0.054643 0.090658 0.092933 -vn 0.119676 0.335509 -0.934404 -v 0.054548 0.091676 0.092363 -vn 0.352066 0.322772 -0.878560 -v 0.054733 0.091666 0.092407 -vn -0.112838 0.549324 -0.827956 -v 0.054364 0.091848 0.092448 -vn -0.352066 0.322770 -0.878561 -v 0.054174 0.091666 0.092407 -vn -0.564000 0.065143 -0.823202 -v 0.054005 0.091460 0.092451 -vn -0.700735 -0.204799 -0.683395 -v 0.053897 0.091244 0.092562 -vn -0.731322 -0.464370 -0.499528 -v 0.053874 0.091037 0.092708 -vn -0.648821 -0.689798 -0.321263 -v 0.053942 0.090858 0.092849 -vn -0.471929 -0.859583 -0.195960 -v 0.054084 0.090724 0.092948 -vn -0.240816 -0.957717 -0.157438 -v 0.054269 0.090647 0.092977 -vn 0.471941 -0.859576 -0.195963 -v 0.054822 0.090724 0.092948 -vn 0.668248 -0.725335 -0.165332 -v 0.054980 0.090830 0.092972 -vn 0.825925 -0.549681 -0.125293 -v 0.055106 0.090969 0.093004 -vn 0.936160 -0.342783 -0.078135 -v 0.055195 0.091135 0.093042 -vn 0.992840 -0.116464 -0.026546 -v 0.055241 0.091316 0.093083 -vn 0.992840 0.116462 0.026548 -v 0.055241 0.091503 0.093126 -vn 0.936162 0.342777 0.078137 -v 0.055195 0.091684 0.093167 -vn 0.825927 0.549679 0.125295 -v 0.055106 0.091849 0.093205 -vn 0.240804 -0.957723 -0.157415 -v 0.054638 0.090647 0.092977 -vn 0.331973 0.537313 -0.775299 -v 0.054716 0.091838 0.092490 -vn 0.531799 0.514016 -0.673036 -v 0.054875 0.091820 0.092571 -vn -0.099553 0.731903 -0.674097 -v 0.054374 0.091993 0.092572 -vn -0.331965 0.537315 -0.775301 -v 0.054190 0.091838 0.092490 -vn -0.563992 0.298050 -0.770116 -v 0.054005 0.091647 0.092493 -vn -0.743152 0.029859 -0.668456 -v 0.053863 0.091432 0.092573 -vn -0.828931 -0.246079 -0.502314 -v 0.053796 0.091211 0.092705 -vn -0.801928 -0.505749 -0.318009 -v 0.053819 0.091004 0.092852 -vn -0.668252 -0.725330 -0.165334 -v 0.053927 0.090830 0.092972 -vn -0.458215 -0.884685 -0.085860 -v 0.054095 0.090704 0.093034 -vn -0.219591 -0.970148 -0.102922 -v 0.054285 0.090638 0.093019 -vn -0.112842 0.136239 0.984228 -v 0.054364 0.091520 0.093885 -vn -0.099544 0.367453 0.924699 -v 0.054374 0.091705 0.093837 -vn -0.292866 0.378043 0.878244 -v 0.054221 0.091713 0.093800 -vn 0.458225 -0.884681 -0.085846 -v 0.054811 0.090704 0.093034 -vn 0.648834 -0.760871 -0.009422 -v 0.054964 0.090802 0.093095 -vn 0.801928 -0.593606 0.067410 -v 0.055087 0.090935 0.093157 -vn 0.908961 -0.392567 0.140293 -v 0.055174 0.091095 0.093215 -vn 0.963989 -0.169263 0.205121 -v 0.055218 0.091274 0.093267 -vn 0.963990 0.063650 0.258209 -v 0.055218 0.091461 0.093309 -vn 0.908959 0.292979 0.296577 -v 0.055174 0.091644 0.093340 -vn 0.801927 0.505742 0.318023 -v 0.055087 0.091814 0.093357 -vn 0.648822 0.689799 0.321259 -v 0.054964 0.091961 0.093359 -vn 0.219591 -0.970148 -0.102919 -v 0.054621 0.090638 0.093019 -vn 0.469184 0.700743 -0.537425 -v 0.054824 0.091969 0.092680 -vn 0.618214 0.671402 -0.408694 -v 0.054942 0.091945 0.092782 -vn -0.080544 0.872772 -0.481437 -v 0.054390 0.092105 0.092727 -vn -0.292882 0.721311 -0.627639 -v 0.054221 0.091985 0.092609 -vn -0.531799 0.514015 -0.673037 -v 0.054031 0.091820 0.092571 -vn -0.743155 0.262773 -0.615362 -v 0.053863 0.091619 0.092616 -vn -0.879116 -0.013912 -0.476405 -v 0.053755 0.091397 0.092726 -vn -0.908957 -0.292985 -0.296575 -v 0.053732 0.091174 0.092868 -vn -0.825929 -0.549675 -0.125293 -v 0.053800 0.090969 0.093004 -vn -0.648839 -0.760868 -0.009407 -v 0.053942 0.090802 0.093095 -vn -0.417861 -0.908334 0.017922 -v 0.054126 0.090686 0.093115 -vn -0.185671 -0.981073 -0.054971 -v 0.054311 0.090630 0.093056 -vn -0.236953 0.586467 0.774538 -v 0.054266 0.091879 0.093716 -vn -0.379601 0.603108 0.701545 -v 0.054154 0.091892 0.093659 -vn 0.417856 -0.908337 0.017908 -v 0.054780 0.090686 0.093115 -vn 0.591706 -0.794350 0.137450 -v 0.054919 0.090775 0.093211 -vn 0.731315 -0.634992 0.248925 -v 0.055032 0.090902 0.093300 -vn 0.828932 -0.439466 0.346036 -v 0.055110 0.091058 0.093378 -vn 0.879119 -0.218996 0.423308 -v 0.055151 0.091235 0.093440 -vn 0.879116 0.013910 0.476406 -v 0.055151 0.091421 0.093483 -vn 0.828929 0.246090 0.502311 -v 0.055110 0.091607 0.093503 -vn 0.731325 0.464366 0.499528 -v 0.055032 0.091782 0.093501 -vn 0.591708 0.656318 0.468111 -v 0.054919 0.091934 0.093475 -vn 0.417879 0.810852 0.409753 -v 0.054780 0.092057 0.093428 -vn 0.185669 -0.981074 -0.054959 -v 0.054595 0.090630 0.093056 -vn 0.500204 0.823811 -0.266706 -v 0.054847 0.092066 0.092896 -vn 0.591719 0.794342 -0.137437 -v 0.054919 0.092043 0.092998 -vn -0.056876 0.963708 -0.260829 -v 0.054409 0.092176 0.092903 -vn -0.236966 0.864201 -0.443850 -v 0.054266 0.092098 0.092756 -vn -0.469180 0.700745 -0.537426 -v 0.054082 0.091969 0.092680 -vn -0.700724 0.480750 -0.527129 -v 0.053897 0.091793 0.092687 -vn -0.879118 0.218995 -0.423311 -v 0.053755 0.091584 0.092768 -vn -0.963990 -0.063651 -0.258208 -v 0.053688 0.091358 0.092899 -vn -0.936158 -0.342786 -0.078141 -v 0.053711 0.091135 0.093042 -vn -0.801926 -0.593608 0.067412 -v 0.053819 0.090935 0.093157 -vn -0.591703 -0.794351 0.137456 -v 0.053987 0.090775 0.093211 -vn -0.353248 -0.929136 0.109190 -v 0.054177 0.090669 0.093187 -vn -0.140934 -0.989884 -0.016340 -v 0.054345 0.090623 0.093085 -vn -0.268063 0.773269 0.574628 -v 0.054243 0.092027 0.093557 -vn -0.353241 0.790042 0.501054 -v 0.054177 0.092040 0.093499 -vn 0.417876 0.908328 -0.017879 -v 0.054780 0.092133 0.093093 -vn 0.458215 0.884689 0.085815 -v 0.054811 0.092114 0.093174 -vn -0.029893 0.999247 -0.024752 -v 0.054430 0.092203 0.093092 -vn -0.167343 0.957655 -0.234293 -v 0.054322 0.092171 0.092924 -vn -0.379607 0.847558 -0.370868 -v 0.054154 0.092085 0.092814 -vn -0.618215 0.671403 -0.408690 -v 0.053964 0.091945 0.092782 -vn -0.828929 0.439470 -0.346039 -v 0.053796 0.091760 0.092830 -vn -0.963989 0.169264 -0.205124 -v 0.053688 0.091544 0.092942 -vn -0.992840 -0.116463 -0.026550 -v 0.053665 0.091316 0.093083 -vn -0.908957 -0.392576 0.140291 -v 0.053732 0.091095 0.093215 -vn -0.731318 -0.634992 0.248918 -v 0.053874 0.090902 0.093300 -vn -0.500195 -0.823819 0.266696 -v 0.054059 0.090752 0.093313 -vn -0.268101 -0.945903 0.182730 -v 0.054243 0.090656 0.093244 -vn -0.087945 -0.996067 0.010796 -v 0.054386 0.090618 0.093106 -vn 0.292886 -0.721301 0.627648 -v 0.054685 0.090834 0.093600 -vn 0.331962 -0.537318 0.775300 -v 0.054716 0.090980 0.093718 -vn 0.112837 -0.549317 0.827961 -v 0.054543 0.090971 0.093760 -vn 0.119673 -0.335516 0.934402 -v 0.054548 0.091142 0.093846 -vn -0.119675 -0.335517 0.934402 -v 0.054358 0.091142 0.093846 -vn -0.119677 -0.102595 0.987498 -v 0.054358 0.091329 0.093888 -vn -0.352077 -0.089870 0.931647 -v 0.054174 0.091339 0.093844 -vn -0.331967 0.148236 0.931571 -v 0.054190 0.091529 0.093844 -vn -0.531803 0.171539 0.829313 -v 0.054031 0.091548 0.093763 -vn -0.469180 0.398606 0.788025 -v 0.054082 0.091729 0.093729 -vn -0.618228 0.427951 0.659282 -v 0.053964 0.091753 0.093627 -vn -0.500196 0.626850 0.597380 -v 0.054059 0.091911 0.093577 -vn -0.591708 0.656315 0.468116 -v 0.053987 0.091934 0.093475 -vn -0.417883 0.810849 0.409754 -v 0.054126 0.092057 0.093428 -vn -0.458202 0.834485 0.306082 -v 0.054095 0.092075 0.093347 -vn -0.240821 0.931330 0.273184 -v 0.054269 0.092151 0.093320 -vn -0.248001 0.944529 0.215317 -v 0.054263 0.092161 0.093276 -vn -0.140902 0.899164 0.414309 -v 0.054345 0.092126 0.093428 -vn -0.167342 0.761519 0.626168 -v 0.054322 0.092018 0.093597 -vn -0.087942 0.892985 0.441412 -v 0.054386 0.092121 0.093449 -vn -0.080548 0.577895 0.812126 -v 0.054390 0.091873 0.093746 -vn -0.056888 0.755468 0.652711 -v 0.054409 0.092013 0.093618 -vn -0.041740 0.882200 0.469022 -v 0.054430 0.092119 0.093460 -vn 0.041747 0.882203 0.469016 -v 0.054476 0.092119 0.093460 -vn 0.056890 0.755471 0.652708 -v 0.054498 0.092013 0.093618 -vn 0.080546 0.577897 0.812125 -v 0.054517 0.091873 0.093746 -vn 0.099546 0.367448 0.924701 -v 0.054532 0.091705 0.093837 -vn 0.112843 0.136240 0.984228 -v 0.054543 0.091520 0.093885 -vn 0.331965 0.148233 0.931572 -v 0.054716 0.091529 0.093844 -vn 0.292869 0.378041 0.878244 -v 0.054685 0.091713 0.093800 -vn 0.236956 0.586470 0.774535 -v 0.054640 0.091879 0.093716 -vn 0.167339 0.761520 0.626167 -v 0.054584 0.092018 0.093597 -vn 0.087936 0.892984 0.441415 -v 0.054520 0.092121 0.093449 -vn 0.353237 -0.929140 0.109187 -v 0.054729 0.090669 0.093187 -vn 0.379623 -0.847556 0.370857 -v 0.054752 0.090733 0.093395 -vn 0.500197 -0.823815 0.266707 -v 0.054847 0.090752 0.093313 -vn 0.469184 -0.700744 0.537424 -v 0.054824 0.090850 0.093528 -vn 0.618208 -0.671409 0.408692 -v 0.054942 0.090873 0.093427 -vn 0.531789 -0.514020 0.673041 -v 0.054875 0.090999 0.093637 -vn 0.700721 -0.480757 0.527128 -v 0.055009 0.091025 0.093522 -vn 0.563991 -0.298054 0.770116 -v 0.054901 0.091172 0.093715 -vn 0.743158 -0.262765 0.615363 -v 0.055043 0.091200 0.093593 -vn 0.564003 -0.065131 0.823200 -v 0.054901 0.091358 0.093758 -vn 0.743152 -0.029866 0.668456 -v 0.055043 0.091386 0.093635 -vn 0.531806 0.171542 0.829311 -v 0.054875 0.091548 0.093763 -vn 0.700730 0.204803 0.683398 -v 0.055009 0.091574 0.093647 -vn 0.469182 0.398608 0.788023 -v 0.054824 0.091729 0.093729 -vn 0.618221 0.427948 0.659289 -v 0.054942 0.091753 0.093627 -vn 0.379598 0.603106 0.701547 -v 0.054752 0.091892 0.093659 -vn 0.500197 0.626846 0.597384 -v 0.054847 0.091911 0.093577 -vn 0.268065 0.773264 0.574634 -v 0.054663 0.092027 0.093557 -vn 0.353241 0.790045 0.501049 -v 0.054729 0.092040 0.093499 -vn 0.140896 0.899167 0.414302 -v 0.054561 0.092126 0.093428 -vn 0.185645 0.907974 0.375658 -v 0.054595 0.092133 0.093398 -vn 0.219610 0.918919 0.327656 -v 0.054621 0.092141 0.093362 -vn 0.240819 0.931331 0.273181 -v 0.054638 0.092151 0.093320 -vn 0.458212 0.834478 0.306084 -v 0.054811 0.092075 0.093347 -vn 0.471925 0.859585 0.195963 -v 0.054822 0.092095 0.093261 -vn 0.668244 0.725338 0.165333 -v 0.054980 0.091989 0.093236 -vn 0.648831 0.760874 0.009400 -v 0.054964 0.092017 0.093114 -vn 0.801926 0.593607 -0.067423 -v 0.055087 0.091884 0.093052 -vn 0.731315 0.634992 -0.248925 -v 0.055032 0.091916 0.092908 -vn 0.828932 0.439466 -0.346036 -v 0.055110 0.091760 0.092830 -vn 0.700721 0.480757 -0.527128 -v 0.055009 0.091793 0.092687 -vn 0.743158 0.262766 -0.615362 -v 0.055043 0.091619 0.092616 -vn 0.563990 0.298056 -0.770115 -v 0.054901 0.091647 0.092493 -vn 0.564002 0.065138 -0.823201 -v 0.054901 0.091460 0.092451 -vn 0.352068 0.089865 -0.931650 -v 0.054733 0.091480 0.092364 -vn 0.331965 -0.148227 -0.931573 -v 0.054716 0.091289 0.092365 -vn 0.112845 -0.136242 -0.984228 -v 0.054543 0.091299 0.092323 -vn 0.099547 -0.367447 -0.924702 -v 0.054532 0.091114 0.092372 -vn -0.099544 -0.367453 -0.924699 -v 0.054374 0.091114 0.092372 -vn -0.080545 -0.577891 -0.812130 -v 0.054390 0.090946 0.092463 -vn -0.236958 -0.586461 -0.774541 -v 0.054266 0.090939 0.092492 -vn -0.167346 -0.761516 -0.626170 -v 0.054322 0.090800 0.092612 -vn -0.268081 -0.773269 -0.574620 -v 0.054243 0.090791 0.092652 -vn -0.140902 -0.899166 -0.414304 -v 0.054345 0.090692 0.092780 -vn -0.185637 -0.907973 -0.375664 -v 0.054311 0.090686 0.092810 -vn 0.219631 0.970133 0.102978 -v 0.054621 0.092181 0.093190 -vn 0.353234 0.929142 -0.109178 -v 0.054729 0.092149 0.093022 -vn 0.185654 0.981076 0.054981 -v 0.054595 0.092189 0.093153 -vn 0.379604 0.847558 -0.370874 -v 0.054752 0.092085 0.092814 -vn 0.268068 0.945908 -0.182749 -v 0.054663 0.092162 0.092964 -vn 0.140879 0.989893 0.016292 -v 0.054561 0.092196 0.093123 -vn 0.292883 0.721311 -0.627638 -v 0.054685 0.091985 0.092609 -vn 0.236967 0.864201 -0.443851 -v 0.054640 0.092098 0.092756 -vn 0.167338 0.957657 -0.234288 -v 0.054584 0.092171 0.092924 -vn 0.087947 0.996067 -0.010797 -v 0.054520 0.092200 0.093102 -vn 0.112832 0.549329 -0.827953 -v 0.054543 0.091848 0.092448 -vn 0.099555 0.731901 -0.674100 -v 0.054532 0.091993 0.092572 -vn 0.080543 0.872773 -0.481436 -v 0.054517 0.092105 0.092727 -vn 0.056877 0.963709 -0.260827 -v 0.054498 0.092176 0.092903 -vn 0.029897 0.999246 -0.024754 -v 0.054476 0.092203 0.093092 -vn -0.087945 0.996067 -0.010796 -v 0.054386 0.092200 0.093102 -vn -0.268072 0.945906 -0.182753 -v 0.054243 0.092162 0.092964 -vn -0.500193 0.823817 -0.266706 -v 0.054059 0.092066 0.092896 -vn -0.731322 0.634988 -0.248916 -v 0.053874 0.091916 0.092908 -vn -0.908956 0.392580 -0.140288 -v 0.053732 0.091723 0.092994 -vn -0.992840 0.116462 0.026552 -v 0.053665 0.091503 0.093126 -vn -0.963989 -0.169258 0.205125 -v 0.053688 0.091274 0.093267 -vn -0.828930 -0.439469 0.346038 -v 0.053796 0.091058 0.093378 -vn -0.618214 -0.671410 0.408682 -v 0.053964 0.090873 0.093427 -vn -0.379620 -0.847559 0.370853 -v 0.054154 0.090733 0.093395 -vn -0.167343 -0.957655 0.234293 -v 0.054322 0.090647 0.093284 -vn -0.140877 0.989893 0.016293 -v 0.054345 0.092196 0.093123 -vn -0.353238 0.929140 -0.109188 -v 0.054177 0.092149 0.093022 -vn -0.591716 0.794344 -0.137436 -v 0.053987 0.092043 0.092998 -vn -0.801926 0.593607 -0.067423 -v 0.053819 0.091884 0.093052 -vn -0.936160 0.342781 0.078138 -v 0.053711 0.091684 0.093167 -vn -0.963990 0.063650 0.258208 -v 0.053688 0.091461 0.093309 -vn -0.879120 -0.218997 0.423307 -v 0.053755 0.091235 0.093440 -vn -0.700724 -0.480750 0.527129 -v 0.053897 0.091025 0.093522 -vn -0.469180 -0.700745 0.537426 -v 0.054082 0.090850 0.093528 -vn -0.236966 -0.864201 0.443850 -v 0.054266 0.090720 0.093452 -vn -0.056876 -0.963708 0.260829 -v 0.054409 0.090642 0.093305 -vn 0.087947 -0.996067 0.010797 -v 0.054520 0.090618 0.093106 -vn 0.056877 -0.963709 0.260827 -v 0.054498 0.090642 0.093305 -vn -0.080544 -0.872772 0.481437 -v 0.054390 0.090714 0.093482 -vn -0.292880 -0.721304 0.627648 -v 0.054221 0.090834 0.093600 -vn -0.531790 -0.514013 0.673045 -v 0.054031 0.090999 0.093637 -vn -0.743155 -0.262773 0.615362 -v 0.053863 0.091200 0.093593 -vn -0.879116 0.013911 0.476404 -v 0.053755 0.091421 0.093483 -vn -0.908959 0.292981 0.296572 -v 0.053732 0.091644 0.093340 -vn -0.825931 0.549674 0.125288 -v 0.053800 0.091849 0.093205 -vn -0.648835 0.760871 0.009387 -v 0.053942 0.092017 0.093114 -vn -0.417883 0.908325 -0.017890 -v 0.054126 0.092133 0.093093 -vn -0.185647 0.981077 0.054983 -v 0.054311 0.092189 0.093153 -vn -0.668248 0.725334 0.165331 -v 0.053927 0.091989 0.093236 -vn -0.458210 0.884691 0.085827 -v 0.054095 0.092114 0.093174 -vn -0.219629 0.970132 0.102990 -v 0.054285 0.092181 0.093190 -vn 0.236967 -0.864201 0.443851 -v 0.054640 0.090720 0.093452 -vn 0.080543 -0.872773 0.481436 -v 0.054517 0.090714 0.093482 -vn 0.099556 -0.731892 0.674109 -v 0.054532 0.090825 0.093636 -vn -0.099554 -0.731894 0.674107 -v 0.054374 0.090825 0.093636 -vn -0.112840 -0.549315 0.827961 -v 0.054364 0.090971 0.093760 -vn -0.331960 -0.537318 0.775301 -v 0.054190 0.090980 0.093718 -vn -0.352063 -0.322782 0.878557 -v 0.054174 0.091152 0.093802 -vn -0.563988 -0.298052 0.770119 -v 0.054005 0.091172 0.093715 -vn -0.563999 -0.065137 0.823203 -v 0.054005 0.091358 0.093758 -vn -0.743151 -0.029861 0.668457 -v 0.053863 0.091386 0.093635 -vn -0.700734 0.204803 0.683395 -v 0.053897 0.091574 0.093647 -vn -0.828926 0.246091 0.502316 -v 0.053796 0.091607 0.093503 -vn -0.731325 0.464369 0.499525 -v 0.053874 0.091782 0.093501 -vn -0.801922 0.505747 0.318026 -v 0.053819 0.091814 0.093357 -vn -0.648827 0.689789 0.321271 -v 0.053942 0.091961 0.093359 -vn -0.471913 0.859591 0.195961 -v 0.054084 0.092095 0.093261 -vn -0.240808 0.957719 0.157434 -v 0.054269 0.092171 0.093231 -vn 0.248038 0.757257 -0.604185 -v 0.054643 0.089499 0.093198 -vn 0.240810 0.720222 -0.650608 -v 0.054638 0.089471 0.093162 -vn 0.000001 0.779124 -0.626870 -v 0.054453 0.089517 0.093183 -vn -0.219648 0.829083 -0.514175 -v 0.054285 0.089554 0.093267 -vn -0.185604 0.859832 -0.475647 -v 0.054311 0.089578 0.093296 -vn -0.056883 -0.981335 0.183699 -v 0.054409 0.088119 0.093831 -vn -0.029919 -0.910798 0.411766 -v 0.054430 0.088176 0.094012 -vn -0.087977 -0.901870 0.422954 -v 0.054386 0.088183 0.094020 -vn 0.000001 -0.784171 0.620544 -v 0.054453 0.088276 0.094174 -vn 0.029917 -0.910797 0.411770 -v 0.054476 0.088176 0.094012 -vn 0.041755 -0.590874 0.805682 -v 0.054476 0.088412 0.094307 -vn -0.041761 -0.590868 0.805686 -v 0.054430 0.088412 0.094307 -vn 0.140873 -0.629920 0.763777 -v 0.054561 0.088392 0.094282 -vn 0.268070 -0.446897 0.853476 -v 0.054663 0.088537 0.094354 -vn 0.167323 -0.413924 0.894802 -v 0.054584 0.088562 0.094387 -vn 0.056886 -0.981336 0.183696 -v 0.054498 0.088119 0.093831 -vn 0.080551 -0.995258 -0.054524 -v 0.054517 0.088106 0.093641 -vn 0.087974 -0.901866 0.422963 -v 0.054520 0.088183 0.094020 -vn 0.167329 -0.964360 0.204965 -v 0.054584 0.088132 0.093847 -vn 0.236970 -0.971211 -0.024391 -v 0.054640 0.088125 0.093664 -vn 0.292895 -0.922337 -0.252005 -v 0.054685 0.088163 0.093482 -vn 0.140895 -0.884539 0.444680 -v 0.054561 0.088197 0.094037 -vn 0.268059 -0.931390 0.246287 -v 0.054663 0.088158 0.093880 -vn 0.379603 -0.924520 0.034110 -v 0.054752 0.088162 0.093710 -vn 0.469186 -0.864626 -0.179683 -v 0.054824 0.088209 0.093539 -vn 0.531807 -0.755339 -0.382941 -v 0.054875 0.088296 0.093376 -vn 0.185623 -0.859833 0.475638 -v 0.054595 0.088216 0.094061 -vn 0.353246 -0.884314 0.305295 -v 0.054729 0.088195 0.093926 -vn 0.500196 -0.857886 0.117623 -v 0.054847 0.088214 0.093776 -vn 0.618208 -0.782283 -0.076494 -v 0.054942 0.088274 0.093621 -vn 0.700723 -0.662001 -0.265974 -v 0.055009 0.088370 0.093469 -vn 0.743149 -0.504000 -0.440128 -v 0.055043 0.088496 0.093330 -vn 0.219586 -0.829155 0.514086 -v 0.054621 0.088239 0.094090 -vn 0.417873 -0.825927 0.378453 -v 0.054780 0.088240 0.093983 -vn 0.591709 -0.775192 0.221262 -v 0.054919 0.088280 0.093858 -vn 0.731326 -0.680072 0.051617 -v 0.055032 0.088355 0.093722 -vn 0.828930 -0.546155 -0.120791 -v 0.055110 0.088461 0.093584 -vn 0.879118 -0.381141 -0.286151 -v 0.055151 0.088593 0.093452 -vn 0.879119 -0.194416 -0.435146 -v 0.055151 0.088743 0.093332 -vn 0.240816 -0.794244 0.557838 -v 0.054638 0.088266 0.094124 -vn -0.240816 -0.794245 0.557838 -v 0.054269 0.088266 0.094124 -vn -0.219593 -0.829138 0.514110 -v 0.054285 0.088239 0.094090 -vn -0.417882 -0.825924 0.378449 -v 0.054126 0.088240 0.093983 -vn -0.353247 -0.884319 0.305280 -v 0.054177 0.088195 0.093926 -vn -0.500195 -0.857886 0.117625 -v 0.054059 0.088214 0.093776 -vn -0.379613 -0.924516 0.034116 -v 0.054154 0.088162 0.093710 -vn -0.469182 -0.864628 -0.179686 -v 0.054082 0.088209 0.093539 -vn -0.292891 -0.922336 -0.252016 -v 0.054221 0.088163 0.093482 -vn -0.331968 -0.820751 -0.464936 -v 0.054190 0.088244 0.093311 -vn -0.112833 -0.854439 -0.507152 -v 0.054364 0.088217 0.093278 -vn -0.119675 -0.708101 -0.695895 -v 0.054358 0.088334 0.093127 -vn 0.119680 -0.708104 -0.695892 -v 0.054548 0.088334 0.093127 -vn -0.119680 -0.521367 -0.844898 -v 0.054358 0.088484 0.093007 -vn -0.352072 -0.672367 -0.651129 -v 0.054174 0.088362 0.093162 -vn -0.531797 -0.755340 -0.382953 -v 0.054031 0.088296 0.093376 -vn -0.618212 -0.782282 -0.076480 -v 0.053964 0.088274 0.093621 -vn -0.591700 -0.775202 0.221252 -v 0.053987 0.088280 0.093858 -vn -0.458211 -0.759576 0.461613 -v 0.054095 0.088292 0.094048 -vn -0.248024 -0.757231 0.604223 -v 0.054263 0.088294 0.094159 -vn 0.352061 0.485640 0.800129 -v 0.054733 0.089282 0.094314 -vn 0.352063 0.672363 0.651137 -v 0.054733 0.089431 0.094195 -vn 0.119661 0.708082 0.695917 -v 0.054548 0.089460 0.094230 -vn 0.458210 -0.759583 0.461603 -v 0.054811 0.088292 0.094048 -vn 0.648833 -0.681252 0.338987 -v 0.054964 0.088354 0.093951 -vn 0.801931 -0.563954 0.197137 -v 0.055087 0.088447 0.093838 -vn 0.908958 -0.414541 0.044157 -v 0.055174 0.088566 0.093715 -vn 0.963989 -0.241561 -0.111234 -v 0.055218 0.088704 0.093591 -vn 0.963990 -0.054828 -0.260224 -v 0.055218 0.088854 0.093471 -vn 0.908961 0.135071 -0.394393 -v 0.055174 0.089006 0.093364 -vn 0.248025 -0.757235 0.604217 -v 0.054643 0.088294 0.094159 -vn 0.119679 -0.521368 -0.844898 -v 0.054548 0.088484 0.093007 -vn 0.352063 -0.485645 -0.800125 -v 0.054733 0.088512 0.093043 -vn -0.112850 -0.304814 -0.945702 -v 0.054364 0.088657 0.092927 -vn -0.352069 -0.485640 -0.800126 -v 0.054174 0.088512 0.093043 -vn -0.563987 -0.603002 -0.564186 -v 0.054005 0.088417 0.093231 -vn -0.700726 -0.661998 -0.265974 -v 0.053897 0.088370 0.093469 -vn -0.731330 -0.680068 0.051614 -v 0.053874 0.088355 0.093722 -vn -0.648830 -0.681252 0.338992 -v 0.053942 0.088354 0.093951 -vn -0.471926 -0.689140 0.549884 -v 0.054084 0.088347 0.094117 -vn -0.240813 -0.720224 0.650605 -v 0.054269 0.088322 0.094195 -vn 0.471932 -0.689131 0.549890 -v 0.054822 0.088347 0.094117 -vn 0.668250 -0.581499 0.464005 -v 0.054980 0.088432 0.094049 -vn 0.825929 -0.440677 0.351633 -v 0.055106 0.088544 0.093960 -vn 0.936159 -0.274813 0.219279 -v 0.055195 0.088677 0.093854 -vn 0.992840 -0.093366 0.074502 -v 0.055241 0.088822 0.093738 -vn 0.992840 0.093365 -0.074504 -v 0.055241 0.088972 0.093619 -vn 0.936161 0.274805 -0.219281 -v 0.055195 0.089117 0.093503 -vn 0.825927 0.440679 -0.351633 -v 0.055106 0.089249 0.093397 -vn 0.240809 -0.720215 0.650616 -v 0.054638 0.088322 0.094195 -vn 0.331966 -0.271140 -0.903483 -v 0.054716 0.088684 0.092960 -vn 0.531796 -0.205711 -0.821509 -v 0.054875 0.088736 0.093025 -vn -0.099553 -0.070693 -0.992518 -v 0.054374 0.088845 0.092890 -vn -0.331960 -0.271145 -0.903484 -v 0.054190 0.088684 0.092960 -vn -0.563993 -0.416269 -0.713185 -v 0.054005 0.088567 0.093112 -vn -0.743152 -0.503998 -0.440125 -v 0.053863 0.088496 0.093330 -vn -0.828930 -0.546156 -0.120786 -v 0.053796 0.088461 0.093584 -vn -0.801934 -0.563950 0.197133 -v 0.053819 0.088447 0.093838 -vn -0.668252 -0.581501 0.463999 -v 0.053927 0.088432 0.094049 -vn -0.458212 -0.618712 0.638152 -v 0.054095 0.088402 0.094186 -vn -0.219606 -0.685341 0.694321 -v 0.054285 0.088349 0.094228 -vn -0.112855 0.854432 0.507158 -v 0.054364 0.089576 0.094079 -vn -0.099554 0.952064 0.289246 -v 0.054374 0.089654 0.093904 -vn -0.292891 0.922338 0.252007 -v 0.054221 0.089630 0.093875 -vn 0.458221 -0.618706 0.638151 -v 0.054811 0.088402 0.094186 -vn 0.648836 -0.481761 0.588997 -v 0.054964 0.088511 0.094148 -vn 0.801927 -0.317401 0.506132 -v 0.055087 0.088642 0.094082 -vn 0.908956 -0.135077 0.394402 -v 0.055174 0.088787 0.093993 -vn 0.963990 0.054834 0.260225 -v 0.055218 0.088940 0.093886 -vn 0.963990 0.241563 0.111224 -v 0.055218 0.089089 0.093766 -vn 0.908960 0.414538 -0.044151 -v 0.055174 0.089228 0.093642 -vn 0.801927 0.563963 -0.197130 -v 0.055087 0.089347 0.093519 -vn 0.648826 0.681257 -0.338989 -v 0.054964 0.089440 0.093406 -vn 0.219601 -0.685338 0.694325 -v 0.054621 0.088349 0.094228 -vn 0.469181 0.016732 -0.882944 -v 0.054824 0.088914 0.092977 -vn 0.618215 0.099077 -0.779739 -v 0.054942 0.088979 0.093058 -vn -0.080550 0.167745 -0.982534 -v 0.054390 0.089035 0.092899 -vn -0.292878 -0.040979 -0.955271 -v 0.054221 0.088868 0.092920 -vn -0.531798 -0.205716 -0.821506 -v 0.054031 0.088736 0.093025 -vn -0.743156 -0.317266 -0.589119 -v 0.053863 0.088646 0.093210 -vn -0.879116 -0.381144 -0.286154 -v 0.053755 0.088593 0.093452 -vn -0.908956 -0.414546 0.044161 -v 0.053732 0.088566 0.093715 -vn -0.825932 -0.440671 0.351631 -v 0.053800 0.088544 0.093960 -vn -0.648839 -0.481750 0.589003 -v 0.053942 0.088511 0.094148 -vn -0.417871 -0.552340 0.721321 -v 0.054126 0.088454 0.094251 -vn -0.185643 -0.654651 0.732781 -v 0.054311 0.088373 0.094258 -vn -0.236966 0.971212 0.024395 -v 0.054266 0.089668 0.093693 -vn -0.379614 0.924516 -0.034110 -v 0.054154 0.089632 0.093646 -vn 0.417865 -0.552346 0.721320 -v 0.054780 0.088454 0.094251 -vn 0.591716 -0.387806 0.706738 -v 0.054919 0.088585 0.094240 -vn 0.731321 -0.201284 0.651655 -v 0.055032 0.088734 0.094197 -vn 0.828928 -0.003462 0.559344 -v 0.055110 0.088892 0.094124 -vn 0.879118 0.194416 0.435149 -v 0.055151 0.089050 0.094024 -vn 0.879115 0.381144 0.286158 -v 0.055151 0.089200 0.093905 -vn 0.828930 0.546156 0.120788 -v 0.055110 0.089332 0.093773 -vn 0.731323 0.680076 -0.051606 -v 0.055032 0.089439 0.093635 -vn 0.591706 0.775193 -0.221268 -v 0.054919 0.089514 0.093499 -vn 0.417883 0.825922 -0.378452 -v 0.054780 0.089553 0.093374 -vn 0.185640 -0.654655 0.732779 -v 0.054595 0.088373 0.094258 -vn 0.500198 0.305116 -0.810374 -v 0.054847 0.089144 0.093035 -vn 0.591711 0.387820 -0.706734 -v 0.054919 0.089209 0.093117 -vn -0.056904 0.396936 -0.916081 -v 0.054409 0.089218 0.092954 -vn -0.236966 0.191794 -0.952398 -v 0.054266 0.089054 0.092923 -vn -0.469185 0.016743 -0.882941 -v 0.054082 0.088914 0.092977 -vn -0.700727 -0.112381 -0.704522 -v 0.053897 0.088810 0.093118 -vn -0.879115 -0.194419 -0.435152 -v 0.053755 0.088743 0.093332 -vn -0.963990 -0.241561 -0.111228 -v 0.053688 0.088704 0.093591 -vn -0.936158 -0.274818 0.219281 -v 0.053711 0.088677 0.093854 -vn -0.801927 -0.317405 0.506130 -v 0.053819 0.088642 0.094082 -vn -0.591712 -0.387806 0.706742 -v 0.053987 0.088585 0.094240 -vn -0.353248 -0.493962 0.794492 -v 0.054177 0.088500 0.094308 -vn -0.140878 -0.629922 0.763774 -v 0.054345 0.088392 0.094282 -vn -0.268064 0.931388 -0.246289 -v 0.054243 0.089636 0.093477 -vn -0.353257 0.884318 -0.305274 -v 0.054177 0.089599 0.093431 -vn 0.417872 0.552366 -0.721300 -v 0.054780 0.089339 0.093106 -vn 0.458221 0.618706 -0.638151 -v 0.054811 0.089391 0.093171 -vn -0.029919 0.603686 -0.796661 -v 0.054430 0.089382 0.093050 -vn -0.167377 0.413930 -0.894789 -v 0.054322 0.089231 0.092970 -vn -0.379594 0.238479 -0.893888 -v 0.054154 0.089091 0.092969 -vn -0.618213 0.099073 -0.779742 -v 0.053964 0.088979 0.093058 -vn -0.828926 0.003456 -0.559347 -v 0.053796 0.088902 0.093233 -vn -0.963991 -0.054827 -0.260222 -v 0.053688 0.088854 0.093471 -vn -0.992841 -0.093367 0.074498 -v 0.053665 0.088822 0.093738 -vn -0.908954 -0.135085 0.394404 -v 0.053732 0.088787 0.093993 -vn -0.731322 -0.201285 0.651654 -v 0.053874 0.088734 0.094197 -vn -0.500192 -0.305109 0.810380 -v 0.054059 0.088650 0.094322 -vn -0.268062 -0.446886 0.853485 -v 0.054243 0.088537 0.094354 -vn -0.087907 -0.612580 0.785505 -v 0.054386 0.088405 0.094298 -vn 0.292872 0.040981 0.955273 -v 0.054685 0.088925 0.094437 -vn 0.331962 0.271143 0.903484 -v 0.054716 0.089110 0.094397 -vn 0.112830 0.304819 0.945703 -v 0.054543 0.089136 0.094430 -vn 0.119675 0.521372 0.844896 -v 0.054548 0.089310 0.094350 -vn -0.119673 0.521362 0.844902 -v 0.054358 0.089310 0.094350 -vn -0.119662 0.708093 0.695906 -v 0.054358 0.089460 0.094230 -vn -0.352069 0.672368 0.651129 -v 0.054174 0.089431 0.094195 -vn -0.331978 0.820754 0.464923 -v 0.054190 0.089550 0.094045 -vn -0.531804 0.755338 0.382947 -v 0.054031 0.089498 0.093980 -vn -0.469183 0.864626 0.179692 -v 0.054082 0.089585 0.093818 -vn -0.618213 0.782281 0.076479 -v 0.053964 0.089520 0.093736 -vn -0.500193 0.857888 -0.117626 -v 0.054059 0.089579 0.093581 -vn -0.591703 0.775199 -0.221257 -v 0.053987 0.089514 0.093499 -vn -0.417880 0.825923 -0.378453 -v 0.054126 0.089553 0.093374 -vn -0.458210 0.759575 -0.461617 -v 0.054095 0.089501 0.093309 -vn -0.240833 0.794222 -0.557862 -v 0.054269 0.089528 0.093233 -vn -0.248024 0.757263 -0.604183 -v 0.054263 0.089499 0.093198 -vn -0.140895 0.884549 -0.444659 -v 0.054345 0.089597 0.093320 -vn -0.167332 0.964359 -0.204966 -v 0.054322 0.089661 0.093510 -vn -0.087955 0.901868 -0.422962 -v 0.054386 0.089610 0.093337 -vn -0.080549 0.995258 0.054525 -v 0.054390 0.089687 0.093716 -vn -0.056877 0.981337 -0.183694 -v 0.054409 0.089675 0.093526 -vn -0.041684 0.916751 -0.397278 -v 0.054430 0.089617 0.093345 -vn 0.041700 0.916752 -0.397275 -v 0.054476 0.089617 0.093345 -vn 0.056885 0.981335 -0.183701 -v 0.054498 0.089675 0.093526 -vn 0.080551 0.995258 0.054524 -v 0.054517 0.089687 0.093716 -vn 0.099559 0.952062 0.289250 -v 0.054532 0.089654 0.093904 -vn 0.112846 0.854438 0.507150 -v 0.054543 0.089576 0.094079 -vn 0.331985 0.820755 0.464917 -v 0.054716 0.089550 0.094045 -vn 0.292892 0.922338 0.252006 -v 0.054685 0.089630 0.093875 -vn 0.236969 0.971211 0.024389 -v 0.054640 0.089668 0.093693 -vn 0.167327 0.964362 -0.204956 -v 0.054584 0.089661 0.093510 -vn 0.087927 0.901873 -0.422959 -v 0.054520 0.089610 0.093337 -vn 0.353250 -0.493958 0.794494 -v 0.054729 0.088500 0.094308 -vn 0.379608 -0.238489 0.893880 -v 0.054752 0.088702 0.094388 -vn 0.500193 -0.305116 0.810378 -v 0.054847 0.088650 0.094322 -vn 0.469182 -0.016740 0.882943 -v 0.054824 0.088880 0.094380 -vn 0.618221 -0.099078 0.779735 -v 0.054942 0.088814 0.094298 -vn 0.531803 0.205722 0.821501 -v 0.054875 0.089058 0.094332 -vn 0.700721 0.112375 0.704530 -v 0.055009 0.088984 0.094239 -vn 0.563994 0.416268 0.713184 -v 0.054901 0.089227 0.094245 -vn 0.743150 0.317276 0.589121 -v 0.055043 0.089148 0.094147 -vn 0.564006 0.602995 0.564175 -v 0.054901 0.089376 0.094126 -vn 0.743147 0.504006 0.440125 -v 0.055043 0.089298 0.094027 -vn 0.531807 0.755338 0.382944 -v 0.054875 0.089498 0.093980 -vn 0.700722 0.662001 0.265974 -v 0.055009 0.089424 0.093888 -vn 0.469185 0.864625 0.179691 -v 0.054824 0.089585 0.093818 -vn 0.618210 0.782282 0.076491 -v 0.054942 0.089520 0.093736 -vn 0.379603 0.924521 -0.034103 -v 0.054752 0.089632 0.093646 -vn 0.500194 0.857887 -0.117623 -v 0.054847 0.089579 0.093581 -vn 0.268067 0.931389 -0.246282 -v 0.054663 0.089636 0.093477 -vn 0.353249 0.884316 -0.305286 -v 0.054729 0.089599 0.093431 -vn 0.140912 0.884537 -0.444678 -v 0.054561 0.089597 0.093320 -vn 0.185608 0.859838 -0.475634 -v 0.054595 0.089578 0.093296 -vn 0.219626 0.829095 -0.514165 -v 0.054621 0.089554 0.093267 -vn 0.240828 0.794218 -0.557870 -v 0.054638 0.089528 0.093233 -vn 0.458210 0.759582 -0.461604 -v 0.054811 0.089501 0.093309 -vn 0.471917 0.689125 -0.549910 -v 0.054822 0.089446 0.093240 -vn 0.668243 0.581510 -0.464002 -v 0.054980 0.089361 0.093308 -vn 0.648823 0.481764 -0.589010 -v 0.054964 0.089283 0.093209 -vn 0.801927 0.317399 -0.506133 -v 0.055087 0.089152 0.093275 -vn 0.731317 0.201280 -0.651660 -v 0.055032 0.089060 0.093160 -vn 0.828926 0.003457 -0.559348 -v 0.055110 0.088902 0.093233 -vn 0.700728 -0.112382 -0.704521 -v 0.055009 0.088810 0.093118 -vn 0.743150 -0.317271 -0.589124 -v 0.055043 0.088646 0.093210 -vn 0.564000 -0.416269 -0.713179 -v 0.054901 0.088567 0.093112 -vn 0.563994 -0.602995 -0.564188 -v 0.054901 0.088417 0.093231 -vn 0.352060 -0.672369 -0.651133 -v 0.054733 0.088362 0.093162 -vn 0.331961 -0.820747 -0.464947 -v 0.054716 0.088244 0.093311 -vn 0.112834 -0.854434 -0.507160 -v 0.054543 0.088217 0.093278 -vn 0.099553 -0.952057 -0.289270 -v 0.054532 0.088140 0.093453 -vn -0.099556 -0.952056 -0.289272 -v 0.054374 0.088140 0.093453 -vn -0.080549 -0.995258 -0.054525 -v 0.054390 0.088106 0.093641 -vn -0.236967 -0.971211 -0.024396 -v 0.054266 0.088125 0.093664 -vn -0.167324 -0.964359 0.204974 -v 0.054322 0.088132 0.093847 -vn -0.268062 -0.931386 0.246298 -v 0.054243 0.088158 0.093880 -vn -0.140898 -0.884542 0.444672 -v 0.054345 0.088197 0.094037 -vn -0.185603 -0.859838 0.475637 -v 0.054311 0.088216 0.094061 -vn 0.219604 0.685332 -0.694330 -v 0.054621 0.089444 0.093129 -vn 0.353235 0.493959 -0.794500 -v 0.054729 0.089294 0.093049 -vn 0.185640 0.654657 -0.732777 -v 0.054595 0.089421 0.093099 -vn 0.379590 0.238486 -0.893888 -v 0.054752 0.089091 0.092969 -vn 0.268072 0.446894 -0.853477 -v 0.054663 0.089257 0.093003 -vn 0.140879 0.629914 -0.763781 -v 0.054561 0.089402 0.093075 -vn 0.292890 -0.040983 -0.955268 -v 0.054685 0.088868 0.092920 -vn 0.236953 0.191804 -0.952399 -v 0.054640 0.089054 0.092923 -vn 0.167379 0.413925 -0.894791 -v 0.054584 0.089231 0.092970 -vn 0.088018 0.612607 -0.785472 -v 0.054520 0.089389 0.093059 -vn 0.112844 -0.304819 -0.945702 -v 0.054543 0.088657 0.092927 -vn 0.099550 -0.070689 -0.992518 -v 0.054532 0.088845 0.092890 -vn 0.080556 0.167748 -0.982533 -v 0.054517 0.089035 0.092899 -vn 0.056912 0.396932 -0.916082 -v 0.054498 0.089218 0.092954 -vn 0.029921 0.603686 -0.796661 -v 0.054476 0.089382 0.093050 -vn -0.088009 0.612608 -0.785471 -v 0.054386 0.089389 0.093059 -vn -0.268082 0.446903 -0.853470 -v 0.054243 0.089257 0.093003 -vn -0.500190 0.305121 -0.810378 -v 0.054059 0.089144 0.093035 -vn -0.731323 0.201285 -0.651652 -v 0.053874 0.089060 0.093160 -vn -0.908958 0.135077 -0.394398 -v 0.053732 0.089006 0.093364 -vn -0.992841 0.093366 -0.074502 -v 0.053665 0.088972 0.093619 -vn -0.963989 0.054838 0.260225 -v 0.053688 0.088940 0.093886 -vn -0.828926 -0.003458 0.559348 -v 0.053796 0.088892 0.094124 -vn -0.618221 -0.099089 0.779733 -v 0.053964 0.088814 0.094298 -vn -0.379611 -0.238496 0.893876 -v 0.054154 0.088702 0.094388 -vn -0.167339 -0.413922 0.894799 -v 0.054322 0.088562 0.094387 -vn -0.140891 0.629916 -0.763777 -v 0.054345 0.089402 0.093075 -vn -0.353230 0.493950 -0.794508 -v 0.054177 0.089294 0.093049 -vn -0.591709 0.387818 -0.706738 -v 0.053987 0.089209 0.093117 -vn -0.801927 0.317398 -0.506134 -v 0.053819 0.089152 0.093275 -vn -0.936160 0.274809 -0.219281 -v 0.053711 0.089117 0.093503 -vn -0.963990 0.241562 0.111224 -v 0.053688 0.089089 0.093766 -vn -0.879118 0.194413 0.435150 -v 0.053755 0.089050 0.094024 -vn -0.700728 0.112372 0.704523 -v 0.053897 0.088984 0.094239 -vn -0.469182 -0.016742 0.882943 -v 0.054082 0.088880 0.094380 -vn -0.236976 -0.191811 0.952392 -v 0.054266 0.088739 0.094434 -vn -0.056901 -0.396960 0.916071 -v 0.054409 0.088576 0.094403 -vn 0.087918 -0.612587 0.785499 -v 0.054520 0.088405 0.094298 -vn 0.056907 -0.396952 0.916074 -v 0.054498 0.088576 0.094403 -vn -0.080550 -0.167747 0.982534 -v 0.054390 0.088758 0.094458 -vn -0.292871 0.040988 0.955273 -v 0.054221 0.088925 0.094437 -vn -0.531795 0.205726 0.821505 -v 0.054031 0.089058 0.094332 -vn -0.743151 0.317273 0.589121 -v 0.053863 0.089148 0.094147 -vn -0.879116 0.381143 0.286156 -v 0.053755 0.089200 0.093905 -vn -0.908960 0.414539 -0.044156 -v 0.053732 0.089228 0.093642 -vn -0.825931 0.440674 -0.351631 -v 0.053800 0.089249 0.093397 -vn -0.648827 0.481756 -0.589011 -v 0.053942 0.089283 0.093209 -vn -0.417873 0.552368 -0.721298 -v 0.054126 0.089339 0.093106 -vn -0.185631 0.654649 -0.732786 -v 0.054311 0.089421 0.093099 -vn -0.668239 0.581514 -0.464003 -v 0.053927 0.089361 0.093308 -vn -0.458211 0.618713 -0.638152 -v 0.054095 0.089391 0.093171 -vn -0.219623 0.685345 -0.694311 -v 0.054285 0.089444 0.093129 -vn 0.236971 -0.191799 0.952396 -v 0.054640 0.088739 0.094434 -vn 0.080556 -0.167749 0.982533 -v 0.054517 0.088758 0.094458 -vn 0.099554 0.070713 0.992516 -v 0.054532 0.088949 0.094467 -vn -0.099550 0.070712 0.992517 -v 0.054374 0.088949 0.094467 -vn -0.112836 0.304824 0.945701 -v 0.054364 0.089136 0.094430 -vn -0.331959 0.271144 0.903484 -v 0.054190 0.089110 0.094397 -vn -0.352071 0.485633 0.800129 -v 0.054174 0.089282 0.094314 -vn -0.563989 0.416278 0.713183 -v 0.054005 0.089227 0.094245 -vn -0.564003 0.602992 0.564183 -v 0.054005 0.089376 0.094126 -vn -0.743146 0.504009 0.440123 -v 0.053863 0.089298 0.094027 -vn -0.700726 0.661998 0.265974 -v 0.053897 0.089424 0.093888 -vn -0.828928 0.546158 0.120789 -v 0.053796 0.089332 0.093773 -vn -0.731323 0.680076 -0.051609 -v 0.053874 0.089439 0.093635 -vn -0.801926 0.563963 -0.197128 -v 0.053819 0.089347 0.093519 -vn -0.648824 0.681259 -0.338988 -v 0.053942 0.089440 0.093406 -vn -0.471925 0.689129 -0.549898 -v 0.054084 0.089446 0.093240 -vn -0.240809 0.720213 -0.650618 -v 0.054269 0.089471 0.093162 -# 5577 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 10//10 11//11 12//12 -f 13//13 14//14 15//15 -f 16//16 17//17 18//18 -f 19//19 16//16 20//20 -f 21//21 22//22 23//23 -f 24//24 25//25 26//26 -f 27//27 28//28 29//29 -f 30//30 31//31 32//32 -f 33//33 34//34 35//35 -f 36//36 37//37 38//38 -f 39//39 40//40 41//41 -f 42//42 43//43 44//44 -f 45//45 46//46 47//47 -f 48//48 49//49 50//50 -f 51//51 52//52 53//53 -f 54//54 55//55 56//56 -f 57//57 58//58 59//59 -f 60//60 61//61 62//62 -f 63//63 64//64 65//65 -f 66//66 67//67 68//68 -f 69//69 70//70 71//71 -f 72//72 73//73 74//74 -f 75//75 76//76 77//77 -f 78//78 79//79 80//80 -f 81//81 82//82 83//83 -f 84//84 85//85 86//86 -f 87//87 88//88 89//89 -f 90//90 91//91 92//92 -f 93//93 94//94 95//95 -f 96//96 97//97 98//98 -f 99//99 100//100 101//101 -f 102//102 103//103 104//104 -f 105//105 106//106 107//107 -f 108//108 109//109 110//110 -f 111//111 112//112 113//113 -f 114//114 14//14 115//115 -f 115//115 14//14 13//13 -f 115//115 13//13 116//116 -f 116//116 13//13 117//117 -f 118//118 119//119 120//120 -f 121//121 122//122 21//21 -f 19//19 20//20 22//22 -f 123//123 124//124 18//18 -f 125//125 15//15 126//126 -f 126//126 15//15 14//14 -f 126//126 14//14 26//26 -f 26//26 14//14 114//114 -f 26//26 114//114 24//24 -f 127//127 125//125 128//128 -f 128//128 125//125 126//126 -f 128//128 126//126 129//129 -f 129//129 126//126 26//26 -f 129//129 26//26 118//118 -f 118//118 26//26 25//25 -f 118//118 25//25 119//119 -f 130//130 127//127 131//131 -f 131//131 127//127 128//128 -f 131//131 128//128 132//132 -f 132//132 128//128 129//129 -f 132//132 129//129 133//133 -f 133//133 129//129 118//118 -f 133//133 118//118 121//121 -f 121//121 118//118 120//120 -f 121//121 120//120 122//122 -f 134//134 135//135 136//136 -f 17//17 137//137 18//18 -f 18//18 137//137 138//138 -f 18//18 138//138 123//123 -f 123//123 138//138 139//139 -f 123//123 139//139 140//140 -f 140//140 139//139 141//141 -f 140//140 141//141 142//142 -f 142//142 141//141 143//143 -f 142//142 143//143 144//144 -f 144//144 143//143 145//145 -f 76//76 72//72 77//77 -f 77//77 72//72 74//74 -f 77//77 74//74 146//146 -f 146//146 74//74 147//147 -f 146//146 147//147 148//148 -f 148//148 147//147 149//149 -f 148//148 149//149 150//150 -f 150//150 149//149 151//151 -f 150//150 151//151 152//152 -f 152//152 151//151 153//153 -f 73//73 154//154 74//74 -f 74//74 154//154 155//155 -f 74//74 155//155 147//147 -f 147//147 155//155 156//156 -f 147//147 156//156 149//149 -f 149//149 156//156 157//157 -f 149//149 157//157 151//151 -f 151//151 157//157 158//158 -f 151//151 158//158 153//153 -f 153//153 158//158 159//159 -f 153//153 159//159 160//160 -f 160//160 159//159 161//161 -f 70//70 162//162 71//71 -f 71//71 162//162 163//163 -f 71//71 163//163 164//164 -f 164//164 163//163 165//165 -f 164//164 165//165 166//166 -f 166//166 165//165 167//167 -f 166//166 167//167 168//168 -f 168//168 167//167 169//169 -f 168//168 169//169 170//170 -f 170//170 169//169 171//171 -f 67//67 63//63 68//68 -f 68//68 63//63 65//65 -f 68//68 65//65 172//172 -f 172//172 65//65 173//173 -f 172//172 173//173 174//174 -f 174//174 173//173 175//175 -f 174//174 175//175 176//176 -f 176//176 175//175 177//177 -f 176//176 177//177 178//178 -f 178//178 177//177 179//179 -f 88//88 60//60 89//89 -f 89//89 60//60 62//62 -f 89//89 62//62 180//180 -f 180//180 62//62 181//181 -f 180//180 181//181 182//182 -f 182//182 181//181 183//183 -f 182//182 183//183 184//184 -f 184//184 183//183 185//185 -f 184//184 185//185 186//186 -f 186//186 185//185 187//187 -f 91//91 57//57 92//92 -f 92//92 57//57 59//59 -f 92//92 59//59 188//188 -f 188//188 59//59 189//189 -f 188//188 189//189 190//190 -f 190//190 189//189 191//191 -f 190//190 191//191 192//192 -f 192//192 191//191 193//193 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 58//58 54//54 59//59 -f 59//59 54//54 56//56 -f 59//59 56//56 189//189 -f 189//189 56//56 196//196 -f 189//189 196//196 191//191 -f 191//191 196//196 197//197 -f 191//191 197//197 193//193 -f 193//193 197//197 198//198 -f 193//193 198//198 195//195 -f 195//195 198//198 199//199 -f 195//195 199//199 200//200 -f 200//200 199//199 201//201 -f 94//94 51//51 95//95 -f 95//95 51//51 53//53 -f 95//95 53//53 202//202 -f 202//202 53//53 203//203 -f 202//202 203//203 204//204 -f 204//204 203//203 205//205 -f 204//204 205//205 206//206 -f 206//206 205//205 207//207 -f 206//206 207//207 208//208 -f 208//208 207//207 209//209 -f 97//97 48//48 98//98 -f 98//98 48//48 50//50 -f 98//98 50//50 210//210 -f 210//210 50//50 211//211 -f 210//210 211//211 212//212 -f 212//212 211//211 213//213 -f 212//212 213//213 214//214 -f 214//214 213//213 215//215 -f 214//214 215//215 216//216 -f 216//216 215//215 217//217 -f 218//218 99//99 219//219 -f 219//219 99//99 101//101 -f 219//219 101//101 220//220 -f 220//220 101//101 221//221 -f 220//220 221//221 222//222 -f 222//222 221//221 223//223 -f 222//222 223//223 224//224 -f 224//224 223//223 225//225 -f 224//224 225//225 226//226 -f 226//226 225//225 227//227 -f 100//100 42//42 101//101 -f 101//101 42//42 44//44 -f 101//101 44//44 221//221 -f 221//221 44//44 228//228 -f 221//221 228//228 223//223 -f 223//223 228//228 229//229 -f 223//223 229//229 225//225 -f 225//225 229//229 230//230 -f 225//225 230//230 227//227 -f 227//227 230//230 231//231 -f 227//227 231//231 232//232 -f 232//232 231//231 233//233 -f 103//103 39//39 104//104 -f 104//104 39//39 41//41 -f 104//104 41//41 234//234 -f 234//234 41//41 235//235 -f 234//234 235//235 236//236 -f 236//236 235//235 237//237 -f 236//236 237//237 238//238 -f 238//238 237//237 239//239 -f 238//238 239//239 240//240 -f 240//240 239//239 241//241 -f 242//242 105//105 243//243 -f 243//243 105//105 107//107 -f 243//243 107//107 244//244 -f 244//244 107//107 245//245 -f 244//244 245//245 246//246 -f 246//246 245//245 247//247 -f 246//246 247//247 248//248 -f 248//248 247//247 249//249 -f 248//248 249//249 250//250 -f 250//250 249//249 251//251 -f 252//252 108//108 253//253 -f 253//253 108//108 110//110 -f 253//253 110//110 254//254 -f 254//254 110//110 255//255 -f 254//254 255//255 256//256 -f 256//256 255//255 257//257 -f 256//256 257//257 258//258 -f 258//258 257//257 259//259 -f 258//258 259//259 260//260 -f 260//260 259//259 261//261 -f 28//28 262//262 29//29 -f 29//29 262//262 263//263 -f 29//29 263//263 264//264 -f 264//264 263//263 265//265 -f 264//264 265//265 266//266 -f 266//266 265//265 267//267 -f 266//266 267//267 268//268 -f 268//268 267//267 269//269 -f 268//268 269//269 270//270 -f 270//270 269//269 271//271 -f 262//262 111//111 263//263 -f 263//263 111//111 113//113 -f 263//263 113//113 265//265 -f 265//265 113//113 272//272 -f 265//265 272//272 267//267 -f 267//267 272//272 273//273 -f 267//267 273//273 269//269 -f 269//269 273//273 274//274 -f 269//269 274//274 271//271 -f 271//271 274//274 275//275 -f 271//271 275//275 276//276 -f 276//276 275//275 277//277 -f 278//278 136//136 279//279 -f 279//279 136//136 135//135 -f 279//279 135//135 280//280 -f 280//280 135//135 281//281 -f 280//280 281//281 282//282 -f 283//283 284//284 285//285 -f 285//285 284//284 134//134 -f 285//285 134//134 286//286 -f 286//286 134//134 136//136 -f 286//286 136//136 287//287 -f 287//287 136//136 278//278 -f 287//287 278//278 124//124 -f 284//284 288//288 134//134 -f 134//134 288//288 289//289 -f 134//134 289//289 135//135 -f 135//135 289//289 290//290 -f 135//135 290//290 281//281 -f 124//124 123//123 287//287 -f 287//287 123//123 140//140 -f 287//287 140//140 286//286 -f 286//286 140//140 142//142 -f 286//286 142//142 285//285 -f 285//285 142//142 144//144 -f 285//285 144//144 283//283 -f 291//291 292//292 293//293 -f 293//293 292//292 145//145 -f 293//293 145//145 294//294 -f 294//294 145//145 143//143 -f 294//294 143//143 295//295 -f 295//295 143//143 141//141 -f 295//295 141//141 296//296 -f 296//296 141//141 139//139 -f 296//296 139//139 80//80 -f 80//80 139//139 138//138 -f 80//80 138//138 78//78 -f 78//78 138//138 137//137 -f 292//292 297//297 145//145 -f 145//145 297//297 298//298 -f 145//145 298//298 144//144 -f 144//144 298//298 299//299 -f 144//144 299//299 283//283 -f 79//79 75//75 80//80 -f 80//80 75//75 77//77 -f 80//80 77//77 296//296 -f 296//296 77//77 146//146 -f 296//296 146//146 295//295 -f 295//295 146//146 148//148 -f 295//295 148//148 294//294 -f 294//294 148//148 150//150 -f 294//294 150//150 293//293 -f 293//293 150//150 152//152 -f 293//293 152//152 291//291 -f 160//160 300//300 153//153 -f 153//153 300//300 301//301 -f 153//153 301//301 152//152 -f 152//152 301//301 302//302 -f 152//152 302//302 291//291 -f 154//154 81//81 155//155 -f 155//155 81//81 83//83 -f 155//155 83//83 156//156 -f 156//156 83//83 303//303 -f 156//156 303//303 157//157 -f 157//157 303//303 304//304 -f 157//157 304//304 158//158 -f 158//158 304//304 305//305 -f 158//158 305//305 159//159 -f 159//159 305//305 12//12 -f 159//159 12//12 161//161 -f 161//161 12//12 11//11 -f 82//82 69//69 83//83 -f 83//83 69//69 71//71 -f 83//83 71//71 303//303 -f 303//303 71//71 164//164 -f 303//303 164//164 304//304 -f 304//304 164//164 166//166 -f 304//304 166//166 305//305 -f 305//305 166//166 168//168 -f 305//305 168//168 12//12 -f 12//12 168//168 170//170 -f 12//12 170//170 10//10 -f 306//306 307//307 308//308 -f 308//308 307//307 171//171 -f 308//308 171//171 309//309 -f 309//309 171//171 169//169 -f 309//309 169//169 310//310 -f 310//310 169//169 167//167 -f 310//310 167//167 311//311 -f 311//311 167//167 165//165 -f 311//311 165//165 86//86 -f 86//86 165//165 163//163 -f 86//86 163//163 84//84 -f 84//84 163//163 162//162 -f 307//307 312//312 171//171 -f 171//171 312//312 313//313 -f 171//171 313//313 170//170 -f 170//170 313//313 314//314 -f 170//170 314//314 10//10 -f 85//85 66//66 86//86 -f 86//86 66//66 68//68 -f 86//86 68//68 311//311 -f 311//311 68//68 172//172 -f 311//311 172//172 310//310 -f 310//310 172//172 174//174 -f 310//310 174//174 309//309 -f 309//309 174//174 176//176 -f 309//309 176//176 308//308 -f 308//308 176//176 178//178 -f 308//308 178//178 306//306 -f 315//315 316//316 317//317 -f 317//317 316//316 179//179 -f 317//317 179//179 318//318 -f 318//318 179//179 177//177 -f 318//318 177//177 319//319 -f 319//319 177//177 175//175 -f 319//319 175//175 320//320 -f 320//320 175//175 173//173 -f 320//320 173//173 321//321 -f 321//321 173//173 65//65 -f 321//321 65//65 322//322 -f 322//322 65//65 64//64 -f 316//316 323//323 179//179 -f 179//179 323//323 324//324 -f 179//179 324//324 178//178 -f 178//178 324//324 325//325 -f 178//178 325//325 306//306 -f 322//322 87//87 321//321 -f 321//321 87//87 89//89 -f 321//321 89//89 320//320 -f 320//320 89//89 180//180 -f 320//320 180//180 319//319 -f 319//319 180//180 182//182 -f 319//319 182//182 318//318 -f 318//318 182//182 184//184 -f 318//318 184//184 317//317 -f 317//317 184//184 186//186 -f 317//317 186//186 315//315 -f 326//326 327//327 328//328 -f 328//328 327//327 187//187 -f 328//328 187//187 329//329 -f 329//329 187//187 185//185 -f 329//329 185//185 330//330 -f 330//330 185//185 183//183 -f 330//330 183//183 331//331 -f 331//331 183//183 181//181 -f 331//331 181//181 332//332 -f 332//332 181//181 62//62 -f 332//332 62//62 333//333 -f 333//333 62//62 61//61 -f 327//327 334//334 187//187 -f 187//187 334//334 335//335 -f 187//187 335//335 186//186 -f 186//186 335//335 336//336 -f 186//186 336//336 315//315 -f 333//333 90//90 332//332 -f 332//332 90//90 92//92 -f 332//332 92//92 331//331 -f 331//331 92//92 188//188 -f 331//331 188//188 330//330 -f 330//330 188//188 190//190 -f 330//330 190//190 329//329 -f 329//329 190//190 192//192 -f 329//329 192//192 328//328 -f 328//328 192//192 194//194 -f 328//328 194//194 326//326 -f 200//200 337//337 195//195 -f 195//195 337//337 338//338 -f 195//195 338//338 194//194 -f 194//194 338//338 339//339 -f 194//194 339//339 326//326 -f 55//55 340//340 56//56 -f 56//56 340//340 341//341 -f 56//56 341//341 196//196 -f 196//196 341//341 342//342 -f 196//196 342//342 197//197 -f 197//197 342//342 343//343 -f 197//197 343//343 198//198 -f 198//198 343//343 344//344 -f 198//198 344//344 199//199 -f 199//199 344//344 9//9 -f 199//199 9//9 201//201 -f 201//201 9//9 8//8 -f 340//340 93//93 341//341 -f 341//341 93//93 95//95 -f 341//341 95//95 342//342 -f 342//342 95//95 202//202 -f 342//342 202//202 343//343 -f 343//343 202//202 204//204 -f 343//343 204//204 344//344 -f 344//344 204//204 206//206 -f 344//344 206//206 9//9 -f 9//9 206//206 208//208 -f 9//9 208//208 7//7 -f 345//345 346//346 347//347 -f 347//347 346//346 209//209 -f 347//347 209//209 348//348 -f 348//348 209//209 207//207 -f 348//348 207//207 349//349 -f 349//349 207//207 205//205 -f 349//349 205//205 350//350 -f 350//350 205//205 203//203 -f 350//350 203//203 351//351 -f 351//351 203//203 53//53 -f 351//351 53//53 352//352 -f 352//352 53//53 52//52 -f 346//346 353//353 209//209 -f 209//209 353//353 354//354 -f 209//209 354//354 208//208 -f 208//208 354//354 355//355 -f 208//208 355//355 7//7 -f 352//352 96//96 351//351 -f 351//351 96//96 98//98 -f 351//351 98//98 350//350 -f 350//350 98//98 210//210 -f 350//350 210//210 349//349 -f 349//349 210//210 212//212 -f 349//349 212//212 348//348 -f 348//348 212//212 214//214 -f 348//348 214//214 347//347 -f 347//347 214//214 216//216 -f 347//347 216//216 345//345 -f 356//356 357//357 358//358 -f 358//358 357//357 217//217 -f 358//358 217//217 359//359 -f 359//359 217//217 215//215 -f 359//359 215//215 360//360 -f 360//360 215//215 213//213 -f 360//360 213//213 361//361 -f 361//361 213//213 211//211 -f 361//361 211//211 47//47 -f 47//47 211//211 50//50 -f 47//47 50//50 45//45 -f 45//45 50//50 49//49 -f 357//357 362//362 217//217 -f 217//217 362//362 363//363 -f 217//217 363//363 216//216 -f 216//216 363//363 364//364 -f 216//216 364//364 345//345 -f 46//46 218//218 47//47 -f 47//47 218//218 219//219 -f 47//47 219//219 361//361 -f 361//361 219//219 220//220 -f 361//361 220//220 360//360 -f 360//360 220//220 222//222 -f 360//360 222//222 359//359 -f 359//359 222//222 224//224 -f 359//359 224//224 358//358 -f 358//358 224//224 226//226 -f 358//358 226//226 356//356 -f 232//232 365//365 227//227 -f 227//227 365//365 366//366 -f 227//227 366//366 226//226 -f 226//226 366//366 367//367 -f 226//226 367//367 356//356 -f 43//43 368//368 44//44 -f 44//44 368//368 369//369 -f 44//44 369//369 228//228 -f 228//228 369//369 370//370 -f 228//228 370//370 229//229 -f 229//229 370//370 371//371 -f 229//229 371//371 230//230 -f 230//230 371//371 372//372 -f 230//230 372//372 231//231 -f 231//231 372//372 6//6 -f 231//231 6//6 233//233 -f 233//233 6//6 5//5 -f 368//368 102//102 369//369 -f 369//369 102//102 104//104 -f 369//369 104//104 370//370 -f 370//370 104//104 234//234 -f 370//370 234//234 371//371 -f 371//371 234//234 236//236 -f 371//371 236//236 372//372 -f 372//372 236//236 238//238 -f 372//372 238//238 6//6 -f 6//6 238//238 240//240 -f 6//6 240//240 4//4 -f 373//373 374//374 375//375 -f 375//375 374//374 241//241 -f 375//375 241//241 376//376 -f 376//376 241//241 239//239 -f 376//376 239//239 377//377 -f 377//377 239//239 237//237 -f 377//377 237//237 378//378 -f 378//378 237//237 235//235 -f 378//378 235//235 38//38 -f 38//38 235//235 41//41 -f 38//38 41//41 36//36 -f 36//36 41//41 40//40 -f 374//374 379//379 241//241 -f 241//241 379//379 380//380 -f 241//241 380//380 240//240 -f 240//240 380//380 381//381 -f 240//240 381//381 4//4 -f 37//37 242//242 38//38 -f 38//38 242//242 243//243 -f 38//38 243//243 378//378 -f 378//378 243//243 244//244 -f 378//378 244//244 377//377 -f 377//377 244//244 246//246 -f 377//377 246//246 376//376 -f 376//376 246//246 248//248 -f 376//376 248//248 375//375 -f 375//375 248//248 250//250 -f 375//375 250//250 373//373 -f 382//382 383//383 384//384 -f 384//384 383//383 251//251 -f 384//384 251//251 385//385 -f 385//385 251//251 249//249 -f 385//385 249//249 386//386 -f 386//386 249//249 247//247 -f 386//386 247//247 387//387 -f 387//387 247//247 245//245 -f 387//387 245//245 35//35 -f 35//35 245//245 107//107 -f 35//35 107//107 33//33 -f 33//33 107//107 106//106 -f 383//383 388//388 251//251 -f 251//251 388//388 389//389 -f 251//251 389//389 250//250 -f 250//250 389//389 390//390 -f 250//250 390//390 373//373 -f 34//34 252//252 35//35 -f 35//35 252//252 253//253 -f 35//35 253//253 387//387 -f 387//387 253//253 254//254 -f 387//387 254//254 386//386 -f 386//386 254//254 256//256 -f 386//386 256//256 385//385 -f 385//385 256//256 258//258 -f 385//385 258//258 384//384 -f 384//384 258//258 260//260 -f 384//384 260//260 382//382 -f 391//391 392//392 393//393 -f 393//393 392//392 261//261 -f 393//393 261//261 394//394 -f 394//394 261//261 259//259 -f 394//394 259//259 395//395 -f 395//395 259//259 257//257 -f 395//395 257//257 396//396 -f 396//396 257//257 255//255 -f 396//396 255//255 32//32 -f 32//32 255//255 110//110 -f 32//32 110//110 30//30 -f 30//30 110//110 109//109 -f 392//392 397//397 261//261 -f 261//261 397//397 398//398 -f 261//261 398//398 260//260 -f 260//260 398//398 399//399 -f 260//260 399//399 382//382 -f 31//31 27//27 32//32 -f 32//32 27//27 29//29 -f 32//32 29//29 396//396 -f 396//396 29//29 264//264 -f 396//396 264//264 395//395 -f 395//395 264//264 266//266 -f 395//395 266//266 394//394 -f 394//394 266//266 268//268 -f 394//394 268//268 393//393 -f 393//393 268//268 270//270 -f 393//393 270//270 391//391 -f 276//276 400//400 271//271 -f 271//271 400//400 401//401 -f 271//271 401//401 270//270 -f 270//270 401//401 402//402 -f 270//270 402//402 391//391 -f 112//112 117//117 113//113 -f 113//113 117//117 13//13 -f 113//113 13//13 272//272 -f 272//272 13//13 15//15 -f 272//272 15//15 273//273 -f 273//273 15//15 125//125 -f 273//273 125//125 274//274 -f 274//274 125//125 127//127 -f 274//274 127//127 275//275 -f 275//275 127//127 130//130 -f 275//275 130//130 277//277 -f 277//277 130//130 403//403 -f 404//404 405//405 406//406 -f 21//21 23//23 121//121 -f 121//121 23//23 407//407 -f 121//121 407//407 133//133 -f 133//133 407//407 408//408 -f 133//133 408//408 132//132 -f 132//132 408//408 409//409 -f 132//132 409//409 131//131 -f 131//131 409//409 404//404 -f 131//131 404//404 130//130 -f 130//130 404//404 406//406 -f 130//130 406//406 403//403 -f 22//22 20//20 23//23 -f 23//23 20//20 410//410 -f 23//23 410//410 407//407 -f 407//407 410//410 411//411 -f 407//407 411//411 408//408 -f 408//408 411//411 412//412 -f 408//408 412//412 409//409 -f 409//409 412//412 3//3 -f 409//409 3//3 404//404 -f 404//404 3//3 2//2 -f 404//404 2//2 405//405 -f 16//16 18//18 20//20 -f 20//20 18//18 124//124 -f 20//20 124//124 410//410 -f 410//410 124//124 278//278 -f 410//410 278//278 411//411 -f 411//411 278//278 279//279 -f 411//411 279//279 412//412 -f 412//412 279//279 280//280 -f 412//412 280//280 3//3 -f 3//3 280//280 282//282 -f 3//3 282//282 1//1 -f 413//413 390//390 414//414 -f 414//414 390//390 389//389 -f 389//389 388//388 414//414 -f 414//414 388//388 383//383 -f 414//414 383//383 415//415 -f 383//383 382//382 415//415 -f 415//415 382//382 399//399 -f 415//415 399//399 416//416 -f 416//416 399//399 398//398 -f 398//398 397//397 416//416 -f 416//416 397//397 392//392 -f 416//416 392//392 417//417 -f 392//392 391//391 417//417 -f 417//417 391//391 402//402 -f 417//417 402//402 418//418 -f 402//402 401//401 418//418 -f 418//418 401//401 400//400 -f 418//418 400//400 419//419 -f 419//419 400//400 276//276 -f 276//276 277//277 419//419 -f 419//419 277//277 403//403 -f 419//419 403//403 420//420 -f 403//403 406//406 420//420 -f 420//420 406//406 405//405 -f 420//420 405//405 421//421 -f 421//421 405//405 2//2 -f 2//2 1//1 421//421 -f 421//421 1//1 282//282 -f 421//421 282//282 422//422 -f 282//282 281//281 422//422 -f 422//422 281//281 290//290 -f 422//422 290//290 423//423 -f 423//423 290//290 289//289 -f 289//289 288//288 423//423 -f 423//423 288//288 284//284 -f 423//423 284//284 424//424 -f 284//284 283//283 424//424 -f 424//424 283//283 299//299 -f 424//424 299//299 425//425 -f 425//425 299//299 298//298 -f 298//298 297//297 425//425 -f 425//425 297//297 292//292 -f 425//425 292//292 426//426 -f 292//292 291//291 426//426 -f 426//426 291//291 302//302 -f 426//426 302//302 427//427 -f 302//302 301//301 427//427 -f 427//427 301//301 300//300 -f 427//427 300//300 428//428 -f 428//428 300//300 160//160 -f 160//160 161//161 428//428 -f 428//428 161//161 11//11 -f 428//428 11//11 429//429 -f 11//11 10//10 429//429 -f 429//429 10//10 314//314 -f 429//429 314//314 430//430 -f 430//430 314//314 313//313 -f 313//313 312//312 430//430 -f 430//430 312//312 307//307 -f 430//430 307//307 431//431 -f 307//307 306//306 431//431 -f 431//431 306//306 325//325 -f 431//431 325//325 432//432 -f 432//432 325//325 324//324 -f 324//324 323//323 432//432 -f 432//432 323//323 316//316 -f 432//432 316//316 433//433 -f 335//335 434//434 336//336 -f 336//336 434//434 433//433 -f 336//336 433//433 315//315 -f 315//315 433//433 316//316 -f 335//335 334//334 434//434 -f 434//434 334//334 327//327 -f 434//434 327//327 435//435 -f 327//327 326//326 435//435 -f 435//435 326//326 339//339 -f 435//435 339//339 436//436 -f 339//339 338//338 436//436 -f 436//436 338//338 337//337 -f 436//436 337//337 437//437 -f 437//437 337//337 200//200 -f 200//200 201//201 437//437 -f 437//437 201//201 8//8 -f 437//437 8//8 438//438 -f 8//8 7//7 438//438 -f 438//438 7//7 355//355 -f 438//438 355//355 439//439 -f 439//439 355//355 354//354 -f 354//354 353//353 439//439 -f 439//439 353//353 346//346 -f 439//439 346//346 440//440 -f 346//346 345//345 440//440 -f 440//440 345//345 364//364 -f 440//440 364//364 441//441 -f 441//441 364//364 363//363 -f 363//363 362//362 441//441 -f 441//441 362//362 357//357 -f 441//441 357//357 442//442 -f 366//366 443//443 367//367 -f 367//367 443//443 442//442 -f 367//367 442//442 356//356 -f 356//356 442//442 357//357 -f 366//366 365//365 443//443 -f 443//443 365//365 232//232 -f 443//443 232//232 444//444 -f 232//232 233//233 444//444 -f 444//444 233//233 5//5 -f 444//444 5//5 445//445 -f 5//5 4//4 445//445 -f 445//445 4//4 381//381 -f 445//445 381//381 446//446 -f 446//446 381//381 380//380 -f 380//380 379//379 446//446 -f 446//446 379//379 374//374 -f 446//446 374//374 413//413 -f 413//413 374//374 373//373 -f 413//413 373//373 390//390 -f 422//422 447//447 448//448 -f 449//449 450//450 431//431 -f 431//431 450//450 430//430 -f 449//449 431//431 451//451 -f 451//451 431//431 432//432 -f 451//451 432//432 452//452 -f 422//422 448//448 421//421 -f 450//450 453//453 430//430 -f 430//430 453//453 454//454 -f 430//430 454//454 429//429 -f 452//452 432//432 455//455 -f 455//455 432//432 433//433 -f 455//455 433//433 456//456 -f 457//457 458//458 427//427 -f 427//427 458//458 426//426 -f 459//459 460//460 435//435 -f 435//435 460//460 434//434 -f 446//446 461//461 462//462 -f 447//447 422//422 463//463 -f 463//463 422//422 423//423 -f 463//463 423//423 464//464 -f 460//460 465//465 434//434 -f 434//434 465//465 466//466 -f 434//434 466//466 433//433 -f 433//433 466//466 467//467 -f 433//433 467//467 456//456 -f 446//446 462//462 445//445 -f 461//461 446//446 468//468 -f 468//468 446//446 413//413 -f 468//468 413//413 469//469 -f 464//464 423//423 470//470 -f 470//470 423//423 424//424 -f 470//470 424//424 471//471 -f 425//425 472//472 424//424 -f 424//424 472//472 473//473 -f 424//424 473//473 471//471 -f 458//458 474//474 426//426 -f 426//426 474//474 475//475 -f 426//426 475//475 425//425 -f 425//425 475//475 476//476 -f 425//425 476//476 472//472 -f 454//454 477//477 429//429 -f 429//429 477//477 478//478 -f 429//429 478//478 428//428 -f 459//459 435//435 479//479 -f 479//479 435//435 436//436 -f 479//479 436//436 480//480 -f 481//481 482//482 439//439 -f 439//439 482//482 438//438 -f 481//481 439//439 483//483 -f 483//483 439//439 440//440 -f 483//483 440//440 484//484 -f 469//469 413//413 485//485 -f 485//485 413//413 414//414 -f 485//485 414//414 486//486 -f 486//486 414//414 487//487 -f 487//487 414//414 415//415 -f 487//487 415//415 488//488 -f 489//489 490//490 418//418 -f 418//418 490//490 417//417 -f 489//489 418//418 491//491 -f 491//491 418//418 419//419 -f 491//491 419//419 492//492 -f 478//478 493//493 428//428 -f 428//428 493//493 494//494 -f 428//428 494//494 427//427 -f 427//427 494//494 495//495 -f 427//427 495//495 457//457 -f 480//480 436//436 496//496 -f 496//496 436//436 437//437 -f 496//496 437//437 497//497 -f 482//482 498//498 438//438 -f 438//438 498//498 499//499 -f 438//438 499//499 437//437 -f 437//437 499//499 500//500 -f 437//437 500//500 497//497 -f 441//441 442//442 501//501 -f 488//488 415//415 502//502 -f 502//502 415//415 416//416 -f 502//502 416//416 503//503 -f 490//490 504//504 417//417 -f 417//417 504//504 505//505 -f 417//417 505//505 416//416 -f 416//416 505//505 506//506 -f 416//416 506//506 503//503 -f 492//492 419//419 507//507 -f 507//507 419//419 420//420 -f 507//507 420//420 508//508 -f 448//448 509//509 421//421 -f 421//421 509//509 510//510 -f 421//421 510//510 420//420 -f 420//420 510//510 511//511 -f 420//420 511//511 508//508 -f 501//501 512//512 441//441 -f 441//441 512//512 513//513 -f 441//441 513//513 440//440 -f 440//440 513//513 514//514 -f 440//440 514//514 484//484 -f 515//515 516//516 444//444 -f 444//444 516//516 443//443 -f 516//516 517//517 443//443 -f 443//443 517//517 518//518 -f 443//443 518//518 442//442 -f 442//442 518//518 519//519 -f 442//442 519//519 501//501 -f 462//462 520//520 445//445 -f 445//445 520//520 521//521 -f 445//445 521//521 444//444 -f 444//444 521//521 522//522 -f 444//444 522//522 515//515 -f 448//448 523//523 509//509 -f 509//509 523//523 524//524 -f 509//509 524//524 510//510 -f 510//510 524//524 525//525 -f 510//510 525//525 511//511 -f 511//511 525//525 526//526 -f 511//511 526//526 508//508 -f 508//508 526//526 527//527 -f 508//508 527//527 507//507 -f 507//507 527//527 528//528 -f 507//507 528//528 492//492 -f 492//492 528//528 529//529 -f 492//492 529//529 491//491 -f 491//491 529//529 530//530 -f 491//491 530//530 489//489 -f 489//489 530//530 531//531 -f 489//489 531//531 490//490 -f 490//490 531//531 532//532 -f 490//490 532//532 504//504 -f 504//504 532//532 533//533 -f 504//504 533//533 505//505 -f 505//505 533//533 534//534 -f 505//505 534//534 506//506 -f 506//506 534//534 535//535 -f 506//506 535//535 503//503 -f 503//503 535//535 536//536 -f 503//503 536//536 502//502 -f 502//502 536//536 537//537 -f 502//502 537//537 488//488 -f 488//488 537//537 538//538 -f 488//488 538//538 487//487 -f 487//487 538//538 539//539 -f 487//487 539//539 486//486 -f 486//486 539//539 540//540 -f 486//486 540//540 485//485 -f 485//485 540//540 541//541 -f 485//485 541//541 469//469 -f 469//469 541//541 542//542 -f 469//469 542//542 468//468 -f 468//468 542//542 543//543 -f 468//468 543//543 461//461 -f 461//461 543//543 544//544 -f 461//461 544//544 462//462 -f 462//462 544//544 545//545 -f 462//462 545//545 520//520 -f 520//520 545//545 546//546 -f 520//520 546//546 521//521 -f 521//521 546//546 547//547 -f 521//521 547//547 522//522 -f 522//522 547//547 548//548 -f 522//522 548//548 515//515 -f 515//515 548//548 549//549 -f 515//515 549//549 516//516 -f 516//516 549//549 550//550 -f 516//516 550//550 517//517 -f 517//517 550//550 551//551 -f 517//517 551//551 518//518 -f 518//518 551//551 552//552 -f 518//518 552//552 519//519 -f 519//519 552//552 553//553 -f 519//519 553//553 501//501 -f 501//501 553//553 554//554 -f 501//501 554//554 512//512 -f 512//512 554//554 555//555 -f 512//512 555//555 513//513 -f 513//513 555//555 556//556 -f 513//513 556//556 514//514 -f 514//514 556//556 557//557 -f 514//514 557//557 484//484 -f 484//484 557//557 558//558 -f 484//484 558//558 483//483 -f 483//483 558//558 559//559 -f 483//483 559//559 481//481 -f 481//481 559//559 560//560 -f 481//481 560//560 482//482 -f 482//482 560//560 561//561 -f 482//482 561//561 498//498 -f 498//498 561//561 562//562 -f 498//498 562//562 499//499 -f 499//499 562//562 563//563 -f 499//499 563//563 500//500 -f 500//500 563//563 564//564 -f 500//500 564//564 497//497 -f 497//497 564//564 565//565 -f 497//497 565//565 496//496 -f 496//496 565//565 566//566 -f 496//496 566//566 480//480 -f 480//480 566//566 567//567 -f 480//480 567//567 479//479 -f 479//479 567//567 568//568 -f 479//479 568//568 459//459 -f 459//459 568//568 569//569 -f 459//459 569//569 460//460 -f 460//460 569//569 570//570 -f 460//460 570//570 465//465 -f 465//465 570//570 571//571 -f 465//465 571//571 466//466 -f 466//466 571//571 572//572 -f 466//466 572//572 467//467 -f 467//467 572//572 573//573 -f 467//467 573//573 456//456 -f 456//456 573//573 574//574 -f 456//456 574//574 455//455 -f 455//455 574//574 575//575 -f 455//455 575//575 452//452 -f 452//452 575//575 576//576 -f 452//452 576//576 451//451 -f 451//451 576//576 577//577 -f 451//451 577//577 449//449 -f 449//449 577//577 578//578 -f 449//449 578//578 450//450 -f 450//450 578//578 579//579 -f 450//450 579//579 453//453 -f 453//453 579//579 580//580 -f 453//453 580//580 454//454 -f 454//454 580//580 581//581 -f 454//454 581//581 477//477 -f 477//477 581//581 582//582 -f 477//477 582//582 478//478 -f 478//478 582//582 583//583 -f 478//478 583//583 493//493 -f 493//493 583//583 584//584 -f 493//493 584//584 494//494 -f 494//494 584//584 585//585 -f 494//494 585//585 495//495 -f 495//495 585//585 586//586 -f 495//495 586//586 457//457 -f 457//457 586//586 587//587 -f 457//457 587//587 458//458 -f 458//458 587//587 588//588 -f 458//458 588//588 474//474 -f 474//474 588//588 589//589 -f 474//474 589//589 475//475 -f 475//475 589//589 590//590 -f 475//475 590//590 476//476 -f 476//476 590//590 591//591 -f 476//476 591//591 472//472 -f 472//472 591//591 592//592 -f 472//472 592//592 473//473 -f 473//473 592//592 593//593 -f 473//473 593//593 471//471 -f 471//471 593//593 594//594 -f 471//471 594//594 470//470 -f 470//470 594//594 595//595 -f 470//470 595//595 464//464 -f 464//464 595//595 596//596 -f 464//464 596//596 463//463 -f 463//463 596//596 597//597 -f 463//463 597//597 447//447 -f 447//447 597//597 598//598 -f 447//447 598//598 448//448 -f 448//448 598//598 523//523 -f 598//598 599//599 523//523 -f 523//523 599//599 600//600 -f 523//523 600//600 524//524 -f 524//524 600//600 601//601 -f 524//524 601//601 525//525 -f 525//525 601//601 602//602 -f 525//525 602//602 526//526 -f 526//526 602//602 603//603 -f 526//526 603//603 527//527 -f 527//527 603//603 604//604 -f 527//527 604//604 528//528 -f 528//528 604//604 605//605 -f 528//528 605//605 529//529 -f 529//529 605//605 606//606 -f 529//529 606//606 530//530 -f 530//530 606//606 607//607 -f 530//530 607//607 531//531 -f 531//531 607//607 608//608 -f 531//531 608//608 532//532 -f 532//532 608//608 609//609 -f 532//532 609//609 533//533 -f 533//533 609//609 610//610 -f 533//533 610//610 534//534 -f 534//534 610//610 611//611 -f 534//534 611//611 535//535 -f 535//535 611//611 612//612 -f 535//535 612//612 536//536 -f 536//536 612//612 613//613 -f 536//536 613//613 537//537 -f 537//537 613//613 614//614 -f 537//537 614//614 538//538 -f 538//538 614//614 615//615 -f 538//538 615//615 539//539 -f 539//539 615//615 616//616 -f 539//539 616//616 540//540 -f 540//540 616//616 617//617 -f 540//540 617//617 541//541 -f 541//541 617//617 618//618 -f 541//541 618//618 542//542 -f 542//542 618//618 619//619 -f 542//542 619//619 543//543 -f 543//543 619//619 620//620 -f 543//543 620//620 544//544 -f 544//544 620//620 621//621 -f 544//544 621//621 545//545 -f 545//545 621//621 622//622 -f 545//545 622//622 546//546 -f 546//546 622//622 623//623 -f 546//546 623//623 547//547 -f 547//547 623//623 624//624 -f 547//547 624//624 548//548 -f 548//548 624//624 625//625 -f 548//548 625//625 549//549 -f 549//549 625//625 626//626 -f 549//549 626//626 550//550 -f 550//550 626//626 627//627 -f 550//550 627//627 551//551 -f 551//551 627//627 628//628 -f 551//551 628//628 552//552 -f 552//552 628//628 629//629 -f 552//552 629//629 553//553 -f 553//553 629//629 630//630 -f 553//553 630//630 554//554 -f 554//554 630//630 631//631 -f 554//554 631//631 555//555 -f 555//555 631//631 632//632 -f 555//555 632//632 556//556 -f 556//556 632//632 633//633 -f 556//556 633//633 557//557 -f 557//557 633//633 634//634 -f 557//557 634//634 558//558 -f 558//558 634//634 635//635 -f 558//558 635//635 559//559 -f 559//559 635//635 636//636 -f 559//559 636//636 560//560 -f 560//560 636//636 637//637 -f 560//560 637//637 561//561 -f 561//561 637//637 638//638 -f 561//561 638//638 562//562 -f 562//562 638//638 639//639 -f 562//562 639//639 563//563 -f 563//563 639//639 640//640 -f 563//563 640//640 564//564 -f 564//564 640//640 641//641 -f 564//564 641//641 565//565 -f 565//565 641//641 642//642 -f 565//565 642//642 566//566 -f 566//566 642//642 643//643 -f 566//566 643//643 567//567 -f 567//567 643//643 644//644 -f 567//567 644//644 568//568 -f 568//568 644//644 645//645 -f 568//568 645//645 569//569 -f 569//569 645//645 646//646 -f 569//569 646//646 570//570 -f 570//570 646//646 647//647 -f 570//570 647//647 571//571 -f 571//571 647//647 648//648 -f 571//571 648//648 572//572 -f 572//572 648//648 649//649 -f 572//572 649//649 573//573 -f 573//573 649//649 650//650 -f 573//573 650//650 574//574 -f 574//574 650//650 651//651 -f 574//574 651//651 575//575 -f 575//575 651//651 652//652 -f 575//575 652//652 576//576 -f 576//576 652//652 653//653 -f 576//576 653//653 577//577 -f 577//577 653//653 654//654 -f 577//577 654//654 578//578 -f 578//578 654//654 655//655 -f 578//578 655//655 579//579 -f 579//579 655//655 656//656 -f 579//579 656//656 580//580 -f 580//580 656//656 657//657 -f 580//580 657//657 581//581 -f 581//581 657//657 658//658 -f 581//581 658//658 582//582 -f 582//582 658//658 659//659 -f 582//582 659//659 583//583 -f 583//583 659//659 660//660 -f 583//583 660//660 584//584 -f 584//584 660//660 661//661 -f 584//584 661//661 585//585 -f 585//585 661//661 662//662 -f 585//585 662//662 586//586 -f 586//586 662//662 663//663 -f 586//586 663//663 587//587 -f 587//587 663//663 664//664 -f 587//587 664//664 588//588 -f 588//588 664//664 665//665 -f 588//588 665//665 589//589 -f 589//589 665//665 666//666 -f 589//589 666//666 590//590 -f 590//590 666//666 667//667 -f 590//590 667//667 591//591 -f 591//591 667//667 668//668 -f 591//591 668//668 592//592 -f 592//592 668//668 669//669 -f 592//592 669//669 593//593 -f 593//593 669//669 670//670 -f 593//593 670//670 594//594 -f 594//594 670//670 671//671 -f 594//594 671//671 595//595 -f 595//595 671//671 672//672 -f 595//595 672//672 596//596 -f 596//596 672//672 673//673 -f 596//596 673//673 597//597 -f 597//597 673//673 674//674 -f 597//597 674//674 598//598 -f 598//598 674//674 599//599 -f 674//674 675//675 599//599 -f 599//599 675//675 676//676 -f 599//599 676//676 600//600 -f 600//600 676//676 677//677 -f 600//600 677//677 601//601 -f 601//601 677//677 678//678 -f 601//601 678//678 602//602 -f 602//602 678//678 679//679 -f 602//602 679//679 603//603 -f 603//603 679//679 680//680 -f 603//603 680//680 604//604 -f 604//604 680//680 681//681 -f 604//604 681//681 605//605 -f 605//605 681//681 682//682 -f 605//605 682//682 606//606 -f 606//606 682//682 683//683 -f 606//606 683//683 607//607 -f 607//607 683//683 684//684 -f 607//607 684//684 608//608 -f 608//608 684//684 685//685 -f 608//608 685//685 609//609 -f 609//609 685//685 686//686 -f 609//609 686//686 610//610 -f 610//610 686//686 687//687 -f 610//610 687//687 611//611 -f 611//611 687//687 688//688 -f 611//611 688//688 612//612 -f 612//612 688//688 689//689 -f 612//612 689//689 613//613 -f 613//613 689//689 690//690 -f 613//613 690//690 614//614 -f 614//614 690//690 691//691 -f 614//614 691//691 615//615 -f 615//615 691//691 692//692 -f 615//615 692//692 616//616 -f 616//616 692//692 693//693 -f 616//616 693//693 617//617 -f 617//617 693//693 694//694 -f 617//617 694//694 618//618 -f 618//618 694//694 695//695 -f 618//618 695//695 619//619 -f 619//619 695//695 696//696 -f 619//619 696//696 620//620 -f 620//620 696//696 697//697 -f 620//620 697//697 621//621 -f 621//621 697//697 698//698 -f 621//621 698//698 622//622 -f 622//622 698//698 699//699 -f 622//622 699//699 623//623 -f 623//623 699//699 700//700 -f 623//623 700//700 624//624 -f 624//624 700//700 701//701 -f 624//624 701//701 625//625 -f 625//625 701//701 702//702 -f 625//625 702//702 626//626 -f 626//626 702//702 703//703 -f 626//626 703//703 627//627 -f 627//627 703//703 704//704 -f 627//627 704//704 628//628 -f 628//628 704//704 705//705 -f 628//628 705//705 629//629 -f 629//629 705//705 706//706 -f 629//629 706//706 630//630 -f 630//630 706//706 707//707 -f 630//630 707//707 631//631 -f 631//631 707//707 708//708 -f 631//631 708//708 632//632 -f 632//632 708//708 709//709 -f 632//632 709//709 633//633 -f 633//633 709//709 710//710 -f 633//633 710//710 634//634 -f 634//634 710//710 711//711 -f 634//634 711//711 635//635 -f 635//635 711//711 712//712 -f 635//635 712//712 636//636 -f 636//636 712//712 713//713 -f 636//636 713//713 637//637 -f 637//637 713//713 714//714 -f 637//637 714//714 638//638 -f 638//638 714//714 715//715 -f 638//638 715//715 639//639 -f 639//639 715//715 716//716 -f 639//639 716//716 640//640 -f 640//640 716//716 717//717 -f 640//640 717//717 641//641 -f 641//641 717//717 718//718 -f 641//641 718//718 642//642 -f 642//642 718//718 719//719 -f 642//642 719//719 643//643 -f 643//643 719//719 720//720 -f 643//643 720//720 644//644 -f 644//644 720//720 721//721 -f 644//644 721//721 645//645 -f 645//645 721//721 722//722 -f 645//645 722//722 646//646 -f 646//646 722//722 723//723 -f 646//646 723//723 647//647 -f 647//647 723//723 724//724 -f 647//647 724//724 648//648 -f 648//648 724//724 725//725 -f 648//648 725//725 649//649 -f 649//649 725//725 726//726 -f 649//649 726//726 650//650 -f 650//650 726//726 727//727 -f 650//650 727//727 651//651 -f 651//651 727//727 728//728 -f 651//651 728//728 652//652 -f 652//652 728//728 729//729 -f 652//652 729//729 653//653 -f 653//653 729//729 730//730 -f 653//653 730//730 654//654 -f 654//654 730//730 731//731 -f 654//654 731//731 655//655 -f 655//655 731//731 732//732 -f 655//655 732//732 656//656 -f 656//656 732//732 733//733 -f 656//656 733//733 657//657 -f 657//657 733//733 734//734 -f 657//657 734//734 658//658 -f 658//658 734//734 735//735 -f 658//658 735//735 659//659 -f 659//659 735//735 736//736 -f 659//659 736//736 660//660 -f 660//660 736//736 737//737 -f 660//660 737//737 661//661 -f 661//661 737//737 738//738 -f 661//661 738//738 662//662 -f 662//662 738//738 739//739 -f 662//662 739//739 663//663 -f 663//663 739//739 740//740 -f 663//663 740//740 664//664 -f 664//664 740//740 741//741 -f 664//664 741//741 665//665 -f 665//665 741//741 742//742 -f 665//665 742//742 666//666 -f 666//666 742//742 743//743 -f 666//666 743//743 667//667 -f 667//667 743//743 744//744 -f 667//667 744//744 668//668 -f 668//668 744//744 745//745 -f 668//668 745//745 669//669 -f 669//669 745//745 746//746 -f 669//669 746//746 670//670 -f 670//670 746//746 747//747 -f 670//670 747//747 671//671 -f 671//671 747//747 748//748 -f 671//671 748//748 672//672 -f 672//672 748//748 749//749 -f 672//672 749//749 673//673 -f 673//673 749//749 750//750 -f 673//673 750//750 674//674 -f 674//674 750//750 675//675 -f 692//692 751//751 693//693 -f 693//693 751//751 752//752 -f 693//693 752//752 694//694 -f 694//694 752//752 753//753 -f 694//694 753//753 695//695 -f 695//695 753//753 754//754 -f 695//695 754//754 696//696 -f 696//696 754//754 755//755 -f 696//696 755//755 697//697 -f 697//697 755//755 756//756 -f 697//697 756//756 698//698 -f 698//698 756//756 757//757 -f 698//698 757//757 699//699 -f 699//699 757//757 758//758 -f 699//699 758//758 700//700 -f 700//700 758//758 759//759 -f 700//700 759//759 701//701 -f 701//701 759//759 760//760 -f 701//701 760//760 702//702 -f 702//702 760//760 761//761 -f 702//702 761//761 703//703 -f 703//703 761//761 762//762 -f 703//703 762//762 704//704 -f 704//704 762//762 763//763 -f 704//704 763//763 705//705 -f 705//705 763//763 764//764 -f 705//705 764//764 706//706 -f 706//706 764//764 765//765 -f 706//706 765//765 707//707 -f 707//707 765//765 766//766 -f 707//707 766//766 708//708 -f 708//708 766//766 767//767 -f 708//708 767//767 709//709 -f 709//709 767//767 768//768 -f 709//709 768//768 710//710 -f 710//710 768//768 769//769 -f 710//710 769//769 711//711 -f 711//711 769//769 770//770 -f 711//711 770//770 712//712 -f 712//712 770//770 771//771 -f 712//712 771//771 713//713 -f 713//713 771//771 772//772 -f 713//713 772//772 714//714 -f 714//714 772//772 773//773 -f 714//714 773//773 715//715 -f 715//715 773//773 774//774 -f 715//715 774//774 716//716 -f 716//716 774//774 775//775 -f 716//716 775//775 717//717 -f 717//717 775//775 776//776 -f 717//717 776//776 718//718 -f 718//718 776//776 777//777 -f 718//718 777//777 719//719 -f 719//719 777//777 778//778 -f 719//719 778//778 720//720 -f 720//720 778//778 779//779 -f 720//720 779//779 721//721 -f 721//721 779//779 780//780 -f 721//721 780//780 722//722 -f 722//722 780//780 781//781 -f 722//722 781//781 723//723 -f 723//723 781//781 782//782 -f 723//723 782//782 724//724 -f 724//724 782//782 783//783 -f 724//724 783//783 725//725 -f 725//725 783//783 784//784 -f 725//725 784//784 726//726 -f 726//726 784//784 785//785 -f 726//726 785//785 727//727 -f 727//727 785//785 786//786 -f 727//727 786//786 728//728 -f 728//728 786//786 787//787 -f 728//728 787//787 729//729 -f 729//729 787//787 788//788 -f 729//729 788//788 730//730 -f 730//730 788//788 789//789 -f 730//730 789//789 731//731 -f 731//731 789//789 790//790 -f 731//731 790//790 732//732 -f 732//732 790//790 791//791 -f 732//732 791//791 733//733 -f 733//733 791//791 792//792 -f 733//733 792//792 734//734 -f 734//734 792//792 793//793 -f 734//734 793//793 735//735 -f 735//735 793//793 794//794 -f 735//735 794//794 736//736 -f 736//736 794//794 795//795 -f 736//736 795//795 737//737 -f 737//737 795//795 796//796 -f 737//737 796//796 738//738 -f 738//738 796//796 797//797 -f 738//738 797//797 739//739 -f 739//739 797//797 798//798 -f 739//739 798//798 740//740 -f 740//740 798//798 799//799 -f 740//740 799//799 741//741 -f 741//741 799//799 800//800 -f 741//741 800//800 742//742 -f 742//742 800//800 801//801 -f 742//742 801//801 743//743 -f 743//743 801//801 802//802 -f 743//743 802//802 744//744 -f 744//744 802//802 803//803 -f 744//744 803//803 745//745 -f 745//745 803//803 804//804 -f 745//745 804//804 746//746 -f 746//746 804//804 805//805 -f 746//746 805//805 747//747 -f 747//747 805//805 806//806 -f 747//747 806//806 748//748 -f 748//748 806//806 807//807 -f 748//748 807//807 749//749 -f 749//749 807//807 808//808 -f 749//749 808//808 750//750 -f 750//750 808//808 809//809 -f 750//750 809//809 675//675 -f 675//675 809//809 810//810 -f 675//675 810//810 676//676 -f 676//676 810//810 811//811 -f 676//676 811//811 677//677 -f 677//677 811//811 812//812 -f 677//677 812//812 678//678 -f 678//678 812//812 813//813 -f 678//678 813//813 679//679 -f 679//679 813//813 814//814 -f 679//679 814//814 680//680 -f 680//680 814//814 815//815 -f 680//680 815//815 681//681 -f 681//681 815//815 816//816 -f 681//681 816//816 682//682 -f 682//682 816//816 817//817 -f 682//682 817//817 683//683 -f 683//683 817//817 818//818 -f 683//683 818//818 684//684 -f 684//684 818//818 819//819 -f 684//684 819//819 685//685 -f 685//685 819//819 820//820 -f 685//685 820//820 686//686 -f 686//686 820//820 821//821 -f 686//686 821//821 687//687 -f 687//687 821//821 822//822 -f 687//687 822//822 688//688 -f 688//688 822//822 823//823 -f 688//688 823//823 689//689 -f 689//689 823//823 824//824 -f 689//689 824//824 690//690 -f 690//690 824//824 825//825 -f 690//690 825//825 691//691 -f 691//691 825//825 826//826 -f 691//691 826//826 692//692 -f 692//692 826//826 751//751 -f 809//809 827//827 810//810 -f 810//810 827//827 828//828 -f 810//810 828//828 811//811 -f 811//811 828//828 829//829 -f 811//811 829//829 812//812 -f 812//812 829//829 830//830 -f 812//812 830//830 813//813 -f 813//813 830//830 831//831 -f 813//813 831//831 814//814 -f 814//814 831//831 832//832 -f 814//814 832//832 815//815 -f 815//815 832//832 833//833 -f 815//815 833//833 816//816 -f 816//816 833//833 834//834 -f 816//816 834//834 817//817 -f 817//817 834//834 835//835 -f 817//817 835//835 818//818 -f 818//818 835//835 836//836 -f 818//818 836//836 819//819 -f 819//819 836//836 837//837 -f 819//819 837//837 820//820 -f 820//820 837//837 838//838 -f 820//820 838//838 821//821 -f 821//821 838//838 839//839 -f 821//821 839//839 822//822 -f 822//822 839//839 840//840 -f 822//822 840//840 823//823 -f 823//823 840//840 841//841 -f 823//823 841//841 824//824 -f 824//824 841//841 842//842 -f 824//824 842//842 825//825 -f 825//825 842//842 843//843 -f 825//825 843//843 826//826 -f 826//826 843//843 844//844 -f 826//826 844//844 751//751 -f 751//751 844//844 845//845 -f 751//751 845//845 752//752 -f 752//752 845//845 846//846 -f 752//752 846//846 753//753 -f 753//753 846//846 847//847 -f 753//753 847//847 754//754 -f 754//754 847//847 848//848 -f 754//754 848//848 755//755 -f 755//755 848//848 849//849 -f 755//755 849//849 756//756 -f 756//756 849//849 850//850 -f 756//756 850//850 757//757 -f 757//757 850//850 851//851 -f 757//757 851//851 758//758 -f 758//758 851//851 852//852 -f 758//758 852//852 759//759 -f 759//759 852//852 853//853 -f 759//759 853//853 760//760 -f 760//760 853//853 854//854 -f 760//760 854//854 761//761 -f 761//761 854//854 855//855 -f 761//761 855//855 762//762 -f 762//762 855//855 856//856 -f 762//762 856//856 763//763 -f 763//763 856//856 857//857 -f 763//763 857//857 764//764 -f 764//764 857//857 858//858 -f 764//764 858//858 765//765 -f 765//765 858//858 859//859 -f 765//765 859//859 766//766 -f 766//766 859//859 860//860 -f 766//766 860//860 767//767 -f 767//767 860//860 861//861 -f 767//767 861//861 768//768 -f 768//768 861//861 862//862 -f 768//768 862//862 769//769 -f 769//769 862//862 863//863 -f 769//769 863//863 770//770 -f 770//770 863//863 864//864 -f 770//770 864//864 771//771 -f 771//771 864//864 865//865 -f 771//771 865//865 772//772 -f 772//772 865//865 866//866 -f 772//772 866//866 773//773 -f 773//773 866//866 867//867 -f 773//773 867//867 774//774 -f 774//774 867//867 868//868 -f 774//774 868//868 775//775 -f 775//775 868//868 869//869 -f 775//775 869//869 776//776 -f 776//776 869//869 870//870 -f 776//776 870//870 777//777 -f 777//777 870//870 871//871 -f 777//777 871//871 778//778 -f 778//778 871//871 872//872 -f 778//778 872//872 779//779 -f 779//779 872//872 873//873 -f 779//779 873//873 780//780 -f 780//780 873//873 874//874 -f 780//780 874//874 781//781 -f 781//781 874//874 875//875 -f 781//781 875//875 782//782 -f 782//782 875//875 876//876 -f 782//782 876//876 783//783 -f 783//783 876//876 877//877 -f 783//783 877//877 784//784 -f 784//784 877//877 878//878 -f 784//784 878//878 785//785 -f 785//785 878//878 879//879 -f 785//785 879//879 786//786 -f 786//786 879//879 880//880 -f 786//786 880//880 787//787 -f 787//787 880//880 881//881 -f 787//787 881//881 788//788 -f 788//788 881//881 882//882 -f 788//788 882//882 789//789 -f 789//789 882//882 883//883 -f 789//789 883//883 790//790 -f 790//790 883//883 884//884 -f 790//790 884//884 791//791 -f 791//791 884//884 885//885 -f 791//791 885//885 792//792 -f 792//792 885//885 886//886 -f 792//792 886//886 793//793 -f 793//793 886//886 887//887 -f 793//793 887//887 794//794 -f 794//794 887//887 888//888 -f 794//794 888//888 795//795 -f 795//795 888//888 889//889 -f 795//795 889//889 796//796 -f 796//796 889//889 890//890 -f 796//796 890//890 797//797 -f 797//797 890//890 891//891 -f 797//797 891//891 798//798 -f 798//798 891//891 892//892 -f 798//798 892//892 799//799 -f 799//799 892//892 893//893 -f 799//799 893//893 800//800 -f 800//800 893//893 894//894 -f 800//800 894//894 801//801 -f 801//801 894//894 895//895 -f 801//801 895//895 802//802 -f 802//802 895//895 896//896 -f 802//802 896//896 803//803 -f 803//803 896//896 897//897 -f 803//803 897//897 804//804 -f 804//804 897//897 898//898 -f 804//804 898//898 805//805 -f 805//805 898//898 899//899 -f 805//805 899//899 806//806 -f 806//806 899//899 900//900 -f 806//806 900//900 807//807 -f 807//807 900//900 901//901 -f 807//807 901//901 808//808 -f 808//808 901//901 902//902 -f 808//808 902//902 809//809 -f 809//809 902//902 827//827 -f 902//902 903//903 827//827 -f 827//827 903//903 904//904 -f 827//827 904//904 828//828 -f 828//828 904//904 905//905 -f 828//828 905//905 829//829 -f 829//829 905//905 906//906 -f 829//829 906//906 830//830 -f 830//830 906//906 907//907 -f 830//830 907//907 831//831 -f 831//831 907//907 908//908 -f 831//831 908//908 832//832 -f 832//832 908//908 909//909 -f 832//832 909//909 833//833 -f 833//833 909//909 910//910 -f 833//833 910//910 834//834 -f 834//834 910//910 911//911 -f 834//834 911//911 835//835 -f 835//835 911//911 912//912 -f 835//835 912//912 836//836 -f 836//836 912//912 913//913 -f 836//836 913//913 837//837 -f 837//837 913//913 914//914 -f 837//837 914//914 838//838 -f 838//838 914//914 915//915 -f 838//838 915//915 839//839 -f 839//839 915//915 916//916 -f 839//839 916//916 840//840 -f 840//840 916//916 917//917 -f 840//840 917//917 841//841 -f 841//841 917//917 918//918 -f 841//841 918//918 842//842 -f 842//842 918//918 919//919 -f 842//842 919//919 843//843 -f 843//843 919//919 920//920 -f 843//843 920//920 844//844 -f 844//844 920//920 921//921 -f 844//844 921//921 845//845 -f 845//845 921//921 922//922 -f 845//845 922//922 846//846 -f 846//846 922//922 923//923 -f 846//846 923//923 847//847 -f 847//847 923//923 924//924 -f 847//847 924//924 848//848 -f 848//848 924//924 925//925 -f 848//848 925//925 849//849 -f 849//849 925//925 926//926 -f 849//849 926//926 850//850 -f 850//850 926//926 927//927 -f 850//850 927//927 851//851 -f 851//851 927//927 928//928 -f 851//851 928//928 852//852 -f 852//852 928//928 929//929 -f 852//852 929//929 853//853 -f 853//853 929//929 930//930 -f 853//853 930//930 854//854 -f 854//854 930//930 931//931 -f 854//854 931//931 855//855 -f 855//855 931//931 932//932 -f 855//855 932//932 856//856 -f 856//856 932//932 933//933 -f 856//856 933//933 857//857 -f 857//857 933//933 934//934 -f 857//857 934//934 858//858 -f 858//858 934//934 935//935 -f 858//858 935//935 859//859 -f 859//859 935//935 936//936 -f 859//859 936//936 860//860 -f 860//860 936//936 937//937 -f 860//860 937//937 861//861 -f 861//861 937//937 938//938 -f 861//861 938//938 862//862 -f 862//862 938//938 939//939 -f 862//862 939//939 863//863 -f 863//863 939//939 940//940 -f 863//863 940//940 864//864 -f 864//864 940//940 941//941 -f 864//864 941//941 865//865 -f 865//865 941//941 942//942 -f 865//865 942//942 866//866 -f 866//866 942//942 943//943 -f 866//866 943//943 867//867 -f 867//867 943//943 944//944 -f 867//867 944//944 868//868 -f 868//868 944//944 945//945 -f 868//868 945//945 869//869 -f 869//869 945//945 946//946 -f 869//869 946//946 870//870 -f 870//870 946//946 947//947 -f 870//870 947//947 871//871 -f 871//871 947//947 948//948 -f 871//871 948//948 872//872 -f 872//872 948//948 949//949 -f 872//872 949//949 873//873 -f 873//873 949//949 950//950 -f 873//873 950//950 874//874 -f 874//874 950//950 951//951 -f 874//874 951//951 875//875 -f 875//875 951//951 952//952 -f 875//875 952//952 876//876 -f 876//876 952//952 953//953 -f 876//876 953//953 877//877 -f 877//877 953//953 954//954 -f 877//877 954//954 878//878 -f 878//878 954//954 955//955 -f 878//878 955//955 879//879 -f 879//879 955//955 956//956 -f 879//879 956//956 880//880 -f 880//880 956//956 957//957 -f 880//880 957//957 881//881 -f 881//881 957//957 958//958 -f 881//881 958//958 882//882 -f 882//882 958//958 959//959 -f 882//882 959//959 883//883 -f 883//883 959//959 960//960 -f 883//883 960//960 884//884 -f 884//884 960//960 961//961 -f 884//884 961//961 885//885 -f 885//885 961//961 962//962 -f 885//885 962//962 886//886 -f 886//886 962//962 963//963 -f 886//886 963//963 887//887 -f 887//887 963//963 964//964 -f 887//887 964//964 888//888 -f 888//888 964//964 965//965 -f 888//888 965//965 889//889 -f 889//889 965//965 966//966 -f 889//889 966//966 890//890 -f 890//890 966//966 967//967 -f 890//890 967//967 891//891 -f 891//891 967//967 968//968 -f 891//891 968//968 892//892 -f 892//892 968//968 969//969 -f 892//892 969//969 893//893 -f 893//893 969//969 970//970 -f 893//893 970//970 894//894 -f 894//894 970//970 971//971 -f 894//894 971//971 895//895 -f 895//895 971//971 972//972 -f 895//895 972//972 896//896 -f 896//896 972//972 973//973 -f 896//896 973//973 897//897 -f 897//897 973//973 974//974 -f 897//897 974//974 898//898 -f 898//898 974//974 975//975 -f 898//898 975//975 899//899 -f 899//899 975//975 976//976 -f 899//899 976//976 900//900 -f 900//900 976//976 977//977 -f 900//900 977//977 901//901 -f 901//901 977//977 978//978 -f 901//901 978//978 902//902 -f 902//902 978//978 903//903 -f 978//978 979//979 903//903 -f 903//903 979//979 980//980 -f 903//903 980//980 904//904 -f 904//904 980//980 981//981 -f 904//904 981//981 905//905 -f 905//905 981//981 982//982 -f 905//905 982//982 906//906 -f 906//906 982//982 983//983 -f 906//906 983//983 907//907 -f 907//907 983//983 984//984 -f 907//907 984//984 908//908 -f 908//908 984//984 985//985 -f 908//908 985//985 909//909 -f 909//909 985//985 986//986 -f 909//909 986//986 910//910 -f 910//910 986//986 987//987 -f 910//910 987//987 911//911 -f 911//911 987//987 988//988 -f 911//911 988//988 912//912 -f 912//912 988//988 989//989 -f 912//912 989//989 913//913 -f 913//913 989//989 990//990 -f 913//913 990//990 914//914 -f 914//914 990//990 991//991 -f 914//914 991//991 915//915 -f 915//915 991//991 992//992 -f 915//915 992//992 916//916 -f 916//916 992//992 993//993 -f 916//916 993//993 917//917 -f 917//917 993//993 994//994 -f 917//917 994//994 918//918 -f 918//918 994//994 995//995 -f 918//918 995//995 919//919 -f 919//919 995//995 996//996 -f 919//919 996//996 920//920 -f 920//920 996//996 997//997 -f 920//920 997//997 921//921 -f 921//921 997//997 998//998 -f 921//921 998//998 922//922 -f 922//922 998//998 999//999 -f 922//922 999//999 923//923 -f 923//923 999//999 1000//1000 -f 923//923 1000//1000 924//924 -f 924//924 1000//1000 1001//1001 -f 924//924 1001//1001 925//925 -f 925//925 1001//1001 1002//1002 -f 925//925 1002//1002 926//926 -f 926//926 1002//1002 1003//1003 -f 926//926 1003//1003 927//927 -f 927//927 1003//1003 1004//1004 -f 927//927 1004//1004 928//928 -f 928//928 1004//1004 1005//1005 -f 928//928 1005//1005 929//929 -f 929//929 1005//1005 1006//1006 -f 929//929 1006//1006 930//930 -f 930//930 1006//1006 1007//1007 -f 930//930 1007//1007 931//931 -f 931//931 1007//1007 1008//1008 -f 931//931 1008//1008 932//932 -f 932//932 1008//1008 1009//1009 -f 932//932 1009//1009 933//933 -f 933//933 1009//1009 1010//1010 -f 933//933 1010//1010 934//934 -f 934//934 1010//1010 1011//1011 -f 934//934 1011//1011 935//935 -f 935//935 1011//1011 1012//1012 -f 935//935 1012//1012 936//936 -f 936//936 1012//1012 1013//1013 -f 936//936 1013//1013 937//937 -f 937//937 1013//1013 1014//1014 -f 937//937 1014//1014 938//938 -f 938//938 1014//1014 1015//1015 -f 938//938 1015//1015 939//939 -f 939//939 1015//1015 1016//1016 -f 939//939 1016//1016 940//940 -f 940//940 1016//1016 1017//1017 -f 940//940 1017//1017 941//941 -f 941//941 1017//1017 1018//1018 -f 941//941 1018//1018 942//942 -f 942//942 1018//1018 1019//1019 -f 942//942 1019//1019 943//943 -f 943//943 1019//1019 1020//1020 -f 943//943 1020//1020 944//944 -f 944//944 1020//1020 1021//1021 -f 944//944 1021//1021 945//945 -f 945//945 1021//1021 1022//1022 -f 945//945 1022//1022 946//946 -f 946//946 1022//1022 1023//1023 -f 946//946 1023//1023 947//947 -f 947//947 1023//1023 1024//1024 -f 947//947 1024//1024 948//948 -f 948//948 1024//1024 1025//1025 -f 948//948 1025//1025 949//949 -f 949//949 1025//1025 1026//1026 -f 949//949 1026//1026 950//950 -f 950//950 1026//1026 1027//1027 -f 950//950 1027//1027 951//951 -f 951//951 1027//1027 1028//1028 -f 951//951 1028//1028 952//952 -f 952//952 1028//1028 1029//1029 -f 952//952 1029//1029 953//953 -f 953//953 1029//1029 1030//1030 -f 953//953 1030//1030 954//954 -f 954//954 1030//1030 1031//1031 -f 954//954 1031//1031 955//955 -f 955//955 1031//1031 1032//1032 -f 955//955 1032//1032 956//956 -f 956//956 1032//1032 1033//1033 -f 956//956 1033//1033 957//957 -f 957//957 1033//1033 1034//1034 -f 957//957 1034//1034 958//958 -f 958//958 1034//1034 1035//1035 -f 958//958 1035//1035 959//959 -f 959//959 1035//1035 1036//1036 -f 959//959 1036//1036 960//960 -f 960//960 1036//1036 1037//1037 -f 960//960 1037//1037 961//961 -f 961//961 1037//1037 1038//1038 -f 961//961 1038//1038 962//962 -f 962//962 1038//1038 1039//1039 -f 962//962 1039//1039 963//963 -f 963//963 1039//1039 1040//1040 -f 963//963 1040//1040 964//964 -f 964//964 1040//1040 1041//1041 -f 964//964 1041//1041 965//965 -f 965//965 1041//1041 1042//1042 -f 965//965 1042//1042 966//966 -f 966//966 1042//1042 1043//1043 -f 966//966 1043//1043 967//967 -f 967//967 1043//1043 1044//1044 -f 967//967 1044//1044 968//968 -f 968//968 1044//1044 1045//1045 -f 968//968 1045//1045 969//969 -f 969//969 1045//1045 1046//1046 -f 969//969 1046//1046 970//970 -f 970//970 1046//1046 1047//1047 -f 970//970 1047//1047 971//971 -f 971//971 1047//1047 1048//1048 -f 971//971 1048//1048 972//972 -f 972//972 1048//1048 1049//1049 -f 972//972 1049//1049 973//973 -f 973//973 1049//1049 1050//1050 -f 973//973 1050//1050 974//974 -f 974//974 1050//1050 1051//1051 -f 974//974 1051//1051 975//975 -f 975//975 1051//1051 1052//1052 -f 975//975 1052//1052 976//976 -f 976//976 1052//1052 1053//1053 -f 976//976 1053//1053 977//977 -f 977//977 1053//1053 1054//1054 -f 977//977 1054//1054 978//978 -f 978//978 1054//1054 979//979 -f 1055//1055 1056//1056 1034//1034 -f 1057//1057 1036//1036 1056//1056 -f 1056//1056 1036//1036 1035//1035 -f 1056//1056 1035//1035 1034//1034 -f 1034//1034 1033//1033 1055//1055 -f 1055//1055 1033//1033 1032//1032 -f 1055//1055 1032//1032 1058//1058 -f 1029//1029 1059//1059 1030//1030 -f 1030//1030 1059//1059 1058//1058 -f 1030//1030 1058//1058 1031//1031 -f 1031//1031 1058//1058 1032//1032 -f 1060//1060 1038//1038 1057//1057 -f 1057//1057 1038//1038 1037//1037 -f 1057//1057 1037//1037 1036//1036 -f 990//990 989//989 1061//1061 -f 1061//1061 989//989 1062//1062 -f 999//999 998//998 1063//1063 -f 1063//1063 998//998 1064//1064 -f 999//999 1063//1063 1000//1000 -f 1000//1000 1063//1063 1065//1065 -f 1000//1000 1065//1065 1001//1001 -f 1010//1010 1009//1009 1066//1066 -f 1066//1066 1009//1009 1067//1067 -f 1068//1068 1017//1017 1016//1016 -f 1029//1029 1028//1028 1059//1059 -f 1059//1059 1028//1028 1027//1027 -f 1059//1059 1027//1027 1069//1069 -f 979//979 1054//1054 1070//1070 -f 1070//1070 1054//1054 1071//1071 -f 1001//1001 1065//1065 1002//1002 -f 1002//1002 1065//1065 1072//1072 -f 1002//1002 1072//1072 1003//1003 -f 1009//1009 1008//1008 1067//1067 -f 1067//1067 1008//1008 1007//1007 -f 1067//1067 1007//1007 1073//1073 -f 1068//1068 1016//1016 1074//1074 -f 1017//1017 1068//1068 1018//1018 -f 1018//1018 1068//1068 1075//1075 -f 1018//1018 1075//1075 1019//1019 -f 1027//1027 1026//1026 1069//1069 -f 1069//1069 1026//1026 1025//1025 -f 1069//1069 1025//1025 1076//1076 -f 1042//1042 1041//1041 1077//1077 -f 1077//1077 1041//1041 1040//1040 -f 1077//1077 1040//1040 1060//1060 -f 1060//1060 1040//1040 1039//1039 -f 1060//1060 1039//1039 1038//1038 -f 1042//1042 1077//1077 1043//1043 -f 1043//1043 1077//1077 1078//1078 -f 1043//1043 1078//1078 1044//1044 -f 1044//1044 1078//1078 1045//1045 -f 1045//1045 1078//1078 1079//1079 -f 1045//1045 1079//1079 1046//1046 -f 1046//1046 1079//1079 1047//1047 -f 1047//1047 1079//1079 1080//1080 -f 1047//1047 1080//1080 1048//1048 -f 1007//1007 1006//1006 1073//1073 -f 1073//1073 1006//1006 1005//1005 -f 1073//1073 1005//1005 1072//1072 -f 1072//1072 1005//1005 1004//1004 -f 1072//1072 1004//1004 1003//1003 -f 1010//1010 1066//1066 1011//1011 -f 1011//1011 1066//1066 1081//1081 -f 1011//1011 1081//1081 1012//1012 -f 1016//1016 1015//1015 1074//1074 -f 1074//1074 1015//1015 1014//1014 -f 1074//1074 1014//1014 1081//1081 -f 1081//1081 1014//1014 1013//1013 -f 1081//1081 1013//1013 1012//1012 -f 1054//1054 1053//1053 1071//1071 -f 1071//1071 1053//1053 1052//1052 -f 1071//1071 1052//1052 1082//1082 -f 979//979 1070//1070 980//980 -f 980//980 1070//1070 1083//1083 -f 980//980 1083//1083 981//981 -f 1084//1084 992//992 1061//1061 -f 1061//1061 992//992 991//991 -f 1061//1061 991//991 990//990 -f 1085//1085 994//994 1084//1084 -f 1084//1084 994//994 993//993 -f 1084//1084 993//993 992//992 -f 998//998 997//997 1064//1064 -f 1064//1064 997//997 996//996 -f 1064//1064 996//996 1085//1085 -f 1085//1085 996//996 995//995 -f 1085//1085 995//995 994//994 -f 1025//1025 1024//1024 1076//1076 -f 1076//1076 1024//1024 1023//1023 -f 1076//1076 1023//1023 1086//1086 -f 1052//1052 1051//1051 1082//1082 -f 1082//1082 1051//1051 1050//1050 -f 1082//1082 1050//1050 1080//1080 -f 1080//1080 1050//1050 1049//1049 -f 1080//1080 1049//1049 1048//1048 -f 1087//1087 1088//1088 985//985 -f 989//989 988//988 1062//1062 -f 1062//1062 988//988 987//987 -f 1062//1062 987//987 1088//1088 -f 1088//1088 987//987 986//986 -f 1088//1088 986//986 985//985 -f 1023//1023 1022//1022 1086//1086 -f 1086//1086 1022//1022 1021//1021 -f 1086//1086 1021//1021 1075//1075 -f 1075//1075 1021//1021 1020//1020 -f 1075//1075 1020//1020 1019//1019 -f 985//985 984//984 1087//1087 -f 1087//1087 984//984 983//983 -f 1087//1087 983//983 1083//1083 -f 1083//1083 983//983 982//982 -f 1083//1083 982//982 981//981 -f 1085//1085 1089//1089 1064//1064 -f 1064//1064 1089//1089 1090//1090 -f 1091//1091 1092//1092 1084//1084 -f 1084//1084 1092//1092 1093//1093 -f 1084//1084 1093//1093 1085//1085 -f 1085//1085 1093//1093 1094//1094 -f 1085//1085 1094//1094 1089//1089 -f 1091//1091 1084//1084 1095//1095 -f 1095//1095 1084//1084 1061//1061 -f 1095//1095 1061//1061 1096//1096 -f 1096//1096 1061//1061 1097//1097 -f 1097//1097 1061//1061 1062//1062 -f 1097//1097 1062//1062 1098//1098 -f 1098//1098 1062//1062 1099//1099 -f 1099//1099 1062//1062 1088//1088 -f 1099//1099 1088//1088 1100//1100 -f 1087//1087 1101//1101 1102//1102 -f 1087//1087 1102//1102 1088//1088 -f 1088//1088 1102//1102 1103//1103 -f 1088//1088 1103//1103 1100//1100 -f 1101//1101 1087//1087 1104//1104 -f 1104//1104 1087//1087 1083//1083 -f 1104//1104 1083//1083 1105//1105 -f 1070//1070 1106//1106 1107//1107 -f 1070//1070 1107//1107 1083//1083 -f 1083//1083 1107//1107 1108//1108 -f 1083//1083 1108//1108 1105//1105 -f 1106//1106 1070//1070 1109//1109 -f 1109//1109 1070//1070 1071//1071 -f 1109//1109 1071//1071 1110//1110 -f 1082//1082 1111//1111 1071//1071 -f 1071//1071 1111//1111 1112//1112 -f 1071//1071 1112//1112 1110//1110 -f 1113//1113 1114//1114 1080//1080 -f 1080//1080 1114//1114 1115//1115 -f 1080//1080 1115//1115 1082//1082 -f 1082//1082 1115//1115 1116//1116 -f 1082//1082 1116//1116 1111//1111 -f 1113//1113 1080//1080 1117//1117 -f 1117//1117 1080//1080 1079//1079 -f 1117//1117 1079//1079 1118//1118 -f 1118//1118 1079//1079 1119//1119 -f 1119//1119 1079//1079 1078//1078 -f 1119//1119 1078//1078 1120//1120 -f 1120//1120 1078//1078 1121//1121 -f 1121//1121 1078//1078 1077//1077 -f 1121//1121 1077//1077 1122//1122 -f 1060//1060 1123//1123 1124//1124 -f 1060//1060 1124//1124 1077//1077 -f 1077//1077 1124//1124 1125//1125 -f 1077//1077 1125//1125 1122//1122 -f 1123//1123 1060//1060 1126//1126 -f 1126//1126 1060//1060 1057//1057 -f 1126//1126 1057//1057 1127//1127 -f 1056//1056 1128//1128 1129//1129 -f 1056//1056 1129//1129 1057//1057 -f 1057//1057 1129//1129 1130//1130 -f 1057//1057 1130//1130 1127//1127 -f 1128//1128 1056//1056 1131//1131 -f 1131//1131 1056//1056 1055//1055 -f 1131//1131 1055//1055 1132//1132 -f 1058//1058 1133//1133 1055//1055 -f 1055//1055 1133//1133 1134//1134 -f 1055//1055 1134//1134 1132//1132 -f 1059//1059 1135//1135 1058//1058 -f 1058//1058 1135//1135 1136//1136 -f 1058//1058 1136//1136 1133//1133 -f 1137//1137 1138//1138 1069//1069 -f 1069//1069 1138//1138 1139//1139 -f 1069//1069 1139//1139 1059//1059 -f 1059//1059 1139//1139 1140//1140 -f 1059//1059 1140//1140 1135//1135 -f 1137//1137 1069//1069 1141//1141 -f 1141//1141 1069//1069 1076//1076 -f 1141//1141 1076//1076 1142//1142 -f 1142//1142 1076//1076 1143//1143 -f 1143//1143 1076//1076 1086//1086 -f 1143//1143 1086//1086 1144//1144 -f 1075//1075 1145//1145 1146//1146 -f 1075//1075 1146//1146 1086//1086 -f 1086//1086 1146//1146 1147//1147 -f 1086//1086 1147//1147 1144//1144 -f 1145//1145 1075//1075 1148//1148 -f 1148//1148 1075//1075 1068//1068 -f 1148//1148 1068//1068 1149//1149 -f 1074//1074 1150//1150 1151//1151 -f 1074//1074 1151//1151 1068//1068 -f 1068//1068 1151//1151 1152//1152 -f 1068//1068 1152//1152 1149//1149 -f 1150//1150 1074//1074 1153//1153 -f 1153//1153 1074//1074 1081//1081 -f 1153//1153 1081//1081 1154//1154 -f 1066//1066 1155//1155 1081//1081 -f 1081//1081 1155//1155 1156//1156 -f 1081//1081 1156//1156 1154//1154 -f 1067//1067 1157//1157 1066//1066 -f 1066//1066 1157//1157 1158//1158 -f 1066//1066 1158//1158 1155//1155 -f 1159//1159 1160//1160 1073//1073 -f 1073//1073 1160//1160 1161//1161 -f 1073//1073 1161//1161 1067//1067 -f 1067//1067 1161//1161 1162//1162 -f 1067//1067 1162//1162 1157//1157 -f 1159//1159 1073//1073 1163//1163 -f 1163//1163 1073//1073 1072//1072 -f 1163//1163 1072//1072 1164//1164 -f 1164//1164 1072//1072 1165//1165 -f 1165//1165 1072//1072 1065//1065 -f 1165//1165 1065//1065 1166//1166 -f 1063//1063 1167//1167 1065//1065 -f 1065//1065 1167//1167 1168//1168 -f 1065//1065 1168//1168 1166//1166 -f 1090//1090 1169//1169 1064//1064 -f 1064//1064 1169//1169 1170//1170 -f 1064//1064 1170//1170 1063//1063 -f 1063//1063 1170//1170 1171//1171 -f 1063//1063 1171//1171 1167//1167 -f 1172//1172 1173//1173 1174//1174 -f 1175//1175 1176//1176 1177//1177 -f 1178//1178 1179//1179 1180//1180 -f 1181//1181 1182//1182 1183//1183 -f 1184//1184 1185//1185 1186//1186 -f 1187//1187 1188//1188 1189//1189 -f 1190//1190 1191//1191 1192//1192 -f 1193//1193 1194//1194 1195//1195 -f 1105//1105 1108//1108 1196//1196 -f 1101//1101 1104//1104 1197//1197 -f 1100//1100 1103//1103 1198//1198 -f 1090//1090 1089//1089 1199//1199 -f 1168//1168 1167//1167 1200//1200 -f 1159//1159 1163//1163 1201//1201 -f 1158//1158 1157//1157 1202//1202 -f 1156//1156 1155//1155 1203//1203 -f 1150//1150 1153//1153 1204//1204 -f 1152//1152 1151//1151 1205//1205 -f 1147//1147 1146//1146 1206//1206 -f 1137//1137 1141//1141 1207//1207 -f 1139//1139 1138//1138 1208//1208 -f 1136//1136 1135//1135 1209//1209 -f 1134//1134 1133//1133 1210//1210 -f 1130//1130 1129//1129 1211//1211 -f 1125//1125 1124//1124 1212//1212 -f 1118//1118 1119//1119 1213//1213 -f 1113//1113 1117//1117 1214//1214 -f 1116//1116 1115//1115 1215//1215 -f 1112//1112 1111//1111 1216//1216 -f 1109//1109 1110//1110 1217//1217 -f 1121//1121 1122//1122 1218//1218 -f 1126//1126 1127//1127 1219//1219 -f 1131//1131 1132//1132 1220//1220 -f 1143//1143 1144//1144 1221//1221 -f 1148//1148 1149//1149 1222//1222 -f 1161//1161 1160//1160 1223//1223 -f 1165//1165 1166//1166 1224//1224 -f 1170//1170 1169//1169 1225//1225 -f 1094//1094 1093//1093 1193//1193 -f 1193//1193 1093//1093 1092//1092 -f 1193//1193 1092//1092 1194//1194 -f 1194//1194 1092//1092 1091//1091 -f 1226//1226 1095//1095 1096//1096 -f 1227//1227 1097//1097 1098//1098 -f 1100//1100 1198//1198 1099//1099 -f 1103//1103 1102//1102 1228//1228 -f 1228//1228 1102//1102 1101//1101 -f 1105//1105 1196//1196 1104//1104 -f 1108//1108 1107//1107 1229//1229 -f 1229//1229 1107//1107 1106//1106 -f 1230//1230 1195//1195 1231//1231 -f 1231//1231 1195//1195 1194//1194 -f 1231//1231 1194//1194 1226//1226 -f 1226//1226 1194//1194 1091//1091 -f 1226//1226 1091//1091 1095//1095 -f 1232//1232 1230//1230 1233//1233 -f 1233//1233 1230//1230 1231//1231 -f 1233//1233 1231//1231 1234//1234 -f 1234//1234 1231//1231 1226//1226 -f 1234//1234 1226//1226 1227//1227 -f 1227//1227 1226//1226 1096//1096 -f 1227//1227 1096//1096 1097//1097 -f 1235//1235 1236//1236 1237//1237 -f 1237//1237 1236//1236 1238//1238 -f 1237//1237 1238//1238 1239//1239 -f 1239//1239 1238//1238 1240//1240 -f 1241//1241 1232//1232 1242//1242 -f 1242//1242 1232//1232 1233//1233 -f 1242//1242 1233//1233 1243//1243 -f 1243//1243 1233//1233 1234//1234 -f 1243//1243 1234//1234 1244//1244 -f 1244//1244 1234//1234 1227//1227 -f 1244//1244 1227//1227 1245//1245 -f 1245//1245 1227//1227 1098//1098 -f 1245//1245 1098//1098 1099//1099 -f 1246//1246 1247//1247 1248//1248 -f 1110//1110 1112//1112 1217//1217 -f 1217//1217 1112//1112 1216//1216 -f 1217//1217 1216//1216 1249//1249 -f 1249//1249 1216//1216 1250//1250 -f 1249//1249 1250//1250 1251//1251 -f 1251//1251 1250//1250 1252//1252 -f 1251//1251 1252//1252 1253//1253 -f 1253//1253 1252//1252 1254//1254 -f 1253//1253 1254//1254 1255//1255 -f 1255//1255 1254//1254 1256//1256 -f 1111//1111 1116//1116 1216//1216 -f 1216//1216 1116//1116 1215//1215 -f 1216//1216 1215//1215 1250//1250 -f 1250//1250 1215//1215 1257//1257 -f 1250//1250 1257//1257 1252//1252 -f 1252//1252 1257//1257 1258//1258 -f 1252//1252 1258//1258 1254//1254 -f 1254//1254 1258//1258 1259//1259 -f 1254//1254 1259//1259 1256//1256 -f 1256//1256 1259//1259 1260//1260 -f 1256//1256 1260//1260 1261//1261 -f 1261//1261 1260//1260 1262//1262 -f 1117//1117 1118//1118 1214//1214 -f 1214//1214 1118//1118 1213//1213 -f 1214//1214 1213//1213 1263//1263 -f 1263//1263 1213//1213 1264//1264 -f 1263//1263 1264//1264 1265//1265 -f 1265//1265 1264//1264 1266//1266 -f 1265//1265 1266//1266 1267//1267 -f 1267//1267 1266//1266 1268//1268 -f 1267//1267 1268//1268 1269//1269 -f 1269//1269 1268//1268 1270//1270 -f 1122//1122 1125//1125 1218//1218 -f 1218//1218 1125//1125 1212//1212 -f 1218//1218 1212//1212 1271//1271 -f 1271//1271 1212//1212 1272//1272 -f 1271//1271 1272//1272 1273//1273 -f 1273//1273 1272//1272 1274//1274 -f 1273//1273 1274//1274 1275//1275 -f 1275//1275 1274//1274 1276//1276 -f 1275//1275 1276//1276 1277//1277 -f 1277//1277 1276//1276 1278//1278 -f 1124//1124 1123//1123 1212//1212 -f 1212//1212 1123//1123 1279//1279 -f 1212//1212 1279//1279 1272//1272 -f 1272//1272 1279//1279 1280//1280 -f 1272//1272 1280//1280 1274//1274 -f 1274//1274 1280//1280 1281//1281 -f 1274//1274 1281//1281 1276//1276 -f 1276//1276 1281//1281 1282//1282 -f 1276//1276 1282//1282 1278//1278 -f 1278//1278 1282//1282 1283//1283 -f 1278//1278 1283//1283 1284//1284 -f 1284//1284 1283//1283 1285//1285 -f 1129//1129 1128//1128 1211//1211 -f 1211//1211 1128//1128 1286//1286 -f 1211//1211 1286//1286 1287//1287 -f 1287//1287 1286//1286 1288//1288 -f 1287//1287 1288//1288 1289//1289 -f 1289//1289 1288//1288 1290//1290 -f 1289//1289 1290//1290 1291//1291 -f 1291//1291 1290//1290 1292//1292 -f 1291//1291 1292//1292 1293//1293 -f 1293//1293 1292//1292 1294//1294 -f 1133//1133 1136//1136 1210//1210 -f 1210//1210 1136//1136 1209//1209 -f 1210//1210 1209//1209 1295//1295 -f 1295//1295 1209//1209 1296//1296 -f 1295//1295 1296//1296 1297//1297 -f 1297//1297 1296//1296 1298//1298 -f 1297//1297 1298//1298 1299//1299 -f 1299//1299 1298//1298 1300//1300 -f 1299//1299 1300//1300 1301//1301 -f 1301//1301 1300//1300 1302//1302 -f 1135//1135 1140//1140 1209//1209 -f 1209//1209 1140//1140 1303//1303 -f 1209//1209 1303//1303 1296//1296 -f 1296//1296 1303//1303 1304//1304 -f 1296//1296 1304//1304 1298//1298 -f 1298//1298 1304//1304 1305//1305 -f 1298//1298 1305//1305 1300//1300 -f 1300//1300 1305//1305 1306//1306 -f 1300//1300 1306//1306 1302//1302 -f 1302//1302 1306//1306 1307//1307 -f 1302//1302 1307//1307 1308//1308 -f 1308//1308 1307//1307 1309//1309 -f 1141//1141 1142//1142 1207//1207 -f 1207//1207 1142//1142 1310//1310 -f 1207//1207 1310//1310 1311//1311 -f 1311//1311 1310//1310 1312//1312 -f 1311//1311 1312//1312 1313//1313 -f 1313//1313 1312//1312 1314//1314 -f 1313//1313 1314//1314 1315//1315 -f 1315//1315 1314//1314 1316//1316 -f 1315//1315 1316//1316 1317//1317 -f 1317//1317 1316//1316 1318//1318 -f 1146//1146 1145//1145 1206//1206 -f 1206//1206 1145//1145 1319//1319 -f 1206//1206 1319//1319 1320//1320 -f 1320//1320 1319//1319 1321//1321 -f 1320//1320 1321//1321 1322//1322 -f 1322//1322 1321//1321 1323//1323 -f 1322//1322 1323//1323 1324//1324 -f 1324//1324 1323//1323 1325//1325 -f 1324//1324 1325//1325 1326//1326 -f 1326//1326 1325//1325 1327//1327 -f 1145//1145 1148//1148 1319//1319 -f 1319//1319 1148//1148 1222//1222 -f 1319//1319 1222//1222 1321//1321 -f 1321//1321 1222//1222 1328//1328 -f 1321//1321 1328//1328 1323//1323 -f 1323//1323 1328//1328 1329//1329 -f 1323//1323 1329//1329 1325//1325 -f 1325//1325 1329//1329 1330//1330 -f 1325//1325 1330//1330 1327//1327 -f 1327//1327 1330//1330 1331//1331 -f 1327//1327 1331//1331 1332//1332 -f 1332//1332 1331//1331 1333//1333 -f 1153//1153 1154//1154 1204//1204 -f 1204//1204 1154//1154 1334//1334 -f 1204//1204 1334//1334 1335//1335 -f 1335//1335 1334//1334 1336//1336 -f 1335//1335 1336//1336 1337//1337 -f 1337//1337 1336//1336 1338//1338 -f 1337//1337 1338//1338 1339//1339 -f 1339//1339 1338//1338 1340//1340 -f 1339//1339 1340//1340 1341//1341 -f 1341//1341 1340//1340 1342//1342 -f 1157//1157 1162//1162 1202//1202 -f 1202//1202 1162//1162 1343//1343 -f 1202//1202 1343//1343 1344//1344 -f 1344//1344 1343//1343 1345//1345 -f 1344//1344 1345//1345 1346//1346 -f 1346//1346 1345//1345 1347//1347 -f 1346//1346 1347//1347 1348//1348 -f 1348//1348 1347//1347 1349//1349 -f 1348//1348 1349//1349 1350//1350 -f 1350//1350 1349//1349 1351//1351 -f 1162//1162 1161//1161 1343//1343 -f 1343//1343 1161//1161 1223//1223 -f 1343//1343 1223//1223 1345//1345 -f 1345//1345 1223//1223 1352//1352 -f 1345//1345 1352//1352 1347//1347 -f 1347//1347 1352//1352 1353//1353 -f 1347//1347 1353//1353 1349//1349 -f 1349//1349 1353//1353 1354//1354 -f 1349//1349 1354//1354 1351//1351 -f 1351//1351 1354//1354 1355//1355 -f 1351//1351 1355//1355 1356//1356 -f 1356//1356 1355//1355 1357//1357 -f 1164//1164 1165//1165 1358//1358 -f 1358//1358 1165//1165 1224//1224 -f 1358//1358 1224//1224 1359//1359 -f 1359//1359 1224//1224 1360//1360 -f 1359//1359 1360//1360 1361//1361 -f 1361//1361 1360//1360 1362//1362 -f 1361//1361 1362//1362 1363//1363 -f 1363//1363 1362//1362 1364//1364 -f 1363//1363 1364//1364 1365//1365 -f 1365//1365 1364//1364 1366//1366 -f 1171//1171 1170//1170 1367//1367 -f 1367//1367 1170//1170 1225//1225 -f 1367//1367 1225//1225 1368//1368 -f 1368//1368 1225//1225 1369//1369 -f 1368//1368 1369//1369 1370//1370 -f 1370//1370 1369//1369 1371//1371 -f 1370//1370 1371//1371 1372//1372 -f 1372//1372 1371//1371 1373//1373 -f 1372//1372 1373//1373 1374//1374 -f 1374//1374 1373//1373 1375//1375 -f 1169//1169 1090//1090 1225//1225 -f 1225//1225 1090//1090 1199//1199 -f 1225//1225 1199//1199 1369//1369 -f 1369//1369 1199//1199 1376//1376 -f 1369//1369 1376//1376 1371//1371 -f 1371//1371 1376//1376 1377//1377 -f 1371//1371 1377//1377 1373//1373 -f 1373//1373 1377//1377 1378//1378 -f 1373//1373 1378//1378 1375//1375 -f 1375//1375 1378//1378 1379//1379 -f 1375//1375 1379//1379 1380//1380 -f 1380//1380 1379//1379 1381//1381 -f 1382//1382 1190//1190 1235//1235 -f 1235//1235 1190//1190 1192//1192 -f 1235//1235 1192//1192 1236//1236 -f 1239//1239 1248//1248 1237//1237 -f 1237//1237 1248//1248 1247//1247 -f 1237//1237 1247//1247 1235//1235 -f 1235//1235 1247//1247 1383//1383 -f 1235//1235 1383//1383 1382//1382 -f 1384//1384 1385//1385 1386//1386 -f 1386//1386 1385//1385 1246//1246 -f 1386//1386 1246//1246 1387//1387 -f 1387//1387 1246//1246 1248//1248 -f 1387//1387 1248//1248 1388//1388 -f 1388//1388 1248//1248 1239//1239 -f 1388//1388 1239//1239 1389//1389 -f 1389//1389 1239//1239 1240//1240 -f 1389//1389 1240//1240 1390//1390 -f 1385//1385 1391//1391 1246//1246 -f 1246//1246 1391//1391 1392//1392 -f 1246//1246 1392//1392 1247//1247 -f 1247//1247 1392//1392 1393//1393 -f 1247//1247 1393//1393 1383//1383 -f 1106//1106 1109//1109 1390//1390 -f 1390//1390 1109//1109 1217//1217 -f 1390//1390 1217//1217 1389//1389 -f 1389//1389 1217//1217 1249//1249 -f 1389//1389 1249//1249 1388//1388 -f 1388//1388 1249//1249 1251//1251 -f 1388//1388 1251//1251 1387//1387 -f 1387//1387 1251//1251 1253//1253 -f 1387//1387 1253//1253 1386//1386 -f 1386//1386 1253//1253 1255//1255 -f 1386//1386 1255//1255 1384//1384 -f 1261//1261 1394//1394 1256//1256 -f 1256//1256 1394//1394 1395//1395 -f 1256//1256 1395//1395 1255//1255 -f 1255//1255 1395//1395 1396//1396 -f 1255//1255 1396//1396 1384//1384 -f 1115//1115 1114//1114 1215//1215 -f 1215//1215 1114//1114 1397//1397 -f 1215//1215 1397//1397 1257//1257 -f 1257//1257 1397//1397 1398//1398 -f 1257//1257 1398//1398 1258//1258 -f 1258//1258 1398//1398 1399//1399 -f 1258//1258 1399//1399 1259//1259 -f 1259//1259 1399//1399 1400//1400 -f 1259//1259 1400//1400 1260//1260 -f 1260//1260 1400//1400 1189//1189 -f 1260//1260 1189//1189 1262//1262 -f 1262//1262 1189//1189 1188//1188 -f 1114//1114 1113//1113 1397//1397 -f 1397//1397 1113//1113 1214//1214 -f 1397//1397 1214//1214 1398//1398 -f 1398//1398 1214//1214 1263//1263 -f 1398//1398 1263//1263 1399//1399 -f 1399//1399 1263//1263 1265//1265 -f 1399//1399 1265//1265 1400//1400 -f 1400//1400 1265//1265 1267//1267 -f 1400//1400 1267//1267 1189//1189 -f 1189//1189 1267//1267 1269//1269 -f 1189//1189 1269//1269 1187//1187 -f 1401//1401 1402//1402 1403//1403 -f 1403//1403 1402//1402 1270//1270 -f 1403//1403 1270//1270 1404//1404 -f 1404//1404 1270//1270 1268//1268 -f 1404//1404 1268//1268 1405//1405 -f 1405//1405 1268//1268 1266//1266 -f 1405//1405 1266//1266 1406//1406 -f 1406//1406 1266//1266 1264//1264 -f 1406//1406 1264//1264 1407//1407 -f 1407//1407 1264//1264 1213//1213 -f 1407//1407 1213//1213 1120//1120 -f 1120//1120 1213//1213 1119//1119 -f 1402//1402 1408//1408 1270//1270 -f 1270//1270 1408//1408 1409//1409 -f 1270//1270 1409//1409 1269//1269 -f 1269//1269 1409//1409 1410//1410 -f 1269//1269 1410//1410 1187//1187 -f 1120//1120 1121//1121 1407//1407 -f 1407//1407 1121//1121 1218//1218 -f 1407//1407 1218//1218 1406//1406 -f 1406//1406 1218//1218 1271//1271 -f 1406//1406 1271//1271 1405//1405 -f 1405//1405 1271//1271 1273//1273 -f 1405//1405 1273//1273 1404//1404 -f 1404//1404 1273//1273 1275//1275 -f 1404//1404 1275//1275 1403//1403 -f 1403//1403 1275//1275 1277//1277 -f 1403//1403 1277//1277 1401//1401 -f 1284//1284 1411//1411 1278//1278 -f 1278//1278 1411//1411 1412//1412 -f 1278//1278 1412//1412 1277//1277 -f 1277//1277 1412//1412 1413//1413 -f 1277//1277 1413//1413 1401//1401 -f 1123//1123 1126//1126 1279//1279 -f 1279//1279 1126//1126 1219//1219 -f 1279//1279 1219//1219 1280//1280 -f 1280//1280 1219//1219 1414//1414 -f 1280//1280 1414//1414 1281//1281 -f 1281//1281 1414//1414 1415//1415 -f 1281//1281 1415//1415 1282//1282 -f 1282//1282 1415//1415 1416//1416 -f 1282//1282 1416//1416 1283//1283 -f 1283//1283 1416//1416 1186//1186 -f 1283//1283 1186//1186 1285//1285 -f 1285//1285 1186//1186 1185//1185 -f 1127//1127 1130//1130 1219//1219 -f 1219//1219 1130//1130 1211//1211 -f 1219//1219 1211//1211 1414//1414 -f 1414//1414 1211//1211 1287//1287 -f 1414//1414 1287//1287 1415//1415 -f 1415//1415 1287//1287 1289//1289 -f 1415//1415 1289//1289 1416//1416 -f 1416//1416 1289//1289 1291//1291 -f 1416//1416 1291//1291 1186//1186 -f 1186//1186 1291//1291 1293//1293 -f 1186//1186 1293//1293 1184//1184 -f 1417//1417 1418//1418 1419//1419 -f 1419//1419 1418//1418 1294//1294 -f 1419//1419 1294//1294 1420//1420 -f 1420//1420 1294//1294 1292//1292 -f 1420//1420 1292//1292 1421//1421 -f 1421//1421 1292//1292 1290//1290 -f 1421//1421 1290//1290 1422//1422 -f 1422//1422 1290//1290 1288//1288 -f 1422//1422 1288//1288 1220//1220 -f 1220//1220 1288//1288 1286//1286 -f 1220//1220 1286//1286 1131//1131 -f 1131//1131 1286//1286 1128//1128 -f 1418//1418 1423//1423 1294//1294 -f 1294//1294 1423//1423 1424//1424 -f 1294//1294 1424//1424 1293//1293 -f 1293//1293 1424//1424 1425//1425 -f 1293//1293 1425//1425 1184//1184 -f 1132//1132 1134//1134 1220//1220 -f 1220//1220 1134//1134 1210//1210 -f 1220//1220 1210//1210 1422//1422 -f 1422//1422 1210//1210 1295//1295 -f 1422//1422 1295//1295 1421//1421 -f 1421//1421 1295//1295 1297//1297 -f 1421//1421 1297//1297 1420//1420 -f 1420//1420 1297//1297 1299//1299 -f 1420//1420 1299//1299 1419//1419 -f 1419//1419 1299//1299 1301//1301 -f 1419//1419 1301//1301 1417//1417 -f 1308//1308 1426//1426 1302//1302 -f 1302//1302 1426//1426 1427//1427 -f 1302//1302 1427//1427 1301//1301 -f 1301//1301 1427//1427 1428//1428 -f 1301//1301 1428//1428 1417//1417 -f 1140//1140 1139//1139 1303//1303 -f 1303//1303 1139//1139 1208//1208 -f 1303//1303 1208//1208 1304//1304 -f 1304//1304 1208//1208 1429//1429 -f 1304//1304 1429//1429 1305//1305 -f 1305//1305 1429//1429 1430//1430 -f 1305//1305 1430//1430 1306//1306 -f 1306//1306 1430//1430 1431//1431 -f 1306//1306 1431//1431 1307//1307 -f 1307//1307 1431//1431 1183//1183 -f 1307//1307 1183//1183 1309//1309 -f 1309//1309 1183//1183 1182//1182 -f 1138//1138 1137//1137 1208//1208 -f 1208//1208 1137//1137 1207//1207 -f 1208//1208 1207//1207 1429//1429 -f 1429//1429 1207//1207 1311//1311 -f 1429//1429 1311//1311 1430//1430 -f 1430//1430 1311//1311 1313//1313 -f 1430//1430 1313//1313 1431//1431 -f 1431//1431 1313//1313 1315//1315 -f 1431//1431 1315//1315 1183//1183 -f 1183//1183 1315//1315 1317//1317 -f 1183//1183 1317//1317 1181//1181 -f 1432//1432 1433//1433 1434//1434 -f 1434//1434 1433//1433 1318//1318 -f 1434//1434 1318//1318 1435//1435 -f 1435//1435 1318//1318 1316//1316 -f 1435//1435 1316//1316 1436//1436 -f 1436//1436 1316//1316 1314//1314 -f 1436//1436 1314//1314 1437//1437 -f 1437//1437 1314//1314 1312//1312 -f 1437//1437 1312//1312 1221//1221 -f 1221//1221 1312//1312 1310//1310 -f 1221//1221 1310//1310 1143//1143 -f 1143//1143 1310//1310 1142//1142 -f 1433//1433 1438//1438 1318//1318 -f 1318//1318 1438//1438 1439//1439 -f 1318//1318 1439//1439 1317//1317 -f 1317//1317 1439//1439 1440//1440 -f 1317//1317 1440//1440 1181//1181 -f 1144//1144 1147//1147 1221//1221 -f 1221//1221 1147//1147 1206//1206 -f 1221//1221 1206//1206 1437//1437 -f 1437//1437 1206//1206 1320//1320 -f 1437//1437 1320//1320 1436//1436 -f 1436//1436 1320//1320 1322//1322 -f 1436//1436 1322//1322 1435//1435 -f 1435//1435 1322//1322 1324//1324 -f 1435//1435 1324//1324 1434//1434 -f 1434//1434 1324//1324 1326//1326 -f 1434//1434 1326//1326 1432//1432 -f 1332//1332 1441//1441 1327//1327 -f 1327//1327 1441//1441 1442//1442 -f 1327//1327 1442//1442 1326//1326 -f 1326//1326 1442//1442 1443//1443 -f 1326//1326 1443//1443 1432//1432 -f 1149//1149 1152//1152 1222//1222 -f 1222//1222 1152//1152 1205//1205 -f 1222//1222 1205//1205 1328//1328 -f 1328//1328 1205//1205 1444//1444 -f 1328//1328 1444//1444 1329//1329 -f 1329//1329 1444//1444 1445//1445 -f 1329//1329 1445//1445 1330//1330 -f 1330//1330 1445//1445 1446//1446 -f 1330//1330 1446//1446 1331//1331 -f 1331//1331 1446//1446 1180//1180 -f 1331//1331 1180//1180 1333//1333 -f 1333//1333 1180//1180 1179//1179 -f 1151//1151 1150//1150 1205//1205 -f 1205//1205 1150//1150 1204//1204 -f 1205//1205 1204//1204 1444//1444 -f 1444//1444 1204//1204 1335//1335 -f 1444//1444 1335//1335 1445//1445 -f 1445//1445 1335//1335 1337//1337 -f 1445//1445 1337//1337 1446//1446 -f 1446//1446 1337//1337 1339//1339 -f 1446//1446 1339//1339 1180//1180 -f 1180//1180 1339//1339 1341//1341 -f 1180//1180 1341//1341 1178//1178 -f 1447//1447 1448//1448 1449//1449 -f 1449//1449 1448//1448 1342//1342 -f 1449//1449 1342//1342 1450//1450 -f 1450//1450 1342//1342 1340//1340 -f 1450//1450 1340//1340 1451//1451 -f 1451//1451 1340//1340 1338//1338 -f 1451//1451 1338//1338 1452//1452 -f 1452//1452 1338//1338 1336//1336 -f 1452//1452 1336//1336 1203//1203 -f 1203//1203 1336//1336 1334//1334 -f 1203//1203 1334//1334 1156//1156 -f 1156//1156 1334//1334 1154//1154 -f 1448//1448 1453//1453 1342//1342 -f 1342//1342 1453//1453 1454//1454 -f 1342//1342 1454//1454 1341//1341 -f 1341//1341 1454//1454 1455//1455 -f 1341//1341 1455//1455 1178//1178 -f 1155//1155 1158//1158 1203//1203 -f 1203//1203 1158//1158 1202//1202 -f 1203//1203 1202//1202 1452//1452 -f 1452//1452 1202//1202 1344//1344 -f 1452//1452 1344//1344 1451//1451 -f 1451//1451 1344//1344 1346//1346 -f 1451//1451 1346//1346 1450//1450 -f 1450//1450 1346//1346 1348//1348 -f 1450//1450 1348//1348 1449//1449 -f 1449//1449 1348//1348 1350//1350 -f 1449//1449 1350//1350 1447//1447 -f 1356//1356 1456//1456 1351//1351 -f 1351//1351 1456//1456 1457//1457 -f 1351//1351 1457//1457 1350//1350 -f 1350//1350 1457//1457 1458//1458 -f 1350//1350 1458//1458 1447//1447 -f 1160//1160 1159//1159 1223//1223 -f 1223//1223 1159//1159 1201//1201 -f 1223//1223 1201//1201 1352//1352 -f 1352//1352 1201//1201 1459//1459 -f 1352//1352 1459//1459 1353//1353 -f 1353//1353 1459//1459 1460//1460 -f 1353//1353 1460//1460 1354//1354 -f 1354//1354 1460//1460 1461//1461 -f 1354//1354 1461//1461 1355//1355 -f 1355//1355 1461//1461 1177//1177 -f 1355//1355 1177//1177 1357//1357 -f 1357//1357 1177//1177 1176//1176 -f 1163//1163 1164//1164 1201//1201 -f 1201//1201 1164//1164 1358//1358 -f 1201//1201 1358//1358 1459//1459 -f 1459//1459 1358//1358 1359//1359 -f 1459//1459 1359//1359 1460//1460 -f 1460//1460 1359//1359 1361//1361 -f 1460//1460 1361//1361 1461//1461 -f 1461//1461 1361//1361 1363//1363 -f 1461//1461 1363//1363 1177//1177 -f 1177//1177 1363//1363 1365//1365 -f 1177//1177 1365//1365 1175//1175 -f 1462//1462 1463//1463 1464//1464 -f 1464//1464 1463//1463 1366//1366 -f 1464//1464 1366//1366 1465//1465 -f 1465//1465 1366//1366 1364//1364 -f 1465//1465 1364//1364 1466//1466 -f 1466//1466 1364//1364 1362//1362 -f 1466//1466 1362//1362 1467//1467 -f 1467//1467 1362//1362 1360//1360 -f 1467//1467 1360//1360 1200//1200 -f 1200//1200 1360//1360 1224//1224 -f 1200//1200 1224//1224 1168//1168 -f 1168//1168 1224//1224 1166//1166 -f 1463//1463 1468//1468 1366//1366 -f 1366//1366 1468//1468 1469//1469 -f 1366//1366 1469//1469 1365//1365 -f 1365//1365 1469//1469 1470//1470 -f 1365//1365 1470//1470 1175//1175 -f 1167//1167 1171//1171 1200//1200 -f 1200//1200 1171//1171 1367//1367 -f 1200//1200 1367//1367 1467//1467 -f 1467//1467 1367//1367 1368//1368 -f 1467//1467 1368//1368 1466//1466 -f 1466//1466 1368//1368 1370//1370 -f 1466//1466 1370//1370 1465//1465 -f 1465//1465 1370//1370 1372//1372 -f 1465//1465 1372//1372 1464//1464 -f 1464//1464 1372//1372 1374//1374 -f 1464//1464 1374//1374 1462//1462 -f 1380//1380 1471//1471 1375//1375 -f 1375//1375 1471//1471 1472//1472 -f 1375//1375 1472//1472 1374//1374 -f 1374//1374 1472//1472 1473//1473 -f 1374//1374 1473//1473 1462//1462 -f 1089//1089 1094//1094 1199//1199 -f 1199//1199 1094//1094 1193//1193 -f 1199//1199 1193//1193 1376//1376 -f 1376//1376 1193//1193 1195//1195 -f 1376//1376 1195//1195 1377//1377 -f 1377//1377 1195//1195 1230//1230 -f 1377//1377 1230//1230 1378//1378 -f 1378//1378 1230//1230 1232//1232 -f 1378//1378 1232//1232 1379//1379 -f 1379//1379 1232//1232 1241//1241 -f 1379//1379 1241//1241 1381//1381 -f 1381//1381 1241//1241 1474//1474 -f 1475//1475 1476//1476 1477//1477 -f 1099//1099 1198//1198 1245//1245 -f 1245//1245 1198//1198 1478//1478 -f 1245//1245 1478//1478 1244//1244 -f 1244//1244 1478//1478 1479//1479 -f 1244//1244 1479//1479 1243//1243 -f 1243//1243 1479//1479 1480//1480 -f 1243//1243 1480//1480 1242//1242 -f 1242//1242 1480//1480 1475//1475 -f 1242//1242 1475//1475 1241//1241 -f 1241//1241 1475//1475 1477//1477 -f 1241//1241 1477//1477 1474//1474 -f 1103//1103 1228//1228 1198//1198 -f 1198//1198 1228//1228 1481//1481 -f 1198//1198 1481//1481 1478//1478 -f 1478//1478 1481//1481 1482//1482 -f 1478//1478 1482//1482 1479//1479 -f 1479//1479 1482//1482 1483//1483 -f 1479//1479 1483//1483 1480//1480 -f 1480//1480 1483//1483 1174//1174 -f 1480//1480 1174//1174 1475//1475 -f 1475//1475 1174//1174 1173//1173 -f 1475//1475 1173//1173 1476//1476 -f 1101//1101 1197//1197 1228//1228 -f 1228//1228 1197//1197 1484//1484 -f 1228//1228 1484//1484 1481//1481 -f 1481//1481 1484//1484 1485//1485 -f 1481//1481 1485//1485 1482//1482 -f 1482//1482 1485//1485 1486//1486 -f 1482//1482 1486//1486 1483//1483 -f 1483//1483 1486//1486 1487//1487 -f 1483//1483 1487//1487 1174//1174 -f 1174//1174 1487//1487 1488//1488 -f 1174//1174 1488//1488 1172//1172 -f 1489//1489 1490//1490 1491//1491 -f 1104//1104 1196//1196 1197//1197 -f 1197//1197 1196//1196 1492//1492 -f 1197//1197 1492//1492 1484//1484 -f 1484//1484 1492//1492 1493//1493 -f 1484//1484 1493//1493 1485//1485 -f 1485//1485 1493//1493 1494//1494 -f 1485//1485 1494//1494 1486//1486 -f 1486//1486 1494//1494 1489//1489 -f 1486//1486 1489//1489 1487//1487 -f 1487//1487 1489//1489 1491//1491 -f 1487//1487 1491//1491 1488//1488 -f 1495//1495 1496//1496 1497//1497 -f 1108//1108 1229//1229 1196//1196 -f 1196//1196 1229//1229 1498//1498 -f 1196//1196 1498//1498 1492//1492 -f 1492//1492 1498//1498 1499//1499 -f 1492//1492 1499//1499 1493//1493 -f 1493//1493 1499//1499 1500//1500 -f 1493//1493 1500//1500 1494//1494 -f 1494//1494 1500//1500 1495//1495 -f 1494//1494 1495//1495 1489//1489 -f 1489//1489 1495//1495 1497//1497 -f 1489//1489 1497//1497 1490//1490 -f 1106//1106 1390//1390 1229//1229 -f 1229//1229 1390//1390 1240//1240 -f 1229//1229 1240//1240 1498//1498 -f 1498//1498 1240//1240 1238//1238 -f 1498//1498 1238//1238 1499//1499 -f 1499//1499 1238//1238 1236//1236 -f 1499//1499 1236//1236 1500//1500 -f 1500//1500 1236//1236 1192//1192 -f 1500//1500 1192//1192 1495//1495 -f 1495//1495 1192//1192 1191//1191 -f 1495//1495 1191//1191 1496//1496 -f 1501//1501 1502//1502 1468//1468 -f 1503//1503 1356//1356 1504//1504 -f 1504//1504 1356//1356 1357//1357 -f 1504//1504 1357//1357 1505//1505 -f 1505//1505 1357//1357 1176//1176 -f 1505//1505 1176//1176 1506//1506 -f 1507//1507 1458//1458 1508//1508 -f 1508//1508 1458//1458 1457//1457 -f 1508//1508 1457//1457 1503//1503 -f 1503//1503 1457//1457 1456//1456 -f 1503//1503 1456//1456 1356//1356 -f 1509//1509 1455//1455 1510//1510 -f 1510//1510 1455//1455 1454//1454 -f 1510//1510 1454//1454 1511//1511 -f 1511//1511 1454//1454 1453//1453 -f 1511//1511 1453//1453 1512//1512 -f 1512//1512 1453//1453 1448//1448 -f 1512//1512 1448//1448 1507//1507 -f 1507//1507 1448//1448 1447//1447 -f 1507//1507 1447//1447 1458//1458 -f 1513//1513 1441//1441 1514//1514 -f 1514//1514 1441//1441 1332//1332 -f 1514//1514 1332//1332 1515//1515 -f 1515//1515 1332//1332 1333//1333 -f 1515//1515 1333//1333 1516//1516 -f 1516//1516 1333//1333 1179//1179 -f 1516//1516 1179//1179 1509//1509 -f 1509//1509 1179//1179 1178//1178 -f 1509//1509 1178//1178 1455//1455 -f 1517//1517 1438//1438 1518//1518 -f 1518//1518 1438//1438 1433//1433 -f 1518//1518 1433//1433 1519//1519 -f 1519//1519 1433//1433 1432//1432 -f 1519//1519 1432//1432 1520//1520 -f 1520//1520 1432//1432 1443//1443 -f 1520//1520 1443//1443 1513//1513 -f 1513//1513 1443//1443 1442//1442 -f 1513//1513 1442//1442 1441//1441 -f 1521//1521 1309//1309 1522//1522 -f 1522//1522 1309//1309 1182//1182 -f 1522//1522 1182//1182 1523//1523 -f 1523//1523 1182//1182 1181//1181 -f 1523//1523 1181//1181 1524//1524 -f 1524//1524 1181//1181 1440//1440 -f 1524//1524 1440//1440 1517//1517 -f 1517//1517 1440//1440 1439//1439 -f 1517//1517 1439//1439 1438//1438 -f 1423//1423 1418//1418 1525//1525 -f 1525//1525 1418//1418 1417//1417 -f 1525//1525 1417//1417 1526//1526 -f 1526//1526 1417//1417 1428//1428 -f 1526//1526 1428//1428 1527//1527 -f 1527//1527 1428//1428 1427//1427 -f 1527//1527 1427//1427 1528//1528 -f 1528//1528 1427//1427 1426//1426 -f 1528//1528 1426//1426 1521//1521 -f 1521//1521 1426//1426 1308//1308 -f 1521//1521 1308//1308 1309//1309 -f 1525//1525 1529//1529 1423//1423 -f 1423//1423 1529//1529 1530//1530 -f 1423//1423 1530//1530 1424//1424 -f 1424//1424 1530//1530 1531//1531 -f 1532//1532 1284//1284 1533//1533 -f 1533//1533 1284//1284 1285//1285 -f 1533//1533 1285//1285 1534//1534 -f 1534//1534 1285//1285 1185//1185 -f 1534//1534 1185//1185 1535//1535 -f 1535//1535 1185//1185 1184//1184 -f 1535//1535 1184//1184 1531//1531 -f 1531//1531 1184//1184 1425//1425 -f 1531//1531 1425//1425 1424//1424 -f 1536//1536 1402//1402 1537//1537 -f 1537//1537 1402//1402 1401//1401 -f 1537//1537 1401//1401 1538//1538 -f 1538//1538 1401//1401 1413//1413 -f 1538//1538 1413//1413 1539//1539 -f 1539//1539 1413//1413 1412//1412 -f 1539//1539 1412//1412 1532//1532 -f 1532//1532 1412//1412 1411//1411 -f 1532//1532 1411//1411 1284//1284 -f 1540//1540 1187//1187 1541//1541 -f 1541//1541 1187//1187 1410//1410 -f 1541//1541 1410//1410 1542//1542 -f 1542//1542 1410//1410 1409//1409 -f 1542//1542 1409//1409 1536//1536 -f 1536//1536 1409//1409 1408//1408 -f 1536//1536 1408//1408 1402//1402 -f 1543//1543 1396//1396 1544//1544 -f 1544//1544 1396//1396 1395//1395 -f 1544//1544 1395//1395 1545//1545 -f 1545//1545 1395//1395 1394//1394 -f 1545//1545 1394//1394 1546//1546 -f 1546//1546 1394//1394 1261//1261 -f 1546//1546 1261//1261 1547//1547 -f 1547//1547 1261//1261 1262//1262 -f 1547//1547 1262//1262 1540//1540 -f 1540//1540 1262//1262 1188//1188 -f 1540//1540 1188//1188 1187//1187 -f 1548//1548 1393//1393 1549//1549 -f 1549//1549 1393//1393 1392//1392 -f 1549//1549 1392//1392 1550//1550 -f 1550//1550 1392//1392 1391//1391 -f 1550//1550 1391//1391 1551//1551 -f 1551//1551 1391//1391 1385//1385 -f 1551//1551 1385//1385 1543//1543 -f 1543//1543 1385//1385 1384//1384 -f 1543//1543 1384//1384 1396//1396 -f 1552//1552 1496//1496 1553//1553 -f 1553//1553 1496//1496 1191//1191 -f 1553//1553 1191//1191 1554//1554 -f 1554//1554 1191//1191 1190//1190 -f 1554//1554 1190//1190 1555//1555 -f 1555//1555 1190//1190 1382//1382 -f 1555//1555 1382//1382 1548//1548 -f 1548//1548 1382//1382 1383//1383 -f 1548//1548 1383//1383 1393//1393 -f 1556//1556 1173//1173 1557//1557 -f 1557//1557 1173//1173 1172//1172 -f 1557//1557 1172//1172 1558//1558 -f 1558//1558 1172//1172 1488//1488 -f 1558//1558 1488//1488 1559//1559 -f 1559//1559 1488//1488 1491//1491 -f 1559//1559 1491//1491 1560//1560 -f 1560//1560 1491//1491 1490//1490 -f 1560//1560 1490//1490 1552//1552 -f 1552//1552 1490//1490 1497//1497 -f 1552//1552 1497//1497 1496//1496 -f 1561//1561 1380//1380 1562//1562 -f 1562//1562 1380//1380 1381//1381 -f 1562//1562 1381//1381 1563//1563 -f 1563//1563 1381//1381 1474//1474 -f 1563//1563 1474//1474 1564//1564 -f 1564//1564 1474//1474 1477//1477 -f 1564//1564 1477//1477 1556//1556 -f 1556//1556 1477//1477 1476//1476 -f 1556//1556 1476//1476 1173//1173 -f 1501//1501 1468//1468 1565//1565 -f 1468//1468 1463//1463 1565//1565 -f 1565//1565 1463//1463 1462//1462 -f 1565//1565 1462//1462 1566//1566 -f 1566//1566 1462//1462 1473//1473 -f 1566//1566 1473//1473 1567//1567 -f 1567//1567 1473//1473 1472//1472 -f 1567//1567 1472//1472 1561//1561 -f 1561//1561 1472//1472 1471//1471 -f 1561//1561 1471//1471 1380//1380 -f 1176//1176 1175//1175 1506//1506 -f 1506//1506 1175//1175 1470//1470 -f 1506//1506 1470//1470 1502//1502 -f 1502//1502 1470//1470 1469//1469 -f 1502//1502 1469//1469 1468//1468 -f 1565//1565 1568//1568 1501//1501 -f 1501//1501 1568//1568 1569//1569 -f 1501//1501 1569//1569 1502//1502 -f 1502//1502 1569//1569 1570//1570 -f 1502//1502 1570//1570 1506//1506 -f 1564//1564 1571//1571 1563//1563 -f 1563//1563 1571//1571 1572//1572 -f 1563//1563 1572//1572 1562//1562 -f 1562//1562 1572//1572 1573//1573 -f 1562//1562 1573//1573 1561//1561 -f 1561//1561 1573//1573 1574//1574 -f 1561//1561 1574//1574 1567//1567 -f 1567//1567 1574//1574 1575//1575 -f 1567//1567 1575//1575 1566//1566 -f 1566//1566 1575//1575 1576//1576 -f 1566//1566 1576//1576 1565//1565 -f 1565//1565 1576//1576 1577//1577 -f 1565//1565 1577//1577 1568//1568 -f 1560//1560 1578//1578 1559//1559 -f 1559//1559 1578//1578 1579//1579 -f 1559//1559 1579//1579 1558//1558 -f 1558//1558 1579//1579 1580//1580 -f 1558//1558 1580//1580 1557//1557 -f 1557//1557 1580//1580 1581//1581 -f 1557//1557 1581//1581 1556//1556 -f 1556//1556 1581//1581 1582//1582 -f 1556//1556 1582//1582 1564//1564 -f 1564//1564 1582//1582 1583//1583 -f 1564//1564 1583//1583 1571//1571 -f 1555//1555 1584//1584 1554//1554 -f 1554//1554 1584//1584 1585//1585 -f 1554//1554 1585//1585 1553//1553 -f 1553//1553 1585//1585 1586//1586 -f 1553//1553 1586//1586 1552//1552 -f 1552//1552 1586//1586 1587//1587 -f 1552//1552 1587//1587 1560//1560 -f 1560//1560 1587//1587 1588//1588 -f 1560//1560 1588//1588 1578//1578 -f 1544//1544 1589//1589 1543//1543 -f 1543//1543 1589//1589 1590//1590 -f 1543//1543 1590//1590 1551//1551 -f 1551//1551 1590//1590 1591//1591 -f 1551//1551 1591//1591 1550//1550 -f 1550//1550 1591//1591 1592//1592 -f 1550//1550 1592//1592 1549//1549 -f 1549//1549 1592//1592 1593//1593 -f 1549//1549 1593//1593 1548//1548 -f 1548//1548 1593//1593 1594//1594 -f 1548//1548 1594//1594 1555//1555 -f 1555//1555 1594//1594 1595//1595 -f 1555//1555 1595//1595 1584//1584 -f 1540//1540 1596//1596 1547//1547 -f 1547//1547 1596//1596 1597//1597 -f 1547//1547 1597//1597 1546//1546 -f 1546//1546 1597//1597 1598//1598 -f 1546//1546 1598//1598 1545//1545 -f 1545//1545 1598//1598 1599//1599 -f 1545//1545 1599//1599 1544//1544 -f 1544//1544 1599//1599 1600//1600 -f 1544//1544 1600//1600 1589//1589 -f 1535//1535 1601//1601 1534//1534 -f 1534//1534 1601//1601 1602//1602 -f 1534//1534 1602//1602 1533//1533 -f 1533//1533 1602//1602 1603//1603 -f 1533//1533 1603//1603 1532//1532 -f 1532//1532 1603//1603 1604//1604 -f 1532//1532 1604//1604 1539//1539 -f 1539//1539 1604//1604 1605//1605 -f 1539//1539 1605//1605 1538//1538 -f 1538//1538 1605//1605 1606//1606 -f 1538//1538 1606//1606 1537//1537 -f 1537//1537 1606//1606 1607//1607 -f 1537//1537 1607//1607 1536//1536 -f 1536//1536 1607//1607 1608//1608 -f 1536//1536 1608//1608 1542//1542 -f 1542//1542 1608//1608 1609//1609 -f 1542//1542 1609//1609 1541//1541 -f 1541//1541 1609//1609 1610//1610 -f 1541//1541 1610//1610 1540//1540 -f 1540//1540 1610//1610 1611//1611 -f 1540//1540 1611//1611 1596//1596 -f 1526//1526 1612//1612 1525//1525 -f 1525//1525 1612//1612 1613//1613 -f 1525//1525 1613//1613 1529//1529 -f 1529//1529 1613//1613 1614//1614 -f 1529//1529 1614//1614 1530//1530 -f 1530//1530 1614//1614 1615//1615 -f 1530//1530 1615//1615 1531//1531 -f 1531//1531 1615//1615 1616//1616 -f 1531//1531 1616//1616 1535//1535 -f 1535//1535 1616//1616 1617//1617 -f 1535//1535 1617//1617 1601//1601 -f 1520//1520 1618//1618 1519//1519 -f 1519//1519 1618//1618 1619//1619 -f 1519//1519 1619//1619 1518//1518 -f 1518//1518 1619//1619 1620//1620 -f 1518//1518 1620//1620 1517//1517 -f 1517//1517 1620//1620 1621//1621 -f 1517//1517 1621//1621 1524//1524 -f 1524//1524 1621//1621 1622//1622 -f 1524//1524 1622//1622 1523//1523 -f 1523//1523 1622//1622 1623//1623 -f 1523//1523 1623//1623 1522//1522 -f 1522//1522 1623//1623 1624//1624 -f 1522//1522 1624//1624 1521//1521 -f 1521//1521 1624//1624 1625//1625 -f 1521//1521 1625//1625 1528//1528 -f 1528//1528 1625//1625 1626//1626 -f 1528//1528 1626//1626 1527//1527 -f 1527//1527 1626//1626 1627//1627 -f 1527//1527 1627//1627 1526//1526 -f 1526//1526 1627//1627 1628//1628 -f 1526//1526 1628//1628 1612//1612 -f 1516//1516 1629//1629 1515//1515 -f 1515//1515 1629//1629 1630//1630 -f 1515//1515 1630//1630 1514//1514 -f 1514//1514 1630//1630 1631//1631 -f 1514//1514 1631//1631 1513//1513 -f 1513//1513 1631//1631 1632//1632 -f 1513//1513 1632//1632 1520//1520 -f 1520//1520 1632//1632 1633//1633 -f 1520//1520 1633//1633 1618//1618 -f 1508//1508 1634//1634 1507//1507 -f 1507//1507 1634//1634 1635//1635 -f 1507//1507 1635//1635 1512//1512 -f 1512//1512 1635//1635 1636//1636 -f 1512//1512 1636//1636 1511//1511 -f 1511//1511 1636//1636 1637//1637 -f 1511//1511 1637//1637 1510//1510 -f 1510//1510 1637//1637 1638//1638 -f 1510//1510 1638//1638 1509//1509 -f 1509//1509 1638//1638 1639//1639 -f 1509//1509 1639//1639 1516//1516 -f 1516//1516 1639//1639 1640//1640 -f 1516//1516 1640//1640 1629//1629 -f 1570//1570 1641//1641 1506//1506 -f 1506//1506 1641//1641 1642//1642 -f 1506//1506 1642//1642 1505//1505 -f 1505//1505 1642//1642 1643//1643 -f 1505//1505 1643//1643 1504//1504 -f 1504//1504 1643//1643 1644//1644 -f 1504//1504 1644//1644 1503//1503 -f 1503//1503 1644//1644 1645//1645 -f 1503//1503 1645//1645 1508//1508 -f 1508//1508 1645//1645 1646//1646 -f 1508//1508 1646//1646 1634//1634 -f 1647//1647 1648//1648 1649//1649 -f 1650//1650 1651//1651 1652//1652 -f 1653//1653 1654//1654 1655//1655 -f 1656//1656 1657//1657 1658//1658 -f 1659//1659 1660//1660 1661//1661 -f 1662//1662 1663//1663 1664//1664 -f 1665//1665 1666//1666 1667//1667 -f 1668//1668 1669//1669 1670//1670 -f 1671//1671 1672//1672 1673//1673 -f 1674//1674 1675//1675 1676//1676 -f 1677//1677 1678//1678 1679//1679 -f 1680//1680 1681//1681 1682//1682 -f 1682//1682 1681//1681 1683//1683 -f 1683//1683 1585//1585 1682//1682 -f 1682//1682 1585//1585 1584//1584 -f 1682//1682 1584//1584 1595//1595 -f 1595//1595 1594//1594 1684//1684 -f 1684//1684 1594//1594 1593//1593 -f 1684//1684 1593//1593 1685//1685 -f 1685//1685 1593//1593 1592//1592 -f 1685//1685 1592//1592 1677//1677 -f 1592//1592 1591//1591 1677//1677 -f 1677//1677 1591//1591 1590//1590 -f 1677//1677 1590//1590 1678//1678 -f 1590//1590 1589//1589 1678//1678 -f 1678//1678 1589//1589 1600//1600 -f 1678//1678 1600//1600 1686//1686 -f 1686//1686 1600//1600 1599//1599 -f 1686//1686 1599//1599 1674//1674 -f 1599//1599 1598//1598 1674//1674 -f 1674//1674 1598//1598 1597//1597 -f 1674//1674 1597//1597 1675//1675 -f 1597//1597 1596//1596 1675//1675 -f 1675//1675 1596//1596 1611//1611 -f 1675//1675 1611//1611 1687//1687 -f 1687//1687 1611//1611 1610//1610 -f 1687//1687 1610//1610 1688//1688 -f 1610//1610 1609//1609 1688//1688 -f 1688//1688 1609//1609 1608//1608 -f 1688//1688 1608//1608 1689//1689 -f 1689//1689 1608//1608 1607//1607 -f 1689//1689 1607//1607 1606//1606 -f 1690//1690 1605//1605 1604//1604 -f 1690//1690 1604//1604 1691//1691 -f 1691//1691 1604//1604 1603//1603 -f 1691//1691 1603//1603 1671//1671 -f 1603//1603 1602//1602 1671//1671 -f 1671//1671 1602//1602 1601//1601 -f 1671//1671 1601//1601 1672//1672 -f 1601//1601 1617//1617 1672//1672 -f 1672//1672 1617//1617 1616//1616 -f 1672//1672 1616//1616 1692//1692 -f 1692//1692 1616//1616 1615//1615 -f 1692//1692 1615//1615 1668//1668 -f 1615//1615 1614//1614 1668//1668 -f 1668//1668 1614//1614 1613//1613 -f 1668//1668 1613//1613 1669//1669 -f 1613//1613 1612//1612 1669//1669 -f 1669//1669 1612//1612 1628//1628 -f 1669//1669 1628//1628 1693//1693 -f 1693//1693 1628//1628 1627//1627 -f 1693//1693 1627//1627 1694//1694 -f 1624//1624 1695//1695 1625//1625 -f 1625//1625 1695//1695 1694//1694 -f 1625//1625 1694//1694 1626//1626 -f 1626//1626 1694//1694 1627//1627 -f 1696//1696 1623//1623 1622//1622 -f 1696//1696 1622//1622 1697//1697 -f 1697//1697 1622//1622 1621//1621 -f 1697//1697 1621//1621 1665//1665 -f 1621//1621 1620//1620 1665//1665 -f 1665//1665 1620//1620 1619//1619 -f 1665//1665 1619//1619 1666//1666 -f 1619//1619 1618//1618 1666//1666 -f 1666//1666 1618//1618 1633//1633 -f 1666//1666 1633//1633 1698//1698 -f 1698//1698 1633//1633 1632//1632 -f 1698//1698 1632//1632 1662//1662 -f 1632//1632 1631//1631 1662//1662 -f 1662//1662 1631//1631 1630//1630 -f 1662//1662 1630//1630 1663//1663 -f 1630//1630 1629//1629 1663//1663 -f 1663//1663 1629//1629 1640//1640 -f 1663//1663 1640//1640 1699//1699 -f 1699//1699 1640//1640 1639//1639 -f 1699//1699 1639//1639 1700//1700 -f 1639//1639 1638//1638 1700//1700 -f 1700//1700 1638//1638 1637//1637 -f 1700//1700 1637//1637 1659//1659 -f 1637//1637 1636//1636 1659//1659 -f 1659//1659 1636//1636 1635//1635 -f 1659//1659 1635//1635 1660//1660 -f 1635//1635 1634//1634 1660//1660 -f 1660//1660 1634//1634 1646//1646 -f 1660//1660 1646//1646 1701//1701 -f 1701//1701 1646//1646 1645//1645 -f 1701//1701 1645//1645 1656//1656 -f 1645//1645 1644//1644 1656//1656 -f 1656//1656 1644//1644 1643//1643 -f 1656//1656 1643//1643 1657//1657 -f 1643//1643 1642//1642 1657//1657 -f 1657//1657 1642//1642 1641//1641 -f 1657//1657 1641//1641 1702//1702 -f 1702//1702 1641//1641 1570//1570 -f 1702//1702 1570//1570 1653//1653 -f 1570//1570 1569//1569 1653//1653 -f 1653//1653 1569//1569 1568//1568 -f 1653//1653 1568//1568 1654//1654 -f 1568//1568 1577//1577 1654//1654 -f 1654//1654 1577//1577 1576//1576 -f 1654//1654 1576//1576 1703//1703 -f 1703//1703 1576//1576 1575//1575 -f 1703//1703 1575//1575 1704//1704 -f 1575//1575 1574//1574 1704//1704 -f 1704//1704 1574//1574 1573//1573 -f 1704//1704 1573//1573 1650//1650 -f 1573//1573 1572//1572 1650//1650 -f 1650//1650 1572//1572 1571//1571 -f 1650//1650 1571//1571 1651//1651 -f 1571//1571 1583//1583 1651//1651 -f 1651//1651 1583//1583 1582//1582 -f 1651//1651 1582//1582 1705//1705 -f 1705//1705 1582//1582 1581//1581 -f 1705//1705 1581//1581 1647//1647 -f 1581//1581 1580//1580 1647//1647 -f 1647//1647 1580//1580 1579//1579 -f 1647//1647 1579//1579 1648//1648 -f 1579//1579 1578//1578 1648//1648 -f 1648//1648 1578//1578 1588//1588 -f 1648//1648 1588//1588 1706//1706 -f 1706//1706 1588//1588 1587//1587 -f 1706//1706 1587//1587 1683//1683 -f 1683//1683 1587//1587 1586//1586 -f 1683//1683 1586//1586 1585//1585 -f 1595//1595 1684//1684 1682//1682 -f 1682//1682 1684//1684 1707//1707 -f 1682//1682 1707//1707 1680//1680 -f 1679//1679 1708//1708 1677//1677 -f 1677//1677 1708//1708 1709//1709 -f 1677//1677 1709//1709 1685//1685 -f 1685//1685 1709//1709 1710//1710 -f 1685//1685 1710//1710 1684//1684 -f 1684//1684 1710//1710 1711//1711 -f 1684//1684 1711//1711 1707//1707 -f 1676//1676 1712//1712 1674//1674 -f 1674//1674 1712//1712 1713//1713 -f 1674//1674 1713//1713 1686//1686 -f 1686//1686 1713//1713 1714//1714 -f 1686//1686 1714//1714 1678//1678 -f 1678//1678 1714//1714 1715//1715 -f 1678//1678 1715//1715 1679//1679 -f 1688//1688 1716//1716 1687//1687 -f 1687//1687 1716//1716 1717//1717 -f 1687//1687 1717//1717 1675//1675 -f 1675//1675 1717//1717 1718//1718 -f 1675//1675 1718//1718 1676//1676 -f 1719//1719 1689//1689 1690//1690 -f 1690//1690 1689//1689 1606//1606 -f 1690//1690 1606//1606 1605//1605 -f 1719//1719 1720//1720 1689//1689 -f 1689//1689 1720//1720 1721//1721 -f 1689//1689 1721//1721 1688//1688 -f 1688//1688 1721//1721 1722//1722 -f 1688//1688 1722//1722 1716//1716 -f 1673//1673 1723//1723 1671//1671 -f 1671//1671 1723//1723 1724//1724 -f 1671//1671 1724//1724 1691//1691 -f 1691//1691 1724//1724 1725//1725 -f 1691//1691 1725//1725 1690//1690 -f 1690//1690 1725//1725 1726//1726 -f 1690//1690 1726//1726 1719//1719 -f 1670//1670 1727//1727 1668//1668 -f 1668//1668 1727//1727 1728//1728 -f 1668//1668 1728//1728 1692//1692 -f 1692//1692 1728//1728 1729//1729 -f 1692//1692 1729//1729 1672//1672 -f 1672//1672 1729//1729 1730//1730 -f 1672//1672 1730//1730 1673//1673 -f 1694//1694 1731//1731 1693//1693 -f 1693//1693 1731//1731 1732//1732 -f 1693//1693 1732//1732 1669//1669 -f 1669//1669 1732//1732 1733//1733 -f 1669//1669 1733//1733 1670//1670 -f 1734//1734 1695//1695 1696//1696 -f 1696//1696 1695//1695 1624//1624 -f 1696//1696 1624//1624 1623//1623 -f 1734//1734 1735//1735 1695//1695 -f 1695//1695 1735//1735 1736//1736 -f 1695//1695 1736//1736 1694//1694 -f 1694//1694 1736//1736 1737//1737 -f 1694//1694 1737//1737 1731//1731 -f 1667//1667 1738//1738 1665//1665 -f 1665//1665 1738//1738 1739//1739 -f 1665//1665 1739//1739 1697//1697 -f 1697//1697 1739//1739 1740//1740 -f 1697//1697 1740//1740 1696//1696 -f 1696//1696 1740//1740 1741//1741 -f 1696//1696 1741//1741 1734//1734 -f 1664//1664 1742//1742 1662//1662 -f 1662//1662 1742//1742 1743//1743 -f 1662//1662 1743//1743 1698//1698 -f 1698//1698 1743//1743 1744//1744 -f 1698//1698 1744//1744 1666//1666 -f 1666//1666 1744//1744 1745//1745 -f 1666//1666 1745//1745 1667//1667 -f 1700//1700 1746//1746 1699//1699 -f 1699//1699 1746//1746 1747//1747 -f 1699//1699 1747//1747 1663//1663 -f 1663//1663 1747//1747 1748//1748 -f 1663//1663 1748//1748 1664//1664 -f 1661//1661 1749//1749 1659//1659 -f 1659//1659 1749//1749 1750//1750 -f 1659//1659 1750//1750 1700//1700 -f 1700//1700 1750//1750 1751//1751 -f 1700//1700 1751//1751 1746//1746 -f 1658//1658 1752//1752 1656//1656 -f 1656//1656 1752//1752 1753//1753 -f 1656//1656 1753//1753 1701//1701 -f 1701//1701 1753//1753 1754//1754 -f 1701//1701 1754//1754 1660//1660 -f 1660//1660 1754//1754 1755//1755 -f 1660//1660 1755//1755 1661//1661 -f 1655//1655 1756//1756 1653//1653 -f 1653//1653 1756//1756 1757//1757 -f 1653//1653 1757//1757 1702//1702 -f 1702//1702 1757//1757 1758//1758 -f 1702//1702 1758//1758 1657//1657 -f 1657//1657 1758//1758 1759//1759 -f 1657//1657 1759//1759 1658//1658 -f 1704//1704 1760//1760 1703//1703 -f 1703//1703 1760//1760 1761//1761 -f 1703//1703 1761//1761 1654//1654 -f 1654//1654 1761//1761 1762//1762 -f 1654//1654 1762//1762 1655//1655 -f 1652//1652 1763//1763 1650//1650 -f 1650//1650 1763//1763 1764//1764 -f 1650//1650 1764//1764 1704//1704 -f 1704//1704 1764//1764 1765//1765 -f 1704//1704 1765//1765 1760//1760 -f 1649//1649 1766//1766 1647//1647 -f 1647//1647 1766//1766 1767//1767 -f 1647//1647 1767//1767 1705//1705 -f 1705//1705 1767//1767 1768//1768 -f 1705//1705 1768//1768 1651//1651 -f 1651//1651 1768//1768 1769//1769 -f 1651//1651 1769//1769 1652//1652 -f 1681//1681 1770//1770 1683//1683 -f 1683//1683 1770//1770 1771//1771 -f 1683//1683 1771//1771 1706//1706 -f 1706//1706 1771//1771 1772//1772 -f 1706//1706 1772//1772 1648//1648 -f 1648//1648 1772//1772 1773//1773 -f 1648//1648 1773//1773 1649//1649 -f 1774//1774 1758//1758 1775//1775 -f 1775//1775 1758//1758 1757//1757 -f 1775//1775 1757//1757 1776//1776 -f 1776//1776 1757//1757 1756//1756 -f 1776//1776 1756//1756 1777//1777 -f 1777//1777 1756//1756 1655//1655 -f 1777//1777 1655//1655 1778//1778 -f 1655//1655 1762//1762 1778//1778 -f 1778//1778 1762//1762 1761//1761 -f 1778//1778 1761//1761 1779//1779 -f 1779//1779 1761//1761 1760//1760 -f 1779//1779 1760//1760 1780//1780 -f 1780//1780 1760//1760 1765//1765 -f 1780//1780 1765//1765 1781//1781 -f 1781//1781 1765//1765 1764//1764 -f 1781//1781 1764//1764 1782//1782 -f 1782//1782 1764//1764 1763//1763 -f 1782//1782 1763//1763 1783//1783 -f 1783//1783 1763//1763 1652//1652 -f 1783//1783 1652//1652 1784//1784 -f 1784//1784 1652//1652 1769//1769 -f 1784//1784 1769//1769 1785//1785 -f 1785//1785 1769//1769 1768//1768 -f 1785//1785 1768//1768 1786//1786 -f 1768//1768 1767//1767 1786//1786 -f 1786//1786 1767//1767 1766//1766 -f 1786//1786 1766//1766 1787//1787 -f 1787//1787 1766//1766 1649//1649 -f 1787//1787 1649//1649 1788//1788 -f 1788//1788 1649//1649 1773//1773 -f 1788//1788 1773//1773 1789//1789 -f 1789//1789 1773//1773 1772//1772 -f 1789//1789 1772//1772 1790//1790 -f 1790//1790 1772//1772 1771//1771 -f 1790//1790 1771//1771 1791//1791 -f 1771//1771 1770//1770 1791//1791 -f 1791//1791 1770//1770 1681//1681 -f 1791//1791 1681//1681 1792//1792 -f 1792//1792 1681//1681 1680//1680 -f 1792//1792 1680//1680 1793//1793 -f 1793//1793 1680//1680 1707//1707 -f 1793//1793 1707//1707 1794//1794 -f 1794//1794 1707//1707 1711//1711 -f 1794//1794 1711//1711 1795//1795 -f 1795//1795 1711//1711 1710//1710 -f 1795//1795 1710//1710 1796//1796 -f 1796//1796 1710//1710 1709//1709 -f 1796//1796 1709//1709 1797//1797 -f 1709//1709 1708//1708 1797//1797 -f 1797//1797 1708//1708 1679//1679 -f 1797//1797 1679//1679 1798//1798 -f 1798//1798 1679//1679 1715//1715 -f 1798//1798 1715//1715 1799//1799 -f 1799//1799 1715//1715 1714//1714 -f 1799//1799 1714//1714 1800//1800 -f 1800//1800 1714//1714 1713//1713 -f 1800//1800 1713//1713 1801//1801 -f 1713//1713 1712//1712 1801//1801 -f 1801//1801 1712//1712 1676//1676 -f 1801//1801 1676//1676 1802//1802 -f 1802//1802 1676//1676 1718//1718 -f 1802//1802 1718//1718 1803//1803 -f 1803//1803 1718//1718 1717//1717 -f 1803//1803 1717//1717 1804//1804 -f 1804//1804 1717//1717 1716//1716 -f 1804//1804 1716//1716 1805//1805 -f 1716//1716 1722//1722 1805//1805 -f 1805//1805 1722//1722 1721//1721 -f 1805//1805 1721//1721 1806//1806 -f 1806//1806 1721//1721 1720//1720 -f 1806//1806 1720//1720 1807//1807 -f 1807//1807 1720//1720 1719//1719 -f 1807//1807 1719//1719 1808//1808 -f 1808//1808 1719//1719 1726//1726 -f 1808//1808 1726//1726 1809//1809 -f 1809//1809 1726//1726 1725//1725 -f 1809//1809 1725//1725 1810//1810 -f 1810//1810 1725//1725 1724//1724 -f 1810//1810 1724//1724 1811//1811 -f 1811//1811 1724//1724 1723//1723 -f 1811//1811 1723//1723 1812//1812 -f 1812//1812 1723//1723 1673//1673 -f 1812//1812 1673//1673 1813//1813 -f 1673//1673 1730//1730 1813//1813 -f 1813//1813 1730//1730 1729//1729 -f 1813//1813 1729//1729 1814//1814 -f 1814//1814 1729//1729 1728//1728 -f 1814//1814 1728//1728 1815//1815 -f 1815//1815 1728//1728 1727//1727 -f 1815//1815 1727//1727 1816//1816 -f 1816//1816 1727//1727 1670//1670 -f 1816//1816 1670//1670 1817//1817 -f 1817//1817 1670//1670 1733//1733 -f 1817//1817 1733//1733 1818//1818 -f 1818//1818 1733//1733 1732//1732 -f 1818//1818 1732//1732 1819//1819 -f 1819//1819 1732//1732 1731//1731 -f 1819//1819 1731//1731 1820//1820 -f 1731//1731 1737//1737 1820//1820 -f 1820//1820 1737//1737 1736//1736 -f 1820//1820 1736//1736 1821//1821 -f 1821//1821 1736//1736 1735//1735 -f 1821//1821 1735//1735 1822//1822 -f 1822//1822 1735//1735 1734//1734 -f 1822//1822 1734//1734 1823//1823 -f 1823//1823 1734//1734 1741//1741 -f 1823//1823 1741//1741 1824//1824 -f 1824//1824 1741//1741 1740//1740 -f 1824//1824 1740//1740 1825//1825 -f 1740//1740 1739//1739 1825//1825 -f 1825//1825 1739//1739 1738//1738 -f 1825//1825 1738//1738 1826//1826 -f 1826//1826 1738//1738 1667//1667 -f 1826//1826 1667//1667 1827//1827 -f 1827//1827 1667//1667 1745//1745 -f 1827//1827 1745//1745 1828//1828 -f 1828//1828 1745//1745 1744//1744 -f 1828//1828 1744//1744 1829//1829 -f 1829//1829 1744//1744 1743//1743 -f 1829//1829 1743//1743 1830//1830 -f 1743//1743 1742//1742 1830//1830 -f 1830//1830 1742//1742 1664//1664 -f 1830//1830 1664//1664 1831//1831 -f 1831//1831 1664//1664 1748//1748 -f 1831//1831 1748//1748 1832//1832 -f 1832//1832 1748//1748 1747//1747 -f 1832//1832 1747//1747 1833//1833 -f 1833//1833 1747//1747 1746//1746 -f 1833//1833 1746//1746 1834//1834 -f 1834//1834 1746//1746 1751//1751 -f 1834//1834 1751//1751 1835//1835 -f 1835//1835 1751//1751 1750//1750 -f 1835//1835 1750//1750 1836//1836 -f 1750//1750 1749//1749 1836//1836 -f 1836//1836 1749//1749 1661//1661 -f 1836//1836 1661//1661 1837//1837 -f 1837//1837 1661//1661 1755//1755 -f 1837//1837 1755//1755 1838//1838 -f 1838//1838 1755//1755 1754//1754 -f 1838//1838 1754//1754 1839//1839 -f 1839//1839 1754//1754 1753//1753 -f 1839//1839 1753//1753 1840//1840 -f 1753//1753 1752//1752 1840//1840 -f 1840//1840 1752//1752 1658//1658 -f 1840//1840 1658//1658 1774//1774 -f 1774//1774 1658//1658 1759//1759 -f 1774//1774 1759//1759 1758//1758 -f 1779//1779 111//111 1778//1778 -f 1778//1778 111//111 262//262 -f 1778//1778 262//262 1777//1777 -f 1777//1777 262//262 28//28 -f 1777//1777 28//28 1776//1776 -f 1776//1776 28//28 27//27 -f 1776//1776 27//27 1775//1775 -f 1781//1781 116//116 1780//1780 -f 1780//1780 116//116 117//117 -f 1780//1780 117//117 1779//1779 -f 1779//1779 117//117 112//112 -f 1779//1779 112//112 111//111 -f 1785//1785 119//119 1784//1784 -f 1784//1784 119//119 25//25 -f 1784//1784 25//25 1783//1783 -f 1783//1783 25//25 24//24 -f 1783//1783 24//24 1782//1782 -f 1782//1782 24//24 114//114 -f 1782//1782 114//114 1781//1781 -f 1781//1781 114//114 115//115 -f 1781//1781 115//115 116//116 -f 1789//1789 19//19 1788//1788 -f 1788//1788 19//19 22//22 -f 1788//1788 22//22 1787//1787 -f 1787//1787 22//22 21//21 -f 1787//1787 21//21 1786//1786 -f 1786//1786 21//21 122//122 -f 1786//1786 122//122 1785//1785 -f 1785//1785 122//122 120//120 -f 1785//1785 120//120 119//119 -f 1793//1793 79//79 1792//1792 -f 1792//1792 79//79 78//78 -f 1792//1792 78//78 1791//1791 -f 1791//1791 78//78 137//137 -f 1791//1791 137//137 1790//1790 -f 1790//1790 137//137 17//17 -f 1790//1790 17//17 1789//1789 -f 1789//1789 17//17 16//16 -f 1789//1789 16//16 19//19 -f 82//82 81//81 1797//1797 -f 1797//1797 81//81 154//154 -f 1797//1797 154//154 1796//1796 -f 1796//1796 154//154 73//73 -f 1796//1796 73//73 1795//1795 -f 1795//1795 73//73 72//72 -f 1795//1795 72//72 1794//1794 -f 1794//1794 72//72 76//76 -f 1794//1794 76//76 1793//1793 -f 1793//1793 76//76 75//75 -f 1793//1793 75//75 79//79 -f 1797//1797 1798//1798 82//82 -f 82//82 1798//1798 1799//1799 -f 82//82 1799//1799 69//69 -f 69//69 1799//1799 1800//1800 -f 1804//1804 66//66 1803//1803 -f 1803//1803 66//66 85//85 -f 1803//1803 85//85 1802//1802 -f 1802//1802 85//85 84//84 -f 1802//1802 84//84 1801//1801 -f 1801//1801 84//84 162//162 -f 1801//1801 162//162 1800//1800 -f 1800//1800 162//162 70//70 -f 1800//1800 70//70 69//69 -f 1808//1808 87//87 1807//1807 -f 1807//1807 87//87 322//322 -f 1807//1807 322//322 1806//1806 -f 1806//1806 322//322 64//64 -f 1806//1806 64//64 1805//1805 -f 1805//1805 64//64 63//63 -f 1805//1805 63//63 1804//1804 -f 1804//1804 63//63 67//67 -f 1804//1804 67//67 66//66 -f 1811//1811 333//333 1810//1810 -f 1810//1810 333//333 61//61 -f 1810//1810 61//61 1809//1809 -f 1809//1809 61//61 60//60 -f 1809//1809 60//60 1808//1808 -f 1808//1808 60//60 88//88 -f 1808//1808 88//88 87//87 -f 1816//1816 55//55 1815//1815 -f 1815//1815 55//55 54//54 -f 1815//1815 54//54 1814//1814 -f 1814//1814 54//54 58//58 -f 1814//1814 58//58 1813//1813 -f 1813//1813 58//58 57//57 -f 1813//1813 57//57 1812//1812 -f 1812//1812 57//57 91//91 -f 1812//1812 91//91 1811//1811 -f 1811//1811 91//91 90//90 -f 1811//1811 90//90 333//333 -f 1820//1820 52//52 1819//1819 -f 1819//1819 52//52 51//51 -f 1819//1819 51//51 1818//1818 -f 1818//1818 51//51 94//94 -f 1818//1818 94//94 1817//1817 -f 1817//1817 94//94 93//93 -f 1817//1817 93//93 1816//1816 -f 1816//1816 93//93 340//340 -f 1816//1816 340//340 55//55 -f 1824//1824 49//49 1823//1823 -f 1823//1823 49//49 48//48 -f 1823//1823 48//48 1822//1822 -f 1822//1822 48//48 97//97 -f 1822//1822 97//97 1821//1821 -f 1821//1821 97//97 96//96 -f 1821//1821 96//96 1820//1820 -f 1820//1820 96//96 352//352 -f 1820//1820 352//352 52//52 -f 1829//1829 42//42 1828//1828 -f 1828//1828 42//42 100//100 -f 1828//1828 100//100 1827//1827 -f 1827//1827 100//100 99//99 -f 1827//1827 99//99 1826//1826 -f 1826//1826 99//99 218//218 -f 1826//1826 218//218 1825//1825 -f 1825//1825 218//218 46//46 -f 1825//1825 46//46 1824//1824 -f 1824//1824 46//46 45//45 -f 1824//1824 45//45 49//49 -f 1833//1833 39//39 1832//1832 -f 1832//1832 39//39 103//103 -f 1832//1832 103//103 1831//1831 -f 1831//1831 103//103 102//102 -f 1831//1831 102//102 1830//1830 -f 1830//1830 102//102 368//368 -f 1830//1830 368//368 1829//1829 -f 1829//1829 368//368 43//43 -f 1829//1829 43//43 42//42 -f 1838//1838 106//106 1837//1837 -f 1837//1837 106//106 105//105 -f 1837//1837 105//105 1836//1836 -f 1836//1836 105//105 242//242 -f 1836//1836 242//242 1835//1835 -f 1835//1835 242//242 37//37 -f 1835//1835 37//37 1834//1834 -f 1834//1834 37//37 36//36 -f 1834//1834 36//36 1833//1833 -f 1833//1833 36//36 40//40 -f 1833//1833 40//40 39//39 -f 1840//1840 252//252 1839//1839 -f 1839//1839 252//252 34//34 -f 1839//1839 34//34 1838//1838 -f 1838//1838 34//34 33//33 -f 1838//1838 33//33 106//106 -f 27//27 31//31 1775//1775 -f 1775//1775 31//31 30//30 -f 1775//1775 30//30 1774//1774 -f 1774//1774 30//30 109//109 -f 1774//1774 109//109 1840//1840 -f 1840//1840 109//109 108//108 -f 1840//1840 108//108 252//252 -f 1841//1841 1842//1842 1843//1843 -f 1843//1843 1842//1842 1844//1844 -f 1842//1842 1845//1845 1844//1844 -f 1844//1844 1845//1845 1846//1846 -f 1844//1844 1846//1846 1847//1847 -f 1846//1846 1848//1848 1847//1847 -f 1847//1847 1848//1848 1849//1849 -f 1847//1847 1849//1849 1850//1850 -f 1849//1849 1851//1851 1850//1850 -f 1850//1850 1851//1851 1852//1852 -f 1850//1850 1852//1852 1853//1853 -f 1854//1854 1855//1855 1856//1856 -f 1856//1856 1855//1855 1853//1853 -f 1856//1856 1853//1853 1857//1857 -f 1857//1857 1853//1853 1852//1852 -f 1854//1854 1858//1858 1855//1855 -f 1855//1855 1858//1858 1859//1859 -f 1855//1855 1859//1859 1860//1860 -f 1861//1861 1862//1862 1863//1863 -f 1863//1863 1862//1862 1860//1860 -f 1863//1863 1860//1860 1864//1864 -f 1864//1864 1860//1860 1859//1859 -f 1861//1861 1865//1865 1862//1862 -f 1862//1862 1865//1865 1866//1866 -f 1862//1862 1866//1866 1867//1867 -f 1866//1866 1868//1868 1867//1867 -f 1867//1867 1868//1868 1869//1869 -f 1867//1867 1869//1869 1870//1870 -f 1871//1871 1872//1872 1873//1873 -f 1873//1873 1872//1872 1870//1870 -f 1873//1873 1870//1870 1874//1874 -f 1874//1874 1870//1870 1869//1869 -f 1871//1871 1875//1875 1872//1872 -f 1872//1872 1875//1875 1876//1876 -f 1872//1872 1876//1876 1877//1877 -f 1878//1878 1879//1879 1880//1880 -f 1880//1880 1879//1879 1877//1877 -f 1880//1880 1877//1877 1881//1881 -f 1881//1881 1877//1877 1876//1876 -f 1878//1878 1882//1882 1879//1879 -f 1879//1879 1882//1882 1883//1883 -f 1879//1879 1883//1883 1884//1884 -f 1883//1883 1885//1885 1884//1884 -f 1884//1884 1885//1885 1886//1886 -f 1884//1884 1886//1886 1887//1887 -f 1886//1886 1888//1888 1887//1887 -f 1887//1887 1888//1888 1889//1889 -f 1887//1887 1889//1889 1890//1890 -f 1889//1889 1891//1891 1890//1890 -f 1890//1890 1891//1891 1892//1892 -f 1890//1890 1892//1892 1893//1893 -f 1894//1894 1895//1895 1896//1896 -f 1896//1896 1895//1895 1893//1893 -f 1896//1896 1893//1893 1897//1897 -f 1897//1897 1893//1893 1892//1892 -f 1894//1894 1898//1898 1895//1895 -f 1895//1895 1898//1898 1899//1899 -f 1895//1895 1899//1899 1900//1900 -f 1901//1901 1902//1902 1903//1903 -f 1903//1903 1902//1902 1900//1900 -f 1903//1903 1900//1900 1904//1904 -f 1904//1904 1900//1900 1899//1899 -f 1901//1901 1905//1905 1902//1902 -f 1902//1902 1905//1905 1906//1906 -f 1902//1902 1906//1906 1907//1907 -f 1906//1906 1908//1908 1907//1907 -f 1907//1907 1908//1908 1909//1909 -f 1907//1907 1909//1909 1910//1910 -f 1911//1911 1912//1912 1913//1913 -f 1913//1913 1912//1912 1910//1910 -f 1913//1913 1910//1910 1914//1914 -f 1914//1914 1910//1910 1909//1909 -f 1911//1911 1915//1915 1912//1912 -f 1912//1912 1915//1915 1916//1916 -f 1912//1912 1916//1916 1917//1917 -f 1918//1918 1919//1919 1920//1920 -f 1920//1920 1919//1919 1917//1917 -f 1920//1920 1917//1917 1921//1921 -f 1921//1921 1917//1917 1916//1916 -f 1918//1918 1922//1922 1919//1919 -f 1919//1919 1922//1922 1923//1923 -f 1919//1919 1923//1923 1924//1924 -f 1923//1923 1925//1925 1924//1924 -f 1924//1924 1925//1925 1926//1926 -f 1924//1924 1926//1926 1927//1927 -f 1926//1926 1928//1928 1927//1927 -f 1927//1927 1928//1928 1929//1929 -f 1927//1927 1929//1929 1930//1930 -f 1929//1929 1931//1931 1930//1930 -f 1930//1930 1931//1931 1932//1932 -f 1930//1930 1932//1932 1933//1933 -f 1934//1934 1935//1935 1936//1936 -f 1936//1936 1935//1935 1933//1933 -f 1936//1936 1933//1933 1937//1937 -f 1937//1937 1933//1933 1932//1932 -f 1934//1934 1938//1938 1935//1935 -f 1935//1935 1938//1938 1939//1939 -f 1935//1935 1939//1939 1940//1940 -f 1941//1941 1942//1942 1943//1943 -f 1943//1943 1942//1942 1940//1940 -f 1943//1943 1940//1940 1944//1944 -f 1944//1944 1940//1940 1939//1939 -f 1941//1941 1945//1945 1942//1942 -f 1942//1942 1945//1945 1946//1946 -f 1942//1942 1946//1946 1947//1947 -f 1946//1946 1948//1948 1947//1947 -f 1947//1947 1948//1948 1949//1949 -f 1947//1947 1949//1949 1950//1950 -f 1951//1951 1952//1952 1953//1953 -f 1953//1953 1952//1952 1950//1950 -f 1953//1953 1950//1950 1954//1954 -f 1954//1954 1950//1950 1949//1949 -f 1951//1951 1955//1955 1952//1952 -f 1952//1952 1955//1955 1956//1956 -f 1952//1952 1956//1956 1957//1957 -f 1956//1956 1958//1958 1957//1957 -f 1957//1957 1958//1958 1959//1959 -f 1957//1957 1959//1959 1843//1843 -f 1843//1843 1959//1959 1960//1960 -f 1843//1843 1960//1960 1841//1841 -f 1961//1961 1962//1962 1963//1963 -f 1964//1964 1965//1965 1966//1966 -f 1967//1967 1968//1968 1969//1969 -f 1970//1970 1971//1971 1972//1972 -f 1973//1973 1974//1974 1975//1975 -f 1976//1976 1977//1977 1978//1978 -f 1937//1937 1932//1932 1979//1979 -f 1956//1956 1955//1955 1980//1980 -f 1842//1842 1841//1841 1981//1981 -f 1848//1848 1846//1846 1982//1982 -f 1851//1851 1849//1849 1983//1983 -f 1859//1859 1858//1858 1984//1984 -f 1861//1861 1863//1863 1985//1985 -f 1866//1866 1865//1865 1986//1986 -f 1874//1874 1869//1869 1987//1987 -f 1871//1871 1873//1873 1988//1988 -f 1876//1876 1875//1875 1989//1989 -f 1883//1883 1882//1882 1990//1990 -f 1888//1888 1886//1886 1991//1991 -f 1891//1891 1889//1889 1992//1992 -f 1899//1899 1898//1898 1993//1993 -f 1901//1901 1903//1903 1994//1994 -f 1906//1906 1905//1905 1995//1995 -f 1914//1914 1909//1909 1996//1996 -f 1911//1911 1913//1913 1997//1997 -f 1916//1916 1915//1915 1998//1998 -f 1923//1923 1922//1922 1999//1999 -f 1928//1928 1926//1926 2000//2000 -f 1931//1931 1929//1929 2001//2001 -f 1920//1920 1921//1921 2002//2002 -f 1896//1896 1897//1897 2003//2003 -f 1880//1880 1881//1881 2004//2004 -f 1856//1856 1857//1857 2005//2005 -f 1959//1959 1958//1958 2006//2006 -f 1953//1953 1954//1954 1976//1976 -f 1946//1946 1977//1977 1948//1948 -f 1948//1948 1977//1977 1976//1976 -f 1948//1948 1976//1976 1949//1949 -f 1949//1949 1976//1976 1954//1954 -f 2007//2007 1945//1945 1941//1941 -f 2008//2008 1943//1943 1944//1944 -f 2009//2009 1938//1938 1934//1934 -f 1937//1937 1979//1979 1936//1936 -f 2010//2010 1978//1978 2011//2011 -f 2011//2011 1978//1978 1977//1977 -f 2011//2011 1977//1977 2007//2007 -f 2007//2007 1977//1977 1946//1946 -f 2007//2007 1946//1946 1945//1945 -f 2012//2012 2013//2013 2014//2014 -f 1915//1915 1911//1911 1998//1998 -f 1998//1998 1911//1911 1997//1997 -f 1998//1998 1997//1997 2015//2015 -f 2015//2015 1997//1997 2016//2016 -f 2015//2015 2016//2016 2017//2017 -f 2017//2017 2016//2016 2018//2018 -f 2017//2017 2018//2018 2019//2019 -f 1875//1875 1871//1871 1989//1989 -f 1989//1989 1871//1871 1988//1988 -f 1989//1989 1988//1988 2020//2020 -f 2020//2020 1988//1988 2021//2021 -f 2020//2020 2021//2021 2022//2022 -f 2022//2022 2021//2021 2023//2023 -f 2022//2022 2023//2023 2024//2024 -f 1955//1955 1951//1951 1980//1980 -f 1980//1980 1951//1951 2025//2025 -f 1980//1980 2025//2025 2026//2026 -f 2026//2026 2025//2025 2027//2027 -f 2026//2026 2027//2027 2028//2028 -f 2028//2028 2027//2027 2029//2029 -f 2028//2028 2029//2029 2030//2030 -f 2031//2031 2010//2010 2032//2032 -f 2032//2032 2010//2010 2011//2011 -f 2032//2032 2011//2011 2033//2033 -f 2033//2033 2011//2011 2007//2007 -f 2033//2033 2007//2007 2008//2008 -f 2008//2008 2007//2007 1941//1941 -f 2008//2008 1941//1941 1943//1943 -f 1921//1921 1916//1916 2002//2002 -f 2002//2002 1916//1916 1998//1998 -f 2002//2002 1998//1998 2034//2034 -f 2034//2034 1998//1998 2015//2015 -f 2034//2034 2015//2015 2035//2035 -f 2035//2035 2015//2015 2017//2017 -f 2035//2035 2017//2017 2036//2036 -f 2036//2036 2017//2017 2019//2019 -f 2036//2036 2019//2019 2037//2037 -f 1881//1881 1876//1876 2004//2004 -f 2004//2004 1876//1876 1989//1989 -f 2004//2004 1989//1989 2038//2038 -f 2038//2038 1989//1989 2020//2020 -f 2038//2038 2020//2020 2039//2039 -f 2039//2039 2020//2020 2022//2022 -f 2039//2039 2022//2022 2040//2040 -f 2040//2040 2022//2022 2024//2024 -f 2040//2040 2024//2024 2041//2041 -f 1958//1958 1956//1956 2006//2006 -f 2006//2006 1956//1956 1980//1980 -f 2006//2006 1980//1980 2042//2042 -f 2042//2042 1980//1980 2026//2026 -f 2042//2042 2026//2026 2043//2043 -f 2043//2043 2026//2026 2028//2028 -f 2043//2043 2028//2028 2044//2044 -f 2044//2044 2028//2028 2030//2030 -f 2044//2044 2030//2030 2045//2045 -f 2046//2046 2031//2031 2047//2047 -f 2047//2047 2031//2031 2032//2032 -f 2047//2047 2032//2032 2048//2048 -f 2048//2048 2032//2032 2033//2033 -f 2048//2048 2033//2033 2049//2049 -f 2049//2049 2033//2033 2008//2008 -f 2049//2049 2008//2008 2050//2050 -f 2050//2050 2008//2008 1944//1944 -f 2050//2050 1944//1944 1939//1939 -f 1918//1918 1920//1920 2051//2051 -f 2051//2051 1920//1920 2002//2002 -f 2051//2051 2002//2002 2052//2052 -f 2052//2052 2002//2002 2034//2034 -f 2052//2052 2034//2034 2053//2053 -f 2053//2053 2034//2034 2035//2035 -f 2053//2053 2035//2035 2054//2054 -f 2054//2054 2035//2035 2036//2036 -f 2054//2054 2036//2036 2055//2055 -f 2055//2055 2036//2036 2037//2037 -f 2055//2055 2037//2037 2056//2056 -f 1878//1878 1880//1880 2057//2057 -f 2057//2057 1880//1880 2004//2004 -f 2057//2057 2004//2004 2058//2058 -f 2058//2058 2004//2004 2038//2038 -f 2058//2058 2038//2038 2059//2059 -f 2059//2059 2038//2038 2039//2039 -f 2059//2059 2039//2039 2060//2060 -f 2060//2060 2039//2039 2040//2040 -f 2060//2060 2040//2040 2061//2061 -f 2061//2061 2040//2040 2041//2041 -f 2061//2061 2041//2041 2062//2062 -f 1960//1960 1959//1959 2063//2063 -f 2063//2063 1959//1959 2006//2006 -f 2063//2063 2006//2006 2064//2064 -f 2064//2064 2006//2006 2042//2042 -f 2064//2064 2042//2042 2065//2065 -f 2065//2065 2042//2042 2043//2043 -f 2065//2065 2043//2043 2066//2066 -f 2066//2066 2043//2043 2044//2044 -f 2066//2066 2044//2044 2067//2067 -f 2067//2067 2044//2044 2045//2045 -f 2067//2067 2045//2045 2068//2068 -f 2069//2069 2046//2046 2070//2070 -f 2070//2070 2046//2046 2047//2047 -f 2070//2070 2047//2047 2071//2071 -f 2071//2071 2047//2047 2048//2048 -f 2071//2071 2048//2048 2072//2072 -f 2072//2072 2048//2048 2049//2049 -f 2072//2072 2049//2049 2073//2073 -f 2073//2073 2049//2049 2050//2050 -f 2073//2073 2050//2050 2009//2009 -f 2009//2009 2050//2050 1939//1939 -f 2009//2009 1939//1939 1938//1938 -f 2074//2074 2075//2075 2076//2076 -f 1922//1922 1918//1918 1999//1999 -f 1999//1999 1918//1918 2051//2051 -f 1999//1999 2051//2051 2077//2077 -f 2077//2077 2051//2051 2052//2052 -f 2077//2077 2052//2052 2078//2078 -f 2078//2078 2052//2052 2053//2053 -f 2078//2078 2053//2053 2079//2079 -f 2079//2079 2053//2053 2054//2054 -f 2079//2079 2054//2054 2080//2080 -f 2080//2080 2054//2054 2055//2055 -f 2080//2080 2055//2055 2081//2081 -f 2081//2081 2055//2055 2056//2056 -f 2081//2081 2056//2056 2082//2082 -f 2083//2083 2084//2084 2085//2085 -f 1882//1882 1878//1878 1990//1990 -f 1990//1990 1878//1878 2057//2057 -f 1990//1990 2057//2057 2086//2086 -f 2086//2086 2057//2057 2058//2058 -f 2086//2086 2058//2058 2087//2087 -f 2087//2087 2058//2058 2059//2059 -f 2087//2087 2059//2059 2088//2088 -f 2088//2088 2059//2059 2060//2060 -f 2088//2088 2060//2060 2089//2089 -f 2089//2089 2060//2060 2061//2061 -f 2089//2089 2061//2061 2090//2090 -f 2090//2090 2061//2061 2062//2062 -f 2090//2090 2062//2062 2091//2091 -f 2092//2092 2093//2093 2094//2094 -f 1841//1841 1960//1960 1981//1981 -f 1981//1981 1960//1960 2063//2063 -f 1981//1981 2063//2063 2095//2095 -f 2095//2095 2063//2063 2064//2064 -f 2095//2095 2064//2064 2096//2096 -f 2096//2096 2064//2064 2065//2065 -f 2096//2096 2065//2065 2097//2097 -f 2097//2097 2065//2065 2066//2066 -f 2097//2097 2066//2066 2098//2098 -f 2098//2098 2066//2066 2067//2067 -f 2098//2098 2067//2067 2099//2099 -f 2099//2099 2067//2067 2068//2068 -f 2099//2099 2068//2068 2100//2100 -f 2101//2101 2102//2102 2103//2103 -f 2104//2104 2069//2069 2105//2105 -f 2105//2105 2069//2069 2070//2070 -f 2105//2105 2070//2070 2106//2106 -f 2106//2106 2070//2070 2071//2071 -f 2106//2106 2071//2071 2107//2107 -f 2107//2107 2071//2071 2072//2072 -f 2107//2107 2072//2072 2108//2108 -f 2108//2108 2072//2072 2073//2073 -f 2108//2108 2073//2073 2109//2109 -f 2109//2109 2073//2073 2009//2009 -f 2109//2109 2009//2009 2110//2110 -f 2110//2110 2009//2009 1934//1934 -f 2110//2110 1934//1934 1936//1936 -f 2111//2111 2075//2075 2112//2112 -f 2112//2112 2075//2075 2074//2074 -f 2112//2112 2074//2074 2113//2113 -f 2114//2114 2115//2115 2116//2116 -f 2116//2116 2115//2115 2113//2113 -f 2116//2116 2113//2113 2117//2117 -f 2117//2117 2113//2113 2074//2074 -f 2117//2117 2074//2074 2118//2118 -f 2118//2118 2074//2074 2076//2076 -f 2118//2118 2076//2076 2119//2119 -f 2120//2120 2121//2121 2122//2122 -f 2122//2122 2121//2121 2123//2123 -f 2122//2122 2123//2123 2124//2124 -f 2124//2124 2123//2123 2125//2125 -f 2124//2124 2125//2125 2126//2126 -f 2126//2126 2125//2125 2127//2127 -f 2126//2126 2127//2127 2128//2128 -f 2128//2128 2127//2127 2012//2012 -f 2128//2128 2012//2012 2129//2129 -f 2129//2129 2012//2012 2014//2014 -f 2129//2129 2014//2014 2130//2130 -f 1932//1932 1931//1931 2130//2130 -f 2130//2130 1931//1931 2001//2001 -f 2130//2130 2001//2001 2129//2129 -f 2129//2129 2001//2001 2131//2131 -f 2129//2129 2131//2131 2128//2128 -f 2128//2128 2131//2131 2132//2132 -f 2128//2128 2132//2132 2126//2126 -f 2126//2126 2132//2132 2133//2133 -f 2126//2126 2133//2133 2124//2124 -f 2124//2124 2133//2133 2134//2134 -f 2124//2124 2134//2134 2122//2122 -f 2122//2122 2134//2134 2135//2135 -f 2122//2122 2135//2135 2120//2120 -f 2120//2120 2135//2135 2136//2136 -f 2120//2120 2136//2136 2137//2137 -f 2137//2137 2136//2136 2138//2138 -f 1926//1926 1925//1925 2000//2000 -f 2000//2000 1925//1925 2139//2139 -f 2000//2000 2139//2139 2140//2140 -f 2140//2140 2139//2139 2141//2141 -f 2140//2140 2141//2141 2142//2142 -f 2142//2142 2141//2141 2143//2143 -f 2142//2142 2143//2143 2144//2144 -f 2144//2144 2143//2143 2145//2145 -f 2144//2144 2145//2145 2146//2146 -f 2146//2146 2145//2145 2147//2147 -f 2146//2146 2147//2147 2148//2148 -f 2148//2148 2147//2147 2149//2149 -f 2148//2148 2149//2149 2150//2150 -f 2150//2150 2149//2149 1975//1975 -f 2151//2151 2084//2084 2152//2152 -f 2152//2152 2084//2084 2083//2083 -f 2152//2152 2083//2083 2153//2153 -f 2154//2154 2155//2155 2156//2156 -f 2156//2156 2155//2155 2153//2153 -f 2156//2156 2153//2153 2157//2157 -f 2157//2157 2153//2153 2083//2083 -f 2157//2157 2083//2083 2158//2158 -f 2158//2158 2083//2083 2085//2085 -f 2158//2158 2085//2085 2159//2159 -f 1909//1909 1908//1908 1996//1996 -f 1996//1996 1908//1908 2160//2160 -f 1996//1996 2160//2160 2161//2161 -f 2161//2161 2160//2160 2162//2162 -f 2161//2161 2162//2162 2163//2163 -f 2163//2163 2162//2162 2164//2164 -f 2163//2163 2164//2164 2165//2165 -f 2165//2165 2164//2164 2166//2166 -f 2165//2165 2166//2166 2167//2167 -f 2167//2167 2166//2166 2168//2168 -f 2167//2167 2168//2168 2169//2169 -f 2169//2169 2168//2168 2170//2170 -f 2169//2169 2170//2170 2171//2171 -f 2171//2171 2170//2170 2172//2172 -f 1905//1905 1901//1901 1995//1995 -f 1995//1995 1901//1901 1994//1994 -f 1995//1995 1994//1994 2173//2173 -f 2173//2173 1994//1994 2174//2174 -f 2173//2173 2174//2174 2175//2175 -f 2175//2175 2174//2174 2176//2176 -f 2175//2175 2176//2176 2177//2177 -f 2177//2177 2176//2176 2178//2178 -f 2177//2177 2178//2178 2179//2179 -f 2179//2179 2178//2178 2180//2180 -f 2179//2179 2180//2180 2181//2181 -f 2181//2181 2180//2180 2182//2182 -f 2181//2181 2182//2182 2183//2183 -f 2183//2183 2182//2182 2184//2184 -f 2183//2183 2184//2184 2185//2185 -f 1903//1903 1904//1904 1994//1994 -f 1994//1994 1904//1904 2186//2186 -f 1994//1994 2186//2186 2174//2174 -f 2174//2174 2186//2186 2187//2187 -f 2174//2174 2187//2187 2176//2176 -f 2176//2176 2187//2187 2188//2188 -f 2176//2176 2188//2188 2178//2178 -f 2178//2178 2188//2188 2189//2189 -f 2178//2178 2189//2189 2180//2180 -f 2180//2180 2189//2189 2190//2190 -f 2180//2180 2190//2190 2182//2182 -f 2182//2182 2190//2190 2191//2191 -f 2182//2182 2191//2191 2184//2184 -f 2184//2184 2191//2191 2192//2192 -f 1904//1904 1899//1899 2186//2186 -f 2186//2186 1899//1899 1993//1993 -f 2186//2186 1993//1993 2187//2187 -f 2187//2187 1993//1993 2193//2193 -f 2187//2187 2193//2193 2188//2188 -f 2188//2188 2193//2193 2194//2194 -f 2188//2188 2194//2194 2189//2189 -f 2189//2189 2194//2194 2195//2195 -f 2189//2189 2195//2195 2190//2190 -f 2190//2190 2195//2195 2196//2196 -f 2190//2190 2196//2196 2191//2191 -f 2191//2191 2196//2196 2197//2197 -f 2191//2191 2197//2197 2192//2192 -f 2192//2192 2197//2197 2198//2198 -f 1898//1898 1894//1894 1993//1993 -f 1993//1993 1894//1894 2199//2199 -f 1993//1993 2199//2199 2193//2193 -f 2193//2193 2199//2199 2200//2200 -f 2193//2193 2200//2200 2194//2194 -f 2194//2194 2200//2200 2201//2201 -f 2194//2194 2201//2201 2195//2195 -f 2195//2195 2201//2201 2202//2202 -f 2195//2195 2202//2202 2196//2196 -f 2196//2196 2202//2202 2203//2203 -f 2196//2196 2203//2203 2197//2197 -f 2197//2197 2203//2203 2204//2204 -f 2197//2197 2204//2204 2198//2198 -f 2198//2198 2204//2204 2205//2205 -f 2198//2198 2205//2205 2206//2206 -f 2206//2206 2205//2205 2207//2207 -f 1897//1897 1892//1892 2003//2003 -f 2003//2003 1892//1892 2208//2208 -f 2003//2003 2208//2208 2209//2209 -f 2209//2209 2208//2208 2210//2210 -f 2209//2209 2210//2210 2211//2211 -f 2211//2211 2210//2210 2212//2212 -f 2211//2211 2212//2212 2213//2213 -f 2213//2213 2212//2212 2214//2214 -f 2213//2213 2214//2214 2215//2215 -f 2215//2215 2214//2214 2216//2216 -f 2215//2215 2216//2216 2217//2217 -f 2217//2217 2216//2216 2218//2218 -f 2217//2217 2218//2218 2219//2219 -f 2219//2219 2218//2218 2220//2220 -f 1892//1892 1891//1891 2208//2208 -f 2208//2208 1891//1891 1992//1992 -f 2208//2208 1992//1992 2210//2210 -f 2210//2210 1992//1992 2221//2221 -f 2210//2210 2221//2221 2212//2212 -f 2212//2212 2221//2221 2222//2222 -f 2212//2212 2222//2222 2214//2214 -f 2214//2214 2222//2222 2223//2223 -f 2214//2214 2223//2223 2216//2216 -f 2216//2216 2223//2223 2224//2224 -f 2216//2216 2224//2224 2218//2218 -f 2218//2218 2224//2224 2225//2225 -f 2218//2218 2225//2225 2220//2220 -f 2220//2220 2225//2225 2226//2226 -f 2220//2220 2226//2226 2227//2227 -f 2227//2227 2226//2226 2228//2228 -f 2229//2229 2093//2093 2230//2230 -f 2230//2230 2093//2093 2092//2092 -f 2230//2230 2092//2092 2231//2231 -f 2232//2232 2233//2233 2234//2234 -f 2234//2234 2233//2233 2231//2231 -f 2234//2234 2231//2231 2235//2235 -f 2235//2235 2231//2231 2092//2092 -f 2235//2235 2092//2092 2236//2236 -f 2236//2236 2092//2092 2094//2094 -f 2236//2236 2094//2094 2237//2237 -f 1869//1869 1868//1868 1987//1987 -f 1987//1987 1868//1868 2238//2238 -f 1987//1987 2238//2238 2239//2239 -f 2239//2239 2238//2238 2240//2240 -f 2239//2239 2240//2240 2241//2241 -f 2241//2241 2240//2240 2242//2242 -f 2241//2241 2242//2242 2243//2243 -f 2243//2243 2242//2242 2244//2244 -f 2243//2243 2244//2244 2245//2245 -f 2245//2245 2244//2244 2246//2246 -f 2245//2245 2246//2246 2247//2247 -f 2247//2247 2246//2246 2248//2248 -f 2247//2247 2248//2248 2249//2249 -f 2249//2249 2248//2248 2250//2250 -f 1865//1865 1861//1861 1986//1986 -f 1986//1986 1861//1861 1985//1985 -f 1986//1986 1985//1985 2251//2251 -f 2251//2251 1985//1985 2252//2252 -f 2251//2251 2252//2252 2253//2253 -f 2253//2253 2252//2252 2254//2254 -f 2253//2253 2254//2254 2255//2255 -f 2255//2255 2254//2254 2256//2256 -f 2255//2255 2256//2256 2257//2257 -f 2257//2257 2256//2256 2258//2258 -f 2257//2257 2258//2258 2259//2259 -f 2259//2259 2258//2258 2260//2260 -f 2259//2259 2260//2260 2261//2261 -f 2261//2261 2260//2260 2262//2262 -f 2261//2261 2262//2262 2263//2263 -f 1863//1863 1864//1864 1985//1985 -f 1985//1985 1864//1864 2264//2264 -f 1985//1985 2264//2264 2252//2252 -f 2252//2252 2264//2264 2265//2265 -f 2252//2252 2265//2265 2254//2254 -f 2254//2254 2265//2265 2266//2266 -f 2254//2254 2266//2266 2256//2256 -f 2256//2256 2266//2266 2267//2267 -f 2256//2256 2267//2267 2258//2258 -f 2258//2258 2267//2267 2268//2268 -f 2258//2258 2268//2268 2260//2260 -f 2260//2260 2268//2268 2269//2269 -f 2260//2260 2269//2269 2262//2262 -f 2262//2262 2269//2269 2270//2270 -f 1864//1864 1859//1859 2264//2264 -f 2264//2264 1859//1859 1984//1984 -f 2264//2264 1984//1984 2265//2265 -f 2265//2265 1984//1984 2271//2271 -f 2265//2265 2271//2271 2266//2266 -f 2266//2266 2271//2271 2272//2272 -f 2266//2266 2272//2272 2267//2267 -f 2267//2267 2272//2272 2273//2273 -f 2267//2267 2273//2273 2268//2268 -f 2268//2268 2273//2273 2274//2274 -f 2268//2268 2274//2274 2269//2269 -f 2269//2269 2274//2274 2275//2275 -f 2269//2269 2275//2275 2270//2270 -f 2270//2270 2275//2275 2276//2276 -f 1858//1858 1854//1854 1984//1984 -f 1984//1984 1854//1854 2277//2277 -f 1984//1984 2277//2277 2271//2271 -f 2271//2271 2277//2277 2278//2278 -f 2271//2271 2278//2278 2272//2272 -f 2272//2272 2278//2278 2279//2279 -f 2272//2272 2279//2279 2273//2273 -f 2273//2273 2279//2279 2280//2280 -f 2273//2273 2280//2280 2274//2274 -f 2274//2274 2280//2280 2281//2281 -f 2274//2274 2281//2281 2275//2275 -f 2275//2275 2281//2281 2282//2282 -f 2275//2275 2282//2282 2276//2276 -f 2276//2276 2282//2282 2283//2283 -f 2276//2276 2283//2283 2284//2284 -f 2284//2284 2283//2283 2285//2285 -f 1857//1857 1852//1852 2005//2005 -f 2005//2005 1852//1852 2286//2286 -f 2005//2005 2286//2286 2287//2287 -f 2287//2287 2286//2286 2288//2288 -f 2287//2287 2288//2288 2289//2289 -f 2289//2289 2288//2288 2290//2290 -f 2289//2289 2290//2290 2291//2291 -f 2291//2291 2290//2290 2292//2292 -f 2291//2291 2292//2292 2293//2293 -f 2293//2293 2292//2292 2294//2294 -f 2293//2293 2294//2294 2295//2295 -f 2295//2295 2294//2294 2296//2296 -f 2295//2295 2296//2296 2297//2297 -f 2297//2297 2296//2296 2298//2298 -f 1852//1852 1851//1851 2286//2286 -f 2286//2286 1851//1851 1983//1983 -f 2286//2286 1983//1983 2288//2288 -f 2288//2288 1983//1983 2299//2299 -f 2288//2288 2299//2299 2290//2290 -f 2290//2290 2299//2299 2300//2300 -f 2290//2290 2300//2300 2292//2292 -f 2292//2292 2300//2300 2301//2301 -f 2292//2292 2301//2301 2294//2294 -f 2294//2294 2301//2301 2302//2302 -f 2294//2294 2302//2302 2296//2296 -f 2296//2296 2302//2302 2303//2303 -f 2296//2296 2303//2303 2298//2298 -f 2298//2298 2303//2303 2304//2304 -f 2298//2298 2304//2304 2305//2305 -f 2305//2305 2304//2304 2306//2306 -f 2307//2307 2102//2102 2308//2308 -f 2308//2308 2102//2102 2101//2101 -f 2308//2308 2101//2101 2309//2309 -f 2310//2310 2311//2311 2312//2312 -f 2312//2312 2311//2311 2309//2309 -f 2312//2312 2309//2309 2313//2313 -f 2313//2313 2309//2309 2101//2101 -f 2313//2313 2101//2101 2314//2314 -f 2314//2314 2101//2101 2103//2103 -f 2314//2314 2103//2103 2315//2315 -f 2013//2013 2119//2119 2316//2316 -f 2316//2316 2119//2119 2076//2076 -f 2316//2316 2076//2076 2317//2317 -f 2317//2317 2076//2076 2075//2075 -f 2317//2317 2075//2075 2318//2318 -f 2318//2318 2075//2075 2111//2111 -f 2318//2318 2111//2111 2319//2319 -f 2319//2319 2111//2111 2320//2320 -f 2319//2319 2320//2320 2321//2321 -f 2115//2115 2322//2322 2113//2113 -f 2113//2113 2322//2322 2323//2323 -f 2113//2113 2323//2323 2112//2112 -f 2112//2112 2323//2323 2324//2324 -f 2112//2112 2324//2324 2111//2111 -f 2111//2111 2324//2324 2325//2325 -f 2111//2111 2325//2325 2320//2320 -f 2013//2013 2012//2012 2119//2119 -f 2119//2119 2012//2012 2127//2127 -f 2119//2119 2127//2127 2118//2118 -f 2118//2118 2127//2127 2125//2125 -f 2118//2118 2125//2125 2117//2117 -f 2117//2117 2125//2125 2123//2123 -f 2117//2117 2123//2123 2116//2116 -f 2116//2116 2123//2123 2121//2121 -f 2116//2116 2121//2121 2114//2114 -f 2137//2137 2326//2326 2120//2120 -f 2120//2120 2326//2326 2327//2327 -f 2120//2120 2327//2327 2121//2121 -f 2121//2121 2327//2327 2328//2328 -f 2121//2121 2328//2328 2114//2114 -f 2329//2329 2138//2138 2150//2150 -f 2150//2150 2138//2138 2136//2136 -f 2150//2150 2136//2136 2148//2148 -f 2148//2148 2136//2136 2135//2135 -f 2148//2148 2135//2135 2146//2146 -f 2146//2146 2135//2135 2134//2134 -f 2146//2146 2134//2134 2144//2144 -f 2144//2144 2134//2134 2133//2133 -f 2144//2144 2133//2133 2142//2142 -f 2142//2142 2133//2133 2132//2132 -f 2142//2142 2132//2132 2140//2140 -f 2140//2140 2132//2132 2131//2131 -f 2140//2140 2131//2131 2000//2000 -f 2000//2000 2131//2131 2001//2001 -f 2000//2000 2001//2001 1928//1928 -f 1928//1928 2001//2001 1929//1929 -f 1975//1975 1974//1974 2150//2150 -f 2150//2150 1974//1974 2330//2330 -f 2150//2150 2330//2330 2329//2329 -f 2331//2331 1973//1973 2082//2082 -f 2082//2082 1973//1973 1975//1975 -f 2082//2082 1975//1975 2081//2081 -f 2081//2081 1975//1975 2149//2149 -f 2081//2081 2149//2149 2080//2080 -f 2080//2080 2149//2149 2147//2147 -f 2080//2080 2147//2147 2079//2079 -f 2079//2079 2147//2147 2145//2145 -f 2079//2079 2145//2145 2078//2078 -f 2078//2078 2145//2145 2143//2143 -f 2078//2078 2143//2143 2077//2077 -f 2077//2077 2143//2143 2141//2141 -f 2077//2077 2141//2141 1999//1999 -f 1999//1999 2141//2141 2139//2139 -f 1999//1999 2139//2139 1923//1923 -f 1923//1923 2139//2139 1925//1925 -f 2018//2018 2159//2159 2019//2019 -f 2019//2019 2159//2159 2085//2085 -f 2019//2019 2085//2085 2037//2037 -f 2037//2037 2085//2085 2084//2084 -f 2037//2037 2084//2084 2056//2056 -f 2056//2056 2084//2084 2151//2151 -f 2056//2056 2151//2151 2082//2082 -f 2082//2082 2151//2151 2332//2332 -f 2082//2082 2332//2332 2331//2331 -f 2155//2155 2333//2333 2153//2153 -f 2153//2153 2333//2333 2334//2334 -f 2153//2153 2334//2334 2152//2152 -f 2152//2152 2334//2334 2335//2335 -f 2152//2152 2335//2335 2151//2151 -f 2151//2151 2335//2335 2336//2336 -f 2151//2151 2336//2336 2332//2332 -f 1913//1913 1914//1914 1997//1997 -f 1997//1997 1914//1914 1996//1996 -f 1997//1997 1996//1996 2016//2016 -f 2016//2016 1996//1996 2161//2161 -f 2016//2016 2161//2161 2018//2018 -f 2018//2018 2161//2161 2163//2163 -f 2018//2018 2163//2163 2159//2159 -f 2159//2159 2163//2163 2165//2165 -f 2159//2159 2165//2165 2158//2158 -f 2158//2158 2165//2165 2167//2167 -f 2158//2158 2167//2167 2157//2157 -f 2157//2157 2167//2167 2169//2169 -f 2157//2157 2169//2169 2156//2156 -f 2156//2156 2169//2169 2171//2171 -f 2156//2156 2171//2171 2154//2154 -f 2337//2337 2338//2338 2172//2172 -f 2172//2172 2338//2338 2339//2339 -f 2172//2172 2339//2339 2171//2171 -f 2171//2171 2339//2339 2340//2340 -f 2171//2171 2340//2340 2154//2154 -f 1908//1908 1906//1906 2160//2160 -f 2160//2160 1906//1906 1995//1995 -f 2160//2160 1995//1995 2162//2162 -f 2162//2162 1995//1995 2173//2173 -f 2162//2162 2173//2173 2164//2164 -f 2164//2164 2173//2173 2175//2175 -f 2164//2164 2175//2175 2166//2166 -f 2166//2166 2175//2175 2177//2177 -f 2166//2166 2177//2177 2168//2168 -f 2168//2168 2177//2177 2179//2179 -f 2168//2168 2179//2179 2170//2170 -f 2170//2170 2179//2179 2181//2181 -f 2170//2170 2181//2181 2172//2172 -f 2172//2172 2181//2181 2183//2183 -f 2172//2172 2183//2183 2337//2337 -f 2337//2337 2183//2183 2185//2185 -f 2206//2206 2341//2341 2198//2198 -f 2198//2198 2341//2341 2342//2342 -f 2198//2198 2342//2342 2192//2192 -f 2192//2192 2342//2342 2343//2343 -f 2192//2192 2343//2343 2184//2184 -f 2184//2184 2343//2343 2344//2344 -f 2184//2184 2344//2344 2185//2185 -f 1894//1894 1896//1896 2199//2199 -f 2199//2199 1896//1896 2003//2003 -f 2199//2199 2003//2003 2200//2200 -f 2200//2200 2003//2003 2209//2209 -f 2200//2200 2209//2209 2201//2201 -f 2201//2201 2209//2209 2211//2211 -f 2201//2201 2211//2211 2202//2202 -f 2202//2202 2211//2211 2213//2213 -f 2202//2202 2213//2213 2203//2203 -f 2203//2203 2213//2213 2215//2215 -f 2203//2203 2215//2215 2204//2204 -f 2204//2204 2215//2215 2217//2217 -f 2204//2204 2217//2217 2205//2205 -f 2205//2205 2217//2217 2219//2219 -f 2205//2205 2219//2219 2207//2207 -f 2227//2227 2345//2345 2220//2220 -f 2220//2220 2345//2345 2346//2346 -f 2220//2220 2346//2346 2219//2219 -f 2219//2219 2346//2346 2347//2347 -f 2219//2219 2347//2347 2207//2207 -f 1971//1971 2228//2228 1972//1972 -f 1972//1972 2228//2228 2226//2226 -f 1972//1972 2226//2226 2348//2348 -f 2348//2348 2226//2226 2225//2225 -f 2348//2348 2225//2225 2349//2349 -f 2349//2349 2225//2225 2224//2224 -f 2349//2349 2224//2224 2350//2350 -f 2350//2350 2224//2224 2223//2223 -f 2350//2350 2223//2223 2351//2351 -f 2351//2351 2223//2223 2222//2222 -f 2351//2351 2222//2222 2352//2352 -f 2352//2352 2222//2222 2221//2221 -f 2352//2352 2221//2221 1991//1991 -f 1991//1991 2221//2221 1992//1992 -f 1991//1991 1992//1992 1888//1888 -f 1888//1888 1992//1992 1889//1889 -f 1968//1968 1970//1970 1969//1969 -f 1969//1969 1970//1970 1972//1972 -f 1969//1969 1972//1972 2353//2353 -f 2353//2353 1972//1972 2348//2348 -f 2353//2353 2348//2348 2354//2354 -f 2354//2354 2348//2348 2349//2349 -f 2354//2354 2349//2349 2355//2355 -f 2355//2355 2349//2349 2350//2350 -f 2355//2355 2350//2350 2356//2356 -f 2356//2356 2350//2350 2351//2351 -f 2356//2356 2351//2351 2357//2357 -f 2357//2357 2351//2351 2352//2352 -f 2357//2357 2352//2352 2358//2358 -f 2358//2358 2352//2352 1991//1991 -f 2358//2358 1991//1991 1885//1885 -f 1885//1885 1991//1991 1886//1886 -f 2359//2359 1967//1967 2091//2091 -f 2091//2091 1967//1967 1969//1969 -f 2091//2091 1969//1969 2090//2090 -f 2090//2090 1969//1969 2353//2353 -f 2090//2090 2353//2353 2089//2089 -f 2089//2089 2353//2353 2354//2354 -f 2089//2089 2354//2354 2088//2088 -f 2088//2088 2354//2354 2355//2355 -f 2088//2088 2355//2355 2087//2087 -f 2087//2087 2355//2355 2356//2356 -f 2087//2087 2356//2356 2086//2086 -f 2086//2086 2356//2356 2357//2357 -f 2086//2086 2357//2357 1990//1990 -f 1990//1990 2357//2357 2358//2358 -f 1990//1990 2358//2358 1883//1883 -f 1883//1883 2358//2358 1885//1885 -f 2023//2023 2237//2237 2024//2024 -f 2024//2024 2237//2237 2094//2094 -f 2024//2024 2094//2094 2041//2041 -f 2041//2041 2094//2094 2093//2093 -f 2041//2041 2093//2093 2062//2062 -f 2062//2062 2093//2093 2229//2229 -f 2062//2062 2229//2229 2091//2091 -f 2091//2091 2229//2229 2360//2360 -f 2091//2091 2360//2360 2359//2359 -f 2233//2233 2361//2361 2231//2231 -f 2231//2231 2361//2361 2362//2362 -f 2231//2231 2362//2362 2230//2230 -f 2230//2230 2362//2362 2363//2363 -f 2230//2230 2363//2363 2229//2229 -f 2229//2229 2363//2363 2364//2364 -f 2229//2229 2364//2364 2360//2360 -f 1873//1873 1874//1874 1988//1988 -f 1988//1988 1874//1874 1987//1987 -f 1988//1988 1987//1987 2021//2021 -f 2021//2021 1987//1987 2239//2239 -f 2021//2021 2239//2239 2023//2023 -f 2023//2023 2239//2239 2241//2241 -f 2023//2023 2241//2241 2237//2237 -f 2237//2237 2241//2241 2243//2243 -f 2237//2237 2243//2243 2236//2236 -f 2236//2236 2243//2243 2245//2245 -f 2236//2236 2245//2245 2235//2235 -f 2235//2235 2245//2245 2247//2247 -f 2235//2235 2247//2247 2234//2234 -f 2234//2234 2247//2247 2249//2249 -f 2234//2234 2249//2249 2232//2232 -f 2365//2365 2366//2366 2250//2250 -f 2250//2250 2366//2366 2367//2367 -f 2250//2250 2367//2367 2249//2249 -f 2249//2249 2367//2367 2368//2368 -f 2249//2249 2368//2368 2232//2232 -f 1868//1868 1866//1866 2238//2238 -f 2238//2238 1866//1866 1986//1986 -f 2238//2238 1986//1986 2240//2240 -f 2240//2240 1986//1986 2251//2251 -f 2240//2240 2251//2251 2242//2242 -f 2242//2242 2251//2251 2253//2253 -f 2242//2242 2253//2253 2244//2244 -f 2244//2244 2253//2253 2255//2255 -f 2244//2244 2255//2255 2246//2246 -f 2246//2246 2255//2255 2257//2257 -f 2246//2246 2257//2257 2248//2248 -f 2248//2248 2257//2257 2259//2259 -f 2248//2248 2259//2259 2250//2250 -f 2250//2250 2259//2259 2261//2261 -f 2250//2250 2261//2261 2365//2365 -f 2365//2365 2261//2261 2263//2263 -f 2284//2284 2369//2369 2276//2276 -f 2276//2276 2369//2369 2370//2370 -f 2276//2276 2370//2370 2270//2270 -f 2270//2270 2370//2370 2371//2371 -f 2270//2270 2371//2371 2262//2262 -f 2262//2262 2371//2371 2372//2372 -f 2262//2262 2372//2372 2263//2263 -f 1854//1854 1856//1856 2277//2277 -f 2277//2277 1856//1856 2005//2005 -f 2277//2277 2005//2005 2278//2278 -f 2278//2278 2005//2005 2287//2287 -f 2278//2278 2287//2287 2279//2279 -f 2279//2279 2287//2287 2289//2289 -f 2279//2279 2289//2289 2280//2280 -f 2280//2280 2289//2289 2291//2291 -f 2280//2280 2291//2291 2281//2281 -f 2281//2281 2291//2291 2293//2293 -f 2281//2281 2293//2293 2282//2282 -f 2282//2282 2293//2293 2295//2295 -f 2282//2282 2295//2295 2283//2283 -f 2283//2283 2295//2295 2297//2297 -f 2283//2283 2297//2297 2285//2285 -f 2305//2305 2373//2373 2298//2298 -f 2298//2298 2373//2373 2374//2374 -f 2298//2298 2374//2374 2297//2297 -f 2297//2297 2374//2374 2375//2375 -f 2297//2297 2375//2375 2285//2285 -f 1965//1965 2306//2306 1966//1966 -f 1966//1966 2306//2306 2304//2304 -f 1966//1966 2304//2304 2376//2376 -f 2376//2376 2304//2304 2303//2303 -f 2376//2376 2303//2303 2377//2377 -f 2377//2377 2303//2303 2302//2302 -f 2377//2377 2302//2302 2378//2378 -f 2378//2378 2302//2302 2301//2301 -f 2378//2378 2301//2301 2379//2379 -f 2379//2379 2301//2301 2300//2300 -f 2379//2379 2300//2300 2380//2380 -f 2380//2380 2300//2300 2299//2299 -f 2380//2380 2299//2299 1982//1982 -f 1982//1982 2299//2299 1983//1983 -f 1982//1982 1983//1983 1848//1848 -f 1848//1848 1983//1983 1849//1849 -f 1962//1962 1964//1964 1963//1963 -f 1963//1963 1964//1964 1966//1966 -f 1963//1963 1966//1966 2381//2381 -f 2381//2381 1966//1966 2376//2376 -f 2381//2381 2376//2376 2382//2382 -f 2382//2382 2376//2376 2377//2377 -f 2382//2382 2377//2377 2383//2383 -f 2383//2383 2377//2377 2378//2378 -f 2383//2383 2378//2378 2384//2384 -f 2384//2384 2378//2378 2379//2379 -f 2384//2384 2379//2379 2385//2385 -f 2385//2385 2379//2379 2380//2380 -f 2385//2385 2380//2380 2386//2386 -f 2386//2386 2380//2380 1982//1982 -f 2386//2386 1982//1982 1845//1845 -f 1845//1845 1982//1982 1846//1846 -f 2387//2387 1961//1961 2100//2100 -f 2100//2100 1961//1961 1963//1963 -f 2100//2100 1963//1963 2099//2099 -f 2099//2099 1963//1963 2381//2381 -f 2099//2099 2381//2381 2098//2098 -f 2098//2098 2381//2381 2382//2382 -f 2098//2098 2382//2382 2097//2097 -f 2097//2097 2382//2382 2383//2383 -f 2097//2097 2383//2383 2096//2096 -f 2096//2096 2383//2383 2384//2384 -f 2096//2096 2384//2384 2095//2095 -f 2095//2095 2384//2384 2385//2385 -f 2095//2095 2385//2385 1981//1981 -f 1981//1981 2385//2385 2386//2386 -f 1981//1981 2386//2386 1842//1842 -f 1842//1842 2386//2386 1845//1845 -f 2029//2029 2315//2315 2030//2030 -f 2030//2030 2315//2315 2103//2103 -f 2030//2030 2103//2103 2045//2045 -f 2045//2045 2103//2103 2102//2102 -f 2045//2045 2102//2102 2068//2068 -f 2068//2068 2102//2102 2307//2307 -f 2068//2068 2307//2307 2100//2100 -f 2100//2100 2307//2307 2388//2388 -f 2100//2100 2388//2388 2387//2387 -f 2311//2311 2389//2389 2309//2309 -f 2309//2309 2389//2389 2390//2390 -f 2309//2309 2390//2390 2308//2308 -f 2308//2308 2390//2390 2391//2391 -f 2308//2308 2391//2391 2307//2307 -f 2307//2307 2391//2391 2392//2392 -f 2307//2307 2392//2392 2388//2388 -f 2393//2393 2310//2310 2104//2104 -f 2104//2104 2310//2310 2312//2312 -f 2104//2104 2312//2312 2069//2069 -f 2069//2069 2312//2312 2313//2313 -f 2069//2069 2313//2313 2046//2046 -f 2046//2046 2313//2313 2314//2314 -f 2046//2046 2314//2314 2031//2031 -f 2031//2031 2314//2314 2315//2315 -f 2031//2031 2315//2315 2010//2010 -f 2010//2010 2315//2315 2029//2029 -f 2010//2010 2029//2029 1978//1978 -f 1978//1978 2029//2029 2027//2027 -f 1978//1978 2027//2027 1976//1976 -f 1976//1976 2027//2027 2025//2025 -f 1976//1976 2025//2025 1953//1953 -f 1953//1953 2025//2025 1951//1951 -f 2394//2394 2395//2395 2396//2396 -f 1936//1936 1979//1979 2110//2110 -f 2110//2110 1979//1979 2397//2397 -f 2110//2110 2397//2397 2109//2109 -f 2109//2109 2397//2397 2398//2398 -f 2109//2109 2398//2398 2108//2108 -f 2108//2108 2398//2398 2399//2399 -f 2108//2108 2399//2399 2107//2107 -f 2107//2107 2399//2399 2400//2400 -f 2107//2107 2400//2400 2106//2106 -f 2106//2106 2400//2400 2401//2401 -f 2106//2106 2401//2401 2105//2105 -f 2105//2105 2401//2401 2394//2394 -f 2105//2105 2394//2394 2104//2104 -f 2104//2104 2394//2394 2396//2396 -f 2104//2104 2396//2396 2393//2393 -f 1932//1932 2130//2130 1979//1979 -f 1979//1979 2130//2130 2014//2014 -f 1979//1979 2014//2014 2397//2397 -f 2397//2397 2014//2014 2013//2013 -f 2397//2397 2013//2013 2398//2398 -f 2398//2398 2013//2013 2316//2316 -f 2398//2398 2316//2316 2399//2399 -f 2399//2399 2316//2316 2317//2317 -f 2399//2399 2317//2317 2400//2400 -f 2400//2400 2317//2317 2318//2318 -f 2400//2400 2318//2318 2401//2401 -f 2401//2401 2318//2318 2319//2319 -f 2401//2401 2319//2319 2394//2394 -f 2394//2394 2319//2319 2321//2321 -f 2394//2394 2321//2321 2395//2395 -f 2370//2370 2369//2369 2402//2402 -f 2402//2402 2369//2369 2284//2284 -f 2402//2402 2284//2284 2403//2403 -f 2370//2370 2402//2402 2371//2371 -f 2371//2371 2402//2402 2404//2404 -f 2371//2371 2404//2404 2372//2372 -f 2372//2372 2404//2404 2263//2263 -f 2263//2263 2404//2404 2405//2405 -f 2263//2263 2405//2405 2365//2365 -f 2365//2365 2405//2405 2366//2366 -f 2366//2366 2405//2405 2406//2406 -f 2366//2366 2406//2406 2367//2367 -f 2367//2367 2406//2406 2368//2368 -f 2368//2368 2406//2406 2407//2407 -f 2368//2368 2407//2407 2232//2232 -f 2408//2408 2361//2361 2407//2407 -f 2407//2407 2361//2361 2233//2233 -f 2407//2407 2233//2233 2232//2232 -f 2409//2409 2363//2363 2408//2408 -f 2408//2408 2363//2363 2362//2362 -f 2408//2408 2362//2362 2361//2361 -f 1967//1967 2359//2359 2410//2410 -f 2410//2410 2359//2359 2360//2360 -f 2410//2410 2360//2360 2409//2409 -f 2409//2409 2360//2360 2364//2364 -f 2409//2409 2364//2364 2363//2363 -f 1967//1967 2410//2410 1968//1968 -f 1968//1968 2410//2410 2411//2411 -f 1968//1968 2411//2411 1970//1970 -f 1970//1970 2411//2411 1971//1971 -f 1971//1971 2411//2411 2412//2412 -f 1971//1971 2412//2412 2228//2228 -f 2413//2413 2345//2345 2412//2412 -f 2412//2412 2345//2345 2227//2227 -f 2412//2412 2227//2227 2228//2228 -f 2414//2414 2347//2347 2413//2413 -f 2413//2413 2347//2347 2346//2346 -f 2413//2413 2346//2346 2345//2345 -f 2342//2342 2341//2341 2415//2415 -f 2415//2415 2341//2341 2206//2206 -f 2415//2415 2206//2206 2414//2414 -f 2414//2414 2206//2206 2207//2207 -f 2414//2414 2207//2207 2347//2347 -f 2342//2342 2415//2415 2343//2343 -f 2343//2343 2415//2415 2416//2416 -f 2343//2343 2416//2416 2344//2344 -f 2344//2344 2416//2416 2185//2185 -f 2185//2185 2416//2416 2417//2417 -f 2185//2185 2417//2417 2337//2337 -f 2337//2337 2417//2417 2338//2338 -f 2338//2338 2417//2417 2418//2418 -f 2338//2338 2418//2418 2339//2339 -f 2339//2339 2418//2418 2340//2340 -f 2340//2340 2418//2418 2419//2419 -f 2340//2340 2419//2419 2154//2154 -f 2420//2420 2333//2333 2419//2419 -f 2419//2419 2333//2333 2155//2155 -f 2419//2419 2155//2155 2154//2154 -f 2421//2421 2335//2335 2420//2420 -f 2420//2420 2335//2335 2334//2334 -f 2420//2420 2334//2334 2333//2333 -f 1973//1973 2331//2331 2422//2422 -f 2422//2422 2331//2331 2332//2332 -f 2422//2422 2332//2332 2421//2421 -f 2421//2421 2332//2332 2336//2336 -f 2421//2421 2336//2336 2335//2335 -f 1973//1973 2422//2422 1974//1974 -f 1974//1974 2422//2422 2423//2423 -f 1974//1974 2423//2423 2330//2330 -f 2330//2330 2423//2423 2329//2329 -f 2329//2329 2423//2423 2424//2424 -f 2329//2329 2424//2424 2138//2138 -f 2425//2425 2326//2326 2424//2424 -f 2424//2424 2326//2326 2137//2137 -f 2424//2424 2137//2137 2138//2138 -f 2426//2426 2328//2328 2425//2425 -f 2425//2425 2328//2328 2327//2327 -f 2425//2425 2327//2327 2326//2326 -f 2323//2323 2322//2322 2427//2427 -f 2427//2427 2322//2322 2115//2115 -f 2427//2427 2115//2115 2426//2426 -f 2426//2426 2115//2115 2114//2114 -f 2426//2426 2114//2114 2328//2328 -f 2323//2323 2427//2427 2324//2324 -f 2324//2324 2427//2427 2428//2428 -f 2324//2324 2428//2428 2325//2325 -f 2325//2325 2428//2428 2320//2320 -f 2320//2320 2428//2428 2429//2429 -f 2320//2320 2429//2429 2321//2321 -f 2321//2321 2429//2429 2395//2395 -f 2395//2395 2429//2429 2430//2430 -f 2395//2395 2430//2430 2396//2396 -f 2396//2396 2430//2430 2393//2393 -f 2393//2393 2430//2430 2431//2431 -f 2393//2393 2431//2431 2310//2310 -f 2432//2432 2389//2389 2431//2431 -f 2431//2431 2389//2389 2311//2311 -f 2431//2431 2311//2311 2310//2310 -f 2433//2433 2391//2391 2432//2432 -f 2432//2432 2391//2391 2390//2390 -f 2432//2432 2390//2390 2389//2389 -f 1961//1961 2387//2387 2434//2434 -f 2434//2434 2387//2387 2388//2388 -f 2434//2434 2388//2388 2433//2433 -f 2433//2433 2388//2388 2392//2392 -f 2433//2433 2392//2392 2391//2391 -f 1961//1961 2434//2434 1962//1962 -f 1962//1962 2434//2434 2435//2435 -f 1962//1962 2435//2435 1964//1964 -f 1964//1964 2435//2435 1965//1965 -f 1965//1965 2435//2435 2436//2436 -f 1965//1965 2436//2436 2306//2306 -f 2437//2437 2373//2373 2436//2436 -f 2436//2436 2373//2373 2305//2305 -f 2436//2436 2305//2305 2306//2306 -f 2284//2284 2285//2285 2403//2403 -f 2403//2403 2285//2285 2375//2375 -f 2403//2403 2375//2375 2437//2437 -f 2437//2437 2375//2375 2374//2374 -f 2437//2437 2374//2374 2373//2373 -f 2414//2414 2438//2438 2415//2415 -f 2415//2415 2438//2438 2439//2439 -f 2415//2415 2439//2439 2416//2416 -f 2416//2416 2439//2439 2440//2440 -f 2416//2416 2440//2440 2417//2417 -f 2417//2417 2440//2440 2441//2441 -f 2417//2417 2441//2441 2418//2418 -f 2418//2418 2441//2441 2442//2442 -f 2418//2418 2442//2442 2419//2419 -f 2419//2419 2442//2442 2443//2443 -f 2419//2419 2443//2443 2420//2420 -f 2426//2426 2444//2444 2427//2427 -f 2427//2427 2444//2444 2445//2445 -f 2427//2427 2445//2445 2428//2428 -f 2428//2428 2445//2445 2446//2446 -f 2428//2428 2446//2446 2429//2429 -f 2429//2429 2446//2446 2447//2447 -f 2429//2429 2447//2447 2430//2430 -f 2430//2430 2447//2447 2448//2448 -f 2430//2430 2448//2448 2431//2431 -f 2431//2431 2448//2448 2449//2449 -f 2431//2431 2449//2449 2432//2432 -f 2408//2408 2450//2450 2409//2409 -f 2409//2409 2450//2450 2451//2451 -f 2409//2409 2451//2451 2410//2410 -f 2410//2410 2451//2451 2452//2452 -f 2410//2410 2452//2452 2411//2411 -f 2411//2411 2452//2452 2453//2453 -f 2411//2411 2453//2453 2412//2412 -f 2412//2412 2453//2453 2454//2454 -f 2412//2412 2454//2454 2413//2413 -f 2413//2413 2454//2454 2455//2455 -f 2413//2413 2455//2455 2414//2414 -f 2414//2414 2455//2455 2456//2456 -f 2414//2414 2456//2456 2438//2438 -f 2443//2443 2457//2457 2420//2420 -f 2420//2420 2457//2457 2458//2458 -f 2420//2420 2458//2458 2421//2421 -f 2421//2421 2458//2458 2459//2459 -f 2421//2421 2459//2459 2422//2422 -f 2422//2422 2459//2459 2460//2460 -f 2422//2422 2460//2460 2423//2423 -f 2423//2423 2460//2460 2461//2461 -f 2423//2423 2461//2461 2424//2424 -f 2424//2424 2461//2461 2462//2462 -f 2424//2424 2462//2462 2425//2425 -f 2425//2425 2462//2462 2463//2463 -f 2425//2425 2463//2463 2426//2426 -f 2426//2426 2463//2463 2464//2464 -f 2426//2426 2464//2464 2444//2444 -f 2449//2449 2465//2465 2432//2432 -f 2432//2432 2465//2465 2466//2466 -f 2432//2432 2466//2466 2433//2433 -f 2433//2433 2466//2466 2467//2467 -f 2433//2433 2467//2467 2434//2434 -f 2434//2434 2467//2467 2468//2468 -f 2434//2434 2468//2468 2435//2435 -f 2435//2435 2468//2468 2469//2469 -f 2435//2435 2469//2469 2436//2436 -f 2436//2436 2469//2469 2470//2470 -f 2436//2436 2470//2470 2437//2437 -f 2437//2437 2470//2470 2471//2471 -f 2437//2437 2471//2471 2403//2403 -f 2403//2403 2471//2471 2472//2472 -f 2472//2472 2473//2473 2403//2403 -f 2403//2403 2473//2473 2474//2474 -f 2403//2403 2474//2474 2402//2402 -f 2402//2402 2474//2474 2475//2475 -f 2402//2402 2475//2475 2404//2404 -f 2404//2404 2475//2475 2476//2476 -f 2404//2404 2476//2476 2405//2405 -f 2405//2405 2476//2476 2477//2477 -f 2405//2405 2477//2477 2406//2406 -f 2406//2406 2477//2477 2478//2478 -f 2406//2406 2478//2478 2407//2407 -f 2407//2407 2478//2478 2479//2479 -f 2407//2407 2479//2479 2408//2408 -f 2408//2408 2479//2479 2480//2480 -f 2408//2408 2480//2480 2450//2450 -f 2481//2481 2482//2482 2483//2483 -f 2484//2484 2485//2485 2486//2486 -f 2487//2487 2488//2488 2489//2489 -f 2490//2490 2491//2491 2492//2492 -f 2493//2493 2494//2494 2495//2495 -f 2496//2496 2497//2497 2498//2498 -f 2499//2499 2500//2500 2501//2501 -f 2502//2502 2503//2503 2504//2504 -f 2505//2505 2506//2506 2507//2507 -f 2508//2508 2509//2509 2510//2510 -f 2511//2511 2512//2512 2513//2513 -f 2514//2514 2515//2515 2516//2516 -f 2473//2473 2472//2472 2517//2517 -f 2445//2445 2518//2518 2519//2519 -f 2445//2445 2519//2519 2446//2446 -f 2446//2446 2519//2519 2520//2520 -f 2446//2446 2520//2520 2447//2447 -f 2447//2447 2520//2520 2521//2521 -f 2447//2447 2521//2521 2448//2448 -f 2448//2448 2521//2521 2522//2522 -f 2448//2448 2522//2522 2449//2449 -f 2518//2518 2523//2523 2524//2524 -f 2518//2518 2524//2524 2519//2519 -f 2519//2519 2524//2524 2525//2525 -f 2519//2519 2525//2525 2520//2520 -f 2520//2520 2525//2525 2526//2526 -f 2520//2520 2526//2526 2521//2521 -f 2521//2521 2526//2526 2527//2527 -f 2521//2521 2527//2527 2522//2522 -f 2523//2523 2528//2528 2529//2529 -f 2463//2463 2462//2462 2530//2530 -f 2530//2530 2462//2462 2531//2531 -f 2530//2530 2531//2531 2532//2532 -f 2532//2532 2531//2531 2533//2533 -f 2532//2532 2533//2533 2534//2534 -f 2534//2534 2533//2533 2513//2513 -f 2460//2460 2459//2459 2535//2535 -f 2535//2535 2459//2459 2536//2536 -f 2535//2535 2536//2536 2537//2537 -f 2537//2537 2536//2536 2538//2538 -f 2537//2537 2538//2538 2539//2539 -f 2539//2539 2538//2538 2510//2510 -f 2457//2457 2443//2443 2540//2540 -f 2540//2540 2443//2443 2541//2541 -f 2540//2540 2541//2541 2542//2542 -f 2542//2542 2541//2541 2543//2543 -f 2542//2542 2543//2543 2544//2544 -f 2544//2544 2543//2543 2507//2507 -f 2441//2441 2440//2440 2545//2545 -f 2545//2545 2440//2440 2546//2546 -f 2545//2545 2546//2546 2547//2547 -f 2547//2547 2546//2546 2548//2548 -f 2547//2547 2548//2548 2549//2549 -f 2549//2549 2548//2548 2504//2504 -f 2438//2438 2456//2456 2550//2550 -f 2550//2550 2456//2456 2551//2551 -f 2550//2550 2551//2551 2552//2552 -f 2552//2552 2551//2551 2553//2553 -f 2552//2552 2553//2553 2554//2554 -f 2554//2554 2553//2553 2555//2555 -f 2453//2453 2452//2452 2556//2556 -f 2556//2556 2452//2452 2557//2557 -f 2556//2556 2557//2557 2558//2558 -f 2558//2558 2557//2557 2559//2559 -f 2558//2558 2559//2559 2560//2560 -f 2560//2560 2559//2559 2501//2501 -f 2450//2450 2480//2480 2561//2561 -f 2561//2561 2480//2480 2562//2562 -f 2561//2561 2562//2562 2563//2563 -f 2563//2563 2562//2562 2564//2564 -f 2563//2563 2564//2564 2565//2565 -f 2565//2565 2564//2564 2498//2498 -f 2478//2478 2477//2477 2566//2566 -f 2566//2566 2477//2477 2567//2567 -f 2566//2566 2567//2567 2568//2568 -f 2568//2568 2567//2567 2569//2569 -f 2568//2568 2569//2569 2570//2570 -f 2570//2570 2569//2569 2495//2495 -f 2475//2475 2474//2474 2571//2571 -f 2571//2571 2474//2474 2572//2572 -f 2571//2571 2572//2572 2573//2573 -f 2573//2573 2572//2572 2574//2574 -f 2573//2573 2574//2574 2575//2575 -f 2575//2575 2574//2574 2492//2492 -f 2470//2470 2469//2469 2576//2576 -f 2576//2576 2469//2469 2577//2577 -f 2576//2576 2577//2577 2578//2578 -f 2578//2578 2577//2577 2579//2579 -f 2578//2578 2579//2579 2580//2580 -f 2580//2580 2579//2579 2486//2486 -f 2467//2467 2466//2466 2581//2581 -f 2581//2581 2466//2466 2582//2582 -f 2581//2581 2582//2582 2583//2583 -f 2583//2583 2582//2582 2584//2584 -f 2583//2583 2584//2584 2585//2585 -f 2585//2585 2584//2584 2483//2483 -f 2523//2523 2529//2529 2524//2524 -f 2524//2524 2529//2529 2586//2586 -f 2524//2524 2586//2586 2525//2525 -f 2525//2525 2586//2586 2587//2587 -f 2525//2525 2587//2587 2526//2526 -f 2526//2526 2587//2587 2588//2588 -f 2526//2526 2588//2588 2527//2527 -f 2589//2589 2529//2529 2590//2590 -f 2590//2590 2529//2529 2528//2528 -f 2590//2590 2528//2528 2591//2591 -f 2515//2515 2591//2591 2516//2516 -f 2516//2516 2591//2591 2528//2528 -f 2516//2516 2528//2528 2592//2592 -f 2592//2592 2528//2528 2523//2523 -f 2592//2592 2523//2523 2593//2593 -f 2593//2593 2523//2523 2518//2518 -f 2593//2593 2518//2518 2444//2444 -f 2444//2444 2518//2518 2445//2445 -f 2594//2594 2514//2514 2595//2595 -f 2595//2595 2514//2514 2516//2516 -f 2595//2595 2516//2516 2596//2596 -f 2596//2596 2516//2516 2592//2592 -f 2596//2596 2592//2592 2597//2597 -f 2597//2597 2592//2592 2593//2593 -f 2597//2597 2593//2593 2464//2464 -f 2464//2464 2593//2593 2444//2444 -f 2464//2464 2463//2463 2597//2597 -f 2597//2597 2463//2463 2530//2530 -f 2597//2597 2530//2530 2596//2596 -f 2596//2596 2530//2530 2532//2532 -f 2596//2596 2532//2532 2595//2595 -f 2595//2595 2532//2532 2534//2534 -f 2595//2595 2534//2534 2594//2594 -f 2594//2594 2534//2534 2598//2598 -f 2513//2513 2512//2512 2534//2534 -f 2534//2534 2512//2512 2599//2599 -f 2534//2534 2599//2599 2598//2598 -f 2600//2600 2511//2511 2601//2601 -f 2601//2601 2511//2511 2513//2513 -f 2601//2601 2513//2513 2602//2602 -f 2602//2602 2513//2513 2533//2533 -f 2602//2602 2533//2533 2603//2603 -f 2603//2603 2533//2533 2531//2531 -f 2603//2603 2531//2531 2461//2461 -f 2461//2461 2531//2531 2462//2462 -f 2461//2461 2460//2460 2603//2603 -f 2603//2603 2460//2460 2535//2535 -f 2603//2603 2535//2535 2602//2602 -f 2602//2602 2535//2535 2537//2537 -f 2602//2602 2537//2537 2601//2601 -f 2601//2601 2537//2537 2539//2539 -f 2601//2601 2539//2539 2600//2600 -f 2600//2600 2539//2539 2604//2604 -f 2510//2510 2509//2509 2539//2539 -f 2539//2539 2509//2509 2605//2605 -f 2539//2539 2605//2605 2604//2604 -f 2606//2606 2508//2508 2607//2607 -f 2607//2607 2508//2508 2510//2510 -f 2607//2607 2510//2510 2608//2608 -f 2608//2608 2510//2510 2538//2538 -f 2608//2608 2538//2538 2609//2609 -f 2609//2609 2538//2538 2536//2536 -f 2609//2609 2536//2536 2458//2458 -f 2458//2458 2536//2536 2459//2459 -f 2458//2458 2457//2457 2609//2609 -f 2609//2609 2457//2457 2540//2540 -f 2609//2609 2540//2540 2608//2608 -f 2608//2608 2540//2540 2542//2542 -f 2608//2608 2542//2542 2607//2607 -f 2607//2607 2542//2542 2544//2544 -f 2607//2607 2544//2544 2606//2606 -f 2606//2606 2544//2544 2610//2610 -f 2507//2507 2506//2506 2544//2544 -f 2544//2544 2506//2506 2611//2611 -f 2544//2544 2611//2611 2610//2610 -f 2612//2612 2505//2505 2613//2613 -f 2613//2613 2505//2505 2507//2507 -f 2613//2613 2507//2507 2614//2614 -f 2614//2614 2507//2507 2543//2543 -f 2614//2614 2543//2543 2615//2615 -f 2615//2615 2543//2543 2541//2541 -f 2615//2615 2541//2541 2442//2442 -f 2442//2442 2541//2541 2443//2443 -f 2442//2442 2441//2441 2615//2615 -f 2615//2615 2441//2441 2545//2545 -f 2615//2615 2545//2545 2614//2614 -f 2614//2614 2545//2545 2547//2547 -f 2614//2614 2547//2547 2613//2613 -f 2613//2613 2547//2547 2549//2549 -f 2613//2613 2549//2549 2612//2612 -f 2612//2612 2549//2549 2616//2616 -f 2504//2504 2503//2503 2549//2549 -f 2549//2549 2503//2503 2617//2617 -f 2549//2549 2617//2617 2616//2616 -f 2618//2618 2502//2502 2619//2619 -f 2619//2619 2502//2502 2504//2504 -f 2619//2619 2504//2504 2620//2620 -f 2620//2620 2504//2504 2548//2548 -f 2620//2620 2548//2548 2621//2621 -f 2621//2621 2548//2548 2546//2546 -f 2621//2621 2546//2546 2439//2439 -f 2439//2439 2546//2546 2440//2440 -f 2439//2439 2438//2438 2621//2621 -f 2621//2621 2438//2438 2550//2550 -f 2621//2621 2550//2550 2620//2620 -f 2620//2620 2550//2550 2552//2552 -f 2620//2620 2552//2552 2619//2619 -f 2619//2619 2552//2552 2554//2554 -f 2619//2619 2554//2554 2618//2618 -f 2618//2618 2554//2554 2622//2622 -f 2623//2623 2624//2624 2625//2625 -f 2625//2625 2624//2624 2555//2555 -f 2625//2625 2555//2555 2626//2626 -f 2626//2626 2555//2555 2553//2553 -f 2626//2626 2553//2553 2627//2627 -f 2627//2627 2553//2553 2551//2551 -f 2627//2627 2551//2551 2455//2455 -f 2455//2455 2551//2551 2456//2456 -f 2624//2624 2628//2628 2555//2555 -f 2555//2555 2628//2628 2629//2629 -f 2555//2555 2629//2629 2554//2554 -f 2554//2554 2629//2629 2630//2630 -f 2554//2554 2630//2630 2622//2622 -f 2631//2631 2623//2623 2632//2632 -f 2632//2632 2623//2623 2625//2625 -f 2632//2632 2625//2625 2633//2633 -f 2633//2633 2625//2625 2626//2626 -f 2633//2633 2626//2626 2634//2634 -f 2634//2634 2626//2626 2627//2627 -f 2634//2634 2627//2627 2454//2454 -f 2454//2454 2627//2627 2455//2455 -f 2454//2454 2453//2453 2634//2634 -f 2634//2634 2453//2453 2556//2556 -f 2634//2634 2556//2556 2633//2633 -f 2633//2633 2556//2556 2558//2558 -f 2633//2633 2558//2558 2632//2632 -f 2632//2632 2558//2558 2560//2560 -f 2632//2632 2560//2560 2631//2631 -f 2631//2631 2560//2560 2635//2635 -f 2501//2501 2500//2500 2560//2560 -f 2560//2560 2500//2500 2636//2636 -f 2560//2560 2636//2636 2635//2635 -f 2637//2637 2499//2499 2638//2638 -f 2638//2638 2499//2499 2501//2501 -f 2638//2638 2501//2501 2639//2639 -f 2639//2639 2501//2501 2559//2559 -f 2639//2639 2559//2559 2640//2640 -f 2640//2640 2559//2559 2557//2557 -f 2640//2640 2557//2557 2451//2451 -f 2451//2451 2557//2557 2452//2452 -f 2451//2451 2450//2450 2640//2640 -f 2640//2640 2450//2450 2561//2561 -f 2640//2640 2561//2561 2639//2639 -f 2639//2639 2561//2561 2563//2563 -f 2639//2639 2563//2563 2638//2638 -f 2638//2638 2563//2563 2565//2565 -f 2638//2638 2565//2565 2637//2637 -f 2637//2637 2565//2565 2641//2641 -f 2498//2498 2497//2497 2565//2565 -f 2565//2565 2497//2497 2642//2642 -f 2565//2565 2642//2642 2641//2641 -f 2643//2643 2496//2496 2644//2644 -f 2644//2644 2496//2496 2498//2498 -f 2644//2644 2498//2498 2645//2645 -f 2645//2645 2498//2498 2564//2564 -f 2645//2645 2564//2564 2646//2646 -f 2646//2646 2564//2564 2562//2562 -f 2646//2646 2562//2562 2479//2479 -f 2479//2479 2562//2562 2480//2480 -f 2479//2479 2478//2478 2646//2646 -f 2646//2646 2478//2478 2566//2566 -f 2646//2646 2566//2566 2645//2645 -f 2645//2645 2566//2566 2568//2568 -f 2645//2645 2568//2568 2644//2644 -f 2644//2644 2568//2568 2570//2570 -f 2644//2644 2570//2570 2643//2643 -f 2643//2643 2570//2570 2647//2647 -f 2495//2495 2494//2494 2570//2570 -f 2570//2570 2494//2494 2648//2648 -f 2570//2570 2648//2648 2647//2647 -f 2649//2649 2493//2493 2650//2650 -f 2650//2650 2493//2493 2495//2495 -f 2650//2650 2495//2495 2651//2651 -f 2651//2651 2495//2495 2569//2569 -f 2651//2651 2569//2569 2652//2652 -f 2652//2652 2569//2569 2567//2567 -f 2652//2652 2567//2567 2476//2476 -f 2476//2476 2567//2567 2477//2477 -f 2476//2476 2475//2475 2652//2652 -f 2652//2652 2475//2475 2571//2571 -f 2652//2652 2571//2571 2651//2651 -f 2651//2651 2571//2571 2573//2573 -f 2651//2651 2573//2573 2650//2650 -f 2650//2650 2573//2573 2575//2575 -f 2650//2650 2575//2575 2649//2649 -f 2649//2649 2575//2575 2653//2653 -f 2492//2492 2491//2491 2575//2575 -f 2575//2575 2491//2491 2654//2654 -f 2575//2575 2654//2654 2653//2653 -f 2488//2488 2490//2490 2489//2489 -f 2489//2489 2490//2490 2492//2492 -f 2489//2489 2492//2492 2655//2655 -f 2655//2655 2492//2492 2574//2574 -f 2655//2655 2574//2574 2517//2517 -f 2517//2517 2574//2574 2572//2572 -f 2517//2517 2572//2572 2473//2473 -f 2473//2473 2572//2572 2474//2474 -f 2656//2656 2487//2487 2657//2657 -f 2657//2657 2487//2487 2489//2489 -f 2657//2657 2489//2489 2658//2658 -f 2658//2658 2489//2489 2655//2655 -f 2658//2658 2655//2655 2659//2659 -f 2659//2659 2655//2655 2517//2517 -f 2659//2659 2517//2517 2471//2471 -f 2471//2471 2517//2517 2472//2472 -f 2471//2471 2470//2470 2659//2659 -f 2659//2659 2470//2470 2576//2576 -f 2659//2659 2576//2576 2658//2658 -f 2658//2658 2576//2576 2578//2578 -f 2658//2658 2578//2578 2657//2657 -f 2657//2657 2578//2578 2580//2580 -f 2657//2657 2580//2580 2656//2656 -f 2656//2656 2580//2580 2660//2660 -f 2486//2486 2485//2485 2580//2580 -f 2580//2580 2485//2485 2661//2661 -f 2580//2580 2661//2661 2660//2660 -f 2662//2662 2484//2484 2663//2663 -f 2663//2663 2484//2484 2486//2486 -f 2663//2663 2486//2486 2664//2664 -f 2664//2664 2486//2486 2579//2579 -f 2664//2664 2579//2579 2665//2665 -f 2665//2665 2579//2579 2577//2577 -f 2665//2665 2577//2577 2468//2468 -f 2468//2468 2577//2577 2469//2469 -f 2468//2468 2467//2467 2665//2665 -f 2665//2665 2467//2467 2581//2581 -f 2665//2665 2581//2581 2664//2664 -f 2664//2664 2581//2581 2583//2583 -f 2664//2664 2583//2583 2663//2663 -f 2663//2663 2583//2583 2585//2585 -f 2663//2663 2585//2585 2662//2662 -f 2662//2662 2585//2585 2666//2666 -f 2483//2483 2482//2482 2585//2585 -f 2585//2585 2482//2482 2667//2667 -f 2585//2585 2667//2667 2666//2666 -f 2668//2668 2481//2481 2669//2669 -f 2669//2669 2481//2481 2483//2483 -f 2669//2669 2483//2483 2670//2670 -f 2670//2670 2483//2483 2584//2584 -f 2670//2670 2584//2584 2671//2671 -f 2671//2671 2584//2584 2582//2582 -f 2671//2671 2582//2582 2465//2465 -f 2465//2465 2582//2582 2466//2466 -f 2465//2465 2449//2449 2671//2671 -f 2671//2671 2449//2449 2522//2522 -f 2671//2671 2522//2522 2670//2670 -f 2670//2670 2522//2522 2527//2527 -f 2670//2670 2527//2527 2669//2669 -f 2669//2669 2527//2527 2588//2588 -f 2669//2669 2588//2588 2668//2668 -f 2668//2668 2588//2588 2672//2672 -f 2589//2589 2673//2673 2529//2529 -f 2529//2529 2673//2673 2674//2674 -f 2529//2529 2674//2674 2586//2586 -f 2586//2586 2674//2674 2675//2675 -f 2586//2586 2675//2675 2587//2587 -f 2587//2587 2675//2675 2676//2676 -f 2587//2587 2676//2676 2588//2588 -f 2588//2588 2676//2676 2677//2677 -f 2588//2588 2677//2677 2672//2672 -f 2678//2678 2491//2491 2679//2679 -f 2679//2679 2491//2491 2490//2490 -f 2679//2679 2490//2490 2680//2680 -f 2680//2680 2490//2490 2488//2488 -f 2680//2680 2488//2488 2681//2681 -f 2681//2681 2488//2488 2487//2487 -f 2681//2681 2487//2487 2682//2682 -f 2682//2682 2487//2487 2656//2656 -f 2682//2682 2656//2656 2683//2683 -f 2683//2683 2656//2656 2660//2660 -f 2683//2683 2660//2660 2684//2684 -f 2684//2684 2660//2660 2661//2661 -f 2684//2684 2661//2661 2685//2685 -f 2685//2685 2661//2661 2485//2485 -f 2685//2685 2485//2485 2686//2686 -f 2686//2686 2485//2485 2484//2484 -f 2686//2686 2484//2484 2687//2687 -f 2687//2687 2484//2484 2662//2662 -f 2687//2687 2662//2662 2688//2688 -f 2688//2688 2662//2662 2666//2666 -f 2688//2688 2666//2666 2689//2689 -f 2689//2689 2666//2666 2667//2667 -f 2689//2689 2667//2667 2690//2690 -f 2690//2690 2667//2667 2482//2482 -f 2690//2690 2482//2482 2691//2691 -f 2691//2691 2482//2482 2481//2481 -f 2691//2691 2481//2481 2692//2692 -f 2692//2692 2481//2481 2668//2668 -f 2692//2692 2668//2668 2693//2693 -f 2693//2693 2668//2668 2672//2672 -f 2693//2693 2672//2672 2694//2694 -f 2694//2694 2672//2672 2677//2677 -f 2694//2694 2677//2677 2695//2695 -f 2695//2695 2677//2677 2676//2676 -f 2695//2695 2676//2676 2696//2696 -f 2696//2696 2676//2676 2675//2675 -f 2696//2696 2675//2675 2697//2697 -f 2697//2697 2675//2675 2674//2674 -f 2697//2697 2674//2674 2698//2698 -f 2698//2698 2674//2674 2673//2673 -f 2698//2698 2673//2673 2699//2699 -f 2699//2699 2673//2673 2589//2589 -f 2699//2699 2589//2589 2700//2700 -f 2700//2700 2589//2589 2590//2590 -f 2700//2700 2590//2590 2701//2701 -f 2701//2701 2590//2590 2591//2591 -f 2701//2701 2591//2591 2702//2702 -f 2702//2702 2591//2591 2515//2515 -f 2702//2702 2515//2515 2703//2703 -f 2703//2703 2515//2515 2514//2514 -f 2703//2703 2514//2514 2704//2704 -f 2704//2704 2514//2514 2594//2594 -f 2704//2704 2594//2594 2705//2705 -f 2705//2705 2594//2594 2598//2598 -f 2705//2705 2598//2598 2706//2706 -f 2706//2706 2598//2598 2599//2599 -f 2706//2706 2599//2599 2707//2707 -f 2707//2707 2599//2599 2512//2512 -f 2707//2707 2512//2512 2708//2708 -f 2708//2708 2512//2512 2511//2511 -f 2708//2708 2511//2511 2709//2709 -f 2709//2709 2511//2511 2600//2600 -f 2709//2709 2600//2600 2710//2710 -f 2710//2710 2600//2600 2604//2604 -f 2710//2710 2604//2604 2711//2711 -f 2711//2711 2604//2604 2605//2605 -f 2711//2711 2605//2605 2712//2712 -f 2712//2712 2605//2605 2509//2509 -f 2712//2712 2509//2509 2713//2713 -f 2713//2713 2509//2509 2508//2508 -f 2713//2713 2508//2508 2714//2714 -f 2714//2714 2508//2508 2606//2606 -f 2714//2714 2606//2606 2715//2715 -f 2715//2715 2606//2606 2610//2610 -f 2715//2715 2610//2610 2716//2716 -f 2716//2716 2610//2610 2611//2611 -f 2716//2716 2611//2611 2717//2717 -f 2717//2717 2611//2611 2506//2506 -f 2717//2717 2506//2506 2718//2718 -f 2718//2718 2506//2506 2505//2505 -f 2718//2718 2505//2505 2719//2719 -f 2719//2719 2505//2505 2612//2612 -f 2719//2719 2612//2612 2720//2720 -f 2720//2720 2612//2612 2616//2616 -f 2720//2720 2616//2616 2721//2721 -f 2721//2721 2616//2616 2617//2617 -f 2721//2721 2617//2617 2722//2722 -f 2722//2722 2617//2617 2503//2503 -f 2722//2722 2503//2503 2723//2723 -f 2723//2723 2503//2503 2502//2502 -f 2723//2723 2502//2502 2724//2724 -f 2724//2724 2502//2502 2618//2618 -f 2724//2724 2618//2618 2725//2725 -f 2725//2725 2618//2618 2622//2622 -f 2725//2725 2622//2622 2726//2726 -f 2726//2726 2622//2622 2630//2630 -f 2726//2726 2630//2630 2727//2727 -f 2727//2727 2630//2630 2629//2629 -f 2727//2727 2629//2629 2728//2728 -f 2728//2728 2629//2629 2628//2628 -f 2728//2728 2628//2628 2729//2729 -f 2729//2729 2628//2628 2624//2624 -f 2729//2729 2624//2624 2730//2730 -f 2730//2730 2624//2624 2623//2623 -f 2730//2730 2623//2623 2731//2731 -f 2731//2731 2623//2623 2631//2631 -f 2731//2731 2631//2631 2732//2732 -f 2732//2732 2631//2631 2635//2635 -f 2732//2732 2635//2635 2733//2733 -f 2733//2733 2635//2635 2636//2636 -f 2733//2733 2636//2636 2734//2734 -f 2734//2734 2636//2636 2500//2500 -f 2734//2734 2500//2500 2735//2735 -f 2735//2735 2500//2500 2499//2499 -f 2735//2735 2499//2499 2736//2736 -f 2736//2736 2499//2499 2637//2637 -f 2736//2736 2637//2637 2737//2737 -f 2737//2737 2637//2637 2641//2641 -f 2737//2737 2641//2641 2738//2738 -f 2738//2738 2641//2641 2642//2642 -f 2738//2738 2642//2642 2739//2739 -f 2739//2739 2642//2642 2497//2497 -f 2739//2739 2497//2497 2740//2740 -f 2740//2740 2497//2497 2496//2496 -f 2740//2740 2496//2496 2741//2741 -f 2741//2741 2496//2496 2643//2643 -f 2741//2741 2643//2643 2742//2742 -f 2742//2742 2643//2643 2647//2647 -f 2742//2742 2647//2647 2743//2743 -f 2743//2743 2647//2647 2648//2648 -f 2743//2743 2648//2648 2744//2744 -f 2744//2744 2648//2648 2494//2494 -f 2744//2744 2494//2494 2745//2745 -f 2745//2745 2494//2494 2493//2493 -f 2745//2745 2493//2493 2746//2746 -f 2746//2746 2493//2493 2649//2649 -f 2746//2746 2649//2649 2747//2747 -f 2747//2747 2649//2649 2653//2653 -f 2747//2747 2653//2653 2748//2748 -f 2748//2748 2653//2653 2654//2654 -f 2748//2748 2654//2654 2678//2678 -f 2678//2678 2654//2654 2491//2491 -f 2749//2749 2697//2697 2698//2698 -f 2749//2749 2698//2698 2750//2750 -f 2750//2750 2698//2698 2699//2699 -f 2750//2750 2699//2699 2751//2751 -f 2751//2751 2699//2699 2700//2700 -f 2751//2751 2700//2700 2752//2752 -f 2700//2700 2701//2701 2752//2752 -f 2752//2752 2701//2701 2702//2702 -f 2752//2752 2702//2702 2753//2753 -f 2753//2753 2702//2702 2703//2703 -f 2703//2703 2704//2704 2753//2753 -f 2753//2753 2704//2704 2705//2705 -f 2753//2753 2705//2705 2754//2754 -f 2754//2754 2705//2705 2706//2706 -f 2754//2754 2706//2706 2755//2755 -f 2755//2755 2706//2706 2707//2707 -f 2755//2755 2707//2707 2756//2756 -f 2756//2756 2707//2707 2708//2708 -f 2708//2708 2709//2709 2756//2756 -f 2756//2756 2709//2709 2710//2710 -f 2756//2756 2710//2710 2757//2757 -f 2757//2757 2710//2710 2711//2711 -f 2757//2757 2711//2711 2758//2758 -f 2758//2758 2711//2711 2712//2712 -f 2758//2758 2712//2712 2759//2759 -f 2759//2759 2712//2712 2713//2713 -f 2713//2713 2714//2714 2759//2759 -f 2759//2759 2714//2714 2715//2715 -f 2759//2759 2715//2715 2760//2760 -f 2760//2760 2715//2715 2716//2716 -f 2760//2760 2716//2716 2761//2761 -f 2761//2761 2716//2716 2717//2717 -f 2761//2761 2717//2717 2762//2762 -f 2762//2762 2717//2717 2718//2718 -f 2718//2718 2719//2719 2762//2762 -f 2762//2762 2719//2719 2720//2720 -f 2762//2762 2720//2720 2763//2763 -f 2763//2763 2720//2720 2721//2721 -f 2763//2763 2721//2721 2764//2764 -f 2764//2764 2721//2721 2722//2722 -f 2764//2764 2722//2722 2765//2765 -f 2765//2765 2722//2722 2723//2723 -f 2723//2723 2724//2724 2765//2765 -f 2765//2765 2724//2724 2725//2725 -f 2765//2765 2725//2725 2766//2766 -f 2766//2766 2725//2725 2726//2726 -f 2766//2766 2726//2726 2767//2767 -f 2726//2726 2727//2727 2767//2767 -f 2767//2767 2727//2727 2728//2728 -f 2767//2767 2728//2728 2768//2768 -f 2768//2768 2728//2728 2729//2729 -f 2768//2768 2729//2729 2769//2769 -f 2769//2769 2729//2729 2730//2730 -f 2730//2730 2731//2731 2769//2769 -f 2769//2769 2731//2731 2732//2732 -f 2769//2769 2732//2732 2770//2770 -f 2770//2770 2732//2732 2733//2733 -f 2770//2770 2733//2733 2771//2771 -f 2771//2771 2733//2733 2734//2734 -f 2771//2771 2734//2734 2772//2772 -f 2772//2772 2734//2734 2735//2735 -f 2735//2735 2736//2736 2772//2772 -f 2772//2772 2736//2736 2737//2737 -f 2772//2772 2737//2737 2773//2773 -f 2773//2773 2737//2737 2738//2738 -f 2773//2773 2738//2738 2774//2774 -f 2774//2774 2738//2738 2739//2739 -f 2774//2774 2739//2739 2775//2775 -f 2775//2775 2739//2739 2740//2740 -f 2740//2740 2741//2741 2775//2775 -f 2775//2775 2741//2741 2742//2742 -f 2775//2775 2742//2742 2776//2776 -f 2776//2776 2742//2742 2743//2743 -f 2776//2776 2743//2743 2777//2777 -f 2777//2777 2743//2743 2744//2744 -f 2777//2777 2744//2744 2778//2778 -f 2778//2778 2744//2744 2745//2745 -f 2745//2745 2746//2746 2778//2778 -f 2778//2778 2746//2746 2747//2747 -f 2778//2778 2747//2747 2779//2779 -f 2779//2779 2747//2747 2748//2748 -f 2779//2779 2748//2748 2780//2780 -f 2748//2748 2678//2678 2780//2780 -f 2780//2780 2678//2678 2679//2679 -f 2780//2780 2679//2679 2781//2781 -f 2781//2781 2679//2679 2680//2680 -f 2781//2781 2680//2680 2782//2782 -f 2782//2782 2680//2680 2681//2681 -f 2681//2681 2682//2682 2782//2782 -f 2782//2782 2682//2682 2683//2683 -f 2782//2782 2683//2683 2783//2783 -f 2783//2783 2683//2683 2684//2684 -f 2783//2783 2684//2684 2784//2784 -f 2784//2784 2684//2684 2685//2685 -f 2784//2784 2685//2685 2785//2785 -f 2785//2785 2685//2685 2686//2686 -f 2686//2686 2687//2687 2785//2785 -f 2785//2785 2687//2687 2688//2688 -f 2785//2785 2688//2688 2786//2786 -f 2786//2786 2688//2688 2689//2689 -f 2786//2786 2689//2689 2787//2787 -f 2787//2787 2689//2689 2690//2690 -f 2787//2787 2690//2690 2788//2788 -f 2788//2788 2690//2690 2691//2691 -f 2691//2691 2692//2692 2788//2788 -f 2788//2788 2692//2692 2693//2693 -f 2788//2788 2693//2693 2789//2789 -f 2789//2789 2693//2693 2694//2694 -f 2789//2789 2694//2694 2790//2790 -f 2790//2790 2694//2694 2695//2695 -f 2790//2790 2695//2695 2749//2749 -f 2749//2749 2695//2695 2696//2696 -f 2749//2749 2696//2696 2697//2697 -f 2749//2749 2791//2791 2790//2790 -f 2790//2790 2791//2791 2792//2792 -f 2790//2790 2792//2792 2789//2789 -f 2789//2789 2792//2792 2793//2793 -f 2789//2789 2793//2793 2788//2788 -f 2788//2788 2793//2793 2794//2794 -f 2788//2788 2794//2794 2787//2787 -f 2787//2787 2794//2794 2795//2795 -f 2787//2787 2795//2795 2786//2786 -f 2786//2786 2795//2795 2796//2796 -f 2786//2786 2796//2796 2785//2785 -f 2785//2785 2796//2796 2797//2797 -f 2785//2785 2797//2797 2784//2784 -f 2784//2784 2797//2797 2798//2798 -f 2784//2784 2798//2798 2783//2783 -f 2783//2783 2798//2798 2799//2799 -f 2783//2783 2799//2799 2782//2782 -f 2782//2782 2799//2799 2800//2800 -f 2782//2782 2800//2800 2781//2781 -f 2781//2781 2800//2800 2801//2801 -f 2781//2781 2801//2801 2780//2780 -f 2780//2780 2801//2801 2802//2802 -f 2780//2780 2802//2802 2779//2779 -f 2779//2779 2802//2802 2803//2803 -f 2779//2779 2803//2803 2778//2778 -f 2778//2778 2803//2803 2804//2804 -f 2778//2778 2804//2804 2777//2777 -f 2777//2777 2804//2804 2805//2805 -f 2777//2777 2805//2805 2776//2776 -f 2776//2776 2805//2805 2806//2806 -f 2776//2776 2806//2806 2775//2775 -f 2775//2775 2806//2806 2807//2807 -f 2775//2775 2807//2807 2774//2774 -f 2774//2774 2807//2807 2808//2808 -f 2774//2774 2808//2808 2773//2773 -f 2773//2773 2808//2808 2809//2809 -f 2773//2773 2809//2809 2772//2772 -f 2772//2772 2809//2809 2810//2810 -f 2772//2772 2810//2810 2771//2771 -f 2771//2771 2810//2810 2811//2811 -f 2771//2771 2811//2811 2770//2770 -f 2770//2770 2811//2811 2812//2812 -f 2770//2770 2812//2812 2769//2769 -f 2769//2769 2812//2812 2813//2813 -f 2769//2769 2813//2813 2768//2768 -f 2768//2768 2813//2813 2814//2814 -f 2768//2768 2814//2814 2767//2767 -f 2767//2767 2814//2814 2815//2815 -f 2767//2767 2815//2815 2766//2766 -f 2766//2766 2815//2815 2816//2816 -f 2766//2766 2816//2816 2765//2765 -f 2765//2765 2816//2816 2817//2817 -f 2765//2765 2817//2817 2764//2764 -f 2764//2764 2817//2817 2818//2818 -f 2764//2764 2818//2818 2763//2763 -f 2763//2763 2818//2818 2819//2819 -f 2763//2763 2819//2819 2762//2762 -f 2762//2762 2819//2819 2820//2820 -f 2762//2762 2820//2820 2761//2761 -f 2761//2761 2820//2820 2821//2821 -f 2761//2761 2821//2821 2760//2760 -f 2760//2760 2821//2821 2822//2822 -f 2760//2760 2822//2822 2759//2759 -f 2759//2759 2822//2822 2823//2823 -f 2759//2759 2823//2823 2758//2758 -f 2758//2758 2823//2823 2824//2824 -f 2758//2758 2824//2824 2757//2757 -f 2757//2757 2824//2824 2825//2825 -f 2757//2757 2825//2825 2756//2756 -f 2756//2756 2825//2825 2826//2826 -f 2756//2756 2826//2826 2755//2755 -f 2755//2755 2826//2826 2827//2827 -f 2755//2755 2827//2827 2754//2754 -f 2754//2754 2827//2827 2828//2828 -f 2754//2754 2828//2828 2753//2753 -f 2753//2753 2828//2828 2829//2829 -f 2753//2753 2829//2829 2752//2752 -f 2752//2752 2829//2829 2830//2830 -f 2752//2752 2830//2830 2751//2751 -f 2751//2751 2830//2830 2831//2831 -f 2751//2751 2831//2831 2750//2750 -f 2750//2750 2831//2831 2832//2832 -f 2750//2750 2832//2832 2749//2749 -f 2749//2749 2832//2832 2791//2791 -f 2832//2832 2833//2833 2791//2791 -f 2791//2791 2833//2833 2834//2834 -f 2791//2791 2834//2834 2792//2792 -f 2792//2792 2834//2834 2835//2835 -f 2792//2792 2835//2835 2793//2793 -f 2793//2793 2835//2835 2836//2836 -f 2793//2793 2836//2836 2794//2794 -f 2794//2794 2836//2836 2837//2837 -f 2794//2794 2837//2837 2795//2795 -f 2795//2795 2837//2837 2838//2838 -f 2795//2795 2838//2838 2796//2796 -f 2796//2796 2838//2838 2839//2839 -f 2796//2796 2839//2839 2797//2797 -f 2797//2797 2839//2839 2840//2840 -f 2797//2797 2840//2840 2798//2798 -f 2798//2798 2840//2840 2841//2841 -f 2798//2798 2841//2841 2799//2799 -f 2799//2799 2841//2841 2842//2842 -f 2799//2799 2842//2842 2800//2800 -f 2800//2800 2842//2842 2843//2843 -f 2800//2800 2843//2843 2801//2801 -f 2801//2801 2843//2843 2844//2844 -f 2801//2801 2844//2844 2802//2802 -f 2802//2802 2844//2844 2845//2845 -f 2802//2802 2845//2845 2803//2803 -f 2803//2803 2845//2845 2846//2846 -f 2803//2803 2846//2846 2804//2804 -f 2804//2804 2846//2846 2847//2847 -f 2804//2804 2847//2847 2805//2805 -f 2805//2805 2847//2847 2848//2848 -f 2805//2805 2848//2848 2806//2806 -f 2806//2806 2848//2848 2849//2849 -f 2806//2806 2849//2849 2807//2807 -f 2807//2807 2849//2849 2850//2850 -f 2807//2807 2850//2850 2808//2808 -f 2808//2808 2850//2850 2851//2851 -f 2808//2808 2851//2851 2809//2809 -f 2809//2809 2851//2851 2852//2852 -f 2809//2809 2852//2852 2810//2810 -f 2810//2810 2852//2852 2853//2853 -f 2810//2810 2853//2853 2811//2811 -f 2811//2811 2853//2853 2854//2854 -f 2811//2811 2854//2854 2812//2812 -f 2812//2812 2854//2854 2855//2855 -f 2812//2812 2855//2855 2813//2813 -f 2813//2813 2855//2855 2856//2856 -f 2813//2813 2856//2856 2814//2814 -f 2814//2814 2856//2856 2857//2857 -f 2814//2814 2857//2857 2815//2815 -f 2815//2815 2857//2857 2858//2858 -f 2815//2815 2858//2858 2816//2816 -f 2816//2816 2858//2858 2859//2859 -f 2816//2816 2859//2859 2817//2817 -f 2817//2817 2859//2859 2860//2860 -f 2817//2817 2860//2860 2818//2818 -f 2818//2818 2860//2860 2861//2861 -f 2818//2818 2861//2861 2819//2819 -f 2819//2819 2861//2861 2862//2862 -f 2819//2819 2862//2862 2820//2820 -f 2820//2820 2862//2862 2863//2863 -f 2820//2820 2863//2863 2821//2821 -f 2821//2821 2863//2863 2864//2864 -f 2821//2821 2864//2864 2822//2822 -f 2822//2822 2864//2864 2865//2865 -f 2822//2822 2865//2865 2823//2823 -f 2823//2823 2865//2865 2866//2866 -f 2823//2823 2866//2866 2824//2824 -f 2824//2824 2866//2866 2867//2867 -f 2824//2824 2867//2867 2825//2825 -f 2825//2825 2867//2867 2868//2868 -f 2825//2825 2868//2868 2826//2826 -f 2826//2826 2868//2868 2869//2869 -f 2826//2826 2869//2869 2827//2827 -f 2827//2827 2869//2869 2870//2870 -f 2827//2827 2870//2870 2828//2828 -f 2828//2828 2870//2870 2871//2871 -f 2828//2828 2871//2871 2829//2829 -f 2829//2829 2871//2871 2872//2872 -f 2829//2829 2872//2872 2830//2830 -f 2830//2830 2872//2872 2873//2873 -f 2830//2830 2873//2873 2831//2831 -f 2831//2831 2873//2873 2874//2874 -f 2831//2831 2874//2874 2832//2832 -f 2832//2832 2874//2874 2833//2833 -f 2875//2875 2876//2876 2843//2843 -f 2843//2843 2876//2876 2877//2877 -f 2843//2843 2877//2877 2844//2844 -f 2844//2844 2877//2877 2878//2878 -f 2844//2844 2878//2878 2845//2845 -f 2845//2845 2878//2878 2879//2879 -f 2845//2845 2879//2879 2846//2846 -f 2846//2846 2879//2879 2880//2880 -f 2846//2846 2880//2880 2847//2847 -f 2847//2847 2880//2880 2881//2881 -f 2847//2847 2881//2881 2848//2848 -f 2848//2848 2881//2881 2882//2882 -f 2848//2848 2882//2882 2849//2849 -f 2849//2849 2882//2882 2883//2883 -f 2849//2849 2883//2883 2850//2850 -f 2850//2850 2883//2883 2884//2884 -f 2850//2850 2884//2884 2851//2851 -f 2851//2851 2884//2884 2885//2885 -f 2851//2851 2885//2885 2852//2852 -f 2852//2852 2885//2885 2886//2886 -f 2852//2852 2886//2886 2853//2853 -f 2853//2853 2886//2886 2887//2887 -f 2853//2853 2887//2887 2854//2854 -f 2854//2854 2887//2887 2888//2888 -f 2854//2854 2888//2888 2855//2855 -f 2855//2855 2888//2888 2889//2889 -f 2855//2855 2889//2889 2856//2856 -f 2856//2856 2889//2889 2890//2890 -f 2856//2856 2890//2890 2857//2857 -f 2857//2857 2890//2890 2891//2891 -f 2857//2857 2891//2891 2858//2858 -f 2858//2858 2891//2891 2892//2892 -f 2858//2858 2892//2892 2859//2859 -f 2859//2859 2892//2892 2893//2893 -f 2859//2859 2893//2893 2860//2860 -f 2860//2860 2893//2893 2894//2894 -f 2860//2860 2894//2894 2861//2861 -f 2861//2861 2894//2894 2895//2895 -f 2861//2861 2895//2895 2862//2862 -f 2862//2862 2895//2895 2896//2896 -f 2862//2862 2896//2896 2863//2863 -f 2863//2863 2896//2896 2897//2897 -f 2863//2863 2897//2897 2864//2864 -f 2864//2864 2897//2897 2898//2898 -f 2864//2864 2898//2898 2865//2865 -f 2865//2865 2898//2898 2899//2899 -f 2865//2865 2899//2899 2866//2866 -f 2866//2866 2899//2899 2900//2900 -f 2866//2866 2900//2900 2867//2867 -f 2867//2867 2900//2900 2901//2901 -f 2867//2867 2901//2901 2868//2868 -f 2868//2868 2901//2901 2902//2902 -f 2868//2868 2902//2902 2869//2869 -f 2869//2869 2902//2902 2903//2903 -f 2869//2869 2903//2903 2870//2870 -f 2870//2870 2903//2903 2904//2904 -f 2870//2870 2904//2904 2871//2871 -f 2871//2871 2904//2904 2905//2905 -f 2871//2871 2905//2905 2872//2872 -f 2872//2872 2905//2905 2906//2906 -f 2872//2872 2906//2906 2873//2873 -f 2873//2873 2906//2906 2907//2907 -f 2873//2873 2907//2907 2874//2874 -f 2874//2874 2907//2907 2908//2908 -f 2874//2874 2908//2908 2833//2833 -f 2833//2833 2908//2908 2909//2909 -f 2833//2833 2909//2909 2834//2834 -f 2834//2834 2909//2909 2910//2910 -f 2834//2834 2910//2910 2835//2835 -f 2835//2835 2910//2910 2911//2911 -f 2835//2835 2911//2911 2836//2836 -f 2836//2836 2911//2911 2912//2912 -f 2836//2836 2912//2912 2837//2837 -f 2837//2837 2912//2912 2913//2913 -f 2837//2837 2913//2913 2838//2838 -f 2838//2838 2913//2913 2914//2914 -f 2838//2838 2914//2914 2839//2839 -f 2839//2839 2914//2914 2915//2915 -f 2839//2839 2915//2915 2840//2840 -f 2840//2840 2915//2915 2916//2916 -f 2840//2840 2916//2916 2841//2841 -f 2841//2841 2916//2916 2917//2917 -f 2841//2841 2917//2917 2842//2842 -f 2842//2842 2917//2917 2875//2875 -f 2842//2842 2875//2875 2843//2843 -f 1879//1879 2889//2889 1877//1877 -f 1877//1877 2889//2889 2888//2888 -f 1877//1877 2888//2888 1872//1872 -f 1872//1872 2888//2888 2887//2887 -f 1872//1872 2887//2887 1870//1870 -f 1870//1870 2887//2887 2886//2886 -f 1870//1870 2886//2886 1867//1867 -f 1867//1867 2886//2886 2885//2885 -f 1867//1867 2885//2885 1862//1862 -f 1862//1862 2885//2885 2884//2884 -f 1862//1862 2884//2884 1860//1860 -f 1940//1940 2910//2910 1935//1935 -f 1935//1935 2910//2910 2909//2909 -f 1935//1935 2909//2909 1933//1933 -f 1933//1933 2909//2909 2908//2908 -f 1933//1933 2908//2908 1930//1930 -f 1930//1930 2908//2908 2907//2907 -f 1930//1930 2907//2907 1927//1927 -f 1927//1927 2907//2907 2906//2906 -f 1927//1927 2906//2906 1924//1924 -f 1924//1924 2906//2906 2905//2905 -f 1924//1924 2905//2905 1919//1919 -f 2905//2905 2904//2904 1919//1919 -f 1919//1919 2904//2904 2903//2903 -f 1919//1919 2903//2903 1917//1917 -f 1917//1917 2903//2903 2902//2902 -f 1917//1917 2902//2902 1912//1912 -f 1912//1912 2902//2902 2901//2901 -f 1912//1912 2901//2901 1910//1910 -f 1910//1910 2901//2901 2900//2900 -f 1910//1910 2900//2900 1907//1907 -f 1907//1907 2900//2900 2899//2899 -f 1907//1907 2899//2899 1902//1902 -f 1902//1902 2899//2899 2898//2898 -f 1902//1902 2898//2898 1900//1900 -f 2884//2884 2883//2883 1860//1860 -f 1860//1860 2883//2883 2882//2882 -f 1860//1860 2882//2882 1855//1855 -f 1855//1855 2882//2882 2881//2881 -f 1855//1855 2881//2881 1853//1853 -f 1853//1853 2881//2881 2880//2880 -f 1853//1853 2880//2880 1850//1850 -f 1850//1850 2880//2880 2879//2879 -f 1850//1850 2879//2879 1847//1847 -f 1847//1847 2879//2879 2878//2878 -f 1847//1847 2878//2878 1844//1844 -f 1844//1844 2878//2878 2877//2877 -f 1844//1844 2877//2877 1843//1843 -f 1843//1843 2877//2877 2876//2876 -f 2898//2898 2897//2897 1900//1900 -f 1900//1900 2897//2897 2896//2896 -f 1900//1900 2896//2896 1895//1895 -f 1895//1895 2896//2896 2895//2895 -f 1895//1895 2895//2895 1893//1893 -f 1893//1893 2895//2895 2894//2894 -f 1893//1893 2894//2894 1890//1890 -f 1890//1890 2894//2894 2893//2893 -f 1890//1890 2893//2893 1887//1887 -f 1887//1887 2893//2893 2892//2892 -f 1887//1887 2892//2892 1884//1884 -f 1884//1884 2892//2892 2891//2891 -f 1884//1884 2891//2891 1879//1879 -f 1879//1879 2891//2891 2890//2890 -f 1879//1879 2890//2890 2889//2889 -f 2876//2876 2875//2875 1843//1843 -f 1843//1843 2875//2875 2917//2917 -f 1843//1843 2917//2917 1957//1957 -f 1957//1957 2917//2917 2916//2916 -f 1957//1957 2916//2916 1952//1952 -f 1952//1952 2916//2916 2915//2915 -f 1952//1952 2915//2915 1950//1950 -f 1950//1950 2915//2915 2914//2914 -f 1950//1950 2914//2914 1947//1947 -f 1947//1947 2914//2914 2913//2913 -f 1947//1947 2913//2913 1942//1942 -f 1942//1942 2913//2913 2912//2912 -f 1942//1942 2912//2912 1940//1940 -f 1940//1940 2912//2912 2911//2911 -f 1940//1940 2911//2911 2910//2910 -f 2918//2918 2919//2919 2920//2920 -f 2921//2921 2922//2922 2923//2923 -f 2924//2924 2925//2925 2926//2926 -f 2926//2926 2925//2925 2927//2927 -f 2924//2924 2926//2926 2928//2928 -f 2924//2924 2928//2928 2929//2929 -f 2929//2929 2928//2928 2930//2930 -f 2929//2929 2930//2930 2931//2931 -f 2922//2922 2921//2921 2932//2932 -f 2932//2932 2921//2921 2933//2933 -f 2932//2932 2933//2933 2930//2930 -f 2930//2930 2933//2933 2931//2931 -f 2934//2934 2935//2935 2923//2923 -f 2923//2923 2935//2935 2936//2936 -f 2923//2923 2936//2936 2921//2921 -f 2937//2937 2938//2938 2939//2939 -f 2939//2939 2938//2938 2940//2940 -f 2939//2939 2940//2940 2934//2934 -f 2934//2934 2940//2940 2941//2941 -f 2934//2934 2941//2941 2935//2935 -f 2942//2942 2943//2943 2944//2944 -f 2944//2944 2943//2943 2945//2945 -f 2944//2944 2945//2945 2937//2937 -f 2937//2937 2945//2945 2938//2938 -f 2925//2925 2946//2946 2927//2927 -f 2927//2927 2946//2946 2947//2947 -f 2927//2927 2947//2947 2942//2942 -f 2942//2942 2947//2947 2943//2943 -f 2948//2948 2949//2949 2950//2950 -f 2950//2950 2949//2949 2951//2951 -f 2948//2948 2950//2950 2952//2952 -f 2948//2948 2952//2952 2953//2953 -f 2953//2953 2952//2952 2954//2954 -f 2953//2953 2954//2954 2955//2955 -f 2919//2919 2918//2918 2956//2956 -f 2956//2956 2918//2918 2957//2957 -f 2956//2956 2957//2957 2954//2954 -f 2954//2954 2957//2957 2955//2955 -f 2958//2958 2959//2959 2920//2920 -f 2920//2920 2959//2959 2960//2960 -f 2920//2920 2960//2960 2918//2918 -f 2961//2961 2962//2962 2963//2963 -f 2963//2963 2962//2962 2964//2964 -f 2963//2963 2964//2964 2958//2958 -f 2958//2958 2964//2964 2965//2965 -f 2958//2958 2965//2965 2959//2959 -f 2966//2966 2967//2967 2968//2968 -f 2968//2968 2967//2967 2969//2969 -f 2968//2968 2969//2969 2961//2961 -f 2961//2961 2969//2969 2962//2962 -f 2949//2949 2970//2970 2951//2951 -f 2951//2951 2970//2970 2971//2971 -f 2951//2951 2971//2971 2966//2966 -f 2966//2966 2971//2971 2967//2967 -f 2923//2923 2972//2972 2934//2934 -f 2934//2934 2972//2972 2973//2973 -f 2934//2934 2973//2973 2939//2939 -f 2939//2939 2973//2973 2974//2974 -f 2939//2939 2974//2974 2937//2937 -f 2937//2937 2974//2974 2975//2975 -f 2937//2937 2975//2975 2944//2944 -f 2944//2944 2975//2975 2976//2976 -f 2944//2944 2976//2976 2942//2942 -f 2942//2942 2976//2976 2977//2977 -f 2942//2942 2977//2977 2927//2927 -f 2927//2927 2977//2977 2978//2978 -f 2927//2927 2978//2978 2926//2926 -f 2926//2926 2978//2978 2979//2979 -f 2926//2926 2979//2979 2928//2928 -f 2928//2928 2979//2979 2980//2980 -f 2928//2928 2980//2980 2930//2930 -f 2930//2930 2980//2980 2981//2981 -f 2930//2930 2981//2981 2932//2932 -f 2932//2932 2981//2981 2982//2982 -f 2932//2932 2982//2982 2922//2922 -f 2922//2922 2982//2982 2983//2983 -f 2922//2922 2983//2983 2923//2923 -f 2923//2923 2983//2983 2972//2972 -f 2972//2972 2920//2920 2973//2973 -f 2973//2973 2920//2920 2919//2919 -f 2973//2973 2919//2919 2974//2974 -f 2974//2974 2919//2919 2956//2956 -f 2974//2974 2956//2956 2975//2975 -f 2975//2975 2956//2956 2954//2954 -f 2975//2975 2954//2954 2976//2976 -f 2976//2976 2954//2954 2952//2952 -f 2976//2976 2952//2952 2977//2977 -f 2977//2977 2952//2952 2950//2950 -f 2977//2977 2950//2950 2978//2978 -f 2978//2978 2950//2950 2951//2951 -f 2978//2978 2951//2951 2979//2979 -f 2979//2979 2951//2951 2966//2966 -f 2979//2979 2966//2966 2980//2980 -f 2980//2980 2966//2966 2968//2968 -f 2980//2980 2968//2968 2981//2981 -f 2981//2981 2968//2968 2961//2961 -f 2981//2981 2961//2961 2982//2982 -f 2982//2982 2961//2961 2963//2963 -f 2982//2982 2963//2963 2983//2983 -f 2983//2983 2963//2963 2958//2958 -f 2983//2983 2958//2958 2972//2972 -f 2972//2972 2958//2958 2920//2920 -f 2984//2984 2985//2985 2986//2986 -f 2987//2987 2988//2988 2989//2989 -f 2990//2990 2991//2991 2992//2992 -f 2992//2992 2991//2991 2993//2993 -f 2990//2990 2992//2992 2994//2994 -f 2990//2990 2994//2994 2995//2995 -f 2995//2995 2994//2994 2996//2996 -f 2995//2995 2996//2996 2997//2997 -f 2988//2988 2987//2987 2998//2998 -f 2998//2998 2987//2987 2999//2999 -f 2998//2998 2999//2999 2996//2996 -f 2996//2996 2999//2999 2997//2997 -f 3000//3000 3001//3001 2989//2989 -f 2989//2989 3001//3001 3002//3002 -f 2989//2989 3002//3002 2987//2987 -f 3003//3003 3004//3004 3005//3005 -f 3005//3005 3004//3004 3006//3006 -f 3005//3005 3006//3006 3000//3000 -f 3000//3000 3006//3006 3007//3007 -f 3000//3000 3007//3007 3001//3001 -f 3008//3008 3009//3009 3010//3010 -f 3010//3010 3009//3009 3011//3011 -f 3010//3010 3011//3011 3003//3003 -f 3003//3003 3011//3011 3004//3004 -f 2991//2991 3012//3012 2993//2993 -f 2993//2993 3012//3012 3013//3013 -f 2993//2993 3013//3013 3008//3008 -f 3008//3008 3013//3013 3009//3009 -f 3014//3014 3015//3015 3016//3016 -f 3016//3016 3015//3015 3017//3017 -f 3014//3014 3016//3016 3018//3018 -f 3014//3014 3018//3018 3019//3019 -f 3019//3019 3018//3018 3020//3020 -f 3019//3019 3020//3020 3021//3021 -f 2985//2985 2984//2984 3022//3022 -f 3022//3022 2984//2984 3023//3023 -f 3022//3022 3023//3023 3020//3020 -f 3020//3020 3023//3023 3021//3021 -f 3024//3024 3025//3025 2986//2986 -f 2986//2986 3025//3025 3026//3026 -f 2986//2986 3026//3026 2984//2984 -f 3027//3027 3028//3028 3029//3029 -f 3029//3029 3028//3028 3030//3030 -f 3029//3029 3030//3030 3024//3024 -f 3024//3024 3030//3030 3031//3031 -f 3024//3024 3031//3031 3025//3025 -f 3032//3032 3033//3033 3034//3034 -f 3034//3034 3033//3033 3035//3035 -f 3034//3034 3035//3035 3027//3027 -f 3027//3027 3035//3035 3028//3028 -f 3015//3015 3036//3036 3017//3017 -f 3017//3017 3036//3036 3037//3037 -f 3017//3017 3037//3037 3032//3032 -f 3032//3032 3037//3037 3033//3033 -f 2989//2989 3038//3038 3000//3000 -f 3000//3000 3038//3038 3039//3039 -f 3000//3000 3039//3039 3005//3005 -f 3005//3005 3039//3039 3040//3040 -f 3005//3005 3040//3040 3003//3003 -f 3003//3003 3040//3040 3041//3041 -f 3003//3003 3041//3041 3010//3010 -f 3010//3010 3041//3041 3042//3042 -f 3010//3010 3042//3042 3008//3008 -f 3008//3008 3042//3042 3043//3043 -f 3008//3008 3043//3043 2993//2993 -f 2993//2993 3043//3043 3044//3044 -f 2993//2993 3044//3044 2992//2992 -f 2992//2992 3044//3044 3045//3045 -f 2992//2992 3045//3045 2994//2994 -f 2994//2994 3045//3045 3046//3046 -f 2994//2994 3046//3046 2996//2996 -f 2996//2996 3046//3046 3047//3047 -f 2996//2996 3047//3047 2998//2998 -f 2998//2998 3047//3047 3048//3048 -f 2998//2998 3048//3048 2988//2988 -f 2988//2988 3048//3048 3049//3049 -f 2988//2988 3049//3049 2989//2989 -f 2989//2989 3049//3049 3038//3038 -f 3038//3038 2986//2986 3039//3039 -f 3039//3039 2986//2986 2985//2985 -f 3039//3039 2985//2985 3040//3040 -f 3040//3040 2985//2985 3022//3022 -f 3040//3040 3022//3022 3041//3041 -f 3041//3041 3022//3022 3020//3020 -f 3041//3041 3020//3020 3042//3042 -f 3042//3042 3020//3020 3018//3018 -f 3042//3042 3018//3018 3043//3043 -f 3043//3043 3018//3018 3016//3016 -f 3043//3043 3016//3016 3044//3044 -f 3044//3044 3016//3016 3017//3017 -f 3044//3044 3017//3017 3045//3045 -f 3045//3045 3017//3017 3032//3032 -f 3045//3045 3032//3032 3046//3046 -f 3046//3046 3032//3032 3034//3034 -f 3046//3046 3034//3034 3047//3047 -f 3047//3047 3034//3034 3027//3027 -f 3047//3047 3027//3027 3048//3048 -f 3048//3048 3027//3027 3029//3029 -f 3048//3048 3029//3029 3049//3049 -f 3049//3049 3029//3029 3024//3024 -f 3049//3049 3024//3024 3038//3038 -f 3038//3038 3024//3024 2986//2986 -f 3050//3050 3051//3051 3052//3052 -f 3053//3053 3054//3054 3055//3055 -f 3056//3056 3057//3057 3058//3058 -f 3058//3058 3057//3057 3059//3059 -f 3056//3056 3058//3058 3060//3060 -f 3056//3056 3060//3060 3061//3061 -f 3061//3061 3060//3060 3062//3062 -f 3061//3061 3062//3062 3063//3063 -f 3054//3054 3053//3053 3064//3064 -f 3064//3064 3053//3053 3065//3065 -f 3064//3064 3065//3065 3062//3062 -f 3062//3062 3065//3065 3063//3063 -f 3066//3066 3067//3067 3055//3055 -f 3055//3055 3067//3067 3068//3068 -f 3055//3055 3068//3068 3053//3053 -f 3069//3069 3070//3070 3071//3071 -f 3071//3071 3070//3070 3072//3072 -f 3071//3071 3072//3072 3066//3066 -f 3066//3066 3072//3072 3073//3073 -f 3066//3066 3073//3073 3067//3067 -f 3074//3074 3075//3075 3076//3076 -f 3076//3076 3075//3075 3077//3077 -f 3076//3076 3077//3077 3069//3069 -f 3069//3069 3077//3077 3070//3070 -f 3057//3057 3078//3078 3059//3059 -f 3059//3059 3078//3078 3079//3079 -f 3059//3059 3079//3079 3074//3074 -f 3074//3074 3079//3079 3075//3075 -f 3080//3080 3081//3081 3082//3082 -f 3082//3082 3081//3081 3083//3083 -f 3080//3080 3082//3082 3084//3084 -f 3080//3080 3084//3084 3085//3085 -f 3085//3085 3084//3084 3086//3086 -f 3085//3085 3086//3086 3087//3087 -f 3051//3051 3050//3050 3088//3088 -f 3088//3088 3050//3050 3089//3089 -f 3088//3088 3089//3089 3086//3086 -f 3086//3086 3089//3089 3087//3087 -f 3090//3090 3091//3091 3052//3052 -f 3052//3052 3091//3091 3092//3092 -f 3052//3052 3092//3092 3050//3050 -f 3093//3093 3094//3094 3095//3095 -f 3095//3095 3094//3094 3096//3096 -f 3095//3095 3096//3096 3090//3090 -f 3090//3090 3096//3096 3097//3097 -f 3090//3090 3097//3097 3091//3091 -f 3098//3098 3099//3099 3100//3100 -f 3100//3100 3099//3099 3101//3101 -f 3100//3100 3101//3101 3093//3093 -f 3093//3093 3101//3101 3094//3094 -f 3081//3081 3102//3102 3083//3083 -f 3083//3083 3102//3102 3103//3103 -f 3083//3083 3103//3103 3098//3098 -f 3098//3098 3103//3103 3099//3099 -f 3055//3055 3104//3104 3066//3066 -f 3066//3066 3104//3104 3105//3105 -f 3066//3066 3105//3105 3071//3071 -f 3071//3071 3105//3105 3106//3106 -f 3071//3071 3106//3106 3069//3069 -f 3069//3069 3106//3106 3107//3107 -f 3069//3069 3107//3107 3076//3076 -f 3076//3076 3107//3107 3108//3108 -f 3076//3076 3108//3108 3074//3074 -f 3074//3074 3108//3108 3109//3109 -f 3074//3074 3109//3109 3059//3059 -f 3059//3059 3109//3109 3110//3110 -f 3059//3059 3110//3110 3058//3058 -f 3058//3058 3110//3110 3111//3111 -f 3058//3058 3111//3111 3060//3060 -f 3060//3060 3111//3111 3112//3112 -f 3060//3060 3112//3112 3062//3062 -f 3062//3062 3112//3112 3113//3113 -f 3062//3062 3113//3113 3064//3064 -f 3064//3064 3113//3113 3114//3114 -f 3064//3064 3114//3114 3054//3054 -f 3054//3054 3114//3114 3115//3115 -f 3054//3054 3115//3115 3055//3055 -f 3055//3055 3115//3115 3104//3104 -f 3104//3104 3052//3052 3105//3105 -f 3105//3105 3052//3052 3051//3051 -f 3105//3105 3051//3051 3106//3106 -f 3106//3106 3051//3051 3088//3088 -f 3106//3106 3088//3088 3107//3107 -f 3107//3107 3088//3088 3086//3086 -f 3107//3107 3086//3086 3108//3108 -f 3108//3108 3086//3086 3084//3084 -f 3108//3108 3084//3084 3109//3109 -f 3109//3109 3084//3084 3082//3082 -f 3109//3109 3082//3082 3110//3110 -f 3110//3110 3082//3082 3083//3083 -f 3110//3110 3083//3083 3111//3111 -f 3111//3111 3083//3083 3098//3098 -f 3111//3111 3098//3098 3112//3112 -f 3112//3112 3098//3098 3100//3100 -f 3112//3112 3100//3100 3113//3113 -f 3113//3113 3100//3100 3093//3093 -f 3113//3113 3093//3093 3114//3114 -f 3114//3114 3093//3093 3095//3095 -f 3114//3114 3095//3095 3115//3115 -f 3115//3115 3095//3095 3090//3090 -f 3115//3115 3090//3090 3104//3104 -f 3104//3104 3090//3090 3052//3052 -f 3116//3116 3117//3117 3118//3118 -f 3119//3119 3120//3120 3121//3121 -f 3122//3122 3123//3123 3124//3124 -f 3124//3124 3123//3123 3125//3125 -f 3122//3122 3124//3124 3126//3126 -f 3122//3122 3126//3126 3127//3127 -f 3127//3127 3126//3126 3128//3128 -f 3127//3127 3128//3128 3129//3129 -f 3120//3120 3119//3119 3130//3130 -f 3130//3130 3119//3119 3131//3131 -f 3130//3130 3131//3131 3128//3128 -f 3128//3128 3131//3131 3129//3129 -f 3132//3132 3133//3133 3121//3121 -f 3121//3121 3133//3133 3134//3134 -f 3121//3121 3134//3134 3119//3119 -f 3135//3135 3136//3136 3137//3137 -f 3137//3137 3136//3136 3138//3138 -f 3137//3137 3138//3138 3132//3132 -f 3132//3132 3138//3138 3139//3139 -f 3132//3132 3139//3139 3133//3133 -f 3140//3140 3141//3141 3142//3142 -f 3142//3142 3141//3141 3143//3143 -f 3142//3142 3143//3143 3135//3135 -f 3135//3135 3143//3143 3136//3136 -f 3123//3123 3144//3144 3125//3125 -f 3125//3125 3144//3144 3145//3145 -f 3125//3125 3145//3145 3140//3140 -f 3140//3140 3145//3145 3141//3141 -f 3146//3146 3147//3147 3148//3148 -f 3148//3148 3147//3147 3149//3149 -f 3146//3146 3148//3148 3150//3150 -f 3146//3146 3150//3150 3151//3151 -f 3151//3151 3150//3150 3152//3152 -f 3151//3151 3152//3152 3153//3153 -f 3117//3117 3116//3116 3154//3154 -f 3154//3154 3116//3116 3155//3155 -f 3154//3154 3155//3155 3152//3152 -f 3152//3152 3155//3155 3153//3153 -f 3156//3156 3157//3157 3118//3118 -f 3118//3118 3157//3157 3158//3158 -f 3118//3118 3158//3158 3116//3116 -f 3159//3159 3160//3160 3161//3161 -f 3161//3161 3160//3160 3162//3162 -f 3161//3161 3162//3162 3156//3156 -f 3156//3156 3162//3162 3163//3163 -f 3156//3156 3163//3163 3157//3157 -f 3164//3164 3165//3165 3166//3166 -f 3166//3166 3165//3165 3167//3167 -f 3166//3166 3167//3167 3159//3159 -f 3159//3159 3167//3167 3160//3160 -f 3147//3147 3168//3168 3149//3149 -f 3149//3149 3168//3168 3169//3169 -f 3149//3149 3169//3169 3164//3164 -f 3164//3164 3169//3169 3165//3165 -f 3121//3121 3170//3170 3132//3132 -f 3132//3132 3170//3170 3171//3171 -f 3132//3132 3171//3171 3137//3137 -f 3137//3137 3171//3171 3172//3172 -f 3137//3137 3172//3172 3135//3135 -f 3135//3135 3172//3172 3173//3173 -f 3135//3135 3173//3173 3142//3142 -f 3142//3142 3173//3173 3174//3174 -f 3142//3142 3174//3174 3140//3140 -f 3140//3140 3174//3174 3175//3175 -f 3140//3140 3175//3175 3125//3125 -f 3125//3125 3175//3175 3176//3176 -f 3125//3125 3176//3176 3124//3124 -f 3124//3124 3176//3176 3177//3177 -f 3124//3124 3177//3177 3126//3126 -f 3126//3126 3177//3177 3178//3178 -f 3126//3126 3178//3178 3128//3128 -f 3128//3128 3178//3178 3179//3179 -f 3128//3128 3179//3179 3130//3130 -f 3130//3130 3179//3179 3180//3180 -f 3130//3130 3180//3180 3120//3120 -f 3120//3120 3180//3180 3181//3181 -f 3120//3120 3181//3181 3121//3121 -f 3121//3121 3181//3181 3170//3170 -f 3170//3170 3118//3118 3171//3171 -f 3171//3171 3118//3118 3117//3117 -f 3171//3171 3117//3117 3172//3172 -f 3172//3172 3117//3117 3154//3154 -f 3172//3172 3154//3154 3173//3173 -f 3173//3173 3154//3154 3152//3152 -f 3173//3173 3152//3152 3174//3174 -f 3174//3174 3152//3152 3150//3150 -f 3174//3174 3150//3150 3175//3175 -f 3175//3175 3150//3150 3148//3148 -f 3175//3175 3148//3148 3176//3176 -f 3176//3176 3148//3148 3149//3149 -f 3176//3176 3149//3149 3177//3177 -f 3177//3177 3149//3149 3164//3164 -f 3177//3177 3164//3164 3178//3178 -f 3178//3178 3164//3164 3166//3166 -f 3178//3178 3166//3166 3179//3179 -f 3179//3179 3166//3166 3159//3159 -f 3179//3179 3159//3159 3180//3180 -f 3180//3180 3159//3159 3161//3161 -f 3180//3180 3161//3161 3181//3181 -f 3181//3181 3161//3161 3156//3156 -f 3181//3181 3156//3156 3170//3170 -f 3170//3170 3156//3156 3118//3118 -f 3182//3182 3183//3183 3184//3184 -f 3185//3185 3186//3186 3187//3187 -f 3188//3188 3189//3189 3190//3190 -f 3190//3190 3189//3189 3191//3191 -f 3188//3188 3190//3190 3192//3192 -f 3188//3188 3192//3192 3193//3193 -f 3193//3193 3192//3192 3194//3194 -f 3193//3193 3194//3194 3195//3195 -f 3186//3186 3185//3185 3196//3196 -f 3196//3196 3185//3185 3197//3197 -f 3196//3196 3197//3197 3194//3194 -f 3194//3194 3197//3197 3195//3195 -f 3198//3198 3199//3199 3187//3187 -f 3187//3187 3199//3199 3200//3200 -f 3187//3187 3200//3200 3185//3185 -f 3201//3201 3202//3202 3203//3203 -f 3203//3203 3202//3202 3204//3204 -f 3203//3203 3204//3204 3198//3198 -f 3198//3198 3204//3204 3205//3205 -f 3198//3198 3205//3205 3199//3199 -f 3206//3206 3207//3207 3208//3208 -f 3208//3208 3207//3207 3209//3209 -f 3208//3208 3209//3209 3201//3201 -f 3201//3201 3209//3209 3202//3202 -f 3189//3189 3210//3210 3191//3191 -f 3191//3191 3210//3210 3211//3211 -f 3191//3191 3211//3211 3206//3206 -f 3206//3206 3211//3211 3207//3207 -f 3212//3212 3213//3213 3214//3214 -f 3214//3214 3213//3213 3215//3215 -f 3212//3212 3214//3214 3216//3216 -f 3212//3212 3216//3216 3217//3217 -f 3217//3217 3216//3216 3218//3218 -f 3217//3217 3218//3218 3219//3219 -f 3183//3183 3182//3182 3220//3220 -f 3220//3220 3182//3182 3221//3221 -f 3220//3220 3221//3221 3218//3218 -f 3218//3218 3221//3221 3219//3219 -f 3222//3222 3223//3223 3184//3184 -f 3184//3184 3223//3223 3224//3224 -f 3184//3184 3224//3224 3182//3182 -f 3225//3225 3226//3226 3227//3227 -f 3227//3227 3226//3226 3228//3228 -f 3227//3227 3228//3228 3222//3222 -f 3222//3222 3228//3228 3229//3229 -f 3222//3222 3229//3229 3223//3223 -f 3230//3230 3231//3231 3232//3232 -f 3232//3232 3231//3231 3233//3233 -f 3232//3232 3233//3233 3225//3225 -f 3225//3225 3233//3233 3226//3226 -f 3213//3213 3234//3234 3215//3215 -f 3215//3215 3234//3234 3235//3235 -f 3215//3215 3235//3235 3230//3230 -f 3230//3230 3235//3235 3231//3231 -f 3187//3187 3236//3236 3198//3198 -f 3198//3198 3236//3236 3237//3237 -f 3198//3198 3237//3237 3203//3203 -f 3203//3203 3237//3237 3238//3238 -f 3203//3203 3238//3238 3201//3201 -f 3201//3201 3238//3238 3239//3239 -f 3201//3201 3239//3239 3208//3208 -f 3208//3208 3239//3239 3240//3240 -f 3208//3208 3240//3240 3206//3206 -f 3206//3206 3240//3240 3241//3241 -f 3206//3206 3241//3241 3191//3191 -f 3191//3191 3241//3241 3242//3242 -f 3191//3191 3242//3242 3190//3190 -f 3190//3190 3242//3242 3243//3243 -f 3190//3190 3243//3243 3192//3192 -f 3192//3192 3243//3243 3244//3244 -f 3192//3192 3244//3244 3194//3194 -f 3194//3194 3244//3244 3245//3245 -f 3194//3194 3245//3245 3196//3196 -f 3196//3196 3245//3245 3246//3246 -f 3196//3196 3246//3246 3186//3186 -f 3186//3186 3246//3246 3247//3247 -f 3186//3186 3247//3247 3187//3187 -f 3187//3187 3247//3247 3236//3236 -f 3236//3236 3184//3184 3237//3237 -f 3237//3237 3184//3184 3183//3183 -f 3237//3237 3183//3183 3238//3238 -f 3238//3238 3183//3183 3220//3220 -f 3238//3238 3220//3220 3239//3239 -f 3239//3239 3220//3220 3218//3218 -f 3239//3239 3218//3218 3240//3240 -f 3240//3240 3218//3218 3216//3216 -f 3240//3240 3216//3216 3241//3241 -f 3241//3241 3216//3216 3214//3214 -f 3241//3241 3214//3214 3242//3242 -f 3242//3242 3214//3214 3215//3215 -f 3242//3242 3215//3215 3243//3243 -f 3243//3243 3215//3215 3230//3230 -f 3243//3243 3230//3230 3244//3244 -f 3244//3244 3230//3230 3232//3232 -f 3244//3244 3232//3232 3245//3245 -f 3245//3245 3232//3232 3225//3225 -f 3245//3245 3225//3225 3246//3246 -f 3246//3246 3225//3225 3227//3227 -f 3246//3246 3227//3227 3247//3247 -f 3247//3247 3227//3227 3222//3222 -f 3247//3247 3222//3222 3236//3236 -f 3236//3236 3222//3222 3184//3184 -f 3248//3248 3249//3249 3250//3250 -f 3251//3251 3252//3252 3253//3253 -f 3254//3254 3255//3255 3256//3256 -f 3256//3256 3255//3255 3257//3257 -f 3254//3254 3256//3256 3258//3258 -f 3254//3254 3258//3258 3259//3259 -f 3259//3259 3258//3258 3260//3260 -f 3259//3259 3260//3260 3261//3261 -f 3252//3252 3251//3251 3262//3262 -f 3262//3262 3251//3251 3263//3263 -f 3262//3262 3263//3263 3260//3260 -f 3260//3260 3263//3263 3261//3261 -f 3264//3264 3265//3265 3253//3253 -f 3253//3253 3265//3265 3266//3266 -f 3253//3253 3266//3266 3251//3251 -f 3267//3267 3268//3268 3269//3269 -f 3269//3269 3268//3268 3270//3270 -f 3269//3269 3270//3270 3264//3264 -f 3264//3264 3270//3270 3271//3271 -f 3264//3264 3271//3271 3265//3265 -f 3272//3272 3273//3273 3274//3274 -f 3274//3274 3273//3273 3275//3275 -f 3274//3274 3275//3275 3267//3267 -f 3267//3267 3275//3275 3268//3268 -f 3255//3255 3276//3276 3257//3257 -f 3257//3257 3276//3276 3277//3277 -f 3257//3257 3277//3277 3272//3272 -f 3272//3272 3277//3277 3273//3273 -f 3278//3278 3279//3279 3280//3280 -f 3280//3280 3279//3279 3281//3281 -f 3278//3278 3280//3280 3282//3282 -f 3278//3278 3282//3282 3283//3283 -f 3283//3283 3282//3282 3284//3284 -f 3283//3283 3284//3284 3285//3285 -f 3249//3249 3248//3248 3286//3286 -f 3286//3286 3248//3248 3287//3287 -f 3286//3286 3287//3287 3284//3284 -f 3284//3284 3287//3287 3285//3285 -f 3288//3288 3289//3289 3250//3250 -f 3250//3250 3289//3289 3290//3290 -f 3250//3250 3290//3290 3248//3248 -f 3291//3291 3292//3292 3293//3293 -f 3293//3293 3292//3292 3294//3294 -f 3293//3293 3294//3294 3288//3288 -f 3288//3288 3294//3294 3295//3295 -f 3288//3288 3295//3295 3289//3289 -f 3296//3296 3297//3297 3298//3298 -f 3298//3298 3297//3297 3299//3299 -f 3298//3298 3299//3299 3291//3291 -f 3291//3291 3299//3299 3292//3292 -f 3279//3279 3300//3300 3281//3281 -f 3281//3281 3300//3300 3301//3301 -f 3281//3281 3301//3301 3296//3296 -f 3296//3296 3301//3301 3297//3297 -f 3253//3253 3302//3302 3264//3264 -f 3264//3264 3302//3302 3303//3303 -f 3264//3264 3303//3303 3269//3269 -f 3269//3269 3303//3303 3304//3304 -f 3269//3269 3304//3304 3267//3267 -f 3267//3267 3304//3304 3305//3305 -f 3267//3267 3305//3305 3274//3274 -f 3274//3274 3305//3305 3306//3306 -f 3274//3274 3306//3306 3272//3272 -f 3272//3272 3306//3306 3307//3307 -f 3272//3272 3307//3307 3257//3257 -f 3257//3257 3307//3307 3308//3308 -f 3257//3257 3308//3308 3256//3256 -f 3256//3256 3308//3308 3309//3309 -f 3256//3256 3309//3309 3258//3258 -f 3258//3258 3309//3309 3310//3310 -f 3258//3258 3310//3310 3260//3260 -f 3260//3260 3310//3310 3311//3311 -f 3260//3260 3311//3311 3262//3262 -f 3262//3262 3311//3311 3312//3312 -f 3262//3262 3312//3312 3252//3252 -f 3252//3252 3312//3312 3313//3313 -f 3252//3252 3313//3313 3253//3253 -f 3253//3253 3313//3313 3302//3302 -f 3302//3302 3250//3250 3303//3303 -f 3303//3303 3250//3250 3249//3249 -f 3303//3303 3249//3249 3304//3304 -f 3304//3304 3249//3249 3286//3286 -f 3304//3304 3286//3286 3305//3305 -f 3305//3305 3286//3286 3284//3284 -f 3305//3305 3284//3284 3306//3306 -f 3306//3306 3284//3284 3282//3282 -f 3306//3306 3282//3282 3307//3307 -f 3307//3307 3282//3282 3280//3280 -f 3307//3307 3280//3280 3308//3308 -f 3308//3308 3280//3280 3281//3281 -f 3308//3308 3281//3281 3309//3309 -f 3309//3309 3281//3281 3296//3296 -f 3309//3309 3296//3296 3310//3310 -f 3310//3310 3296//3296 3298//3298 -f 3310//3310 3298//3298 3311//3311 -f 3311//3311 3298//3298 3291//3291 -f 3311//3311 3291//3291 3312//3312 -f 3312//3312 3291//3291 3293//3293 -f 3312//3312 3293//3293 3313//3313 -f 3313//3313 3293//3293 3288//3288 -f 3313//3313 3288//3288 3302//3302 -f 3302//3302 3288//3288 3250//3250 -f 3314//3314 3315//3315 3316//3316 -f 3317//3317 3318//3318 3319//3319 -f 3320//3320 3321//3321 3322//3322 -f 3322//3322 3321//3321 3323//3323 -f 3320//3320 3322//3322 3324//3324 -f 3320//3320 3324//3324 3325//3325 -f 3325//3325 3324//3324 3326//3326 -f 3325//3325 3326//3326 3327//3327 -f 3318//3318 3317//3317 3328//3328 -f 3328//3328 3317//3317 3329//3329 -f 3328//3328 3329//3329 3326//3326 -f 3326//3326 3329//3329 3327//3327 -f 3330//3330 3331//3331 3319//3319 -f 3319//3319 3331//3331 3332//3332 -f 3319//3319 3332//3332 3317//3317 -f 3333//3333 3334//3334 3335//3335 -f 3335//3335 3334//3334 3336//3336 -f 3335//3335 3336//3336 3330//3330 -f 3330//3330 3336//3336 3337//3337 -f 3330//3330 3337//3337 3331//3331 -f 3338//3338 3339//3339 3340//3340 -f 3340//3340 3339//3339 3341//3341 -f 3340//3340 3341//3341 3333//3333 -f 3333//3333 3341//3341 3334//3334 -f 3321//3321 3342//3342 3323//3323 -f 3323//3323 3342//3342 3343//3343 -f 3323//3323 3343//3343 3338//3338 -f 3338//3338 3343//3343 3339//3339 -f 3344//3344 3345//3345 3346//3346 -f 3346//3346 3345//3345 3347//3347 -f 3344//3344 3346//3346 3348//3348 -f 3344//3344 3348//3348 3349//3349 -f 3349//3349 3348//3348 3350//3350 -f 3349//3349 3350//3350 3351//3351 -f 3315//3315 3314//3314 3352//3352 -f 3352//3352 3314//3314 3353//3353 -f 3352//3352 3353//3353 3350//3350 -f 3350//3350 3353//3353 3351//3351 -f 3354//3354 3355//3355 3316//3316 -f 3316//3316 3355//3355 3356//3356 -f 3316//3316 3356//3356 3314//3314 -f 3357//3357 3358//3358 3359//3359 -f 3359//3359 3358//3358 3360//3360 -f 3359//3359 3360//3360 3354//3354 -f 3354//3354 3360//3360 3361//3361 -f 3354//3354 3361//3361 3355//3355 -f 3362//3362 3363//3363 3364//3364 -f 3364//3364 3363//3363 3365//3365 -f 3364//3364 3365//3365 3357//3357 -f 3357//3357 3365//3365 3358//3358 -f 3345//3345 3366//3366 3347//3347 -f 3347//3347 3366//3366 3367//3367 -f 3347//3347 3367//3367 3362//3362 -f 3362//3362 3367//3367 3363//3363 -f 3319//3319 3368//3368 3330//3330 -f 3330//3330 3368//3368 3369//3369 -f 3330//3330 3369//3369 3335//3335 -f 3335//3335 3369//3369 3370//3370 -f 3335//3335 3370//3370 3333//3333 -f 3333//3333 3370//3370 3371//3371 -f 3333//3333 3371//3371 3340//3340 -f 3340//3340 3371//3371 3372//3372 -f 3340//3340 3372//3372 3338//3338 -f 3338//3338 3372//3372 3373//3373 -f 3338//3338 3373//3373 3323//3323 -f 3323//3323 3373//3373 3374//3374 -f 3323//3323 3374//3374 3322//3322 -f 3322//3322 3374//3374 3375//3375 -f 3322//3322 3375//3375 3324//3324 -f 3324//3324 3375//3375 3376//3376 -f 3324//3324 3376//3376 3326//3326 -f 3326//3326 3376//3376 3377//3377 -f 3326//3326 3377//3377 3328//3328 -f 3328//3328 3377//3377 3378//3378 -f 3328//3328 3378//3378 3318//3318 -f 3318//3318 3378//3378 3379//3379 -f 3318//3318 3379//3379 3319//3319 -f 3319//3319 3379//3379 3368//3368 -f 3368//3368 3316//3316 3369//3369 -f 3369//3369 3316//3316 3315//3315 -f 3369//3369 3315//3315 3370//3370 -f 3370//3370 3315//3315 3352//3352 -f 3370//3370 3352//3352 3371//3371 -f 3371//3371 3352//3352 3350//3350 -f 3371//3371 3350//3350 3372//3372 -f 3372//3372 3350//3350 3348//3348 -f 3372//3372 3348//3348 3373//3373 -f 3373//3373 3348//3348 3346//3346 -f 3373//3373 3346//3346 3374//3374 -f 3374//3374 3346//3346 3347//3347 -f 3374//3374 3347//3347 3375//3375 -f 3375//3375 3347//3347 3362//3362 -f 3375//3375 3362//3362 3376//3376 -f 3376//3376 3362//3362 3364//3364 -f 3376//3376 3364//3364 3377//3377 -f 3377//3377 3364//3364 3357//3357 -f 3377//3377 3357//3357 3378//3378 -f 3378//3378 3357//3357 3359//3359 -f 3378//3378 3359//3359 3379//3379 -f 3379//3379 3359//3359 3354//3354 -f 3379//3379 3354//3354 3368//3368 -f 3368//3368 3354//3354 3316//3316 -f 3380//3380 3381//3381 3382//3382 -f 3383//3383 3384//3384 3382//3382 -f 3385//3385 3386//3386 3387//3387 -f 3387//3387 3386//3386 3388//3388 -f 3389//3389 3388//3388 3386//3386 -f 2959//2959 2965//2965 3390//3390 -f 3390//3390 2965//2965 2964//2964 -f 3390//3390 2964//2964 2962//2962 -f 3388//3388 2967//2967 2971//2971 -f 2969//2969 2967//2967 3388//3388 -f 2962//2962 2969//2969 3390//3390 -f 3390//3390 2969//2969 3388//3388 -f 3388//3388 2970//2970 2949//2949 -f 2971//2971 2970//2970 3388//3388 -f 3388//3388 2948//2948 2953//2953 -f 2949//2949 2948//2948 3388//3388 -f 3388//3388 2953//2953 2955//2955 -f 3388//3388 2955//2955 3391//3391 -f 3391//3391 2955//2955 2957//2957 -f 2957//2957 2918//2918 3391//3391 -f 3391//3391 2918//2918 2960//2960 -f 3392//3392 3393//3393 3394//3394 -f 3389//3389 3386//3386 3395//3395 -f 3395//3395 3386//3386 3385//3385 -f 3395//3395 3385//3385 3396//3396 -f 3397//3397 3388//3388 3389//3389 -f 3397//3397 3389//3389 3398//3398 -f 3398//3398 3389//3389 3395//3395 -f 3398//3398 3395//3395 3399//3399 -f 3399//3399 3395//3395 3396//3396 -f 3399//3399 3396//3396 3400//3400 -f 3401//3401 3388//3388 3397//3397 -f 3401//3401 3397//3397 3402//3402 -f 3402//3402 3397//3397 3398//3398 -f 3402//3402 3398//3398 3403//3403 -f 3403//3403 3398//3398 3399//3399 -f 3403//3403 3399//3399 3404//3404 -f 3404//3404 3399//3399 3400//3400 -f 3404//3404 3400//3400 3405//3405 -f 3406//3406 3388//3388 3401//3401 -f 3406//3406 3401//3401 3407//3407 -f 3407//3407 3401//3401 3402//3402 -f 3407//3407 3402//3402 3408//3408 -f 3408//3408 3402//3402 3403//3403 -f 3408//3408 3403//3403 3409//3409 -f 3409//3409 3403//3403 3404//3404 -f 3409//3409 3404//3404 3410//3410 -f 3410//3410 3404//3404 3405//3405 -f 3410//3410 3405//3405 3411//3411 -f 3412//3412 3388//3388 3406//3406 -f 3412//3412 3406//3406 3413//3413 -f 3413//3413 3406//3406 3407//3407 -f 3413//3413 3407//3407 3414//3414 -f 3414//3414 3407//3407 3408//3408 -f 3414//3414 3408//3408 3415//3415 -f 3415//3415 3408//3408 3409//3409 -f 3415//3415 3409//3409 3416//3416 -f 3416//3416 3409//3409 3410//3410 -f 3416//3416 3410//3410 3417//3417 -f 3417//3417 3410//3410 3411//3411 -f 3417//3417 3411//3411 3418//3418 -f 3419//3419 3388//3388 3412//3412 -f 3388//3388 3420//3420 3421//3421 -f 3421//3421 3420//3420 3422//3422 -f 3421//3421 3422//3422 3423//3423 -f 3423//3423 3422//3422 3424//3424 -f 3423//3423 3424//3424 3425//3425 -f 3425//3425 3424//3424 3426//3426 -f 3425//3425 3426//3426 3427//3427 -f 3427//3427 3426//3426 3428//3428 -f 3427//3427 3428//3428 3429//3429 -f 3429//3429 3428//3428 3430//3430 -f 3429//3429 3430//3430 3431//3431 -f 3432//3432 3430//3430 3433//3433 -f 3433//3433 3430//3430 3428//3428 -f 3433//3433 3428//3428 3434//3434 -f 3434//3434 3428//3428 3426//3426 -f 3434//3434 3426//3426 3435//3435 -f 3435//3435 3426//3426 3424//3424 -f 3435//3435 3424//3424 3436//3436 -f 3436//3436 3424//3424 3422//3422 -f 3436//3436 3422//3422 3437//3437 -f 3437//3437 3422//3422 3420//3420 -f 3437//3437 3420//3420 3438//3438 -f 3438//3438 3420//3420 3388//3388 -f 3439//3439 3440//3440 3441//3441 -f 3419//3419 3412//3412 3442//3442 -f 3442//3442 3412//3412 3413//3413 -f 3442//3442 3413//3413 3443//3443 -f 3443//3443 3413//3413 3414//3414 -f 3443//3443 3414//3414 3444//3444 -f 3444//3444 3414//3414 3415//3415 -f 3444//3444 3415//3415 3445//3445 -f 3445//3445 3415//3415 3416//3416 -f 3445//3445 3416//3416 3446//3446 -f 3446//3446 3416//3416 3417//3417 -f 3446//3446 3417//3417 3447//3447 -f 3447//3447 3417//3417 3418//3418 -f 3447//3447 3418//3418 3448//3448 -f 3449//3449 3388//3388 3419//3419 -f 3431//3431 3450//3450 3451//3451 -f 3452//3452 3432//3432 3453//3453 -f 3453//3453 3432//3432 3433//3433 -f 3453//3453 3433//3433 3454//3454 -f 3454//3454 3433//3433 3434//3434 -f 3454//3454 3434//3434 3455//3455 -f 3455//3455 3434//3434 3435//3435 -f 3455//3455 3435//3435 3456//3456 -f 3456//3456 3435//3435 3436//3436 -f 3456//3456 3436//3436 3457//3457 -f 3457//3457 3436//3436 3437//3437 -f 3457//3457 3437//3437 3458//3458 -f 3458//3458 3437//3437 3438//3438 -f 3458//3458 3438//3438 3459//3459 -f 3459//3459 3438//3438 3388//3388 -f 3449//3449 3419//3419 3460//3460 -f 3460//3460 3419//3419 3442//3442 -f 3460//3460 3442//3442 3461//3461 -f 3461//3461 3442//3442 3443//3443 -f 3461//3461 3443//3443 3462//3462 -f 3462//3462 3443//3443 3444//3444 -f 3462//3462 3444//3444 3463//3463 -f 3463//3463 3444//3444 3445//3445 -f 3463//3463 3445//3445 3464//3464 -f 3464//3464 3445//3445 3446//3446 -f 3464//3464 3446//3446 3465//3465 -f 3465//3465 3446//3446 3447//3447 -f 3465//3465 3447//3447 3466//3466 -f 3466//3466 3447//3447 3448//3448 -f 3466//3466 3448//3448 3467//3467 -f 3468//3468 3388//3388 3449//3449 -f 3451//3451 3469//3469 3470//3470 -f 3471//3471 3452//3452 3472//3472 -f 3472//3472 3452//3452 3453//3453 -f 3472//3472 3453//3453 3473//3473 -f 3473//3473 3453//3453 3454//3454 -f 3473//3473 3454//3454 3474//3474 -f 3474//3474 3454//3454 3455//3455 -f 3474//3474 3455//3455 3475//3475 -f 3475//3475 3455//3455 3456//3456 -f 3475//3475 3456//3456 3476//3476 -f 3476//3476 3456//3456 3457//3457 -f 3476//3476 3457//3457 3477//3477 -f 3477//3477 3457//3457 3458//3458 -f 3477//3477 3458//3458 3478//3478 -f 3478//3478 3458//3458 3459//3459 -f 3478//3478 3459//3459 3479//3479 -f 3479//3479 3459//3459 3388//3388 -f 3480//3480 3481//3481 3482//3482 -f 3468//3468 3449//3449 3483//3483 -f 3483//3483 3449//3449 3460//3460 -f 3483//3483 3460//3460 3484//3484 -f 3484//3484 3460//3460 3461//3461 -f 3484//3484 3461//3461 3485//3485 -f 3485//3485 3461//3461 3462//3462 -f 3485//3485 3462//3462 3486//3486 -f 3486//3486 3462//3462 3463//3463 -f 3486//3486 3463//3463 3487//3487 -f 3487//3487 3463//3463 3464//3464 -f 3487//3487 3464//3464 3488//3488 -f 3488//3488 3464//3464 3465//3465 -f 3488//3488 3465//3465 3489//3489 -f 3489//3489 3465//3465 3466//3466 -f 3489//3489 3466//3466 3490//3490 -f 3490//3490 3466//3466 3467//3467 -f 3490//3490 3467//3467 3491//3491 -f 3492//3492 3388//3388 3468//3468 -f 3470//3470 3493//3493 3494//3494 -f 3495//3495 3471//3471 3496//3496 -f 3496//3496 3471//3471 3472//3472 -f 3496//3496 3472//3472 3497//3497 -f 3497//3497 3472//3472 3473//3473 -f 3497//3497 3473//3473 3498//3498 -f 3498//3498 3473//3473 3474//3474 -f 3498//3498 3474//3474 3499//3499 -f 3499//3499 3474//3474 3475//3475 -f 3499//3499 3475//3475 3500//3500 -f 3500//3500 3475//3475 3476//3476 -f 3500//3500 3476//3476 3501//3501 -f 3501//3501 3476//3476 3477//3477 -f 3501//3501 3477//3477 3502//3502 -f 3502//3502 3477//3477 3478//3478 -f 3502//3502 3478//3478 3503//3503 -f 3503//3503 3478//3478 3479//3479 -f 3503//3503 3479//3479 3504//3504 -f 3504//3504 3479//3479 3388//3388 -f 3482//3482 3505//3505 3506//3506 -f 3492//3492 3468//3468 3507//3507 -f 3507//3507 3468//3468 3483//3483 -f 3507//3507 3483//3483 3508//3508 -f 3508//3508 3483//3483 3484//3484 -f 3508//3508 3484//3484 3509//3509 -f 3509//3509 3484//3484 3485//3485 -f 3509//3509 3485//3485 3510//3510 -f 3510//3510 3485//3485 3486//3486 -f 3510//3510 3486//3486 3511//3511 -f 3511//3511 3486//3486 3487//3487 -f 3511//3511 3487//3487 3512//3512 -f 3512//3512 3487//3487 3488//3488 -f 3512//3512 3488//3488 3513//3513 -f 3513//3513 3488//3488 3489//3489 -f 3513//3513 3489//3489 3514//3514 -f 3514//3514 3489//3489 3490//3490 -f 3514//3514 3490//3490 3515//3515 -f 3515//3515 3490//3490 3491//3491 -f 3515//3515 3491//3491 3516//3516 -f 3517//3517 3388//3388 3492//3492 -f 3494//3494 3518//3518 3519//3519 -f 3520//3520 3495//3495 3521//3521 -f 3521//3521 3495//3495 3496//3496 -f 3521//3521 3496//3496 3522//3522 -f 3522//3522 3496//3496 3497//3497 -f 3522//3522 3497//3497 3523//3523 -f 3523//3523 3497//3497 3498//3498 -f 3523//3523 3498//3498 3524//3524 -f 3524//3524 3498//3498 3499//3499 -f 3524//3524 3499//3499 3525//3525 -f 3525//3525 3499//3499 3500//3500 -f 3525//3525 3500//3500 3526//3526 -f 3526//3526 3500//3500 3501//3501 -f 3526//3526 3501//3501 3527//3527 -f 3527//3527 3501//3501 3502//3502 -f 3527//3527 3502//3502 3528//3528 -f 3528//3528 3502//3502 3503//3503 -f 3528//3528 3503//3503 3529//3529 -f 3529//3529 3503//3503 3504//3504 -f 3529//3529 3504//3504 3530//3530 -f 3530//3530 3504//3504 3388//3388 -f 3506//3506 3531//3531 3532//3532 -f 3519//3519 3533//3533 3534//3534 -f 3535//3535 3520//3520 3536//3536 -f 3536//3536 3520//3520 3521//3521 -f 3536//3536 3521//3521 3537//3537 -f 3537//3537 3521//3521 3522//3522 -f 3537//3537 3522//3522 3538//3538 -f 3538//3538 3522//3522 3523//3523 -f 3538//3538 3523//3523 3539//3539 -f 3539//3539 3523//3523 3524//3524 -f 3539//3539 3524//3524 3540//3540 -f 3540//3540 3524//3524 3525//3525 -f 3540//3540 3525//3525 3541//3541 -f 3541//3541 3525//3525 3526//3526 -f 3541//3541 3526//3526 3542//3542 -f 3542//3542 3526//3526 3527//3527 -f 3542//3542 3527//3527 3543//3543 -f 3543//3543 3527//3527 3528//3528 -f 3543//3543 3528//3528 3544//3544 -f 3544//3544 3528//3528 3529//3529 -f 3544//3544 3529//3529 3545//3545 -f 3545//3545 3529//3529 3530//3530 -f 3545//3545 3530//3530 3546//3546 -f 3546//3546 3530//3530 3388//3388 -f 3547//3547 3548//3548 3549//3549 -f 3549//3549 3548//3548 3550//3550 -f 3549//3549 3550//3550 3551//3551 -f 3551//3551 3550//3550 3552//3552 -f 3551//3551 3552//3552 3553//3553 -f 3553//3553 3552//3552 3554//3554 -f 3553//3553 3554//3554 3555//3555 -f 3555//3555 3554//3554 3556//3556 -f 3555//3555 3556//3556 3557//3557 -f 3557//3557 3556//3556 3558//3558 -f 3557//3557 3558//3558 3559//3559 -f 3559//3559 3558//3558 3560//3560 -f 3559//3559 3560//3560 3561//3561 -f 3561//3561 3560//3560 3562//3562 -f 3561//3561 3562//3562 3563//3563 -f 3384//3384 3383//3383 3532//3532 -f 3532//3532 3531//3531 3384//3384 -f 3384//3384 3531//3531 3564//3564 -f 3384//3384 3564//3564 3382//3382 -f 3506//3506 3505//3505 3531//3531 -f 3531//3531 3505//3505 3565//3565 -f 3531//3531 3565//3565 3564//3564 -f 3564//3564 3565//3565 3566//3566 -f 3564//3564 3566//3566 3382//3382 -f 3482//3482 3481//3481 3505//3505 -f 3505//3505 3481//3481 3567//3567 -f 3505//3505 3567//3567 3565//3565 -f 3565//3565 3567//3567 3568//3568 -f 3565//3565 3568//3568 3566//3566 -f 3566//3566 3568//3568 3569//3569 -f 3566//3566 3569//3569 3382//3382 -f 3570//3570 3569//3569 3571//3571 -f 3571//3571 3569//3569 3568//3568 -f 3571//3571 3568//3568 3572//3572 -f 3572//3572 3568//3568 3567//3567 -f 3572//3572 3567//3567 3573//3573 -f 3573//3573 3567//3567 3481//3481 -f 3573//3573 3481//3481 3574//3574 -f 3574//3574 3481//3481 3480//3480 -f 3574//3574 3480//3480 3441//3441 -f 3441//3441 3440//3440 3574//3574 -f 3574//3574 3440//3440 3575//3575 -f 3574//3574 3575//3575 3573//3573 -f 3573//3573 3575//3575 3576//3576 -f 3573//3573 3576//3576 3572//3572 -f 3572//3572 3576//3576 3577//3577 -f 3572//3572 3577//3577 3571//3571 -f 3571//3571 3577//3577 3578//3578 -f 3571//3571 3578//3578 3570//3570 -f 3570//3570 3578//3578 3579//3579 -f 3570//3570 3579//3579 3382//3382 -f 3392//3392 3517//3517 3393//3393 -f 3393//3393 3517//3517 3580//3580 -f 3393//3393 3580//3580 3581//3581 -f 3581//3581 3580//3580 3582//3582 -f 3581//3581 3582//3582 3583//3583 -f 3583//3583 3582//3582 3584//3584 -f 3583//3583 3584//3584 3585//3585 -f 3585//3585 3584//3584 3586//3586 -f 3585//3585 3586//3586 3587//3587 -f 3587//3587 3586//3586 3588//3588 -f 3587//3587 3588//3588 3589//3589 -f 3589//3589 3588//3588 3590//3590 -f 3589//3589 3590//3590 3591//3591 -f 3591//3591 3590//3590 3592//3592 -f 3591//3591 3592//3592 3593//3593 -f 3593//3593 3592//3592 3594//3594 -f 3593//3593 3594//3594 3595//3595 -f 3595//3595 3594//3594 3596//3596 -f 3595//3595 3596//3596 3597//3597 -f 3597//3597 3596//3596 3598//3598 -f 3597//3597 3598//3598 3599//3599 -f 3599//3599 3598//3598 3600//3600 -f 3599//3599 3600//3600 3382//3382 -f 3382//3382 3601//3601 3602//3602 -f 3602//3602 3601//3601 3603//3603 -f 3602//3602 3603//3603 3604//3604 -f 3604//3604 3603//3603 3605//3605 -f 3604//3604 3605//3605 3606//3606 -f 3606//3606 3605//3605 3607//3607 -f 3606//3606 3607//3607 3608//3608 -f 3608//3608 3607//3607 3609//3609 -f 3608//3608 3609//3609 3610//3610 -f 3610//3610 3609//3609 3611//3611 -f 3610//3610 3611//3611 3612//3612 -f 3612//3612 3611//3611 3613//3613 -f 3612//3612 3613//3613 3614//3614 -f 3614//3614 3613//3613 3615//3615 -f 3614//3614 3615//3615 3616//3616 -f 3616//3616 3615//3615 3617//3617 -f 3616//3616 3617//3617 3618//3618 -f 3618//3618 3617//3617 3619//3619 -f 3618//3618 3619//3619 3620//3620 -f 3620//3620 3619//3619 3621//3621 -f 3620//3620 3621//3621 3622//3622 -f 3622//3622 3621//3621 3623//3623 -f 3622//3622 3623//3623 3624//3624 -f 3624//3624 3623//3623 3388//3388 -f 3381//3381 3380//3380 3534//3534 -f 3534//3534 3533//3533 3381//3381 -f 3381//3381 3533//3533 3625//3625 -f 3381//3381 3625//3625 3382//3382 -f 3519//3519 3518//3518 3533//3533 -f 3533//3533 3518//3518 3626//3626 -f 3533//3533 3626//3626 3625//3625 -f 3625//3625 3626//3626 3627//3627 -f 3625//3625 3627//3627 3382//3382 -f 3494//3494 3493//3493 3518//3518 -f 3518//3518 3493//3493 3628//3628 -f 3518//3518 3628//3628 3626//3626 -f 3626//3626 3628//3628 3629//3629 -f 3626//3626 3629//3629 3627//3627 -f 3627//3627 3629//3629 3630//3630 -f 3627//3627 3630//3630 3382//3382 -f 3470//3470 3469//3469 3493//3493 -f 3493//3493 3469//3469 3631//3631 -f 3493//3493 3631//3631 3628//3628 -f 3628//3628 3631//3631 3632//3632 -f 3628//3628 3632//3632 3629//3629 -f 3629//3629 3632//3632 3633//3633 -f 3629//3629 3633//3633 3630//3630 -f 3630//3630 3633//3633 3634//3634 -f 3630//3630 3634//3634 3382//3382 -f 3451//3451 3450//3450 3469//3469 -f 3469//3469 3450//3450 3635//3635 -f 3469//3469 3635//3635 3631//3631 -f 3631//3631 3635//3635 3636//3636 -f 3631//3631 3636//3636 3632//3632 -f 3632//3632 3636//3636 3637//3637 -f 3632//3632 3637//3637 3633//3633 -f 3633//3633 3637//3637 3638//3638 -f 3633//3633 3638//3638 3634//3634 -f 3634//3634 3638//3638 3639//3639 -f 3634//3634 3639//3639 3382//3382 -f 3382//3382 3535//3535 3640//3640 -f 3640//3640 3535//3535 3536//3536 -f 3640//3640 3536//3536 3641//3641 -f 3641//3641 3536//3536 3537//3537 -f 3641//3641 3537//3537 3642//3642 -f 3642//3642 3537//3537 3538//3538 -f 3642//3642 3538//3538 3643//3643 -f 3643//3643 3538//3538 3539//3539 -f 3643//3643 3539//3539 3644//3644 -f 3644//3644 3539//3539 3540//3540 -f 3644//3644 3540//3540 3645//3645 -f 3645//3645 3540//3540 3541//3541 -f 3645//3645 3541//3541 3646//3646 -f 3646//3646 3541//3541 3542//3542 -f 3646//3646 3542//3542 3647//3647 -f 3647//3647 3542//3542 3543//3543 -f 3647//3647 3543//3543 3648//3648 -f 3648//3648 3543//3543 3544//3544 -f 3648//3648 3544//3544 3649//3649 -f 3649//3649 3544//3544 3545//3545 -f 3649//3649 3545//3545 3650//3650 -f 3650//3650 3545//3545 3546//3546 -f 3650//3650 3546//3546 3391//3391 -f 3391//3391 3546//3546 3388//3388 -f 3382//3382 3640//3640 3651//3651 -f 3651//3651 3640//3640 3641//3641 -f 3651//3651 3641//3641 3652//3652 -f 3652//3652 3641//3641 3642//3642 -f 3652//3652 3642//3642 3653//3653 -f 3653//3653 3642//3642 3643//3643 -f 3653//3653 3643//3643 3654//3654 -f 3654//3654 3643//3643 3644//3644 -f 3654//3654 3644//3644 3655//3655 -f 3655//3655 3644//3644 3645//3645 -f 3655//3655 3645//3645 3656//3656 -f 3656//3656 3645//3645 3646//3646 -f 3656//3656 3646//3646 3657//3657 -f 3657//3657 3646//3646 3647//3647 -f 3657//3657 3647//3647 3658//3658 -f 3658//3658 3647//3647 3648//3648 -f 3658//3658 3648//3648 3659//3659 -f 3659//3659 3648//3648 3649//3649 -f 3659//3659 3649//3649 3660//3660 -f 3660//3660 3649//3649 3650//3650 -f 3660//3660 3650//3650 3661//3661 -f 3661//3661 3650//3650 3391//3391 -f 3661//3661 3391//3391 3390//3390 -f 3390//3390 3391//3391 2960//2960 -f 3390//3390 2960//2960 2959//2959 -f 3431//3431 3430//3430 3450//3450 -f 3450//3450 3430//3430 3432//3432 -f 3450//3450 3432//3432 3635//3635 -f 3635//3635 3432//3432 3452//3452 -f 3635//3635 3452//3452 3636//3636 -f 3636//3636 3452//3452 3471//3471 -f 3636//3636 3471//3471 3637//3637 -f 3637//3637 3471//3471 3495//3495 -f 3637//3637 3495//3495 3638//3638 -f 3638//3638 3495//3495 3520//3520 -f 3638//3638 3520//3520 3639//3639 -f 3639//3639 3520//3520 3535//3535 -f 3639//3639 3535//3535 3382//3382 -f 3388//3388 3662//3662 3390//3390 -f 3390//3390 3662//3662 3663//3663 -f 3390//3390 3663//3663 3661//3661 -f 3661//3661 3663//3663 3664//3664 -f 3661//3661 3664//3664 3660//3660 -f 3660//3660 3664//3664 3665//3665 -f 3660//3660 3665//3665 3659//3659 -f 3659//3659 3665//3665 3666//3666 -f 3659//3659 3666//3666 3658//3658 -f 3658//3658 3666//3666 3667//3667 -f 3658//3658 3667//3667 3657//3657 -f 3657//3657 3667//3667 3668//3668 -f 3657//3657 3668//3668 3656//3656 -f 3656//3656 3668//3668 3669//3669 -f 3656//3656 3669//3669 3655//3655 -f 3655//3655 3669//3669 3670//3670 -f 3655//3655 3670//3670 3654//3654 -f 3654//3654 3670//3670 3671//3671 -f 3654//3654 3671//3671 3653//3653 -f 3653//3653 3671//3671 3672//3672 -f 3653//3653 3672//3672 3652//3652 -f 3652//3652 3672//3672 3673//3673 -f 3652//3652 3673//3673 3651//3651 -f 3651//3651 3673//3673 3382//3382 -f 3670//3670 3674//3674 3671//3671 -f 3671//3671 3674//3674 3675//3675 -f 3671//3671 3675//3675 3672//3672 -f 3672//3672 3675//3675 3676//3676 -f 3672//3672 3676//3676 3673//3673 -f 3673//3673 3676//3676 3382//3382 -f 3394//3394 3677//3677 3678//3678 -f 3678//3678 3677//3677 3679//3679 -f 3678//3678 3679//3679 3680//3680 -f 3680//3680 3679//3679 3681//3681 -f 3680//3680 3681//3681 3682//3682 -f 3682//3682 3681//3681 3683//3683 -f 3682//3682 3683//3683 3684//3684 -f 3684//3684 3683//3683 3685//3685 -f 3684//3684 3685//3685 3686//3686 -f 3686//3686 3685//3685 3687//3687 -f 3686//3686 3687//3687 3688//3688 -f 3688//3688 3687//3687 3689//3689 -f 3688//3688 3689//3689 3690//3690 -f 3690//3690 3689//3689 3691//3691 -f 3690//3690 3691//3691 3674//3674 -f 3674//3674 3691//3691 3692//3692 -f 3674//3674 3692//3692 3675//3675 -f 3675//3675 3692//3692 3693//3693 -f 3675//3675 3693//3693 3676//3676 -f 3676//3676 3693//3693 3382//3382 -f 3677//3677 3547//3547 3679//3679 -f 3679//3679 3547//3547 3549//3549 -f 3679//3679 3549//3549 3681//3681 -f 3681//3681 3549//3549 3551//3551 -f 3681//3681 3551//3551 3683//3683 -f 3683//3683 3551//3551 3553//3553 -f 3683//3683 3553//3553 3685//3685 -f 3685//3685 3553//3553 3555//3555 -f 3685//3685 3555//3555 3687//3687 -f 3687//3687 3555//3555 3557//3557 -f 3687//3687 3557//3557 3689//3689 -f 3689//3689 3557//3557 3559//3559 -f 3689//3689 3559//3559 3691//3691 -f 3691//3691 3559//3559 3561//3561 -f 3691//3691 3561//3561 3692//3692 -f 3692//3692 3561//3561 3563//3563 -f 3692//3692 3563//3563 3693//3693 -f 3693//3693 3563//3563 3382//3382 -f 3382//3382 3602//3602 3380//3380 -f 3380//3380 3602//3602 3604//3604 -f 3380//3380 3604//3604 3534//3534 -f 3534//3534 3604//3604 3606//3606 -f 3534//3534 3606//3606 3519//3519 -f 3519//3519 3606//3606 3608//3608 -f 3519//3519 3608//3608 3494//3494 -f 3494//3494 3608//3608 3610//3610 -f 3494//3494 3610//3610 3470//3470 -f 3470//3470 3610//3610 3612//3612 -f 3470//3470 3612//3612 3451//3451 -f 3451//3451 3612//3612 3614//3614 -f 3451//3451 3614//3614 3431//3431 -f 3431//3431 3614//3614 3616//3616 -f 3431//3431 3616//3616 3429//3429 -f 3429//3429 3616//3616 3618//3618 -f 3429//3429 3618//3618 3427//3427 -f 3427//3427 3618//3618 3620//3620 -f 3427//3427 3620//3620 3425//3425 -f 3425//3425 3620//3620 3622//3622 -f 3425//3425 3622//3622 3423//3423 -f 3423//3423 3622//3622 3624//3624 -f 3423//3423 3624//3624 3421//3421 -f 3421//3421 3624//3624 3388//3388 -f 3601//3601 3516//3516 3603//3603 -f 3603//3603 3516//3516 3491//3491 -f 3603//3603 3491//3491 3605//3605 -f 3605//3605 3491//3491 3467//3467 -f 3605//3605 3467//3467 3607//3607 -f 3607//3607 3467//3467 3448//3448 -f 3607//3607 3448//3448 3609//3609 -f 3609//3609 3448//3448 3418//3418 -f 3609//3609 3418//3418 3611//3611 -f 3611//3611 3418//3418 3411//3411 -f 3611//3611 3411//3411 3613//3613 -f 3613//3613 3411//3411 3405//3405 -f 3613//3613 3405//3405 3615//3615 -f 3615//3615 3405//3405 3400//3400 -f 3615//3615 3400//3400 3617//3617 -f 3617//3617 3400//3400 3396//3396 -f 3617//3617 3396//3396 3619//3619 -f 3619//3619 3396//3396 3385//3385 -f 3619//3619 3385//3385 3621//3621 -f 3621//3621 3385//3385 3387//3387 -f 3621//3621 3387//3387 3623//3623 -f 3623//3623 3387//3387 3388//3388 -f 3517//3517 3492//3492 3580//3580 -f 3580//3580 3492//3492 3507//3507 -f 3580//3580 3507//3507 3582//3582 -f 3582//3582 3507//3507 3508//3508 -f 3582//3582 3508//3508 3584//3584 -f 3584//3584 3508//3508 3509//3509 -f 3584//3584 3509//3509 3586//3586 -f 3586//3586 3509//3509 3510//3510 -f 3586//3586 3510//3510 3588//3588 -f 3588//3588 3510//3510 3511//3511 -f 3588//3588 3511//3511 3590//3590 -f 3590//3590 3511//3511 3512//3512 -f 3590//3590 3512//3512 3592//3592 -f 3592//3592 3512//3512 3513//3513 -f 3592//3592 3513//3513 3594//3594 -f 3594//3594 3513//3513 3514//3514 -f 3594//3594 3514//3514 3596//3596 -f 3596//3596 3514//3514 3515//3515 -f 3596//3596 3515//3515 3598//3598 -f 3598//3598 3515//3515 3516//3516 -f 3598//3598 3516//3516 3600//3600 -f 3600//3600 3516//3516 3601//3601 -f 3600//3600 3601//3601 3382//3382 -f 3562//3562 3382//3382 3563//3563 -f 3548//3548 3439//3439 3550//3550 -f 3550//3550 3439//3439 3441//3441 -f 3550//3550 3441//3441 3552//3552 -f 3552//3552 3441//3441 3480//3480 -f 3552//3552 3480//3480 3554//3554 -f 3554//3554 3480//3480 3482//3482 -f 3554//3554 3482//3482 3556//3556 -f 3556//3556 3482//3482 3506//3506 -f 3556//3556 3506//3506 3558//3558 -f 3558//3558 3506//3506 3532//3532 -f 3558//3558 3532//3532 3560//3560 -f 3560//3560 3532//3532 3383//3383 -f 3560//3560 3383//3383 3562//3562 -f 3562//3562 3383//3383 3382//3382 -f 3392//3392 3388//3388 3517//3517 -f 3394//3394 3393//3393 3677//3677 -f 3677//3677 3393//3393 3581//3581 -f 3677//3677 3581//3581 3547//3547 -f 3547//3547 3581//3581 3583//3583 -f 3547//3547 3583//3583 3548//3548 -f 3548//3548 3583//3583 3585//3585 -f 3548//3548 3585//3585 3439//3439 -f 3439//3439 3585//3585 3587//3587 -f 3439//3439 3587//3587 3440//3440 -f 3440//3440 3587//3587 3589//3589 -f 3440//3440 3589//3589 3575//3575 -f 3575//3575 3589//3589 3591//3591 -f 3575//3575 3591//3591 3576//3576 -f 3576//3576 3591//3591 3593//3593 -f 3576//3576 3593//3593 3577//3577 -f 3577//3577 3593//3593 3595//3595 -f 3577//3577 3595//3595 3578//3578 -f 3578//3578 3595//3595 3597//3597 -f 3578//3578 3597//3597 3579//3579 -f 3579//3579 3597//3597 3599//3599 -f 3579//3579 3599//3599 3382//3382 -f 3674//3674 3670//3670 3690//3690 -f 3690//3690 3670//3670 3669//3669 -f 3690//3690 3669//3669 3688//3688 -f 3688//3688 3669//3669 3668//3668 -f 3688//3688 3668//3668 3686//3686 -f 3686//3686 3668//3668 3667//3667 -f 3686//3686 3667//3667 3684//3684 -f 3684//3684 3667//3667 3666//3666 -f 3684//3684 3666//3666 3682//3682 -f 3682//3682 3666//3666 3665//3665 -f 3682//3682 3665//3665 3680//3680 -f 3680//3680 3665//3665 3664//3664 -f 3680//3680 3664//3664 3678//3678 -f 3678//3678 3664//3664 3663//3663 -f 3678//3678 3663//3663 3394//3394 -f 3394//3394 3663//3663 3662//3662 -f 3394//3394 3662//3662 3392//3392 -f 3392//3392 3662//3662 3388//3388 -f 3382//3382 3276//3276 3255//3255 -f 3277//3277 3276//3276 3382//3382 -f 3382//3382 3254//3254 3259//3259 -f 3255//3255 3254//3254 3382//3382 -f 3382//3382 3259//3259 3261//3261 -f 3275//3275 3273//3273 3382//3382 -f 3263//3263 3251//3251 3570//3570 -f 3382//3382 3261//3261 3570//3570 -f 3570//3570 3261//3261 3263//3263 -f 3270//3270 3268//3268 3569//3569 -f 3270//3270 3569//3569 3271//3271 -f 3570//3570 3251//3251 3266//3266 -f 3570//3570 3266//3266 3569//3569 -f 3569//3569 3266//3266 3265//3265 -f 3569//3569 3265//3265 3271//3271 -f 3273//3273 3277//3277 3382//3382 -f 3268//3268 3275//3275 3569//3569 -f 3569//3569 3275//3275 3382//3382 -f 3694//3694 3695//3695 3696//3696 -f 3697//3697 3698//3698 3696//3696 -f 3699//3699 3700//3700 3701//3701 -f 3701//3701 3700//3700 3702//3702 -f 3703//3703 3702//3702 3700//3700 -f 3355//3355 3361//3361 3704//3704 -f 3704//3704 3361//3361 3360//3360 -f 3704//3704 3360//3360 3358//3358 -f 3702//3702 3363//3363 3367//3367 -f 3365//3365 3363//3363 3702//3702 -f 3358//3358 3365//3365 3704//3704 -f 3704//3704 3365//3365 3702//3702 -f 3702//3702 3366//3366 3345//3345 -f 3367//3367 3366//3366 3702//3702 -f 3702//3702 3344//3344 3349//3349 -f 3345//3345 3344//3344 3702//3702 -f 3702//3702 3349//3349 3351//3351 -f 3702//3702 3351//3351 3705//3705 -f 3705//3705 3351//3351 3353//3353 -f 3353//3353 3314//3314 3705//3705 -f 3705//3705 3314//3314 3356//3356 -f 3706//3706 3707//3707 3708//3708 -f 3703//3703 3700//3700 3709//3709 -f 3709//3709 3700//3700 3699//3699 -f 3709//3709 3699//3699 3710//3710 -f 3711//3711 3702//3702 3703//3703 -f 3711//3711 3703//3703 3712//3712 -f 3712//3712 3703//3703 3709//3709 -f 3712//3712 3709//3709 3713//3713 -f 3713//3713 3709//3709 3710//3710 -f 3713//3713 3710//3710 3714//3714 -f 3715//3715 3702//3702 3711//3711 -f 3715//3715 3711//3711 3716//3716 -f 3716//3716 3711//3711 3712//3712 -f 3716//3716 3712//3712 3717//3717 -f 3717//3717 3712//3712 3713//3713 -f 3717//3717 3713//3713 3718//3718 -f 3718//3718 3713//3713 3714//3714 -f 3718//3718 3714//3714 3719//3719 -f 3720//3720 3702//3702 3715//3715 -f 3720//3720 3715//3715 3721//3721 -f 3721//3721 3715//3715 3716//3716 -f 3721//3721 3716//3716 3722//3722 -f 3722//3722 3716//3716 3717//3717 -f 3722//3722 3717//3717 3723//3723 -f 3723//3723 3717//3717 3718//3718 -f 3723//3723 3718//3718 3724//3724 -f 3724//3724 3718//3718 3719//3719 -f 3724//3724 3719//3719 3725//3725 -f 3726//3726 3702//3702 3720//3720 -f 3726//3726 3720//3720 3727//3727 -f 3727//3727 3720//3720 3721//3721 -f 3727//3727 3721//3721 3728//3728 -f 3728//3728 3721//3721 3722//3722 -f 3728//3728 3722//3722 3729//3729 -f 3729//3729 3722//3722 3723//3723 -f 3729//3729 3723//3723 3730//3730 -f 3730//3730 3723//3723 3724//3724 -f 3730//3730 3724//3724 3731//3731 -f 3731//3731 3724//3724 3725//3725 -f 3731//3731 3725//3725 3732//3732 -f 3733//3733 3702//3702 3726//3726 -f 3702//3702 3734//3734 3735//3735 -f 3735//3735 3734//3734 3736//3736 -f 3735//3735 3736//3736 3737//3737 -f 3737//3737 3736//3736 3738//3738 -f 3737//3737 3738//3738 3739//3739 -f 3739//3739 3738//3738 3740//3740 -f 3739//3739 3740//3740 3741//3741 -f 3741//3741 3740//3740 3742//3742 -f 3741//3741 3742//3742 3743//3743 -f 3743//3743 3742//3742 3744//3744 -f 3743//3743 3744//3744 3745//3745 -f 3746//3746 3744//3744 3747//3747 -f 3747//3747 3744//3744 3742//3742 -f 3747//3747 3742//3742 3748//3748 -f 3748//3748 3742//3742 3740//3740 -f 3748//3748 3740//3740 3749//3749 -f 3749//3749 3740//3740 3738//3738 -f 3749//3749 3738//3738 3750//3750 -f 3750//3750 3738//3738 3736//3736 -f 3750//3750 3736//3736 3751//3751 -f 3751//3751 3736//3736 3734//3734 -f 3751//3751 3734//3734 3752//3752 -f 3752//3752 3734//3734 3702//3702 -f 3753//3753 3754//3754 3755//3755 -f 3733//3733 3726//3726 3756//3756 -f 3756//3756 3726//3726 3727//3727 -f 3756//3756 3727//3727 3757//3757 -f 3757//3757 3727//3727 3728//3728 -f 3757//3757 3728//3728 3758//3758 -f 3758//3758 3728//3728 3729//3729 -f 3758//3758 3729//3729 3759//3759 -f 3759//3759 3729//3729 3730//3730 -f 3759//3759 3730//3730 3760//3760 -f 3760//3760 3730//3730 3731//3731 -f 3760//3760 3731//3731 3761//3761 -f 3761//3761 3731//3731 3732//3732 -f 3761//3761 3732//3732 3762//3762 -f 3763//3763 3702//3702 3733//3733 -f 3745//3745 3764//3764 3765//3765 -f 3766//3766 3746//3746 3767//3767 -f 3767//3767 3746//3746 3747//3747 -f 3767//3767 3747//3747 3768//3768 -f 3768//3768 3747//3747 3748//3748 -f 3768//3768 3748//3748 3769//3769 -f 3769//3769 3748//3748 3749//3749 -f 3769//3769 3749//3749 3770//3770 -f 3770//3770 3749//3749 3750//3750 -f 3770//3770 3750//3750 3771//3771 -f 3771//3771 3750//3750 3751//3751 -f 3771//3771 3751//3751 3772//3772 -f 3772//3772 3751//3751 3752//3752 -f 3772//3772 3752//3752 3773//3773 -f 3773//3773 3752//3752 3702//3702 -f 3763//3763 3733//3733 3774//3774 -f 3774//3774 3733//3733 3756//3756 -f 3774//3774 3756//3756 3775//3775 -f 3775//3775 3756//3756 3757//3757 -f 3775//3775 3757//3757 3776//3776 -f 3776//3776 3757//3757 3758//3758 -f 3776//3776 3758//3758 3777//3777 -f 3777//3777 3758//3758 3759//3759 -f 3777//3777 3759//3759 3778//3778 -f 3778//3778 3759//3759 3760//3760 -f 3778//3778 3760//3760 3779//3779 -f 3779//3779 3760//3760 3761//3761 -f 3779//3779 3761//3761 3780//3780 -f 3780//3780 3761//3761 3762//3762 -f 3780//3780 3762//3762 3781//3781 -f 3782//3782 3702//3702 3763//3763 -f 3765//3765 3783//3783 3784//3784 -f 3785//3785 3766//3766 3786//3786 -f 3786//3786 3766//3766 3767//3767 -f 3786//3786 3767//3767 3787//3787 -f 3787//3787 3767//3767 3768//3768 -f 3787//3787 3768//3768 3788//3788 -f 3788//3788 3768//3768 3769//3769 -f 3788//3788 3769//3769 3789//3789 -f 3789//3789 3769//3769 3770//3770 -f 3789//3789 3770//3770 3790//3790 -f 3790//3790 3770//3770 3771//3771 -f 3790//3790 3771//3771 3791//3791 -f 3791//3791 3771//3771 3772//3772 -f 3791//3791 3772//3772 3792//3792 -f 3792//3792 3772//3772 3773//3773 -f 3792//3792 3773//3773 3793//3793 -f 3793//3793 3773//3773 3702//3702 -f 3794//3794 3795//3795 3796//3796 -f 3782//3782 3763//3763 3797//3797 -f 3797//3797 3763//3763 3774//3774 -f 3797//3797 3774//3774 3798//3798 -f 3798//3798 3774//3774 3775//3775 -f 3798//3798 3775//3775 3799//3799 -f 3799//3799 3775//3775 3776//3776 -f 3799//3799 3776//3776 3800//3800 -f 3800//3800 3776//3776 3777//3777 -f 3800//3800 3777//3777 3801//3801 -f 3801//3801 3777//3777 3778//3778 -f 3801//3801 3778//3778 3802//3802 -f 3802//3802 3778//3778 3779//3779 -f 3802//3802 3779//3779 3803//3803 -f 3803//3803 3779//3779 3780//3780 -f 3803//3803 3780//3780 3804//3804 -f 3804//3804 3780//3780 3781//3781 -f 3804//3804 3781//3781 3805//3805 -f 3806//3806 3702//3702 3782//3782 -f 3784//3784 3807//3807 3808//3808 -f 3809//3809 3785//3785 3810//3810 -f 3810//3810 3785//3785 3786//3786 -f 3810//3810 3786//3786 3811//3811 -f 3811//3811 3786//3786 3787//3787 -f 3811//3811 3787//3787 3812//3812 -f 3812//3812 3787//3787 3788//3788 -f 3812//3812 3788//3788 3813//3813 -f 3813//3813 3788//3788 3789//3789 -f 3813//3813 3789//3789 3814//3814 -f 3814//3814 3789//3789 3790//3790 -f 3814//3814 3790//3790 3815//3815 -f 3815//3815 3790//3790 3791//3791 -f 3815//3815 3791//3791 3816//3816 -f 3816//3816 3791//3791 3792//3792 -f 3816//3816 3792//3792 3817//3817 -f 3817//3817 3792//3792 3793//3793 -f 3817//3817 3793//3793 3818//3818 -f 3818//3818 3793//3793 3702//3702 -f 3796//3796 3819//3819 3820//3820 -f 3806//3806 3782//3782 3821//3821 -f 3821//3821 3782//3782 3797//3797 -f 3821//3821 3797//3797 3822//3822 -f 3822//3822 3797//3797 3798//3798 -f 3822//3822 3798//3798 3823//3823 -f 3823//3823 3798//3798 3799//3799 -f 3823//3823 3799//3799 3824//3824 -f 3824//3824 3799//3799 3800//3800 -f 3824//3824 3800//3800 3825//3825 -f 3825//3825 3800//3800 3801//3801 -f 3825//3825 3801//3801 3826//3826 -f 3826//3826 3801//3801 3802//3802 -f 3826//3826 3802//3802 3827//3827 -f 3827//3827 3802//3802 3803//3803 -f 3827//3827 3803//3803 3828//3828 -f 3828//3828 3803//3803 3804//3804 -f 3828//3828 3804//3804 3829//3829 -f 3829//3829 3804//3804 3805//3805 -f 3829//3829 3805//3805 3830//3830 -f 3831//3831 3702//3702 3806//3806 -f 3808//3808 3832//3832 3833//3833 -f 3834//3834 3809//3809 3835//3835 -f 3835//3835 3809//3809 3810//3810 -f 3835//3835 3810//3810 3836//3836 -f 3836//3836 3810//3810 3811//3811 -f 3836//3836 3811//3811 3837//3837 -f 3837//3837 3811//3811 3812//3812 -f 3837//3837 3812//3812 3838//3838 -f 3838//3838 3812//3812 3813//3813 -f 3838//3838 3813//3813 3839//3839 -f 3839//3839 3813//3813 3814//3814 -f 3839//3839 3814//3814 3840//3840 -f 3840//3840 3814//3814 3815//3815 -f 3840//3840 3815//3815 3841//3841 -f 3841//3841 3815//3815 3816//3816 -f 3841//3841 3816//3816 3842//3842 -f 3842//3842 3816//3816 3817//3817 -f 3842//3842 3817//3817 3843//3843 -f 3843//3843 3817//3817 3818//3818 -f 3843//3843 3818//3818 3844//3844 -f 3844//3844 3818//3818 3702//3702 -f 3820//3820 3845//3845 3846//3846 -f 3833//3833 3847//3847 3848//3848 -f 3849//3849 3834//3834 3850//3850 -f 3850//3850 3834//3834 3835//3835 -f 3850//3850 3835//3835 3851//3851 -f 3851//3851 3835//3835 3836//3836 -f 3851//3851 3836//3836 3852//3852 -f 3852//3852 3836//3836 3837//3837 -f 3852//3852 3837//3837 3853//3853 -f 3853//3853 3837//3837 3838//3838 -f 3853//3853 3838//3838 3854//3854 -f 3854//3854 3838//3838 3839//3839 -f 3854//3854 3839//3839 3855//3855 -f 3855//3855 3839//3839 3840//3840 -f 3855//3855 3840//3840 3856//3856 -f 3856//3856 3840//3840 3841//3841 -f 3856//3856 3841//3841 3857//3857 -f 3857//3857 3841//3841 3842//3842 -f 3857//3857 3842//3842 3858//3858 -f 3858//3858 3842//3842 3843//3843 -f 3858//3858 3843//3843 3859//3859 -f 3859//3859 3843//3843 3844//3844 -f 3859//3859 3844//3844 3860//3860 -f 3860//3860 3844//3844 3702//3702 -f 3861//3861 3862//3862 3863//3863 -f 3863//3863 3862//3862 3864//3864 -f 3863//3863 3864//3864 3865//3865 -f 3865//3865 3864//3864 3866//3866 -f 3865//3865 3866//3866 3867//3867 -f 3867//3867 3866//3866 3868//3868 -f 3867//3867 3868//3868 3869//3869 -f 3869//3869 3868//3868 3870//3870 -f 3869//3869 3870//3870 3871//3871 -f 3871//3871 3870//3870 3872//3872 -f 3871//3871 3872//3872 3873//3873 -f 3873//3873 3872//3872 3874//3874 -f 3873//3873 3874//3874 3875//3875 -f 3875//3875 3874//3874 3876//3876 -f 3875//3875 3876//3876 3877//3877 -f 3698//3698 3697//3697 3846//3846 -f 3846//3846 3845//3845 3698//3698 -f 3698//3698 3845//3845 3878//3878 -f 3698//3698 3878//3878 3696//3696 -f 3820//3820 3819//3819 3845//3845 -f 3845//3845 3819//3819 3879//3879 -f 3845//3845 3879//3879 3878//3878 -f 3878//3878 3879//3879 3880//3880 -f 3878//3878 3880//3880 3696//3696 -f 3796//3796 3795//3795 3819//3819 -f 3819//3819 3795//3795 3881//3881 -f 3819//3819 3881//3881 3879//3879 -f 3879//3879 3881//3881 3882//3882 -f 3879//3879 3882//3882 3880//3880 -f 3880//3880 3882//3882 3883//3883 -f 3880//3880 3883//3883 3696//3696 -f 3884//3884 3883//3883 3885//3885 -f 3885//3885 3883//3883 3882//3882 -f 3885//3885 3882//3882 3886//3886 -f 3886//3886 3882//3882 3881//3881 -f 3886//3886 3881//3881 3887//3887 -f 3887//3887 3881//3881 3795//3795 -f 3887//3887 3795//3795 3888//3888 -f 3888//3888 3795//3795 3794//3794 -f 3888//3888 3794//3794 3755//3755 -f 3755//3755 3754//3754 3888//3888 -f 3888//3888 3754//3754 3889//3889 -f 3888//3888 3889//3889 3887//3887 -f 3887//3887 3889//3889 3890//3890 -f 3887//3887 3890//3890 3886//3886 -f 3886//3886 3890//3890 3891//3891 -f 3886//3886 3891//3891 3885//3885 -f 3885//3885 3891//3891 3892//3892 -f 3885//3885 3892//3892 3884//3884 -f 3884//3884 3892//3892 3893//3893 -f 3884//3884 3893//3893 3696//3696 -f 3706//3706 3831//3831 3707//3707 -f 3707//3707 3831//3831 3894//3894 -f 3707//3707 3894//3894 3895//3895 -f 3895//3895 3894//3894 3896//3896 -f 3895//3895 3896//3896 3897//3897 -f 3897//3897 3896//3896 3898//3898 -f 3897//3897 3898//3898 3899//3899 -f 3899//3899 3898//3898 3900//3900 -f 3899//3899 3900//3900 3901//3901 -f 3901//3901 3900//3900 3902//3902 -f 3901//3901 3902//3902 3903//3903 -f 3903//3903 3902//3902 3904//3904 -f 3903//3903 3904//3904 3905//3905 -f 3905//3905 3904//3904 3906//3906 -f 3905//3905 3906//3906 3907//3907 -f 3907//3907 3906//3906 3908//3908 -f 3907//3907 3908//3908 3909//3909 -f 3909//3909 3908//3908 3910//3910 -f 3909//3909 3910//3910 3911//3911 -f 3911//3911 3910//3910 3912//3912 -f 3911//3911 3912//3912 3913//3913 -f 3913//3913 3912//3912 3914//3914 -f 3913//3913 3914//3914 3696//3696 -f 3696//3696 3915//3915 3916//3916 -f 3916//3916 3915//3915 3917//3917 -f 3916//3916 3917//3917 3918//3918 -f 3918//3918 3917//3917 3919//3919 -f 3918//3918 3919//3919 3920//3920 -f 3920//3920 3919//3919 3921//3921 -f 3920//3920 3921//3921 3922//3922 -f 3922//3922 3921//3921 3923//3923 -f 3922//3922 3923//3923 3924//3924 -f 3924//3924 3923//3923 3925//3925 -f 3924//3924 3925//3925 3926//3926 -f 3926//3926 3925//3925 3927//3927 -f 3926//3926 3927//3927 3928//3928 -f 3928//3928 3927//3927 3929//3929 -f 3928//3928 3929//3929 3930//3930 -f 3930//3930 3929//3929 3931//3931 -f 3930//3930 3931//3931 3932//3932 -f 3932//3932 3931//3931 3933//3933 -f 3932//3932 3933//3933 3934//3934 -f 3934//3934 3933//3933 3935//3935 -f 3934//3934 3935//3935 3936//3936 -f 3936//3936 3935//3935 3937//3937 -f 3936//3936 3937//3937 3938//3938 -f 3938//3938 3937//3937 3702//3702 -f 3695//3695 3694//3694 3848//3848 -f 3848//3848 3847//3847 3695//3695 -f 3695//3695 3847//3847 3939//3939 -f 3695//3695 3939//3939 3696//3696 -f 3833//3833 3832//3832 3847//3847 -f 3847//3847 3832//3832 3940//3940 -f 3847//3847 3940//3940 3939//3939 -f 3939//3939 3940//3940 3941//3941 -f 3939//3939 3941//3941 3696//3696 -f 3808//3808 3807//3807 3832//3832 -f 3832//3832 3807//3807 3942//3942 -f 3832//3832 3942//3942 3940//3940 -f 3940//3940 3942//3942 3943//3943 -f 3940//3940 3943//3943 3941//3941 -f 3941//3941 3943//3943 3944//3944 -f 3941//3941 3944//3944 3696//3696 -f 3784//3784 3783//3783 3807//3807 -f 3807//3807 3783//3783 3945//3945 -f 3807//3807 3945//3945 3942//3942 -f 3942//3942 3945//3945 3946//3946 -f 3942//3942 3946//3946 3943//3943 -f 3943//3943 3946//3946 3947//3947 -f 3943//3943 3947//3947 3944//3944 -f 3944//3944 3947//3947 3948//3948 -f 3944//3944 3948//3948 3696//3696 -f 3765//3765 3764//3764 3783//3783 -f 3783//3783 3764//3764 3949//3949 -f 3783//3783 3949//3949 3945//3945 -f 3945//3945 3949//3949 3950//3950 -f 3945//3945 3950//3950 3946//3946 -f 3946//3946 3950//3950 3951//3951 -f 3946//3946 3951//3951 3947//3947 -f 3947//3947 3951//3951 3952//3952 -f 3947//3947 3952//3952 3948//3948 -f 3948//3948 3952//3952 3953//3953 -f 3948//3948 3953//3953 3696//3696 -f 3696//3696 3849//3849 3954//3954 -f 3954//3954 3849//3849 3850//3850 -f 3954//3954 3850//3850 3955//3955 -f 3955//3955 3850//3850 3851//3851 -f 3955//3955 3851//3851 3956//3956 -f 3956//3956 3851//3851 3852//3852 -f 3956//3956 3852//3852 3957//3957 -f 3957//3957 3852//3852 3853//3853 -f 3957//3957 3853//3853 3958//3958 -f 3958//3958 3853//3853 3854//3854 -f 3958//3958 3854//3854 3959//3959 -f 3959//3959 3854//3854 3855//3855 -f 3959//3959 3855//3855 3960//3960 -f 3960//3960 3855//3855 3856//3856 -f 3960//3960 3856//3856 3961//3961 -f 3961//3961 3856//3856 3857//3857 -f 3961//3961 3857//3857 3962//3962 -f 3962//3962 3857//3857 3858//3858 -f 3962//3962 3858//3858 3963//3963 -f 3963//3963 3858//3858 3859//3859 -f 3963//3963 3859//3859 3964//3964 -f 3964//3964 3859//3859 3860//3860 -f 3964//3964 3860//3860 3705//3705 -f 3705//3705 3860//3860 3702//3702 -f 3696//3696 3954//3954 3965//3965 -f 3965//3965 3954//3954 3955//3955 -f 3965//3965 3955//3955 3966//3966 -f 3966//3966 3955//3955 3956//3956 -f 3966//3966 3956//3956 3967//3967 -f 3967//3967 3956//3956 3957//3957 -f 3967//3967 3957//3957 3968//3968 -f 3968//3968 3957//3957 3958//3958 -f 3968//3968 3958//3958 3969//3969 -f 3969//3969 3958//3958 3959//3959 -f 3969//3969 3959//3959 3970//3970 -f 3970//3970 3959//3959 3960//3960 -f 3970//3970 3960//3960 3971//3971 -f 3971//3971 3960//3960 3961//3961 -f 3971//3971 3961//3961 3972//3972 -f 3972//3972 3961//3961 3962//3962 -f 3972//3972 3962//3962 3973//3973 -f 3973//3973 3962//3962 3963//3963 -f 3973//3973 3963//3963 3974//3974 -f 3974//3974 3963//3963 3964//3964 -f 3974//3974 3964//3964 3975//3975 -f 3975//3975 3964//3964 3705//3705 -f 3975//3975 3705//3705 3704//3704 -f 3704//3704 3705//3705 3356//3356 -f 3704//3704 3356//3356 3355//3355 -f 3745//3745 3744//3744 3764//3764 -f 3764//3764 3744//3744 3746//3746 -f 3764//3764 3746//3746 3949//3949 -f 3949//3949 3746//3746 3766//3766 -f 3949//3949 3766//3766 3950//3950 -f 3950//3950 3766//3766 3785//3785 -f 3950//3950 3785//3785 3951//3951 -f 3951//3951 3785//3785 3809//3809 -f 3951//3951 3809//3809 3952//3952 -f 3952//3952 3809//3809 3834//3834 -f 3952//3952 3834//3834 3953//3953 -f 3953//3953 3834//3834 3849//3849 -f 3953//3953 3849//3849 3696//3696 -f 3702//3702 3976//3976 3704//3704 -f 3704//3704 3976//3976 3977//3977 -f 3704//3704 3977//3977 3975//3975 -f 3975//3975 3977//3977 3978//3978 -f 3975//3975 3978//3978 3974//3974 -f 3974//3974 3978//3978 3979//3979 -f 3974//3974 3979//3979 3973//3973 -f 3973//3973 3979//3979 3980//3980 -f 3973//3973 3980//3980 3972//3972 -f 3972//3972 3980//3980 3981//3981 -f 3972//3972 3981//3981 3971//3971 -f 3971//3971 3981//3981 3982//3982 -f 3971//3971 3982//3982 3970//3970 -f 3970//3970 3982//3982 3983//3983 -f 3970//3970 3983//3983 3969//3969 -f 3969//3969 3983//3983 3984//3984 -f 3969//3969 3984//3984 3968//3968 -f 3968//3968 3984//3984 3985//3985 -f 3968//3968 3985//3985 3967//3967 -f 3967//3967 3985//3985 3986//3986 -f 3967//3967 3986//3986 3966//3966 -f 3966//3966 3986//3986 3987//3987 -f 3966//3966 3987//3987 3965//3965 -f 3965//3965 3987//3987 3696//3696 -f 3984//3984 3988//3988 3985//3985 -f 3985//3985 3988//3988 3989//3989 -f 3985//3985 3989//3989 3986//3986 -f 3986//3986 3989//3989 3990//3990 -f 3986//3986 3990//3990 3987//3987 -f 3987//3987 3990//3990 3696//3696 -f 3708//3708 3991//3991 3992//3992 -f 3992//3992 3991//3991 3993//3993 -f 3992//3992 3993//3993 3994//3994 -f 3994//3994 3993//3993 3995//3995 -f 3994//3994 3995//3995 3996//3996 -f 3996//3996 3995//3995 3997//3997 -f 3996//3996 3997//3997 3998//3998 -f 3998//3998 3997//3997 3999//3999 -f 3998//3998 3999//3999 4000//4000 -f 4000//4000 3999//3999 4001//4001 -f 4000//4000 4001//4001 4002//4002 -f 4002//4002 4001//4001 4003//4003 -f 4002//4002 4003//4003 4004//4004 -f 4004//4004 4003//4003 4005//4005 -f 4004//4004 4005//4005 3988//3988 -f 3988//3988 4005//4005 4006//4006 -f 3988//3988 4006//4006 3989//3989 -f 3989//3989 4006//4006 4007//4007 -f 3989//3989 4007//4007 3990//3990 -f 3990//3990 4007//4007 3696//3696 -f 3991//3991 3861//3861 3993//3993 -f 3993//3993 3861//3861 3863//3863 -f 3993//3993 3863//3863 3995//3995 -f 3995//3995 3863//3863 3865//3865 -f 3995//3995 3865//3865 3997//3997 -f 3997//3997 3865//3865 3867//3867 -f 3997//3997 3867//3867 3999//3999 -f 3999//3999 3867//3867 3869//3869 -f 3999//3999 3869//3869 4001//4001 -f 4001//4001 3869//3869 3871//3871 -f 4001//4001 3871//3871 4003//4003 -f 4003//4003 3871//3871 3873//3873 -f 4003//4003 3873//3873 4005//4005 -f 4005//4005 3873//3873 3875//3875 -f 4005//4005 3875//3875 4006//4006 -f 4006//4006 3875//3875 3877//3877 -f 4006//4006 3877//3877 4007//4007 -f 4007//4007 3877//3877 3696//3696 -f 3696//3696 3916//3916 3694//3694 -f 3694//3694 3916//3916 3918//3918 -f 3694//3694 3918//3918 3848//3848 -f 3848//3848 3918//3918 3920//3920 -f 3848//3848 3920//3920 3833//3833 -f 3833//3833 3920//3920 3922//3922 -f 3833//3833 3922//3922 3808//3808 -f 3808//3808 3922//3922 3924//3924 -f 3808//3808 3924//3924 3784//3784 -f 3784//3784 3924//3924 3926//3926 -f 3784//3784 3926//3926 3765//3765 -f 3765//3765 3926//3926 3928//3928 -f 3765//3765 3928//3928 3745//3745 -f 3745//3745 3928//3928 3930//3930 -f 3745//3745 3930//3930 3743//3743 -f 3743//3743 3930//3930 3932//3932 -f 3743//3743 3932//3932 3741//3741 -f 3741//3741 3932//3932 3934//3934 -f 3741//3741 3934//3934 3739//3739 -f 3739//3739 3934//3934 3936//3936 -f 3739//3739 3936//3936 3737//3737 -f 3737//3737 3936//3936 3938//3938 -f 3737//3737 3938//3938 3735//3735 -f 3735//3735 3938//3938 3702//3702 -f 3915//3915 3830//3830 3917//3917 -f 3917//3917 3830//3830 3805//3805 -f 3917//3917 3805//3805 3919//3919 -f 3919//3919 3805//3805 3781//3781 -f 3919//3919 3781//3781 3921//3921 -f 3921//3921 3781//3781 3762//3762 -f 3921//3921 3762//3762 3923//3923 -f 3923//3923 3762//3762 3732//3732 -f 3923//3923 3732//3732 3925//3925 -f 3925//3925 3732//3732 3725//3725 -f 3925//3925 3725//3725 3927//3927 -f 3927//3927 3725//3725 3719//3719 -f 3927//3927 3719//3719 3929//3929 -f 3929//3929 3719//3719 3714//3714 -f 3929//3929 3714//3714 3931//3931 -f 3931//3931 3714//3714 3710//3710 -f 3931//3931 3710//3710 3933//3933 -f 3933//3933 3710//3710 3699//3699 -f 3933//3933 3699//3699 3935//3935 -f 3935//3935 3699//3699 3701//3701 -f 3935//3935 3701//3701 3937//3937 -f 3937//3937 3701//3701 3702//3702 -f 3831//3831 3806//3806 3894//3894 -f 3894//3894 3806//3806 3821//3821 -f 3894//3894 3821//3821 3896//3896 -f 3896//3896 3821//3821 3822//3822 -f 3896//3896 3822//3822 3898//3898 -f 3898//3898 3822//3822 3823//3823 -f 3898//3898 3823//3823 3900//3900 -f 3900//3900 3823//3823 3824//3824 -f 3900//3900 3824//3824 3902//3902 -f 3902//3902 3824//3824 3825//3825 -f 3902//3902 3825//3825 3904//3904 -f 3904//3904 3825//3825 3826//3826 -f 3904//3904 3826//3826 3906//3906 -f 3906//3906 3826//3826 3827//3827 -f 3906//3906 3827//3827 3908//3908 -f 3908//3908 3827//3827 3828//3828 -f 3908//3908 3828//3828 3910//3910 -f 3910//3910 3828//3828 3829//3829 -f 3910//3910 3829//3829 3912//3912 -f 3912//3912 3829//3829 3830//3830 -f 3912//3912 3830//3830 3914//3914 -f 3914//3914 3830//3830 3915//3915 -f 3914//3914 3915//3915 3696//3696 -f 3876//3876 3696//3696 3877//3877 -f 3862//3862 3753//3753 3864//3864 -f 3864//3864 3753//3753 3755//3755 -f 3864//3864 3755//3755 3866//3866 -f 3866//3866 3755//3755 3794//3794 -f 3866//3866 3794//3794 3868//3868 -f 3868//3868 3794//3794 3796//3796 -f 3868//3868 3796//3796 3870//3870 -f 3870//3870 3796//3796 3820//3820 -f 3870//3870 3820//3820 3872//3872 -f 3872//3872 3820//3820 3846//3846 -f 3872//3872 3846//3846 3874//3874 -f 3874//3874 3846//3846 3697//3697 -f 3874//3874 3697//3697 3876//3876 -f 3876//3876 3697//3697 3696//3696 -f 3706//3706 3702//3702 3831//3831 -f 3708//3708 3707//3707 3991//3991 -f 3991//3991 3707//3707 3895//3895 -f 3991//3991 3895//3895 3861//3861 -f 3861//3861 3895//3895 3897//3897 -f 3861//3861 3897//3897 3862//3862 -f 3862//3862 3897//3897 3899//3899 -f 3862//3862 3899//3899 3753//3753 -f 3753//3753 3899//3899 3901//3901 -f 3753//3753 3901//3901 3754//3754 -f 3754//3754 3901//3901 3903//3903 -f 3754//3754 3903//3903 3889//3889 -f 3889//3889 3903//3903 3905//3905 -f 3889//3889 3905//3905 3890//3890 -f 3890//3890 3905//3905 3907//3907 -f 3890//3890 3907//3907 3891//3891 -f 3891//3891 3907//3907 3909//3909 -f 3891//3891 3909//3909 3892//3892 -f 3892//3892 3909//3909 3911//3911 -f 3892//3892 3911//3911 3893//3893 -f 3893//3893 3911//3911 3913//3913 -f 3893//3893 3913//3913 3696//3696 -f 3988//3988 3984//3984 4004//4004 -f 4004//4004 3984//3984 3983//3983 -f 4004//4004 3983//3983 4002//4002 -f 4002//4002 3983//3983 3982//3982 -f 4002//4002 3982//3982 4000//4000 -f 4000//4000 3982//3982 3981//3981 -f 4000//4000 3981//3981 3998//3998 -f 3998//3998 3981//3981 3980//3980 -f 3998//3998 3980//3980 3996//3996 -f 3996//3996 3980//3980 3979//3979 -f 3996//3996 3979//3979 3994//3994 -f 3994//3994 3979//3979 3978//3978 -f 3994//3994 3978//3978 3992//3992 -f 3992//3992 3978//3978 3977//3977 -f 3992//3992 3977//3977 3708//3708 -f 3708//3708 3977//3977 3976//3976 -f 3708//3708 3976//3976 3706//3706 -f 3706//3706 3976//3976 3702//3702 -f 3696//3696 2946//2946 2925//2925 -f 2947//2947 2946//2946 3696//3696 -f 3696//3696 2924//2924 2929//2929 -f 2925//2925 2924//2924 3696//3696 -f 3696//3696 2929//2929 2931//2931 -f 2945//2945 2943//2943 3696//3696 -f 2933//2933 2921//2921 3884//3884 -f 3696//3696 2931//2931 3884//3884 -f 3884//3884 2931//2931 2933//2933 -f 2940//2940 2938//2938 3883//3883 -f 2940//2940 3883//3883 2941//2941 -f 3884//3884 2921//2921 2936//2936 -f 3884//3884 2936//2936 3883//3883 -f 3883//3883 2936//2936 2935//2935 -f 3883//3883 2935//2935 2941//2941 -f 2943//2943 2947//2947 3696//3696 -f 2938//2938 2945//2945 3883//3883 -f 3883//3883 2945//2945 3696//3696 -f 4008//4008 4009//4009 4010//4010 -f 4011//4011 4012//4012 4010//4010 -f 4013//4013 4014//4014 4015//4015 -f 4015//4015 4014//4014 4016//4016 -f 4017//4017 4016//4016 4014//4014 -f 3025//3025 3031//3031 4018//4018 -f 4018//4018 3031//3031 3030//3030 -f 4018//4018 3030//3030 3028//3028 -f 4016//4016 3033//3033 3037//3037 -f 3035//3035 3033//3033 4016//4016 -f 3028//3028 3035//3035 4018//4018 -f 4018//4018 3035//3035 4016//4016 -f 4016//4016 3036//3036 3015//3015 -f 3037//3037 3036//3036 4016//4016 -f 4016//4016 3014//3014 3019//3019 -f 3015//3015 3014//3014 4016//4016 -f 4016//4016 3019//3019 3021//3021 -f 4016//4016 3021//3021 4019//4019 -f 4019//4019 3021//3021 3023//3023 -f 3023//3023 2984//2984 4019//4019 -f 4019//4019 2984//2984 3026//3026 -f 4020//4020 4021//4021 4022//4022 -f 4017//4017 4014//4014 4023//4023 -f 4023//4023 4014//4014 4013//4013 -f 4023//4023 4013//4013 4024//4024 -f 4025//4025 4016//4016 4017//4017 -f 4025//4025 4017//4017 4026//4026 -f 4026//4026 4017//4017 4023//4023 -f 4026//4026 4023//4023 4027//4027 -f 4027//4027 4023//4023 4024//4024 -f 4027//4027 4024//4024 4028//4028 -f 4029//4029 4016//4016 4025//4025 -f 4029//4029 4025//4025 4030//4030 -f 4030//4030 4025//4025 4026//4026 -f 4030//4030 4026//4026 4031//4031 -f 4031//4031 4026//4026 4027//4027 -f 4031//4031 4027//4027 4032//4032 -f 4032//4032 4027//4027 4028//4028 -f 4032//4032 4028//4028 4033//4033 -f 4034//4034 4016//4016 4029//4029 -f 4034//4034 4029//4029 4035//4035 -f 4035//4035 4029//4029 4030//4030 -f 4035//4035 4030//4030 4036//4036 -f 4036//4036 4030//4030 4031//4031 -f 4036//4036 4031//4031 4037//4037 -f 4037//4037 4031//4031 4032//4032 -f 4037//4037 4032//4032 4038//4038 -f 4038//4038 4032//4032 4033//4033 -f 4038//4038 4033//4033 4039//4039 -f 4040//4040 4016//4016 4034//4034 -f 4040//4040 4034//4034 4041//4041 -f 4041//4041 4034//4034 4035//4035 -f 4041//4041 4035//4035 4042//4042 -f 4042//4042 4035//4035 4036//4036 -f 4042//4042 4036//4036 4043//4043 -f 4043//4043 4036//4036 4037//4037 -f 4043//4043 4037//4037 4044//4044 -f 4044//4044 4037//4037 4038//4038 -f 4044//4044 4038//4038 4045//4045 -f 4045//4045 4038//4038 4039//4039 -f 4045//4045 4039//4039 4046//4046 -f 4047//4047 4016//4016 4040//4040 -f 4016//4016 4048//4048 4049//4049 -f 4049//4049 4048//4048 4050//4050 -f 4049//4049 4050//4050 4051//4051 -f 4051//4051 4050//4050 4052//4052 -f 4051//4051 4052//4052 4053//4053 -f 4053//4053 4052//4052 4054//4054 -f 4053//4053 4054//4054 4055//4055 -f 4055//4055 4054//4054 4056//4056 -f 4055//4055 4056//4056 4057//4057 -f 4057//4057 4056//4056 4058//4058 -f 4057//4057 4058//4058 4059//4059 -f 4060//4060 4058//4058 4061//4061 -f 4061//4061 4058//4058 4056//4056 -f 4061//4061 4056//4056 4062//4062 -f 4062//4062 4056//4056 4054//4054 -f 4062//4062 4054//4054 4063//4063 -f 4063//4063 4054//4054 4052//4052 -f 4063//4063 4052//4052 4064//4064 -f 4064//4064 4052//4052 4050//4050 -f 4064//4064 4050//4050 4065//4065 -f 4065//4065 4050//4050 4048//4048 -f 4065//4065 4048//4048 4066//4066 -f 4066//4066 4048//4048 4016//4016 -f 4067//4067 4068//4068 4069//4069 -f 4047//4047 4040//4040 4070//4070 -f 4070//4070 4040//4040 4041//4041 -f 4070//4070 4041//4041 4071//4071 -f 4071//4071 4041//4041 4042//4042 -f 4071//4071 4042//4042 4072//4072 -f 4072//4072 4042//4042 4043//4043 -f 4072//4072 4043//4043 4073//4073 -f 4073//4073 4043//4043 4044//4044 -f 4073//4073 4044//4044 4074//4074 -f 4074//4074 4044//4044 4045//4045 -f 4074//4074 4045//4045 4075//4075 -f 4075//4075 4045//4045 4046//4046 -f 4075//4075 4046//4046 4076//4076 -f 4077//4077 4016//4016 4047//4047 -f 4059//4059 4078//4078 4079//4079 -f 4080//4080 4060//4060 4081//4081 -f 4081//4081 4060//4060 4061//4061 -f 4081//4081 4061//4061 4082//4082 -f 4082//4082 4061//4061 4062//4062 -f 4082//4082 4062//4062 4083//4083 -f 4083//4083 4062//4062 4063//4063 -f 4083//4083 4063//4063 4084//4084 -f 4084//4084 4063//4063 4064//4064 -f 4084//4084 4064//4064 4085//4085 -f 4085//4085 4064//4064 4065//4065 -f 4085//4085 4065//4065 4086//4086 -f 4086//4086 4065//4065 4066//4066 -f 4086//4086 4066//4066 4087//4087 -f 4087//4087 4066//4066 4016//4016 -f 4077//4077 4047//4047 4088//4088 -f 4088//4088 4047//4047 4070//4070 -f 4088//4088 4070//4070 4089//4089 -f 4089//4089 4070//4070 4071//4071 -f 4089//4089 4071//4071 4090//4090 -f 4090//4090 4071//4071 4072//4072 -f 4090//4090 4072//4072 4091//4091 -f 4091//4091 4072//4072 4073//4073 -f 4091//4091 4073//4073 4092//4092 -f 4092//4092 4073//4073 4074//4074 -f 4092//4092 4074//4074 4093//4093 -f 4093//4093 4074//4074 4075//4075 -f 4093//4093 4075//4075 4094//4094 -f 4094//4094 4075//4075 4076//4076 -f 4094//4094 4076//4076 4095//4095 -f 4096//4096 4016//4016 4077//4077 -f 4079//4079 4097//4097 4098//4098 -f 4099//4099 4080//4080 4100//4100 -f 4100//4100 4080//4080 4081//4081 -f 4100//4100 4081//4081 4101//4101 -f 4101//4101 4081//4081 4082//4082 -f 4101//4101 4082//4082 4102//4102 -f 4102//4102 4082//4082 4083//4083 -f 4102//4102 4083//4083 4103//4103 -f 4103//4103 4083//4083 4084//4084 -f 4103//4103 4084//4084 4104//4104 -f 4104//4104 4084//4084 4085//4085 -f 4104//4104 4085//4085 4105//4105 -f 4105//4105 4085//4085 4086//4086 -f 4105//4105 4086//4086 4106//4106 -f 4106//4106 4086//4086 4087//4087 -f 4106//4106 4087//4087 4107//4107 -f 4107//4107 4087//4087 4016//4016 -f 4108//4108 4109//4109 4110//4110 -f 4096//4096 4077//4077 4111//4111 -f 4111//4111 4077//4077 4088//4088 -f 4111//4111 4088//4088 4112//4112 -f 4112//4112 4088//4088 4089//4089 -f 4112//4112 4089//4089 4113//4113 -f 4113//4113 4089//4089 4090//4090 -f 4113//4113 4090//4090 4114//4114 -f 4114//4114 4090//4090 4091//4091 -f 4114//4114 4091//4091 4115//4115 -f 4115//4115 4091//4091 4092//4092 -f 4115//4115 4092//4092 4116//4116 -f 4116//4116 4092//4092 4093//4093 -f 4116//4116 4093//4093 4117//4117 -f 4117//4117 4093//4093 4094//4094 -f 4117//4117 4094//4094 4118//4118 -f 4118//4118 4094//4094 4095//4095 -f 4118//4118 4095//4095 4119//4119 -f 4120//4120 4016//4016 4096//4096 -f 4098//4098 4121//4121 4122//4122 -f 4123//4123 4099//4099 4124//4124 -f 4124//4124 4099//4099 4100//4100 -f 4124//4124 4100//4100 4125//4125 -f 4125//4125 4100//4100 4101//4101 -f 4125//4125 4101//4101 4126//4126 -f 4126//4126 4101//4101 4102//4102 -f 4126//4126 4102//4102 4127//4127 -f 4127//4127 4102//4102 4103//4103 -f 4127//4127 4103//4103 4128//4128 -f 4128//4128 4103//4103 4104//4104 -f 4128//4128 4104//4104 4129//4129 -f 4129//4129 4104//4104 4105//4105 -f 4129//4129 4105//4105 4130//4130 -f 4130//4130 4105//4105 4106//4106 -f 4130//4130 4106//4106 4131//4131 -f 4131//4131 4106//4106 4107//4107 -f 4131//4131 4107//4107 4132//4132 -f 4132//4132 4107//4107 4016//4016 -f 4110//4110 4133//4133 4134//4134 -f 4120//4120 4096//4096 4135//4135 -f 4135//4135 4096//4096 4111//4111 -f 4135//4135 4111//4111 4136//4136 -f 4136//4136 4111//4111 4112//4112 -f 4136//4136 4112//4112 4137//4137 -f 4137//4137 4112//4112 4113//4113 -f 4137//4137 4113//4113 4138//4138 -f 4138//4138 4113//4113 4114//4114 -f 4138//4138 4114//4114 4139//4139 -f 4139//4139 4114//4114 4115//4115 -f 4139//4139 4115//4115 4140//4140 -f 4140//4140 4115//4115 4116//4116 -f 4140//4140 4116//4116 4141//4141 -f 4141//4141 4116//4116 4117//4117 -f 4141//4141 4117//4117 4142//4142 -f 4142//4142 4117//4117 4118//4118 -f 4142//4142 4118//4118 4143//4143 -f 4143//4143 4118//4118 4119//4119 -f 4143//4143 4119//4119 4144//4144 -f 4145//4145 4016//4016 4120//4120 -f 4122//4122 4146//4146 4147//4147 -f 4148//4148 4123//4123 4149//4149 -f 4149//4149 4123//4123 4124//4124 -f 4149//4149 4124//4124 4150//4150 -f 4150//4150 4124//4124 4125//4125 -f 4150//4150 4125//4125 4151//4151 -f 4151//4151 4125//4125 4126//4126 -f 4151//4151 4126//4126 4152//4152 -f 4152//4152 4126//4126 4127//4127 -f 4152//4152 4127//4127 4153//4153 -f 4153//4153 4127//4127 4128//4128 -f 4153//4153 4128//4128 4154//4154 -f 4154//4154 4128//4128 4129//4129 -f 4154//4154 4129//4129 4155//4155 -f 4155//4155 4129//4129 4130//4130 -f 4155//4155 4130//4130 4156//4156 -f 4156//4156 4130//4130 4131//4131 -f 4156//4156 4131//4131 4157//4157 -f 4157//4157 4131//4131 4132//4132 -f 4157//4157 4132//4132 4158//4158 -f 4158//4158 4132//4132 4016//4016 -f 4134//4134 4159//4159 4160//4160 -f 4147//4147 4161//4161 4162//4162 -f 4163//4163 4148//4148 4164//4164 -f 4164//4164 4148//4148 4149//4149 -f 4164//4164 4149//4149 4165//4165 -f 4165//4165 4149//4149 4150//4150 -f 4165//4165 4150//4150 4166//4166 -f 4166//4166 4150//4150 4151//4151 -f 4166//4166 4151//4151 4167//4167 -f 4167//4167 4151//4151 4152//4152 -f 4167//4167 4152//4152 4168//4168 -f 4168//4168 4152//4152 4153//4153 -f 4168//4168 4153//4153 4169//4169 -f 4169//4169 4153//4153 4154//4154 -f 4169//4169 4154//4154 4170//4170 -f 4170//4170 4154//4154 4155//4155 -f 4170//4170 4155//4155 4171//4171 -f 4171//4171 4155//4155 4156//4156 -f 4171//4171 4156//4156 4172//4172 -f 4172//4172 4156//4156 4157//4157 -f 4172//4172 4157//4157 4173//4173 -f 4173//4173 4157//4157 4158//4158 -f 4173//4173 4158//4158 4174//4174 -f 4174//4174 4158//4158 4016//4016 -f 4175//4175 4176//4176 4177//4177 -f 4177//4177 4176//4176 4178//4178 -f 4177//4177 4178//4178 4179//4179 -f 4179//4179 4178//4178 4180//4180 -f 4179//4179 4180//4180 4181//4181 -f 4181//4181 4180//4180 4182//4182 -f 4181//4181 4182//4182 4183//4183 -f 4183//4183 4182//4182 4184//4184 -f 4183//4183 4184//4184 4185//4185 -f 4185//4185 4184//4184 4186//4186 -f 4185//4185 4186//4186 4187//4187 -f 4187//4187 4186//4186 4188//4188 -f 4187//4187 4188//4188 4189//4189 -f 4189//4189 4188//4188 4190//4190 -f 4189//4189 4190//4190 4191//4191 -f 4012//4012 4011//4011 4160//4160 -f 4160//4160 4159//4159 4012//4012 -f 4012//4012 4159//4159 4192//4192 -f 4012//4012 4192//4192 4010//4010 -f 4134//4134 4133//4133 4159//4159 -f 4159//4159 4133//4133 4193//4193 -f 4159//4159 4193//4193 4192//4192 -f 4192//4192 4193//4193 4194//4194 -f 4192//4192 4194//4194 4010//4010 -f 4110//4110 4109//4109 4133//4133 -f 4133//4133 4109//4109 4195//4195 -f 4133//4133 4195//4195 4193//4193 -f 4193//4193 4195//4195 4196//4196 -f 4193//4193 4196//4196 4194//4194 -f 4194//4194 4196//4196 4197//4197 -f 4194//4194 4197//4197 4010//4010 -f 4198//4198 4197//4197 4199//4199 -f 4199//4199 4197//4197 4196//4196 -f 4199//4199 4196//4196 4200//4200 -f 4200//4200 4196//4196 4195//4195 -f 4200//4200 4195//4195 4201//4201 -f 4201//4201 4195//4195 4109//4109 -f 4201//4201 4109//4109 4202//4202 -f 4202//4202 4109//4109 4108//4108 -f 4202//4202 4108//4108 4069//4069 -f 4069//4069 4068//4068 4202//4202 -f 4202//4202 4068//4068 4203//4203 -f 4202//4202 4203//4203 4201//4201 -f 4201//4201 4203//4203 4204//4204 -f 4201//4201 4204//4204 4200//4200 -f 4200//4200 4204//4204 4205//4205 -f 4200//4200 4205//4205 4199//4199 -f 4199//4199 4205//4205 4206//4206 -f 4199//4199 4206//4206 4198//4198 -f 4198//4198 4206//4206 4207//4207 -f 4198//4198 4207//4207 4010//4010 -f 4020//4020 4145//4145 4021//4021 -f 4021//4021 4145//4145 4208//4208 -f 4021//4021 4208//4208 4209//4209 -f 4209//4209 4208//4208 4210//4210 -f 4209//4209 4210//4210 4211//4211 -f 4211//4211 4210//4210 4212//4212 -f 4211//4211 4212//4212 4213//4213 -f 4213//4213 4212//4212 4214//4214 -f 4213//4213 4214//4214 4215//4215 -f 4215//4215 4214//4214 4216//4216 -f 4215//4215 4216//4216 4217//4217 -f 4217//4217 4216//4216 4218//4218 -f 4217//4217 4218//4218 4219//4219 -f 4219//4219 4218//4218 4220//4220 -f 4219//4219 4220//4220 4221//4221 -f 4221//4221 4220//4220 4222//4222 -f 4221//4221 4222//4222 4223//4223 -f 4223//4223 4222//4222 4224//4224 -f 4223//4223 4224//4224 4225//4225 -f 4225//4225 4224//4224 4226//4226 -f 4225//4225 4226//4226 4227//4227 -f 4227//4227 4226//4226 4228//4228 -f 4227//4227 4228//4228 4010//4010 -f 4010//4010 4229//4229 4230//4230 -f 4230//4230 4229//4229 4231//4231 -f 4230//4230 4231//4231 4232//4232 -f 4232//4232 4231//4231 4233//4233 -f 4232//4232 4233//4233 4234//4234 -f 4234//4234 4233//4233 4235//4235 -f 4234//4234 4235//4235 4236//4236 -f 4236//4236 4235//4235 4237//4237 -f 4236//4236 4237//4237 4238//4238 -f 4238//4238 4237//4237 4239//4239 -f 4238//4238 4239//4239 4240//4240 -f 4240//4240 4239//4239 4241//4241 -f 4240//4240 4241//4241 4242//4242 -f 4242//4242 4241//4241 4243//4243 -f 4242//4242 4243//4243 4244//4244 -f 4244//4244 4243//4243 4245//4245 -f 4244//4244 4245//4245 4246//4246 -f 4246//4246 4245//4245 4247//4247 -f 4246//4246 4247//4247 4248//4248 -f 4248//4248 4247//4247 4249//4249 -f 4248//4248 4249//4249 4250//4250 -f 4250//4250 4249//4249 4251//4251 -f 4250//4250 4251//4251 4252//4252 -f 4252//4252 4251//4251 4016//4016 -f 4009//4009 4008//4008 4162//4162 -f 4162//4162 4161//4161 4009//4009 -f 4009//4009 4161//4161 4253//4253 -f 4009//4009 4253//4253 4010//4010 -f 4147//4147 4146//4146 4161//4161 -f 4161//4161 4146//4146 4254//4254 -f 4161//4161 4254//4254 4253//4253 -f 4253//4253 4254//4254 4255//4255 -f 4253//4253 4255//4255 4010//4010 -f 4122//4122 4121//4121 4146//4146 -f 4146//4146 4121//4121 4256//4256 -f 4146//4146 4256//4256 4254//4254 -f 4254//4254 4256//4256 4257//4257 -f 4254//4254 4257//4257 4255//4255 -f 4255//4255 4257//4257 4258//4258 -f 4255//4255 4258//4258 4010//4010 -f 4098//4098 4097//4097 4121//4121 -f 4121//4121 4097//4097 4259//4259 -f 4121//4121 4259//4259 4256//4256 -f 4256//4256 4259//4259 4260//4260 -f 4256//4256 4260//4260 4257//4257 -f 4257//4257 4260//4260 4261//4261 -f 4257//4257 4261//4261 4258//4258 -f 4258//4258 4261//4261 4262//4262 -f 4258//4258 4262//4262 4010//4010 -f 4079//4079 4078//4078 4097//4097 -f 4097//4097 4078//4078 4263//4263 -f 4097//4097 4263//4263 4259//4259 -f 4259//4259 4263//4263 4264//4264 -f 4259//4259 4264//4264 4260//4260 -f 4260//4260 4264//4264 4265//4265 -f 4260//4260 4265//4265 4261//4261 -f 4261//4261 4265//4265 4266//4266 -f 4261//4261 4266//4266 4262//4262 -f 4262//4262 4266//4266 4267//4267 -f 4262//4262 4267//4267 4010//4010 -f 4010//4010 4163//4163 4268//4268 -f 4268//4268 4163//4163 4164//4164 -f 4268//4268 4164//4164 4269//4269 -f 4269//4269 4164//4164 4165//4165 -f 4269//4269 4165//4165 4270//4270 -f 4270//4270 4165//4165 4166//4166 -f 4270//4270 4166//4166 4271//4271 -f 4271//4271 4166//4166 4167//4167 -f 4271//4271 4167//4167 4272//4272 -f 4272//4272 4167//4167 4168//4168 -f 4272//4272 4168//4168 4273//4273 -f 4273//4273 4168//4168 4169//4169 -f 4273//4273 4169//4169 4274//4274 -f 4274//4274 4169//4169 4170//4170 -f 4274//4274 4170//4170 4275//4275 -f 4275//4275 4170//4170 4171//4171 -f 4275//4275 4171//4171 4276//4276 -f 4276//4276 4171//4171 4172//4172 -f 4276//4276 4172//4172 4277//4277 -f 4277//4277 4172//4172 4173//4173 -f 4277//4277 4173//4173 4278//4278 -f 4278//4278 4173//4173 4174//4174 -f 4278//4278 4174//4174 4019//4019 -f 4019//4019 4174//4174 4016//4016 -f 4010//4010 4268//4268 4279//4279 -f 4279//4279 4268//4268 4269//4269 -f 4279//4279 4269//4269 4280//4280 -f 4280//4280 4269//4269 4270//4270 -f 4280//4280 4270//4270 4281//4281 -f 4281//4281 4270//4270 4271//4271 -f 4281//4281 4271//4271 4282//4282 -f 4282//4282 4271//4271 4272//4272 -f 4282//4282 4272//4272 4283//4283 -f 4283//4283 4272//4272 4273//4273 -f 4283//4283 4273//4273 4284//4284 -f 4284//4284 4273//4273 4274//4274 -f 4284//4284 4274//4274 4285//4285 -f 4285//4285 4274//4274 4275//4275 -f 4285//4285 4275//4275 4286//4286 -f 4286//4286 4275//4275 4276//4276 -f 4286//4286 4276//4276 4287//4287 -f 4287//4287 4276//4276 4277//4277 -f 4287//4287 4277//4277 4288//4288 -f 4288//4288 4277//4277 4278//4278 -f 4288//4288 4278//4278 4289//4289 -f 4289//4289 4278//4278 4019//4019 -f 4289//4289 4019//4019 4018//4018 -f 4018//4018 4019//4019 3026//3026 -f 4018//4018 3026//3026 3025//3025 -f 4059//4059 4058//4058 4078//4078 -f 4078//4078 4058//4058 4060//4060 -f 4078//4078 4060//4060 4263//4263 -f 4263//4263 4060//4060 4080//4080 -f 4263//4263 4080//4080 4264//4264 -f 4264//4264 4080//4080 4099//4099 -f 4264//4264 4099//4099 4265//4265 -f 4265//4265 4099//4099 4123//4123 -f 4265//4265 4123//4123 4266//4266 -f 4266//4266 4123//4123 4148//4148 -f 4266//4266 4148//4148 4267//4267 -f 4267//4267 4148//4148 4163//4163 -f 4267//4267 4163//4163 4010//4010 -f 4016//4016 4290//4290 4018//4018 -f 4018//4018 4290//4290 4291//4291 -f 4018//4018 4291//4291 4289//4289 -f 4289//4289 4291//4291 4292//4292 -f 4289//4289 4292//4292 4288//4288 -f 4288//4288 4292//4292 4293//4293 -f 4288//4288 4293//4293 4287//4287 -f 4287//4287 4293//4293 4294//4294 -f 4287//4287 4294//4294 4286//4286 -f 4286//4286 4294//4294 4295//4295 -f 4286//4286 4295//4295 4285//4285 -f 4285//4285 4295//4295 4296//4296 -f 4285//4285 4296//4296 4284//4284 -f 4284//4284 4296//4296 4297//4297 -f 4284//4284 4297//4297 4283//4283 -f 4283//4283 4297//4297 4298//4298 -f 4283//4283 4298//4298 4282//4282 -f 4282//4282 4298//4298 4299//4299 -f 4282//4282 4299//4299 4281//4281 -f 4281//4281 4299//4299 4300//4300 -f 4281//4281 4300//4300 4280//4280 -f 4280//4280 4300//4300 4301//4301 -f 4280//4280 4301//4301 4279//4279 -f 4279//4279 4301//4301 4010//4010 -f 4298//4298 4302//4302 4299//4299 -f 4299//4299 4302//4302 4303//4303 -f 4299//4299 4303//4303 4300//4300 -f 4300//4300 4303//4303 4304//4304 -f 4300//4300 4304//4304 4301//4301 -f 4301//4301 4304//4304 4010//4010 -f 4022//4022 4305//4305 4306//4306 -f 4306//4306 4305//4305 4307//4307 -f 4306//4306 4307//4307 4308//4308 -f 4308//4308 4307//4307 4309//4309 -f 4308//4308 4309//4309 4310//4310 -f 4310//4310 4309//4309 4311//4311 -f 4310//4310 4311//4311 4312//4312 -f 4312//4312 4311//4311 4313//4313 -f 4312//4312 4313//4313 4314//4314 -f 4314//4314 4313//4313 4315//4315 -f 4314//4314 4315//4315 4316//4316 -f 4316//4316 4315//4315 4317//4317 -f 4316//4316 4317//4317 4318//4318 -f 4318//4318 4317//4317 4319//4319 -f 4318//4318 4319//4319 4302//4302 -f 4302//4302 4319//4319 4320//4320 -f 4302//4302 4320//4320 4303//4303 -f 4303//4303 4320//4320 4321//4321 -f 4303//4303 4321//4321 4304//4304 -f 4304//4304 4321//4321 4010//4010 -f 4305//4305 4175//4175 4307//4307 -f 4307//4307 4175//4175 4177//4177 -f 4307//4307 4177//4177 4309//4309 -f 4309//4309 4177//4177 4179//4179 -f 4309//4309 4179//4179 4311//4311 -f 4311//4311 4179//4179 4181//4181 -f 4311//4311 4181//4181 4313//4313 -f 4313//4313 4181//4181 4183//4183 -f 4313//4313 4183//4183 4315//4315 -f 4315//4315 4183//4183 4185//4185 -f 4315//4315 4185//4185 4317//4317 -f 4317//4317 4185//4185 4187//4187 -f 4317//4317 4187//4187 4319//4319 -f 4319//4319 4187//4187 4189//4189 -f 4319//4319 4189//4189 4320//4320 -f 4320//4320 4189//4189 4191//4191 -f 4320//4320 4191//4191 4321//4321 -f 4321//4321 4191//4191 4010//4010 -f 4010//4010 4230//4230 4008//4008 -f 4008//4008 4230//4230 4232//4232 -f 4008//4008 4232//4232 4162//4162 -f 4162//4162 4232//4232 4234//4234 -f 4162//4162 4234//4234 4147//4147 -f 4147//4147 4234//4234 4236//4236 -f 4147//4147 4236//4236 4122//4122 -f 4122//4122 4236//4236 4238//4238 -f 4122//4122 4238//4238 4098//4098 -f 4098//4098 4238//4238 4240//4240 -f 4098//4098 4240//4240 4079//4079 -f 4079//4079 4240//4240 4242//4242 -f 4079//4079 4242//4242 4059//4059 -f 4059//4059 4242//4242 4244//4244 -f 4059//4059 4244//4244 4057//4057 -f 4057//4057 4244//4244 4246//4246 -f 4057//4057 4246//4246 4055//4055 -f 4055//4055 4246//4246 4248//4248 -f 4055//4055 4248//4248 4053//4053 -f 4053//4053 4248//4248 4250//4250 -f 4053//4053 4250//4250 4051//4051 -f 4051//4051 4250//4250 4252//4252 -f 4051//4051 4252//4252 4049//4049 -f 4049//4049 4252//4252 4016//4016 -f 4229//4229 4144//4144 4231//4231 -f 4231//4231 4144//4144 4119//4119 -f 4231//4231 4119//4119 4233//4233 -f 4233//4233 4119//4119 4095//4095 -f 4233//4233 4095//4095 4235//4235 -f 4235//4235 4095//4095 4076//4076 -f 4235//4235 4076//4076 4237//4237 -f 4237//4237 4076//4076 4046//4046 -f 4237//4237 4046//4046 4239//4239 -f 4239//4239 4046//4046 4039//4039 -f 4239//4239 4039//4039 4241//4241 -f 4241//4241 4039//4039 4033//4033 -f 4241//4241 4033//4033 4243//4243 -f 4243//4243 4033//4033 4028//4028 -f 4243//4243 4028//4028 4245//4245 -f 4245//4245 4028//4028 4024//4024 -f 4245//4245 4024//4024 4247//4247 -f 4247//4247 4024//4024 4013//4013 -f 4247//4247 4013//4013 4249//4249 -f 4249//4249 4013//4013 4015//4015 -f 4249//4249 4015//4015 4251//4251 -f 4251//4251 4015//4015 4016//4016 -f 4145//4145 4120//4120 4208//4208 -f 4208//4208 4120//4120 4135//4135 -f 4208//4208 4135//4135 4210//4210 -f 4210//4210 4135//4135 4136//4136 -f 4210//4210 4136//4136 4212//4212 -f 4212//4212 4136//4136 4137//4137 -f 4212//4212 4137//4137 4214//4214 -f 4214//4214 4137//4137 4138//4138 -f 4214//4214 4138//4138 4216//4216 -f 4216//4216 4138//4138 4139//4139 -f 4216//4216 4139//4139 4218//4218 -f 4218//4218 4139//4139 4140//4140 -f 4218//4218 4140//4140 4220//4220 -f 4220//4220 4140//4140 4141//4141 -f 4220//4220 4141//4141 4222//4222 -f 4222//4222 4141//4141 4142//4142 -f 4222//4222 4142//4142 4224//4224 -f 4224//4224 4142//4142 4143//4143 -f 4224//4224 4143//4143 4226//4226 -f 4226//4226 4143//4143 4144//4144 -f 4226//4226 4144//4144 4228//4228 -f 4228//4228 4144//4144 4229//4229 -f 4228//4228 4229//4229 4010//4010 -f 4190//4190 4010//4010 4191//4191 -f 4176//4176 4067//4067 4178//4178 -f 4178//4178 4067//4067 4069//4069 -f 4178//4178 4069//4069 4180//4180 -f 4180//4180 4069//4069 4108//4108 -f 4180//4180 4108//4108 4182//4182 -f 4182//4182 4108//4108 4110//4110 -f 4182//4182 4110//4110 4184//4184 -f 4184//4184 4110//4110 4134//4134 -f 4184//4184 4134//4134 4186//4186 -f 4186//4186 4134//4134 4160//4160 -f 4186//4186 4160//4160 4188//4188 -f 4188//4188 4160//4160 4011//4011 -f 4188//4188 4011//4011 4190//4190 -f 4190//4190 4011//4011 4010//4010 -f 4020//4020 4016//4016 4145//4145 -f 4022//4022 4021//4021 4305//4305 -f 4305//4305 4021//4021 4209//4209 -f 4305//4305 4209//4209 4175//4175 -f 4175//4175 4209//4209 4211//4211 -f 4175//4175 4211//4211 4176//4176 -f 4176//4176 4211//4211 4213//4213 -f 4176//4176 4213//4213 4067//4067 -f 4067//4067 4213//4213 4215//4215 -f 4067//4067 4215//4215 4068//4068 -f 4068//4068 4215//4215 4217//4217 -f 4068//4068 4217//4217 4203//4203 -f 4203//4203 4217//4217 4219//4219 -f 4203//4203 4219//4219 4204//4204 -f 4204//4204 4219//4219 4221//4221 -f 4204//4204 4221//4221 4205//4205 -f 4205//4205 4221//4221 4223//4223 -f 4205//4205 4223//4223 4206//4206 -f 4206//4206 4223//4223 4225//4225 -f 4206//4206 4225//4225 4207//4207 -f 4207//4207 4225//4225 4227//4227 -f 4207//4207 4227//4227 4010//4010 -f 4302//4302 4298//4298 4318//4318 -f 4318//4318 4298//4298 4297//4297 -f 4318//4318 4297//4297 4316//4316 -f 4316//4316 4297//4297 4296//4296 -f 4316//4316 4296//4296 4314//4314 -f 4314//4314 4296//4296 4295//4295 -f 4314//4314 4295//4295 4312//4312 -f 4312//4312 4295//4295 4294//4294 -f 4312//4312 4294//4294 4310//4310 -f 4310//4310 4294//4294 4293//4293 -f 4310//4310 4293//4293 4308//4308 -f 4308//4308 4293//4293 4292//4292 -f 4308//4308 4292//4292 4306//4306 -f 4306//4306 4292//4292 4291//4291 -f 4306//4306 4291//4291 4022//4022 -f 4022//4022 4291//4291 4290//4290 -f 4022//4022 4290//4290 4020//4020 -f 4020//4020 4290//4290 4016//4016 -f 4010//4010 3342//3342 3321//3321 -f 3343//3343 3342//3342 4010//4010 -f 4010//4010 3320//3320 3325//3325 -f 3321//3321 3320//3320 4010//4010 -f 4010//4010 3325//3325 3327//3327 -f 3341//3341 3339//3339 4010//4010 -f 3329//3329 3317//3317 4198//4198 -f 4010//4010 3327//3327 4198//4198 -f 4198//4198 3327//3327 3329//3329 -f 3336//3336 3334//3334 4197//4197 -f 3336//3336 4197//4197 3337//3337 -f 4198//4198 3317//3317 3332//3332 -f 4198//4198 3332//3332 4197//4197 -f 4197//4197 3332//3332 3331//3331 -f 4197//4197 3331//3331 3337//3337 -f 3339//3339 3343//3343 4010//4010 -f 3334//3334 3341//3341 4197//4197 -f 4197//4197 3341//3341 4010//4010 -f 4322//4322 4323//4323 4324//4324 -f 4325//4325 4326//4326 4324//4324 -f 4327//4327 4328//4328 4329//4329 -f 4329//4329 4328//4328 4330//4330 -f 4331//4331 4330//4330 4328//4328 -f 3091//3091 3097//3097 4332//4332 -f 4332//4332 3097//3097 3096//3096 -f 4332//4332 3096//3096 3094//3094 -f 4330//4330 3099//3099 3103//3103 -f 3101//3101 3099//3099 4330//4330 -f 3094//3094 3101//3101 4332//4332 -f 4332//4332 3101//3101 4330//4330 -f 4330//4330 3102//3102 3081//3081 -f 3103//3103 3102//3102 4330//4330 -f 4330//4330 3080//3080 3085//3085 -f 3081//3081 3080//3080 4330//4330 -f 4330//4330 3085//3085 3087//3087 -f 4330//4330 3087//3087 4333//4333 -f 4333//4333 3087//3087 3089//3089 -f 3089//3089 3050//3050 4333//4333 -f 4333//4333 3050//3050 3092//3092 -f 4334//4334 4335//4335 4336//4336 -f 4331//4331 4328//4328 4337//4337 -f 4337//4337 4328//4328 4327//4327 -f 4337//4337 4327//4327 4338//4338 -f 4339//4339 4330//4330 4331//4331 -f 4339//4339 4331//4331 4340//4340 -f 4340//4340 4331//4331 4337//4337 -f 4340//4340 4337//4337 4341//4341 -f 4341//4341 4337//4337 4338//4338 -f 4341//4341 4338//4338 4342//4342 -f 4343//4343 4330//4330 4339//4339 -f 4343//4343 4339//4339 4344//4344 -f 4344//4344 4339//4339 4340//4340 -f 4344//4344 4340//4340 4345//4345 -f 4345//4345 4340//4340 4341//4341 -f 4345//4345 4341//4341 4346//4346 -f 4346//4346 4341//4341 4342//4342 -f 4346//4346 4342//4342 4347//4347 -f 4348//4348 4330//4330 4343//4343 -f 4348//4348 4343//4343 4349//4349 -f 4349//4349 4343//4343 4344//4344 -f 4349//4349 4344//4344 4350//4350 -f 4350//4350 4344//4344 4345//4345 -f 4350//4350 4345//4345 4351//4351 -f 4351//4351 4345//4345 4346//4346 -f 4351//4351 4346//4346 4352//4352 -f 4352//4352 4346//4346 4347//4347 -f 4352//4352 4347//4347 4353//4353 -f 4354//4354 4330//4330 4348//4348 -f 4354//4354 4348//4348 4355//4355 -f 4355//4355 4348//4348 4349//4349 -f 4355//4355 4349//4349 4356//4356 -f 4356//4356 4349//4349 4350//4350 -f 4356//4356 4350//4350 4357//4357 -f 4357//4357 4350//4350 4351//4351 -f 4357//4357 4351//4351 4358//4358 -f 4358//4358 4351//4351 4352//4352 -f 4358//4358 4352//4352 4359//4359 -f 4359//4359 4352//4352 4353//4353 -f 4359//4359 4353//4353 4360//4360 -f 4361//4361 4330//4330 4354//4354 -f 4330//4330 4362//4362 4363//4363 -f 4363//4363 4362//4362 4364//4364 -f 4363//4363 4364//4364 4365//4365 -f 4365//4365 4364//4364 4366//4366 -f 4365//4365 4366//4366 4367//4367 -f 4367//4367 4366//4366 4368//4368 -f 4367//4367 4368//4368 4369//4369 -f 4369//4369 4368//4368 4370//4370 -f 4369//4369 4370//4370 4371//4371 -f 4371//4371 4370//4370 4372//4372 -f 4371//4371 4372//4372 4373//4373 -f 4374//4374 4372//4372 4375//4375 -f 4375//4375 4372//4372 4370//4370 -f 4375//4375 4370//4370 4376//4376 -f 4376//4376 4370//4370 4368//4368 -f 4376//4376 4368//4368 4377//4377 -f 4377//4377 4368//4368 4366//4366 -f 4377//4377 4366//4366 4378//4378 -f 4378//4378 4366//4366 4364//4364 -f 4378//4378 4364//4364 4379//4379 -f 4379//4379 4364//4364 4362//4362 -f 4379//4379 4362//4362 4380//4380 -f 4380//4380 4362//4362 4330//4330 -f 4381//4381 4382//4382 4383//4383 -f 4361//4361 4354//4354 4384//4384 -f 4384//4384 4354//4354 4355//4355 -f 4384//4384 4355//4355 4385//4385 -f 4385//4385 4355//4355 4356//4356 -f 4385//4385 4356//4356 4386//4386 -f 4386//4386 4356//4356 4357//4357 -f 4386//4386 4357//4357 4387//4387 -f 4387//4387 4357//4357 4358//4358 -f 4387//4387 4358//4358 4388//4388 -f 4388//4388 4358//4358 4359//4359 -f 4388//4388 4359//4359 4389//4389 -f 4389//4389 4359//4359 4360//4360 -f 4389//4389 4360//4360 4390//4390 -f 4391//4391 4330//4330 4361//4361 -f 4373//4373 4392//4392 4393//4393 -f 4394//4394 4374//4374 4395//4395 -f 4395//4395 4374//4374 4375//4375 -f 4395//4395 4375//4375 4396//4396 -f 4396//4396 4375//4375 4376//4376 -f 4396//4396 4376//4376 4397//4397 -f 4397//4397 4376//4376 4377//4377 -f 4397//4397 4377//4377 4398//4398 -f 4398//4398 4377//4377 4378//4378 -f 4398//4398 4378//4378 4399//4399 -f 4399//4399 4378//4378 4379//4379 -f 4399//4399 4379//4379 4400//4400 -f 4400//4400 4379//4379 4380//4380 -f 4400//4400 4380//4380 4401//4401 -f 4401//4401 4380//4380 4330//4330 -f 4391//4391 4361//4361 4402//4402 -f 4402//4402 4361//4361 4384//4384 -f 4402//4402 4384//4384 4403//4403 -f 4403//4403 4384//4384 4385//4385 -f 4403//4403 4385//4385 4404//4404 -f 4404//4404 4385//4385 4386//4386 -f 4404//4404 4386//4386 4405//4405 -f 4405//4405 4386//4386 4387//4387 -f 4405//4405 4387//4387 4406//4406 -f 4406//4406 4387//4387 4388//4388 -f 4406//4406 4388//4388 4407//4407 -f 4407//4407 4388//4388 4389//4389 -f 4407//4407 4389//4389 4408//4408 -f 4408//4408 4389//4389 4390//4390 -f 4408//4408 4390//4390 4409//4409 -f 4410//4410 4330//4330 4391//4391 -f 4393//4393 4411//4411 4412//4412 -f 4413//4413 4394//4394 4414//4414 -f 4414//4414 4394//4394 4395//4395 -f 4414//4414 4395//4395 4415//4415 -f 4415//4415 4395//4395 4396//4396 -f 4415//4415 4396//4396 4416//4416 -f 4416//4416 4396//4396 4397//4397 -f 4416//4416 4397//4397 4417//4417 -f 4417//4417 4397//4397 4398//4398 -f 4417//4417 4398//4398 4418//4418 -f 4418//4418 4398//4398 4399//4399 -f 4418//4418 4399//4399 4419//4419 -f 4419//4419 4399//4399 4400//4400 -f 4419//4419 4400//4400 4420//4420 -f 4420//4420 4400//4400 4401//4401 -f 4420//4420 4401//4401 4421//4421 -f 4421//4421 4401//4401 4330//4330 -f 4422//4422 4423//4423 4424//4424 -f 4410//4410 4391//4391 4425//4425 -f 4425//4425 4391//4391 4402//4402 -f 4425//4425 4402//4402 4426//4426 -f 4426//4426 4402//4402 4403//4403 -f 4426//4426 4403//4403 4427//4427 -f 4427//4427 4403//4403 4404//4404 -f 4427//4427 4404//4404 4428//4428 -f 4428//4428 4404//4404 4405//4405 -f 4428//4428 4405//4405 4429//4429 -f 4429//4429 4405//4405 4406//4406 -f 4429//4429 4406//4406 4430//4430 -f 4430//4430 4406//4406 4407//4407 -f 4430//4430 4407//4407 4431//4431 -f 4431//4431 4407//4407 4408//4408 -f 4431//4431 4408//4408 4432//4432 -f 4432//4432 4408//4408 4409//4409 -f 4432//4432 4409//4409 4433//4433 -f 4434//4434 4330//4330 4410//4410 -f 4412//4412 4435//4435 4436//4436 -f 4437//4437 4413//4413 4438//4438 -f 4438//4438 4413//4413 4414//4414 -f 4438//4438 4414//4414 4439//4439 -f 4439//4439 4414//4414 4415//4415 -f 4439//4439 4415//4415 4440//4440 -f 4440//4440 4415//4415 4416//4416 -f 4440//4440 4416//4416 4441//4441 -f 4441//4441 4416//4416 4417//4417 -f 4441//4441 4417//4417 4442//4442 -f 4442//4442 4417//4417 4418//4418 -f 4442//4442 4418//4418 4443//4443 -f 4443//4443 4418//4418 4419//4419 -f 4443//4443 4419//4419 4444//4444 -f 4444//4444 4419//4419 4420//4420 -f 4444//4444 4420//4420 4445//4445 -f 4445//4445 4420//4420 4421//4421 -f 4445//4445 4421//4421 4446//4446 -f 4446//4446 4421//4421 4330//4330 -f 4424//4424 4447//4447 4448//4448 -f 4434//4434 4410//4410 4449//4449 -f 4449//4449 4410//4410 4425//4425 -f 4449//4449 4425//4425 4450//4450 -f 4450//4450 4425//4425 4426//4426 -f 4450//4450 4426//4426 4451//4451 -f 4451//4451 4426//4426 4427//4427 -f 4451//4451 4427//4427 4452//4452 -f 4452//4452 4427//4427 4428//4428 -f 4452//4452 4428//4428 4453//4453 -f 4453//4453 4428//4428 4429//4429 -f 4453//4453 4429//4429 4454//4454 -f 4454//4454 4429//4429 4430//4430 -f 4454//4454 4430//4430 4455//4455 -f 4455//4455 4430//4430 4431//4431 -f 4455//4455 4431//4431 4456//4456 -f 4456//4456 4431//4431 4432//4432 -f 4456//4456 4432//4432 4457//4457 -f 4457//4457 4432//4432 4433//4433 -f 4457//4457 4433//4433 4458//4458 -f 4459//4459 4330//4330 4434//4434 -f 4436//4436 4460//4460 4461//4461 -f 4462//4462 4437//4437 4463//4463 -f 4463//4463 4437//4437 4438//4438 -f 4463//4463 4438//4438 4464//4464 -f 4464//4464 4438//4438 4439//4439 -f 4464//4464 4439//4439 4465//4465 -f 4465//4465 4439//4439 4440//4440 -f 4465//4465 4440//4440 4466//4466 -f 4466//4466 4440//4440 4441//4441 -f 4466//4466 4441//4441 4467//4467 -f 4467//4467 4441//4441 4442//4442 -f 4467//4467 4442//4442 4468//4468 -f 4468//4468 4442//4442 4443//4443 -f 4468//4468 4443//4443 4469//4469 -f 4469//4469 4443//4443 4444//4444 -f 4469//4469 4444//4444 4470//4470 -f 4470//4470 4444//4444 4445//4445 -f 4470//4470 4445//4445 4471//4471 -f 4471//4471 4445//4445 4446//4446 -f 4471//4471 4446//4446 4472//4472 -f 4472//4472 4446//4446 4330//4330 -f 4448//4448 4473//4473 4474//4474 -f 4461//4461 4475//4475 4476//4476 -f 4477//4477 4462//4462 4478//4478 -f 4478//4478 4462//4462 4463//4463 -f 4478//4478 4463//4463 4479//4479 -f 4479//4479 4463//4463 4464//4464 -f 4479//4479 4464//4464 4480//4480 -f 4480//4480 4464//4464 4465//4465 -f 4480//4480 4465//4465 4481//4481 -f 4481//4481 4465//4465 4466//4466 -f 4481//4481 4466//4466 4482//4482 -f 4482//4482 4466//4466 4467//4467 -f 4482//4482 4467//4467 4483//4483 -f 4483//4483 4467//4467 4468//4468 -f 4483//4483 4468//4468 4484//4484 -f 4484//4484 4468//4468 4469//4469 -f 4484//4484 4469//4469 4485//4485 -f 4485//4485 4469//4469 4470//4470 -f 4485//4485 4470//4470 4486//4486 -f 4486//4486 4470//4470 4471//4471 -f 4486//4486 4471//4471 4487//4487 -f 4487//4487 4471//4471 4472//4472 -f 4487//4487 4472//4472 4488//4488 -f 4488//4488 4472//4472 4330//4330 -f 4489//4489 4490//4490 4491//4491 -f 4491//4491 4490//4490 4492//4492 -f 4491//4491 4492//4492 4493//4493 -f 4493//4493 4492//4492 4494//4494 -f 4493//4493 4494//4494 4495//4495 -f 4495//4495 4494//4494 4496//4496 -f 4495//4495 4496//4496 4497//4497 -f 4497//4497 4496//4496 4498//4498 -f 4497//4497 4498//4498 4499//4499 -f 4499//4499 4498//4498 4500//4500 -f 4499//4499 4500//4500 4501//4501 -f 4501//4501 4500//4500 4502//4502 -f 4501//4501 4502//4502 4503//4503 -f 4503//4503 4502//4502 4504//4504 -f 4503//4503 4504//4504 4505//4505 -f 4326//4326 4325//4325 4474//4474 -f 4474//4474 4473//4473 4326//4326 -f 4326//4326 4473//4473 4506//4506 -f 4326//4326 4506//4506 4324//4324 -f 4448//4448 4447//4447 4473//4473 -f 4473//4473 4447//4447 4507//4507 -f 4473//4473 4507//4507 4506//4506 -f 4506//4506 4507//4507 4508//4508 -f 4506//4506 4508//4508 4324//4324 -f 4424//4424 4423//4423 4447//4447 -f 4447//4447 4423//4423 4509//4509 -f 4447//4447 4509//4509 4507//4507 -f 4507//4507 4509//4509 4510//4510 -f 4507//4507 4510//4510 4508//4508 -f 4508//4508 4510//4510 4511//4511 -f 4508//4508 4511//4511 4324//4324 -f 4512//4512 4511//4511 4513//4513 -f 4513//4513 4511//4511 4510//4510 -f 4513//4513 4510//4510 4514//4514 -f 4514//4514 4510//4510 4509//4509 -f 4514//4514 4509//4509 4515//4515 -f 4515//4515 4509//4509 4423//4423 -f 4515//4515 4423//4423 4516//4516 -f 4516//4516 4423//4423 4422//4422 -f 4516//4516 4422//4422 4383//4383 -f 4383//4383 4382//4382 4516//4516 -f 4516//4516 4382//4382 4517//4517 -f 4516//4516 4517//4517 4515//4515 -f 4515//4515 4517//4517 4518//4518 -f 4515//4515 4518//4518 4514//4514 -f 4514//4514 4518//4518 4519//4519 -f 4514//4514 4519//4519 4513//4513 -f 4513//4513 4519//4519 4520//4520 -f 4513//4513 4520//4520 4512//4512 -f 4512//4512 4520//4520 4521//4521 -f 4512//4512 4521//4521 4324//4324 -f 4334//4334 4459//4459 4335//4335 -f 4335//4335 4459//4459 4522//4522 -f 4335//4335 4522//4522 4523//4523 -f 4523//4523 4522//4522 4524//4524 -f 4523//4523 4524//4524 4525//4525 -f 4525//4525 4524//4524 4526//4526 -f 4525//4525 4526//4526 4527//4527 -f 4527//4527 4526//4526 4528//4528 -f 4527//4527 4528//4528 4529//4529 -f 4529//4529 4528//4528 4530//4530 -f 4529//4529 4530//4530 4531//4531 -f 4531//4531 4530//4530 4532//4532 -f 4531//4531 4532//4532 4533//4533 -f 4533//4533 4532//4532 4534//4534 -f 4533//4533 4534//4534 4535//4535 -f 4535//4535 4534//4534 4536//4536 -f 4535//4535 4536//4536 4537//4537 -f 4537//4537 4536//4536 4538//4538 -f 4537//4537 4538//4538 4539//4539 -f 4539//4539 4538//4538 4540//4540 -f 4539//4539 4540//4540 4541//4541 -f 4541//4541 4540//4540 4542//4542 -f 4541//4541 4542//4542 4324//4324 -f 4324//4324 4543//4543 4544//4544 -f 4544//4544 4543//4543 4545//4545 -f 4544//4544 4545//4545 4546//4546 -f 4546//4546 4545//4545 4547//4547 -f 4546//4546 4547//4547 4548//4548 -f 4548//4548 4547//4547 4549//4549 -f 4548//4548 4549//4549 4550//4550 -f 4550//4550 4549//4549 4551//4551 -f 4550//4550 4551//4551 4552//4552 -f 4552//4552 4551//4551 4553//4553 -f 4552//4552 4553//4553 4554//4554 -f 4554//4554 4553//4553 4555//4555 -f 4554//4554 4555//4555 4556//4556 -f 4556//4556 4555//4555 4557//4557 -f 4556//4556 4557//4557 4558//4558 -f 4558//4558 4557//4557 4559//4559 -f 4558//4558 4559//4559 4560//4560 -f 4560//4560 4559//4559 4561//4561 -f 4560//4560 4561//4561 4562//4562 -f 4562//4562 4561//4561 4563//4563 -f 4562//4562 4563//4563 4564//4564 -f 4564//4564 4563//4563 4565//4565 -f 4564//4564 4565//4565 4566//4566 -f 4566//4566 4565//4565 4330//4330 -f 4323//4323 4322//4322 4476//4476 -f 4476//4476 4475//4475 4323//4323 -f 4323//4323 4475//4475 4567//4567 -f 4323//4323 4567//4567 4324//4324 -f 4461//4461 4460//4460 4475//4475 -f 4475//4475 4460//4460 4568//4568 -f 4475//4475 4568//4568 4567//4567 -f 4567//4567 4568//4568 4569//4569 -f 4567//4567 4569//4569 4324//4324 -f 4436//4436 4435//4435 4460//4460 -f 4460//4460 4435//4435 4570//4570 -f 4460//4460 4570//4570 4568//4568 -f 4568//4568 4570//4570 4571//4571 -f 4568//4568 4571//4571 4569//4569 -f 4569//4569 4571//4571 4572//4572 -f 4569//4569 4572//4572 4324//4324 -f 4412//4412 4411//4411 4435//4435 -f 4435//4435 4411//4411 4573//4573 -f 4435//4435 4573//4573 4570//4570 -f 4570//4570 4573//4573 4574//4574 -f 4570//4570 4574//4574 4571//4571 -f 4571//4571 4574//4574 4575//4575 -f 4571//4571 4575//4575 4572//4572 -f 4572//4572 4575//4575 4576//4576 -f 4572//4572 4576//4576 4324//4324 -f 4393//4393 4392//4392 4411//4411 -f 4411//4411 4392//4392 4577//4577 -f 4411//4411 4577//4577 4573//4573 -f 4573//4573 4577//4577 4578//4578 -f 4573//4573 4578//4578 4574//4574 -f 4574//4574 4578//4578 4579//4579 -f 4574//4574 4579//4579 4575//4575 -f 4575//4575 4579//4579 4580//4580 -f 4575//4575 4580//4580 4576//4576 -f 4576//4576 4580//4580 4581//4581 -f 4576//4576 4581//4581 4324//4324 -f 4324//4324 4477//4477 4582//4582 -f 4582//4582 4477//4477 4478//4478 -f 4582//4582 4478//4478 4583//4583 -f 4583//4583 4478//4478 4479//4479 -f 4583//4583 4479//4479 4584//4584 -f 4584//4584 4479//4479 4480//4480 -f 4584//4584 4480//4480 4585//4585 -f 4585//4585 4480//4480 4481//4481 -f 4585//4585 4481//4481 4586//4586 -f 4586//4586 4481//4481 4482//4482 -f 4586//4586 4482//4482 4587//4587 -f 4587//4587 4482//4482 4483//4483 -f 4587//4587 4483//4483 4588//4588 -f 4588//4588 4483//4483 4484//4484 -f 4588//4588 4484//4484 4589//4589 -f 4589//4589 4484//4484 4485//4485 -f 4589//4589 4485//4485 4590//4590 -f 4590//4590 4485//4485 4486//4486 -f 4590//4590 4486//4486 4591//4591 -f 4591//4591 4486//4486 4487//4487 -f 4591//4591 4487//4487 4592//4592 -f 4592//4592 4487//4487 4488//4488 -f 4592//4592 4488//4488 4333//4333 -f 4333//4333 4488//4488 4330//4330 -f 4324//4324 4582//4582 4593//4593 -f 4593//4593 4582//4582 4583//4583 -f 4593//4593 4583//4583 4594//4594 -f 4594//4594 4583//4583 4584//4584 -f 4594//4594 4584//4584 4595//4595 -f 4595//4595 4584//4584 4585//4585 -f 4595//4595 4585//4585 4596//4596 -f 4596//4596 4585//4585 4586//4586 -f 4596//4596 4586//4586 4597//4597 -f 4597//4597 4586//4586 4587//4587 -f 4597//4597 4587//4587 4598//4598 -f 4598//4598 4587//4587 4588//4588 -f 4598//4598 4588//4588 4599//4599 -f 4599//4599 4588//4588 4589//4589 -f 4599//4599 4589//4589 4600//4600 -f 4600//4600 4589//4589 4590//4590 -f 4600//4600 4590//4590 4601//4601 -f 4601//4601 4590//4590 4591//4591 -f 4601//4601 4591//4591 4602//4602 -f 4602//4602 4591//4591 4592//4592 -f 4602//4602 4592//4592 4603//4603 -f 4603//4603 4592//4592 4333//4333 -f 4603//4603 4333//4333 4332//4332 -f 4332//4332 4333//4333 3092//3092 -f 4332//4332 3092//3092 3091//3091 -f 4373//4373 4372//4372 4392//4392 -f 4392//4392 4372//4372 4374//4374 -f 4392//4392 4374//4374 4577//4577 -f 4577//4577 4374//4374 4394//4394 -f 4577//4577 4394//4394 4578//4578 -f 4578//4578 4394//4394 4413//4413 -f 4578//4578 4413//4413 4579//4579 -f 4579//4579 4413//4413 4437//4437 -f 4579//4579 4437//4437 4580//4580 -f 4580//4580 4437//4437 4462//4462 -f 4580//4580 4462//4462 4581//4581 -f 4581//4581 4462//4462 4477//4477 -f 4581//4581 4477//4477 4324//4324 -f 4330//4330 4604//4604 4332//4332 -f 4332//4332 4604//4604 4605//4605 -f 4332//4332 4605//4605 4603//4603 -f 4603//4603 4605//4605 4606//4606 -f 4603//4603 4606//4606 4602//4602 -f 4602//4602 4606//4606 4607//4607 -f 4602//4602 4607//4607 4601//4601 -f 4601//4601 4607//4607 4608//4608 -f 4601//4601 4608//4608 4600//4600 -f 4600//4600 4608//4608 4609//4609 -f 4600//4600 4609//4609 4599//4599 -f 4599//4599 4609//4609 4610//4610 -f 4599//4599 4610//4610 4598//4598 -f 4598//4598 4610//4610 4611//4611 -f 4598//4598 4611//4611 4597//4597 -f 4597//4597 4611//4611 4612//4612 -f 4597//4597 4612//4612 4596//4596 -f 4596//4596 4612//4612 4613//4613 -f 4596//4596 4613//4613 4595//4595 -f 4595//4595 4613//4613 4614//4614 -f 4595//4595 4614//4614 4594//4594 -f 4594//4594 4614//4614 4615//4615 -f 4594//4594 4615//4615 4593//4593 -f 4593//4593 4615//4615 4324//4324 -f 4612//4612 4616//4616 4613//4613 -f 4613//4613 4616//4616 4617//4617 -f 4613//4613 4617//4617 4614//4614 -f 4614//4614 4617//4617 4618//4618 -f 4614//4614 4618//4618 4615//4615 -f 4615//4615 4618//4618 4324//4324 -f 4336//4336 4619//4619 4620//4620 -f 4620//4620 4619//4619 4621//4621 -f 4620//4620 4621//4621 4622//4622 -f 4622//4622 4621//4621 4623//4623 -f 4622//4622 4623//4623 4624//4624 -f 4624//4624 4623//4623 4625//4625 -f 4624//4624 4625//4625 4626//4626 -f 4626//4626 4625//4625 4627//4627 -f 4626//4626 4627//4627 4628//4628 -f 4628//4628 4627//4627 4629//4629 -f 4628//4628 4629//4629 4630//4630 -f 4630//4630 4629//4629 4631//4631 -f 4630//4630 4631//4631 4632//4632 -f 4632//4632 4631//4631 4633//4633 -f 4632//4632 4633//4633 4616//4616 -f 4616//4616 4633//4633 4634//4634 -f 4616//4616 4634//4634 4617//4617 -f 4617//4617 4634//4634 4635//4635 -f 4617//4617 4635//4635 4618//4618 -f 4618//4618 4635//4635 4324//4324 -f 4619//4619 4489//4489 4621//4621 -f 4621//4621 4489//4489 4491//4491 -f 4621//4621 4491//4491 4623//4623 -f 4623//4623 4491//4491 4493//4493 -f 4623//4623 4493//4493 4625//4625 -f 4625//4625 4493//4493 4495//4495 -f 4625//4625 4495//4495 4627//4627 -f 4627//4627 4495//4495 4497//4497 -f 4627//4627 4497//4497 4629//4629 -f 4629//4629 4497//4497 4499//4499 -f 4629//4629 4499//4499 4631//4631 -f 4631//4631 4499//4499 4501//4501 -f 4631//4631 4501//4501 4633//4633 -f 4633//4633 4501//4501 4503//4503 -f 4633//4633 4503//4503 4634//4634 -f 4634//4634 4503//4503 4505//4505 -f 4634//4634 4505//4505 4635//4635 -f 4635//4635 4505//4505 4324//4324 -f 4324//4324 4544//4544 4322//4322 -f 4322//4322 4544//4544 4546//4546 -f 4322//4322 4546//4546 4476//4476 -f 4476//4476 4546//4546 4548//4548 -f 4476//4476 4548//4548 4461//4461 -f 4461//4461 4548//4548 4550//4550 -f 4461//4461 4550//4550 4436//4436 -f 4436//4436 4550//4550 4552//4552 -f 4436//4436 4552//4552 4412//4412 -f 4412//4412 4552//4552 4554//4554 -f 4412//4412 4554//4554 4393//4393 -f 4393//4393 4554//4554 4556//4556 -f 4393//4393 4556//4556 4373//4373 -f 4373//4373 4556//4556 4558//4558 -f 4373//4373 4558//4558 4371//4371 -f 4371//4371 4558//4558 4560//4560 -f 4371//4371 4560//4560 4369//4369 -f 4369//4369 4560//4560 4562//4562 -f 4369//4369 4562//4562 4367//4367 -f 4367//4367 4562//4562 4564//4564 -f 4367//4367 4564//4564 4365//4365 -f 4365//4365 4564//4564 4566//4566 -f 4365//4365 4566//4566 4363//4363 -f 4363//4363 4566//4566 4330//4330 -f 4543//4543 4458//4458 4545//4545 -f 4545//4545 4458//4458 4433//4433 -f 4545//4545 4433//4433 4547//4547 -f 4547//4547 4433//4433 4409//4409 -f 4547//4547 4409//4409 4549//4549 -f 4549//4549 4409//4409 4390//4390 -f 4549//4549 4390//4390 4551//4551 -f 4551//4551 4390//4390 4360//4360 -f 4551//4551 4360//4360 4553//4553 -f 4553//4553 4360//4360 4353//4353 -f 4553//4553 4353//4353 4555//4555 -f 4555//4555 4353//4353 4347//4347 -f 4555//4555 4347//4347 4557//4557 -f 4557//4557 4347//4347 4342//4342 -f 4557//4557 4342//4342 4559//4559 -f 4559//4559 4342//4342 4338//4338 -f 4559//4559 4338//4338 4561//4561 -f 4561//4561 4338//4338 4327//4327 -f 4561//4561 4327//4327 4563//4563 -f 4563//4563 4327//4327 4329//4329 -f 4563//4563 4329//4329 4565//4565 -f 4565//4565 4329//4329 4330//4330 -f 4459//4459 4434//4434 4522//4522 -f 4522//4522 4434//4434 4449//4449 -f 4522//4522 4449//4449 4524//4524 -f 4524//4524 4449//4449 4450//4450 -f 4524//4524 4450//4450 4526//4526 -f 4526//4526 4450//4450 4451//4451 -f 4526//4526 4451//4451 4528//4528 -f 4528//4528 4451//4451 4452//4452 -f 4528//4528 4452//4452 4530//4530 -f 4530//4530 4452//4452 4453//4453 -f 4530//4530 4453//4453 4532//4532 -f 4532//4532 4453//4453 4454//4454 -f 4532//4532 4454//4454 4534//4534 -f 4534//4534 4454//4454 4455//4455 -f 4534//4534 4455//4455 4536//4536 -f 4536//4536 4455//4455 4456//4456 -f 4536//4536 4456//4456 4538//4538 -f 4538//4538 4456//4456 4457//4457 -f 4538//4538 4457//4457 4540//4540 -f 4540//4540 4457//4457 4458//4458 -f 4540//4540 4458//4458 4542//4542 -f 4542//4542 4458//4458 4543//4543 -f 4542//4542 4543//4543 4324//4324 -f 4504//4504 4324//4324 4505//4505 -f 4490//4490 4381//4381 4492//4492 -f 4492//4492 4381//4381 4383//4383 -f 4492//4492 4383//4383 4494//4494 -f 4494//4494 4383//4383 4422//4422 -f 4494//4494 4422//4422 4496//4496 -f 4496//4496 4422//4422 4424//4424 -f 4496//4496 4424//4424 4498//4498 -f 4498//4498 4424//4424 4448//4448 -f 4498//4498 4448//4448 4500//4500 -f 4500//4500 4448//4448 4474//4474 -f 4500//4500 4474//4474 4502//4502 -f 4502//4502 4474//4474 4325//4325 -f 4502//4502 4325//4325 4504//4504 -f 4504//4504 4325//4325 4324//4324 -f 4334//4334 4330//4330 4459//4459 -f 4336//4336 4335//4335 4619//4619 -f 4619//4619 4335//4335 4523//4523 -f 4619//4619 4523//4523 4489//4489 -f 4489//4489 4523//4523 4525//4525 -f 4489//4489 4525//4525 4490//4490 -f 4490//4490 4525//4525 4527//4527 -f 4490//4490 4527//4527 4381//4381 -f 4381//4381 4527//4527 4529//4529 -f 4381//4381 4529//4529 4382//4382 -f 4382//4382 4529//4529 4531//4531 -f 4382//4382 4531//4531 4517//4517 -f 4517//4517 4531//4531 4533//4533 -f 4517//4517 4533//4533 4518//4518 -f 4518//4518 4533//4533 4535//4535 -f 4518//4518 4535//4535 4519//4519 -f 4519//4519 4535//4535 4537//4537 -f 4519//4519 4537//4537 4520//4520 -f 4520//4520 4537//4537 4539//4539 -f 4520//4520 4539//4539 4521//4521 -f 4521//4521 4539//4539 4541//4541 -f 4521//4521 4541//4541 4324//4324 -f 4616//4616 4612//4612 4632//4632 -f 4632//4632 4612//4612 4611//4611 -f 4632//4632 4611//4611 4630//4630 -f 4630//4630 4611//4611 4610//4610 -f 4630//4630 4610//4610 4628//4628 -f 4628//4628 4610//4610 4609//4609 -f 4628//4628 4609//4609 4626//4626 -f 4626//4626 4609//4609 4608//4608 -f 4626//4626 4608//4608 4624//4624 -f 4624//4624 4608//4608 4607//4607 -f 4624//4624 4607//4607 4622//4622 -f 4622//4622 4607//4607 4606//4606 -f 4622//4622 4606//4606 4620//4620 -f 4620//4620 4606//4606 4605//4605 -f 4620//4620 4605//4605 4336//4336 -f 4336//4336 4605//4605 4604//4604 -f 4336//4336 4604//4604 4334//4334 -f 4334//4334 4604//4604 4330//4330 -f 4324//4324 3012//3012 2991//2991 -f 3013//3013 3012//3012 4324//4324 -f 4324//4324 2990//2990 2995//2995 -f 2991//2991 2990//2990 4324//4324 -f 4324//4324 2995//2995 2997//2997 -f 3011//3011 3009//3009 4324//4324 -f 2999//2999 2987//2987 4512//4512 -f 4324//4324 2997//2997 4512//4512 -f 4512//4512 2997//2997 2999//2999 -f 3006//3006 3004//3004 4511//4511 -f 3006//3006 4511//4511 3007//3007 -f 4512//4512 2987//2987 3002//3002 -f 4512//4512 3002//3002 4511//4511 -f 4511//4511 3002//3002 3001//3001 -f 4511//4511 3001//3001 3007//3007 -f 3009//3009 3013//3013 4324//4324 -f 3004//3004 3011//3011 4511//4511 -f 4511//4511 3011//3011 4324//4324 -f 4636//4636 4637//4637 4638//4638 -f 4639//4639 4640//4640 4638//4638 -f 4641//4641 4642//4642 4643//4643 -f 4643//4643 4642//4642 4644//4644 -f 4645//4645 4644//4644 4642//4642 -f 3157//3157 3163//3163 4646//4646 -f 4646//4646 3163//3163 3162//3162 -f 4646//4646 3162//3162 3160//3160 -f 4644//4644 3165//3165 3169//3169 -f 3167//3167 3165//3165 4644//4644 -f 3160//3160 3167//3167 4646//4646 -f 4646//4646 3167//3167 4644//4644 -f 4644//4644 3168//3168 3147//3147 -f 3169//3169 3168//3168 4644//4644 -f 4644//4644 3146//3146 3151//3151 -f 3147//3147 3146//3146 4644//4644 -f 4644//4644 3151//3151 3153//3153 -f 4644//4644 3153//3153 4647//4647 -f 4647//4647 3153//3153 3155//3155 -f 3155//3155 3116//3116 4647//4647 -f 4647//4647 3116//3116 3158//3158 -f 4648//4648 4649//4649 4650//4650 -f 4645//4645 4642//4642 4651//4651 -f 4651//4651 4642//4642 4641//4641 -f 4651//4651 4641//4641 4652//4652 -f 4653//4653 4644//4644 4645//4645 -f 4653//4653 4645//4645 4654//4654 -f 4654//4654 4645//4645 4651//4651 -f 4654//4654 4651//4651 4655//4655 -f 4655//4655 4651//4651 4652//4652 -f 4655//4655 4652//4652 4656//4656 -f 4657//4657 4644//4644 4653//4653 -f 4657//4657 4653//4653 4658//4658 -f 4658//4658 4653//4653 4654//4654 -f 4658//4658 4654//4654 4659//4659 -f 4659//4659 4654//4654 4655//4655 -f 4659//4659 4655//4655 4660//4660 -f 4660//4660 4655//4655 4656//4656 -f 4660//4660 4656//4656 4661//4661 -f 4662//4662 4644//4644 4657//4657 -f 4662//4662 4657//4657 4663//4663 -f 4663//4663 4657//4657 4658//4658 -f 4663//4663 4658//4658 4664//4664 -f 4664//4664 4658//4658 4659//4659 -f 4664//4664 4659//4659 4665//4665 -f 4665//4665 4659//4659 4660//4660 -f 4665//4665 4660//4660 4666//4666 -f 4666//4666 4660//4660 4661//4661 -f 4666//4666 4661//4661 4667//4667 -f 4668//4668 4644//4644 4662//4662 -f 4668//4668 4662//4662 4669//4669 -f 4669//4669 4662//4662 4663//4663 -f 4669//4669 4663//4663 4670//4670 -f 4670//4670 4663//4663 4664//4664 -f 4670//4670 4664//4664 4671//4671 -f 4671//4671 4664//4664 4665//4665 -f 4671//4671 4665//4665 4672//4672 -f 4672//4672 4665//4665 4666//4666 -f 4672//4672 4666//4666 4673//4673 -f 4673//4673 4666//4666 4667//4667 -f 4673//4673 4667//4667 4674//4674 -f 4675//4675 4644//4644 4668//4668 -f 4644//4644 4676//4676 4677//4677 -f 4677//4677 4676//4676 4678//4678 -f 4677//4677 4678//4678 4679//4679 -f 4679//4679 4678//4678 4680//4680 -f 4679//4679 4680//4680 4681//4681 -f 4681//4681 4680//4680 4682//4682 -f 4681//4681 4682//4682 4683//4683 -f 4683//4683 4682//4682 4684//4684 -f 4683//4683 4684//4684 4685//4685 -f 4685//4685 4684//4684 4686//4686 -f 4685//4685 4686//4686 4687//4687 -f 4688//4688 4686//4686 4689//4689 -f 4689//4689 4686//4686 4684//4684 -f 4689//4689 4684//4684 4690//4690 -f 4690//4690 4684//4684 4682//4682 -f 4690//4690 4682//4682 4691//4691 -f 4691//4691 4682//4682 4680//4680 -f 4691//4691 4680//4680 4692//4692 -f 4692//4692 4680//4680 4678//4678 -f 4692//4692 4678//4678 4693//4693 -f 4693//4693 4678//4678 4676//4676 -f 4693//4693 4676//4676 4694//4694 -f 4694//4694 4676//4676 4644//4644 -f 4695//4695 4696//4696 4697//4697 -f 4675//4675 4668//4668 4698//4698 -f 4698//4698 4668//4668 4669//4669 -f 4698//4698 4669//4669 4699//4699 -f 4699//4699 4669//4669 4670//4670 -f 4699//4699 4670//4670 4700//4700 -f 4700//4700 4670//4670 4671//4671 -f 4700//4700 4671//4671 4701//4701 -f 4701//4701 4671//4671 4672//4672 -f 4701//4701 4672//4672 4702//4702 -f 4702//4702 4672//4672 4673//4673 -f 4702//4702 4673//4673 4703//4703 -f 4703//4703 4673//4673 4674//4674 -f 4703//4703 4674//4674 4704//4704 -f 4705//4705 4644//4644 4675//4675 -f 4687//4687 4706//4706 4707//4707 -f 4708//4708 4688//4688 4709//4709 -f 4709//4709 4688//4688 4689//4689 -f 4709//4709 4689//4689 4710//4710 -f 4710//4710 4689//4689 4690//4690 -f 4710//4710 4690//4690 4711//4711 -f 4711//4711 4690//4690 4691//4691 -f 4711//4711 4691//4691 4712//4712 -f 4712//4712 4691//4691 4692//4692 -f 4712//4712 4692//4692 4713//4713 -f 4713//4713 4692//4692 4693//4693 -f 4713//4713 4693//4693 4714//4714 -f 4714//4714 4693//4693 4694//4694 -f 4714//4714 4694//4694 4715//4715 -f 4715//4715 4694//4694 4644//4644 -f 4705//4705 4675//4675 4716//4716 -f 4716//4716 4675//4675 4698//4698 -f 4716//4716 4698//4698 4717//4717 -f 4717//4717 4698//4698 4699//4699 -f 4717//4717 4699//4699 4718//4718 -f 4718//4718 4699//4699 4700//4700 -f 4718//4718 4700//4700 4719//4719 -f 4719//4719 4700//4700 4701//4701 -f 4719//4719 4701//4701 4720//4720 -f 4720//4720 4701//4701 4702//4702 -f 4720//4720 4702//4702 4721//4721 -f 4721//4721 4702//4702 4703//4703 -f 4721//4721 4703//4703 4722//4722 -f 4722//4722 4703//4703 4704//4704 -f 4722//4722 4704//4704 4723//4723 -f 4724//4724 4644//4644 4705//4705 -f 4707//4707 4725//4725 4726//4726 -f 4727//4727 4708//4708 4728//4728 -f 4728//4728 4708//4708 4709//4709 -f 4728//4728 4709//4709 4729//4729 -f 4729//4729 4709//4709 4710//4710 -f 4729//4729 4710//4710 4730//4730 -f 4730//4730 4710//4710 4711//4711 -f 4730//4730 4711//4711 4731//4731 -f 4731//4731 4711//4711 4712//4712 -f 4731//4731 4712//4712 4732//4732 -f 4732//4732 4712//4712 4713//4713 -f 4732//4732 4713//4713 4733//4733 -f 4733//4733 4713//4713 4714//4714 -f 4733//4733 4714//4714 4734//4734 -f 4734//4734 4714//4714 4715//4715 -f 4734//4734 4715//4715 4735//4735 -f 4735//4735 4715//4715 4644//4644 -f 4736//4736 4737//4737 4738//4738 -f 4724//4724 4705//4705 4739//4739 -f 4739//4739 4705//4705 4716//4716 -f 4739//4739 4716//4716 4740//4740 -f 4740//4740 4716//4716 4717//4717 -f 4740//4740 4717//4717 4741//4741 -f 4741//4741 4717//4717 4718//4718 -f 4741//4741 4718//4718 4742//4742 -f 4742//4742 4718//4718 4719//4719 -f 4742//4742 4719//4719 4743//4743 -f 4743//4743 4719//4719 4720//4720 -f 4743//4743 4720//4720 4744//4744 -f 4744//4744 4720//4720 4721//4721 -f 4744//4744 4721//4721 4745//4745 -f 4745//4745 4721//4721 4722//4722 -f 4745//4745 4722//4722 4746//4746 -f 4746//4746 4722//4722 4723//4723 -f 4746//4746 4723//4723 4747//4747 -f 4748//4748 4644//4644 4724//4724 -f 4726//4726 4749//4749 4750//4750 -f 4751//4751 4727//4727 4752//4752 -f 4752//4752 4727//4727 4728//4728 -f 4752//4752 4728//4728 4753//4753 -f 4753//4753 4728//4728 4729//4729 -f 4753//4753 4729//4729 4754//4754 -f 4754//4754 4729//4729 4730//4730 -f 4754//4754 4730//4730 4755//4755 -f 4755//4755 4730//4730 4731//4731 -f 4755//4755 4731//4731 4756//4756 -f 4756//4756 4731//4731 4732//4732 -f 4756//4756 4732//4732 4757//4757 -f 4757//4757 4732//4732 4733//4733 -f 4757//4757 4733//4733 4758//4758 -f 4758//4758 4733//4733 4734//4734 -f 4758//4758 4734//4734 4759//4759 -f 4759//4759 4734//4734 4735//4735 -f 4759//4759 4735//4735 4760//4760 -f 4760//4760 4735//4735 4644//4644 -f 4738//4738 4761//4761 4762//4762 -f 4748//4748 4724//4724 4763//4763 -f 4763//4763 4724//4724 4739//4739 -f 4763//4763 4739//4739 4764//4764 -f 4764//4764 4739//4739 4740//4740 -f 4764//4764 4740//4740 4765//4765 -f 4765//4765 4740//4740 4741//4741 -f 4765//4765 4741//4741 4766//4766 -f 4766//4766 4741//4741 4742//4742 -f 4766//4766 4742//4742 4767//4767 -f 4767//4767 4742//4742 4743//4743 -f 4767//4767 4743//4743 4768//4768 -f 4768//4768 4743//4743 4744//4744 -f 4768//4768 4744//4744 4769//4769 -f 4769//4769 4744//4744 4745//4745 -f 4769//4769 4745//4745 4770//4770 -f 4770//4770 4745//4745 4746//4746 -f 4770//4770 4746//4746 4771//4771 -f 4771//4771 4746//4746 4747//4747 -f 4771//4771 4747//4747 4772//4772 -f 4773//4773 4644//4644 4748//4748 -f 4750//4750 4774//4774 4775//4775 -f 4776//4776 4751//4751 4777//4777 -f 4777//4777 4751//4751 4752//4752 -f 4777//4777 4752//4752 4778//4778 -f 4778//4778 4752//4752 4753//4753 -f 4778//4778 4753//4753 4779//4779 -f 4779//4779 4753//4753 4754//4754 -f 4779//4779 4754//4754 4780//4780 -f 4780//4780 4754//4754 4755//4755 -f 4780//4780 4755//4755 4781//4781 -f 4781//4781 4755//4755 4756//4756 -f 4781//4781 4756//4756 4782//4782 -f 4782//4782 4756//4756 4757//4757 -f 4782//4782 4757//4757 4783//4783 -f 4783//4783 4757//4757 4758//4758 -f 4783//4783 4758//4758 4784//4784 -f 4784//4784 4758//4758 4759//4759 -f 4784//4784 4759//4759 4785//4785 -f 4785//4785 4759//4759 4760//4760 -f 4785//4785 4760//4760 4786//4786 -f 4786//4786 4760//4760 4644//4644 -f 4762//4762 4787//4787 4788//4788 -f 4775//4775 4789//4789 4790//4790 -f 4791//4791 4776//4776 4792//4792 -f 4792//4792 4776//4776 4777//4777 -f 4792//4792 4777//4777 4793//4793 -f 4793//4793 4777//4777 4778//4778 -f 4793//4793 4778//4778 4794//4794 -f 4794//4794 4778//4778 4779//4779 -f 4794//4794 4779//4779 4795//4795 -f 4795//4795 4779//4779 4780//4780 -f 4795//4795 4780//4780 4796//4796 -f 4796//4796 4780//4780 4781//4781 -f 4796//4796 4781//4781 4797//4797 -f 4797//4797 4781//4781 4782//4782 -f 4797//4797 4782//4782 4798//4798 -f 4798//4798 4782//4782 4783//4783 -f 4798//4798 4783//4783 4799//4799 -f 4799//4799 4783//4783 4784//4784 -f 4799//4799 4784//4784 4800//4800 -f 4800//4800 4784//4784 4785//4785 -f 4800//4800 4785//4785 4801//4801 -f 4801//4801 4785//4785 4786//4786 -f 4801//4801 4786//4786 4802//4802 -f 4802//4802 4786//4786 4644//4644 -f 4803//4803 4804//4804 4805//4805 -f 4805//4805 4804//4804 4806//4806 -f 4805//4805 4806//4806 4807//4807 -f 4807//4807 4806//4806 4808//4808 -f 4807//4807 4808//4808 4809//4809 -f 4809//4809 4808//4808 4810//4810 -f 4809//4809 4810//4810 4811//4811 -f 4811//4811 4810//4810 4812//4812 -f 4811//4811 4812//4812 4813//4813 -f 4813//4813 4812//4812 4814//4814 -f 4813//4813 4814//4814 4815//4815 -f 4815//4815 4814//4814 4816//4816 -f 4815//4815 4816//4816 4817//4817 -f 4817//4817 4816//4816 4818//4818 -f 4817//4817 4818//4818 4819//4819 -f 4640//4640 4639//4639 4788//4788 -f 4788//4788 4787//4787 4640//4640 -f 4640//4640 4787//4787 4820//4820 -f 4640//4640 4820//4820 4638//4638 -f 4762//4762 4761//4761 4787//4787 -f 4787//4787 4761//4761 4821//4821 -f 4787//4787 4821//4821 4820//4820 -f 4820//4820 4821//4821 4822//4822 -f 4820//4820 4822//4822 4638//4638 -f 4738//4738 4737//4737 4761//4761 -f 4761//4761 4737//4737 4823//4823 -f 4761//4761 4823//4823 4821//4821 -f 4821//4821 4823//4823 4824//4824 -f 4821//4821 4824//4824 4822//4822 -f 4822//4822 4824//4824 4825//4825 -f 4822//4822 4825//4825 4638//4638 -f 4826//4826 4825//4825 4827//4827 -f 4827//4827 4825//4825 4824//4824 -f 4827//4827 4824//4824 4828//4828 -f 4828//4828 4824//4824 4823//4823 -f 4828//4828 4823//4823 4829//4829 -f 4829//4829 4823//4823 4737//4737 -f 4829//4829 4737//4737 4830//4830 -f 4830//4830 4737//4737 4736//4736 -f 4830//4830 4736//4736 4697//4697 -f 4697//4697 4696//4696 4830//4830 -f 4830//4830 4696//4696 4831//4831 -f 4830//4830 4831//4831 4829//4829 -f 4829//4829 4831//4831 4832//4832 -f 4829//4829 4832//4832 4828//4828 -f 4828//4828 4832//4832 4833//4833 -f 4828//4828 4833//4833 4827//4827 -f 4827//4827 4833//4833 4834//4834 -f 4827//4827 4834//4834 4826//4826 -f 4826//4826 4834//4834 4835//4835 -f 4826//4826 4835//4835 4638//4638 -f 4648//4648 4773//4773 4649//4649 -f 4649//4649 4773//4773 4836//4836 -f 4649//4649 4836//4836 4837//4837 -f 4837//4837 4836//4836 4838//4838 -f 4837//4837 4838//4838 4839//4839 -f 4839//4839 4838//4838 4840//4840 -f 4839//4839 4840//4840 4841//4841 -f 4841//4841 4840//4840 4842//4842 -f 4841//4841 4842//4842 4843//4843 -f 4843//4843 4842//4842 4844//4844 -f 4843//4843 4844//4844 4845//4845 -f 4845//4845 4844//4844 4846//4846 -f 4845//4845 4846//4846 4847//4847 -f 4847//4847 4846//4846 4848//4848 -f 4847//4847 4848//4848 4849//4849 -f 4849//4849 4848//4848 4850//4850 -f 4849//4849 4850//4850 4851//4851 -f 4851//4851 4850//4850 4852//4852 -f 4851//4851 4852//4852 4853//4853 -f 4853//4853 4852//4852 4854//4854 -f 4853//4853 4854//4854 4855//4855 -f 4855//4855 4854//4854 4856//4856 -f 4855//4855 4856//4856 4638//4638 -f 4638//4638 4857//4857 4858//4858 -f 4858//4858 4857//4857 4859//4859 -f 4858//4858 4859//4859 4860//4860 -f 4860//4860 4859//4859 4861//4861 -f 4860//4860 4861//4861 4862//4862 -f 4862//4862 4861//4861 4863//4863 -f 4862//4862 4863//4863 4864//4864 -f 4864//4864 4863//4863 4865//4865 -f 4864//4864 4865//4865 4866//4866 -f 4866//4866 4865//4865 4867//4867 -f 4866//4866 4867//4867 4868//4868 -f 4868//4868 4867//4867 4869//4869 -f 4868//4868 4869//4869 4870//4870 -f 4870//4870 4869//4869 4871//4871 -f 4870//4870 4871//4871 4872//4872 -f 4872//4872 4871//4871 4873//4873 -f 4872//4872 4873//4873 4874//4874 -f 4874//4874 4873//4873 4875//4875 -f 4874//4874 4875//4875 4876//4876 -f 4876//4876 4875//4875 4877//4877 -f 4876//4876 4877//4877 4878//4878 -f 4878//4878 4877//4877 4879//4879 -f 4878//4878 4879//4879 4880//4880 -f 4880//4880 4879//4879 4644//4644 -f 4637//4637 4636//4636 4790//4790 -f 4790//4790 4789//4789 4637//4637 -f 4637//4637 4789//4789 4881//4881 -f 4637//4637 4881//4881 4638//4638 -f 4775//4775 4774//4774 4789//4789 -f 4789//4789 4774//4774 4882//4882 -f 4789//4789 4882//4882 4881//4881 -f 4881//4881 4882//4882 4883//4883 -f 4881//4881 4883//4883 4638//4638 -f 4750//4750 4749//4749 4774//4774 -f 4774//4774 4749//4749 4884//4884 -f 4774//4774 4884//4884 4882//4882 -f 4882//4882 4884//4884 4885//4885 -f 4882//4882 4885//4885 4883//4883 -f 4883//4883 4885//4885 4886//4886 -f 4883//4883 4886//4886 4638//4638 -f 4726//4726 4725//4725 4749//4749 -f 4749//4749 4725//4725 4887//4887 -f 4749//4749 4887//4887 4884//4884 -f 4884//4884 4887//4887 4888//4888 -f 4884//4884 4888//4888 4885//4885 -f 4885//4885 4888//4888 4889//4889 -f 4885//4885 4889//4889 4886//4886 -f 4886//4886 4889//4889 4890//4890 -f 4886//4886 4890//4890 4638//4638 -f 4707//4707 4706//4706 4725//4725 -f 4725//4725 4706//4706 4891//4891 -f 4725//4725 4891//4891 4887//4887 -f 4887//4887 4891//4891 4892//4892 -f 4887//4887 4892//4892 4888//4888 -f 4888//4888 4892//4892 4893//4893 -f 4888//4888 4893//4893 4889//4889 -f 4889//4889 4893//4893 4894//4894 -f 4889//4889 4894//4894 4890//4890 -f 4890//4890 4894//4894 4895//4895 -f 4890//4890 4895//4895 4638//4638 -f 4638//4638 4791//4791 4896//4896 -f 4896//4896 4791//4791 4792//4792 -f 4896//4896 4792//4792 4897//4897 -f 4897//4897 4792//4792 4793//4793 -f 4897//4897 4793//4793 4898//4898 -f 4898//4898 4793//4793 4794//4794 -f 4898//4898 4794//4794 4899//4899 -f 4899//4899 4794//4794 4795//4795 -f 4899//4899 4795//4795 4900//4900 -f 4900//4900 4795//4795 4796//4796 -f 4900//4900 4796//4796 4901//4901 -f 4901//4901 4796//4796 4797//4797 -f 4901//4901 4797//4797 4902//4902 -f 4902//4902 4797//4797 4798//4798 -f 4902//4902 4798//4798 4903//4903 -f 4903//4903 4798//4798 4799//4799 -f 4903//4903 4799//4799 4904//4904 -f 4904//4904 4799//4799 4800//4800 -f 4904//4904 4800//4800 4905//4905 -f 4905//4905 4800//4800 4801//4801 -f 4905//4905 4801//4801 4906//4906 -f 4906//4906 4801//4801 4802//4802 -f 4906//4906 4802//4802 4647//4647 -f 4647//4647 4802//4802 4644//4644 -f 4638//4638 4896//4896 4907//4907 -f 4907//4907 4896//4896 4897//4897 -f 4907//4907 4897//4897 4908//4908 -f 4908//4908 4897//4897 4898//4898 -f 4908//4908 4898//4898 4909//4909 -f 4909//4909 4898//4898 4899//4899 -f 4909//4909 4899//4899 4910//4910 -f 4910//4910 4899//4899 4900//4900 -f 4910//4910 4900//4900 4911//4911 -f 4911//4911 4900//4900 4901//4901 -f 4911//4911 4901//4901 4912//4912 -f 4912//4912 4901//4901 4902//4902 -f 4912//4912 4902//4902 4913//4913 -f 4913//4913 4902//4902 4903//4903 -f 4913//4913 4903//4903 4914//4914 -f 4914//4914 4903//4903 4904//4904 -f 4914//4914 4904//4904 4915//4915 -f 4915//4915 4904//4904 4905//4905 -f 4915//4915 4905//4905 4916//4916 -f 4916//4916 4905//4905 4906//4906 -f 4916//4916 4906//4906 4917//4917 -f 4917//4917 4906//4906 4647//4647 -f 4917//4917 4647//4647 4646//4646 -f 4646//4646 4647//4647 3158//3158 -f 4646//4646 3158//3158 3157//3157 -f 4687//4687 4686//4686 4706//4706 -f 4706//4706 4686//4686 4688//4688 -f 4706//4706 4688//4688 4891//4891 -f 4891//4891 4688//4688 4708//4708 -f 4891//4891 4708//4708 4892//4892 -f 4892//4892 4708//4708 4727//4727 -f 4892//4892 4727//4727 4893//4893 -f 4893//4893 4727//4727 4751//4751 -f 4893//4893 4751//4751 4894//4894 -f 4894//4894 4751//4751 4776//4776 -f 4894//4894 4776//4776 4895//4895 -f 4895//4895 4776//4776 4791//4791 -f 4895//4895 4791//4791 4638//4638 -f 4644//4644 4918//4918 4646//4646 -f 4646//4646 4918//4918 4919//4919 -f 4646//4646 4919//4919 4917//4917 -f 4917//4917 4919//4919 4920//4920 -f 4917//4917 4920//4920 4916//4916 -f 4916//4916 4920//4920 4921//4921 -f 4916//4916 4921//4921 4915//4915 -f 4915//4915 4921//4921 4922//4922 -f 4915//4915 4922//4922 4914//4914 -f 4914//4914 4922//4922 4923//4923 -f 4914//4914 4923//4923 4913//4913 -f 4913//4913 4923//4923 4924//4924 -f 4913//4913 4924//4924 4912//4912 -f 4912//4912 4924//4924 4925//4925 -f 4912//4912 4925//4925 4911//4911 -f 4911//4911 4925//4925 4926//4926 -f 4911//4911 4926//4926 4910//4910 -f 4910//4910 4926//4926 4927//4927 -f 4910//4910 4927//4927 4909//4909 -f 4909//4909 4927//4927 4928//4928 -f 4909//4909 4928//4928 4908//4908 -f 4908//4908 4928//4928 4929//4929 -f 4908//4908 4929//4929 4907//4907 -f 4907//4907 4929//4929 4638//4638 -f 4926//4926 4930//4930 4927//4927 -f 4927//4927 4930//4930 4931//4931 -f 4927//4927 4931//4931 4928//4928 -f 4928//4928 4931//4931 4932//4932 -f 4928//4928 4932//4932 4929//4929 -f 4929//4929 4932//4932 4638//4638 -f 4650//4650 4933//4933 4934//4934 -f 4934//4934 4933//4933 4935//4935 -f 4934//4934 4935//4935 4936//4936 -f 4936//4936 4935//4935 4937//4937 -f 4936//4936 4937//4937 4938//4938 -f 4938//4938 4937//4937 4939//4939 -f 4938//4938 4939//4939 4940//4940 -f 4940//4940 4939//4939 4941//4941 -f 4940//4940 4941//4941 4942//4942 -f 4942//4942 4941//4941 4943//4943 -f 4942//4942 4943//4943 4944//4944 -f 4944//4944 4943//4943 4945//4945 -f 4944//4944 4945//4945 4946//4946 -f 4946//4946 4945//4945 4947//4947 -f 4946//4946 4947//4947 4930//4930 -f 4930//4930 4947//4947 4948//4948 -f 4930//4930 4948//4948 4931//4931 -f 4931//4931 4948//4948 4949//4949 -f 4931//4931 4949//4949 4932//4932 -f 4932//4932 4949//4949 4638//4638 -f 4933//4933 4803//4803 4935//4935 -f 4935//4935 4803//4803 4805//4805 -f 4935//4935 4805//4805 4937//4937 -f 4937//4937 4805//4805 4807//4807 -f 4937//4937 4807//4807 4939//4939 -f 4939//4939 4807//4807 4809//4809 -f 4939//4939 4809//4809 4941//4941 -f 4941//4941 4809//4809 4811//4811 -f 4941//4941 4811//4811 4943//4943 -f 4943//4943 4811//4811 4813//4813 -f 4943//4943 4813//4813 4945//4945 -f 4945//4945 4813//4813 4815//4815 -f 4945//4945 4815//4815 4947//4947 -f 4947//4947 4815//4815 4817//4817 -f 4947//4947 4817//4817 4948//4948 -f 4948//4948 4817//4817 4819//4819 -f 4948//4948 4819//4819 4949//4949 -f 4949//4949 4819//4819 4638//4638 -f 4638//4638 4858//4858 4636//4636 -f 4636//4636 4858//4858 4860//4860 -f 4636//4636 4860//4860 4790//4790 -f 4790//4790 4860//4860 4862//4862 -f 4790//4790 4862//4862 4775//4775 -f 4775//4775 4862//4862 4864//4864 -f 4775//4775 4864//4864 4750//4750 -f 4750//4750 4864//4864 4866//4866 -f 4750//4750 4866//4866 4726//4726 -f 4726//4726 4866//4866 4868//4868 -f 4726//4726 4868//4868 4707//4707 -f 4707//4707 4868//4868 4870//4870 -f 4707//4707 4870//4870 4687//4687 -f 4687//4687 4870//4870 4872//4872 -f 4687//4687 4872//4872 4685//4685 -f 4685//4685 4872//4872 4874//4874 -f 4685//4685 4874//4874 4683//4683 -f 4683//4683 4874//4874 4876//4876 -f 4683//4683 4876//4876 4681//4681 -f 4681//4681 4876//4876 4878//4878 -f 4681//4681 4878//4878 4679//4679 -f 4679//4679 4878//4878 4880//4880 -f 4679//4679 4880//4880 4677//4677 -f 4677//4677 4880//4880 4644//4644 -f 4857//4857 4772//4772 4859//4859 -f 4859//4859 4772//4772 4747//4747 -f 4859//4859 4747//4747 4861//4861 -f 4861//4861 4747//4747 4723//4723 -f 4861//4861 4723//4723 4863//4863 -f 4863//4863 4723//4723 4704//4704 -f 4863//4863 4704//4704 4865//4865 -f 4865//4865 4704//4704 4674//4674 -f 4865//4865 4674//4674 4867//4867 -f 4867//4867 4674//4674 4667//4667 -f 4867//4867 4667//4667 4869//4869 -f 4869//4869 4667//4667 4661//4661 -f 4869//4869 4661//4661 4871//4871 -f 4871//4871 4661//4661 4656//4656 -f 4871//4871 4656//4656 4873//4873 -f 4873//4873 4656//4656 4652//4652 -f 4873//4873 4652//4652 4875//4875 -f 4875//4875 4652//4652 4641//4641 -f 4875//4875 4641//4641 4877//4877 -f 4877//4877 4641//4641 4643//4643 -f 4877//4877 4643//4643 4879//4879 -f 4879//4879 4643//4643 4644//4644 -f 4773//4773 4748//4748 4836//4836 -f 4836//4836 4748//4748 4763//4763 -f 4836//4836 4763//4763 4838//4838 -f 4838//4838 4763//4763 4764//4764 -f 4838//4838 4764//4764 4840//4840 -f 4840//4840 4764//4764 4765//4765 -f 4840//4840 4765//4765 4842//4842 -f 4842//4842 4765//4765 4766//4766 -f 4842//4842 4766//4766 4844//4844 -f 4844//4844 4766//4766 4767//4767 -f 4844//4844 4767//4767 4846//4846 -f 4846//4846 4767//4767 4768//4768 -f 4846//4846 4768//4768 4848//4848 -f 4848//4848 4768//4768 4769//4769 -f 4848//4848 4769//4769 4850//4850 -f 4850//4850 4769//4769 4770//4770 -f 4850//4850 4770//4770 4852//4852 -f 4852//4852 4770//4770 4771//4771 -f 4852//4852 4771//4771 4854//4854 -f 4854//4854 4771//4771 4772//4772 -f 4854//4854 4772//4772 4856//4856 -f 4856//4856 4772//4772 4857//4857 -f 4856//4856 4857//4857 4638//4638 -f 4818//4818 4638//4638 4819//4819 -f 4804//4804 4695//4695 4806//4806 -f 4806//4806 4695//4695 4697//4697 -f 4806//4806 4697//4697 4808//4808 -f 4808//4808 4697//4697 4736//4736 -f 4808//4808 4736//4736 4810//4810 -f 4810//4810 4736//4736 4738//4738 -f 4810//4810 4738//4738 4812//4812 -f 4812//4812 4738//4738 4762//4762 -f 4812//4812 4762//4762 4814//4814 -f 4814//4814 4762//4762 4788//4788 -f 4814//4814 4788//4788 4816//4816 -f 4816//4816 4788//4788 4639//4639 -f 4816//4816 4639//4639 4818//4818 -f 4818//4818 4639//4639 4638//4638 -f 4648//4648 4644//4644 4773//4773 -f 4650//4650 4649//4649 4933//4933 -f 4933//4933 4649//4649 4837//4837 -f 4933//4933 4837//4837 4803//4803 -f 4803//4803 4837//4837 4839//4839 -f 4803//4803 4839//4839 4804//4804 -f 4804//4804 4839//4839 4841//4841 -f 4804//4804 4841//4841 4695//4695 -f 4695//4695 4841//4841 4843//4843 -f 4695//4695 4843//4843 4696//4696 -f 4696//4696 4843//4843 4845//4845 -f 4696//4696 4845//4845 4831//4831 -f 4831//4831 4845//4845 4847//4847 -f 4831//4831 4847//4847 4832//4832 -f 4832//4832 4847//4847 4849//4849 -f 4832//4832 4849//4849 4833//4833 -f 4833//4833 4849//4849 4851//4851 -f 4833//4833 4851//4851 4834//4834 -f 4834//4834 4851//4851 4853//4853 -f 4834//4834 4853//4853 4835//4835 -f 4835//4835 4853//4853 4855//4855 -f 4835//4835 4855//4855 4638//4638 -f 4930//4930 4926//4926 4946//4946 -f 4946//4946 4926//4926 4925//4925 -f 4946//4946 4925//4925 4944//4944 -f 4944//4944 4925//4925 4924//4924 -f 4944//4944 4924//4924 4942//4942 -f 4942//4942 4924//4924 4923//4923 -f 4942//4942 4923//4923 4940//4940 -f 4940//4940 4923//4923 4922//4922 -f 4940//4940 4922//4922 4938//4938 -f 4938//4938 4922//4922 4921//4921 -f 4938//4938 4921//4921 4936//4936 -f 4936//4936 4921//4921 4920//4920 -f 4936//4936 4920//4920 4934//4934 -f 4934//4934 4920//4920 4919//4919 -f 4934//4934 4919//4919 4650//4650 -f 4650//4650 4919//4919 4918//4918 -f 4650//4650 4918//4918 4648//4648 -f 4648//4648 4918//4918 4644//4644 -f 4638//4638 3078//3078 3057//3057 -f 3079//3079 3078//3078 4638//4638 -f 4638//4638 3056//3056 3061//3061 -f 3057//3057 3056//3056 4638//4638 -f 4638//4638 3061//3061 3063//3063 -f 3077//3077 3075//3075 4638//4638 -f 3065//3065 3053//3053 4826//4826 -f 4638//4638 3063//3063 4826//4826 -f 4826//4826 3063//3063 3065//3065 -f 3072//3072 3070//3070 4825//4825 -f 3072//3072 4825//4825 3073//3073 -f 4826//4826 3053//3053 3068//3068 -f 4826//4826 3068//3068 4825//4825 -f 4825//4825 3068//3068 3067//3067 -f 4825//4825 3067//3067 3073//3073 -f 3075//3075 3079//3079 4638//4638 -f 3070//3070 3077//3077 4825//4825 -f 4825//4825 3077//3077 4638//4638 -f 4950//4950 4951//4951 4952//4952 -f 4953//4953 4954//4954 4952//4952 -f 4955//4955 4956//4956 4957//4957 -f 4957//4957 4956//4956 4958//4958 -f 4959//4959 4958//4958 4956//4956 -f 3223//3223 3229//3229 4960//4960 -f 4960//4960 3229//3229 3228//3228 -f 4960//4960 3228//3228 3226//3226 -f 4958//4958 3231//3231 3235//3235 -f 3233//3233 3231//3231 4958//4958 -f 3226//3226 3233//3233 4960//4960 -f 4960//4960 3233//3233 4958//4958 -f 4958//4958 3234//3234 3213//3213 -f 3235//3235 3234//3234 4958//4958 -f 4958//4958 3212//3212 3217//3217 -f 3213//3213 3212//3212 4958//4958 -f 4958//4958 3217//3217 3219//3219 -f 4958//4958 3219//3219 4961//4961 -f 4961//4961 3219//3219 3221//3221 -f 3221//3221 3182//3182 4961//4961 -f 4961//4961 3182//3182 3224//3224 -f 4962//4962 4963//4963 4964//4964 -f 4959//4959 4956//4956 4965//4965 -f 4965//4965 4956//4956 4955//4955 -f 4965//4965 4955//4955 4966//4966 -f 4967//4967 4958//4958 4959//4959 -f 4967//4967 4959//4959 4968//4968 -f 4968//4968 4959//4959 4965//4965 -f 4968//4968 4965//4965 4969//4969 -f 4969//4969 4965//4965 4966//4966 -f 4969//4969 4966//4966 4970//4970 -f 4971//4971 4958//4958 4967//4967 -f 4971//4971 4967//4967 4972//4972 -f 4972//4972 4967//4967 4968//4968 -f 4972//4972 4968//4968 4973//4973 -f 4973//4973 4968//4968 4969//4969 -f 4973//4973 4969//4969 4974//4974 -f 4974//4974 4969//4969 4970//4970 -f 4974//4974 4970//4970 4975//4975 -f 4976//4976 4958//4958 4971//4971 -f 4976//4976 4971//4971 4977//4977 -f 4977//4977 4971//4971 4972//4972 -f 4977//4977 4972//4972 4978//4978 -f 4978//4978 4972//4972 4973//4973 -f 4978//4978 4973//4973 4979//4979 -f 4979//4979 4973//4973 4974//4974 -f 4979//4979 4974//4974 4980//4980 -f 4980//4980 4974//4974 4975//4975 -f 4980//4980 4975//4975 4981//4981 -f 4982//4982 4958//4958 4976//4976 -f 4982//4982 4976//4976 4983//4983 -f 4983//4983 4976//4976 4977//4977 -f 4983//4983 4977//4977 4984//4984 -f 4984//4984 4977//4977 4978//4978 -f 4984//4984 4978//4978 4985//4985 -f 4985//4985 4978//4978 4979//4979 -f 4985//4985 4979//4979 4986//4986 -f 4986//4986 4979//4979 4980//4980 -f 4986//4986 4980//4980 4987//4987 -f 4987//4987 4980//4980 4981//4981 -f 4987//4987 4981//4981 4988//4988 -f 4989//4989 4958//4958 4982//4982 -f 4958//4958 4990//4990 4991//4991 -f 4991//4991 4990//4990 4992//4992 -f 4991//4991 4992//4992 4993//4993 -f 4993//4993 4992//4992 4994//4994 -f 4993//4993 4994//4994 4995//4995 -f 4995//4995 4994//4994 4996//4996 -f 4995//4995 4996//4996 4997//4997 -f 4997//4997 4996//4996 4998//4998 -f 4997//4997 4998//4998 4999//4999 -f 4999//4999 4998//4998 5000//5000 -f 4999//4999 5000//5000 5001//5001 -f 5002//5002 5000//5000 5003//5003 -f 5003//5003 5000//5000 4998//4998 -f 5003//5003 4998//4998 5004//5004 -f 5004//5004 4998//4998 4996//4996 -f 5004//5004 4996//4996 5005//5005 -f 5005//5005 4996//4996 4994//4994 -f 5005//5005 4994//4994 5006//5006 -f 5006//5006 4994//4994 4992//4992 -f 5006//5006 4992//4992 5007//5007 -f 5007//5007 4992//4992 4990//4990 -f 5007//5007 4990//4990 5008//5008 -f 5008//5008 4990//4990 4958//4958 -f 5009//5009 5010//5010 5011//5011 -f 4989//4989 4982//4982 5012//5012 -f 5012//5012 4982//4982 4983//4983 -f 5012//5012 4983//4983 5013//5013 -f 5013//5013 4983//4983 4984//4984 -f 5013//5013 4984//4984 5014//5014 -f 5014//5014 4984//4984 4985//4985 -f 5014//5014 4985//4985 5015//5015 -f 5015//5015 4985//4985 4986//4986 -f 5015//5015 4986//4986 5016//5016 -f 5016//5016 4986//4986 4987//4987 -f 5016//5016 4987//4987 5017//5017 -f 5017//5017 4987//4987 4988//4988 -f 5017//5017 4988//4988 5018//5018 -f 5019//5019 4958//4958 4989//4989 -f 5001//5001 5020//5020 5021//5021 -f 5022//5022 5002//5002 5023//5023 -f 5023//5023 5002//5002 5003//5003 -f 5023//5023 5003//5003 5024//5024 -f 5024//5024 5003//5003 5004//5004 -f 5024//5024 5004//5004 5025//5025 -f 5025//5025 5004//5004 5005//5005 -f 5025//5025 5005//5005 5026//5026 -f 5026//5026 5005//5005 5006//5006 -f 5026//5026 5006//5006 5027//5027 -f 5027//5027 5006//5006 5007//5007 -f 5027//5027 5007//5007 5028//5028 -f 5028//5028 5007//5007 5008//5008 -f 5028//5028 5008//5008 5029//5029 -f 5029//5029 5008//5008 4958//4958 -f 5019//5019 4989//4989 5030//5030 -f 5030//5030 4989//4989 5012//5012 -f 5030//5030 5012//5012 5031//5031 -f 5031//5031 5012//5012 5013//5013 -f 5031//5031 5013//5013 5032//5032 -f 5032//5032 5013//5013 5014//5014 -f 5032//5032 5014//5014 5033//5033 -f 5033//5033 5014//5014 5015//5015 -f 5033//5033 5015//5015 5034//5034 -f 5034//5034 5015//5015 5016//5016 -f 5034//5034 5016//5016 5035//5035 -f 5035//5035 5016//5016 5017//5017 -f 5035//5035 5017//5017 5036//5036 -f 5036//5036 5017//5017 5018//5018 -f 5036//5036 5018//5018 5037//5037 -f 5038//5038 4958//4958 5019//5019 -f 5021//5021 5039//5039 5040//5040 -f 5041//5041 5022//5022 5042//5042 -f 5042//5042 5022//5022 5023//5023 -f 5042//5042 5023//5023 5043//5043 -f 5043//5043 5023//5023 5024//5024 -f 5043//5043 5024//5024 5044//5044 -f 5044//5044 5024//5024 5025//5025 -f 5044//5044 5025//5025 5045//5045 -f 5045//5045 5025//5025 5026//5026 -f 5045//5045 5026//5026 5046//5046 -f 5046//5046 5026//5026 5027//5027 -f 5046//5046 5027//5027 5047//5047 -f 5047//5047 5027//5027 5028//5028 -f 5047//5047 5028//5028 5048//5048 -f 5048//5048 5028//5028 5029//5029 -f 5048//5048 5029//5029 5049//5049 -f 5049//5049 5029//5029 4958//4958 -f 5050//5050 5051//5051 5052//5052 -f 5038//5038 5019//5019 5053//5053 -f 5053//5053 5019//5019 5030//5030 -f 5053//5053 5030//5030 5054//5054 -f 5054//5054 5030//5030 5031//5031 -f 5054//5054 5031//5031 5055//5055 -f 5055//5055 5031//5031 5032//5032 -f 5055//5055 5032//5032 5056//5056 -f 5056//5056 5032//5032 5033//5033 -f 5056//5056 5033//5033 5057//5057 -f 5057//5057 5033//5033 5034//5034 -f 5057//5057 5034//5034 5058//5058 -f 5058//5058 5034//5034 5035//5035 -f 5058//5058 5035//5035 5059//5059 -f 5059//5059 5035//5035 5036//5036 -f 5059//5059 5036//5036 5060//5060 -f 5060//5060 5036//5036 5037//5037 -f 5060//5060 5037//5037 5061//5061 -f 5062//5062 4958//4958 5038//5038 -f 5040//5040 5063//5063 5064//5064 -f 5065//5065 5041//5041 5066//5066 -f 5066//5066 5041//5041 5042//5042 -f 5066//5066 5042//5042 5067//5067 -f 5067//5067 5042//5042 5043//5043 -f 5067//5067 5043//5043 5068//5068 -f 5068//5068 5043//5043 5044//5044 -f 5068//5068 5044//5044 5069//5069 -f 5069//5069 5044//5044 5045//5045 -f 5069//5069 5045//5045 5070//5070 -f 5070//5070 5045//5045 5046//5046 -f 5070//5070 5046//5046 5071//5071 -f 5071//5071 5046//5046 5047//5047 -f 5071//5071 5047//5047 5072//5072 -f 5072//5072 5047//5047 5048//5048 -f 5072//5072 5048//5048 5073//5073 -f 5073//5073 5048//5048 5049//5049 -f 5073//5073 5049//5049 5074//5074 -f 5074//5074 5049//5049 4958//4958 -f 5052//5052 5075//5075 5076//5076 -f 5062//5062 5038//5038 5077//5077 -f 5077//5077 5038//5038 5053//5053 -f 5077//5077 5053//5053 5078//5078 -f 5078//5078 5053//5053 5054//5054 -f 5078//5078 5054//5054 5079//5079 -f 5079//5079 5054//5054 5055//5055 -f 5079//5079 5055//5055 5080//5080 -f 5080//5080 5055//5055 5056//5056 -f 5080//5080 5056//5056 5081//5081 -f 5081//5081 5056//5056 5057//5057 -f 5081//5081 5057//5057 5082//5082 -f 5082//5082 5057//5057 5058//5058 -f 5082//5082 5058//5058 5083//5083 -f 5083//5083 5058//5058 5059//5059 -f 5083//5083 5059//5059 5084//5084 -f 5084//5084 5059//5059 5060//5060 -f 5084//5084 5060//5060 5085//5085 -f 5085//5085 5060//5060 5061//5061 -f 5085//5085 5061//5061 5086//5086 -f 5087//5087 4958//4958 5062//5062 -f 5064//5064 5088//5088 5089//5089 -f 5090//5090 5065//5065 5091//5091 -f 5091//5091 5065//5065 5066//5066 -f 5091//5091 5066//5066 5092//5092 -f 5092//5092 5066//5066 5067//5067 -f 5092//5092 5067//5067 5093//5093 -f 5093//5093 5067//5067 5068//5068 -f 5093//5093 5068//5068 5094//5094 -f 5094//5094 5068//5068 5069//5069 -f 5094//5094 5069//5069 5095//5095 -f 5095//5095 5069//5069 5070//5070 -f 5095//5095 5070//5070 5096//5096 -f 5096//5096 5070//5070 5071//5071 -f 5096//5096 5071//5071 5097//5097 -f 5097//5097 5071//5071 5072//5072 -f 5097//5097 5072//5072 5098//5098 -f 5098//5098 5072//5072 5073//5073 -f 5098//5098 5073//5073 5099//5099 -f 5099//5099 5073//5073 5074//5074 -f 5099//5099 5074//5074 5100//5100 -f 5100//5100 5074//5074 4958//4958 -f 5076//5076 5101//5101 5102//5102 -f 5089//5089 5103//5103 5104//5104 -f 5105//5105 5090//5090 5106//5106 -f 5106//5106 5090//5090 5091//5091 -f 5106//5106 5091//5091 5107//5107 -f 5107//5107 5091//5091 5092//5092 -f 5107//5107 5092//5092 5108//5108 -f 5108//5108 5092//5092 5093//5093 -f 5108//5108 5093//5093 5109//5109 -f 5109//5109 5093//5093 5094//5094 -f 5109//5109 5094//5094 5110//5110 -f 5110//5110 5094//5094 5095//5095 -f 5110//5110 5095//5095 5111//5111 -f 5111//5111 5095//5095 5096//5096 -f 5111//5111 5096//5096 5112//5112 -f 5112//5112 5096//5096 5097//5097 -f 5112//5112 5097//5097 5113//5113 -f 5113//5113 5097//5097 5098//5098 -f 5113//5113 5098//5098 5114//5114 -f 5114//5114 5098//5098 5099//5099 -f 5114//5114 5099//5099 5115//5115 -f 5115//5115 5099//5099 5100//5100 -f 5115//5115 5100//5100 5116//5116 -f 5116//5116 5100//5100 4958//4958 -f 5117//5117 5118//5118 5119//5119 -f 5119//5119 5118//5118 5120//5120 -f 5119//5119 5120//5120 5121//5121 -f 5121//5121 5120//5120 5122//5122 -f 5121//5121 5122//5122 5123//5123 -f 5123//5123 5122//5122 5124//5124 -f 5123//5123 5124//5124 5125//5125 -f 5125//5125 5124//5124 5126//5126 -f 5125//5125 5126//5126 5127//5127 -f 5127//5127 5126//5126 5128//5128 -f 5127//5127 5128//5128 5129//5129 -f 5129//5129 5128//5128 5130//5130 -f 5129//5129 5130//5130 5131//5131 -f 5131//5131 5130//5130 5132//5132 -f 5131//5131 5132//5132 5133//5133 -f 4954//4954 4953//4953 5102//5102 -f 5102//5102 5101//5101 4954//4954 -f 4954//4954 5101//5101 5134//5134 -f 4954//4954 5134//5134 4952//4952 -f 5076//5076 5075//5075 5101//5101 -f 5101//5101 5075//5075 5135//5135 -f 5101//5101 5135//5135 5134//5134 -f 5134//5134 5135//5135 5136//5136 -f 5134//5134 5136//5136 4952//4952 -f 5052//5052 5051//5051 5075//5075 -f 5075//5075 5051//5051 5137//5137 -f 5075//5075 5137//5137 5135//5135 -f 5135//5135 5137//5137 5138//5138 -f 5135//5135 5138//5138 5136//5136 -f 5136//5136 5138//5138 5139//5139 -f 5136//5136 5139//5139 4952//4952 -f 5140//5140 5139//5139 5141//5141 -f 5141//5141 5139//5139 5138//5138 -f 5141//5141 5138//5138 5142//5142 -f 5142//5142 5138//5138 5137//5137 -f 5142//5142 5137//5137 5143//5143 -f 5143//5143 5137//5137 5051//5051 -f 5143//5143 5051//5051 5144//5144 -f 5144//5144 5051//5051 5050//5050 -f 5144//5144 5050//5050 5011//5011 -f 5011//5011 5010//5010 5144//5144 -f 5144//5144 5010//5010 5145//5145 -f 5144//5144 5145//5145 5143//5143 -f 5143//5143 5145//5145 5146//5146 -f 5143//5143 5146//5146 5142//5142 -f 5142//5142 5146//5146 5147//5147 -f 5142//5142 5147//5147 5141//5141 -f 5141//5141 5147//5147 5148//5148 -f 5141//5141 5148//5148 5140//5140 -f 5140//5140 5148//5148 5149//5149 -f 5140//5140 5149//5149 4952//4952 -f 4962//4962 5087//5087 4963//4963 -f 4963//4963 5087//5087 5150//5150 -f 4963//4963 5150//5150 5151//5151 -f 5151//5151 5150//5150 5152//5152 -f 5151//5151 5152//5152 5153//5153 -f 5153//5153 5152//5152 5154//5154 -f 5153//5153 5154//5154 5155//5155 -f 5155//5155 5154//5154 5156//5156 -f 5155//5155 5156//5156 5157//5157 -f 5157//5157 5156//5156 5158//5158 -f 5157//5157 5158//5158 5159//5159 -f 5159//5159 5158//5158 5160//5160 -f 5159//5159 5160//5160 5161//5161 -f 5161//5161 5160//5160 5162//5162 -f 5161//5161 5162//5162 5163//5163 -f 5163//5163 5162//5162 5164//5164 -f 5163//5163 5164//5164 5165//5165 -f 5165//5165 5164//5164 5166//5166 -f 5165//5165 5166//5166 5167//5167 -f 5167//5167 5166//5166 5168//5168 -f 5167//5167 5168//5168 5169//5169 -f 5169//5169 5168//5168 5170//5170 -f 5169//5169 5170//5170 4952//4952 -f 4952//4952 5171//5171 5172//5172 -f 5172//5172 5171//5171 5173//5173 -f 5172//5172 5173//5173 5174//5174 -f 5174//5174 5173//5173 5175//5175 -f 5174//5174 5175//5175 5176//5176 -f 5176//5176 5175//5175 5177//5177 -f 5176//5176 5177//5177 5178//5178 -f 5178//5178 5177//5177 5179//5179 -f 5178//5178 5179//5179 5180//5180 -f 5180//5180 5179//5179 5181//5181 -f 5180//5180 5181//5181 5182//5182 -f 5182//5182 5181//5181 5183//5183 -f 5182//5182 5183//5183 5184//5184 -f 5184//5184 5183//5183 5185//5185 -f 5184//5184 5185//5185 5186//5186 -f 5186//5186 5185//5185 5187//5187 -f 5186//5186 5187//5187 5188//5188 -f 5188//5188 5187//5187 5189//5189 -f 5188//5188 5189//5189 5190//5190 -f 5190//5190 5189//5189 5191//5191 -f 5190//5190 5191//5191 5192//5192 -f 5192//5192 5191//5191 5193//5193 -f 5192//5192 5193//5193 5194//5194 -f 5194//5194 5193//5193 4958//4958 -f 4951//4951 4950//4950 5104//5104 -f 5104//5104 5103//5103 4951//4951 -f 4951//4951 5103//5103 5195//5195 -f 4951//4951 5195//5195 4952//4952 -f 5089//5089 5088//5088 5103//5103 -f 5103//5103 5088//5088 5196//5196 -f 5103//5103 5196//5196 5195//5195 -f 5195//5195 5196//5196 5197//5197 -f 5195//5195 5197//5197 4952//4952 -f 5064//5064 5063//5063 5088//5088 -f 5088//5088 5063//5063 5198//5198 -f 5088//5088 5198//5198 5196//5196 -f 5196//5196 5198//5198 5199//5199 -f 5196//5196 5199//5199 5197//5197 -f 5197//5197 5199//5199 5200//5200 -f 5197//5197 5200//5200 4952//4952 -f 5040//5040 5039//5039 5063//5063 -f 5063//5063 5039//5039 5201//5201 -f 5063//5063 5201//5201 5198//5198 -f 5198//5198 5201//5201 5202//5202 -f 5198//5198 5202//5202 5199//5199 -f 5199//5199 5202//5202 5203//5203 -f 5199//5199 5203//5203 5200//5200 -f 5200//5200 5203//5203 5204//5204 -f 5200//5200 5204//5204 4952//4952 -f 5021//5021 5020//5020 5039//5039 -f 5039//5039 5020//5020 5205//5205 -f 5039//5039 5205//5205 5201//5201 -f 5201//5201 5205//5205 5206//5206 -f 5201//5201 5206//5206 5202//5202 -f 5202//5202 5206//5206 5207//5207 -f 5202//5202 5207//5207 5203//5203 -f 5203//5203 5207//5207 5208//5208 -f 5203//5203 5208//5208 5204//5204 -f 5204//5204 5208//5208 5209//5209 -f 5204//5204 5209//5209 4952//4952 -f 4952//4952 5105//5105 5210//5210 -f 5210//5210 5105//5105 5106//5106 -f 5210//5210 5106//5106 5211//5211 -f 5211//5211 5106//5106 5107//5107 -f 5211//5211 5107//5107 5212//5212 -f 5212//5212 5107//5107 5108//5108 -f 5212//5212 5108//5108 5213//5213 -f 5213//5213 5108//5108 5109//5109 -f 5213//5213 5109//5109 5214//5214 -f 5214//5214 5109//5109 5110//5110 -f 5214//5214 5110//5110 5215//5215 -f 5215//5215 5110//5110 5111//5111 -f 5215//5215 5111//5111 5216//5216 -f 5216//5216 5111//5111 5112//5112 -f 5216//5216 5112//5112 5217//5217 -f 5217//5217 5112//5112 5113//5113 -f 5217//5217 5113//5113 5218//5218 -f 5218//5218 5113//5113 5114//5114 -f 5218//5218 5114//5114 5219//5219 -f 5219//5219 5114//5114 5115//5115 -f 5219//5219 5115//5115 5220//5220 -f 5220//5220 5115//5115 5116//5116 -f 5220//5220 5116//5116 4961//4961 -f 4961//4961 5116//5116 4958//4958 -f 4952//4952 5210//5210 5221//5221 -f 5221//5221 5210//5210 5211//5211 -f 5221//5221 5211//5211 5222//5222 -f 5222//5222 5211//5211 5212//5212 -f 5222//5222 5212//5212 5223//5223 -f 5223//5223 5212//5212 5213//5213 -f 5223//5223 5213//5213 5224//5224 -f 5224//5224 5213//5213 5214//5214 -f 5224//5224 5214//5214 5225//5225 -f 5225//5225 5214//5214 5215//5215 -f 5225//5225 5215//5215 5226//5226 -f 5226//5226 5215//5215 5216//5216 -f 5226//5226 5216//5216 5227//5227 -f 5227//5227 5216//5216 5217//5217 -f 5227//5227 5217//5217 5228//5228 -f 5228//5228 5217//5217 5218//5218 -f 5228//5228 5218//5218 5229//5229 -f 5229//5229 5218//5218 5219//5219 -f 5229//5229 5219//5219 5230//5230 -f 5230//5230 5219//5219 5220//5220 -f 5230//5230 5220//5220 5231//5231 -f 5231//5231 5220//5220 4961//4961 -f 5231//5231 4961//4961 4960//4960 -f 4960//4960 4961//4961 3224//3224 -f 4960//4960 3224//3224 3223//3223 -f 5001//5001 5000//5000 5020//5020 -f 5020//5020 5000//5000 5002//5002 -f 5020//5020 5002//5002 5205//5205 -f 5205//5205 5002//5002 5022//5022 -f 5205//5205 5022//5022 5206//5206 -f 5206//5206 5022//5022 5041//5041 -f 5206//5206 5041//5041 5207//5207 -f 5207//5207 5041//5041 5065//5065 -f 5207//5207 5065//5065 5208//5208 -f 5208//5208 5065//5065 5090//5090 -f 5208//5208 5090//5090 5209//5209 -f 5209//5209 5090//5090 5105//5105 -f 5209//5209 5105//5105 4952//4952 -f 4958//4958 5232//5232 4960//4960 -f 4960//4960 5232//5232 5233//5233 -f 4960//4960 5233//5233 5231//5231 -f 5231//5231 5233//5233 5234//5234 -f 5231//5231 5234//5234 5230//5230 -f 5230//5230 5234//5234 5235//5235 -f 5230//5230 5235//5235 5229//5229 -f 5229//5229 5235//5235 5236//5236 -f 5229//5229 5236//5236 5228//5228 -f 5228//5228 5236//5236 5237//5237 -f 5228//5228 5237//5237 5227//5227 -f 5227//5227 5237//5237 5238//5238 -f 5227//5227 5238//5238 5226//5226 -f 5226//5226 5238//5238 5239//5239 -f 5226//5226 5239//5239 5225//5225 -f 5225//5225 5239//5239 5240//5240 -f 5225//5225 5240//5240 5224//5224 -f 5224//5224 5240//5240 5241//5241 -f 5224//5224 5241//5241 5223//5223 -f 5223//5223 5241//5241 5242//5242 -f 5223//5223 5242//5242 5222//5222 -f 5222//5222 5242//5242 5243//5243 -f 5222//5222 5243//5243 5221//5221 -f 5221//5221 5243//5243 4952//4952 -f 5240//5240 5244//5244 5241//5241 -f 5241//5241 5244//5244 5245//5245 -f 5241//5241 5245//5245 5242//5242 -f 5242//5242 5245//5245 5246//5246 -f 5242//5242 5246//5246 5243//5243 -f 5243//5243 5246//5246 4952//4952 -f 4964//4964 5247//5247 5248//5248 -f 5248//5248 5247//5247 5249//5249 -f 5248//5248 5249//5249 5250//5250 -f 5250//5250 5249//5249 5251//5251 -f 5250//5250 5251//5251 5252//5252 -f 5252//5252 5251//5251 5253//5253 -f 5252//5252 5253//5253 5254//5254 -f 5254//5254 5253//5253 5255//5255 -f 5254//5254 5255//5255 5256//5256 -f 5256//5256 5255//5255 5257//5257 -f 5256//5256 5257//5257 5258//5258 -f 5258//5258 5257//5257 5259//5259 -f 5258//5258 5259//5259 5260//5260 -f 5260//5260 5259//5259 5261//5261 -f 5260//5260 5261//5261 5244//5244 -f 5244//5244 5261//5261 5262//5262 -f 5244//5244 5262//5262 5245//5245 -f 5245//5245 5262//5262 5263//5263 -f 5245//5245 5263//5263 5246//5246 -f 5246//5246 5263//5263 4952//4952 -f 5247//5247 5117//5117 5249//5249 -f 5249//5249 5117//5117 5119//5119 -f 5249//5249 5119//5119 5251//5251 -f 5251//5251 5119//5119 5121//5121 -f 5251//5251 5121//5121 5253//5253 -f 5253//5253 5121//5121 5123//5123 -f 5253//5253 5123//5123 5255//5255 -f 5255//5255 5123//5123 5125//5125 -f 5255//5255 5125//5125 5257//5257 -f 5257//5257 5125//5125 5127//5127 -f 5257//5257 5127//5127 5259//5259 -f 5259//5259 5127//5127 5129//5129 -f 5259//5259 5129//5129 5261//5261 -f 5261//5261 5129//5129 5131//5131 -f 5261//5261 5131//5131 5262//5262 -f 5262//5262 5131//5131 5133//5133 -f 5262//5262 5133//5133 5263//5263 -f 5263//5263 5133//5133 4952//4952 -f 4952//4952 5172//5172 4950//4950 -f 4950//4950 5172//5172 5174//5174 -f 4950//4950 5174//5174 5104//5104 -f 5104//5104 5174//5174 5176//5176 -f 5104//5104 5176//5176 5089//5089 -f 5089//5089 5176//5176 5178//5178 -f 5089//5089 5178//5178 5064//5064 -f 5064//5064 5178//5178 5180//5180 -f 5064//5064 5180//5180 5040//5040 -f 5040//5040 5180//5180 5182//5182 -f 5040//5040 5182//5182 5021//5021 -f 5021//5021 5182//5182 5184//5184 -f 5021//5021 5184//5184 5001//5001 -f 5001//5001 5184//5184 5186//5186 -f 5001//5001 5186//5186 4999//4999 -f 4999//4999 5186//5186 5188//5188 -f 4999//4999 5188//5188 4997//4997 -f 4997//4997 5188//5188 5190//5190 -f 4997//4997 5190//5190 4995//4995 -f 4995//4995 5190//5190 5192//5192 -f 4995//4995 5192//5192 4993//4993 -f 4993//4993 5192//5192 5194//5194 -f 4993//4993 5194//5194 4991//4991 -f 4991//4991 5194//5194 4958//4958 -f 5171//5171 5086//5086 5173//5173 -f 5173//5173 5086//5086 5061//5061 -f 5173//5173 5061//5061 5175//5175 -f 5175//5175 5061//5061 5037//5037 -f 5175//5175 5037//5037 5177//5177 -f 5177//5177 5037//5037 5018//5018 -f 5177//5177 5018//5018 5179//5179 -f 5179//5179 5018//5018 4988//4988 -f 5179//5179 4988//4988 5181//5181 -f 5181//5181 4988//4988 4981//4981 -f 5181//5181 4981//4981 5183//5183 -f 5183//5183 4981//4981 4975//4975 -f 5183//5183 4975//4975 5185//5185 -f 5185//5185 4975//4975 4970//4970 -f 5185//5185 4970//4970 5187//5187 -f 5187//5187 4970//4970 4966//4966 -f 5187//5187 4966//4966 5189//5189 -f 5189//5189 4966//4966 4955//4955 -f 5189//5189 4955//4955 5191//5191 -f 5191//5191 4955//4955 4957//4957 -f 5191//5191 4957//4957 5193//5193 -f 5193//5193 4957//4957 4958//4958 -f 5087//5087 5062//5062 5150//5150 -f 5150//5150 5062//5062 5077//5077 -f 5150//5150 5077//5077 5152//5152 -f 5152//5152 5077//5077 5078//5078 -f 5152//5152 5078//5078 5154//5154 -f 5154//5154 5078//5078 5079//5079 -f 5154//5154 5079//5079 5156//5156 -f 5156//5156 5079//5079 5080//5080 -f 5156//5156 5080//5080 5158//5158 -f 5158//5158 5080//5080 5081//5081 -f 5158//5158 5081//5081 5160//5160 -f 5160//5160 5081//5081 5082//5082 -f 5160//5160 5082//5082 5162//5162 -f 5162//5162 5082//5082 5083//5083 -f 5162//5162 5083//5083 5164//5164 -f 5164//5164 5083//5083 5084//5084 -f 5164//5164 5084//5084 5166//5166 -f 5166//5166 5084//5084 5085//5085 -f 5166//5166 5085//5085 5168//5168 -f 5168//5168 5085//5085 5086//5086 -f 5168//5168 5086//5086 5170//5170 -f 5170//5170 5086//5086 5171//5171 -f 5170//5170 5171//5171 4952//4952 -f 5132//5132 4952//4952 5133//5133 -f 5118//5118 5009//5009 5120//5120 -f 5120//5120 5009//5009 5011//5011 -f 5120//5120 5011//5011 5122//5122 -f 5122//5122 5011//5011 5050//5050 -f 5122//5122 5050//5050 5124//5124 -f 5124//5124 5050//5050 5052//5052 -f 5124//5124 5052//5052 5126//5126 -f 5126//5126 5052//5052 5076//5076 -f 5126//5126 5076//5076 5128//5128 -f 5128//5128 5076//5076 5102//5102 -f 5128//5128 5102//5102 5130//5130 -f 5130//5130 5102//5102 4953//4953 -f 5130//5130 4953//4953 5132//5132 -f 5132//5132 4953//4953 4952//4952 -f 4962//4962 4958//4958 5087//5087 -f 4964//4964 4963//4963 5247//5247 -f 5247//5247 4963//4963 5151//5151 -f 5247//5247 5151//5151 5117//5117 -f 5117//5117 5151//5151 5153//5153 -f 5117//5117 5153//5153 5118//5118 -f 5118//5118 5153//5153 5155//5155 -f 5118//5118 5155//5155 5009//5009 -f 5009//5009 5155//5155 5157//5157 -f 5009//5009 5157//5157 5010//5010 -f 5010//5010 5157//5157 5159//5159 -f 5010//5010 5159//5159 5145//5145 -f 5145//5145 5159//5159 5161//5161 -f 5145//5145 5161//5161 5146//5146 -f 5146//5146 5161//5161 5163//5163 -f 5146//5146 5163//5163 5147//5147 -f 5147//5147 5163//5163 5165//5165 -f 5147//5147 5165//5165 5148//5148 -f 5148//5148 5165//5165 5167//5167 -f 5148//5148 5167//5167 5149//5149 -f 5149//5149 5167//5167 5169//5169 -f 5149//5149 5169//5169 4952//4952 -f 5244//5244 5240//5240 5260//5260 -f 5260//5260 5240//5240 5239//5239 -f 5260//5260 5239//5239 5258//5258 -f 5258//5258 5239//5239 5238//5238 -f 5258//5258 5238//5238 5256//5256 -f 5256//5256 5238//5238 5237//5237 -f 5256//5256 5237//5237 5254//5254 -f 5254//5254 5237//5237 5236//5236 -f 5254//5254 5236//5236 5252//5252 -f 5252//5252 5236//5236 5235//5235 -f 5252//5252 5235//5235 5250//5250 -f 5250//5250 5235//5235 5234//5234 -f 5250//5250 5234//5234 5248//5248 -f 5248//5248 5234//5234 5233//5233 -f 5248//5248 5233//5233 4964//4964 -f 4964//4964 5233//5233 5232//5232 -f 4964//4964 5232//5232 4962//4962 -f 4962//4962 5232//5232 4958//4958 -f 4952//4952 3144//3144 3123//3123 -f 3145//3145 3144//3144 4952//4952 -f 4952//4952 3122//3122 3127//3127 -f 3123//3123 3122//3122 4952//4952 -f 4952//4952 3127//3127 3129//3129 -f 3143//3143 3141//3141 4952//4952 -f 3131//3131 3119//3119 5140//5140 -f 4952//4952 3129//3129 5140//5140 -f 5140//5140 3129//3129 3131//3131 -f 3138//3138 3136//3136 5139//5139 -f 3138//3138 5139//5139 3139//3139 -f 5140//5140 3119//3119 3134//3134 -f 5140//5140 3134//3134 5139//5139 -f 5139//5139 3134//3134 3133//3133 -f 5139//5139 3133//3133 3139//3139 -f 3141//3141 3145//3145 4952//4952 -f 3136//3136 3143//3143 5139//5139 -f 5139//5139 3143//3143 4952//4952 -f 5264//5264 5265//5265 5266//5266 -f 5267//5267 5268//5268 5266//5266 -f 5269//5269 5270//5270 5271//5271 -f 5271//5271 5270//5270 5272//5272 -f 5273//5273 5272//5272 5270//5270 -f 3289//3289 3295//3295 5274//5274 -f 5274//5274 3295//3295 3294//3294 -f 5274//5274 3294//3294 3292//3292 -f 5272//5272 3297//3297 3301//3301 -f 3299//3299 3297//3297 5272//5272 -f 3292//3292 3299//3299 5274//5274 -f 5274//5274 3299//3299 5272//5272 -f 5272//5272 3300//3300 3279//3279 -f 3301//3301 3300//3300 5272//5272 -f 5272//5272 3278//3278 3283//3283 -f 3279//3279 3278//3278 5272//5272 -f 5272//5272 3283//3283 3285//3285 -f 5272//5272 3285//3285 5275//5275 -f 5275//5275 3285//3285 3287//3287 -f 3287//3287 3248//3248 5275//5275 -f 5275//5275 3248//3248 3290//3290 -f 5276//5276 5277//5277 5278//5278 -f 5273//5273 5270//5270 5279//5279 -f 5279//5279 5270//5270 5269//5269 -f 5279//5279 5269//5269 5280//5280 -f 5281//5281 5272//5272 5273//5273 -f 5281//5281 5273//5273 5282//5282 -f 5282//5282 5273//5273 5279//5279 -f 5282//5282 5279//5279 5283//5283 -f 5283//5283 5279//5279 5280//5280 -f 5283//5283 5280//5280 5284//5284 -f 5285//5285 5272//5272 5281//5281 -f 5285//5285 5281//5281 5286//5286 -f 5286//5286 5281//5281 5282//5282 -f 5286//5286 5282//5282 5287//5287 -f 5287//5287 5282//5282 5283//5283 -f 5287//5287 5283//5283 5288//5288 -f 5288//5288 5283//5283 5284//5284 -f 5288//5288 5284//5284 5289//5289 -f 5290//5290 5272//5272 5285//5285 -f 5290//5290 5285//5285 5291//5291 -f 5291//5291 5285//5285 5286//5286 -f 5291//5291 5286//5286 5292//5292 -f 5292//5292 5286//5286 5287//5287 -f 5292//5292 5287//5287 5293//5293 -f 5293//5293 5287//5287 5288//5288 -f 5293//5293 5288//5288 5294//5294 -f 5294//5294 5288//5288 5289//5289 -f 5294//5294 5289//5289 5295//5295 -f 5296//5296 5272//5272 5290//5290 -f 5296//5296 5290//5290 5297//5297 -f 5297//5297 5290//5290 5291//5291 -f 5297//5297 5291//5291 5298//5298 -f 5298//5298 5291//5291 5292//5292 -f 5298//5298 5292//5292 5299//5299 -f 5299//5299 5292//5292 5293//5293 -f 5299//5299 5293//5293 5300//5300 -f 5300//5300 5293//5293 5294//5294 -f 5300//5300 5294//5294 5301//5301 -f 5301//5301 5294//5294 5295//5295 -f 5301//5301 5295//5295 5302//5302 -f 5303//5303 5272//5272 5296//5296 -f 5272//5272 5304//5304 5305//5305 -f 5305//5305 5304//5304 5306//5306 -f 5305//5305 5306//5306 5307//5307 -f 5307//5307 5306//5306 5308//5308 -f 5307//5307 5308//5308 5309//5309 -f 5309//5309 5308//5308 5310//5310 -f 5309//5309 5310//5310 5311//5311 -f 5311//5311 5310//5310 5312//5312 -f 5311//5311 5312//5312 5313//5313 -f 5313//5313 5312//5312 5314//5314 -f 5313//5313 5314//5314 5315//5315 -f 5316//5316 5314//5314 5317//5317 -f 5317//5317 5314//5314 5312//5312 -f 5317//5317 5312//5312 5318//5318 -f 5318//5318 5312//5312 5310//5310 -f 5318//5318 5310//5310 5319//5319 -f 5319//5319 5310//5310 5308//5308 -f 5319//5319 5308//5308 5320//5320 -f 5320//5320 5308//5308 5306//5306 -f 5320//5320 5306//5306 5321//5321 -f 5321//5321 5306//5306 5304//5304 -f 5321//5321 5304//5304 5322//5322 -f 5322//5322 5304//5304 5272//5272 -f 5323//5323 5324//5324 5325//5325 -f 5303//5303 5296//5296 5326//5326 -f 5326//5326 5296//5296 5297//5297 -f 5326//5326 5297//5297 5327//5327 -f 5327//5327 5297//5297 5298//5298 -f 5327//5327 5298//5298 5328//5328 -f 5328//5328 5298//5298 5299//5299 -f 5328//5328 5299//5299 5329//5329 -f 5329//5329 5299//5299 5300//5300 -f 5329//5329 5300//5300 5330//5330 -f 5330//5330 5300//5300 5301//5301 -f 5330//5330 5301//5301 5331//5331 -f 5331//5331 5301//5301 5302//5302 -f 5331//5331 5302//5302 5332//5332 -f 5333//5333 5272//5272 5303//5303 -f 5315//5315 5334//5334 5335//5335 -f 5336//5336 5316//5316 5337//5337 -f 5337//5337 5316//5316 5317//5317 -f 5337//5337 5317//5317 5338//5338 -f 5338//5338 5317//5317 5318//5318 -f 5338//5338 5318//5318 5339//5339 -f 5339//5339 5318//5318 5319//5319 -f 5339//5339 5319//5319 5340//5340 -f 5340//5340 5319//5319 5320//5320 -f 5340//5340 5320//5320 5341//5341 -f 5341//5341 5320//5320 5321//5321 -f 5341//5341 5321//5321 5342//5342 -f 5342//5342 5321//5321 5322//5322 -f 5342//5342 5322//5322 5343//5343 -f 5343//5343 5322//5322 5272//5272 -f 5333//5333 5303//5303 5344//5344 -f 5344//5344 5303//5303 5326//5326 -f 5344//5344 5326//5326 5345//5345 -f 5345//5345 5326//5326 5327//5327 -f 5345//5345 5327//5327 5346//5346 -f 5346//5346 5327//5327 5328//5328 -f 5346//5346 5328//5328 5347//5347 -f 5347//5347 5328//5328 5329//5329 -f 5347//5347 5329//5329 5348//5348 -f 5348//5348 5329//5329 5330//5330 -f 5348//5348 5330//5330 5349//5349 -f 5349//5349 5330//5330 5331//5331 -f 5349//5349 5331//5331 5350//5350 -f 5350//5350 5331//5331 5332//5332 -f 5350//5350 5332//5332 5351//5351 -f 5352//5352 5272//5272 5333//5333 -f 5335//5335 5353//5353 5354//5354 -f 5355//5355 5336//5336 5356//5356 -f 5356//5356 5336//5336 5337//5337 -f 5356//5356 5337//5337 5357//5357 -f 5357//5357 5337//5337 5338//5338 -f 5357//5357 5338//5338 5358//5358 -f 5358//5358 5338//5338 5339//5339 -f 5358//5358 5339//5339 5359//5359 -f 5359//5359 5339//5339 5340//5340 -f 5359//5359 5340//5340 5360//5360 -f 5360//5360 5340//5340 5341//5341 -f 5360//5360 5341//5341 5361//5361 -f 5361//5361 5341//5341 5342//5342 -f 5361//5361 5342//5342 5362//5362 -f 5362//5362 5342//5342 5343//5343 -f 5362//5362 5343//5343 5363//5363 -f 5363//5363 5343//5343 5272//5272 -f 5364//5364 5365//5365 5366//5366 -f 5352//5352 5333//5333 5367//5367 -f 5367//5367 5333//5333 5344//5344 -f 5367//5367 5344//5344 5368//5368 -f 5368//5368 5344//5344 5345//5345 -f 5368//5368 5345//5345 5369//5369 -f 5369//5369 5345//5345 5346//5346 -f 5369//5369 5346//5346 5370//5370 -f 5370//5370 5346//5346 5347//5347 -f 5370//5370 5347//5347 5371//5371 -f 5371//5371 5347//5347 5348//5348 -f 5371//5371 5348//5348 5372//5372 -f 5372//5372 5348//5348 5349//5349 -f 5372//5372 5349//5349 5373//5373 -f 5373//5373 5349//5349 5350//5350 -f 5373//5373 5350//5350 5374//5374 -f 5374//5374 5350//5350 5351//5351 -f 5374//5374 5351//5351 5375//5375 -f 5376//5376 5272//5272 5352//5352 -f 5354//5354 5377//5377 5378//5378 -f 5379//5379 5355//5355 5380//5380 -f 5380//5380 5355//5355 5356//5356 -f 5380//5380 5356//5356 5381//5381 -f 5381//5381 5356//5356 5357//5357 -f 5381//5381 5357//5357 5382//5382 -f 5382//5382 5357//5357 5358//5358 -f 5382//5382 5358//5358 5383//5383 -f 5383//5383 5358//5358 5359//5359 -f 5383//5383 5359//5359 5384//5384 -f 5384//5384 5359//5359 5360//5360 -f 5384//5384 5360//5360 5385//5385 -f 5385//5385 5360//5360 5361//5361 -f 5385//5385 5361//5361 5386//5386 -f 5386//5386 5361//5361 5362//5362 -f 5386//5386 5362//5362 5387//5387 -f 5387//5387 5362//5362 5363//5363 -f 5387//5387 5363//5363 5388//5388 -f 5388//5388 5363//5363 5272//5272 -f 5366//5366 5389//5389 5390//5390 -f 5376//5376 5352//5352 5391//5391 -f 5391//5391 5352//5352 5367//5367 -f 5391//5391 5367//5367 5392//5392 -f 5392//5392 5367//5367 5368//5368 -f 5392//5392 5368//5368 5393//5393 -f 5393//5393 5368//5368 5369//5369 -f 5393//5393 5369//5369 5394//5394 -f 5394//5394 5369//5369 5370//5370 -f 5394//5394 5370//5370 5395//5395 -f 5395//5395 5370//5370 5371//5371 -f 5395//5395 5371//5371 5396//5396 -f 5396//5396 5371//5371 5372//5372 -f 5396//5396 5372//5372 5397//5397 -f 5397//5397 5372//5372 5373//5373 -f 5397//5397 5373//5373 5398//5398 -f 5398//5398 5373//5373 5374//5374 -f 5398//5398 5374//5374 5399//5399 -f 5399//5399 5374//5374 5375//5375 -f 5399//5399 5375//5375 5400//5400 -f 5401//5401 5272//5272 5376//5376 -f 5378//5378 5402//5402 5403//5403 -f 5404//5404 5379//5379 5405//5405 -f 5405//5405 5379//5379 5380//5380 -f 5405//5405 5380//5380 5406//5406 -f 5406//5406 5380//5380 5381//5381 -f 5406//5406 5381//5381 5407//5407 -f 5407//5407 5381//5381 5382//5382 -f 5407//5407 5382//5382 5408//5408 -f 5408//5408 5382//5382 5383//5383 -f 5408//5408 5383//5383 5409//5409 -f 5409//5409 5383//5383 5384//5384 -f 5409//5409 5384//5384 5410//5410 -f 5410//5410 5384//5384 5385//5385 -f 5410//5410 5385//5385 5411//5411 -f 5411//5411 5385//5385 5386//5386 -f 5411//5411 5386//5386 5412//5412 -f 5412//5412 5386//5386 5387//5387 -f 5412//5412 5387//5387 5413//5413 -f 5413//5413 5387//5387 5388//5388 -f 5413//5413 5388//5388 5414//5414 -f 5414//5414 5388//5388 5272//5272 -f 5390//5390 5415//5415 5416//5416 -f 5403//5403 5417//5417 5418//5418 -f 5419//5419 5404//5404 5420//5420 -f 5420//5420 5404//5404 5405//5405 -f 5420//5420 5405//5405 5421//5421 -f 5421//5421 5405//5405 5406//5406 -f 5421//5421 5406//5406 5422//5422 -f 5422//5422 5406//5406 5407//5407 -f 5422//5422 5407//5407 5423//5423 -f 5423//5423 5407//5407 5408//5408 -f 5423//5423 5408//5408 5424//5424 -f 5424//5424 5408//5408 5409//5409 -f 5424//5424 5409//5409 5425//5425 -f 5425//5425 5409//5409 5410//5410 -f 5425//5425 5410//5410 5426//5426 -f 5426//5426 5410//5410 5411//5411 -f 5426//5426 5411//5411 5427//5427 -f 5427//5427 5411//5411 5412//5412 -f 5427//5427 5412//5412 5428//5428 -f 5428//5428 5412//5412 5413//5413 -f 5428//5428 5413//5413 5429//5429 -f 5429//5429 5413//5413 5414//5414 -f 5429//5429 5414//5414 5430//5430 -f 5430//5430 5414//5414 5272//5272 -f 5431//5431 5432//5432 5433//5433 -f 5433//5433 5432//5432 5434//5434 -f 5433//5433 5434//5434 5435//5435 -f 5435//5435 5434//5434 5436//5436 -f 5435//5435 5436//5436 5437//5437 -f 5437//5437 5436//5436 5438//5438 -f 5437//5437 5438//5438 5439//5439 -f 5439//5439 5438//5438 5440//5440 -f 5439//5439 5440//5440 5441//5441 -f 5441//5441 5440//5440 5442//5442 -f 5441//5441 5442//5442 5443//5443 -f 5443//5443 5442//5442 5444//5444 -f 5443//5443 5444//5444 5445//5445 -f 5445//5445 5444//5444 5446//5446 -f 5445//5445 5446//5446 5447//5447 -f 5268//5268 5267//5267 5416//5416 -f 5416//5416 5415//5415 5268//5268 -f 5268//5268 5415//5415 5448//5448 -f 5268//5268 5448//5448 5266//5266 -f 5390//5390 5389//5389 5415//5415 -f 5415//5415 5389//5389 5449//5449 -f 5415//5415 5449//5449 5448//5448 -f 5448//5448 5449//5449 5450//5450 -f 5448//5448 5450//5450 5266//5266 -f 5366//5366 5365//5365 5389//5389 -f 5389//5389 5365//5365 5451//5451 -f 5389//5389 5451//5451 5449//5449 -f 5449//5449 5451//5451 5452//5452 -f 5449//5449 5452//5452 5450//5450 -f 5450//5450 5452//5452 5453//5453 -f 5450//5450 5453//5453 5266//5266 -f 5454//5454 5453//5453 5455//5455 -f 5455//5455 5453//5453 5452//5452 -f 5455//5455 5452//5452 5456//5456 -f 5456//5456 5452//5452 5451//5451 -f 5456//5456 5451//5451 5457//5457 -f 5457//5457 5451//5451 5365//5365 -f 5457//5457 5365//5365 5458//5458 -f 5458//5458 5365//5365 5364//5364 -f 5458//5458 5364//5364 5325//5325 -f 5325//5325 5324//5324 5458//5458 -f 5458//5458 5324//5324 5459//5459 -f 5458//5458 5459//5459 5457//5457 -f 5457//5457 5459//5459 5460//5460 -f 5457//5457 5460//5460 5456//5456 -f 5456//5456 5460//5460 5461//5461 -f 5456//5456 5461//5461 5455//5455 -f 5455//5455 5461//5461 5462//5462 -f 5455//5455 5462//5462 5454//5454 -f 5454//5454 5462//5462 5463//5463 -f 5454//5454 5463//5463 5266//5266 -f 5276//5276 5401//5401 5277//5277 -f 5277//5277 5401//5401 5464//5464 -f 5277//5277 5464//5464 5465//5465 -f 5465//5465 5464//5464 5466//5466 -f 5465//5465 5466//5466 5467//5467 -f 5467//5467 5466//5466 5468//5468 -f 5467//5467 5468//5468 5469//5469 -f 5469//5469 5468//5468 5470//5470 -f 5469//5469 5470//5470 5471//5471 -f 5471//5471 5470//5470 5472//5472 -f 5471//5471 5472//5472 5473//5473 -f 5473//5473 5472//5472 5474//5474 -f 5473//5473 5474//5474 5475//5475 -f 5475//5475 5474//5474 5476//5476 -f 5475//5475 5476//5476 5477//5477 -f 5477//5477 5476//5476 5478//5478 -f 5477//5477 5478//5478 5479//5479 -f 5479//5479 5478//5478 5480//5480 -f 5479//5479 5480//5480 5481//5481 -f 5481//5481 5480//5480 5482//5482 -f 5481//5481 5482//5482 5483//5483 -f 5483//5483 5482//5482 5484//5484 -f 5483//5483 5484//5484 5266//5266 -f 5266//5266 5485//5485 5486//5486 -f 5486//5486 5485//5485 5487//5487 -f 5486//5486 5487//5487 5488//5488 -f 5488//5488 5487//5487 5489//5489 -f 5488//5488 5489//5489 5490//5490 -f 5490//5490 5489//5489 5491//5491 -f 5490//5490 5491//5491 5492//5492 -f 5492//5492 5491//5491 5493//5493 -f 5492//5492 5493//5493 5494//5494 -f 5494//5494 5493//5493 5495//5495 -f 5494//5494 5495//5495 5496//5496 -f 5496//5496 5495//5495 5497//5497 -f 5496//5496 5497//5497 5498//5498 -f 5498//5498 5497//5497 5499//5499 -f 5498//5498 5499//5499 5500//5500 -f 5500//5500 5499//5499 5501//5501 -f 5500//5500 5501//5501 5502//5502 -f 5502//5502 5501//5501 5503//5503 -f 5502//5502 5503//5503 5504//5504 -f 5504//5504 5503//5503 5505//5505 -f 5504//5504 5505//5505 5506//5506 -f 5506//5506 5505//5505 5507//5507 -f 5506//5506 5507//5507 5508//5508 -f 5508//5508 5507//5507 5272//5272 -f 5265//5265 5264//5264 5418//5418 -f 5418//5418 5417//5417 5265//5265 -f 5265//5265 5417//5417 5509//5509 -f 5265//5265 5509//5509 5266//5266 -f 5403//5403 5402//5402 5417//5417 -f 5417//5417 5402//5402 5510//5510 -f 5417//5417 5510//5510 5509//5509 -f 5509//5509 5510//5510 5511//5511 -f 5509//5509 5511//5511 5266//5266 -f 5378//5378 5377//5377 5402//5402 -f 5402//5402 5377//5377 5512//5512 -f 5402//5402 5512//5512 5510//5510 -f 5510//5510 5512//5512 5513//5513 -f 5510//5510 5513//5513 5511//5511 -f 5511//5511 5513//5513 5514//5514 -f 5511//5511 5514//5514 5266//5266 -f 5354//5354 5353//5353 5377//5377 -f 5377//5377 5353//5353 5515//5515 -f 5377//5377 5515//5515 5512//5512 -f 5512//5512 5515//5515 5516//5516 -f 5512//5512 5516//5516 5513//5513 -f 5513//5513 5516//5516 5517//5517 -f 5513//5513 5517//5517 5514//5514 -f 5514//5514 5517//5517 5518//5518 -f 5514//5514 5518//5518 5266//5266 -f 5335//5335 5334//5334 5353//5353 -f 5353//5353 5334//5334 5519//5519 -f 5353//5353 5519//5519 5515//5515 -f 5515//5515 5519//5519 5520//5520 -f 5515//5515 5520//5520 5516//5516 -f 5516//5516 5520//5520 5521//5521 -f 5516//5516 5521//5521 5517//5517 -f 5517//5517 5521//5521 5522//5522 -f 5517//5517 5522//5522 5518//5518 -f 5518//5518 5522//5522 5523//5523 -f 5518//5518 5523//5523 5266//5266 -f 5266//5266 5419//5419 5524//5524 -f 5524//5524 5419//5419 5420//5420 -f 5524//5524 5420//5420 5525//5525 -f 5525//5525 5420//5420 5421//5421 -f 5525//5525 5421//5421 5526//5526 -f 5526//5526 5421//5421 5422//5422 -f 5526//5526 5422//5422 5527//5527 -f 5527//5527 5422//5422 5423//5423 -f 5527//5527 5423//5423 5528//5528 -f 5528//5528 5423//5423 5424//5424 -f 5528//5528 5424//5424 5529//5529 -f 5529//5529 5424//5424 5425//5425 -f 5529//5529 5425//5425 5530//5530 -f 5530//5530 5425//5425 5426//5426 -f 5530//5530 5426//5426 5531//5531 -f 5531//5531 5426//5426 5427//5427 -f 5531//5531 5427//5427 5532//5532 -f 5532//5532 5427//5427 5428//5428 -f 5532//5532 5428//5428 5533//5533 -f 5533//5533 5428//5428 5429//5429 -f 5533//5533 5429//5429 5534//5534 -f 5534//5534 5429//5429 5430//5430 -f 5534//5534 5430//5430 5275//5275 -f 5275//5275 5430//5430 5272//5272 -f 5266//5266 5524//5524 5535//5535 -f 5535//5535 5524//5524 5525//5525 -f 5535//5535 5525//5525 5536//5536 -f 5536//5536 5525//5525 5526//5526 -f 5536//5536 5526//5526 5537//5537 -f 5537//5537 5526//5526 5527//5527 -f 5537//5537 5527//5527 5538//5538 -f 5538//5538 5527//5527 5528//5528 -f 5538//5538 5528//5528 5539//5539 -f 5539//5539 5528//5528 5529//5529 -f 5539//5539 5529//5529 5540//5540 -f 5540//5540 5529//5529 5530//5530 -f 5540//5540 5530//5530 5541//5541 -f 5541//5541 5530//5530 5531//5531 -f 5541//5541 5531//5531 5542//5542 -f 5542//5542 5531//5531 5532//5532 -f 5542//5542 5532//5532 5543//5543 -f 5543//5543 5532//5532 5533//5533 -f 5543//5543 5533//5533 5544//5544 -f 5544//5544 5533//5533 5534//5534 -f 5544//5544 5534//5534 5545//5545 -f 5545//5545 5534//5534 5275//5275 -f 5545//5545 5275//5275 5274//5274 -f 5274//5274 5275//5275 3290//3290 -f 5274//5274 3290//3290 3289//3289 -f 5315//5315 5314//5314 5334//5334 -f 5334//5334 5314//5314 5316//5316 -f 5334//5334 5316//5316 5519//5519 -f 5519//5519 5316//5316 5336//5336 -f 5519//5519 5336//5336 5520//5520 -f 5520//5520 5336//5336 5355//5355 -f 5520//5520 5355//5355 5521//5521 -f 5521//5521 5355//5355 5379//5379 -f 5521//5521 5379//5379 5522//5522 -f 5522//5522 5379//5379 5404//5404 -f 5522//5522 5404//5404 5523//5523 -f 5523//5523 5404//5404 5419//5419 -f 5523//5523 5419//5419 5266//5266 -f 5272//5272 5546//5546 5274//5274 -f 5274//5274 5546//5546 5547//5547 -f 5274//5274 5547//5547 5545//5545 -f 5545//5545 5547//5547 5548//5548 -f 5545//5545 5548//5548 5544//5544 -f 5544//5544 5548//5548 5549//5549 -f 5544//5544 5549//5549 5543//5543 -f 5543//5543 5549//5549 5550//5550 -f 5543//5543 5550//5550 5542//5542 -f 5542//5542 5550//5550 5551//5551 -f 5542//5542 5551//5551 5541//5541 -f 5541//5541 5551//5551 5552//5552 -f 5541//5541 5552//5552 5540//5540 -f 5540//5540 5552//5552 5553//5553 -f 5540//5540 5553//5553 5539//5539 -f 5539//5539 5553//5553 5554//5554 -f 5539//5539 5554//5554 5538//5538 -f 5538//5538 5554//5554 5555//5555 -f 5538//5538 5555//5555 5537//5537 -f 5537//5537 5555//5555 5556//5556 -f 5537//5537 5556//5556 5536//5536 -f 5536//5536 5556//5556 5557//5557 -f 5536//5536 5557//5557 5535//5535 -f 5535//5535 5557//5557 5266//5266 -f 5554//5554 5558//5558 5555//5555 -f 5555//5555 5558//5558 5559//5559 -f 5555//5555 5559//5559 5556//5556 -f 5556//5556 5559//5559 5560//5560 -f 5556//5556 5560//5560 5557//5557 -f 5557//5557 5560//5560 5266//5266 -f 5278//5278 5561//5561 5562//5562 -f 5562//5562 5561//5561 5563//5563 -f 5562//5562 5563//5563 5564//5564 -f 5564//5564 5563//5563 5565//5565 -f 5564//5564 5565//5565 5566//5566 -f 5566//5566 5565//5565 5567//5567 -f 5566//5566 5567//5567 5568//5568 -f 5568//5568 5567//5567 5569//5569 -f 5568//5568 5569//5569 5570//5570 -f 5570//5570 5569//5569 5571//5571 -f 5570//5570 5571//5571 5572//5572 -f 5572//5572 5571//5571 5573//5573 -f 5572//5572 5573//5573 5574//5574 -f 5574//5574 5573//5573 5575//5575 -f 5574//5574 5575//5575 5558//5558 -f 5558//5558 5575//5575 5576//5576 -f 5558//5558 5576//5576 5559//5559 -f 5559//5559 5576//5576 5577//5577 -f 5559//5559 5577//5577 5560//5560 -f 5560//5560 5577//5577 5266//5266 -f 5561//5561 5431//5431 5563//5563 -f 5563//5563 5431//5431 5433//5433 -f 5563//5563 5433//5433 5565//5565 -f 5565//5565 5433//5433 5435//5435 -f 5565//5565 5435//5435 5567//5567 -f 5567//5567 5435//5435 5437//5437 -f 5567//5567 5437//5437 5569//5569 -f 5569//5569 5437//5437 5439//5439 -f 5569//5569 5439//5439 5571//5571 -f 5571//5571 5439//5439 5441//5441 -f 5571//5571 5441//5441 5573//5573 -f 5573//5573 5441//5441 5443//5443 -f 5573//5573 5443//5443 5575//5575 -f 5575//5575 5443//5443 5445//5445 -f 5575//5575 5445//5445 5576//5576 -f 5576//5576 5445//5445 5447//5447 -f 5576//5576 5447//5447 5577//5577 -f 5577//5577 5447//5447 5266//5266 -f 5266//5266 5486//5486 5264//5264 -f 5264//5264 5486//5486 5488//5488 -f 5264//5264 5488//5488 5418//5418 -f 5418//5418 5488//5488 5490//5490 -f 5418//5418 5490//5490 5403//5403 -f 5403//5403 5490//5490 5492//5492 -f 5403//5403 5492//5492 5378//5378 -f 5378//5378 5492//5492 5494//5494 -f 5378//5378 5494//5494 5354//5354 -f 5354//5354 5494//5494 5496//5496 -f 5354//5354 5496//5496 5335//5335 -f 5335//5335 5496//5496 5498//5498 -f 5335//5335 5498//5498 5315//5315 -f 5315//5315 5498//5498 5500//5500 -f 5315//5315 5500//5500 5313//5313 -f 5313//5313 5500//5500 5502//5502 -f 5313//5313 5502//5502 5311//5311 -f 5311//5311 5502//5502 5504//5504 -f 5311//5311 5504//5504 5309//5309 -f 5309//5309 5504//5504 5506//5506 -f 5309//5309 5506//5506 5307//5307 -f 5307//5307 5506//5506 5508//5508 -f 5307//5307 5508//5508 5305//5305 -f 5305//5305 5508//5508 5272//5272 -f 5485//5485 5400//5400 5487//5487 -f 5487//5487 5400//5400 5375//5375 -f 5487//5487 5375//5375 5489//5489 -f 5489//5489 5375//5375 5351//5351 -f 5489//5489 5351//5351 5491//5491 -f 5491//5491 5351//5351 5332//5332 -f 5491//5491 5332//5332 5493//5493 -f 5493//5493 5332//5332 5302//5302 -f 5493//5493 5302//5302 5495//5495 -f 5495//5495 5302//5302 5295//5295 -f 5495//5495 5295//5295 5497//5497 -f 5497//5497 5295//5295 5289//5289 -f 5497//5497 5289//5289 5499//5499 -f 5499//5499 5289//5289 5284//5284 -f 5499//5499 5284//5284 5501//5501 -f 5501//5501 5284//5284 5280//5280 -f 5501//5501 5280//5280 5503//5503 -f 5503//5503 5280//5280 5269//5269 -f 5503//5503 5269//5269 5505//5505 -f 5505//5505 5269//5269 5271//5271 -f 5505//5505 5271//5271 5507//5507 -f 5507//5507 5271//5271 5272//5272 -f 5401//5401 5376//5376 5464//5464 -f 5464//5464 5376//5376 5391//5391 -f 5464//5464 5391//5391 5466//5466 -f 5466//5466 5391//5391 5392//5392 -f 5466//5466 5392//5392 5468//5468 -f 5468//5468 5392//5392 5393//5393 -f 5468//5468 5393//5393 5470//5470 -f 5470//5470 5393//5393 5394//5394 -f 5470//5470 5394//5394 5472//5472 -f 5472//5472 5394//5394 5395//5395 -f 5472//5472 5395//5395 5474//5474 -f 5474//5474 5395//5395 5396//5396 -f 5474//5474 5396//5396 5476//5476 -f 5476//5476 5396//5396 5397//5397 -f 5476//5476 5397//5397 5478//5478 -f 5478//5478 5397//5397 5398//5398 -f 5478//5478 5398//5398 5480//5480 -f 5480//5480 5398//5398 5399//5399 -f 5480//5480 5399//5399 5482//5482 -f 5482//5482 5399//5399 5400//5400 -f 5482//5482 5400//5400 5484//5484 -f 5484//5484 5400//5400 5485//5485 -f 5484//5484 5485//5485 5266//5266 -f 5446//5446 5266//5266 5447//5447 -f 5432//5432 5323//5323 5434//5434 -f 5434//5434 5323//5323 5325//5325 -f 5434//5434 5325//5325 5436//5436 -f 5436//5436 5325//5325 5364//5364 -f 5436//5436 5364//5364 5438//5438 -f 5438//5438 5364//5364 5366//5366 -f 5438//5438 5366//5366 5440//5440 -f 5440//5440 5366//5366 5390//5390 -f 5440//5440 5390//5390 5442//5442 -f 5442//5442 5390//5390 5416//5416 -f 5442//5442 5416//5416 5444//5444 -f 5444//5444 5416//5416 5267//5267 -f 5444//5444 5267//5267 5446//5446 -f 5446//5446 5267//5267 5266//5266 -f 5276//5276 5272//5272 5401//5401 -f 5278//5278 5277//5277 5561//5561 -f 5561//5561 5277//5277 5465//5465 -f 5561//5561 5465//5465 5431//5431 -f 5431//5431 5465//5465 5467//5467 -f 5431//5431 5467//5467 5432//5432 -f 5432//5432 5467//5467 5469//5469 -f 5432//5432 5469//5469 5323//5323 -f 5323//5323 5469//5469 5471//5471 -f 5323//5323 5471//5471 5324//5324 -f 5324//5324 5471//5471 5473//5473 -f 5324//5324 5473//5473 5459//5459 -f 5459//5459 5473//5473 5475//5475 -f 5459//5459 5475//5475 5460//5460 -f 5460//5460 5475//5475 5477//5477 -f 5460//5460 5477//5477 5461//5461 -f 5461//5461 5477//5477 5479//5479 -f 5461//5461 5479//5479 5462//5462 -f 5462//5462 5479//5479 5481//5481 -f 5462//5462 5481//5481 5463//5463 -f 5463//5463 5481//5481 5483//5483 -f 5463//5463 5483//5483 5266//5266 -f 5558//5558 5554//5554 5574//5574 -f 5574//5574 5554//5554 5553//5553 -f 5574//5574 5553//5553 5572//5572 -f 5572//5572 5553//5553 5552//5552 -f 5572//5572 5552//5552 5570//5570 -f 5570//5570 5552//5552 5551//5551 -f 5570//5570 5551//5551 5568//5568 -f 5568//5568 5551//5551 5550//5550 -f 5568//5568 5550//5550 5566//5566 -f 5566//5566 5550//5550 5549//5549 -f 5566//5566 5549//5549 5564//5564 -f 5564//5564 5549//5549 5548//5548 -f 5564//5564 5548//5548 5562//5562 -f 5562//5562 5548//5548 5547//5547 -f 5562//5562 5547//5547 5278//5278 -f 5278//5278 5547//5547 5546//5546 -f 5278//5278 5546//5546 5276//5276 -f 5276//5276 5546//5546 5272//5272 -f 5266//5266 3210//3210 3189//3189 -f 3211//3211 3210//3210 5266//5266 -f 5266//5266 3188//3188 3193//3193 -f 3189//3189 3188//3188 5266//5266 -f 5266//5266 3193//3193 3195//3195 -f 3209//3209 3207//3207 5266//5266 -f 3197//3197 3185//3185 5454//5454 -f 5266//5266 3195//3195 5454//5454 -f 5454//5454 3195//3195 3197//3197 -f 3204//3204 3202//3202 5453//5453 -f 3204//3204 5453//5453 3205//3205 -f 5454//5454 3185//3185 3200//3200 -f 5454//5454 3200//3200 5453//5453 -f 5453//5453 3200//3200 3199//3199 -f 5453//5453 3199//3199 3205//3205 -f 3207//3207 3211//3211 5266//5266 -f 3202//3202 3209//3209 5453//5453 -f 5453//5453 3209//3209 5266//5266 -# 11154 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper.obj deleted file mode 100644 index 6658d1ffc..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper.obj +++ /dev/null @@ -1,8064 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mid_upper_osnovno.obj -# -# Vertices: 1968 -# Faces: 4112 -# -#### -vn -0.707106 -0.612373 -0.353554 -v 0.055603 0.069975 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.071511 0.144746 -vn -0.707107 -0.612372 -0.353554 -v 0.055603 0.071511 0.142086 -vn -0.770264 -0.318861 0.552287 -v 0.055603 0.096912 0.158389 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.098893 0.158575 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.098893 0.156361 -vn -0.770260 -0.318866 -0.552291 -v 0.055603 0.096912 0.160554 -vn -0.770264 0.000000 -0.637725 -v 0.055603 0.096287 0.160722 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.096597 0.163289 -vn -0.707106 0.612373 0.353554 -v 0.055603 0.070197 0.156361 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.067511 0.156361 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.067511 0.158575 -vn -0.770263 0.552286 -0.318865 -v 0.055603 0.068428 0.153875 -vn -0.770261 0.637728 0.000000 -v 0.055603 0.068261 0.153250 -vn -0.904531 0.110364 0.411877 -v 0.055603 0.077091 0.144420 -vn -0.707111 -0.353552 0.612369 -v 0.055603 0.077656 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.077905 0.144746 -vn -0.770265 0.318861 0.552286 -v 0.055603 0.095662 0.158389 -vn -0.770258 0.000000 0.637732 -v 0.055603 0.096287 0.158222 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.096597 0.156361 -vn -0.707107 -0.612373 -0.353553 -v 0.055603 0.087601 0.170217 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.090287 0.170217 -vn -0.707109 -0.612374 -0.353545 -v 0.055603 0.090287 0.165564 -vn -0.770264 -0.000000 0.637725 -v 0.055603 0.084287 0.179006 -vn -0.770260 -0.318866 0.552291 -v 0.055603 0.084912 0.179174 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.084893 0.176792 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.086287 0.176792 -vn -0.770262 -0.552286 0.318869 -v 0.055603 0.085370 0.179631 -vn -0.770264 -0.637725 -0.000000 -v 0.055603 0.085537 0.180256 -vn -0.684468 0.627475 0.371187 -v 0.055603 0.085572 0.188730 -vn -0.770260 -0.552291 -0.318866 -v 0.055603 0.085370 0.180881 -vn -0.770265 -0.318861 -0.552286 -v 0.055603 0.084912 0.181339 -vn -0.684468 0.537285 0.492777 -v 0.055603 0.083283 0.191815 -vn -0.770258 -0.000000 -0.637732 -v 0.055603 0.084287 0.181506 -vn -0.684468 0.423927 0.593119 -v 0.055603 0.080407 0.194361 -vn -0.770264 0.318861 -0.552287 -v 0.055603 0.083662 0.181339 -vn -0.684468 0.292291 0.667885 -v 0.055603 0.077066 0.196258 -vn -0.667615 -0.702657 -0.246098 -v 0.055603 0.082144 0.179669 -vn -0.770263 0.552286 0.318865 -v 0.055603 0.083205 0.179631 -vn -0.707106 -0.612373 -0.353554 -v 0.055603 0.083805 0.176792 -vn -0.770260 0.318866 0.552291 -v 0.055603 0.083662 0.179174 -vn -0.735435 -0.492196 -0.465702 -v 0.055603 0.078729 0.187901 -vn -0.735435 -0.589800 -0.333574 -v 0.055603 0.080530 0.185464 -vn -0.735435 -0.652739 -0.181840 -v 0.055603 0.081691 0.182665 -vn -0.770261 0.552291 -0.318862 -v 0.055603 0.083205 0.180881 -vn -0.770261 0.637728 0.000000 -v 0.055603 0.083037 0.180256 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.094287 0.165503 -vn -0.770263 -0.552286 0.318865 -v 0.055603 0.093370 0.165775 -vn -0.770261 -0.637728 0.000000 -v 0.055603 0.093537 0.166400 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.094287 0.170217 -vn -0.770261 -0.552291 -0.318862 -v 0.055603 0.093370 0.167025 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.092893 0.170217 -vn -0.770260 0.318866 0.552291 -v 0.055603 0.091662 0.165317 -vn -0.770264 -0.000000 0.637725 -v 0.055603 0.092287 0.165150 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.092893 0.163289 -vn -0.770260 -0.318866 0.552291 -v 0.055603 0.092912 0.165317 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.094287 0.163289 -vn -0.770262 -0.318869 -0.552286 -v 0.055603 0.092912 0.167482 -vn -0.770264 0.000000 -0.637725 -v 0.055603 0.092287 0.167650 -vn -0.770262 0.318869 -0.552286 -v 0.055603 0.091662 0.167482 -vn -0.770261 0.552291 -0.318862 -v 0.055603 0.091205 0.167025 -vn -0.770261 0.637728 0.000000 -v 0.055603 0.091037 0.166400 -vn -0.707104 -0.612379 -0.353548 -v 0.055603 0.090323 0.165503 -vn -0.707107 -0.612372 -0.353554 -v 0.055603 0.084893 0.174907 -vn -0.707107 -0.612373 -0.353552 -v 0.055603 0.086287 0.172492 -vn -0.770265 -0.318861 -0.552286 -v 0.055603 0.088912 0.174411 -vn -0.770258 -0.000000 -0.637732 -v 0.055603 0.088287 0.174578 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.090287 0.176792 -vn -0.770263 0.552286 0.318865 -v 0.055603 0.087205 0.172703 -vn -0.770265 0.318861 -0.552287 -v 0.055603 0.087662 0.174411 -vn -0.770261 0.552291 -0.318862 -v 0.055603 0.087205 0.173953 -vn -0.770261 0.637729 0.000000 -v 0.055603 0.087037 0.173328 -vn -0.770260 0.318866 0.552291 -v 0.055603 0.087662 0.172245 -vn -0.770264 -0.000000 0.637725 -v 0.055603 0.088287 0.172078 -vn -0.770260 -0.318866 0.552291 -v 0.055603 0.088912 0.172245 -vn -0.770263 -0.552286 0.318865 -v 0.055603 0.089370 0.172703 -vn -0.770261 -0.637728 0.000000 -v 0.055603 0.089537 0.173328 -vn -0.770261 -0.552291 -0.318862 -v 0.055603 0.089370 0.173953 -vn -0.770263 0.552286 0.318865 -v 0.055603 0.091205 0.165775 -vn -0.707107 -0.612372 -0.353553 -v 0.055603 0.091601 0.163289 -vn -0.707106 -0.612373 -0.353553 -v 0.055603 0.092893 0.161050 -vn -0.707098 -0.612366 -0.353583 -v 0.055603 0.094287 0.158636 -vn -0.770260 0.318866 -0.552291 -v 0.055603 0.095662 0.160554 -vn -0.770263 0.552286 -0.318865 -v 0.055603 0.095205 0.160097 -vn -0.770261 0.637728 0.000000 -v 0.055603 0.095037 0.159472 -vn -0.707116 -0.612350 -0.353574 -v 0.055603 0.094323 0.158575 -vn -0.770261 0.552291 0.318862 -v 0.055603 0.095205 0.158847 -vn -0.707107 -0.612373 -0.353551 -v 0.055603 0.095601 0.156361 -vn -0.904533 -0.411874 0.110362 -v 0.055603 0.096144 0.155420 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.096597 0.144746 -vn -0.707108 -0.353552 0.612372 -v 0.055603 0.094287 0.154348 -vn -0.770258 -0.000000 -0.637732 -v 0.055603 0.073511 0.147572 -vn -0.770265 0.318861 -0.552287 -v 0.055603 0.072886 0.147404 -vn -0.707107 0.612373 0.353553 -v 0.055603 0.071511 0.154086 -vn -0.770264 -0.000000 0.637725 -v 0.055603 0.073511 0.145072 -vn -0.770260 -0.318866 0.552291 -v 0.055603 0.074136 0.145239 -vn -0.707107 0.612371 0.353555 -v 0.055603 0.076903 0.144746 -vn -0.770263 -0.552286 0.318865 -v 0.055603 0.074593 0.145697 -vn -0.770261 0.552291 -0.318862 -v 0.055603 0.072428 0.146947 -vn -0.770261 0.637729 0.000000 -v 0.055603 0.072261 0.146322 -vn -0.770263 0.552286 0.318865 -v 0.055603 0.072428 0.145697 -vn -0.770260 0.318866 0.552291 -v 0.055603 0.072886 0.145239 -vn -0.770261 -0.637728 0.000000 -v 0.055603 0.074761 0.146322 -vn -0.770261 -0.552291 -0.318862 -v 0.055603 0.074593 0.146947 -vn -0.770265 -0.318861 -0.552286 -v 0.055603 0.074136 0.147404 -vn -0.770262 -0.552286 -0.318869 -v 0.055603 0.070593 0.153875 -vn -0.707107 -0.612373 -0.353553 -v 0.055603 0.067511 0.149014 -vn -0.770260 -0.318866 -0.552291 -v 0.055603 0.070136 0.154332 -vn -0.770264 0.000000 -0.637725 -v 0.055603 0.069511 0.154500 -vn -0.770260 0.318866 -0.552291 -v 0.055603 0.068886 0.154332 -vn -0.770261 0.552291 0.318862 -v 0.055603 0.068428 0.152625 -vn -0.770265 0.318861 0.552286 -v 0.055603 0.068886 0.152167 -vn -0.770258 0.000000 0.637732 -v 0.055603 0.069511 0.152000 -vn -0.770264 -0.318861 0.552287 -v 0.055603 0.070136 0.152167 -vn -0.770260 -0.552291 0.318865 -v 0.055603 0.070593 0.152625 -vn -0.770264 -0.637725 -0.000000 -v 0.055603 0.070761 0.153250 -vn -0.707107 -0.612373 -0.353552 -v 0.055603 0.061991 0.158575 -vn -0.707107 -0.612371 -0.353554 -v 0.055603 0.059269 0.163289 -vn -0.770264 0.637725 0.000000 -v 0.055603 0.064261 0.160178 -vn -0.770264 0.000001 -0.637725 -v 0.055603 0.065511 0.161428 -vn -0.770261 0.318867 -0.552288 -v 0.055603 0.064886 0.161261 -vn -0.770261 0.552288 -0.318867 -v 0.055603 0.064428 0.160803 -vn -0.770266 -0.318861 0.552284 -v 0.055603 0.066136 0.159095 -vn -0.770259 -0.552293 0.318864 -v 0.055603 0.066593 0.159553 -vn -0.770259 0.552293 0.318864 -v 0.055603 0.064428 0.159553 -vn -0.770266 0.318862 0.552284 -v 0.055603 0.064886 0.159095 -vn -0.770258 0.000001 0.637732 -v 0.055603 0.065511 0.158928 -vn -0.707107 0.612373 0.353553 -v 0.055603 0.067511 0.161014 -vn -0.707107 0.612372 0.353554 -v 0.055603 0.068919 0.158575 -vn -0.770264 -0.637725 -0.000000 -v 0.055603 0.066761 0.160178 -vn -0.770261 -0.552288 -0.318867 -v 0.055603 0.066593 0.160803 -vn -0.707106 0.612373 0.353554 -v 0.055603 0.066197 0.163289 -vn -0.770261 -0.318866 -0.552288 -v 0.055603 0.066136 0.161261 -vn -0.770262 0.318869 0.552286 -v 0.055603 0.060886 0.166024 -vn -0.770264 -0.000000 0.637725 -v 0.055603 0.061511 0.165856 -vn -0.742517 -0.523221 -0.418220 -v 0.055603 0.058575 0.164491 -vn -0.770260 0.318866 -0.552291 -v 0.055603 0.060886 0.168189 -vn -0.770263 0.552286 -0.318865 -v 0.055603 0.060428 0.167731 -vn -0.684468 -0.635195 -0.357815 -v 0.055603 0.053531 0.170231 -vn -0.684467 -0.547601 -0.481288 -v 0.055603 0.055753 0.167097 -vn -0.770261 0.637729 0.000000 -v 0.055603 0.060261 0.167106 -vn -0.770261 0.552291 0.318862 -v 0.055603 0.060428 0.166481 -vn -0.707107 0.612372 0.353554 -v 0.055603 0.064919 0.165503 -vn -0.770262 -0.318870 0.552285 -v 0.055603 0.062136 0.166024 -vn -0.770261 -0.552292 0.318861 -v 0.055603 0.062593 0.166481 -vn -0.770261 -0.637728 0.000000 -v 0.055603 0.062761 0.167106 -vn -0.667615 0.564456 0.485468 -v 0.055603 0.063091 0.168669 -vn -0.770264 0.000000 -0.637725 -v 0.055603 0.061511 0.168356 -vn -0.735435 0.483849 0.474369 -v 0.055603 0.060723 0.170559 -vn -0.770260 -0.318866 -0.552289 -v 0.055603 0.062136 0.168189 -vn -0.770263 -0.552287 -0.318864 -v 0.055603 0.062593 0.167731 -vn -0.735436 0.583782 0.343995 -v 0.055603 0.058880 0.172964 -vn -0.684467 -0.695400 -0.218914 -v 0.055603 0.052003 0.173755 -vn -0.735435 0.649408 0.193404 -v 0.055603 0.057669 0.175743 -vn -0.684467 -0.725620 -0.070573 -v 0.055603 0.051236 0.177520 -vn -0.735435 0.676865 0.031446 -v 0.055603 0.057163 0.178730 -vn -0.735435 0.664542 -0.132361 -v 0.055603 0.057390 0.181752 -vn -0.684467 -0.724551 0.080811 -v 0.055603 0.051263 0.181361 -vn -0.684467 -0.692240 0.228710 -v 0.055603 0.052083 0.185114 -vn -0.735435 0.613162 -0.288388 -v 0.055603 0.058338 0.184630 -vn -0.684467 -0.630080 0.366748 -v 0.055603 0.053660 0.188617 -vn -0.735435 0.525746 -0.427465 -v 0.055603 0.059950 0.187196 -vn -0.684467 -0.540750 0.488972 -v 0.055603 0.055927 0.191718 -vn -0.735435 0.407430 -0.541420 -v 0.055603 0.062133 0.189298 -vn -0.684468 -0.428104 0.590111 -v 0.055603 0.058786 0.194285 -vn -0.735435 0.265169 -0.623555 -v 0.055603 0.064757 0.190813 -vn -0.684467 -0.296999 0.665805 -v 0.055603 0.062113 0.196206 -vn -0.735435 0.107325 -0.669042 -v 0.055603 0.067669 0.191653 -vn -0.684467 -0.153087 0.712789 -v 0.055603 0.065764 0.197398 -vn -0.684467 -0.002573 0.729039 -v 0.055603 0.069584 0.197810 -vn -0.735436 -0.056830 -0.675207 -v 0.055603 0.070698 0.191766 -vn -0.684468 0.148052 0.713852 -v 0.055603 0.073406 0.197425 -vn -0.735435 -0.217645 -0.641690 -v 0.055603 0.073664 0.191148 -vn -0.735435 -0.365666 -0.570459 -v 0.055603 0.076395 0.189834 -vn -0.770261 -0.552291 0.318862 -v 0.055603 0.097370 0.158847 -vn -0.770261 -0.637729 0.000000 -v 0.055603 0.097537 0.159472 -vn -0.707107 0.612373 0.353553 -v 0.055603 0.098893 0.162658 -vn -0.770263 -0.552286 -0.318865 -v 0.055603 0.097370 0.160097 -vn -0.707106 0.612373 0.353554 -v 0.055603 0.098529 0.163289 -vn -0.770265 -0.000000 -0.637725 -v 0.055603 0.098649 0.136600 -vn -0.770259 0.318865 -0.552292 -v 0.055603 0.097849 0.136386 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.096597 0.140510 -vn -0.770264 0.552285 -0.318864 -v 0.055603 0.097264 0.135800 -vn -0.770260 0.637730 0.000000 -v 0.055603 0.097049 0.135000 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.096597 0.132200 -vn -0.770263 0.552289 0.318862 -v 0.055603 0.097264 0.134200 -vn -0.770260 0.318868 0.552288 -v 0.055603 0.097849 0.133614 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.098893 0.132200 -vn -0.770265 0.000000 0.637725 -v 0.055603 0.098649 0.133400 -vn -0.707107 0.707107 0.000000 -v 0.055603 0.105749 0.132200 -vn -0.770260 -0.318868 0.552288 -v 0.055603 0.099449 0.133614 -vn -0.770263 -0.552289 0.318862 -v 0.055603 0.100035 0.134200 -vn -0.770260 -0.637730 -0.000000 -v 0.055603 0.100249 0.135000 -vn -0.707107 0.707107 0.000000 -v 0.055603 0.105749 0.140510 -vn -0.770264 -0.552285 -0.318864 -v 0.055603 0.100035 0.135800 -vn -0.770262 0.552287 -0.318866 -v 0.055603 0.089264 0.135800 -vn -0.770262 0.637727 -0.000000 -v 0.055603 0.089049 0.135000 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.086287 0.132200 -vn -0.770261 0.552290 0.318863 -v 0.055603 0.089264 0.134200 -vn -0.770261 0.318869 0.552286 -v 0.055603 0.089849 0.133614 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.090287 0.132200 -vn -0.770265 0.000000 0.637725 -v 0.055603 0.090649 0.133400 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.092893 0.132200 -vn -0.770260 -0.318868 0.552288 -v 0.055603 0.091449 0.133614 -vn -0.770263 -0.552289 0.318862 -v 0.055603 0.092035 0.134200 -vn -0.770260 -0.637730 -0.000000 -v 0.055603 0.092249 0.135000 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.092893 0.140510 -vn -0.770264 -0.552285 -0.318864 -v 0.055603 0.092035 0.135800 -vn -0.770259 -0.318865 -0.552292 -v 0.055603 0.091449 0.136386 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.090287 0.140510 -vn -0.770265 -0.000000 -0.637725 -v 0.055603 0.090649 0.136600 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.086287 0.140510 -vn -0.770260 0.318866 -0.552290 -v 0.055603 0.089849 0.136386 -vn -0.707106 0.612373 0.353554 -v 0.055603 0.102529 0.156361 -vn -0.692678 0.646867 0.318999 -v 0.055603 0.104409 0.153104 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.098893 0.144746 -vn -0.678875 0.709235 0.190039 -v 0.055603 0.105408 0.150692 -vn -0.707107 0.612372 0.353553 -v 0.055603 0.101251 0.158575 -vn -0.707107 0.612373 0.353551 -v 0.055603 0.090733 0.176792 -vn -0.707107 0.612372 0.353554 -v 0.055603 0.092893 0.173050 -vn -0.707105 0.612375 0.353552 -v 0.055603 0.094287 0.170636 -vn -0.707108 0.612373 0.353549 -v 0.055603 0.094529 0.170217 -vn -0.707107 0.612373 0.353553 -v 0.055603 0.096597 0.166636 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.096597 0.165503 -vn -0.707107 0.612372 0.353554 -v 0.055603 0.097251 0.165503 -vn -0.684468 0.690608 0.233592 -v 0.055603 0.087174 0.185238 -vn -0.742518 0.623799 0.244013 -v 0.055603 0.088020 0.181491 -vn -0.707106 0.612374 0.353552 -v 0.055603 0.090287 0.177564 -vn -0.707106 -0.612373 -0.353553 -v 0.055603 0.063269 0.156361 -vn -0.722128 -0.690278 -0.045243 -v 0.055603 0.075549 0.132412 -vn -0.737701 -0.652124 -0.174736 -v 0.055603 0.075208 0.135000 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.077905 0.140510 -vn -0.577350 -0.577350 -0.577350 -v 0.055603 0.075549 0.131000 -vn -0.707107 -0.707107 0.000000 -v 0.055603 0.075549 0.132200 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.077905 0.132200 -vn -0.707107 -0.612373 -0.353553 -v 0.055603 0.072421 0.140510 -vn -0.722128 -0.620420 -0.305957 -v 0.055603 0.074209 0.137412 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.084893 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.084893 0.140510 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.086287 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.090287 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.092893 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.098893 0.140510 -vn -0.770259 -0.318865 -0.552292 -v 0.055603 0.099449 0.136386 -vn -0.692678 0.719703 0.047172 -v 0.055603 0.105749 0.148104 -vn -0.707107 0.707107 0.000000 -v 0.055603 0.105749 0.144746 -vn -0.770262 0.637727 -0.000000 -v 0.055603 0.081049 0.135000 -vn -0.770261 0.552290 0.318863 -v 0.055603 0.081264 0.134200 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.084893 0.132200 -vn -0.770261 -0.552290 0.318863 -v 0.055603 0.084035 0.134200 -vn -0.770262 -0.637727 0.000000 -v 0.055603 0.084249 0.135000 -vn -0.770261 0.318869 0.552286 -v 0.055603 0.081849 0.133614 -vn -0.770264 0.000001 0.637725 -v 0.055603 0.082649 0.133400 -vn -0.770262 -0.318868 0.552286 -v 0.055603 0.083449 0.133614 -vn -0.770262 0.552287 -0.318866 -v 0.055603 0.081264 0.135800 -vn -0.770262 -0.552287 -0.318866 -v 0.055603 0.084035 0.135800 -vn -0.770260 -0.318866 -0.552290 -v 0.055603 0.083449 0.136386 -vn -0.770264 0.000001 -0.637725 -v 0.055603 0.082649 0.136600 -vn -0.770260 0.318866 -0.552290 -v 0.055603 0.081849 0.136386 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.094287 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.094287 0.140510 -vn -1.000000 0.000000 0.000000 -v 0.055603 0.094287 0.132200 -vn -0.707105 -0.353560 0.612371 -v 0.055603 0.077905 0.144890 -vn -0.707108 -0.353554 0.612371 -v 0.055603 0.084893 0.148924 -vn -0.707106 -0.353555 0.612372 -v 0.055603 0.086287 0.149729 -vn -0.707107 -0.353554 0.612372 -v 0.055603 0.090287 0.152039 -vn -0.707106 -0.353553 0.612374 -v 0.055603 0.092893 0.153543 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.077905 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.084893 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.086287 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.090287 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.092893 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.094287 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.096597 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.055603 0.098893 0.131000 -vn -0.577350 0.577350 -0.577350 -v 0.055603 0.105749 0.131000 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.094287 0.163289 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.096597 0.163289 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.096597 0.165503 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.096597 0.144746 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.098893 0.144746 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.098893 0.156361 -vn 0.707107 0.612372 0.353553 -v 0.059603 0.101251 0.158575 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.098893 0.158575 -vn 0.707107 0.612373 0.353553 -v 0.059603 0.098893 0.162658 -vn 0.707106 0.612374 0.353552 -v 0.059603 0.090287 0.177564 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.090287 0.176792 -vn 0.707107 0.612373 0.353551 -v 0.059603 0.090733 0.176792 -vn 0.707107 -0.612372 -0.353554 -v 0.059603 0.071511 0.142086 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.071511 0.144746 -vn 0.707106 -0.612373 -0.353554 -v 0.059603 0.069975 0.144746 -vn 0.722128 -0.690278 -0.045243 -v 0.059603 0.075549 0.132412 -vn 0.707107 -0.707107 0.000000 -v 0.059603 0.075549 0.132200 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.077905 0.132200 -vn 0.707110 -0.612374 -0.353545 -v 0.059603 0.090287 0.165564 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.090287 0.170217 -vn 0.707107 -0.612373 -0.353553 -v 0.059603 0.087601 0.170217 -vn 0.770264 -0.637725 0.000000 -v 0.059603 0.085537 0.180256 -vn 0.770262 -0.552286 0.318869 -v 0.059603 0.085370 0.179631 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.086287 0.176792 -vn 0.684468 0.627474 0.371187 -v 0.059603 0.085572 0.188730 -vn 0.770264 -0.318861 -0.552287 -v 0.059603 0.084912 0.181339 -vn 0.770260 -0.552291 -0.318866 -v 0.059603 0.085370 0.180881 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.084893 0.176792 -vn 0.770260 -0.318865 0.552291 -v 0.059603 0.084912 0.179174 -vn 0.707106 -0.612373 -0.353554 -v 0.059603 0.083805 0.176792 -vn 0.770264 0.000000 0.637725 -v 0.059603 0.084287 0.179006 -vn 0.770260 0.318866 0.552291 -v 0.059603 0.083662 0.179174 -vn 0.667615 -0.702657 -0.246098 -v 0.059603 0.082144 0.179669 -vn 0.770263 0.552286 0.318865 -v 0.059603 0.083205 0.179631 -vn 0.770261 0.637728 0.000000 -v 0.059603 0.083037 0.180256 -vn 0.735435 -0.652739 -0.181840 -v 0.059603 0.081691 0.182665 -vn 0.770258 0.000000 -0.637732 -v 0.059603 0.084287 0.181506 -vn 0.684467 0.537285 0.492777 -v 0.059603 0.083283 0.191815 -vn 0.770265 0.318861 -0.552286 -v 0.059603 0.083662 0.181339 -vn 0.684467 0.423927 0.593119 -v 0.059603 0.080407 0.194361 -vn 0.684468 0.292291 0.667885 -v 0.059603 0.077066 0.196258 -vn 0.770261 0.552291 -0.318862 -v 0.059603 0.083205 0.180881 -vn 0.735435 -0.589800 -0.333574 -v 0.059603 0.080530 0.185464 -vn 0.735435 -0.492196 -0.465702 -v 0.059603 0.078729 0.187901 -vn 0.770261 -0.552291 -0.318862 -v 0.059603 0.093370 0.167025 -vn 0.770261 -0.637728 0.000000 -v 0.059603 0.093537 0.166400 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.094287 0.165503 -vn 0.770263 -0.552286 0.318865 -v 0.059603 0.093370 0.165775 -vn 0.770260 -0.318865 0.552291 -v 0.059603 0.092912 0.165317 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.094287 0.170217 -vn 0.770262 -0.318869 -0.552286 -v 0.059603 0.092912 0.167482 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.092893 0.170217 -vn 0.770264 -0.000000 -0.637725 -v 0.059603 0.092287 0.167650 -vn 0.770262 0.318869 -0.552286 -v 0.059603 0.091662 0.167482 -vn 0.770260 0.318865 -0.552291 -v 0.059603 0.060886 0.168189 -vn 0.770264 -0.000000 -0.637725 -v 0.059603 0.061511 0.168356 -vn 0.735435 0.483849 0.474369 -v 0.059603 0.060723 0.170559 -vn 0.770261 -0.552292 0.318861 -v 0.059603 0.062593 0.166481 -vn 0.770262 -0.318870 0.552285 -v 0.059603 0.062136 0.166024 -vn 0.707107 0.612372 0.353554 -v 0.059603 0.064919 0.165503 -vn 0.770264 0.000000 0.637725 -v 0.059603 0.061511 0.165856 -vn 0.667615 0.564456 0.485468 -v 0.059603 0.063091 0.168669 -vn 0.770260 -0.318866 -0.552289 -v 0.059603 0.062136 0.168189 -vn 0.770263 -0.552287 -0.318864 -v 0.059603 0.062593 0.167731 -vn 0.770261 -0.637728 0.000000 -v 0.059603 0.062761 0.167106 -vn 0.770263 0.552286 -0.318865 -v 0.059603 0.060428 0.167731 -vn 0.684468 -0.635195 -0.357815 -v 0.059603 0.053531 0.170231 -vn 0.770261 0.637729 0.000000 -v 0.059603 0.060261 0.167106 -vn 0.684467 -0.547601 -0.481288 -v 0.059603 0.055753 0.167097 -vn 0.770261 0.552291 0.318862 -v 0.059603 0.060428 0.166481 -vn 0.742517 -0.523221 -0.418220 -v 0.059603 0.058575 0.164491 -vn 0.770262 0.318869 0.552286 -v 0.059603 0.060886 0.166024 -vn 0.707107 -0.612371 -0.353554 -v 0.059603 0.059269 0.163289 -vn 0.770261 0.552288 -0.318867 -v 0.059603 0.064428 0.160803 -vn 0.770261 0.318867 -0.552288 -v 0.059603 0.064886 0.161261 -vn 0.707106 0.612373 0.353554 -v 0.059603 0.066197 0.163289 -vn 0.770261 -0.552288 -0.318867 -v 0.059603 0.066593 0.160803 -vn 0.707107 0.612373 0.353553 -v 0.059603 0.067511 0.161014 -vn 0.770261 -0.318866 -0.552288 -v 0.059603 0.066136 0.161261 -vn 0.770264 0.000001 -0.637725 -v 0.059603 0.065511 0.161428 -vn 0.770264 -0.637725 0.000000 -v 0.059603 0.066761 0.160178 -vn 0.770259 -0.552293 0.318864 -v 0.059603 0.066593 0.159553 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.067511 0.158575 -vn 0.770266 -0.318861 0.552284 -v 0.059603 0.066136 0.159095 -vn 0.770258 0.000001 0.637732 -v 0.059603 0.065511 0.158928 -vn 0.707107 -0.612373 -0.353552 -v 0.059603 0.061991 0.158575 -vn 0.770266 0.318862 0.552284 -v 0.059603 0.064886 0.159095 -vn 0.770259 0.552293 0.318864 -v 0.059603 0.064428 0.159553 -vn 0.770264 0.637725 -0.000000 -v 0.059603 0.064261 0.160178 -vn 0.770264 -0.637725 0.000000 -v 0.059603 0.070761 0.153250 -vn 0.770260 -0.552291 0.318866 -v 0.059603 0.070593 0.152625 -vn 0.770265 -0.318861 0.552286 -v 0.059603 0.070136 0.152167 -vn 0.770258 -0.000000 0.637732 -v 0.059603 0.069511 0.152000 -vn 0.707107 -0.612373 -0.353553 -v 0.059603 0.067511 0.149014 -vn 0.770264 0.318861 0.552287 -v 0.059603 0.068886 0.152167 -vn 0.770261 0.552291 0.318862 -v 0.059603 0.068428 0.152625 -vn 0.770261 0.637728 0.000000 -v 0.059603 0.068261 0.153250 -vn 0.770263 0.552286 -0.318865 -v 0.059603 0.068428 0.153875 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.067511 0.156361 -vn 0.770260 0.318865 -0.552291 -v 0.059603 0.068886 0.154332 -vn 0.707107 0.612372 0.353554 -v 0.059603 0.068919 0.158575 -vn 0.707106 0.612373 0.353554 -v 0.059603 0.070197 0.156361 -vn 0.770264 -0.000000 -0.637725 -v 0.059603 0.069511 0.154500 -vn 0.770260 -0.318866 -0.552291 -v 0.059603 0.070136 0.154332 -vn 0.707107 0.612373 0.353553 -v 0.059603 0.071511 0.154086 -vn 0.770262 -0.552286 -0.318869 -v 0.059603 0.070593 0.153875 -vn 0.707108 0.612371 0.353555 -v 0.059603 0.076903 0.144746 -vn 0.770263 -0.552286 0.318865 -v 0.059603 0.074593 0.145697 -vn 0.770260 -0.318866 0.552291 -v 0.059603 0.074136 0.145239 -vn 0.770264 0.000000 0.637725 -v 0.059603 0.073511 0.145072 -vn 0.770260 0.318866 0.552291 -v 0.059603 0.072886 0.145239 -vn 0.770263 0.552286 0.318865 -v 0.059603 0.072428 0.145697 -vn 0.770261 0.637729 0.000000 -v 0.059603 0.072261 0.146322 -vn 0.770261 0.552291 -0.318862 -v 0.059603 0.072428 0.146947 -vn 0.770265 0.318861 -0.552286 -v 0.059603 0.072886 0.147404 -vn 0.770258 0.000000 -0.637732 -v 0.059603 0.073511 0.147572 -vn 0.770265 -0.318861 -0.552287 -v 0.059603 0.074136 0.147404 -vn 0.770261 -0.552291 -0.318862 -v 0.059603 0.074593 0.146947 -vn 0.770261 -0.637728 0.000000 -v 0.059603 0.074761 0.146322 -vn 0.707111 -0.353552 0.612369 -v 0.059603 0.077656 0.144746 -vn 0.904531 0.110365 0.411877 -v 0.059603 0.077091 0.144420 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.077905 0.140510 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.094287 0.144746 -vn 0.707106 -0.353553 0.612374 -v 0.059603 0.092893 0.153543 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.092893 0.144746 -vn 0.707107 -0.353554 0.612372 -v 0.059603 0.090287 0.152039 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.090287 0.144746 -vn 0.707106 -0.353555 0.612372 -v 0.059603 0.086287 0.149729 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.086287 0.144746 -vn 0.707107 -0.353554 0.612371 -v 0.059603 0.084893 0.148924 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.084893 0.144746 -vn 0.707105 -0.353560 0.612371 -v 0.059603 0.077905 0.144890 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.077905 0.144746 -vn 0.770265 -0.318861 0.552287 -v 0.059603 0.096912 0.158389 -vn 0.770258 -0.000000 0.637732 -v 0.059603 0.096287 0.158222 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.096597 0.156361 -vn 0.770265 0.318861 0.552287 -v 0.059603 0.095662 0.158389 -vn 0.770264 -0.000000 -0.637725 -v 0.059603 0.096287 0.160722 -vn 0.770260 0.318866 -0.552291 -v 0.059603 0.095662 0.160554 -vn 0.770263 0.552286 -0.318865 -v 0.059603 0.095205 0.160097 -vn 0.904533 -0.411874 0.110362 -v 0.059603 0.096144 0.155420 -vn 0.707107 -0.612373 -0.353551 -v 0.059603 0.095601 0.156361 -vn 0.707116 -0.612350 -0.353574 -v 0.059603 0.094323 0.158575 -vn 0.770261 0.552291 0.318862 -v 0.059603 0.095205 0.158847 -vn 0.707098 -0.612366 -0.353583 -v 0.059603 0.094287 0.158636 -vn 0.770261 0.637728 0.000000 -v 0.059603 0.095037 0.159472 -vn 0.707107 -0.612372 -0.353553 -v 0.059603 0.091601 0.163289 -vn 0.707106 -0.612373 -0.353553 -v 0.059603 0.092893 0.161050 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.092893 0.163289 -vn 0.770265 0.318861 -0.552286 -v 0.059603 0.087662 0.174411 -vn 0.770258 0.000000 -0.637732 -v 0.059603 0.088287 0.174578 -vn 0.770261 -0.637728 0.000000 -v 0.059603 0.089537 0.173328 -vn 0.770263 -0.552286 0.318865 -v 0.059603 0.089370 0.172703 -vn 0.770260 -0.318865 0.552291 -v 0.059603 0.088912 0.172245 -vn 0.770264 -0.318861 -0.552287 -v 0.059603 0.088912 0.174411 -vn 0.770261 -0.552291 -0.318862 -v 0.059603 0.089370 0.173953 -vn 0.770264 0.000000 0.637725 -v 0.059603 0.088287 0.172078 -vn 0.770260 0.318866 0.552291 -v 0.059603 0.087662 0.172245 -vn 0.707107 -0.612373 -0.353552 -v 0.059603 0.086287 0.172492 -vn 0.770263 0.552286 0.318865 -v 0.059603 0.087205 0.172703 -vn 0.770261 0.637728 0.000000 -v 0.059603 0.087037 0.173328 -vn 0.770261 0.552291 -0.318862 -v 0.059603 0.087205 0.173953 -vn 0.707107 -0.612372 -0.353554 -v 0.059603 0.084893 0.174907 -vn 0.735436 -0.056830 -0.675207 -v 0.059603 0.070698 0.191766 -vn 0.735435 -0.217645 -0.641690 -v 0.059603 0.073664 0.191148 -vn 0.735435 -0.365666 -0.570459 -v 0.059603 0.076395 0.189834 -vn 0.684468 0.148052 0.713852 -v 0.059603 0.073406 0.197425 -vn 0.684467 -0.002573 0.729039 -v 0.059603 0.069584 0.197810 -vn 0.735435 0.107325 -0.669042 -v 0.059603 0.067669 0.191653 -vn 0.684467 -0.153087 0.712789 -v 0.059603 0.065764 0.197398 -vn 0.735435 0.265169 -0.623555 -v 0.059603 0.064757 0.190813 -vn 0.684467 -0.296999 0.665804 -v 0.059603 0.062113 0.196206 -vn 0.735435 0.407430 -0.541420 -v 0.059603 0.062133 0.189298 -vn 0.684468 -0.428104 0.590111 -v 0.059603 0.058786 0.194285 -vn 0.735435 0.525746 -0.427465 -v 0.059603 0.059950 0.187196 -vn 0.684467 -0.540750 0.488972 -v 0.059603 0.055927 0.191718 -vn 0.735435 0.613162 -0.288388 -v 0.059603 0.058338 0.184630 -vn 0.684467 -0.630080 0.366748 -v 0.059603 0.053660 0.188617 -vn 0.684467 -0.692240 0.228710 -v 0.059603 0.052083 0.185114 -vn 0.735435 0.664542 -0.132361 -v 0.059603 0.057390 0.181752 -vn 0.684467 -0.724551 0.080811 -v 0.059603 0.051263 0.181361 -vn 0.735435 0.676865 0.031446 -v 0.059603 0.057163 0.178730 -vn 0.684467 -0.725620 -0.070573 -v 0.059603 0.051236 0.177520 -vn 0.735435 0.649408 0.193404 -v 0.059603 0.057669 0.175743 -vn 0.684467 -0.695400 -0.218914 -v 0.059603 0.052003 0.173755 -vn 0.735436 0.583783 0.343995 -v 0.059603 0.058880 0.172964 -vn 0.770261 -0.637728 0.000000 -v 0.059603 0.097537 0.159472 -vn 0.770263 -0.552286 -0.318865 -v 0.059603 0.097370 0.160097 -vn 0.770260 -0.318865 -0.552291 -v 0.059603 0.096912 0.160554 -vn 0.707106 0.612373 0.353554 -v 0.059603 0.098529 0.163289 -vn 0.707107 -0.612373 -0.353553 -v 0.059603 0.072421 0.140510 -vn 0.722128 -0.620420 -0.305957 -v 0.059603 0.074209 0.137412 -vn 0.737701 -0.652124 -0.174736 -v 0.059603 0.075208 0.135000 -vn 0.707106 -0.612373 -0.353553 -v 0.059603 0.063269 0.156361 -vn 0.742518 0.623799 0.244013 -v 0.059603 0.088020 0.181491 -vn 0.684468 0.690608 0.233592 -v 0.059603 0.087174 0.185238 -vn 0.707107 0.612372 0.353554 -v 0.059603 0.092893 0.173050 -vn 0.707108 0.612373 0.353549 -v 0.059603 0.094529 0.170217 -vn 0.707105 0.612375 0.353552 -v 0.059603 0.094287 0.170636 -vn 0.707107 0.612373 0.353553 -v 0.059603 0.096597 0.166636 -vn 0.707107 0.612372 0.353554 -v 0.059603 0.097251 0.165503 -vn 0.707107 0.707107 0.000000 -v 0.059603 0.105749 0.144746 -vn 0.692678 0.719703 0.047172 -v 0.059603 0.105749 0.148104 -vn 0.678875 0.709235 0.190039 -v 0.059603 0.105408 0.150692 -vn 0.692678 0.646867 0.318999 -v 0.059603 0.104409 0.153104 -vn 0.707106 0.612373 0.353554 -v 0.059603 0.102529 0.156361 -vn 0.770260 -0.637730 0.000000 -v 0.059603 0.100249 0.135000 -vn 0.707107 0.707107 0.000000 -v 0.059603 0.105749 0.132200 -vn 0.770264 -0.552285 -0.318864 -v 0.059603 0.100035 0.135800 -vn 0.707107 0.707107 0.000000 -v 0.059603 0.105749 0.140510 -vn 0.770263 -0.552289 0.318861 -v 0.059603 0.100035 0.134200 -vn 0.770260 -0.318868 0.552288 -v 0.059603 0.099449 0.133614 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.098893 0.132200 -vn 0.770265 -0.000000 0.637725 -v 0.059603 0.098649 0.133400 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.096597 0.132200 -vn 0.770260 0.318868 0.552288 -v 0.059603 0.097849 0.133614 -vn 0.770263 0.552289 0.318862 -v 0.059603 0.097264 0.134200 -vn 0.770260 0.637730 0.000000 -v 0.059603 0.097049 0.135000 -vn 0.770264 0.552285 -0.318864 -v 0.059603 0.097264 0.135800 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.096597 0.140510 -vn 0.770259 0.318865 -0.552292 -v 0.059603 0.097849 0.136386 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.098893 0.140510 -vn 0.770265 0.000000 -0.637725 -v 0.059603 0.098649 0.136600 -vn 0.770259 -0.318865 -0.552292 -v 0.059603 0.099449 0.136386 -vn 0.770260 -0.637730 0.000000 -v 0.059603 0.092249 0.135000 -vn 0.770263 -0.552289 0.318862 -v 0.059603 0.092035 0.134200 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.092893 0.132200 -vn 0.770260 -0.318868 0.552288 -v 0.059603 0.091449 0.133614 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.090287 0.132200 -vn 0.770265 -0.000000 0.637725 -v 0.059603 0.090649 0.133400 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.086287 0.132200 -vn 0.770261 0.318869 0.552286 -v 0.059603 0.089849 0.133614 -vn 0.770261 0.552290 0.318863 -v 0.059603 0.089264 0.134200 -vn 0.770262 0.637727 0.000000 -v 0.059603 0.089049 0.135000 -vn 0.770262 0.552287 -0.318866 -v 0.059603 0.089264 0.135800 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.086287 0.140510 -vn 0.770260 0.318866 -0.552290 -v 0.059603 0.089849 0.136386 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.090287 0.140510 -vn 0.770265 0.000000 -0.637725 -v 0.059603 0.090649 0.136600 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.092893 0.140510 -vn 0.770259 -0.318865 -0.552292 -v 0.059603 0.091449 0.136386 -vn 0.770264 -0.552285 -0.318864 -v 0.059603 0.092035 0.135800 -vn 0.577350 0.577350 -0.577350 -v 0.059603 0.105749 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.098893 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.096597 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.094287 0.131000 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.094287 0.132200 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.092893 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.090287 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.086287 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.084893 0.131000 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.084893 0.132200 -vn 0.707107 0.000000 -0.707107 -v 0.059603 0.077905 0.131000 -vn 0.577350 -0.577350 -0.577350 -v 0.059603 0.075549 0.131000 -vn 0.770262 -0.637727 -0.000000 -v 0.059603 0.084249 0.135000 -vn 0.770261 -0.552290 0.318863 -v 0.059603 0.084035 0.134200 -vn 0.770261 0.552290 0.318863 -v 0.059603 0.081264 0.134200 -vn 0.770262 0.637727 0.000000 -v 0.059603 0.081049 0.135000 -vn 0.770260 -0.318866 -0.552290 -v 0.059603 0.083449 0.136386 -vn 0.770262 -0.552287 -0.318866 -v 0.059603 0.084035 0.135800 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.084893 0.140510 -vn 0.770262 -0.318868 0.552286 -v 0.059603 0.083449 0.133614 -vn 0.770264 0.000001 0.637725 -v 0.059603 0.082649 0.133400 -vn 0.770261 0.318869 0.552286 -v 0.059603 0.081849 0.133614 -vn 0.770262 0.552287 -0.318866 -v 0.059603 0.081264 0.135800 -vn 0.770260 0.318866 -0.552290 -v 0.059603 0.081849 0.136386 -vn 0.770264 0.000001 -0.637725 -v 0.059603 0.082649 0.136600 -vn 1.000000 0.000000 0.000000 -v 0.059603 0.094287 0.140510 -vn 0.770261 -0.552291 0.318862 -v 0.059603 0.097370 0.158847 -vn 0.707108 -0.353552 0.612372 -v 0.059603 0.094287 0.154348 -vn 0.770264 0.000000 0.637725 -v 0.059603 0.092287 0.165150 -vn 0.770260 0.318866 0.552291 -v 0.059603 0.091662 0.165317 -vn 0.707103 -0.612379 -0.353548 -v 0.059603 0.090323 0.165503 -vn 0.770263 0.552286 0.318865 -v 0.059603 0.091205 0.165775 -vn 0.770261 0.637728 0.000000 -v 0.059603 0.091037 0.166400 -vn 0.770261 0.552291 -0.318862 -v 0.059603 0.091205 0.167025 -vn -0.707106 -0.612373 -0.353554 -v 0.091603 0.069975 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.071511 0.144746 -vn -0.707107 -0.612372 -0.353554 -v 0.091603 0.071511 0.142086 -vn -0.770264 -0.318861 0.552287 -v 0.091603 0.096912 0.158389 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.098893 0.158575 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.098893 0.156361 -vn -0.770260 -0.318865 -0.552291 -v 0.091603 0.096912 0.160554 -vn -0.770264 0.000000 -0.637725 -v 0.091603 0.096287 0.160722 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.096597 0.163289 -vn -0.707106 0.612373 0.353554 -v 0.091603 0.070197 0.156361 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.067511 0.156361 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.067511 0.158575 -vn -0.770263 0.552286 -0.318865 -v 0.091603 0.068428 0.153875 -vn -0.770261 0.637728 0.000000 -v 0.091603 0.068261 0.153250 -vn -0.904531 0.110365 0.411877 -v 0.091603 0.077091 0.144420 -vn -0.707111 -0.353552 0.612369 -v 0.091603 0.077656 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.077905 0.144746 -vn -0.770265 0.318861 0.552287 -v 0.091603 0.095662 0.158389 -vn -0.770258 0.000000 0.637732 -v 0.091603 0.096287 0.158222 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.096597 0.156361 -vn -0.707107 -0.612373 -0.353553 -v 0.091603 0.087601 0.170217 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.090287 0.170217 -vn -0.707109 -0.612374 -0.353545 -v 0.091603 0.090287 0.165564 -vn -0.770264 0.000000 0.637725 -v 0.091603 0.084287 0.179006 -vn -0.770258 -0.318872 0.552290 -v 0.091603 0.084912 0.179174 -vn -1.000000 -0.000003 0.000000 -v 0.091603 0.084893 0.176792 -vn -1.000000 -0.000003 -0.000000 -v 0.091603 0.086287 0.176792 -vn -0.770262 -0.552287 0.318866 -v 0.091603 0.085370 0.179631 -vn -0.770264 -0.637725 0.000000 -v 0.091603 0.085537 0.180256 -vn -0.684469 0.627473 0.371187 -v 0.091603 0.085572 0.188730 -vn -0.770260 -0.552292 -0.318864 -v 0.091603 0.085370 0.180881 -vn -0.770262 -0.318869 -0.552286 -v 0.091603 0.084912 0.181339 -vn -0.684467 0.537285 0.492777 -v 0.091603 0.083283 0.191815 -vn -0.770258 -0.000000 -0.637732 -v 0.091603 0.084287 0.181506 -vn -0.684468 0.423927 0.593119 -v 0.091603 0.080407 0.194361 -vn -0.770264 0.318861 -0.552287 -v 0.091603 0.083662 0.181339 -vn -0.684468 0.292291 0.667885 -v 0.091603 0.077066 0.196258 -vn -0.667615 -0.702657 -0.246098 -v 0.091603 0.082144 0.179669 -vn -0.770263 0.552286 0.318865 -v 0.091603 0.083205 0.179631 -vn -0.707106 -0.612373 -0.353554 -v 0.091603 0.083805 0.176792 -vn -0.770260 0.318865 0.552291 -v 0.091603 0.083662 0.179174 -vn -0.735435 -0.492196 -0.465702 -v 0.091603 0.078729 0.187901 -vn -0.735435 -0.589800 -0.333574 -v 0.091603 0.080530 0.185464 -vn -0.735435 -0.652740 -0.181840 -v 0.091603 0.081691 0.182665 -vn -0.770261 0.552291 -0.318862 -v 0.091603 0.083205 0.180881 -vn -0.770261 0.637728 0.000000 -v 0.091603 0.083037 0.180256 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.094287 0.165503 -vn -0.770263 -0.552286 0.318865 -v 0.091603 0.093370 0.165775 -vn -0.770261 -0.637728 -0.000000 -v 0.091603 0.093537 0.166400 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.094287 0.170217 -vn -0.770261 -0.552291 -0.318862 -v 0.091603 0.093370 0.167025 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.092893 0.170217 -vn -0.770260 0.318865 0.552291 -v 0.091603 0.091662 0.165317 -vn -0.770264 0.000000 0.637725 -v 0.091603 0.092287 0.165150 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.092893 0.163289 -vn -0.770260 -0.318865 0.552291 -v 0.091603 0.092912 0.165317 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.094287 0.163289 -vn -0.770262 -0.318869 -0.552286 -v 0.091603 0.092912 0.167482 -vn -0.770264 0.000000 -0.637725 -v 0.091603 0.092287 0.167650 -vn -0.770262 0.318869 -0.552286 -v 0.091603 0.091662 0.167482 -vn -0.770261 0.552291 -0.318862 -v 0.091603 0.091205 0.167025 -vn -0.770261 0.637728 0.000000 -v 0.091603 0.091037 0.166400 -vn -0.707104 -0.612379 -0.353548 -v 0.091603 0.090323 0.165503 -vn -0.707106 -0.612374 -0.353553 -v 0.091603 0.084893 0.174907 -vn -0.707107 -0.612373 -0.353552 -v 0.091603 0.086287 0.172492 -vn -0.770264 -0.318861 -0.552287 -v 0.091603 0.088912 0.174411 -vn -0.770258 -0.000000 -0.637732 -v 0.091603 0.088287 0.174578 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.090287 0.176792 -vn -0.770263 0.552286 0.318865 -v 0.091603 0.087205 0.172703 -vn -0.770265 0.318861 -0.552287 -v 0.091603 0.087662 0.174411 -vn -0.770261 0.552291 -0.318862 -v 0.091603 0.087205 0.173953 -vn -0.770261 0.637728 0.000000 -v 0.091603 0.087037 0.173328 -vn -0.770260 0.318865 0.552291 -v 0.091603 0.087662 0.172245 -vn -0.770264 0.000000 0.637725 -v 0.091603 0.088287 0.172078 -vn -0.770260 -0.318865 0.552291 -v 0.091603 0.088912 0.172245 -vn -0.770263 -0.552286 0.318865 -v 0.091603 0.089370 0.172703 -vn -0.770261 -0.637728 -0.000000 -v 0.091603 0.089537 0.173328 -vn -0.770261 -0.552291 -0.318862 -v 0.091603 0.089370 0.173953 -vn -0.770263 0.552286 0.318865 -v 0.091603 0.091205 0.165775 -vn -0.707107 -0.612372 -0.353553 -v 0.091603 0.091601 0.163289 -vn -0.707106 -0.612373 -0.353553 -v 0.091603 0.092893 0.161050 -vn -0.707098 -0.612366 -0.353583 -v 0.091603 0.094287 0.158636 -vn -0.770260 0.318866 -0.552291 -v 0.091603 0.095662 0.160554 -vn -0.770263 0.552286 -0.318865 -v 0.091603 0.095205 0.160097 -vn -0.770261 0.637728 0.000000 -v 0.091603 0.095037 0.159472 -vn -0.707116 -0.612350 -0.353574 -v 0.091603 0.094323 0.158575 -vn -0.770261 0.552291 0.318862 -v 0.091603 0.095205 0.158847 -vn -0.707107 -0.612373 -0.353551 -v 0.091603 0.095601 0.156361 -vn -0.904533 -0.411874 0.110362 -v 0.091603 0.096144 0.155420 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.096597 0.144746 -vn -0.707108 -0.353552 0.612372 -v 0.091603 0.094287 0.154348 -vn -0.770258 -0.000000 -0.637732 -v 0.091603 0.073511 0.147572 -vn -0.770265 0.318861 -0.552287 -v 0.091603 0.072886 0.147404 -vn -0.707107 0.612373 0.353553 -v 0.091603 0.071511 0.154086 -vn -0.770264 0.000000 0.637725 -v 0.091603 0.073511 0.145072 -vn -0.770260 -0.318866 0.552291 -v 0.091603 0.074136 0.145239 -vn -0.707107 0.612371 0.353555 -v 0.091603 0.076903 0.144746 -vn -0.770263 -0.552286 0.318865 -v 0.091603 0.074593 0.145697 -vn -0.770261 0.552291 -0.318862 -v 0.091603 0.072428 0.146947 -vn -0.770261 0.637728 0.000000 -v 0.091603 0.072261 0.146322 -vn -0.770263 0.552286 0.318865 -v 0.091603 0.072428 0.145697 -vn -0.770260 0.318865 0.552291 -v 0.091603 0.072886 0.145239 -vn -0.770261 -0.637728 -0.000000 -v 0.091603 0.074761 0.146322 -vn -0.770261 -0.552291 -0.318862 -v 0.091603 0.074593 0.146947 -vn -0.770265 -0.318861 -0.552287 -v 0.091603 0.074136 0.147404 -vn -0.770262 -0.552286 -0.318869 -v 0.091603 0.070593 0.153875 -vn -0.707107 -0.612373 -0.353553 -v 0.091603 0.067511 0.149014 -vn -0.770260 -0.318865 -0.552291 -v 0.091603 0.070136 0.154332 -vn -0.770264 0.000000 -0.637725 -v 0.091603 0.069511 0.154500 -vn -0.770260 0.318865 -0.552291 -v 0.091603 0.068886 0.154332 -vn -0.770261 0.552291 0.318862 -v 0.091603 0.068428 0.152625 -vn -0.770264 0.318861 0.552287 -v 0.091603 0.068886 0.152167 -vn -0.770258 0.000000 0.637732 -v 0.091603 0.069511 0.152000 -vn -0.770264 -0.318861 0.552287 -v 0.091603 0.070136 0.152167 -vn -0.770260 -0.552291 0.318866 -v 0.091603 0.070593 0.152625 -vn -0.770264 -0.637725 0.000000 -v 0.091603 0.070761 0.153250 -vn -0.707107 -0.612373 -0.353553 -v 0.091603 0.061991 0.158575 -vn -0.707107 -0.612372 -0.353554 -v 0.091603 0.059269 0.163289 -vn -0.770264 0.637725 0.000000 -v 0.091603 0.064261 0.160178 -vn -0.770264 0.000001 -0.637725 -v 0.091603 0.065511 0.161428 -vn -0.770261 0.318867 -0.552288 -v 0.091603 0.064886 0.161261 -vn -0.770261 0.552288 -0.318867 -v 0.091603 0.064428 0.160803 -vn -0.770266 -0.318861 0.552284 -v 0.091603 0.066136 0.159095 -vn -0.770259 -0.552293 0.318864 -v 0.091603 0.066593 0.159553 -vn -0.770259 0.552293 0.318864 -v 0.091603 0.064428 0.159553 -vn -0.770266 0.318862 0.552284 -v 0.091603 0.064886 0.159095 -vn -0.770258 0.000001 0.637732 -v 0.091603 0.065511 0.158928 -vn -0.707107 0.612373 0.353553 -v 0.091603 0.067511 0.161014 -vn -0.707107 0.612372 0.353554 -v 0.091603 0.068919 0.158575 -vn -0.770264 -0.637725 0.000000 -v 0.091603 0.066761 0.160178 -vn -0.770261 -0.552288 -0.318867 -v 0.091603 0.066593 0.160803 -vn -0.707106 0.612373 0.353554 -v 0.091603 0.066197 0.163289 -vn -0.770261 -0.318866 -0.552288 -v 0.091603 0.066136 0.161261 -vn -0.770262 0.318869 0.552286 -v 0.091603 0.060886 0.166024 -vn -0.770264 0.000000 0.637725 -v 0.091603 0.061511 0.165856 -vn -0.742517 -0.523221 -0.418220 -v 0.091603 0.058575 0.164491 -vn -0.770260 0.318866 -0.552291 -v 0.091603 0.060886 0.168189 -vn -0.770263 0.552286 -0.318865 -v 0.091603 0.060428 0.167731 -vn -0.684468 -0.635195 -0.357815 -v 0.091603 0.053531 0.170231 -vn -0.684467 -0.547601 -0.481288 -v 0.091603 0.055753 0.167097 -vn -0.770261 0.637728 0.000000 -v 0.091603 0.060261 0.167106 -vn -0.770261 0.552291 0.318862 -v 0.091603 0.060428 0.166481 -vn -0.707107 0.612372 0.353554 -v 0.091603 0.064919 0.165503 -vn -0.770261 -0.318868 0.552287 -v 0.091603 0.062136 0.166024 -vn -0.770262 -0.552290 0.318862 -v 0.091603 0.062593 0.166481 -vn -0.770261 -0.637728 -0.000000 -v 0.091603 0.062761 0.167106 -vn -0.667615 0.564456 0.485469 -v 0.091603 0.063091 0.168669 -vn -0.770264 0.000000 -0.637725 -v 0.091603 0.061511 0.168356 -vn -0.735435 0.483848 0.474369 -v 0.091603 0.060723 0.170559 -vn -0.770259 -0.318865 -0.552292 -v 0.091603 0.062136 0.168189 -vn -0.770264 -0.552285 -0.318866 -v 0.091603 0.062593 0.167731 -vn -0.735436 0.583783 0.343995 -v 0.091603 0.058880 0.172964 -vn -0.684467 -0.695400 -0.218914 -v 0.091603 0.052003 0.173755 -vn -0.735435 0.649408 0.193404 -v 0.091603 0.057669 0.175743 -vn -0.684467 -0.725620 -0.070573 -v 0.091603 0.051236 0.177520 -vn -0.735435 0.676865 0.031446 -v 0.091603 0.057163 0.178730 -vn -0.735435 0.664542 -0.132361 -v 0.091603 0.057390 0.181752 -vn -0.684467 -0.724551 0.080811 -v 0.091603 0.051263 0.181361 -vn -0.684467 -0.692240 0.228710 -v 0.091603 0.052083 0.185114 -vn -0.735435 0.613162 -0.288388 -v 0.091603 0.058338 0.184630 -vn -0.684467 -0.630080 0.366748 -v 0.091603 0.053660 0.188617 -vn -0.735435 0.525746 -0.427465 -v 0.091603 0.059950 0.187196 -vn -0.684467 -0.540750 0.488972 -v 0.091603 0.055927 0.191718 -vn -0.735435 0.407430 -0.541420 -v 0.091603 0.062133 0.189298 -vn -0.684468 -0.428104 0.590111 -v 0.091603 0.058786 0.194285 -vn -0.735435 0.265169 -0.623555 -v 0.091603 0.064757 0.190813 -vn -0.684467 -0.296999 0.665805 -v 0.091603 0.062113 0.196206 -vn -0.735435 0.107325 -0.669042 -v 0.091603 0.067669 0.191653 -vn -0.684467 -0.153087 0.712789 -v 0.091603 0.065764 0.197398 -vn -0.684467 -0.002573 0.729039 -v 0.091603 0.069584 0.197810 -vn -0.735436 -0.056830 -0.675207 -v 0.091603 0.070698 0.191766 -vn -0.684468 0.148052 0.713852 -v 0.091603 0.073406 0.197425 -vn -0.735435 -0.217645 -0.641690 -v 0.091603 0.073664 0.191148 -vn -0.735435 -0.365666 -0.570459 -v 0.091603 0.076395 0.189834 -vn -0.770261 -0.552291 0.318862 -v 0.091603 0.097370 0.158847 -vn -0.770261 -0.637728 -0.000000 -v 0.091603 0.097537 0.159472 -vn -0.707107 0.612373 0.353553 -v 0.091603 0.098893 0.162658 -vn -0.770263 -0.552286 -0.318865 -v 0.091603 0.097370 0.160097 -vn -0.707106 0.612373 0.353554 -v 0.091603 0.098529 0.163289 -vn -0.770265 0.000000 -0.637725 -v 0.091603 0.098649 0.136600 -vn -0.770259 0.318865 -0.552292 -v 0.091603 0.097849 0.136386 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.096597 0.140510 -vn -0.770264 0.552285 -0.318864 -v 0.091603 0.097264 0.135800 -vn -0.770260 0.637730 -0.000000 -v 0.091603 0.097049 0.135000 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.096597 0.132200 -vn -0.770263 0.552289 0.318862 -v 0.091603 0.097264 0.134200 -vn -0.770260 0.318868 0.552288 -v 0.091603 0.097849 0.133614 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.098893 0.132200 -vn -0.770265 -0.000000 0.637725 -v 0.091603 0.098649 0.133400 -vn -0.707107 0.707107 0.000000 -v 0.091603 0.105749 0.132200 -vn -0.770260 -0.318868 0.552288 -v 0.091603 0.099449 0.133614 -vn -0.770263 -0.552289 0.318861 -v 0.091603 0.100035 0.134200 -vn -0.770260 -0.637730 0.000000 -v 0.091603 0.100249 0.135000 -vn -0.707107 0.707107 0.000000 -v 0.091603 0.105749 0.140510 -vn -0.770264 -0.552285 -0.318864 -v 0.091603 0.100035 0.135800 -vn -0.770262 0.552287 -0.318866 -v 0.091603 0.089264 0.135800 -vn -0.770262 0.637727 -0.000000 -v 0.091603 0.089049 0.135000 -vn -1.000000 -0.000003 0.000000 -v 0.091603 0.086287 0.132200 -vn -0.770261 0.552290 0.318863 -v 0.091603 0.089264 0.134200 -vn -0.770261 0.318869 0.552286 -v 0.091603 0.089849 0.133614 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.090287 0.132200 -vn -0.770265 -0.000000 0.637725 -v 0.091603 0.090649 0.133400 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.092893 0.132200 -vn -0.770260 -0.318868 0.552288 -v 0.091603 0.091449 0.133614 -vn -0.770263 -0.552289 0.318862 -v 0.091603 0.092035 0.134200 -vn -0.770260 -0.637730 0.000000 -v 0.091603 0.092249 0.135000 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.092893 0.140510 -vn -0.770264 -0.552285 -0.318864 -v 0.091603 0.092035 0.135800 -vn -0.770259 -0.318865 -0.552292 -v 0.091603 0.091449 0.136386 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.090287 0.140510 -vn -0.770265 0.000000 -0.637725 -v 0.091603 0.090649 0.136600 -vn -1.000000 -0.000003 0.000000 -v 0.091603 0.086287 0.140510 -vn -0.770260 0.318866 -0.552290 -v 0.091603 0.089849 0.136386 -vn -0.707106 0.612373 0.353554 -v 0.091603 0.102529 0.156361 -vn -0.692678 0.646867 0.318999 -v 0.091603 0.104409 0.153104 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.098893 0.144746 -vn -0.678875 0.709235 0.190039 -v 0.091603 0.105408 0.150692 -vn -0.707107 0.612372 0.353553 -v 0.091603 0.101251 0.158575 -vn -0.707107 0.612373 0.353551 -v 0.091603 0.090733 0.176792 -vn -0.707107 0.612372 0.353554 -v 0.091603 0.092893 0.173050 -vn -0.707105 0.612375 0.353552 -v 0.091603 0.094287 0.170636 -vn -0.707108 0.612373 0.353549 -v 0.091603 0.094529 0.170217 -vn -0.707107 0.612373 0.353553 -v 0.091603 0.096597 0.166636 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.096597 0.165503 -vn -0.707107 0.612372 0.353554 -v 0.091603 0.097251 0.165503 -vn -0.684468 0.690608 0.233592 -v 0.091603 0.087174 0.185238 -vn -0.742518 0.623799 0.244013 -v 0.091603 0.088020 0.181491 -vn -0.707106 0.612374 0.353552 -v 0.091603 0.090287 0.177564 -vn -0.707107 -0.612373 -0.353553 -v 0.091603 0.063269 0.156361 -vn -0.722128 -0.690278 -0.045243 -v 0.091603 0.075549 0.132412 -vn -0.737701 -0.652124 -0.174736 -v 0.091603 0.075208 0.135000 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.077905 0.140510 -vn -0.577350 -0.577350 -0.577350 -v 0.091603 0.075549 0.131000 -vn -0.707107 -0.707107 0.000000 -v 0.091603 0.075549 0.132200 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.077905 0.132200 -vn -0.707107 -0.612373 -0.353553 -v 0.091603 0.072421 0.140510 -vn -0.722128 -0.620420 -0.305957 -v 0.091603 0.074209 0.137412 -vn -1.000000 -0.000003 0.000000 -v 0.091603 0.084893 0.144746 -vn -1.000000 -0.000003 0.000000 -v 0.091603 0.084893 0.140510 -vn -1.000000 -0.000003 0.000000 -v 0.091603 0.086287 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.090287 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.092893 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.098893 0.140510 -vn -0.770259 -0.318865 -0.552292 -v 0.091603 0.099449 0.136386 -vn -0.692678 0.719703 0.047172 -v 0.091603 0.105749 0.148104 -vn -0.707107 0.707107 0.000000 -v 0.091603 0.105749 0.144746 -vn -0.770262 0.637727 -0.000000 -v 0.091603 0.081049 0.135000 -vn -0.770261 0.552290 0.318863 -v 0.091603 0.081264 0.134200 -vn -1.000000 -0.000003 0.000000 -v 0.091603 0.084893 0.132200 -vn -0.770261 -0.552290 0.318863 -v 0.091603 0.084035 0.134200 -vn -0.770262 -0.637727 0.000000 -v 0.091603 0.084249 0.135000 -vn -0.770261 0.318869 0.552286 -v 0.091603 0.081849 0.133614 -vn -0.770264 0.000001 0.637725 -v 0.091603 0.082649 0.133400 -vn -0.770262 -0.318868 0.552286 -v 0.091603 0.083449 0.133614 -vn -0.770262 0.552287 -0.318866 -v 0.091603 0.081264 0.135800 -vn -0.770262 -0.552287 -0.318866 -v 0.091603 0.084035 0.135800 -vn -0.770260 -0.318866 -0.552290 -v 0.091603 0.083449 0.136386 -vn -0.770264 0.000001 -0.637725 -v 0.091603 0.082649 0.136600 -vn -0.770260 0.318866 -0.552290 -v 0.091603 0.081849 0.136386 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.094287 0.144746 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.094287 0.140510 -vn -1.000000 0.000000 0.000000 -v 0.091603 0.094287 0.132200 -vn -0.707105 -0.353560 0.612371 -v 0.091603 0.077905 0.144890 -vn -0.707107 -0.353557 0.612371 -v 0.091603 0.084893 0.148924 -vn -0.707106 -0.353556 0.612372 -v 0.091603 0.086287 0.149729 -vn -0.707107 -0.353554 0.612372 -v 0.091603 0.090287 0.152039 -vn -0.707106 -0.353553 0.612374 -v 0.091603 0.092893 0.153543 -vn -0.707107 0.000000 -0.707107 -v 0.091603 0.077905 0.131000 -vn -0.707106 -0.000002 -0.707107 -v 0.091603 0.084893 0.131000 -vn -0.707107 -0.000002 -0.707106 -v 0.091603 0.086287 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.091603 0.090287 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.091603 0.092893 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.091603 0.094287 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.091603 0.096597 0.131000 -vn -0.707107 0.000000 -0.707107 -v 0.091603 0.098893 0.131000 -vn -0.577350 0.577350 -0.577350 -v 0.091603 0.105749 0.131000 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.094287 0.163289 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.096597 0.163289 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.096597 0.165503 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.096597 0.144746 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.098893 0.144746 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.098893 0.156361 -vn 0.707107 0.612372 0.353553 -v 0.095603 0.101251 0.158575 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.098893 0.158575 -vn 0.707107 0.612373 0.353553 -v 0.095603 0.098893 0.162658 -vn 0.707106 0.612374 0.353552 -v 0.095603 0.090287 0.177564 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.090287 0.176792 -vn 0.707107 0.612373 0.353551 -v 0.095603 0.090733 0.176792 -vn 0.707107 -0.612372 -0.353554 -v 0.095603 0.071511 0.142086 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.071511 0.144746 -vn 0.707106 -0.612373 -0.353554 -v 0.095603 0.069975 0.144746 -vn 0.722128 -0.690278 -0.045243 -v 0.095603 0.075549 0.132412 -vn 0.707107 -0.707107 0.000000 -v 0.095603 0.075549 0.132200 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.077905 0.132200 -vn 0.707110 -0.612374 -0.353545 -v 0.095603 0.090287 0.165564 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.090287 0.170217 -vn 0.707107 -0.612373 -0.353553 -v 0.095603 0.087601 0.170217 -vn 0.770264 -0.637725 0.000000 -v 0.095603 0.085537 0.180256 -vn 0.770262 -0.552285 0.318871 -v 0.095603 0.085370 0.179631 -vn 1.000000 0.000002 0.000000 -v 0.095603 0.086287 0.176792 -vn 0.684467 0.627476 0.371187 -v 0.095603 0.085572 0.188730 -vn 0.770267 -0.318853 -0.552287 -v 0.095603 0.084912 0.181339 -vn 0.770259 -0.552290 -0.318867 -v 0.095603 0.085370 0.180881 -vn 1.000000 0.000003 0.000000 -v 0.095603 0.084893 0.176792 -vn 0.770263 -0.318857 0.552291 -v 0.095603 0.084912 0.179174 -vn 0.707106 -0.612372 -0.353554 -v 0.095603 0.083805 0.176792 -vn 0.770264 0.000000 0.637725 -v 0.095603 0.084287 0.179006 -vn 0.770260 0.318865 0.552291 -v 0.095603 0.083662 0.179174 -vn 0.667615 -0.702657 -0.246098 -v 0.095603 0.082144 0.179669 -vn 0.770263 0.552286 0.318865 -v 0.095603 0.083205 0.179631 -vn 0.770261 0.637728 -0.000000 -v 0.095603 0.083037 0.180256 -vn 0.735435 -0.652740 -0.181840 -v 0.095603 0.081691 0.182665 -vn 0.770259 0.000000 -0.637732 -v 0.095603 0.084287 0.181506 -vn 0.684467 0.537285 0.492777 -v 0.095603 0.083283 0.191815 -vn 0.770264 0.318861 -0.552287 -v 0.095603 0.083662 0.181339 -vn 0.684467 0.423927 0.593119 -v 0.095603 0.080407 0.194361 -vn 0.684468 0.292291 0.667885 -v 0.095603 0.077066 0.196258 -vn 0.770261 0.552291 -0.318862 -v 0.095603 0.083205 0.180881 -vn 0.735435 -0.589800 -0.333574 -v 0.095603 0.080530 0.185464 -vn 0.735435 -0.492196 -0.465702 -v 0.095603 0.078729 0.187901 -vn 0.770261 -0.552291 -0.318862 -v 0.095603 0.093370 0.167025 -vn 0.770261 -0.637728 0.000000 -v 0.095603 0.093537 0.166400 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.094287 0.165503 -vn 0.770263 -0.552286 0.318865 -v 0.095603 0.093370 0.165775 -vn 0.770260 -0.318865 0.552291 -v 0.095603 0.092912 0.165317 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.094287 0.170217 -vn 0.770262 -0.318869 -0.552286 -v 0.095603 0.092912 0.167482 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.092893 0.170217 -vn 0.770264 0.000000 -0.637725 -v 0.095603 0.092287 0.167650 -vn 0.770262 0.318869 -0.552286 -v 0.095603 0.091662 0.167482 -vn 0.770260 0.318865 -0.552291 -v 0.095603 0.060886 0.168189 -vn 0.770264 0.000000 -0.637725 -v 0.095603 0.061511 0.168356 -vn 0.735435 0.483848 0.474369 -v 0.095603 0.060723 0.170559 -vn 0.770262 -0.552290 0.318862 -v 0.095603 0.062593 0.166481 -vn 0.770261 -0.318868 0.552287 -v 0.095603 0.062136 0.166024 -vn 0.707107 0.612372 0.353554 -v 0.095603 0.064919 0.165503 -vn 0.770264 0.000000 0.637725 -v 0.095603 0.061511 0.165856 -vn 0.667615 0.564456 0.485469 -v 0.095603 0.063091 0.168669 -vn 0.770259 -0.318865 -0.552292 -v 0.095603 0.062136 0.168189 -vn 0.770264 -0.552285 -0.318866 -v 0.095603 0.062593 0.167731 -vn 0.770261 -0.637728 0.000000 -v 0.095603 0.062761 0.167106 -vn 0.770263 0.552286 -0.318865 -v 0.095603 0.060428 0.167731 -vn 0.684468 -0.635195 -0.357815 -v 0.095603 0.053531 0.170231 -vn 0.770261 0.637728 -0.000000 -v 0.095603 0.060261 0.167106 -vn 0.684467 -0.547601 -0.481288 -v 0.095603 0.055753 0.167097 -vn 0.770261 0.552291 0.318862 -v 0.095603 0.060428 0.166481 -vn 0.742517 -0.523221 -0.418220 -v 0.095603 0.058575 0.164491 -vn 0.770262 0.318869 0.552286 -v 0.095603 0.060886 0.166024 -vn 0.707107 -0.612372 -0.353554 -v 0.095603 0.059269 0.163289 -vn 0.770261 0.552288 -0.318867 -v 0.095603 0.064428 0.160803 -vn 0.770261 0.318867 -0.552288 -v 0.095603 0.064886 0.161261 -vn 0.707106 0.612373 0.353554 -v 0.095603 0.066197 0.163289 -vn 0.770261 -0.552288 -0.318867 -v 0.095603 0.066593 0.160803 -vn 0.707107 0.612373 0.353553 -v 0.095603 0.067511 0.161014 -vn 0.770261 -0.318866 -0.552288 -v 0.095603 0.066136 0.161261 -vn 0.770264 0.000001 -0.637725 -v 0.095603 0.065511 0.161428 -vn 0.770264 -0.637725 0.000000 -v 0.095603 0.066761 0.160178 -vn 0.770259 -0.552293 0.318864 -v 0.095603 0.066593 0.159553 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.067511 0.158575 -vn 0.770266 -0.318861 0.552284 -v 0.095603 0.066136 0.159095 -vn 0.770258 0.000001 0.637732 -v 0.095603 0.065511 0.158928 -vn 0.707107 -0.612373 -0.353553 -v 0.095603 0.061991 0.158575 -vn 0.770266 0.318862 0.552284 -v 0.095603 0.064886 0.159095 -vn 0.770259 0.552293 0.318864 -v 0.095603 0.064428 0.159553 -vn 0.770264 0.637725 0.000000 -v 0.095603 0.064261 0.160178 -vn 0.770264 -0.637725 0.000000 -v 0.095603 0.070761 0.153250 -vn 0.770260 -0.552291 0.318866 -v 0.095603 0.070593 0.152625 -vn 0.770265 -0.318861 0.552287 -v 0.095603 0.070136 0.152167 -vn 0.770258 -0.000000 0.637732 -v 0.095603 0.069511 0.152000 -vn 0.707107 -0.612373 -0.353553 -v 0.095603 0.067511 0.149014 -vn 0.770264 0.318861 0.552287 -v 0.095603 0.068886 0.152167 -vn 0.770261 0.552291 0.318862 -v 0.095603 0.068428 0.152625 -vn 0.770261 0.637728 -0.000000 -v 0.095603 0.068261 0.153250 -vn 0.770263 0.552286 -0.318865 -v 0.095603 0.068428 0.153875 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.067511 0.156361 -vn 0.770260 0.318865 -0.552291 -v 0.095603 0.068886 0.154332 -vn 0.707107 0.612372 0.353554 -v 0.095603 0.068919 0.158575 -vn 0.707106 0.612373 0.353554 -v 0.095603 0.070197 0.156361 -vn 0.770264 0.000000 -0.637725 -v 0.095603 0.069511 0.154500 -vn 0.770260 -0.318865 -0.552291 -v 0.095603 0.070136 0.154332 -vn 0.707107 0.612373 0.353553 -v 0.095603 0.071511 0.154086 -vn 0.770262 -0.552286 -0.318869 -v 0.095603 0.070593 0.153875 -vn 0.707108 0.612371 0.353555 -v 0.095603 0.076903 0.144746 -vn 0.770263 -0.552286 0.318865 -v 0.095603 0.074593 0.145697 -vn 0.770260 -0.318865 0.552291 -v 0.095603 0.074136 0.145239 -vn 0.770264 0.000000 0.637725 -v 0.095603 0.073511 0.145072 -vn 0.770260 0.318866 0.552291 -v 0.095603 0.072886 0.145239 -vn 0.770263 0.552286 0.318865 -v 0.095603 0.072428 0.145697 -vn 0.770261 0.637728 -0.000000 -v 0.095603 0.072261 0.146322 -vn 0.770261 0.552291 -0.318862 -v 0.095603 0.072428 0.146947 -vn 0.770265 0.318861 -0.552287 -v 0.095603 0.072886 0.147404 -vn 0.770258 0.000000 -0.637732 -v 0.095603 0.073511 0.147572 -vn 0.770265 -0.318861 -0.552287 -v 0.095603 0.074136 0.147404 -vn 0.770261 -0.552291 -0.318862 -v 0.095603 0.074593 0.146947 -vn 0.770261 -0.637728 0.000000 -v 0.095603 0.074761 0.146322 -vn 0.707111 -0.353552 0.612369 -v 0.095603 0.077656 0.144746 -vn 0.904531 0.110365 0.411877 -v 0.095603 0.077091 0.144420 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.077905 0.140510 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.094287 0.144746 -vn 0.707106 -0.353553 0.612374 -v 0.095603 0.092893 0.153543 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.092893 0.144746 -vn 0.707107 -0.353554 0.612372 -v 0.095603 0.090287 0.152039 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.090287 0.144746 -vn 0.707106 -0.353554 0.612373 -v 0.095603 0.086287 0.149729 -vn 1.000000 0.000003 0.000000 -v 0.095603 0.086287 0.144746 -vn 0.707108 -0.353552 0.612371 -v 0.095603 0.084893 0.148924 -vn 1.000000 0.000003 0.000000 -v 0.095603 0.084893 0.144746 -vn 0.707105 -0.353560 0.612371 -v 0.095603 0.077905 0.144890 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.077905 0.144746 -vn 0.770264 -0.318861 0.552287 -v 0.095603 0.096912 0.158389 -vn 0.770258 -0.000000 0.637732 -v 0.095603 0.096287 0.158222 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.096597 0.156361 -vn 0.770265 0.318861 0.552287 -v 0.095603 0.095662 0.158389 -vn 0.770264 0.000000 -0.637725 -v 0.095603 0.096287 0.160722 -vn 0.770260 0.318865 -0.552291 -v 0.095603 0.095662 0.160554 -vn 0.770263 0.552286 -0.318865 -v 0.095603 0.095205 0.160097 -vn 0.904533 -0.411874 0.110362 -v 0.095603 0.096144 0.155420 -vn 0.707107 -0.612373 -0.353551 -v 0.095603 0.095601 0.156361 -vn 0.707116 -0.612350 -0.353574 -v 0.095603 0.094323 0.158575 -vn 0.770261 0.552291 0.318862 -v 0.095603 0.095205 0.158847 -vn 0.707098 -0.612366 -0.353583 -v 0.095603 0.094287 0.158636 -vn 0.770261 0.637728 -0.000000 -v 0.095603 0.095037 0.159472 -vn 0.707107 -0.612372 -0.353553 -v 0.095603 0.091601 0.163289 -vn 0.707106 -0.612373 -0.353553 -v 0.095603 0.092893 0.161050 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.092893 0.163289 -vn 0.770264 0.318861 -0.552287 -v 0.095603 0.087662 0.174411 -vn 0.770258 0.000000 -0.637732 -v 0.095603 0.088287 0.174578 -vn 0.770261 -0.637728 0.000000 -v 0.095603 0.089537 0.173328 -vn 0.770263 -0.552286 0.318865 -v 0.095603 0.089370 0.172703 -vn 0.770260 -0.318865 0.552291 -v 0.095603 0.088912 0.172245 -vn 0.770264 -0.318861 -0.552287 -v 0.095603 0.088912 0.174411 -vn 0.770261 -0.552291 -0.318862 -v 0.095603 0.089370 0.173953 -vn 0.770264 0.000000 0.637725 -v 0.095603 0.088287 0.172078 -vn 0.770260 0.318866 0.552291 -v 0.095603 0.087662 0.172245 -vn 0.707107 -0.612373 -0.353553 -v 0.095603 0.086287 0.172492 -vn 0.770263 0.552286 0.318865 -v 0.095603 0.087205 0.172703 -vn 0.770261 0.637728 -0.000000 -v 0.095603 0.087037 0.173328 -vn 0.770261 0.552291 -0.318862 -v 0.095603 0.087205 0.173953 -vn 0.707109 -0.612369 -0.353554 -v 0.095603 0.084893 0.174907 -vn 0.735436 -0.056830 -0.675207 -v 0.095603 0.070698 0.191766 -vn 0.735435 -0.217645 -0.641690 -v 0.095603 0.073664 0.191148 -vn 0.735435 -0.365666 -0.570459 -v 0.095603 0.076395 0.189834 -vn 0.684468 0.148052 0.713852 -v 0.095603 0.073406 0.197425 -vn 0.684467 -0.002573 0.729039 -v 0.095603 0.069584 0.197810 -vn 0.735435 0.107325 -0.669042 -v 0.095603 0.067669 0.191653 -vn 0.684467 -0.153087 0.712789 -v 0.095603 0.065764 0.197398 -vn 0.735435 0.265169 -0.623555 -v 0.095603 0.064757 0.190813 -vn 0.684467 -0.296999 0.665805 -v 0.095603 0.062113 0.196206 -vn 0.735435 0.407430 -0.541420 -v 0.095603 0.062133 0.189298 -vn 0.684468 -0.428104 0.590111 -v 0.095603 0.058786 0.194285 -vn 0.735435 0.525746 -0.427465 -v 0.095603 0.059950 0.187196 -vn 0.684467 -0.540750 0.488972 -v 0.095603 0.055927 0.191718 -vn 0.735435 0.613162 -0.288388 -v 0.095603 0.058338 0.184630 -vn 0.684467 -0.630080 0.366748 -v 0.095603 0.053660 0.188617 -vn 0.684467 -0.692240 0.228710 -v 0.095603 0.052083 0.185114 -vn 0.735435 0.664542 -0.132361 -v 0.095603 0.057390 0.181752 -vn 0.684467 -0.724551 0.080811 -v 0.095603 0.051263 0.181361 -vn 0.735435 0.676865 0.031446 -v 0.095603 0.057163 0.178730 -vn 0.684467 -0.725620 -0.070573 -v 0.095603 0.051236 0.177520 -vn 0.735435 0.649408 0.193404 -v 0.095603 0.057669 0.175743 -vn 0.684467 -0.695400 -0.218914 -v 0.095603 0.052003 0.173755 -vn 0.735436 0.583783 0.343995 -v 0.095603 0.058880 0.172964 -vn 0.770261 -0.637728 0.000000 -v 0.095603 0.097537 0.159472 -vn 0.770263 -0.552286 -0.318865 -v 0.095603 0.097370 0.160097 -vn 0.770260 -0.318865 -0.552291 -v 0.095603 0.096912 0.160554 -vn 0.707106 0.612373 0.353554 -v 0.095603 0.098529 0.163289 -vn 0.707107 -0.612373 -0.353553 -v 0.095603 0.072421 0.140510 -vn 0.722128 -0.620420 -0.305957 -v 0.095603 0.074209 0.137412 -vn 0.737701 -0.652124 -0.174736 -v 0.095603 0.075208 0.135000 -vn 0.707107 -0.612373 -0.353553 -v 0.095603 0.063269 0.156361 -vn 0.742518 0.623799 0.244013 -v 0.095603 0.088020 0.181491 -vn 0.684468 0.690608 0.233592 -v 0.095603 0.087174 0.185238 -vn 0.707107 0.612372 0.353554 -v 0.095603 0.092893 0.173050 -vn 0.707108 0.612373 0.353549 -v 0.095603 0.094529 0.170217 -vn 0.707105 0.612375 0.353552 -v 0.095603 0.094287 0.170636 -vn 0.707107 0.612373 0.353553 -v 0.095603 0.096597 0.166636 -vn 0.707107 0.612372 0.353554 -v 0.095603 0.097251 0.165503 -vn 0.707107 0.707107 0.000000 -v 0.095603 0.105749 0.144746 -vn 0.692678 0.719703 0.047172 -v 0.095603 0.105749 0.148104 -vn 0.678875 0.709235 0.190039 -v 0.095603 0.105408 0.150692 -vn 0.692678 0.646867 0.318999 -v 0.095603 0.104409 0.153104 -vn 0.707106 0.612373 0.353554 -v 0.095603 0.102529 0.156361 -vn 0.770260 -0.637730 -0.000000 -v 0.095603 0.100249 0.135000 -vn 0.707107 0.707107 0.000000 -v 0.095603 0.105749 0.132200 -vn 0.770264 -0.552285 -0.318864 -v 0.095603 0.100035 0.135800 -vn 0.707107 0.707107 0.000000 -v 0.095603 0.105749 0.140510 -vn 0.770263 -0.552289 0.318862 -v 0.095603 0.100035 0.134200 -vn 0.770261 -0.318868 0.552288 -v 0.095603 0.099449 0.133614 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.098893 0.132200 -vn 0.770265 0.000000 0.637725 -v 0.095603 0.098649 0.133400 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.096597 0.132200 -vn 0.770260 0.318868 0.552288 -v 0.095603 0.097849 0.133614 -vn 0.770263 0.552289 0.318862 -v 0.095603 0.097264 0.134200 -vn 0.770260 0.637730 0.000000 -v 0.095603 0.097049 0.135000 -vn 0.770264 0.552285 -0.318864 -v 0.095603 0.097264 0.135800 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.096597 0.140510 -vn 0.770259 0.318865 -0.552292 -v 0.095603 0.097849 0.136386 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.098893 0.140510 -vn 0.770265 -0.000000 -0.637725 -v 0.095603 0.098649 0.136600 -vn 0.770259 -0.318865 -0.552292 -v 0.095603 0.099449 0.136386 -vn 0.770260 -0.637730 -0.000000 -v 0.095603 0.092249 0.135000 -vn 0.770263 -0.552289 0.318862 -v 0.095603 0.092035 0.134200 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.092893 0.132200 -vn 0.770260 -0.318868 0.552288 -v 0.095603 0.091449 0.133614 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.090287 0.132200 -vn 0.770265 0.000000 0.637725 -v 0.095603 0.090649 0.133400 -vn 1.000000 0.000003 0.000000 -v 0.095603 0.086287 0.132200 -vn 0.770261 0.318869 0.552286 -v 0.095603 0.089849 0.133614 -vn 0.770261 0.552290 0.318863 -v 0.095603 0.089264 0.134200 -vn 0.770262 0.637727 0.000000 -v 0.095603 0.089049 0.135000 -vn 0.770262 0.552287 -0.318866 -v 0.095603 0.089264 0.135800 -vn 1.000000 0.000003 0.000000 -v 0.095603 0.086287 0.140510 -vn 0.770260 0.318866 -0.552290 -v 0.095603 0.089849 0.136386 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.090287 0.140510 -vn 0.770265 -0.000000 -0.637725 -v 0.095603 0.090649 0.136600 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.092893 0.140510 -vn 0.770259 -0.318865 -0.552292 -v 0.095603 0.091449 0.136386 -vn 0.770264 -0.552285 -0.318864 -v 0.095603 0.092035 0.135800 -vn 0.577350 0.577350 -0.577350 -v 0.095603 0.105749 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.095603 0.098893 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.095603 0.096597 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.095603 0.094287 0.131000 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.094287 0.132200 -vn 0.707107 0.000000 -0.707107 -v 0.095603 0.092893 0.131000 -vn 0.707107 0.000000 -0.707107 -v 0.095603 0.090287 0.131000 -vn 0.707106 0.000002 -0.707107 -v 0.095603 0.086287 0.131000 -vn 0.707107 0.000002 -0.707106 -v 0.095603 0.084893 0.131000 -vn 1.000000 0.000003 0.000000 -v 0.095603 0.084893 0.132200 -vn 0.707107 0.000000 -0.707107 -v 0.095603 0.077905 0.131000 -vn 0.577350 -0.577350 -0.577350 -v 0.095603 0.075549 0.131000 -vn 0.770262 -0.637727 -0.000000 -v 0.095603 0.084249 0.135000 -vn 0.770261 -0.552290 0.318863 -v 0.095603 0.084035 0.134200 -vn 0.770261 0.552290 0.318863 -v 0.095603 0.081264 0.134200 -vn 0.770262 0.637727 0.000000 -v 0.095603 0.081049 0.135000 -vn 0.770260 -0.318866 -0.552290 -v 0.095603 0.083449 0.136386 -vn 0.770262 -0.552287 -0.318866 -v 0.095603 0.084035 0.135800 -vn 1.000000 0.000003 0.000000 -v 0.095603 0.084893 0.140510 -vn 0.770262 -0.318868 0.552286 -v 0.095603 0.083449 0.133614 -vn 0.770264 0.000001 0.637725 -v 0.095603 0.082649 0.133400 -vn 0.770261 0.318869 0.552286 -v 0.095603 0.081849 0.133614 -vn 0.770262 0.552287 -0.318866 -v 0.095603 0.081264 0.135800 -vn 0.770260 0.318866 -0.552290 -v 0.095603 0.081849 0.136386 -vn 0.770264 0.000001 -0.637725 -v 0.095603 0.082649 0.136600 -vn 1.000000 0.000000 0.000000 -v 0.095603 0.094287 0.140510 -vn 0.770261 -0.552291 0.318862 -v 0.095603 0.097370 0.158847 -vn 0.707108 -0.353552 0.612372 -v 0.095603 0.094287 0.154348 -vn 0.770264 0.000000 0.637725 -v 0.095603 0.092287 0.165150 -vn 0.770260 0.318866 0.552291 -v 0.095603 0.091662 0.165317 -vn 0.707103 -0.612379 -0.353548 -v 0.095603 0.090323 0.165503 -vn 0.770263 0.552286 0.318865 -v 0.095603 0.091205 0.165775 -vn 0.770261 0.637728 -0.000000 -v 0.095603 0.091037 0.166400 -vn 0.770261 0.552291 -0.318862 -v 0.095603 0.091205 0.167025 -vn 0.770259 -0.318867 0.552290 -v 0.098753 0.099499 0.126701 -vn 0.770265 -0.000001 0.637724 -v 0.098753 0.098749 0.126500 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.098828 0.115875 -vn 0.686917 -0.677661 -0.262527 -v 0.098753 0.076762 0.090581 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.078499 0.090000 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.078499 0.093172 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.091832 0.088625 -vn 0.770257 -0.637734 0.000001 -v 0.098753 0.091999 0.088000 -vn 1.000000 -0.000000 0.000000 -v 0.098753 0.092124 0.090000 -vn 0.686917 0.617883 -0.382577 -v 0.098753 0.103502 0.088104 -vn 0.686917 0.677661 -0.262527 -v 0.098753 0.104736 0.090581 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.098828 0.090000 -vn 0.770261 -0.637728 0.000000 -v 0.098753 0.097656 0.090343 -vn 0.770262 -0.552289 0.318864 -v 0.098753 0.097489 0.089718 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.089374 0.102000 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.086175 0.102282 -vn 0.770261 -0.637728 0.000000 -v 0.098753 0.086342 0.101657 -vn 0.770261 -0.318860 -0.552291 -v 0.098753 0.085717 0.102739 -vn 1.000000 0.000001 -0.000000 -v 0.098753 0.089374 0.115875 -vn 0.770262 0.000004 -0.637728 -v 0.098753 0.085092 0.102907 -vn 1.000000 0.000001 0.000000 -v 0.098753 0.084874 0.115875 -vn 0.770262 0.318863 -0.552289 -v 0.098753 0.084467 0.102739 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.082671 0.115875 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.082671 0.102000 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.084010 0.102282 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.082671 0.098828 -vn 0.770262 0.552289 0.318863 -v 0.098753 0.084010 0.101032 -vn 0.770261 0.637728 -0.000000 -v 0.098753 0.083842 0.101657 -vn 1.000000 0.000003 0.000001 -v 0.098753 0.084874 0.093172 -vn 0.770262 0.000004 -0.637728 -v 0.098753 0.085092 0.091593 -vn 0.744070 0.540506 0.392699 -v 0.098753 0.086502 0.092914 -vn 0.770261 -0.318859 -0.552292 -v 0.098753 0.085717 0.091426 -vn 0.744071 0.392699 0.540505 -v 0.098753 0.087663 0.091753 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.086175 0.090968 -vn 0.744071 0.206455 0.635401 -v 0.098753 0.089127 0.091007 -vn 0.770262 0.318863 0.552289 -v 0.098753 0.084467 0.089261 -vn 0.770262 0.552289 0.318863 -v 0.098753 0.084010 0.089718 -vn 1.000000 -0.000000 0.000000 -v 0.098753 0.082671 0.090000 -vn 0.770261 0.637728 -0.000000 -v 0.098753 0.083842 0.090343 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.082671 0.093172 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.084010 0.090968 -vn 0.770262 0.318863 -0.552289 -v 0.098753 0.084467 0.091426 -vn 0.686918 -0.437956 -0.579947 -v 0.098753 0.081710 0.084030 -vn 0.686918 -0.323933 -0.650547 -v 0.098753 0.084063 0.082573 -vn 0.770262 0.000005 0.637728 -v 0.098753 0.085092 0.089093 -vn 0.686917 -0.198880 -0.698993 -v 0.098753 0.086644 0.081573 -vn 0.770261 -0.318860 0.552291 -v 0.098753 0.085717 0.089261 -vn 0.686917 -0.067055 -0.723636 -v 0.098753 0.089365 0.081064 -vn 0.770262 -0.552289 0.318864 -v 0.098753 0.086175 0.089718 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.089374 0.090000 -vn 0.770261 -0.637728 0.000000 -v 0.098753 0.086342 0.090343 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.097489 0.090968 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.093703 0.090000 -vn 0.770262 0.552289 0.318863 -v 0.098753 0.095323 0.089718 -vn 0.770261 0.637728 -0.000000 -v 0.098753 0.095156 0.090343 -vn 0.770262 -0.318863 -0.552289 -v 0.098753 0.097031 0.091426 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.098828 0.093172 -vn 0.770261 -0.000000 -0.637728 -v 0.098753 0.096406 0.091593 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.096624 0.093172 -vn 0.770262 0.318863 -0.552289 -v 0.098753 0.095781 0.091426 -vn 0.744071 -0.540505 0.392699 -v 0.098753 0.094996 0.092914 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.095323 0.090968 -vn 0.744071 -0.392699 0.540505 -v 0.098753 0.093835 0.091753 -vn 0.770262 0.318863 0.552289 -v 0.098753 0.095781 0.089261 -vn 0.686917 0.198881 -0.698993 -v 0.098753 0.094854 0.081573 -vn 0.770261 -0.000000 0.637729 -v 0.098753 0.096406 0.089093 -vn 0.686917 0.323934 -0.650547 -v 0.098753 0.097435 0.082573 -vn 0.770262 -0.318864 0.552289 -v 0.098753 0.097031 0.089261 -vn 0.686917 0.437957 -0.579947 -v 0.098753 0.099789 0.084030 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.098828 0.102000 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.097489 0.102282 -vn 0.770261 -0.637728 0.000000 -v 0.098753 0.097656 0.101657 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.098828 0.098828 -vn 0.770262 -0.552289 0.318863 -v 0.098753 0.097489 0.101032 -vn 0.770262 -0.318863 0.552289 -v 0.098753 0.097031 0.100574 -vn 0.770262 -0.318863 -0.552289 -v 0.098753 0.097031 0.102739 -vn 0.770261 -0.000000 -0.637728 -v 0.098753 0.096406 0.102907 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.096624 0.115875 -vn 0.770262 0.318863 -0.552289 -v 0.098753 0.095781 0.102739 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.093703 0.115875 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.095323 0.102282 -vn 0.770262 0.552289 0.318863 -v 0.098753 0.095323 0.101032 -vn 0.770261 0.637728 -0.000000 -v 0.098753 0.095156 0.101657 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.093703 0.102000 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.096624 0.098828 -vn 0.770261 0.000000 0.637728 -v 0.098753 0.096406 0.100407 -vn 0.744071 -0.540505 -0.392699 -v 0.098753 0.094996 0.099086 -vn 0.770262 0.318863 0.552289 -v 0.098753 0.095781 0.100574 -vn 0.744071 -0.392699 -0.540505 -v 0.098753 0.093835 0.100247 -vn 0.770261 -0.000000 -0.637728 -v 0.098753 0.098749 0.097250 -vn 0.770262 -0.318863 -0.552289 -v 0.098753 0.099374 0.097083 -vn 0.707107 0.707107 0.000000 -v 0.098753 0.105749 0.098828 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.099832 0.096625 -vn 0.696858 0.716444 -0.033123 -v 0.098753 0.105749 0.096000 -vn 0.770261 -0.637728 0.000000 -v 0.098753 0.099999 0.096000 -vn 0.686917 0.714362 -0.133538 -v 0.098753 0.105494 0.093244 -vn 0.686917 0.537065 -0.489598 -v 0.098753 0.101834 0.085895 -vn 0.686917 0.067055 -0.723636 -v 0.098753 0.092133 0.081064 -vn 0.770261 -0.552290 0.318863 -v 0.098753 0.091832 0.087375 -vn 0.770262 -0.318864 0.552289 -v 0.098753 0.091374 0.086917 -vn 0.770261 -0.000000 0.637729 -v 0.098753 0.090749 0.086750 -vn 0.770262 0.318864 0.552289 -v 0.098753 0.090124 0.086917 -vn 0.770261 0.552290 0.318863 -v 0.098753 0.089667 0.087375 -vn 0.770257 0.637734 0.000001 -v 0.098753 0.089499 0.088000 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.089667 0.088625 -vn 0.770262 0.318863 -0.552289 -v 0.098753 0.090124 0.089083 -vn 0.770261 -0.000000 -0.637728 -v 0.098753 0.090749 0.089250 -vn 0.770262 -0.318863 -0.552289 -v 0.098753 0.091374 0.089083 -vn 0.686916 -0.537066 -0.489598 -v 0.098753 0.079664 0.085895 -vn 0.686917 -0.617883 -0.382577 -v 0.098753 0.077996 0.088104 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.078499 0.098828 -vn 0.696858 -0.716444 -0.033123 -v 0.098753 0.075749 0.096000 -vn 0.686917 -0.714362 -0.133537 -v 0.098753 0.076005 0.093244 -vn 0.770262 -0.552289 0.318863 -v 0.098753 0.099832 0.095375 -vn 0.770262 -0.318863 0.552289 -v 0.098753 0.099374 0.094917 -vn 0.770261 0.000000 0.637728 -v 0.098753 0.098749 0.094750 -vn 0.770262 0.318863 0.552289 -v 0.098753 0.098124 0.094917 -vn 0.770262 0.318863 -0.552289 -v 0.098753 0.098124 0.097083 -vn 0.770262 0.552289 0.318863 -v 0.098753 0.097667 0.095375 -vn 0.770261 0.637728 -0.000000 -v 0.098753 0.097499 0.096000 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.097667 0.096625 -vn 0.770262 -0.318863 -0.552289 -v 0.098753 0.083374 0.097083 -vn 1.000000 0.000003 -0.000000 -v 0.098753 0.084874 0.098828 -vn 0.770261 -0.000000 -0.637728 -v 0.098753 0.082749 0.097250 -vn 0.770262 0.318863 -0.552289 -v 0.098753 0.082124 0.097083 -vn 0.770262 -0.318863 0.552289 -v 0.098753 0.083374 0.094917 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.083832 0.096625 -vn 0.770261 -0.637728 0.000000 -v 0.098753 0.083999 0.096000 -vn 0.770262 -0.552289 0.318863 -v 0.098753 0.083832 0.095375 -vn 0.770261 0.000000 0.637728 -v 0.098753 0.082749 0.094750 -vn 0.770262 0.318863 0.552289 -v 0.098753 0.082124 0.094917 -vn 0.770262 0.552289 0.318863 -v 0.098753 0.081667 0.095375 -vn 0.770261 0.637728 -0.000000 -v 0.098753 0.081499 0.096000 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.081667 0.096625 -vn 0.744071 -0.635401 -0.206455 -v 0.098753 0.095742 0.097622 -vn 0.744071 -0.668100 0.000000 -v 0.098753 0.095999 0.096000 -vn 0.744071 -0.635401 0.206455 -v 0.098753 0.095742 0.094378 -vn 0.744071 0.206455 -0.635401 -v 0.098753 0.089127 0.100993 -vn 0.744071 -0.000000 -0.668100 -v 0.098753 0.090749 0.101250 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.092124 0.102000 -vn 0.744071 -0.206455 -0.635401 -v 0.098753 0.092372 0.100993 -vn 0.744069 0.635404 0.206455 -v 0.098753 0.085756 0.094378 -vn 0.744067 0.668105 -0.000000 -v 0.098753 0.085499 0.096000 -vn 0.744069 0.635404 -0.206455 -v 0.098753 0.085756 0.097622 -vn 0.744070 0.540506 -0.392699 -v 0.098753 0.086502 0.099086 -vn 0.744071 0.000000 0.668100 -v 0.098753 0.090749 0.090750 -vn 0.744071 -0.206455 0.635401 -v 0.098753 0.092372 0.091007 -vn 0.770263 -0.637727 -0.000002 -v 0.098753 0.092249 0.128000 -vn 0.707107 0.000000 0.707107 -v 0.098753 0.093703 0.131000 -vn 0.770262 -0.552286 -0.318868 -v 0.098753 0.092048 0.128750 -vn 0.707107 0.000000 0.707107 -v 0.098753 0.092124 0.131000 -vn 0.770259 -0.318867 -0.552290 -v 0.098753 0.091499 0.129299 -vn 0.770262 -0.552287 0.318866 -v 0.098753 0.092048 0.127250 -vn 0.770262 0.552287 0.318866 -v 0.098753 0.089450 0.127250 -vn 0.770262 0.637727 -0.000001 -v 0.098753 0.089249 0.128000 -vn 0.707107 0.000001 0.707107 -v 0.098753 0.084874 0.131000 -vn 0.770261 0.552287 -0.318868 -v 0.098753 0.089450 0.128750 -vn 0.707107 0.000001 0.707107 -v 0.098753 0.089374 0.131000 -vn 0.770259 0.318867 -0.552290 -v 0.098753 0.089999 0.129299 -vn 0.770265 0.000000 -0.637724 -v 0.098753 0.090749 0.129500 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.092124 0.115875 -vn 0.770259 -0.318867 0.552290 -v 0.098753 0.091499 0.126701 -vn 0.770265 -0.000000 0.637724 -v 0.098753 0.090749 0.126500 -vn 0.770259 0.318867 0.552290 -v 0.098753 0.089999 0.126701 -vn 0.770262 -0.552287 0.318866 -v 0.098753 0.084048 0.127250 -vn 0.770259 -0.318867 0.552290 -v 0.098753 0.083499 0.126701 -vn 0.770262 -0.552286 -0.318868 -v 0.098753 0.084048 0.128750 -vn 0.770263 -0.637727 -0.000002 -v 0.098753 0.084249 0.128000 -vn 0.770261 0.637729 -0.000002 -v 0.098753 0.081249 0.128000 -vn 0.707107 0.000000 0.707107 -v 0.098753 0.078499 0.131000 -vn 0.770264 0.552287 0.318863 -v 0.098753 0.081450 0.127250 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.078499 0.115875 -vn 0.770259 0.318867 0.552290 -v 0.098753 0.081999 0.126701 -vn 0.770265 -0.000000 0.637724 -v 0.098753 0.082749 0.126500 -vn 0.770263 0.552287 -0.318864 -v 0.098753 0.081450 0.128750 -vn 0.770259 0.318867 -0.552290 -v 0.098753 0.081999 0.129299 -vn 0.707107 0.000000 0.707107 -v 0.098753 0.082671 0.131000 -vn 0.770265 0.000000 -0.637724 -v 0.098753 0.082749 0.129500 -vn 0.770259 -0.318867 -0.552290 -v 0.098753 0.083499 0.129299 -vn 0.770259 -0.318867 -0.552290 -v 0.098753 0.099499 0.129299 -vn 0.770263 -0.552287 -0.318864 -v 0.098753 0.100048 0.128750 -vn 0.577350 0.577350 0.577350 -v 0.098753 0.105749 0.131000 -vn 0.770260 -0.637729 -0.000002 -v 0.098753 0.100249 0.128000 -vn 0.707107 0.707107 0.000000 -v 0.098753 0.105749 0.115875 -vn 0.770264 -0.552287 0.318863 -v 0.098753 0.100048 0.127250 -vn 0.770265 -0.000001 -0.637724 -v 0.098753 0.098749 0.129500 -vn 0.707107 0.000000 0.707107 -v 0.098753 0.098828 0.131000 -vn 0.770260 0.318868 -0.552288 -v 0.098753 0.097999 0.129299 -vn 0.707107 0.000000 0.707107 -v 0.098753 0.096624 0.131000 -vn 0.770261 0.552288 -0.318866 -v 0.098753 0.097450 0.128750 -vn 0.770262 0.552289 0.318864 -v 0.098753 0.097450 0.127250 -vn 0.770263 0.637727 -0.000002 -v 0.098753 0.097249 0.128000 -vn 0.770261 0.318868 0.552288 -v 0.098753 0.097999 0.126701 -vn 0.770262 -0.318863 0.552289 -v 0.098753 0.091374 0.102917 -vn 0.770262 -0.552289 0.318863 -v 0.098753 0.091832 0.103375 -vn 0.770261 -0.637729 0.000000 -v 0.098753 0.091999 0.104000 -vn 0.770261 0.000000 0.637728 -v 0.098753 0.090749 0.102750 -vn 0.770262 0.318863 0.552289 -v 0.098753 0.090124 0.102917 -vn 0.770261 -0.000000 -0.637728 -v 0.098753 0.090749 0.105250 -vn 0.770262 -0.318863 -0.552289 -v 0.098753 0.091374 0.105083 -vn 0.770262 -0.552289 -0.318863 -v 0.098753 0.091832 0.104625 -vn 0.744071 0.392699 -0.540505 -v 0.098753 0.087663 0.100247 -vn 0.770262 -0.552289 0.318863 -v 0.098753 0.086175 0.101032 -vn 0.770262 -0.318861 0.552291 -v 0.098753 0.085717 0.100574 -vn 0.770263 0.000006 0.637727 -v 0.098753 0.085092 0.100407 -vn 0.770262 0.318863 0.552289 -v 0.098753 0.084467 0.100574 -vn 0.770262 0.318863 -0.552288 -v 0.098753 0.090124 0.105083 -vn 0.770262 0.552289 0.318863 -v 0.098753 0.089667 0.103375 -vn 0.770261 0.637729 -0.000000 -v 0.098753 0.089499 0.104000 -vn 0.770262 0.552289 -0.318863 -v 0.098753 0.089667 0.104625 -vn 0.707107 0.707107 0.000000 -v 0.098753 0.105749 0.102000 -vn 1.000000 0.000000 0.000000 -v 0.098753 0.078499 0.102000 -vn 0.577350 -0.577350 0.577350 -v 0.098753 0.075749 0.131000 -vn 0.707107 -0.707107 0.000000 -v 0.098753 0.075749 0.115875 -vn 0.707107 -0.707107 0.000000 -v 0.098753 0.075749 0.102000 -vn 0.707107 -0.707107 0.000000 -v 0.098753 0.075749 0.098828 -vn -0.770259 0.318867 0.552290 -v 0.094753 0.081999 0.126701 -vn -0.770265 0.000000 0.637724 -v 0.094753 0.082749 0.126500 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.082671 0.115875 -vn -0.770263 0.552286 0.318866 -v 0.094753 0.089450 0.127250 -vn -1.000000 -0.000001 0.000000 -v 0.094753 0.089374 0.115875 -vn -1.000000 -0.000001 0.000000 -v 0.094753 0.084874 0.115875 -vn -0.744071 -0.392699 0.540505 -v 0.094753 0.093835 0.091753 -vn -1.000000 -0.000000 -0.000000 -v 0.094753 0.093703 0.090000 -vn -1.000000 0.000000 -0.000000 -v 0.094753 0.092124 0.090000 -vn -0.686917 0.537063 -0.489599 -v 0.094753 0.101834 0.085895 -vn -0.686916 0.437956 -0.579948 -v 0.094753 0.099789 0.084030 -vn -1.000000 -0.000000 -0.000000 -v 0.094753 0.098828 0.090000 -vn -0.686917 -0.677661 -0.262527 -v 0.094753 0.076762 0.090581 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.078499 0.090000 -vn -0.686917 -0.617883 -0.382577 -v 0.094753 0.077996 0.088104 -vn -0.770261 0.637728 0.000000 -v 0.094753 0.095156 0.090343 -vn -0.770262 0.552288 0.318863 -v 0.094753 0.095323 0.089718 -vn -0.744071 0.206455 -0.635401 -v 0.094753 0.089127 0.100993 -vn -0.744071 0.392699 -0.540505 -v 0.094753 0.087663 0.100247 -vn -0.770262 -0.552289 0.318863 -v 0.094753 0.086175 0.101032 -vn -0.770263 -0.318867 0.552285 -v 0.094753 0.085717 0.100574 -vn -0.744072 0.540503 -0.392700 -v 0.094753 0.086502 0.099086 -vn -0.770261 -0.000004 0.637729 -v 0.094753 0.085092 0.100407 -vn -1.000000 -0.000003 0.000001 -v 0.094753 0.084874 0.098828 -vn -0.770262 0.318863 0.552289 -v 0.094753 0.084467 0.100574 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.082671 0.098828 -vn -0.770262 0.552289 0.318863 -v 0.094753 0.084010 0.101032 -vn -0.770261 0.637728 0.000000 -v 0.094753 0.083842 0.101657 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.082671 0.102000 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.084010 0.102282 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.084467 0.102739 -vn -0.770260 -0.000005 -0.637730 -v 0.094753 0.085092 0.102907 -vn -0.770262 -0.318866 -0.552286 -v 0.094753 0.085717 0.102739 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.086175 0.102282 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.083832 0.096625 -vn -0.770262 -0.318863 -0.552289 -v 0.094753 0.083374 0.097083 -vn -0.770261 0.000000 -0.637728 -v 0.094753 0.082749 0.097250 -vn -0.770261 -0.637728 -0.000000 -v 0.094753 0.083999 0.096000 -vn -1.000000 -0.000003 -0.000000 -v 0.094753 0.084874 0.093172 -vn -0.770262 -0.552289 0.318863 -v 0.094753 0.083832 0.095375 -vn -0.770261 0.637728 0.000000 -v 0.094753 0.081499 0.096000 -vn -0.770262 0.552289 0.318863 -v 0.094753 0.081667 0.095375 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.078499 0.093172 -vn -0.770262 0.318863 0.552289 -v 0.094753 0.082124 0.094917 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.082671 0.093172 -vn -0.770261 -0.000000 0.637728 -v 0.094753 0.082749 0.094750 -vn -0.770262 -0.318863 0.552289 -v 0.094753 0.083374 0.094917 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.082124 0.097083 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.081667 0.096625 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.078499 0.098828 -vn -0.770263 -0.318866 0.552286 -v 0.094753 0.085717 0.089261 -vn -0.770262 -0.552289 0.318863 -v 0.094753 0.086175 0.089718 -vn -1.000000 -0.000000 -0.000000 -v 0.094753 0.089374 0.090000 -vn -0.770261 -0.637728 -0.000000 -v 0.094753 0.086342 0.090343 -vn -0.770262 -0.552289 0.318863 -v 0.094753 0.097489 0.089718 -vn -0.770261 -0.637728 -0.000000 -v 0.094753 0.097656 0.090343 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.098828 0.093172 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.097489 0.090968 -vn -0.770262 -0.318863 -0.552289 -v 0.094753 0.097031 0.091426 -vn -0.770262 -0.318863 0.552288 -v 0.094753 0.097031 0.089261 -vn -0.770262 0.000000 0.637728 -v 0.094753 0.096406 0.089093 -vn -0.686916 0.323934 -0.650548 -v 0.094753 0.097435 0.082573 -vn -0.770263 0.318863 0.552288 -v 0.094753 0.095781 0.089261 -vn -0.686917 0.198881 -0.698994 -v 0.094753 0.094854 0.081573 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.095323 0.090968 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.095781 0.091426 -vn -0.744071 -0.540505 0.392699 -v 0.094753 0.094996 0.092914 -vn -0.770261 0.000000 -0.637728 -v 0.094753 0.096406 0.091593 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.096624 0.093172 -vn -0.770261 -0.000000 0.637728 -v 0.094753 0.098749 0.094750 -vn -0.770262 -0.318863 0.552289 -v 0.094753 0.099374 0.094917 -vn -0.686917 0.714362 -0.133538 -v 0.094753 0.105494 0.093244 -vn -0.770262 -0.552288 0.318863 -v 0.094753 0.099832 0.095375 -vn -0.696858 0.716444 -0.033123 -v 0.094753 0.105749 0.096000 -vn -0.770261 -0.637728 -0.000000 -v 0.094753 0.099999 0.096000 -vn -0.707107 0.707107 0.000000 -v 0.094753 0.105749 0.098828 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.099832 0.096625 -vn -0.770262 -0.318863 -0.552289 -v 0.094753 0.099374 0.097083 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.098828 0.098828 -vn -0.770261 0.000000 -0.637728 -v 0.094753 0.098749 0.097250 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.096624 0.098828 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.098124 0.097083 -vn -0.770262 0.318863 0.552289 -v 0.094753 0.098124 0.094917 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.097667 0.096625 -vn -0.770261 0.637728 0.000000 -v 0.094753 0.097499 0.096000 -vn -0.770262 0.552289 0.318863 -v 0.094753 0.097667 0.095375 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.098828 0.102000 -vn -0.770262 -0.552289 0.318863 -v 0.094753 0.097489 0.101032 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.095781 0.102739 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.095323 0.102282 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.093703 0.102000 -vn -0.770261 0.637728 0.000000 -v 0.094753 0.095156 0.101657 -vn -0.744071 -0.392699 -0.540505 -v 0.094753 0.093835 0.100247 -vn -0.770262 0.552289 0.318863 -v 0.094753 0.095323 0.101032 -vn -0.744071 -0.540505 -0.392699 -v 0.094753 0.094996 0.099086 -vn -0.770262 0.318863 0.552289 -v 0.094753 0.095781 0.100574 -vn -0.770261 -0.000000 0.637728 -v 0.094753 0.096406 0.100407 -vn -0.770262 -0.318863 0.552289 -v 0.094753 0.097031 0.100574 -vn -0.770261 -0.637728 -0.000000 -v 0.094753 0.097656 0.101657 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.097489 0.102282 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.098828 0.115875 -vn -0.770262 -0.318863 -0.552289 -v 0.094753 0.097031 0.102739 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.096624 0.115875 -vn -0.770261 0.000000 -0.637728 -v 0.094753 0.096406 0.102907 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.093703 0.115875 -vn -0.686917 -0.714362 -0.133537 -v 0.094753 0.076005 0.093244 -vn -0.696858 -0.716444 -0.033123 -v 0.094753 0.075749 0.096000 -vn -0.686917 -0.537064 -0.489599 -v 0.094753 0.079664 0.085895 -vn -1.000000 0.000000 -0.000000 -v 0.094753 0.082671 0.090000 -vn -0.686917 -0.437956 -0.579949 -v 0.094753 0.081710 0.084030 -vn -0.770265 0.637723 -0.000001 -v 0.094753 0.089499 0.088000 -vn -0.770263 0.552287 0.318863 -v 0.094753 0.089667 0.087375 -vn -0.686916 -0.067055 -0.723636 -v 0.094753 0.089365 0.081064 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.089667 0.088625 -vn -0.686917 -0.198881 -0.698993 -v 0.094753 0.086644 0.081573 -vn -0.770261 -0.000005 0.637729 -v 0.094753 0.085092 0.089093 -vn -0.686916 -0.323935 -0.650548 -v 0.094753 0.084063 0.082573 -vn -0.770262 0.318863 0.552288 -v 0.094753 0.084467 0.089261 -vn -0.770262 0.552288 0.318863 -v 0.094753 0.084010 0.089718 -vn -0.770261 0.637728 0.000000 -v 0.094753 0.083842 0.090343 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.084010 0.090968 -vn -0.770263 0.318863 0.552288 -v 0.094753 0.090124 0.086917 -vn -0.770262 -0.000000 0.637728 -v 0.094753 0.090749 0.086750 -vn -0.686916 0.067055 -0.723636 -v 0.094753 0.092133 0.081064 -vn -0.770263 -0.318863 0.552288 -v 0.094753 0.091374 0.086917 -vn -0.770263 -0.552287 0.318863 -v 0.094753 0.091832 0.087375 -vn -0.770265 -0.637723 -0.000001 -v 0.094753 0.091999 0.088000 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.091832 0.088625 -vn -0.770262 -0.318863 -0.552289 -v 0.094753 0.091374 0.089083 -vn -0.770261 0.000000 -0.637728 -v 0.094753 0.090749 0.089250 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.090124 0.089083 -vn -0.686917 0.677661 -0.262527 -v 0.094753 0.104736 0.090581 -vn -0.686917 0.617884 -0.382577 -v 0.094753 0.103502 0.088104 -vn -0.744071 -0.635401 0.206455 -v 0.094753 0.095742 0.094378 -vn -0.744071 -0.668100 -0.000000 -v 0.094753 0.095999 0.096000 -vn -0.744071 -0.635401 -0.206455 -v 0.094753 0.095742 0.097622 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.084467 0.091426 -vn -0.770260 -0.000006 -0.637730 -v 0.094753 0.085092 0.091593 -vn -0.770263 -0.318866 -0.552286 -v 0.094753 0.085717 0.091426 -vn -0.744072 0.540503 0.392700 -v 0.094753 0.086502 0.092914 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.086175 0.090968 -vn -0.744071 0.392699 0.540505 -v 0.094753 0.087663 0.091753 -vn -0.744071 0.206455 0.635401 -v 0.094753 0.089127 0.091007 -vn -0.744071 -0.000000 0.668100 -v 0.094753 0.090749 0.090750 -vn -0.744071 -0.206455 0.635401 -v 0.094753 0.092372 0.091007 -vn -0.744073 0.635399 -0.206454 -v 0.094753 0.085756 0.097622 -vn -0.744075 0.668096 0.000000 -v 0.094753 0.085499 0.096000 -vn -0.744073 0.635399 0.206454 -v 0.094753 0.085756 0.094378 -vn -0.770261 -0.637728 -0.000000 -v 0.094753 0.086342 0.101657 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.089374 0.102000 -vn -0.744071 0.000000 -0.668100 -v 0.094753 0.090749 0.101250 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.092124 0.102000 -vn -0.744071 -0.206455 -0.635401 -v 0.094753 0.092372 0.100993 -vn -0.707107 0.000000 0.707107 -v 0.094753 0.092124 0.131000 -vn -0.707107 0.000000 0.707107 -v 0.094753 0.093703 0.131000 -vn -0.770262 -0.552286 -0.318868 -v 0.094753 0.092048 0.128750 -vn -0.770263 -0.637727 -0.000002 -v 0.094753 0.092249 0.128000 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.092124 0.115875 -vn -0.770262 -0.552287 0.318866 -v 0.094753 0.092048 0.127250 -vn -0.770259 0.318867 0.552290 -v 0.094753 0.089999 0.126701 -vn -0.770265 0.000000 0.637724 -v 0.094753 0.090749 0.126500 -vn -0.770259 -0.318867 0.552290 -v 0.094753 0.091499 0.126701 -vn -0.770264 0.637726 -0.000002 -v 0.094753 0.089249 0.128000 -vn -0.707107 -0.000001 0.707107 -v 0.094753 0.084874 0.131000 -vn -0.770262 0.552286 -0.318868 -v 0.094753 0.089450 0.128750 -vn -0.707107 -0.000001 0.707107 -v 0.094753 0.089374 0.131000 -vn -0.770259 -0.318867 -0.552290 -v 0.094753 0.091499 0.129299 -vn -0.770265 -0.000000 -0.637724 -v 0.094753 0.090749 0.129500 -vn -0.770259 0.318867 -0.552290 -v 0.094753 0.089999 0.129299 -vn -0.770259 -0.318867 0.552290 -v 0.094753 0.083499 0.126701 -vn -0.770262 -0.552287 0.318866 -v 0.094753 0.084048 0.127250 -vn -0.770263 -0.637727 -0.000002 -v 0.094753 0.084249 0.128000 -vn -0.770263 0.552287 -0.318864 -v 0.094753 0.081450 0.128750 -vn -0.770260 0.637729 -0.000002 -v 0.094753 0.081249 0.128000 -vn -0.707107 0.000000 0.707107 -v 0.094753 0.078499 0.131000 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.078499 0.115875 -vn -0.770264 0.552287 0.318863 -v 0.094753 0.081450 0.127250 -vn -0.770262 -0.552286 -0.318868 -v 0.094753 0.084048 0.128750 -vn -0.770259 -0.318867 -0.552290 -v 0.094753 0.083499 0.129299 -vn -0.707107 0.000000 0.707107 -v 0.094753 0.082671 0.131000 -vn -0.770265 -0.000000 -0.637724 -v 0.094753 0.082749 0.129500 -vn -0.770259 0.318867 -0.552290 -v 0.094753 0.081999 0.129299 -vn -0.770260 -0.637729 -0.000002 -v 0.094753 0.100249 0.128000 -vn -0.577350 0.577350 0.577350 -v 0.094753 0.105749 0.131000 -vn -0.770264 -0.552287 0.318863 -v 0.094753 0.100048 0.127250 -vn -0.707107 0.707107 0.000000 -v 0.094753 0.105749 0.115875 -vn -0.770259 -0.318867 0.552290 -v 0.094753 0.099499 0.126701 -vn -0.770265 -0.000001 0.637724 -v 0.094753 0.098749 0.126500 -vn -0.770263 -0.552287 -0.318864 -v 0.094753 0.100048 0.128750 -vn -0.770259 -0.318867 -0.552290 -v 0.094753 0.099499 0.129299 -vn -0.707107 0.000000 0.707107 -v 0.094753 0.098828 0.131000 -vn -0.770265 -0.000001 -0.637724 -v 0.094753 0.098749 0.129500 -vn -0.707107 0.000000 0.707107 -v 0.094753 0.096624 0.131000 -vn -0.770261 0.318868 -0.552288 -v 0.094753 0.097999 0.129299 -vn -0.770261 0.552288 -0.318866 -v 0.094753 0.097450 0.128750 -vn -0.770260 0.318868 0.552288 -v 0.094753 0.097999 0.126701 -vn -0.770262 0.552288 0.318864 -v 0.094753 0.097450 0.127250 -vn -0.770263 0.637727 -0.000002 -v 0.094753 0.097249 0.128000 -vn -0.707107 0.707107 0.000000 -v 0.094753 0.105749 0.102000 -vn -0.770261 0.637729 0.000000 -v 0.094753 0.089499 0.104000 -vn -0.770262 0.552289 0.318863 -v 0.094753 0.089667 0.103375 -vn -0.770261 -0.637729 -0.000000 -v 0.094753 0.091999 0.104000 -vn -0.770262 -0.552289 -0.318863 -v 0.094753 0.091832 0.104625 -vn -0.770262 0.552289 -0.318863 -v 0.094753 0.089667 0.104625 -vn -0.770262 0.318863 0.552289 -v 0.094753 0.090124 0.102917 -vn -0.770261 -0.000000 0.637728 -v 0.094753 0.090749 0.102750 -vn -0.770262 -0.318863 0.552289 -v 0.094753 0.091374 0.102917 -vn -0.770262 -0.552289 0.318863 -v 0.094753 0.091832 0.103375 -vn -0.770262 -0.318863 -0.552289 -v 0.094753 0.091374 0.105083 -vn -0.770261 0.000000 -0.637728 -v 0.094753 0.090749 0.105250 -vn -0.770262 0.318863 -0.552289 -v 0.094753 0.090124 0.105083 -vn -1.000000 0.000000 0.000000 -v 0.094753 0.078499 0.102000 -vn -0.707107 -0.707107 0.000000 -v 0.094753 0.075749 0.098828 -vn -0.707107 -0.707107 0.000000 -v 0.094753 0.075749 0.102000 -vn -0.707107 -0.707107 0.000000 -v 0.094753 0.075749 0.115875 -vn -0.577350 -0.577350 0.577350 -v 0.094753 0.075749 0.131000 -vn 0.770259 -0.318867 0.552290 -v 0.056453 0.099499 0.126701 -vn 0.770265 -0.000001 0.637724 -v 0.056453 0.098749 0.126500 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.098828 0.115875 -vn 0.686917 -0.677661 -0.262527 -v 0.056453 0.076762 0.090581 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.078499 0.090000 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.078499 0.093172 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.091832 0.088625 -vn 0.770261 -0.637729 0.000000 -v 0.056453 0.091999 0.088000 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.092124 0.090000 -vn 0.686917 0.617883 -0.382577 -v 0.056453 0.103502 0.088104 -vn 0.686917 0.677661 -0.262527 -v 0.056453 0.104736 0.090581 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.098828 0.090000 -vn 0.770261 -0.637728 0.000000 -v 0.056453 0.097656 0.090343 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.097489 0.089718 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.089374 0.102000 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.086175 0.102282 -vn 0.770261 -0.637728 0.000000 -v 0.056453 0.086342 0.101657 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.085717 0.102739 -vn 1.000000 -0.000000 0.000000 -v 0.056453 0.089374 0.115875 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.085092 0.102907 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.084874 0.115875 -vn 0.770262 0.318863 -0.552289 -v 0.056453 0.084467 0.102739 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.082671 0.115875 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.082671 0.102000 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.084010 0.102282 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.082671 0.098828 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.084010 0.101032 -vn 0.770261 0.637728 -0.000000 -v 0.056453 0.083842 0.101657 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.084874 0.093172 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.085092 0.091593 -vn 0.744071 0.540505 0.392699 -v 0.056453 0.086502 0.092914 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.085717 0.091426 -vn 0.744071 0.392699 0.540505 -v 0.056453 0.087663 0.091753 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.086175 0.090968 -vn 0.744071 0.206455 0.635401 -v 0.056453 0.089127 0.091007 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.084467 0.089261 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.084010 0.089718 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.082671 0.090000 -vn 0.770261 0.637728 -0.000000 -v 0.056453 0.083842 0.090343 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.082671 0.093172 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.084010 0.090968 -vn 0.770262 0.318863 -0.552289 -v 0.056453 0.084467 0.091426 -vn 0.686917 -0.437956 -0.579948 -v 0.056453 0.081710 0.084030 -vn 0.686917 -0.323934 -0.650548 -v 0.056453 0.084063 0.082573 -vn 0.770261 0.000000 0.637728 -v 0.056453 0.085092 0.089093 -vn 0.686917 -0.198881 -0.698993 -v 0.056453 0.086644 0.081573 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.085717 0.089261 -vn 0.686917 -0.067055 -0.723636 -v 0.056453 0.089365 0.081064 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.086175 0.089718 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.089374 0.090000 -vn 0.770261 -0.637728 0.000000 -v 0.056453 0.086342 0.090343 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.097489 0.090968 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.093703 0.090000 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.095323 0.089718 -vn 0.770261 0.637728 -0.000000 -v 0.056453 0.095156 0.090343 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.097031 0.091426 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.098828 0.093172 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.096406 0.091593 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.096624 0.093172 -vn 0.770262 0.318863 -0.552289 -v 0.056453 0.095781 0.091426 -vn 0.744071 -0.540505 0.392699 -v 0.056453 0.094996 0.092914 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.095323 0.090968 -vn 0.744071 -0.392699 0.540505 -v 0.056453 0.093835 0.091753 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.095781 0.089261 -vn 0.686917 0.198881 -0.698993 -v 0.056453 0.094854 0.081573 -vn 0.770261 0.000000 0.637729 -v 0.056453 0.096406 0.089093 -vn 0.686917 0.323934 -0.650548 -v 0.056453 0.097435 0.082573 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.097031 0.089261 -vn 0.686917 0.437956 -0.579948 -v 0.056453 0.099789 0.084030 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.098828 0.102000 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.097489 0.102282 -vn 0.770261 -0.637728 0.000000 -v 0.056453 0.097656 0.101657 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.098828 0.098828 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.097489 0.101032 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.097031 0.100574 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.097031 0.102739 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.096406 0.102907 -vn 1.000000 -0.000000 0.000000 -v 0.056453 0.096624 0.115875 -vn 0.770262 0.318863 -0.552289 -v 0.056453 0.095781 0.102739 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.093703 0.115875 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.095323 0.102282 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.095323 0.101032 -vn 0.770261 0.637728 -0.000000 -v 0.056453 0.095156 0.101657 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.093703 0.102000 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.096624 0.098828 -vn 0.770261 0.000000 0.637728 -v 0.056453 0.096406 0.100407 -vn 0.744071 -0.540505 -0.392699 -v 0.056453 0.094996 0.099086 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.095781 0.100574 -vn 0.744071 -0.392699 -0.540505 -v 0.056453 0.093835 0.100247 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.098749 0.097250 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.099374 0.097083 -vn 0.707107 0.707107 0.000000 -v 0.056453 0.105749 0.098828 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.099832 0.096625 -vn 0.696858 0.716444 -0.033123 -v 0.056453 0.105749 0.096000 -vn 0.770261 -0.637728 0.000000 -v 0.056453 0.099999 0.096000 -vn 0.686917 0.714362 -0.133538 -v 0.056453 0.105494 0.093244 -vn 0.686917 0.537064 -0.489599 -v 0.056453 0.101834 0.085895 -vn 0.686917 0.067055 -0.723636 -v 0.056453 0.092133 0.081064 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.091832 0.087375 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.091374 0.086917 -vn 0.770261 0.000000 0.637728 -v 0.056453 0.090749 0.086750 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.090124 0.086917 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.089667 0.087375 -vn 0.770261 0.637729 -0.000000 -v 0.056453 0.089499 0.088000 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.089667 0.088625 -vn 0.770262 0.318863 -0.552289 -v 0.056453 0.090124 0.089083 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.090749 0.089250 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.091374 0.089083 -vn 0.686917 -0.537065 -0.489599 -v 0.056453 0.079664 0.085895 -vn 0.686917 -0.617883 -0.382577 -v 0.056453 0.077996 0.088104 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.078499 0.098828 -vn 0.696858 -0.716444 -0.033123 -v 0.056453 0.075749 0.096000 -vn 0.686917 -0.714362 -0.133537 -v 0.056453 0.076005 0.093244 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.099832 0.095375 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.099374 0.094917 -vn 0.770261 0.000000 0.637728 -v 0.056453 0.098749 0.094750 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.098124 0.094917 -vn 0.770262 0.318863 -0.552289 -v 0.056453 0.098124 0.097083 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.097667 0.095375 -vn 0.770261 0.637728 -0.000000 -v 0.056453 0.097499 0.096000 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.097667 0.096625 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.083374 0.097083 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.084874 0.098828 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.082749 0.097250 -vn 0.770262 0.318863 -0.552289 -v 0.056453 0.082124 0.097083 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.083374 0.094917 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.083832 0.096625 -vn 0.770261 -0.637728 0.000000 -v 0.056453 0.083999 0.096000 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.083832 0.095375 -vn 0.770261 0.000000 0.637728 -v 0.056453 0.082749 0.094750 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.082124 0.094917 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.081667 0.095375 -vn 0.770261 0.637728 -0.000000 -v 0.056453 0.081499 0.096000 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.081667 0.096625 -vn 0.744071 -0.635401 -0.206455 -v 0.056453 0.095742 0.097622 -vn 0.744071 -0.668100 0.000000 -v 0.056453 0.095999 0.096000 -vn 0.744071 -0.635401 0.206455 -v 0.056453 0.095742 0.094378 -vn 0.744071 0.206455 -0.635401 -v 0.056453 0.089127 0.100993 -vn 0.744071 -0.000000 -0.668100 -v 0.056453 0.090749 0.101250 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.092124 0.102000 -vn 0.744071 -0.206455 -0.635401 -v 0.056453 0.092371 0.100993 -vn 0.744071 0.635401 0.206455 -v 0.056453 0.085756 0.094378 -vn 0.744071 0.668100 -0.000000 -v 0.056453 0.085499 0.096000 -vn 0.744071 0.635401 -0.206455 -v 0.056453 0.085756 0.097622 -vn 0.744071 0.540505 -0.392699 -v 0.056453 0.086502 0.099086 -vn 0.744071 0.000000 0.668100 -v 0.056453 0.090749 0.090750 -vn 0.744071 -0.206455 0.635401 -v 0.056453 0.092371 0.091007 -vn 0.770263 -0.637727 -0.000001 -v 0.056453 0.092249 0.128000 -vn 0.707107 -0.000000 0.707107 -v 0.056453 0.093703 0.131000 -vn 0.770262 -0.552286 -0.318868 -v 0.056453 0.092048 0.128750 -vn 0.707107 0.000000 0.707107 -v 0.056453 0.092124 0.131000 -vn 0.770259 -0.318867 -0.552290 -v 0.056453 0.091499 0.129299 -vn 0.770266 -0.552281 0.318868 -v 0.056453 0.092048 0.127250 -vn 0.770263 0.552286 0.318866 -v 0.056453 0.089450 0.127250 -vn 0.770261 0.637728 0.000002 -v 0.056453 0.089249 0.128000 -vn 0.707107 -0.000000 0.707107 -v 0.056453 0.084874 0.131000 -vn 0.770262 0.552286 -0.318868 -v 0.056453 0.089450 0.128750 -vn 0.707107 0.000000 0.707107 -v 0.056453 0.089374 0.131000 -vn 0.770259 0.318867 -0.552290 -v 0.056453 0.089999 0.129299 -vn 0.770265 0.000000 -0.637724 -v 0.056453 0.090749 0.129500 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.092124 0.115875 -vn 0.770259 -0.318867 0.552290 -v 0.056453 0.091499 0.126701 -vn 0.770265 -0.000000 0.637724 -v 0.056453 0.090749 0.126500 -vn 0.770259 0.318867 0.552290 -v 0.056453 0.089999 0.126701 -vn 0.770266 -0.552280 0.318868 -v 0.056453 0.084048 0.127250 -vn 0.770259 -0.318867 0.552290 -v 0.056453 0.083499 0.126701 -vn 0.770262 -0.552286 -0.318868 -v 0.056453 0.084048 0.128750 -vn 0.770262 -0.637727 -0.000001 -v 0.056453 0.084249 0.128000 -vn 0.770258 0.637733 0.000003 -v 0.056453 0.081249 0.128000 -vn 0.707107 -0.000000 0.707107 -v 0.056453 0.078499 0.131000 -vn 0.770264 0.552286 0.318863 -v 0.056453 0.081450 0.127250 -vn 1.000000 -0.000000 0.000000 -v 0.056453 0.078499 0.115875 -vn 0.770259 0.318867 0.552290 -v 0.056453 0.081999 0.126701 -vn 0.770265 -0.000000 0.637724 -v 0.056453 0.082749 0.126500 -vn 0.770263 0.552287 -0.318864 -v 0.056453 0.081450 0.128750 -vn 0.770259 0.318867 -0.552290 -v 0.056453 0.081999 0.129299 -vn 0.707107 0.000000 0.707107 -v 0.056453 0.082671 0.131000 -vn 0.770265 0.000000 -0.637724 -v 0.056453 0.082749 0.129500 -vn 0.770259 -0.318867 -0.552290 -v 0.056453 0.083499 0.129299 -vn 0.770259 -0.318867 -0.552290 -v 0.056453 0.099499 0.129299 -vn 0.770263 -0.552287 -0.318864 -v 0.056453 0.100048 0.128750 -vn 0.577350 0.577350 0.577350 -v 0.056453 0.105749 0.131000 -vn 0.770260 -0.637730 -0.000001 -v 0.056453 0.100249 0.128000 -vn 0.707107 0.707107 0.000000 -v 0.056453 0.105749 0.115875 -vn 0.770265 -0.552284 0.318865 -v 0.056453 0.100048 0.127250 -vn 0.770265 -0.000001 -0.637724 -v 0.056453 0.098749 0.129500 -vn 0.707107 0.000000 0.707107 -v 0.056453 0.098828 0.131000 -vn 0.770260 0.318868 -0.552288 -v 0.056453 0.097999 0.129299 -vn 0.707107 0.000000 0.707107 -v 0.056453 0.096624 0.131000 -vn 0.770261 0.552288 -0.318866 -v 0.056453 0.097450 0.128750 -vn 0.770266 0.552282 0.318866 -v 0.056453 0.097450 0.127250 -vn 0.770262 0.637727 -0.000001 -v 0.056453 0.097249 0.128000 -vn 0.770261 0.318868 0.552288 -v 0.056453 0.097999 0.126701 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.091374 0.102917 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.091832 0.103375 -vn 0.770261 -0.637729 0.000000 -v 0.056453 0.091999 0.104000 -vn 0.770261 0.000000 0.637728 -v 0.056453 0.090749 0.102750 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.090124 0.102917 -vn 0.770261 -0.000000 -0.637728 -v 0.056453 0.090749 0.105250 -vn 0.770262 -0.318863 -0.552289 -v 0.056453 0.091374 0.105083 -vn 0.770262 -0.552289 -0.318863 -v 0.056453 0.091832 0.104625 -vn 0.744071 0.392699 -0.540505 -v 0.056453 0.087663 0.100247 -vn 0.770262 -0.552289 0.318863 -v 0.056453 0.086175 0.101032 -vn 0.770262 -0.318863 0.552289 -v 0.056453 0.085717 0.100574 -vn 0.770261 0.000000 0.637728 -v 0.056453 0.085092 0.100407 -vn 0.770262 0.318863 0.552289 -v 0.056453 0.084467 0.100574 -vn 0.770262 0.318863 -0.552288 -v 0.056453 0.090124 0.105083 -vn 0.770262 0.552289 0.318863 -v 0.056453 0.089667 0.103375 -vn 0.770261 0.637729 -0.000000 -v 0.056453 0.089499 0.104000 -vn 0.770262 0.552289 -0.318863 -v 0.056453 0.089667 0.104625 -vn 0.707107 0.707107 0.000000 -v 0.056453 0.105749 0.102000 -vn 1.000000 0.000000 0.000000 -v 0.056453 0.078499 0.102000 -vn 0.577350 -0.577350 0.577350 -v 0.056453 0.075749 0.131000 -vn 0.707107 -0.707107 0.000000 -v 0.056453 0.075749 0.115875 -vn 0.707107 -0.707107 0.000000 -v 0.056453 0.075749 0.102000 -vn 0.707107 -0.707107 0.000000 -v 0.056453 0.075749 0.098828 -vn -0.770259 0.318867 0.552290 -v 0.052453 0.081999 0.126701 -vn -0.770265 0.000000 0.637724 -v 0.052453 0.082749 0.126500 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.082671 0.115875 -vn -0.770262 0.552287 0.318865 -v 0.052453 0.089450 0.127250 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.089374 0.115875 -vn -1.000000 -0.000000 -0.000000 -v 0.052453 0.084874 0.115875 -vn -0.744071 -0.392699 0.540505 -v 0.052453 0.093835 0.091753 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.093703 0.090000 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.092124 0.090000 -vn -0.686917 0.537064 -0.489599 -v 0.052453 0.101834 0.085895 -vn -0.686917 0.437956 -0.579948 -v 0.052453 0.099789 0.084030 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.098828 0.090000 -vn -0.686917 -0.677661 -0.262527 -v 0.052453 0.076762 0.090581 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.078499 0.090000 -vn -0.686917 -0.617883 -0.382577 -v 0.052453 0.077996 0.088104 -vn -0.770261 0.637728 0.000000 -v 0.052453 0.095156 0.090343 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.095323 0.089718 -vn -0.744071 0.206455 -0.635401 -v 0.052453 0.089127 0.100993 -vn -0.744071 0.392699 -0.540505 -v 0.052453 0.087663 0.100247 -vn -0.770262 -0.552289 0.318863 -v 0.052453 0.086175 0.101032 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.085717 0.100574 -vn -0.744071 0.540505 -0.392699 -v 0.052453 0.086502 0.099086 -vn -0.770261 -0.000000 0.637728 -v 0.052453 0.085092 0.100407 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.084874 0.098828 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.084467 0.100574 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.082671 0.098828 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.084010 0.101032 -vn -0.770261 0.637728 0.000000 -v 0.052453 0.083842 0.101657 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.082671 0.102000 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.084010 0.102282 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.084467 0.102739 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.085092 0.102907 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.085717 0.102739 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.086175 0.102282 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.083832 0.096625 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.083374 0.097083 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.082749 0.097250 -vn -0.770261 -0.637728 -0.000000 -v 0.052453 0.083999 0.096000 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.084874 0.093172 -vn -0.770262 -0.552289 0.318863 -v 0.052453 0.083832 0.095375 -vn -0.770261 0.637728 0.000000 -v 0.052453 0.081499 0.096000 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.081667 0.095375 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.078499 0.093172 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.082124 0.094917 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.082671 0.093172 -vn -0.770261 -0.000000 0.637728 -v 0.052453 0.082749 0.094750 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.083374 0.094917 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.082124 0.097083 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.081667 0.096625 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.078499 0.098828 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.085717 0.089261 -vn -0.770262 -0.552289 0.318863 -v 0.052453 0.086175 0.089718 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.089374 0.090000 -vn -0.770261 -0.637728 -0.000000 -v 0.052453 0.086342 0.090343 -vn -0.770262 -0.552289 0.318863 -v 0.052453 0.097489 0.089718 -vn -0.770261 -0.637728 -0.000000 -v 0.052453 0.097656 0.090343 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.098828 0.093172 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.097489 0.090968 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.097031 0.091426 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.097031 0.089261 -vn -0.770261 -0.000000 0.637728 -v 0.052453 0.096406 0.089093 -vn -0.686917 0.323934 -0.650548 -v 0.052453 0.097435 0.082573 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.095781 0.089261 -vn -0.686917 0.198881 -0.698993 -v 0.052453 0.094854 0.081573 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.095323 0.090968 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.095781 0.091426 -vn -0.744071 -0.540505 0.392699 -v 0.052453 0.094996 0.092914 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.096406 0.091593 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.096624 0.093172 -vn -0.770261 -0.000000 0.637728 -v 0.052453 0.098749 0.094750 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.099374 0.094917 -vn -0.686917 0.714362 -0.133538 -v 0.052453 0.105494 0.093244 -vn -0.770262 -0.552288 0.318863 -v 0.052453 0.099832 0.095375 -vn -0.696858 0.716444 -0.033123 -v 0.052453 0.105749 0.096000 -vn -0.770261 -0.637728 -0.000000 -v 0.052453 0.099999 0.096000 -vn -0.707107 0.707107 0.000000 -v 0.052453 0.105749 0.098828 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.099832 0.096625 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.099374 0.097083 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.098828 0.098828 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.098749 0.097250 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.096624 0.098828 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.098124 0.097083 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.098124 0.094917 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.097667 0.096625 -vn -0.770261 0.637728 0.000000 -v 0.052453 0.097499 0.096000 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.097667 0.095375 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.098828 0.102000 -vn -0.770262 -0.552289 0.318863 -v 0.052453 0.097489 0.101032 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.095781 0.102739 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.095323 0.102282 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.093703 0.102000 -vn -0.770261 0.637728 0.000000 -v 0.052453 0.095156 0.101657 -vn -0.744071 -0.392699 -0.540505 -v 0.052453 0.093835 0.100247 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.095323 0.101032 -vn -0.744071 -0.540505 -0.392699 -v 0.052453 0.094996 0.099086 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.095781 0.100574 -vn -0.770261 -0.000000 0.637728 -v 0.052453 0.096406 0.100407 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.097031 0.100574 -vn -0.770261 -0.637728 -0.000000 -v 0.052453 0.097656 0.101657 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.097489 0.102282 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.098828 0.115875 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.097031 0.102739 -vn -1.000000 0.000000 -0.000000 -v 0.052453 0.096624 0.115875 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.096406 0.102907 -vn -1.000000 -0.000000 -0.000000 -v 0.052453 0.093703 0.115875 -vn -0.686917 -0.714362 -0.133537 -v 0.052453 0.076005 0.093244 -vn -0.696858 -0.716444 -0.033123 -v 0.052453 0.075749 0.096000 -vn -0.686917 -0.537065 -0.489599 -v 0.052453 0.079664 0.085895 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.082671 0.090000 -vn -0.686917 -0.437956 -0.579948 -v 0.052453 0.081710 0.084030 -vn -0.770261 0.637729 0.000000 -v 0.052453 0.089499 0.088000 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.089667 0.087375 -vn -0.686917 -0.067055 -0.723636 -v 0.052453 0.089365 0.081064 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.089667 0.088625 -vn -0.686917 -0.198881 -0.698993 -v 0.052453 0.086644 0.081573 -vn -0.770261 -0.000000 0.637729 -v 0.052453 0.085092 0.089093 -vn -0.686917 -0.323934 -0.650548 -v 0.052453 0.084063 0.082573 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.084467 0.089261 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.084010 0.089718 -vn -0.770261 0.637728 0.000000 -v 0.052453 0.083842 0.090343 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.084010 0.090968 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.090124 0.086917 -vn -0.770261 -0.000000 0.637728 -v 0.052453 0.090749 0.086750 -vn -0.686917 0.067055 -0.723636 -v 0.052453 0.092133 0.081064 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.091374 0.086917 -vn -0.770262 -0.552289 0.318863 -v 0.052453 0.091832 0.087375 -vn -0.770261 -0.637729 -0.000000 -v 0.052453 0.091999 0.088000 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.091832 0.088625 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.091374 0.089083 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.090749 0.089250 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.090124 0.089083 -vn -0.686917 0.677661 -0.262527 -v 0.052453 0.104736 0.090581 -vn -0.686917 0.617884 -0.382577 -v 0.052453 0.103502 0.088104 -vn -0.744071 -0.635401 0.206455 -v 0.052453 0.095742 0.094378 -vn -0.744071 -0.668100 -0.000000 -v 0.052453 0.095999 0.096000 -vn -0.744071 -0.635401 -0.206455 -v 0.052453 0.095742 0.097622 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.084467 0.091426 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.085092 0.091593 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.085717 0.091426 -vn -0.744071 0.540505 0.392699 -v 0.052453 0.086502 0.092914 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.086175 0.090968 -vn -0.744071 0.392699 0.540505 -v 0.052453 0.087663 0.091753 -vn -0.744071 0.206455 0.635401 -v 0.052453 0.089127 0.091007 -vn -0.744071 -0.000000 0.668100 -v 0.052453 0.090749 0.090750 -vn -0.744071 -0.206455 0.635401 -v 0.052453 0.092371 0.091007 -vn -0.744071 0.635401 -0.206455 -v 0.052453 0.085756 0.097622 -vn -0.744071 0.668100 0.000000 -v 0.052453 0.085499 0.096000 -vn -0.744071 0.635401 0.206455 -v 0.052453 0.085756 0.094378 -vn -0.770261 -0.637728 -0.000000 -v 0.052453 0.086342 0.101657 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.089374 0.102000 -vn -0.744071 0.000000 -0.668100 -v 0.052453 0.090749 0.101250 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.092124 0.102000 -vn -0.744071 -0.206455 -0.635401 -v 0.052453 0.092371 0.100993 -vn -0.707107 0.000000 0.707107 -v 0.052453 0.092124 0.131000 -vn -0.707107 0.000000 0.707107 -v 0.052453 0.093703 0.131000 -vn -0.770262 -0.552286 -0.318868 -v 0.052453 0.092048 0.128750 -vn -0.770263 -0.637726 -0.000002 -v 0.052453 0.092249 0.128000 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.092124 0.115875 -vn -0.770259 -0.552292 0.318864 -v 0.052453 0.092048 0.127250 -vn -0.770259 0.318867 0.552290 -v 0.052453 0.089999 0.126701 -vn -0.770265 0.000000 0.637724 -v 0.052453 0.090749 0.126500 -vn -0.770259 -0.318867 0.552290 -v 0.052453 0.091499 0.126701 -vn -0.770264 0.637725 -0.000005 -v 0.052453 0.089249 0.128000 -vn -0.707107 0.000000 0.707107 -v 0.052453 0.084874 0.131000 -vn -0.770262 0.552286 -0.318868 -v 0.052453 0.089450 0.128750 -vn -0.707107 0.000000 0.707107 -v 0.052453 0.089374 0.131000 -vn -0.770259 -0.318867 -0.552290 -v 0.052453 0.091499 0.129299 -vn -0.770265 -0.000000 -0.637724 -v 0.052453 0.090749 0.129500 -vn -0.770259 0.318867 -0.552290 -v 0.052453 0.089999 0.129299 -vn -0.770259 -0.318867 0.552290 -v 0.052453 0.083499 0.126701 -vn -0.770258 -0.552293 0.318864 -v 0.052453 0.084048 0.127250 -vn -0.770263 -0.637726 -0.000002 -v 0.052453 0.084249 0.128000 -vn -0.770263 0.552287 -0.318864 -v 0.052453 0.081450 0.128750 -vn -0.770261 0.637729 -0.000002 -v 0.052453 0.081249 0.128000 -vn -0.707107 -0.000000 0.707107 -v 0.052453 0.078499 0.131000 -vn -1.000000 0.000000 -0.000000 -v 0.052453 0.078499 0.115875 -vn -0.770261 0.552291 0.318860 -v 0.052453 0.081450 0.127250 -vn -0.770262 -0.552286 -0.318868 -v 0.052453 0.084048 0.128750 -vn -0.770259 -0.318867 -0.552290 -v 0.052453 0.083499 0.129299 -vn -0.707107 0.000000 0.707107 -v 0.052453 0.082671 0.131000 -vn -0.770265 -0.000000 -0.637724 -v 0.052453 0.082749 0.129500 -vn -0.770259 0.318867 -0.552290 -v 0.052453 0.081999 0.129299 -vn -0.770262 -0.637728 -0.000005 -v 0.052453 0.100249 0.128000 -vn -0.577350 0.577350 0.577350 -v 0.052453 0.105749 0.131000 -vn -0.770263 -0.552287 0.318862 -v 0.052453 0.100048 0.127250 -vn -0.707107 0.707107 -0.000000 -v 0.052453 0.105749 0.115875 -vn -0.770259 -0.318867 0.552290 -v 0.052453 0.099499 0.126701 -vn -0.770265 -0.000001 0.637724 -v 0.052453 0.098749 0.126500 -vn -0.770263 -0.552287 -0.318864 -v 0.052453 0.100048 0.128750 -vn -0.770259 -0.318867 -0.552290 -v 0.052453 0.099499 0.129299 -vn -0.707107 0.000000 0.707107 -v 0.052453 0.098828 0.131000 -vn -0.770265 -0.000001 -0.637724 -v 0.052453 0.098749 0.129500 -vn -0.707107 -0.000000 0.707107 -v 0.052453 0.096624 0.131000 -vn -0.770261 0.318868 -0.552288 -v 0.052453 0.097999 0.129299 -vn -0.770261 0.552288 -0.318866 -v 0.052453 0.097450 0.128750 -vn -0.770260 0.318868 0.552288 -v 0.052453 0.097999 0.126701 -vn -0.770258 0.552295 0.318862 -v 0.052453 0.097450 0.127250 -vn -0.770263 0.637726 -0.000002 -v 0.052453 0.097249 0.128000 -vn -0.707107 0.707107 0.000000 -v 0.052453 0.105749 0.102000 -vn -0.770261 0.637729 0.000000 -v 0.052453 0.089499 0.104000 -vn -0.770262 0.552289 0.318863 -v 0.052453 0.089667 0.103375 -vn -0.770261 -0.637729 -0.000000 -v 0.052453 0.091999 0.104000 -vn -0.770262 -0.552289 -0.318863 -v 0.052453 0.091832 0.104625 -vn -0.770262 0.552289 -0.318863 -v 0.052453 0.089667 0.104625 -vn -0.770262 0.318863 0.552289 -v 0.052453 0.090124 0.102917 -vn -0.770261 -0.000000 0.637728 -v 0.052453 0.090749 0.102750 -vn -0.770262 -0.318863 0.552289 -v 0.052453 0.091374 0.102917 -vn -0.770262 -0.552289 0.318863 -v 0.052453 0.091832 0.103375 -vn -0.770262 -0.318863 -0.552289 -v 0.052453 0.091374 0.105083 -vn -0.770261 0.000000 -0.637728 -v 0.052453 0.090749 0.105250 -vn -0.770262 0.318863 -0.552289 -v 0.052453 0.090124 0.105083 -vn -1.000000 0.000000 0.000000 -v 0.052453 0.078499 0.102000 -vn -0.707107 -0.707107 0.000000 -v 0.052453 0.075749 0.098828 -vn -0.707107 -0.707107 0.000000 -v 0.052453 0.075749 0.102000 -vn -0.707107 -0.707107 -0.000000 -v 0.052453 0.075749 0.115875 -vn -0.577350 -0.577350 0.577350 -v 0.052453 0.075749 0.131000 -# 1968 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 10//10 11//11 12//12 -f 13//13 14//14 11//11 -f 15//15 16//16 17//17 -f 18//18 19//19 20//20 -f 21//21 22//22 23//23 -f 24//24 25//25 26//26 -f 26//26 25//25 27//27 -f 25//25 28//28 27//27 -f 27//27 28//28 29//29 -f 27//27 29//29 30//30 -f 29//29 31//31 30//30 -f 30//30 31//31 32//32 -f 30//30 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 38//38 39//39 40//40 -f 40//40 39//39 41//41 -f 42//42 37//37 43//43 -f 43//43 37//37 36//36 -f 43//43 36//36 44//44 -f 44//44 36//36 45//45 -f 44//44 45//45 38//38 -f 38//38 45//45 46//46 -f 38//38 46//46 39//39 -f 47//47 48//48 49//49 -f 47//47 49//49 50//50 -f 50//50 49//49 51//51 -f 50//50 51//51 52//52 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 51//51 58//58 52//52 -f 52//52 58//58 59//59 -f 52//52 59//59 22//22 -f 59//59 60//60 22//22 -f 22//22 60//60 61//61 -f 22//22 61//61 23//23 -f 23//23 61//61 62//62 -f 23//23 62//62 63//63 -f 41//41 24//24 40//40 -f 40//40 24//24 26//26 -f 40//40 26//26 64//64 -f 64//64 26//26 27//27 -f 64//64 27//27 65//65 -f 66//66 67//67 68//68 -f 68//68 67//67 27//27 -f 21//21 65//65 69//69 -f 67//67 70//70 27//27 -f 27//27 70//70 71//71 -f 27//27 71//71 65//65 -f 65//65 71//71 72//72 -f 65//65 72//72 69//69 -f 69//69 73//73 21//21 -f 21//21 73//73 74//74 -f 21//21 74//74 22//22 -f 22//22 74//74 75//75 -f 75//75 76//76 22//22 -f 22//22 76//76 77//77 -f 22//22 77//77 68//68 -f 68//68 77//77 78//78 -f 68//68 78//78 66//66 -f 62//62 79//79 63//63 -f 63//63 79//79 53//53 -f 63//63 53//53 80//80 -f 80//80 53//53 55//55 -f 80//80 55//55 81//81 -f 81//81 55//55 57//57 -f 81//81 57//57 82//82 -f 9//9 8//8 57//57 -f 8//8 83//83 57//57 -f 57//57 83//83 84//84 -f 57//57 84//84 82//82 -f 82//82 84//84 85//85 -f 82//82 85//85 86//86 -f 85//85 87//87 86//86 -f 86//86 87//87 18//18 -f 86//86 18//18 88//88 -f 88//88 18//18 20//20 -f 88//88 20//20 89//89 -f 89//89 20//20 90//90 -f 89//89 90//90 91//91 -f 92//92 93//93 94//94 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 93//93 99//99 94//94 -f 94//94 99//99 100//100 -f 94//94 100//100 2//2 -f 2//2 100//100 101//101 -f 2//2 101//101 102//102 -f 98//98 103//103 97//97 -f 97//97 103//103 104//104 -f 97//97 104//104 94//94 -f 94//94 104//104 105//105 -f 94//94 105//105 92//92 -f 10//10 94//94 106//106 -f 11//11 14//14 107//107 -f 106//106 108//108 10//10 -f 10//10 108//108 109//109 -f 10//10 109//109 11//11 -f 11//11 109//109 110//110 -f 11//11 110//110 13//13 -f 14//14 111//111 107//107 -f 107//107 111//111 112//112 -f 107//107 112//112 1//1 -f 1//1 112//112 113//113 -f 1//1 113//113 2//2 -f 113//113 114//114 2//2 -f 2//2 114//114 115//115 -f 2//2 115//115 94//94 -f 94//94 115//115 116//116 -f 94//94 116//116 106//106 -f 117//117 118//118 119//119 -f 120//120 121//121 118//118 -f 118//118 121//121 122//122 -f 118//118 122//122 119//119 -f 12//12 123//123 124//124 -f 119//119 125//125 117//117 -f 117//117 125//125 126//126 -f 117//117 126//126 127//127 -f 124//124 128//128 12//12 -f 12//12 128//128 129//129 -f 12//12 129//129 10//10 -f 124//124 130//130 128//128 -f 128//128 130//130 131//131 -f 128//128 131//131 132//132 -f 132//132 131//131 133//133 -f 132//132 133//133 120//120 -f 134//134 135//135 136//136 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 140//140 138//138 141//141 -f 140//140 141//141 136//136 -f 136//136 141//141 142//142 -f 136//136 142//142 134//134 -f 120//120 118//118 132//132 -f 132//132 118//118 136//136 -f 132//132 136//136 143//143 -f 143//143 136//136 135//135 -f 143//143 135//135 144//144 -f 144//144 145//145 143//143 -f 143//143 145//145 146//146 -f 143//143 146//146 147//147 -f 148//148 149//149 150//150 -f 150//150 149//149 147//147 -f 150//150 147//147 151//151 -f 151//151 147//147 146//146 -f 148//148 137//137 149//149 -f 149//149 137//137 139//139 -f 149//149 139//139 152//152 -f 152//152 139//139 153//153 -f 152//152 153//153 154//154 -f 154//154 153//153 155//155 -f 154//154 155//155 156//156 -f 156//156 155//155 157//157 -f 155//155 158//158 157//157 -f 157//157 158//158 159//159 -f 157//157 159//159 160//160 -f 160//160 159//159 161//161 -f 160//160 161//161 162//162 -f 162//162 161//161 163//163 -f 162//162 163//163 164//164 -f 164//164 163//163 165//165 -f 164//164 165//165 166//166 -f 166//166 165//165 167//167 -f 166//166 167//167 168//168 -f 167//167 169//169 168//168 -f 168//168 169//169 170//170 -f 168//168 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 37//37 -f 173//173 37//37 174//174 -f 174//174 37//37 42//42 -f 4//4 175//175 5//5 -f 5//5 175//175 176//176 -f 5//5 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 180//180 181//181 182//182 -f 181//181 183//183 182//182 -f 182//182 183//183 184//184 -f 182//182 184//184 185//185 -f 184//184 186//186 185//185 -f 185//185 186//186 187//187 -f 185//185 187//187 188//188 -f 188//188 187//187 189//189 -f 188//188 189//189 190//190 -f 190//190 189//189 191//191 -f 191//191 192//192 190//190 -f 190//190 192//192 193//193 -f 190//190 193//193 194//194 -f 194//194 193//193 195//195 -f 196//196 197//197 198//198 -f 197//197 199//199 198//198 -f 198//198 199//199 200//200 -f 198//198 200//200 201//201 -f 201//201 200//200 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 204//204 205//205 203//203 -f 203//203 205//205 206//206 -f 203//203 206//206 207//207 -f 206//206 208//208 207//207 -f 207//207 208//208 209//209 -f 207//207 209//209 210//210 -f 210//210 209//209 211//211 -f 210//210 211//211 212//212 -f 212//212 211//211 213//213 -f 212//212 213//213 196//196 -f 214//214 215//215 216//216 -f 216//216 215//215 217//217 -f 177//177 218//218 5//5 -f 5//5 218//218 214//214 -f 5//5 214//214 6//6 -f 6//6 214//214 216//216 -f 68//68 219//219 22//22 -f 22//22 219//219 220//220 -f 22//22 220//220 52//52 -f 52//52 220//220 221//221 -f 52//52 221//221 50//50 -f 50//50 221//221 222//222 -f 50//50 222//222 47//47 -f 47//47 222//222 223//223 -f 47//47 223//223 224//224 -f 224//224 223//223 225//225 -f 224//224 225//225 179//179 -f 30//30 226//226 27//27 -f 27//27 226//226 227//227 -f 27//27 227//227 68//68 -f 68//68 227//227 228//228 -f 68//68 228//228 219//219 -f 107//107 229//229 11//11 -f 11//11 229//229 117//117 -f 11//11 117//117 12//12 -f 12//12 117//117 127//127 -f 12//12 127//127 123//123 -f 230//230 231//231 232//232 -f 233//233 234//234 235//235 -f 235//235 234//234 230//230 -f 102//102 95//95 2//2 -f 2//2 95//95 97//97 -f 2//2 97//97 3//3 -f 3//3 97//97 15//15 -f 3//3 15//15 236//236 -f 236//236 15//15 232//232 -f 236//236 232//232 237//237 -f 237//237 232//232 231//231 -f 178//178 7//7 179//179 -f 179//179 7//7 9//9 -f 179//179 9//9 224//224 -f 224//224 9//9 57//57 -f 224//224 57//57 47//47 -f 47//47 57//57 56//56 -f 47//47 56//56 48//48 -f 15//15 17//17 232//232 -f 232//232 17//17 238//238 -f 232//232 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 212//212 -f 212//212 240//240 241//241 -f 212//212 241//241 210//210 -f 210//210 241//241 242//242 -f 210//210 242//242 207//207 -f 19//19 4//4 20//20 -f 20//20 4//4 6//6 -f 20//20 6//6 90//90 -f 90//90 6//6 216//216 -f 90//90 216//216 182//182 -f 182//182 216//216 243//243 -f 182//182 243//243 180//180 -f 180//180 243//243 244//244 -f 217//217 245//245 216//216 -f 216//216 245//245 246//246 -f 216//216 246//246 243//243 -f 243//243 246//246 194//194 -f 243//243 194//194 244//244 -f 244//244 194//194 195//195 -f 235//235 247//247 248//248 -f 249//249 250//250 251//251 -f 248//248 252//252 235//235 -f 235//235 252//252 253//253 -f 235//235 253//253 249//249 -f 249//249 253//253 254//254 -f 249//249 254//254 250//250 -f 230//230 232//232 235//235 -f 235//235 232//232 255//255 -f 235//235 255//255 247//247 -f 256//256 257//257 239//239 -f 239//239 257//257 258//258 -f 239//239 258//258 232//232 -f 232//232 258//258 259//259 -f 232//232 259//259 255//255 -f 196//196 198//198 212//212 -f 212//212 198//198 249//249 -f 212//212 249//249 239//239 -f 239//239 249//249 251//251 -f 239//239 251//251 256//256 -f 242//242 260//260 207//207 -f 207//207 260//260 261//261 -f 207//207 261//261 203//203 -f 203//203 261//261 262//262 -f 16//16 263//263 17//17 -f 17//17 263//263 264//264 -f 17//17 264//264 238//238 -f 238//238 264//264 265//265 -f 238//238 265//265 240//240 -f 240//240 265//265 266//266 -f 240//240 266//266 241//241 -f 241//241 266//266 267//267 -f 241//241 267//267 242//242 -f 242//242 267//267 91//91 -f 242//242 91//91 260//260 -f 260//260 91//91 90//90 -f 260//260 90//90 261//261 -f 261//261 90//90 182//182 -f 261//261 182//182 262//262 -f 262//262 182//182 185//185 -f 233//233 235//235 268//268 -f 268//268 235//235 249//249 -f 268//268 249//249 269//269 -f 269//269 249//249 198//198 -f 269//269 198//198 270//270 -f 270//270 198//198 201//201 -f 270//270 201//201 271//271 -f 271//271 201//201 203//203 -f 271//271 203//203 272//272 -f 272//272 203//203 262//262 -f 272//272 262//262 273//273 -f 273//273 262//262 185//185 -f 273//273 185//185 274//274 -f 274//274 185//185 188//188 -f 274//274 188//188 275//275 -f 275//275 188//188 190//190 -f 275//275 190//190 276//276 -f 277//277 278//278 279//279 -f 280//280 281//281 282//282 -f 283//283 284//284 282//282 -f 284//284 283//283 285//285 -f 286//286 287//287 288//288 -f 289//289 290//290 291//291 -f 292//292 293//293 294//294 -f 295//295 296//296 297//297 -f 298//298 299//299 300//300 -f 301//301 302//302 303//303 -f 300//300 299//299 304//304 -f 304//304 299//299 305//305 -f 304//304 305//305 306//306 -f 305//305 307//307 306//306 -f 306//306 307//307 308//308 -f 306//306 308//308 309//309 -f 308//308 310//310 309//309 -f 309//309 310//310 311//311 -f 309//309 311//311 312//312 -f 302//302 301//301 313//313 -f 313//313 301//301 314//314 -f 313//313 314//314 315//315 -f 315//315 314//314 316//316 -f 315//315 316//316 317//317 -f 311//311 318//318 312//312 -f 312//312 318//318 315//315 -f 312//312 315//315 319//319 -f 319//319 315//315 317//317 -f 319//319 317//317 320//320 -f 321//321 322//322 323//323 -f 323//323 322//322 324//324 -f 323//323 324//324 325//325 -f 321//321 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 331//331 332//332 333//333 -f 334//334 335//335 336//336 -f 336//336 335//335 337//337 -f 333//333 332//332 338//338 -f 332//332 339//339 338//338 -f 338//338 339//339 340//340 -f 338//338 340//340 336//336 -f 336//336 340//340 341//341 -f 336//336 341//341 334//334 -f 342//342 343//343 344//344 -f 344//344 343//343 345//345 -f 344//344 345//345 346//346 -f 346//346 345//345 347//347 -f 346//346 347//347 348//348 -f 349//349 350//350 351//351 -f 351//351 352//352 349//349 -f 349//349 352//352 336//336 -f 349//349 336//336 347//347 -f 347//347 336//336 337//337 -f 347//347 337//337 348//348 -f 353//353 354//354 355//355 -f 355//355 354//354 352//352 -f 355//355 352//352 356//356 -f 356//356 352//352 351//351 -f 357//357 358//358 359//359 -f 359//359 358//358 360//360 -f 359//359 360//360 361//361 -f 362//362 363//363 364//364 -f 362//362 364//364 349//349 -f 349//349 364//364 365//365 -f 349//349 365//365 350//350 -f 366//366 367//367 290//290 -f 290//290 367//367 368//368 -f 290//290 368//368 291//291 -f 291//291 368//368 369//369 -f 291//291 369//369 370//370 -f 370//370 369//369 371//371 -f 370//370 371//371 372//372 -f 373//373 374//374 375//375 -f 375//375 374//374 376//376 -f 353//353 357//357 354//354 -f 354//354 357//357 359//359 -f 354//354 359//359 377//377 -f 377//377 359//359 375//375 -f 377//377 375//375 378//378 -f 378//378 375//375 376//376 -f 376//376 379//379 378//378 -f 378//378 379//379 380//380 -f 378//378 380//380 381//381 -f 381//381 380//380 382//382 -f 383//383 384//384 385//385 -f 386//386 387//387 290//290 -f 290//290 387//387 388//388 -f 388//388 389//389 290//290 -f 290//290 389//389 381//381 -f 290//290 381//381 366//366 -f 366//366 381//381 382//382 -f 389//389 390//390 381//381 -f 381//381 390//390 391//391 -f 381//381 391//391 392//392 -f 392//392 393//393 381//381 -f 381//381 393//393 394//394 -f 381//381 394//394 383//383 -f 383//383 394//394 395//395 -f 383//383 395//395 384//384 -f 396//396 397//397 398//398 -f 399//399 400//400 401//401 -f 401//401 400//400 402//402 -f 401//401 402//402 403//403 -f 403//403 402//402 404//404 -f 403//403 404//404 405//405 -f 405//405 404//404 406//406 -f 405//405 406//406 407//407 -f 407//407 406//406 408//408 -f 407//407 408//408 409//409 -f 410//410 411//411 412//412 -f 412//412 411//411 413//413 -f 414//414 278//278 415//415 -f 415//415 278//278 277//277 -f 415//415 277//277 416//416 -f 417//417 412//412 418//418 -f 418//418 412//412 413//413 -f 418//418 413//413 419//419 -f 419//419 413//413 420//420 -f 419//419 420//420 421//421 -f 421//421 420//420 422//422 -f 423//423 424//424 425//425 -f 425//425 424//424 421//421 -f 425//425 421//421 277//277 -f 277//277 421//421 422//422 -f 277//277 422//422 416//416 -f 426//426 427//427 287//287 -f 428//428 429//429 296//296 -f 296//296 429//429 430//430 -f 296//296 430//430 297//297 -f 427//427 431//431 287//287 -f 287//287 431//431 432//432 -f 287//287 432//432 428//428 -f 430//430 433//433 297//297 -f 297//297 433//433 434//434 -f 297//297 434//434 435//435 -f 435//435 434//434 436//436 -f 435//435 436//436 437//437 -f 300//300 438//438 426//426 -f 306//306 439//439 304//304 -f 304//304 439//439 435//435 -f 304//304 435//435 300//300 -f 300//300 435//435 437//437 -f 300//300 437//437 438//438 -f 440//440 441//441 317//317 -f 317//317 441//441 442//442 -f 317//317 442//442 320//320 -f 317//317 443//443 440//440 -f 440//440 443//443 444//444 -f 440//440 444//444 445//445 -f 445//445 444//444 446//446 -f 445//445 446//446 447//447 -f 447//447 446//446 448//448 -f 447//447 448//448 449//449 -f 449//449 448//448 450//450 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 453//453 -f 452//452 454//454 453//453 -f 453//453 454//454 455//455 -f 453//453 455//455 456//456 -f 456//456 455//455 457//457 -f 456//456 457//457 458//458 -f 458//458 457//457 459//459 -f 458//458 459//459 460//460 -f 460//460 459//459 461//461 -f 460//460 461//461 462//462 -f 462//462 461//461 343//343 -f 462//462 343//343 333//333 -f 333//333 343//343 342//342 -f 333//333 342//342 331//331 -f 463//463 284//284 464//464 -f 464//464 284//284 285//285 -f 464//464 285//285 465//465 -f 465//465 285//285 466//466 -f 465//465 466//466 414//414 -f 385//385 386//386 383//383 -f 383//383 386//386 290//290 -f 383//383 290//290 397//397 -f 397//397 290//290 289//289 -f 397//397 289//289 398//398 -f 398//398 289//289 467//467 -f 398//398 467//467 468//468 -f 292//292 294//294 469//469 -f 372//372 373//373 370//370 -f 370//370 373//373 375//375 -f 370//370 375//375 470//470 -f 470//470 375//375 359//359 -f 470//470 359//359 362//362 -f 362//362 359//359 361//361 -f 362//362 361//361 363//363 -f 426//426 287//287 300//300 -f 300//300 287//287 286//286 -f 300//300 286//286 471//471 -f 303//303 298//298 301//301 -f 301//301 298//298 300//300 -f 301//301 300//300 472//472 -f 472//472 300//300 471//471 -f 428//428 296//296 287//287 -f 287//287 296//296 473//473 -f 287//287 473//473 288//288 -f 474//474 475//475 326//326 -f 326//326 475//475 473//473 -f 326//326 473//473 328//328 -f 328//328 473//473 296//296 -f 328//328 296//296 330//330 -f 321//321 323//323 326//326 -f 326//326 323//323 476//476 -f 326//326 476//476 474//474 -f 414//414 466//466 278//278 -f 278//278 466//466 477//477 -f 278//278 477//477 279//279 -f 281//281 478//478 479//479 -f 479//479 480//480 281//281 -f 281//281 480//480 481//481 -f 281//281 481//481 282//282 -f 282//282 481//481 482//482 -f 282//282 482//482 283//283 -f 483//483 484//484 485//485 -f 485//485 484//484 486//486 -f 483//483 487//487 484//484 -f 484//484 487//487 488//488 -f 484//484 488//488 489//489 -f 489//489 488//488 490//490 -f 489//489 490//490 491//491 -f 491//491 490//490 492//492 -f 491//491 492//492 493//493 -f 494//494 495//495 496//496 -f 496//496 495//495 497//497 -f 496//496 497//497 498//498 -f 498//498 497//497 499//499 -f 498//498 499//499 486//486 -f 486//486 499//499 500//500 -f 486//486 500//500 485//485 -f 501//501 502//502 503//503 -f 503//503 502//502 504//504 -f 503//503 504//504 505//505 -f 505//505 504//504 506//506 -f 505//505 506//506 507//507 -f 507//507 506//506 508//508 -f 507//507 508//508 509//509 -f 510//510 511//511 512//512 -f 512//512 511//511 513//513 -f 512//512 513//513 514//514 -f 514//514 513//513 515//515 -f 514//514 515//515 516//516 -f 516//516 515//515 517//517 -f 516//516 517//517 518//518 -f 519//519 484//484 520//520 -f 520//520 484//484 489//489 -f 520//520 489//489 521//521 -f 521//521 489//489 491//491 -f 521//521 491//491 522//522 -f 522//522 491//491 523//523 -f 522//522 523//523 524//524 -f 524//524 523//523 503//503 -f 524//524 503//503 525//525 -f 525//525 503//503 505//505 -f 525//525 505//505 526//526 -f 526//526 505//505 507//507 -f 526//526 507//507 527//527 -f 527//527 507//507 528//528 -f 527//527 528//528 529//529 -f 529//529 528//528 294//294 -f 529//529 294//294 530//530 -f 530//530 294//294 293//293 -f 528//528 531//531 532//532 -f 533//533 534//534 294//294 -f 294//294 534//534 398//398 -f 294//294 398//398 469//469 -f 469//469 398//398 468//468 -f 535//535 536//536 537//537 -f 532//532 538//538 528//528 -f 528//528 538//538 539//539 -f 528//528 539//539 294//294 -f 294//294 539//539 540//540 -f 294//294 540//540 533//533 -f 534//534 541//541 398//398 -f 398//398 541//541 542//542 -f 398//398 542//542 537//537 -f 537//537 542//542 543//543 -f 537//537 543//543 535//535 -f 509//509 510//510 507//507 -f 507//507 510//510 512//512 -f 507//507 512//512 528//528 -f 528//528 512//512 537//537 -f 528//528 537//537 531//531 -f 531//531 537//537 536//536 -f 493//493 494//494 491//491 -f 491//491 494//494 496//496 -f 491//491 496//496 523//523 -f 523//523 496//496 544//544 -f 523//523 544//544 503//503 -f 503//503 544//544 516//516 -f 503//503 516//516 501//501 -f 501//501 516//516 518//518 -f 486//486 478//478 498//498 -f 498//498 478//478 281//281 -f 498//498 281//281 496//496 -f 496//496 281//281 280//280 -f 496//496 280//280 544//544 -f 544//544 280//280 399//399 -f 544//544 399//399 516//516 -f 516//516 399//399 401//401 -f 516//516 401//401 514//514 -f 514//514 401//401 403//403 -f 514//514 403//403 512//512 -f 512//512 403//403 405//405 -f 512//512 405//405 537//537 -f 537//537 405//405 407//407 -f 537//537 407//407 398//398 -f 398//398 407//407 409//409 -f 398//398 409//409 396//396 -f 396//396 409//409 408//408 -f 463//463 545//545 284//284 -f 284//284 545//545 410//410 -f 284//284 410//410 282//282 -f 282//282 410//410 412//412 -f 282//282 412//412 280//280 -f 280//280 412//412 417//417 -f 280//280 417//417 399//399 -f 399//399 417//417 546//546 -f 399//399 546//546 400//400 -f 477//477 476//476 279//279 -f 279//279 476//476 323//323 -f 279//279 323//323 277//277 -f 277//277 323//323 325//325 -f 277//277 325//325 425//425 -f 425//425 325//325 547//547 -f 425//425 547//547 423//423 -f 423//423 547//547 548//548 -f 423//423 548//548 549//549 -f 549//549 548//548 550//550 -f 549//549 550//550 295//295 -f 295//295 550//550 551//551 -f 295//295 551//551 296//296 -f 296//296 551//551 552//552 -f 296//296 552//552 330//330 -f 233//233 530//530 234//234 -f 234//234 530//530 293//293 -f 234//234 293//293 230//230 -f 230//230 293//293 292//292 -f 519//519 276//276 484//484 -f 484//484 276//276 190//190 -f 484//484 190//190 486//486 -f 486//486 190//190 194//194 -f 486//486 194//194 478//478 -f 478//478 194//194 246//246 -f 478//478 246//246 479//479 -f 479//479 246//246 245//245 -f 230//230 292//292 231//231 -f 231//231 292//292 469//469 -f 231//231 469//469 237//237 -f 237//237 469//469 468//468 -f 237//237 468//468 236//236 -f 236//236 468//468 467//467 -f 236//236 467//467 3//3 -f 3//3 467//467 289//289 -f 3//3 289//289 1//1 -f 1//1 289//289 291//291 -f 1//1 291//291 107//107 -f 107//107 291//291 370//370 -f 107//107 370//370 229//229 -f 229//229 370//370 470//470 -f 229//229 470//470 117//117 -f 117//117 470//470 362//362 -f 117//117 362//362 118//118 -f 118//118 362//362 349//349 -f 118//118 349//349 136//136 -f 136//136 349//349 347//347 -f 136//136 347//347 345//345 -f 136//136 345//345 140//140 -f 140//140 345//345 343//343 -f 140//140 343//343 139//139 -f 139//139 343//343 461//461 -f 139//139 461//461 153//153 -f 153//153 461//461 459//459 -f 153//153 459//459 155//155 -f 155//155 459//459 457//457 -f 155//155 457//457 158//158 -f 158//158 457//457 455//455 -f 158//158 455//455 159//159 -f 159//159 455//455 454//454 -f 159//159 454//454 161//161 -f 161//161 454//454 452//452 -f 161//161 452//452 163//163 -f 163//163 452//452 450//450 -f 163//163 450//450 165//165 -f 165//165 450//450 448//448 -f 165//165 448//448 167//167 -f 167//167 448//448 446//446 -f 167//167 446//446 169//169 -f 169//169 446//446 444//444 -f 169//169 444//444 170//170 -f 170//170 444//444 443//443 -f 170//170 443//443 172//172 -f 172//172 443//443 317//317 -f 172//172 317//317 37//37 -f 37//37 317//317 316//316 -f 37//37 316//316 35//35 -f 35//35 316//316 314//314 -f 35//35 314//314 33//33 -f 33//33 314//314 301//301 -f 33//33 301//301 30//30 -f 30//30 301//301 472//472 -f 30//30 472//472 226//226 -f 226//226 472//472 471//471 -f 226//226 471//471 227//227 -f 227//227 471//471 228//228 -f 228//228 471//471 286//286 -f 228//228 286//286 219//219 -f 219//219 286//286 288//288 -f 219//219 288//288 220//220 -f 220//220 288//288 473//473 -f 220//220 473//473 221//221 -f 221//221 473//473 475//475 -f 221//221 475//475 222//222 -f 222//222 475//475 474//474 -f 222//222 474//474 223//223 -f 223//223 474//474 476//476 -f 223//223 476//476 225//225 -f 225//225 476//476 477//477 -f 225//225 477//477 179//179 -f 179//179 477//477 466//466 -f 179//179 466//466 177//177 -f 177//177 466//466 285//285 -f 177//177 285//285 218//218 -f 218//218 285//285 283//283 -f 218//218 283//283 214//214 -f 214//214 283//283 482//482 -f 214//214 482//482 215//215 -f 215//215 482//482 481//481 -f 38//38 309//309 44//44 -f 44//44 309//309 312//312 -f 44//44 312//312 43//43 -f 43//43 312//312 319//319 -f 43//43 319//319 42//42 -f 42//42 319//319 320//320 -f 42//42 320//320 174//174 -f 174//174 320//320 442//442 -f 174//174 442//442 173//173 -f 173//173 442//442 441//441 -f 173//173 441//441 171//171 -f 171//171 441//441 440//440 -f 171//171 440//440 168//168 -f 168//168 440//440 445//445 -f 168//168 445//445 166//166 -f 166//166 445//445 447//447 -f 166//166 447//447 164//164 -f 164//164 447//447 449//449 -f 164//164 449//449 162//162 -f 162//162 449//449 451//451 -f 162//162 451//451 160//160 -f 160//160 451//451 453//453 -f 160//160 453//453 157//157 -f 157//157 453//453 456//456 -f 157//157 456//456 156//156 -f 156//156 456//456 458//458 -f 156//156 458//458 154//154 -f 154//154 458//458 460//460 -f 154//154 460//460 152//152 -f 152//152 460//460 462//462 -f 152//152 462//462 149//149 -f 149//149 462//462 333//333 -f 149//149 333//333 147//147 -f 147//147 333//333 338//338 -f 397//397 15//15 383//383 -f 383//383 15//15 97//97 -f 383//383 97//97 381//381 -f 381//381 97//97 94//94 -f 381//381 94//94 378//378 -f 378//378 94//94 10//10 -f 378//378 10//10 377//377 -f 377//377 10//10 129//129 -f 377//377 129//129 354//354 -f 354//354 129//129 128//128 -f 354//354 128//128 352//352 -f 352//352 128//128 132//132 -f 352//352 132//132 336//336 -f 336//336 132//132 143//143 -f 336//336 143//143 338//338 -f 338//338 143//143 147//147 -f 15//15 397//397 16//16 -f 16//16 397//397 396//396 -f 16//16 396//396 263//263 -f 263//263 396//396 408//408 -f 263//263 408//408 264//264 -f 264//264 408//408 406//406 -f 264//264 406//406 265//265 -f 265//265 406//406 404//404 -f 265//265 404//404 266//266 -f 266//266 404//404 402//402 -f 266//266 402//402 267//267 -f 267//267 402//402 400//400 -f 267//267 400//400 91//91 -f 91//91 400//400 546//546 -f 91//91 546//546 89//89 -f 89//89 546//546 417//417 -f 49//49 322//322 51//51 -f 51//51 322//322 321//321 -f 51//51 321//321 58//58 -f 58//58 321//321 327//327 -f 58//58 327//327 59//59 -f 59//59 327//327 329//329 -f 59//59 329//329 60//60 -f 60//60 329//329 330//330 -f 60//60 330//330 61//61 -f 61//61 330//330 552//552 -f 61//61 552//552 62//62 -f 62//62 552//552 551//551 -f 62//62 551//551 79//79 -f 79//79 551//551 550//550 -f 79//79 550//550 53//53 -f 53//53 550//550 548//548 -f 53//53 548//548 54//54 -f 54//54 548//548 547//547 -f 54//54 547//547 56//56 -f 56//56 547//547 325//325 -f 56//56 325//325 48//48 -f 48//48 325//325 324//324 -f 48//48 324//324 49//49 -f 49//49 324//324 322//322 -f 215//215 481//481 480//480 -f 215//215 480//480 217//217 -f 217//217 480//480 479//479 -f 217//217 479//479 245//245 -f 89//89 417//417 88//88 -f 88//88 417//417 418//418 -f 88//88 418//418 86//86 -f 86//86 418//418 419//419 -f 86//86 419//419 82//82 -f 82//82 419//419 421//421 -f 82//82 421//421 81//81 -f 81//81 421//421 424//424 -f 81//81 424//424 80//80 -f 80//80 424//424 423//423 -f 80//80 423//423 63//63 -f 63//63 423//423 549//549 -f 63//63 549//549 23//23 -f 23//23 549//549 295//295 -f 23//23 295//295 21//21 -f 21//21 295//295 297//297 -f 21//21 297//297 65//65 -f 65//65 297//297 435//435 -f 65//65 435//435 64//64 -f 64//64 435//435 439//439 -f 64//64 439//439 40//40 -f 40//40 439//439 306//306 -f 40//40 306//306 38//38 -f 38//38 306//306 309//309 -f 146//146 341//341 151//151 -f 151//151 341//341 340//340 -f 151//151 340//340 150//150 -f 150//150 340//340 339//339 -f 150//150 339//339 148//148 -f 148//148 339//339 332//332 -f 148//148 332//332 137//137 -f 137//137 332//332 331//331 -f 137//137 331//331 138//138 -f 138//138 331//331 342//342 -f 138//138 342//342 141//141 -f 141//141 342//342 344//344 -f 141//141 344//344 142//142 -f 142//142 344//344 346//346 -f 142//142 346//346 134//134 -f 134//134 346//346 348//348 -f 134//134 348//348 135//135 -f 135//135 348//348 337//337 -f 135//135 337//337 144//144 -f 144//144 337//337 335//335 -f 144//144 335//335 145//145 -f 145//145 335//335 334//334 -f 145//145 334//334 146//146 -f 146//146 334//334 341//341 -f 130//130 357//357 131//131 -f 131//131 357//357 353//353 -f 131//131 353//353 133//133 -f 133//133 353//353 355//355 -f 133//133 355//355 120//120 -f 120//120 355//355 356//356 -f 120//120 356//356 121//121 -f 121//121 356//356 351//351 -f 121//121 351//351 122//122 -f 122//122 351//351 350//350 -f 122//122 350//350 119//119 -f 119//119 350//350 365//365 -f 119//119 365//365 125//125 -f 125//125 365//365 364//364 -f 125//125 364//364 126//126 -f 126//126 364//364 363//363 -f 126//126 363//363 127//127 -f 127//127 363//363 361//361 -f 127//127 361//361 123//123 -f 123//123 361//361 360//360 -f 123//123 360//360 124//124 -f 124//124 360//360 358//358 -f 124//124 358//358 130//130 -f 130//130 358//358 357//357 -f 116//116 366//366 106//106 -f 106//106 366//366 382//382 -f 106//106 382//382 108//108 -f 108//108 382//382 380//380 -f 108//108 380//380 109//109 -f 109//109 380//380 379//379 -f 109//109 379//379 110//110 -f 110//110 379//379 376//376 -f 110//110 376//376 13//13 -f 13//13 376//376 374//374 -f 13//13 374//374 14//14 -f 14//14 374//374 373//373 -f 14//14 373//373 111//111 -f 111//111 373//373 372//372 -f 111//111 372//372 112//112 -f 112//112 372//372 371//371 -f 112//112 371//371 113//113 -f 113//113 371//371 369//369 -f 113//113 369//369 114//114 -f 114//114 369//369 368//368 -f 114//114 368//368 115//115 -f 115//115 368//368 367//367 -f 115//115 367//367 116//116 -f 116//116 367//367 366//366 -f 103//103 395//395 104//104 -f 104//104 395//395 394//394 -f 104//104 394//394 105//105 -f 105//105 394//394 393//393 -f 105//105 393//393 92//92 -f 92//92 393//393 392//392 -f 92//92 392//392 93//93 -f 93//93 392//392 391//391 -f 93//93 391//391 99//99 -f 99//99 391//391 390//390 -f 99//99 390//390 100//100 -f 100//100 390//390 389//389 -f 100//100 389//389 101//101 -f 101//101 389//389 388//388 -f 101//101 388//388 102//102 -f 102//102 388//388 387//387 -f 102//102 387//387 95//95 -f 95//95 387//387 386//386 -f 95//95 386//386 96//96 -f 96//96 386//386 385//385 -f 96//96 385//385 98//98 -f 98//98 385//385 384//384 -f 98//98 384//384 103//103 -f 103//103 384//384 395//395 -f 176//176 463//463 178//178 -f 178//178 463//463 464//464 -f 178//178 464//464 7//7 -f 7//7 464//464 465//465 -f 7//7 465//465 8//8 -f 8//8 465//465 414//414 -f 8//8 414//414 83//83 -f 83//83 414//414 415//415 -f 83//83 415//415 84//84 -f 84//84 415//415 416//416 -f 84//84 416//416 85//85 -f 85//85 416//416 422//422 -f 85//85 422//422 87//87 -f 87//87 422//422 420//420 -f 87//87 420//420 18//18 -f 18//18 420//420 413//413 -f 18//18 413//413 19//19 -f 19//19 413//413 411//411 -f 19//19 411//411 4//4 -f 4//4 411//411 410//410 -f 4//4 410//410 175//175 -f 175//175 410//410 545//545 -f 175//175 545//545 176//176 -f 176//176 545//545 463//463 -f 77//77 428//428 78//78 -f 78//78 428//428 432//432 -f 78//78 432//432 66//66 -f 66//66 432//432 431//431 -f 66//66 431//431 67//67 -f 67//67 431//431 427//427 -f 67//67 427//427 70//70 -f 70//70 427//427 426//426 -f 70//70 426//426 71//71 -f 71//71 426//426 438//438 -f 71//71 438//438 72//72 -f 72//72 438//438 437//437 -f 72//72 437//437 69//69 -f 69//69 437//437 436//436 -f 69//69 436//436 73//73 -f 73//73 436//436 434//434 -f 73//73 434//434 74//74 -f 74//74 434//434 433//433 -f 74//74 433//433 75//75 -f 75//75 433//433 430//430 -f 75//75 430//430 76//76 -f 76//76 430//430 429//429 -f 76//76 429//429 77//77 -f 77//77 429//429 428//428 -f 29//29 298//298 31//31 -f 31//31 298//298 303//303 -f 31//31 303//303 32//32 -f 32//32 303//303 302//302 -f 32//32 302//302 34//34 -f 34//34 302//302 313//313 -f 34//34 313//313 36//36 -f 36//36 313//313 315//315 -f 36//36 315//315 45//45 -f 45//45 315//315 318//318 -f 45//45 318//318 46//46 -f 46//46 318//318 311//311 -f 46//46 311//311 39//39 -f 39//39 311//311 310//310 -f 39//39 310//310 41//41 -f 41//41 310//310 308//308 -f 41//41 308//308 24//24 -f 24//24 308//308 307//307 -f 24//24 307//307 25//25 -f 25//25 307//307 305//305 -f 25//25 305//305 28//28 -f 28//28 305//305 299//299 -f 28//28 299//299 29//29 -f 29//29 299//299 298//298 -f 193//193 483//483 195//195 -f 195//195 483//483 485//485 -f 195//195 485//485 244//244 -f 244//244 485//485 500//500 -f 244//244 500//500 180//180 -f 180//180 500//500 499//499 -f 180//180 499//499 181//181 -f 181//181 499//499 497//497 -f 181//181 497//497 183//183 -f 183//183 497//497 495//495 -f 183//183 495//495 184//184 -f 184//184 495//495 494//494 -f 184//184 494//494 186//186 -f 186//186 494//494 493//493 -f 186//186 493//493 187//187 -f 187//187 493//493 492//492 -f 187//187 492//492 189//189 -f 189//189 492//492 490//490 -f 189//189 490//490 191//191 -f 191//191 490//490 488//488 -f 191//191 488//488 192//192 -f 192//192 488//488 487//487 -f 192//192 487//487 193//193 -f 193//193 487//487 483//483 -f 206//206 501//501 208//208 -f 208//208 501//501 518//518 -f 208//208 518//518 209//209 -f 209//209 518//518 517//517 -f 209//209 517//517 211//211 -f 211//211 517//517 515//515 -f 211//211 515//515 213//213 -f 213//213 515//515 513//513 -f 213//213 513//513 196//196 -f 196//196 513//513 511//511 -f 196//196 511//511 197//197 -f 197//197 511//511 510//510 -f 197//197 510//510 199//199 -f 199//199 510//510 509//509 -f 199//199 509//509 200//200 -f 200//200 509//509 508//508 -f 200//200 508//508 202//202 -f 202//202 508//508 506//506 -f 202//202 506//506 204//204 -f 204//204 506//506 504//504 -f 204//204 504//504 205//205 -f 205//205 504//504 502//502 -f 205//205 502//502 206//206 -f 206//206 502//502 501//501 -f 251//251 531//531 256//256 -f 256//256 531//531 536//536 -f 256//256 536//536 257//257 -f 257//257 536//536 535//535 -f 257//257 535//535 258//258 -f 258//258 535//535 543//543 -f 258//258 543//543 259//259 -f 259//259 543//543 542//542 -f 259//259 542//542 255//255 -f 255//255 542//542 541//541 -f 255//255 541//541 247//247 -f 247//247 541//541 534//534 -f 247//247 534//534 248//248 -f 248//248 534//534 533//533 -f 248//248 533//533 252//252 -f 252//252 533//533 540//540 -f 252//252 540//540 253//253 -f 253//253 540//540 539//539 -f 253//253 539//539 254//254 -f 254//254 539//539 538//538 -f 254//254 538//538 250//250 -f 250//250 538//538 532//532 -f 250//250 532//532 251//251 -f 251//251 532//532 531//531 -f 276//276 519//519 275//275 -f 275//275 519//519 520//520 -f 275//275 520//520 274//274 -f 274//274 520//520 521//521 -f 274//274 521//521 273//273 -f 273//273 521//521 522//522 -f 273//273 522//522 272//272 -f 272//272 522//522 524//524 -f 272//272 524//524 271//271 -f 271//271 524//524 525//525 -f 271//271 525//525 270//270 -f 270//270 525//525 526//526 -f 270//270 526//526 269//269 -f 269//269 526//526 527//527 -f 269//269 527//527 268//268 -f 268//268 527//527 529//529 -f 268//268 529//529 233//233 -f 233//233 529//529 530//530 -f 553//553 554//554 555//555 -f 556//556 557//557 558//558 -f 559//559 560//560 561//561 -f 562//562 563//563 564//564 -f 565//565 566//566 563//563 -f 567//567 568//568 569//569 -f 570//570 571//571 572//572 -f 573//573 574//574 575//575 -f 576//576 577//577 578//578 -f 578//578 577//577 579//579 -f 577//577 580//580 579//579 -f 579//579 580//580 581//581 -f 579//579 581//581 582//582 -f 581//581 583//583 582//582 -f 582//582 583//583 584//584 -f 582//582 584//584 585//585 -f 585//585 584//584 586//586 -f 585//585 586//586 587//587 -f 587//587 586//586 588//588 -f 587//587 588//588 589//589 -f 590//590 591//591 592//592 -f 592//592 591//591 593//593 -f 594//594 589//589 595//595 -f 595//595 589//589 588//588 -f 595//595 588//588 596//596 -f 596//596 588//588 597//597 -f 596//596 597//597 590//590 -f 590//590 597//597 598//598 -f 590//590 598//598 591//591 -f 599//599 600//600 601//601 -f 599//599 601//601 602//602 -f 602//602 601//601 603//603 -f 602//602 603//603 604//604 -f 605//605 606//606 607//607 -f 607//607 606//606 608//608 -f 607//607 608//608 609//609 -f 603//603 610//610 604//604 -f 604//604 610//610 611//611 -f 604//604 611//611 574//574 -f 611//611 612//612 574//574 -f 574//574 612//612 613//613 -f 574//574 613//613 575//575 -f 575//575 613//613 614//614 -f 575//575 614//614 615//615 -f 593//593 576//576 592//592 -f 592//592 576//576 578//578 -f 592//592 578//578 616//616 -f 616//616 578//578 579//579 -f 616//616 579//579 617//617 -f 618//618 619//619 620//620 -f 620//620 619//619 579//579 -f 573//573 617//617 621//621 -f 619//619 622//622 579//579 -f 579//579 622//622 623//623 -f 579//579 623//623 617//617 -f 617//617 623//623 624//624 -f 617//617 624//624 621//621 -f 621//621 625//625 573//573 -f 573//573 625//625 626//626 -f 573//573 626//626 574//574 -f 574//574 626//626 627//627 -f 627//627 628//628 574//574 -f 574//574 628//628 629//629 -f 574//574 629//629 620//620 -f 620//620 629//629 630//630 -f 620//620 630//630 618//618 -f 614//614 631//631 615//615 -f 615//615 631//631 605//605 -f 615//615 605//605 632//632 -f 632//632 605//605 607//607 -f 632//632 607//607 633//633 -f 633//633 607//607 609//609 -f 633//633 609//609 634//634 -f 561//561 560//560 609//609 -f 560//560 635//635 609//609 -f 609//609 635//635 636//636 -f 609//609 636//636 634//634 -f 634//634 636//636 637//637 -f 634//634 637//637 638//638 -f 637//637 639//639 638//638 -f 638//638 639//639 570//570 -f 638//638 570//570 640//640 -f 640//640 570//570 572//572 -f 640//640 572//572 641//641 -f 641//641 572//572 642//642 -f 641//641 642//642 643//643 -f 644//644 645//645 646//646 -f 647//647 648//648 649//649 -f 649//649 648//648 650//650 -f 645//645 651//651 646//646 -f 646//646 651//651 652//652 -f 646//646 652//652 554//554 -f 554//554 652//652 653//653 -f 554//554 653//653 654//654 -f 650//650 655//655 649//649 -f 649//649 655//655 656//656 -f 649//649 656//656 646//646 -f 646//646 656//656 657//657 -f 646//646 657//657 644//644 -f 562//562 646//646 658//658 -f 563//563 566//566 659//659 -f 658//658 660//660 562//562 -f 562//562 660//660 661//661 -f 562//562 661//661 563//563 -f 563//563 661//661 662//662 -f 563//563 662//662 565//565 -f 566//566 663//663 659//659 -f 659//659 663//663 664//664 -f 659//659 664//664 553//553 -f 553//553 664//664 665//665 -f 553//553 665//665 554//554 -f 665//665 666//666 554//554 -f 554//554 666//666 667//667 -f 554//554 667//667 646//646 -f 646//646 667//667 668//668 -f 646//646 668//668 658//658 -f 669//669 670//670 671//671 -f 672//672 673//673 670//670 -f 670//670 673//673 674//674 -f 670//670 674//674 671//671 -f 564//564 675//675 676//676 -f 671//671 677//677 669//669 -f 669//669 677//677 678//678 -f 669//669 678//678 679//679 -f 676//676 680//680 564//564 -f 564//564 680//680 681//681 -f 564//564 681//681 562//562 -f 676//676 682//682 680//680 -f 680//680 682//682 683//683 -f 680//680 683//683 684//684 -f 684//684 683//683 685//685 -f 684//684 685//685 672//672 -f 686//686 687//687 688//688 -f 689//689 690//690 691//691 -f 691//691 690//690 692//692 -f 692//692 690//690 693//693 -f 692//692 693//693 688//688 -f 688//688 693//693 694//694 -f 688//688 694//694 686//686 -f 672//672 670//670 684//684 -f 684//684 670//670 688//688 -f 684//684 688//688 695//695 -f 695//695 688//688 687//687 -f 695//695 687//687 696//696 -f 696//696 697//697 695//695 -f 695//695 697//697 698//698 -f 695//695 698//698 699//699 -f 700//700 701//701 702//702 -f 702//702 701//701 699//699 -f 702//702 699//699 703//703 -f 703//703 699//699 698//698 -f 700//700 689//689 701//701 -f 701//701 689//689 691//691 -f 701//701 691//691 704//704 -f 704//704 691//691 705//705 -f 704//704 705//705 706//706 -f 706//706 705//705 707//707 -f 706//706 707//707 708//708 -f 708//708 707//707 709//709 -f 707//707 710//710 709//709 -f 709//709 710//710 711//711 -f 709//709 711//711 712//712 -f 712//712 711//711 713//713 -f 712//712 713//713 714//714 -f 714//714 713//713 715//715 -f 714//714 715//715 716//716 -f 716//716 715//715 717//717 -f 716//716 717//717 718//718 -f 718//718 717//717 719//719 -f 718//718 719//719 720//720 -f 719//719 721//721 720//720 -f 720//720 721//721 722//722 -f 720//720 722//722 723//723 -f 723//723 722//722 724//724 -f 723//723 724//724 725//725 -f 725//725 724//724 589//589 -f 725//725 589//589 726//726 -f 726//726 589//589 594//594 -f 556//556 727//727 557//557 -f 557//557 727//727 728//728 -f 557//557 728//728 729//729 -f 729//729 728//728 730//730 -f 729//729 730//730 731//731 -f 732//732 733//733 734//734 -f 733//733 735//735 734//734 -f 734//734 735//735 736//736 -f 734//734 736//736 737//737 -f 736//736 738//738 737//737 -f 737//737 738//738 739//739 -f 737//737 739//739 740//740 -f 740//740 739//739 741//741 -f 740//740 741//741 742//742 -f 742//742 741//741 743//743 -f 743//743 744//744 742//742 -f 742//742 744//744 745//745 -f 742//742 745//745 746//746 -f 746//746 745//745 747//747 -f 748//748 749//749 750//750 -f 749//749 751//751 750//750 -f 750//750 751//751 752//752 -f 750//750 752//752 753//753 -f 753//753 752//752 754//754 -f 753//753 754//754 755//755 -f 755//755 754//754 756//756 -f 756//756 757//757 755//755 -f 755//755 757//757 758//758 -f 755//755 758//758 759//759 -f 758//758 760//760 759//759 -f 759//759 760//760 761//761 -f 759//759 761//761 762//762 -f 762//762 761//761 763//763 -f 762//762 763//763 764//764 -f 764//764 763//763 765//765 -f 764//764 765//765 748//748 -f 766//766 767//767 768//768 -f 768//768 767//767 769//769 -f 729//729 770//770 557//557 -f 557//557 770//770 766//766 -f 557//557 766//766 558//558 -f 558//558 766//766 768//768 -f 620//620 771//771 574//574 -f 574//574 771//771 772//772 -f 574//574 772//772 604//604 -f 604//604 772//772 773//773 -f 604//604 773//773 602//602 -f 602//602 773//773 774//774 -f 602//602 774//774 599//599 -f 599//599 774//774 775//775 -f 599//599 775//775 776//776 -f 776//776 775//775 777//777 -f 776//776 777//777 731//731 -f 582//582 778//778 579//579 -f 579//579 778//778 779//779 -f 579//579 779//779 620//620 -f 620//620 779//779 780//780 -f 620//620 780//780 771//771 -f 659//659 781//781 563//563 -f 563//563 781//781 669//669 -f 563//563 669//669 564//564 -f 564//564 669//669 679//679 -f 564//564 679//679 675//675 -f 782//782 783//783 784//784 -f 785//785 786//786 787//787 -f 787//787 786//786 782//782 -f 654//654 647//647 554//554 -f 554//554 647//647 649//649 -f 554//554 649//649 555//555 -f 555//555 649//649 567//567 -f 555//555 567//567 788//788 -f 788//788 567//567 784//784 -f 788//788 784//784 789//789 -f 789//789 784//784 783//783 -f 730//730 559//559 731//731 -f 731//731 559//559 561//561 -f 731//731 561//561 776//776 -f 776//776 561//561 609//609 -f 776//776 609//609 599//599 -f 599//599 609//609 608//608 -f 599//599 608//608 600//600 -f 567//567 569//569 784//784 -f 784//784 569//569 790//790 -f 784//784 790//790 791//791 -f 791//791 790//790 792//792 -f 791//791 792//792 764//764 -f 764//764 792//792 793//793 -f 764//764 793//793 762//762 -f 762//762 793//793 794//794 -f 762//762 794//794 759//759 -f 571//571 556//556 572//572 -f 572//572 556//556 558//558 -f 572//572 558//558 642//642 -f 642//642 558//558 768//768 -f 642//642 768//768 734//734 -f 734//734 768//768 795//795 -f 734//734 795//795 732//732 -f 732//732 795//795 796//796 -f 769//769 797//797 768//768 -f 768//768 797//797 798//798 -f 768//768 798//798 795//795 -f 795//795 798//798 746//746 -f 795//795 746//746 796//796 -f 796//796 746//746 747//747 -f 787//787 799//799 800//800 -f 801//801 802//802 803//803 -f 800//800 804//804 787//787 -f 787//787 804//804 805//805 -f 787//787 805//805 801//801 -f 801//801 805//805 806//806 -f 801//801 806//806 802//802 -f 782//782 784//784 787//787 -f 787//787 784//784 807//807 -f 787//787 807//807 799//799 -f 808//808 809//809 791//791 -f 791//791 809//809 810//810 -f 791//791 810//810 784//784 -f 784//784 810//810 811//811 -f 784//784 811//811 807//807 -f 748//748 750//750 764//764 -f 764//764 750//750 801//801 -f 764//764 801//801 791//791 -f 791//791 801//801 803//803 -f 791//791 803//803 808//808 -f 794//794 812//812 759//759 -f 759//759 812//812 813//813 -f 759//759 813//813 755//755 -f 755//755 813//813 814//814 -f 568//568 815//815 569//569 -f 569//569 815//815 816//816 -f 569//569 816//816 790//790 -f 790//790 816//816 817//817 -f 790//790 817//817 792//792 -f 792//792 817//817 818//818 -f 792//792 818//818 793//793 -f 793//793 818//818 819//819 -f 793//793 819//819 794//794 -f 794//794 819//819 643//643 -f 794//794 643//643 812//812 -f 812//812 643//643 642//642 -f 812//812 642//642 813//813 -f 813//813 642//642 734//734 -f 813//813 734//734 814//814 -f 814//814 734//734 737//737 -f 785//785 787//787 820//820 -f 820//820 787//787 801//801 -f 820//820 801//801 821//821 -f 821//821 801//801 750//750 -f 821//821 750//750 822//822 -f 822//822 750//750 753//753 -f 822//822 753//753 823//823 -f 823//823 753//753 755//755 -f 823//823 755//755 824//824 -f 824//824 755//755 814//814 -f 824//824 814//814 825//825 -f 825//825 814//814 737//737 -f 825//825 737//737 826//826 -f 826//826 737//737 740//740 -f 826//826 740//740 827//827 -f 827//827 740//740 742//742 -f 827//827 742//742 828//828 -f 829//829 830//830 831//831 -f 832//832 833//833 834//834 -f 835//835 836//836 834//834 -f 836//836 835//835 837//837 -f 838//838 839//839 840//840 -f 841//841 842//842 843//843 -f 844//844 845//845 846//846 -f 847//847 848//848 849//849 -f 850//850 851//851 852//852 -f 853//853 854//854 855//855 -f 852//852 851//851 856//856 -f 856//856 851//851 857//857 -f 856//856 857//857 858//858 -f 857//857 859//859 858//858 -f 858//858 859//859 860//860 -f 858//858 860//860 861//861 -f 860//860 862//862 861//861 -f 861//861 862//862 863//863 -f 861//861 863//863 864//864 -f 854//854 853//853 865//865 -f 865//865 853//853 866//866 -f 865//865 866//866 867//867 -f 867//867 866//866 868//868 -f 867//867 868//868 869//869 -f 863//863 870//870 864//864 -f 864//864 870//870 867//867 -f 864//864 867//867 871//871 -f 871//871 867//867 869//869 -f 871//871 869//869 872//872 -f 873//873 874//874 875//875 -f 875//875 874//874 876//876 -f 875//875 876//876 877//877 -f 873//873 878//878 879//879 -f 879//879 878//878 880//880 -f 879//879 880//880 881//881 -f 881//881 880//880 882//882 -f 883//883 884//884 885//885 -f 886//886 887//887 888//888 -f 888//888 887//887 889//889 -f 885//885 884//884 890//890 -f 884//884 891//891 890//890 -f 890//890 891//891 892//892 -f 890//890 892//892 888//888 -f 888//888 892//892 893//893 -f 888//888 893//893 886//886 -f 894//894 895//895 896//896 -f 896//896 895//895 897//897 -f 896//896 897//897 898//898 -f 898//898 897//897 899//899 -f 898//898 899//899 900//900 -f 901//901 902//902 903//903 -f 903//903 904//904 901//901 -f 901//901 904//904 888//888 -f 901//901 888//888 899//899 -f 899//899 888//888 889//889 -f 899//899 889//889 900//900 -f 905//905 906//906 907//907 -f 907//907 906//906 904//904 -f 907//907 904//904 908//908 -f 908//908 904//904 903//903 -f 909//909 910//910 911//911 -f 911//911 910//910 912//912 -f 911//911 912//912 913//913 -f 914//914 915//915 916//916 -f 914//914 916//916 901//901 -f 901//901 916//916 917//917 -f 901//901 917//917 902//902 -f 918//918 919//919 842//842 -f 842//842 919//919 920//920 -f 842//842 920//920 843//843 -f 843//843 920//920 921//921 -f 843//843 921//921 922//922 -f 922//922 921//921 923//923 -f 922//922 923//923 924//924 -f 925//925 926//926 927//927 -f 927//927 926//926 928//928 -f 905//905 909//909 906//906 -f 906//906 909//909 911//911 -f 906//906 911//911 929//929 -f 929//929 911//911 927//927 -f 929//929 927//927 930//930 -f 930//930 927//927 928//928 -f 928//928 931//931 930//930 -f 930//930 931//931 932//932 -f 930//930 932//932 933//933 -f 933//933 932//932 934//934 -f 935//935 936//936 937//937 -f 938//938 939//939 842//842 -f 842//842 939//939 940//940 -f 940//940 941//941 842//842 -f 842//842 941//941 933//933 -f 842//842 933//933 918//918 -f 918//918 933//933 934//934 -f 941//941 942//942 933//933 -f 933//933 942//942 943//943 -f 933//933 943//943 944//944 -f 944//944 945//945 933//933 -f 933//933 945//945 946//946 -f 933//933 946//946 935//935 -f 935//935 946//946 947//947 -f 935//935 947//947 936//936 -f 948//948 949//949 950//950 -f 951//951 952//952 953//953 -f 953//953 952//952 954//954 -f 953//953 954//954 955//955 -f 955//955 954//954 956//956 -f 955//955 956//956 957//957 -f 957//957 956//956 958//958 -f 957//957 958//958 959//959 -f 959//959 958//958 960//960 -f 959//959 960//960 961//961 -f 962//962 963//963 964//964 -f 964//964 963//963 965//965 -f 966//966 830//830 967//967 -f 967//967 830//830 829//829 -f 967//967 829//829 968//968 -f 969//969 964//964 970//970 -f 970//970 964//964 965//965 -f 970//970 965//965 971//971 -f 971//971 965//965 972//972 -f 971//971 972//972 973//973 -f 973//973 972//972 974//974 -f 975//975 976//976 977//977 -f 977//977 976//976 973//973 -f 977//977 973//973 829//829 -f 829//829 973//973 974//974 -f 829//829 974//974 968//968 -f 978//978 979//979 839//839 -f 980//980 981//981 848//848 -f 848//848 981//981 982//982 -f 848//848 982//982 849//849 -f 979//979 983//983 839//839 -f 839//839 983//983 984//984 -f 839//839 984//984 980//980 -f 982//982 985//985 849//849 -f 849//849 985//985 986//986 -f 849//849 986//986 987//987 -f 987//987 986//986 988//988 -f 987//987 988//988 989//989 -f 852//852 990//990 978//978 -f 858//858 991//991 856//856 -f 856//856 991//991 987//987 -f 856//856 987//987 852//852 -f 852//852 987//987 989//989 -f 852//852 989//989 990//990 -f 992//992 993//993 869//869 -f 869//869 993//993 994//994 -f 869//869 994//994 872//872 -f 869//869 995//995 992//992 -f 992//992 995//995 996//996 -f 992//992 996//996 997//997 -f 997//997 996//996 998//998 -f 997//997 998//998 999//999 -f 999//999 998//998 1000//1000 -f 999//999 1000//1000 1001//1001 -f 1001//1001 1000//1000 1002//1002 -f 1001//1001 1002//1002 1003//1003 -f 1003//1003 1002//1002 1004//1004 -f 1003//1003 1004//1004 1005//1005 -f 1004//1004 1006//1006 1005//1005 -f 1005//1005 1006//1006 1007//1007 -f 1005//1005 1007//1007 1008//1008 -f 1008//1008 1007//1007 1009//1009 -f 1008//1008 1009//1009 1010//1010 -f 1010//1010 1009//1009 1011//1011 -f 1010//1010 1011//1011 1012//1012 -f 1012//1012 1011//1011 1013//1013 -f 1012//1012 1013//1013 1014//1014 -f 1014//1014 1013//1013 895//895 -f 1014//1014 895//895 885//885 -f 885//885 895//895 894//894 -f 885//885 894//894 883//883 -f 1015//1015 836//836 1016//1016 -f 1016//1016 836//836 837//837 -f 1016//1016 837//837 1017//1017 -f 1017//1017 837//837 1018//1018 -f 1017//1017 1018//1018 966//966 -f 937//937 938//938 935//935 -f 935//935 938//938 842//842 -f 935//935 842//842 949//949 -f 949//949 842//842 841//841 -f 949//949 841//841 950//950 -f 950//950 841//841 1019//1019 -f 950//950 1019//1019 1020//1020 -f 844//844 846//846 1021//1021 -f 924//924 925//925 922//922 -f 922//922 925//925 927//927 -f 922//922 927//927 1022//1022 -f 1022//1022 927//927 911//911 -f 1022//1022 911//911 914//914 -f 914//914 911//911 913//913 -f 914//914 913//913 915//915 -f 978//978 839//839 852//852 -f 852//852 839//839 838//838 -f 852//852 838//838 1023//1023 -f 855//855 850//850 853//853 -f 853//853 850//850 852//852 -f 853//853 852//852 1024//1024 -f 1024//1024 852//852 1023//1023 -f 980//980 848//848 839//839 -f 839//839 848//848 1025//1025 -f 839//839 1025//1025 840//840 -f 1026//1026 1027//1027 878//878 -f 878//878 1027//1027 1025//1025 -f 878//878 1025//1025 880//880 -f 880//880 1025//1025 848//848 -f 880//880 848//848 882//882 -f 873//873 875//875 878//878 -f 878//878 875//875 1028//1028 -f 878//878 1028//1028 1026//1026 -f 966//966 1018//1018 830//830 -f 830//830 1018//1018 1029//1029 -f 830//830 1029//1029 831//831 -f 833//833 1030//1030 1031//1031 -f 1031//1031 1032//1032 833//833 -f 833//833 1032//1032 1033//1033 -f 833//833 1033//1033 834//834 -f 834//834 1033//1033 1034//1034 -f 834//834 1034//1034 835//835 -f 1035//1035 1036//1036 1037//1037 -f 1037//1037 1036//1036 1038//1038 -f 1035//1035 1039//1039 1036//1036 -f 1036//1036 1039//1039 1040//1040 -f 1036//1036 1040//1040 1041//1041 -f 1041//1041 1040//1040 1042//1042 -f 1041//1041 1042//1042 1043//1043 -f 1043//1043 1042//1042 1044//1044 -f 1043//1043 1044//1044 1045//1045 -f 1046//1046 1047//1047 1048//1048 -f 1048//1048 1047//1047 1049//1049 -f 1048//1048 1049//1049 1050//1050 -f 1050//1050 1049//1049 1051//1051 -f 1050//1050 1051//1051 1038//1038 -f 1038//1038 1051//1051 1052//1052 -f 1038//1038 1052//1052 1037//1037 -f 1053//1053 1054//1054 1055//1055 -f 1055//1055 1054//1054 1056//1056 -f 1055//1055 1056//1056 1057//1057 -f 1057//1057 1056//1056 1058//1058 -f 1057//1057 1058//1058 1059//1059 -f 1059//1059 1058//1058 1060//1060 -f 1059//1059 1060//1060 1061//1061 -f 1062//1062 1063//1063 1064//1064 -f 1064//1064 1063//1063 1065//1065 -f 1064//1064 1065//1065 1066//1066 -f 1066//1066 1065//1065 1067//1067 -f 1066//1066 1067//1067 1068//1068 -f 1068//1068 1067//1067 1069//1069 -f 1068//1068 1069//1069 1070//1070 -f 1071//1071 1036//1036 1072//1072 -f 1072//1072 1036//1036 1041//1041 -f 1072//1072 1041//1041 1073//1073 -f 1073//1073 1041//1041 1043//1043 -f 1073//1073 1043//1043 1074//1074 -f 1074//1074 1043//1043 1075//1075 -f 1074//1074 1075//1075 1076//1076 -f 1076//1076 1075//1075 1055//1055 -f 1076//1076 1055//1055 1077//1077 -f 1077//1077 1055//1055 1057//1057 -f 1077//1077 1057//1057 1078//1078 -f 1078//1078 1057//1057 1059//1059 -f 1078//1078 1059//1059 1079//1079 -f 1079//1079 1059//1059 1080//1080 -f 1079//1079 1080//1080 1081//1081 -f 1081//1081 1080//1080 846//846 -f 1081//1081 846//846 1082//1082 -f 1082//1082 846//846 845//845 -f 1080//1080 1083//1083 1084//1084 -f 1085//1085 1086//1086 846//846 -f 846//846 1086//1086 950//950 -f 846//846 950//950 1021//1021 -f 1021//1021 950//950 1020//1020 -f 1087//1087 1088//1088 1089//1089 -f 1084//1084 1090//1090 1080//1080 -f 1080//1080 1090//1090 1091//1091 -f 1080//1080 1091//1091 846//846 -f 846//846 1091//1091 1092//1092 -f 846//846 1092//1092 1085//1085 -f 1086//1086 1093//1093 950//950 -f 950//950 1093//1093 1094//1094 -f 950//950 1094//1094 1089//1089 -f 1089//1089 1094//1094 1095//1095 -f 1089//1089 1095//1095 1087//1087 -f 1061//1061 1062//1062 1059//1059 -f 1059//1059 1062//1062 1064//1064 -f 1059//1059 1064//1064 1080//1080 -f 1080//1080 1064//1064 1089//1089 -f 1080//1080 1089//1089 1083//1083 -f 1083//1083 1089//1089 1088//1088 -f 1045//1045 1046//1046 1043//1043 -f 1043//1043 1046//1046 1048//1048 -f 1043//1043 1048//1048 1075//1075 -f 1075//1075 1048//1048 1096//1096 -f 1075//1075 1096//1096 1055//1055 -f 1055//1055 1096//1096 1068//1068 -f 1055//1055 1068//1068 1053//1053 -f 1053//1053 1068//1068 1070//1070 -f 1038//1038 1030//1030 1050//1050 -f 1050//1050 1030//1030 833//833 -f 1050//1050 833//833 1048//1048 -f 1048//1048 833//833 832//832 -f 1048//1048 832//832 1096//1096 -f 1096//1096 832//832 951//951 -f 1096//1096 951//951 1068//1068 -f 1068//1068 951//951 953//953 -f 1068//1068 953//953 1066//1066 -f 1066//1066 953//953 955//955 -f 1066//1066 955//955 1064//1064 -f 1064//1064 955//955 957//957 -f 1064//1064 957//957 1089//1089 -f 1089//1089 957//957 959//959 -f 1089//1089 959//959 950//950 -f 950//950 959//959 961//961 -f 950//950 961//961 948//948 -f 948//948 961//961 960//960 -f 1015//1015 1097//1097 836//836 -f 836//836 1097//1097 962//962 -f 836//836 962//962 834//834 -f 834//834 962//962 964//964 -f 834//834 964//964 832//832 -f 832//832 964//964 969//969 -f 832//832 969//969 951//951 -f 951//951 969//969 1098//1098 -f 951//951 1098//1098 952//952 -f 1029//1029 1028//1028 831//831 -f 831//831 1028//1028 875//875 -f 831//831 875//875 829//829 -f 829//829 875//875 877//877 -f 829//829 877//877 977//977 -f 977//977 877//877 1099//1099 -f 977//977 1099//1099 975//975 -f 975//975 1099//1099 1100//1100 -f 975//975 1100//1100 1101//1101 -f 1101//1101 1100//1100 1102//1102 -f 1101//1101 1102//1102 847//847 -f 847//847 1102//1102 1103//1103 -f 847//847 1103//1103 848//848 -f 848//848 1103//1103 1104//1104 -f 848//848 1104//1104 882//882 -f 785//785 1082//1082 786//786 -f 786//786 1082//1082 845//845 -f 786//786 845//845 782//782 -f 782//782 845//845 844//844 -f 1071//1071 828//828 1036//1036 -f 1036//1036 828//828 742//742 -f 1036//1036 742//742 1038//1038 -f 1038//1038 742//742 746//746 -f 1038//1038 746//746 1030//1030 -f 1030//1030 746//746 798//798 -f 1030//1030 798//798 1031//1031 -f 1031//1031 798//798 797//797 -f 782//782 844//844 783//783 -f 783//783 844//844 1021//1021 -f 783//783 1021//1021 789//789 -f 789//789 1021//1021 1020//1020 -f 789//789 1020//1020 788//788 -f 788//788 1020//1020 1019//1019 -f 788//788 1019//1019 555//555 -f 555//555 1019//1019 841//841 -f 555//555 841//841 553//553 -f 553//553 841//841 843//843 -f 553//553 843//843 659//659 -f 659//659 843//843 922//922 -f 659//659 922//922 781//781 -f 781//781 922//922 1022//1022 -f 781//781 1022//1022 669//669 -f 669//669 1022//1022 914//914 -f 669//669 914//914 670//670 -f 670//670 914//914 901//901 -f 670//670 901//901 688//688 -f 688//688 901//901 899//899 -f 688//688 899//899 897//897 -f 688//688 897//897 692//692 -f 692//692 897//897 895//895 -f 692//692 895//895 691//691 -f 691//691 895//895 1013//1013 -f 691//691 1013//1013 705//705 -f 705//705 1013//1013 1011//1011 -f 705//705 1011//1011 707//707 -f 707//707 1011//1011 1009//1009 -f 707//707 1009//1009 710//710 -f 710//710 1009//1009 1007//1007 -f 710//710 1007//1007 711//711 -f 711//711 1007//1007 1006//1006 -f 711//711 1006//1006 713//713 -f 713//713 1006//1006 1004//1004 -f 713//713 1004//1004 715//715 -f 715//715 1004//1004 1002//1002 -f 715//715 1002//1002 717//717 -f 717//717 1002//1002 1000//1000 -f 717//717 1000//1000 719//719 -f 719//719 1000//1000 998//998 -f 719//719 998//998 721//721 -f 721//721 998//998 996//996 -f 721//721 996//996 722//722 -f 722//722 996//996 995//995 -f 722//722 995//995 724//724 -f 724//724 995//995 869//869 -f 724//724 869//869 589//589 -f 589//589 869//869 868//868 -f 589//589 868//868 587//587 -f 587//587 868//868 866//866 -f 587//587 866//866 585//585 -f 585//585 866//866 853//853 -f 585//585 853//853 582//582 -f 582//582 853//853 1024//1024 -f 582//582 1024//1024 778//778 -f 778//778 1024//1024 1023//1023 -f 778//778 1023//1023 779//779 -f 779//779 1023//1023 780//780 -f 780//780 1023//1023 838//838 -f 780//780 838//838 771//771 -f 771//771 838//838 840//840 -f 771//771 840//840 772//772 -f 772//772 840//840 1025//1025 -f 772//772 1025//1025 773//773 -f 773//773 1025//1025 1027//1027 -f 773//773 1027//1027 774//774 -f 774//774 1027//1027 1026//1026 -f 774//774 1026//1026 775//775 -f 775//775 1026//1026 1028//1028 -f 775//775 1028//1028 777//777 -f 777//777 1028//1028 1029//1029 -f 777//777 1029//1029 731//731 -f 731//731 1029//1029 1018//1018 -f 731//731 1018//1018 729//729 -f 729//729 1018//1018 837//837 -f 729//729 837//837 770//770 -f 770//770 837//837 835//835 -f 770//770 835//835 766//766 -f 766//766 835//835 1034//1034 -f 766//766 1034//1034 767//767 -f 767//767 1034//1034 1033//1033 -f 590//590 861//861 596//596 -f 596//596 861//861 864//864 -f 596//596 864//864 595//595 -f 595//595 864//864 871//871 -f 595//595 871//871 594//594 -f 594//594 871//871 872//872 -f 594//594 872//872 726//726 -f 726//726 872//872 994//994 -f 726//726 994//994 725//725 -f 725//725 994//994 993//993 -f 725//725 993//993 723//723 -f 723//723 993//993 992//992 -f 723//723 992//992 720//720 -f 720//720 992//992 997//997 -f 720//720 997//997 718//718 -f 718//718 997//997 999//999 -f 718//718 999//999 716//716 -f 716//716 999//999 1001//1001 -f 716//716 1001//1001 714//714 -f 714//714 1001//1001 1003//1003 -f 714//714 1003//1003 712//712 -f 712//712 1003//1003 1005//1005 -f 712//712 1005//1005 709//709 -f 709//709 1005//1005 1008//1008 -f 709//709 1008//1008 708//708 -f 708//708 1008//1008 1010//1010 -f 708//708 1010//1010 706//706 -f 706//706 1010//1010 1012//1012 -f 706//706 1012//1012 704//704 -f 704//704 1012//1012 1014//1014 -f 704//704 1014//1014 701//701 -f 701//701 1014//1014 885//885 -f 701//701 885//885 699//699 -f 699//699 885//885 890//890 -f 949//949 567//567 935//935 -f 935//935 567//567 649//649 -f 935//935 649//649 933//933 -f 933//933 649//649 646//646 -f 933//933 646//646 930//930 -f 930//930 646//646 562//562 -f 930//930 562//562 929//929 -f 929//929 562//562 681//681 -f 929//929 681//681 906//906 -f 906//906 681//681 680//680 -f 906//906 680//680 904//904 -f 904//904 680//680 684//684 -f 904//904 684//684 888//888 -f 888//888 684//684 695//695 -f 888//888 695//695 890//890 -f 890//890 695//695 699//699 -f 567//567 949//949 568//568 -f 568//568 949//949 948//948 -f 568//568 948//948 815//815 -f 815//815 948//948 960//960 -f 815//815 960//960 816//816 -f 816//816 960//960 958//958 -f 816//816 958//958 817//817 -f 817//817 958//958 956//956 -f 817//817 956//956 818//818 -f 818//818 956//956 954//954 -f 818//818 954//954 819//819 -f 819//819 954//954 952//952 -f 819//819 952//952 643//643 -f 643//643 952//952 1098//1098 -f 643//643 1098//1098 641//641 -f 641//641 1098//1098 969//969 -f 601//601 874//874 603//603 -f 603//603 874//874 873//873 -f 603//603 873//873 610//610 -f 610//610 873//873 879//879 -f 610//610 879//879 611//611 -f 611//611 879//879 881//881 -f 611//611 881//881 612//612 -f 612//612 881//881 882//882 -f 612//612 882//882 613//613 -f 613//613 882//882 1104//1104 -f 613//613 1104//1104 614//614 -f 614//614 1104//1104 1103//1103 -f 614//614 1103//1103 631//631 -f 631//631 1103//1103 1102//1102 -f 631//631 1102//1102 605//605 -f 605//605 1102//1102 1100//1100 -f 605//605 1100//1100 606//606 -f 606//606 1100//1100 1099//1099 -f 606//606 1099//1099 608//608 -f 608//608 1099//1099 877//877 -f 608//608 877//877 600//600 -f 600//600 877//877 876//876 -f 600//600 876//876 601//601 -f 601//601 876//876 874//874 -f 767//767 1033//1033 1032//1032 -f 767//767 1032//1032 769//769 -f 769//769 1032//1032 1031//1031 -f 769//769 1031//1031 797//797 -f 641//641 969//969 640//640 -f 640//640 969//969 970//970 -f 640//640 970//970 638//638 -f 638//638 970//970 971//971 -f 638//638 971//971 634//634 -f 634//634 971//971 973//973 -f 634//634 973//973 633//633 -f 633//633 973//973 976//976 -f 633//633 976//976 632//632 -f 632//632 976//976 975//975 -f 632//632 975//975 615//615 -f 615//615 975//975 1101//1101 -f 615//615 1101//1101 575//575 -f 575//575 1101//1101 847//847 -f 575//575 847//847 573//573 -f 573//573 847//847 849//849 -f 573//573 849//849 617//617 -f 617//617 849//849 987//987 -f 617//617 987//987 616//616 -f 616//616 987//987 991//991 -f 616//616 991//991 592//592 -f 592//592 991//991 858//858 -f 592//592 858//858 590//590 -f 590//590 858//858 861//861 -f 698//698 893//893 703//703 -f 703//703 893//893 892//892 -f 703//703 892//892 702//702 -f 702//702 892//892 891//891 -f 702//702 891//891 700//700 -f 700//700 891//891 884//884 -f 700//700 884//884 689//689 -f 689//689 884//884 883//883 -f 689//689 883//883 690//690 -f 690//690 883//883 894//894 -f 690//690 894//894 693//693 -f 693//693 894//894 896//896 -f 693//693 896//896 694//694 -f 694//694 896//896 898//898 -f 694//694 898//898 686//686 -f 686//686 898//898 900//900 -f 686//686 900//900 687//687 -f 687//687 900//900 889//889 -f 687//687 889//889 696//696 -f 696//696 889//889 887//887 -f 696//696 887//887 697//697 -f 697//697 887//887 886//886 -f 697//697 886//886 698//698 -f 698//698 886//886 893//893 -f 682//682 909//909 683//683 -f 683//683 909//909 905//905 -f 683//683 905//905 685//685 -f 685//685 905//905 907//907 -f 685//685 907//907 672//672 -f 672//672 907//907 908//908 -f 672//672 908//908 673//673 -f 673//673 908//908 903//903 -f 673//673 903//903 674//674 -f 674//674 903//903 902//902 -f 674//674 902//902 671//671 -f 671//671 902//902 917//917 -f 671//671 917//917 677//677 -f 677//677 917//917 916//916 -f 677//677 916//916 678//678 -f 678//678 916//916 915//915 -f 678//678 915//915 679//679 -f 679//679 915//915 913//913 -f 679//679 913//913 675//675 -f 675//675 913//913 912//912 -f 675//675 912//912 676//676 -f 676//676 912//912 910//910 -f 676//676 910//910 682//682 -f 682//682 910//910 909//909 -f 668//668 918//918 658//658 -f 658//658 918//918 934//934 -f 658//658 934//934 660//660 -f 660//660 934//934 932//932 -f 660//660 932//932 661//661 -f 661//661 932//932 931//931 -f 661//661 931//931 662//662 -f 662//662 931//931 928//928 -f 662//662 928//928 565//565 -f 565//565 928//928 926//926 -f 565//565 926//926 566//566 -f 566//566 926//926 925//925 -f 566//566 925//925 663//663 -f 663//663 925//925 924//924 -f 663//663 924//924 664//664 -f 664//664 924//924 923//923 -f 664//664 923//923 665//665 -f 665//665 923//923 921//921 -f 665//665 921//921 666//666 -f 666//666 921//921 920//920 -f 666//666 920//920 667//667 -f 667//667 920//920 919//919 -f 667//667 919//919 668//668 -f 668//668 919//919 918//918 -f 655//655 947//947 656//656 -f 656//656 947//947 946//946 -f 656//656 946//946 657//657 -f 657//657 946//946 945//945 -f 657//657 945//945 644//644 -f 644//644 945//945 944//944 -f 644//644 944//944 645//645 -f 645//645 944//944 943//943 -f 645//645 943//943 651//651 -f 651//651 943//943 942//942 -f 651//651 942//942 652//652 -f 652//652 942//942 941//941 -f 652//652 941//941 653//653 -f 653//653 941//941 940//940 -f 653//653 940//940 654//654 -f 654//654 940//940 939//939 -f 654//654 939//939 647//647 -f 647//647 939//939 938//938 -f 647//647 938//938 648//648 -f 648//648 938//938 937//937 -f 648//648 937//937 650//650 -f 650//650 937//937 936//936 -f 650//650 936//936 655//655 -f 655//655 936//936 947//947 -f 728//728 1015//1015 730//730 -f 730//730 1015//1015 1016//1016 -f 730//730 1016//1016 559//559 -f 559//559 1016//1016 1017//1017 -f 559//559 1017//1017 560//560 -f 560//560 1017//1017 966//966 -f 560//560 966//966 635//635 -f 635//635 966//966 967//967 -f 635//635 967//967 636//636 -f 636//636 967//967 968//968 -f 636//636 968//968 637//637 -f 637//637 968//968 974//974 -f 637//637 974//974 639//639 -f 639//639 974//974 972//972 -f 639//639 972//972 570//570 -f 570//570 972//972 965//965 -f 570//570 965//965 571//571 -f 571//571 965//965 963//963 -f 571//571 963//963 556//556 -f 556//556 963//963 962//962 -f 556//556 962//962 727//727 -f 727//727 962//962 1097//1097 -f 727//727 1097//1097 728//728 -f 728//728 1097//1097 1015//1015 -f 629//629 980//980 630//630 -f 630//630 980//980 984//984 -f 630//630 984//984 618//618 -f 618//618 984//984 983//983 -f 618//618 983//983 619//619 -f 619//619 983//983 979//979 -f 619//619 979//979 622//622 -f 622//622 979//979 978//978 -f 622//622 978//978 623//623 -f 623//623 978//978 990//990 -f 623//623 990//990 624//624 -f 624//624 990//990 989//989 -f 624//624 989//989 621//621 -f 621//621 989//989 988//988 -f 621//621 988//988 625//625 -f 625//625 988//988 986//986 -f 625//625 986//986 626//626 -f 626//626 986//986 985//985 -f 626//626 985//985 627//627 -f 627//627 985//985 982//982 -f 627//627 982//982 628//628 -f 628//628 982//982 981//981 -f 628//628 981//981 629//629 -f 629//629 981//981 980//980 -f 581//581 850//850 583//583 -f 583//583 850//850 855//855 -f 583//583 855//855 584//584 -f 584//584 855//855 854//854 -f 584//584 854//854 586//586 -f 586//586 854//854 865//865 -f 586//586 865//865 588//588 -f 588//588 865//865 867//867 -f 588//588 867//867 597//597 -f 597//597 867//867 870//870 -f 597//597 870//870 598//598 -f 598//598 870//870 863//863 -f 598//598 863//863 591//591 -f 591//591 863//863 862//862 -f 591//591 862//862 593//593 -f 593//593 862//862 860//860 -f 593//593 860//860 576//576 -f 576//576 860//860 859//859 -f 576//576 859//859 577//577 -f 577//577 859//859 857//857 -f 577//577 857//857 580//580 -f 580//580 857//857 851//851 -f 580//580 851//851 581//581 -f 581//581 851//851 850//850 -f 745//745 1035//1035 747//747 -f 747//747 1035//1035 1037//1037 -f 747//747 1037//1037 796//796 -f 796//796 1037//1037 1052//1052 -f 796//796 1052//1052 732//732 -f 732//732 1052//1052 1051//1051 -f 732//732 1051//1051 733//733 -f 733//733 1051//1051 1049//1049 -f 733//733 1049//1049 735//735 -f 735//735 1049//1049 1047//1047 -f 735//735 1047//1047 736//736 -f 736//736 1047//1047 1046//1046 -f 736//736 1046//1046 738//738 -f 738//738 1046//1046 1045//1045 -f 738//738 1045//1045 739//739 -f 739//739 1045//1045 1044//1044 -f 739//739 1044//1044 741//741 -f 741//741 1044//1044 1042//1042 -f 741//741 1042//1042 743//743 -f 743//743 1042//1042 1040//1040 -f 743//743 1040//1040 744//744 -f 744//744 1040//1040 1039//1039 -f 744//744 1039//1039 745//745 -f 745//745 1039//1039 1035//1035 -f 758//758 1053//1053 760//760 -f 760//760 1053//1053 1070//1070 -f 760//760 1070//1070 761//761 -f 761//761 1070//1070 1069//1069 -f 761//761 1069//1069 763//763 -f 763//763 1069//1069 1067//1067 -f 763//763 1067//1067 765//765 -f 765//765 1067//1067 1065//1065 -f 765//765 1065//1065 748//748 -f 748//748 1065//1065 1063//1063 -f 748//748 1063//1063 749//749 -f 749//749 1063//1063 1062//1062 -f 749//749 1062//1062 751//751 -f 751//751 1062//1062 1061//1061 -f 751//751 1061//1061 752//752 -f 752//752 1061//1061 1060//1060 -f 752//752 1060//1060 754//754 -f 754//754 1060//1060 1058//1058 -f 754//754 1058//1058 756//756 -f 756//756 1058//1058 1056//1056 -f 756//756 1056//1056 757//757 -f 757//757 1056//1056 1054//1054 -f 757//757 1054//1054 758//758 -f 758//758 1054//1054 1053//1053 -f 803//803 1083//1083 808//808 -f 808//808 1083//1083 1088//1088 -f 808//808 1088//1088 809//809 -f 809//809 1088//1088 1087//1087 -f 809//809 1087//1087 810//810 -f 810//810 1087//1087 1095//1095 -f 810//810 1095//1095 811//811 -f 811//811 1095//1095 1094//1094 -f 811//811 1094//1094 807//807 -f 807//807 1094//1094 1093//1093 -f 807//807 1093//1093 799//799 -f 799//799 1093//1093 1086//1086 -f 799//799 1086//1086 800//800 -f 800//800 1086//1086 1085//1085 -f 800//800 1085//1085 804//804 -f 804//804 1085//1085 1092//1092 -f 804//804 1092//1092 805//805 -f 805//805 1092//1092 1091//1091 -f 805//805 1091//1091 806//806 -f 806//806 1091//1091 1090//1090 -f 806//806 1090//1090 802//802 -f 802//802 1090//1090 1084//1084 -f 802//802 1084//1084 803//803 -f 803//803 1084//1084 1083//1083 -f 828//828 1071//1071 827//827 -f 827//827 1071//1071 1072//1072 -f 827//827 1072//1072 826//826 -f 826//826 1072//1072 1073//1073 -f 826//826 1073//1073 825//825 -f 825//825 1073//1073 1074//1074 -f 825//825 1074//1074 824//824 -f 824//824 1074//1074 1076//1076 -f 824//824 1076//1076 823//823 -f 823//823 1076//1076 1077//1077 -f 823//823 1077//1077 822//822 -f 822//822 1077//1077 1078//1078 -f 822//822 1078//1078 821//821 -f 821//821 1078//1078 1079//1079 -f 821//821 1079//1079 820//820 -f 820//820 1079//1079 1081//1081 -f 820//820 1081//1081 785//785 -f 785//785 1081//1081 1082//1082 -f 1105//1105 1106//1106 1107//1107 -f 1108//1108 1109//1109 1110//1110 -f 1111//1111 1112//1112 1113//1113 -f 1114//1114 1115//1115 1116//1116 -f 1117//1117 1118//1118 1116//1116 -f 1119//1119 1120//1120 1121//1121 -f 1120//1120 1119//1119 1122//1122 -f 1122//1122 1119//1119 1123//1123 -f 1122//1122 1123//1123 1124//1124 -f 1124//1124 1123//1123 1125//1125 -f 1124//1124 1125//1125 1126//1126 -f 1127//1127 1128//1128 1129//1129 -f 1130//1130 1131//1131 1128//1128 -f 1128//1128 1131//1131 1132//1132 -f 1128//1128 1132//1132 1129//1129 -f 1133//1133 1134//1134 1135//1135 -f 1135//1135 1134//1134 1136//1136 -f 1135//1135 1136//1136 1137//1137 -f 1137//1137 1136//1136 1138//1138 -f 1137//1137 1138//1138 1139//1139 -f 1140//1140 1141//1141 1142//1142 -f 1142//1142 1141//1141 1143//1143 -f 1142//1142 1143//1143 1144//1144 -f 1144//1144 1143//1143 1145//1145 -f 1144//1144 1145//1145 1146//1146 -f 1147//1147 1148//1148 1149//1149 -f 1149//1149 1148//1148 1150//1150 -f 1149//1149 1150//1150 1151//1151 -f 1151//1151 1150//1150 1152//1152 -f 1151//1151 1152//1152 1153//1153 -f 1153//1153 1152//1152 1154//1154 -f 1153//1153 1154//1154 1155//1155 -f 1117//1117 1116//1116 1156//1156 -f 1157//1157 1158//1158 1159//1159 -f 1160//1160 1161//1161 1162//1162 -f 1162//1162 1161//1161 1163//1163 -f 1162//1162 1163//1163 1164//1164 -f 1164//1164 1163//1163 1165//1165 -f 1164//1164 1165//1165 1166//1166 -f 1166//1166 1165//1165 1167//1167 -f 1168//1168 1169//1169 1170//1170 -f 1170//1170 1169//1169 1171//1171 -f 1170//1170 1171//1171 1172//1172 -f 1172//1172 1171//1171 1173//1173 -f 1172//1172 1173//1173 1118//1118 -f 1174//1174 1175//1175 1176//1176 -f 1174//1174 1176//1176 1177//1177 -f 1177//1177 1176//1176 1178//1178 -f 1177//1177 1178//1178 1179//1179 -f 1175//1175 1174//1174 1180//1180 -f 1180//1180 1174//1174 1107//1107 -f 1180//1180 1107//1107 1181//1181 -f 1181//1181 1107//1107 1182//1182 -f 1181//1181 1182//1182 1183//1183 -f 1183//1183 1182//1182 1184//1184 -f 1183//1183 1184//1184 1185//1185 -f 1186//1186 1187//1187 1188//1188 -f 1189//1189 1190//1190 1191//1191 -f 1191//1191 1190//1190 1192//1192 -f 1191//1191 1192//1192 1193//1193 -f 1194//1194 1195//1195 1196//1196 -f 1196//1196 1195//1195 1197//1197 -f 1196//1196 1197//1197 1198//1198 -f 1198//1198 1197//1197 1199//1199 -f 1198//1198 1199//1199 1200//1200 -f 1160//1160 1156//1156 1161//1161 -f 1161//1161 1156//1156 1116//1116 -f 1161//1161 1116//1116 1200//1200 -f 1200//1200 1116//1116 1115//1115 -f 1118//1118 1173//1173 1116//1116 -f 1116//1116 1173//1173 1201//1201 -f 1116//1116 1201//1201 1114//1114 -f 1112//1112 1202//1202 1113//1113 -f 1113//1113 1202//1202 1169//1169 -f 1113//1113 1169//1169 1157//1157 -f 1157//1157 1169//1169 1168//1168 -f 1157//1157 1168//1168 1158//1158 -f 1112//1112 1203//1203 1202//1202 -f 1202//1202 1203//1203 1204//1204 -f 1202//1202 1204//1204 1152//1152 -f 1152//1152 1204//1204 1205//1205 -f 1152//1152 1205//1205 1206//1206 -f 1206//1206 1207//1207 1152//1152 -f 1152//1152 1207//1207 1208//1208 -f 1152//1152 1208//1208 1154//1154 -f 1154//1154 1208//1208 1209//1209 -f 1209//1209 1210//1210 1154//1154 -f 1154//1154 1210//1210 1211//1211 -f 1154//1154 1211//1211 1113//1113 -f 1113//1113 1211//1211 1212//1212 -f 1113//1113 1212//1212 1111//1111 -f 1149//1149 1140//1140 1147//1147 -f 1147//1147 1140//1140 1142//1142 -f 1147//1147 1142//1142 1213//1213 -f 1213//1213 1142//1142 1214//1214 -f 1215//1215 1216//1216 1110//1110 -f 1110//1110 1216//1216 1217//1217 -f 1110//1110 1217//1217 1108//1108 -f 1199//1199 1218//1218 1200//1200 -f 1200//1200 1218//1218 1219//1219 -f 1200//1200 1219//1219 1161//1161 -f 1161//1161 1219//1219 1220//1220 -f 1161//1161 1220//1220 1163//1163 -f 1163//1163 1220//1220 1221//1221 -f 1222//1222 1177//1177 1189//1189 -f 1189//1189 1177//1177 1179//1179 -f 1189//1189 1179//1179 1190//1190 -f 1221//1221 1223//1223 1163//1163 -f 1163//1163 1223//1223 1224//1224 -f 1163//1163 1224//1224 1189//1189 -f 1189//1189 1224//1224 1225//1225 -f 1189//1189 1225//1225 1222//1222 -f 1226//1226 1227//1227 1228//1228 -f 1228//1228 1227//1227 1130//1130 -f 1228//1228 1130//1130 1229//1229 -f 1230//1230 1144//1144 1133//1133 -f 1133//1133 1144//1144 1146//1146 -f 1133//1133 1146//1146 1134//1134 -f 1226//1226 1231//1231 1227//1227 -f 1227//1227 1231//1231 1232//1232 -f 1227//1227 1232//1232 1133//1133 -f 1133//1133 1232//1232 1233//1233 -f 1133//1133 1233//1233 1230//1230 -f 1234//1234 1235//1235 1110//1110 -f 1110//1110 1235//1235 1236//1236 -f 1110//1110 1236//1236 1215//1215 -f 1215//1215 1236//1236 1237//1237 -f 1215//1215 1237//1237 1238//1238 -f 1191//1191 1239//1239 1189//1189 -f 1189//1189 1239//1239 1240//1240 -f 1189//1189 1240//1240 1163//1163 -f 1163//1163 1240//1240 1241//1241 -f 1163//1163 1241//1241 1165//1165 -f 1242//1242 1243//1243 1244//1244 -f 1244//1244 1243//1243 1245//1245 -f 1244//1244 1245//1245 1193//1193 -f 1135//1135 1246//1246 1133//1133 -f 1133//1133 1246//1246 1247//1247 -f 1133//1133 1247//1247 1227//1227 -f 1227//1227 1247//1247 1248//1248 -f 1227//1227 1248//1248 1249//1249 -f 1138//1138 1155//1155 1139//1139 -f 1139//1139 1155//1155 1154//1154 -f 1139//1139 1154//1154 1250//1250 -f 1250//1250 1154//1154 1113//1113 -f 1250//1250 1113//1113 1251//1251 -f 1251//1251 1113//1113 1157//1157 -f 1251//1251 1157//1157 1167//1167 -f 1167//1167 1157//1157 1159//1159 -f 1167//1167 1159//1159 1166//1166 -f 1252//1252 1253//1253 1254//1254 -f 1254//1254 1253//1253 1255//1255 -f 1254//1254 1255//1255 1256//1256 -f 1184//1184 1252//1252 1257//1257 -f 1258//1258 1259//1259 1260//1260 -f 1260//1260 1259//1259 1261//1261 -f 1260//1260 1261//1261 1262//1262 -f 1262//1262 1261//1261 1263//1263 -f 1262//1262 1263//1263 1255//1255 -f 1255//1255 1263//1263 1264//1264 -f 1255//1255 1264//1264 1256//1256 -f 1187//1187 1185//1185 1188//1188 -f 1188//1188 1185//1185 1184//1184 -f 1188//1188 1184//1184 1265//1265 -f 1265//1265 1184//1184 1257//1257 -f 1265//1265 1257//1257 1266//1266 -f 1266//1266 1267//1267 1123//1123 -f 1123//1123 1267//1267 1268//1268 -f 1269//1269 1270//1270 1125//1125 -f 1125//1125 1270//1270 1127//1127 -f 1125//1125 1127//1127 1126//1126 -f 1126//1126 1127//1127 1129//1129 -f 1260//1260 1271//1271 1272//1272 -f 1268//1268 1258//1258 1123//1123 -f 1123//1123 1258//1258 1260//1260 -f 1123//1123 1260//1260 1125//1125 -f 1125//1125 1260//1260 1272//1272 -f 1125//1125 1272//1272 1269//1269 -f 1273//1273 1274//1274 1275//1275 -f 1275//1275 1274//1274 1276//1276 -f 1275//1275 1276//1276 1277//1277 -f 1277//1277 1276//1276 1278//1278 -f 1273//1273 1279//1279 1274//1274 -f 1274//1274 1279//1279 1280//1280 -f 1274//1274 1280//1280 1281//1281 -f 1281//1281 1280//1280 1282//1282 -f 1281//1281 1282//1282 1260//1260 -f 1260//1260 1282//1282 1283//1283 -f 1260//1260 1283//1283 1271//1271 -f 1284//1284 1285//1285 1286//1286 -f 1286//1286 1285//1285 1287//1287 -f 1286//1286 1287//1287 1288//1288 -f 1288//1288 1287//1287 1289//1289 -f 1284//1284 1286//1286 1290//1290 -f 1290//1290 1286//1286 1291//1291 -f 1290//1290 1291//1291 1292//1292 -f 1292//1292 1291//1291 1293//1293 -f 1292//1292 1293//1293 1294//1294 -f 1182//1182 1295//1295 1296//1296 -f 1107//1107 1106//1106 1182//1182 -f 1182//1182 1106//1106 1297//1297 -f 1182//1182 1297//1297 1295//1295 -f 1252//1252 1184//1184 1253//1253 -f 1253//1253 1184//1184 1182//1182 -f 1253//1253 1182//1182 1293//1293 -f 1293//1293 1182//1182 1296//1296 -f 1293//1293 1296//1296 1294//1294 -f 1298//1298 1244//1244 1299//1299 -f 1299//1299 1244//1244 1300//1300 -f 1301//1301 1302//1302 1119//1119 -f 1303//1303 1304//1304 1265//1265 -f 1265//1265 1304//1304 1305//1305 -f 1298//1298 1301//1301 1244//1244 -f 1244//1244 1301//1301 1119//1119 -f 1244//1244 1119//1119 1242//1242 -f 1242//1242 1119//1119 1121//1121 -f 1242//1242 1121//1121 1306//1306 -f 1306//1306 1121//1121 1307//1307 -f 1306//1306 1307//1307 1249//1249 -f 1249//1249 1307//1307 1308//1308 -f 1249//1249 1308//1308 1227//1227 -f 1227//1227 1308//1308 1309//1309 -f 1227//1227 1309//1309 1130//1130 -f 1130//1130 1309//1309 1310//1310 -f 1130//1130 1310//1310 1131//1131 -f 1266//1266 1123//1123 1265//1265 -f 1265//1265 1123//1123 1311//1311 -f 1265//1265 1311//1311 1303//1303 -f 1192//1192 1186//1186 1193//1193 -f 1193//1193 1186//1186 1188//1188 -f 1193//1193 1188//1188 1244//1244 -f 1244//1244 1188//1188 1265//1265 -f 1244//1244 1265//1265 1300//1300 -f 1300//1300 1265//1265 1305//1305 -f 1302//1302 1312//1312 1119//1119 -f 1119//1119 1312//1312 1313//1313 -f 1119//1119 1313//1313 1123//1123 -f 1123//1123 1313//1313 1314//1314 -f 1123//1123 1314//1314 1311//1311 -f 1289//1289 1105//1105 1288//1288 -f 1288//1288 1105//1105 1107//1107 -f 1288//1288 1107//1107 1315//1315 -f 1315//1315 1107//1107 1174//1174 -f 1315//1315 1174//1174 1196//1196 -f 1196//1196 1174//1174 1177//1177 -f 1196//1196 1177//1177 1194//1194 -f 1194//1194 1177//1177 1222//1222 -f 1270//1270 1278//1278 1127//1127 -f 1127//1127 1278//1278 1276//1276 -f 1127//1127 1276//1276 1128//1128 -f 1128//1128 1276//1276 1316//1316 -f 1128//1128 1316//1316 1130//1130 -f 1130//1130 1316//1316 1215//1215 -f 1130//1130 1215//1215 1229//1229 -f 1229//1229 1215//1215 1238//1238 -f 1274//1274 1317//1317 1276//1276 -f 1276//1276 1317//1317 1318//1318 -f 1276//1276 1318//1318 1316//1316 -f 1316//1316 1318//1318 1319//1319 -f 1316//1316 1319//1319 1215//1215 -f 1215//1215 1319//1319 1320//1320 -f 1215//1215 1320//1320 1216//1216 -f 1230//1230 1234//1234 1144//1144 -f 1144//1144 1234//1234 1110//1110 -f 1144//1144 1110//1110 1142//1142 -f 1142//1142 1110//1110 1109//1109 -f 1142//1142 1109//1109 1214//1214 -f 1214//1214 1109//1109 1108//1108 -f 1321//1321 1322//1322 1323//1323 -f 1324//1324 1325//1325 1326//1326 -f 1327//1327 1328//1328 1329//1329 -f 1330//1330 1331//1331 1332//1332 -f 1333//1333 1334//1334 1335//1335 -f 1336//1336 1337//1337 1328//1328 -f 1338//1338 1339//1339 1340//1340 -f 1340//1340 1339//1339 1341//1341 -f 1341//1341 1339//1339 1342//1342 -f 1341//1341 1342//1342 1343//1343 -f 1343//1343 1342//1342 1344//1344 -f 1343//1343 1344//1344 1345//1345 -f 1346//1346 1347//1347 1345//1345 -f 1347//1347 1346//1346 1348//1348 -f 1348//1348 1346//1346 1349//1349 -f 1348//1348 1349//1349 1350//1350 -f 1350//1350 1349//1349 1351//1351 -f 1351//1351 1349//1349 1323//1323 -f 1351//1351 1323//1323 1352//1352 -f 1352//1352 1323//1323 1326//1326 -f 1352//1352 1326//1326 1353//1353 -f 1353//1353 1326//1326 1325//1325 -f 1353//1353 1325//1325 1354//1354 -f 1344//1344 1355//1355 1356//1356 -f 1345//1345 1344//1344 1346//1346 -f 1346//1346 1344//1344 1356//1356 -f 1346//1346 1356//1356 1357//1357 -f 1355//1355 1344//1344 1358//1358 -f 1358//1358 1344//1344 1359//1359 -f 1358//1358 1359//1359 1360//1360 -f 1361//1361 1362//1362 1363//1363 -f 1363//1363 1362//1362 1364//1364 -f 1363//1363 1364//1364 1365//1365 -f 1365//1365 1364//1364 1366//1366 -f 1365//1365 1366//1366 1359//1359 -f 1359//1359 1366//1366 1367//1367 -f 1359//1359 1367//1367 1360//1360 -f 1368//1368 1369//1369 1370//1370 -f 1370//1370 1369//1369 1361//1361 -f 1371//1371 1372//1372 1373//1373 -f 1373//1373 1372//1372 1374//1374 -f 1332//1332 1375//1375 1376//1376 -f 1332//1332 1376//1376 1377//1377 -f 1377//1377 1376//1376 1378//1378 -f 1377//1377 1378//1378 1379//1379 -f 1375//1375 1332//1332 1380//1380 -f 1380//1380 1332//1332 1331//1331 -f 1380//1380 1331//1331 1381//1381 -f 1381//1381 1331//1331 1382//1382 -f 1381//1381 1382//1382 1383//1383 -f 1383//1383 1382//1382 1384//1384 -f 1383//1383 1384//1384 1337//1337 -f 1336//1336 1328//1328 1385//1385 -f 1385//1385 1328//1328 1327//1327 -f 1385//1385 1327//1327 1386//1386 -f 1386//1386 1327//1327 1387//1387 -f 1386//1386 1387//1387 1388//1388 -f 1388//1388 1387//1387 1389//1389 -f 1388//1388 1389//1389 1379//1379 -f 1390//1390 1391//1391 1392//1392 -f 1392//1392 1391//1391 1393//1393 -f 1392//1392 1393//1393 1394//1394 -f 1394//1394 1393//1393 1395//1395 -f 1394//1394 1395//1395 1396//1396 -f 1396//1396 1395//1395 1397//1397 -f 1396//1396 1397//1397 1398//1398 -f 1399//1399 1400//1400 1401//1401 -f 1401//1401 1400//1400 1402//1402 -f 1379//1379 1389//1389 1377//1377 -f 1377//1377 1389//1389 1403//1403 -f 1377//1377 1403//1403 1390//1390 -f 1402//1402 1404//1404 1401//1401 -f 1401//1401 1404//1404 1405//1405 -f 1401//1401 1405//1405 1389//1389 -f 1389//1389 1405//1405 1406//1406 -f 1389//1389 1406//1406 1403//1403 -f 1407//1407 1399//1399 1408//1408 -f 1409//1409 1410//1410 1411//1411 -f 1411//1411 1410//1410 1412//1412 -f 1413//1413 1414//1414 1415//1415 -f 1415//1415 1414//1414 1416//1416 -f 1415//1415 1416//1416 1401//1401 -f 1401//1401 1416//1416 1417//1417 -f 1401//1401 1417//1417 1399//1399 -f 1399//1399 1417//1417 1418//1418 -f 1399//1399 1418//1418 1408//1408 -f 1408//1408 1419//1419 1407//1407 -f 1407//1407 1419//1419 1420//1420 -f 1407//1407 1420//1420 1421//1421 -f 1421//1421 1420//1420 1422//1422 -f 1421//1421 1422//1422 1423//1423 -f 1423//1423 1422//1422 1424//1424 -f 1423//1423 1424//1424 1425//1425 -f 1361//1361 1363//1363 1370//1370 -f 1370//1370 1363//1363 1426//1426 -f 1370//1370 1426//1426 1427//1427 -f 1335//1335 1334//1334 1428//1428 -f 1428//1428 1334//1334 1429//1429 -f 1428//1428 1429//1429 1430//1430 -f 1431//1431 1432//1432 1433//1433 -f 1434//1434 1431//1431 1373//1373 -f 1373//1373 1431//1431 1433//1433 -f 1373//1373 1433//1433 1371//1371 -f 1371//1371 1433//1433 1435//1435 -f 1371//1371 1435//1435 1436//1436 -f 1436//1436 1435//1435 1437//1437 -f 1436//1436 1437//1437 1438//1438 -f 1438//1438 1437//1437 1430//1430 -f 1438//1438 1430//1430 1439//1439 -f 1439//1439 1430//1430 1429//1429 -f 1439//1439 1429//1429 1440//1440 -f 1440//1440 1429//1429 1441//1441 -f 1432//1432 1442//1442 1433//1433 -f 1433//1433 1442//1442 1443//1443 -f 1433//1433 1443//1443 1444//1444 -f 1443//1443 1445//1445 1444//1444 -f 1444//1444 1445//1445 1446//1446 -f 1444//1444 1446//1446 1447//1447 -f 1448//1448 1449//1449 1329//1329 -f 1329//1329 1449//1449 1450//1450 -f 1329//1329 1450//1450 1373//1373 -f 1373//1373 1450//1450 1451//1451 -f 1373//1373 1451//1451 1434//1434 -f 1337//1337 1384//1384 1328//1328 -f 1328//1328 1384//1384 1444//1444 -f 1328//1328 1444//1444 1329//1329 -f 1329//1329 1444//1444 1447//1447 -f 1329//1329 1447//1447 1448//1448 -f 1390//1390 1392//1392 1377//1377 -f 1377//1377 1392//1392 1452//1452 -f 1377//1377 1452//1452 1332//1332 -f 1332//1332 1452//1452 1453//1453 -f 1332//1332 1453//1453 1330//1330 -f 1387//1387 1454//1454 1389//1389 -f 1389//1389 1454//1454 1455//1455 -f 1389//1389 1455//1455 1401//1401 -f 1401//1401 1455//1455 1456//1456 -f 1401//1401 1456//1456 1415//1415 -f 1457//1457 1365//1365 1458//1458 -f 1458//1458 1365//1365 1359//1359 -f 1458//1458 1359//1359 1459//1459 -f 1459//1459 1359//1359 1460//1460 -f 1459//1459 1460//1460 1461//1461 -f 1461//1461 1460//1460 1462//1462 -f 1461//1461 1462//1462 1374//1374 -f 1374//1374 1462//1462 1463//1463 -f 1374//1374 1463//1463 1373//1373 -f 1373//1373 1463//1463 1464//1464 -f 1373//1373 1464//1464 1329//1329 -f 1329//1329 1464//1464 1465//1465 -f 1329//1329 1465//1465 1327//1327 -f 1342//1342 1466//1466 1344//1344 -f 1344//1344 1466//1466 1467//1467 -f 1344//1344 1467//1467 1359//1359 -f 1359//1359 1467//1467 1468//1468 -f 1359//1359 1468//1468 1460//1460 -f 1340//1340 1469//1469 1338//1338 -f 1338//1338 1469//1469 1470//1470 -f 1338//1338 1470//1470 1471//1471 -f 1471//1471 1470//1470 1472//1472 -f 1471//1471 1472//1472 1473//1473 -f 1473//1473 1472//1472 1411//1411 -f 1473//1473 1411//1411 1413//1413 -f 1413//1413 1411//1411 1412//1412 -f 1413//1413 1412//1412 1414//1414 -f 1474//1474 1475//1475 1476//1476 -f 1476//1476 1475//1475 1477//1477 -f 1425//1425 1478//1478 1479//1479 -f 1324//1324 1480//1480 1325//1325 -f 1325//1325 1480//1480 1481//1481 -f 1325//1325 1481//1481 1478//1478 -f 1478//1478 1481//1481 1482//1482 -f 1478//1478 1482//1482 1479//1479 -f 1483//1483 1484//1484 1485//1485 -f 1485//1485 1484//1484 1486//1486 -f 1476//1476 1487//1487 1474//1474 -f 1474//1474 1487//1487 1488//1488 -f 1474//1474 1488//1488 1486//1486 -f 1486//1486 1488//1488 1489//1489 -f 1486//1486 1489//1489 1485//1485 -f 1323//1323 1322//1322 1326//1326 -f 1326//1326 1322//1322 1490//1490 -f 1326//1326 1490//1490 1491//1491 -f 1483//1483 1324//1324 1484//1484 -f 1484//1484 1324//1324 1326//1326 -f 1484//1484 1326//1326 1492//1492 -f 1492//1492 1326//1326 1491//1491 -f 1493//1493 1494//1494 1495//1495 -f 1495//1495 1494//1494 1496//1496 -f 1496//1496 1494//1494 1497//1497 -f 1496//1496 1497//1497 1321//1321 -f 1492//1492 1498//1498 1484//1484 -f 1484//1484 1498//1498 1499//1499 -f 1484//1484 1499//1499 1500//1500 -f 1500//1500 1499//1499 1501//1501 -f 1500//1500 1501//1501 1495//1495 -f 1495//1495 1501//1501 1502//1502 -f 1495//1495 1502//1502 1493//1493 -f 1503//1503 1504//1504 1505//1505 -f 1505//1505 1504//1504 1506//1506 -f 1505//1505 1506//1506 1507//1507 -f 1507//1507 1506//1506 1508//1508 -f 1503//1503 1509//1509 1504//1504 -f 1504//1504 1509//1509 1510//1510 -f 1504//1504 1510//1510 1511//1511 -f 1511//1511 1510//1510 1512//1512 -f 1511//1511 1512//1512 1513//1513 -f 1513//1513 1512//1512 1514//1514 -f 1513//1513 1514//1514 1515//1515 -f 1508//1508 1421//1421 1516//1516 -f 1516//1516 1421//1421 1423//1423 -f 1516//1516 1423//1423 1517//1517 -f 1517//1517 1423//1423 1518//1518 -f 1333//1333 1426//1426 1334//1334 -f 1334//1334 1426//1426 1363//1363 -f 1334//1334 1363//1363 1429//1429 -f 1429//1429 1363//1363 1365//1365 -f 1429//1429 1365//1365 1441//1441 -f 1441//1441 1365//1365 1457//1457 -f 1508//1508 1506//1506 1421//1421 -f 1421//1421 1506//1506 1519//1519 -f 1421//1421 1519//1519 1407//1407 -f 1407//1407 1519//1519 1396//1396 -f 1407//1407 1396//1396 1399//1399 -f 1399//1399 1396//1396 1398//1398 -f 1399//1399 1398//1398 1400//1400 -f 1470//1470 1520//1520 1521//1521 -f 1522//1522 1523//1523 1478//1478 -f 1469//1469 1354//1354 1470//1470 -f 1470//1470 1354//1354 1325//1325 -f 1470//1470 1325//1325 1520//1520 -f 1520//1520 1325//1325 1524//1524 -f 1521//1521 1525//1525 1470//1470 -f 1470//1470 1525//1525 1526//1526 -f 1470//1470 1526//1526 1472//1472 -f 1472//1472 1526//1526 1527//1527 -f 1472//1472 1527//1527 1528//1528 -f 1528//1528 1522//1522 1472//1472 -f 1472//1472 1522//1522 1478//1478 -f 1472//1472 1478//1478 1411//1411 -f 1411//1411 1478//1478 1425//1425 -f 1411//1411 1425//1425 1409//1409 -f 1409//1409 1425//1425 1424//1424 -f 1523//1523 1529//1529 1478//1478 -f 1478//1478 1529//1529 1530//1530 -f 1478//1478 1530//1530 1325//1325 -f 1325//1325 1530//1530 1531//1531 -f 1325//1325 1531//1531 1524//1524 -f 1321//1321 1323//1323 1496//1496 -f 1496//1496 1323//1323 1349//1349 -f 1496//1496 1349//1349 1532//1532 -f 1532//1532 1349//1349 1346//1346 -f 1532//1532 1346//1346 1370//1370 -f 1370//1370 1346//1346 1357//1357 -f 1370//1370 1357//1357 1368//1368 -f 1479//1479 1477//1477 1425//1425 -f 1425//1425 1477//1477 1475//1475 -f 1425//1425 1475//1475 1423//1423 -f 1423//1423 1475//1475 1513//1513 -f 1423//1423 1513//1513 1518//1518 -f 1518//1518 1513//1513 1515//1515 -f 1427//1427 1533//1533 1370//1370 -f 1370//1370 1533//1533 1534//1534 -f 1370//1370 1534//1534 1532//1532 -f 1532//1532 1534//1534 1535//1535 -f 1532//1532 1535//1535 1496//1496 -f 1496//1496 1535//1535 1536//1536 -f 1496//1496 1536//1536 1495//1495 -f 1216//1216 1427//1427 1426//1426 -f 1216//1216 1426//1426 1217//1217 -f 1217//1217 1426//1426 1333//1333 -f 1217//1217 1333//1333 1108//1108 -f 1108//1108 1333//1333 1335//1335 -f 1108//1108 1335//1335 1214//1214 -f 1214//1214 1335//1335 1428//1428 -f 1214//1214 1428//1428 1213//1213 -f 1213//1213 1428//1428 1430//1430 -f 1213//1213 1430//1430 1147//1147 -f 1147//1147 1430//1430 1437//1437 -f 1147//1147 1437//1437 1148//1148 -f 1148//1148 1437//1437 1435//1435 -f 1148//1148 1435//1435 1150//1150 -f 1150//1150 1435//1435 1433//1433 -f 1150//1150 1433//1433 1152//1152 -f 1152//1152 1433//1433 1444//1444 -f 1152//1152 1444//1444 1202//1202 -f 1202//1202 1444//1444 1384//1384 -f 1202//1202 1384//1384 1169//1169 -f 1169//1169 1384//1384 1382//1382 -f 1169//1169 1382//1382 1171//1171 -f 1171//1171 1382//1382 1331//1331 -f 1171//1171 1331//1331 1173//1173 -f 1173//1173 1331//1331 1330//1330 -f 1173//1173 1330//1330 1201//1201 -f 1201//1201 1330//1330 1453//1453 -f 1201//1201 1453//1453 1114//1114 -f 1114//1114 1453//1453 1452//1452 -f 1114//1114 1452//1452 1115//1115 -f 1115//1115 1452//1452 1392//1392 -f 1115//1115 1392//1392 1200//1200 -f 1200//1200 1392//1392 1394//1394 -f 1200//1200 1394//1394 1198//1198 -f 1504//1504 1286//1286 1506//1506 -f 1506//1506 1286//1286 1288//1288 -f 1506//1506 1288//1288 1519//1519 -f 1519//1519 1288//1288 1315//1315 -f 1519//1519 1315//1315 1396//1396 -f 1396//1396 1315//1315 1196//1196 -f 1396//1396 1196//1196 1394//1394 -f 1394//1394 1196//1196 1198//1198 -f 1536//1536 1317//1317 1495//1495 -f 1495//1495 1317//1317 1274//1274 -f 1495//1495 1274//1274 1500//1500 -f 1500//1500 1274//1274 1281//1281 -f 1500//1500 1281//1281 1484//1484 -f 1484//1484 1281//1281 1260//1260 -f 1484//1484 1260//1260 1486//1486 -f 1486//1486 1260//1260 1262//1262 -f 1486//1486 1262//1262 1474//1474 -f 1474//1474 1262//1262 1255//1255 -f 1474//1474 1255//1255 1475//1475 -f 1475//1475 1255//1255 1253//1253 -f 1475//1475 1253//1253 1513//1513 -f 1513//1513 1253//1253 1293//1293 -f 1513//1513 1293//1293 1511//1511 -f 1511//1511 1293//1293 1291//1291 -f 1511//1511 1291//1291 1504//1504 -f 1504//1504 1291//1291 1286//1286 -f 1427//1427 1216//1216 1533//1533 -f 1533//1533 1216//1216 1320//1320 -f 1533//1533 1320//1320 1534//1534 -f 1534//1534 1320//1320 1319//1319 -f 1534//1534 1319//1319 1535//1535 -f 1535//1535 1319//1319 1318//1318 -f 1535//1535 1318//1318 1536//1536 -f 1536//1536 1318//1318 1317//1317 -f 1313//1313 1520//1520 1314//1314 -f 1314//1314 1520//1520 1524//1524 -f 1314//1314 1524//1524 1311//1311 -f 1311//1311 1524//1524 1531//1531 -f 1311//1311 1531//1531 1303//1303 -f 1303//1303 1531//1531 1530//1530 -f 1303//1303 1530//1530 1304//1304 -f 1304//1304 1530//1530 1529//1529 -f 1304//1304 1529//1529 1305//1305 -f 1305//1305 1529//1529 1523//1523 -f 1305//1305 1523//1523 1300//1300 -f 1300//1300 1523//1523 1522//1522 -f 1300//1300 1522//1522 1299//1299 -f 1299//1299 1522//1522 1528//1528 -f 1299//1299 1528//1528 1298//1298 -f 1298//1298 1528//1528 1527//1527 -f 1298//1298 1527//1527 1301//1301 -f 1301//1301 1527//1527 1526//1526 -f 1301//1301 1526//1526 1302//1302 -f 1302//1302 1526//1526 1525//1525 -f 1302//1302 1525//1525 1312//1312 -f 1312//1312 1525//1525 1521//1521 -f 1312//1312 1521//1521 1313//1313 -f 1313//1313 1521//1521 1520//1520 -f 1187//1187 1412//1412 1185//1185 -f 1185//1185 1412//1412 1410//1410 -f 1185//1185 1410//1410 1183//1183 -f 1183//1183 1410//1410 1409//1409 -f 1183//1183 1409//1409 1181//1181 -f 1181//1181 1409//1409 1424//1424 -f 1181//1181 1424//1424 1180//1180 -f 1180//1180 1424//1424 1422//1422 -f 1180//1180 1422//1422 1175//1175 -f 1175//1175 1422//1422 1420//1420 -f 1175//1175 1420//1420 1176//1176 -f 1176//1176 1420//1420 1419//1419 -f 1176//1176 1419//1419 1178//1178 -f 1178//1178 1419//1419 1408//1408 -f 1178//1178 1408//1408 1179//1179 -f 1179//1179 1408//1408 1418//1418 -f 1179//1179 1418//1418 1190//1190 -f 1190//1190 1418//1418 1417//1417 -f 1190//1190 1417//1417 1192//1192 -f 1192//1192 1417//1417 1416//1416 -f 1192//1192 1416//1416 1186//1186 -f 1186//1186 1416//1416 1414//1414 -f 1186//1186 1414//1414 1187//1187 -f 1187//1187 1414//1414 1412//1412 -f 1224//1224 1405//1405 1225//1225 -f 1225//1225 1405//1405 1404//1404 -f 1225//1225 1404//1404 1222//1222 -f 1222//1222 1404//1404 1402//1402 -f 1222//1222 1402//1402 1194//1194 -f 1194//1194 1402//1402 1400//1400 -f 1194//1194 1400//1400 1195//1195 -f 1195//1195 1400//1400 1398//1398 -f 1195//1195 1398//1398 1197//1197 -f 1197//1197 1398//1398 1397//1397 -f 1197//1197 1397//1397 1199//1199 -f 1199//1199 1397//1397 1395//1395 -f 1199//1199 1395//1395 1218//1218 -f 1218//1218 1395//1395 1393//1393 -f 1218//1218 1393//1393 1219//1219 -f 1219//1219 1393//1393 1391//1391 -f 1219//1219 1391//1391 1220//1220 -f 1220//1220 1391//1391 1390//1390 -f 1220//1220 1390//1390 1221//1221 -f 1221//1221 1390//1390 1403//1403 -f 1221//1221 1403//1403 1223//1223 -f 1223//1223 1403//1403 1406//1406 -f 1223//1223 1406//1406 1224//1224 -f 1224//1224 1406//1406 1405//1405 -f 1159//1159 1336//1336 1166//1166 -f 1166//1166 1336//1336 1385//1385 -f 1166//1166 1385//1385 1164//1164 -f 1164//1164 1385//1385 1386//1386 -f 1164//1164 1386//1386 1162//1162 -f 1162//1162 1386//1386 1388//1388 -f 1162//1162 1388//1388 1160//1160 -f 1160//1160 1388//1388 1379//1379 -f 1160//1160 1379//1379 1156//1156 -f 1156//1156 1379//1379 1378//1378 -f 1156//1156 1378//1378 1117//1117 -f 1117//1117 1378//1378 1376//1376 -f 1117//1117 1376//1376 1118//1118 -f 1118//1118 1376//1376 1375//1375 -f 1118//1118 1375//1375 1172//1172 -f 1172//1172 1375//1375 1380//1380 -f 1172//1172 1380//1380 1170//1170 -f 1170//1170 1380//1380 1381//1381 -f 1170//1170 1381//1381 1168//1168 -f 1168//1168 1381//1381 1383//1383 -f 1168//1168 1383//1383 1158//1158 -f 1158//1158 1383//1383 1337//1337 -f 1158//1158 1337//1337 1159//1159 -f 1159//1159 1337//1337 1336//1336 -f 1208//1208 1431//1431 1209//1209 -f 1209//1209 1431//1431 1434//1434 -f 1209//1209 1434//1434 1210//1210 -f 1210//1210 1434//1434 1451//1451 -f 1210//1210 1451//1451 1211//1211 -f 1211//1211 1451//1451 1450//1450 -f 1211//1211 1450//1450 1212//1212 -f 1212//1212 1450//1450 1449//1449 -f 1212//1212 1449//1449 1111//1111 -f 1111//1111 1449//1449 1448//1448 -f 1111//1111 1448//1448 1112//1112 -f 1112//1112 1448//1448 1447//1447 -f 1112//1112 1447//1447 1203//1203 -f 1203//1203 1447//1447 1446//1446 -f 1203//1203 1446//1446 1204//1204 -f 1204//1204 1446//1446 1445//1445 -f 1204//1204 1445//1445 1205//1205 -f 1205//1205 1445//1445 1443//1443 -f 1205//1205 1443//1443 1206//1206 -f 1206//1206 1443//1443 1442//1442 -f 1206//1206 1442//1442 1207//1207 -f 1207//1207 1442//1442 1432//1432 -f 1207//1207 1432//1432 1208//1208 -f 1208//1208 1432//1432 1431//1431 -f 1143//1143 1440//1440 1145//1145 -f 1145//1145 1440//1440 1441//1441 -f 1145//1145 1441//1441 1146//1146 -f 1146//1146 1441//1441 1457//1457 -f 1146//1146 1457//1457 1134//1134 -f 1134//1134 1457//1457 1458//1458 -f 1134//1134 1458//1458 1136//1136 -f 1136//1136 1458//1458 1459//1459 -f 1136//1136 1459//1459 1138//1138 -f 1138//1138 1459//1459 1461//1461 -f 1138//1138 1461//1461 1155//1155 -f 1155//1155 1461//1461 1374//1374 -f 1155//1155 1374//1374 1153//1153 -f 1153//1153 1374//1374 1372//1372 -f 1153//1153 1372//1372 1151//1151 -f 1151//1151 1372//1372 1371//1371 -f 1151//1151 1371//1371 1149//1149 -f 1149//1149 1371//1371 1436//1436 -f 1149//1149 1436//1436 1140//1140 -f 1140//1140 1436//1436 1438//1438 -f 1140//1140 1438//1438 1141//1141 -f 1141//1141 1438//1438 1439//1439 -f 1141//1141 1439//1439 1143//1143 -f 1143//1143 1439//1439 1440//1440 -f 1237//1237 1361//1361 1238//1238 -f 1238//1238 1361//1361 1369//1369 -f 1238//1238 1369//1369 1229//1229 -f 1229//1229 1369//1369 1368//1368 -f 1229//1229 1368//1368 1228//1228 -f 1228//1228 1368//1368 1357//1357 -f 1228//1228 1357//1357 1226//1226 -f 1226//1226 1357//1357 1356//1356 -f 1226//1226 1356//1356 1231//1231 -f 1231//1231 1356//1356 1355//1355 -f 1231//1231 1355//1355 1232//1232 -f 1232//1232 1355//1355 1358//1358 -f 1232//1232 1358//1358 1233//1233 -f 1233//1233 1358//1358 1360//1360 -f 1233//1233 1360//1360 1230//1230 -f 1230//1230 1360//1360 1367//1367 -f 1230//1230 1367//1367 1234//1234 -f 1234//1234 1367//1367 1366//1366 -f 1234//1234 1366//1366 1235//1235 -f 1235//1235 1366//1366 1364//1364 -f 1235//1235 1364//1364 1236//1236 -f 1236//1236 1364//1364 1362//1362 -f 1236//1236 1362//1362 1237//1237 -f 1237//1237 1362//1362 1361//1361 -f 1132//1132 1348//1348 1129//1129 -f 1129//1129 1348//1348 1350//1350 -f 1129//1129 1350//1350 1126//1126 -f 1126//1126 1350//1350 1351//1351 -f 1126//1126 1351//1351 1124//1124 -f 1124//1124 1351//1351 1352//1352 -f 1124//1124 1352//1352 1122//1122 -f 1122//1122 1352//1352 1353//1353 -f 1122//1122 1353//1353 1120//1120 -f 1120//1120 1353//1353 1354//1354 -f 1120//1120 1354//1354 1121//1121 -f 1121//1121 1354//1354 1469//1469 -f 1121//1121 1469//1469 1307//1307 -f 1307//1307 1469//1469 1340//1340 -f 1307//1307 1340//1340 1308//1308 -f 1308//1308 1340//1340 1341//1341 -f 1308//1308 1341//1341 1309//1309 -f 1309//1309 1341//1341 1343//1343 -f 1309//1309 1343//1343 1310//1310 -f 1310//1310 1343//1343 1345//1345 -f 1310//1310 1345//1345 1131//1131 -f 1131//1131 1345//1345 1347//1347 -f 1131//1131 1347//1347 1132//1132 -f 1132//1132 1347//1347 1348//1348 -f 1455//1455 1240//1240 1456//1456 -f 1456//1456 1240//1240 1239//1239 -f 1456//1456 1239//1239 1415//1415 -f 1415//1415 1239//1239 1191//1191 -f 1415//1415 1191//1191 1413//1413 -f 1413//1413 1191//1191 1193//1193 -f 1413//1413 1193//1193 1473//1473 -f 1473//1473 1193//1193 1245//1245 -f 1473//1473 1245//1245 1471//1471 -f 1471//1471 1245//1245 1243//1243 -f 1471//1471 1243//1243 1338//1338 -f 1338//1338 1243//1243 1242//1242 -f 1338//1338 1242//1242 1339//1339 -f 1339//1339 1242//1242 1306//1306 -f 1339//1339 1306//1306 1342//1342 -f 1342//1342 1306//1306 1249//1249 -f 1342//1342 1249//1249 1466//1466 -f 1466//1466 1249//1249 1248//1248 -f 1466//1466 1248//1248 1467//1467 -f 1467//1467 1248//1248 1247//1247 -f 1467//1467 1247//1247 1468//1468 -f 1468//1468 1247//1247 1246//1246 -f 1468//1468 1246//1246 1460//1460 -f 1460//1460 1246//1246 1135//1135 -f 1460//1460 1135//1135 1462//1462 -f 1462//1462 1135//1135 1137//1137 -f 1462//1462 1137//1137 1463//1463 -f 1463//1463 1137//1137 1139//1139 -f 1463//1463 1139//1139 1464//1464 -f 1464//1464 1139//1139 1250//1250 -f 1464//1464 1250//1250 1465//1465 -f 1465//1465 1250//1250 1251//1251 -f 1465//1465 1251//1251 1327//1327 -f 1327//1327 1251//1251 1167//1167 -f 1327//1327 1167//1167 1387//1387 -f 1387//1387 1167//1167 1165//1165 -f 1387//1387 1165//1165 1454//1454 -f 1454//1454 1165//1165 1241//1241 -f 1454//1454 1241//1241 1455//1455 -f 1455//1455 1241//1241 1240//1240 -f 1477//1477 1252//1252 1476//1476 -f 1476//1476 1252//1252 1254//1254 -f 1476//1476 1254//1254 1487//1487 -f 1487//1487 1254//1254 1256//1256 -f 1487//1487 1256//1256 1488//1488 -f 1488//1488 1256//1256 1264//1264 -f 1488//1488 1264//1264 1489//1489 -f 1489//1489 1264//1264 1263//1263 -f 1489//1489 1263//1263 1485//1485 -f 1485//1485 1263//1263 1261//1261 -f 1485//1485 1261//1261 1483//1483 -f 1483//1483 1261//1261 1259//1259 -f 1483//1483 1259//1259 1324//1324 -f 1324//1324 1259//1259 1258//1258 -f 1324//1324 1258//1258 1480//1480 -f 1480//1480 1258//1258 1268//1268 -f 1480//1480 1268//1268 1481//1481 -f 1481//1481 1268//1268 1267//1267 -f 1481//1481 1267//1267 1482//1482 -f 1482//1482 1267//1267 1266//1266 -f 1482//1482 1266//1266 1479//1479 -f 1479//1479 1266//1266 1257//1257 -f 1479//1479 1257//1257 1477//1477 -f 1477//1477 1257//1257 1252//1252 -f 1492//1492 1272//1272 1498//1498 -f 1498//1498 1272//1272 1271//1271 -f 1498//1498 1271//1271 1499//1499 -f 1499//1499 1271//1271 1283//1283 -f 1499//1499 1283//1283 1501//1501 -f 1501//1501 1283//1283 1282//1282 -f 1501//1501 1282//1282 1502//1502 -f 1502//1502 1282//1282 1280//1280 -f 1502//1502 1280//1280 1493//1493 -f 1493//1493 1280//1280 1279//1279 -f 1493//1493 1279//1279 1494//1494 -f 1494//1494 1279//1279 1273//1273 -f 1494//1494 1273//1273 1497//1497 -f 1497//1497 1273//1273 1275//1275 -f 1497//1497 1275//1275 1321//1321 -f 1321//1321 1275//1275 1277//1277 -f 1321//1321 1277//1277 1322//1322 -f 1322//1322 1277//1277 1278//1278 -f 1322//1322 1278//1278 1490//1490 -f 1490//1490 1278//1278 1270//1270 -f 1490//1490 1270//1270 1491//1491 -f 1491//1491 1270//1270 1269//1269 -f 1491//1491 1269//1269 1492//1492 -f 1492//1492 1269//1269 1272//1272 -f 1503//1503 1287//1287 1509//1509 -f 1509//1509 1287//1287 1285//1285 -f 1509//1509 1285//1285 1510//1510 -f 1510//1510 1285//1285 1284//1284 -f 1510//1510 1284//1284 1512//1512 -f 1512//1512 1284//1284 1290//1290 -f 1512//1512 1290//1290 1514//1514 -f 1514//1514 1290//1290 1292//1292 -f 1514//1514 1292//1292 1515//1515 -f 1515//1515 1292//1292 1294//1294 -f 1515//1515 1294//1294 1518//1518 -f 1518//1518 1294//1294 1296//1296 -f 1518//1518 1296//1296 1517//1517 -f 1517//1517 1296//1296 1295//1295 -f 1517//1517 1295//1295 1516//1516 -f 1516//1516 1295//1295 1297//1297 -f 1516//1516 1297//1297 1508//1508 -f 1508//1508 1297//1297 1106//1106 -f 1508//1508 1106//1106 1507//1507 -f 1507//1507 1106//1106 1105//1105 -f 1507//1507 1105//1105 1505//1505 -f 1505//1505 1105//1105 1289//1289 -f 1505//1505 1289//1289 1503//1503 -f 1503//1503 1289//1289 1287//1287 -f 1537//1537 1538//1538 1539//1539 -f 1540//1540 1541//1541 1542//1542 -f 1543//1543 1544//1544 1545//1545 -f 1546//1546 1547//1547 1548//1548 -f 1549//1549 1550//1550 1548//1548 -f 1551//1551 1552//1552 1553//1553 -f 1552//1552 1551//1551 1554//1554 -f 1554//1554 1551//1551 1555//1555 -f 1554//1554 1555//1555 1556//1556 -f 1556//1556 1555//1555 1557//1557 -f 1556//1556 1557//1557 1558//1558 -f 1559//1559 1560//1560 1561//1561 -f 1562//1562 1563//1563 1560//1560 -f 1560//1560 1563//1563 1564//1564 -f 1560//1560 1564//1564 1561//1561 -f 1565//1565 1566//1566 1567//1567 -f 1567//1567 1566//1566 1568//1568 -f 1567//1567 1568//1568 1569//1569 -f 1569//1569 1568//1568 1570//1570 -f 1569//1569 1570//1570 1571//1571 -f 1572//1572 1573//1573 1574//1574 -f 1574//1574 1573//1573 1575//1575 -f 1574//1574 1575//1575 1576//1576 -f 1576//1576 1575//1575 1577//1577 -f 1576//1576 1577//1577 1578//1578 -f 1579//1579 1580//1580 1581//1581 -f 1581//1581 1580//1580 1582//1582 -f 1581//1581 1582//1582 1583//1583 -f 1583//1583 1582//1582 1584//1584 -f 1583//1583 1584//1584 1585//1585 -f 1585//1585 1584//1584 1586//1586 -f 1585//1585 1586//1586 1587//1587 -f 1549//1549 1548//1548 1588//1588 -f 1589//1589 1590//1590 1591//1591 -f 1592//1592 1593//1593 1594//1594 -f 1594//1594 1593//1593 1595//1595 -f 1594//1594 1595//1595 1596//1596 -f 1596//1596 1595//1595 1597//1597 -f 1596//1596 1597//1597 1598//1598 -f 1598//1598 1597//1597 1599//1599 -f 1600//1600 1601//1601 1602//1602 -f 1602//1602 1601//1601 1603//1603 -f 1602//1602 1603//1603 1604//1604 -f 1604//1604 1603//1603 1605//1605 -f 1604//1604 1605//1605 1550//1550 -f 1606//1606 1607//1607 1608//1608 -f 1606//1606 1608//1608 1609//1609 -f 1609//1609 1608//1608 1610//1610 -f 1609//1609 1610//1610 1611//1611 -f 1607//1607 1606//1606 1612//1612 -f 1612//1612 1606//1606 1539//1539 -f 1612//1612 1539//1539 1613//1613 -f 1613//1613 1539//1539 1614//1614 -f 1613//1613 1614//1614 1615//1615 -f 1615//1615 1614//1614 1616//1616 -f 1615//1615 1616//1616 1617//1617 -f 1618//1618 1619//1619 1620//1620 -f 1621//1621 1622//1622 1623//1623 -f 1623//1623 1622//1622 1624//1624 -f 1623//1623 1624//1624 1625//1625 -f 1626//1626 1627//1627 1628//1628 -f 1628//1628 1627//1627 1629//1629 -f 1628//1628 1629//1629 1630//1630 -f 1630//1630 1629//1629 1631//1631 -f 1630//1630 1631//1631 1632//1632 -f 1592//1592 1588//1588 1593//1593 -f 1593//1593 1588//1588 1548//1548 -f 1593//1593 1548//1548 1632//1632 -f 1632//1632 1548//1548 1547//1547 -f 1550//1550 1605//1605 1548//1548 -f 1548//1548 1605//1605 1633//1633 -f 1548//1548 1633//1633 1546//1546 -f 1544//1544 1634//1634 1545//1545 -f 1545//1545 1634//1634 1601//1601 -f 1545//1545 1601//1601 1589//1589 -f 1589//1589 1601//1601 1600//1600 -f 1589//1589 1600//1600 1590//1590 -f 1544//1544 1635//1635 1634//1634 -f 1634//1634 1635//1635 1636//1636 -f 1634//1634 1636//1636 1584//1584 -f 1584//1584 1636//1636 1637//1637 -f 1584//1584 1637//1637 1638//1638 -f 1638//1638 1639//1639 1584//1584 -f 1584//1584 1639//1639 1640//1640 -f 1584//1584 1640//1640 1586//1586 -f 1586//1586 1640//1640 1641//1641 -f 1641//1641 1642//1642 1586//1586 -f 1586//1586 1642//1642 1643//1643 -f 1586//1586 1643//1643 1545//1545 -f 1545//1545 1643//1643 1644//1644 -f 1545//1545 1644//1644 1543//1543 -f 1581//1581 1572//1572 1579//1579 -f 1579//1579 1572//1572 1574//1574 -f 1579//1579 1574//1574 1645//1645 -f 1645//1645 1574//1574 1646//1646 -f 1647//1647 1648//1648 1542//1542 -f 1542//1542 1648//1648 1649//1649 -f 1542//1542 1649//1649 1540//1540 -f 1631//1631 1650//1650 1632//1632 -f 1632//1632 1650//1650 1651//1651 -f 1632//1632 1651//1651 1593//1593 -f 1593//1593 1651//1651 1652//1652 -f 1593//1593 1652//1652 1595//1595 -f 1595//1595 1652//1652 1653//1653 -f 1654//1654 1609//1609 1621//1621 -f 1621//1621 1609//1609 1611//1611 -f 1621//1621 1611//1611 1622//1622 -f 1653//1653 1655//1655 1595//1595 -f 1595//1595 1655//1655 1656//1656 -f 1595//1595 1656//1656 1621//1621 -f 1621//1621 1656//1656 1657//1657 -f 1621//1621 1657//1657 1654//1654 -f 1658//1658 1659//1659 1660//1660 -f 1660//1660 1659//1659 1562//1562 -f 1660//1660 1562//1562 1661//1661 -f 1662//1662 1576//1576 1565//1565 -f 1565//1565 1576//1576 1578//1578 -f 1565//1565 1578//1578 1566//1566 -f 1658//1658 1663//1663 1659//1659 -f 1659//1659 1663//1663 1664//1664 -f 1659//1659 1664//1664 1565//1565 -f 1565//1565 1664//1664 1665//1665 -f 1565//1565 1665//1665 1662//1662 -f 1666//1666 1667//1667 1542//1542 -f 1542//1542 1667//1667 1668//1668 -f 1542//1542 1668//1668 1647//1647 -f 1647//1647 1668//1668 1669//1669 -f 1647//1647 1669//1669 1670//1670 -f 1623//1623 1671//1671 1621//1621 -f 1621//1621 1671//1671 1672//1672 -f 1621//1621 1672//1672 1595//1595 -f 1595//1595 1672//1672 1673//1673 -f 1595//1595 1673//1673 1597//1597 -f 1674//1674 1675//1675 1676//1676 -f 1676//1676 1675//1675 1677//1677 -f 1676//1676 1677//1677 1625//1625 -f 1567//1567 1678//1678 1565//1565 -f 1565//1565 1678//1678 1679//1679 -f 1565//1565 1679//1679 1659//1659 -f 1659//1659 1679//1679 1680//1680 -f 1659//1659 1680//1680 1681//1681 -f 1570//1570 1587//1587 1571//1571 -f 1571//1571 1587//1587 1586//1586 -f 1571//1571 1586//1586 1682//1682 -f 1682//1682 1586//1586 1545//1545 -f 1682//1682 1545//1545 1683//1683 -f 1683//1683 1545//1545 1589//1589 -f 1683//1683 1589//1589 1599//1599 -f 1599//1599 1589//1589 1591//1591 -f 1599//1599 1591//1591 1598//1598 -f 1684//1684 1685//1685 1686//1686 -f 1686//1686 1685//1685 1687//1687 -f 1686//1686 1687//1687 1688//1688 -f 1616//1616 1684//1684 1689//1689 -f 1690//1690 1691//1691 1692//1692 -f 1692//1692 1691//1691 1693//1693 -f 1692//1692 1693//1693 1694//1694 -f 1694//1694 1693//1693 1695//1695 -f 1694//1694 1695//1695 1687//1687 -f 1687//1687 1695//1695 1696//1696 -f 1687//1687 1696//1696 1688//1688 -f 1619//1619 1617//1617 1620//1620 -f 1620//1620 1617//1617 1616//1616 -f 1620//1620 1616//1616 1697//1697 -f 1697//1697 1616//1616 1689//1689 -f 1697//1697 1689//1689 1698//1698 -f 1698//1698 1699//1699 1555//1555 -f 1555//1555 1699//1699 1700//1700 -f 1701//1701 1702//1702 1557//1557 -f 1557//1557 1702//1702 1559//1559 -f 1557//1557 1559//1559 1558//1558 -f 1558//1558 1559//1559 1561//1561 -f 1692//1692 1703//1703 1704//1704 -f 1700//1700 1690//1690 1555//1555 -f 1555//1555 1690//1690 1692//1692 -f 1555//1555 1692//1692 1557//1557 -f 1557//1557 1692//1692 1704//1704 -f 1557//1557 1704//1704 1701//1701 -f 1705//1705 1706//1706 1707//1707 -f 1707//1707 1706//1706 1708//1708 -f 1707//1707 1708//1708 1709//1709 -f 1709//1709 1708//1708 1710//1710 -f 1705//1705 1711//1711 1706//1706 -f 1706//1706 1711//1711 1712//1712 -f 1706//1706 1712//1712 1713//1713 -f 1713//1713 1712//1712 1714//1714 -f 1713//1713 1714//1714 1692//1692 -f 1692//1692 1714//1714 1715//1715 -f 1692//1692 1715//1715 1703//1703 -f 1716//1716 1717//1717 1718//1718 -f 1718//1718 1717//1717 1719//1719 -f 1718//1718 1719//1719 1720//1720 -f 1720//1720 1719//1719 1721//1721 -f 1716//1716 1718//1718 1722//1722 -f 1722//1722 1718//1718 1723//1723 -f 1722//1722 1723//1723 1724//1724 -f 1724//1724 1723//1723 1725//1725 -f 1724//1724 1725//1725 1726//1726 -f 1614//1614 1727//1727 1728//1728 -f 1539//1539 1538//1538 1614//1614 -f 1614//1614 1538//1538 1729//1729 -f 1614//1614 1729//1729 1727//1727 -f 1684//1684 1616//1616 1685//1685 -f 1685//1685 1616//1616 1614//1614 -f 1685//1685 1614//1614 1725//1725 -f 1725//1725 1614//1614 1728//1728 -f 1725//1725 1728//1728 1726//1726 -f 1730//1730 1676//1676 1731//1731 -f 1731//1731 1676//1676 1732//1732 -f 1733//1733 1734//1734 1551//1551 -f 1735//1735 1736//1736 1697//1697 -f 1697//1697 1736//1736 1737//1737 -f 1730//1730 1733//1733 1676//1676 -f 1676//1676 1733//1733 1551//1551 -f 1676//1676 1551//1551 1674//1674 -f 1674//1674 1551//1551 1553//1553 -f 1674//1674 1553//1553 1738//1738 -f 1738//1738 1553//1553 1739//1739 -f 1738//1738 1739//1739 1681//1681 -f 1681//1681 1739//1739 1740//1740 -f 1681//1681 1740//1740 1659//1659 -f 1659//1659 1740//1740 1741//1741 -f 1659//1659 1741//1741 1562//1562 -f 1562//1562 1741//1741 1742//1742 -f 1562//1562 1742//1742 1563//1563 -f 1698//1698 1555//1555 1697//1697 -f 1697//1697 1555//1555 1743//1743 -f 1697//1697 1743//1743 1735//1735 -f 1624//1624 1618//1618 1625//1625 -f 1625//1625 1618//1618 1620//1620 -f 1625//1625 1620//1620 1676//1676 -f 1676//1676 1620//1620 1697//1697 -f 1676//1676 1697//1697 1732//1732 -f 1732//1732 1697//1697 1737//1737 -f 1734//1734 1744//1744 1551//1551 -f 1551//1551 1744//1744 1745//1745 -f 1551//1551 1745//1745 1555//1555 -f 1555//1555 1745//1745 1746//1746 -f 1555//1555 1746//1746 1743//1743 -f 1721//1721 1537//1537 1720//1720 -f 1720//1720 1537//1537 1539//1539 -f 1720//1720 1539//1539 1747//1747 -f 1747//1747 1539//1539 1606//1606 -f 1747//1747 1606//1606 1628//1628 -f 1628//1628 1606//1606 1609//1609 -f 1628//1628 1609//1609 1626//1626 -f 1626//1626 1609//1609 1654//1654 -f 1702//1702 1710//1710 1559//1559 -f 1559//1559 1710//1710 1708//1708 -f 1559//1559 1708//1708 1560//1560 -f 1560//1560 1708//1708 1748//1748 -f 1560//1560 1748//1748 1562//1562 -f 1562//1562 1748//1748 1647//1647 -f 1562//1562 1647//1647 1661//1661 -f 1661//1661 1647//1647 1670//1670 -f 1706//1706 1749//1749 1708//1708 -f 1708//1708 1749//1749 1750//1750 -f 1708//1708 1750//1750 1748//1748 -f 1748//1748 1750//1750 1751//1751 -f 1748//1748 1751//1751 1647//1647 -f 1647//1647 1751//1751 1752//1752 -f 1647//1647 1752//1752 1648//1648 -f 1662//1662 1666//1666 1576//1576 -f 1576//1576 1666//1666 1542//1542 -f 1576//1576 1542//1542 1574//1574 -f 1574//1574 1542//1542 1541//1541 -f 1574//1574 1541//1541 1646//1646 -f 1646//1646 1541//1541 1540//1540 -f 1753//1753 1754//1754 1755//1755 -f 1756//1756 1757//1757 1758//1758 -f 1759//1759 1760//1760 1761//1761 -f 1762//1762 1763//1763 1764//1764 -f 1765//1765 1766//1766 1767//1767 -f 1768//1768 1769//1769 1760//1760 -f 1770//1770 1771//1771 1772//1772 -f 1772//1772 1771//1771 1773//1773 -f 1773//1773 1771//1771 1774//1774 -f 1773//1773 1774//1774 1775//1775 -f 1775//1775 1774//1774 1776//1776 -f 1775//1775 1776//1776 1777//1777 -f 1778//1778 1779//1779 1777//1777 -f 1779//1779 1778//1778 1780//1780 -f 1780//1780 1778//1778 1781//1781 -f 1780//1780 1781//1781 1782//1782 -f 1782//1782 1781//1781 1783//1783 -f 1783//1783 1781//1781 1755//1755 -f 1783//1783 1755//1755 1784//1784 -f 1784//1784 1755//1755 1758//1758 -f 1784//1784 1758//1758 1785//1785 -f 1785//1785 1758//1758 1757//1757 -f 1785//1785 1757//1757 1786//1786 -f 1776//1776 1787//1787 1788//1788 -f 1777//1777 1776//1776 1778//1778 -f 1778//1778 1776//1776 1788//1788 -f 1778//1778 1788//1788 1789//1789 -f 1787//1787 1776//1776 1790//1790 -f 1790//1790 1776//1776 1791//1791 -f 1790//1790 1791//1791 1792//1792 -f 1793//1793 1794//1794 1795//1795 -f 1795//1795 1794//1794 1796//1796 -f 1795//1795 1796//1796 1797//1797 -f 1797//1797 1796//1796 1798//1798 -f 1797//1797 1798//1798 1791//1791 -f 1791//1791 1798//1798 1799//1799 -f 1791//1791 1799//1799 1792//1792 -f 1800//1800 1801//1801 1802//1802 -f 1802//1802 1801//1801 1793//1793 -f 1803//1803 1804//1804 1805//1805 -f 1805//1805 1804//1804 1806//1806 -f 1764//1764 1807//1807 1808//1808 -f 1764//1764 1808//1808 1809//1809 -f 1809//1809 1808//1808 1810//1810 -f 1809//1809 1810//1810 1811//1811 -f 1807//1807 1764//1764 1812//1812 -f 1812//1812 1764//1764 1763//1763 -f 1812//1812 1763//1763 1813//1813 -f 1813//1813 1763//1763 1814//1814 -f 1813//1813 1814//1814 1815//1815 -f 1815//1815 1814//1814 1816//1816 -f 1815//1815 1816//1816 1769//1769 -f 1768//1768 1760//1760 1817//1817 -f 1817//1817 1760//1760 1759//1759 -f 1817//1817 1759//1759 1818//1818 -f 1818//1818 1759//1759 1819//1819 -f 1818//1818 1819//1819 1820//1820 -f 1820//1820 1819//1819 1821//1821 -f 1820//1820 1821//1821 1811//1811 -f 1822//1822 1823//1823 1824//1824 -f 1824//1824 1823//1823 1825//1825 -f 1824//1824 1825//1825 1826//1826 -f 1826//1826 1825//1825 1827//1827 -f 1826//1826 1827//1827 1828//1828 -f 1828//1828 1827//1827 1829//1829 -f 1828//1828 1829//1829 1830//1830 -f 1831//1831 1832//1832 1833//1833 -f 1833//1833 1832//1832 1834//1834 -f 1811//1811 1821//1821 1809//1809 -f 1809//1809 1821//1821 1835//1835 -f 1809//1809 1835//1835 1822//1822 -f 1834//1834 1836//1836 1833//1833 -f 1833//1833 1836//1836 1837//1837 -f 1833//1833 1837//1837 1821//1821 -f 1821//1821 1837//1837 1838//1838 -f 1821//1821 1838//1838 1835//1835 -f 1839//1839 1831//1831 1840//1840 -f 1841//1841 1842//1842 1843//1843 -f 1843//1843 1842//1842 1844//1844 -f 1845//1845 1846//1846 1847//1847 -f 1847//1847 1846//1846 1848//1848 -f 1847//1847 1848//1848 1833//1833 -f 1833//1833 1848//1848 1849//1849 -f 1833//1833 1849//1849 1831//1831 -f 1831//1831 1849//1849 1850//1850 -f 1831//1831 1850//1850 1840//1840 -f 1840//1840 1851//1851 1839//1839 -f 1839//1839 1851//1851 1852//1852 -f 1839//1839 1852//1852 1853//1853 -f 1853//1853 1852//1852 1854//1854 -f 1853//1853 1854//1854 1855//1855 -f 1855//1855 1854//1854 1856//1856 -f 1855//1855 1856//1856 1857//1857 -f 1793//1793 1795//1795 1802//1802 -f 1802//1802 1795//1795 1858//1858 -f 1802//1802 1858//1858 1859//1859 -f 1767//1767 1766//1766 1860//1860 -f 1860//1860 1766//1766 1861//1861 -f 1860//1860 1861//1861 1862//1862 -f 1863//1863 1864//1864 1865//1865 -f 1866//1866 1863//1863 1805//1805 -f 1805//1805 1863//1863 1865//1865 -f 1805//1805 1865//1865 1803//1803 -f 1803//1803 1865//1865 1867//1867 -f 1803//1803 1867//1867 1868//1868 -f 1868//1868 1867//1867 1869//1869 -f 1868//1868 1869//1869 1870//1870 -f 1870//1870 1869//1869 1862//1862 -f 1870//1870 1862//1862 1871//1871 -f 1871//1871 1862//1862 1861//1861 -f 1871//1871 1861//1861 1872//1872 -f 1872//1872 1861//1861 1873//1873 -f 1864//1864 1874//1874 1865//1865 -f 1865//1865 1874//1874 1875//1875 -f 1865//1865 1875//1875 1876//1876 -f 1875//1875 1877//1877 1876//1876 -f 1876//1876 1877//1877 1878//1878 -f 1876//1876 1878//1878 1879//1879 -f 1880//1880 1881//1881 1761//1761 -f 1761//1761 1881//1881 1882//1882 -f 1761//1761 1882//1882 1805//1805 -f 1805//1805 1882//1882 1883//1883 -f 1805//1805 1883//1883 1866//1866 -f 1769//1769 1816//1816 1760//1760 -f 1760//1760 1816//1816 1876//1876 -f 1760//1760 1876//1876 1761//1761 -f 1761//1761 1876//1876 1879//1879 -f 1761//1761 1879//1879 1880//1880 -f 1822//1822 1824//1824 1809//1809 -f 1809//1809 1824//1824 1884//1884 -f 1809//1809 1884//1884 1764//1764 -f 1764//1764 1884//1884 1885//1885 -f 1764//1764 1885//1885 1762//1762 -f 1819//1819 1886//1886 1821//1821 -f 1821//1821 1886//1886 1887//1887 -f 1821//1821 1887//1887 1833//1833 -f 1833//1833 1887//1887 1888//1888 -f 1833//1833 1888//1888 1847//1847 -f 1889//1889 1797//1797 1890//1890 -f 1890//1890 1797//1797 1791//1791 -f 1890//1890 1791//1791 1891//1891 -f 1891//1891 1791//1791 1892//1892 -f 1891//1891 1892//1892 1893//1893 -f 1893//1893 1892//1892 1894//1894 -f 1893//1893 1894//1894 1806//1806 -f 1806//1806 1894//1894 1895//1895 -f 1806//1806 1895//1895 1805//1805 -f 1805//1805 1895//1895 1896//1896 -f 1805//1805 1896//1896 1761//1761 -f 1761//1761 1896//1896 1897//1897 -f 1761//1761 1897//1897 1759//1759 -f 1774//1774 1898//1898 1776//1776 -f 1776//1776 1898//1898 1899//1899 -f 1776//1776 1899//1899 1791//1791 -f 1791//1791 1899//1899 1900//1900 -f 1791//1791 1900//1900 1892//1892 -f 1772//1772 1901//1901 1770//1770 -f 1770//1770 1901//1901 1902//1902 -f 1770//1770 1902//1902 1903//1903 -f 1903//1903 1902//1902 1904//1904 -f 1903//1903 1904//1904 1905//1905 -f 1905//1905 1904//1904 1843//1843 -f 1905//1905 1843//1843 1845//1845 -f 1845//1845 1843//1843 1844//1844 -f 1845//1845 1844//1844 1846//1846 -f 1906//1906 1907//1907 1908//1908 -f 1908//1908 1907//1907 1909//1909 -f 1857//1857 1910//1910 1911//1911 -f 1756//1756 1912//1912 1757//1757 -f 1757//1757 1912//1912 1913//1913 -f 1757//1757 1913//1913 1910//1910 -f 1910//1910 1913//1913 1914//1914 -f 1910//1910 1914//1914 1911//1911 -f 1915//1915 1916//1916 1917//1917 -f 1917//1917 1916//1916 1918//1918 -f 1908//1908 1919//1919 1906//1906 -f 1906//1906 1919//1919 1920//1920 -f 1906//1906 1920//1920 1918//1918 -f 1918//1918 1920//1920 1921//1921 -f 1918//1918 1921//1921 1917//1917 -f 1755//1755 1754//1754 1758//1758 -f 1758//1758 1754//1754 1922//1922 -f 1758//1758 1922//1922 1923//1923 -f 1915//1915 1756//1756 1916//1916 -f 1916//1916 1756//1756 1758//1758 -f 1916//1916 1758//1758 1924//1924 -f 1924//1924 1758//1758 1923//1923 -f 1925//1925 1926//1926 1927//1927 -f 1927//1927 1926//1926 1928//1928 -f 1928//1928 1926//1926 1929//1929 -f 1928//1928 1929//1929 1753//1753 -f 1924//1924 1930//1930 1916//1916 -f 1916//1916 1930//1930 1931//1931 -f 1916//1916 1931//1931 1932//1932 -f 1932//1932 1931//1931 1933//1933 -f 1932//1932 1933//1933 1927//1927 -f 1927//1927 1933//1933 1934//1934 -f 1927//1927 1934//1934 1925//1925 -f 1935//1935 1936//1936 1937//1937 -f 1937//1937 1936//1936 1938//1938 -f 1937//1937 1938//1938 1939//1939 -f 1939//1939 1938//1938 1940//1940 -f 1935//1935 1941//1941 1936//1936 -f 1936//1936 1941//1941 1942//1942 -f 1936//1936 1942//1942 1943//1943 -f 1943//1943 1942//1942 1944//1944 -f 1943//1943 1944//1944 1945//1945 -f 1945//1945 1944//1944 1946//1946 -f 1945//1945 1946//1946 1947//1947 -f 1940//1940 1853//1853 1948//1948 -f 1948//1948 1853//1853 1855//1855 -f 1948//1948 1855//1855 1949//1949 -f 1949//1949 1855//1855 1950//1950 -f 1765//1765 1858//1858 1766//1766 -f 1766//1766 1858//1858 1795//1795 -f 1766//1766 1795//1795 1861//1861 -f 1861//1861 1795//1795 1797//1797 -f 1861//1861 1797//1797 1873//1873 -f 1873//1873 1797//1797 1889//1889 -f 1940//1940 1938//1938 1853//1853 -f 1853//1853 1938//1938 1951//1951 -f 1853//1853 1951//1951 1839//1839 -f 1839//1839 1951//1951 1828//1828 -f 1839//1839 1828//1828 1831//1831 -f 1831//1831 1828//1828 1830//1830 -f 1831//1831 1830//1830 1832//1832 -f 1902//1902 1952//1952 1953//1953 -f 1954//1954 1955//1955 1910//1910 -f 1901//1901 1786//1786 1902//1902 -f 1902//1902 1786//1786 1757//1757 -f 1902//1902 1757//1757 1952//1952 -f 1952//1952 1757//1757 1956//1956 -f 1953//1953 1957//1957 1902//1902 -f 1902//1902 1957//1957 1958//1958 -f 1902//1902 1958//1958 1904//1904 -f 1904//1904 1958//1958 1959//1959 -f 1904//1904 1959//1959 1960//1960 -f 1960//1960 1954//1954 1904//1904 -f 1904//1904 1954//1954 1910//1910 -f 1904//1904 1910//1910 1843//1843 -f 1843//1843 1910//1910 1857//1857 -f 1843//1843 1857//1857 1841//1841 -f 1841//1841 1857//1857 1856//1856 -f 1955//1955 1961//1961 1910//1910 -f 1910//1910 1961//1961 1962//1962 -f 1910//1910 1962//1962 1757//1757 -f 1757//1757 1962//1962 1963//1963 -f 1757//1757 1963//1963 1956//1956 -f 1753//1753 1755//1755 1928//1928 -f 1928//1928 1755//1755 1781//1781 -f 1928//1928 1781//1781 1964//1964 -f 1964//1964 1781//1781 1778//1778 -f 1964//1964 1778//1778 1802//1802 -f 1802//1802 1778//1778 1789//1789 -f 1802//1802 1789//1789 1800//1800 -f 1911//1911 1909//1909 1857//1857 -f 1857//1857 1909//1909 1907//1907 -f 1857//1857 1907//1907 1855//1855 -f 1855//1855 1907//1907 1945//1945 -f 1855//1855 1945//1945 1950//1950 -f 1950//1950 1945//1945 1947//1947 -f 1859//1859 1965//1965 1802//1802 -f 1802//1802 1965//1965 1966//1966 -f 1802//1802 1966//1966 1964//1964 -f 1964//1964 1966//1966 1967//1967 -f 1964//1964 1967//1967 1928//1928 -f 1928//1928 1967//1967 1968//1968 -f 1928//1928 1968//1968 1927//1927 -f 1648//1648 1859//1859 1858//1858 -f 1648//1648 1858//1858 1649//1649 -f 1649//1649 1858//1858 1765//1765 -f 1649//1649 1765//1765 1540//1540 -f 1540//1540 1765//1765 1767//1767 -f 1540//1540 1767//1767 1646//1646 -f 1646//1646 1767//1767 1860//1860 -f 1646//1646 1860//1860 1645//1645 -f 1645//1645 1860//1860 1862//1862 -f 1645//1645 1862//1862 1579//1579 -f 1579//1579 1862//1862 1869//1869 -f 1579//1579 1869//1869 1580//1580 -f 1580//1580 1869//1869 1867//1867 -f 1580//1580 1867//1867 1582//1582 -f 1582//1582 1867//1867 1865//1865 -f 1582//1582 1865//1865 1584//1584 -f 1584//1584 1865//1865 1876//1876 -f 1584//1584 1876//1876 1634//1634 -f 1634//1634 1876//1876 1816//1816 -f 1634//1634 1816//1816 1601//1601 -f 1601//1601 1816//1816 1814//1814 -f 1601//1601 1814//1814 1603//1603 -f 1603//1603 1814//1814 1763//1763 -f 1603//1603 1763//1763 1605//1605 -f 1605//1605 1763//1763 1762//1762 -f 1605//1605 1762//1762 1633//1633 -f 1633//1633 1762//1762 1885//1885 -f 1633//1633 1885//1885 1546//1546 -f 1546//1546 1885//1885 1884//1884 -f 1546//1546 1884//1884 1547//1547 -f 1547//1547 1884//1884 1824//1824 -f 1547//1547 1824//1824 1632//1632 -f 1632//1632 1824//1824 1826//1826 -f 1632//1632 1826//1826 1630//1630 -f 1936//1936 1718//1718 1938//1938 -f 1938//1938 1718//1718 1720//1720 -f 1938//1938 1720//1720 1951//1951 -f 1951//1951 1720//1720 1747//1747 -f 1951//1951 1747//1747 1828//1828 -f 1828//1828 1747//1747 1628//1628 -f 1828//1828 1628//1628 1826//1826 -f 1826//1826 1628//1628 1630//1630 -f 1968//1968 1749//1749 1927//1927 -f 1927//1927 1749//1749 1706//1706 -f 1927//1927 1706//1706 1932//1932 -f 1932//1932 1706//1706 1713//1713 -f 1932//1932 1713//1713 1916//1916 -f 1916//1916 1713//1713 1692//1692 -f 1916//1916 1692//1692 1918//1918 -f 1918//1918 1692//1692 1694//1694 -f 1918//1918 1694//1694 1906//1906 -f 1906//1906 1694//1694 1687//1687 -f 1906//1906 1687//1687 1907//1907 -f 1907//1907 1687//1687 1685//1685 -f 1907//1907 1685//1685 1945//1945 -f 1945//1945 1685//1685 1725//1725 -f 1945//1945 1725//1725 1943//1943 -f 1943//1943 1725//1725 1723//1723 -f 1943//1943 1723//1723 1936//1936 -f 1936//1936 1723//1723 1718//1718 -f 1859//1859 1648//1648 1965//1965 -f 1965//1965 1648//1648 1752//1752 -f 1965//1965 1752//1752 1966//1966 -f 1966//1966 1752//1752 1751//1751 -f 1966//1966 1751//1751 1967//1967 -f 1967//1967 1751//1751 1750//1750 -f 1967//1967 1750//1750 1968//1968 -f 1968//1968 1750//1750 1749//1749 -f 1745//1745 1952//1952 1746//1746 -f 1746//1746 1952//1952 1956//1956 -f 1746//1746 1956//1956 1743//1743 -f 1743//1743 1956//1956 1963//1963 -f 1743//1743 1963//1963 1735//1735 -f 1735//1735 1963//1963 1962//1962 -f 1735//1735 1962//1962 1736//1736 -f 1736//1736 1962//1962 1961//1961 -f 1736//1736 1961//1961 1737//1737 -f 1737//1737 1961//1961 1955//1955 -f 1737//1737 1955//1955 1732//1732 -f 1732//1732 1955//1955 1954//1954 -f 1732//1732 1954//1954 1731//1731 -f 1731//1731 1954//1954 1960//1960 -f 1731//1731 1960//1960 1730//1730 -f 1730//1730 1960//1960 1959//1959 -f 1730//1730 1959//1959 1733//1733 -f 1733//1733 1959//1959 1958//1958 -f 1733//1733 1958//1958 1734//1734 -f 1734//1734 1958//1958 1957//1957 -f 1734//1734 1957//1957 1744//1744 -f 1744//1744 1957//1957 1953//1953 -f 1744//1744 1953//1953 1745//1745 -f 1745//1745 1953//1953 1952//1952 -f 1619//1619 1844//1844 1617//1617 -f 1617//1617 1844//1844 1842//1842 -f 1617//1617 1842//1842 1615//1615 -f 1615//1615 1842//1842 1841//1841 -f 1615//1615 1841//1841 1613//1613 -f 1613//1613 1841//1841 1856//1856 -f 1613//1613 1856//1856 1612//1612 -f 1612//1612 1856//1856 1854//1854 -f 1612//1612 1854//1854 1607//1607 -f 1607//1607 1854//1854 1852//1852 -f 1607//1607 1852//1852 1608//1608 -f 1608//1608 1852//1852 1851//1851 -f 1608//1608 1851//1851 1610//1610 -f 1610//1610 1851//1851 1840//1840 -f 1610//1610 1840//1840 1611//1611 -f 1611//1611 1840//1840 1850//1850 -f 1611//1611 1850//1850 1622//1622 -f 1622//1622 1850//1850 1849//1849 -f 1622//1622 1849//1849 1624//1624 -f 1624//1624 1849//1849 1848//1848 -f 1624//1624 1848//1848 1618//1618 -f 1618//1618 1848//1848 1846//1846 -f 1618//1618 1846//1846 1619//1619 -f 1619//1619 1846//1846 1844//1844 -f 1656//1656 1837//1837 1657//1657 -f 1657//1657 1837//1837 1836//1836 -f 1657//1657 1836//1836 1654//1654 -f 1654//1654 1836//1836 1834//1834 -f 1654//1654 1834//1834 1626//1626 -f 1626//1626 1834//1834 1832//1832 -f 1626//1626 1832//1832 1627//1627 -f 1627//1627 1832//1832 1830//1830 -f 1627//1627 1830//1830 1629//1629 -f 1629//1629 1830//1830 1829//1829 -f 1629//1629 1829//1829 1631//1631 -f 1631//1631 1829//1829 1827//1827 -f 1631//1631 1827//1827 1650//1650 -f 1650//1650 1827//1827 1825//1825 -f 1650//1650 1825//1825 1651//1651 -f 1651//1651 1825//1825 1823//1823 -f 1651//1651 1823//1823 1652//1652 -f 1652//1652 1823//1823 1822//1822 -f 1652//1652 1822//1822 1653//1653 -f 1653//1653 1822//1822 1835//1835 -f 1653//1653 1835//1835 1655//1655 -f 1655//1655 1835//1835 1838//1838 -f 1655//1655 1838//1838 1656//1656 -f 1656//1656 1838//1838 1837//1837 -f 1591//1591 1768//1768 1598//1598 -f 1598//1598 1768//1768 1817//1817 -f 1598//1598 1817//1817 1596//1596 -f 1596//1596 1817//1817 1818//1818 -f 1596//1596 1818//1818 1594//1594 -f 1594//1594 1818//1818 1820//1820 -f 1594//1594 1820//1820 1592//1592 -f 1592//1592 1820//1820 1811//1811 -f 1592//1592 1811//1811 1588//1588 -f 1588//1588 1811//1811 1810//1810 -f 1588//1588 1810//1810 1549//1549 -f 1549//1549 1810//1810 1808//1808 -f 1549//1549 1808//1808 1550//1550 -f 1550//1550 1808//1808 1807//1807 -f 1550//1550 1807//1807 1604//1604 -f 1604//1604 1807//1807 1812//1812 -f 1604//1604 1812//1812 1602//1602 -f 1602//1602 1812//1812 1813//1813 -f 1602//1602 1813//1813 1600//1600 -f 1600//1600 1813//1813 1815//1815 -f 1600//1600 1815//1815 1590//1590 -f 1590//1590 1815//1815 1769//1769 -f 1590//1590 1769//1769 1591//1591 -f 1591//1591 1769//1769 1768//1768 -f 1640//1640 1863//1863 1641//1641 -f 1641//1641 1863//1863 1866//1866 -f 1641//1641 1866//1866 1642//1642 -f 1642//1642 1866//1866 1883//1883 -f 1642//1642 1883//1883 1643//1643 -f 1643//1643 1883//1883 1882//1882 -f 1643//1643 1882//1882 1644//1644 -f 1644//1644 1882//1882 1881//1881 -f 1644//1644 1881//1881 1543//1543 -f 1543//1543 1881//1881 1880//1880 -f 1543//1543 1880//1880 1544//1544 -f 1544//1544 1880//1880 1879//1879 -f 1544//1544 1879//1879 1635//1635 -f 1635//1635 1879//1879 1878//1878 -f 1635//1635 1878//1878 1636//1636 -f 1636//1636 1878//1878 1877//1877 -f 1636//1636 1877//1877 1637//1637 -f 1637//1637 1877//1877 1875//1875 -f 1637//1637 1875//1875 1638//1638 -f 1638//1638 1875//1875 1874//1874 -f 1638//1638 1874//1874 1639//1639 -f 1639//1639 1874//1874 1864//1864 -f 1639//1639 1864//1864 1640//1640 -f 1640//1640 1864//1864 1863//1863 -f 1575//1575 1872//1872 1577//1577 -f 1577//1577 1872//1872 1873//1873 -f 1577//1577 1873//1873 1578//1578 -f 1578//1578 1873//1873 1889//1889 -f 1578//1578 1889//1889 1566//1566 -f 1566//1566 1889//1889 1890//1890 -f 1566//1566 1890//1890 1568//1568 -f 1568//1568 1890//1890 1891//1891 -f 1568//1568 1891//1891 1570//1570 -f 1570//1570 1891//1891 1893//1893 -f 1570//1570 1893//1893 1587//1587 -f 1587//1587 1893//1893 1806//1806 -f 1587//1587 1806//1806 1585//1585 -f 1585//1585 1806//1806 1804//1804 -f 1585//1585 1804//1804 1583//1583 -f 1583//1583 1804//1804 1803//1803 -f 1583//1583 1803//1803 1581//1581 -f 1581//1581 1803//1803 1868//1868 -f 1581//1581 1868//1868 1572//1572 -f 1572//1572 1868//1868 1870//1870 -f 1572//1572 1870//1870 1573//1573 -f 1573//1573 1870//1870 1871//1871 -f 1573//1573 1871//1871 1575//1575 -f 1575//1575 1871//1871 1872//1872 -f 1669//1669 1793//1793 1670//1670 -f 1670//1670 1793//1793 1801//1801 -f 1670//1670 1801//1801 1661//1661 -f 1661//1661 1801//1801 1800//1800 -f 1661//1661 1800//1800 1660//1660 -f 1660//1660 1800//1800 1789//1789 -f 1660//1660 1789//1789 1658//1658 -f 1658//1658 1789//1789 1788//1788 -f 1658//1658 1788//1788 1663//1663 -f 1663//1663 1788//1788 1787//1787 -f 1663//1663 1787//1787 1664//1664 -f 1664//1664 1787//1787 1790//1790 -f 1664//1664 1790//1790 1665//1665 -f 1665//1665 1790//1790 1792//1792 -f 1665//1665 1792//1792 1662//1662 -f 1662//1662 1792//1792 1799//1799 -f 1662//1662 1799//1799 1666//1666 -f 1666//1666 1799//1799 1798//1798 -f 1666//1666 1798//1798 1667//1667 -f 1667//1667 1798//1798 1796//1796 -f 1667//1667 1796//1796 1668//1668 -f 1668//1668 1796//1796 1794//1794 -f 1668//1668 1794//1794 1669//1669 -f 1669//1669 1794//1794 1793//1793 -f 1564//1564 1780//1780 1561//1561 -f 1561//1561 1780//1780 1782//1782 -f 1561//1561 1782//1782 1558//1558 -f 1558//1558 1782//1782 1783//1783 -f 1558//1558 1783//1783 1556//1556 -f 1556//1556 1783//1783 1784//1784 -f 1556//1556 1784//1784 1554//1554 -f 1554//1554 1784//1784 1785//1785 -f 1554//1554 1785//1785 1552//1552 -f 1552//1552 1785//1785 1786//1786 -f 1552//1552 1786//1786 1553//1553 -f 1553//1553 1786//1786 1901//1901 -f 1553//1553 1901//1901 1739//1739 -f 1739//1739 1901//1901 1772//1772 -f 1739//1739 1772//1772 1740//1740 -f 1740//1740 1772//1772 1773//1773 -f 1740//1740 1773//1773 1741//1741 -f 1741//1741 1773//1773 1775//1775 -f 1741//1741 1775//1775 1742//1742 -f 1742//1742 1775//1775 1777//1777 -f 1742//1742 1777//1777 1563//1563 -f 1563//1563 1777//1777 1779//1779 -f 1563//1563 1779//1779 1564//1564 -f 1564//1564 1779//1779 1780//1780 -f 1887//1887 1672//1672 1888//1888 -f 1888//1888 1672//1672 1671//1671 -f 1888//1888 1671//1671 1847//1847 -f 1847//1847 1671//1671 1623//1623 -f 1847//1847 1623//1623 1845//1845 -f 1845//1845 1623//1623 1625//1625 -f 1845//1845 1625//1625 1905//1905 -f 1905//1905 1625//1625 1677//1677 -f 1905//1905 1677//1677 1903//1903 -f 1903//1903 1677//1677 1675//1675 -f 1903//1903 1675//1675 1770//1770 -f 1770//1770 1675//1675 1674//1674 -f 1770//1770 1674//1674 1771//1771 -f 1771//1771 1674//1674 1738//1738 -f 1771//1771 1738//1738 1774//1774 -f 1774//1774 1738//1738 1681//1681 -f 1774//1774 1681//1681 1898//1898 -f 1898//1898 1681//1681 1680//1680 -f 1898//1898 1680//1680 1899//1899 -f 1899//1899 1680//1680 1679//1679 -f 1899//1899 1679//1679 1900//1900 -f 1900//1900 1679//1679 1678//1678 -f 1900//1900 1678//1678 1892//1892 -f 1892//1892 1678//1678 1567//1567 -f 1892//1892 1567//1567 1894//1894 -f 1894//1894 1567//1567 1569//1569 -f 1894//1894 1569//1569 1895//1895 -f 1895//1895 1569//1569 1571//1571 -f 1895//1895 1571//1571 1896//1896 -f 1896//1896 1571//1571 1682//1682 -f 1896//1896 1682//1682 1897//1897 -f 1897//1897 1682//1682 1683//1683 -f 1897//1897 1683//1683 1759//1759 -f 1759//1759 1683//1683 1599//1599 -f 1759//1759 1599//1599 1819//1819 -f 1819//1819 1599//1599 1597//1597 -f 1819//1819 1597//1597 1886//1886 -f 1886//1886 1597//1597 1673//1673 -f 1886//1886 1673//1673 1887//1887 -f 1887//1887 1673//1673 1672//1672 -f 1909//1909 1684//1684 1908//1908 -f 1908//1908 1684//1684 1686//1686 -f 1908//1908 1686//1686 1919//1919 -f 1919//1919 1686//1686 1688//1688 -f 1919//1919 1688//1688 1920//1920 -f 1920//1920 1688//1688 1696//1696 -f 1920//1920 1696//1696 1921//1921 -f 1921//1921 1696//1696 1695//1695 -f 1921//1921 1695//1695 1917//1917 -f 1917//1917 1695//1695 1693//1693 -f 1917//1917 1693//1693 1915//1915 -f 1915//1915 1693//1693 1691//1691 -f 1915//1915 1691//1691 1756//1756 -f 1756//1756 1691//1691 1690//1690 -f 1756//1756 1690//1690 1912//1912 -f 1912//1912 1690//1690 1700//1700 -f 1912//1912 1700//1700 1913//1913 -f 1913//1913 1700//1700 1699//1699 -f 1913//1913 1699//1699 1914//1914 -f 1914//1914 1699//1699 1698//1698 -f 1914//1914 1698//1698 1911//1911 -f 1911//1911 1698//1698 1689//1689 -f 1911//1911 1689//1689 1909//1909 -f 1909//1909 1689//1689 1684//1684 -f 1924//1924 1704//1704 1930//1930 -f 1930//1930 1704//1704 1703//1703 -f 1930//1930 1703//1703 1931//1931 -f 1931//1931 1703//1703 1715//1715 -f 1931//1931 1715//1715 1933//1933 -f 1933//1933 1715//1715 1714//1714 -f 1933//1933 1714//1714 1934//1934 -f 1934//1934 1714//1714 1712//1712 -f 1934//1934 1712//1712 1925//1925 -f 1925//1925 1712//1712 1711//1711 -f 1925//1925 1711//1711 1926//1926 -f 1926//1926 1711//1711 1705//1705 -f 1926//1926 1705//1705 1929//1929 -f 1929//1929 1705//1705 1707//1707 -f 1929//1929 1707//1707 1753//1753 -f 1753//1753 1707//1707 1709//1709 -f 1753//1753 1709//1709 1754//1754 -f 1754//1754 1709//1709 1710//1710 -f 1754//1754 1710//1710 1922//1922 -f 1922//1922 1710//1710 1702//1702 -f 1922//1922 1702//1702 1923//1923 -f 1923//1923 1702//1702 1701//1701 -f 1923//1923 1701//1701 1924//1924 -f 1924//1924 1701//1701 1704//1704 -f 1935//1935 1719//1719 1941//1941 -f 1941//1941 1719//1719 1717//1717 -f 1941//1941 1717//1717 1942//1942 -f 1942//1942 1717//1717 1716//1716 -f 1942//1942 1716//1716 1944//1944 -f 1944//1944 1716//1716 1722//1722 -f 1944//1944 1722//1722 1946//1946 -f 1946//1946 1722//1722 1724//1724 -f 1946//1946 1724//1724 1947//1947 -f 1947//1947 1724//1724 1726//1726 -f 1947//1947 1726//1726 1950//1950 -f 1950//1950 1726//1726 1728//1728 -f 1950//1950 1728//1728 1949//1949 -f 1949//1949 1728//1728 1727//1727 -f 1949//1949 1727//1727 1948//1948 -f 1948//1948 1727//1727 1729//1729 -f 1948//1948 1729//1729 1940//1940 -f 1940//1940 1729//1729 1538//1538 -f 1940//1940 1538//1538 1939//1939 -f 1939//1939 1538//1538 1537//1537 -f 1939//1939 1537//1537 1937//1937 -f 1937//1937 1537//1537 1721//1721 -f 1937//1937 1721//1721 1935//1935 -f 1935//1935 1721//1721 1719//1719 -# 4112 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_grey.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_grey.obj deleted file mode 100644 index bab99a607..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_grey.obj +++ /dev/null @@ -1,676 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mid_upper_sivo.obj -# -# Vertices: 160 -# Faces: 340 -# -#### -vn -0.301512 0.301511 0.904534 -v 0.059603 0.101849 0.131000 -vn -0.577350 0.577350 0.577350 -v 0.056453 0.105749 0.131000 -vn -0.301512 -0.301511 0.904534 -v 0.059603 0.079649 0.131000 -vn -0.577351 -0.577350 0.577350 -v 0.056453 0.075749 0.131000 -vn 0.301512 -0.301511 0.904534 -v 0.091603 0.079649 0.131000 -vn 0.577351 -0.577350 0.577350 -v 0.094753 0.075749 0.131000 -vn 0.301512 0.301511 0.904534 -v 0.091603 0.101849 0.131000 -vn 0.577350 0.577350 0.577350 -v 0.094753 0.105749 0.131000 -vn 0.770262 -0.637727 -0.000000 -v 0.094753 0.100349 0.128000 -vn 0.577352 0.577349 -0.577349 -v 0.094753 0.105749 0.125000 -vn 0.770262 -0.552287 -0.318866 -v 0.094753 0.100135 0.128800 -vn 0.770261 -0.552290 0.318863 -v 0.094753 0.100135 0.127200 -vn 0.770261 -0.318869 0.552287 -v 0.094753 0.099549 0.126614 -vn 0.770265 -0.000000 0.637724 -v 0.094753 0.098749 0.126400 -vn 0.770265 -0.000000 0.637724 -v 0.094753 0.090749 0.126400 -vn 0.770260 0.318868 0.552288 -v 0.094753 0.089949 0.126614 -vn 0.770262 -0.637727 -0.000000 -v 0.094753 0.084349 0.128000 -vn 0.770263 0.552289 0.318862 -v 0.094753 0.089364 0.127200 -vn 0.770264 -0.552285 -0.318864 -v 0.094753 0.084135 0.128800 -vn 0.770258 0.637733 0.000000 -v 0.094753 0.089149 0.128000 -vn 0.770259 -0.318865 -0.552292 -v 0.094753 0.083549 0.129386 -vn 0.770261 -0.318869 0.552287 -v 0.094753 0.091549 0.126614 -vn 0.770261 -0.552290 0.318863 -v 0.094753 0.092135 0.127200 -vn 0.770264 -0.637725 -0.000000 -v 0.094753 0.092349 0.128000 -vn 0.770260 0.318868 0.552288 -v 0.094753 0.097949 0.126614 -vn 0.770262 -0.552287 -0.318866 -v 0.094753 0.092135 0.128800 -vn 0.770261 0.552289 0.318865 -v 0.094753 0.097364 0.127200 -vn 0.770259 -0.318866 -0.552290 -v 0.094753 0.091549 0.129386 -vn 0.770261 0.318869 0.552287 -v 0.094753 0.081949 0.126614 -vn 0.577351 -0.577350 -0.577350 -v 0.094753 0.075749 0.125000 -vn 0.770264 -0.000000 0.637725 -v 0.094753 0.082749 0.126400 -vn 0.770261 -0.318868 0.552288 -v 0.094753 0.083549 0.126614 -vn 0.770263 -0.552289 0.318862 -v 0.094753 0.084135 0.127200 -vn 0.770261 0.552290 0.318864 -v 0.094753 0.081364 0.127200 -vn 0.770262 0.637727 0.000000 -v 0.094753 0.081149 0.128000 -vn 0.770262 0.552287 -0.318866 -v 0.094753 0.081364 0.128800 -vn 0.770259 0.318867 -0.552290 -v 0.094753 0.081949 0.129386 -vn 0.770264 0.000000 -0.637725 -v 0.094753 0.082749 0.129600 -vn 0.770264 0.552285 -0.318864 -v 0.094753 0.089364 0.128800 -vn 0.770259 0.318865 -0.552292 -v 0.094753 0.089949 0.129386 -vn 0.770265 0.000000 -0.637725 -v 0.094753 0.090749 0.129600 -vn 0.770262 0.637727 0.000000 -v 0.094753 0.097149 0.128000 -vn 0.770263 0.552285 -0.318867 -v 0.094753 0.097364 0.128800 -vn 0.770259 0.318865 -0.552292 -v 0.094753 0.097949 0.129386 -vn 0.770264 0.000000 -0.637725 -v 0.094753 0.098749 0.129600 -vn 0.770259 -0.318866 -0.552290 -v 0.094753 0.099549 0.129386 -vn -0.770262 -0.552287 -0.318866 -v 0.056453 0.100135 0.128800 -vn -0.770262 -0.637727 0.000000 -v 0.056453 0.100349 0.128000 -vn -0.577350 0.577350 -0.577350 -v 0.056453 0.105749 0.125000 -vn -0.770261 -0.552290 0.318863 -v 0.056453 0.100135 0.127200 -vn -0.770262 -0.552287 -0.318866 -v 0.056453 0.092135 0.128800 -vn -0.770263 0.552285 -0.318867 -v 0.056453 0.097364 0.128800 -vn -0.770262 -0.637727 0.000000 -v 0.056453 0.092349 0.128000 -vn -0.770258 0.637733 -0.000000 -v 0.056453 0.097149 0.128000 -vn -0.770259 0.318865 -0.552292 -v 0.056453 0.089949 0.129386 -vn -0.770260 -0.318868 0.552288 -v 0.056453 0.083549 0.126614 -vn -0.770263 -0.552289 0.318862 -v 0.056453 0.084135 0.127200 -vn -0.770260 -0.637730 0.000000 -v 0.056453 0.084349 0.128000 -vn -0.770264 -0.552285 -0.318864 -v 0.056453 0.084135 0.128800 -vn -0.770265 -0.000000 -0.637724 -v 0.056453 0.090749 0.129600 -vn -0.770264 0.000000 0.637725 -v 0.056453 0.090749 0.126400 -vn -0.770261 -0.318869 0.552286 -v 0.056453 0.091549 0.126614 -vn -0.770261 -0.552290 0.318863 -v 0.056453 0.092135 0.127200 -vn -0.770261 0.552290 0.318863 -v 0.056453 0.081364 0.127200 -vn -0.770261 0.318869 0.552286 -v 0.056453 0.081949 0.126614 -vn -0.577352 -0.577349 -0.577349 -v 0.056453 0.075749 0.125000 -vn -0.770265 0.000000 0.637724 -v 0.056453 0.082749 0.126400 -vn -0.770264 0.552285 -0.318864 -v 0.056453 0.089364 0.128800 -vn -0.770262 0.637727 -0.000000 -v 0.056453 0.089149 0.128000 -vn -0.770263 0.552289 0.318862 -v 0.056453 0.089364 0.127200 -vn -0.770260 0.318868 0.552288 -v 0.056453 0.089949 0.126614 -vn -0.770261 0.552289 0.318865 -v 0.056453 0.097364 0.127200 -vn -0.770261 0.318868 0.552288 -v 0.056453 0.097949 0.126614 -vn -0.770264 0.000000 0.637725 -v 0.056453 0.098749 0.126400 -vn -0.770261 -0.318869 0.552287 -v 0.056453 0.099549 0.126614 -vn -0.770262 0.552287 -0.318866 -v 0.056453 0.081364 0.128800 -vn -0.770262 0.637727 -0.000000 -v 0.056453 0.081149 0.128000 -vn -0.770259 -0.318867 -0.552290 -v 0.056453 0.099549 0.129386 -vn -0.770264 -0.000000 -0.637725 -v 0.056453 0.098749 0.129600 -vn -0.770259 0.318865 -0.552292 -v 0.056453 0.097949 0.129386 -vn -0.770259 -0.318867 -0.552290 -v 0.056453 0.091549 0.129386 -vn -0.770259 -0.318865 -0.552292 -v 0.056453 0.083549 0.129386 -vn -0.770264 -0.000000 -0.637725 -v 0.056453 0.082749 0.129600 -vn -0.770259 0.318866 -0.552290 -v 0.056453 0.081949 0.129386 -vn -0.577350 0.577350 0.577350 -v 0.059603 0.101849 0.139000 -vn 0.577351 0.577350 0.577350 -v 0.091603 0.101849 0.139000 -vn -0.770261 -0.318869 0.552286 -v 0.059603 0.091549 0.133614 -vn -0.770262 0.637727 -0.000000 -v 0.059603 0.097149 0.135094 -vn -0.770262 0.552288 0.318864 -v 0.059603 0.097364 0.134294 -vn -0.770263 0.318863 -0.552287 -v 0.059603 0.081949 0.136480 -vn -0.770261 0.552290 -0.318864 -v 0.059603 0.081364 0.135894 -vn -0.577351 -0.577350 0.577350 -v 0.059603 0.079649 0.139000 -vn -0.770262 0.637727 -0.000000 -v 0.059603 0.081149 0.135094 -vn -0.770260 0.000000 0.637730 -v 0.059603 0.098749 0.133494 -vn -0.770263 -0.318863 0.552287 -v 0.059603 0.099549 0.133708 -vn -0.770263 0.318862 0.552289 -v 0.059603 0.097949 0.133708 -vn -0.770265 0.000000 0.637725 -v 0.059603 0.090749 0.133400 -vn -0.770261 0.552290 0.318863 -v 0.059603 0.081364 0.134294 -vn -0.770263 0.318863 0.552287 -v 0.059603 0.081949 0.133708 -vn -0.770260 0.000000 0.637730 -v 0.059603 0.082749 0.133494 -vn -0.770261 -0.552290 0.318863 -v 0.059603 0.092135 0.134200 -vn -0.770262 -0.637727 0.000000 -v 0.059603 0.092349 0.135000 -vn -0.770262 0.552288 -0.318865 -v 0.059603 0.097364 0.135894 -vn -0.770262 -0.552287 -0.318866 -v 0.059603 0.092135 0.135800 -vn -0.770262 0.318862 -0.552289 -v 0.059603 0.097949 0.136480 -vn -0.770260 -0.318867 -0.552290 -v 0.059603 0.091549 0.136386 -vn -0.770259 0.318865 -0.552292 -v 0.059603 0.089949 0.136386 -vn -0.770264 0.552285 -0.318864 -v 0.059603 0.089364 0.135800 -vn -0.770263 -0.318862 0.552289 -v 0.059603 0.083549 0.133708 -vn -0.770259 0.637731 -0.000000 -v 0.059603 0.089149 0.135000 -vn -0.770263 0.552289 0.318862 -v 0.059603 0.089364 0.134200 -vn -0.770260 0.318868 0.552288 -v 0.059603 0.089949 0.133614 -vn -0.770261 -0.552290 0.318863 -v 0.059603 0.100135 0.134294 -vn -0.770262 -0.637727 0.000000 -v 0.059603 0.100349 0.135094 -vn -0.770261 -0.552290 -0.318863 -v 0.059603 0.100135 0.135894 -vn -0.770263 -0.318863 -0.552287 -v 0.059603 0.099549 0.136480 -vn -0.770260 -0.000000 -0.637730 -v 0.059603 0.098749 0.136694 -vn -0.770264 -0.000000 -0.637725 -v 0.059603 0.090749 0.136600 -vn -0.770263 -0.552289 0.318862 -v 0.059603 0.084135 0.134294 -vn -0.770260 -0.637730 0.000000 -v 0.059603 0.084349 0.135094 -vn -0.770263 -0.552289 -0.318861 -v 0.059603 0.084135 0.135894 -vn -0.770263 -0.318862 -0.552289 -v 0.059603 0.083549 0.136480 -vn -0.770260 -0.000000 -0.637730 -v 0.059603 0.082749 0.136694 -vn 0.577350 -0.577350 0.577350 -v 0.091603 0.079649 0.139000 -vn 0.770260 0.000000 -0.637730 -v 0.091603 0.098749 0.136694 -vn 0.770263 -0.318863 -0.552287 -v 0.091603 0.099549 0.136480 -vn 0.770261 -0.552290 -0.318863 -v 0.091603 0.100135 0.135894 -vn 0.770262 -0.637727 -0.000000 -v 0.091603 0.100349 0.135094 -vn 0.770263 0.318863 0.552287 -v 0.091603 0.081949 0.133708 -vn 0.770261 0.552290 0.318863 -v 0.091603 0.081364 0.134294 -vn 0.770262 0.637727 0.000000 -v 0.091603 0.081149 0.135094 -vn 0.770261 0.552290 -0.318863 -v 0.091603 0.081364 0.135894 -vn 0.770263 -0.552289 0.318862 -v 0.091603 0.084135 0.134294 -vn 0.770263 -0.318862 0.552289 -v 0.091603 0.083549 0.133708 -vn 0.770261 -0.552290 0.318863 -v 0.091603 0.100135 0.134294 -vn 0.770263 -0.318863 0.552287 -v 0.091603 0.099549 0.133708 -vn 0.770260 -0.000000 0.637730 -v 0.091603 0.098749 0.133494 -vn 0.770260 -0.000000 0.637730 -v 0.091603 0.082749 0.133494 -vn 0.770263 0.318863 -0.552287 -v 0.091603 0.081949 0.136480 -vn 0.770260 0.000000 -0.637730 -v 0.091603 0.082749 0.136694 -vn 0.770263 -0.318862 -0.552289 -v 0.091603 0.083549 0.136480 -vn 0.770263 0.318862 -0.552289 -v 0.091603 0.097949 0.136480 -vn 0.770262 0.552288 -0.318864 -v 0.091603 0.097364 0.135894 -vn 0.770265 0.000000 -0.637724 -v 0.091603 0.090749 0.136600 -vn 0.770263 0.637726 0.000000 -v 0.091603 0.097149 0.135094 -vn 0.770260 -0.318866 -0.552290 -v 0.091603 0.091549 0.136386 -vn 0.770262 0.552289 0.318865 -v 0.091603 0.097364 0.134294 -vn 0.770262 -0.552287 -0.318866 -v 0.091603 0.092135 0.135800 -vn 0.770263 0.318862 0.552289 -v 0.091603 0.097949 0.133708 -vn 0.770261 -0.637729 -0.000000 -v 0.091603 0.092349 0.135000 -vn 0.770261 -0.552290 0.318863 -v 0.091603 0.092135 0.134200 -vn 0.770261 -0.318869 0.552286 -v 0.091603 0.091549 0.133614 -vn 0.770264 -0.000000 0.637725 -v 0.091603 0.090749 0.133400 -vn 0.770260 0.318868 0.552288 -v 0.091603 0.089949 0.133614 -vn 0.770260 -0.637730 -0.000000 -v 0.091603 0.084349 0.135094 -vn 0.770263 0.552289 0.318862 -v 0.091603 0.089364 0.134200 -vn 0.770263 -0.552289 -0.318862 -v 0.091603 0.084135 0.135894 -vn 0.770260 0.637730 0.000000 -v 0.091603 0.089149 0.135000 -vn 0.770264 0.552285 -0.318864 -v 0.091603 0.089364 0.135800 -vn 0.770259 0.318865 -0.552292 -v 0.091603 0.089949 0.136386 -# 160 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 1//1 -f 1//1 8//8 2//2 -f 9//9 10//10 11//11 -f 11//11 10//10 8//8 -f 9//9 12//12 10//10 -f 10//10 12//12 13//13 -f 10//10 13//13 14//14 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 10//10 22//22 15//15 -f 22//22 10//10 23//23 -f 23//23 10//10 14//14 -f 23//23 14//14 24//24 -f 24//24 14//14 25//25 -f 24//24 25//25 26//26 -f 26//26 25//25 27//27 -f 26//26 27//27 28//28 -f 29//29 30//30 31//31 -f 31//31 30//30 10//10 -f 31//31 10//10 32//32 -f 32//32 10//10 15//15 -f 32//32 15//15 33//33 -f 33//33 15//15 17//17 -f 29//29 34//34 30//30 -f 30//30 34//34 35//35 -f 30//30 35//35 6//6 -f 35//35 36//36 6//6 -f 6//6 36//36 37//37 -f 6//6 37//37 38//38 -f 21//21 20//20 38//38 -f 38//38 20//20 39//39 -f 38//38 39//39 6//6 -f 6//6 39//39 40//40 -f 6//6 40//40 41//41 -f 27//27 42//42 28//28 -f 28//28 42//42 43//43 -f 28//28 43//43 41//41 -f 41//41 43//43 44//44 -f 41//41 44//44 6//6 -f 6//6 44//44 45//45 -f 6//6 45//45 8//8 -f 8//8 45//45 46//46 -f 8//8 46//46 11//11 -f 47//47 2//2 48//48 -f 48//48 2//2 49//49 -f 48//48 49//49 50//50 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 55//55 56//56 57//57 -f 57//57 58//58 55//55 -f 55//55 58//58 59//59 -f 55//55 59//59 60//60 -f 61//61 62//62 54//54 -f 54//54 62//62 63//63 -f 54//54 63//63 53//53 -f 64//64 65//65 66//66 -f 66//66 65//65 67//67 -f 55//55 68//68 56//56 -f 56//56 68//68 69//69 -f 56//56 69//69 67//67 -f 67//67 69//69 70//70 -f 67//67 70//70 66//66 -f 66//66 70//70 71//71 -f 66//66 71//71 61//61 -f 54//54 72//72 61//61 -f 61//61 72//72 73//73 -f 61//61 73//73 66//66 -f 66//66 73//73 74//74 -f 66//66 74//74 49//49 -f 49//49 74//74 75//75 -f 49//49 75//75 50//50 -f 4//4 76//76 66//66 -f 66//66 76//76 77//77 -f 66//66 77//77 64//64 -f 47//47 78//78 2//2 -f 2//2 78//78 79//79 -f 2//2 79//79 4//4 -f 4//4 79//79 80//80 -f 4//4 80//80 60//60 -f 60//60 80//80 52//52 -f 60//60 52//52 81//81 -f 81//81 52//52 51//51 -f 59//59 82//82 60//60 -f 60//60 82//82 83//83 -f 60//60 83//83 4//4 -f 4//4 83//83 84//84 -f 4//4 84//84 76//76 -f 8//8 10//10 2//2 -f 2//2 10//10 49//49 -f 30//30 6//6 66//66 -f 66//66 6//6 4//4 -f 10//10 30//30 49//49 -f 49//49 30//30 66//66 -f 20//20 69//69 39//39 -f 39//39 69//69 68//68 -f 39//39 68//68 40//40 -f 40//40 68//68 55//55 -f 40//40 55//55 41//41 -f 41//41 55//55 60//60 -f 41//41 60//60 28//28 -f 28//28 60//60 81//81 -f 28//28 81//81 26//26 -f 26//26 81//81 51//51 -f 26//26 51//51 24//24 -f 24//24 51//51 53//53 -f 24//24 53//53 23//23 -f 23//23 53//53 63//63 -f 23//23 63//63 22//22 -f 22//22 63//63 62//62 -f 22//22 62//62 15//15 -f 15//15 62//62 61//61 -f 15//15 61//61 16//16 -f 16//16 61//61 71//71 -f 16//16 71//71 18//18 -f 18//18 71//71 70//70 -f 18//18 70//70 20//20 -f 20//20 70//70 69//69 -f 35//35 77//77 36//36 -f 36//36 77//77 76//76 -f 36//36 76//76 37//37 -f 37//37 76//76 84//84 -f 37//37 84//84 38//38 -f 38//38 84//84 83//83 -f 38//38 83//83 21//21 -f 21//21 83//83 82//82 -f 21//21 82//82 19//19 -f 19//19 82//82 59//59 -f 19//19 59//59 17//17 -f 17//17 59//59 58//58 -f 17//17 58//58 33//33 -f 33//33 58//58 57//57 -f 33//33 57//57 32//32 -f 32//32 57//57 56//56 -f 32//32 56//56 31//31 -f 31//31 56//56 67//67 -f 31//31 67//67 29//29 -f 29//29 67//67 65//65 -f 29//29 65//65 34//34 -f 34//34 65//65 64//64 -f 34//34 64//64 35//35 -f 35//35 64//64 77//77 -f 42//42 54//54 43//43 -f 43//43 54//54 52//52 -f 43//43 52//52 44//44 -f 44//44 52//52 80//80 -f 44//44 80//80 45//45 -f 45//45 80//80 79//79 -f 45//45 79//79 46//46 -f 46//46 79//79 78//78 -f 46//46 78//78 11//11 -f 11//11 78//78 47//47 -f 11//11 47//47 9//9 -f 9//9 47//47 48//48 -f 9//9 48//48 12//12 -f 12//12 48//48 50//50 -f 12//12 50//50 13//13 -f 13//13 50//50 75//75 -f 13//13 75//75 14//14 -f 14//14 75//75 74//74 -f 14//14 74//74 25//25 -f 25//25 74//74 73//73 -f 25//25 73//73 27//27 -f 27//27 73//73 72//72 -f 27//27 72//72 42//42 -f 42//42 72//72 54//54 -f 85//85 86//86 1//1 -f 1//1 86//86 7//7 -f 87//87 88//88 89//89 -f 90//90 91//91 92//92 -f 92//92 91//91 93//93 -f 92//92 93//93 3//3 -f 1//1 94//94 95//95 -f 94//94 1//1 96//96 -f 96//96 1//1 3//3 -f 96//96 3//3 89//89 -f 89//89 3//3 97//97 -f 89//89 97//97 87//87 -f 93//93 98//98 3//3 -f 3//3 98//98 99//99 -f 3//3 99//99 100//100 -f 87//87 101//101 88//88 -f 88//88 101//101 102//102 -f 88//88 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 100//100 -f 100//100 110//110 111//111 -f 100//100 111//111 3//3 -f 3//3 111//111 112//112 -f 3//3 112//112 97//97 -f 95//95 113//113 1//1 -f 1//1 113//113 114//114 -f 1//1 114//114 85//85 -f 85//85 114//114 115//115 -f 85//85 115//115 116//116 -f 116//116 117//117 85//85 -f 85//85 117//117 105//105 -f 85//85 105//105 118//118 -f 118//118 105//105 106//106 -f 109//109 119//119 107//107 -f 107//107 119//119 120//120 -f 107//107 120//120 118//118 -f 118//118 120//120 121//121 -f 118//118 121//121 85//85 -f 85//85 121//121 122//122 -f 85//85 122//122 92//92 -f 92//92 122//122 123//123 -f 92//92 123//123 90//90 -f 124//124 92//92 5//5 -f 5//5 92//92 3//3 -f 86//86 125//125 126//126 -f 126//126 127//127 86//86 -f 86//86 127//127 128//128 -f 86//86 128//128 7//7 -f 129//129 130//130 5//5 -f 5//5 130//130 131//131 -f 5//5 131//131 124//124 -f 124//124 131//131 132//132 -f 133//133 134//134 7//7 -f 128//128 135//135 7//7 -f 7//7 135//135 136//136 -f 7//7 136//136 137//137 -f 7//7 134//134 5//5 -f 5//5 134//134 138//138 -f 5//5 138//138 129//129 -f 132//132 139//139 124//124 -f 124//124 139//139 140//140 -f 124//124 140//140 141//141 -f 125//125 86//86 142//142 -f 142//142 86//86 124//124 -f 142//142 124//124 143//143 -f 143//143 124//124 144//144 -f 143//143 144//144 145//145 -f 145//145 144//144 146//146 -f 145//145 146//146 147//147 -f 147//147 146//146 148//148 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 137//137 -f 137//137 150//150 151//151 -f 137//137 151//151 7//7 -f 151//151 152//152 7//7 -f 7//7 152//152 153//153 -f 7//7 153//153 133//133 -f 133//133 153//153 154//154 -f 133//133 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 158//158 -f 157//157 158//158 141//141 -f 141//141 158//158 159//159 -f 141//141 159//159 124//124 -f 124//124 159//159 160//160 -f 124//124 160//160 144//144 -f 92//92 124//124 85//85 -f 85//85 124//124 86//86 -f 158//158 110//110 159//159 -f 159//159 110//110 108//108 -f 159//159 108//108 160//160 -f 160//160 108//108 107//107 -f 160//160 107//107 144//144 -f 144//144 107//107 118//118 -f 144//144 118//118 146//146 -f 146//146 118//118 106//106 -f 146//146 106//106 148//148 -f 148//148 106//106 104//104 -f 148//148 104//104 150//150 -f 150//150 104//104 102//102 -f 150//150 102//102 151//151 -f 151//151 102//102 101//101 -f 151//151 101//101 152//152 -f 152//152 101//101 87//87 -f 152//152 87//87 153//153 -f 153//153 87//87 97//97 -f 153//153 97//97 154//154 -f 154//154 97//97 112//112 -f 154//154 112//112 156//156 -f 156//156 112//112 111//111 -f 156//156 111//111 158//158 -f 158//158 111//111 110//110 -f 145//145 88//88 143//143 -f 143//143 88//88 103//103 -f 143//143 103//103 142//142 -f 142//142 103//103 105//105 -f 142//142 105//105 125//125 -f 125//125 105//105 117//117 -f 125//125 117//117 126//126 -f 126//126 117//117 116//116 -f 126//126 116//116 127//127 -f 127//127 116//116 115//115 -f 127//127 115//115 128//128 -f 128//128 115//115 114//114 -f 128//128 114//114 135//135 -f 135//135 114//114 113//113 -f 135//135 113//113 136//136 -f 136//136 113//113 95//95 -f 136//136 95//95 137//137 -f 137//137 95//95 94//94 -f 137//137 94//94 149//149 -f 149//149 94//94 96//96 -f 149//149 96//96 147//147 -f 147//147 96//96 89//89 -f 147//147 89//89 145//145 -f 145//145 89//89 88//88 -f 131//131 93//93 132//132 -f 132//132 93//93 91//91 -f 132//132 91//91 139//139 -f 139//139 91//91 90//90 -f 139//139 90//90 140//140 -f 140//140 90//90 123//123 -f 140//140 123//123 141//141 -f 141//141 123//123 122//122 -f 141//141 122//122 157//157 -f 157//157 122//122 121//121 -f 157//157 121//121 155//155 -f 155//155 121//121 120//120 -f 155//155 120//120 133//133 -f 133//133 120//120 119//119 -f 133//133 119//119 134//134 -f 134//134 119//119 109//109 -f 134//134 109//109 138//138 -f 138//138 109//109 100//100 -f 138//138 100//100 129//129 -f 129//129 100//100 99//99 -f 129//129 99//99 130//130 -f 130//130 99//99 98//98 -f 130//130 98//98 131//131 -f 131//131 98//98 93//93 -# 340 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_motor.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_motor.obj deleted file mode 100644 index e171c78cd..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_motor.obj +++ /dev/null @@ -1,14328 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mid_upper_motor.obj -# -# Vertices: 3504 -# Faces: 7304 -# -#### -vn -0.577350 0.788675 -0.211324 -v 0.064603 0.093129 0.150142 -vn -0.577350 -0.211326 -0.788675 -v 0.064603 0.083170 0.144392 -vn -0.904534 0.411872 -0.110361 -v 0.064603 0.092379 0.151441 -vn -0.904534 -0.110361 -0.411873 -v 0.064603 0.082420 0.145691 -vn -0.678875 0.280988 -0.678362 -v 0.064603 0.077007 0.142566 -vn 0.000000 -0.499997 0.866027 -v 0.064603 0.077642 0.144666 -vn 0.000000 0.000002 -1.000000 -v 0.064603 0.077142 0.146532 -vn -0.000000 0.866023 0.500004 -v 0.064603 0.056272 0.181980 -vn 0.000001 -0.500005 -0.866022 -v 0.064603 0.077642 0.146398 -vn 0.000008 0.499997 0.866027 -v 0.064603 0.056638 0.181614 -vn 0.000003 -0.866026 -0.499998 -v 0.064603 0.078009 0.146032 -vn 0.000000 -0.866030 -0.499992 -v 0.064603 0.074026 0.192230 -vn 0.000000 0.499994 -0.866029 -v 0.064603 0.094656 0.156798 -vn -0.000001 -1.000000 -0.000004 -v 0.064603 0.074160 0.191730 -vn 0.000000 -0.866027 0.499998 -v 0.064603 0.074026 0.191230 -vn 0.000000 -0.866023 0.500004 -v 0.064603 0.078009 0.145032 -vn 0.000000 -1.000000 -0.000004 -v 0.064603 0.078142 0.145532 -vn 0.000006 -0.499997 0.866027 -v 0.064603 0.073660 0.190864 -vn -0.000000 0.866024 -0.500003 -v 0.064603 0.094290 0.156432 -vn -0.000000 1.000000 0.000004 -v 0.064603 0.094156 0.155932 -vn -0.678874 0.446989 -0.582522 -v 0.064603 0.097791 0.154566 -vn 0.000000 -0.866026 0.499998 -v 0.064603 0.096022 0.155432 -vn -0.653229 0.655721 -0.378579 -v 0.064603 0.098157 0.154933 -vn 0.000000 -1.000000 -0.000000 -v 0.064603 0.096156 0.155932 -vn -0.653226 0.757163 -0.000003 -v 0.064603 0.098291 0.155433 -vn -0.678874 0.678363 0.280987 -v 0.064603 0.098157 0.155933 -vn 0.000000 -0.866026 -0.499998 -v 0.064603 0.096022 0.156432 -vn 0.000000 -0.500006 -0.866022 -v 0.064603 0.095656 0.156798 -vn 0.003864 0.825662 0.564151 -v 0.064603 0.077657 0.191440 -vn -0.000000 0.000002 -1.000000 -v 0.064603 0.095156 0.156932 -vn 0.004459 0.104081 0.994559 -v 0.064603 0.073850 0.193912 -vn 0.000000 0.000000 -1.000000 -v 0.064603 0.073160 0.192730 -vn 0.001694 -0.209111 0.977890 -v 0.064603 0.072288 0.193830 -vn -0.000000 0.500006 -0.866022 -v 0.064603 0.072660 0.192596 -vn -0.000000 -0.430512 0.902585 -v 0.064603 0.070827 0.193270 -vn -0.000000 0.866026 -0.499998 -v 0.064603 0.072294 0.192230 -vn 0.000829 -0.565851 0.824507 -v 0.064603 0.056971 0.185270 -vn -0.000001 1.000000 -0.000004 -v 0.064603 0.072160 0.191730 -vn 0.005792 0.406416 0.913670 -v 0.064603 0.075361 0.193507 -vn 0.000000 -0.500006 -0.866022 -v 0.064603 0.073660 0.192596 -vn 0.006980 0.668856 0.743359 -v 0.064603 0.076673 0.192655 -vn -0.653228 -0.378578 -0.655722 -v 0.064603 0.076007 0.142566 -vn -0.678873 -0.582522 -0.446989 -v 0.064603 0.075641 0.142933 -vn -0.653226 -0.000000 -0.757163 -v 0.064603 0.076507 0.142433 -vn 0.000000 0.499994 0.866029 -v 0.064603 0.076642 0.144666 -vn 0.000000 0.000002 1.000000 -v 0.064603 0.077142 0.144532 -vn 0.000000 -0.000000 1.000000 -v 0.064603 0.057138 0.181480 -vn 0.000000 -0.499997 0.866027 -v 0.064603 0.057638 0.181614 -vn 0.000000 -0.866025 0.500001 -v 0.064603 0.058004 0.181980 -vn -0.000002 0.499997 0.866027 -v 0.064603 0.072660 0.190864 -vn 0.000000 -1.000000 -0.000004 -v 0.064603 0.058138 0.182480 -vn 0.000000 0.866023 0.500004 -v 0.064603 0.072294 0.191230 -vn 0.000000 -0.866028 -0.499995 -v 0.064603 0.058004 0.182980 -vn -0.000000 -0.500006 -0.866022 -v 0.064603 0.057638 0.183346 -vn 0.000000 0.000000 -1.000000 -v 0.064603 0.057138 0.183480 -vn 0.002423 -0.742799 0.669511 -v 0.064603 0.055755 0.184285 -vn 0.000000 0.500006 -0.866022 -v 0.064603 0.056638 0.183346 -vn 0.004299 -0.913359 0.407133 -v 0.064603 0.054903 0.182973 -vn -0.000000 0.866027 0.499997 -v 0.064603 0.094290 0.155432 -vn 0.000000 0.000000 1.000000 -v 0.064603 0.073160 0.190730 -vn -0.000001 0.500003 0.866024 -v 0.064603 0.094656 0.155066 -vn 0.000000 0.000002 1.000000 -v 0.064603 0.095156 0.154932 -vn -0.000001 -0.500006 0.866022 -v 0.064603 0.095656 0.155066 -vn 0.000004 0.500003 -0.866024 -v 0.064603 0.076642 0.146398 -vn -0.000000 0.866027 -0.499997 -v 0.064603 0.076276 0.146032 -vn 0.001160 -0.902482 -0.430726 -v 0.064603 0.055141 0.178440 -vn -0.000000 1.000000 -0.000004 -v 0.064603 0.076142 0.145532 -vn -0.000000 0.866024 0.500002 -v 0.064603 0.076276 0.145032 -vn -0.000000 0.866026 -0.499998 -v 0.064603 0.056272 0.182980 -vn 0.000000 1.000000 -0.000004 -v 0.064603 0.056138 0.182480 -vn 0.005610 -0.994471 0.104863 -v 0.064603 0.054498 0.181462 -vn 0.003335 -0.977668 -0.210127 -v 0.064603 0.054580 0.179900 -vn 0.904534 0.411872 -0.110361 -v 0.086603 0.092379 0.151441 -vn 0.678873 0.446989 -0.582522 -v 0.086603 0.097791 0.154566 -vn 0.770263 -0.318867 0.552285 -v 0.086603 0.095656 0.155066 -vn 0.577350 -0.211325 -0.788675 -v 0.086603 0.083170 0.144392 -vn 0.577350 0.788676 -0.211324 -v 0.086603 0.093129 0.150142 -vn 0.904534 -0.110361 -0.411872 -v 0.086603 0.082420 0.145691 -vn 0.770260 -0.552291 -0.318864 -v 0.086603 0.096022 0.156432 -vn 0.770263 -0.637726 0.000000 -v 0.086603 0.096156 0.155932 -vn 0.678874 0.678363 0.280987 -v 0.086603 0.098157 0.155933 -vn 0.770258 0.318862 0.552294 -v 0.086603 0.076642 0.144666 -vn 0.770266 0.552283 0.318863 -v 0.086603 0.076276 0.145032 -vn 0.678873 -0.582522 -0.446989 -v 0.086603 0.075641 0.142933 -vn 0.770259 0.637731 -0.000002 -v 0.086603 0.076142 0.145532 -vn -0.003383 -0.901536 -0.432692 -v 0.086603 0.055141 0.178440 -vn 0.770263 0.552289 -0.318861 -v 0.086603 0.076276 0.146032 -vn 0.770259 0.318867 -0.552290 -v 0.086603 0.076642 0.146398 -vn 0.770258 0.318863 -0.552295 -v 0.086603 0.094656 0.156798 -vn 0.770265 -0.552286 0.318861 -v 0.086603 0.074026 0.191230 -vn 0.770260 -0.318863 0.552291 -v 0.086603 0.073660 0.190864 -vn 0.770261 0.318866 0.552289 -v 0.086603 0.094656 0.155066 -vn 0.770263 0.552289 0.318861 -v 0.086603 0.094290 0.155432 -vn 0.770263 -0.637727 -0.000002 -v 0.086603 0.078142 0.145532 -vn 0.770263 -0.552285 0.318865 -v 0.086603 0.078009 0.145032 -vn 0.653226 0.757163 -0.000003 -v 0.086603 0.098291 0.155433 -vn 0.653228 0.655721 -0.378579 -v 0.086603 0.098157 0.154933 -vn 0.770260 -0.552291 0.318864 -v 0.086603 0.096022 0.155432 -vn 0.770263 0.000000 0.637727 -v 0.086603 0.073160 0.190730 -vn 0.770260 0.318863 0.552291 -v 0.086603 0.072660 0.190864 -vn 0.770264 -0.552286 0.318863 -v 0.086603 0.058004 0.181980 -vn 0.770259 -0.318863 0.552292 -v 0.086603 0.057638 0.181614 -vn 0.770263 0.000000 0.637727 -v 0.086603 0.057138 0.181480 -vn 0.678875 0.280988 -0.678362 -v 0.086603 0.077007 0.142566 -vn 0.770260 -0.318863 0.552291 -v 0.086603 0.077642 0.144666 -vn 0.770263 0.000001 0.637726 -v 0.086603 0.077142 0.144532 -vn 0.653226 0.000000 -0.757163 -v 0.086603 0.076507 0.142433 -vn 0.653228 -0.378578 -0.655722 -v 0.086603 0.076007 0.142566 -vn -0.006827 -0.913524 0.406727 -v 0.086603 0.054903 0.182973 -vn -0.006827 -0.994499 0.104526 -v 0.086603 0.054498 0.181462 -vn 0.770263 0.552286 0.318866 -v 0.086603 0.056272 0.181980 -vn -0.006827 -0.978125 -0.207908 -v 0.086603 0.054580 0.179900 -vn 0.770260 0.318863 0.552291 -v 0.086603 0.056638 0.181614 -vn -0.003380 -0.564403 0.825493 -v 0.086603 0.056971 0.185270 -vn 0.770262 0.637728 -0.000002 -v 0.086603 0.072160 0.191730 -vn -0.003380 -0.432697 0.901533 -v 0.086603 0.070827 0.193270 -vn 0.770260 0.552291 -0.318864 -v 0.086603 0.072294 0.192230 -vn -0.006826 -0.207906 0.978125 -v 0.086603 0.072288 0.193830 -vn 0.770263 0.318867 -0.552286 -v 0.086603 0.072660 0.192596 -vn -0.006827 0.104527 0.994499 -v 0.086603 0.073850 0.193912 -vn 0.770263 0.000001 0.637727 -v 0.086603 0.095156 0.154932 -vn 0.770260 -0.552291 -0.318864 -v 0.086603 0.078009 0.146032 -vn 0.770263 -0.318867 -0.552285 -v 0.086603 0.077642 0.146398 -vn 0.770258 0.637733 0.000002 -v 0.086603 0.094156 0.155932 -vn 0.770263 0.000001 -0.637726 -v 0.086603 0.077142 0.146532 -vn 0.770266 0.552284 -0.318863 -v 0.086603 0.094290 0.156432 -vn 0.770263 -0.318867 -0.552285 -v 0.086603 0.095656 0.156798 -vn -0.003384 0.825490 0.564406 -v 0.086603 0.077657 0.191440 -vn 0.770263 0.000001 -0.637726 -v 0.086603 0.095156 0.156932 -vn 0.770261 -0.552292 -0.318859 -v 0.086603 0.074026 0.192230 -vn 0.770259 -0.637731 -0.000002 -v 0.086603 0.074160 0.191730 -vn 0.770263 -0.000000 -0.637727 -v 0.086603 0.073160 0.192730 -vn 0.770263 -0.318867 -0.552285 -v 0.086603 0.073660 0.192596 -vn -0.006827 0.406726 0.913525 -v 0.086603 0.075361 0.193507 -vn -0.006827 0.669115 0.743128 -v 0.086603 0.076673 0.192655 -vn 0.770263 0.637727 -0.000002 -v 0.086603 0.056138 0.182480 -vn 0.770260 0.552291 -0.318864 -v 0.086603 0.056272 0.182980 -vn -0.006827 -0.743128 0.669114 -v 0.086603 0.055755 0.184285 -vn 0.770263 0.318867 -0.552285 -v 0.086603 0.056638 0.183346 -vn 0.770263 -0.000000 -0.637727 -v 0.086603 0.057138 0.183480 -vn 0.770263 -0.318867 -0.552285 -v 0.086603 0.057638 0.183346 -vn 0.770263 0.552285 0.318866 -v 0.086603 0.072294 0.191230 -vn 0.770260 -0.552292 -0.318862 -v 0.086603 0.058004 0.182980 -vn 0.770261 -0.637729 -0.000002 -v 0.086603 0.058138 0.182480 -vn -1.000000 0.000000 0.000000 -v 0.059603 0.079027 0.141568 -vn -0.923879 0.191342 -0.331416 -v 0.059603 0.079089 0.141459 -vn -0.717305 -0.397226 -0.572438 -v 0.059603 0.078656 0.141209 -vn -0.995906 -0.079960 -0.042164 -v 0.059603 0.056440 0.179190 -vn -0.913026 -0.267658 0.307803 -v 0.059603 0.056213 0.179661 -vn -0.913687 -0.203210 0.351968 -v 0.059603 0.056828 0.180017 -vn -0.774232 -0.440522 -0.454429 -v 0.059603 0.076503 0.147439 -vn -0.487319 -0.223090 -0.844246 -v 0.059603 0.076579 0.147398 -vn -0.940158 0.213457 -0.265593 -v 0.059603 0.075975 0.147093 -vn -0.770260 -0.318866 0.552291 -v 0.059603 0.097340 0.158348 -vn -0.770263 -0.552286 0.318865 -v 0.059603 0.097798 0.158805 -vn -1.000000 0.000000 0.000000 -v 0.059603 0.099219 0.157844 -vn -0.707104 -0.353549 0.612378 -v 0.059603 0.096281 0.162932 -vn -0.770258 0.000000 -0.637732 -v 0.059603 0.096715 0.160680 -vn -0.973782 0.095188 0.206612 -v 0.059603 0.094657 0.161995 -vn -0.770265 0.318861 -0.552286 -v 0.059603 0.096090 0.160513 -vn -0.770261 0.552291 -0.318862 -v 0.059603 0.095633 0.160055 -vn -0.770261 0.637728 -0.000000 -v 0.059603 0.095465 0.159430 -vn -0.539522 0.816069 0.207237 -v 0.059603 0.093855 0.157384 -vn -0.770263 0.552286 0.318865 -v 0.059603 0.095633 0.158805 -vn -0.770261 -0.637728 0.000000 -v 0.059603 0.097965 0.159430 -vn -0.770261 -0.552291 -0.318862 -v 0.059603 0.097798 0.160055 -vn -0.770265 -0.318861 -0.552286 -v 0.059603 0.097340 0.160513 -vn -0.942586 -0.322314 -0.087438 -v 0.059603 0.097006 0.156548 -vn -0.934095 -0.307447 -0.181501 -v 0.059603 0.096896 0.156812 -vn -0.770264 -0.000000 0.637725 -v 0.059603 0.096715 0.158180 -vn -0.940630 -0.191084 -0.280539 -v 0.059603 0.096232 0.157558 -vn -0.770260 0.318866 0.552291 -v 0.059603 0.096090 0.158348 -vn -0.940309 -0.027544 -0.339206 -v 0.059603 0.095286 0.157877 -vn -0.939226 0.136074 -0.315179 -v 0.059603 0.094306 0.157687 -vn -0.707108 0.353548 -0.612374 -v 0.059603 0.099531 0.157303 -vn -0.973781 0.226528 -0.020872 -v 0.059603 0.097907 0.156366 -vn -0.939246 -0.341902 0.030350 -v 0.059603 0.097103 0.155836 -vn -0.816497 0.557678 -0.149428 -v 0.059603 0.098657 0.155066 -vn -0.941721 -0.281868 0.183609 -v 0.059603 0.096801 0.154885 -vn -0.973781 0.206616 -0.095188 -v 0.059603 0.097142 0.154191 -vn -0.770261 -0.318867 0.552288 -v 0.059603 0.095202 0.151051 -vn -0.770261 -0.552288 0.318867 -v 0.059603 0.095660 0.151508 -vn -0.707106 0.612372 0.353556 -v 0.059603 0.098079 0.152568 -vn -0.770262 -0.637728 0.000005 -v 0.059603 0.095827 0.152133 -vn -0.770264 -0.552286 -0.318863 -v 0.059603 0.095660 0.152758 -vn -0.770262 -0.318858 -0.552291 -v 0.059603 0.095202 0.153216 -vn -0.770258 0.000000 -0.637732 -v 0.059603 0.094577 0.153383 -vn -0.770265 0.318861 -0.552286 -v 0.059603 0.093952 0.153216 -vn -0.945215 0.170324 0.278493 -v 0.059603 0.094138 0.154268 -vn -0.939541 0.288588 0.184337 -v 0.059603 0.093448 0.154989 -vn -0.770259 0.552290 -0.318868 -v 0.059603 0.093495 0.152758 -vn -0.770265 0.637724 -0.000002 -v 0.059603 0.093327 0.152133 -vn -0.973781 -0.020872 -0.226530 -v 0.059603 0.091513 0.150941 -vn -0.770260 0.552291 0.318865 -v 0.059603 0.093495 0.151508 -vn -0.707103 -0.612370 -0.353565 -v 0.059603 0.092450 0.149318 -vn -0.770262 0.318869 0.552286 -v 0.059603 0.093952 0.151051 -vn -0.770264 -0.000000 0.637725 -v 0.059603 0.094577 0.150883 -vn -0.943022 0.014622 0.332410 -v 0.059603 0.095095 0.153983 -vn -0.942131 -0.153881 0.297844 -v 0.059603 0.096067 0.154208 -vn -0.525277 0.611188 -0.592059 -v 0.059603 0.093274 0.155422 -vn -0.707106 0.353553 -0.612373 -v 0.059603 0.085899 0.151165 -vn -1.000000 0.000000 0.000000 -v 0.059603 0.086337 0.150407 -vn -0.766712 0.174798 -0.617737 -v 0.059603 0.078602 0.146952 -vn -0.938471 -0.315177 -0.141194 -v 0.059603 0.078886 0.146405 -vn -0.465169 -0.179275 -0.866879 -v 0.059603 0.078482 0.146948 -vn -0.923879 0.191342 -0.331414 -v 0.059603 0.087399 0.148566 -vn -0.973781 0.206615 -0.095188 -v 0.059603 0.083286 0.146191 -vn -0.770261 0.552291 0.318862 -v 0.059603 0.079638 0.143508 -vn -0.770265 0.318861 0.552286 -v 0.059603 0.080096 0.143051 -vn -0.770258 -0.000000 0.637732 -v 0.059603 0.080721 0.142883 -vn -0.770262 -0.552286 -0.318867 -v 0.059603 0.081803 0.144758 -vn -0.770264 -0.637725 0.000004 -v 0.059603 0.081971 0.144133 -vn -0.707107 0.612371 0.353555 -v 0.059603 0.084223 0.144568 -vn -0.770259 -0.552290 0.318868 -v 0.059603 0.081803 0.143508 -vn -0.770265 -0.318861 0.552286 -v 0.059603 0.081346 0.143051 -vn -0.717281 0.057827 -0.694380 -v 0.059603 0.073659 0.142366 -vn -0.923879 -0.331414 -0.191342 -v 0.059603 0.073346 0.142907 -vn -0.973781 -0.095188 -0.206615 -v 0.059603 0.075391 0.143366 -vn -0.949431 0.212273 0.231347 -v 0.059603 0.075683 0.144238 -vn -0.816496 -0.149429 -0.557678 -v 0.059603 0.076141 0.142066 -vn -0.942336 0.150723 0.298805 -v 0.059603 0.076235 0.143806 -vn -0.940883 0.007953 0.338639 -v 0.059603 0.077181 0.143582 -vn -0.973781 -0.020872 -0.226526 -v 0.059603 0.077656 0.142941 -vn -0.945657 -0.094694 0.311072 -v 0.059603 0.077785 0.143690 -vn -0.707104 -0.612370 -0.353563 -v 0.059603 0.078594 0.141318 -vn -0.770263 0.552286 -0.318865 -v 0.059603 0.072250 0.146555 -vn -0.717286 -0.572434 0.397266 -v 0.059603 0.070409 0.147995 -vn -0.770260 0.318865 -0.552291 -v 0.059603 0.072708 0.147013 -vn -0.973781 -0.226528 0.020873 -v 0.059603 0.072141 0.148995 -vn -0.770264 0.000000 -0.637725 -v 0.059603 0.073333 0.147180 -vn -0.770260 -0.318866 -0.552291 -v 0.059603 0.073958 0.147013 -vn -0.770261 0.637729 -0.000002 -v 0.059603 0.072083 0.145930 -vn -0.770264 0.552286 0.318863 -v 0.059603 0.072250 0.145305 -vn -0.770263 -0.552286 -0.318865 -v 0.059603 0.074415 0.146555 -vn -0.770261 -0.637728 0.000000 -v 0.059603 0.074583 0.145930 -vn -0.940960 0.311284 -0.133030 -v 0.059603 0.075366 0.146336 -vn -0.770261 -0.552291 0.318862 -v 0.059603 0.074415 0.145305 -vn -0.770262 0.318858 0.552291 -v 0.059603 0.072708 0.144848 -vn -0.770258 -0.000000 0.637732 -v 0.059603 0.073333 0.144680 -vn -0.770265 -0.318861 0.552286 -v 0.059603 0.073958 0.144848 -vn -0.934278 0.310606 0.175068 -v 0.059603 0.075514 0.144458 -vn -0.941334 0.335894 0.032631 -v 0.059603 0.075199 0.145378 -vn -0.707108 -0.612372 -0.353553 -v 0.059603 0.074364 0.151144 -vn -1.000000 0.000000 0.000000 -v 0.059603 0.073714 0.150769 -vn -0.707106 -0.612373 -0.353554 -v 0.059603 0.070364 0.158072 -vn -1.000000 0.000000 0.000000 -v 0.059603 0.069714 0.157697 -vn -0.707106 -0.612373 -0.353554 -v 0.059603 0.066364 0.165001 -vn -1.000000 0.000000 0.000000 -v 0.059603 0.065714 0.164626 -vn -0.534577 -0.821220 -0.199565 -v 0.059603 0.057478 0.180392 -vn -0.997107 -0.075947 0.003058 -v 0.059603 0.060690 0.171828 -vn -0.973781 -0.095188 -0.206615 -v 0.059603 0.063391 0.164150 -vn -0.770264 -0.552288 0.318860 -v 0.059603 0.062415 0.166090 -vn -0.770258 -0.637732 -0.000000 -v 0.059603 0.062583 0.166715 -vn -0.770262 -0.552292 -0.318857 -v 0.059603 0.062415 0.167340 -vn -0.717283 -0.572435 0.397269 -v 0.059603 0.059391 0.171078 -vn -0.973781 -0.226528 0.020872 -v 0.059603 0.060141 0.169779 -vn -0.770265 -0.318861 -0.552285 -v 0.059603 0.061958 0.167797 -vn -0.717281 0.057829 -0.694380 -v 0.059603 0.061659 0.163150 -vn -0.770264 0.000000 0.637725 -v 0.059603 0.061333 0.165465 -vn -0.770260 -0.318866 0.552290 -v 0.059603 0.061958 0.165632 -vn -0.770258 0.000000 -0.637732 -v 0.059603 0.061333 0.167965 -vn -0.770265 0.318862 -0.552285 -v 0.059603 0.060708 0.167797 -vn -0.717282 -0.572436 0.397270 -v 0.059603 0.058409 0.168779 -vn -0.770260 0.552292 -0.318863 -v 0.059603 0.060250 0.167340 -vn -0.770262 0.637728 -0.000002 -v 0.059603 0.060083 0.166715 -vn -0.770263 0.552286 0.318865 -v 0.059603 0.060250 0.166090 -vn -0.770260 0.318866 0.552291 -v 0.059603 0.060708 0.165632 -vn -0.973781 -0.095188 -0.206617 -v 0.059603 0.067391 0.157222 -vn -0.717281 0.057828 -0.694380 -v 0.059603 0.065659 0.156222 -vn -0.770264 -0.000000 0.637725 -v 0.059603 0.065333 0.158537 -vn -0.770260 -0.318866 0.552291 -v 0.059603 0.065958 0.158704 -vn -0.770263 -0.552286 0.318865 -v 0.059603 0.066415 0.159162 -vn -0.770261 -0.637728 0.000000 -v 0.059603 0.066583 0.159787 -vn -0.770261 -0.552291 -0.318862 -v 0.059603 0.066415 0.160412 -vn -0.770264 -0.318861 -0.552287 -v 0.059603 0.065958 0.160869 -vn -0.973781 -0.226528 0.020872 -v 0.059603 0.064141 0.162851 -vn -0.923879 -0.331415 -0.191341 -v 0.059603 0.063766 0.163501 -vn -0.770258 0.000000 -0.637732 -v 0.059603 0.065333 0.161037 -vn -0.770265 0.318861 -0.552286 -v 0.059603 0.064708 0.160869 -vn -0.717284 -0.572435 0.397267 -v 0.059603 0.062409 0.161851 -vn -0.770261 0.552291 -0.318862 -v 0.059603 0.064250 0.160412 -vn -0.770261 0.637728 -0.000000 -v 0.059603 0.064083 0.159787 -vn -0.770263 0.552286 0.318865 -v 0.059603 0.064250 0.159162 -vn -0.770260 0.318866 0.552291 -v 0.059603 0.064708 0.158704 -vn -0.973781 -0.095188 -0.206616 -v 0.059603 0.071391 0.150294 -vn -0.717281 0.057828 -0.694380 -v 0.059603 0.069659 0.149294 -vn -0.770264 -0.000000 0.637725 -v 0.059603 0.069333 0.151608 -vn -0.770264 0.552286 -0.318863 -v 0.059603 0.068250 0.153483 -vn -0.717284 -0.572435 0.397269 -v 0.059603 0.066409 0.154923 -vn -0.770260 0.318865 -0.552291 -v 0.059603 0.068708 0.153941 -vn -0.973781 -0.226530 0.020873 -v 0.059603 0.068141 0.155923 -vn -0.770264 0.000000 -0.637725 -v 0.059603 0.069333 0.154108 -vn -0.770259 -0.318866 -0.552291 -v 0.059603 0.069958 0.153941 -vn -0.923879 -0.331415 -0.191342 -v 0.059603 0.071766 0.149644 -vn -0.770260 -0.318866 0.552291 -v 0.059603 0.069958 0.151776 -vn -0.770263 -0.552286 0.318865 -v 0.059603 0.070415 0.152233 -vn -0.770261 -0.637729 0.000002 -v 0.059603 0.070583 0.152858 -vn -0.770264 -0.552286 -0.318863 -v 0.059603 0.070415 0.153483 -vn -0.923880 -0.331412 -0.191340 -v 0.059603 0.067766 0.156572 -vn -0.770261 0.637729 0.000002 -v 0.059603 0.068083 0.152858 -vn -0.770263 0.552286 0.318865 -v 0.059603 0.068250 0.152233 -vn -0.770260 0.318866 0.552291 -v 0.059603 0.068708 0.151776 -vn -0.770260 -0.318866 -0.552291 -v 0.059603 0.081346 0.145216 -vn -0.770264 0.000000 -0.637725 -v 0.059603 0.080721 0.145383 -vn -0.770262 0.318869 -0.552286 -v 0.059603 0.080096 0.145216 -vn -0.942086 -0.334868 0.018396 -v 0.059603 0.079091 0.145455 -vn -0.770260 0.552291 -0.318864 -v 0.059603 0.079638 0.144758 -vn -0.944675 -0.280767 0.169586 -v 0.059603 0.078812 0.144523 -vn -0.770262 0.637728 -0.000002 -v 0.059603 0.079471 0.144133 -vn -0.938161 -0.194639 0.286304 -v 0.059603 0.078117 0.143843 -vn -0.717282 0.694379 0.057826 -v 0.059603 0.084286 0.144459 -vn -0.717283 0.694378 0.057829 -v 0.059603 0.098142 0.152459 -vn -0.717302 -0.397228 -0.572440 -v 0.059603 0.092513 0.149209 -vn -0.717267 0.572434 -0.397300 -v 0.059603 0.099640 0.157366 -vn -0.923880 0.331411 0.191342 -v 0.059603 0.099327 0.157907 -vn -0.717285 -0.057823 0.694376 -v 0.059603 0.096390 0.162995 -vn -0.770264 -0.000000 0.637725 -v 0.059603 0.092715 0.165108 -vn -0.770260 -0.318865 0.552291 -v 0.059603 0.093340 0.165276 -vn -0.707107 0.612372 0.353553 -v 0.059603 0.091684 0.161144 -vn -0.707108 0.353548 -0.612374 -v 0.059603 0.095531 0.164231 -vn -0.770261 -0.637728 0.000000 -v 0.059603 0.093965 0.166358 -vn -0.770261 -0.552291 -0.318862 -v 0.059603 0.093798 0.166983 -vn -0.973782 0.095188 0.206612 -v 0.059603 0.090657 0.168923 -vn -0.707104 -0.353549 0.612378 -v 0.059603 0.092281 0.169860 -vn -0.770265 -0.318861 -0.552287 -v 0.059603 0.093340 0.167441 -vn -0.770261 0.552291 -0.318862 -v 0.059603 0.091633 0.166983 -vn -0.707106 0.612373 0.353554 -v 0.059603 0.087684 0.168072 -vn -0.770265 0.318861 -0.552286 -v 0.059603 0.092090 0.167441 -vn -0.770258 0.000000 -0.637732 -v 0.059603 0.092715 0.167608 -vn -0.923879 0.331416 0.191342 -v 0.059603 0.094282 0.162644 -vn -0.973781 0.226527 -0.020871 -v 0.059603 0.093907 0.163294 -vn -0.770263 -0.552286 0.318865 -v 0.059603 0.093798 0.165733 -vn -0.770261 0.637728 -0.000000 -v 0.059603 0.091465 0.166358 -vn -0.770263 0.552286 0.318865 -v 0.059603 0.091633 0.165733 -vn -0.770260 0.318866 0.552291 -v 0.059603 0.092090 0.165276 -vn -0.717285 -0.057823 0.694376 -v 0.059603 0.092390 0.169923 -vn -0.717267 0.572433 -0.397301 -v 0.059603 0.095640 0.164294 -vn -0.770258 -0.000000 0.637732 -v 0.059603 0.088715 0.172037 -vn -0.770265 -0.318861 0.552287 -v 0.059603 0.089340 0.172204 -vn -0.770261 -0.552291 0.318862 -v 0.059603 0.089798 0.172662 -vn -0.770261 -0.637728 0.000000 -v 0.059603 0.089965 0.173287 -vn -0.707108 0.353548 -0.612374 -v 0.059603 0.091531 0.171159 -vn -0.770263 -0.552286 -0.318865 -v 0.059603 0.089798 0.173912 -vn -0.973782 0.095188 0.206612 -v 0.059603 0.086657 0.175851 -vn -0.707104 -0.353549 0.612378 -v 0.059603 0.088281 0.176789 -vn -0.770260 -0.318866 -0.552291 -v 0.059603 0.089340 0.174369 -vn -0.973781 0.226527 -0.020871 -v 0.059603 0.089907 0.170222 -vn -0.923879 0.331416 0.191342 -v 0.059603 0.090282 0.169572 -vn -0.770264 0.000000 -0.637725 -v 0.059603 0.088715 0.174537 -vn -0.770260 0.318865 -0.552291 -v 0.059603 0.088090 0.174369 -vn -0.707106 0.612373 0.353553 -v 0.059603 0.083684 0.175001 -vn -0.770263 0.552286 -0.318865 -v 0.059603 0.087633 0.173912 -vn -0.770261 0.637728 -0.000000 -v 0.059603 0.087465 0.173287 -vn -0.770261 0.552291 0.318862 -v 0.059603 0.087633 0.172662 -vn -0.770265 0.318861 0.552286 -v 0.059603 0.088090 0.172204 -vn -0.717283 -0.057821 0.694378 -v 0.059603 0.088390 0.176851 -vn -0.717267 0.572433 -0.397301 -v 0.059603 0.091640 0.171222 -vn -0.770258 -0.000000 0.637732 -v 0.059603 0.084715 0.178965 -vn -0.770265 -0.318861 0.552287 -v 0.059603 0.085340 0.179132 -vn -0.997107 0.035326 0.067301 -v 0.059603 0.080608 0.183328 -vn -0.717285 -0.057828 0.694377 -v 0.059603 0.081907 0.184078 -vn -0.973781 0.095187 0.206614 -v 0.059603 0.082657 0.182779 -vn -0.925072 -0.173458 0.337866 -v 0.059603 0.076046 0.191144 -vn -0.996376 0.075795 0.038601 -v 0.059603 0.076358 0.190690 -vn -0.549138 0.582719 0.599071 -v 0.059603 0.074784 0.190416 -vn -0.770260 -0.318865 -0.552290 -v 0.059603 0.085340 0.181297 -vn -0.770264 0.000000 -0.637725 -v 0.059603 0.084715 0.181465 -vn -0.770260 0.318865 -0.552291 -v 0.059603 0.084090 0.181297 -vn -0.770263 0.552286 -0.318865 -v 0.059603 0.083633 0.180840 -vn -0.770261 -0.552291 0.318862 -v 0.059603 0.085798 0.179590 -vn -0.770261 -0.637728 0.000000 -v 0.059603 0.085965 0.180215 -vn -0.707109 0.353545 -0.612374 -v 0.059603 0.087531 0.178088 -vn -0.770263 -0.552286 -0.318865 -v 0.059603 0.085798 0.180840 -vn -0.707104 -0.353549 0.612378 -v 0.059603 0.084281 0.183717 -vn -0.770261 0.637729 -0.000000 -v 0.059603 0.083465 0.180215 -vn -0.770261 0.552291 0.318862 -v 0.059603 0.083633 0.179590 -vn -0.770265 0.318861 0.552286 -v 0.059603 0.084090 0.179132 -vn -0.973781 0.226527 -0.020871 -v 0.059603 0.085907 0.177150 -vn -0.923879 0.331416 0.191342 -v 0.059603 0.086282 0.176501 -vn -0.717283 -0.057821 0.694378 -v 0.059603 0.084390 0.183779 -vn -0.717271 0.572431 -0.397297 -v 0.059603 0.087640 0.178150 -vn -0.511595 0.760477 -0.399932 -v 0.059608 0.093858 0.157380 -vn -0.328056 0.931829 0.155155 -v 0.056803 0.093858 0.157380 -vn -0.297115 0.187184 0.936315 -v 0.059553 0.074684 0.190589 -vn -0.185746 -0.373147 0.908988 -v 0.059803 0.074684 0.190589 -vn -0.717285 0.397274 0.572430 -v 0.059353 0.074784 0.190416 -vn -0.131337 0.750443 0.647754 -v 0.059353 0.082784 0.176559 -vn -0.341584 0.587468 0.733622 -v 0.056803 0.082784 0.176559 -vn -0.325842 0.728531 -0.602553 -v 0.056803 0.093280 0.155426 -vn -0.523528 0.849142 -0.069836 -v 0.059611 0.093280 0.155426 -vn -0.333459 0.290221 -0.896982 -v 0.056803 0.078602 0.146952 -vn -0.939708 -0.071656 -0.334388 -v 0.056603 0.077596 0.147428 -vn -0.849421 -0.251011 -0.464196 -v 0.056603 0.076734 0.147438 -vn -0.875580 -0.466614 0.125023 -v 0.056603 0.065637 0.166659 -vn -0.932050 -0.012456 0.362116 -v 0.056603 0.070019 0.167866 -vn -0.932222 -0.082085 0.352456 -v 0.056603 0.072246 0.168159 -vn -0.938929 0.332544 -0.088471 -v 0.056603 0.093287 0.156487 -vn -0.932223 -0.149325 0.329641 -v 0.056603 0.074374 0.168881 -vn -0.932221 -0.210819 0.294143 -v 0.056603 0.076319 0.170004 -vn -0.848124 0.528452 -0.037751 -v 0.056603 0.093709 0.157238 -vn -0.842677 0.478043 -0.247733 -v 0.056603 0.093230 0.155628 -vn -0.844519 -0.001342 -0.535524 -v 0.056603 0.078369 0.147048 -vn -0.904937 -0.101231 0.413329 -v 0.056603 0.067939 0.167989 -vn -0.904817 -0.308004 0.294006 -v 0.056603 0.080309 0.175130 -vn -0.875576 0.125026 0.466622 -v 0.056603 0.082611 0.176459 -vn -0.931919 -0.307399 0.192439 -v 0.056603 0.079375 0.173268 -vn -0.932224 -0.264189 0.247311 -v 0.056603 0.078008 0.171485 -vn -0.110048 -0.398608 0.910495 -v 0.061303 0.070221 0.192920 -vn -0.375126 -0.403549 0.834523 -v 0.061303 0.070827 0.193270 -vn -0.375941 -0.520254 0.766814 -v 0.061303 0.056971 0.185270 -vn -0.110052 -0.589214 0.800447 -v 0.061303 0.057577 0.185620 -vn -0.118637 -0.781272 0.612813 -v 0.060853 0.057577 0.185620 -vn -0.118633 -0.140095 0.983005 -v 0.060853 0.070221 0.192920 -vn -0.804181 -0.077592 0.589298 -v 0.059353 0.082511 0.176633 -vn -0.934287 -0.138761 0.328411 -v 0.059353 0.074135 0.190041 -vn -0.735271 0.188569 -0.651013 -v 0.059353 0.067117 0.188051 -vn -0.735271 0.338887 -0.586969 -v 0.059353 0.065099 0.187191 -vn -0.934291 0.284368 0.215025 -v 0.059353 0.071471 0.190755 -vn -0.777811 -0.144696 0.611615 -v 0.059353 0.067900 0.168197 -vn -0.735272 0.135573 0.664075 -v 0.059353 0.067829 0.170394 -vn -0.685654 -0.028433 0.727372 -v 0.059353 0.070078 0.168069 -vn -0.735271 -0.027292 0.677224 -v 0.059353 0.070016 0.170218 -vn -0.685529 -0.167547 0.708504 -v 0.059353 0.072239 0.168363 -vn -0.735271 -0.188569 0.651014 -v 0.059353 0.072181 0.170570 -vn -0.685730 -0.300968 0.662716 -v 0.059353 0.074303 0.169068 -vn -0.735271 -0.338887 0.586969 -v 0.059353 0.074199 0.171430 -vn -0.685923 -0.423027 0.592079 -v 0.059353 0.076192 0.170159 -vn -0.686108 -0.529155 0.499250 -v 0.059353 0.077835 0.171593 -vn -0.735271 0.469510 -0.488811 -v 0.059353 0.063345 0.185873 -vn -0.735270 0.572848 -0.362247 -v 0.059353 0.061958 0.184174 -vn -0.945447 -0.325776 -0.000001 -v 0.059353 0.059088 0.182480 -vn -0.735271 0.642893 -0.214629 -v 0.059353 0.061017 0.182192 -vn -0.945445 -0.282137 0.162890 -v 0.059353 0.058827 0.181505 -vn -0.735271 0.675576 -0.054538 -v 0.059353 0.060579 0.180043 -vn -0.934287 -0.215031 0.284376 -v 0.059353 0.058113 0.180791 -vn -0.735271 0.668997 0.108722 -v 0.059353 0.060667 0.177851 -vn -0.735271 0.623537 0.265665 -v 0.059353 0.061277 0.175743 -vn -0.804190 -0.471550 0.361828 -v 0.059353 0.065537 0.166833 -vn -0.717286 -0.694376 -0.057824 -v 0.059353 0.057464 0.180416 -vn -0.131330 -0.936190 -0.326037 -v 0.059353 0.065464 0.166559 -vn -0.735270 0.541843 0.407167 -v 0.059353 0.062374 0.173844 -vn -0.735272 0.428654 0.525005 -v 0.059353 0.063894 0.172261 -vn -0.735270 0.290557 0.612336 -v 0.059353 0.065748 0.171089 -vn -0.934290 -0.328402 -0.138759 -v 0.059353 0.058827 0.183455 -vn -0.921348 -0.379915 -0.082355 -v 0.059353 0.058327 0.184321 -vn -0.921349 0.261280 0.287836 -v 0.059353 0.070971 0.191621 -vn -0.735271 -0.541841 -0.407168 -v 0.059353 0.076924 0.184777 -vn -0.735271 -0.428655 -0.525007 -v 0.059353 0.075404 0.186359 -vn -0.945449 -0.000002 0.325770 -v 0.059353 0.073160 0.189780 -vn -0.735271 -0.290556 -0.612334 -v 0.059353 0.073550 0.187532 -vn -0.945444 0.162894 0.282136 -v 0.059353 0.072185 0.190041 -vn -0.735270 -0.135573 -0.664077 -v 0.059353 0.071469 0.188226 -vn -0.735271 0.027290 -0.677223 -v 0.059353 0.069283 0.188403 -vn -0.735271 -0.469510 0.488812 -v 0.059353 0.075953 0.172747 -vn -0.778046 -0.457390 0.430626 -v 0.059353 0.080148 0.175268 -vn -0.686287 -0.615373 0.387720 -v 0.059353 0.079171 0.173318 -vn -0.735271 -0.572847 0.362248 -v 0.059353 0.077340 0.174447 -vn -0.735271 -0.642892 0.214630 -v 0.059353 0.078281 0.176429 -vn -0.735271 -0.675576 0.054538 -v 0.059353 0.078720 0.178578 -vn -0.735271 -0.668997 -0.108722 -v 0.059353 0.078631 0.180770 -vn -0.735271 -0.623537 -0.265665 -v 0.059353 0.078021 0.182877 -vn -0.370449 -0.213974 0.903871 -v 0.061303 0.072184 0.193807 -vn -0.375399 0.001150 0.926863 -v 0.061303 0.073639 0.193930 -vn -0.392617 0.148443 0.907643 -v 0.061303 0.073850 0.193912 -vn -0.375034 0.281952 0.883093 -v 0.061303 0.075066 0.193627 -vn -0.400479 0.411757 0.818580 -v 0.061303 0.075361 0.193507 -vn -0.374935 0.532946 0.758546 -v 0.061303 0.076346 0.192926 -vn -0.397512 0.632927 0.664370 -v 0.061303 0.076673 0.192655 -vn -0.088068 0.848032 0.522576 -v 0.061103 0.077657 0.191440 -vn -0.081125 0.566981 0.819727 -v 0.061103 0.077343 0.191919 -vn -0.089208 0.726440 0.681416 -v 0.061303 0.077343 0.191919 -vn 0.301509 0.934106 0.191152 -v 0.061603 0.085881 0.183197 -vn 0.770260 -0.318865 -0.552291 -v 0.061603 0.085340 0.181297 -vn 0.770263 -0.552286 -0.318865 -v 0.061603 0.085798 0.180840 -vn 0.609995 0.686244 0.396202 -v 0.061603 0.082715 0.179060 -vn 0.770261 0.552291 0.318862 -v 0.061603 0.083633 0.179590 -vn 0.770261 0.637728 0.000000 -v 0.061603 0.083465 0.180215 -vn 0.301510 0.632595 0.713383 -v 0.061603 0.087881 0.179733 -vn 0.770261 -0.637728 -0.000000 -v 0.061603 0.085965 0.180215 -vn 0.770261 -0.552291 0.318862 -v 0.061603 0.085798 0.179590 -vn 0.609994 0.000000 0.792406 -v 0.061603 0.084715 0.177905 -vn 0.609994 0.686244 -0.396202 -v 0.061603 0.082715 0.181369 -vn 0.770263 0.552286 -0.318865 -v 0.061603 0.083633 0.180840 -vn 0.770260 0.318866 -0.552291 -v 0.061603 0.084090 0.181297 -vn 0.770264 -0.000000 -0.637725 -v 0.061603 0.084715 0.181465 -vn 0.770265 -0.318861 0.552287 -v 0.061603 0.085340 0.179132 -vn 0.770258 0.000000 0.637732 -v 0.061603 0.084715 0.178965 -vn 0.770265 0.318861 0.552286 -v 0.061603 0.084090 0.179132 -vn 0.609995 -0.000000 0.792406 -v 0.061603 0.088715 0.170977 -vn 0.770258 0.000000 0.637732 -v 0.061603 0.088715 0.172037 -vn 0.609994 0.686243 0.396204 -v 0.061603 0.086715 0.172132 -vn 0.770265 0.318861 0.552286 -v 0.061603 0.088090 0.172204 -vn 0.609994 0.686244 -0.396203 -v 0.061603 0.086715 0.174441 -vn 0.770260 0.318866 -0.552291 -v 0.061603 0.088090 0.174369 -vn 0.301512 0.934105 0.191152 -v 0.061603 0.089881 0.176269 -vn 0.770264 -0.000000 -0.637725 -v 0.061603 0.088715 0.174537 -vn 0.770260 -0.318865 -0.552291 -v 0.061603 0.089340 0.174369 -vn 0.770263 -0.552286 -0.318865 -v 0.061603 0.089798 0.173912 -vn 0.301511 0.632593 0.713384 -v 0.061603 0.091881 0.172804 -vn 0.770261 -0.637728 -0.000000 -v 0.061603 0.089965 0.173287 -vn 0.770261 -0.552291 0.318862 -v 0.061603 0.089798 0.172662 -vn 0.770265 -0.318861 0.552286 -v 0.061603 0.089340 0.172204 -vn 0.770261 0.552291 0.318862 -v 0.061603 0.087633 0.172662 -vn 0.770261 0.637728 0.000000 -v 0.061603 0.087465 0.173287 -vn 0.770263 0.552286 -0.318865 -v 0.061603 0.087633 0.173912 -vn 0.609994 0.686243 -0.396203 -v 0.061603 0.090715 0.167513 -vn 0.770265 0.318861 -0.552286 -v 0.061603 0.092090 0.167441 -vn 0.301514 0.934105 0.191149 -v 0.061603 0.093881 0.169340 -vn 0.770258 -0.000000 -0.637732 -v 0.061603 0.092715 0.167608 -vn 0.609994 0.686243 0.396205 -v 0.061603 0.090715 0.165204 -vn 0.770261 0.637728 0.000000 -v 0.061603 0.091465 0.166358 -vn 0.770261 0.552291 -0.318862 -v 0.061603 0.091633 0.166983 -vn 0.770265 -0.318861 -0.552286 -v 0.061603 0.093340 0.167441 -vn 0.770261 -0.552291 -0.318862 -v 0.061603 0.093798 0.166983 -vn 0.301511 0.632593 0.713384 -v 0.061603 0.095881 0.165876 -vn 0.770260 -0.318866 0.552291 -v 0.061603 0.093340 0.165276 -vn 0.609995 -0.000001 0.792405 -v 0.061603 0.092715 0.164049 -vn 0.770263 -0.552286 0.318865 -v 0.061603 0.093798 0.165733 -vn 0.770261 -0.637728 -0.000000 -v 0.061603 0.093965 0.166358 -vn 0.770264 0.000000 0.637725 -v 0.061603 0.092715 0.165108 -vn 0.770260 0.318865 0.552291 -v 0.061603 0.092090 0.165276 -vn 0.770263 0.552286 0.318865 -v 0.061603 0.091633 0.165733 -vn 0.717284 -0.397266 -0.572436 -v 0.064603 0.078656 0.141209 -vn 0.741787 0.661208 -0.112052 -v 0.064603 0.079739 0.141834 -vn 0.904534 -0.110358 -0.411873 -v 0.064603 0.078406 0.141642 -vn 0.846480 0.468863 -0.252270 -v 0.064603 0.079605 0.144066 -vn 0.846480 0.532182 -0.015959 -v 0.064603 0.083782 0.180831 -vn 0.741786 0.628650 -0.233565 -v 0.064603 0.085015 0.182697 -vn 0.717283 -0.057823 0.694379 -v 0.064603 0.084390 0.183779 -vn 0.717283 -0.572434 0.397272 -v 0.064603 0.058409 0.168779 -vn 0.741787 -0.112053 -0.661208 -v 0.064603 0.059034 0.167697 -vn 0.904535 -0.411870 0.110361 -v 0.064603 0.058842 0.169029 -vn 0.846479 -0.252272 -0.468863 -v 0.064603 0.061266 0.167831 -vn 0.717284 -0.572435 0.397268 -v 0.064603 0.062409 0.161851 -vn 0.741788 -0.112056 -0.661206 -v 0.064603 0.063034 0.160769 -vn 0.904533 -0.411875 0.110362 -v 0.064603 0.062842 0.162101 -vn 0.846478 -0.252274 -0.468864 -v 0.064603 0.065266 0.160903 -vn 0.717284 -0.572434 0.397270 -v 0.064603 0.066409 0.154923 -vn 0.741788 -0.112051 -0.661208 -v 0.064603 0.067034 0.153840 -vn 0.904535 -0.411871 0.110362 -v 0.064603 0.066842 0.155173 -vn 0.846478 -0.252272 -0.468863 -v 0.064603 0.069266 0.153974 -vn 0.904534 -0.110363 -0.411873 -v 0.064603 0.066092 0.156472 -vn 0.904537 -0.110356 -0.411868 -v 0.064603 0.074092 0.142616 -vn 0.577350 -0.211328 -0.788674 -v 0.064603 0.074842 0.141316 -vn 0.904533 -0.110363 -0.411873 -v 0.064603 0.076141 0.142066 -vn 0.741787 -0.628649 0.233566 -v 0.064603 0.061034 0.164233 -vn 0.717283 0.057824 -0.694378 -v 0.064603 0.061659 0.163150 -vn 0.846479 -0.532183 0.015958 -v 0.064603 0.062266 0.166099 -vn 0.904534 -0.110363 -0.411872 -v 0.064603 0.062092 0.163400 -vn 0.846479 -0.532183 0.015958 -v 0.064603 0.066266 0.159170 -vn 0.741787 -0.628649 0.233566 -v 0.064603 0.065034 0.157304 -vn 0.717283 0.057824 -0.694378 -v 0.064603 0.065659 0.156222 -vn 0.904534 -0.411873 0.110360 -v 0.064603 0.059391 0.171078 -vn 0.741788 0.628649 -0.233563 -v 0.064603 0.097015 0.161912 -vn 0.717284 -0.057826 0.694377 -v 0.064603 0.096390 0.162995 -vn 0.846479 0.532184 -0.015957 -v 0.064603 0.095782 0.160046 -vn 0.904534 0.110363 0.411873 -v 0.064603 0.095957 0.162745 -vn 0.741787 -0.628649 0.233565 -v 0.064603 0.069034 0.150376 -vn 0.717282 0.057834 -0.694379 -v 0.064603 0.069659 0.149294 -vn 0.846479 -0.532184 0.015957 -v 0.064603 0.070266 0.152242 -vn 0.904537 -0.110356 -0.411868 -v 0.064603 0.070092 0.149544 -vn 0.846478 -0.252272 -0.468864 -v 0.064603 0.073266 0.147046 -vn 0.846478 -0.532184 0.015957 -v 0.064603 0.074266 0.145314 -vn 0.717283 0.572434 -0.397272 -v 0.064603 0.095640 0.164294 -vn 0.741787 0.112053 0.661208 -v 0.064603 0.095015 0.165376 -vn 0.904535 0.411871 -0.110362 -v 0.064603 0.095207 0.164044 -vn 0.846479 0.252272 0.468864 -v 0.064603 0.092782 0.165242 -vn 0.741788 0.628649 -0.233563 -v 0.064603 0.093015 0.168840 -vn 0.717284 -0.057826 0.694377 -v 0.064603 0.092390 0.169923 -vn 0.846479 0.532184 -0.015957 -v 0.064603 0.091782 0.166974 -vn 0.904534 0.110363 0.411873 -v 0.064603 0.091957 0.169673 -vn 0.717283 0.572434 -0.397272 -v 0.064603 0.091640 0.171222 -vn 0.741787 0.112053 0.661208 -v 0.064603 0.091015 0.172304 -vn 0.904535 0.411871 -0.110362 -v 0.064603 0.091207 0.170972 -vn 0.846479 0.252272 0.468864 -v 0.064603 0.088782 0.172170 -vn 0.577350 -0.788675 0.211323 -v 0.064603 0.058092 0.170328 -vn 0.717285 -0.572438 0.397261 -v 0.064603 0.070409 0.147995 -vn 0.741788 -0.112051 -0.661208 -v 0.064603 0.071034 0.146912 -vn 0.904532 -0.411878 0.110358 -v 0.064603 0.070842 0.148245 -vn 0.741787 -0.628649 0.233564 -v 0.064603 0.073034 0.143448 -vn 0.717282 0.057833 -0.694379 -v 0.064603 0.073659 0.142366 -vn 0.717283 0.572435 -0.397271 -v 0.064603 0.099640 0.157366 -vn 0.741787 0.112052 0.661209 -v 0.064603 0.099015 0.158448 -vn 0.904535 0.411871 -0.110362 -v 0.064603 0.099207 0.157116 -vn 0.846478 0.252272 0.468864 -v 0.064603 0.096782 0.158314 -vn 0.741788 0.628649 -0.233563 -v 0.064603 0.089015 0.175769 -vn 0.717283 -0.057825 0.694378 -v 0.064603 0.088390 0.176851 -vn 0.846476 0.532187 -0.015955 -v 0.064603 0.087782 0.173903 -vn 0.904534 0.110363 0.411873 -v 0.064603 0.087957 0.176601 -vn 0.904534 0.411872 -0.110362 -v 0.064603 0.087207 0.177900 -vn 0.904534 0.110363 0.411873 -v 0.064603 0.083957 0.183529 -vn 0.577350 0.211324 0.788675 -v 0.064603 0.083207 0.184828 -vn 0.904535 0.110360 0.411871 -v 0.064603 0.081907 0.184078 -vn 0.846478 0.468864 -0.252272 -v 0.064603 0.093461 0.152066 -vn 0.846479 -0.015958 -0.532183 -v 0.064603 0.095193 0.153066 -vn 0.741787 -0.233564 -0.628649 -v 0.064603 0.083203 0.143834 -vn 0.717283 0.694378 0.057829 -v 0.064603 0.084286 0.144459 -vn 0.846480 -0.015959 -0.532181 -v 0.064603 0.081337 0.145066 -vn 0.904535 0.411871 -0.110358 -v 0.064603 0.084036 0.144892 -vn 0.904535 -0.110361 -0.411871 -v 0.064603 0.092263 0.149642 -vn 0.717283 -0.397271 -0.572434 -v 0.064603 0.092513 0.149209 -vn 0.741787 0.661208 -0.112052 -v 0.064603 0.093595 0.149834 -vn 0.577350 -0.211323 -0.788676 -v 0.064603 0.076891 0.140767 -vn 0.741787 -0.233565 -0.628649 -v 0.064603 0.097059 0.151834 -vn 0.717283 0.694378 0.057830 -v 0.064603 0.098142 0.152459 -vn 0.904534 0.411872 -0.110358 -v 0.064603 0.097892 0.152892 -vn 0.577351 0.788675 -0.211323 -v 0.064603 0.099407 0.153767 -vn 0.577350 0.788675 -0.211328 -v 0.064603 0.099957 0.155816 -vn 0.904535 0.411871 -0.110362 -v 0.064603 0.098657 0.155066 -vn 0.846478 0.252274 0.468863 -v 0.064603 0.084782 0.179099 -vn 0.741788 0.112055 0.661207 -v 0.064603 0.087015 0.179233 -vn 0.717284 0.572434 -0.397270 -v 0.064603 0.087640 0.178150 -vn -0.075084 -0.396814 0.914823 -v 0.063103 0.087015 0.179233 -vn -0.609994 0.000000 0.792406 -v 0.063103 0.084715 0.177905 -vn -0.846478 0.252273 0.468865 -v 0.063103 0.084782 0.179099 -vn -0.609994 0.686244 0.396202 -v 0.063103 0.082715 0.179060 -vn -0.846479 0.532183 -0.015958 -v 0.063103 0.083782 0.180831 -vn -0.609994 0.686244 -0.396203 -v 0.063103 0.082715 0.181369 -vn -0.075085 0.593857 -0.801059 -v 0.063103 0.085015 0.182697 -vn -0.075086 -0.396810 0.914825 -v 0.063103 0.091015 0.172304 -vn -0.609995 -0.000001 0.792406 -v 0.063103 0.088715 0.170977 -vn -0.846478 0.252272 0.468864 -v 0.063103 0.088782 0.172170 -vn -0.609994 0.686243 0.396204 -v 0.063103 0.086715 0.172132 -vn -0.846478 0.532184 -0.015957 -v 0.063103 0.087782 0.173903 -vn -0.609994 0.686244 -0.396203 -v 0.063103 0.086715 0.174441 -vn -0.075084 0.593853 -0.801063 -v 0.063103 0.089015 0.175769 -vn -0.075086 -0.396810 0.914825 -v 0.063103 0.095015 0.165376 -vn -0.609995 -0.000001 0.792405 -v 0.063103 0.092715 0.164049 -vn -0.846478 0.252272 0.468864 -v 0.063103 0.092782 0.165242 -vn -0.609994 0.686243 0.396205 -v 0.063103 0.090715 0.165204 -vn -0.846478 0.532184 -0.015957 -v 0.063103 0.091782 0.166974 -vn -0.609994 0.686244 -0.396203 -v 0.063103 0.090715 0.167513 -vn -0.075084 0.593852 -0.801063 -v 0.063103 0.093015 0.168840 -vn 0.297109 0.306053 0.904465 -v 0.063603 0.087881 0.179733 -vn 0.297109 0.936316 -0.187186 -v 0.063603 0.088506 0.178650 -vn -0.297109 0.936316 -0.187185 -v 0.060603 0.088506 0.178650 -vn -0.297108 0.306057 0.904465 -v 0.060603 0.085256 0.184279 -vn 0.297107 0.936319 -0.187177 -v 0.063603 0.085881 0.183197 -vn 0.297106 0.306056 0.904465 -v 0.063603 0.085256 0.184279 -vn 0.297107 0.306056 0.904465 -v 0.063603 0.091881 0.172804 -vn 0.297108 0.936318 -0.187178 -v 0.063603 0.092506 0.171722 -vn -0.297109 0.936317 -0.187180 -v 0.060603 0.092506 0.171722 -vn -0.297108 0.306057 0.904465 -v 0.060603 0.089256 0.177351 -vn 0.297108 0.936317 -0.187183 -v 0.063603 0.089881 0.176269 -vn 0.297107 0.306056 0.904465 -v 0.063603 0.089256 0.177351 -vn 0.297107 0.306056 0.904465 -v 0.063603 0.095881 0.165876 -vn 0.297108 0.936318 -0.187178 -v 0.063603 0.096506 0.164794 -vn -0.297109 0.936317 -0.187180 -v 0.060603 0.096506 0.164794 -vn -0.297109 0.306053 0.904466 -v 0.060603 0.093256 0.170423 -vn 0.297109 0.936316 -0.187186 -v 0.063603 0.093881 0.169340 -vn 0.297109 0.306053 0.904465 -v 0.063603 0.093256 0.170423 -vn 0.609994 0.686243 -0.396203 -v 0.061603 0.094715 0.160585 -vn 0.770265 0.318861 -0.552286 -v 0.061603 0.096090 0.160513 -vn 0.301514 0.934105 0.191149 -v 0.061603 0.097881 0.162412 -vn 0.770258 -0.000000 -0.637732 -v 0.061603 0.096715 0.160680 -vn 0.609994 0.000001 0.792406 -v 0.061603 0.096715 0.157121 -vn 0.301511 0.632593 0.713384 -v 0.061603 0.099881 0.158948 -vn 0.770263 -0.552286 0.318865 -v 0.061603 0.097798 0.158805 -vn 0.770260 0.318866 0.552291 -v 0.061603 0.096090 0.158348 -vn 0.609995 0.686244 0.396202 -v 0.061603 0.094715 0.158275 -vn 0.770264 0.000000 0.637725 -v 0.061603 0.096715 0.158180 -vn 0.770260 -0.318866 0.552291 -v 0.061603 0.097340 0.158348 -vn 0.770263 0.552286 0.318865 -v 0.061603 0.095633 0.158805 -vn 0.770261 0.637728 0.000000 -v 0.061603 0.095465 0.159430 -vn 0.770261 0.552291 -0.318862 -v 0.061603 0.095633 0.160055 -vn 0.770265 -0.318861 -0.552286 -v 0.061603 0.097340 0.160513 -vn 0.770261 -0.552291 -0.318862 -v 0.061603 0.097798 0.160055 -vn 0.770261 -0.637728 -0.000000 -v 0.061603 0.097965 0.159430 -vn 0.301513 0.713382 -0.632594 -v 0.061603 0.094095 0.148968 -vn 0.301510 0.191150 -0.934106 -v 0.061603 0.097559 0.150968 -vn 0.770261 -0.318867 0.552288 -v 0.061603 0.095202 0.151051 -vn 0.770261 -0.552288 0.318867 -v 0.061603 0.095660 0.151508 -vn 0.770258 -0.000000 -0.637732 -v 0.061603 0.094577 0.153383 -vn 0.609994 -0.396203 -0.686244 -v 0.061603 0.095732 0.154133 -vn 0.770265 0.318861 -0.552287 -v 0.061603 0.093952 0.153216 -vn 0.609994 0.396203 -0.686243 -v 0.061603 0.093423 0.154133 -vn 0.770259 0.552290 -0.318868 -v 0.061603 0.093495 0.152758 -vn 0.609994 0.792406 0.000001 -v 0.061603 0.092268 0.152133 -vn 0.770265 0.637724 -0.000002 -v 0.061603 0.093327 0.152133 -vn 0.770264 0.000000 0.637725 -v 0.061603 0.094577 0.150883 -vn 0.770262 0.318869 0.552286 -v 0.061603 0.093952 0.151051 -vn 0.770260 0.552291 0.318866 -v 0.061603 0.093495 0.151508 -vn 0.770262 -0.318858 -0.552291 -v 0.061603 0.095202 0.153216 -vn 0.770264 -0.552286 -0.318863 -v 0.061603 0.095660 0.152758 -vn 0.770262 -0.637728 0.000005 -v 0.061603 0.095827 0.152133 -vn -0.075087 -0.396809 0.914825 -v 0.063103 0.099015 0.158448 -vn -0.609994 0.000001 0.792406 -v 0.063103 0.096715 0.157121 -vn -0.846479 0.252272 0.468864 -v 0.063103 0.096782 0.158314 -vn -0.609994 0.686244 0.396203 -v 0.063103 0.094715 0.158275 -vn -0.846478 0.532184 -0.015957 -v 0.063103 0.095782 0.160046 -vn -0.609994 0.686244 -0.396203 -v 0.063103 0.094715 0.160585 -vn -0.075084 0.593852 -0.801063 -v 0.063103 0.097015 0.161912 -vn 0.297108 0.306058 0.904464 -v 0.063603 0.099881 0.158948 -vn 0.297108 0.936318 -0.187178 -v 0.063603 0.100506 0.157866 -vn -0.297109 0.936317 -0.187180 -v 0.060603 0.100506 0.157866 -vn -0.297109 0.306053 0.904465 -v 0.060603 0.097256 0.163495 -vn 0.297109 0.936316 -0.187186 -v 0.063603 0.097881 0.162412 -vn 0.297109 0.306053 0.904465 -v 0.063603 0.097256 0.163495 -vn -0.846479 0.468864 -0.252272 -v 0.063103 0.093461 0.152066 -vn -0.075085 0.914823 0.396813 -v 0.063103 0.093595 0.149834 -vn -0.609994 0.792406 0.000001 -v 0.063103 0.092268 0.152133 -vn -0.609994 -0.396203 -0.686244 -v 0.063103 0.095732 0.154133 -vn -0.075085 -0.801061 -0.593854 -v 0.063103 0.097059 0.151834 -vn -0.846479 -0.015958 -0.532183 -v 0.063103 0.095193 0.153066 -vn -0.609994 0.396204 -0.686243 -v 0.063103 0.093423 0.154133 -vn 0.297108 0.904465 -0.306055 -v 0.063603 0.094095 0.148968 -vn 0.297108 -0.187182 -0.936317 -v 0.063603 0.093013 0.148343 -vn -0.297107 -0.187182 -0.936318 -v 0.060603 0.093013 0.148343 -vn -0.297109 0.904465 -0.306054 -v 0.060603 0.098642 0.151593 -vn 0.297108 -0.187181 -0.936317 -v 0.063603 0.097559 0.150968 -vn 0.297108 0.904465 -0.306054 -v 0.063603 0.098642 0.151593 -vn -0.087120 -0.949030 0.302905 -v 0.061103 0.059391 0.171078 -vn -0.081891 -0.872788 -0.481180 -v 0.061103 0.055141 0.178440 -vn -0.087119 0.212188 0.973338 -v 0.061103 0.081907 0.184078 -vn -0.297109 0.306054 0.904465 -v 0.061103 0.083207 0.184828 -vn -0.319809 0.095729 0.942634 -v 0.060353 0.081733 0.183978 -vn -0.554225 -0.107281 0.825425 -v 0.059804 0.081258 0.183703 -vn -0.227459 0.073473 0.971012 -v 0.061103 0.083957 0.183529 -vn -0.227459 0.877655 -0.421882 -v 0.061103 0.087207 0.177900 -vn -0.227458 0.073474 0.971012 -v 0.061103 0.087957 0.176601 -vn -0.227458 0.877657 -0.421878 -v 0.061103 0.091207 0.170972 -vn -0.227459 0.073470 0.971012 -v 0.061103 0.091957 0.169673 -vn -0.227458 0.877657 -0.421878 -v 0.061103 0.095207 0.164044 -vn -0.227459 0.073470 0.971012 -v 0.061103 0.095957 0.162745 -vn -0.227458 0.877657 -0.421878 -v 0.061103 0.099207 0.157116 -vn -0.297108 0.936317 -0.187185 -v 0.061103 0.099957 0.155816 -vn -0.297108 0.904466 -0.306053 -v 0.061103 0.099407 0.153767 -vn -0.227457 0.971013 -0.073466 -v 0.061103 0.097892 0.152892 -vn -0.227454 -0.421880 -0.877657 -v 0.061103 0.092263 0.149642 -vn -0.227458 0.971013 -0.073468 -v 0.061103 0.084036 0.144892 -vn -0.297107 0.904467 -0.306052 -v 0.060603 0.084786 0.143593 -vn 0.297105 0.904468 -0.306050 -v 0.063603 0.084786 0.143593 -vn 0.297109 0.904465 -0.306056 -v 0.063603 0.080239 0.140968 -vn 0.297109 -0.187185 -0.936316 -v 0.063603 0.079156 0.140343 -vn 0.301511 0.713382 -0.632596 -v 0.061603 0.080239 0.140968 -vn -0.297107 -0.187183 -0.936317 -v 0.060603 0.079156 0.140343 -vn 0.301508 0.191154 -0.934106 -v 0.061603 0.083703 0.142968 -vn 0.297107 -0.187181 -0.936318 -v 0.063603 0.083703 0.142968 -vn -0.227458 -0.421878 -0.877657 -v 0.061103 0.078406 0.141642 -vn -0.297108 -0.187180 -0.936317 -v 0.061103 0.076891 0.140767 -vn -0.297107 -0.306058 -0.904464 -v 0.061103 0.074842 0.141316 -vn -0.227456 -0.073469 -0.971013 -v 0.061103 0.074092 0.142616 -vn 0.297108 -0.306059 -0.904464 -v 0.063603 0.072793 0.141866 -vn -0.297107 -0.306055 -0.904465 -v 0.060603 0.072793 0.141866 -vn 0.297109 -0.306053 -0.904465 -v 0.063603 0.070168 0.146412 -vn 0.297109 -0.936316 0.187184 -v 0.063603 0.069543 0.147495 -vn 0.301509 -0.632594 -0.713384 -v 0.061603 0.070168 0.146412 -vn -0.297109 -0.936317 0.187182 -v 0.060603 0.069543 0.147495 -vn 0.301514 -0.934105 -0.191149 -v 0.061603 0.072168 0.142948 -vn 0.297108 -0.936316 0.187186 -v 0.063603 0.072168 0.142948 -vn -0.227460 -0.877657 0.421878 -v 0.061103 0.070842 0.148245 -vn -0.227456 -0.073469 -0.971013 -v 0.061103 0.070092 0.149544 -vn 0.297107 -0.306056 -0.904465 -v 0.063603 0.068793 0.148794 -vn -0.297107 -0.306054 -0.904466 -v 0.060603 0.068793 0.148794 -vn 0.297109 -0.306053 -0.904465 -v 0.063603 0.066168 0.153340 -vn 0.297109 -0.936316 0.187186 -v 0.063603 0.065543 0.154423 -vn 0.301510 -0.632595 -0.713383 -v 0.061603 0.066168 0.153340 -vn -0.297109 -0.936316 0.187185 -v 0.060603 0.065543 0.154423 -vn 0.301509 -0.934106 -0.191152 -v 0.061603 0.068168 0.149876 -vn 0.297108 -0.936318 0.187177 -v 0.063603 0.068168 0.149876 -vn -0.227458 -0.877655 0.421883 -v 0.061103 0.066842 0.155173 -vn -0.227461 -0.073473 -0.971011 -v 0.061103 0.066092 0.156472 -vn 0.297107 -0.306056 -0.904465 -v 0.063603 0.064793 0.155722 -vn -0.297109 -0.306056 -0.904464 -v 0.060603 0.064793 0.155722 -vn 0.297108 -0.306050 -0.904467 -v 0.063603 0.062168 0.160269 -vn 0.297108 -0.936317 0.187185 -v 0.063603 0.061543 0.161351 -vn 0.301513 -0.632595 -0.713382 -v 0.061603 0.062168 0.160269 -vn -0.297108 -0.936317 0.187184 -v 0.060603 0.061543 0.161351 -vn 0.301508 -0.934106 -0.191152 -v 0.061603 0.064168 0.156804 -vn 0.297108 -0.936318 0.187177 -v 0.063603 0.064168 0.156804 -vn -0.227457 -0.877655 0.421882 -v 0.061103 0.062842 0.162101 -vn -0.227462 -0.073476 -0.971011 -v 0.061103 0.062092 0.163400 -vn 0.297107 -0.306056 -0.904465 -v 0.063603 0.060793 0.162650 -vn -0.297109 -0.306056 -0.904465 -v 0.060603 0.060793 0.162650 -vn 0.297107 -0.306056 -0.904465 -v 0.063603 0.058168 0.167197 -vn 0.297108 -0.936318 0.187178 -v 0.063603 0.057543 0.168279 -vn 0.301512 -0.632593 -0.713384 -v 0.061603 0.058168 0.167197 -vn -0.297108 -0.936318 0.187179 -v 0.060603 0.057543 0.168279 -vn 0.301510 -0.934105 -0.191152 -v 0.061603 0.060168 0.163733 -vn 0.297108 -0.936318 0.187177 -v 0.063603 0.060168 0.163733 -vn -0.227457 -0.877657 0.421878 -v 0.061103 0.058842 0.169029 -vn -0.297109 -0.936317 0.187180 -v 0.061103 0.058092 0.170328 -vn -0.554238 -0.661193 0.505613 -v 0.059804 0.060040 0.171453 -vn -0.319806 -0.864208 0.388417 -v 0.060353 0.059565 0.171179 -vn -0.174806 -0.594109 0.785161 -v 0.059856 0.057364 0.180589 -vn -0.297103 -0.904471 0.306042 -v 0.059553 0.057364 0.180589 -vn -0.332595 -0.679776 -0.653670 -v 0.056803 0.076503 0.147439 -vn -0.341586 -0.929065 -0.141975 -v 0.056803 0.065464 0.166559 -vn -0.341590 -0.733614 0.587474 -v 0.056803 0.065537 0.166833 -vn -0.371668 -0.211471 0.903960 -v 0.056803 0.067900 0.168197 -vn -0.391740 -0.031333 0.919542 -v 0.056803 0.070012 0.168066 -vn -0.391672 -0.208473 0.896176 -v 0.056803 0.072201 0.168354 -vn -0.391408 -0.379554 0.838295 -v 0.056803 0.074291 0.169063 -vn -0.391145 -0.536048 0.748103 -v 0.056803 0.076203 0.170166 -vn -0.390901 -0.671920 0.629062 -v 0.056803 0.077862 0.171622 -vn -0.391236 -0.780656 0.487350 -v 0.056803 0.079205 0.173374 -vn -0.371670 -0.677671 0.634526 -v 0.056803 0.080148 0.175268 -vn -0.341580 -0.141983 0.929066 -v 0.056803 0.082511 0.176633 -vn -0.609994 -0.396203 -0.686244 -v 0.063103 0.081876 0.146133 -vn 0.609994 -0.396203 -0.686243 -v 0.061603 0.081876 0.146133 -vn -0.075084 -0.801063 -0.593852 -v 0.063103 0.083203 0.143834 -vn 0.770265 -0.318861 0.552287 -v 0.061603 0.081346 0.143051 -vn 0.770259 -0.552290 0.318868 -v 0.061603 0.081803 0.143508 -vn 0.770261 0.552291 0.318862 -v 0.061603 0.079638 0.143508 -vn 0.609994 0.792406 -0.000001 -v 0.061603 0.078412 0.144133 -vn 0.770265 0.318861 0.552286 -v 0.061603 0.080096 0.143051 -vn 0.770258 0.000000 0.637732 -v 0.061603 0.080721 0.142883 -vn 0.770262 0.637728 -0.000002 -v 0.061603 0.079471 0.144133 -vn 0.770260 0.552291 -0.318864 -v 0.061603 0.079638 0.144758 -vn 0.609995 0.396202 -0.686244 -v 0.061603 0.079566 0.146133 -vn 0.770262 0.318869 -0.552286 -v 0.061603 0.080096 0.145216 -vn 0.770264 -0.000000 -0.637725 -v 0.061603 0.080721 0.145383 -vn 0.770260 -0.318866 -0.552291 -v 0.061603 0.081346 0.145216 -vn 0.770262 -0.552286 -0.318867 -v 0.061603 0.081803 0.144758 -vn 0.770264 -0.637725 0.000004 -v 0.061603 0.081971 0.144133 -vn -0.075084 0.914824 0.396813 -v 0.063103 0.079739 0.141834 -vn -0.609994 0.792406 -0.000001 -v 0.063103 0.078412 0.144133 -vn -0.609994 0.396202 -0.686244 -v 0.063103 0.079566 0.146133 -vn -0.846479 0.468864 -0.252272 -v 0.063103 0.079605 0.144066 -vn -0.846479 -0.015958 -0.532183 -v 0.063103 0.081337 0.145066 -vn -0.609994 -0.686244 0.396203 -v 0.063103 0.075333 0.144775 -vn 0.609994 -0.686244 0.396203 -v 0.061603 0.075333 0.144775 -vn -0.075084 -0.593853 0.801063 -v 0.063103 0.073034 0.143448 -vn 0.609994 -0.000000 -0.792406 -v 0.061603 0.073333 0.148240 -vn 0.770263 0.552286 -0.318865 -v 0.061603 0.072250 0.146555 -vn 0.770260 0.318866 -0.552291 -v 0.061603 0.072708 0.147013 -vn 0.770264 -0.000000 -0.637725 -v 0.061603 0.073333 0.147180 -vn 0.609995 -0.686244 -0.396202 -v 0.061603 0.075333 0.147085 -vn 0.770260 -0.318866 -0.552291 -v 0.061603 0.073958 0.147013 -vn 0.770265 -0.318861 0.552286 -v 0.061603 0.073958 0.144848 -vn 0.770258 0.000000 0.637732 -v 0.061603 0.073333 0.144680 -vn 0.770262 0.318858 0.552291 -v 0.061603 0.072708 0.144848 -vn 0.770264 0.552286 0.318863 -v 0.061603 0.072250 0.145305 -vn 0.770261 0.637729 -0.000002 -v 0.061603 0.072083 0.145930 -vn 0.770263 -0.552286 -0.318865 -v 0.061603 0.074415 0.146555 -vn 0.770261 -0.637728 -0.000000 -v 0.061603 0.074583 0.145930 -vn 0.770261 -0.552291 0.318862 -v 0.061603 0.074415 0.145305 -vn -0.075083 0.396815 -0.914823 -v 0.063103 0.071034 0.146912 -vn -0.609994 -0.000001 -0.792406 -v 0.063103 0.073333 0.148240 -vn -0.609994 -0.686244 -0.396202 -v 0.063103 0.075333 0.147085 -vn -0.846478 -0.252272 -0.468864 -v 0.063103 0.073266 0.147046 -vn -0.846479 -0.532184 0.015957 -v 0.063103 0.074266 0.145314 -vn -0.609994 -0.686244 0.396202 -v 0.063103 0.071333 0.151704 -vn 0.609994 -0.686244 0.396202 -v 0.061603 0.071333 0.151704 -vn -0.075086 -0.593857 0.801059 -v 0.063103 0.069034 0.150376 -vn 0.609994 -0.000000 -0.792406 -v 0.061603 0.069333 0.155168 -vn 0.770264 0.552286 -0.318863 -v 0.061603 0.068250 0.153483 -vn 0.770260 0.318866 -0.552291 -v 0.061603 0.068708 0.153941 -vn 0.770264 -0.000000 -0.637725 -v 0.061603 0.069333 0.154108 -vn 0.609995 -0.686243 -0.396203 -v 0.061603 0.071333 0.154013 -vn 0.770260 -0.318866 -0.552291 -v 0.061603 0.069958 0.153941 -vn 0.770264 0.000000 0.637725 -v 0.061603 0.069333 0.151608 -vn 0.770260 -0.318866 0.552291 -v 0.061603 0.069958 0.151776 -vn 0.770264 -0.552286 -0.318863 -v 0.061603 0.070415 0.153483 -vn 0.770261 -0.637729 0.000002 -v 0.061603 0.070583 0.152858 -vn 0.770263 -0.552286 0.318865 -v 0.061603 0.070415 0.152233 -vn 0.770260 0.318865 0.552291 -v 0.061603 0.068708 0.151776 -vn 0.770263 0.552286 0.318865 -v 0.061603 0.068250 0.152233 -vn 0.770261 0.637729 0.000002 -v 0.061603 0.068083 0.152858 -vn -0.075083 0.396815 -0.914823 -v 0.063103 0.067034 0.153840 -vn -0.609994 -0.000001 -0.792406 -v 0.063103 0.069333 0.155168 -vn -0.609994 -0.686244 0.396203 -v 0.063103 0.067333 0.158632 -vn 0.609994 -0.686244 0.396203 -v 0.061603 0.067333 0.158632 -vn -0.075085 -0.593857 0.801060 -v 0.063103 0.065034 0.157304 -vn 0.770264 0.000000 0.637725 -v 0.061603 0.065333 0.158537 -vn 0.770260 -0.318866 0.552291 -v 0.061603 0.065958 0.158704 -vn 0.770260 0.318865 0.552291 -v 0.061603 0.064708 0.158704 -vn 0.770263 0.552286 0.318865 -v 0.061603 0.064250 0.159162 -vn 0.770265 -0.318861 -0.552286 -v 0.061603 0.065958 0.160869 -vn 0.609995 -0.686244 -0.396202 -v 0.061603 0.067333 0.160941 -vn 0.770258 -0.000000 -0.637732 -v 0.061603 0.065333 0.161037 -vn 0.609994 0.000001 -0.792406 -v 0.061603 0.065333 0.162096 -vn 0.770261 -0.552291 -0.318862 -v 0.061603 0.066415 0.160412 -vn 0.770261 -0.637728 -0.000000 -v 0.061603 0.066583 0.159787 -vn 0.770263 -0.552286 0.318865 -v 0.061603 0.066415 0.159162 -vn 0.770261 0.637728 0.000000 -v 0.061603 0.064083 0.159787 -vn 0.770261 0.552291 -0.318862 -v 0.061603 0.064250 0.160412 -vn 0.770265 0.318861 -0.552287 -v 0.061603 0.064708 0.160869 -vn -0.075083 0.396816 -0.914822 -v 0.063103 0.063034 0.160769 -vn -0.609994 0.000000 -0.792406 -v 0.063103 0.065333 0.162096 -vn -0.609994 -0.686243 0.396204 -v 0.063103 0.063333 0.165560 -vn 0.609994 -0.686243 0.396204 -v 0.061603 0.063333 0.165560 -vn -0.075086 -0.593856 0.801060 -v 0.063103 0.061034 0.164233 -vn 0.770262 -0.552292 -0.318857 -v 0.061603 0.062415 0.167340 -vn 0.770258 -0.637732 0.000000 -v 0.061603 0.062583 0.166715 -vn 0.609994 -0.686243 -0.396204 -v 0.061603 0.063333 0.167869 -vn 0.609994 0.000001 -0.792406 -v 0.061603 0.061333 0.169024 -vn 0.770260 0.552292 -0.318863 -v 0.061603 0.060250 0.167340 -vn 0.770265 0.318862 -0.552285 -v 0.061603 0.060708 0.167797 -vn 0.770258 0.000000 -0.637732 -v 0.061603 0.061333 0.167965 -vn 0.770265 -0.318861 -0.552285 -v 0.061603 0.061958 0.167797 -vn 0.770264 -0.552288 0.318860 -v 0.061603 0.062415 0.166090 -vn 0.770260 -0.318866 0.552290 -v 0.061603 0.061958 0.165632 -vn 0.770264 0.000000 0.637725 -v 0.061603 0.061333 0.165465 -vn 0.770260 0.318865 0.552291 -v 0.061603 0.060708 0.165632 -vn 0.770263 0.552286 0.318865 -v 0.061603 0.060250 0.166090 -vn 0.770262 0.637728 -0.000002 -v 0.061603 0.060083 0.166715 -vn -0.075086 0.396810 -0.914824 -v 0.063103 0.059034 0.167697 -vn -0.609995 0.000001 -0.792406 -v 0.063103 0.061333 0.169024 -vn -0.609995 -0.686243 -0.396203 -v 0.063103 0.071333 0.154013 -vn -0.846478 -0.252272 -0.468864 -v 0.063103 0.069266 0.153974 -vn -0.846479 -0.532184 0.015957 -v 0.063103 0.070266 0.152242 -vn -0.609994 -0.686244 -0.396202 -v 0.063103 0.067333 0.160941 -vn -0.846478 -0.252274 -0.468864 -v 0.063103 0.065266 0.160903 -vn -0.846479 -0.532183 0.015958 -v 0.063103 0.066266 0.159170 -vn -0.609994 -0.686243 -0.396204 -v 0.063103 0.063333 0.167869 -vn -0.846479 -0.252272 -0.468863 -v 0.063103 0.061266 0.167831 -vn -0.846479 -0.532183 0.015958 -v 0.063103 0.062266 0.166099 -vn -0.034164 -0.998100 -0.051270 -v 0.061103 0.054892 0.178931 -vn -0.091616 -0.956356 -0.277469 -v 0.061303 0.054892 0.178931 -vn -0.414908 -0.879324 -0.233751 -v 0.061303 0.054580 0.179900 -vn -0.377863 -0.922461 -0.079278 -v 0.061303 0.054512 0.180300 -vn -0.408211 -0.911811 0.044322 -v 0.061303 0.054498 0.181462 -vn -0.375049 -0.906030 0.196080 -v 0.061303 0.054539 0.181764 -vn -0.391912 -0.860899 0.324436 -v 0.061303 0.054903 0.182973 -vn -0.375411 -0.803793 0.461501 -v 0.061303 0.054989 0.183157 -vn -0.371278 -0.676740 0.635748 -v 0.061303 0.055824 0.184360 -vn -0.407588 -0.817849 -0.406196 -v 0.059553 0.058154 0.184221 -vn -0.392034 -0.851191 -0.348975 -v 0.059553 0.058654 0.183355 -vn -0.678874 -0.678362 -0.280988 -v 0.061103 0.058654 0.183355 -vn -0.376182 -0.888650 -0.262274 -v 0.059727 0.057829 0.184784 -vn -0.217183 -0.968147 -0.124594 -v 0.060203 0.057591 0.185196 -vn -0.057148 -0.993068 -0.102709 -v 0.060853 0.057504 0.185346 -vn -0.578893 -0.788459 0.207881 -v 0.061103 0.057504 0.185346 -vn -0.797130 -0.463450 0.387037 -v 0.061103 0.055010 0.179230 -vn -0.393455 -0.904762 0.163089 -v 0.061103 0.054998 0.179199 -vn -0.915144 -0.401246 -0.038899 -v 0.061103 0.054710 0.180325 -vn -0.770263 0.552285 0.318866 -v 0.061103 0.056272 0.181980 -vn -0.770260 0.318863 0.552291 -v 0.061103 0.056638 0.181614 -vn -0.770262 0.000000 0.637727 -v 0.061103 0.057138 0.181480 -vn -0.678875 -0.446985 0.582523 -v 0.061103 0.058013 0.180964 -vn -0.770260 -0.318863 0.552291 -v 0.061103 0.057638 0.181614 -vn -0.653226 -0.655722 0.378581 -v 0.061103 0.058654 0.181605 -vn -0.770264 -0.552286 0.318863 -v 0.061103 0.058004 0.181980 -vn -0.653227 -0.757162 -0.000002 -v 0.061103 0.058888 0.182480 -vn -0.770261 -0.637729 -0.000002 -v 0.061103 0.058138 0.182480 -vn -0.770261 -0.552292 -0.318862 -v 0.061103 0.058004 0.182980 -vn -0.770263 -0.318867 -0.552285 -v 0.061103 0.057638 0.183346 -vn -0.917199 -0.224844 0.328925 -v 0.061103 0.057071 0.185096 -vn -0.770262 0.000000 -0.637727 -v 0.061103 0.057138 0.183480 -vn -0.911012 -0.300798 0.282095 -v 0.061103 0.055970 0.184223 -vn -0.770263 0.318867 -0.552285 -v 0.061103 0.056638 0.183346 -vn -0.915052 -0.356525 0.188598 -v 0.061103 0.055169 0.183068 -vn -0.770260 0.552291 -0.318864 -v 0.061103 0.056272 0.182980 -vn -0.916109 -0.394218 0.073051 -v 0.061103 0.054737 0.181731 -vn -0.770262 0.637727 -0.000002 -v 0.061103 0.056138 0.182480 -vn -0.392024 -0.562669 0.727820 -v 0.059553 0.058013 0.180964 -vn -0.376081 -0.494394 0.783669 -v 0.059856 0.056099 0.179859 -vn -0.075593 -0.767977 0.636001 -v 0.060913 0.055022 0.179237 -vn -0.358799 -0.579084 0.732069 -v 0.059941 0.055703 0.179630 -vn -0.279287 -0.675288 0.682631 -v 0.060188 0.055358 0.179431 -vn -0.178096 -0.741302 0.647111 -v 0.060481 0.055155 0.179314 -vn -0.406967 -0.913443 -0.000002 -v 0.059553 0.058888 0.182480 -vn -0.406959 -0.791066 0.456726 -v 0.059553 0.058654 0.181605 -vn -0.057148 0.585466 0.808680 -v 0.060853 0.070494 0.192846 -vn -0.578878 0.214177 0.786783 -v 0.061103 0.070494 0.192846 -vn -0.678874 0.582523 0.446986 -v 0.061103 0.071644 0.190855 -vn -0.217179 0.591980 0.776140 -v 0.060203 0.070581 0.192696 -vn -0.376175 0.671470 0.638451 -v 0.059727 0.070819 0.192284 -vn -0.407589 0.760701 0.505179 -v 0.059553 0.071144 0.191721 -vn -0.392034 0.727816 0.562667 -v 0.059553 0.071644 0.190855 -vn -0.770260 -0.318863 0.552291 -v 0.061103 0.073660 0.190864 -vn -0.770265 -0.552286 0.318861 -v 0.061103 0.074026 0.191230 -vn -0.503541 -0.210659 0.837896 -v 0.061103 0.077058 0.191960 -vn -0.770259 -0.637731 -0.000002 -v 0.061103 0.074160 0.191730 -vn -0.916755 0.233068 0.324408 -v 0.061103 0.076225 0.192766 -vn -0.770262 -0.552292 -0.318859 -v 0.061103 0.074026 0.192230 -vn -0.916347 0.130492 0.378523 -v 0.061103 0.074997 0.193440 -vn -0.770263 -0.318867 -0.552285 -v 0.061103 0.073660 0.192596 -vn -0.915126 0.013927 0.402927 -v 0.061103 0.073626 0.193730 -vn -0.770262 0.000000 -0.637727 -v 0.061103 0.073160 0.192730 -vn -0.911047 -0.094260 0.401383 -v 0.061103 0.072230 0.193612 -vn -0.770263 0.318867 -0.552285 -v 0.061103 0.072660 0.192596 -vn -0.917219 -0.172505 0.359097 -v 0.061103 0.070927 0.193096 -vn -0.770260 0.552291 -0.318864 -v 0.061103 0.072294 0.192230 -vn -0.770263 0.637727 -0.000002 -v 0.061103 0.072160 0.191730 -vn -0.770263 0.552285 0.318866 -v 0.061103 0.072294 0.191230 -vn -0.653227 0.378581 0.655722 -v 0.061103 0.072285 0.190214 -vn -0.770260 0.318863 0.552291 -v 0.061103 0.072660 0.190864 -vn -0.653227 -0.000001 0.757162 -v 0.061103 0.073160 0.189980 -vn -0.770262 0.000000 0.637727 -v 0.061103 0.073160 0.190730 -vn -0.678874 -0.280988 0.678363 -v 0.061103 0.074035 0.190214 -vn -0.392027 -0.348974 0.851195 -v 0.059553 0.074035 0.190214 -vn -0.406971 -0.000003 0.913441 -v 0.059553 0.073160 0.189980 -vn -0.406961 0.456723 0.791067 -v 0.059553 0.072285 0.190214 -vn -0.141902 -0.142771 0.979531 -v 0.060638 0.077007 0.191930 -vn -0.036075 -0.140316 0.989449 -v 0.061103 0.077082 0.191973 -vn -0.451060 0.359121 0.817054 -v 0.061130 0.077082 0.191973 -vn -0.386592 -0.453721 0.802922 -v 0.059803 0.075946 0.191317 -vn -0.396291 -0.400976 0.825937 -v 0.059810 0.076061 0.191384 -vn -0.267267 -0.205428 0.941471 -v 0.060231 0.076789 0.191804 -vn -0.361088 -0.301729 0.882369 -v 0.059945 0.076463 0.191616 -vn -0.133425 0.108844 -0.985064 -v 0.059803 0.076845 0.147256 -vn -0.658765 0.001688 -0.752347 -v 0.061103 0.077142 0.147282 -vn -0.344947 0.390635 -0.853473 -v 0.059803 0.076267 0.147047 -vn -0.658699 0.369568 -0.655389 -v 0.061103 0.076267 0.147047 -vn -0.390797 0.611161 -0.688302 -v 0.059803 0.076095 0.146933 -vn -0.662041 0.649238 -0.374422 -v 0.061103 0.075627 0.146407 -vn -0.660765 0.750592 0.000503 -v 0.061103 0.075392 0.145532 -vn -0.391324 0.869798 -0.300527 -v 0.059803 0.075548 0.146253 -vn -0.344708 0.760831 -0.549830 -v 0.059803 0.075627 0.146407 -vn -0.659324 0.650791 0.376514 -v 0.061103 0.075627 0.144657 -vn -0.391800 0.905300 0.164087 -v 0.059803 0.075398 0.145394 -vn -0.356506 0.928832 -0.100866 -v 0.059803 0.075392 0.145532 -vn -0.657711 0.375870 0.652792 -v 0.061103 0.076267 0.144016 -vn -0.407740 0.712474 0.571078 -v 0.059803 0.075681 0.144568 -vn -0.367161 0.853150 0.370577 -v 0.059803 0.075627 0.144657 -vn -0.654709 -0.653438 0.379967 -v 0.061103 0.078658 0.144657 -vn -0.422282 -0.472079 0.773834 -v 0.059803 0.078017 0.144016 -vn -0.653963 -0.379484 0.654465 -v 0.061103 0.078017 0.144016 -vn -0.415224 -0.003309 0.909713 -v 0.059803 0.077177 0.143782 -vn -0.655409 -0.000957 0.755273 -v 0.061103 0.077142 0.143782 -vn -0.393181 0.328611 0.858734 -v 0.059803 0.076328 0.143983 -vn -0.376617 0.555268 0.741510 -v 0.059803 0.076267 0.144016 -vn -0.657717 -0.753265 0.000884 -v 0.061103 0.078892 0.145532 -vn -0.393189 -0.907983 0.144806 -v 0.059803 0.078891 0.145462 -vn -0.406163 -0.781079 0.474286 -v 0.059803 0.078640 0.144627 -vn -0.660325 -0.651538 -0.373455 -v 0.061103 0.078658 0.146407 -vn -0.394657 -0.859943 -0.323643 -v 0.059803 0.078707 0.146315 -vn -0.380457 -0.918764 -0.105478 -v 0.059803 0.078892 0.145532 -vn -0.660893 -0.371727 -0.651951 -v 0.061103 0.078017 0.147047 -vn -0.126325 -0.545551 -0.828503 -v 0.059803 0.078181 0.146940 -vn -0.388745 -0.756896 -0.525344 -v 0.059803 0.078658 0.146407 -vn -0.322676 -0.290054 -0.900971 -v 0.056803 0.078181 0.146940 -vn -0.352527 -0.429314 -0.831514 -v 0.056803 0.078017 0.147047 -vn -0.383265 -0.208992 -0.899684 -v 0.056803 0.077549 0.147234 -vn -0.274665 -0.046488 -0.960416 -v 0.056803 0.077142 0.147282 -vn -0.323524 -0.160491 -0.932510 -v 0.056803 0.076845 0.147256 -vn -0.770263 0.552289 -0.318861 -v 0.061103 0.076276 0.146032 -vn -0.770261 0.318866 -0.552288 -v 0.061103 0.076642 0.146398 -vn -0.770263 0.000001 -0.637726 -v 0.061103 0.077142 0.146532 -vn -0.770263 -0.318867 -0.552285 -v 0.061103 0.077642 0.146398 -vn -0.770260 -0.552291 -0.318864 -v 0.061103 0.078009 0.146032 -vn -0.770263 -0.637727 -0.000002 -v 0.061103 0.078142 0.145532 -vn -0.770263 -0.552286 0.318866 -v 0.061103 0.078009 0.145032 -vn -0.770260 -0.318863 0.552291 -v 0.061103 0.077642 0.144666 -vn -0.770263 0.000001 0.637726 -v 0.061103 0.077142 0.144532 -vn -0.770258 0.318862 0.552294 -v 0.061103 0.076642 0.144666 -vn -0.770266 0.552283 0.318863 -v 0.061103 0.076276 0.145032 -vn -0.770259 0.637731 -0.000002 -v 0.061103 0.076142 0.145532 -vn -0.660917 0.373902 -0.650681 -v 0.061103 0.094281 0.157447 -vn -0.660950 0.651917 -0.371685 -v 0.061103 0.093640 0.156807 -vn -0.090473 0.817782 -0.568372 -v 0.059803 0.093748 0.156971 -vn -0.081886 0.995899 0.038471 -v 0.059803 0.093406 0.155896 -vn -0.656888 0.753986 0.001710 -v 0.061103 0.093406 0.155932 -vn -0.420593 0.781140 0.461435 -v 0.059803 0.093624 0.155086 -vn -0.653089 0.654190 0.381457 -v 0.061103 0.093640 0.155057 -vn -0.653678 0.381084 0.653820 -v 0.061103 0.094281 0.154416 -vn -0.656509 0.000108 0.754318 -v 0.061103 0.095156 0.154182 -vn -0.392619 0.142191 0.908643 -v 0.059803 0.095101 0.154182 -vn -0.406953 0.478987 0.777793 -v 0.059803 0.094243 0.154439 -vn -0.657039 -0.376882 0.652886 -v 0.061103 0.096031 0.154416 -vn -0.393738 -0.333135 0.856733 -v 0.059803 0.095974 0.154385 -vn -0.382797 -0.111953 0.917024 -v 0.059803 0.095156 0.154182 -vn -0.657552 -0.652467 0.376711 -v 0.061103 0.096671 0.155057 -vn -0.393997 -0.715075 0.577438 -v 0.059803 0.096632 0.154992 -vn -0.380910 -0.554248 0.740078 -v 0.059803 0.096031 0.154416 -vn -0.658052 -0.752973 -0.000038 -v 0.061103 0.096906 0.155932 -vn -0.394242 -0.907472 0.145146 -v 0.059803 0.096904 0.155846 -vn -0.379013 -0.849859 0.366181 -v 0.059803 0.096671 0.155057 -vn -0.658535 -0.651689 -0.376341 -v 0.061103 0.096671 0.156807 -vn -0.409682 -0.846789 -0.339277 -v 0.059803 0.096717 0.156722 -vn -0.391922 -0.915580 -0.090058 -v 0.059803 0.096906 0.155932 -vn -0.659000 -0.375975 -0.651431 -v 0.061103 0.096031 0.157447 -vn -0.394721 -0.583497 -0.709737 -v 0.059803 0.096121 0.157391 -vn -0.375109 -0.746042 -0.550195 -v 0.059803 0.096671 0.156807 -vn -0.659456 0.000151 -0.751743 -v 0.061103 0.095156 0.157682 -vn -0.394944 -0.153035 -0.905869 -v 0.059803 0.095273 0.157678 -vn -0.373143 -0.373532 -0.849258 -v 0.059803 0.096031 0.157447 -vn -0.339319 0.509732 -0.790592 -v 0.059803 0.094281 0.157447 -vn -0.385320 0.333850 -0.860275 -v 0.059803 0.094393 0.157507 -vn -0.371143 0.098841 -0.923300 -v 0.059803 0.095156 0.157682 -vn -0.322197 0.852378 -0.411874 -v 0.056803 0.093748 0.156971 -vn -0.343790 0.824530 -0.449399 -v 0.056803 0.093640 0.156807 -vn -0.386035 0.891511 -0.237034 -v 0.056803 0.093478 0.156430 -vn -0.306512 0.948182 -0.083676 -v 0.056803 0.093406 0.155932 -vn -0.324489 0.941530 -0.090708 -v 0.056803 0.093406 0.155896 -vn -0.770266 0.552283 -0.318863 -v 0.061103 0.094290 0.156432 -vn -0.770258 0.318862 -0.552294 -v 0.061103 0.094656 0.156798 -vn -0.770263 0.000001 -0.637726 -v 0.061103 0.095156 0.156932 -vn -0.770263 -0.318867 -0.552285 -v 0.061103 0.095656 0.156798 -vn -0.770260 -0.552291 -0.318864 -v 0.061103 0.096022 0.156432 -vn -0.770263 -0.637726 0.000000 -v 0.061103 0.096156 0.155932 -vn -0.770260 -0.552291 0.318864 -v 0.061103 0.096022 0.155432 -vn -0.770263 -0.318867 0.552285 -v 0.061103 0.095656 0.155066 -vn -0.770263 0.000001 0.637726 -v 0.061103 0.095156 0.154932 -vn -0.770261 0.318866 0.552288 -v 0.061103 0.094656 0.155066 -vn -0.770263 0.552289 0.318861 -v 0.061103 0.094290 0.155432 -vn -0.770259 0.637731 0.000002 -v 0.061103 0.094156 0.155932 -vn -0.301560 0.811516 0.500503 -v 0.060584 0.077577 0.191393 -vn -0.517907 0.725908 0.452582 -v 0.060353 0.077483 0.191339 -vn -0.709500 0.598089 0.372691 -v 0.060042 0.077277 0.191220 -vn -0.851022 0.443686 0.280899 -v 0.059804 0.077008 0.191065 -vn -0.951518 0.261453 0.162035 -v 0.059696 0.076808 0.190949 -vn -0.913761 -0.070270 0.400129 -v 0.059611 0.076177 0.191223 -vn -0.817787 0.150878 0.555392 -v 0.059767 0.076635 0.191498 -vn -0.615731 0.369831 0.695773 -v 0.060097 0.077008 0.191721 -vn -0.322017 0.520308 0.790939 -v 0.060566 0.077257 0.191868 -vn -0.307938 -0.836684 -0.452918 -v 0.060584 0.055221 0.178486 -vn -0.520709 -0.752384 -0.403461 -v 0.060353 0.055315 0.178540 -vn -0.702638 -0.627415 -0.335634 -v 0.060042 0.055521 0.178659 -vn -0.952565 -0.268620 -0.143047 -v 0.059696 0.055990 0.178930 -vn -0.854008 -0.460674 -0.241763 -v 0.059804 0.055790 0.178815 -vn -0.177914 -0.982690 -0.051639 -v 0.060874 0.054908 0.178940 -vn -0.445568 -0.895243 -0.003035 -v 0.060355 0.055068 0.179029 -vn -0.671647 -0.736611 0.079342 -v 0.060003 0.055314 0.179166 -vn -0.850368 -0.482831 0.209163 -v 0.059705 0.055732 0.179398 -vn -0.807281 -0.546568 0.222623 -v 0.059554 0.057952 0.184970 -vn -0.807282 0.080484 0.584652 -v 0.059554 0.070596 0.192270 -vn -0.466085 -0.717166 0.518109 -v 0.060103 0.057678 0.185446 -vn -0.466084 -0.090122 0.880139 -v 0.060103 0.070322 0.192746 -vn -0.680956 -0.366163 0.634211 -v 0.060103 0.074199 0.171430 -vn -0.680956 -0.203745 0.703410 -v 0.060103 0.072181 0.170570 -vn -0.680957 -0.029489 0.731730 -v 0.060103 0.070016 0.170218 -vn -0.680956 0.146485 0.717525 -v 0.060103 0.067829 0.170394 -vn -0.680957 0.313942 0.661618 -v 0.060103 0.065748 0.171089 -vn -0.680955 0.463156 0.567262 -v 0.060103 0.063894 0.172261 -vn -0.680957 0.585451 0.439936 -v 0.060103 0.062374 0.173844 -vn -0.680956 0.673723 0.287047 -v 0.060103 0.061277 0.175743 -vn -0.680956 0.722841 0.117473 -v 0.060103 0.060667 0.177851 -vn -0.680956 0.729949 -0.058928 -v 0.060103 0.060579 0.180043 -vn -0.680956 0.694636 -0.231904 -v 0.060103 0.061017 0.182192 -vn -0.680957 0.618953 -0.391402 -v 0.060103 0.061958 0.184174 -vn -0.680956 0.507299 -0.528154 -v 0.060103 0.063345 0.185873 -vn -0.680957 0.366162 -0.634211 -v 0.060103 0.065099 0.187191 -vn -0.680956 0.203746 -0.703410 -v 0.060103 0.067117 0.188051 -vn -0.680956 0.029486 -0.731731 -v 0.060103 0.069283 0.188403 -vn -0.680957 -0.146484 -0.717523 -v 0.060103 0.071469 0.188226 -vn -0.680956 -0.313942 -0.661619 -v 0.060103 0.073550 0.187532 -vn -0.680957 -0.463155 -0.567261 -v 0.060103 0.075404 0.186359 -vn -0.680957 -0.585450 -0.439939 -v 0.060103 0.076924 0.184777 -vn -0.680956 -0.673723 -0.287048 -v 0.060103 0.078021 0.182877 -vn -0.680956 -0.722841 -0.117473 -v 0.060103 0.078631 0.180770 -vn -0.680956 -0.729949 0.058928 -v 0.060103 0.078720 0.178578 -vn -0.680956 -0.694636 0.231904 -v 0.060103 0.078281 0.176429 -vn -0.680956 -0.618952 0.391403 -v 0.060103 0.077340 0.174447 -vn -0.680957 -0.507298 0.528154 -v 0.060103 0.075953 0.172747 -vn -0.740587 0.659818 -0.127170 -v 0.060103 0.076228 0.178042 -vn -0.740587 0.597262 -0.307912 -v 0.060103 0.075604 0.176240 -vn -0.740586 0.486321 -0.463707 -v 0.060103 0.074498 0.174687 -vn -0.740586 0.335982 -0.581935 -v 0.060103 0.072999 0.173508 -vn -0.740587 0.158422 -0.653019 -v 0.060103 0.071229 0.172799 -vn -0.740587 -0.031974 -0.671200 -v 0.060103 0.069330 0.172618 -vn -0.740586 0.031973 0.671200 -v 0.060103 0.069968 0.186003 -vn -0.740586 0.219775 0.635005 -v 0.060103 0.071841 0.185642 -vn -0.740587 0.389774 0.547364 -v 0.060103 0.073536 0.184768 -vn -0.740586 0.528197 0.415379 -v 0.060103 0.074916 0.183452 -vn -0.740587 0.623827 0.249743 -v 0.060103 0.075869 0.181801 -vn -0.740587 0.668918 0.063874 -v 0.060103 0.076319 0.179947 -vn -0.740587 -0.219778 -0.635003 -v 0.060103 0.067458 0.172979 -vn -0.740586 -0.389776 -0.547363 -v 0.060103 0.065763 0.173853 -vn -0.740586 -0.528197 -0.415379 -v 0.060103 0.064383 0.175169 -vn -0.740586 -0.623827 -0.249743 -v 0.060103 0.063429 0.176820 -vn -0.740587 -0.668918 -0.063874 -v 0.060103 0.062979 0.178674 -vn -0.740587 -0.659818 0.127170 -v 0.060103 0.063070 0.180578 -vn -0.740586 -0.597263 0.307910 -v 0.060103 0.063694 0.182380 -vn -0.740586 -0.486323 0.463705 -v 0.060103 0.064800 0.183934 -vn -0.740588 -0.335979 0.581935 -v 0.060103 0.066299 0.185113 -vn -0.740586 -0.158419 0.653021 -v 0.060103 0.068070 0.185822 -vn -0.676434 0.368253 -0.637830 -v 0.059353 0.072999 0.173508 -vn -0.676433 0.173638 -0.715743 -v 0.059353 0.071229 0.172799 -vn -0.676434 -0.035045 -0.735669 -v 0.059353 0.069330 0.172618 -vn -0.676434 -0.240888 -0.695996 -v 0.059353 0.067458 0.172979 -vn -0.676434 -0.427215 -0.599937 -v 0.059353 0.065763 0.173853 -vn -0.676434 -0.578931 -0.455276 -v 0.059353 0.064383 0.175169 -vn -0.676434 -0.683746 -0.273731 -v 0.059353 0.063429 0.176820 -vn -0.676434 -0.733169 -0.070009 -v 0.059353 0.062979 0.178674 -vn -0.676434 -0.723194 0.139385 -v 0.059353 0.063070 0.180578 -vn -0.676434 -0.654630 0.337485 -v 0.059353 0.063694 0.182380 -vn -0.676434 -0.533034 0.508244 -v 0.059353 0.064800 0.183934 -vn -0.676433 -0.368252 0.637832 -v 0.059353 0.066299 0.185113 -vn -0.676434 -0.173635 0.715743 -v 0.059353 0.068070 0.185822 -vn -0.676434 0.035044 0.735669 -v 0.059353 0.069968 0.186003 -vn -0.676434 0.240885 0.695997 -v 0.059353 0.071841 0.185642 -vn -0.676433 0.427213 0.599939 -v 0.059353 0.073536 0.184768 -vn -0.676434 0.578931 0.455276 -v 0.059353 0.074916 0.183452 -vn -0.676434 0.683746 0.273731 -v 0.059353 0.075869 0.181801 -vn -0.676434 0.733169 0.070009 -v 0.059353 0.076319 0.179947 -vn -0.676434 0.723194 -0.139385 -v 0.059353 0.076228 0.178042 -vn -0.676434 0.654630 -0.337487 -v 0.059353 0.075604 0.176240 -vn -0.676434 0.533032 -0.508246 -v 0.059353 0.074498 0.174687 -vn -0.746100 -0.640711 -0.181177 -v 0.059353 0.074220 0.180603 -vn -0.746098 -0.664825 0.036679 -v 0.059353 0.074392 0.179049 -vn -0.746099 -0.616892 0.250559 -v 0.059353 0.074050 0.177523 -vn -0.746099 -0.502109 0.437289 -v 0.059353 0.073231 0.176191 -vn -0.746098 -0.332916 0.576631 -v 0.059353 0.072024 0.175197 -vn -0.746098 -0.127650 0.653485 -v 0.059353 0.070560 0.174648 -vn -0.746100 0.091454 0.659523 -v 0.059353 0.068997 0.174605 -vn -0.746098 0.300648 0.594095 -v 0.059353 0.067504 0.175072 -vn -0.746099 0.233466 -0.623563 -v 0.059353 0.067984 0.183759 -vn -0.746099 0.018347 -0.665583 -v 0.059353 0.069518 0.184059 -vn -0.746099 -0.198760 -0.635477 -v 0.059353 0.071067 0.183844 -vn -0.746100 -0.394330 -0.536506 -v 0.059353 0.072462 0.183138 -vn -0.746098 -0.547170 -0.379399 -v 0.059353 0.073553 0.182017 -vn -0.746099 0.477259 0.464285 -v 0.059353 0.066244 0.175998 -vn -0.746099 0.602153 0.284162 -v 0.059353 0.065353 0.177283 -vn -0.746099 0.661794 0.073248 -v 0.059353 0.064928 0.178788 -vn -0.746099 0.649719 -0.145606 -v 0.059353 0.065014 0.180349 -vn -0.746099 0.567238 -0.348680 -v 0.059353 0.065603 0.181798 -vn -0.746099 0.423287 -0.513969 -v 0.059353 0.066629 0.182977 -vn -0.671869 -0.370333 0.641440 -v 0.061853 0.072024 0.175197 -vn -0.671869 -0.141996 0.726931 -v 0.061853 0.070560 0.174648 -vn -0.671867 0.101733 0.733651 -v 0.061853 0.068997 0.174605 -vn -0.671869 0.334438 0.660865 -v 0.061853 0.067504 0.175072 -vn -0.671868 0.530900 0.516468 -v 0.061853 0.066244 0.175998 -vn -0.671869 0.669831 0.316100 -v 0.061853 0.065353 0.177283 -vn -0.671869 0.736175 0.081480 -v 0.061853 0.064928 0.178788 -vn -0.671868 0.722744 -0.161971 -v 0.061853 0.065014 0.180349 -vn -0.671869 0.630991 -0.387869 -v 0.061853 0.065603 0.181798 -vn -0.671868 0.470862 -0.571736 -v 0.061853 0.066629 0.182977 -vn -0.671869 0.259706 -0.693647 -v 0.061853 0.067984 0.183759 -vn -0.671869 0.020409 -0.740389 -v 0.061853 0.069518 0.184059 -vn -0.671869 -0.221099 -0.706900 -v 0.061853 0.071067 0.183844 -vn -0.671868 -0.438652 -0.596807 -v 0.061853 0.072462 0.183138 -vn -0.671870 -0.608666 -0.422039 -v 0.061853 0.073553 0.182017 -vn -0.671868 -0.712724 -0.201540 -v 0.061853 0.074220 0.180603 -vn -0.671869 -0.739545 0.040802 -v 0.061853 0.074392 0.179049 -vn -0.671868 -0.686227 0.278720 -v 0.061853 0.074050 0.177523 -vn -0.671868 -0.558544 0.486438 -v 0.061853 0.073231 0.176191 -vn -1.000000 0.000000 0.000000 -v 0.061853 0.069649 0.179310 -vn 0.770261 -0.552291 0.318862 -v 0.091603 0.089798 0.172662 -vn 0.770265 -0.318861 0.552286 -v 0.091603 0.089341 0.172204 -vn 0.923880 0.331412 0.191341 -v 0.091603 0.091265 0.171871 -vn 0.987815 0.150331 -0.040281 -v 0.091603 0.067162 0.164018 -vn 0.923879 0.191342 -0.331415 -v 0.091603 0.067747 0.164356 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.065497 0.168253 -vn 0.991004 -0.118498 -0.062196 -v 0.091603 0.056007 0.178940 -vn 0.997001 -0.077294 0.003753 -v 0.091603 0.060257 0.171578 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.060976 0.174534 -vn 0.973781 -0.226527 0.020872 -v 0.091603 0.060141 0.169779 -vn 0.707112 -0.353540 0.612374 -v 0.091603 0.058517 0.168842 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.059492 0.167153 -vn 0.973781 0.226527 -0.020872 -v 0.091603 0.097907 0.156366 -vn 0.717281 0.572434 -0.397275 -v 0.091603 0.099640 0.157366 -vn 0.923880 0.331414 0.191341 -v 0.091603 0.099452 0.157690 -vn 0.945452 -0.325760 -0.000000 -v 0.091603 0.061703 0.182806 -vn 0.736823 -0.502429 0.452390 -v 0.091603 0.065636 0.182924 -vn 0.945448 -0.282127 -0.162886 -v 0.091603 0.061569 0.183306 -vn 0.736822 -0.338044 0.585507 -v 0.091603 0.066949 0.183987 -vn 0.945454 -0.162879 -0.282113 -v 0.091603 0.061203 0.183672 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.061647 0.174921 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.064288 0.176446 -vn 0.945445 -0.162895 0.282134 -v 0.091603 0.061203 0.181940 -vn 0.945452 0.000003 0.325762 -v 0.091603 0.060703 0.181806 -vn 0.945445 0.162890 0.282137 -v 0.091603 0.060203 0.181940 -vn 0.990581 -0.101755 0.091621 -v 0.091603 0.056498 0.183616 -vn 0.945456 0.282110 0.162874 -v 0.091603 0.059837 0.182306 -vn 0.945450 0.325767 0.000001 -v 0.091603 0.059703 0.182806 -vn 0.945441 0.000004 -0.325793 -v 0.091603 0.060703 0.183806 -vn 0.991446 -0.065260 0.113033 -v 0.091603 0.064399 0.188404 -vn 0.945454 0.162874 -0.282114 -v 0.091603 0.060203 0.183672 -vn 0.991446 -0.065260 0.113034 -v 0.091603 0.059138 0.185366 -vn 0.945448 0.282129 -0.162883 -v 0.091603 0.059837 0.183306 -vn 0.991004 -0.071524 0.113112 -v 0.091603 0.057471 0.184404 -vn 0.990582 -0.086170 0.106409 -v 0.091603 0.056954 0.184048 -vn 0.770261 -0.637728 -0.000000 -v 0.091603 0.062583 0.166715 -vn 0.770263 -0.552287 0.318864 -v 0.091603 0.062415 0.166090 -vn 0.973781 -0.095187 -0.206614 -v 0.091603 0.063391 0.164150 -vn 0.770260 -0.318866 0.552290 -v 0.091603 0.061958 0.165632 -vn 0.707105 0.353549 -0.612377 -v 0.091603 0.061767 0.163213 -vn 0.770264 0.000000 0.637725 -v 0.091603 0.061333 0.165465 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.060517 0.165378 -vn 0.770260 0.318865 0.552291 -v 0.091603 0.060708 0.165632 -vn 0.770263 0.552286 0.318865 -v 0.091603 0.060250 0.166090 -vn 0.770262 0.637728 -0.000002 -v 0.091603 0.060083 0.166715 -vn 0.770260 0.552292 -0.318863 -v 0.091603 0.060250 0.167340 -vn 0.770261 -0.552292 -0.318861 -v 0.091603 0.062415 0.167340 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.064826 0.167865 -vn 0.770265 -0.318861 -0.552285 -v 0.091603 0.061958 0.167797 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.063801 0.169641 -vn 0.770258 0.000000 -0.637732 -v 0.091603 0.061333 0.167965 -vn 0.770265 0.318862 -0.552285 -v 0.091603 0.060708 0.167797 -vn 0.770261 -0.637729 0.000002 -v 0.091603 0.070583 0.152858 -vn 0.973781 -0.095189 -0.206615 -v 0.091603 0.071391 0.150294 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.072701 0.154225 -vn 0.770266 -0.637722 -0.000008 -v 0.091603 0.073849 0.152117 -vn 0.770261 -0.552288 0.318866 -v 0.091603 0.073889 0.152267 -vn 0.770263 -0.552286 0.318865 -v 0.091603 0.070415 0.152233 -vn 0.770260 -0.318865 0.552291 -v 0.091603 0.069958 0.151776 -vn 0.707109 0.353564 -0.612363 -v 0.091603 0.069767 0.149356 -vn 0.770264 0.000000 0.637725 -v 0.091603 0.069333 0.151608 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.068392 0.151738 -vn 0.973781 -0.226528 0.020872 -v 0.091603 0.068141 0.155923 -vn 0.707116 -0.353534 0.612374 -v 0.091603 0.066517 0.154985 -vn 0.770264 0.552286 -0.318863 -v 0.091603 0.068250 0.153483 -vn 0.770260 0.318865 -0.552291 -v 0.091603 0.068708 0.153941 -vn 0.770264 -0.000000 -0.637725 -v 0.091603 0.069333 0.154108 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.070826 0.157473 -vn 0.770260 -0.318865 -0.552291 -v 0.091603 0.069958 0.153941 -vn 0.770264 -0.552286 -0.318863 -v 0.091603 0.070415 0.153483 -vn 0.770260 0.318865 0.552291 -v 0.091603 0.068708 0.151776 -vn 0.770263 0.552286 0.318865 -v 0.091603 0.068250 0.152233 -vn 0.770261 0.637729 0.000002 -v 0.091603 0.068083 0.152858 -vn 0.770262 0.318869 -0.552286 -v 0.091603 0.080096 0.145216 -vn 0.770264 -0.000000 -0.637725 -v 0.091603 0.080721 0.145383 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.081201 0.147153 -vn 0.770260 -0.318865 -0.552291 -v 0.091603 0.081346 0.145216 -vn 0.770262 -0.552286 -0.318867 -v 0.091603 0.081803 0.144758 -vn 0.923880 0.191341 -0.331414 -v 0.091603 0.083138 0.143797 -vn 0.770264 -0.637725 0.000004 -v 0.091603 0.081971 0.144133 -vn 0.770259 -0.552290 0.318868 -v 0.091603 0.081803 0.143508 -vn 0.770265 -0.318861 0.552286 -v 0.091603 0.081346 0.143051 -vn 0.923880 0.191342 -0.331413 -v 0.091603 0.080497 0.142272 -vn 0.770258 -0.000000 0.637732 -v 0.091603 0.080721 0.142883 -vn 0.770265 0.318861 0.552287 -v 0.091603 0.080096 0.143051 -vn 0.923879 0.191344 -0.331415 -v 0.091603 0.079826 0.141884 -vn 0.770261 0.552291 0.318862 -v 0.091603 0.079638 0.143508 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.077888 0.145240 -vn 0.770262 0.637728 -0.000002 -v 0.091603 0.079471 0.144133 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.078559 0.145628 -vn 0.770260 0.552291 -0.318864 -v 0.091603 0.079638 0.144758 -vn 0.923880 0.331413 0.191342 -v 0.091603 0.089015 0.175769 -vn 0.717283 -0.057828 0.694378 -v 0.091603 0.088390 0.176851 -vn 1.000000 0.000003 0.000001 -v 0.091603 0.085659 0.173831 -vn 0.973781 0.095188 0.206614 -v 0.091603 0.086657 0.175851 -vn 1.000000 0.000001 -0.000001 -v 0.091603 0.083034 0.178378 -vn 0.973781 0.226529 -0.020872 -v 0.091603 0.085907 0.177150 -vn 0.770260 0.000004 0.637730 -v 0.091603 0.084716 0.178965 -vn 0.770265 0.318861 0.552286 -v 0.091603 0.084091 0.179132 -vn 0.770261 0.552291 0.318862 -v 0.091603 0.083633 0.179590 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.082009 0.180153 -vn 0.923878 0.331417 0.191343 -v 0.091603 0.085365 0.182091 -vn 0.770289 0.318849 -0.552259 -v 0.091603 0.084091 0.181297 -vn 0.770270 0.000001 -0.637718 -v 0.091603 0.084716 0.181465 -vn 0.770261 0.637728 0.000000 -v 0.091603 0.083466 0.180215 -vn 0.770263 0.552286 -0.318865 -v 0.091603 0.083633 0.180840 -vn 0.770259 -0.318863 -0.552293 -v 0.091603 0.085340 0.181297 -vn 0.770263 -0.552286 -0.318865 -v 0.091603 0.085798 0.180840 -vn 0.923880 0.331413 0.191341 -v 0.091603 0.086390 0.180315 -vn 0.770261 -0.637728 -0.000000 -v 0.091603 0.085965 0.180215 -vn 0.717286 0.572433 -0.397267 -v 0.091603 0.087640 0.178150 -vn 0.770261 -0.552291 0.318862 -v 0.091603 0.085798 0.179590 -vn 0.770264 -0.318858 0.552289 -v 0.091603 0.085340 0.179132 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.093034 0.161057 -vn 0.973781 0.095187 0.206614 -v 0.091603 0.094657 0.161995 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.090909 0.164738 -vn 0.973781 0.226528 -0.020872 -v 0.091603 0.093907 0.163294 -vn 0.770264 0.000000 0.637725 -v 0.091603 0.092716 0.165108 -vn 0.770258 0.000000 -0.637732 -v 0.091603 0.092716 0.167608 -vn 0.717285 -0.057830 0.694375 -v 0.091603 0.092390 0.169923 -vn 0.770265 0.318861 -0.552286 -v 0.091603 0.092091 0.167441 -vn 0.973781 0.095187 0.206614 -v 0.091603 0.090657 0.168923 -vn 0.770261 0.552291 -0.318862 -v 0.091603 0.091633 0.166983 -vn 0.770265 -0.318861 -0.552287 -v 0.091603 0.093341 0.167441 -vn 0.770261 -0.552291 -0.318862 -v 0.091603 0.093798 0.166983 -vn 0.923880 0.331412 0.191341 -v 0.091603 0.094265 0.166675 -vn 0.770261 -0.637728 -0.000000 -v 0.091603 0.093966 0.166358 -vn 0.717282 0.572435 -0.397272 -v 0.091603 0.095640 0.164294 -vn 0.770263 -0.552286 0.318865 -v 0.091603 0.093798 0.165733 -vn 0.770260 -0.318865 0.552291 -v 0.091603 0.093341 0.165276 -vn 0.770261 0.637728 0.000000 -v 0.091603 0.091466 0.166358 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.089034 0.167985 -vn 0.770263 0.552286 0.318865 -v 0.091603 0.091633 0.165733 -vn 0.770260 0.318865 0.552291 -v 0.091603 0.092091 0.165276 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.095035 0.155140 -vn 0.770264 0.552289 -0.318858 -v 0.091603 0.094409 0.156124 -vn 0.737700 0.410992 -0.535615 -v 0.091603 0.094300 0.156015 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.091723 0.153228 -vn 0.770256 -0.000004 0.637735 -v 0.091603 0.090950 0.162117 -vn 0.770266 0.318854 0.552289 -v 0.091603 0.091100 0.162077 -vn 0.737701 0.535616 0.410991 -v 0.091603 0.091209 0.161967 -vn 0.707106 0.612373 0.353554 -v 0.091603 0.092059 0.160495 -vn 0.737705 0.623738 0.258346 -v 0.091603 0.094409 0.156424 -vn 0.707107 -0.353553 0.612372 -v 0.091603 0.087660 0.160264 -vn 0.737702 -0.258355 0.623737 -v 0.091603 0.090800 0.162077 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.089848 0.164125 -vn 0.707107 -0.612372 -0.353554 -v 0.091603 0.086863 0.157495 -vn 0.737703 -0.623736 -0.258355 -v 0.091603 0.086013 0.158967 -vn 1.000000 0.000000 -0.000000 -v 0.091603 0.081274 0.159175 -vn 0.770255 -0.637736 -0.000008 -v 0.091603 0.085973 0.159117 -vn 0.770272 -0.552279 0.318855 -v 0.091603 0.086013 0.159267 -vn 1.000000 0.000002 -0.000000 -v 0.091603 0.085171 0.161425 -vn 0.737696 -0.410989 0.535624 -v 0.091603 0.086123 0.159377 -vn 0.707107 0.353553 -0.612373 -v 0.091603 0.091160 0.154202 -vn 0.707105 0.353557 -0.612372 -v 0.091603 0.089796 0.153415 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.090359 0.152440 -vn 0.737705 0.258353 -0.623735 -v 0.091603 0.089623 0.153315 -vn 0.717282 0.572435 -0.397272 -v 0.091603 0.091640 0.171222 -vn 0.973781 0.226528 -0.020872 -v 0.091603 0.089907 0.170222 -vn 1.000000 0.000000 -0.000000 -v 0.091603 0.087909 0.169934 -vn 0.923882 0.191331 -0.331412 -v 0.091603 0.098034 0.152397 -vn 0.717285 0.694377 0.057818 -v 0.091603 0.098142 0.152459 -vn 0.973781 0.206616 -0.095188 -v 0.091603 0.097142 0.154191 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.096096 0.155753 -vn 0.816497 0.557678 -0.149427 -v 0.091603 0.098657 0.155066 -vn 0.717285 -0.397269 -0.572434 -v 0.091603 0.092513 0.149209 -vn 0.923879 0.191342 -0.331415 -v 0.091603 0.093660 0.149872 -vn 0.973779 -0.020876 -0.226535 -v 0.091603 0.091513 0.150941 -vn 0.923881 0.191335 -0.331414 -v 0.091603 0.091296 0.150816 -vn 1.000000 0.000001 0.000000 -v 0.091603 0.086462 0.150190 -vn 0.770255 0.000000 -0.637737 -v 0.091603 0.089473 0.153274 -vn 0.717283 0.694378 0.057825 -v 0.091603 0.084286 0.144459 -vn 0.973781 0.206615 -0.095187 -v 0.091603 0.083286 0.146191 -vn 0.923880 0.191342 -0.331412 -v 0.091603 0.087399 0.148566 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.073580 0.142753 -vn 0.707110 0.353564 -0.612363 -v 0.091603 0.073767 0.142428 -vn 0.973781 -0.095189 -0.206615 -v 0.091603 0.075391 0.143366 -vn 0.717286 -0.397268 -0.572433 -v 0.091603 0.078656 0.141209 -vn 0.973781 -0.020872 -0.226526 -v 0.091603 0.077656 0.142941 -vn 0.816496 -0.149429 -0.557678 -v 0.091603 0.076141 0.142066 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.065392 0.156934 -vn 0.707112 0.353561 -0.612362 -v 0.091603 0.065767 0.156284 -vn 0.973781 -0.095188 -0.206614 -v 0.091603 0.067391 0.157222 -vn 0.717256 0.057880 -0.694402 -v 0.091603 0.065659 0.156222 -vn 0.923880 -0.331413 -0.191341 -v 0.091603 0.065284 0.156871 -vn 0.923880 -0.331413 -0.191341 -v 0.091603 0.063034 0.160769 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.067451 0.163319 -vn 0.973781 -0.226528 0.020872 -v 0.091603 0.064141 0.162851 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.063142 0.160831 -vn 0.707113 -0.353540 0.612373 -v 0.091603 0.062517 0.161914 -vn 0.717284 -0.572428 0.397277 -v 0.091603 0.062409 0.161851 -vn 0.717281 -0.572435 0.397274 -v 0.091603 0.059391 0.171078 -vn 0.990581 -0.114835 0.074575 -v 0.091603 0.056116 0.183118 -vn 0.990582 -0.125087 0.055692 -v 0.091603 0.055817 0.182566 -vn 0.990582 -0.127830 -0.049069 -v 0.091603 0.055737 0.179506 -vn 0.990581 -0.133933 -0.028468 -v 0.091603 0.055558 0.180108 -vn 0.990581 -0.132260 0.035439 -v 0.091603 0.055607 0.181975 -vn 0.990581 -0.136175 0.014313 -v 0.091603 0.055493 0.181358 -vn 0.990582 -0.136737 -0.007166 -v 0.091603 0.055476 0.180730 -vn 0.945453 -0.162878 0.282116 -v 0.091603 0.071595 0.187940 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.074810 0.182521 -vn 0.945452 -0.282116 0.162883 -v 0.091603 0.071961 0.188306 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.078123 0.184434 -vn 0.945452 -0.325761 0.000001 -v 0.091603 0.072095 0.188806 -vn 0.945446 -0.282132 -0.162890 -v 0.091603 0.071961 0.189306 -vn 0.990581 0.055692 0.125089 -v 0.091603 0.074954 0.192594 -vn 0.990582 0.035438 0.132259 -v 0.091603 0.074363 0.192803 -vn 0.945454 -0.162880 -0.282113 -v 0.091603 0.071595 0.189672 -vn 0.990582 -0.007168 0.136735 -v 0.091603 0.073118 0.192934 -vn 0.990581 0.014314 0.136177 -v 0.091603 0.073745 0.192918 -vn 0.991005 0.113111 0.071523 -v 0.091603 0.076791 0.190940 -vn 0.990581 0.106412 0.086170 -v 0.091603 0.076436 0.191457 -vn 0.990582 0.091620 0.101755 -v 0.091603 0.076004 0.191912 -vn 0.717284 -0.057826 0.694378 -v 0.091603 0.084390 0.183779 -vn 0.973781 0.095187 0.206614 -v 0.091603 0.082657 0.182779 -vn 0.717286 -0.057824 0.694376 -v 0.091603 0.081907 0.184078 -vn 0.997001 0.035398 0.068815 -v 0.091603 0.081041 0.183578 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.079184 0.185046 -vn 0.973781 -0.226527 0.020873 -v 0.091603 0.072141 0.148995 -vn 0.707098 -0.353577 0.612369 -v 0.091603 0.070517 0.148057 -vn 0.770263 0.552286 -0.318865 -v 0.091603 0.072250 0.146555 -vn 0.770260 0.318865 -0.552291 -v 0.091603 0.072708 0.147013 -vn 0.707106 -0.612373 -0.353554 -v 0.091603 0.074739 0.150495 -vn 0.737697 -0.623737 -0.258372 -v 0.091603 0.073889 0.151967 -vn 0.770264 -0.000000 -0.637725 -v 0.091603 0.073333 0.147180 -vn 0.770260 -0.318865 -0.552291 -v 0.091603 0.073958 0.147013 -vn 0.737700 -0.535615 -0.410992 -v 0.091603 0.077089 0.146424 -vn 0.770263 -0.552286 -0.318865 -v 0.091603 0.074415 0.146555 -vn 0.770264 -0.318858 -0.552289 -v 0.091603 0.077199 0.146315 -vn 0.770261 -0.637728 -0.000000 -v 0.091603 0.074583 0.145930 -vn 0.770261 -0.552291 0.318862 -v 0.091603 0.074415 0.145305 -vn 0.770265 -0.318861 0.552286 -v 0.091603 0.073958 0.144848 -vn 0.770258 -0.000000 0.637732 -v 0.091603 0.073333 0.144680 -vn 0.770262 0.318858 0.552291 -v 0.091603 0.072708 0.144848 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.072892 0.143944 -vn 0.770264 0.552286 0.318863 -v 0.091603 0.072250 0.145305 -vn 0.770261 0.637729 -0.000002 -v 0.091603 0.072083 0.145930 -vn 0.770256 -0.000004 -0.637735 -v 0.091603 0.077349 0.146274 -vn 0.707106 0.353554 -0.612372 -v 0.091603 0.077997 0.146602 -vn 0.737704 0.258351 -0.623737 -v 0.091603 0.077499 0.146315 -vn 0.737699 0.623738 0.258362 -v 0.091603 0.082285 0.149424 -vn 0.770266 0.637723 -0.000008 -v 0.091603 0.082325 0.149274 -vn 0.770257 0.552289 -0.318875 -v 0.091603 0.082285 0.149124 -vn 0.737700 0.410993 -0.535616 -v 0.091603 0.082175 0.149015 -vn 0.707106 0.353554 -0.612373 -v 0.091603 0.080638 0.148127 -vn 0.737700 0.535616 0.410991 -v 0.091603 0.079085 0.154967 -vn 0.707106 0.612373 0.353553 -v 0.091603 0.079935 0.153495 -vn 1.000000 0.000001 0.000000 -v 0.091603 0.083399 0.155495 -vn 1.000000 0.000001 0.000000 -v 0.091603 0.085774 0.151381 -vn 0.770266 -0.318854 -0.552289 -v 0.091603 0.089323 0.153315 -vn 0.770266 0.318854 0.552289 -v 0.091603 0.078975 0.155077 -vn 0.737700 -0.535615 -0.410992 -v 0.091603 0.089213 0.153424 -vn 0.737700 -0.410993 0.535615 -v 0.091603 0.073999 0.152377 -vn 0.707107 -0.353554 0.612372 -v 0.091603 0.074497 0.152664 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.073372 0.154613 -vn 0.707107 -0.353553 0.612372 -v 0.091603 0.077138 0.154189 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.076013 0.156138 -vn 0.737704 -0.258350 0.623738 -v 0.091603 0.078675 0.155077 -vn 0.770255 -0.000000 0.637737 -v 0.091603 0.078825 0.155117 -vn 0.973781 0.206614 -0.095188 -v 0.091603 0.076082 0.169168 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.073399 0.172815 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.076024 0.168269 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.077296 0.175065 -vn 1.000000 0.000002 -0.000000 -v 0.091603 0.084660 0.165460 -vn 0.923879 -0.191341 0.331414 -v 0.091603 0.084160 0.166326 -vn 0.923880 -0.191341 0.331414 -v 0.091603 0.082796 0.165539 -vn 1.000000 0.000000 -0.000001 -v 0.091603 0.086848 0.169321 -vn 0.923882 -0.331409 -0.191340 -v 0.091603 0.086761 0.169271 -vn 0.987815 -0.150331 0.040282 -v 0.091603 0.087386 0.168189 -vn 1.000000 0.000001 0.000000 -v 0.091603 0.087973 0.167373 -vn 0.923882 -0.331407 -0.191339 -v 0.091603 0.084511 0.173169 -vn 1.000000 0.000003 0.000001 -v 0.091603 0.084598 0.173219 -vn 0.987815 -0.040281 -0.150329 -v 0.091603 0.084136 0.173818 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.068138 0.169778 -vn 0.923880 0.191342 -0.331413 -v 0.091603 0.070388 0.165881 -vn 0.973781 -0.020872 -0.226528 -v 0.091603 0.075216 0.168668 -vn 0.707110 -0.612368 -0.353555 -v 0.091603 0.075591 0.168019 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.078274 0.164371 -vn 0.707109 -0.612371 -0.353551 -v 0.091603 0.077841 0.164121 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.079399 0.162423 -vn 0.973781 -0.206614 0.095188 -v 0.091603 0.078466 0.163039 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.074138 0.159385 -vn 0.923881 -0.191340 0.331411 -v 0.091603 0.073638 0.160251 -vn 0.923882 -0.191338 0.331408 -v 0.091603 0.070997 0.158726 -vn 0.736824 -0.070671 -0.672381 -v 0.091603 0.069085 0.173940 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.067113 0.171553 -vn 0.736822 0.140565 -0.661313 -v 0.091603 0.070772 0.174028 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.072374 0.174591 -vn 0.736823 -0.274988 -0.617635 -v 0.091603 0.067453 0.174377 -vn 0.736823 -0.452389 -0.502430 -v 0.091603 0.066036 0.175297 -vn 0.736824 -0.585506 -0.338043 -v 0.091603 0.064973 0.176610 -vn 0.736824 -0.661311 -0.140565 -v 0.091603 0.064367 0.178188 -vn 0.945454 -0.282110 0.162881 -v 0.091603 0.061569 0.182306 -vn 0.736823 -0.672382 0.070670 -v 0.091603 0.064279 0.179875 -vn 0.736825 -0.617633 0.274988 -v 0.091603 0.064716 0.181507 -vn 0.736824 0.672380 -0.070670 -v 0.091603 0.075020 0.178746 -vn 0.736824 0.617634 -0.274989 -v 0.091603 0.074582 0.177114 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.076271 0.176841 -vn 0.736823 0.502431 -0.452388 -v 0.091603 0.073662 0.175697 -vn 0.736825 0.338041 -0.585505 -v 0.091603 0.072349 0.174634 -vn 0.945453 0.162879 0.282116 -v 0.091603 0.070595 0.187940 -vn 0.945456 0.282106 0.162877 -v 0.091603 0.070229 0.188306 -vn 0.736824 0.274989 0.617633 -v 0.091603 0.071846 0.184244 -vn 0.991446 -0.065259 0.113033 -v 0.091603 0.068296 0.190654 -vn 0.736824 0.070671 0.672381 -v 0.091603 0.070214 0.184681 -vn 0.736824 0.661311 0.140566 -v 0.091603 0.074931 0.180433 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.077635 0.177628 -vn 0.736824 0.585506 0.338042 -v 0.091603 0.074326 0.182010 -vn 0.736824 0.452389 0.502428 -v 0.091603 0.073262 0.183323 -vn 0.945453 -0.000000 0.325759 -v 0.091603 0.071095 0.187806 -vn 0.990581 -0.028467 0.133933 -v 0.091603 0.072496 0.192852 -vn 0.990582 -0.049069 0.127830 -v 0.091603 0.071894 0.192674 -vn 0.945453 0.000000 -0.325759 -v 0.091603 0.071095 0.189806 -vn 0.991005 -0.062196 0.118497 -v 0.091603 0.071327 0.192404 -vn 0.945453 0.162879 -0.282114 -v 0.091603 0.070595 0.189672 -vn 0.991446 -0.065259 0.113032 -v 0.091603 0.069660 0.191441 -vn 0.945450 0.282124 -0.162881 -v 0.091603 0.070229 0.189306 -vn 0.945453 0.325759 -0.000000 -v 0.091603 0.070095 0.188806 -vn 0.736823 -0.140567 0.661311 -v 0.091603 0.068526 0.184592 -vn 0.945453 -0.162879 0.282116 -v 0.091603 0.066221 0.169248 -vn 0.945453 0.000000 0.325759 -v 0.091603 0.065721 0.169114 -vn 0.945452 -0.325760 0.000002 -v 0.091603 0.066721 0.170114 -vn 0.945446 -0.282134 0.162886 -v 0.091603 0.066587 0.169614 -vn 0.945453 0.162879 -0.282114 -v 0.091603 0.065221 0.170980 -vn 0.945453 0.000000 -0.325759 -v 0.091603 0.065721 0.171114 -vn 0.945454 -0.162880 -0.282113 -v 0.091603 0.066221 0.170980 -vn 0.945446 -0.282132 -0.162890 -v 0.091603 0.066587 0.170614 -vn 0.945450 0.162882 0.282122 -v 0.091603 0.065221 0.169248 -vn 0.945451 0.282122 0.162879 -v 0.091603 0.064855 0.169614 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.064472 0.170028 -vn 0.945447 0.325776 0.000002 -v 0.091603 0.064721 0.170114 -vn 0.945450 0.282124 -0.162881 -v 0.091603 0.064855 0.170614 -vn 0.945453 -0.000000 0.325759 -v 0.091603 0.079577 0.177114 -vn 0.945453 0.162879 0.282116 -v 0.091603 0.079077 0.177248 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.078660 0.175853 -vn 0.945453 -0.162879 0.282115 -v 0.091603 0.080077 0.177248 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.080948 0.179541 -vn 0.945451 -0.282122 -0.162879 -v 0.091603 0.080443 0.178614 -vn 1.000000 0.000000 -0.000000 -v 0.091603 0.081973 0.177765 -vn 0.945447 -0.325777 -0.000003 -v 0.091603 0.080577 0.178114 -vn 0.945456 -0.282105 0.162878 -v 0.091603 0.080443 0.177614 -vn 0.923880 0.191341 -0.331413 -v 0.091603 0.080910 0.171956 -vn 0.923877 0.191346 -0.331418 -v 0.091603 0.079546 0.171168 -vn 0.945453 0.000000 -0.325759 -v 0.091603 0.079577 0.179114 -vn 0.945454 -0.162880 -0.282113 -v 0.091603 0.080077 0.178980 -vn 0.945452 0.282116 0.162885 -v 0.091603 0.078711 0.177614 -vn 0.945452 0.325760 -0.000002 -v 0.091603 0.078577 0.178114 -vn 0.945446 0.282134 -0.162886 -v 0.091603 0.078711 0.178614 -vn 0.945453 0.162879 -0.282116 -v 0.091603 0.079077 0.178980 -vn 0.717291 0.057810 -0.694371 -v 0.091603 0.061659 0.163150 -vn 0.923880 -0.331412 -0.191341 -v 0.091603 0.060409 0.165315 -vn 0.923881 -0.331411 -0.191340 -v 0.091603 0.059384 0.167091 -vn 0.717283 -0.572429 0.397279 -v 0.091603 0.058409 0.168779 -vn 0.717256 0.057880 -0.694402 -v 0.091603 0.069659 0.149294 -vn 0.923880 -0.331412 -0.191341 -v 0.091603 0.068284 0.151675 -vn 0.717284 -0.572426 0.397281 -v 0.091603 0.066409 0.154923 -vn 0.717256 0.057877 -0.694402 -v 0.091603 0.073659 0.142366 -vn 0.923881 -0.331412 -0.191339 -v 0.091603 0.073471 0.142690 -vn 0.923880 -0.331413 -0.191342 -v 0.091603 0.072784 0.143881 -vn 0.717286 -0.572443 0.397253 -v 0.091603 0.070409 0.147995 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.069701 0.159421 -vn 0.770263 -0.552286 0.318865 -v 0.091603 0.066415 0.159162 -vn 0.770260 -0.318865 0.552291 -v 0.091603 0.065958 0.158704 -vn 0.770264 0.000000 0.637725 -v 0.091603 0.065333 0.158537 -vn 0.770260 0.318865 0.552291 -v 0.091603 0.064708 0.158704 -vn 0.770263 0.552286 0.318865 -v 0.091603 0.064250 0.159162 -vn 0.770261 0.637728 0.000000 -v 0.091603 0.064083 0.159787 -vn 0.770258 0.000000 -0.637732 -v 0.091603 0.065333 0.161037 -vn 0.770265 0.318861 -0.552286 -v 0.091603 0.064708 0.160869 -vn 0.770261 0.552291 -0.318862 -v 0.091603 0.064250 0.160412 -vn 0.770265 -0.318861 -0.552287 -v 0.091603 0.065958 0.160869 -vn 0.770261 -0.552291 -0.318862 -v 0.091603 0.066415 0.160412 -vn 0.770261 -0.637728 -0.000000 -v 0.091603 0.066583 0.159787 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.071497 0.157860 -vn 0.945453 -0.162879 0.282114 -v 0.091603 0.073971 0.155825 -vn 0.945453 -0.000000 0.325759 -v 0.091603 0.073471 0.155691 -vn 0.945452 0.282116 -0.162883 -v 0.091603 0.072605 0.157191 -vn 0.945453 0.162878 -0.282116 -v 0.091603 0.072971 0.157557 -vn 0.945454 0.162880 0.282113 -v 0.091603 0.072971 0.155825 -vn 0.945446 0.282132 0.162890 -v 0.091603 0.072605 0.156191 -vn 0.945452 0.325761 -0.000001 -v 0.091603 0.072471 0.156691 -vn 0.987815 0.040282 0.150329 -v 0.091603 0.070412 0.158389 -vn 0.923881 0.331410 0.191340 -v 0.091603 0.069787 0.159471 -vn 0.923880 0.331413 0.191342 -v 0.091603 0.067537 0.163369 -vn 0.945453 0.000000 -0.325759 -v 0.091603 0.073471 0.157691 -vn 0.945453 -0.162879 -0.282116 -v 0.091603 0.073971 0.157557 -vn 0.945457 -0.282106 -0.162874 -v 0.091603 0.074337 0.157191 -vn 0.945450 -0.282124 0.162881 -v 0.091603 0.074337 0.156191 -vn 0.945447 -0.325776 -0.000001 -v 0.091603 0.074471 0.156691 -vn 1.000000 0.000002 0.000001 -v 0.091603 0.086535 0.162213 -vn 1.000000 0.000000 -0.000000 -v 0.091603 0.083296 0.164673 -vn 0.973781 0.020872 0.226527 -v 0.091603 0.079332 0.163539 -vn 0.707108 0.612371 0.353554 -v 0.091603 0.078707 0.164621 -vn 0.707108 0.612372 0.353552 -v 0.091603 0.076457 0.168519 -vn 0.945453 -0.162879 0.282114 -v 0.091603 0.087827 0.163825 -vn 0.945453 -0.000000 0.325759 -v 0.091603 0.087327 0.163691 -vn 0.945450 -0.282124 0.162881 -v 0.091603 0.088193 0.164191 -vn 0.707109 -0.353555 0.612368 -v 0.091603 0.086296 0.159477 -vn 0.945452 0.325762 0.000001 -v 0.091603 0.086327 0.164691 -vn 0.945450 0.282124 0.162882 -v 0.091603 0.086461 0.164191 -vn 0.945454 0.162880 0.282113 -v 0.091603 0.086827 0.163825 -vn 0.945455 0.282107 -0.162880 -v 0.091603 0.086461 0.165191 -vn 0.945453 0.162880 -0.282116 -v 0.091603 0.086827 0.165557 -vn 0.945453 0.000000 -0.325759 -v 0.091603 0.087327 0.165691 -vn 0.945453 -0.162879 -0.282116 -v 0.091603 0.087827 0.165557 -vn 0.945452 -0.282116 -0.162885 -v 0.091603 0.088193 0.165191 -vn 0.945452 -0.325760 0.000002 -v 0.091603 0.088327 0.164691 -vn 0.770264 0.000000 0.637725 -v 0.091603 0.094577 0.150883 -vn 0.770261 -0.318867 0.552288 -v 0.091603 0.095202 0.151051 -vn 0.923881 0.191340 -0.331412 -v 0.091603 0.096973 0.151784 -vn 0.770261 -0.552288 0.318867 -v 0.091603 0.095660 0.151508 -vn 0.770262 -0.637728 0.000005 -v 0.091603 0.095827 0.152133 -vn 0.770265 0.637724 -0.000002 -v 0.091603 0.093327 0.152133 -vn 0.770260 0.552291 0.318865 -v 0.091603 0.093495 0.151508 -vn 0.770262 0.318869 0.552286 -v 0.091603 0.093952 0.151051 -vn 0.770262 -0.318858 -0.552291 -v 0.091603 0.095202 0.153216 -vn 0.770264 -0.552286 -0.318863 -v 0.091603 0.095660 0.152758 -vn 0.770259 0.552290 -0.318868 -v 0.091603 0.093495 0.152758 -vn 0.770265 0.318861 -0.552286 -v 0.091603 0.093952 0.153216 -vn 0.770258 0.000000 -0.637732 -v 0.091603 0.094577 0.153383 -vn 0.990581 0.074575 0.114836 -v 0.091603 0.075506 0.192294 -vn 0.770261 0.552291 0.318862 -v 0.091603 0.087633 0.172662 -vn 0.770261 0.637728 0.000000 -v 0.091603 0.087466 0.173287 -vn 0.770258 -0.000000 0.637732 -v 0.091603 0.088716 0.172037 -vn 0.770265 0.318861 0.552287 -v 0.091603 0.088091 0.172204 -vn 0.770263 0.552286 -0.318865 -v 0.091603 0.087633 0.173912 -vn 0.770260 0.318865 -0.552291 -v 0.091603 0.088091 0.174369 -vn 0.770264 -0.000000 -0.637725 -v 0.091603 0.088716 0.174537 -vn 0.770260 -0.318865 -0.552291 -v 0.091603 0.089341 0.174369 -vn 0.770263 -0.552286 -0.318865 -v 0.091603 0.089798 0.173912 -vn 0.770261 -0.637729 -0.000000 -v 0.091603 0.089965 0.173287 -vn 0.770258 0.000000 -0.637732 -v 0.091603 0.096716 0.160680 -vn 0.717286 -0.057830 0.694375 -v 0.091603 0.096390 0.162995 -vn 0.770265 0.318861 -0.552286 -v 0.091603 0.096091 0.160513 -vn 0.770261 0.552291 -0.318862 -v 0.091603 0.095633 0.160055 -vn 0.770261 0.637728 0.000000 -v 0.091603 0.095466 0.159430 -vn 0.770265 -0.318861 -0.552287 -v 0.091603 0.097341 0.160513 -vn 0.770261 -0.552291 -0.318862 -v 0.091603 0.097798 0.160055 -vn 0.923880 0.331412 0.191341 -v 0.091603 0.098765 0.158881 -vn 0.770261 -0.637728 -0.000000 -v 0.091603 0.097966 0.159430 -vn 0.770263 -0.552286 0.318865 -v 0.091603 0.097798 0.158805 -vn 0.770260 -0.318865 0.552291 -v 0.091603 0.097341 0.158348 -vn 0.770264 0.000000 0.637725 -v 0.091603 0.096716 0.158180 -vn 1.000000 0.000000 0.000000 -v 0.091603 0.095409 0.156944 -vn 0.770260 0.318865 0.552291 -v 0.091603 0.096091 0.158348 -vn 0.770263 0.552286 0.318865 -v 0.091603 0.095633 0.158805 -vn 0.770255 0.637737 -0.000008 -v 0.091603 0.094450 0.156274 -vn -0.301511 -0.632593 -0.713384 -v 0.089603 0.058168 0.167197 -vn -0.770262 0.637728 -0.000002 -v 0.089603 0.060083 0.166715 -vn -0.770263 0.552286 0.318865 -v 0.089603 0.060250 0.166090 -vn -0.609994 -0.686243 -0.396205 -v 0.089603 0.063333 0.167869 -vn -0.770260 -0.552292 -0.318861 -v 0.089603 0.062415 0.167340 -vn -0.770265 -0.318861 -0.552285 -v 0.089603 0.061958 0.167797 -vn -0.301510 -0.934106 -0.191152 -v 0.089603 0.060168 0.163733 -vn -0.770260 0.318865 0.552291 -v 0.089603 0.060708 0.165632 -vn -0.770264 0.000000 0.637725 -v 0.089603 0.061333 0.165465 -vn -0.609994 -0.686243 0.396204 -v 0.089603 0.063333 0.165560 -vn -0.609995 0.000002 -0.792406 -v 0.089603 0.061333 0.169024 -vn -0.770258 0.000000 -0.637732 -v 0.089603 0.061333 0.167965 -vn -0.770265 0.318862 -0.552285 -v 0.089603 0.060708 0.167797 -vn -0.770260 0.552292 -0.318863 -v 0.089603 0.060250 0.167340 -vn -0.770260 -0.318866 0.552289 -v 0.089603 0.061958 0.165632 -vn -0.770263 -0.552287 0.318864 -v 0.089603 0.062415 0.166090 -vn -0.770261 -0.637729 0.000000 -v 0.089603 0.062583 0.166715 -vn -0.609995 -0.686244 0.396202 -v 0.089603 0.067333 0.158632 -vn -0.770263 -0.552286 0.318865 -v 0.089603 0.066415 0.159162 -vn -0.609994 -0.686244 -0.396203 -v 0.089603 0.067333 0.160941 -vn -0.770261 -0.637729 0.000000 -v 0.089603 0.066583 0.159787 -vn -0.609994 -0.000000 -0.792406 -v 0.089603 0.065333 0.162096 -vn -0.770265 0.318861 -0.552287 -v 0.089603 0.064708 0.160869 -vn -0.301511 -0.632595 -0.713383 -v 0.089603 0.062168 0.160269 -vn -0.770261 0.552291 -0.318862 -v 0.089603 0.064250 0.160412 -vn -0.770261 0.637728 -0.000000 -v 0.089603 0.064083 0.159787 -vn -0.770263 0.552286 0.318865 -v 0.089603 0.064250 0.159162 -vn -0.301509 -0.934106 -0.191152 -v 0.089603 0.064168 0.156804 -vn -0.770260 0.318865 0.552291 -v 0.089603 0.064708 0.158704 -vn -0.770264 -0.000000 0.637725 -v 0.089603 0.065333 0.158537 -vn -0.770260 -0.318866 0.552291 -v 0.089603 0.065958 0.158704 -vn -0.770261 -0.552291 -0.318862 -v 0.089603 0.066415 0.160412 -vn -0.770265 -0.318861 -0.552286 -v 0.089603 0.065958 0.160869 -vn -0.770258 -0.000000 -0.637732 -v 0.089603 0.065333 0.161037 -vn -0.609994 -0.000001 -0.792406 -v 0.089603 0.069333 0.155168 -vn -0.770260 0.318866 -0.552291 -v 0.089603 0.068708 0.153941 -vn -0.301511 -0.632595 -0.713383 -v 0.089603 0.066168 0.153340 -vn -0.770264 0.552286 -0.318863 -v 0.089603 0.068250 0.153483 -vn -0.609995 -0.686243 -0.396203 -v 0.089603 0.071333 0.154013 -vn -0.770260 -0.318865 -0.552291 -v 0.089603 0.069958 0.153941 -vn -0.770264 0.000000 -0.637725 -v 0.089603 0.069333 0.154108 -vn -0.770261 0.637729 0.000002 -v 0.089603 0.068083 0.152858 -vn -0.770263 0.552286 0.318865 -v 0.089603 0.068250 0.152233 -vn -0.301510 -0.934105 -0.191152 -v 0.089603 0.068168 0.149876 -vn -0.770260 -0.318866 0.552291 -v 0.089603 0.069958 0.151776 -vn -0.609994 -0.686244 0.396201 -v 0.089603 0.071333 0.151704 -vn -0.770264 -0.000000 0.637725 -v 0.089603 0.069333 0.151608 -vn -0.770260 0.318865 0.552291 -v 0.089603 0.068708 0.151776 -vn -0.770263 -0.552286 0.318865 -v 0.089603 0.070415 0.152233 -vn -0.770261 -0.637729 0.000002 -v 0.089603 0.070583 0.152858 -vn -0.770264 -0.552286 -0.318863 -v 0.089603 0.070415 0.153483 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.056686 0.180313 -vn -0.904536 0.110364 0.411866 -v 0.086603 0.095957 0.162745 -vn -0.717288 -0.057824 0.694374 -v 0.086603 0.096390 0.162995 -vn -0.741788 0.628649 -0.233563 -v 0.086603 0.097015 0.161912 -vn -0.904533 -0.110362 -0.411875 -v 0.086603 0.066092 0.156472 -vn -0.717283 0.057823 -0.694378 -v 0.086603 0.065659 0.156222 -vn -0.741787 -0.628649 0.233565 -v 0.086603 0.065034 0.157304 -vn -0.741787 -0.112054 -0.661209 -v 0.086603 0.059034 0.167697 -vn -0.717282 -0.572435 0.397271 -v 0.086603 0.058409 0.168779 -vn -0.846479 -0.252272 -0.468863 -v 0.086603 0.061266 0.167831 -vn -0.904536 -0.411869 0.110359 -v 0.086603 0.058842 0.169029 -vn -0.707105 -0.612372 -0.353557 -v 0.086603 0.058679 0.169311 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.061949 0.171198 -vn -0.846479 -0.532183 0.015958 -v 0.086603 0.062266 0.166099 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.065336 0.165331 -vn -0.741787 -0.628649 0.233566 -v 0.086603 0.061034 0.164233 -vn -0.904534 -0.110363 -0.411873 -v 0.086603 0.062092 0.163400 -vn -0.717283 0.057822 -0.694378 -v 0.086603 0.061659 0.163150 -vn -0.923879 -0.331415 -0.191340 -v 0.086603 0.061634 0.163193 -vn -0.846478 -0.252274 -0.468864 -v 0.086603 0.065266 0.160903 -vn -0.741788 -0.112054 -0.661206 -v 0.086603 0.063034 0.160769 -vn -0.717284 -0.572434 0.397270 -v 0.086603 0.062409 0.161851 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.069886 0.157450 -vn -0.846479 -0.532183 0.015958 -v 0.086603 0.066266 0.159170 -vn -0.904534 -0.411872 0.110362 -v 0.086603 0.062842 0.162101 -vn -0.846479 -0.252272 -0.468863 -v 0.086603 0.069266 0.153974 -vn -0.741788 -0.112050 -0.661208 -v 0.086603 0.067034 0.153840 -vn -0.717284 -0.572434 0.397271 -v 0.086603 0.066409 0.154923 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.073986 0.150349 -vn -0.707105 -0.612373 -0.353556 -v 0.086603 0.070717 0.148461 -vn -0.904535 -0.110359 -0.411870 -v 0.086603 0.070092 0.149544 -vn -0.846479 -0.532184 0.015957 -v 0.086603 0.070266 0.152242 -vn -0.707109 -0.612372 -0.353549 -v 0.086603 0.066617 0.155563 -vn -0.904533 -0.411873 0.110366 -v 0.086603 0.066842 0.155173 -vn -0.904533 -0.411876 0.110355 -v 0.086603 0.070842 0.148245 -vn -0.846478 -0.532184 0.015957 -v 0.086603 0.074266 0.145314 -vn -0.846479 -0.252272 -0.468864 -v 0.086603 0.073266 0.147046 -vn -0.976005 0.188575 -0.108875 -v 0.086603 0.076363 0.145982 -vn -0.904530 -0.110358 -0.411882 -v 0.086603 0.076141 0.142066 -vn -0.577350 -0.211328 -0.788674 -v 0.086603 0.074842 0.141316 -vn -0.904535 -0.110359 -0.411870 -v 0.086603 0.074092 0.142616 -vn -0.976004 0.217754 -0.000001 -v 0.086603 0.076242 0.145532 -vn -0.741787 -0.628649 0.233564 -v 0.086603 0.073034 0.143448 -vn -0.717275 0.057839 -0.694385 -v 0.086603 0.073659 0.142366 -vn -0.976004 0.000000 0.217755 -v 0.086603 0.077142 0.144632 -vn -0.976003 0.108877 0.188582 -v 0.086603 0.076692 0.144752 -vn -0.976002 0.188587 0.108879 -v 0.086603 0.076363 0.145082 -vn -0.577350 -0.211325 -0.788675 -v 0.086603 0.076891 0.140767 -vn -0.707111 -0.612365 -0.353559 -v 0.086603 0.076241 0.141893 -vn -0.904534 -0.110358 -0.411873 -v 0.086603 0.078406 0.141642 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.078211 0.143031 -vn -0.717284 -0.397267 -0.572436 -v 0.086603 0.078656 0.141209 -vn -0.923879 0.191342 -0.331415 -v 0.086603 0.079111 0.141472 -vn -0.717281 0.694380 0.057828 -v 0.086603 0.084286 0.144459 -vn -0.741787 -0.233563 -0.628649 -v 0.086603 0.083203 0.143834 -vn -0.904533 0.411873 -0.110364 -v 0.086603 0.084036 0.144892 -vn -0.846479 -0.015958 -0.532183 -v 0.086603 0.081337 0.145066 -vn -0.707110 0.353552 -0.612369 -v 0.086603 0.085400 0.145680 -vn -1.000000 -0.000002 0.000002 -v 0.086603 0.084750 0.146806 -vn -0.707107 0.353553 -0.612372 -v 0.086603 0.088149 0.147267 -vn -1.000000 -0.000001 -0.000000 -v 0.086603 0.087499 0.148393 -vn -0.707105 0.353555 -0.612373 -v 0.086603 0.090899 0.148855 -vn -1.000000 -0.000000 0.000000 -v 0.086603 0.090249 0.149981 -vn -0.904535 -0.110360 -0.411869 -v 0.086603 0.092263 0.149642 -vn -0.846479 0.468864 -0.252272 -v 0.086603 0.093461 0.152066 -vn -0.717283 -0.397271 -0.572434 -v 0.086603 0.092513 0.149209 -vn -0.741787 0.661208 -0.112052 -v 0.086603 0.093595 0.149834 -vn -0.846479 -0.015958 -0.532183 -v 0.086603 0.095193 0.153066 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.095467 0.152993 -vn -0.741787 -0.233565 -0.628649 -v 0.086603 0.097059 0.151834 -vn -0.904534 0.411873 -0.110359 -v 0.086603 0.097892 0.152892 -vn -0.717282 0.694379 0.057831 -v 0.086603 0.098142 0.152459 -vn -0.846479 0.532184 -0.015957 -v 0.086603 0.095782 0.160046 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.091242 0.160311 -vn -0.707104 0.612378 0.353549 -v 0.086603 0.095832 0.162961 -vn -0.976003 -0.108877 0.188582 -v 0.086603 0.095606 0.155152 -vn -0.976003 -0.188584 0.108878 -v 0.086603 0.095935 0.155482 -vn -0.904535 0.411871 -0.110362 -v 0.086603 0.099207 0.157116 -vn -0.976003 -0.217758 -0.000000 -v 0.086603 0.096056 0.155932 -vn -0.976003 -0.188585 -0.108878 -v 0.086603 0.095935 0.156382 -vn -0.976005 0.188575 -0.108875 -v 0.086603 0.094376 0.156382 -vn -0.976004 0.217754 -0.000001 -v 0.086603 0.094256 0.155932 -vn -0.976005 0.188574 0.108876 -v 0.086603 0.094376 0.155482 -vn -0.976004 0.108878 0.188579 -v 0.086603 0.094706 0.155152 -vn -0.976004 0.000000 0.217755 -v 0.086603 0.095156 0.155032 -vn -0.717283 0.572435 -0.397271 -v 0.086603 0.099640 0.157366 -vn -0.741787 0.112052 0.661209 -v 0.086603 0.099015 0.158448 -vn -0.846479 0.252272 0.468863 -v 0.086603 0.096782 0.158314 -vn -0.976003 -0.108877 -0.188583 -v 0.086603 0.095606 0.156711 -vn -0.976004 0.000001 -0.217754 -v 0.086603 0.095156 0.156832 -vn -0.976004 0.108877 -0.188580 -v 0.086603 0.094706 0.156711 -vn -0.577350 0.788675 -0.211328 -v 0.086603 0.099957 0.155816 -vn -0.904534 0.411872 -0.110364 -v 0.086603 0.098657 0.155066 -vn -0.707108 0.612373 0.353551 -v 0.086603 0.098757 0.154893 -vn -0.577351 0.788675 -0.211323 -v 0.086603 0.099407 0.153767 -vn -0.707107 0.612372 0.353553 -v 0.086603 0.091732 0.170063 -vn -0.904534 0.110361 0.411872 -v 0.086603 0.091957 0.169673 -vn -0.741787 0.112054 0.661209 -v 0.086603 0.095015 0.165376 -vn -0.717283 0.572435 -0.397271 -v 0.086603 0.095640 0.164294 -vn -0.846479 0.252272 0.468864 -v 0.086603 0.092782 0.165242 -vn -0.904535 0.411870 -0.110361 -v 0.086603 0.095207 0.164044 -vn -0.846479 0.532184 -0.015957 -v 0.086603 0.091782 0.166974 -vn -0.741788 0.628649 -0.233563 -v 0.086603 0.093015 0.168840 -vn -0.717288 -0.057824 0.694374 -v 0.086603 0.092390 0.169923 -vn -0.707104 -0.353554 0.612375 -v 0.086603 0.085089 0.168017 -vn -0.707112 -0.353558 0.612364 -v 0.086603 0.086367 0.168755 -vn -1.000000 -0.000001 0.000000 -v 0.086603 0.087142 0.167413 -vn -0.904531 -0.411880 0.110357 -v 0.086603 0.086626 0.168905 -vn -0.904537 0.411867 -0.110356 -v 0.086603 0.087207 0.177900 -vn -0.904534 0.110363 0.411873 -v 0.086603 0.087957 0.176601 -vn -1.000000 -0.000000 -0.000000 -v 0.086603 0.082592 0.175293 -vn -0.923882 0.331403 0.191348 -v 0.086603 0.087615 0.178193 -vn -0.717286 0.572440 -0.397257 -v 0.086603 0.087640 0.178150 -vn -0.741787 0.112054 0.661209 -v 0.086603 0.091015 0.172304 -vn -0.717283 0.572435 -0.397271 -v 0.086603 0.091640 0.171222 -vn -0.846478 0.252272 0.468864 -v 0.086603 0.088782 0.172170 -vn -0.904534 0.411871 -0.110362 -v 0.086603 0.091207 0.170972 -vn -0.717283 -0.057825 0.694378 -v 0.086603 0.088390 0.176851 -vn -0.741788 0.628649 -0.233563 -v 0.086603 0.089015 0.175769 -vn -0.846478 0.532184 -0.015957 -v 0.086603 0.087782 0.173903 -vn -0.707107 0.612373 0.353553 -v 0.086603 0.083794 0.183811 -vn -0.904533 0.110362 0.411873 -v 0.086603 0.083957 0.183529 -vn -0.741789 0.112052 0.661206 -v 0.086603 0.087015 0.179233 -vn -0.846477 0.252273 0.468865 -v 0.086603 0.084782 0.179099 -vn -0.846479 0.532183 -0.015958 -v 0.086603 0.083782 0.180831 -vn -0.741787 0.628648 -0.233567 -v 0.086603 0.085015 0.182697 -vn -0.717284 -0.057825 0.694378 -v 0.086603 0.084390 0.183779 -vn -0.707107 0.612372 0.353553 -v 0.086603 0.078945 0.189210 -vn -0.904534 0.110360 0.411872 -v 0.086603 0.081907 0.184078 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.079204 0.181161 -vn -0.976003 -0.217756 -0.000001 -v 0.086603 0.074060 0.191730 -vn -0.976005 -0.188574 -0.108876 -v 0.086603 0.073939 0.192180 -vn -0.976004 -0.108878 -0.188579 -v 0.086603 0.073610 0.192509 -vn -0.976004 -0.000000 -0.217755 -v 0.086603 0.073160 0.192630 -vn -0.976003 0.108877 -0.188582 -v 0.086603 0.072710 0.192509 -vn -0.976005 0.188573 -0.108874 -v 0.086603 0.072380 0.192180 -vn -0.707109 -0.353559 0.612366 -v 0.086603 0.070589 0.193132 -vn -0.976003 0.217757 -0.000001 -v 0.086603 0.072260 0.191730 -vn -0.976002 0.188588 0.108877 -v 0.086603 0.072380 0.191280 -vn -0.976004 0.108874 0.188580 -v 0.086603 0.072710 0.190950 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.072664 0.189538 -vn -0.976002 0.000000 0.217760 -v 0.086603 0.073160 0.190830 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.073942 0.190276 -vn -0.976005 -0.108875 0.188577 -v 0.086603 0.073610 0.190950 -vn -0.976000 -0.188597 0.108886 -v 0.086603 0.073939 0.191280 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.058007 0.181076 -vn -0.976005 -0.108874 0.188578 -v 0.086603 0.057588 0.181700 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.059284 0.181813 -vn -0.976002 -0.188588 0.108878 -v 0.086603 0.057918 0.182030 -vn -0.976003 -0.217756 -0.000000 -v 0.086603 0.058038 0.182480 -vn -0.976004 -0.188578 -0.108878 -v 0.086603 0.057918 0.182930 -vn -0.976004 -0.108877 -0.188581 -v 0.086603 0.057588 0.183259 -vn -0.707110 -0.353545 0.612374 -v 0.086603 0.057209 0.185407 -vn -0.976004 -0.000000 -0.217755 -v 0.086603 0.057138 0.183380 -vn -0.976003 0.108878 -0.188581 -v 0.086603 0.056688 0.183259 -vn -0.976004 0.188578 -0.108878 -v 0.086603 0.056359 0.182930 -vn -0.976003 0.217756 0.000000 -v 0.086603 0.056238 0.182480 -vn -0.976001 0.188593 0.108880 -v 0.086603 0.056359 0.182030 -vn -0.976004 0.108874 0.188580 -v 0.086603 0.056688 0.181700 -vn -0.976002 0.000000 0.217760 -v 0.086603 0.057138 0.181580 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.058399 0.177347 -vn -0.577350 -0.788675 0.211324 -v 0.086603 0.058092 0.170328 -vn -0.904534 -0.411873 0.110360 -v 0.086603 0.059391 0.171078 -vn -0.707107 -0.612373 -0.353553 -v 0.086603 0.056428 0.176210 -vn -0.904534 0.411872 -0.110361 -v 0.086603 0.076582 0.168302 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.074624 0.170693 -vn -0.707107 0.353553 -0.612372 -v 0.086603 0.078899 0.169640 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.077374 0.172281 -vn -0.707107 0.353554 -0.612372 -v 0.086603 0.082211 0.171552 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.080686 0.174193 -vn -0.707108 0.353552 -0.612372 -v 0.086603 0.082839 0.171915 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.081314 0.174556 -vn -0.707102 0.353561 -0.612373 -v 0.086603 0.084117 0.172652 -vn -1.000000 -0.000000 0.000000 -v 0.086603 0.079174 0.162813 -vn -0.904534 0.110361 0.411872 -v 0.086603 0.078832 0.164405 -vn -1.000000 -0.000001 -0.000000 -v 0.086603 0.081924 0.164400 -vn -0.707107 -0.353554 0.612372 -v 0.086603 0.081149 0.165742 -vn -1.000000 -0.000002 0.000002 -v 0.086603 0.085236 0.166313 -vn -0.707105 -0.353555 0.612374 -v 0.086603 0.084461 0.167655 -vn -1.000000 -0.000001 0.000002 -v 0.086603 0.085864 0.166675 -vn -0.707109 -0.353548 0.612373 -v 0.086603 0.070432 0.159555 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.071207 0.158213 -vn -0.904532 0.110365 0.411876 -v 0.086603 0.070172 0.159405 -vn -0.904531 0.411880 -0.110357 -v 0.086603 0.067922 0.163302 -vn -0.707110 0.353560 -0.612365 -v 0.086603 0.068182 0.163452 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.076425 0.161225 -vn -0.707107 -0.353552 0.612373 -v 0.086603 0.075650 0.162567 -vn -0.904534 -0.411872 0.110361 -v 0.086603 0.077966 0.163905 -vn -0.904534 -0.110361 -0.411872 -v 0.086603 0.075716 0.167802 -vn -0.707108 0.353554 -0.612371 -v 0.086603 0.069459 0.164190 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.067934 0.166831 -vn -0.707108 0.353553 -0.612372 -v 0.086603 0.070087 0.164552 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.068562 0.167193 -vn -0.707106 0.353553 -0.612374 -v 0.086603 0.073400 0.166465 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.071875 0.169106 -vn -0.707106 -0.353553 0.612374 -v 0.086603 0.072337 0.160655 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.073112 0.159313 -vn -0.707107 -0.353554 0.612372 -v 0.086603 0.071709 0.160292 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.072484 0.158950 -vn -0.976003 -0.188584 0.108878 -v 0.086603 0.077922 0.145082 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.079532 0.143793 -vn -0.976003 -0.108877 0.188582 -v 0.086603 0.077592 0.144752 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.075307 0.151111 -vn -0.976004 0.000001 -0.217754 -v 0.086603 0.077142 0.146432 -vn -0.741788 -0.112050 -0.661208 -v 0.086603 0.071034 0.146912 -vn -0.717285 -0.572438 0.397262 -v 0.086603 0.070409 0.147995 -vn -0.976004 0.108877 -0.188580 -v 0.086603 0.076692 0.146311 -vn -0.976003 -0.217758 -0.000000 -v 0.086603 0.078042 0.145532 -vn -0.976005 -0.188572 -0.108875 -v 0.086603 0.077922 0.145982 -vn -0.976004 -0.108877 -0.188581 -v 0.086603 0.077592 0.146311 -vn -0.770263 0.552286 0.318865 -v 0.086603 0.068567 0.178685 -vn -0.770260 0.318866 0.552291 -v 0.086603 0.069024 0.178228 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.068487 0.174973 -vn -0.770264 0.000000 0.637725 -v 0.086603 0.069649 0.178060 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.071237 0.176561 -vn -0.770260 -0.318865 0.552291 -v 0.086603 0.070274 0.178228 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.073986 0.178148 -vn -0.770263 -0.552286 0.318865 -v 0.086603 0.070732 0.178685 -vn -0.770261 -0.637728 -0.000000 -v 0.086603 0.070899 0.179310 -vn -0.770261 -0.552291 -0.318862 -v 0.086603 0.070732 0.179935 -vn -0.770265 -0.318861 -0.552286 -v 0.086603 0.070274 0.180393 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.070436 0.184297 -vn -0.770258 -0.000000 -0.637732 -v 0.086603 0.069649 0.180560 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.067687 0.182710 -vn -0.770265 0.318861 -0.552286 -v 0.086603 0.069024 0.180393 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.064937 0.181122 -vn -0.770261 0.552291 -0.318862 -v 0.086603 0.068567 0.179935 -vn -0.770261 0.637728 0.000000 -v 0.086603 0.068399 0.179310 -vn -0.770258 0.552295 0.318862 -v 0.086603 0.059924 0.182356 -vn -0.770268 0.318860 0.552283 -v 0.086603 0.060253 0.182026 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.061624 0.179210 -vn -0.770256 -0.000000 0.637735 -v 0.086603 0.060703 0.181906 -vn -0.770267 -0.318859 0.552284 -v 0.086603 0.061153 0.182026 -vn -0.770260 -0.552293 0.318860 -v 0.086603 0.061482 0.182356 -vn -0.770263 -0.552287 -0.318865 -v 0.086603 0.061482 0.183256 -vn -0.770260 -0.318865 -0.552290 -v 0.086603 0.061153 0.183585 -vn -0.707106 -0.353553 0.612373 -v 0.086603 0.061150 0.187682 -vn -0.770263 0.000000 -0.637726 -v 0.086603 0.060703 0.183706 -vn -0.707108 -0.353554 0.612371 -v 0.086603 0.057837 0.185770 -vn -0.770260 0.318865 -0.552290 -v 0.086603 0.060253 0.183585 -vn -0.770263 0.552287 -0.318864 -v 0.086603 0.059924 0.183256 -vn -0.770261 0.552288 -0.318866 -v 0.086603 0.064942 0.170564 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.063269 0.171961 -vn -0.770261 0.318866 -0.552288 -v 0.086603 0.065271 0.170894 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.064547 0.172698 -vn -0.770263 0.000000 -0.637726 -v 0.086603 0.065721 0.171014 -vn -0.770263 -0.000000 0.637726 -v 0.086603 0.065721 0.169214 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.066657 0.166093 -vn -0.770263 0.637726 0.000000 -v 0.086603 0.064821 0.170114 -vn -0.770261 0.552288 0.318866 -v 0.086603 0.064942 0.169664 -vn -0.770261 0.318866 0.552288 -v 0.086603 0.065271 0.169335 -vn -0.770260 -0.318864 0.552292 -v 0.086603 0.066171 0.169335 -vn -0.770264 -0.552285 0.318863 -v 0.086603 0.066500 0.169664 -vn -0.770259 -0.637731 0.000000 -v 0.086603 0.066621 0.170114 -vn -0.770260 -0.318864 -0.552292 -v 0.086603 0.066171 0.170894 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.065174 0.173061 -vn -0.770264 -0.552286 -0.318863 -v 0.086603 0.066500 0.170564 -vn -0.770264 0.552285 -0.318863 -v 0.086603 0.072692 0.157141 -vn -0.770259 0.637731 -0.000000 -v 0.086603 0.072571 0.156691 -vn -0.770264 0.552285 0.318863 -v 0.086603 0.072692 0.156241 -vn -0.770260 0.318864 0.552292 -v 0.086603 0.073021 0.155911 -vn -0.770263 -0.000000 0.637726 -v 0.086603 0.073471 0.155791 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.076584 0.151849 -vn -0.770260 0.318864 -0.552292 -v 0.086603 0.073021 0.157470 -vn -0.770261 -0.318866 0.552288 -v 0.086603 0.073921 0.155911 -vn -0.770261 -0.552288 0.318866 -v 0.086603 0.074250 0.156241 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.077212 0.152211 -vn -0.770263 -0.637726 -0.000000 -v 0.086603 0.074371 0.156691 -vn -0.770261 -0.552288 -0.318866 -v 0.086603 0.074250 0.157141 -vn -0.770261 -0.318866 -0.552288 -v 0.086603 0.073921 0.157470 -vn -0.770263 0.000000 -0.637726 -v 0.086603 0.073471 0.157591 -vn -0.770261 0.552288 0.318866 -v 0.086603 0.070316 0.188356 -vn -0.770261 0.318866 0.552288 -v 0.086603 0.070645 0.188026 -vn -0.770263 -0.000000 0.637726 -v 0.086603 0.071095 0.187906 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.073749 0.186210 -vn -0.770260 -0.318864 0.552292 -v 0.086603 0.071545 0.188026 -vn -0.770264 -0.552285 0.318863 -v 0.086603 0.071875 0.188356 -vn -0.770264 -0.552285 -0.318863 -v 0.086603 0.071875 0.189256 -vn -0.770260 -0.318864 -0.552292 -v 0.086603 0.071545 0.189585 -vn -0.707107 -0.353554 0.612372 -v 0.086603 0.069961 0.192770 -vn -0.770263 0.000000 -0.637726 -v 0.086603 0.071095 0.189706 -vn -0.770261 0.318866 -0.552288 -v 0.086603 0.070645 0.189585 -vn -0.707108 -0.353552 0.612372 -v 0.086603 0.066649 0.190857 -vn -0.770261 0.552288 -0.318866 -v 0.086603 0.070316 0.189256 -vn -0.770261 -0.552288 0.318866 -v 0.086603 0.088107 0.164241 -vn -0.770261 -0.637728 0.000005 -v 0.086603 0.088227 0.164691 -vn -0.770264 -0.552285 -0.318863 -v 0.086603 0.088107 0.165141 -vn -0.770260 -0.318864 -0.552292 -v 0.086603 0.087777 0.165470 -vn -0.770263 0.000000 -0.637726 -v 0.086603 0.087327 0.165591 -vn -0.770261 -0.318866 0.552288 -v 0.086603 0.087777 0.163911 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.089964 0.159574 -vn -0.770263 -0.000000 0.637726 -v 0.086603 0.087327 0.163791 -vn -0.770261 0.318866 -0.552288 -v 0.086603 0.086877 0.165470 -vn -0.770261 0.552288 -0.318866 -v 0.086603 0.086548 0.165141 -vn -0.770263 0.637726 0.000000 -v 0.086603 0.086427 0.164691 -vn -0.770261 0.318866 0.552288 -v 0.086603 0.086877 0.163911 -vn -1.000000 -0.000000 0.000000 -v 0.086603 0.089336 0.159211 -vn -0.770261 0.552288 0.318866 -v 0.086603 0.086548 0.164241 -vn -0.770261 -0.318866 0.552288 -v 0.086603 0.080027 0.177335 -vn -0.770261 -0.552288 0.318866 -v 0.086603 0.080357 0.177664 -vn -0.770263 -0.637726 -0.000000 -v 0.086603 0.080477 0.178114 -vn -0.770263 -0.000000 0.637726 -v 0.086603 0.079577 0.177214 -vn -0.904537 -0.110354 -0.411868 -v 0.086603 0.084376 0.172802 -vn -0.770261 -0.552288 -0.318866 -v 0.086603 0.080357 0.178564 -vn -0.770261 -0.318866 -0.552288 -v 0.086603 0.080027 0.178894 -vn -0.770263 0.000000 -0.637726 -v 0.086603 0.079577 0.179014 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.077927 0.180423 -vn -0.577350 0.211324 0.788675 -v 0.086603 0.083207 0.184828 -vn -0.770260 0.318864 0.552292 -v 0.086603 0.079127 0.177335 -vn -0.770264 0.552285 0.318863 -v 0.086603 0.078798 0.177664 -vn -0.770260 0.318864 -0.552292 -v 0.086603 0.079127 0.178894 -vn -0.770264 0.552285 -0.318863 -v 0.086603 0.078798 0.178564 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.077299 0.180061 -vn -0.770259 0.637731 -0.000000 -v 0.086603 0.078677 0.178114 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.072036 0.189176 -vn -0.770259 -0.637731 0.000000 -v 0.086603 0.071995 0.188806 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.075654 0.187310 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.074377 0.186572 -vn -0.770263 0.637726 0.000000 -v 0.086603 0.070195 0.188806 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.068724 0.187263 -vn -0.707107 -0.353553 0.612372 -v 0.086603 0.063899 0.189270 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.065974 0.185676 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.063225 0.184088 -vn -0.770261 -0.637728 0.000000 -v 0.086603 0.061603 0.182806 -vn -1.000000 -0.000001 -0.000000 -v 0.086603 0.086024 0.157299 -vn -1.000000 -0.000001 -0.000000 -v 0.086603 0.083274 0.155711 -vn -1.000000 -0.000000 0.000000 -v 0.086603 0.080525 0.154124 -vn -0.707107 0.353554 -0.612372 -v 0.086603 0.094089 0.152429 -vn -0.741787 0.661208 -0.112052 -v 0.086603 0.079739 0.141834 -vn -0.846479 0.468864 -0.252272 -v 0.086603 0.079605 0.144066 -vn -0.707107 0.353554 -0.612372 -v 0.086603 0.080709 0.144704 -vn -0.770262 0.637727 0.000002 -v 0.086603 0.059803 0.182806 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.059912 0.182176 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.060997 0.178847 -vn -1.000000 0.000000 0.000000 -v 0.086603 0.059719 0.178110 -vn -0.741787 -0.628649 0.233564 -v 0.086603 0.069034 0.150376 -vn -0.717275 0.057839 -0.694385 -v 0.086603 0.069659 0.149294 -vn 0.075088 -0.593855 0.801061 -v 0.088103 0.061034 0.164233 -vn 0.609994 -0.686243 0.396204 -v 0.088103 0.063333 0.165560 -vn 0.846479 -0.532183 0.015958 -v 0.088103 0.062266 0.166099 -vn 0.609994 -0.686243 -0.396205 -v 0.088103 0.063333 0.167869 -vn 0.846479 -0.252272 -0.468863 -v 0.088103 0.061266 0.167831 -vn 0.609995 0.000002 -0.792406 -v 0.088103 0.061333 0.169024 -vn 0.075086 0.396810 -0.914825 -v 0.088103 0.059034 0.167697 -vn 0.075086 -0.593856 0.801060 -v 0.088103 0.065034 0.157304 -vn 0.609994 -0.686244 0.396202 -v 0.088103 0.067333 0.158632 -vn 0.846479 -0.532183 0.015958 -v 0.088103 0.066266 0.159170 -vn 0.609994 -0.686244 -0.396203 -v 0.088103 0.067333 0.160941 -vn 0.846478 -0.252274 -0.468864 -v 0.088103 0.065266 0.160903 -vn 0.609994 -0.000001 -0.792406 -v 0.088103 0.065333 0.162096 -vn 0.075085 0.396815 -0.914823 -v 0.088103 0.063034 0.160769 -vn 0.075087 -0.593857 0.801059 -v 0.088103 0.069034 0.150376 -vn 0.609994 -0.686245 0.396201 -v 0.088103 0.071333 0.151704 -vn 0.846478 -0.532184 0.015957 -v 0.088103 0.070266 0.152242 -vn 0.609995 -0.686243 -0.396203 -v 0.088103 0.071333 0.154013 -vn 0.846478 -0.252272 -0.468864 -v 0.088103 0.069266 0.153974 -vn 0.609994 -0.000001 -0.792406 -v 0.088103 0.069333 0.155168 -vn 0.075084 0.396815 -0.914822 -v 0.088103 0.067034 0.153840 -vn -0.297108 -0.936318 0.187177 -v 0.087603 0.060168 0.163733 -vn -0.297107 -0.306056 -0.904465 -v 0.087603 0.060793 0.162650 -vn 0.297109 -0.306057 -0.904464 -v 0.090603 0.060793 0.162650 -vn 0.297110 -0.936317 0.187179 -v 0.090603 0.057543 0.168279 -vn -0.297108 -0.306057 -0.904465 -v 0.087603 0.058168 0.167197 -vn -0.297108 -0.936318 0.187178 -v 0.087603 0.057543 0.168279 -vn -0.297109 -0.936318 0.187177 -v 0.087603 0.064168 0.156804 -vn -0.297108 -0.306057 -0.904465 -v 0.087603 0.064793 0.155722 -vn 0.297111 -0.306055 -0.904464 -v 0.090603 0.064793 0.155722 -vn 0.297110 -0.936316 0.187185 -v 0.090603 0.061543 0.161351 -vn -0.297108 -0.306052 -0.904466 -v 0.087603 0.062168 0.160269 -vn -0.297108 -0.936316 0.187186 -v 0.087603 0.061543 0.161351 -vn -0.297109 -0.936318 0.187177 -v 0.087603 0.068168 0.149876 -vn -0.297108 -0.306053 -0.904466 -v 0.087603 0.068793 0.148794 -vn 0.297110 -0.306052 -0.904465 -v 0.090603 0.068793 0.148794 -vn 0.297110 -0.936316 0.187185 -v 0.090603 0.065543 0.154423 -vn -0.297109 -0.306052 -0.904466 -v 0.087603 0.066168 0.153340 -vn -0.297108 -0.936316 0.187186 -v 0.087603 0.065543 0.154423 -vn -0.609994 -0.000001 -0.792406 -v 0.089603 0.073333 0.148240 -vn -0.770260 0.318866 -0.552291 -v 0.089603 0.072708 0.147013 -vn -0.301511 -0.632595 -0.713383 -v 0.089603 0.070168 0.146412 -vn -0.770263 0.552286 -0.318865 -v 0.089603 0.072250 0.146555 -vn -0.609994 -0.686243 0.396203 -v 0.089603 0.075333 0.144775 -vn -0.301516 -0.934104 -0.191150 -v 0.089603 0.072168 0.142948 -vn -0.770258 0.000000 0.637732 -v 0.089603 0.073333 0.144680 -vn -0.770261 -0.637728 0.000000 -v 0.089603 0.074583 0.145930 -vn -0.609995 -0.686244 -0.396202 -v 0.089603 0.075333 0.147085 -vn -0.770261 -0.552291 0.318862 -v 0.089603 0.074415 0.145305 -vn -0.770265 -0.318861 0.552286 -v 0.089603 0.073958 0.144848 -vn -0.770263 -0.552286 -0.318865 -v 0.089603 0.074415 0.146555 -vn -0.770260 -0.318865 -0.552291 -v 0.089603 0.073958 0.147013 -vn -0.770264 0.000000 -0.637725 -v 0.089603 0.073333 0.147180 -vn -0.770261 0.637729 -0.000002 -v 0.089603 0.072083 0.145930 -vn -0.770264 0.552286 0.318863 -v 0.089603 0.072250 0.145305 -vn -0.770262 0.318858 0.552291 -v 0.089603 0.072708 0.144848 -vn -0.301506 0.191154 -0.934106 -v 0.089603 0.083703 0.142968 -vn -0.301510 0.713383 -0.632595 -v 0.089603 0.080239 0.140968 -vn -0.770265 -0.318861 0.552287 -v 0.089603 0.081346 0.143051 -vn -0.770258 0.000000 0.637732 -v 0.089603 0.080721 0.142883 -vn -0.770260 0.552291 -0.318864 -v 0.089603 0.079638 0.144758 -vn -0.609994 0.792406 -0.000001 -v 0.089603 0.078412 0.144133 -vn -0.770262 0.318869 -0.552286 -v 0.089603 0.080096 0.145216 -vn -0.609994 0.396202 -0.686244 -v 0.089603 0.079566 0.146133 -vn -0.770264 0.000000 -0.637725 -v 0.089603 0.080721 0.145383 -vn -0.609994 -0.396204 -0.686243 -v 0.089603 0.081876 0.146133 -vn -0.770260 -0.318865 -0.552291 -v 0.089603 0.081346 0.145216 -vn -0.770259 -0.552290 0.318868 -v 0.089603 0.081803 0.143508 -vn -0.770264 -0.637725 0.000004 -v 0.089603 0.081971 0.144133 -vn -0.770262 -0.552286 -0.318867 -v 0.089603 0.081803 0.144758 -vn -0.770262 0.637728 -0.000002 -v 0.089603 0.079471 0.144133 -vn -0.770261 0.552291 0.318862 -v 0.089603 0.079638 0.143508 -vn -0.770265 0.318861 0.552286 -v 0.089603 0.080096 0.143051 -vn 0.075083 -0.593853 0.801062 -v 0.088103 0.073034 0.143448 -vn 0.609994 -0.686244 0.396203 -v 0.088103 0.075333 0.144775 -vn 0.846478 -0.532184 0.015957 -v 0.088103 0.074266 0.145314 -vn 0.609994 -0.686244 -0.396202 -v 0.088103 0.075333 0.147085 -vn 0.846478 -0.252272 -0.468864 -v 0.088103 0.073266 0.147046 -vn 0.609994 -0.000001 -0.792406 -v 0.088103 0.073333 0.148240 -vn 0.075084 0.396815 -0.914822 -v 0.088103 0.071034 0.146912 -vn -0.297108 -0.936316 0.187186 -v 0.087603 0.072168 0.142948 -vn -0.297108 -0.306055 -0.904465 -v 0.087603 0.072793 0.141866 -vn 0.297109 -0.306053 -0.904465 -v 0.090603 0.072793 0.141866 -vn 0.297111 -0.936316 0.187182 -v 0.090603 0.069543 0.147495 -vn -0.297109 -0.306052 -0.904466 -v 0.087603 0.070168 0.146412 -vn -0.297109 -0.936317 0.187184 -v 0.087603 0.069543 0.147495 -vn 0.846479 -0.015958 -0.532183 -v 0.088103 0.081337 0.145066 -vn 0.075083 -0.801063 -0.593852 -v 0.088103 0.083203 0.143834 -vn 0.609994 -0.396203 -0.686243 -v 0.088103 0.081876 0.146133 -vn 0.609994 0.792406 -0.000001 -v 0.088103 0.078412 0.144133 -vn 0.075084 0.914824 0.396813 -v 0.088103 0.079739 0.141834 -vn 0.846479 0.468863 -0.252272 -v 0.088103 0.079605 0.144066 -vn 0.609994 0.396202 -0.686244 -v 0.088103 0.079566 0.146133 -vn -0.297108 -0.187180 -0.936317 -v 0.087603 0.083703 0.142968 -vn -0.297106 0.904468 -0.306049 -v 0.087603 0.084786 0.143593 -vn 0.297109 0.904466 -0.306052 -v 0.090603 0.084786 0.143593 -vn 0.297110 -0.187183 -0.936316 -v 0.090603 0.079156 0.140343 -vn -0.297108 0.904465 -0.306056 -v 0.087603 0.080239 0.140968 -vn -0.297108 -0.187185 -0.936316 -v 0.087603 0.079156 0.140343 -vn 0.088121 0.210825 0.973544 -v 0.090603 0.081907 0.184078 -vn 0.130018 0.838615 0.528980 -v 0.090603 0.077657 0.191440 -vn 0.130017 -0.461770 0.877419 -v 0.090603 0.070827 0.193270 -vn 0.130020 -0.528982 0.838613 -v 0.090603 0.056971 0.185270 -vn 0.088125 -0.948528 0.304185 -v 0.090603 0.059391 0.171078 -vn 0.130011 -0.877419 -0.461772 -v 0.090603 0.055141 0.178440 -vn 0.297110 -0.936317 0.187180 -v 0.090103 0.058092 0.170328 -vn 0.318858 -0.863426 0.390928 -v 0.091103 0.059507 0.171145 -vn 0.552290 -0.661270 0.507639 -v 0.091469 0.059824 0.171328 -vn 0.227458 -0.877657 0.421879 -v 0.090103 0.058842 0.169029 -vn 0.227458 -0.073472 -0.971012 -v 0.090103 0.062092 0.163400 -vn 0.227459 -0.877655 0.421882 -v 0.090103 0.062842 0.162101 -vn 0.227462 -0.073473 -0.971011 -v 0.090103 0.066092 0.156472 -vn 0.227459 -0.877654 0.421883 -v 0.090103 0.066842 0.155173 -vn 0.227458 -0.073469 -0.971012 -v 0.090103 0.070092 0.149544 -vn 0.227460 -0.877656 0.421878 -v 0.090103 0.070842 0.148245 -vn 0.227458 -0.073469 -0.971012 -v 0.090103 0.074092 0.142616 -vn 0.297108 -0.306058 -0.904464 -v 0.090103 0.074842 0.141316 -vn 0.297109 -0.187181 -0.936317 -v 0.090103 0.076891 0.140767 -vn 0.227460 -0.421878 -0.877656 -v 0.090103 0.078406 0.141642 -vn 0.227458 0.971013 -0.073467 -v 0.090103 0.084036 0.144892 -vn 0.227456 -0.421880 -0.877657 -v 0.090103 0.092263 0.149642 -vn 0.297108 -0.187182 -0.936317 -v 0.090603 0.093013 0.148343 -vn -0.297108 -0.187182 -0.936317 -v 0.087603 0.093013 0.148343 -vn -0.297108 -0.187181 -0.936317 -v 0.087603 0.097559 0.150968 -vn -0.297108 0.904466 -0.306053 -v 0.087603 0.098642 0.151593 -vn -0.301510 0.191149 -0.934106 -v 0.089603 0.097559 0.150968 -vn 0.297111 0.904465 -0.306054 -v 0.090603 0.098642 0.151593 -vn -0.301513 0.713383 -0.632594 -v 0.089603 0.094095 0.148968 -vn -0.297108 0.904465 -0.306054 -v 0.087603 0.094095 0.148968 -vn 0.227457 0.971013 -0.073466 -v 0.090103 0.097892 0.152892 -vn 0.297109 0.904466 -0.306053 -v 0.090103 0.099407 0.153767 -vn 0.297109 0.936316 -0.187185 -v 0.090103 0.099957 0.155816 -vn 0.227458 0.877656 -0.421879 -v 0.090103 0.099207 0.157116 -vn 0.297109 0.936317 -0.187179 -v 0.090603 0.100506 0.157866 -vn -0.297108 0.936318 -0.187178 -v 0.087603 0.100506 0.157866 -vn -0.297108 0.936316 -0.187186 -v 0.087603 0.097881 0.162412 -vn -0.297109 0.306054 0.904465 -v 0.087603 0.097256 0.163495 -vn -0.301514 0.934105 0.191149 -v 0.089603 0.097881 0.162412 -vn 0.297111 0.306053 0.904465 -v 0.090603 0.097256 0.163495 -vn -0.301511 0.632593 0.713384 -v 0.089603 0.099881 0.158948 -vn -0.297109 0.306058 0.904464 -v 0.087603 0.099881 0.158948 -vn 0.227461 0.073468 0.971012 -v 0.090103 0.095957 0.162745 -vn 0.227458 0.877656 -0.421879 -v 0.090103 0.095207 0.164044 -vn 0.297110 0.936317 -0.187179 -v 0.090603 0.096506 0.164794 -vn -0.297108 0.936318 -0.187178 -v 0.087603 0.096506 0.164794 -vn -0.297108 0.936316 -0.187186 -v 0.087603 0.093881 0.169340 -vn -0.297109 0.306054 0.904465 -v 0.087603 0.093256 0.170423 -vn -0.301514 0.934105 0.191149 -v 0.089603 0.093881 0.169340 -vn 0.297111 0.306053 0.904465 -v 0.090603 0.093256 0.170423 -vn -0.301511 0.632593 0.713384 -v 0.089603 0.095881 0.165876 -vn -0.297108 0.306057 0.904465 -v 0.087603 0.095881 0.165876 -vn 0.227460 0.073468 0.971012 -v 0.090103 0.091957 0.169673 -vn 0.227458 0.877656 -0.421879 -v 0.090103 0.091207 0.170972 -vn 0.297109 0.936317 -0.187179 -v 0.090603 0.092506 0.171722 -vn -0.297108 0.936318 -0.187178 -v 0.087603 0.092506 0.171722 -vn -0.297108 0.936317 -0.187183 -v 0.087603 0.089881 0.176269 -vn -0.297107 0.306056 0.904465 -v 0.087603 0.089256 0.177351 -vn -0.301511 0.934105 0.191152 -v 0.089603 0.089881 0.176269 -vn 0.297109 0.306056 0.904464 -v 0.090603 0.089256 0.177351 -vn -0.301510 0.632593 0.713385 -v 0.089603 0.091881 0.172804 -vn -0.297108 0.306057 0.904465 -v 0.087603 0.091881 0.172804 -vn 0.227459 0.073472 0.971012 -v 0.090103 0.087957 0.176601 -vn 0.227456 0.877655 -0.421884 -v 0.090103 0.087207 0.177900 -vn 0.297109 0.936316 -0.187184 -v 0.090603 0.088506 0.178650 -vn -0.297108 0.936316 -0.187186 -v 0.087603 0.088506 0.178650 -vn -0.297110 0.936317 -0.187177 -v 0.087603 0.085881 0.183197 -vn -0.297110 0.306056 0.904464 -v 0.087603 0.085256 0.184279 -vn -0.301510 0.934105 0.191152 -v 0.089603 0.085881 0.183197 -vn 0.297108 0.306057 0.904464 -v 0.090603 0.085256 0.184279 -vn -0.301511 0.632595 0.713383 -v 0.089603 0.087881 0.179733 -vn -0.297109 0.306052 0.904466 -v 0.087603 0.087881 0.179733 -vn 0.227459 0.073472 0.971012 -v 0.090103 0.083957 0.183529 -vn 0.297110 0.306054 0.904465 -v 0.090103 0.083207 0.184828 -vn 0.552289 -0.108989 0.826498 -v 0.091469 0.081474 0.183828 -vn 0.318861 0.093191 0.943209 -v 0.091103 0.081791 0.184011 -vn 0.128160 0.602700 -0.787609 -v 0.094303 0.094300 0.156015 -vn 0.128152 0.380733 -0.915762 -v 0.094303 0.089623 0.153315 -vn 0.128152 0.915764 0.380727 -v 0.094303 0.094409 0.156424 -vn 0.128160 0.787609 0.602700 -v 0.094303 0.091209 0.161967 -vn 0.128147 -0.602687 0.787621 -v 0.094303 0.086123 0.159377 -vn 0.128145 -0.380736 0.915761 -v 0.094303 0.090800 0.162077 -vn 0.128160 -0.787609 -0.602700 -v 0.094303 0.089213 0.153424 -vn 0.128152 -0.915759 -0.380739 -v 0.094303 0.086013 0.158967 -vn 0.988104 -0.039799 -0.148547 -v 0.094603 0.089473 0.153574 -vn 0.988105 0.148539 -0.039809 -v 0.094603 0.094150 0.156274 -vn 0.988105 -0.148539 0.039797 -v 0.094603 0.086273 0.159117 -vn 0.988106 0.039795 0.148533 -v 0.094603 0.090950 0.161817 -vn 0.128160 -0.787609 -0.602700 -v 0.094303 0.077089 0.146424 -vn 0.128157 -0.915752 -0.380755 -v 0.094303 0.073889 0.151967 -vn 0.128143 0.380732 -0.915763 -v 0.094303 0.077499 0.146315 -vn 0.128146 0.602700 -0.787611 -v 0.094303 0.082175 0.149015 -vn 0.128142 0.915760 0.380740 -v 0.094303 0.082285 0.149424 -vn 0.128160 0.787609 0.602700 -v 0.094303 0.079085 0.154967 -vn 0.128145 -0.380730 0.915764 -v 0.094303 0.078675 0.155077 -vn 0.128147 -0.602700 0.787611 -v 0.094303 0.073999 0.152377 -vn 0.988106 -0.148535 0.039797 -v 0.094603 0.074149 0.152117 -vn 0.988104 -0.039801 -0.148546 -v 0.094603 0.077349 0.146574 -vn 0.988106 0.039804 0.148535 -v 0.094603 0.078825 0.154817 -vn 0.988104 0.148544 -0.039806 -v 0.094603 0.082025 0.149274 -vn 0.609994 0.792406 0.000002 -v 0.088103 0.092268 0.152133 -vn -0.609994 0.792406 0.000002 -v 0.089603 0.092268 0.152133 -vn 0.075085 0.914823 0.396813 -v 0.088103 0.093595 0.149834 -vn -0.770261 -0.318867 0.552288 -v 0.089603 0.095202 0.151051 -vn -0.770264 -0.000000 0.637725 -v 0.089603 0.094577 0.150883 -vn -0.770264 -0.552286 -0.318863 -v 0.089603 0.095660 0.152758 -vn -0.609994 -0.396203 -0.686243 -v 0.089603 0.095732 0.154133 -vn -0.770262 -0.637728 0.000005 -v 0.089603 0.095827 0.152133 -vn -0.770261 -0.552288 0.318867 -v 0.089603 0.095660 0.151508 -vn -0.770262 -0.318858 -0.552291 -v 0.089603 0.095202 0.153216 -vn -0.770258 -0.000000 -0.637732 -v 0.089603 0.094577 0.153383 -vn -0.609994 0.396203 -0.686243 -v 0.089603 0.093423 0.154133 -vn -0.770265 0.318861 -0.552286 -v 0.089603 0.093952 0.153216 -vn -0.770259 0.552290 -0.318868 -v 0.089603 0.093495 0.152758 -vn -0.770265 0.637724 -0.000002 -v 0.089603 0.093327 0.152133 -vn -0.770260 0.552291 0.318865 -v 0.089603 0.093495 0.151508 -vn -0.770262 0.318869 0.552286 -v 0.089603 0.093952 0.151051 -vn 0.075085 -0.801061 -0.593854 -v 0.088103 0.097059 0.151834 -vn 0.609994 -0.396203 -0.686244 -v 0.088103 0.095732 0.154133 -vn 0.609994 0.396204 -0.686243 -v 0.088103 0.093423 0.154133 -vn 0.846479 -0.015958 -0.532183 -v 0.088103 0.095193 0.153066 -vn 0.846479 0.468864 -0.252272 -v 0.088103 0.093461 0.152066 -vn 0.609994 0.000000 0.792406 -v 0.088103 0.096716 0.157121 -vn -0.609994 0.000000 0.792406 -v 0.089603 0.096716 0.157121 -vn 0.075086 -0.396808 0.914825 -v 0.088103 0.099015 0.158448 -vn -0.609994 0.686243 -0.396203 -v 0.089603 0.094715 0.160585 -vn -0.770258 -0.000000 -0.637732 -v 0.089603 0.096716 0.160680 -vn -0.770265 0.318861 -0.552287 -v 0.089603 0.096091 0.160513 -vn -0.770261 0.552291 -0.318862 -v 0.089603 0.095633 0.160055 -vn -0.609995 0.686244 0.396202 -v 0.089603 0.094715 0.158275 -vn -0.770261 0.637729 -0.000000 -v 0.089603 0.095466 0.159430 -vn -0.770260 -0.318866 0.552291 -v 0.089603 0.097341 0.158348 -vn -0.770263 -0.552286 0.318865 -v 0.089603 0.097798 0.158805 -vn -0.770261 -0.637728 0.000000 -v 0.089603 0.097966 0.159430 -vn -0.770261 -0.552291 -0.318862 -v 0.089603 0.097798 0.160055 -vn -0.770265 -0.318861 -0.552286 -v 0.089603 0.097341 0.160513 -vn -0.770263 0.552286 0.318865 -v 0.089603 0.095633 0.158805 -vn -0.770260 0.318865 0.552291 -v 0.089603 0.096091 0.158348 -vn -0.770264 -0.000000 0.637725 -v 0.089603 0.096716 0.158180 -vn 0.075084 0.593853 -0.801063 -v 0.088103 0.097015 0.161912 -vn 0.609994 0.686243 -0.396203 -v 0.088103 0.094715 0.160585 -vn 0.609994 0.686244 0.396203 -v 0.088103 0.094715 0.158275 -vn 0.846478 0.532184 -0.015957 -v 0.088103 0.095782 0.160046 -vn 0.846478 0.252272 0.468864 -v 0.088103 0.096782 0.158314 -vn 0.609995 -0.000002 0.792406 -v 0.088103 0.092716 0.164049 -vn -0.609995 -0.000001 0.792406 -v 0.089603 0.092716 0.164049 -vn 0.075085 -0.396810 0.914825 -v 0.088103 0.095015 0.165376 -vn -0.609994 0.686243 -0.396203 -v 0.089603 0.090715 0.167513 -vn -0.770258 -0.000000 -0.637732 -v 0.089603 0.092716 0.167608 -vn -0.770265 0.318861 -0.552287 -v 0.089603 0.092091 0.167441 -vn -0.770261 0.552291 -0.318862 -v 0.089603 0.091633 0.166983 -vn -0.609994 0.686243 0.396205 -v 0.089603 0.090715 0.165204 -vn -0.770261 0.637729 -0.000000 -v 0.089603 0.091466 0.166358 -vn -0.770263 -0.552286 0.318865 -v 0.089603 0.093798 0.165733 -vn -0.770260 -0.318866 0.552291 -v 0.089603 0.093341 0.165276 -vn -0.770263 0.552286 0.318865 -v 0.089603 0.091633 0.165733 -vn -0.770260 0.318865 0.552291 -v 0.089603 0.092091 0.165276 -vn -0.770264 -0.000000 0.637725 -v 0.089603 0.092716 0.165108 -vn -0.770261 -0.637728 0.000000 -v 0.089603 0.093966 0.166358 -vn -0.770261 -0.552291 -0.318862 -v 0.089603 0.093798 0.166983 -vn -0.770265 -0.318861 -0.552286 -v 0.089603 0.093341 0.167441 -vn 0.075084 0.593853 -0.801063 -v 0.088103 0.093015 0.168840 -vn 0.609994 0.686243 -0.396203 -v 0.088103 0.090715 0.167513 -vn 0.609994 -0.000001 0.792406 -v 0.088103 0.088716 0.170977 -vn -0.609994 -0.000001 0.792406 -v 0.089603 0.088716 0.170977 -vn 0.075085 -0.396810 0.914825 -v 0.088103 0.091015 0.172304 -vn -0.770261 -0.552291 0.318862 -v 0.089603 0.089798 0.172662 -vn -0.770265 -0.318861 0.552286 -v 0.089603 0.089341 0.172204 -vn -0.770261 -0.637728 0.000000 -v 0.089603 0.089965 0.173287 -vn -0.770263 -0.552286 -0.318865 -v 0.089603 0.089798 0.173912 -vn -0.770261 0.637729 -0.000000 -v 0.089603 0.087466 0.173287 -vn -0.609994 0.686243 0.396204 -v 0.089603 0.086716 0.172132 -vn -0.770263 0.552286 -0.318865 -v 0.089603 0.087633 0.173912 -vn -0.609994 0.686243 -0.396203 -v 0.089603 0.086716 0.174441 -vn -0.770261 0.552291 0.318862 -v 0.089603 0.087633 0.172662 -vn -0.770265 0.318861 0.552286 -v 0.089603 0.088091 0.172204 -vn -0.770258 0.000000 0.637732 -v 0.089603 0.088716 0.172037 -vn -0.770260 -0.318865 -0.552291 -v 0.089603 0.089341 0.174369 -vn -0.770264 0.000000 -0.637725 -v 0.089603 0.088716 0.174537 -vn -0.770260 0.318866 -0.552291 -v 0.089603 0.088091 0.174369 -vn 0.075083 0.593853 -0.801062 -v 0.088103 0.089015 0.175769 -vn 0.609994 0.686244 -0.396203 -v 0.088103 0.086716 0.174441 -vn 0.609994 0.000002 0.792406 -v 0.088103 0.084716 0.177905 -vn -0.609995 -0.000000 0.792405 -v 0.089603 0.084716 0.177905 -vn 0.075085 -0.396813 0.914823 -v 0.088103 0.087015 0.179233 -vn -0.770261 0.552291 0.318862 -v 0.089603 0.083633 0.179590 -vn -0.770265 0.318861 0.552286 -v 0.089603 0.084091 0.179132 -vn -0.609995 0.686244 0.396202 -v 0.089603 0.082716 0.179060 -vn -0.609995 0.686244 -0.396202 -v 0.089603 0.082716 0.181369 -vn -0.770262 -0.000003 -0.637727 -v 0.089603 0.084716 0.181465 -vn -0.770260 0.318866 -0.552291 -v 0.089603 0.084091 0.181297 -vn -0.770263 0.552286 -0.318865 -v 0.089603 0.083633 0.180840 -vn -0.770261 0.637729 -0.000000 -v 0.089603 0.083466 0.180215 -vn -0.770257 -0.000005 0.637733 -v 0.089603 0.084716 0.178965 -vn -0.770267 -0.318862 0.552282 -v 0.089603 0.085340 0.179132 -vn -0.770261 -0.552291 0.318862 -v 0.089603 0.085798 0.179590 -vn -0.770261 -0.637728 0.000000 -v 0.089603 0.085965 0.180215 -vn -0.770263 -0.552286 -0.318865 -v 0.089603 0.085798 0.180840 -vn -0.770260 -0.318869 -0.552288 -v 0.089603 0.085340 0.181297 -vn 0.075086 0.593857 -0.801060 -v 0.088103 0.085015 0.182697 -vn 0.609995 0.686244 -0.396202 -v 0.088103 0.082716 0.181369 -vn 0.609994 0.686243 0.396205 -v 0.088103 0.090715 0.165204 -vn 0.846478 0.532184 -0.015957 -v 0.088103 0.091782 0.166974 -vn 0.846478 0.252272 0.468864 -v 0.088103 0.092782 0.165242 -vn 0.609994 0.686243 0.396204 -v 0.088103 0.086716 0.172132 -vn 0.846478 0.532184 -0.015957 -v 0.088103 0.087782 0.173903 -vn 0.846479 0.252272 0.468864 -v 0.088103 0.088782 0.172170 -vn 0.609995 0.686244 0.396202 -v 0.088103 0.082716 0.179060 -vn 0.846479 0.532183 -0.015958 -v 0.088103 0.083782 0.180831 -vn 0.846478 0.252276 0.468863 -v 0.088103 0.084782 0.179099 -vn 0.128751 -0.624083 0.770677 -v 0.090603 0.056324 0.184825 -vn 0.129691 -0.736869 0.663479 -v 0.090603 0.055755 0.184285 -vn 0.128741 -0.831692 0.540106 -v 0.090603 0.055278 0.183663 -vn 0.129691 -0.905830 0.403301 -v 0.090603 0.054903 0.182973 -vn 0.128747 -0.957887 0.256666 -v 0.090603 0.054641 0.182234 -vn 0.129692 -0.986122 0.103646 -v 0.090603 0.054498 0.181462 -vn 0.128746 -0.990318 -0.051902 -v 0.090603 0.054478 0.180678 -vn 0.129688 -0.969887 -0.206155 -v 0.090603 0.054580 0.179900 -vn 0.128741 -0.925811 -0.355387 -v 0.090603 0.054803 0.179148 -vn 0.128754 0.770677 0.624083 -v 0.090603 0.077213 0.192086 -vn 0.129696 0.663478 0.736869 -v 0.090603 0.076673 0.192655 -vn 0.128752 0.540105 0.831691 -v 0.090603 0.076051 0.193133 -vn 0.129696 0.403303 0.905829 -v 0.090603 0.075361 0.193507 -vn 0.128751 0.256663 0.957887 -v 0.090603 0.074621 0.193769 -vn 0.129696 0.103641 0.986122 -v 0.090603 0.073850 0.193912 -vn 0.128739 -0.051895 0.990320 -v 0.090603 0.073066 0.193933 -vn 0.129694 -0.206159 0.969886 -v 0.090603 0.072288 0.193830 -vn 0.128738 -0.355384 0.925812 -v 0.090603 0.071536 0.193607 -vn 0.227456 -0.971013 0.073468 -v 0.090603 0.086626 0.168905 -vn 0.227460 0.421880 0.877656 -v 0.090603 0.078832 0.164405 -vn 0.227460 0.971012 -0.073469 -v 0.090603 0.076582 0.168302 -vn 0.227451 -0.421881 -0.877657 -v 0.090603 0.084376 0.172802 -vn 0.765315 -0.609562 0.206704 -v 0.091303 0.086976 0.168299 -vn 0.765317 -0.125769 -0.631247 -v 0.091303 0.084026 0.173408 -vn 0.765315 0.609563 -0.206702 -v 0.091303 0.067572 0.163908 -vn 0.765320 0.125771 0.631242 -v 0.091303 0.070522 0.158799 -vn 0.227458 0.421882 0.877655 -v 0.090603 0.070172 0.159405 -vn 0.227455 0.971013 -0.073467 -v 0.090603 0.067922 0.163302 -vn 0.227461 -0.421880 -0.877655 -v 0.090603 0.075716 0.167802 -vn 0.227461 -0.971012 0.073470 -v 0.090603 0.077966 0.163905 -vn 0.126966 -0.624230 0.770854 -v 0.094103 0.066251 0.183507 -vn 0.126934 -0.831884 0.540237 -v 0.094103 0.065120 0.182251 -vn 0.129687 -0.736867 0.663482 -v 0.094103 0.065636 0.182924 -vn 0.126944 -0.958113 0.256720 -v 0.094103 0.064433 0.180708 -vn 0.129690 -0.905830 0.403302 -v 0.094103 0.064716 0.181507 -vn 0.126959 -0.990548 -0.051916 -v 0.094103 0.064257 0.179028 -vn 0.129674 -0.986124 0.103649 -v 0.094103 0.064279 0.179875 -vn 0.126961 -0.926025 -0.355470 -v 0.094103 0.064608 0.177375 -vn 0.129696 -0.969887 -0.206152 -v 0.094103 0.064367 0.178188 -vn 0.126965 -0.770853 -0.624232 -v 0.094103 0.065453 0.175912 -vn 0.129689 -0.858712 -0.495776 -v 0.094103 0.064973 0.176610 -vn 0.126934 -0.540231 -0.831888 -v 0.094103 0.066708 0.174782 -vn 0.129687 -0.663482 -0.736867 -v 0.094103 0.066036 0.175297 -vn 0.126924 -0.256728 -0.958113 -v 0.094103 0.068252 0.174094 -vn 0.129690 -0.403297 -0.905832 -v 0.094103 0.067453 0.174377 -vn 0.126957 0.051918 -0.990549 -v 0.094103 0.069932 0.173918 -vn 0.129673 -0.103651 -0.986124 -v 0.094103 0.069085 0.173940 -vn 0.126932 0.355464 -0.926031 -v 0.094103 0.071584 0.174269 -vn 0.129680 0.206153 -0.969889 -v 0.094103 0.070772 0.174028 -vn 0.126936 0.624233 -0.770857 -v 0.094103 0.073047 0.175114 -vn 0.129706 0.495778 -0.858709 -v 0.094103 0.072349 0.174634 -vn 0.126933 0.831887 -0.540233 -v 0.094103 0.074178 0.176369 -vn 0.129672 0.736871 -0.663480 -v 0.094103 0.073662 0.175697 -vn 0.126934 0.958111 -0.256730 -v 0.094103 0.074865 0.177913 -vn 0.129690 0.905830 -0.403302 -v 0.094103 0.074582 0.177114 -vn 0.126936 0.990551 0.051913 -v 0.094103 0.075042 0.179593 -vn 0.129695 0.986122 -0.103646 -v 0.094103 0.075020 0.178746 -vn 0.126940 0.926028 0.355470 -v 0.094103 0.074690 0.181246 -vn 0.129683 0.969888 0.206154 -v 0.094103 0.074931 0.180433 -vn 0.126922 0.770862 0.624230 -v 0.094103 0.073846 0.182709 -vn 0.129685 0.858711 0.495779 -v 0.094103 0.074326 0.182010 -vn 0.126933 0.540233 0.831887 -v 0.094103 0.072590 0.183839 -vn 0.129669 0.663482 0.736870 -v 0.094103 0.073262 0.183323 -vn 0.126929 0.256728 0.958113 -v 0.094103 0.071047 0.184526 -vn 0.129690 0.403304 0.905829 -v 0.094103 0.071846 0.184244 -vn 0.126956 -0.051917 0.990549 -v 0.094103 0.069367 0.184703 -vn 0.129673 0.103652 0.986124 -v 0.094103 0.070214 0.184681 -vn 0.129661 -0.495776 0.858717 -v 0.094103 0.066949 0.183987 -vn 0.126980 -0.355474 0.926021 -v 0.094103 0.067714 0.184352 -vn 0.129684 -0.206154 0.969888 -v 0.094103 0.068526 0.184592 -vn 0.990582 0.028468 -0.133931 -v 0.094403 0.070710 0.174322 -vn 0.990583 0.049066 -0.127819 -v 0.094403 0.071477 0.174549 -vn 0.750898 -0.101300 0.652603 -v 0.094403 0.070263 0.175358 -vn 0.750900 -0.330207 0.571938 -v 0.094403 0.071649 0.175846 -vn 0.990583 0.132251 -0.035437 -v 0.094403 0.074575 0.177990 -vn 0.990583 0.136164 -0.014311 -v 0.094403 0.074721 0.178777 -vn 0.750900 -0.629339 0.200207 -v 0.094403 0.073461 0.178098 -vn 0.750898 -0.659166 -0.040657 -v 0.094403 0.073642 0.179557 -vn 0.750899 0.640471 0.161084 -v 0.094403 0.065770 0.178335 -vn 0.750899 0.655411 -0.081158 -v 0.094403 0.065679 0.179802 -vn 0.990583 -0.136724 -0.007166 -v 0.094403 0.064556 0.179043 -vn 0.750898 0.581837 -0.312439 -v 0.094403 0.066125 0.181203 -vn 0.990583 -0.132248 0.035435 -v 0.094403 0.064723 0.180630 -vn 0.990582 -0.136170 0.014313 -v 0.094403 0.064577 0.179843 -vn 0.990582 -0.086168 0.106408 -v 0.094403 0.066440 0.183274 -vn 0.750900 0.429678 -0.501523 -v 0.094403 0.067047 0.182348 -vn 0.990583 -0.068456 0.118569 -v 0.094403 0.067099 0.183727 -vn 0.750898 0.219491 -0.622877 -v 0.094403 0.068320 0.183083 -vn 0.990583 -0.049065 0.127821 -v 0.094403 0.067821 0.184072 -vn 0.990581 0.091622 0.101756 -v 0.094403 0.073062 0.183100 -vn 0.990582 0.074572 0.114832 -v 0.094403 0.072427 0.183588 -vn 0.750898 -0.459740 -0.474121 -v 0.094403 0.072434 0.182182 -vn 0.750900 -0.257421 -0.608181 -v 0.094403 0.071208 0.182994 -vn 0.990582 0.136731 0.007166 -v 0.094403 0.074742 0.179577 -vn 0.990583 0.133923 0.028466 -v 0.094403 0.074638 0.180371 -vn 0.750899 -0.599966 -0.276028 -v 0.094403 0.073283 0.180982 -vn 0.990583 0.068457 -0.118572 -v 0.094403 0.072199 0.174894 -vn 0.990583 0.086164 -0.106405 -v 0.094403 0.072859 0.175347 -vn 0.750898 -0.514519 0.414032 -v 0.094403 0.072765 0.176803 -vn 0.750898 0.141285 0.645128 -v 0.094403 0.068793 0.175403 -vn 0.990582 -0.014312 -0.136170 -v 0.094403 0.069116 0.174238 -vn 0.990582 0.007165 -0.136737 -v 0.094403 0.069916 0.174217 -vn 0.990583 -0.106405 -0.086165 -v 0.094403 0.065686 0.176101 -vn 0.990583 -0.091615 -0.101750 -v 0.094403 0.066237 0.175520 -vn 0.750900 0.539029 0.381572 -v 0.094403 0.066384 0.176999 -vn 0.750899 0.364790 0.550527 -v 0.094403 0.067440 0.175976 -vn 0.990581 -0.101755 0.091621 -v 0.094403 0.065859 0.182723 -vn 0.990582 -0.114830 0.074572 -v 0.094403 0.065372 0.182088 -vn 0.990582 -0.125083 0.055691 -v 0.094403 0.064990 0.181385 -vn 0.990584 -0.028465 0.133917 -v 0.094403 0.068589 0.184299 -vn 0.750898 -0.020336 -0.660105 -v 0.094403 0.069772 0.183308 -vn 0.990583 -0.007166 0.136723 -v 0.094403 0.069382 0.184403 -vn 0.990583 0.055689 0.125080 -v 0.094403 0.071724 0.183969 -vn 0.990584 0.035434 0.132243 -v 0.094403 0.070969 0.184237 -vn 0.990582 0.014313 0.136171 -v 0.094403 0.070182 0.184382 -vn 0.990583 0.127822 0.049067 -v 0.094403 0.074410 0.181138 -vn 0.990583 0.118572 0.068458 -v 0.094403 0.074066 0.181860 -vn 0.990581 0.106411 0.086170 -v 0.094403 0.073613 0.182520 -vn 0.990583 0.101746 -0.091612 -v 0.094403 0.073439 0.175898 -vn 0.990582 0.114829 -0.074571 -v 0.094403 0.073926 0.176533 -vn 0.990583 0.125078 -0.055687 -v 0.094403 0.074308 0.177236 -vn 0.990582 -0.074572 -0.114832 -v 0.094403 0.066872 0.175033 -vn 0.990582 -0.055691 -0.125082 -v 0.094403 0.067575 0.174651 -vn 0.990582 -0.035438 -0.132256 -v 0.094403 0.068329 0.174384 -vn 0.990582 -0.133926 -0.028467 -v 0.094403 0.064661 0.178250 -vn 0.990582 -0.127828 -0.049068 -v 0.094403 0.064888 0.177483 -vn 0.990582 -0.118577 -0.068460 -v 0.094403 0.065232 0.176760 -vn 0.667992 -0.372083 0.644470 -v 0.093803 0.071649 0.175846 -vn 0.667993 -0.579767 0.466536 -v 0.093803 0.072765 0.176803 -vn 0.667992 -0.709150 0.225596 -v 0.093803 0.073461 0.178098 -vn 0.667993 -0.742756 -0.045812 -v 0.093803 0.073642 0.179557 -vn 0.667992 -0.676051 -0.311033 -v 0.093803 0.073283 0.180982 -vn 0.667993 -0.518041 -0.534246 -v 0.093803 0.072434 0.182182 -vn 0.667992 -0.290066 -0.685309 -v 0.093803 0.071208 0.182994 -vn 0.667993 -0.022915 -0.743815 -v 0.093803 0.069772 0.183308 -vn 0.667993 0.247325 -0.701866 -v 0.093803 0.068320 0.183083 -vn 0.667992 0.484169 -0.565126 -v 0.093803 0.067047 0.182348 -vn 0.667993 0.655621 -0.352060 -v 0.093803 0.066125 0.181203 -vn 0.667992 0.738528 -0.091450 -v 0.093803 0.065679 0.179802 -vn 0.667993 0.721692 0.181512 -v 0.093803 0.065770 0.178335 -vn 0.667992 0.607388 0.429962 -v 0.093803 0.066384 0.176999 -vn 0.667993 0.411050 0.620341 -v 0.093803 0.067440 0.175976 -vn 0.667993 0.159202 0.726939 -v 0.093803 0.068793 0.175403 -vn 0.667993 -0.114146 0.735361 -v 0.093803 0.070263 0.175358 -vn 0.976005 0.108875 0.188575 -v 0.093803 0.068887 0.177990 -vn 0.976004 -0.000001 0.217752 -v 0.093803 0.069649 0.177785 -vn 0.976005 -0.108873 0.188576 -v 0.093803 0.070412 0.177990 -vn 0.976003 -0.188582 0.108876 -v 0.093803 0.070970 0.178548 -vn 0.976004 0.217753 0.000000 -v 0.093803 0.068124 0.179310 -vn 0.976004 0.188581 0.108877 -v 0.093803 0.068328 0.178548 -vn 0.976004 -0.000001 -0.217753 -v 0.093803 0.069649 0.180835 -vn 0.976003 0.108878 -0.188582 -v 0.093803 0.068887 0.180631 -vn 0.976005 0.188576 -0.108875 -v 0.093803 0.068328 0.180073 -vn 0.976005 -0.188577 -0.108875 -v 0.093803 0.070970 0.180073 -vn 0.976003 -0.108877 -0.188583 -v 0.093803 0.070412 0.180631 -vn 0.976004 -0.217752 0.000000 -v 0.093803 0.071174 0.179310 -vn -1.000000 -0.000000 -0.000003 -v 0.091584 0.057138 0.182480 -vn -0.460547 0.000000 -0.887635 -v 0.091103 0.057138 0.183280 -vn -0.460548 -0.443821 -0.768712 -v 0.091103 0.057538 0.183172 -vn -0.460548 0.443821 -0.768712 -v 0.091103 0.056738 0.183172 -vn -0.460549 -0.887634 -0.000000 -v 0.091103 0.057938 0.182480 -vn -0.460549 -0.768716 0.443814 -v 0.091103 0.057831 0.182080 -vn -0.460548 -0.768715 -0.443816 -v 0.091103 0.057831 0.182880 -vn -0.460551 -0.000000 0.887633 -v 0.091103 0.057138 0.181680 -vn -0.460549 0.443808 0.768719 -v 0.091103 0.056738 0.181787 -vn -0.460549 -0.443810 0.768718 -v 0.091103 0.057538 0.181787 -vn -0.460549 0.887634 -0.000004 -v 0.091103 0.056338 0.182480 -vn -0.460548 0.768715 -0.443816 -v 0.091103 0.056446 0.182880 -vn -0.460549 0.768716 0.443813 -v 0.091103 0.056446 0.182080 -vn -0.539406 0.421027 -0.729231 -v 0.086661 0.056738 0.183172 -vn -0.539406 -0.000001 -0.842046 -v 0.086661 0.057138 0.183280 -vn -0.539405 -0.421027 -0.729231 -v 0.086661 0.057538 0.183172 -vn -0.539407 -0.729235 -0.421019 -v 0.086661 0.057831 0.182880 -vn -0.539403 -0.842048 -0.000000 -v 0.086661 0.057938 0.182480 -vn -0.539398 -0.729237 0.421026 -v 0.086661 0.057831 0.182080 -vn -0.539408 -0.421017 0.729235 -v 0.086661 0.057538 0.181787 -vn -0.539400 0.000000 0.842050 -v 0.086661 0.057138 0.181680 -vn -0.539408 0.421013 0.729237 -v 0.086661 0.056738 0.181787 -vn -0.539394 0.729242 0.421023 -v 0.086661 0.056446 0.182080 -vn -0.539402 0.842049 -0.000003 -v 0.086661 0.056338 0.182480 -vn -0.539408 0.729235 -0.421018 -v 0.086661 0.056446 0.182880 -vn -1.000000 -0.000000 -0.000003 -v 0.091584 0.073160 0.191730 -vn -0.460547 0.000000 -0.887635 -v 0.091103 0.073160 0.192530 -vn -0.460548 -0.443826 -0.768709 -v 0.091103 0.073560 0.192422 -vn -0.460548 0.443821 -0.768712 -v 0.091103 0.072760 0.192422 -vn -0.460548 -0.887635 -0.000011 -v 0.091103 0.073960 0.191730 -vn -0.460549 -0.768716 0.443813 -v 0.091103 0.073853 0.191330 -vn -0.460548 -0.768714 -0.443818 -v 0.091103 0.073853 0.192130 -vn -0.460551 -0.000000 0.887633 -v 0.091103 0.073160 0.190930 -vn -0.460549 0.443808 0.768719 -v 0.091103 0.072760 0.191037 -vn -0.460549 -0.443808 0.768719 -v 0.091103 0.073560 0.191037 -vn -0.460549 0.887634 -0.000004 -v 0.091103 0.072360 0.191730 -vn -0.460548 0.768715 -0.443816 -v 0.091103 0.072467 0.192130 -vn -0.460549 0.768716 0.443813 -v 0.091103 0.072467 0.191330 -vn -0.539406 0.421026 -0.729231 -v 0.086661 0.072760 0.192422 -vn -0.539406 -0.000001 -0.842046 -v 0.086661 0.073160 0.192530 -vn -0.539406 -0.421032 -0.729228 -v 0.086661 0.073560 0.192422 -vn -0.539411 -0.729230 -0.421021 -v 0.086661 0.073853 0.192130 -vn -0.539405 -0.842047 -0.000011 -v 0.086661 0.073960 0.191730 -vn -0.539387 -0.729244 0.421029 -v 0.086661 0.073853 0.191330 -vn -0.539407 -0.421017 0.729236 -v 0.086661 0.073560 0.191037 -vn -0.539400 0.000000 0.842050 -v 0.086661 0.073160 0.190930 -vn -0.539408 0.421013 0.729237 -v 0.086661 0.072760 0.191037 -vn -0.539400 0.729238 0.421022 -v 0.086661 0.072467 0.191330 -vn -0.539402 0.842048 -0.000004 -v 0.086661 0.072360 0.191730 -vn -0.539414 0.729231 -0.421016 -v 0.086661 0.072467 0.192130 -vn -1.000000 0.000001 -0.000001 -v 0.091584 0.077142 0.145532 -vn -0.460547 -0.000004 -0.887635 -v 0.091103 0.077142 0.146332 -vn -0.460549 -0.443823 -0.768711 -v 0.091103 0.077542 0.146224 -vn -0.460547 0.443825 -0.768710 -v 0.091103 0.076742 0.146224 -vn -0.460549 -0.887634 -0.000004 -v 0.091103 0.077942 0.145532 -vn -0.460548 -0.768711 0.443823 -v 0.091103 0.077835 0.145132 -vn -0.460548 -0.768715 -0.443816 -v 0.091103 0.077835 0.145932 -vn -0.460547 -0.000000 0.887635 -v 0.091103 0.077142 0.144732 -vn -0.460549 0.443816 0.768714 -v 0.091103 0.076742 0.144839 -vn -0.460550 -0.443812 0.768717 -v 0.091103 0.077542 0.144839 -vn -0.460547 0.887635 -0.000004 -v 0.091103 0.076342 0.145532 -vn -0.460549 0.768714 -0.443818 -v 0.091103 0.076450 0.145932 -vn -0.460548 0.768710 0.443825 -v 0.091103 0.076450 0.145132 -vn -0.539408 0.421028 -0.729229 -v 0.086661 0.076742 0.146224 -vn -0.539405 -0.000008 -0.842046 -v 0.086661 0.077142 0.146332 -vn -0.539404 -0.421029 -0.729231 -v 0.086661 0.077542 0.146224 -vn -0.539414 -0.729230 -0.421019 -v 0.086661 0.077835 0.145932 -vn -0.539403 -0.842048 -0.000003 -v 0.086661 0.077942 0.145532 -vn -0.539402 -0.729230 0.421034 -v 0.086661 0.077835 0.145132 -vn -0.539402 -0.421021 0.729237 -v 0.086661 0.077542 0.144839 -vn -0.539406 0.000001 0.842046 -v 0.086661 0.077142 0.144732 -vn -0.539404 0.421022 0.729235 -v 0.086661 0.076742 0.144839 -vn -0.539400 0.729231 0.421034 -v 0.086661 0.076450 0.145132 -vn -0.539405 0.842046 -0.000004 -v 0.086661 0.076342 0.145532 -vn -0.539411 0.729232 -0.421018 -v 0.086661 0.076450 0.145932 -vn -1.000000 0.000002 -0.000000 -v 0.091584 0.095156 0.155932 -vn -0.460547 -0.000004 -0.887635 -v 0.091103 0.095156 0.156732 -vn -0.460550 -0.443813 -0.768716 -v 0.091103 0.095556 0.156624 -vn -0.460547 0.443825 -0.768710 -v 0.091103 0.094756 0.156624 -vn -0.460550 -0.887634 0.000000 -v 0.091103 0.095956 0.155932 -vn -0.460548 -0.768711 0.443823 -v 0.091103 0.095849 0.155532 -vn -0.460548 -0.768711 -0.443823 -v 0.091103 0.095849 0.156332 -vn -0.460547 -0.000000 0.887635 -v 0.091103 0.095156 0.155132 -vn -0.460548 0.443826 0.768709 -v 0.091103 0.094756 0.155239 -vn -0.460550 -0.443812 0.768717 -v 0.091103 0.095556 0.155239 -vn -0.460547 0.887635 -0.000000 -v 0.091103 0.094356 0.155932 -vn -0.460549 0.768714 -0.443818 -v 0.091103 0.094463 0.156332 -vn -0.460548 0.768714 0.443818 -v 0.091103 0.094463 0.155532 -vn -0.539408 0.421028 -0.729229 -v 0.086661 0.094756 0.156624 -vn -0.539405 -0.000008 -0.842046 -v 0.086661 0.095156 0.156732 -vn -0.539402 -0.421019 -0.729238 -v 0.086661 0.095556 0.156624 -vn -0.539403 -0.729231 -0.421031 -v 0.086661 0.095849 0.156332 -vn -0.539401 -0.842049 -0.000000 -v 0.086661 0.095956 0.155932 -vn -0.539402 -0.729230 0.421034 -v 0.086661 0.095849 0.155532 -vn -0.539402 -0.421021 0.729237 -v 0.086661 0.095556 0.155239 -vn -0.539406 0.000001 0.842046 -v 0.086661 0.095156 0.155132 -vn -0.539406 0.421032 0.729228 -v 0.086661 0.094756 0.155239 -vn -0.539411 0.729230 0.421021 -v 0.086661 0.094463 0.155532 -vn -0.539407 0.842045 -0.000001 -v 0.086661 0.094356 0.155932 -vn -0.539411 0.729232 -0.421018 -v 0.086661 0.094463 0.156332 -vn 0.539411 -0.421021 0.729231 -v 0.093644 0.070274 0.178228 -vn 0.539407 -0.729231 0.421024 -v 0.093644 0.070732 0.178685 -vn 0.539408 -0.842045 0.000000 -v 0.093644 0.070899 0.179310 -vn 0.539410 -0.729234 -0.421016 -v 0.093644 0.070732 0.179935 -vn 0.539406 -0.421018 -0.729236 -v 0.093644 0.070274 0.180393 -vn 0.539405 -0.000002 -0.842046 -v 0.093644 0.069649 0.180560 -vn 0.539406 0.421022 -0.729234 -v 0.093644 0.069024 0.180393 -vn 0.539409 0.729233 -0.421019 -v 0.093644 0.068567 0.179935 -vn 0.539408 0.842045 0.000000 -v 0.093644 0.068399 0.179310 -vn 0.539406 0.729231 0.421027 -v 0.093644 0.068567 0.178685 -vn 0.539411 0.421024 0.729229 -v 0.093644 0.069024 0.178228 -vn 0.539410 -0.000002 0.842043 -v 0.093644 0.069649 0.178060 -vn 0.406962 -0.456721 0.791068 -v 0.091503 0.061153 0.182026 -vn 0.406988 -0.791061 0.456710 -v 0.091503 0.061482 0.182356 -vn 0.406987 -0.913434 0.000000 -v 0.091503 0.061603 0.182806 -vn 0.406974 -0.791059 -0.456726 -v 0.091503 0.061482 0.183256 -vn 0.406988 -0.456720 -0.791055 -v 0.091503 0.061153 0.183585 -vn 0.406953 0.000006 -0.913449 -v 0.091503 0.060703 0.183706 -vn 0.406986 0.456712 -0.791060 -v 0.091503 0.060253 0.183585 -vn 0.406975 0.791061 -0.456721 -v 0.091503 0.059924 0.183256 -vn 0.406977 0.913438 0.000004 -v 0.091503 0.059803 0.182806 -vn 0.406997 0.791060 0.456703 -v 0.091503 0.059924 0.182356 -vn 0.406963 0.456712 0.791072 -v 0.091503 0.060253 0.182026 -vn 0.406981 0.000005 0.913436 -v 0.091503 0.060703 0.181906 -vn 0.406989 -0.456714 0.791058 -v 0.091503 0.066171 0.169335 -vn 0.406967 -0.791065 0.456720 -v 0.091503 0.066500 0.169664 -vn 0.406984 -0.913435 0.000003 -v 0.091503 0.066621 0.170114 -vn 0.406967 -0.791062 -0.456727 -v 0.091503 0.066500 0.170564 -vn 0.406987 -0.456719 -0.791056 -v 0.091503 0.066171 0.170894 -vn 0.406988 0.000001 -0.913434 -v 0.091503 0.065721 0.171014 -vn 0.406990 0.456719 -0.791055 -v 0.091503 0.065271 0.170894 -vn 0.406982 0.791057 -0.456723 -v 0.091503 0.064942 0.170564 -vn 0.406970 0.913442 0.000003 -v 0.091503 0.064821 0.170114 -vn 0.406979 0.791058 0.456723 -v 0.091503 0.064942 0.169664 -vn 0.406980 0.456725 0.791056 -v 0.091503 0.065271 0.169335 -vn 0.406987 0.000000 0.913434 -v 0.091503 0.065721 0.169214 -vn 0.406990 -0.456719 0.791055 -v 0.091503 0.073921 0.155911 -vn 0.406982 -0.791057 0.456723 -v 0.091503 0.074250 0.156241 -vn 0.406970 -0.913442 -0.000003 -v 0.091503 0.074371 0.156691 -vn 0.406997 -0.791055 -0.456711 -v 0.091503 0.074250 0.157141 -vn 0.406991 -0.456717 -0.791055 -v 0.091503 0.073921 0.157470 -vn 0.406988 0.000001 -0.913434 -v 0.091503 0.073471 0.157591 -vn 0.406989 0.456714 -0.791058 -v 0.091503 0.073021 0.157470 -vn 0.406984 0.791060 -0.456714 -v 0.091503 0.072692 0.157141 -vn 0.406985 0.913435 -0.000002 -v 0.091503 0.072571 0.156691 -vn 0.406967 0.791062 0.456727 -v 0.091503 0.072692 0.156241 -vn 0.406987 0.456719 0.791056 -v 0.091503 0.073021 0.155911 -vn 0.406988 -0.000001 0.913434 -v 0.091503 0.073471 0.155791 -vn 0.406989 -0.456714 0.791058 -v 0.091503 0.071545 0.188026 -vn 0.406984 -0.791060 0.456714 -v 0.091503 0.071875 0.188356 -vn 0.406985 -0.913435 0.000002 -v 0.091503 0.071995 0.188806 -vn 0.406967 -0.791062 -0.456727 -v 0.091503 0.071875 0.189256 -vn 0.406987 -0.456719 -0.791056 -v 0.091503 0.071545 0.189585 -vn 0.406988 0.000001 -0.913434 -v 0.091503 0.071095 0.189706 -vn 0.406990 0.456719 -0.791055 -v 0.091503 0.070645 0.189585 -vn 0.406982 0.791057 -0.456723 -v 0.091503 0.070316 0.189256 -vn 0.406987 0.913434 -0.000000 -v 0.091503 0.070195 0.188806 -vn 0.406999 0.791053 0.456713 -v 0.091503 0.070316 0.188356 -vn 0.406991 0.456717 0.791055 -v 0.091503 0.070645 0.188026 -vn 0.406988 -0.000001 0.913434 -v 0.091503 0.071095 0.187906 -vn 0.406990 -0.456719 0.791055 -v 0.091503 0.087777 0.163911 -vn 0.406982 -0.791057 0.456723 -v 0.091503 0.088107 0.164241 -vn 0.406987 -0.913434 0.000008 -v 0.091503 0.088227 0.164691 -vn 0.406985 -0.791059 -0.456715 -v 0.091503 0.088107 0.165141 -vn 0.406989 -0.456715 -0.791057 -v 0.091503 0.087777 0.165470 -vn 0.406988 0.000001 -0.913434 -v 0.091503 0.087327 0.165591 -vn 0.406990 0.456719 -0.791055 -v 0.091503 0.086877 0.165470 -vn 0.406998 0.791052 -0.456716 -v 0.091503 0.086548 0.165141 -vn 0.406988 0.913433 0.000001 -v 0.091503 0.086427 0.164691 -vn 0.406980 0.791056 0.456725 -v 0.091503 0.086548 0.164241 -vn 0.406989 0.456721 0.791054 -v 0.091503 0.086877 0.163911 -vn 0.406988 -0.000001 0.913434 -v 0.091503 0.087327 0.163791 -vn 0.406990 -0.456719 0.791055 -v 0.091503 0.080027 0.177335 -vn 0.406999 -0.791052 0.456716 -v 0.091503 0.080357 0.177664 -vn 0.406971 -0.913441 -0.000004 -v 0.091503 0.080477 0.178114 -vn 0.406979 -0.791058 -0.456723 -v 0.091503 0.080357 0.178564 -vn 0.406989 -0.456721 -0.791054 -v 0.091503 0.080027 0.178894 -vn 0.406988 0.000001 -0.913434 -v 0.091503 0.079577 0.179014 -vn 0.406989 0.456714 -0.791058 -v 0.091503 0.079127 0.178894 -vn 0.406967 0.791065 -0.456720 -v 0.091503 0.078798 0.178564 -vn 0.406984 0.913435 -0.000003 -v 0.091503 0.078677 0.178114 -vn 0.406985 0.791059 0.456715 -v 0.091503 0.078798 0.177664 -vn 0.406989 0.456715 0.791057 -v 0.091503 0.079127 0.177335 -vn 0.406988 -0.000001 0.913434 -v 0.091503 0.079577 0.177214 -vn 0.496975 -0.767907 -0.404148 -v 0.091103 0.055257 0.178507 -vn 0.863078 -0.447049 -0.235039 -v 0.091469 0.055574 0.178690 -vn 0.863076 -0.269639 0.427078 -v 0.091469 0.057221 0.184837 -vn 0.860425 -0.320688 0.396015 -v 0.091469 0.056639 0.184437 -vn 0.496977 -0.462955 0.733952 -v 0.091103 0.057038 0.185154 -vn 0.494483 -0.546996 0.675486 -v 0.091103 0.056409 0.184721 -vn 0.494482 -0.645930 0.581602 -v 0.091103 0.055855 0.184196 -vn 0.494482 -0.728962 0.473394 -v 0.091103 0.055390 0.183590 -vn 0.494484 -0.794042 0.353528 -v 0.091103 0.055026 0.182919 -vn 0.494484 -0.839570 0.224963 -v 0.091103 0.054771 0.182199 -vn 0.494484 -0.864425 0.090855 -v 0.091103 0.054632 0.181448 -vn 0.494482 -0.867997 -0.045490 -v 0.091103 0.054612 0.180685 -vn 0.494480 -0.850196 -0.180713 -v 0.091103 0.054711 0.179928 -vn 0.494481 -0.811457 -0.311491 -v 0.091103 0.054928 0.179196 -vn 0.860429 -0.378686 0.340968 -v 0.091469 0.056127 0.183951 -vn 0.860428 -0.427364 0.277533 -v 0.091469 0.055697 0.183390 -vn 0.860426 -0.465521 0.207263 -v 0.091469 0.055360 0.182770 -vn 0.860426 -0.492212 0.131887 -v 0.091469 0.055124 0.182104 -vn 0.860426 -0.506784 0.053265 -v 0.091469 0.054996 0.181410 -vn 0.860426 -0.508878 -0.026668 -v 0.091469 0.054977 0.180704 -vn 0.860427 -0.498439 -0.105945 -v 0.091469 0.055069 0.180004 -vn 0.860427 -0.475727 -0.182615 -v 0.091469 0.055270 0.179327 -vn 0.863075 -0.235041 0.447053 -v 0.091469 0.071077 0.192837 -vn 0.496979 -0.404149 0.767903 -v 0.091103 0.070894 0.193154 -vn 0.863077 0.427075 0.269640 -v 0.091469 0.077224 0.191190 -vn 0.860425 0.396015 0.320688 -v 0.091469 0.076825 0.191771 -vn 0.496976 0.733954 0.462954 -v 0.091103 0.077541 0.191373 -vn 0.494487 0.675484 0.546996 -v 0.091103 0.077109 0.192002 -vn 0.494485 0.581600 0.645931 -v 0.091103 0.076583 0.192556 -vn 0.494484 0.473393 0.728961 -v 0.091103 0.075978 0.193021 -vn 0.494485 0.353531 0.794041 -v 0.091103 0.075307 0.193385 -vn 0.494490 0.224959 0.839567 -v 0.091103 0.074587 0.193640 -vn 0.494485 0.090857 0.864424 -v 0.091103 0.073836 0.193779 -vn 0.494477 -0.045486 0.868000 -v 0.091103 0.073073 0.193799 -vn 0.494488 -0.180718 0.850190 -v 0.091103 0.072316 0.193699 -vn 0.494476 -0.311488 0.811461 -v 0.091103 0.071584 0.193482 -vn 0.860425 0.340974 0.378689 -v 0.091469 0.076338 0.192284 -vn 0.860422 0.277539 0.427371 -v 0.091469 0.075778 0.192714 -vn 0.860425 0.207261 0.465522 -v 0.091469 0.075158 0.193051 -vn 0.860428 0.131885 0.492209 -v 0.091469 0.074492 0.193286 -vn 0.860426 0.053270 0.506784 -v 0.091469 0.073798 0.193415 -vn 0.860427 -0.026670 0.508876 -v 0.091469 0.073092 0.193433 -vn 0.860428 -0.105945 0.498436 -v 0.091469 0.072392 0.193341 -vn 0.860425 -0.182614 0.475732 -v 0.091469 0.071715 0.193141 -vn 0.127830 0.495888 0.858926 -v 0.094303 0.091100 0.162077 -vn 0.127816 -0.000003 0.991798 -v 0.094303 0.090950 0.162117 -vn 0.854924 0.480076 0.196551 -v 0.094563 0.094280 0.156349 -vn 0.854922 0.410258 0.317486 -v 0.094563 0.091080 0.161892 -vn 0.488340 0.805846 0.334866 -v 0.094453 0.094375 0.156404 -vn 0.488327 0.692940 0.530445 -v 0.094453 0.091175 0.161947 -vn 0.127836 0.858923 -0.495892 -v 0.094303 0.094409 0.156124 -vn 0.127818 0.991798 -0.000017 -v 0.094303 0.094450 0.156274 -vn 0.488337 -0.334876 0.805844 -v 0.094453 0.090820 0.162042 -vn 0.482334 0.000001 0.875987 -v 0.094453 0.090950 0.162077 -vn 0.847438 0.265439 0.459772 -v 0.094563 0.091025 0.161947 -vn 0.847432 -0.000000 0.530904 -v 0.094563 0.090950 0.161967 -vn 0.482337 0.438001 0.758621 -v 0.094453 0.091080 0.162042 -vn 0.854934 -0.196571 0.480050 -v 0.094563 0.090875 0.161947 -vn 0.482335 0.875987 -0.000021 -v 0.094453 0.094409 0.156274 -vn 0.854924 0.317468 -0.410268 -v 0.094563 0.094225 0.156144 -vn 0.847426 0.459765 -0.265492 -v 0.094563 0.094280 0.156199 -vn 0.847428 0.530911 -0.000025 -v 0.094563 0.094300 0.156274 -vn 0.482349 0.758618 -0.437993 -v 0.094453 0.094375 0.156144 -vn 0.488349 0.530447 -0.692923 -v 0.094453 0.094280 0.156049 -vn 0.127832 -0.858923 0.495894 -v 0.094303 0.086013 0.159267 -vn 0.127818 -0.991798 -0.000008 -v 0.094303 0.085973 0.159117 -vn 0.854928 -0.317463 0.410261 -v 0.094563 0.086198 0.159247 -vn 0.488340 -0.530447 0.692928 -v 0.094453 0.086143 0.159342 -vn 0.854928 0.196575 -0.480058 -v 0.094563 0.089548 0.153444 -vn 0.488345 0.334873 -0.805841 -v 0.094453 0.089603 0.153349 -vn 0.127830 -0.495888 -0.858926 -v 0.094303 0.089323 0.153315 -vn 0.127816 -0.000003 -0.991798 -v 0.094303 0.089473 0.153274 -vn 0.488341 -0.805841 -0.334878 -v 0.094453 0.086048 0.158987 -vn 0.482334 -0.875987 -0.000005 -v 0.094453 0.086013 0.159117 -vn 0.847428 -0.459767 0.265481 -v 0.094563 0.086143 0.159192 -vn 0.847429 -0.530908 -0.000009 -v 0.094563 0.086123 0.159117 -vn 0.482349 -0.758624 0.437983 -v 0.094453 0.086048 0.159247 -vn 0.854928 -0.480059 -0.196577 -v 0.094563 0.086143 0.159042 -vn 0.482335 -0.000002 -0.875987 -v 0.094453 0.089473 0.153315 -vn 0.854923 -0.410263 -0.317476 -v 0.094563 0.089343 0.153499 -vn 0.847431 -0.265462 -0.459772 -v 0.094563 0.089398 0.153444 -vn 0.847426 0.000000 -0.530913 -v 0.094563 0.089473 0.153424 -vn 0.482340 -0.438003 -0.758618 -v 0.094453 0.089343 0.153349 -vn 0.488338 -0.692935 -0.530440 -v 0.094453 0.089248 0.153444 -vn 0.127817 0.858913 -0.495915 -v 0.094303 0.082285 0.149124 -vn 0.127829 0.991796 -0.000007 -v 0.094303 0.082325 0.149274 -vn 0.488336 0.530452 -0.692927 -v 0.094453 0.082155 0.149049 -vn 0.488338 0.334875 -0.805844 -v 0.094453 0.077479 0.146349 -vn 0.854924 0.317468 -0.410268 -v 0.094563 0.082100 0.149144 -vn 0.854928 0.196569 -0.480061 -v 0.094563 0.077424 0.146444 -vn 0.127830 -0.495894 -0.858923 -v 0.094303 0.077199 0.146315 -vn 0.127815 -0.000011 -0.991798 -v 0.094303 0.077349 0.146274 -vn 0.488329 0.805861 0.334848 -v 0.094453 0.082250 0.149404 -vn 0.482346 0.875981 -0.000005 -v 0.094453 0.082285 0.149274 -vn 0.847424 0.459778 -0.265474 -v 0.094563 0.082155 0.149199 -vn 0.847431 0.530906 -0.000004 -v 0.094563 0.082175 0.149274 -vn 0.482341 0.758628 -0.437986 -v 0.094453 0.082250 0.149144 -vn 0.854930 0.480066 0.196549 -v 0.094563 0.082155 0.149349 -vn 0.482337 0.000003 -0.875986 -v 0.094453 0.077349 0.146315 -vn 0.854916 -0.410266 -0.317492 -v 0.094563 0.077219 0.146499 -vn 0.847432 -0.265448 -0.459779 -v 0.094563 0.077274 0.146444 -vn 0.847425 -0.000015 -0.530915 -v 0.094563 0.077349 0.146424 -vn 0.482338 -0.438003 -0.758620 -v 0.094453 0.077219 0.146349 -vn 0.488327 -0.692940 -0.530445 -v 0.094453 0.077124 0.146444 -vn 0.127836 0.495887 0.858926 -v 0.094303 0.078975 0.155077 -vn 0.127818 0.000005 0.991798 -v 0.094303 0.078825 0.155117 -vn 0.488357 0.692918 0.530445 -v 0.094453 0.079050 0.154947 -vn 0.854932 0.410258 0.317459 -v 0.094563 0.078955 0.154892 -vn 0.488332 -0.805847 -0.334876 -v 0.094453 0.073924 0.151987 -vn 0.854917 -0.480085 -0.196558 -v 0.094563 0.074019 0.152042 -vn 0.127832 -0.858920 0.495898 -v 0.094303 0.073889 0.152267 -vn 0.127834 -0.991796 -0.000012 -v 0.094303 0.073849 0.152117 -vn 0.488341 -0.334871 0.805844 -v 0.094453 0.078695 0.155042 -vn 0.482334 0.000013 0.875987 -v 0.094453 0.078825 0.155077 -vn 0.847432 0.265482 0.459758 -v 0.094563 0.078900 0.154947 -vn 0.847432 0.000009 0.530904 -v 0.094563 0.078825 0.154967 -vn 0.482356 0.437988 0.758617 -v 0.094453 0.078955 0.155042 -vn 0.854937 -0.196567 0.480045 -v 0.094563 0.078750 0.154947 -vn 0.482345 -0.875981 -0.000015 -v 0.094453 0.073889 0.152117 -vn 0.854928 -0.317467 0.410259 -v 0.094563 0.074074 0.152247 -vn 0.847423 -0.459783 0.265469 -v 0.094563 0.074019 0.152192 -vn 0.847431 -0.530905 -0.000020 -v 0.094563 0.073999 0.152117 -vn 0.482346 -0.758629 0.437977 -v 0.094453 0.073924 0.152247 -vn 0.488339 -0.530461 0.692919 -v 0.094453 0.074019 0.152342 -vn 0.860424 0.320688 -0.396018 -v 0.094363 0.072953 0.175230 -vn 0.860421 0.378694 -0.340978 -v 0.094363 0.073551 0.175797 -vn 0.860421 0.427373 -0.277540 -v 0.094363 0.074052 0.176451 -vn 0.860421 0.465527 -0.207267 -v 0.094363 0.074445 0.177175 -vn 0.860421 0.492220 -0.131891 -v 0.094363 0.074720 0.177952 -vn 0.860421 0.506792 -0.053264 -v 0.094363 0.074870 0.178762 -vn 0.860422 0.508884 0.026668 -v 0.094363 0.074892 0.179585 -vn 0.860421 0.498448 0.105948 -v 0.094363 0.074784 0.180402 -vn 0.860421 0.475738 0.182618 -v 0.094363 0.074550 0.181192 -vn 0.860422 0.441311 0.254791 -v 0.094363 0.074196 0.181935 -vn 0.860426 0.396014 0.320685 -v 0.094363 0.073729 0.182614 -vn 0.860428 0.340971 0.378686 -v 0.094363 0.073162 0.183212 -vn 0.860417 0.277544 0.427379 -v 0.094363 0.072509 0.183713 -vn 0.860424 0.207265 0.465524 -v 0.094363 0.071785 0.184106 -vn 0.860425 0.131890 0.492213 -v 0.094363 0.071008 0.184381 -vn 0.860426 0.053264 0.506784 -v 0.094363 0.070198 0.184532 -vn 0.860425 -0.026669 0.508879 -v 0.094363 0.069374 0.184553 -vn 0.860423 -0.105949 0.498444 -v 0.094363 0.068558 0.184446 -vn 0.860412 -0.182621 0.475753 -v 0.094363 0.067768 0.184212 -vn 0.860426 -0.254791 0.441304 -v 0.094363 0.067024 0.183857 -vn 0.860409 -0.320703 0.396038 -v 0.094363 0.066345 0.183390 -vn 0.860423 -0.378694 0.340975 -v 0.094363 0.065748 0.182823 -vn 0.860422 -0.427371 0.277538 -v 0.094363 0.065246 0.182170 -vn 0.860426 -0.465522 0.207261 -v 0.094363 0.064853 0.181446 -vn 0.860423 -0.492217 0.131890 -v 0.094363 0.064578 0.180669 -vn 0.860425 -0.506786 0.053265 -v 0.094363 0.064428 0.179859 -vn 0.860415 -0.508895 -0.026670 -v 0.094363 0.064406 0.179036 -vn 0.860424 -0.498443 -0.105947 -v 0.094363 0.064514 0.178219 -vn 0.860419 -0.475742 -0.182618 -v 0.094363 0.064748 0.177429 -vn 0.860426 -0.441305 -0.254787 -v 0.094363 0.065103 0.176685 -vn 0.860411 -0.396035 -0.320700 -v 0.094363 0.065569 0.176006 -vn 0.860420 -0.340978 -0.378697 -v 0.094363 0.066136 0.175409 -vn 0.860432 -0.277527 -0.427360 -v 0.094363 0.066790 0.174907 -vn 0.860423 -0.207266 -0.465525 -v 0.094363 0.067514 0.174514 -vn 0.860422 -0.131891 -0.492219 -v 0.094363 0.068290 0.174239 -vn 0.860426 -0.053263 -0.506785 -v 0.094363 0.069100 0.174089 -vn 0.860419 0.026670 -0.508889 -v 0.094363 0.069924 0.174068 -vn 0.860420 0.105946 -0.498451 -v 0.094363 0.070741 0.174175 -vn 0.860430 0.182614 -0.475723 -v 0.094363 0.071531 0.174409 -vn 0.860425 0.254787 -0.441307 -v 0.094363 0.072274 0.174764 -vn 0.494471 0.547001 -0.675491 -v 0.094253 0.073022 0.175145 -vn 0.494449 0.645944 -0.581615 -v 0.094253 0.073632 0.175724 -vn 0.494467 0.728971 -0.473396 -v 0.094253 0.074144 0.176391 -vn 0.494467 0.794051 -0.353534 -v 0.094253 0.074546 0.177130 -vn 0.494467 0.839580 -0.224963 -v 0.094253 0.074826 0.177923 -vn 0.494470 0.864433 -0.090856 -v 0.094253 0.074980 0.178750 -vn 0.494470 0.868003 0.045491 -v 0.094253 0.075002 0.179591 -vn 0.494461 0.850207 0.180714 -v 0.094253 0.074892 0.180425 -vn 0.494472 0.811462 0.311491 -v 0.094253 0.074653 0.181231 -vn 0.494462 0.752747 0.434602 -v 0.094253 0.074291 0.181990 -vn 0.494468 0.675492 0.547003 -v 0.094253 0.073815 0.182683 -vn 0.494468 0.581605 0.645939 -v 0.094253 0.073236 0.183294 -vn 0.494465 0.473399 0.728971 -v 0.094253 0.072568 0.183805 -vn 0.494471 0.353535 0.794048 -v 0.094253 0.071829 0.184207 -vn 0.494462 0.224967 0.839582 -v 0.094253 0.071036 0.184488 -vn 0.494463 0.090858 0.864437 -v 0.094253 0.070209 0.184641 -vn 0.494491 -0.045495 0.867992 -v 0.094253 0.069369 0.184663 -vn 0.494462 -0.180714 0.850205 -v 0.094253 0.068535 0.184553 -vn 0.494490 -0.311490 0.811451 -v 0.094253 0.067728 0.184314 -vn 0.494444 -0.434601 0.752760 -v 0.094253 0.066969 0.183952 -vn 0.494482 -0.547004 0.675481 -v 0.094253 0.066276 0.183476 -vn 0.494469 -0.645937 0.581606 -v 0.094253 0.065666 0.182897 -vn 0.494471 -0.728965 0.473401 -v 0.094253 0.065154 0.182230 -vn 0.494477 -0.794045 0.353532 -v 0.094253 0.064753 0.181490 -vn 0.494475 -0.839575 0.224961 -v 0.094253 0.064472 0.180698 -vn 0.494462 -0.864438 0.090856 -v 0.094253 0.064319 0.179871 -vn 0.494478 -0.867999 -0.045488 -v 0.094253 0.064297 0.179030 -vn 0.494477 -0.850196 -0.180718 -v 0.094253 0.064406 0.178196 -vn 0.494491 -0.811452 -0.311488 -v 0.094253 0.064645 0.177390 -vn 0.494478 -0.752742 -0.434593 -v 0.094253 0.065007 0.176630 -vn 0.494481 -0.675486 -0.546999 -v 0.094253 0.065484 0.175937 -vn 0.494459 -0.581611 -0.645940 -v 0.094253 0.066063 0.175327 -vn 0.494485 -0.473388 -0.728964 -v 0.094253 0.066730 0.174815 -vn 0.494473 -0.353531 -0.794048 -v 0.094253 0.067469 0.174414 -vn 0.494460 -0.224969 -0.839582 -v 0.094253 0.068262 0.174133 -vn 0.494463 -0.090857 -0.864437 -v 0.094253 0.069089 0.173980 -vn 0.494491 0.045493 -0.867992 -v 0.094253 0.069930 0.173958 -vn 0.494459 0.180713 -0.850208 -v 0.094253 0.070764 0.174068 -vn 0.494478 0.311488 -0.811459 -v 0.094253 0.071570 0.174307 -vn 0.494488 0.434592 -0.752736 -v 0.094253 0.072329 0.174669 -vn -0.673142 0.717546 -0.178904 -v 0.056103 0.066981 0.179976 -vn -0.674183 0.735893 0.062769 -v 0.056103 0.066909 0.179073 -vn -0.389834 0.920869 -0.005505 -v 0.054903 0.066906 0.179119 -vn -0.675655 0.674311 0.297984 -v 0.056103 0.067135 0.178196 -vn -0.390511 0.874877 0.286518 -v 0.054903 0.067099 0.178280 -vn -0.386443 0.910702 0.145887 -v 0.054903 0.066909 0.179073 -vn -0.676926 0.540032 0.500136 -v 0.056103 0.067633 0.177440 -vn -0.397978 0.731901 0.553114 -v 0.054903 0.067543 0.177543 -vn -0.392166 0.818708 0.419432 -v 0.054903 0.067135 0.178196 -vn -0.678006 0.347771 0.647583 -v 0.056103 0.068349 0.176887 -vn -0.391670 0.526567 0.754534 -v 0.054903 0.068192 0.176978 -vn -0.381567 0.640804 0.666166 -v 0.054903 0.067633 0.177440 -vn -0.678902 0.118412 0.724618 -v 0.056103 0.069206 0.176596 -vn -0.392146 0.260133 0.882356 -v 0.054903 0.068984 0.176642 -vn -0.379264 0.397029 0.835779 -v 0.054903 0.068349 0.176887 -vn -0.679608 -0.123260 0.723146 -v 0.056103 0.070112 0.176600 -vn -0.392528 -0.033008 0.919148 -v 0.054903 0.069841 0.176567 -vn -0.377177 0.112000 0.919344 -v 0.054903 0.069206 0.176596 -vn -0.680135 -0.351203 0.643485 -v 0.056103 0.070967 0.176897 -vn -0.392846 -0.322668 0.861137 -v 0.054903 0.070679 0.176761 -vn -0.375396 -0.184834 0.908248 -v 0.054903 0.070112 0.176600 -vn -0.680484 -0.540902 0.494335 -v 0.056103 0.071679 0.177455 -vn -0.393060 -0.579000 0.714327 -v 0.054903 0.071417 0.177204 -vn -0.374006 -0.462855 0.803670 -v 0.054903 0.070967 0.176897 -vn -0.680657 -0.671969 0.291828 -v 0.056103 0.072172 0.178215 -vn -0.393200 -0.775572 0.493844 -v 0.054903 0.071981 0.177853 -vn -0.373045 -0.693461 0.616400 -v 0.054903 0.071679 0.177455 -vn -0.680659 -0.730316 0.057803 -v 0.056103 0.072391 0.179093 -vn -0.385466 -0.898055 0.211926 -v 0.054903 0.072317 0.178645 -vn -0.372558 -0.852898 0.365741 -v 0.054903 0.072172 0.178215 -vn -0.680484 -0.709664 -0.182532 -v 0.056103 0.072313 0.179995 -vn -0.386237 -0.918706 -0.082461 -v 0.054903 0.072392 0.179502 -vn -0.340448 -0.935297 0.096509 -v 0.054903 0.072391 0.179093 -vn -0.680134 -0.612193 -0.403284 -v 0.056103 0.071946 0.180823 -vn -0.396407 -0.846728 -0.354844 -v 0.054903 0.072199 0.180341 -vn -0.347434 -0.914885 -0.205610 -v 0.054903 0.072313 0.179995 -vn -0.679607 -0.448329 -0.580633 -v 0.056103 0.071330 0.181487 -vn -0.387545 -0.685693 -0.616145 -v 0.054903 0.071756 0.181078 -vn -0.388764 -0.777566 -0.494221 -v 0.054903 0.071946 0.180823 -vn -0.678900 -0.235635 -0.695392 -v 0.056103 0.070533 0.181915 -vn -0.388084 -0.455981 -0.800920 -v 0.054903 0.071106 0.181643 -vn -0.360366 -0.602026 -0.712532 -v 0.054903 0.071330 0.181487 -vn -0.678010 0.003043 -0.735046 -v 0.056103 0.069639 0.182060 -vn -0.388557 -0.179773 -0.903717 -v 0.054903 0.070314 0.181979 -vn -0.366265 -0.342710 -0.865101 -v 0.054903 0.070533 0.181915 -vn -0.676929 0.242017 -0.695123 -v 0.056103 0.068747 0.181908 -vn -0.388970 0.114673 -0.914085 -v 0.054903 0.069457 0.182054 -vn -0.371757 -0.048864 -0.927043 -v 0.054903 0.069639 0.182060 -vn -0.675656 0.455486 -0.579673 -v 0.056103 0.067952 0.181474 -vn -0.397707 0.387122 -0.831845 -v 0.054903 0.068619 0.181860 -vn -0.376765 0.248853 -0.892256 -v 0.054903 0.068747 0.181908 -vn -0.674183 0.620284 -0.400905 -v 0.056103 0.067341 0.180806 -vn -0.389598 0.639173 -0.663077 -v 0.054903 0.067881 0.181417 -vn -0.395237 0.525859 -0.753167 -v 0.054903 0.067952 0.181474 -vn -0.396853 0.890618 -0.222054 -v 0.054903 0.066981 0.179976 -vn -0.389833 0.815643 -0.427501 -v 0.054903 0.067317 0.180768 -vn -0.385313 0.735106 -0.557811 -v 0.054903 0.067341 0.180806 -vn -0.916681 -0.067225 0.393925 -v 0.054603 0.067849 0.189858 -vn -0.916687 -0.001466 0.399603 -v 0.054603 0.069610 0.190010 -vn -0.934362 0.174063 -0.310916 -v 0.054603 0.068192 0.181990 -vn -0.976002 0.211292 -0.052681 -v 0.054603 0.066719 0.171796 -vn -0.976002 0.209328 0.060023 -v 0.054603 0.066728 0.171265 -vn -0.911761 -0.166291 -0.375553 -v 0.054603 0.065126 0.169613 -vn -0.976003 0.151267 0.156642 -v 0.054603 0.067002 0.170811 -vn -0.930603 -0.319508 -0.178584 -v 0.054603 0.072329 0.180768 -vn -0.915898 0.401361 -0.006345 -v 0.054603 0.080335 0.178751 -vn -0.976000 -0.052687 -0.211302 -v 0.054603 0.077659 0.178370 -vn -0.933407 0.302996 0.192211 -v 0.054603 0.067105 0.177629 -vn -0.976003 0.060022 -0.209320 -v 0.054603 0.067431 0.172533 -vn -0.976002 0.156646 -0.151272 -v 0.054603 0.066976 0.172260 -vn -0.976001 -0.156648 0.151272 -v 0.054603 0.068451 0.170836 -vn -0.916682 0.001470 -0.399614 -v 0.054603 0.069688 0.168610 -vn -0.976001 -0.060023 0.209329 -v 0.054603 0.067996 0.170563 -vn -0.916689 -0.064326 -0.394390 -v 0.054603 0.067927 0.168750 -vn -0.976002 0.052682 0.211294 -v 0.054603 0.067466 0.170553 -vn -0.976002 -0.211292 0.052681 -v 0.054603 0.068708 0.171300 -vn -0.916682 0.131145 -0.377486 -v 0.054603 0.073161 0.169203 -vn -0.916686 0.067219 -0.393913 -v 0.054603 0.071449 0.168763 -vn -0.976001 0.060025 -0.209332 -v 0.054603 0.077129 0.178360 -vn -0.976001 0.156647 -0.151272 -v 0.054603 0.076674 0.178087 -vn -0.930832 -0.343613 -0.124426 -v 0.054603 0.072477 0.180453 -vn -0.917897 -0.122029 -0.377589 -v 0.054603 0.066212 0.169177 -vn -0.916685 0.335342 -0.217336 -v 0.054603 0.078628 0.173491 -vn -0.916685 0.294996 -0.269567 -v 0.054603 0.077548 0.172092 -vn -0.976002 -0.209328 -0.060023 -v 0.054603 0.068699 0.171831 -vn -0.916686 0.246600 -0.314443 -v 0.054603 0.076252 0.170891 -vn -0.916687 0.191480 -0.350743 -v 0.054603 0.074776 0.169919 -vn -0.976003 -0.151267 -0.156642 -v 0.054603 0.068426 0.172285 -vn -0.976002 0.209328 0.060023 -v 0.054603 0.076426 0.177092 -vn -0.976003 0.151266 0.156642 -v 0.054603 0.076699 0.176638 -vn -0.932767 -0.133353 0.334906 -v 0.054603 0.070792 0.176482 -vn -0.933023 -0.022870 0.359089 -v 0.054603 0.069862 0.176268 -vn -0.933385 0.089240 0.347604 -v 0.054603 0.068911 0.176351 -vn -0.976002 -0.052682 -0.211294 -v 0.054603 0.067962 0.172543 -vn -0.933859 0.191704 0.301922 -v 0.054603 0.068033 0.176724 -vn -0.930827 0.271448 0.244696 -v 0.054603 0.067313 0.177350 -vn -0.932589 -0.231028 0.277315 -v 0.054603 0.071610 0.176974 -vn -0.932490 -0.305961 0.191963 -v 0.054603 0.072236 0.177694 -vn -0.976002 0.211292 -0.052681 -v 0.054603 0.076417 0.177623 -vn -0.934775 -0.346164 0.079784 -v 0.054603 0.072609 0.178573 -vn -0.935148 -0.353105 -0.028559 -v 0.054603 0.072692 0.179523 -vn -0.976002 0.052682 0.211294 -v 0.054603 0.077164 0.176380 -vn -0.976003 -0.060021 0.209321 -v 0.054603 0.077694 0.176390 -vn -0.916686 0.366538 -0.159175 -v 0.054603 0.079464 0.175048 -vn -0.976003 -0.156643 0.151267 -v 0.054603 0.078149 0.176663 -vn -0.916684 0.387744 -0.096675 -v 0.054603 0.080031 0.176722 -vn -0.976002 -0.211294 0.052682 -v 0.054603 0.078406 0.177127 -vn -0.919655 0.390158 -0.044844 -v 0.054603 0.080316 0.178466 -vn -0.976002 -0.209325 -0.060022 -v 0.054603 0.078397 0.177658 -vn -0.976003 -0.151267 -0.156644 -v 0.054603 0.078124 0.178112 -vn -0.976002 -0.211293 0.052681 -v 0.054603 0.072579 0.186825 -vn -0.976002 -0.209328 -0.060023 -v 0.054603 0.072570 0.187355 -vn -0.916685 0.244286 0.316249 -v 0.054603 0.076190 0.187778 -vn -0.916684 0.064325 0.394401 -v 0.054603 0.071372 0.189871 -vn -0.916686 0.128363 0.378430 -v 0.054603 0.073086 0.189443 -vn -0.976003 -0.151266 -0.156642 -v 0.054603 0.072297 0.187810 -vn -0.931350 0.122336 -0.342959 -v 0.054603 0.068507 0.182138 -vn -0.976002 0.151270 0.156644 -v 0.054603 0.070873 0.186335 -vn -0.916684 0.188901 0.352147 -v 0.054603 0.074707 0.188739 -vn -0.976001 0.211298 -0.052685 -v 0.054603 0.070590 0.187321 -vn -0.976002 0.209326 0.060023 -v 0.054603 0.070599 0.186790 -vn -0.976001 -0.060026 0.209332 -v 0.054603 0.071867 0.186087 -vn -0.976001 -0.156647 0.151272 -v 0.054603 0.072322 0.186361 -vn -0.917268 0.396541 0.037090 -v 0.054603 0.080309 0.180233 -vn -0.916683 0.387023 0.099522 -v 0.054603 0.080012 0.181975 -vn -0.976002 -0.052682 -0.211294 -v 0.054603 0.071833 0.188067 -vn -0.976003 0.060021 -0.209321 -v 0.054603 0.071302 0.188058 -vn -0.976003 0.156643 -0.151267 -v 0.054603 0.070847 0.187785 -vn -0.933540 -0.266356 -0.239911 -v 0.054603 0.071986 0.181271 -vn -0.935066 -0.184813 -0.302484 -v 0.054603 0.071265 0.181897 -vn -0.976003 0.052681 0.211289 -v 0.054603 0.071337 0.186078 -vn -0.935157 -0.082567 -0.344477 -v 0.054603 0.070387 0.182270 -vn -0.935335 0.027432 -0.352698 -v 0.054603 0.069436 0.182353 -vn -0.916686 0.293005 0.271725 -v 0.054603 0.077495 0.186586 -vn -0.916685 0.333735 0.219793 -v 0.054603 0.078585 0.185196 -vn -0.916682 0.365366 0.161869 -v 0.054603 0.079432 0.183645 -vn -0.932523 0.194653 -0.304157 -v 0.054603 0.067967 0.181855 -vn -0.916683 -0.335344 0.217338 -v 0.054603 0.060670 0.185130 -vn -0.916685 -0.294995 0.269567 -v 0.054603 0.061750 0.186528 -vn -0.916685 -0.246604 0.314444 -v 0.054603 0.063046 0.187730 -vn -0.916685 -0.191484 0.350746 -v 0.054603 0.064522 0.188702 -vn -0.916686 -0.131138 0.377477 -v 0.054603 0.066138 0.189418 -vn -0.936216 0.350679 0.022902 -v 0.054603 0.066607 0.179098 -vn -0.933459 0.336398 0.124463 -v 0.054603 0.066821 0.178168 -vn -0.976001 -0.156646 0.151274 -v 0.054603 0.062624 0.180534 -vn -0.976000 -0.060025 0.209334 -v 0.054603 0.062169 0.180260 -vn -0.937081 0.338741 -0.084458 -v 0.054603 0.066690 0.180048 -vn -0.976002 -0.211293 0.052681 -v 0.054603 0.062881 0.180998 -vn -0.936466 0.297863 -0.185227 -v 0.054603 0.067063 0.180927 -vn -0.976002 -0.209325 -0.060025 -v 0.054603 0.062872 0.181528 -vn -0.932378 0.245994 -0.264874 -v 0.054603 0.067689 0.181647 -vn -0.975999 -0.151281 -0.156653 -v 0.054603 0.062599 0.181983 -vn -0.976002 -0.052680 -0.211292 -v 0.054603 0.062135 0.182240 -vn -0.976000 0.060025 -0.209334 -v 0.054603 0.061604 0.182231 -vn -0.916684 -0.366543 0.159177 -v 0.054603 0.059835 0.183573 -vn -0.976002 0.156643 -0.151270 -v 0.054603 0.061149 0.181958 -vn -0.916685 -0.387741 0.096675 -v 0.054603 0.059267 0.181899 -vn -0.976002 0.211295 -0.052683 -v 0.054603 0.060892 0.181494 -vn -0.916684 -0.398366 0.031536 -v 0.054603 0.058983 0.180155 -vn -0.976002 0.209325 0.060024 -v 0.054603 0.060902 0.180963 -vn -0.916684 -0.398124 -0.034463 -v 0.054603 0.058989 0.178388 -vn -0.976000 0.151276 0.156649 -v 0.054603 0.061175 0.180508 -vn -0.916685 -0.387020 -0.099521 -v 0.054603 0.059286 0.176646 -vn -0.976002 0.052680 0.211292 -v 0.054603 0.061639 0.180251 -vn -0.919041 -0.196001 -0.341977 -v 0.054603 0.064591 0.169881 -vn -0.916685 -0.244287 -0.316249 -v 0.054603 0.063108 0.170842 -vn -0.916686 -0.293005 -0.271725 -v 0.054603 0.061804 0.172035 -vn -0.916683 -0.333738 -0.219797 -v 0.054603 0.060713 0.173425 -vn -0.916686 -0.365359 -0.161864 -v 0.054603 0.059866 0.174976 -vn 0.375746 -0.899195 0.224195 -v 0.058803 0.058976 0.181972 -vn -0.375746 -0.923833 0.073135 -v 0.054903 0.058683 0.180178 -vn 0.375746 -0.923833 0.073135 -v 0.058803 0.058683 0.180178 -vn -0.375745 -0.923270 -0.079921 -v 0.054903 0.058690 0.178362 -vn 0.375745 -0.923271 -0.079921 -v 0.058803 0.058690 0.178362 -vn -0.375746 -0.897523 -0.230795 -v 0.054903 0.058996 0.176571 -vn 0.375746 -0.897523 -0.230795 -v 0.058803 0.058996 0.176571 -vn -0.375748 -0.847294 -0.375375 -v 0.054903 0.059592 0.174855 -vn 0.375748 -0.847294 -0.375375 -v 0.058803 0.059592 0.174855 -vn -0.375744 -0.773954 -0.509717 -v 0.054903 0.060462 0.173260 -vn 0.375744 -0.773954 -0.509716 -v 0.058803 0.060462 0.173260 -vn -0.375749 -0.679502 -0.630151 -v 0.054903 0.061584 0.171831 -vn 0.375749 -0.679501 -0.630152 -v 0.058803 0.061584 0.171831 -vn -0.375746 -0.566515 -0.733400 -v 0.054903 0.062925 0.170605 -vn 0.375746 -0.566515 -0.733400 -v 0.058803 0.062925 0.170605 -vn -0.370877 -0.444327 -0.815490 -v 0.054903 0.064449 0.169617 -vn 0.375745 -0.438074 -0.816644 -v 0.058803 0.064449 0.169617 -vn -0.373006 -0.294303 -0.879916 -v 0.054903 0.066116 0.168893 -vn 0.375741 -0.297688 -0.877611 -v 0.058803 0.066116 0.168893 -vn -0.375754 -0.149176 -0.914634 -v 0.054903 0.067878 0.168454 -vn 0.375754 -0.149172 -0.914635 -v 0.058803 0.067878 0.168454 -vn -0.375742 0.003407 -0.926718 -v 0.054903 0.069690 0.168310 -vn 0.372878 0.001342 -0.927879 -v 0.058803 0.069690 0.168310 -vn -0.375749 0.155890 -0.913516 -v 0.054903 0.071500 0.168467 -vn 0.375750 0.155891 -0.913515 -v 0.058803 0.071500 0.168467 -vn -0.375741 0.304126 -0.875400 -v 0.054903 0.073259 0.168920 -vn 0.375741 0.304124 -0.875401 -v 0.058803 0.073259 0.168920 -vn -0.375751 0.444059 -0.813402 -v 0.054903 0.074920 0.169655 -vn 0.375750 0.444060 -0.813402 -v 0.058803 0.074920 0.169655 -vn -0.375750 0.571886 -0.729217 -v 0.054903 0.076437 0.170655 -vn 0.375750 0.571887 -0.729217 -v 0.058803 0.076437 0.170655 -vn -0.375746 0.684114 -0.625142 -v 0.054903 0.077769 0.171890 -vn 0.375747 0.684114 -0.625142 -v 0.058803 0.077769 0.171890 -vn -0.375746 0.777678 -0.504015 -v 0.054903 0.078880 0.173328 -vn 0.375746 0.777678 -0.504016 -v 0.058803 0.078880 0.173328 -vn -0.375748 0.850029 -0.369139 -v 0.054903 0.079739 0.174929 -vn 0.375748 0.850029 -0.369139 -v 0.058803 0.079739 0.174929 -vn -0.375744 0.899196 -0.224193 -v 0.054903 0.080322 0.176649 -vn 0.375744 0.899196 -0.224194 -v 0.058803 0.080322 0.176649 -vn -0.371087 0.925315 -0.078019 -v 0.054903 0.080615 0.178442 -vn 0.375747 0.923832 -0.073134 -v 0.058803 0.080615 0.178442 -vn -0.374422 0.923631 0.081939 -v 0.054903 0.080608 0.180259 -vn 0.375745 0.923270 0.079920 -v 0.058803 0.080608 0.180259 -vn -0.375743 0.897524 0.230796 -v 0.054903 0.080303 0.182050 -vn 0.375743 0.897524 0.230796 -v 0.058803 0.080303 0.182050 -vn -0.375742 0.847296 0.375376 -v 0.054903 0.079706 0.183766 -vn 0.375742 0.847297 0.375375 -v 0.058803 0.079706 0.183766 -vn -0.375748 0.773954 0.509715 -v 0.054903 0.078836 0.185361 -vn 0.375747 0.773953 0.509716 -v 0.058803 0.078836 0.185361 -vn -0.375749 0.679501 0.630151 -v 0.054903 0.077715 0.186790 -vn 0.375749 0.679501 0.630152 -v 0.058803 0.077715 0.186790 -vn -0.375746 0.566514 0.733401 -v 0.054903 0.076374 0.188016 -vn 0.375746 0.566514 0.733401 -v 0.058803 0.076374 0.188016 -vn -0.375745 0.438072 0.816645 -v 0.054903 0.074849 0.189004 -vn 0.375745 0.438073 0.816644 -v 0.058803 0.074849 0.189004 -vn -0.375749 0.297684 0.877609 -v 0.054903 0.073183 0.189727 -vn 0.375749 0.297683 0.877609 -v 0.058803 0.073183 0.189727 -vn -0.375746 0.149175 0.914637 -v 0.054903 0.071420 0.190167 -vn 0.375746 0.149176 0.914637 -v 0.058803 0.071420 0.190167 -vn -0.375751 -0.003404 0.926715 -v 0.054903 0.069609 0.190310 -vn 0.375751 -0.003406 0.926714 -v 0.058803 0.069609 0.190310 -vn -0.375739 -0.155893 0.913519 -v 0.054903 0.067799 0.190154 -vn 0.375740 -0.155890 0.913520 -v 0.058803 0.067799 0.190154 -vn -0.375750 -0.304120 0.875399 -v 0.054903 0.066039 0.189701 -vn 0.375749 -0.304122 0.875398 -v 0.058803 0.066039 0.189701 -vn -0.375748 -0.444063 0.813402 -v 0.054903 0.064378 0.188965 -vn 0.375748 -0.444063 0.813402 -v 0.058803 0.064378 0.188965 -vn -0.375747 -0.571890 0.729216 -v 0.054903 0.062861 0.187966 -vn 0.375747 -0.571890 0.729216 -v 0.058803 0.062861 0.187966 -vn -0.375746 -0.684113 0.625143 -v 0.054903 0.061529 0.186731 -vn 0.375747 -0.684114 0.625143 -v 0.058803 0.061529 0.186731 -vn -0.375744 -0.777679 0.504016 -v 0.054903 0.060418 0.185293 -vn 0.371553 -0.776535 0.508863 -v 0.058803 0.060418 0.185293 -vn -0.375745 -0.850031 0.369139 -v 0.054903 0.059559 0.183692 -vn 0.375745 -0.850031 0.369139 -v 0.058803 0.059559 0.183692 -vn -0.375746 -0.899195 0.224196 -v 0.054903 0.058976 0.181972 -vn 0.976002 0.052681 0.211292 -v 0.059103 0.061639 0.180251 -vn 0.976000 0.151275 0.156649 -v 0.059103 0.061175 0.180508 -vn 0.916684 -0.398124 -0.034463 -v 0.059103 0.058989 0.178388 -vn 0.916684 -0.398366 0.031536 -v 0.059103 0.058983 0.180155 -vn 0.976002 0.209326 0.060023 -v 0.059103 0.060902 0.180963 -vn 0.916685 -0.387741 0.096674 -v 0.059103 0.059267 0.181899 -vn 0.976001 0.211296 -0.052682 -v 0.059103 0.060892 0.181494 -vn 0.916686 -0.366927 0.158274 -v 0.059103 0.059835 0.183573 -vn 0.976002 0.156642 -0.151270 -v 0.059103 0.061149 0.181958 -vn 0.899798 -0.388946 0.197699 -v 0.059103 0.060292 0.184500 -vn 0.976000 0.060026 -0.209334 -v 0.059103 0.061604 0.182231 -vn 0.976003 -0.052682 -0.211290 -v 0.059103 0.062135 0.182240 -vn 0.975999 -0.151278 -0.156655 -v 0.059103 0.062599 0.181983 -vn 0.722326 -0.433357 0.538931 -v 0.059103 0.066890 0.182865 -vn 0.976002 -0.209327 -0.060024 -v 0.059103 0.062872 0.181528 -vn 0.728543 -0.510046 0.457251 -v 0.059103 0.066347 0.182368 -vn 0.976002 -0.156645 0.151272 -v 0.059103 0.062624 0.180534 -vn 0.731173 -0.494025 -0.470452 -v 0.059103 0.066390 0.176207 -vn 0.731172 -0.595502 -0.332814 -v 0.059103 0.065721 0.177115 -vn 0.916685 -0.387020 -0.099521 -v 0.059103 0.059286 0.176646 -vn 0.916686 -0.365359 -0.161865 -v 0.059103 0.059866 0.174976 -vn 0.916683 -0.333738 -0.219796 -v 0.059103 0.060713 0.173425 -vn 0.976000 -0.060026 0.209334 -v 0.059103 0.062169 0.180260 -vn 0.976002 0.156647 -0.151271 -v 0.059103 0.066976 0.172260 -vn 0.976003 0.060021 -0.209321 -v 0.059103 0.067431 0.172533 -vn 0.731172 -0.659560 -0.174262 -v 0.059103 0.065298 0.178161 -vn 0.731172 -0.682177 -0.004762 -v 0.059103 0.065149 0.179279 -vn 0.976002 -0.211292 0.052682 -v 0.059103 0.062881 0.180998 -vn 0.731172 -0.661929 0.165037 -v 0.059103 0.065283 0.180399 -vn 0.731172 -0.600091 0.324467 -v 0.059103 0.065691 0.181451 -vn 0.719461 0.254055 -0.646399 -v 0.059103 0.071479 0.175199 -vn 0.730062 0.128897 -0.671114 -v 0.059103 0.070523 0.174896 -vn 0.976003 -0.151267 -0.156642 -v 0.059103 0.068426 0.172285 -vn 0.731174 -0.038080 -0.681128 -v 0.059103 0.069398 0.174817 -vn 0.976002 -0.052681 -0.211293 -v 0.059103 0.067962 0.172543 -vn 0.731174 -0.206274 -0.650258 -v 0.059103 0.068288 0.175021 -vn 0.731173 -0.361507 -0.578532 -v 0.059103 0.067265 0.175494 -vn 0.976002 -0.209327 -0.060023 -v 0.059103 0.068699 0.171831 -vn 0.976002 -0.211292 0.052682 -v 0.059103 0.068708 0.171300 -vn 0.917637 0.024427 -0.396668 -v 0.059103 0.069832 0.168612 -vn 0.976002 -0.156647 0.151271 -v 0.059103 0.068451 0.170836 -vn 0.976002 0.211292 -0.052682 -v 0.059103 0.066719 0.171796 -vn 0.916686 -0.293005 -0.271725 -v 0.059103 0.061804 0.172035 -vn 0.976002 0.209327 0.060023 -v 0.059103 0.066728 0.171265 -vn 0.916682 -0.128367 -0.378438 -v 0.059103 0.066212 0.169177 -vn 0.916689 -0.064322 -0.394390 -v 0.059103 0.067927 0.168750 -vn 0.976001 -0.060025 0.209329 -v 0.059103 0.067996 0.170563 -vn 0.919927 -0.013746 -0.391850 -v 0.059103 0.069688 0.168610 -vn 0.976001 0.052684 0.211295 -v 0.059103 0.067466 0.170553 -vn 0.976003 0.151267 0.156642 -v 0.059103 0.067002 0.170811 -vn 0.916684 -0.188902 -0.352146 -v 0.059103 0.064591 0.169881 -vn 0.916684 -0.244287 -0.316249 -v 0.059103 0.063108 0.170842 -vn 0.976002 0.156646 -0.151271 -v 0.059103 0.076674 0.178087 -vn 0.976001 0.060025 -0.209330 -v 0.059103 0.077129 0.178360 -vn 0.731172 0.632519 0.255553 -v 0.059103 0.073821 0.180996 -vn 0.731174 0.549092 0.404825 -v 0.059103 0.073271 0.181981 -vn 0.975999 -0.052684 -0.211305 -v 0.059103 0.077659 0.178370 -vn 0.916684 0.398124 0.034462 -v 0.059103 0.080309 0.180233 -vn 0.976002 -0.151270 -0.156643 -v 0.059103 0.078124 0.178112 -vn 0.916685 0.398364 -0.031537 -v 0.059103 0.080316 0.178466 -vn 0.976002 -0.209325 -0.060023 -v 0.059103 0.078397 0.177658 -vn 0.916684 0.387744 -0.096676 -v 0.059103 0.080031 0.176722 -vn 0.976002 -0.211294 0.052683 -v 0.059103 0.078406 0.177127 -vn 0.916686 0.366539 -0.159175 -v 0.059103 0.079464 0.175048 -vn 0.976003 -0.156643 0.151267 -v 0.059103 0.078149 0.176663 -vn 0.916685 0.335342 -0.217337 -v 0.059103 0.078628 0.173491 -vn 0.976003 -0.060020 0.209321 -v 0.059103 0.077694 0.176390 -vn 0.916685 0.294996 -0.269568 -v 0.059103 0.077548 0.172092 -vn 0.976002 0.052681 0.211294 -v 0.059103 0.077164 0.176380 -vn 0.916686 0.246600 -0.314443 -v 0.059103 0.076252 0.170891 -vn 0.720500 0.330549 -0.609604 -v 0.059103 0.071594 0.175252 -vn 0.731171 0.438506 -0.522592 -v 0.059103 0.072542 0.175863 -vn 0.916687 0.191481 -0.350742 -v 0.059103 0.074776 0.169919 -vn 0.976003 0.151266 0.156642 -v 0.059103 0.076699 0.176638 -vn 0.916682 0.131142 -0.377487 -v 0.059103 0.073161 0.169203 -vn 0.731172 0.676201 0.090224 -v 0.059103 0.074110 0.179906 -vn 0.731172 0.677394 -0.080775 -v 0.059103 0.074117 0.178778 -vn 0.976002 0.211292 -0.052682 -v 0.059103 0.076417 0.177623 -vn 0.731171 0.636026 -0.246699 -v 0.059103 0.073845 0.177683 -vn 0.976002 0.209327 0.060023 -v 0.059103 0.076426 0.177092 -vn 0.731172 0.554691 -0.397122 -v 0.059103 0.073308 0.176691 -vn 0.916686 0.067411 -0.393882 -v 0.059103 0.071449 0.168763 -vn 0.916683 0.387024 0.099522 -v 0.059103 0.080012 0.181975 -vn 0.916683 0.365366 0.161868 -v 0.059103 0.079432 0.183645 -vn 0.916685 0.333735 0.219793 -v 0.059103 0.078585 0.185196 -vn 0.916686 0.293005 0.271725 -v 0.059103 0.077495 0.186586 -vn 0.916684 0.244287 0.316249 -v 0.059103 0.076190 0.187778 -vn 0.976001 0.211299 -0.052683 -v 0.059103 0.070590 0.187321 -vn 0.976002 0.156643 -0.151269 -v 0.059103 0.070847 0.187785 -vn 0.916681 -0.067221 0.393926 -v 0.059103 0.067849 0.189858 -vn 0.916686 0.128362 0.378430 -v 0.059103 0.073086 0.189443 -vn 0.916685 0.064326 0.394400 -v 0.059103 0.071372 0.189871 -vn 0.976003 0.060020 -0.209321 -v 0.059103 0.071302 0.188058 -vn 0.731173 0.431165 0.528661 -v 0.059103 0.072493 0.182798 -vn 0.976001 -0.060028 0.209331 -v 0.059103 0.071867 0.186087 -vn 0.916685 -0.294996 0.269567 -v 0.059103 0.061750 0.186528 -vn 0.918768 -0.325871 0.222874 -v 0.059103 0.060670 0.185130 -vn 0.976002 0.209325 0.060023 -v 0.059103 0.070599 0.186790 -vn 0.916687 -0.001469 0.399603 -v 0.059103 0.069610 0.190010 -vn 0.724827 -0.353664 0.591226 -v 0.059103 0.067211 0.183093 -vn 0.731170 -0.215335 0.647319 -v 0.059103 0.068229 0.183580 -vn 0.976002 -0.052681 -0.211294 -v 0.059103 0.071833 0.188067 -vn 0.976003 -0.151266 -0.156642 -v 0.059103 0.072297 0.187810 -vn 0.916684 0.188902 0.352146 -v 0.059103 0.074707 0.188739 -vn 0.976002 -0.209327 -0.060023 -v 0.059103 0.072570 0.187355 -vn 0.976002 -0.211292 0.052682 -v 0.059103 0.072579 0.186825 -vn 0.976002 -0.156646 0.151271 -v 0.059103 0.072322 0.186361 -vn 0.976002 0.151271 0.156643 -v 0.059103 0.070873 0.186335 -vn 0.731174 -0.047588 0.680529 -v 0.059103 0.069335 0.183799 -vn 0.976002 0.052682 0.211291 -v 0.059103 0.071337 0.186078 -vn 0.731172 0.123150 0.670985 -v 0.059103 0.070461 0.183736 -vn 0.731173 0.286147 0.619279 -v 0.059103 0.071537 0.183395 -vn 0.916687 -0.131140 0.377475 -v 0.059103 0.066138 0.189418 -vn 0.916685 -0.191483 0.350746 -v 0.059103 0.064522 0.188702 -vn 0.916685 -0.246604 0.314444 -v 0.059103 0.063046 0.187730 -vn 0.375767 -0.863998 0.335122 -v 0.061003 0.065454 0.180938 -vn 0.411987 -0.795883 0.443663 -v 0.061003 0.065691 0.181451 -vn 0.381721 -0.756381 0.531204 -v 0.061003 0.065990 0.181930 -vn 0.410702 -0.660102 0.628959 -v 0.061003 0.066347 0.182368 -vn 0.381689 -0.601517 0.701777 -v 0.061003 0.066757 0.182758 -vn 0.411981 -0.483705 0.772206 -v 0.061003 0.067211 0.183093 -vn 0.381726 -0.406902 0.829889 -v 0.061003 0.067705 0.183369 -vn 0.411986 -0.276464 0.868237 -v 0.061003 0.068229 0.183580 -vn 0.381718 -0.187750 0.905009 -v 0.061003 0.068775 0.183725 -vn 0.390741 -0.064205 0.918259 -v 0.061003 0.069335 0.183799 -vn 0.375765 0.051735 0.925270 -v 0.061003 0.069900 0.183803 -vn 0.390740 0.166167 0.905379 -v 0.061003 0.070461 0.183736 -vn 0.375766 0.280210 0.883336 -v 0.061003 0.071010 0.183600 -vn 0.411989 0.392816 0.822169 -v 0.061003 0.071537 0.183395 -vn 0.381721 0.482662 0.788243 -v 0.061003 0.072034 0.183127 -vn 0.411989 0.584942 0.698647 -v 0.061003 0.072493 0.182798 -vn 0.381725 0.663525 0.643444 -v 0.061003 0.072908 0.182414 -vn 0.411992 0.740307 0.531232 -v 0.061003 0.073271 0.181981 -vn 0.381723 0.802699 0.458216 -v 0.061003 0.073577 0.181506 -vn 0.411984 0.849164 0.330438 -v 0.061003 0.073821 0.180996 -vn 0.381724 0.891434 0.244195 -v 0.061003 0.074000 0.180460 -vn 0.411987 0.904662 0.108875 -v 0.061003 0.074110 0.179906 -vn 0.381720 0.924159 0.014835 -v 0.061003 0.074149 0.179342 -vn 0.390743 0.914024 -0.108992 -v 0.061003 0.074117 0.178778 -vn 0.375771 0.899184 -0.224196 -v 0.061003 0.074015 0.178222 -vn 0.411987 0.845214 -0.340412 -v 0.061003 0.073845 0.177683 -vn 0.381725 0.816991 -0.432218 -v 0.061003 0.073608 0.177170 -vn 0.390744 0.748457 -0.535847 -v 0.061003 0.073308 0.176691 -vn 0.375767 0.679955 -0.629651 -v 0.061003 0.072951 0.176253 -vn 0.390738 0.591685 -0.705147 -v 0.061003 0.072542 0.175863 -vn 0.375759 0.502015 -0.778964 -v 0.061003 0.072087 0.175528 -vn 0.412691 0.383499 -0.826205 -v 0.061003 0.071594 0.175252 -vn 0.382860 0.298976 -0.874089 -v 0.061003 0.071070 0.175040 -vn 0.411987 0.165465 -0.896040 -v 0.061003 0.070523 0.174896 -vn 0.381725 0.072839 -0.921401 -v 0.061003 0.069963 0.174821 -vn 0.411994 -0.062575 -0.909035 -v 0.061003 0.069398 0.174817 -vn 0.381726 -0.158594 -0.910568 -v 0.061003 0.068837 0.174884 -vn 0.411994 -0.286673 -0.864916 -v 0.061003 0.068288 0.175021 -vn 0.381725 -0.380062 -0.842519 -v 0.061003 0.067762 0.175225 -vn 0.411991 -0.492762 -0.766452 -v 0.061003 0.067265 0.175494 -vn 0.381727 -0.577648 -0.721531 -v 0.061003 0.066805 0.175823 -vn 0.390744 -0.666598 -0.634796 -v 0.061003 0.066390 0.176207 -vn 0.375765 -0.745910 -0.549927 -v 0.061003 0.066027 0.176640 -vn 0.411984 -0.801053 -0.434261 -v 0.061003 0.065721 0.177115 -vn 0.381725 -0.853799 -0.353997 -v 0.061003 0.065477 0.177625 -vn 0.411989 -0.883882 -0.221398 -v 0.061003 0.065298 0.178161 -vn 0.381720 -0.915012 -0.130545 -v 0.061003 0.065189 0.178715 -vn 0.390740 -0.920479 -0.006426 -v 0.061003 0.065149 0.179279 -vn 0.375765 -0.920196 0.109726 -v 0.061003 0.065181 0.179843 -vn 0.377375 -0.898553 0.224032 -v 0.061003 0.065283 0.180399 -vn 0.917912 -0.367127 0.150519 -v 0.061303 0.065733 0.180829 -vn 0.746098 0.646057 -0.161081 -v 0.061303 0.066981 0.179976 -vn 0.746099 0.558748 -0.362127 -v 0.061303 0.067341 0.180806 -vn 0.746098 0.002445 -0.665832 -v 0.061303 0.069639 0.182060 -vn 0.915382 -0.086044 0.393283 -v 0.061303 0.068833 0.183430 -vn 0.746100 0.218507 -0.628959 -v 0.061303 0.068747 0.181908 -vn 0.915180 -0.179197 0.361019 -v 0.061303 0.067834 0.183098 -vn 0.746098 0.410893 -0.523932 -v 0.061303 0.067952 0.181474 -vn 0.915174 -0.263359 0.305119 -v 0.061303 0.066949 0.182528 -vn 0.915176 -0.330964 0.230035 -v 0.061303 0.066234 0.181755 -vn 0.746099 -0.556073 -0.366223 -v 0.061303 0.071946 0.180823 -vn 0.915178 0.287975 0.281992 -v 0.061303 0.072691 0.182207 -vn 0.746099 -0.407032 -0.526937 -v 0.061303 0.071330 0.181487 -vn 0.915176 0.208801 0.344755 -v 0.061303 0.071875 0.182872 -vn 0.746099 -0.213880 -0.630548 -v 0.061303 0.070533 0.181915 -vn 0.917663 0.122426 0.378030 -v 0.061303 0.070919 0.183314 -vn 0.917883 0.022155 0.396232 -v 0.061303 0.069884 0.183504 -vn 0.746099 -0.610732 0.265220 -v 0.061303 0.072172 0.178215 -vn 0.917665 0.384966 -0.098448 -v 0.061303 0.073724 0.178294 -vn 0.746098 -0.663759 0.052546 -v 0.061303 0.072391 0.179093 -vn 0.915383 0.402439 0.010824 -v 0.061303 0.073849 0.179340 -vn 0.746099 -0.644856 -0.165822 -v 0.061303 0.072313 0.179995 -vn 0.915178 0.388205 0.108377 -v 0.061303 0.073710 0.180383 -vn 0.915176 0.349060 0.201521 -v 0.061303 0.073315 0.181359 -vn 0.918423 -0.383850 0.095705 -v 0.061303 0.065574 0.180326 -vn 0.918141 -0.394045 0.041775 -v 0.061303 0.065479 0.179808 -vn 0.746099 0.663354 0.057421 -v 0.061303 0.066909 0.179073 -vn 0.915383 -0.397909 -0.061177 -v 0.061303 0.065486 0.178755 -vn 0.746099 0.608768 0.269700 -v 0.061303 0.067135 0.178196 -vn 0.915179 -0.371560 -0.156177 -v 0.061303 0.065755 0.177737 -vn 0.746100 0.488210 0.452754 -v 0.061303 0.067633 0.177440 -vn 0.746099 -0.112004 0.656347 -v 0.061303 0.070112 0.176600 -vn 0.915180 0.132536 -0.380631 -v 0.061303 0.070975 0.175325 -vn 0.746099 -0.319051 0.584417 -v 0.061303 0.070967 0.176897 -vn 0.917660 0.213244 -0.335302 -v 0.061303 0.071924 0.175780 -vn 0.746099 -0.491523 0.449156 -v 0.061303 0.071679 0.177455 -vn 0.917883 0.291181 -0.269638 -v 0.061303 0.072731 0.176457 -vn 0.915386 0.357867 -0.184390 -v 0.061303 0.073344 0.177313 -vn 0.917663 -0.321247 -0.233872 -v 0.061303 0.066269 0.176818 -vn 0.915386 -0.248179 -0.316978 -v 0.061303 0.066995 0.176056 -vn 0.746100 0.314744 0.586746 -v 0.061303 0.068349 0.176887 -vn 0.915177 -0.163943 -0.368203 -v 0.061303 0.067887 0.175498 -vn 0.746097 0.107177 0.657155 -v 0.061303 0.069206 0.176596 -vn 0.915178 -0.067224 -0.397405 -v 0.061303 0.068891 0.175179 -vn 0.915179 0.033717 -0.401635 -v 0.061303 0.069942 0.175121 -vn 0.671869 0.718669 -0.179185 -v 0.057603 0.066981 0.179976 -vn 0.671868 0.737911 0.063874 -v 0.057603 0.066909 0.179073 -vn 0.671869 0.677189 0.300012 -v 0.057603 0.067135 0.178196 -vn 0.671868 0.543083 0.503641 -v 0.057603 0.067633 0.177440 -vn 0.671868 0.350120 0.652694 -v 0.057603 0.068349 0.176887 -vn 0.671870 0.119222 0.731011 -v 0.057603 0.069206 0.176596 -vn 0.671868 -0.124593 0.730116 -v 0.057603 0.070112 0.176600 -vn 0.671869 -0.354910 0.650101 -v 0.057603 0.070967 0.176897 -vn 0.671868 -0.546768 0.499638 -v 0.057603 0.071679 0.177455 -vn 0.671868 -0.679375 0.295029 -v 0.057603 0.072172 0.178215 -vn 0.671869 -0.738360 0.058452 -v 0.057603 0.072391 0.179093 -vn 0.671868 -0.717334 -0.184459 -v 0.057603 0.072313 0.179995 -vn 0.671868 -0.618572 -0.407384 -v 0.057603 0.071946 0.180823 -vn 0.671869 -0.452779 -0.586160 -v 0.057603 0.071330 0.181487 -vn 0.671868 -0.237919 -0.701418 -v 0.057603 0.070533 0.181915 -vn 0.671870 0.002719 -0.740664 -v 0.057603 0.069639 0.182060 -vn 0.671867 0.243066 -0.699652 -v 0.057603 0.068747 0.181908 -vn 0.671869 0.457073 -0.582817 -v 0.057603 0.067952 0.181474 -vn 0.671868 0.621549 -0.402829 -v 0.057603 0.067341 0.180806 -vn 0.765146 0.226691 -0.602629 -v 0.057603 0.069209 0.180480 -vn 0.765147 0.480784 -0.428249 -v 0.057603 0.068716 0.180142 -vn 0.765146 0.624732 -0.155760 -v 0.057603 0.068436 0.179613 -vn 0.765143 0.625563 0.152405 -v 0.057603 0.068435 0.179015 -vn 0.765143 -0.643858 0.001731 -v 0.057603 0.070899 0.179307 -vn 0.765149 -0.570906 -0.297681 -v 0.057603 0.070758 0.179888 -vn 0.765145 -0.367170 -0.528903 -v 0.057603 0.070362 0.180337 -vn 0.765143 -0.079327 -0.638955 -v 0.057603 0.069803 0.180551 -vn 0.765144 -0.364329 0.530867 -v 0.057603 0.070356 0.178280 -vn 0.765148 -0.569299 0.300745 -v 0.057603 0.070754 0.178727 -vn 0.765142 0.229930 0.601406 -v 0.057603 0.069203 0.178143 -vn 0.765148 -0.075890 0.639366 -v 0.057603 0.069796 0.178069 -vn 0.765150 0.483074 0.425658 -v 0.057603 0.068711 0.178484 -vn -0.765146 0.624732 -0.155760 -v 0.056103 0.068436 0.179613 -vn -0.765143 0.625563 0.152405 -v 0.056103 0.068435 0.179015 -vn -0.765150 0.483074 0.425658 -v 0.056103 0.068711 0.178484 -vn -0.765142 0.229930 0.601406 -v 0.056103 0.069203 0.178143 -vn -0.765148 -0.075890 0.639366 -v 0.056103 0.069796 0.178069 -vn -0.765143 -0.364329 0.530867 -v 0.056103 0.070356 0.178280 -vn -0.765148 -0.569299 0.300745 -v 0.056103 0.070754 0.178727 -vn -0.765143 -0.643858 0.001731 -v 0.056103 0.070899 0.179307 -vn -0.765149 -0.570906 -0.297681 -v 0.056103 0.070758 0.179888 -vn -0.765146 -0.367170 -0.528903 -v 0.056103 0.070362 0.180337 -vn -0.765143 -0.079327 -0.638955 -v 0.056103 0.069803 0.180551 -vn -0.765146 0.226691 -0.602629 -v 0.056103 0.069209 0.180480 -vn -0.765147 0.480783 -0.428249 -v 0.056103 0.068716 0.180142 -vn 0.539396 0.809432 0.232102 -v 0.058973 0.061118 0.181025 -vn 0.539391 0.584937 0.605728 -v 0.058973 0.061331 0.180670 -vn 0.539395 0.203713 0.817039 -v 0.058973 0.061693 0.180470 -vn 0.539390 -0.232100 0.809437 -v 0.058973 0.062107 0.180477 -vn 0.539394 -0.605723 0.584939 -v 0.058973 0.062462 0.180690 -vn 0.539396 -0.817040 0.203709 -v 0.058973 0.062663 0.181052 -vn 0.539395 -0.809434 -0.232096 -v 0.058973 0.062656 0.181466 -vn 0.539386 -0.584942 -0.605727 -v 0.058973 0.062443 0.181821 -vn 0.539395 -0.203713 -0.817040 -v 0.058973 0.062080 0.182022 -vn 0.539390 0.232102 -0.809436 -v 0.058973 0.061666 0.182015 -vn 0.539397 0.605717 -0.584943 -v 0.058973 0.061311 0.181801 -vn 0.539395 0.817040 -0.203713 -v 0.058973 0.061111 0.181439 -vn -0.539397 -0.817040 0.203707 -v 0.054733 0.062663 0.181052 -vn -0.539395 -0.605722 0.584939 -v 0.054733 0.062462 0.180690 -vn -0.539389 -0.232097 0.809438 -v 0.054733 0.062107 0.180477 -vn -0.539395 0.203709 0.817041 -v 0.054733 0.061693 0.180470 -vn -0.539391 0.584939 0.605726 -v 0.054733 0.061331 0.180670 -vn -0.539396 0.809432 0.232104 -v 0.054733 0.061118 0.181025 -vn -0.539395 0.817039 -0.203714 -v 0.054733 0.061111 0.181439 -vn -0.539397 0.605719 -0.584941 -v 0.054733 0.061311 0.181801 -vn -0.539390 0.232098 -0.809437 -v 0.054733 0.061666 0.182015 -vn -0.539396 -0.203706 -0.817041 -v 0.054733 0.062080 0.182022 -vn -0.539386 -0.584948 -0.605721 -v 0.054733 0.062443 0.181821 -vn -0.539393 -0.809435 -0.232100 -v 0.054733 0.062656 0.181466 -vn 0.539396 0.809431 0.232105 -v 0.058973 0.070816 0.186852 -vn 0.539396 0.584946 0.605714 -v 0.058973 0.071029 0.186497 -vn 0.539401 0.203721 0.817034 -v 0.058973 0.071391 0.186297 -vn 0.539392 -0.232111 0.809432 -v 0.058973 0.071805 0.186304 -vn 0.539393 -0.605728 0.584935 -v 0.058973 0.072160 0.186517 -vn 0.539397 -0.817039 0.203711 -v 0.058973 0.072361 0.186879 -vn 0.539396 -0.809433 -0.232100 -v 0.058973 0.072354 0.187293 -vn 0.539401 -0.584935 -0.605720 -v 0.058973 0.072140 0.187648 -vn 0.539397 -0.203706 -0.817040 -v 0.058973 0.071778 0.187849 -vn 0.539402 0.232097 -0.809430 -v 0.058973 0.071364 0.187842 -vn 0.539400 0.605714 -0.584943 -v 0.058973 0.071009 0.187628 -vn 0.539394 0.817041 -0.203714 -v 0.058973 0.070808 0.187266 -vn -0.539397 -0.817039 0.203710 -v 0.054733 0.072361 0.186879 -vn -0.539394 -0.605728 0.584933 -v 0.054733 0.072160 0.186517 -vn -0.539392 -0.232107 0.809434 -v 0.054733 0.071805 0.186304 -vn -0.539399 0.203721 0.817035 -v 0.054733 0.071391 0.186297 -vn -0.539396 0.584944 0.605717 -v 0.054733 0.071029 0.186497 -vn -0.539398 0.809430 0.232105 -v 0.054733 0.070816 0.186852 -vn -0.539393 0.817040 -0.203719 -v 0.054733 0.070808 0.187266 -vn -0.539398 0.605717 -0.584942 -v 0.054733 0.071009 0.187628 -vn -0.539402 0.232100 -0.809429 -v 0.054733 0.071364 0.187842 -vn -0.539398 -0.203708 -0.817039 -v 0.054733 0.071778 0.187849 -vn -0.539401 -0.584934 -0.605721 -v 0.054733 0.072140 0.187648 -vn -0.539396 -0.809433 -0.232099 -v 0.054733 0.072354 0.187293 -vn 0.539396 0.809433 0.232100 -v 0.058973 0.076643 0.177154 -vn 0.539401 0.584935 0.605720 -v 0.058973 0.076856 0.176800 -vn 0.539397 0.203706 0.817040 -v 0.058973 0.077218 0.176599 -vn 0.539402 -0.232097 0.809430 -v 0.058973 0.077632 0.176606 -vn 0.539401 -0.605719 0.584937 -v 0.058973 0.077987 0.176819 -vn 0.539396 -0.817038 0.203717 -v 0.058973 0.078188 0.177181 -vn 0.539399 -0.809431 -0.232099 -v 0.058973 0.078181 0.177596 -vn 0.539396 -0.584946 -0.605714 -v 0.058973 0.077967 0.177950 -vn 0.539389 -0.203719 -0.817042 -v 0.058973 0.077605 0.178151 -vn 0.539390 0.232108 -0.809435 -v 0.058973 0.077191 0.178144 -vn 0.539393 0.605728 -0.584935 -v 0.058973 0.076836 0.177931 -vn 0.539397 0.817039 -0.203711 -v 0.058973 0.076635 0.177569 -vn -0.539396 -0.817038 0.203717 -v 0.054733 0.078188 0.177181 -vn -0.539400 -0.605719 0.584937 -v 0.054733 0.077987 0.176819 -vn -0.539402 -0.232100 0.809429 -v 0.054733 0.077632 0.176606 -vn -0.539398 0.203708 0.817039 -v 0.054733 0.077218 0.176599 -vn -0.539401 0.584934 0.605721 -v 0.054733 0.076856 0.176800 -vn -0.539396 0.809433 0.232099 -v 0.054733 0.076643 0.177154 -vn -0.539397 0.817039 -0.203710 -v 0.054733 0.076635 0.177569 -vn -0.539394 0.605728 -0.584933 -v 0.054733 0.076836 0.177931 -vn -0.539392 0.232107 -0.809434 -v 0.054733 0.077191 0.178144 -vn -0.539387 -0.203726 -0.817042 -v 0.054733 0.077605 0.178151 -vn -0.539394 -0.584942 -0.605720 -v 0.054733 0.077967 0.177950 -vn -0.539399 -0.809432 -0.232097 -v 0.054733 0.078181 0.177596 -vn 0.539396 0.809433 0.232100 -v 0.058973 0.066945 0.171328 -vn 0.539400 0.584939 0.605718 -v 0.058973 0.067158 0.170973 -vn 0.539395 0.203725 0.817037 -v 0.058973 0.067520 0.170772 -vn 0.539396 -0.232100 0.809433 -v 0.058973 0.067934 0.170779 -vn 0.539392 -0.605731 0.584933 -v 0.058973 0.068289 0.170992 -vn 0.539397 -0.817039 0.203711 -v 0.058973 0.068490 0.171354 -vn 0.539396 -0.809433 -0.232100 -v 0.058973 0.068483 0.171769 -vn 0.539400 -0.584939 -0.605718 -v 0.058973 0.068269 0.172123 -vn 0.539398 -0.203709 -0.817039 -v 0.058973 0.067907 0.172324 -vn 0.539402 0.232097 -0.809430 -v 0.058973 0.067493 0.172317 -vn 0.539397 0.605722 -0.584937 -v 0.058973 0.067138 0.172104 -vn 0.539397 0.817039 -0.203711 -v 0.058973 0.066938 0.171742 -vn -0.539397 -0.817039 0.203710 -v 0.054733 0.068490 0.171354 -vn -0.539394 -0.605732 0.584931 -v 0.054733 0.068289 0.170992 -vn -0.539396 -0.232094 0.809435 -v 0.054733 0.067934 0.170779 -vn -0.539393 0.203723 0.817039 -v 0.054733 0.067520 0.170772 -vn -0.539400 0.584937 0.605719 -v 0.054733 0.067158 0.170973 -vn -0.539396 0.809433 0.232099 -v 0.054733 0.066945 0.171328 -vn -0.539397 0.817039 -0.203710 -v 0.054733 0.066938 0.171742 -vn -0.539396 0.605721 -0.584940 -v 0.054733 0.067138 0.172104 -vn -0.539402 0.232101 -0.809429 -v 0.054733 0.067493 0.172317 -vn -0.539398 -0.203711 -0.817038 -v 0.054733 0.067907 0.172324 -vn -0.539400 -0.584937 -0.605719 -v 0.054733 0.068269 0.172123 -vn -0.539396 -0.809433 -0.232099 -v 0.054733 0.068483 0.171769 -# 3504 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 6//6 16//16 4//4 -f 4//4 16//16 17//17 -f 4//4 17//17 3//3 -f 3//3 17//17 11//11 -f 15//15 13//13 18//18 -f 18//18 13//13 19//19 -f 18//18 19//19 20//20 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 24//24 27//27 26//26 -f 26//26 27//27 28//28 -f 26//26 28//28 29//29 -f 29//29 28//28 30//30 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 39//39 12//12 31//31 -f 31//31 12//12 40//40 -f 31//31 40//40 32//32 -f 30//30 13//13 29//29 -f 29//29 13//13 12//12 -f 29//29 12//12 41//41 -f 41//41 12//12 39//39 -f 42//42 43//43 44//44 -f 44//44 43//43 45//45 -f 44//44 45//45 5//5 -f 5//5 45//45 46//46 -f 5//5 46//46 6//6 -f 10//10 47//47 11//11 -f 11//11 47//47 48//48 -f 11//11 48//48 3//3 -f 3//3 48//48 49//49 -f 3//3 49//49 50//50 -f 50//50 49//49 51//51 -f 50//50 51//51 52//52 -f 52//52 51//51 53//53 -f 52//52 53//53 38//38 -f 38//38 53//53 54//54 -f 38//38 54//54 37//37 -f 37//37 54//54 55//55 -f 37//37 55//55 56//56 -f 56//56 55//55 57//57 -f 56//56 57//57 58//58 -f 20//20 59//59 18//18 -f 18//18 59//59 3//3 -f 18//18 3//3 60//60 -f 60//60 3//3 50//50 -f 59//59 61//61 3//3 -f 3//3 61//61 62//62 -f 3//3 62//62 21//21 -f 21//21 62//62 63//63 -f 21//21 63//63 22//22 -f 7//7 64//64 8//8 -f 8//8 64//64 65//65 -f 8//8 65//65 66//66 -f 66//66 65//65 67//67 -f 66//66 67//67 43//43 -f 43//43 67//67 68//68 -f 43//43 68//68 45//45 -f 57//57 69//69 58//58 -f 58//58 69//69 70//70 -f 58//58 70//70 71//71 -f 71//71 70//70 8//8 -f 71//71 8//8 72//72 -f 72//72 8//8 66//66 -f 73//73 74//74 75//75 -f 76//76 77//77 78//78 -f 78//78 77//77 73//73 -f 79//79 80//80 81//81 -f 82//82 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 86//86 87//87 88//88 -f 89//89 90//90 91//91 -f 78//78 92//92 93//93 -f 78//78 94//94 95//95 -f 96//96 81//81 97//97 -f 97//97 81//81 80//80 -f 97//97 80//80 74//74 -f 74//74 80//80 98//98 -f 74//74 98//98 75//75 -f 99//99 100//100 101//101 -f 102//102 103//103 88//88 -f 78//78 95//95 104//104 -f 95//95 105//105 104//104 -f 104//104 105//105 106//106 -f 104//104 106//106 107//107 -f 107//107 106//106 82//82 -f 107//107 82//82 108//108 -f 108//108 82//82 84//84 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 112//112 86//86 111//111 -f 111//111 86//86 88//88 -f 111//111 88//88 113//113 -f 113//113 88//88 103//103 -f 114//114 115//115 116//116 -f 116//116 115//115 117//117 -f 116//116 117//117 118//118 -f 118//118 117//117 119//119 -f 118//118 119//119 120//120 -f 73//73 75//75 78//78 -f 78//78 75//75 121//121 -f 78//78 121//121 92//92 -f 94//94 78//78 122//122 -f 122//122 78//78 93//93 -f 122//122 93//93 123//123 -f 123//123 93//93 124//124 -f 123//123 124//124 125//125 -f 91//91 99//99 89//89 -f 89//89 99//99 101//101 -f 89//89 101//101 126//126 -f 126//126 101//101 102//102 -f 126//126 102//102 124//124 -f 124//124 102//102 88//88 -f 124//124 88//88 125//125 -f 79//79 81//81 127//127 -f 127//127 81//81 128//128 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 89//89 -f 89//89 130//130 131//131 -f 89//89 131//131 90//90 -f 119//119 132//132 120//120 -f 120//120 132//132 133//133 -f 120//120 133//133 134//134 -f 134//134 133//133 130//130 -f 134//134 130//130 135//135 -f 135//135 130//130 128//128 -f 111//111 136//136 109//109 -f 109//109 136//136 137//137 -f 109//109 137//137 138//138 -f 138//138 137//137 139//139 -f 138//138 139//139 114//114 -f 114//114 139//139 140//140 -f 114//114 140//140 115//115 -f 115//115 140//140 141//141 -f 115//115 141//141 142//142 -f 142//142 141//141 143//143 -f 142//142 143//143 100//100 -f 100//100 143//143 144//144 -f 100//100 144//144 101//101 -f 114//114 116//116 37//37 -f 37//37 116//116 35//35 -f 26//26 29//29 81//81 -f 81//81 29//29 128//128 -f 74//74 73//73 21//21 -f 21//21 73//73 3//3 -f 1//1 3//3 77//77 -f 77//77 3//3 73//73 -f 2//2 1//1 76//76 -f 76//76 1//1 77//77 -f 4//4 2//2 78//78 -f 78//78 2//2 76//76 -f 5//5 4//4 104//104 -f 104//104 4//4 78//78 -f 84//84 86//86 43//43 -f 43//43 86//86 66//66 -f 57//57 139//139 69//69 -f 69//69 139//139 137//137 -f 69//69 137//137 70//70 -f 70//70 137//137 136//136 -f 70//70 136//136 8//8 -f 8//8 136//136 111//111 -f 8//8 111//111 10//10 -f 10//10 111//111 113//113 -f 10//10 113//113 47//47 -f 47//47 113//113 103//103 -f 47//47 103//103 48//48 -f 48//48 103//103 102//102 -f 48//48 102//102 49//49 -f 49//49 102//102 101//101 -f 49//49 101//101 51//51 -f 51//51 101//101 144//144 -f 51//51 144//144 53//53 -f 53//53 144//144 143//143 -f 53//53 143//143 54//54 -f 54//54 143//143 141//141 -f 54//54 141//141 55//55 -f 55//55 141//141 140//140 -f 55//55 140//140 57//57 -f 57//57 140//140 139//139 -f 64//64 88//88 65//65 -f 65//65 88//88 87//87 -f 65//65 87//87 67//67 -f 67//67 87//87 85//85 -f 67//67 85//85 68//68 -f 68//68 85//85 83//83 -f 68//68 83//83 45//45 -f 45//45 83//83 82//82 -f 45//45 82//82 46//46 -f 46//46 82//82 106//106 -f 46//46 106//106 6//6 -f 6//6 106//106 105//105 -f 6//6 105//105 16//16 -f 16//16 105//105 95//95 -f 16//16 95//95 17//17 -f 17//17 95//95 94//94 -f 17//17 94//94 11//11 -f 11//11 94//94 122//122 -f 11//11 122//122 9//9 -f 9//9 122//122 123//123 -f 9//9 123//123 7//7 -f 7//7 123//123 125//125 -f 7//7 125//125 64//64 -f 64//64 125//125 88//88 -f 13//13 89//89 19//19 -f 19//19 89//89 126//126 -f 19//19 126//126 20//20 -f 20//20 126//126 124//124 -f 20//20 124//124 59//59 -f 59//59 124//124 93//93 -f 59//59 93//93 61//61 -f 61//61 93//93 92//92 -f 61//61 92//92 62//62 -f 62//62 92//92 121//121 -f 62//62 121//121 63//63 -f 63//63 121//121 75//75 -f 63//63 75//75 22//22 -f 22//22 75//75 98//98 -f 22//22 98//98 24//24 -f 24//24 98//98 80//80 -f 24//24 80//80 27//27 -f 27//27 80//80 79//79 -f 27//27 79//79 28//28 -f 28//28 79//79 127//127 -f 28//28 127//127 30//30 -f 30//30 127//127 129//129 -f 30//30 129//129 13//13 -f 13//13 129//129 89//89 -f 34//34 119//119 36//36 -f 36//36 119//119 117//117 -f 36//36 117//117 38//38 -f 38//38 117//117 115//115 -f 38//38 115//115 52//52 -f 52//52 115//115 142//142 -f 52//52 142//142 50//50 -f 50//50 142//142 100//100 -f 50//50 100//100 60//60 -f 60//60 100//100 99//99 -f 60//60 99//99 18//18 -f 18//18 99//99 91//91 -f 18//18 91//91 15//15 -f 15//15 91//91 90//90 -f 15//15 90//90 14//14 -f 14//14 90//90 131//131 -f 14//14 131//131 12//12 -f 12//12 131//131 130//130 -f 12//12 130//130 40//40 -f 40//40 130//130 133//133 -f 40//40 133//133 32//32 -f 32//32 133//133 132//132 -f 32//32 132//132 34//34 -f 34//34 132//132 119//119 -f 66//66 86//86 112//112 -f 66//66 112//112 72//72 -f 72//72 112//112 110//110 -f 72//72 110//110 71//71 -f 71//71 110//110 109//109 -f 71//71 109//109 58//58 -f 58//58 109//109 138//138 -f 58//58 138//138 56//56 -f 56//56 138//138 114//114 -f 56//56 114//114 37//37 -f 35//35 116//116 118//118 -f 35//35 118//118 33//33 -f 33//33 118//118 120//120 -f 33//33 120//120 31//31 -f 31//31 120//120 134//134 -f 31//31 134//134 39//39 -f 39//39 134//134 135//135 -f 39//39 135//135 41//41 -f 41//41 135//135 128//128 -f 41//41 128//128 29//29 -f 5//5 104//104 107//107 -f 5//5 107//107 44//44 -f 44//44 107//107 108//108 -f 44//44 108//108 42//42 -f 42//42 108//108 84//84 -f 42//42 84//84 43//43 -f 26//26 81//81 96//96 -f 26//26 96//96 25//25 -f 25//25 96//96 97//97 -f 25//25 97//97 23//23 -f 23//23 97//97 74//74 -f 23//23 74//74 21//21 -f 145//145 146//146 147//147 -f 148//148 149//149 150//150 -f 151//151 152//152 153//153 -f 154//154 155//155 156//156 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 155//155 165//165 156//156 -f 156//156 165//165 166//166 -f 156//156 166//166 157//157 -f 157//157 166//166 167//167 -f 157//157 167//167 158//158 -f 156//156 168//168 154//154 -f 154//154 168//168 169//169 -f 154//154 169//169 170//170 -f 170//170 169//169 171//171 -f 170//170 171//171 172//172 -f 172//172 171//171 173//173 -f 172//172 173//173 164//164 -f 164//164 173//173 174//174 -f 164//164 174//174 163//163 -f 156//156 175//175 168//168 -f 168//168 175//175 176//176 -f 168//168 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 180//180 -f 180//180 184//184 185//185 -f 180//180 185//185 186//186 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 187//187 189//189 186//186 -f 186//186 189//189 198//198 -f 186//186 198//198 180//180 -f 180//180 198//198 199//199 -f 180//180 199//199 179//179 -f 200//200 190//190 201//201 -f 201//201 190//190 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 188//188 191//191 190//190 -f 190//190 191//191 193//193 -f 190//190 193//193 202//202 -f 202//202 193//193 206//206 -f 202//202 206//206 204//204 -f 204//204 206//206 207//207 -f 208//208 209//209 145//145 -f 145//145 209//209 210//210 -f 211//211 207//207 212//212 -f 212//212 207//207 213//213 -f 212//212 213//213 214//214 -f 214//214 213//213 215//215 -f 216//216 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 219//219 221//221 220//220 -f 220//220 221//221 222//222 -f 220//220 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 230//230 -f 230//230 229//229 231//231 -f 226//226 232//232 227//227 -f 227//227 232//232 233//233 -f 227//227 233//233 217//217 -f 234//234 153//153 235//235 -f 235//235 153//153 236//236 -f 235//235 236//236 237//237 -f 233//233 238//238 217//217 -f 217//217 238//238 239//239 -f 217//217 239//239 219//219 -f 219//219 239//239 240//240 -f 219//219 240//240 241//241 -f 241//241 240//240 237//237 -f 241//241 237//237 242//242 -f 242//242 237//237 236//236 -f 151//151 153//153 243//243 -f 243//243 153//153 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 249//249 -f 249//249 248//248 150//150 -f 150//150 248//248 250//250 -f 150//150 250//250 148//148 -f 251//251 252//252 248//248 -f 248//248 252//252 253//253 -f 248//248 253//253 254//254 -f 255//255 250//250 256//256 -f 256//256 250//250 248//248 -f 256//256 248//248 257//257 -f 257//257 248//248 254//254 -f 258//258 259//259 251//251 -f 251//251 259//259 260//260 -f 251//251 260//260 252//252 -f 257//257 261//261 256//256 -f 256//256 261//261 262//262 -f 256//256 262//262 263//263 -f 263//263 262//262 264//264 -f 264//264 265//265 263//263 -f 263//263 265//265 266//266 -f 263//263 266//266 258//258 -f 258//258 266//266 267//267 -f 258//258 267//267 259//259 -f 268//268 269//269 270//270 -f 270//270 271//271 268//268 -f 268//268 271//271 272//272 -f 268//268 272//272 246//246 -f 246//246 272//272 273//273 -f 246//246 273//273 274//274 -f 274//274 275//275 246//246 -f 246//246 275//275 276//276 -f 246//246 276//276 248//248 -f 248//248 276//276 277//277 -f 248//248 277//277 251//251 -f 275//275 278//278 276//276 -f 276//276 278//278 279//279 -f 276//276 279//279 280//280 -f 280//280 279//279 281//281 -f 281//281 282//282 280//280 -f 280//280 282//282 283//283 -f 280//280 283//283 269//269 -f 269//269 283//283 284//284 -f 269//269 284//284 270//270 -f 285//285 286//286 287//287 -f 288//288 289//289 290//290 -f 290//290 289//289 291//291 -f 290//290 291//291 292//292 -f 292//292 291//291 293//293 -f 234//234 231//231 153//153 -f 153//153 231//231 229//229 -f 153//153 229//229 244//244 -f 244//244 229//229 294//294 -f 244//244 294//294 285//285 -f 287//287 295//295 285//285 -f 285//285 295//295 296//296 -f 285//285 296//296 244//244 -f 244//244 296//296 297//297 -f 244//244 297//297 298//298 -f 298//298 293//293 244//244 -f 244//244 293//293 291//291 -f 244//244 291//291 246//246 -f 246//246 291//291 299//299 -f 246//246 299//299 268//268 -f 288//288 300//300 289//289 -f 289//289 300//300 301//301 -f 289//289 301//301 286//286 -f 286//286 301//301 302//302 -f 286//286 302//302 287//287 -f 211//211 303//303 207//207 -f 207//207 303//303 304//304 -f 207//207 304//304 204//204 -f 204//204 304//304 305//305 -f 204//204 305//305 306//306 -f 306//306 305//305 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 309//309 -f 308//308 309//309 310//310 -f 310//310 309//309 208//208 -f 310//310 208//208 224//224 -f 224//224 208//208 145//145 -f 224//224 145//145 225//225 -f 225//225 145//145 147//147 -f 311//311 146//146 213//213 -f 213//213 146//146 145//145 -f 213//213 145//145 215//215 -f 215//215 145//145 210//210 -f 312//312 313//313 183//183 -f 183//183 313//313 195//195 -f 183//183 195//195 181//181 -f 181//181 195//195 197//197 -f 314//314 175//175 315//315 -f 315//315 175//175 156//156 -f 315//315 156//156 316//316 -f 316//316 156//156 157//157 -f 317//317 318//318 319//319 -f 320//320 321//321 322//322 -f 323//323 324//324 325//325 -f 325//325 324//324 322//322 -f 326//326 327//327 328//328 -f 328//328 327//327 323//323 -f 328//328 323//323 329//329 -f 329//329 323//323 325//325 -f 160//160 161//161 159//159 -f 159//159 161//161 163//163 -f 159//159 163//163 330//330 -f 330//330 163//163 319//319 -f 330//330 319//319 331//331 -f 331//331 319//319 318//318 -f 331//331 318//318 320//320 -f 320//320 318//318 332//332 -f 320//320 332//332 321//321 -f 326//326 333//333 327//327 -f 327//327 333//333 334//334 -f 327//327 334//334 319//319 -f 319//319 334//334 335//335 -f 319//319 335//335 317//317 -f 322//322 324//324 320//320 -f 320//320 324//324 336//336 -f 320//320 336//336 337//337 -f 338//338 339//339 327//327 -f 340//340 341//341 342//342 -f 342//342 341//341 343//343 -f 344//344 345//345 346//346 -f 346//346 345//345 343//343 -f 340//340 342//342 339//339 -f 339//339 342//342 347//347 -f 339//339 347//347 327//327 -f 327//327 347//347 348//348 -f 327//327 348//348 323//323 -f 346//346 349//349 344//344 -f 344//344 349//349 350//350 -f 344//344 350//350 351//351 -f 351//351 350//350 352//352 -f 352//352 353//353 351//351 -f 351//351 353//353 354//354 -f 351//351 354//354 327//327 -f 327//327 354//354 355//355 -f 327//327 355//355 338//338 -f 343//343 345//345 342//342 -f 342//342 345//345 356//356 -f 342//342 356//356 357//357 -f 358//358 359//359 351//351 -f 360//360 361//361 362//362 -f 363//363 364//364 365//365 -f 365//365 364//364 360//360 -f 365//365 360//360 351//351 -f 366//366 367//367 360//360 -f 360//360 367//367 368//368 -f 360//360 368//368 369//369 -f 370//370 371//371 372//372 -f 372//372 371//371 373//373 -f 360//360 362//362 366//366 -f 366//366 362//362 374//374 -f 366//366 374//374 373//373 -f 369//369 375//375 360//360 -f 360//360 375//375 376//376 -f 360//360 376//376 351//351 -f 351//351 376//376 377//377 -f 351//351 377//377 358//358 -f 370//370 372//372 359//359 -f 359//359 372//372 378//378 -f 359//359 378//378 351//351 -f 351//351 378//378 379//379 -f 351//351 379//379 344//344 -f 373//373 374//374 372//372 -f 372//372 374//374 380//380 -f 372//372 380//380 381//381 -f 163//163 382//382 383//383 -f 384//384 385//385 386//386 -f 386//386 385//385 365//365 -f 386//386 365//365 387//387 -f 387//387 365//365 351//351 -f 387//387 351//351 388//388 -f 388//388 351//351 327//327 -f 388//388 327//327 383//383 -f 383//383 327//327 319//319 -f 383//383 319//319 163//163 -f 389//389 390//390 200//200 -f 389//389 200//200 391//391 -f 391//391 200//200 201//201 -f 391//391 201//201 203//203 -f 392//392 393//393 394//394 -f 395//395 396//396 397//397 -f 396//396 398//398 397//397 -f 397//397 398//398 399//399 -f 397//397 399//399 400//400 -f 401//401 402//402 397//397 -f 397//397 402//402 392//392 -f 392//392 394//394 397//397 -f 397//397 394//394 403//403 -f 397//397 403//403 395//395 -f 404//404 405//405 406//406 -f 406//406 405//405 400//400 -f 406//406 400//400 407//407 -f 407//407 400//400 399//399 -f 37//37 35//35 408//408 -f 408//408 35//35 409//409 -f 410//410 37//37 411//411 -f 411//411 37//37 408//408 -f 411//411 408//408 412//412 -f 412//412 408//408 413//413 -f 386//386 387//387 414//414 -f 386//386 414//414 415//415 -f 416//416 417//417 418//418 -f 419//419 420//420 421//421 -f 421//421 420//420 422//422 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 423//423 424//424 425//425 -f 425//425 424//424 426//426 -f 425//425 426//426 427//427 -f 427//427 426//426 428//428 -f 429//429 430//430 431//431 -f 431//431 430//430 432//432 -f 431//431 432//432 433//433 -f 433//433 432//432 434//434 -f 433//433 434//434 435//435 -f 435//435 434//434 436//436 -f 436//436 437//437 435//435 -f 435//435 437//437 438//438 -f 435//435 438//438 439//439 -f 439//439 438//438 440//440 -f 437//437 441//441 438//438 -f 438//438 441//441 442//442 -f 438//438 442//442 419//419 -f 419//419 442//442 443//443 -f 419//419 443//443 420//420 -f 431//431 444//444 429//429 -f 429//429 444//444 445//445 -f 429//429 445//445 417//417 -f 417//417 445//445 446//446 -f 417//417 446//446 418//418 -f 447//447 448//448 449//449 -f 449//449 448//448 450//450 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 418//418 -f 418//418 452//452 453//453 -f 418//418 453//453 416//416 -f 454//454 455//455 426//426 -f 426//426 455//455 456//456 -f 426//426 456//456 428//428 -f 454//454 457//457 455//455 -f 455//455 457//457 458//458 -f 455//455 458//458 414//414 -f 414//414 458//458 459//459 -f 414//414 459//459 460//460 -f 460//460 461//461 414//414 -f 414//414 461//461 447//447 -f 414//414 447//447 415//415 -f 415//415 447//447 449//449 -f 35//35 33//33 409//409 -f 409//409 33//33 462//462 -f 462//462 33//33 463//463 -f 463//463 33//33 31//31 -f 463//463 31//31 464//464 -f 464//464 31//31 465//465 -f 465//465 31//31 39//39 -f 465//465 39//39 466//466 -f 466//466 39//39 467//467 -f 467//467 39//39 41//41 -f 467//467 41//41 468//468 -f 469//469 470//470 471//471 -f 468//468 41//41 471//471 -f 471//471 41//41 29//29 -f 471//471 29//29 469//469 -f 472//472 473//473 474//474 -f 475//475 476//476 477//477 -f 472//472 474//474 478//478 -f 474//474 479//479 478//478 -f 478//478 479//479 480//480 -f 478//478 480//480 481//481 -f 475//475 477//477 482//482 -f 477//477 483//483 482//482 -f 482//482 483//483 484//484 -f 482//482 484//484 472//472 -f 472//472 484//484 485//485 -f 472//472 485//485 473//473 -f 480//480 486//486 481//481 -f 481//481 486//486 487//487 -f 481//481 487//487 475//475 -f 475//475 487//487 488//488 -f 475//475 488//488 476//476 -f 489//489 490//490 491//491 -f 491//491 490//490 492//492 -f 493//493 494//494 495//495 -f 495//495 494//494 496//496 -f 496//496 497//497 495//495 -f 495//495 497//497 498//498 -f 495//495 498//498 499//499 -f 498//498 500//500 499//499 -f 499//499 500//500 501//501 -f 499//499 501//501 489//489 -f 489//489 501//501 502//502 -f 489//489 502//502 490//490 -f 492//492 503//503 491//491 -f 491//491 503//503 504//504 -f 491//491 504//504 493//493 -f 493//493 504//504 505//505 -f 493//493 505//505 494//494 -f 506//506 507//507 508//508 -f 508//508 507//507 509//509 -f 510//510 511//511 506//506 -f 506//506 511//511 512//512 -f 506//506 512//512 507//507 -f 509//509 513//513 508//508 -f 508//508 513//513 514//514 -f 508//508 514//514 515//515 -f 516//516 517//517 518//518 -f 518//518 517//517 515//515 -f 518//518 515//515 519//519 -f 519//519 515//515 514//514 -f 516//516 520//520 517//517 -f 517//517 520//520 521//521 -f 517//517 521//521 510//510 -f 510//510 521//521 522//522 -f 510//510 522//522 511//511 -f 523//523 524//524 525//525 -f 525//525 524//524 526//526 -f 527//527 528//528 529//529 -f 32//32 40//40 31//31 -f 530//530 531//531 532//532 -f 532//532 531//531 533//533 -f 31//31 40//40 39//39 -f 39//39 40//40 12//12 -f 39//39 12//12 41//41 -f 534//534 535//535 536//536 -f 536//536 535//535 537//537 -f 538//538 539//539 540//540 -f 540//540 539//539 541//541 -f 540//540 541//541 542//542 -f 543//543 544//544 545//545 -f 546//546 547//547 548//548 -f 548//548 547//547 549//549 -f 550//550 551//551 552//552 -f 553//553 64//64 8//8 -f 554//554 555//555 556//556 -f 556//556 555//555 557//557 -f 58//58 71//71 8//8 -f 558//558 559//559 560//560 -f 560//560 559//559 561//561 -f 45//45 562//562 563//563 -f 564//564 565//565 566//566 -f 566//566 565//565 567//567 -f 568//568 569//569 570//570 -f 570//570 569//569 571//571 -f 71//71 72//72 8//8 -f 8//8 72//72 66//66 -f 8//8 66//66 553//553 -f 537//537 550//550 64//64 -f 572//572 573//573 574//574 -f 574//574 573//573 575//575 -f 61//61 545//545 62//62 -f 62//62 545//545 63//63 -f 576//576 532//532 553//553 -f 553//553 532//532 533//533 -f 553//553 533//533 64//64 -f 64//64 533//533 548//548 -f 64//64 548//548 537//537 -f 537//537 548//548 549//549 -f 537//537 549//549 536//536 -f 577//577 578//578 579//579 -f 579//579 578//578 562//562 -f 579//579 562//562 561//561 -f 561//561 562//562 45//45 -f 561//561 45//45 68//68 -f 580//580 581//581 563//563 -f 563//563 581//581 543//543 -f 563//563 543//543 45//45 -f 45//45 543//543 545//545 -f 45//45 545//545 46//46 -f 582//582 583//583 584//584 -f 584//584 583//583 585//585 -f 14//14 7//7 9//9 -f 552//552 542//542 550//550 -f 550//550 542//542 541//541 -f 550//550 541//541 64//64 -f 64//64 541//541 560//560 -f 64//64 560//560 65//65 -f 65//65 560//560 561//561 -f 65//65 561//561 67//67 -f 67//67 561//561 68//68 -f 20//20 9//9 59//59 -f 59//59 9//9 11//11 -f 59//59 11//11 61//61 -f 12//12 14//14 13//13 -f 13//13 14//14 9//9 -f 13//13 9//9 19//19 -f 19//19 9//9 20//20 -f 7//7 14//14 64//64 -f 64//64 14//14 15//15 -f 64//64 15//15 18//18 -f 586//586 587//587 588//588 -f 588//588 587//587 589//589 -f 588//588 589//589 590//590 -f 11//11 17//17 61//61 -f 61//61 17//17 16//16 -f 61//61 16//16 545//545 -f 545//545 16//16 6//6 -f 545//545 6//6 46//46 -f 48//48 47//47 64//64 -f 64//64 47//47 10//10 -f 64//64 10//10 8//8 -f 54//54 35//35 55//55 -f 55//55 35//35 37//37 -f 55//55 37//37 57//57 -f 57//57 37//37 56//56 -f 57//57 56//56 69//69 -f 69//69 56//56 58//58 -f 69//69 58//58 70//70 -f 70//70 58//58 8//8 -f 529//529 591//591 527//527 -f 527//527 591//591 592//592 -f 527//527 592//592 593//593 -f 594//594 595//595 63//63 -f 49//49 48//48 50//50 -f 50//50 48//48 64//64 -f 50//50 64//64 60//60 -f 60//60 64//64 18//18 -f 32//32 31//31 34//34 -f 34//34 31//31 33//33 -f 34//34 33//33 36//36 -f 36//36 33//33 35//35 -f 36//36 35//35 38//38 -f 38//38 35//35 54//54 -f 38//38 54//54 52//52 -f 52//52 54//54 53//53 -f 52//52 53//53 50//50 -f 50//50 53//53 51//51 -f 50//50 51//51 49//49 -f 596//596 597//597 598//598 -f 598//598 597//597 599//599 -f 598//598 599//599 600//600 -f 601//601 602//602 600//600 -f 600//600 602//602 594//594 -f 600//600 594//594 598//598 -f 598//598 594//594 63//63 -f 598//598 63//63 526//526 -f 526//526 63//63 545//545 -f 526//526 545//545 525//525 -f 525//525 545//545 603//603 -f 585//585 28//28 584//584 -f 584//584 28//28 27//27 -f 584//584 27//27 24//24 -f 556//556 13//13 585//585 -f 585//585 13//13 30//30 -f 585//585 30//30 28//28 -f 604//604 605//605 595//595 -f 595//595 605//605 606//606 -f 595//595 606//606 63//63 -f 63//63 606//606 607//607 -f 608//608 584//584 609//609 -f 609//609 584//584 24//24 -f 609//609 24//24 607//607 -f 607//607 24//24 22//22 -f 607//607 22//22 63//63 -f 557//557 566//566 556//556 -f 556//556 566//566 567//567 -f 556//556 567//567 13//13 -f 13//13 567//567 570//570 -f 610//610 527//527 13//13 -f 13//13 527//527 593//593 -f 13//13 593//593 12//12 -f 12//12 593//593 29//29 -f 12//12 29//29 41//41 -f 571//571 574//574 570//570 -f 570//570 574//574 575//575 -f 570//570 575//575 13//13 -f 13//13 575//575 588//588 -f 13//13 588//588 610//610 -f 610//610 588//588 590//590 -f 610//610 590//590 611//611 -f 611//611 590//590 612//612 -f 613//613 614//614 615//615 -f 615//615 614//614 616//616 -f 615//615 616//616 617//617 -f 617//617 616//616 618//618 -f 617//617 618//618 619//619 -f 620//620 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 624//624 623//623 625//625 -f 624//624 625//625 626//626 -f 627//627 628//628 629//629 -f 629//629 628//628 630//630 -f 629//629 630//630 631//631 -f 631//631 630//630 632//632 -f 631//631 632//632 633//633 -f 634//634 635//635 478//478 -f 478//478 635//635 636//636 -f 478//478 636//636 472//472 -f 472//472 636//636 637//637 -f 472//472 637//637 638//638 -f 638//638 637//637 639//639 -f 640//640 641//641 499//499 -f 499//499 641//641 642//642 -f 499//499 642//642 495//495 -f 495//495 642//642 643//643 -f 495//495 643//643 644//644 -f 644//644 643//643 645//645 -f 646//646 647//647 515//515 -f 515//515 647//647 648//648 -f 515//515 648//648 508//508 -f 508//508 648//648 649//649 -f 508//508 649//649 650//650 -f 650//650 649//649 651//651 -f 652//652 653//653 654//654 -f 654//654 653//653 655//655 -f 656//656 657//657 658//658 -f 659//659 660//660 661//661 -f 661//661 660//660 656//656 -f 661//661 656//656 662//662 -f 662//662 656//656 658//658 -f 659//659 663//663 660//660 -f 660//660 663//663 664//664 -f 660//660 664//664 652//652 -f 652//652 664//664 665//665 -f 652//652 665//665 653//653 -f 655//655 666//666 654//654 -f 654//654 666//666 667//667 -f 654//654 667//667 657//657 -f 657//657 667//667 668//668 -f 657//657 668//668 658//658 -f 669//669 670//670 671//671 -f 671//671 670//670 672//672 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 677//677 -f 677//677 676//676 678//678 -f 677//677 678//678 679//679 -f 671//671 680//680 669//669 -f 669//669 680//680 681//681 -f 669//669 681//681 678//678 -f 678//678 681//681 682//682 -f 678//678 682//682 679//679 -f 673//673 683//683 674//674 -f 674//674 683//683 684//684 -f 674//674 684//684 670//670 -f 670//670 684//684 685//685 -f 670//670 685//685 672//672 -f 686//686 687//687 688//688 -f 688//688 687//687 689//689 -f 688//688 689//689 690//690 -f 690//690 689//689 691//691 -f 690//690 691//691 692//692 -f 693//693 694//694 657//657 -f 657//657 694//694 695//695 -f 657//657 695//695 654//654 -f 654//654 695//695 696//696 -f 654//654 696//696 697//697 -f 697//697 696//696 698//698 -f 699//699 700//700 701//701 -f 702//702 703//703 704//704 -f 699//699 701//701 704//704 -f 704//704 701//701 705//705 -f 704//704 705//705 702//702 -f 706//706 707//707 669//669 -f 669//669 707//707 708//708 -f 669//669 708//708 670//670 -f 670//670 708//708 709//709 -f 670//670 709//709 710//710 -f 710//710 709//709 711//711 -f 712//712 553//553 713//713 -f 713//713 553//553 66//66 -f 469//469 29//29 714//714 -f 714//714 29//29 593//593 -f 593//593 592//592 714//714 -f 714//714 592//592 715//715 -f 714//714 715//715 716//716 -f 716//716 715//715 361//361 -f 716//716 361//361 717//717 -f 717//717 361//361 360//360 -f 715//715 592//592 718//718 -f 718//718 592//592 591//591 -f 374//374 362//362 718//718 -f 718//718 591//591 529//529 -f 374//374 718//718 380//380 -f 380//380 718//718 637//637 -f 637//637 718//718 529//529 -f 637//637 529//529 639//639 -f 612//612 590//590 719//719 -f 719//719 378//378 372//372 -f 612//612 719//719 635//635 -f 635//635 719//719 636//636 -f 636//636 719//719 372//372 -f 636//636 372//372 381//381 -f 719//719 590//590 720//720 -f 720//720 590//590 589//589 -f 345//345 344//344 720//720 -f 720//720 589//589 587//587 -f 345//345 720//720 356//356 -f 356//356 720//720 643//643 -f 643//643 720//720 587//587 -f 643//643 587//587 645//645 -f 572//572 574//574 721//721 -f 721//721 347//347 342//342 -f 572//572 721//721 641//641 -f 641//641 721//721 642//642 -f 642//642 721//721 342//342 -f 642//642 342//342 357//357 -f 721//721 574//574 722//722 -f 722//722 574//574 571//571 -f 324//324 323//323 722//722 -f 722//722 571//571 569//569 -f 324//324 722//722 336//336 -f 336//336 722//722 649//649 -f 649//649 722//722 569//569 -f 649//649 569//569 651//651 -f 564//564 566//566 723//723 -f 723//723 331//331 320//320 -f 564//564 723//723 647//647 -f 647//647 723//723 648//648 -f 648//648 723//723 320//320 -f 648//648 320//320 337//337 -f 723//723 566//566 724//724 -f 724//724 566//566 557//557 -f 157//157 159//159 724//724 -f 724//724 557//557 555//555 -f 157//157 724//724 316//316 -f 316//316 724//724 696//696 -f 696//696 724//724 555//555 -f 696//696 555//555 698//698 -f 582//582 584//584 725//725 -f 725//725 176//176 175//175 -f 582//582 725//725 694//694 -f 694//694 725//725 695//695 -f 695//695 725//725 175//175 -f 695//695 175//175 314//314 -f 725//725 584//584 726//726 -f 726//726 584//584 608//608 -f 726//726 608//608 178//178 -f 178//178 608//608 609//609 -f 178//178 609//609 727//727 -f 727//727 609//609 607//607 -f 727//727 607//607 728//728 -f 728//728 607//607 606//606 -f 183//183 180//180 728//728 -f 728//728 606//606 605//605 -f 183//183 728//728 312//312 -f 312//312 728//728 709//709 -f 709//709 728//728 605//605 -f 709//709 605//605 711//711 -f 601//601 600//600 729//729 -f 729//729 193//193 195//195 -f 601//601 729//729 707//707 -f 707//707 729//729 708//708 -f 708//708 729//729 195//195 -f 708//708 195//195 313//313 -f 729//729 600//600 730//730 -f 730//730 600//600 599//599 -f 213//213 207//207 730//730 -f 730//730 599//599 597//597 -f 213//213 730//730 311//311 -f 311//311 730//730 731//731 -f 731//731 730//730 597//597 -f 731//731 597//597 732//732 -f 733//733 734//734 735//735 -f 735//735 734//734 736//736 -f 735//735 736//736 737//737 -f 737//737 736//736 731//731 -f 737//737 731//731 738//738 -f 738//738 731//731 732//732 -f 523//523 525//525 739//739 -f 739//739 223//223 225//225 -f 523//523 739//739 734//734 -f 734//734 739//739 736//736 -f 736//736 739//739 225//225 -f 736//736 225//225 147//147 -f 739//739 525//525 740//740 -f 740//740 525//525 603//603 -f 740//740 603//603 220//220 -f 220//220 603//603 545//545 -f 220//220 545//545 741//741 -f 741//741 545//545 544//544 -f 741//741 544//544 742//742 -f 742//742 544//544 543//543 -f 581//581 743//743 744//744 -f 543//543 581//581 742//742 -f 742//742 581//581 744//744 -f 742//742 744//744 218//218 -f 218//218 744//744 216//216 -f 745//745 746//746 747//747 -f 747//747 746//746 748//748 -f 747//747 748//748 749//749 -f 749//749 748//748 744//744 -f 749//749 744//744 750//750 -f 750//750 744//744 743//743 -f 229//229 227//227 751//751 -f 751//751 227//227 748//748 -f 748//748 746//746 751//751 -f 751//751 746//746 577//577 -f 751//751 577//577 579//579 -f 751//751 579//579 752//752 -f 752//752 579//579 561//561 -f 559//559 753//753 754//754 -f 561//561 559//559 752//752 -f 752//752 559//559 754//754 -f 752//752 754//754 285//285 -f 285//285 754//754 286//286 -f 755//755 756//756 757//757 -f 757//757 756//756 758//758 -f 757//757 758//758 759//759 -f 759//759 758//758 754//754 -f 759//759 754//754 760//760 -f 760//760 754//754 753//753 -f 291//291 289//289 761//761 -f 761//761 289//289 758//758 -f 758//758 756//756 761//761 -f 761//761 756//756 538//538 -f 761//761 538//538 540//540 -f 761//761 540//540 762//762 -f 762//762 540//540 542//542 -f 552//552 763//763 764//764 -f 542//542 552//552 762//762 -f 762//762 552//552 764//764 -f 762//762 764//764 268//268 -f 268//268 764//764 269//269 -f 765//765 766//766 767//767 -f 767//767 766//766 768//768 -f 767//767 768//768 769//769 -f 769//769 768//768 764//764 -f 769//769 764//764 770//770 -f 770//770 764//764 763//763 -f 276//276 280//280 771//771 -f 771//771 280//280 768//768 -f 768//768 766//766 771//771 -f 771//771 766//766 534//534 -f 771//771 534//534 536//536 -f 771//771 536//536 772//772 -f 772//772 536//536 549//549 -f 547//547 773//773 774//774 -f 549//549 547//547 772//772 -f 772//772 547//547 774//774 -f 772//772 774//774 251//251 -f 251//251 774//774 258//258 -f 775//775 776//776 777//777 -f 777//777 776//776 778//778 -f 777//777 778//778 779//779 -f 779//779 778//778 774//774 -f 779//779 774//774 780//780 -f 780//780 774//774 773//773 -f 256//256 263//263 781//781 -f 781//781 263//263 778//778 -f 778//778 776//776 781//781 -f 781//781 776//776 530//530 -f 781//781 530//530 532//532 -f 781//781 532//532 782//782 -f 782//782 532//532 576//576 -f 783//783 250//250 255//255 -f 576//576 553//553 782//782 -f 782//782 553//553 712//712 -f 782//782 712//712 255//255 -f 255//255 712//712 784//784 -f 255//255 784//784 783//783 -f 249//249 785//785 786//786 -f 151//151 243//243 787//787 -f 787//787 243//243 245//245 -f 787//787 245//245 788//788 -f 788//788 245//245 247//247 -f 788//788 247//247 440//440 -f 440//440 247//247 249//249 -f 440//440 249//249 439//439 -f 439//439 249//249 786//786 -f 438//438 419//419 789//789 -f 789//789 419//419 790//790 -f 790//790 419//419 421//421 -f 790//790 421//421 791//791 -f 791//791 421//421 423//423 -f 791//791 423//423 792//792 -f 792//792 423//423 425//425 -f 792//792 425//425 793//793 -f 793//793 425//425 427//427 -f 793//793 427//427 794//794 -f 794//794 427//427 428//428 -f 794//794 428//428 795//795 -f 795//795 428//428 456//456 -f 795//795 456//456 796//796 -f 796//796 456//456 455//455 -f 796//796 455//455 797//797 -f 797//797 455//455 798//798 -f 798//798 455//455 414//414 -f 799//799 800//800 801//801 -f 801//801 800//800 737//737 -f 801//801 737//737 596//596 -f 596//596 737//737 738//738 -f 735//735 737//737 802//802 -f 802//802 737//737 803//803 -f 804//804 805//805 806//806 -f 806//806 805//805 735//735 -f 806//806 735//735 807//807 -f 807//807 735//735 802//802 -f 804//804 808//808 805//805 -f 805//805 808//808 809//809 -f 805//805 809//809 810//810 -f 810//810 809//809 811//811 -f 810//810 811//811 800//800 -f 800//800 811//811 812//812 -f 812//812 813//813 800//800 -f 800//800 813//813 814//814 -f 800//800 814//814 737//737 -f 737//737 814//814 815//815 -f 737//737 815//815 803//803 -f 524//524 733//733 816//816 -f 816//816 733//733 735//735 -f 816//816 735//735 817//817 -f 817//817 735//735 805//805 -f 799//799 818//818 800//800 -f 800//800 818//818 810//810 -f 818//818 817//817 810//810 -f 810//810 817//817 805//805 -f 816//816 817//817 819//819 -f 819//819 817//817 818//818 -f 819//819 818//818 820//820 -f 820//820 818//818 799//799 -f 820//820 799//799 801//801 -f 596//596 598//598 801//801 -f 801//801 598//598 820//820 -f 598//598 526//526 820//820 -f 820//820 526//526 819//819 -f 526//526 524//524 819//819 -f 819//819 524//524 816//816 -f 821//821 822//822 823//823 -f 823//823 822//822 749//749 -f 823//823 749//749 580//580 -f 580//580 749//749 750//750 -f 824//824 747//747 825//825 -f 825//825 826//826 824//824 -f 824//824 826//826 827//827 -f 824//824 827//827 828//828 -f 828//828 827//827 829//829 -f 822//822 830//830 749//749 -f 749//749 830//830 831//831 -f 831//831 832//832 749//749 -f 749//749 832//832 833//833 -f 749//749 833//833 747//747 -f 747//747 833//833 834//834 -f 747//747 834//834 825//825 -f 829//829 835//835 828//828 -f 828//828 835//835 836//836 -f 828//828 836//836 822//822 -f 822//822 836//836 837//837 -f 822//822 837//837 830//830 -f 578//578 745//745 838//838 -f 838//838 745//745 747//747 -f 838//838 747//747 839//839 -f 839//839 747//747 824//824 -f 821//821 840//840 822//822 -f 822//822 840//840 828//828 -f 840//840 839//839 828//828 -f 828//828 839//839 824//824 -f 841//841 838//838 839//839 -f 821//821 823//823 842//842 -f 841//841 839//839 842//842 -f 842//842 839//839 840//840 -f 842//842 840//840 821//821 -f 563//563 842//842 580//580 -f 580//580 842//842 823//823 -f 562//562 841//841 563//563 -f 563//563 841//841 842//842 -f 578//578 838//838 562//562 -f 562//562 838//838 841//841 -f 802//802 215//215 807//807 -f 807//807 215//215 210//210 -f 807//807 210//210 806//806 -f 806//806 210//210 209//209 -f 806//806 209//209 804//804 -f 804//804 209//209 208//208 -f 804//804 208//208 808//808 -f 808//808 208//208 309//309 -f 808//808 309//309 809//809 -f 809//809 309//309 307//307 -f 809//809 307//307 811//811 -f 811//811 307//307 305//305 -f 811//811 305//305 812//812 -f 812//812 305//305 304//304 -f 812//812 304//304 813//813 -f 813//813 304//304 303//303 -f 813//813 303//303 814//814 -f 814//814 303//303 211//211 -f 814//814 211//211 815//815 -f 815//815 211//211 212//212 -f 815//815 212//212 803//803 -f 803//803 212//212 214//214 -f 803//803 214//214 802//802 -f 802//802 214//214 215//215 -f 830//830 240//240 831//831 -f 831//831 240//240 239//239 -f 831//831 239//239 832//832 -f 832//832 239//239 238//238 -f 832//832 238//238 833//833 -f 833//833 238//238 233//233 -f 833//833 233//233 834//834 -f 834//834 233//233 232//232 -f 834//834 232//232 825//825 -f 825//825 232//232 226//226 -f 825//825 226//226 826//826 -f 826//826 226//226 228//228 -f 826//826 228//228 827//827 -f 827//827 228//228 230//230 -f 827//827 230//230 829//829 -f 829//829 230//230 231//231 -f 829//829 231//231 835//835 -f 835//835 231//231 234//234 -f 835//835 234//234 836//836 -f 836//836 234//234 235//235 -f 836//836 235//235 837//837 -f 837//837 235//235 237//237 -f 837//837 237//237 830//830 -f 830//830 237//237 240//240 -f 843//843 844//844 845//845 -f 845//845 844//844 759//759 -f 845//845 759//759 558//558 -f 558//558 759//759 760//760 -f 846//846 757//757 847//847 -f 847//847 848//848 846//846 -f 846//846 848//848 849//849 -f 846//846 849//849 850//850 -f 850//850 849//849 851//851 -f 852//852 759//759 853//853 -f 853//853 759//759 844//844 -f 851//851 854//854 850//850 -f 850//850 854//854 855//855 -f 850//850 855//855 844//844 -f 844//844 855//855 856//856 -f 844//844 856//856 853//853 -f 852//852 857//857 759//759 -f 759//759 857//857 858//858 -f 759//759 858//858 757//757 -f 757//757 858//858 859//859 -f 757//757 859//859 847//847 -f 539//539 755//755 860//860 -f 860//860 755//755 757//757 -f 860//860 757//757 861//861 -f 861//861 757//757 846//846 -f 862//862 863//863 864//864 -f 864//864 863//863 769//769 -f 864//864 769//769 551//551 -f 551//551 769//769 770//770 -f 865//865 769//769 866//866 -f 866//866 769//769 863//863 -f 865//865 867//867 769//769 -f 769//769 867//867 868//868 -f 769//769 868//868 767//767 -f 869//869 870//870 871//871 -f 871//871 870//870 872//872 -f 869//869 873//873 870//870 -f 870//870 873//873 874//874 -f 870//870 874//874 863//863 -f 863//863 874//874 875//875 -f 863//863 875//875 866//866 -f 868//868 876//876 767//767 -f 767//767 876//876 877//877 -f 767//767 877//877 872//872 -f 872//872 877//877 878//878 -f 872//872 878//878 871//871 -f 535//535 765//765 879//879 -f 879//879 765//765 767//767 -f 879//879 767//767 880//880 -f 880//880 767//767 872//872 -f 881//881 882//882 883//883 -f 883//883 882//882 779//779 -f 883//883 779//779 546//546 -f 546//546 779//779 780//780 -f 884//884 885//885 886//886 -f 886//886 885//885 882//882 -f 887//887 777//777 888//888 -f 888//888 889//889 887//887 -f 887//887 889//889 890//890 -f 887//887 890//890 886//886 -f 886//886 890//890 891//891 -f 886//886 891//891 884//884 -f 885//885 892//892 882//882 -f 882//882 892//892 893//893 -f 882//882 893//893 779//779 -f 779//779 893//893 894//894 -f 894//894 895//895 779//779 -f 779//779 895//895 896//896 -f 779//779 896//896 777//777 -f 777//777 896//896 897//897 -f 777//777 897//897 888//888 -f 531//531 775//775 898//898 -f 898//898 775//775 777//777 -f 898//898 777//777 899//899 -f 899//899 777//777 887//887 -f 843//843 900//900 844//844 -f 844//844 900//900 850//850 -f 900//900 861//861 850//850 -f 850//850 861//861 846//846 -f 901//901 860//860 861//861 -f 843//843 845//845 902//902 -f 901//901 861//861 902//902 -f 902//902 861//861 900//900 -f 902//902 900//900 843//843 -f 862//862 903//903 863//863 -f 863//863 903//903 870//870 -f 903//903 880//880 870//870 -f 870//870 880//880 872//872 -f 904//904 879//879 880//880 -f 862//862 864//864 905//905 -f 904//904 880//880 905//905 -f 905//905 880//880 903//903 -f 905//905 903//903 862//862 -f 881//881 906//906 882//882 -f 882//882 906//906 886//886 -f 906//906 899//899 886//886 -f 886//886 899//899 887//887 -f 907//907 898//898 899//899 -f 881//881 883//883 908//908 -f 907//907 899//899 908//908 -f 908//908 899//899 906//906 -f 908//908 906//906 881//881 -f 560//560 902//902 558//558 -f 558//558 902//902 845//845 -f 541//541 901//901 560//560 -f 560//560 901//901 902//902 -f 539//539 860//860 541//541 -f 541//541 860//860 901//901 -f 550//550 905//905 551//551 -f 551//551 905//905 864//864 -f 537//537 904//904 550//550 -f 550//550 904//904 905//905 -f 535//535 879//879 537//537 -f 537//537 879//879 904//904 -f 548//548 908//908 546//546 -f 546//546 908//908 883//883 -f 533//533 907//907 548//548 -f 548//548 907//907 908//908 -f 531//531 898//898 533//533 -f 533//533 898//898 907//907 -f 853//853 295//295 852//852 -f 852//852 295//295 287//287 -f 852//852 287//287 857//857 -f 857//857 287//287 302//302 -f 857//857 302//302 858//858 -f 858//858 302//302 301//301 -f 858//858 301//301 859//859 -f 859//859 301//301 300//300 -f 859//859 300//300 847//847 -f 847//847 300//300 288//288 -f 847//847 288//288 848//848 -f 848//848 288//288 290//290 -f 848//848 290//290 849//849 -f 849//849 290//290 292//292 -f 849//849 292//292 851//851 -f 851//851 292//292 293//293 -f 851//851 293//293 854//854 -f 854//854 293//293 298//298 -f 854//854 298//298 855//855 -f 855//855 298//298 297//297 -f 855//855 297//297 856//856 -f 856//856 297//297 296//296 -f 856//856 296//296 853//853 -f 853//853 296//296 295//295 -f 866//866 271//271 865//865 -f 865//865 271//271 270//270 -f 865//865 270//270 867//867 -f 867//867 270//270 284//284 -f 867//867 284//284 868//868 -f 868//868 284//284 283//283 -f 868//868 283//283 876//876 -f 876//876 283//283 282//282 -f 876//876 282//282 877//877 -f 877//877 282//282 281//281 -f 877//877 281//281 878//878 -f 878//878 281//281 279//279 -f 878//878 279//279 871//871 -f 871//871 279//279 278//278 -f 871//871 278//278 869//869 -f 869//869 278//278 275//275 -f 869//869 275//275 873//873 -f 873//873 275//275 274//274 -f 873//873 274//274 874//874 -f 874//874 274//274 273//273 -f 874//874 273//273 875//875 -f 875//875 273//273 272//272 -f 875//875 272//272 866//866 -f 866//866 272//272 271//271 -f 893//893 260//260 894//894 -f 894//894 260//260 259//259 -f 894//894 259//259 895//895 -f 895//895 259//259 267//267 -f 895//895 267//267 896//896 -f 896//896 267//267 266//266 -f 896//896 266//266 897//897 -f 897//897 266//266 265//265 -f 897//897 265//265 888//888 -f 888//888 265//265 264//264 -f 888//888 264//264 889//889 -f 889//889 264//264 262//262 -f 889//889 262//262 890//890 -f 890//890 262//262 261//261 -f 890//890 261//261 891//891 -f 891//891 261//261 257//257 -f 891//891 257//257 884//884 -f 884//884 257//257 254//254 -f 884//884 254//254 885//885 -f 885//885 254//254 253//253 -f 885//885 253//253 892//892 -f 892//892 253//253 252//252 -f 892//892 252//252 893//893 -f 893//893 252//252 260//260 -f 702//702 674//674 703//703 -f 703//703 674//674 670//670 -f 703//703 670//670 604//604 -f 604//604 670//670 710//710 -f 602//602 706//706 700//700 -f 700//700 706//706 669//669 -f 700//700 669//669 701//701 -f 701//701 669//669 678//678 -f 702//702 705//705 674//674 -f 674//674 705//705 676//676 -f 705//705 701//701 676//676 -f 676//676 701//701 678//678 -f 595//595 704//704 604//604 -f 604//604 704//704 703//703 -f 594//594 699//699 595//595 -f 595//595 699//699 704//704 -f 602//602 700//700 594//594 -f 594//594 700//700 699//699 -f 691//691 652//652 692//692 -f 692//692 652//652 654//654 -f 692//692 654//654 554//554 -f 554//554 654//654 697//697 -f 583//583 693//693 686//686 -f 686//686 693//693 657//657 -f 686//686 657//657 687//687 -f 687//687 657//657 656//656 -f 691//691 689//689 652//652 -f 652//652 689//689 660//660 -f 689//689 687//687 660//660 -f 660//660 687//687 656//656 -f 554//554 556//556 692//692 -f 692//692 556//556 690//690 -f 556//556 585//585 690//690 -f 690//690 585//585 688//688 -f 585//585 583//583 688//688 -f 688//688 583//583 686//686 -f 671//671 181//181 680//680 -f 680//680 181//181 197//197 -f 680//680 197//197 681//681 -f 681//681 197//197 196//196 -f 681//681 196//196 682//682 -f 682//682 196//196 194//194 -f 682//682 194//194 679//679 -f 679//679 194//194 192//192 -f 679//679 192//192 677//677 -f 677//677 192//192 191//191 -f 677//677 191//191 675//675 -f 675//675 191//191 188//188 -f 675//675 188//188 673//673 -f 673//673 188//188 187//187 -f 673//673 187//187 683//683 -f 683//683 187//187 186//186 -f 683//683 186//186 684//684 -f 684//684 186//186 185//185 -f 684//684 185//185 685//685 -f 685//685 185//185 184//184 -f 685//685 184//184 672//672 -f 672//672 184//184 182//182 -f 672//672 182//182 671//671 -f 671//671 182//182 181//181 -f 662//662 154//154 661//661 -f 661//661 154//154 170//170 -f 661//661 170//170 659//659 -f 659//659 170//170 172//172 -f 659//659 172//172 663//663 -f 663//663 172//172 164//164 -f 663//663 164//164 664//664 -f 664//664 164//164 162//162 -f 664//664 162//162 665//665 -f 665//665 162//162 161//161 -f 665//665 161//161 653//653 -f 653//653 161//161 160//160 -f 653//653 160//160 655//655 -f 655//655 160//160 158//158 -f 655//655 158//158 666//666 -f 666//666 158//158 167//167 -f 666//666 167//167 667//667 -f 667//667 167//167 166//166 -f 667//667 166//166 668//668 -f 668//668 166//166 165//165 -f 668//668 165//165 658//658 -f 658//658 165//165 155//155 -f 658//658 155//155 662//662 -f 662//662 155//155 154//154 -f 632//632 506//506 633//633 -f 633//633 506//506 508//508 -f 633//633 508//508 568//568 -f 568//568 508//508 650//650 -f 565//565 646//646 627//627 -f 627//627 646//646 515//515 -f 627//627 515//515 628//628 -f 628//628 515//515 517//517 -f 625//625 493//493 626//626 -f 626//626 493//493 495//495 -f 626//626 495//495 586//586 -f 586//586 495//495 644//644 -f 573//573 640//640 620//620 -f 620//620 640//640 499//499 -f 620//620 499//499 621//621 -f 621//621 499//499 489//489 -f 618//618 482//482 619//619 -f 619//619 482//482 472//472 -f 619//619 472//472 528//528 -f 528//528 472//472 638//638 -f 611//611 634//634 613//613 -f 613//613 634//634 478//478 -f 613//613 478//478 614//614 -f 614//614 478//478 481//481 -f 632//632 630//630 506//506 -f 506//506 630//630 510//510 -f 630//630 628//628 510//510 -f 510//510 628//628 517//517 -f 625//625 623//623 493//493 -f 493//493 623//623 491//491 -f 623//623 621//621 491//491 -f 491//491 621//621 489//489 -f 618//618 616//616 482//482 -f 482//482 616//616 475//475 -f 616//616 614//614 475//475 -f 475//475 614//614 481//481 -f 568//568 570//570 633//633 -f 633//633 570//570 631//631 -f 570//570 567//567 631//631 -f 631//631 567//567 629//629 -f 567//567 565//565 629//629 -f 629//629 565//565 627//627 -f 586//586 588//588 626//626 -f 626//626 588//588 624//624 -f 588//588 575//575 624//624 -f 624//624 575//575 622//622 -f 575//575 573//573 622//622 -f 622//622 573//573 620//620 -f 528//528 527//527 619//619 -f 619//619 527//527 617//617 -f 527//527 610//610 617//617 -f 617//617 610//610 615//615 -f 610//610 611//611 615//615 -f 615//615 611//611 613//613 -f 516//516 318//318 520//520 -f 520//520 318//318 317//317 -f 520//520 317//317 521//521 -f 521//521 317//317 335//335 -f 521//521 335//335 522//522 -f 522//522 335//335 334//334 -f 522//522 334//334 511//511 -f 511//511 334//334 333//333 -f 511//511 333//333 512//512 -f 512//512 333//333 326//326 -f 512//512 326//326 507//507 -f 507//507 326//326 328//328 -f 507//507 328//328 509//509 -f 509//509 328//328 329//329 -f 509//509 329//329 513//513 -f 513//513 329//329 325//325 -f 513//513 325//325 514//514 -f 514//514 325//325 322//322 -f 514//514 322//322 519//519 -f 519//519 322//322 321//321 -f 519//519 321//321 518//518 -f 518//518 321//321 332//332 -f 518//518 332//332 516//516 -f 516//516 332//332 318//318 -f 502//502 339//339 490//490 -f 490//490 339//339 338//338 -f 490//490 338//338 492//492 -f 492//492 338//338 355//355 -f 492//492 355//355 503//503 -f 503//503 355//355 354//354 -f 503//503 354//354 504//504 -f 504//504 354//354 353//353 -f 504//504 353//353 505//505 -f 505//505 353//353 352//352 -f 505//505 352//352 494//494 -f 494//494 352//352 350//350 -f 494//494 350//350 496//496 -f 496//496 350//350 349//349 -f 496//496 349//349 497//497 -f 497//497 349//349 346//346 -f 497//497 346//346 498//498 -f 498//498 346//346 343//343 -f 498//498 343//343 500//500 -f 500//500 343//343 341//341 -f 500//500 341//341 501//501 -f 501//501 341//341 340//340 -f 501//501 340//340 502//502 -f 502//502 340//340 339//339 -f 486//486 359//359 487//487 -f 487//487 359//359 358//358 -f 487//487 358//358 488//488 -f 488//488 358//358 377//377 -f 488//488 377//377 476//476 -f 476//476 377//377 376//376 -f 476//476 376//376 477//477 -f 477//477 376//376 375//375 -f 477//477 375//375 483//483 -f 483//483 375//375 369//369 -f 483//483 369//369 484//484 -f 484//484 369//369 368//368 -f 484//484 368//368 485//485 -f 485//485 368//368 367//367 -f 485//485 367//367 473//473 -f 473//473 367//367 366//366 -f 473//473 366//366 474//474 -f 474//474 366//366 373//373 -f 474//474 373//373 479//479 -f 479//479 373//373 371//371 -f 479//479 371//371 480//480 -f 480//480 371//371 370//370 -f 480//480 370//370 486//486 -f 486//486 370//370 359//359 -f 909//909 713//713 910//910 -f 910//910 713//713 66//66 -f 910//910 66//66 911//911 -f 911//911 66//66 72//72 -f 911//911 72//72 912//912 -f 912//912 72//72 71//71 -f 912//912 71//71 913//913 -f 913//913 71//71 914//914 -f 914//914 71//71 58//58 -f 914//914 58//58 915//915 -f 915//915 58//58 916//916 -f 916//916 58//58 56//56 -f 916//916 56//56 917//917 -f 917//917 56//56 37//37 -f 917//917 37//37 410//410 -f 918//918 919//919 920//920 -f 921//921 918//918 922//922 -f 922//922 918//918 920//920 -f 922//922 920//920 923//923 -f 923//923 920//920 924//924 -f 925//925 926//926 927//927 -f 928//928 929//929 925//925 -f 925//925 929//929 930//930 -f 925//925 930//930 931//931 -f 931//931 930//930 932//932 -f 931//931 932//932 933//933 -f 933//933 932//932 934//934 -f 933//933 934//934 935//935 -f 935//935 934//934 936//936 -f 935//935 936//936 920//920 -f 920//920 936//936 937//937 -f 920//920 937//937 924//924 -f 924//924 937//937 938//938 -f 924//924 938//938 939//939 -f 939//939 938//938 940//940 -f 939//939 940//940 941//941 -f 941//941 940//940 942//942 -f 941//941 942//942 943//943 -f 943//943 942//942 944//944 -f 943//943 944//944 945//945 -f 945//945 944//944 946//946 -f 945//945 946//946 927//927 -f 927//927 946//946 928//928 -f 927//927 928//928 925//925 -f 947//947 786//786 931//931 -f 931//931 786//786 785//785 -f 931//931 785//785 925//925 -f 925//925 785//785 948//948 -f 925//925 948//948 949//949 -f 950//950 951//951 948//948 -f 948//948 951//951 952//952 -f 948//948 952//952 949//949 -f 920//920 919//919 935//935 -f 935//935 919//919 953//953 -f 935//935 953//953 933//933 -f 933//933 953//953 954//954 -f 933//933 954//954 931//931 -f 931//931 954//954 947//947 -f 955//955 956//956 957//957 -f 958//958 955//955 959//959 -f 959//959 955//955 957//957 -f 959//959 957//957 960//960 -f 960//960 957//957 961//961 -f 962//962 963//963 964//964 -f 964//964 963//963 965//965 -f 964//964 965//965 966//966 -f 966//966 965//965 967//967 -f 966//966 967//967 968//968 -f 968//968 967//967 969//969 -f 968//968 969//969 970//970 -f 970//970 969//969 971//971 -f 970//970 971//971 972//972 -f 972//972 971//971 973//973 -f 972//972 973//973 974//974 -f 974//974 973//973 975//975 -f 974//974 975//975 956//956 -f 956//956 975//975 976//976 -f 956//956 976//976 957//957 -f 957//957 976//976 977//977 -f 957//957 977//977 978//978 -f 978//978 977//977 979//979 -f 978//978 979//979 980//980 -f 980//980 979//979 981//981 -f 980//980 981//981 982//982 -f 982//982 981//981 962//962 -f 982//982 962//962 964//964 -f 982//982 983//983 980//980 -f 980//980 983//983 984//984 -f 980//980 984//984 978//978 -f 978//978 984//984 985//985 -f 978//978 985//985 957//957 -f 957//957 985//985 961//961 -f 986//986 964//964 987//987 -f 987//987 964//964 988//988 -f 384//384 983//983 385//385 -f 385//385 983//983 982//982 -f 385//385 982//982 989//989 -f 989//989 982//982 964//964 -f 989//989 964//964 990//990 -f 986//986 991//991 964//964 -f 964//964 991//991 992//992 -f 964//964 992//992 990//990 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 997//997 996//996 998//998 -f 999//999 1000//1000 998//998 -f 998//998 1000//1000 1001//1001 -f 998//998 1001//1001 997//997 -f 1002//1002 1003//1003 999//999 -f 999//999 1003//1003 1004//1004 -f 999//999 1004//1004 1000//1000 -f 1005//1005 1006//1006 1002//1002 -f 1002//1002 1006//1006 1007//1007 -f 1002//1002 1007//1007 1003//1003 -f 1008//1008 1009//1009 1010//1010 -f 1010//1010 1009//1009 1011//1011 -f 1010//1010 1011//1011 1012//1012 -f 1012//1012 1011//1011 1013//1013 -f 1012//1012 1013//1013 1005//1005 -f 1005//1005 1013//1013 1014//1014 -f 1005//1005 1014//1014 1006//1006 -f 1015//1015 1016//1016 1008//1008 -f 1008//1008 1016//1016 1017//1017 -f 1008//1008 1017//1017 1009//1009 -f 1018//1018 1019//1019 1015//1015 -f 1015//1015 1019//1019 1020//1020 -f 1015//1015 1020//1020 1016//1016 -f 1021//1021 1022//1022 1018//1018 -f 1018//1018 1022//1022 1023//1023 -f 1018//1018 1023//1023 1019//1019 -f 1024//1024 1022//1022 1025//1025 -f 1025//1025 1022//1022 1021//1021 -f 1025//1025 1021//1021 1026//1026 -f 1026//1026 1021//1021 994//994 -f 1026//1026 994//994 1027//1027 -f 1027//1027 994//994 993//993 -f 1027//1027 993//993 1028//1028 -f 1029//1029 998//998 1030//1030 -f 1030//1030 998//998 996//996 -f 1030//1030 996//996 1031//1031 -f 1031//1031 996//996 994//994 -f 1031//1031 994//994 1032//1032 -f 1032//1032 994//994 1021//1021 -f 1032//1032 1021//1021 1033//1033 -f 1033//1033 1021//1021 1018//1018 -f 1033//1033 1018//1018 1034//1034 -f 1034//1034 1018//1018 1015//1015 -f 1034//1034 1015//1015 1035//1035 -f 1035//1035 1015//1015 1008//1008 -f 1035//1035 1008//1008 1036//1036 -f 1036//1036 1008//1008 1010//1010 -f 1036//1036 1010//1010 1037//1037 -f 1037//1037 1010//1010 1012//1012 -f 1037//1037 1012//1012 1038//1038 -f 1038//1038 1012//1012 1005//1005 -f 1038//1038 1005//1005 1039//1039 -f 1039//1039 1005//1005 1002//1002 -f 1039//1039 1002//1002 1040//1040 -f 1040//1040 1002//1002 999//999 -f 1040//1040 999//999 1029//1029 -f 1029//1029 999//999 998//998 -f 1041//1041 1042//1042 1043//1043 -f 1044//1044 1045//1045 1046//1046 -f 1046//1046 1045//1045 1047//1047 -f 1046//1046 1047//1047 1048//1048 -f 1049//1049 1050//1050 1048//1048 -f 1048//1048 1050//1050 1051//1051 -f 1048//1048 1051//1051 1046//1046 -f 1052//1052 1053//1053 1049//1049 -f 1049//1049 1053//1053 1054//1054 -f 1049//1049 1054//1054 1050//1050 -f 1055//1055 1056//1056 1052//1052 -f 1052//1052 1056//1056 1057//1057 -f 1052//1052 1057//1057 1053//1053 -f 1058//1058 1059//1059 1055//1055 -f 1055//1055 1059//1059 1060//1060 -f 1055//1055 1060//1060 1056//1056 -f 1061//1061 1062//1062 1058//1058 -f 1058//1058 1062//1062 1063//1063 -f 1058//1058 1063//1063 1059//1059 -f 1064//1064 1065//1065 1061//1061 -f 1061//1061 1065//1065 1066//1066 -f 1061//1061 1066//1066 1062//1062 -f 1067//1067 1068//1068 1064//1064 -f 1064//1064 1068//1068 1069//1069 -f 1064//1064 1069//1069 1065//1065 -f 1043//1043 1070//1070 1041//1041 -f 1041//1041 1070//1070 1071//1071 -f 1041//1041 1071//1071 1067//1067 -f 1067//1067 1071//1071 1072//1072 -f 1067//1067 1072//1072 1068//1068 -f 1073//1073 1043//1043 1074//1074 -f 1074//1074 1043//1043 1042//1042 -f 1074//1074 1042//1042 1075//1075 -f 1075//1075 1042//1042 1045//1045 -f 1075//1075 1045//1045 1076//1076 -f 1076//1076 1045//1045 1044//1044 -f 1076//1076 1044//1044 1077//1077 -f 1078//1078 1042//1042 1079//1079 -f 1079//1079 1042//1042 1041//1041 -f 1079//1079 1041//1041 1080//1080 -f 1080//1080 1041//1041 1067//1067 -f 1080//1080 1067//1067 1081//1081 -f 1081//1081 1067//1067 1064//1064 -f 1081//1081 1064//1064 1082//1082 -f 1082//1082 1064//1064 1061//1061 -f 1082//1082 1061//1061 1083//1083 -f 1083//1083 1061//1061 1058//1058 -f 1083//1083 1058//1058 1084//1084 -f 1084//1084 1058//1058 1055//1055 -f 1084//1084 1055//1055 1085//1085 -f 1085//1085 1055//1055 1052//1052 -f 1085//1085 1052//1052 1086//1086 -f 1086//1086 1052//1052 1049//1049 -f 1086//1086 1049//1049 1087//1087 -f 1087//1087 1049//1049 1048//1048 -f 1087//1087 1048//1048 1088//1088 -f 1088//1088 1048//1048 1047//1047 -f 1088//1088 1047//1047 1089//1089 -f 1089//1089 1047//1047 1045//1045 -f 1089//1089 1045//1045 1078//1078 -f 1078//1078 1045//1045 1042//1042 -f 48//48 932//932 47//47 -f 47//47 932//932 930//930 -f 47//47 930//930 10//10 -f 10//10 930//930 929//929 -f 10//10 929//929 8//8 -f 8//8 929//929 928//928 -f 8//8 928//928 70//70 -f 70//70 928//928 946//946 -f 70//70 946//946 69//69 -f 69//69 946//946 944//944 -f 69//69 944//944 57//57 -f 57//57 944//944 942//942 -f 57//57 942//942 55//55 -f 55//55 942//942 940//940 -f 55//55 940//940 54//54 -f 54//54 940//940 938//938 -f 54//54 938//938 53//53 -f 53//53 938//938 937//937 -f 53//53 937//937 51//51 -f 51//51 937//937 936//936 -f 51//51 936//936 49//49 -f 49//49 936//936 934//934 -f 49//49 934//934 48//48 -f 48//48 934//934 932//932 -f 18//18 962//962 60//60 -f 60//60 962//962 981//981 -f 60//60 981//981 50//50 -f 50//50 981//981 979//979 -f 50//50 979//979 52//52 -f 52//52 979//979 977//977 -f 52//52 977//977 38//38 -f 38//38 977//977 976//976 -f 38//38 976//976 36//36 -f 36//36 976//976 975//975 -f 36//36 975//975 34//34 -f 34//34 975//975 973//973 -f 34//34 973//973 32//32 -f 32//32 973//973 971//971 -f 32//32 971//971 40//40 -f 40//40 971//971 969//969 -f 40//40 969//969 12//12 -f 12//12 969//969 967//967 -f 12//12 967//967 14//14 -f 14//14 967//967 965//965 -f 14//14 965//965 15//15 -f 15//15 965//965 963//963 -f 15//15 963//963 18//18 -f 18//18 963//963 962//962 -f 63//63 1085//1085 62//62 -f 62//62 1085//1085 1086//1086 -f 62//62 1086//1086 61//61 -f 61//61 1086//1086 1087//1087 -f 61//61 1087//1087 59//59 -f 59//59 1087//1087 1088//1088 -f 59//59 1088//1088 20//20 -f 20//20 1088//1088 1089//1089 -f 20//20 1089//1089 19//19 -f 19//19 1089//1089 1078//1078 -f 19//19 1078//1078 13//13 -f 13//13 1078//1078 1079//1079 -f 13//13 1079//1079 30//30 -f 30//30 1079//1079 1080//1080 -f 30//30 1080//1080 28//28 -f 28//28 1080//1080 1081//1081 -f 28//28 1081//1081 27//27 -f 27//27 1081//1081 1082//1082 -f 27//27 1082//1082 24//24 -f 24//24 1082//1082 1083//1083 -f 24//24 1083//1083 22//22 -f 22//22 1083//1083 1084//1084 -f 22//22 1084//1084 63//63 -f 63//63 1084//1084 1085//1085 -f 6//6 1036//1036 46//46 -f 46//46 1036//1036 1037//1037 -f 46//46 1037//1037 45//45 -f 45//45 1037//1037 1038//1038 -f 45//45 1038//1038 68//68 -f 68//68 1038//1038 1039//1039 -f 68//68 1039//1039 67//67 -f 67//67 1039//1039 1040//1040 -f 67//67 1040//1040 65//65 -f 65//65 1040//1040 1029//1029 -f 65//65 1029//1029 64//64 -f 64//64 1029//1029 1030//1030 -f 64//64 1030//1030 7//7 -f 7//7 1030//1030 1031//1031 -f 7//7 1031//1031 9//9 -f 9//9 1031//1031 1032//1032 -f 9//9 1032//1032 11//11 -f 11//11 1032//1032 1033//1033 -f 11//11 1033//1033 17//17 -f 17//17 1033//1033 1034//1034 -f 17//17 1034//1034 16//16 -f 16//16 1034//1034 1035//1035 -f 16//16 1035//1035 6//6 -f 6//6 1035//1035 1036//1036 -f 469//469 714//714 1090//1090 -f 1090//1090 714//714 716//716 -f 1090//1090 716//716 1091//1091 -f 1091//1091 716//716 1092//1092 -f 1092//1092 716//716 717//717 -f 1092//1092 717//717 1093//1093 -f 1093//1093 717//717 1094//1094 -f 1094//1094 717//717 360//360 -f 1094//1094 360//360 364//364 -f 364//364 363//363 1095//1095 -f 364//364 1095//1095 1094//1094 -f 1094//1094 1095//1095 1096//1096 -f 1094//1094 1096//1096 1093//1093 -f 1093//1093 1096//1096 1097//1097 -f 1093//1093 1097//1097 1092//1092 -f 1092//1092 1097//1097 1091//1091 -f 1091//1091 1097//1097 1098//1098 -f 1091//1091 1098//1098 1090//1090 -f 1090//1090 1098//1098 470//470 -f 1090//1090 470//470 469//469 -f 713//713 1099//1099 712//712 -f 712//712 1099//1099 784//784 -f 1099//1099 1100//1100 784//784 -f 784//784 1100//1100 1101//1101 -f 784//784 1101//1101 783//783 -f 148//148 250//250 1102//1102 -f 1102//1102 250//250 783//783 -f 1102//1102 783//783 1103//1103 -f 1103//1103 783//783 1101//1101 -f 713//713 909//909 1104//1104 -f 713//713 1104//1104 1099//1099 -f 1099//1099 1104//1104 1105//1105 -f 1099//1099 1105//1105 1100//1100 -f 1100//1100 1105//1105 1106//1106 -f 1100//1100 1106//1106 1101//1101 -f 1101//1101 1106//1106 1103//1103 -f 1103//1103 1106//1106 1107//1107 -f 1103//1103 1107//1107 1102//1102 -f 1102//1102 1107//1107 149//149 -f 1102//1102 149//149 148//148 -f 446//446 445//445 1108//1108 -f 446//446 1108//1108 1109//1109 -f 1109//1109 1108//1108 1110//1110 -f 1109//1109 1110//1110 1111//1111 -f 1111//1111 1110//1110 412//412 -f 1111//1111 412//412 413//413 -f 1112//1112 426//426 1113//1113 -f 1113//1113 426//426 424//424 -f 1113//1113 424//424 1114//1114 -f 1114//1114 424//424 422//422 -f 1114//1114 422//422 1115//1115 -f 1115//1115 422//422 420//420 -f 1115//1115 420//420 1116//1116 -f 1116//1116 420//420 443//443 -f 1116//1116 443//443 1117//1117 -f 1117//1117 443//443 442//442 -f 1117//1117 442//442 1118//1118 -f 1118//1118 442//442 441//441 -f 1118//1118 441//441 1119//1119 -f 1119//1119 441//441 437//437 -f 1119//1119 437//437 1120//1120 -f 1120//1120 437//437 436//436 -f 1120//1120 436//436 1121//1121 -f 1121//1121 436//436 434//434 -f 1121//1121 434//434 1122//1122 -f 1122//1122 434//434 432//432 -f 1122//1122 432//432 1123//1123 -f 1123//1123 432//432 430//430 -f 1123//1123 430//430 1124//1124 -f 1124//1124 430//430 429//429 -f 1124//1124 429//429 1125//1125 -f 1125//1125 429//429 417//417 -f 1125//1125 417//417 1126//1126 -f 1126//1126 417//417 416//416 -f 1126//1126 416//416 1127//1127 -f 1127//1127 416//416 453//453 -f 1127//1127 453//453 1128//1128 -f 1128//1128 453//453 452//452 -f 1128//1128 452//452 1129//1129 -f 1129//1129 452//452 450//450 -f 1129//1129 450//450 1130//1130 -f 1130//1130 450//450 448//448 -f 1130//1130 448//448 1131//1131 -f 1131//1131 448//448 447//447 -f 1131//1131 447//447 1132//1132 -f 1132//1132 447//447 461//461 -f 1132//1132 461//461 1133//1133 -f 1133//1133 461//461 460//460 -f 1133//1133 460//460 1134//1134 -f 1134//1134 460//460 459//459 -f 1134//1134 459//459 1135//1135 -f 1135//1135 459//459 458//458 -f 1135//1135 458//458 1136//1136 -f 1136//1136 458//458 457//457 -f 1136//1136 457//457 1137//1137 -f 1137//1137 457//457 454//454 -f 1137//1137 454//454 1112//1112 -f 1112//1112 454//454 426//426 -f 1138//1138 1135//1135 1139//1139 -f 1139//1139 1135//1135 1136//1136 -f 1139//1139 1136//1136 1140//1140 -f 1140//1140 1136//1136 1137//1137 -f 1140//1140 1137//1137 1141//1141 -f 1141//1141 1137//1137 1112//1112 -f 1141//1141 1112//1112 1142//1142 -f 1142//1142 1112//1112 1113//1113 -f 1142//1142 1113//1113 1143//1143 -f 1144//1144 1128//1128 1145//1145 -f 1145//1145 1128//1128 1129//1129 -f 1145//1145 1129//1129 1146//1146 -f 1146//1146 1129//1129 1130//1130 -f 1146//1146 1130//1130 1147//1147 -f 1147//1147 1130//1130 1131//1131 -f 1147//1147 1131//1131 1148//1148 -f 1148//1148 1131//1131 1132//1132 -f 1148//1148 1132//1132 1149//1149 -f 1149//1149 1132//1132 1133//1133 -f 1149//1149 1133//1133 1138//1138 -f 1138//1138 1133//1133 1134//1134 -f 1138//1138 1134//1134 1135//1135 -f 1113//1113 1114//1114 1143//1143 -f 1143//1143 1114//1114 1115//1115 -f 1143//1143 1115//1115 1150//1150 -f 1150//1150 1115//1115 1116//1116 -f 1150//1150 1116//1116 1151//1151 -f 1151//1151 1116//1116 1117//1117 -f 1151//1151 1117//1117 1152//1152 -f 1152//1152 1117//1117 1118//1118 -f 1152//1152 1118//1118 1153//1153 -f 1153//1153 1118//1118 1119//1119 -f 1153//1153 1119//1119 1154//1154 -f 1154//1154 1119//1119 1120//1120 -f 1154//1154 1120//1120 1155//1155 -f 1120//1120 1121//1121 1155//1155 -f 1155//1155 1121//1121 1122//1122 -f 1155//1155 1122//1122 1156//1156 -f 1156//1156 1122//1122 1123//1123 -f 1156//1156 1123//1123 1157//1157 -f 1157//1157 1123//1123 1124//1124 -f 1157//1157 1124//1124 1158//1158 -f 1158//1158 1124//1124 1125//1125 -f 1158//1158 1125//1125 1159//1159 -f 1159//1159 1125//1125 1126//1126 -f 1159//1159 1126//1126 1144//1144 -f 1144//1144 1126//1126 1127//1127 -f 1144//1144 1127//1127 1128//1128 -f 1160//1160 1142//1142 1161//1161 -f 1161//1161 1142//1142 1143//1143 -f 1161//1161 1143//1143 1162//1162 -f 1162//1162 1143//1143 1150//1150 -f 1162//1162 1150//1150 1163//1163 -f 1163//1163 1150//1150 1151//1151 -f 1163//1163 1151//1151 1164//1164 -f 1164//1164 1151//1151 1152//1152 -f 1164//1164 1152//1152 1165//1165 -f 1165//1165 1152//1152 1153//1153 -f 1165//1165 1153//1153 1166//1166 -f 1166//1166 1153//1153 1154//1154 -f 1166//1166 1154//1154 1167//1167 -f 1167//1167 1154//1154 1155//1155 -f 1167//1167 1155//1155 1168//1168 -f 1168//1168 1155//1155 1156//1156 -f 1168//1168 1156//1156 1169//1169 -f 1169//1169 1156//1156 1157//1157 -f 1169//1169 1157//1157 1170//1170 -f 1170//1170 1157//1157 1158//1158 -f 1170//1170 1158//1158 1171//1171 -f 1171//1171 1158//1158 1159//1159 -f 1171//1171 1159//1159 1172//1172 -f 1172//1172 1159//1159 1144//1144 -f 1172//1172 1144//1144 1173//1173 -f 1173//1173 1144//1144 1145//1145 -f 1173//1173 1145//1145 1174//1174 -f 1174//1174 1145//1145 1146//1146 -f 1174//1174 1146//1146 1175//1175 -f 1175//1175 1146//1146 1147//1147 -f 1175//1175 1147//1147 1176//1176 -f 1176//1176 1147//1147 1148//1148 -f 1176//1176 1148//1148 1177//1177 -f 1177//1177 1148//1148 1149//1149 -f 1177//1177 1149//1149 1178//1178 -f 1178//1178 1149//1149 1138//1138 -f 1178//1178 1138//1138 1179//1179 -f 1179//1179 1138//1138 1139//1139 -f 1179//1179 1139//1139 1180//1180 -f 1180//1180 1139//1139 1140//1140 -f 1180//1180 1140//1140 1181//1181 -f 1181//1181 1140//1140 1141//1141 -f 1181//1181 1141//1141 1160//1160 -f 1160//1160 1141//1141 1142//1142 -f 1182//1182 1178//1178 1183//1183 -f 1183//1183 1178//1178 1179//1179 -f 1183//1183 1179//1179 1184//1184 -f 1184//1184 1179//1179 1180//1180 -f 1184//1184 1180//1180 1185//1185 -f 1185//1185 1180//1180 1181//1181 -f 1185//1185 1181//1181 1186//1186 -f 1186//1186 1181//1181 1160//1160 -f 1186//1186 1160//1160 1187//1187 -f 1187//1187 1160//1160 1161//1161 -f 1187//1187 1161//1161 1188//1188 -f 1188//1188 1161//1161 1162//1162 -f 1188//1188 1162//1162 1189//1189 -f 1190//1190 1172//1172 1191//1191 -f 1191//1191 1172//1172 1173//1173 -f 1191//1191 1173//1173 1192//1192 -f 1192//1192 1173//1173 1174//1174 -f 1192//1192 1174//1174 1193//1193 -f 1193//1193 1174//1174 1175//1175 -f 1193//1193 1175//1175 1194//1194 -f 1194//1194 1175//1175 1176//1176 -f 1194//1194 1176//1176 1182//1182 -f 1182//1182 1176//1176 1177//1177 -f 1182//1182 1177//1177 1178//1178 -f 1162//1162 1163//1163 1189//1189 -f 1189//1189 1163//1163 1164//1164 -f 1189//1189 1164//1164 1195//1195 -f 1195//1195 1164//1164 1165//1165 -f 1195//1195 1165//1165 1196//1196 -f 1196//1196 1165//1165 1166//1166 -f 1196//1196 1166//1166 1197//1197 -f 1197//1197 1166//1166 1167//1167 -f 1197//1197 1167//1167 1198//1198 -f 1198//1198 1167//1167 1168//1168 -f 1198//1198 1168//1168 1199//1199 -f 1199//1199 1168//1168 1169//1169 -f 1199//1199 1169//1169 1200//1200 -f 1200//1200 1169//1169 1170//1170 -f 1200//1200 1170//1170 1190//1190 -f 1190//1190 1170//1170 1171//1171 -f 1190//1190 1171//1171 1172//1172 -f 1201//1201 1186//1186 1202//1202 -f 1202//1202 1186//1186 1187//1187 -f 1202//1202 1187//1187 1203//1203 -f 1203//1203 1187//1187 1188//1188 -f 1203//1203 1188//1188 1204//1204 -f 1204//1204 1188//1188 1189//1189 -f 1204//1204 1189//1189 1205//1205 -f 1205//1205 1189//1189 1195//1195 -f 1205//1205 1195//1195 1206//1206 -f 1206//1206 1195//1195 1196//1196 -f 1206//1206 1196//1196 1207//1207 -f 1207//1207 1196//1196 1197//1197 -f 1207//1207 1197//1197 1208//1208 -f 1208//1208 1197//1197 1198//1198 -f 1208//1208 1198//1198 1209//1209 -f 1209//1209 1198//1198 1199//1199 -f 1209//1209 1199//1199 1210//1210 -f 1210//1210 1199//1199 1200//1200 -f 1210//1210 1200//1200 1211//1211 -f 1211//1211 1200//1200 1190//1190 -f 1211//1211 1190//1190 1212//1212 -f 1212//1212 1190//1190 1191//1191 -f 1212//1212 1191//1191 1213//1213 -f 1213//1213 1191//1191 1192//1192 -f 1213//1213 1192//1192 1214//1214 -f 1214//1214 1192//1192 1193//1193 -f 1214//1214 1193//1193 1215//1215 -f 1215//1215 1193//1193 1194//1194 -f 1215//1215 1194//1194 1216//1216 -f 1216//1216 1194//1194 1182//1182 -f 1216//1216 1182//1182 1217//1217 -f 1217//1217 1182//1182 1183//1183 -f 1217//1217 1183//1183 1218//1218 -f 1218//1218 1183//1183 1184//1184 -f 1218//1218 1184//1184 1219//1219 -f 1219//1219 1184//1184 1185//1185 -f 1219//1219 1185//1185 1201//1201 -f 1201//1201 1185//1185 1186//1186 -f 1201//1201 1202//1202 1220//1220 -f 1217//1217 1218//1218 1220//1220 -f 1220//1220 1218//1218 1219//1219 -f 1220//1220 1219//1219 1201//1201 -f 1214//1214 1215//1215 1220//1220 -f 1220//1220 1215//1215 1216//1216 -f 1220//1220 1216//1216 1217//1217 -f 1211//1211 1212//1212 1220//1220 -f 1220//1220 1212//1212 1213//1213 -f 1220//1220 1213//1213 1214//1214 -f 1208//1208 1209//1209 1220//1220 -f 1220//1220 1209//1209 1210//1210 -f 1220//1220 1210//1210 1211//1211 -f 1205//1205 1206//1206 1220//1220 -f 1220//1220 1206//1206 1207//1207 -f 1220//1220 1207//1207 1208//1208 -f 1202//1202 1203//1203 1220//1220 -f 1220//1220 1203//1203 1204//1204 -f 1220//1220 1204//1204 1205//1205 -f 778//778 263//263 774//774 -f 774//774 263//263 258//258 -f 768//768 280//280 764//764 -f 764//764 280//280 269//269 -f 758//758 289//289 754//754 -f 754//754 289//289 286//286 -f 216//216 744//744 217//217 -f 217//217 744//744 748//748 -f 217//217 748//748 227//227 -f 311//311 731//731 146//146 -f 146//146 731//731 736//736 -f 146//146 736//736 147//147 -f 708//708 313//313 709//709 -f 709//709 313//313 312//312 -f 316//316 696//696 315//315 -f 315//315 696//696 695//695 -f 315//315 695//695 314//314 -f 648//648 337//337 649//649 -f 649//649 337//337 336//336 -f 642//642 357//357 643//643 -f 643//643 357//357 356//356 -f 636//636 381//381 637//637 -f 637//637 381//381 380//380 -f 528//528 638//638 529//529 -f 529//529 638//638 639//639 -f 612//612 635//635 611//611 -f 611//611 635//635 634//634 -f 586//586 644//644 587//587 -f 587//587 644//644 645//645 -f 572//572 641//641 573//573 -f 573//573 641//641 640//640 -f 568//568 650//650 569//569 -f 569//569 650//650 651//651 -f 564//564 647//647 565//565 -f 565//565 647//647 646//646 -f 554//554 697//697 555//555 -f 555//555 697//697 698//698 -f 582//582 694//694 583//583 -f 583//583 694//694 693//693 -f 530//530 776//776 531//531 -f 531//531 776//776 775//775 -f 546//546 780//780 547//547 -f 547//547 780//780 773//773 -f 534//534 766//766 535//535 -f 535//535 766//766 765//765 -f 551//551 770//770 552//552 -f 552//552 770//770 763//763 -f 538//538 756//756 539//539 -f 539//539 756//756 755//755 -f 558//558 760//760 559//559 -f 559//559 760//760 753//753 -f 577//577 746//746 578//578 -f 578//578 746//746 745//745 -f 580//580 750//750 581//581 -f 581//581 750//750 743//743 -f 604//604 710//710 605//605 -f 605//605 710//710 711//711 -f 601//601 707//707 602//602 -f 602//602 707//707 706//706 -f 596//596 738//738 597//597 -f 597//597 738//738 732//732 -f 523//523 734//734 524//524 -f 524//524 734//734 733//733 -f 782//782 255//255 781//781 -f 781//781 255//255 256//256 -f 276//276 771//771 277//277 -f 277//277 771//771 772//772 -f 277//277 772//772 251//251 -f 291//291 761//761 299//299 -f 299//299 761//761 762//762 -f 299//299 762//762 268//268 -f 229//229 751//751 294//294 -f 294//294 751//751 752//752 -f 294//294 752//752 285//285 -f 742//742 218//218 741//741 -f 741//741 218//218 220//220 -f 740//740 220//220 739//739 -f 739//739 220//220 223//223 -f 718//718 362//362 715//715 -f 715//715 362//362 361//361 -f 378//378 719//719 379//379 -f 379//379 719//719 720//720 -f 379//379 720//720 344//344 -f 347//347 721//721 348//348 -f 348//348 721//721 722//722 -f 348//348 722//722 323//323 -f 331//331 723//723 330//330 -f 330//330 723//723 724//724 -f 330//330 724//724 159//159 -f 728//728 180//180 727//727 -f 727//727 180//180 178//178 -f 726//726 178//178 725//725 -f 725//725 178//178 176//176 -f 730//730 207//207 729//729 -f 729//729 207//207 206//206 -f 729//729 206//206 193//193 -f 415//415 983//983 386//386 -f 386//386 983//983 384//384 -f 983//983 415//415 984//984 -f 984//984 415//415 449//449 -f 984//984 449//449 985//985 -f 985//985 449//449 451//451 -f 985//985 451//451 961//961 -f 961//961 451//451 418//418 -f 989//989 363//363 385//385 -f 385//385 363//363 365//365 -f 446//446 960//960 418//418 -f 418//418 960//960 961//961 -f 987//987 470//470 986//986 -f 986//986 470//470 1098//1098 -f 986//986 1098//1098 991//991 -f 991//991 1098//1098 1097//1097 -f 991//991 1097//1097 992//992 -f 992//992 1097//1097 1096//1096 -f 992//992 1096//1096 990//990 -f 990//990 1096//1096 1095//1095 -f 990//990 1095//1095 989//989 -f 989//989 1095//1095 363//363 -f 960//960 446//446 1109//1109 -f 960//960 1109//1109 959//959 -f 959//959 1109//1109 1111//1111 -f 959//959 1111//1111 958//958 -f 958//958 1111//1111 413//413 -f 958//958 413//413 955//955 -f 988//988 471//471 987//987 -f 987//987 471//471 470//470 -f 408//408 956//956 413//413 -f 413//413 956//956 955//955 -f 974//974 409//409 462//462 -f 471//471 988//988 468//468 -f 468//468 988//988 964//964 -f 468//468 964//964 966//966 -f 974//974 462//462 972//972 -f 972//972 462//462 463//463 -f 972//972 463//463 970//970 -f 970//970 463//463 464//464 -f 970//970 464//464 968//968 -f 464//464 465//465 968//968 -f 968//968 465//465 466//466 -f 968//968 466//466 966//966 -f 966//966 466//466 467//467 -f 966//966 467//467 468//468 -f 409//409 974//974 408//408 -f 408//408 974//974 956//956 -f 947//947 435//435 786//786 -f 786//786 435//435 439//439 -f 785//785 249//249 948//948 -f 948//948 249//249 150//150 -f 948//948 150//150 149//149 -f 919//919 444//444 953//953 -f 953//953 444//444 431//431 -f 953//953 431//431 954//954 -f 954//954 431//431 433//433 -f 954//954 433//433 947//947 -f 947//947 433//433 435//435 -f 926//926 925//925 949//949 -f 926//926 949//949 909//909 -f 948//948 149//149 950//950 -f 950//950 149//149 1107//1107 -f 950//950 1107//1107 951//951 -f 951//951 1107//1107 1106//1106 -f 951//951 1106//1106 952//952 -f 952//952 1106//1106 1105//1105 -f 952//952 1105//1105 949//949 -f 949//949 1105//1105 1104//1104 -f 949//949 1104//1104 909//909 -f 918//918 445//445 919//919 -f 919//919 445//445 444//444 -f 909//909 910//910 926//926 -f 923//923 412//412 1110//1110 -f 923//923 1110//1110 922//922 -f 922//922 1110//1110 1108//1108 -f 922//922 1108//1108 921//921 -f 921//921 1108//1108 445//445 -f 921//921 445//445 918//918 -f 927//927 926//926 910//910 -f 910//910 911//911 927//927 -f 927//927 911//911 912//912 -f 927//927 912//912 945//945 -f 945//945 912//912 913//913 -f 913//913 914//914 945//945 -f 945//945 914//914 915//915 -f 945//945 915//915 943//943 -f 915//915 916//916 943//943 -f 943//943 916//916 917//917 -f 943//943 917//917 941//941 -f 941//941 917//917 410//410 -f 941//941 410//410 939//939 -f 924//924 411//411 923//923 -f 923//923 411//411 412//412 -f 411//411 924//924 410//410 -f 410//410 924//924 939//939 -f 414//414 387//387 798//798 -f 798//798 387//387 388//388 -f 405//405 798//798 388//388 -f 404//404 797//797 405//405 -f 405//405 797//797 798//798 -f 1043//1043 1073//1073 382//382 -f 382//382 1073//1073 383//383 -f 383//383 400//400 388//388 -f 388//388 400//400 405//405 -f 797//797 404//404 796//796 -f 796//796 404//404 406//406 -f 796//796 406//406 795//795 -f 795//795 406//406 407//407 -f 795//795 407//407 794//794 -f 794//794 407//407 399//399 -f 794//794 399//399 793//793 -f 793//793 399//399 398//398 -f 793//793 398//398 792//792 -f 792//792 398//398 396//396 -f 792//792 396//396 791//791 -f 791//791 396//396 395//395 -f 791//791 395//395 790//790 -f 790//790 395//395 403//403 -f 382//382 163//163 174//174 -f 190//190 200//200 1046//1046 -f 1046//1046 200//200 390//390 -f 1046//1046 390//390 1044//1044 -f 190//190 1046//1046 189//189 -f 189//189 1046//1046 1051//1051 -f 189//189 1051//1051 198//198 -f 1051//1051 1050//1050 198//198 -f 198//198 1050//1050 1054//1054 -f 198//198 1054//1054 199//199 -f 1054//1054 1053//1053 199//199 -f 199//199 1053//1053 1057//1057 -f 199//199 1057//1057 179//179 -f 1057//1057 1056//1056 179//179 -f 179//179 1056//1056 1060//1060 -f 179//179 1060//1060 177//177 -f 1060//1060 1059//1059 177//177 -f 177//177 1059//1059 1063//1063 -f 177//177 1063//1063 168//168 -f 168//168 1063//1063 1062//1062 -f 168//168 1062//1062 169//169 -f 169//169 1062//1062 1066//1066 -f 169//169 1066//1066 171//171 -f 1066//1066 1065//1065 171//171 -f 171//171 1065//1065 1069//1069 -f 171//171 1069//1069 173//173 -f 1069//1069 1068//1068 173//173 -f 173//173 1068//1068 1072//1072 -f 173//173 1072//1072 174//174 -f 174//174 1072//1072 1071//1071 -f 174//174 1071//1071 382//382 -f 382//382 1071//1071 1070//1070 -f 382//382 1070//1070 1043//1043 -f 383//383 1073//1073 400//400 -f 394//394 789//789 403//403 -f 403//403 789//789 790//790 -f 789//789 788//788 438//438 -f 438//438 788//788 440//440 -f 389//389 1077//1077 390//390 -f 390//390 1077//1077 1044//1044 -f 1076//1076 1077//1077 401//401 -f 1076//1076 401//401 1075//1075 -f 1075//1075 401//401 397//397 -f 1075//1075 397//397 1074//1074 -f 1074//1074 397//397 400//400 -f 1074//1074 400//400 1073//1073 -f 789//789 394//394 788//788 -f 1077//1077 389//389 401//401 -f 393//393 787//787 394//394 -f 394//394 787//787 788//788 -f 391//391 402//402 389//389 -f 389//389 402//402 401//401 -f 402//402 1024//1024 1025//1025 -f 402//402 1025//1025 392//392 -f 392//392 1025//1025 1026//1026 -f 392//392 1026//1026 393//393 -f 393//393 1026//1026 1027//1027 -f 393//393 1027//1027 1028//1028 -f 393//393 1028//1028 787//787 -f 402//402 391//391 1024//1024 -f 151//151 787//787 152//152 -f 152//152 787//787 1028//1028 -f 152//152 1028//1028 993//993 -f 391//391 203//203 1024//1024 -f 1024//1024 203//203 205//205 -f 1024//1024 205//205 1022//1022 -f 1022//1022 205//205 1023//1023 -f 1023//1023 205//205 204//204 -f 153//153 152//152 993//993 -f 993//993 995//995 153//153 -f 153//153 995//995 997//997 -f 153//153 997//997 236//236 -f 997//997 1001//1001 236//236 -f 236//236 1001//1001 1000//1000 -f 236//236 1000//1000 242//242 -f 1000//1000 1004//1004 242//242 -f 242//242 1004//1004 1003//1003 -f 242//242 1003//1003 241//241 -f 1003//1003 1007//1007 241//241 -f 241//241 1007//1007 1006//1006 -f 241//241 1006//1006 219//219 -f 219//219 1006//1006 221//221 -f 1006//1006 1014//1014 221//221 -f 221//221 1014//1014 1013//1013 -f 221//221 1013//1013 222//222 -f 222//222 1013//1013 1011//1011 -f 222//222 1011//1011 224//224 -f 224//224 1011//1011 1009//1009 -f 224//224 1009//1009 310//310 -f 310//310 1009//1009 308//308 -f 308//308 1009//1009 1017//1017 -f 308//308 1017//1017 306//306 -f 1017//1017 1016//1016 306//306 -f 306//306 1016//1016 1020//1020 -f 306//306 1020//1020 204//204 -f 204//204 1020//1020 1019//1019 -f 204//204 1019//1019 1023//1023 -f 1221//1221 1222//1222 1223//1223 -f 1224//1224 1225//1225 1226//1226 -f 1227//1227 1228//1228 1229//1229 -f 1230//1230 1231//1231 1232//1232 -f 1233//1233 1234//1234 1235//1235 -f 1236//1236 1237//1237 1238//1238 -f 1238//1238 1237//1237 1239//1239 -f 1238//1238 1239//1239 1240//1240 -f 1241//1241 1242//1242 1243//1243 -f 1243//1243 1244//1244 1241//1241 -f 1241//1241 1244//1244 1245//1245 -f 1241//1241 1245//1245 1246//1246 -f 1246//1246 1245//1245 1247//1247 -f 1246//1246 1247//1247 1248//1248 -f 1249//1249 1250//1250 1251//1251 -f 1251//1251 1250//1250 1252//1252 -f 1251//1251 1252//1252 1253//1253 -f 1253//1253 1252//1252 1254//1254 -f 1253//1253 1254//1254 1248//1248 -f 1248//1248 1254//1254 1255//1255 -f 1248//1248 1255//1255 1246//1246 -f 1256//1256 1257//1257 1258//1258 -f 1258//1258 1257//1257 1259//1259 -f 1258//1258 1259//1259 1260//1260 -f 1260//1260 1259//1259 1261//1261 -f 1260//1260 1261//1261 1262//1262 -f 1261//1261 1263//1263 1262//1262 -f 1262//1262 1263//1263 1264//1264 -f 1262//1262 1264//1264 1232//1232 -f 1232//1232 1264//1264 1265//1265 -f 1232//1232 1265//1265 1266//1266 -f 1267//1267 1268//1268 1269//1269 -f 1269//1269 1268//1268 1270//1270 -f 1269//1269 1270//1270 1271//1271 -f 1271//1271 1270//1270 1272//1272 -f 1273//1273 1274//1274 1275//1275 -f 1275//1275 1274//1274 1276//1276 -f 1275//1275 1276//1276 1277//1277 -f 1273//1273 1278//1278 1274//1274 -f 1274//1274 1278//1278 1279//1279 -f 1274//1274 1279//1279 1280//1280 -f 1280//1280 1279//1279 1281//1281 -f 1280//1280 1281//1281 1282//1282 -f 1283//1283 1284//1284 1285//1285 -f 1286//1286 1287//1287 1288//1288 -f 1288//1288 1287//1287 1289//1289 -f 1288//1288 1289//1289 1275//1275 -f 1275//1275 1289//1289 1290//1290 -f 1275//1275 1290//1290 1273//1273 -f 1281//1281 1291//1291 1282//1282 -f 1282//1282 1291//1291 1292//1292 -f 1282//1282 1292//1292 1284//1284 -f 1284//1284 1292//1292 1293//1293 -f 1284//1284 1293//1293 1285//1285 -f 1294//1294 1295//1295 1296//1296 -f 1295//1295 1297//1297 1296//1296 -f 1296//1296 1297//1297 1298//1298 -f 1296//1296 1298//1298 1299//1299 -f 1299//1299 1298//1298 1300//1300 -f 1300//1300 1301//1301 1299//1299 -f 1299//1299 1301//1301 1302//1302 -f 1299//1299 1302//1302 1303//1303 -f 1302//1302 1304//1304 1303//1303 -f 1303//1303 1304//1304 1305//1305 -f 1303//1303 1305//1305 1306//1306 -f 1306//1306 1305//1305 1307//1307 -f 1306//1306 1307//1307 1308//1308 -f 1308//1308 1307//1307 1309//1309 -f 1308//1308 1309//1309 1310//1310 -f 1310//1310 1309//1309 1311//1311 -f 1310//1310 1311//1311 1294//1294 -f 1312//1312 1313//1313 1314//1314 -f 1314//1314 1313//1313 1315//1315 -f 1314//1314 1315//1315 1316//1316 -f 1316//1316 1315//1315 1317//1317 -f 1316//1316 1317//1317 1318//1318 -f 1318//1318 1319//1319 1316//1316 -f 1316//1316 1319//1319 1320//1320 -f 1316//1316 1320//1320 1321//1321 -f 1322//1322 1323//1323 1324//1324 -f 1320//1320 1325//1325 1321//1321 -f 1321//1321 1325//1325 1326//1326 -f 1321//1321 1326//1326 1323//1323 -f 1324//1324 1327//1327 1322//1322 -f 1322//1322 1327//1327 1328//1328 -f 1322//1322 1328//1328 1329//1329 -f 1329//1329 1328//1328 1330//1330 -f 1329//1329 1330//1330 1331//1331 -f 1331//1331 1330//1330 1332//1332 -f 1331//1331 1332//1332 1317//1317 -f 1317//1317 1332//1332 1333//1333 -f 1317//1317 1333//1333 1318//1318 -f 1334//1334 1335//1335 1336//1336 -f 1336//1336 1335//1335 1337//1337 -f 1336//1336 1337//1337 1338//1338 -f 1339//1339 1340//1340 1341//1341 -f 1341//1341 1340//1340 1342//1342 -f 1341//1341 1342//1342 1343//1343 -f 1339//1339 1344//1344 1340//1340 -f 1340//1340 1344//1344 1345//1345 -f 1340//1340 1345//1345 1346//1346 -f 1346//1346 1345//1345 1347//1347 -f 1346//1346 1347//1347 1348//1348 -f 1348//1348 1347//1347 1349//1349 -f 1348//1348 1349//1349 1337//1337 -f 1337//1337 1349//1349 1350//1350 -f 1337//1337 1350//1350 1338//1338 -f 1351//1351 1352//1352 1353//1353 -f 1353//1353 1352//1352 1336//1336 -f 1353//1353 1336//1336 1354//1354 -f 1354//1354 1336//1336 1338//1338 -f 1355//1355 1356//1356 1357//1357 -f 1355//1355 1357//1357 1358//1358 -f 1359//1359 1360//1360 1336//1336 -f 1336//1336 1360//1360 1361//1361 -f 1336//1336 1361//1361 1334//1334 -f 1334//1334 1361//1361 1362//1362 -f 1334//1334 1362//1362 1363//1363 -f 1364//1364 1365//1365 1366//1366 -f 1367//1367 1368//1368 1369//1369 -f 1368//1368 1370//1370 1369//1369 -f 1369//1369 1370//1370 1371//1371 -f 1369//1369 1371//1371 1372//1372 -f 1372//1372 1371//1371 1373//1373 -f 1357//1357 1374//1374 1358//1358 -f 1358//1358 1374//1374 1375//1375 -f 1358//1358 1375//1375 1376//1376 -f 1376//1376 1375//1375 1377//1377 -f 1378//1378 1223//1223 1379//1379 -f 1379//1379 1223//1223 1380//1380 -f 1379//1379 1380//1380 1342//1342 -f 1342//1342 1380//1380 1352//1352 -f 1342//1342 1352//1352 1343//1343 -f 1343//1343 1352//1352 1351//1351 -f 1381//1381 1382//1382 1383//1383 -f 1384//1384 1383//1383 1385//1385 -f 1386//1386 1387//1387 1388//1388 -f 1388//1388 1387//1387 1358//1358 -f 1388//1388 1358//1358 1389//1389 -f 1389//1389 1358//1358 1376//1376 -f 1389//1389 1376//1376 1390//1390 -f 1390//1390 1376//1376 1377//1377 -f 1390//1390 1377//1377 1391//1391 -f 1299//1299 1392//1392 1296//1296 -f 1296//1296 1392//1392 1393//1393 -f 1296//1296 1393//1393 1390//1390 -f 1390//1390 1393//1393 1394//1394 -f 1390//1390 1394//1394 1389//1389 -f 1395//1395 1396//1396 1397//1397 -f 1398//1398 1306//1306 1399//1399 -f 1399//1399 1306//1306 1308//1308 -f 1399//1399 1308//1308 1400//1400 -f 1400//1400 1308//1308 1397//1397 -f 1401//1401 1402//1402 1403//1403 -f 1404//1404 1402//1402 1405//1405 -f 1405//1405 1402//1402 1401//1401 -f 1405//1405 1401//1401 1406//1406 -f 1267//1267 1256//1256 1268//1268 -f 1268//1268 1256//1256 1258//1258 -f 1268//1268 1258//1258 1407//1407 -f 1407//1407 1258//1258 1408//1408 -f 1407//1407 1408//1408 1409//1409 -f 1409//1409 1408//1408 1410//1410 -f 1409//1409 1410//1410 1411//1411 -f 1229//1229 1228//1228 1270//1270 -f 1266//1266 1272//1272 1232//1232 -f 1232//1232 1272//1272 1270//1270 -f 1232//1232 1270//1270 1230//1230 -f 1230//1230 1270//1270 1228//1228 -f 1230//1230 1228//1228 1412//1412 -f 1229//1229 1413//1413 1227//1227 -f 1227//1227 1413//1413 1414//1414 -f 1227//1227 1414//1414 1415//1415 -f 1415//1415 1414//1414 1416//1416 -f 1417//1417 1418//1418 1414//1414 -f 1414//1414 1418//1418 1419//1419 -f 1414//1414 1419//1419 1416//1416 -f 1420//1420 1421//1421 1422//1422 -f 1422//1422 1421//1421 1423//1423 -f 1422//1422 1423//1423 1424//1424 -f 1424//1424 1423//1423 1425//1425 -f 1426//1426 1427//1427 1423//1423 -f 1428//1428 1425//1425 1429//1429 -f 1429//1429 1425//1425 1423//1423 -f 1429//1429 1423//1423 1430//1430 -f 1430//1430 1423//1423 1427//1427 -f 1431//1431 1432//1432 1433//1433 -f 1323//1323 1322//1322 1321//1321 -f 1321//1321 1322//1322 1434//1434 -f 1321//1321 1434//1434 1435//1435 -f 1435//1435 1436//1436 1321//1321 -f 1321//1321 1436//1436 1437//1437 -f 1321//1321 1437//1437 1438//1438 -f 1438//1438 1437//1437 1431//1431 -f 1439//1439 1440//1440 1441//1441 -f 1441//1441 1442//1442 1439//1439 -f 1439//1439 1442//1442 1443//1443 -f 1439//1439 1443//1443 1274//1274 -f 1274//1274 1443//1443 1444//1444 -f 1274//1274 1444//1444 1276//1276 -f 1442//1442 1445//1445 1443//1443 -f 1443//1443 1445//1445 1446//1446 -f 1443//1443 1446//1446 1447//1447 -f 1447//1447 1446//1446 1448//1448 -f 1447//1447 1448//1448 1449//1449 -f 1448//1448 1450//1450 1449//1449 -f 1449//1449 1450//1450 1451//1451 -f 1449//1449 1451//1451 1452//1452 -f 1453//1453 1454//1454 1455//1455 -f 1455//1455 1454//1454 1456//1456 -f 1455//1455 1456//1456 1440//1440 -f 1440//1440 1456//1456 1457//1457 -f 1440//1440 1457//1457 1441//1441 -f 1308//1308 1458//1458 1449//1449 -f 1397//1397 1308//1308 1395//1395 -f 1395//1395 1308//1308 1449//1449 -f 1395//1395 1449//1449 1455//1455 -f 1455//1455 1449//1449 1452//1452 -f 1455//1455 1452//1452 1453//1453 -f 1294//1294 1296//1296 1310//1310 -f 1310//1310 1296//1296 1459//1459 -f 1310//1310 1459//1459 1308//1308 -f 1308//1308 1459//1459 1460//1460 -f 1308//1308 1460//1460 1458//1458 -f 1461//1461 1462//1462 1390//1390 -f 1462//1462 1463//1463 1390//1390 -f 1390//1390 1463//1463 1464//1464 -f 1390//1390 1464//1464 1296//1296 -f 1296//1296 1464//1464 1465//1465 -f 1296//1296 1465//1465 1459//1459 -f 1466//1466 1467//1467 1468//1468 -f 1468//1468 1467//1467 1461//1461 -f 1468//1468 1461//1461 1469//1469 -f 1469//1469 1461//1461 1390//1390 -f 1469//1469 1390//1390 1470//1470 -f 1470//1470 1390//1390 1391//1391 -f 1471//1471 1466//1466 1369//1369 -f 1369//1369 1466//1466 1468//1468 -f 1369//1369 1468//1468 1367//1367 -f 1367//1367 1468//1468 1469//1469 -f 1367//1367 1469//1469 1472//1472 -f 1472//1472 1469//1469 1470//1470 -f 1473//1473 1474//1474 1475//1475 -f 1475//1475 1474//1474 1476//1476 -f 1475//1475 1476//1476 1477//1477 -f 1477//1477 1476//1476 1478//1478 -f 1477//1477 1478//1478 1369//1369 -f 1369//1369 1478//1478 1479//1479 -f 1369//1369 1479//1479 1471//1471 -f 1480//1480 1481//1481 1482//1482 -f 1481//1481 1480//1480 1483//1483 -f 1484//1484 1485//1485 1486//1486 -f 1487//1487 1488//1488 1489//1489 -f 1485//1485 1484//1484 1489//1489 -f 1489//1489 1484//1484 1490//1490 -f 1489//1489 1490//1490 1487//1487 -f 1488//1488 1487//1487 1491//1491 -f 1491//1491 1487//1487 1492//1492 -f 1491//1491 1492//1492 1493//1493 -f 1494//1494 1495//1495 1481//1481 -f 1481//1481 1495//1495 1496//1496 -f 1481//1481 1496//1496 1482//1482 -f 1482//1482 1496//1496 1497//1497 -f 1482//1482 1497//1497 1498//1498 -f 1498//1498 1497//1497 1499//1499 -f 1498//1498 1499//1499 1500//1500 -f 1500//1500 1499//1499 1501//1501 -f 1500//1500 1501//1501 1502//1502 -f 1502//1502 1501//1501 1503//1503 -f 1502//1502 1503//1503 1504//1504 -f 1505//1505 1506//1506 1507//1507 -f 1507//1507 1506//1506 1508//1508 -f 1505//1505 1509//1509 1506//1506 -f 1506//1506 1509//1509 1510//1510 -f 1506//1506 1510//1510 1242//1242 -f 1242//1242 1510//1510 1511//1511 -f 1242//1242 1511//1511 1243//1243 -f 1243//1243 1511//1511 1512//1512 -f 1243//1243 1512//1512 1513//1513 -f 1513//1513 1512//1512 1514//1514 -f 1513//1513 1514//1514 1236//1236 -f 1236//1236 1514//1514 1515//1515 -f 1236//1236 1515//1515 1237//1237 -f 1516//1516 1517//1517 1518//1518 -f 1518//1518 1517//1517 1519//1519 -f 1518//1518 1519//1519 1508//1508 -f 1508//1508 1519//1519 1520//1520 -f 1508//1508 1520//1520 1507//1507 -f 1521//1521 1522//1522 1523//1523 -f 1523//1523 1522//1522 1524//1524 -f 1523//1523 1524//1524 1525//1525 -f 1516//1516 1518//1518 1526//1526 -f 1526//1526 1518//1518 1527//1527 -f 1526//1526 1527//1527 1528//1528 -f 1528//1528 1527//1527 1421//1421 -f 1528//1528 1421//1421 1529//1529 -f 1529//1529 1421//1421 1420//1420 -f 1529//1529 1420//1420 1523//1523 -f 1523//1523 1420//1420 1530//1530 -f 1523//1523 1530//1530 1521//1521 -f 1429//1429 1531//1531 1428//1428 -f 1428//1428 1531//1531 1532//1532 -f 1428//1428 1532//1532 1533//1533 -f 1533//1533 1532//1532 1534//1534 -f 1533//1533 1534//1534 1535//1535 -f 1535//1535 1534//1534 1536//1536 -f 1535//1535 1536//1536 1537//1537 -f 1537//1537 1536//1536 1524//1524 -f 1537//1537 1524//1524 1538//1538 -f 1538//1538 1524//1524 1522//1522 -f 1249//1249 1240//1240 1250//1250 -f 1250//1250 1240//1240 1239//1239 -f 1250//1250 1239//1239 1524//1524 -f 1524//1524 1239//1239 1539//1539 -f 1524//1524 1539//1539 1525//1525 -f 1226//1226 1540//1540 1541//1541 -f 1494//1494 1542//1542 1543//1543 -f 1225//1225 1495//1495 1226//1226 -f 1226//1226 1495//1495 1494//1494 -f 1226//1226 1494//1494 1540//1540 -f 1540//1540 1494//1494 1543//1543 -f 1241//1241 1544//1544 1242//1242 -f 1242//1242 1544//1544 1545//1545 -f 1242//1242 1545//1545 1506//1506 -f 1506//1506 1545//1545 1546//1546 -f 1506//1506 1546//1546 1547//1547 -f 1541//1541 1548//1548 1226//1226 -f 1226//1226 1548//1548 1549//1549 -f 1226//1226 1549//1549 1550//1550 -f 1550//1550 1549//1549 1551//1551 -f 1550//1550 1551//1551 1241//1241 -f 1241//1241 1551//1551 1552//1552 -f 1241//1241 1552//1552 1544//1544 -f 1553//1553 1554//1554 1555//1555 -f 1553//1553 1555//1555 1556//1556 -f 1557//1557 1558//1558 1559//1559 -f 1559//1559 1558//1558 1560//1560 -f 1559//1559 1560//1560 1561//1561 -f 1561//1561 1556//1556 1559//1559 -f 1559//1559 1556//1556 1555//1555 -f 1559//1559 1555//1555 1562//1562 -f 1562//1562 1555//1555 1483//1483 -f 1562//1562 1483//1483 1563//1563 -f 1563//1563 1483//1483 1480//1480 -f 1423//1423 1564//1564 1557//1557 -f 1557//1557 1564//1564 1565//1565 -f 1557//1557 1565//1565 1558//1558 -f 1554//1554 1566//1566 1527//1527 -f 1527//1527 1566//1566 1567//1567 -f 1527//1527 1567//1567 1421//1421 -f 1421//1421 1567//1567 1568//1568 -f 1421//1421 1568//1568 1423//1423 -f 1423//1423 1568//1568 1569//1569 -f 1423//1423 1569//1569 1564//1564 -f 1570//1570 1260//1260 1571//1571 -f 1571//1571 1260//1260 1262//1262 -f 1571//1571 1262//1262 1572//1572 -f 1572//1572 1262//1262 1232//1232 -f 1572//1572 1232//1232 1573//1573 -f 1573//1573 1232//1232 1231//1231 -f 1574//1574 1280//1280 1575//1575 -f 1575//1575 1280//1280 1282//1282 -f 1575//1575 1282//1282 1576//1576 -f 1576//1576 1282//1282 1284//1284 -f 1577//1577 1396//1396 1578//1578 -f 1578//1578 1396//1396 1395//1395 -f 1578//1578 1395//1395 1579//1579 -f 1579//1579 1395//1395 1455//1455 -f 1579//1579 1455//1455 1580//1580 -f 1580//1580 1455//1455 1440//1440 -f 1285//1285 1286//1286 1283//1283 -f 1283//1283 1286//1286 1288//1288 -f 1283//1283 1288//1288 1403//1403 -f 1403//1403 1288//1288 1581//1581 -f 1403//1403 1581//1581 1401//1401 -f 1401//1401 1581//1581 1582//1582 -f 1582//1582 1583//1583 1401//1401 -f 1401//1401 1583//1583 1584//1584 -f 1401//1401 1584//1584 1585//1585 -f 1586//1586 1587//1587 1409//1409 -f 1411//1411 1406//1406 1409//1409 -f 1409//1409 1406//1406 1401//1401 -f 1409//1409 1401//1401 1586//1586 -f 1586//1586 1401//1401 1585//1585 -f 1588//1588 1407//1407 1589//1589 -f 1589//1589 1407//1407 1409//1409 -f 1589//1589 1409//1409 1590//1590 -f 1590//1590 1409//1409 1587//1587 -f 1588//1588 1591//1591 1407//1407 -f 1407//1407 1591//1591 1592//1592 -f 1407//1407 1592//1592 1581//1581 -f 1581//1581 1592//1592 1593//1593 -f 1581//1581 1593//1593 1582//1582 -f 1407//1407 1224//1224 1268//1268 -f 1268//1268 1224//1224 1226//1226 -f 1268//1268 1226//1226 1270//1270 -f 1270//1270 1226//1226 1550//1550 -f 1270//1270 1550//1550 1229//1229 -f 1229//1229 1550//1550 1241//1241 -f 1229//1229 1241//1241 1413//1413 -f 1413//1413 1241//1241 1246//1246 -f 1277//1277 1473//1473 1275//1275 -f 1275//1275 1473//1473 1475//1475 -f 1275//1275 1475//1475 1288//1288 -f 1288//1288 1475//1475 1594//1594 -f 1475//1475 1595//1595 1596//1596 -f 1597//1597 1598//1598 1594//1594 -f 1596//1596 1599//1599 1475//1475 -f 1475//1475 1599//1599 1600//1600 -f 1475//1475 1600//1600 1594//1594 -f 1594//1594 1600//1600 1601//1601 -f 1594//1594 1601//1601 1597//1597 -f 1598//1598 1502//1502 1594//1594 -f 1594//1594 1502//1502 1504//1504 -f 1594//1594 1504//1504 1288//1288 -f 1288//1288 1504//1504 1602//1602 -f 1288//1288 1602//1602 1581//1581 -f 1581//1581 1602//1602 1603//1603 -f 1581//1581 1603//1603 1407//1407 -f 1407//1407 1603//1603 1604//1604 -f 1407//1407 1604//1604 1224//1224 -f 1598//1598 1605//1605 1502//1502 -f 1502//1502 1605//1605 1606//1606 -f 1502//1502 1606//1606 1607//1607 -f 1595//1595 1475//1475 1608//1608 -f 1608//1608 1475//1475 1477//1477 -f 1608//1608 1477//1477 1609//1609 -f 1610//1610 1611//1611 1372//1372 -f 1372//1372 1611//1611 1500//1500 -f 1372//1372 1500//1500 1369//1369 -f 1369//1369 1500//1500 1502//1502 -f 1369//1369 1502//1502 1477//1477 -f 1477//1477 1502//1502 1607//1607 -f 1477//1477 1607//1607 1609//1609 -f 1554//1554 1527//1527 1555//1555 -f 1555//1555 1527//1527 1518//1518 -f 1555//1555 1518//1518 1483//1483 -f 1483//1483 1518//1518 1508//1508 -f 1483//1483 1508//1508 1481//1481 -f 1481//1481 1508//1508 1506//1506 -f 1481//1481 1506//1506 1494//1494 -f 1494//1494 1506//1506 1547//1547 -f 1494//1494 1547//1547 1542//1542 -f 1610//1610 1484//1484 1611//1611 -f 1611//1611 1484//1484 1486//1486 -f 1611//1611 1486//1486 1500//1500 -f 1500//1500 1486//1486 1612//1612 -f 1500//1500 1612//1612 1498//1498 -f 1498//1498 1612//1612 1613//1613 -f 1498//1498 1613//1613 1482//1482 -f 1482//1482 1613//1613 1614//1614 -f 1482//1482 1614//1614 1480//1480 -f 1615//1615 1616//1616 1610//1610 -f 1617//1617 1615//1615 1366//1366 -f 1366//1366 1615//1615 1610//1610 -f 1366//1366 1610//1610 1364//1364 -f 1364//1364 1610//1610 1372//1372 -f 1364//1364 1372//1372 1618//1618 -f 1618//1618 1372//1372 1373//1373 -f 1619//1619 1484//1484 1620//1620 -f 1620//1620 1484//1484 1610//1610 -f 1620//1620 1610//1610 1621//1621 -f 1621//1621 1610//1610 1616//1616 -f 1619//1619 1622//1622 1484//1484 -f 1484//1484 1622//1622 1623//1623 -f 1484//1484 1623//1623 1490//1490 -f 1490//1490 1623//1623 1624//1624 -f 1624//1624 1625//1625 1490//1490 -f 1490//1490 1625//1625 1626//1626 -f 1490//1490 1626//1626 1366//1366 -f 1366//1366 1626//1626 1627//1627 -f 1366//1366 1627//1627 1617//1617 -f 1628//1628 1387//1387 1629//1629 -f 1629//1629 1387//1387 1630//1630 -f 1629//1629 1630//1630 1631//1631 -f 1631//1631 1630//1630 1632//1632 -f 1633//1633 1358//1358 1634//1634 -f 1634//1634 1358//1358 1387//1387 -f 1634//1634 1387//1387 1635//1635 -f 1635//1635 1387//1387 1628//1628 -f 1355//1355 1636//1636 1637//1637 -f 1633//1633 1638//1638 1358//1358 -f 1358//1358 1638//1638 1639//1639 -f 1358//1358 1639//1639 1355//1355 -f 1355//1355 1639//1639 1640//1640 -f 1355//1355 1640//1640 1636//1636 -f 1433//1433 1641//1641 1431//1431 -f 1431//1431 1641//1641 1426//1426 -f 1431//1431 1426//1426 1438//1438 -f 1438//1438 1426//1426 1423//1423 -f 1438//1438 1423//1423 1321//1321 -f 1321//1321 1423//1423 1557//1557 -f 1321//1321 1557//1557 1316//1316 -f 1316//1316 1557//1557 1559//1559 -f 1316//1316 1559//1559 1314//1314 -f 1365//1365 1359//1359 1366//1366 -f 1366//1366 1359//1359 1336//1336 -f 1366//1366 1336//1336 1490//1490 -f 1490//1490 1336//1336 1352//1352 -f 1490//1490 1352//1352 1487//1487 -f 1487//1487 1352//1352 1380//1380 -f 1487//1487 1380//1380 1492//1492 -f 1383//1383 1384//1384 1381//1381 -f 1381//1381 1384//1384 1355//1355 -f 1381//1381 1355//1355 1630//1630 -f 1630//1630 1355//1355 1637//1637 -f 1630//1630 1637//1637 1632//1632 -f 1642//1642 1643//1643 1314//1314 -f 1223//1223 1222//1222 1380//1380 -f 1380//1380 1222//1222 1644//1644 -f 1380//1380 1644//1644 1645//1645 -f 1562//1562 1493//1493 1559//1559 -f 1559//1559 1493//1493 1492//1492 -f 1559//1559 1492//1492 1314//1314 -f 1314//1314 1492//1492 1380//1380 -f 1314//1314 1380//1380 1642//1642 -f 1642//1642 1380//1380 1645//1645 -f 1643//1643 1646//1646 1314//1314 -f 1314//1314 1646//1646 1647//1647 -f 1314//1314 1647//1647 1312//1312 -f 1312//1312 1647//1647 1648//1648 -f 1648//1648 1649//1649 1312//1312 -f 1312//1312 1649//1649 1650//1650 -f 1312//1312 1650//1650 1223//1223 -f 1223//1223 1650//1650 1651//1651 -f 1223//1223 1651//1651 1221//1221 -f 1652//1652 1653//1653 1654//1654 -f 1654//1654 1653//1653 1335//1335 -f 1654//1654 1335//1335 1655//1655 -f 1655//1655 1335//1335 1334//1334 -f 1655//1655 1334//1334 1656//1656 -f 1652//1652 1657//1657 1653//1653 -f 1653//1653 1657//1657 1658//1658 -f 1653//1653 1658//1658 1659//1659 -f 1659//1659 1658//1658 1660//1660 -f 1659//1659 1660//1660 1661//1661 -f 1662//1662 1663//1663 1664//1664 -f 1664//1664 1663//1663 1665//1665 -f 1664//1664 1665//1665 1666//1666 -f 1356//1356 1355//1355 1667//1667 -f 1667//1667 1355//1355 1384//1384 -f 1667//1667 1384//1384 1363//1363 -f 1363//1363 1384//1384 1664//1664 -f 1363//1363 1664//1664 1334//1334 -f 1334//1334 1664//1664 1666//1666 -f 1334//1334 1666//1666 1656//1656 -f 1385//1385 1233//1233 1384//1384 -f 1384//1384 1233//1233 1235//1235 -f 1384//1384 1235//1235 1664//1664 -f 1664//1664 1235//1235 1659//1659 -f 1664//1664 1659//1659 1662//1662 -f 1662//1662 1659//1659 1661//1661 -f 1668//1668 1669//1669 1670//1670 -f 1671//1671 1672//1672 1673//1673 -f 1668//1668 1670//1670 1674//1674 -f 1670//1670 1675//1675 1674//1674 -f 1674//1674 1675//1675 1676//1676 -f 1674//1674 1676//1676 1677//1677 -f 1671//1671 1673//1673 1678//1678 -f 1673//1673 1679//1679 1678//1678 -f 1678//1678 1679//1679 1680//1680 -f 1678//1678 1680//1680 1668//1668 -f 1668//1668 1680//1680 1681//1681 -f 1668//1668 1681//1681 1669//1669 -f 1676//1676 1682//1682 1677//1677 -f 1677//1677 1682//1682 1683//1683 -f 1677//1677 1683//1683 1671//1671 -f 1671//1671 1683//1683 1684//1684 -f 1671//1671 1684//1684 1672//1672 -f 1685//1685 1686//1686 1687//1687 -f 1687//1687 1686//1686 1688//1688 -f 1689//1689 1690//1690 1691//1691 -f 1691//1691 1690//1690 1692//1692 -f 1692//1692 1693//1693 1691//1691 -f 1691//1691 1693//1693 1694//1694 -f 1691//1691 1694//1694 1695//1695 -f 1694//1694 1696//1696 1695//1695 -f 1695//1695 1696//1696 1697//1697 -f 1695//1695 1697//1697 1685//1685 -f 1685//1685 1697//1697 1698//1698 -f 1685//1685 1698//1698 1686//1686 -f 1688//1688 1699//1699 1687//1687 -f 1687//1687 1699//1699 1700//1700 -f 1687//1687 1700//1700 1689//1689 -f 1689//1689 1700//1700 1701//1701 -f 1689//1689 1701//1701 1690//1690 -f 1702//1702 1703//1703 1704//1704 -f 1704//1704 1703//1703 1705//1705 -f 1706//1706 1707//1707 1702//1702 -f 1702//1702 1707//1707 1708//1708 -f 1702//1702 1708//1708 1703//1703 -f 1705//1705 1709//1709 1704//1704 -f 1704//1704 1709//1709 1710//1710 -f 1704//1704 1710//1710 1711//1711 -f 1712//1712 1713//1713 1714//1714 -f 1714//1714 1713//1713 1711//1711 -f 1714//1714 1711//1711 1715//1715 -f 1715//1715 1711//1711 1710//1710 -f 1712//1712 1716//1716 1713//1713 -f 1713//1713 1716//1716 1717//1717 -f 1713//1713 1717//1717 1706//1706 -f 1706//1706 1717//1717 1718//1718 -f 1706//1706 1718//1718 1707//1707 -f 110//110 109//109 1719//1719 -f 1720//1720 1721//1721 1722//1722 -f 1723//1723 1724//1724 1725//1725 -f 1726//1726 1727//1727 1728//1728 -f 1728//1728 1727//1727 1729//1729 -f 1729//1729 1730//1730 1728//1728 -f 1728//1728 1730//1730 1731//1731 -f 1728//1728 1731//1731 1732//1732 -f 1732//1732 1731//1731 1733//1733 -f 1732//1732 1733//1733 1734//1734 -f 1735//1735 1736//1736 1737//1737 -f 1738//1738 1739//1739 1740//1740 -f 1741//1741 1742//1742 1733//1733 -f 1733//1733 1742//1742 1738//1738 -f 1740//1740 1743//1743 1738//1738 -f 1738//1738 1743//1743 1735//1735 -f 1738//1738 1735//1735 1733//1733 -f 1733//1733 1735//1735 1737//1737 -f 1733//1733 1737//1737 1734//1734 -f 1744//1744 1745//1745 1746//1746 -f 1747//1747 1748//1748 1749//1749 -f 1750//1750 1744//1744 1741//1741 -f 1725//1725 1742//1742 1723//1723 -f 1723//1723 1742//1742 1741//1741 -f 1723//1723 1741//1741 1751//1751 -f 1751//1751 1741//1741 1744//1744 -f 1751//1751 1744//1744 1752//1752 -f 1752//1752 1744//1744 1746//1746 -f 1748//1748 1747//1747 1753//1753 -f 1754//1754 1755//1755 1756//1756 -f 1757//1757 1758//1758 1759//1759 -f 1756//1756 1760//1760 1754//1754 -f 1754//1754 1760//1760 1759//1759 -f 1754//1754 1759//1759 1761//1761 -f 1761//1761 1759//1759 1762//1762 -f 1763//1763 1757//1757 1764//1764 -f 1764//1764 1757//1757 1759//1759 -f 1764//1764 1759//1759 1765//1765 -f 1765//1765 1759//1759 1760//1760 -f 1766//1766 1767//1767 1768//1768 -f 1768//1768 1767//1767 1769//1769 -f 1768//1768 1769//1769 1770//1770 -f 1770//1770 1769//1769 1771//1771 -f 1772//1772 1773//1773 1774//1774 -f 1774//1774 1773//1773 1775//1775 -f 1776//1776 1777//1777 1778//1778 -f 1778//1778 1777//1777 1779//1779 -f 1778//1778 1779//1779 1780//1780 -f 1780//1780 1779//1779 1781//1781 -f 1780//1780 1781//1781 1782//1782 -f 1782//1782 1781//1781 1783//1783 -f 1782//1782 1783//1783 1784//1784 -f 1784//1784 1783//1783 1785//1785 -f 1786//1786 1787//1787 1788//1788 -f 1788//1788 1787//1787 1789//1789 -f 1788//1788 1789//1789 1790//1790 -f 1722//1722 1791//1791 1720//1720 -f 1720//1720 1791//1791 1792//1792 -f 1720//1720 1792//1792 1793//1793 -f 1794//1794 1795//1795 1796//1796 -f 1796//1796 1795//1795 1797//1797 -f 1796//1796 1797//1797 1798//1798 -f 1799//1799 1800//1800 1792//1792 -f 1792//1792 1800//1800 1801//1801 -f 1801//1801 1802//1802 1787//1787 -f 1787//1787 1802//1802 1803//1803 -f 1804//1804 1796//1796 1805//1805 -f 1805//1805 1796//1796 1798//1798 -f 1805//1805 1798//1798 1806//1806 -f 1806//1806 1798//1798 1807//1807 -f 1806//1806 1807//1807 1791//1791 -f 1791//1791 1807//1807 1808//1808 -f 1791//1791 1808//1808 1792//1792 -f 1792//1792 1808//1808 1809//1809 -f 1792//1792 1809//1809 1799//1799 -f 1796//1796 1810//1810 1794//1794 -f 1794//1794 1810//1810 1811//1811 -f 1794//1794 1811//1811 1803//1803 -f 1803//1803 1811//1811 1812//1812 -f 1803//1803 1812//1812 1787//1787 -f 1787//1787 1812//1812 1813//1813 -f 1787//1787 1813//1813 1789//1789 -f 1814//1814 1815//1815 1792//1792 -f 1816//1816 1817//1817 1818//1818 -f 1818//1818 1817//1817 1819//1819 -f 1819//1819 1793//1793 1818//1818 -f 1818//1818 1793//1793 1792//1792 -f 1818//1818 1792//1792 1820//1820 -f 1820//1820 1792//1792 1815//1815 -f 1820//1820 1815//1815 1821//1821 -f 1821//1821 1815//1815 1822//1822 -f 1823//1823 1824//1824 1825//1825 -f 1825//1825 1824//1824 1826//1826 -f 1827//1827 1828//1828 1826//1826 -f 1829//1829 1830//1830 1827//1827 -f 1827//1827 1830//1830 1831//1831 -f 1832//1832 1833//1833 1834//1834 -f 1834//1834 1833//1833 1835//1835 -f 1834//1834 1835//1835 1814//1814 -f 1836//1836 1837//1837 1828//1828 -f 1828//1828 1837//1837 1838//1838 -f 1828//1828 1838//1838 1826//1826 -f 1839//1839 1840//1840 1829//1829 -f 1841//1841 1830//1830 1842//1842 -f 1842//1842 1830//1830 1829//1829 -f 1842//1842 1829//1829 1843//1843 -f 1843//1843 1829//1829 1840//1840 -f 1843//1843 1840//1840 1844//1844 -f 1844//1844 1840//1840 1845//1845 -f 1846//1846 1847//1847 1848//1848 -f 135//135 1849//1849 134//134 -f 134//134 1849//1849 1850//1850 -f 134//134 1850//1850 120//120 -f 1850//1850 1851//1851 120//120 -f 120//120 1851//1851 1852//1852 -f 120//120 1852//1852 118//118 -f 118//118 1852//1852 1853//1853 -f 118//118 1853//1853 116//116 -f 116//116 1853//1853 1854//1854 -f 116//116 1854//1854 1855//1855 -f 1855//1855 1854//1854 1856//1856 -f 1857//1857 1858//1858 1859//1859 -f 1859//1859 1858//1858 1860//1860 -f 1859//1859 1860//1860 1861//1861 -f 1861//1861 1860//1860 1862//1862 -f 1861//1861 1862//1862 135//135 -f 135//135 1862//1862 1863//1863 -f 135//135 1863//1863 1849//1849 -f 1864//1864 1865//1865 1866//1866 -f 1866//1866 1865//1865 1867//1867 -f 1866//1866 1867//1867 1868//1868 -f 1869//1869 1870//1870 1871//1871 -f 1871//1871 1870//1870 1872//1872 -f 1871//1871 1872//1872 114//114 -f 114//114 1872//1872 1873//1873 -f 1874//1874 109//109 1873//1873 -f 1873//1873 109//109 138//138 -f 1873//1873 138//138 114//114 -f 1874//1874 1875//1875 109//109 -f 109//109 1875//1875 1876//1876 -f 109//109 1876//1876 1719//1719 -f 1719//1719 1876//1876 1877//1877 -f 1719//1719 1877//1877 1878//1878 -f 1879//1879 86//86 1719//1719 -f 1719//1719 86//86 112//112 -f 1719//1719 112//112 110//110 -f 1730//1730 1880//1880 1731//1731 -f 1731//1731 1880//1880 1881//1881 -f 1731//1731 1881//1881 1879//1879 -f 1879//1879 1881//1881 1882//1882 -f 1879//1879 1882//1882 86//86 -f 1883//1883 1884//1884 1885//1885 -f 1885//1885 1884//1884 1886//1886 -f 1885//1885 1886//1886 1887//1887 -f 1887//1887 1886//1886 1888//1888 -f 1887//1887 1888//1888 1889//1889 -f 1889//1889 1888//1888 1890//1890 -f 1889//1889 1890//1890 1891//1891 -f 1892//1892 1893//1893 1894//1894 -f 1894//1894 1893//1893 1895//1895 -f 1894//1894 1895//1895 1896//1896 -f 1896//1896 1895//1895 1897//1897 -f 1896//1896 1897//1897 1898//1898 -f 1899//1899 1900//1900 1901//1901 -f 1901//1901 1900//1900 1741//1741 -f 1901//1901 1741//1741 1902//1902 -f 1902//1902 1741//1741 1733//1733 -f 1902//1902 1733//1733 1903//1903 -f 1904//1904 1905//1905 1892//1892 -f 1892//1892 1905//1905 1906//1906 -f 1892//1892 1906//1906 1907//1907 -f 1908//1908 1909//1909 1910//1910 -f 1910//1910 1909//1909 1911//1911 -f 1910//1910 1911//1911 1912//1912 -f 1912//1912 1911//1911 1913//1913 -f 1912//1912 1913//1913 1907//1907 -f 1907//1907 1913//1913 1884//1884 -f 1907//1907 1884//1884 1892//1892 -f 1892//1892 1884//1884 1883//1883 -f 1892//1892 1883//1883 1893//1893 -f 1914//1914 1915//1915 1916//1916 -f 1916//1916 1915//1915 1917//1917 -f 1916//1916 1917//1917 1899//1899 -f 1918//1918 1919//1919 1920//1920 -f 1920//1920 1919//1919 1769//1769 -f 1920//1920 1769//1769 1763//1763 -f 1763//1763 1769//1769 1767//1767 -f 1763//1763 1767//1767 1757//1757 -f 1747//1747 1921//1921 1922//1922 -f 1923//1923 1924//1924 1755//1755 -f 1755//1755 1924//1924 1753//1753 -f 1755//1755 1753//1753 1756//1756 -f 1756//1756 1753//1753 1747//1747 -f 1756//1756 1747//1747 1925//1925 -f 1925//1925 1747//1747 1922//1922 -f 1918//1918 1926//1926 1919//1919 -f 1919//1919 1926//1926 1927//1927 -f 1919//1919 1927//1927 1921//1921 -f 1921//1921 1927//1927 1928//1928 -f 1921//1921 1928//1928 1922//1922 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1935//1935 -f 1935//1935 1934//1934 1936//1936 -f 1935//1935 1936//1936 1937//1937 -f 1938//1938 1939//1939 1940//1940 -f 1940//1940 1939//1939 1941//1941 -f 1940//1940 1941//1941 1942//1942 -f 1942//1942 1941//1941 1943//1943 -f 1942//1942 1943//1943 1944//1944 -f 1944//1944 1943//1943 1945//1945 -f 1944//1944 1945//1945 1946//1946 -f 1947//1947 1948//1948 1949//1949 -f 1948//1948 1950//1950 1949//1949 -f 1949//1949 1950//1950 1951//1951 -f 1949//1949 1951//1951 1944//1944 -f 1944//1944 1951//1951 1952//1952 -f 1953//1953 1954//1954 1955//1955 -f 1955//1955 1954//1954 1956//1956 -f 1955//1955 1956//1956 1957//1957 -f 1957//1957 1956//1956 1958//1958 -f 1957//1957 1958//1958 1959//1959 -f 1960//1960 1961//1961 1962//1962 -f 1962//1962 1961//1961 1963//1963 -f 1962//1962 1963//1963 1964//1964 -f 1965//1965 1909//1909 1966//1966 -f 1966//1966 1909//1909 1908//1908 -f 1966//1966 1908//1908 1903//1903 -f 1960//1960 1967//1967 1961//1961 -f 1961//1961 1967//1967 1968//1968 -f 1961//1961 1968//1968 1966//1966 -f 1966//1966 1968//1968 1969//1969 -f 1966//1966 1969//1969 1965//1965 -f 1965//1965 1970//1970 1909//1909 -f 1909//1909 1970//1970 1971//1971 -f 1909//1909 1971//1971 1911//1911 -f 1911//1911 1971//1971 1972//1972 -f 1964//1964 1963//1963 1973//1973 -f 1973//1973 1963//1963 1974//1974 -f 1973//1973 1974//1974 1975//1975 -f 1976//1976 1977//1977 1900//1900 -f 1978//1978 1979//1979 1921//1921 -f 1921//1921 1979//1979 1980//1980 -f 1921//1921 1980//1980 1981//1981 -f 1899//1899 1917//1917 1900//1900 -f 1900//1900 1917//1917 1982//1982 -f 1900//1900 1982//1982 1976//1976 -f 1980//1980 1983//1983 1981//1981 -f 1981//1981 1983//1983 1984//1984 -f 1981//1981 1984//1984 1985//1985 -f 1984//1984 1986//1986 1985//1985 -f 1985//1985 1986//1986 1987//1987 -f 1985//1985 1987//1987 1915//1915 -f 1915//1915 1987//1987 1988//1988 -f 1915//1915 1988//1988 1917//1917 -f 1917//1917 1988//1988 1989//1989 -f 1917//1917 1989//1989 1982//1982 -f 1990//1990 1991//1991 1940//1940 -f 1940//1940 1991//1991 1992//1992 -f 1940//1940 1992//1992 1993//1993 -f 1993//1993 1992//1992 1994//1994 -f 1993//1993 1994//1994 1995//1995 -f 1996//1996 1997//1997 1998//1998 -f 1997//1997 1999//1999 1998//1998 -f 1998//1998 1999//1999 2000//2000 -f 1998//1998 2000//2000 2001//2001 -f 2001//2001 2000//2000 2002//2002 -f 2003//2003 2004//2004 1792//1792 -f 2005//2005 2006//2006 1825//1825 -f 2006//2006 2007//2007 1825//1825 -f 1825//1825 2007//2007 1898//1898 -f 1825//1825 1898//1898 1823//1823 -f 1823//1823 1898//1898 1897//1897 -f 2003//2003 1792//1792 2008//2008 -f 2008//2008 1792//1792 2009//2009 -f 2008//2008 2009//2009 2010//2010 -f 1838//1838 1834//1834 1826//1826 -f 1826//1826 1834//1834 1814//1814 -f 1826//1826 1814//1814 1825//1825 -f 1825//1825 1814//1814 1792//1792 -f 1825//1825 1792//1792 2005//2005 -f 2005//2005 1792//1792 2004//2004 -f 2007//2007 2011//2011 1898//1898 -f 1898//1898 2011//2011 2012//2012 -f 1898//1898 2012//2012 1896//1896 -f 1896//1896 2012//2012 2013//2013 -f 2010//2010 2009//2009 2014//2014 -f 2014//2014 2009//2009 2015//2015 -f 2014//2014 2015//2015 2016//2016 -f 2017//2017 2018//2018 1829//1829 -f 1829//1829 2018//2018 2019//2019 -f 2020//2020 2017//2017 1890//1890 -f 1890//1890 2017//2017 1829//1829 -f 1890//1890 1829//1829 1891//1891 -f 1891//1891 1829//1829 1827//1827 -f 1891//1891 1827//1827 2021//2021 -f 2021//2021 1827//1827 1826//1826 -f 2022//2022 2023//2023 1848//1848 -f 1848//1848 2023//2023 2024//2024 -f 1848//1848 2024//2024 2025//2025 -f 2019//2019 2022//2022 1829//1829 -f 1829//1829 2022//2022 1848//1848 -f 1829//1829 1848//1848 1839//1839 -f 1839//1839 1848//1848 1847//1847 -f 1839//1839 1847//1847 2026//2026 -f 2020//2020 1890//1890 2027//2027 -f 2027//2027 1890//1890 1888//1888 -f 2027//2027 1888//1888 2028//2028 -f 2024//2024 2029//2029 2025//2025 -f 2025//2025 2029//2029 2030//2030 -f 2025//2025 2030//2030 2031//2031 -f 2031//2031 2030//2030 2032//2032 -f 1856//1856 1857//1857 1855//1855 -f 1855//1855 1857//1857 1859//1859 -f 1855//1855 1859//1859 1998//1998 -f 1998//1998 1859//1859 2033//2033 -f 1998//1998 2033//2033 1996//1996 -f 1996//1996 2033//2033 2034//2034 -f 135//135 128//128 1861//1861 -f 1861//1861 128//128 2035//2035 -f 1861//1861 2035//2035 1859//1859 -f 1859//1859 2035//2035 2036//2036 -f 1859//1859 2036//2036 2033//2033 -f 2033//2033 2036//2036 1993//1993 -f 2033//2033 1993//1993 2034//2034 -f 2034//2034 1993//1993 1995//1995 -f 128//128 1846//1846 2035//2035 -f 2035//2035 1846//1846 1848//1848 -f 2035//2035 1848//1848 2036//2036 -f 2036//2036 1848//1848 2025//2025 -f 2036//2036 2025//2025 1993//1993 -f 1993//1993 2025//2025 2031//2031 -f 1993//1993 2031//2031 1940//1940 -f 1940//1940 2031//2031 1935//1935 -f 1940//1940 1935//1935 1938//1938 -f 1938//1938 1935//1935 1937//1937 -f 2002//2002 2037//2037 2001//2001 -f 2001//2001 2037//2037 2038//2038 -f 2001//2001 2038//2038 2039//2039 -f 2039//2039 2038//2038 2040//2040 -f 2039//2039 2040//2040 1955//1955 -f 1955//1955 2040//2040 2041//2041 -f 1955//1955 2041//2041 1953//1953 -f 1953//1953 2041//2041 2042//2042 -f 2037//2037 1990//1990 2038//2038 -f 2038//2038 1990//1990 1940//1940 -f 2038//2038 1940//1940 2040//2040 -f 2040//2040 1940//1940 1942//1942 -f 2040//2040 1942//1942 2041//2041 -f 2041//2041 1942//1942 1944//1944 -f 2041//2041 1944//1944 2042//2042 -f 2042//2042 1944//1944 1952//1952 -f 2013//2013 2016//2016 1896//1896 -f 1896//1896 2016//2016 2015//2015 -f 1896//1896 2015//2015 1894//1894 -f 1894//1894 2015//2015 2043//2043 -f 1894//1894 2043//2043 1892//1892 -f 1892//1892 2043//2043 2044//2044 -f 1892//1892 2044//2044 1904//1904 -f 1904//1904 2044//2044 2045//2045 -f 1801//1801 1787//1787 1792//1792 -f 1792//1792 1787//1787 1786//1786 -f 1792//1792 1786//1786 2009//2009 -f 2009//2009 1786//1786 2046//2046 -f 2009//2009 2046//2046 2015//2015 -f 2015//2015 2046//2046 1783//1783 -f 2015//2015 1783//1783 2043//2043 -f 2043//2043 1783//1783 1781//1781 -f 2043//2043 1781//1781 2044//2044 -f 2044//2044 1781//1781 1779//1779 -f 2044//2044 1779//1779 2045//2045 -f 2045//2045 1779//1779 1777//1777 -f 2045//2045 1777//1777 1775//1775 -f 1775//1775 1777//1777 1776//1776 -f 1775//1775 1776//1776 1774//1774 -f 2032//2032 2028//2028 2031//2031 -f 2031//2031 2028//2028 1888//1888 -f 2031//2031 1888//1888 1935//1935 -f 1935//1935 1888//1888 1886//1886 -f 1935//1935 1886//1886 1933//1933 -f 1933//1933 1886//1886 1884//1884 -f 1933//1933 1884//1884 1931//1931 -f 1931//1931 1884//1884 1913//1913 -f 1931//1931 1913//1913 1974//1974 -f 1974//1974 1913//1913 1911//1911 -f 1974//1974 1911//1911 1975//1975 -f 1975//1975 1911//1911 1972//1972 -f 1771//1771 1769//1769 2047//2047 -f 2047//2047 1769//1769 1919//1919 -f 2047//2047 1919//1919 2048//2048 -f 2048//2048 1919//1919 1921//1921 -f 2048//2048 1921//1921 2049//2049 -f 2049//2049 1921//1921 1981//1981 -f 2049//2049 1981//1981 1775//1775 -f 1775//1775 1981//1981 1985//1985 -f 1775//1775 1985//1985 2045//2045 -f 2045//2045 1985//1985 1915//1915 -f 2045//2045 1915//1915 1904//1904 -f 1904//1904 1915//1915 1914//1914 -f 1904//1904 1914//1914 1905//1905 -f 1959//1959 2050//2050 1957//1957 -f 1957//1957 2050//2050 2051//2051 -f 1957//1957 2051//2051 1871//1871 -f 1871//1871 2051//2051 1866//1866 -f 1871//1871 1866//1866 1869//1869 -f 1869//1869 1866//1866 1868//1868 -f 2050//2050 1947//1947 2051//2051 -f 2051//2051 1947//1947 1949//1949 -f 2051//2051 1949//1949 1866//1866 -f 1866//1866 1949//1949 2052//2052 -f 1866//1866 2052//2052 1864//1864 -f 1864//1864 2052//2052 2053//2053 -f 1946//1946 1929//1929 1944//1944 -f 1944//1944 1929//1929 1931//1931 -f 1944//1944 1931//1931 1949//1949 -f 1949//1949 1931//1931 1974//1974 -f 1949//1949 1974//1974 2052//2052 -f 2052//2052 1974//1974 1963//1963 -f 2052//2052 1963//1963 2053//2053 -f 2053//2053 1963//1963 1961//1961 -f 1903//1903 1733//1733 1966//1966 -f 1966//1966 1733//1733 1731//1731 -f 1966//1966 1731//1731 1961//1961 -f 1961//1961 1731//1731 1879//1879 -f 1961//1961 1879//1879 2053//2053 -f 2053//2053 1879//1879 1719//1719 -f 2053//2053 1719//1719 1864//1864 -f 1864//1864 1719//1719 1878//1878 -f 1864//1864 1878//1878 1865//1865 -f 1977//1977 1978//1978 1900//1900 -f 1900//1900 1978//1978 1921//1921 -f 1900//1900 1921//1921 1741//1741 -f 1741//1741 1921//1921 1747//1747 -f 1741//1741 1747//1747 1750//1750 -f 1750//1750 1747//1747 1749//1749 -f 1750//1750 1749//1749 2054//2054 -f 2054//2054 1749//1749 2055//2055 -f 2056//2056 2057//2057 2058//2058 -f 2058//2058 2057//2057 2059//2059 -f 2058//2058 2059//2059 2060//2060 -f 2060//2060 2059//2059 2061//2061 -f 2060//2060 2061//2061 2062//2062 -f 2063//2063 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2065//2065 2066//2066 2067//2067 -f 2067//2067 2066//2066 2068//2068 -f 2067//2067 2068//2068 2069//2069 -f 2070//2070 2071//2071 2072//2072 -f 2072//2072 2071//2071 2073//2073 -f 2072//2072 2073//2073 2074//2074 -f 2074//2074 2073//2073 2075//2075 -f 2074//2074 2075//2075 2076//2076 -f 2077//2077 2078//2078 1674//1674 -f 1674//1674 2078//2078 2079//2079 -f 1674//1674 2079//2079 1668//1668 -f 1668//1668 2079//2079 2080//2080 -f 1668//1668 2080//2080 2081//2081 -f 2081//2081 2080//2080 2082//2082 -f 2083//2083 2084//2084 1695//1695 -f 1695//1695 2084//2084 2085//2085 -f 1695//1695 2085//2085 1691//1691 -f 1691//1691 2085//2085 2086//2086 -f 1691//1691 2086//2086 2087//2087 -f 2087//2087 2086//2086 2088//2088 -f 2089//2089 2090//2090 1711//1711 -f 1711//1711 2090//2090 2091//2091 -f 1711//1711 2091//2091 1704//1704 -f 1704//1704 2091//2091 2092//2092 -f 1704//1704 2092//2092 2093//2093 -f 2093//2093 2092//2092 2094//2094 -f 2095//2095 2096//2096 2097//2097 -f 2097//2097 2096//2096 2098//2098 -f 2099//2099 2100//2100 2101//2101 -f 2102//2102 2103//2103 2104//2104 -f 2104//2104 2103//2103 2099//2099 -f 2104//2104 2099//2099 2105//2105 -f 2105//2105 2099//2099 2101//2101 -f 2102//2102 2106//2106 2103//2103 -f 2103//2103 2106//2106 2107//2107 -f 2103//2103 2107//2107 2095//2095 -f 2095//2095 2107//2107 2108//2108 -f 2095//2095 2108//2108 2096//2096 -f 2098//2098 2109//2109 2097//2097 -f 2097//2097 2109//2109 2110//2110 -f 2097//2097 2110//2110 2100//2100 -f 2100//2100 2110//2110 2111//2111 -f 2100//2100 2111//2111 2101//2101 -f 2112//2112 2113//2113 2114//2114 -f 2114//2114 2113//2113 2115//2115 -f 2116//2116 2117//2117 2118//2118 -f 2118//2118 2117//2117 2119//2119 -f 2118//2118 2119//2119 2120//2120 -f 2120//2120 2119//2119 2121//2121 -f 2120//2120 2121//2121 2122//2122 -f 2114//2114 2123//2123 2112//2112 -f 2112//2112 2123//2123 2124//2124 -f 2112//2112 2124//2124 2121//2121 -f 2121//2121 2124//2124 2125//2125 -f 2121//2121 2125//2125 2122//2122 -f 2116//2116 2126//2126 2117//2117 -f 2117//2117 2126//2126 2127//2127 -f 2117//2117 2127//2127 2113//2113 -f 2113//2113 2127//2127 2128//2128 -f 2113//2113 2128//2128 2115//2115 -f 2129//2129 2130//2130 2131//2131 -f 2131//2131 2130//2130 2132//2132 -f 2131//2131 2132//2132 2133//2133 -f 2133//2133 2132//2132 2134//2134 -f 2133//2133 2134//2134 2135//2135 -f 2136//2136 2137//2137 2100//2100 -f 2100//2100 2137//2137 2138//2138 -f 2100//2100 2138//2138 2097//2097 -f 2097//2097 2138//2138 2139//2139 -f 2097//2097 2139//2139 2140//2140 -f 2140//2140 2139//2139 2141//2141 -f 2142//2142 2143//2143 2144//2144 -f 2145//2145 2146//2146 2147//2147 -f 2142//2142 2144//2144 2147//2147 -f 2147//2147 2144//2144 2148//2148 -f 2147//2147 2148//2148 2145//2145 -f 2149//2149 2150//2150 2112//2112 -f 2112//2112 2150//2150 2151//2151 -f 2112//2112 2151//2151 2113//2113 -f 2113//2113 2151//2151 2152//2152 -f 2113//2113 2152//2152 2153//2153 -f 2153//2153 2152//2152 2154//2154 -f 2155//2155 1847//1847 2156//2156 -f 2156//2156 1847//1847 1846//1846 -f 2156//2156 1846//1846 128//128 -f 116//116 1855//1855 2157//2157 -f 2157//2157 1855//1855 1998//1998 -f 1998//1998 2001//2001 2157//2157 -f 2157//2157 2001//2001 2039//2039 -f 2157//2157 2039//2039 2158//2158 -f 2158//2158 2039//2039 1955//1955 -f 1955//1955 1957//1957 2158//2158 -f 2158//2158 1957//1957 1871//1871 -f 2158//2158 1871//1871 114//114 -f 1881//1881 2159//2159 1882//1882 -f 1882//1882 2159//2159 2160//2160 -f 1882//1882 2160//2160 86//86 -f 1881//1881 1880//1880 2159//2159 -f 2159//2159 1880//1880 2161//2161 -f 2159//2159 2161//2161 2162//2162 -f 2162//2162 2161//2161 1412//1412 -f 2162//2162 1412//1412 2163//2163 -f 2163//2163 1412//1412 1228//1228 -f 1729//1729 2164//2164 1730//1730 -f 1730//1730 2164//2164 2161//2161 -f 1730//1730 2161//2161 1880//1880 -f 2080//2080 1573//1573 2164//2164 -f 2164//2164 1573//1573 1231//1231 -f 2164//2164 1231//1231 1230//1230 -f 1729//1729 1727//1727 2164//2164 -f 2164//2164 1727//1727 2082//2082 -f 2164//2164 2082//2082 2080//2080 -f 2165//2165 1258//1258 1260//1260 -f 1736//1736 1735//1735 2078//2078 -f 2078//2078 1735//1735 2165//2165 -f 2078//2078 2165//2165 2079//2079 -f 2079//2079 2165//2165 1260//1260 -f 2079//2079 1260//1260 1570//1570 -f 2165//2165 1735//1735 2166//2166 -f 2166//2166 1735//1735 1743//1743 -f 2086//2086 1411//1411 2166//2166 -f 2166//2166 1411//1411 1410//1410 -f 2166//2166 1410//1410 1408//1408 -f 1743//1743 1740//1740 2166//2166 -f 2166//2166 1740//1740 2088//2088 -f 2166//2166 2088//2088 2086//2086 -f 1724//1724 1723//1723 2167//2167 -f 2167//2167 1403//1403 1402//1402 -f 1724//1724 2167//2167 2084//2084 -f 2084//2084 2167//2167 2085//2085 -f 2085//2085 2167//2167 1402//1402 -f 2085//2085 1402//1402 1404//1404 -f 1752//1752 2168//2168 1751//1751 -f 1751//1751 2168//2168 2167//2167 -f 1751//1751 2167//2167 1723//1723 -f 2092//2092 1576//1576 2168//2168 -f 2168//2168 1576//1576 1284//1284 -f 2168//2168 1284//1284 1283//1283 -f 1752//1752 1746//1746 2168//2168 -f 2168//2168 1746//1746 2094//2094 -f 2168//2168 2094//2094 2092//2092 -f 2169//2169 1274//1274 1280//1280 -f 2055//2055 1749//1749 2090//2090 -f 2090//2090 1749//1749 2169//2169 -f 2090//2090 2169//2169 2091//2091 -f 2091//2091 2169//2169 1280//1280 -f 2091//2091 1280//1280 1574//1574 -f 1753//1753 2170//2170 1748//1748 -f 1748//1748 2170//2170 2169//2169 -f 1748//1748 2169//2169 1749//1749 -f 2139//2139 1580//1580 2170//2170 -f 2170//2170 1580//1580 1440//1440 -f 2170//2170 1440//1440 1439//1439 -f 1753//1753 1924//1924 2170//2170 -f 2170//2170 1924//1924 2141//2141 -f 2170//2170 2141//2141 2139//2139 -f 2171//2171 1397//1397 1396//1396 -f 1762//1762 1759//1759 2137//2137 -f 2137//2137 1759//1759 2171//2171 -f 2137//2137 2171//2171 2138//2138 -f 2138//2138 2171//2171 1396//1396 -f 2138//2138 1396//1396 1577//1577 -f 2171//2171 1759//1759 2172//2172 -f 2172//2172 1759//1759 1758//1758 -f 2172//2172 1758//1758 1400//1400 -f 1400//1400 1758//1758 1757//1757 -f 1766//1766 2173//2173 1767//1767 -f 1767//1767 2173//2173 1400//1400 -f 1767//1767 1400//1400 1757//1757 -f 2173//2173 1766//1766 2174//2174 -f 2174//2174 1766//1766 1768//1768 -f 2174//2174 1768//1768 1770//1770 -f 1398//1398 1399//1399 2152//2152 -f 2152//2152 1399//1399 2174//2174 -f 2152//2152 2174//2174 2154//2154 -f 2154//2154 2174//2174 1770//1770 -f 2175//2175 1393//1393 1392//1392 -f 1772//1772 1774//1774 2150//2150 -f 2150//2150 1774//1774 2175//2175 -f 2150//2150 2175//2175 2151//2151 -f 2151//2151 2175//2175 1392//1392 -f 1774//1774 1776//1776 2175//2175 -f 2175//2175 1776//1776 1778//1778 -f 2175//2175 1778//1778 2176//2176 -f 2176//2176 1778//1778 1780//1780 -f 2176//2176 1780//1780 1782//1782 -f 2176//2176 1782//1782 1784//1784 -f 1386//1386 1388//1388 2177//2177 -f 2177//2177 1388//1388 2176//2176 -f 2177//2177 2176//2176 2178//2178 -f 2178//2178 2176//2176 1784//1784 -f 2179//2179 2180//2180 2181//2181 -f 2181//2181 2180//2180 2182//2182 -f 2181//2181 2182//2182 2183//2183 -f 2183//2183 2182//2182 2177//2177 -f 2183//2183 2177//2177 2184//2184 -f 2184//2184 2177//2177 2178//2178 -f 2185//2185 1383//1383 1382//1382 -f 1790//1790 1789//1789 2180//2180 -f 2180//2180 1789//1789 2185//2185 -f 2180//2180 2185//2185 2182//2182 -f 2182//2182 2185//2185 1382//1382 -f 2185//2185 1789//1789 2186//2186 -f 2186//2186 1789//1789 1813//1813 -f 2186//2186 1813//1813 1385//1385 -f 1385//1385 1813//1813 1812//1812 -f 1385//1385 1812//1812 1811//1811 -f 1385//1385 1811//1811 2187//2187 -f 2187//2187 1811//1811 1810//1810 -f 2187//2187 1810//1810 2188//2188 -f 2188//2188 1810//1810 1796//1796 -f 2188//2188 1796//1796 1804//1804 -f 1234//1234 1233//1233 2189//2189 -f 2189//2189 1233//1233 2188//2188 -f 2189//2189 2188//2188 2190//2190 -f 2190//2190 2188//2188 1804//1804 -f 2191//2191 2192//2192 2193//2193 -f 2193//2193 2192//2192 2194//2194 -f 2193//2193 2194//2194 2195//2195 -f 2195//2195 2194//2194 2189//2189 -f 2195//2195 2189//2189 2196//2196 -f 2196//2196 2189//2189 2190//2190 -f 2197//2197 1335//1335 1653//1653 -f 1721//1721 1720//1720 2192//2192 -f 2192//2192 1720//1720 2197//2197 -f 2192//2192 2197//2197 2194//2194 -f 2194//2194 2197//2197 1653//1653 -f 1819//1819 2198//2198 1793//1793 -f 1793//1793 2198//2198 2197//2197 -f 1793//1793 2197//2197 1720//1720 -f 2198//2198 1819//1819 1817//1817 -f 1348//1348 1337//1337 2199//2199 -f 2199//2199 1337//1337 2198//2198 -f 2199//2199 2198//2198 2200//2200 -f 2200//2200 2198//2198 1817//1817 -f 2201//2201 2202//2202 2203//2203 -f 2203//2203 2202//2202 2204//2204 -f 2203//2203 2204//2204 2205//2205 -f 2205//2205 2204//2204 2199//2199 -f 2205//2205 2199//2199 2206//2206 -f 2206//2206 2199//2199 2200//2200 -f 2207//2207 1342//1342 1340//1340 -f 1822//1822 1815//1815 2202//2202 -f 2202//2202 1815//1815 2207//2207 -f 2202//2202 2207//2207 2204//2204 -f 2204//2204 2207//2207 1340//1340 -f 1835//1835 2208//2208 1814//1814 -f 1814//1814 2208//2208 2207//2207 -f 1814//1814 2207//2207 1815//1815 -f 2208//2208 1835//1835 1833//1833 -f 1378//1378 1379//1379 2209//2209 -f 2209//2209 1379//1379 2208//2208 -f 2209//2209 2208//2208 2210//2210 -f 2210//2210 2208//2208 1833//1833 -f 2211//2211 2212//2212 2213//2213 -f 2213//2213 2212//2212 2214//2214 -f 2213//2213 2214//2214 2215//2215 -f 2215//2215 2214//2214 2209//2209 -f 2215//2215 2209//2209 2216//2216 -f 2216//2216 2209//2209 2210//2210 -f 1315//1315 1313//1313 2217//2217 -f 2217//2217 1313//1313 2214//2214 -f 2214//2214 2212//2212 2217//2217 -f 2217//2217 2212//2212 1836//1836 -f 2217//2217 1836//1836 1828//1828 -f 2217//2217 1828//1828 2218//2218 -f 2218//2218 1828//1828 1827//1827 -f 2218//2218 1827//1827 1831//1831 -f 1331//1331 1317//1317 2219//2219 -f 2219//2219 1317//1317 2218//2218 -f 2219//2219 2218//2218 2220//2220 -f 2220//2220 2218//2218 1831//1831 -f 2221//2221 2222//2222 2223//2223 -f 2223//2223 2222//2222 2224//2224 -f 2223//2223 2224//2224 2225//2225 -f 2225//2225 2224//2224 2219//2219 -f 2225//2225 2219//2219 2226//2226 -f 2226//2226 2219//2219 2220//2220 -f 2227//2227 1435//1435 1434//1434 -f 1845//1845 1840//1840 2222//2222 -f 2222//2222 1840//1840 2227//2227 -f 2222//2222 2227//2227 2224//2224 -f 2224//2224 2227//2227 1434//1434 -f 2026//2026 2228//2228 1839//1839 -f 1839//1839 2228//2228 2227//2227 -f 1839//1839 2227//2227 1840//1840 -f 2229//2229 1437//1437 1436//1436 -f 2026//2026 1847//1847 2228//2228 -f 2228//2228 1847//1847 2155//2155 -f 2228//2228 2155//2155 1436//1436 -f 1436//1436 2155//2155 2230//2230 -f 1436//1436 2230//2230 2229//2229 -f 1357//1357 2231//2231 1374//1374 -f 1374//1374 2231//2231 2232//2232 -f 1374//1374 2232//2232 1375//1375 -f 1375//1375 2232//2232 1377//1377 -f 2233//2233 1363//1363 2234//2234 -f 2234//2234 1363//1363 1362//1362 -f 2234//2234 1362//1362 1361//1361 -f 2235//2235 2236//2236 1365//1365 -f 1365//1365 1364//1364 2235//2235 -f 2235//2235 1364//1364 1618//1618 -f 2235//2235 1618//1618 1373//1373 -f 1472//1472 2237//2237 1367//1367 -f 1367//1367 2237//2237 2238//2238 -f 1367//1367 2238//2238 1368//1368 -f 2239//2239 2240//2240 2241//2241 -f 2241//2241 2240//2240 2242//2242 -f 1447//1447 2243//2243 1443//1443 -f 1443//1443 2243//2243 2244//2244 -f 1443//1443 2244//2244 1444//1444 -f 2245//2245 1460//1460 1459//1459 -f 2245//2245 1459//1459 2246//2246 -f 2246//2246 1459//1459 1465//1465 -f 2246//2246 1465//1465 1464//1464 -f 2247//2247 1461//1461 2248//2248 -f 2248//2248 1461//1461 1467//1467 -f 2248//2248 1467//1467 1466//1466 -f 2249//2249 1478//1478 1476//1476 -f 2249//2249 1476//1476 2250//2250 -f 2250//2250 1476//1476 1474//1474 -f 2250//2250 1474//1474 1473//1473 -f 2251//2251 2252//2252 2253//2253 -f 2253//2253 2252//2252 2254//2254 -f 2255//2255 2256//2256 2257//2257 -f 2257//2257 2256//2256 2183//2183 -f 2257//2257 2183//2183 1785//1785 -f 1785//1785 2183//2183 2184//2184 -f 2181//2181 2183//2183 2258//2258 -f 2258//2258 2183//2183 2259//2259 -f 2260//2260 2261//2261 2262//2262 -f 2262//2262 2261//2261 2181//2181 -f 2262//2262 2181//2181 2263//2263 -f 2263//2263 2181//2181 2258//2258 -f 2260//2260 2264//2264 2261//2261 -f 2261//2261 2264//2264 2265//2265 -f 2261//2261 2265//2265 2266//2266 -f 2266//2266 2265//2265 2267//2267 -f 2266//2266 2267//2267 2256//2256 -f 2256//2256 2267//2267 2268//2268 -f 2268//2268 2269//2269 2256//2256 -f 2256//2256 2269//2269 2270//2270 -f 2256//2256 2270//2270 2183//2183 -f 2183//2183 2270//2270 2271//2271 -f 2183//2183 2271//2271 2259//2259 -f 1788//1788 2179//2179 2272//2272 -f 2272//2272 2179//2179 2181//2181 -f 2272//2272 2181//2181 2273//2273 -f 2273//2273 2181//2181 2261//2261 -f 2255//2255 2274//2274 2256//2256 -f 2256//2256 2274//2274 2266//2266 -f 2274//2274 2273//2273 2266//2266 -f 2266//2266 2273//2273 2261//2261 -f 2272//2272 2273//2273 2275//2275 -f 2275//2275 2273//2273 2274//2274 -f 2275//2275 2274//2274 2276//2276 -f 2276//2276 2274//2274 2255//2255 -f 2276//2276 2255//2255 2257//2257 -f 1785//1785 1783//1783 2257//2257 -f 2257//2257 1783//1783 2276//2276 -f 1786//1786 2275//2275 2046//2046 -f 2046//2046 2275//2275 2276//2276 -f 2046//2046 2276//2276 1783//1783 -f 1786//1786 1788//1788 2275//2275 -f 2275//2275 1788//1788 2272//2272 -f 2277//2277 2278//2278 2279//2279 -f 2279//2279 2278//2278 2195//2195 -f 2279//2279 2195//2195 1805//1805 -f 1805//1805 2195//2195 2196//2196 -f 2280//2280 2193//2193 2281//2281 -f 2281//2281 2282//2282 2280//2280 -f 2280//2280 2282//2282 2283//2283 -f 2280//2280 2283//2283 2284//2284 -f 2284//2284 2283//2283 2285//2285 -f 2278//2278 2286//2286 2195//2195 -f 2195//2195 2286//2286 2287//2287 -f 2287//2287 2288//2288 2195//2195 -f 2195//2195 2288//2288 2289//2289 -f 2195//2195 2289//2289 2193//2193 -f 2193//2193 2289//2289 2290//2290 -f 2193//2193 2290//2290 2281//2281 -f 2285//2285 2291//2291 2284//2284 -f 2284//2284 2291//2291 2292//2292 -f 2284//2284 2292//2292 2278//2278 -f 2278//2278 2292//2292 2293//2293 -f 2278//2278 2293//2293 2286//2286 -f 1722//1722 2191//2191 2294//2294 -f 2294//2294 2191//2191 2193//2193 -f 2294//2294 2193//2193 2295//2295 -f 2295//2295 2193//2193 2280//2280 -f 2277//2277 2296//2296 2278//2278 -f 2278//2278 2296//2296 2284//2284 -f 2296//2296 2295//2295 2284//2284 -f 2284//2284 2295//2295 2280//2280 -f 2297//2297 2294//2294 2295//2295 -f 2277//2277 2279//2279 2298//2298 -f 2297//2297 2295//2295 2298//2298 -f 2298//2298 2295//2295 2296//2296 -f 2298//2298 2296//2296 2277//2277 -f 1806//1806 2298//2298 1805//1805 -f 1805//1805 2298//2298 2279//2279 -f 1791//1791 2297//2297 1806//1806 -f 1806//1806 2297//2297 2298//2298 -f 1722//1722 2294//2294 1791//1791 -f 1791//1791 2294//2294 2297//2297 -f 2258//2258 1629//1629 2263//2263 -f 2263//2263 1629//1629 1631//1631 -f 2263//2263 1631//1631 2262//2262 -f 2262//2262 1631//1631 1632//1632 -f 2262//2262 1632//1632 2260//2260 -f 2260//2260 1632//1632 1637//1637 -f 2260//2260 1637//1637 2264//2264 -f 2264//2264 1637//1637 1636//1636 -f 2264//2264 1636//1636 2265//2265 -f 2265//2265 1636//1636 1640//1640 -f 2265//2265 1640//1640 2267//2267 -f 2267//2267 1640//1640 1639//1639 -f 2267//2267 1639//1639 2268//2268 -f 2268//2268 1639//1639 1638//1638 -f 2268//2268 1638//1638 2269//2269 -f 2269//2269 1638//1638 1633//1633 -f 2269//2269 1633//1633 2270//2270 -f 2270//2270 1633//1633 1634//1634 -f 2270//2270 1634//1634 2271//2271 -f 2271//2271 1634//1634 1635//1635 -f 2271//2271 1635//1635 2259//2259 -f 2259//2259 1635//1635 1628//1628 -f 2259//2259 1628//1628 2258//2258 -f 2258//2258 1628//1628 1629//1629 -f 2286//2286 1662//1662 2287//2287 -f 2287//2287 1662//1662 1661//1661 -f 2287//2287 1661//1661 2288//2288 -f 2288//2288 1661//1661 1660//1660 -f 2288//2288 1660//1660 2289//2289 -f 2289//2289 1660//1660 1658//1658 -f 2289//2289 1658//1658 2290//2290 -f 2290//2290 1658//1658 1657//1657 -f 2290//2290 1657//1657 2281//2281 -f 2281//2281 1657//1657 1652//1652 -f 2281//2281 1652//1652 2282//2282 -f 2282//2282 1652//1652 1654//1654 -f 2282//2282 1654//1654 2283//2283 -f 2283//2283 1654//1654 1655//1655 -f 2283//2283 1655//1655 2285//2285 -f 2285//2285 1655//1655 1656//1656 -f 2285//2285 1656//1656 2291//2291 -f 2291//2291 1656//1656 1666//1666 -f 2291//2291 1666//1666 2292//2292 -f 2292//2292 1666//1666 1665//1665 -f 2292//2292 1665//1665 2293//2293 -f 2293//2293 1665//1665 1663//1663 -f 2293//2293 1663//1663 2286//2286 -f 2286//2286 1663//1663 1662//1662 -f 2299//2299 2300//2300 2301//2301 -f 2301//2301 2300//2300 2205//2205 -f 2301//2301 2205//2205 1816//1816 -f 1816//1816 2205//2205 2206//2206 -f 2302//2302 2203//2203 2303//2303 -f 2303//2303 2304//2304 2302//2302 -f 2302//2302 2304//2304 2305//2305 -f 2302//2302 2305//2305 2306//2306 -f 2306//2306 2305//2305 2307//2307 -f 2308//2308 2205//2205 2309//2309 -f 2309//2309 2205//2205 2300//2300 -f 2307//2307 2310//2310 2306//2306 -f 2306//2306 2310//2310 2311//2311 -f 2306//2306 2311//2311 2300//2300 -f 2300//2300 2311//2311 2312//2312 -f 2300//2300 2312//2312 2309//2309 -f 2308//2308 2313//2313 2205//2205 -f 2205//2205 2313//2313 2314//2314 -f 2205//2205 2314//2314 2203//2203 -f 2203//2203 2314//2314 2315//2315 -f 2203//2203 2315//2315 2303//2303 -f 1821//1821 2201//2201 2316//2316 -f 2316//2316 2201//2201 2203//2203 -f 2316//2316 2203//2203 2317//2317 -f 2317//2317 2203//2203 2302//2302 -f 2318//2318 2319//2319 2320//2320 -f 2320//2320 2319//2319 2215//2215 -f 2320//2320 2215//2215 1832//1832 -f 1832//1832 2215//2215 2216//2216 -f 2321//2321 2215//2215 2322//2322 -f 2322//2322 2215//2215 2319//2319 -f 2321//2321 2323//2323 2215//2215 -f 2215//2215 2323//2323 2324//2324 -f 2215//2215 2324//2324 2213//2213 -f 2325//2325 2326//2326 2327//2327 -f 2327//2327 2326//2326 2328//2328 -f 2325//2325 2329//2329 2326//2326 -f 2326//2326 2329//2329 2330//2330 -f 2326//2326 2330//2330 2319//2319 -f 2319//2319 2330//2330 2331//2331 -f 2319//2319 2331//2331 2322//2322 -f 2324//2324 2332//2332 2213//2213 -f 2213//2213 2332//2332 2333//2333 -f 2213//2213 2333//2333 2328//2328 -f 2328//2328 2333//2333 2334//2334 -f 2328//2328 2334//2334 2327//2327 -f 1837//1837 2211//2211 2335//2335 -f 2335//2335 2211//2211 2213//2213 -f 2335//2335 2213//2213 2336//2336 -f 2336//2336 2213//2213 2328//2328 -f 2337//2337 2338//2338 2339//2339 -f 2339//2339 2338//2338 2225//2225 -f 2339//2339 2225//2225 1841//1841 -f 1841//1841 2225//2225 2226//2226 -f 2340//2340 2341//2341 2342//2342 -f 2342//2342 2341//2341 2338//2338 -f 2343//2343 2223//2223 2344//2344 -f 2344//2344 2345//2345 2343//2343 -f 2343//2343 2345//2345 2346//2346 -f 2343//2343 2346//2346 2342//2342 -f 2342//2342 2346//2346 2347//2347 -f 2342//2342 2347//2347 2340//2340 -f 2341//2341 2348//2348 2338//2338 -f 2338//2338 2348//2348 2349//2349 -f 2338//2338 2349//2349 2225//2225 -f 2225//2225 2349//2349 2350//2350 -f 2350//2350 2351//2351 2225//2225 -f 2225//2225 2351//2351 2352//2352 -f 2225//2225 2352//2352 2223//2223 -f 2223//2223 2352//2352 2353//2353 -f 2223//2223 2353//2353 2344//2344 -f 1844//1844 2221//2221 2354//2354 -f 2354//2354 2221//2221 2223//2223 -f 2354//2354 2223//2223 2355//2355 -f 2355//2355 2223//2223 2343//2343 -f 2299//2299 2356//2356 2300//2300 -f 2300//2300 2356//2356 2306//2306 -f 2356//2356 2317//2317 2306//2306 -f 2306//2306 2317//2317 2302//2302 -f 2357//2357 2316//2316 2317//2317 -f 2299//2299 2301//2301 2358//2358 -f 2357//2357 2317//2317 2358//2358 -f 2358//2358 2317//2317 2356//2356 -f 2358//2358 2356//2356 2299//2299 -f 2318//2318 2359//2359 2319//2319 -f 2319//2319 2359//2359 2326//2326 -f 2359//2359 2336//2336 2326//2326 -f 2326//2326 2336//2336 2328//2328 -f 2360//2360 2335//2335 2336//2336 -f 2318//2318 2320//2320 2361//2361 -f 2360//2360 2336//2336 2361//2361 -f 2361//2361 2336//2336 2359//2359 -f 2361//2361 2359//2359 2318//2318 -f 2337//2337 2362//2362 2338//2338 -f 2338//2338 2362//2362 2342//2342 -f 2362//2362 2355//2355 2342//2342 -f 2342//2342 2355//2355 2343//2343 -f 2363//2363 2354//2354 2355//2355 -f 2337//2337 2339//2339 2364//2364 -f 2363//2363 2355//2355 2364//2364 -f 2364//2364 2355//2355 2362//2362 -f 2364//2364 2362//2362 2337//2337 -f 1818//1818 2358//2358 1816//1816 -f 1816//1816 2358//2358 2301//2301 -f 1820//1820 2357//2357 1818//1818 -f 1818//1818 2357//2357 2358//2358 -f 1821//1821 2316//2316 1820//1820 -f 1820//1820 2316//2316 2357//2357 -f 1834//1834 2361//2361 1832//1832 -f 1832//1832 2361//2361 2320//2320 -f 1838//1838 2360//2360 1834//1834 -f 1834//1834 2360//2360 2361//2361 -f 1837//1837 2335//2335 1838//1838 -f 1838//1838 2335//2335 2360//2360 -f 1842//1842 2364//2364 1841//1841 -f 1841//1841 2364//2364 2339//2339 -f 1843//1843 2363//2363 1842//1842 -f 1842//1842 2363//2363 2364//2364 -f 1844//1844 2354//2354 1843//1843 -f 1843//1843 2354//2354 2363//2363 -f 2309//2309 1350//1350 2308//2308 -f 2308//2308 1350//1350 1349//1349 -f 2308//2308 1349//1349 2313//2313 -f 2313//2313 1349//1349 1347//1347 -f 2313//2313 1347//1347 2314//2314 -f 2314//2314 1347//1347 1345//1345 -f 2314//2314 1345//1345 2315//2315 -f 2315//2315 1345//1345 1344//1344 -f 2315//2315 1344//1344 2303//2303 -f 2303//2303 1344//1344 1339//1339 -f 2303//2303 1339//1339 2304//2304 -f 2304//2304 1339//1339 1341//1341 -f 2304//2304 1341//1341 2305//2305 -f 2305//2305 1341//1341 1343//1343 -f 2305//2305 1343//1343 2307//2307 -f 2307//2307 1343//1343 1351//1351 -f 2307//2307 1351//1351 2310//2310 -f 2310//2310 1351//1351 1353//1353 -f 2310//2310 1353//1353 2311//2311 -f 2311//2311 1353//1353 1354//1354 -f 2311//2311 1354//1354 2312//2312 -f 2312//2312 1354//1354 1338//1338 -f 2312//2312 1338//1338 2309//2309 -f 2309//2309 1338//1338 1350//1350 -f 2322//2322 1222//1222 2321//2321 -f 2321//2321 1222//1222 1221//1221 -f 2321//2321 1221//1221 2323//2323 -f 2323//2323 1221//1221 1651//1651 -f 2323//2323 1651//1651 2324//2324 -f 2324//2324 1651//1651 1650//1650 -f 2324//2324 1650//1650 2332//2332 -f 2332//2332 1650//1650 1649//1649 -f 2332//2332 1649//1649 2333//2333 -f 2333//2333 1649//1649 1648//1648 -f 2333//2333 1648//1648 2334//2334 -f 2334//2334 1648//1648 1647//1647 -f 2334//2334 1647//1647 2327//2327 -f 2327//2327 1647//1647 1646//1646 -f 2327//2327 1646//1646 2325//2325 -f 2325//2325 1646//1646 1643//1643 -f 2325//2325 1643//1643 2329//2329 -f 2329//2329 1643//1643 1642//1642 -f 2329//2329 1642//1642 2330//2330 -f 2330//2330 1642//1642 1645//1645 -f 2330//2330 1645//1645 2331//2331 -f 2331//2331 1645//1645 1644//1644 -f 2331//2331 1644//1644 2322//2322 -f 2322//2322 1644//1644 1222//1222 -f 2349//2349 1333//1333 2350//2350 -f 2350//2350 1333//1333 1332//1332 -f 2350//2350 1332//1332 2351//2351 -f 2351//2351 1332//1332 1330//1330 -f 2351//2351 1330//1330 2352//2352 -f 2352//2352 1330//1330 1328//1328 -f 2352//2352 1328//1328 2353//2353 -f 2353//2353 1328//1328 1327//1327 -f 2353//2353 1327//1327 2344//2344 -f 2344//2344 1327//1327 1324//1324 -f 2344//2344 1324//1324 2345//2345 -f 2345//2345 1324//1324 1323//1323 -f 2345//2345 1323//1323 2346//2346 -f 2346//2346 1323//1323 1326//1326 -f 2346//2346 1326//1326 2347//2347 -f 2347//2347 1326//1326 1325//1325 -f 2347//2347 1325//1325 2340//2340 -f 2340//2340 1325//1325 1320//1320 -f 2340//2340 1320//1320 2341//2341 -f 2341//2341 1320//1320 1319//1319 -f 2341//2341 1319//1319 2348//2348 -f 2348//2348 1319//1319 1318//1318 -f 2348//2348 1318//1318 2349//2349 -f 2349//2349 1318//1318 1333//1333 -f 2145//2145 2117//2117 2146//2146 -f 2146//2146 2117//2117 2113//2113 -f 2146//2146 2113//2113 2047//2047 -f 2047//2047 2113//2113 2153//2153 -f 1773//1773 2149//2149 2143//2143 -f 2143//2143 2149//2149 2112//2112 -f 2143//2143 2112//2112 2144//2144 -f 2144//2144 2112//2112 2121//2121 -f 2145//2145 2148//2148 2117//2117 -f 2117//2117 2148//2148 2119//2119 -f 2148//2148 2144//2144 2119//2119 -f 2119//2119 2144//2144 2121//2121 -f 2048//2048 2147//2147 2047//2047 -f 2047//2047 2147//2147 2146//2146 -f 1775//1775 2142//2142 2049//2049 -f 2049//2049 2142//2142 2147//2147 -f 2049//2049 2147//2147 2048//2048 -f 1773//1773 2143//2143 1775//1775 -f 1775//1775 2143//2143 2142//2142 -f 2134//2134 2095//2095 2135//2135 -f 2135//2135 2095//2095 2097//2097 -f 2135//2135 2097//2097 1923//1923 -f 1923//1923 2097//2097 2140//2140 -f 1761//1761 2136//2136 2129//2129 -f 2129//2129 2136//2136 2100//2100 -f 2129//2129 2100//2100 2130//2130 -f 2130//2130 2100//2100 2099//2099 -f 2134//2134 2132//2132 2095//2095 -f 2095//2095 2132//2132 2103//2103 -f 2132//2132 2130//2130 2103//2103 -f 2103//2103 2130//2130 2099//2099 -f 1923//1923 1755//1755 2135//2135 -f 2135//2135 1755//1755 2133//2133 -f 1755//1755 1754//1754 2133//2133 -f 2133//2133 1754//1754 2131//2131 -f 1754//1754 1761//1761 2131//2131 -f 2131//2131 1761//1761 2129//2129 -f 2114//2114 1302//1302 2123//2123 -f 2123//2123 1302//1302 1301//1301 -f 2123//2123 1301//1301 2124//2124 -f 2124//2124 1301//1301 1300//1300 -f 2124//2124 1300//1300 2125//2125 -f 2125//2125 1300//1300 1298//1298 -f 2125//2125 1298//1298 2122//2122 -f 2122//2122 1298//1298 1297//1297 -f 2122//2122 1297//1297 2120//2120 -f 2120//2120 1297//1297 1295//1295 -f 2120//2120 1295//1295 2118//2118 -f 2118//2118 1295//1295 1294//1294 -f 2118//2118 1294//1294 2116//2116 -f 2116//2116 1294//1294 1311//1311 -f 2116//2116 1311//1311 2126//2126 -f 2126//2126 1311//1311 1309//1309 -f 2126//2126 1309//1309 2127//2127 -f 2127//2127 1309//1309 1307//1307 -f 2127//2127 1307//1307 2128//2128 -f 2128//2128 1307//1307 1305//1305 -f 2128//2128 1305//1305 2115//2115 -f 2115//2115 1305//1305 1304//1304 -f 2115//2115 1304//1304 2114//2114 -f 2114//2114 1304//1304 1302//1302 -f 2105//2105 1452//1452 2104//2104 -f 2104//2104 1452//1452 1451//1451 -f 2104//2104 1451//1451 2102//2102 -f 2102//2102 1451//1451 1450//1450 -f 2102//2102 1450//1450 2106//2106 -f 2106//2106 1450//1450 1448//1448 -f 2106//2106 1448//1448 2107//2107 -f 2107//2107 1448//1448 1446//1446 -f 2107//2107 1446//1446 2108//2108 -f 2108//2108 1446//1446 1445//1445 -f 2108//2108 1445//1445 2096//2096 -f 2096//2096 1445//1445 1442//1442 -f 2096//2096 1442//1442 2098//2098 -f 2098//2098 1442//1442 1441//1441 -f 2098//2098 1441//1441 2109//2109 -f 2109//2109 1441//1441 1457//1457 -f 2109//2109 1457//1457 2110//2110 -f 2110//2110 1457//1457 1456//1456 -f 2110//2110 1456//1456 2111//2111 -f 2111//2111 1456//1456 1454//1454 -f 2111//2111 1454//1454 2101//2101 -f 2101//2101 1454//1454 1453//1453 -f 2101//2101 1453//1453 2105//2105 -f 2105//2105 1453//1453 1452//1452 -f 2075//2075 1702//1702 2076//2076 -f 2076//2076 1702//1702 1704//1704 -f 2076//2076 1704//1704 1745//1745 -f 1745//1745 1704//1704 2093//2093 -f 2054//2054 2089//2089 2070//2070 -f 2070//2070 2089//2089 1711//1711 -f 2070//2070 1711//1711 2071//2071 -f 2071//2071 1711//1711 1713//1713 -f 2068//2068 1689//1689 2069//2069 -f 2069//2069 1689//1689 1691//1691 -f 2069//2069 1691//1691 1739//1739 -f 1739//1739 1691//1691 2087//2087 -f 1725//1725 2083//2083 2063//2063 -f 2063//2063 2083//2083 1695//1695 -f 2063//2063 1695//1695 2064//2064 -f 2064//2064 1695//1695 1685//1685 -f 2061//2061 1678//1678 2062//2062 -f 2062//2062 1678//1678 1668//1668 -f 2062//2062 1668//1668 1726//1726 -f 1726//1726 1668//1668 2081//2081 -f 1734//1734 2077//2077 2056//2056 -f 2056//2056 2077//2077 1674//1674 -f 2056//2056 1674//1674 2057//2057 -f 2057//2057 1674//1674 1677//1677 -f 2075//2075 2073//2073 1702//1702 -f 1702//1702 2073//2073 1706//1706 -f 2073//2073 2071//2071 1706//1706 -f 1706//1706 2071//2071 1713//1713 -f 2068//2068 2066//2066 1689//1689 -f 1689//1689 2066//2066 1687//1687 -f 2066//2066 2064//2064 1687//1687 -f 1687//1687 2064//2064 1685//1685 -f 2061//2061 2059//2059 1678//1678 -f 1678//1678 2059//2059 1671//1671 -f 2059//2059 2057//2057 1671//1671 -f 1671//1671 2057//2057 1677//1677 -f 1745//1745 1744//1744 2076//2076 -f 2076//2076 1744//1744 2074//2074 -f 1744//1744 1750//1750 2074//2074 -f 2074//2074 1750//1750 2072//2072 -f 1750//1750 2054//2054 2072//2072 -f 2072//2072 2054//2054 2070//2070 -f 1739//1739 1738//1738 2069//2069 -f 2069//2069 1738//1738 2067//2067 -f 1738//1738 1742//1742 2067//2067 -f 2067//2067 1742//1742 2065//2065 -f 1742//1742 1725//1725 2065//2065 -f 2065//2065 1725//1725 2063//2063 -f 1726//1726 1728//1728 2062//2062 -f 2062//2062 1728//1728 2060//2060 -f 1728//1728 1732//1732 2060//2060 -f 2060//2060 1732//1732 2058//2058 -f 1732//1732 1734//1734 2058//2058 -f 2058//2058 1734//1734 2056//2056 -f 1712//1712 1279//1279 1716//1716 -f 1716//1716 1279//1279 1278//1278 -f 1716//1716 1278//1278 1717//1717 -f 1717//1717 1278//1278 1273//1273 -f 1717//1717 1273//1273 1718//1718 -f 1718//1718 1273//1273 1290//1290 -f 1718//1718 1290//1290 1707//1707 -f 1707//1707 1290//1290 1289//1289 -f 1707//1707 1289//1289 1708//1708 -f 1708//1708 1289//1289 1287//1287 -f 1708//1708 1287//1287 1703//1703 -f 1703//1703 1287//1287 1286//1286 -f 1703//1703 1286//1286 1705//1705 -f 1705//1705 1286//1286 1285//1285 -f 1705//1705 1285//1285 1709//1709 -f 1709//1709 1285//1285 1293//1293 -f 1709//1709 1293//1293 1710//1710 -f 1710//1710 1293//1293 1292//1292 -f 1710//1710 1292//1292 1715//1715 -f 1715//1715 1292//1292 1291//1291 -f 1715//1715 1291//1291 1714//1714 -f 1714//1714 1291//1291 1281//1281 -f 1714//1714 1281//1281 1712//1712 -f 1712//1712 1281//1281 1279//1279 -f 1698//1698 1583//1583 1686//1686 -f 1686//1686 1583//1583 1582//1582 -f 1686//1686 1582//1582 1688//1688 -f 1688//1688 1582//1582 1593//1593 -f 1688//1688 1593//1593 1699//1699 -f 1699//1699 1593//1593 1592//1592 -f 1699//1699 1592//1592 1700//1700 -f 1700//1700 1592//1592 1591//1591 -f 1700//1700 1591//1591 1701//1701 -f 1701//1701 1591//1591 1588//1588 -f 1701//1701 1588//1588 1690//1690 -f 1690//1690 1588//1588 1589//1589 -f 1690//1690 1589//1589 1692//1692 -f 1692//1692 1589//1589 1590//1590 -f 1692//1692 1590//1590 1693//1693 -f 1693//1693 1590//1590 1587//1587 -f 1693//1693 1587//1587 1694//1694 -f 1694//1694 1587//1587 1586//1586 -f 1694//1694 1586//1586 1696//1696 -f 1696//1696 1586//1586 1585//1585 -f 1696//1696 1585//1585 1697//1697 -f 1697//1697 1585//1585 1584//1584 -f 1697//1697 1584//1584 1698//1698 -f 1698//1698 1584//1584 1583//1583 -f 1682//1682 1259//1259 1683//1683 -f 1683//1683 1259//1259 1257//1257 -f 1683//1683 1257//1257 1684//1684 -f 1684//1684 1257//1257 1256//1256 -f 1684//1684 1256//1256 1672//1672 -f 1672//1672 1256//1256 1267//1267 -f 1672//1672 1267//1267 1673//1673 -f 1673//1673 1267//1267 1269//1269 -f 1673//1673 1269//1269 1679//1679 -f 1679//1679 1269//1269 1271//1271 -f 1679//1679 1271//1271 1680//1680 -f 1680//1680 1271//1271 1272//1272 -f 1680//1680 1272//1272 1681//1681 -f 1681//1681 1272//1272 1266//1266 -f 1681//1681 1266//1266 1669//1669 -f 1669//1669 1266//1266 1265//1265 -f 1669//1669 1265//1265 1670//1670 -f 1670//1670 1265//1265 1264//1264 -f 1670//1670 1264//1264 1675//1675 -f 1675//1675 1264//1264 1263//1263 -f 1675//1675 1263//1263 1676//1676 -f 1676//1676 1263//1263 1261//1261 -f 1676//1676 1261//1261 1682//1682 -f 1682//1682 1261//1261 1259//1259 -f 2158//2158 114//114 2365//2365 -f 2365//2365 114//114 138//138 -f 2365//2365 138//138 2366//2366 -f 2366//2366 138//138 2367//2367 -f 2367//2367 138//138 109//109 -f 2367//2367 109//109 2368//2368 -f 2368//2368 109//109 2369//2369 -f 2369//2369 109//109 110//110 -f 2369//2369 110//110 2370//2370 -f 2370//2370 110//110 2371//2371 -f 2371//2371 110//110 112//112 -f 2371//2371 112//112 2372//2372 -f 2372//2372 112//112 2373//2373 -f 2373//2373 112//112 86//86 -f 2373//2373 86//86 2160//2160 -f 2156//2156 128//128 2374//2374 -f 2374//2374 128//128 135//135 -f 2374//2374 135//135 2375//2375 -f 2375//2375 135//135 2376//2376 -f 2376//2376 135//135 134//134 -f 2376//2376 134//134 2377//2377 -f 2377//2377 134//134 2378//2378 -f 2378//2378 134//134 120//120 -f 2378//2378 120//120 2379//2379 -f 2379//2379 120//120 2380//2380 -f 2380//2380 120//120 118//118 -f 2380//2380 118//118 2381//2381 -f 2381//2381 118//118 2382//2382 -f 2382//2382 118//118 116//116 -f 2382//2382 116//116 2157//2157 -f 2383//2383 1826//1826 1824//1824 -f 1824//1824 1823//1823 2383//2383 -f 2383//2383 1823//1823 1897//1897 -f 2383//2383 1897//1897 2384//2384 -f 2384//2384 1897//1897 1895//1895 -f 2384//2384 1895//1895 1893//1893 -f 1612//1612 2384//2384 1613//1613 -f 1613//1613 2384//2384 1614//1614 -f 1893//1893 1883//1883 2384//2384 -f 2384//2384 1883//1883 2385//2385 -f 2384//2384 2385//2385 1614//1614 -f 1614//1614 2385//2385 1480//1480 -f 1887//1887 2386//2386 1885//1885 -f 1885//1885 2386//2386 2385//2385 -f 1885//1885 2385//2385 1883//1883 -f 1887//1887 1889//1889 2386//2386 -f 2386//2386 1889//1889 1891//1891 -f 2386//2386 1891//1891 2021//2021 -f 2387//2387 2388//2388 2386//2386 -f 2021//2021 1826//1826 2386//2386 -f 2386//2386 1826//1826 2383//2383 -f 2386//2386 2383//2383 2387//2387 -f 2389//2389 2390//2390 2391//2391 -f 1901//1901 1902//1902 2391//2391 -f 2391//2391 1902//1902 2392//2392 -f 2391//2391 2392//2392 2389//2389 -f 2392//2392 1902//1902 1903//1903 -f 1903//1903 1908//1908 2392//2392 -f 2392//2392 1908//1908 1910//1910 -f 2392//2392 1910//1910 2393//2393 -f 2393//2393 1910//1910 1912//1912 -f 2393//2393 1912//1912 1907//1907 -f 1496//1496 2393//2393 1497//1497 -f 1497//1497 2393//2393 1499//1499 -f 1907//1907 1906//1906 2393//2393 -f 2393//2393 1906//1906 2394//2394 -f 2393//2393 2394//2394 1499//1499 -f 1499//1499 2394//2394 1501//1501 -f 1914//1914 2391//2391 1905//1905 -f 1905//1905 2391//2391 2394//2394 -f 1905//1905 2394//2394 1906//1906 -f 1914//1914 1916//1916 2391//2391 -f 2391//2391 1916//1916 1899//1899 -f 2391//2391 1899//1899 1901//1901 -f 2395//2395 1239//1239 1237//1237 -f 1515//1515 2396//2396 1237//1237 -f 1237//1237 2396//2396 2397//2397 -f 1237//1237 2397//2397 2395//2395 -f 1514//1514 2398//2398 1515//1515 -f 1515//1515 2398//2398 2399//2399 -f 1515//1515 2399//2399 2396//2396 -f 1512//1512 2400//2400 1514//1514 -f 1514//1514 2400//2400 2401//2401 -f 1514//1514 2401//2401 2398//2398 -f 1511//1511 2402//2402 1512//1512 -f 1512//1512 2402//2402 2403//2403 -f 1512//1512 2403//2403 2400//2400 -f 1510//1510 2404//2404 1511//1511 -f 1511//1511 2404//2404 2405//2405 -f 1511//1511 2405//2405 2402//2402 -f 1509//1509 2406//2406 1510//1510 -f 1510//1510 2406//2406 2407//2407 -f 1510//1510 2407//2407 2404//2404 -f 1505//1505 2408//2408 1509//1509 -f 1509//1509 2408//2408 2409//2409 -f 1509//1509 2409//2409 2406//2406 -f 1507//1507 2410//2410 1505//1505 -f 1505//1505 2410//2410 2411//2411 -f 1505//1505 2411//2411 2408//2408 -f 1520//1520 2412//2412 1507//1507 -f 1507//1507 2412//2412 2413//2413 -f 1507//1507 2413//2413 2410//2410 -f 1519//1519 2414//2414 1520//1520 -f 1520//1520 2414//2414 2415//2415 -f 1520//1520 2415//2415 2412//2412 -f 1517//1517 2416//2416 1519//1519 -f 1519//1519 2416//2416 2417//2417 -f 1519//1519 2417//2417 2414//2414 -f 1516//1516 2418//2418 1517//1517 -f 1517//1517 2418//2418 2419//2419 -f 1517//1517 2419//2419 2416//2416 -f 1526//1526 2420//2420 1516//1516 -f 1516//1516 2420//2420 2421//2421 -f 1516//1516 2421//2421 2418//2418 -f 1528//1528 2422//2422 1526//1526 -f 1526//1526 2422//2422 2423//2423 -f 1526//1526 2423//2423 2420//2420 -f 1529//1529 2424//2424 1528//1528 -f 1528//1528 2424//2424 2425//2425 -f 1528//1528 2425//2425 2422//2422 -f 1523//1523 2426//2426 1529//1529 -f 1529//1529 2426//2426 2427//2427 -f 1529//1529 2427//2427 2424//2424 -f 1525//1525 2428//2428 1523//1523 -f 1523//1523 2428//2428 2429//2429 -f 1523//1523 2429//2429 2426//2426 -f 1539//1539 2430//2430 1525//1525 -f 1525//1525 2430//2430 2431//2431 -f 1525//1525 2431//2431 2428//2428 -f 2395//2395 2432//2432 1239//1239 -f 1239//1239 2432//2432 2433//2433 -f 1239//1239 2433//2433 1539//1539 -f 1539//1539 2433//2433 2434//2434 -f 1539//1539 2434//2434 2430//2430 -f 2435//2435 2436//2436 2437//2437 -f 2437//2437 2436//2436 2438//2438 -f 2439//2439 2440//2440 2441//2441 -f 2441//2441 2440//2440 2442//2442 -f 2443//2443 2444//2444 2445//2445 -f 2446//2446 2447//2447 2444//2444 -f 2444//2444 2447//2447 2448//2448 -f 2444//2444 2448//2448 2445//2445 -f 2449//2449 2450//2450 2451//2451 -f 2451//2451 2450//2450 2452//2452 -f 2451//2451 2452//2452 2453//2453 -f 2454//2454 2455//2455 2456//2456 -f 2456//2456 2455//2455 2457//2457 -f 2440//2440 2458//2458 2442//2442 -f 2442//2442 2458//2458 2459//2459 -f 2442//2442 2459//2459 2460//2460 -f 2436//2436 2461//2461 2438//2438 -f 2438//2438 2461//2461 2462//2462 -f 2438//2438 2462//2462 2463//2463 -f 2464//2464 2465//2465 2437//2437 -f 2437//2437 2465//2465 2466//2466 -f 2437//2437 2466//2466 2435//2435 -f 2467//2467 2468//2468 2469//2469 -f 2469//2469 2468//2468 2470//2470 -f 2449//2449 2471//2471 2450//2450 -f 2450//2450 2471//2471 2472//2472 -f 2450//2450 2472//2472 2446//2446 -f 2446//2446 2472//2472 2473//2473 -f 2446//2446 2473//2473 2447//2447 -f 2453//2453 2452//2452 2474//2474 -f 2474//2474 2452//2452 2475//2475 -f 2474//2474 2475//2475 2476//2476 -f 2455//2455 2477//2477 2457//2457 -f 2457//2457 2477//2477 2478//2478 -f 2457//2457 2478//2478 2475//2475 -f 2475//2475 2478//2478 2479//2479 -f 2475//2475 2479//2479 2476//2476 -f 2459//2459 2480//2480 2460//2460 -f 2460//2460 2480//2480 2481//2481 -f 2460//2460 2481//2481 2456//2456 -f 2456//2456 2481//2481 2482//2482 -f 2456//2456 2482//2482 2454//2454 -f 2462//2462 2483//2483 2463//2463 -f 2463//2463 2483//2483 2484//2484 -f 2463//2463 2484//2484 2441//2441 -f 2441//2441 2484//2484 2485//2485 -f 2441//2441 2485//2485 2439//2439 -f 2468//2468 2486//2486 2470//2470 -f 2470//2470 2486//2486 2487//2487 -f 2470//2470 2487//2487 2464//2464 -f 2464//2464 2487//2487 2488//2488 -f 2464//2464 2488//2488 2465//2465 -f 2445//2445 2489//2489 2443//2443 -f 2443//2443 2489//2489 2490//2490 -f 2443//2443 2490//2490 2469//2469 -f 2469//2469 2490//2490 2491//2491 -f 2469//2469 2491//2491 2467//2467 -f 2492//2492 2438//2438 2493//2493 -f 2493//2493 2438//2438 2463//2463 -f 2493//2493 2463//2463 2494//2494 -f 2494//2494 2463//2463 2441//2441 -f 2494//2494 2441//2441 2495//2495 -f 2495//2495 2441//2441 2442//2442 -f 2495//2495 2442//2442 2496//2496 -f 2496//2496 2442//2442 2460//2460 -f 2496//2496 2460//2460 2497//2497 -f 2497//2497 2460//2460 2456//2456 -f 2497//2497 2456//2456 2498//2498 -f 2498//2498 2456//2456 2457//2457 -f 2498//2498 2457//2457 2499//2499 -f 2499//2499 2457//2457 2475//2475 -f 2499//2499 2475//2475 2500//2500 -f 2500//2500 2475//2475 2452//2452 -f 2500//2500 2452//2452 2501//2501 -f 2501//2501 2452//2452 2450//2450 -f 2501//2501 2450//2450 2502//2502 -f 2502//2502 2450//2450 2446//2446 -f 2502//2502 2446//2446 2503//2503 -f 2503//2503 2446//2446 2444//2444 -f 2503//2503 2444//2444 2504//2504 -f 2504//2504 2444//2444 2443//2443 -f 2504//2504 2443//2443 2505//2505 -f 2505//2505 2443//2443 2469//2469 -f 2505//2505 2469//2469 2506//2506 -f 2506//2506 2469//2469 2470//2470 -f 2506//2506 2470//2470 2507//2507 -f 2507//2507 2470//2470 2464//2464 -f 2507//2507 2464//2464 2508//2508 -f 2508//2508 2464//2464 2437//2437 -f 2508//2508 2437//2437 2492//2492 -f 2492//2492 2437//2437 2438//2438 -f 2509//2509 2507//2507 2510//2510 -f 2510//2510 2507//2507 2508//2508 -f 2510//2510 2508//2508 2511//2511 -f 2511//2511 2508//2508 2492//2492 -f 2511//2511 2492//2492 2512//2512 -f 2513//2513 2504//2504 2514//2514 -f 2514//2514 2504//2504 2505//2505 -f 2514//2514 2505//2505 2509//2509 -f 2509//2509 2505//2505 2506//2506 -f 2509//2509 2506//2506 2507//2507 -f 2515//2515 2500//2500 2516//2516 -f 2516//2516 2500//2500 2501//2501 -f 2516//2516 2501//2501 2517//2517 -f 2517//2517 2501//2501 2502//2502 -f 2517//2517 2502//2502 2513//2513 -f 2513//2513 2502//2502 2503//2503 -f 2513//2513 2503//2503 2504//2504 -f 2518//2518 2497//2497 2519//2519 -f 2519//2519 2497//2497 2498//2498 -f 2519//2519 2498//2498 2515//2515 -f 2515//2515 2498//2498 2499//2499 -f 2515//2515 2499//2499 2500//2500 -f 2492//2492 2493//2493 2512//2512 -f 2512//2512 2493//2493 2494//2494 -f 2512//2512 2494//2494 2520//2520 -f 2520//2520 2494//2494 2495//2495 -f 2520//2520 2495//2495 2518//2518 -f 2518//2518 2495//2495 2496//2496 -f 2518//2518 2496//2496 2497//2497 -f 2521//2521 2522//2522 2523//2523 -f 2524//2524 2522//2522 2521//2521 -f 2521//2521 2525//2525 2526//2526 -f 2527//2527 2525//2525 2521//2521 -f 2523//2523 2527//2527 2521//2521 -f 2521//2521 2528//2528 2529//2529 -f 2530//2530 2528//2528 2521//2521 -f 2526//2526 2530//2530 2521//2521 -f 2521//2521 2531//2531 2532//2532 -f 2533//2533 2531//2531 2521//2521 -f 2529//2529 2533//2533 2521//2521 -f 2532//2532 2524//2524 2521//2521 -f 2524//2524 2534//2534 2522//2522 -f 2522//2522 2534//2534 2535//2535 -f 2522//2522 2535//2535 2523//2523 -f 2523//2523 2535//2535 2536//2536 -f 2523//2523 2536//2536 2527//2527 -f 2527//2527 2536//2536 2537//2537 -f 2527//2527 2537//2537 2525//2525 -f 2525//2525 2537//2537 2538//2538 -f 2525//2525 2538//2538 2526//2526 -f 2526//2526 2538//2538 2539//2539 -f 2526//2526 2539//2539 2530//2530 -f 2530//2530 2539//2539 2540//2540 -f 2530//2530 2540//2540 2528//2528 -f 2528//2528 2540//2540 2541//2541 -f 2528//2528 2541//2541 2529//2529 -f 2529//2529 2541//2541 2542//2542 -f 2529//2529 2542//2542 2533//2533 -f 2533//2533 2542//2542 2543//2543 -f 2533//2533 2543//2543 2531//2531 -f 2531//2531 2543//2543 2544//2544 -f 2531//2531 2544//2544 2532//2532 -f 2532//2532 2544//2544 2545//2545 -f 2532//2532 2545//2545 2524//2524 -f 2524//2524 2545//2545 2534//2534 -f 2535//2535 1872//1872 2536//2536 -f 2536//2536 1872//1872 1870//1870 -f 2536//2536 1870//1870 2537//2537 -f 2537//2537 1870//1870 1869//1869 -f 2537//2537 1869//1869 2538//2538 -f 2538//2538 1869//1869 1868//1868 -f 2538//2538 1868//1868 2539//2539 -f 2539//2539 1868//1868 1867//1867 -f 2539//2539 1867//1867 2540//2540 -f 2540//2540 1867//1867 1865//1865 -f 2540//2540 1865//1865 2541//2541 -f 2541//2541 1865//1865 1878//1878 -f 2541//2541 1878//1878 2542//2542 -f 2542//2542 1878//1878 1877//1877 -f 2542//2542 1877//1877 2543//2543 -f 2543//2543 1877//1877 1876//1876 -f 2543//2543 1876//1876 2544//2544 -f 2544//2544 1876//1876 1875//1875 -f 2544//2544 1875//1875 2545//2545 -f 2545//2545 1875//1875 1874//1874 -f 2545//2545 1874//1874 2534//2534 -f 2534//2534 1874//1874 1873//1873 -f 2534//2534 1873//1873 2535//2535 -f 2535//2535 1873//1873 1872//1872 -f 2546//2546 2547//2547 2548//2548 -f 2549//2549 2547//2547 2546//2546 -f 2546//2546 2550//2550 2551//2551 -f 2552//2552 2550//2550 2546//2546 -f 2548//2548 2552//2552 2546//2546 -f 2546//2546 2553//2553 2554//2554 -f 2555//2555 2553//2553 2546//2546 -f 2551//2551 2555//2555 2546//2546 -f 2546//2546 2556//2556 2557//2557 -f 2558//2558 2556//2556 2546//2546 -f 2554//2554 2558//2558 2546//2546 -f 2557//2557 2549//2549 2546//2546 -f 2549//2549 2559//2559 2547//2547 -f 2547//2547 2559//2559 2560//2560 -f 2547//2547 2560//2560 2548//2548 -f 2548//2548 2560//2560 2561//2561 -f 2548//2548 2561//2561 2552//2552 -f 2552//2552 2561//2561 2562//2562 -f 2552//2552 2562//2562 2550//2550 -f 2550//2550 2562//2562 2563//2563 -f 2550//2550 2563//2563 2551//2551 -f 2551//2551 2563//2563 2564//2564 -f 2551//2551 2564//2564 2555//2555 -f 2555//2555 2564//2564 2565//2565 -f 2555//2555 2565//2565 2553//2553 -f 2553//2553 2565//2565 2566//2566 -f 2553//2553 2566//2566 2554//2554 -f 2554//2554 2566//2566 2567//2567 -f 2554//2554 2567//2567 2558//2558 -f 2558//2558 2567//2567 2568//2568 -f 2558//2558 2568//2568 2556//2556 -f 2556//2556 2568//2568 2569//2569 -f 2556//2556 2569//2569 2557//2557 -f 2557//2557 2569//2569 2570//2570 -f 2557//2557 2570//2570 2549//2549 -f 2549//2549 2570//2570 2559//2559 -f 2560//2560 1852//1852 2561//2561 -f 2561//2561 1852//1852 1851//1851 -f 2561//2561 1851//1851 2562//2562 -f 2562//2562 1851//1851 1850//1850 -f 2562//2562 1850//1850 2563//2563 -f 2563//2563 1850//1850 1849//1849 -f 2563//2563 1849//1849 2564//2564 -f 2564//2564 1849//1849 1863//1863 -f 2564//2564 1863//1863 2565//2565 -f 2565//2565 1863//1863 1862//1862 -f 2565//2565 1862//1862 2566//2566 -f 2566//2566 1862//1862 1860//1860 -f 2566//2566 1860//1860 2567//2567 -f 2567//2567 1860//1860 1858//1858 -f 2567//2567 1858//1858 2568//2568 -f 2568//2568 1858//1858 1857//1857 -f 2568//2568 1857//1857 2569//2569 -f 2569//2569 1857//1857 1856//1856 -f 2569//2569 1856//1856 2570//2570 -f 2570//2570 1856//1856 1854//1854 -f 2570//2570 1854//1854 2559//2559 -f 2559//2559 1854//1854 1853//1853 -f 2559//2559 1853//1853 2560//2560 -f 2560//2560 1853//1853 1852//1852 -f 2571//2571 2572//2572 2573//2573 -f 2574//2574 2572//2572 2571//2571 -f 2571//2571 2575//2575 2576//2576 -f 2577//2577 2575//2575 2571//2571 -f 2573//2573 2577//2577 2571//2571 -f 2571//2571 2578//2578 2579//2579 -f 2580//2580 2578//2578 2571//2571 -f 2576//2576 2580//2580 2571//2571 -f 2571//2571 2581//2581 2582//2582 -f 2583//2583 2581//2581 2571//2571 -f 2579//2579 2583//2583 2571//2571 -f 2582//2582 2574//2574 2571//2571 -f 2574//2574 2584//2584 2572//2572 -f 2572//2572 2584//2584 2585//2585 -f 2572//2572 2585//2585 2573//2573 -f 2573//2573 2585//2585 2586//2586 -f 2573//2573 2586//2586 2577//2577 -f 2577//2577 2586//2586 2587//2587 -f 2577//2577 2587//2587 2575//2575 -f 2575//2575 2587//2587 2588//2588 -f 2575//2575 2588//2588 2576//2576 -f 2576//2576 2588//2588 2589//2589 -f 2576//2576 2589//2589 2580//2580 -f 2580//2580 2589//2589 2590//2590 -f 2580//2580 2590//2590 2578//2578 -f 2578//2578 2590//2590 2591//2591 -f 2578//2578 2591//2591 2579//2579 -f 2579//2579 2591//2591 2592//2592 -f 2579//2579 2592//2592 2583//2583 -f 2583//2583 2592//2592 2593//2593 -f 2583//2583 2593//2593 2581//2581 -f 2581//2581 2593//2593 2594//2594 -f 2581//2581 2594//2594 2582//2582 -f 2582//2582 2594//2594 2595//2595 -f 2582//2582 2595//2595 2574//2574 -f 2574//2574 2595//2595 2584//2584 -f 2585//2585 1922//1922 2586//2586 -f 2586//2586 1922//1922 1928//1928 -f 2586//2586 1928//1928 2587//2587 -f 2587//2587 1928//1928 1927//1927 -f 2587//2587 1927//1927 2588//2588 -f 2588//2588 1927//1927 1926//1926 -f 2588//2588 1926//1926 2589//2589 -f 2589//2589 1926//1926 1918//1918 -f 2589//2589 1918//1918 2590//2590 -f 2590//2590 1918//1918 1920//1920 -f 2590//2590 1920//1920 2591//2591 -f 2591//2591 1920//1920 1763//1763 -f 2591//2591 1763//1763 2592//2592 -f 2592//2592 1763//1763 1764//1764 -f 2592//2592 1764//1764 2593//2593 -f 2593//2593 1764//1764 1765//1765 -f 2593//2593 1765//1765 2594//2594 -f 2594//2594 1765//1765 1760//1760 -f 2594//2594 1760//1760 2595//2595 -f 2595//2595 1760//1760 1756//1756 -f 2595//2595 1756//1756 2584//2584 -f 2584//2584 1756//1756 1925//1925 -f 2584//2584 1925//1925 2585//2585 -f 2585//2585 1925//1925 1922//1922 -f 2596//2596 2597//2597 2598//2598 -f 2599//2599 2597//2597 2596//2596 -f 2596//2596 2600//2600 2601//2601 -f 2602//2602 2600//2600 2596//2596 -f 2598//2598 2602//2602 2596//2596 -f 2596//2596 2603//2603 2604//2604 -f 2605//2605 2603//2603 2596//2596 -f 2601//2601 2605//2605 2596//2596 -f 2596//2596 2606//2606 2607//2607 -f 2608//2608 2606//2606 2596//2596 -f 2604//2604 2608//2608 2596//2596 -f 2607//2607 2599//2599 2596//2596 -f 2599//2599 2609//2609 2597//2597 -f 2597//2597 2609//2609 2610//2610 -f 2597//2597 2610//2610 2598//2598 -f 2598//2598 2610//2610 2611//2611 -f 2598//2598 2611//2611 2602//2602 -f 2602//2602 2611//2611 2612//2612 -f 2602//2602 2612//2612 2600//2600 -f 2600//2600 2612//2612 2613//2613 -f 2600//2600 2613//2613 2601//2601 -f 2601//2601 2613//2613 2614//2614 -f 2601//2601 2614//2614 2605//2605 -f 2605//2605 2614//2614 2615//2615 -f 2605//2605 2615//2615 2603//2603 -f 2603//2603 2615//2615 2616//2616 -f 2603//2603 2616//2616 2604//2604 -f 2604//2604 2616//2616 2617//2617 -f 2604//2604 2617//2617 2608//2608 -f 2608//2608 2617//2617 2618//2618 -f 2608//2608 2618//2618 2606//2606 -f 2606//2606 2618//2618 2619//2619 -f 2606//2606 2619//2619 2607//2607 -f 2607//2607 2619//2619 2620//2620 -f 2607//2607 2620//2620 2599//2599 -f 2599//2599 2620//2620 2609//2609 -f 2610//2610 1808//1808 2611//2611 -f 2611//2611 1808//1808 1807//1807 -f 2611//2611 1807//1807 2612//2612 -f 2612//2612 1807//1807 1798//1798 -f 2612//2612 1798//1798 2613//2613 -f 2613//2613 1798//1798 1797//1797 -f 2613//2613 1797//1797 2614//2614 -f 2614//2614 1797//1797 1795//1795 -f 2614//2614 1795//1795 2615//2615 -f 2615//2615 1795//1795 1794//1794 -f 2615//2615 1794//1794 2616//2616 -f 2616//2616 1794//1794 1803//1803 -f 2616//2616 1803//1803 2617//2617 -f 2617//2617 1803//1803 1802//1802 -f 2617//2617 1802//1802 2618//2618 -f 2618//2618 1802//1802 1801//1801 -f 2618//2618 1801//1801 2619//2619 -f 2619//2619 1801//1801 1800//1800 -f 2619//2619 1800//1800 2620//2620 -f 2620//2620 1800//1800 1799//1799 -f 2620//2620 1799//1799 2609//2609 -f 2609//2609 1799//1799 1809//1809 -f 2609//2609 1809//1809 2610//2610 -f 2610//2610 1809//1809 1808//1808 -f 1934//1934 2621//2621 1936//1936 -f 1936//1936 2621//2621 2622//2622 -f 1936//1936 2622//2622 1937//1937 -f 1937//1937 2622//2622 2623//2623 -f 1937//1937 2623//2623 1938//1938 -f 1938//1938 2623//2623 2624//2624 -f 1938//1938 2624//2624 1939//1939 -f 1939//1939 2624//2624 2625//2625 -f 1939//1939 2625//2625 1941//1941 -f 1941//1941 2625//2625 2626//2626 -f 1941//1941 2626//2626 1943//1943 -f 1943//1943 2626//2626 2627//2627 -f 1943//1943 2627//2627 1945//1945 -f 1945//1945 2627//2627 2628//2628 -f 1945//1945 2628//2628 1946//1946 -f 1946//1946 2628//2628 2629//2629 -f 1946//1946 2629//2629 1929//1929 -f 1929//1929 2629//2629 2630//2630 -f 1929//1929 2630//2630 1930//1930 -f 1930//1930 2630//2630 2631//2631 -f 1930//1930 2631//2631 1932//1932 -f 1932//1932 2631//2631 2632//2632 -f 1932//1932 2632//2632 1934//1934 -f 1934//1934 2632//2632 2621//2621 -f 2622//2622 2512//2512 2623//2623 -f 2623//2623 2512//2512 2520//2520 -f 2623//2623 2520//2520 2624//2624 -f 2624//2624 2520//2520 2518//2518 -f 2624//2624 2518//2518 2625//2625 -f 2625//2625 2518//2518 2519//2519 -f 2625//2625 2519//2519 2626//2626 -f 2626//2626 2519//2519 2515//2515 -f 2626//2626 2515//2515 2627//2627 -f 2627//2627 2515//2515 2516//2516 -f 2627//2627 2516//2516 2628//2628 -f 2628//2628 2516//2516 2517//2517 -f 2628//2628 2517//2517 2629//2629 -f 2629//2629 2517//2517 2513//2513 -f 2629//2629 2513//2513 2630//2630 -f 2630//2630 2513//2513 2514//2514 -f 2630//2630 2514//2514 2631//2631 -f 2631//2631 2514//2514 2509//2509 -f 2631//2631 2509//2509 2632//2632 -f 2632//2632 2509//2509 2510//2510 -f 2632//2632 2510//2510 2621//2621 -f 2621//2621 2510//2510 2511//2511 -f 2621//2621 2511//2511 2622//2622 -f 2622//2622 2511//2511 2512//2512 -f 1951//1951 2633//2633 1952//1952 -f 1952//1952 2633//2633 2634//2634 -f 1952//1952 2634//2634 2042//2042 -f 2042//2042 2634//2634 2635//2635 -f 2042//2042 2635//2635 1953//1953 -f 1953//1953 2635//2635 2636//2636 -f 1953//1953 2636//2636 1954//1954 -f 1954//1954 2636//2636 2637//2637 -f 1954//1954 2637//2637 1956//1956 -f 1956//1956 2637//2637 2638//2638 -f 1956//1956 2638//2638 1958//1958 -f 1958//1958 2638//2638 2639//2639 -f 1958//1958 2639//2639 1959//1959 -f 1959//1959 2639//2639 2640//2640 -f 1959//1959 2640//2640 2050//2050 -f 2050//2050 2640//2640 2641//2641 -f 2050//2050 2641//2641 1947//1947 -f 1947//1947 2641//2641 2642//2642 -f 1947//1947 2642//2642 1948//1948 -f 1948//1948 2642//2642 2643//2643 -f 1948//1948 2643//2643 1950//1950 -f 1950//1950 2643//2643 2644//2644 -f 1950//1950 2644//2644 1951//1951 -f 1951//1951 2644//2644 2633//2633 -f 2634//2634 1513//1513 2635//2635 -f 2635//2635 1513//1513 1236//1236 -f 2635//2635 1236//1236 2636//2636 -f 2636//2636 1236//1236 1238//1238 -f 2636//2636 1238//1238 2637//2637 -f 2637//2637 1238//1238 1240//1240 -f 2637//2637 1240//1240 2638//2638 -f 2638//2638 1240//1240 1249//1249 -f 2638//2638 1249//1249 2639//2639 -f 2639//2639 1249//1249 1251//1251 -f 2639//2639 1251//1251 2640//2640 -f 2640//2640 1251//1251 1253//1253 -f 2640//2640 1253//1253 2641//2641 -f 2641//2641 1253//1253 1248//1248 -f 2641//2641 1248//1248 2642//2642 -f 2642//2642 1248//1248 1247//1247 -f 2642//2642 1247//1247 2643//2643 -f 2643//2643 1247//1247 1245//1245 -f 2643//2643 1245//1245 2644//2644 -f 2644//2644 1245//1245 1244//1244 -f 2644//2644 1244//1244 2633//2633 -f 2633//2633 1244//1244 1243//1243 -f 2633//2633 1243//1243 2634//2634 -f 2634//2634 1243//1243 1513//1513 -f 1970//1970 2645//2645 1971//1971 -f 1971//1971 2645//2645 2646//2646 -f 1971//1971 2646//2646 1972//1972 -f 1972//1972 2646//2646 2647//2647 -f 1972//1972 2647//2647 1975//1975 -f 1975//1975 2647//2647 2648//2648 -f 1975//1975 2648//2648 1973//1973 -f 1973//1973 2648//2648 2649//2649 -f 1973//1973 2649//2649 1964//1964 -f 1964//1964 2649//2649 2650//2650 -f 1964//1964 2650//2650 1962//1962 -f 1962//1962 2650//2650 2651//2651 -f 1962//1962 2651//2651 1960//1960 -f 1960//1960 2651//2651 2652//2652 -f 1960//1960 2652//2652 1967//1967 -f 1967//1967 2652//2652 2653//2653 -f 1967//1967 2653//2653 1968//1968 -f 1968//1968 2653//2653 2654//2654 -f 1968//1968 2654//2654 1969//1969 -f 1969//1969 2654//2654 2655//2655 -f 1969//1969 2655//2655 1965//1965 -f 1965//1965 2655//2655 2656//2656 -f 1965//1965 2656//2656 1970//1970 -f 1970//1970 2656//2656 2645//2645 -f 2646//2646 1543//1543 2647//2647 -f 2647//2647 1543//1543 1542//1542 -f 2647//2647 1542//1542 2648//2648 -f 2648//2648 1542//1542 1547//1547 -f 2648//2648 1547//1547 2649//2649 -f 2649//2649 1547//1547 1546//1546 -f 2649//2649 1546//1546 2650//2650 -f 2650//2650 1546//1546 1545//1545 -f 2650//2650 1545//1545 2651//2651 -f 2651//2651 1545//1545 1544//1544 -f 2651//2651 1544//1544 2652//2652 -f 2652//2652 1544//1544 1552//1552 -f 2652//2652 1552//1552 2653//2653 -f 2653//2653 1552//1552 1551//1551 -f 2653//2653 1551//1551 2654//2654 -f 2654//2654 1551//1551 1549//1549 -f 2654//2654 1549//1549 2655//2655 -f 2655//2655 1549//1549 1548//1548 -f 2655//2655 1548//1548 2656//2656 -f 2656//2656 1548//1548 1541//1541 -f 2656//2656 1541//1541 2645//2645 -f 2645//2645 1541//1541 1540//1540 -f 2645//2645 1540//1540 2646//2646 -f 2646//2646 1540//1540 1543//1543 -f 1983//1983 2657//2657 1984//1984 -f 1984//1984 2657//2657 2658//2658 -f 1984//1984 2658//2658 1986//1986 -f 1986//1986 2658//2658 2659//2659 -f 1986//1986 2659//2659 1987//1987 -f 1987//1987 2659//2659 2660//2660 -f 1987//1987 2660//2660 1988//1988 -f 1988//1988 2660//2660 2661//2661 -f 1988//1988 2661//2661 1989//1989 -f 1989//1989 2661//2661 2662//2662 -f 1989//1989 2662//2662 1982//1982 -f 1982//1982 2662//2662 2663//2663 -f 1982//1982 2663//2663 1976//1976 -f 1976//1976 2663//2663 2664//2664 -f 1976//1976 2664//2664 1977//1977 -f 1977//1977 2664//2664 2665//2665 -f 1977//1977 2665//2665 1978//1978 -f 1978//1978 2665//2665 2666//2666 -f 1978//1978 2666//2666 1979//1979 -f 1979//1979 2666//2666 2667//2667 -f 1979//1979 2667//2667 1980//1980 -f 1980//1980 2667//2667 2668//2668 -f 1980//1980 2668//2668 1983//1983 -f 1983//1983 2668//2668 2657//2657 -f 2658//2658 1608//1608 2659//2659 -f 2659//2659 1608//1608 1609//1609 -f 2659//2659 1609//1609 2660//2660 -f 2660//2660 1609//1609 1607//1607 -f 2660//2660 1607//1607 2661//2661 -f 2661//2661 1607//1607 1606//1606 -f 2661//2661 1606//1606 2662//2662 -f 2662//2662 1606//1606 1605//1605 -f 2662//2662 1605//1605 2663//2663 -f 2663//2663 1605//1605 1598//1598 -f 2663//2663 1598//1598 2664//2664 -f 2664//2664 1598//1598 1597//1597 -f 2664//2664 1597//1597 2665//2665 -f 2665//2665 1597//1597 1601//1601 -f 2665//2665 1601//1601 2666//2666 -f 2666//2666 1601//1601 1600//1600 -f 2666//2666 1600//1600 2667//2667 -f 2667//2667 1600//1600 1599//1599 -f 2667//2667 1599//1599 2668//2668 -f 2668//2668 1599//1599 1596//1596 -f 2668//2668 1596//1596 2657//2657 -f 2657//2657 1596//1596 1595//1595 -f 2657//2657 1595//1595 2658//2658 -f 2658//2658 1595//1595 1608//1608 -f 1994//1994 2669//2669 1995//1995 -f 1995//1995 2669//2669 2670//2670 -f 1995//1995 2670//2670 2034//2034 -f 2034//2034 2670//2670 2671//2671 -f 2034//2034 2671//2671 1996//1996 -f 1996//1996 2671//2671 2672//2672 -f 1996//1996 2672//2672 1997//1997 -f 1997//1997 2672//2672 2673//2673 -f 1997//1997 2673//2673 1999//1999 -f 1999//1999 2673//2673 2674//2674 -f 1999//1999 2674//2674 2000//2000 -f 2000//2000 2674//2674 2675//2675 -f 2000//2000 2675//2675 2002//2002 -f 2002//2002 2675//2675 2676//2676 -f 2002//2002 2676//2676 2037//2037 -f 2037//2037 2676//2676 2677//2677 -f 2037//2037 2677//2677 1990//1990 -f 1990//1990 2677//2677 2678//2678 -f 1990//1990 2678//2678 1991//1991 -f 1991//1991 2678//2678 2679//2679 -f 1991//1991 2679//2679 1992//1992 -f 1992//1992 2679//2679 2680//2680 -f 1992//1992 2680//2680 1994//1994 -f 1994//1994 2680//2680 2669//2669 -f 2670//2670 1422//1422 2671//2671 -f 2671//2671 1422//1422 1424//1424 -f 2671//2671 1424//1424 2672//2672 -f 2672//2672 1424//1424 1425//1425 -f 2672//2672 1425//1425 2673//2673 -f 2673//2673 1425//1425 1428//1428 -f 2673//2673 1428//1428 2674//2674 -f 2674//2674 1428//1428 1533//1533 -f 2674//2674 1533//1533 2675//2675 -f 2675//2675 1533//1533 1535//1535 -f 2675//2675 1535//1535 2676//2676 -f 2676//2676 1535//1535 1537//1537 -f 2676//2676 1537//1537 2677//2677 -f 2677//2677 1537//1537 1538//1538 -f 2677//2677 1538//1538 2678//2678 -f 2678//2678 1538//1538 1522//1522 -f 2678//2678 1522//1522 2679//2679 -f 2679//2679 1522//1522 1521//1521 -f 2679//2679 1521//1521 2680//2680 -f 2680//2680 1521//1521 1530//1530 -f 2680//2680 1530//1530 2669//2669 -f 2669//2669 1530//1530 1420//1420 -f 2669//2669 1420//1420 2670//2670 -f 2670//2670 1420//1420 1422//1422 -f 2008//2008 2681//2681 2003//2003 -f 2003//2003 2681//2681 2682//2682 -f 2003//2003 2682//2682 2004//2004 -f 2004//2004 2682//2682 2683//2683 -f 2004//2004 2683//2683 2005//2005 -f 2005//2005 2683//2683 2684//2684 -f 2005//2005 2684//2684 2006//2006 -f 2006//2006 2684//2684 2685//2685 -f 2006//2006 2685//2685 2007//2007 -f 2007//2007 2685//2685 2686//2686 -f 2007//2007 2686//2686 2011//2011 -f 2011//2011 2686//2686 2687//2687 -f 2011//2011 2687//2687 2012//2012 -f 2012//2012 2687//2687 2688//2688 -f 2012//2012 2688//2688 2013//2013 -f 2013//2013 2688//2688 2689//2689 -f 2013//2013 2689//2689 2016//2016 -f 2016//2016 2689//2689 2690//2690 -f 2016//2016 2690//2690 2014//2014 -f 2014//2014 2690//2690 2691//2691 -f 2014//2014 2691//2691 2010//2010 -f 2010//2010 2691//2691 2692//2692 -f 2010//2010 2692//2692 2008//2008 -f 2008//2008 2692//2692 2681//2681 -f 2682//2682 1617//1617 2683//2683 -f 2683//2683 1617//1617 1627//1627 -f 2683//2683 1627//1627 2684//2684 -f 2684//2684 1627//1627 1626//1626 -f 2684//2684 1626//1626 2685//2685 -f 2685//2685 1626//1626 1625//1625 -f 2685//2685 1625//1625 2686//2686 -f 2686//2686 1625//1625 1624//1624 -f 2686//2686 1624//1624 2687//2687 -f 2687//2687 1624//1624 1623//1623 -f 2687//2687 1623//1623 2688//2688 -f 2688//2688 1623//1623 1622//1622 -f 2688//2688 1622//1622 2689//2689 -f 2689//2689 1622//1622 1619//1619 -f 2689//2689 1619//1619 2690//2690 -f 2690//2690 1619//1619 1620//1620 -f 2690//2690 1620//1620 2691//2691 -f 2691//2691 1620//1620 1621//1621 -f 2691//2691 1621//1621 2692//2692 -f 2692//2692 1621//1621 1616//1616 -f 2692//2692 1616//1616 2681//2681 -f 2681//2681 1616//1616 1615//1615 -f 2681//2681 1615//1615 2682//2682 -f 2682//2682 1615//1615 1617//1617 -f 2017//2017 2693//2693 2018//2018 -f 2018//2018 2693//2693 2694//2694 -f 2018//2018 2694//2694 2019//2019 -f 2019//2019 2694//2694 2695//2695 -f 2019//2019 2695//2695 2022//2022 -f 2022//2022 2695//2695 2696//2696 -f 2022//2022 2696//2696 2023//2023 -f 2023//2023 2696//2696 2697//2697 -f 2023//2023 2697//2697 2024//2024 -f 2024//2024 2697//2697 2698//2698 -f 2024//2024 2698//2698 2029//2029 -f 2029//2029 2698//2698 2699//2699 -f 2029//2029 2699//2699 2030//2030 -f 2030//2030 2699//2699 2700//2700 -f 2030//2030 2700//2700 2032//2032 -f 2032//2032 2700//2700 2701//2701 -f 2032//2032 2701//2701 2028//2028 -f 2028//2028 2701//2701 2702//2702 -f 2028//2028 2702//2702 2027//2027 -f 2027//2027 2702//2702 2703//2703 -f 2027//2027 2703//2703 2020//2020 -f 2020//2020 2703//2703 2704//2704 -f 2020//2020 2704//2704 2017//2017 -f 2017//2017 2704//2704 2693//2693 -f 2694//2694 1561//1561 2695//2695 -f 2695//2695 1561//1561 1560//1560 -f 2695//2695 1560//1560 2696//2696 -f 2696//2696 1560//1560 1558//1558 -f 2696//2696 1558//1558 2697//2697 -f 2697//2697 1558//1558 1565//1565 -f 2697//2697 1565//1565 2698//2698 -f 2698//2698 1565//1565 1564//1564 -f 2698//2698 1564//1564 2699//2699 -f 2699//2699 1564//1564 1569//1569 -f 2699//2699 1569//1569 2700//2700 -f 2700//2700 1569//1569 1568//1568 -f 2700//2700 1568//1568 2701//2701 -f 2701//2701 1568//1568 1567//1567 -f 2701//2701 1567//1567 2702//2702 -f 2702//2702 1567//1567 1566//1566 -f 2702//2702 1566//1566 2703//2703 -f 2703//2703 1566//1566 1554//1554 -f 2703//2703 1554//1554 2704//2704 -f 2704//2704 1554//1554 1553//1553 -f 2704//2704 1553//1553 2693//2693 -f 2693//2693 1553//1553 1556//1556 -f 2693//2693 1556//1556 2694//2694 -f 2694//2694 1556//1556 1561//1561 -f 2160//2160 2159//2159 2162//2162 -f 2160//2160 2162//2162 2705//2705 -f 2705//2705 2162//2162 2163//2163 -f 2705//2705 2163//2163 2706//2706 -f 2706//2706 2163//2163 1228//1228 -f 2706//2706 1228//1228 1227//1227 -f 1254//1254 2707//2707 2708//2708 -f 2707//2707 2709//2709 2710//2710 -f 2709//2709 2158//2158 2365//2365 -f 2709//2709 2365//2365 2710//2710 -f 2710//2710 2365//2365 2366//2366 -f 2710//2710 2366//2366 2711//2711 -f 2711//2711 2366//2366 2367//2367 -f 2711//2711 2367//2367 2712//2712 -f 2712//2712 2367//2367 2368//2368 -f 2712//2712 2368//2368 2713//2713 -f 2713//2713 2368//2368 2369//2369 -f 2713//2713 2369//2369 2714//2714 -f 2714//2714 2369//2369 2370//2370 -f 2714//2714 2370//2370 2715//2715 -f 2715//2715 2370//2370 2371//2371 -f 2715//2715 2371//2371 2716//2716 -f 2716//2716 2371//2371 2372//2372 -f 2716//2716 2372//2372 2717//2717 -f 2717//2717 2372//2372 2373//2373 -f 2717//2717 2373//2373 2718//2718 -f 2718//2718 2373//2373 2160//2160 -f 2718//2718 2160//2160 2705//2705 -f 2707//2707 2710//2710 2708//2708 -f 2708//2708 2710//2710 2711//2711 -f 2708//2708 2711//2711 2719//2719 -f 2719//2719 2711//2711 2712//2712 -f 2719//2719 2712//2712 2720//2720 -f 2720//2720 2712//2712 2713//2713 -f 2720//2720 2713//2713 2721//2721 -f 2721//2721 2713//2713 2714//2714 -f 2721//2721 2714//2714 2722//2722 -f 2722//2722 2714//2714 2715//2715 -f 2722//2722 2715//2715 2723//2723 -f 2723//2723 2715//2715 2716//2716 -f 2723//2723 2716//2716 2724//2724 -f 2724//2724 2716//2716 2717//2717 -f 2724//2724 2717//2717 2725//2725 -f 2725//2725 2717//2717 2718//2718 -f 2725//2725 2718//2718 2726//2726 -f 2726//2726 2718//2718 2705//2705 -f 2726//2726 2705//2705 2706//2706 -f 1254//1254 2708//2708 1255//1255 -f 1255//1255 2708//2708 2719//2719 -f 1255//1255 2719//2719 1246//1246 -f 1246//1246 2719//2719 2720//2720 -f 1246//1246 2720//2720 1413//1413 -f 1413//1413 2720//2720 2721//2721 -f 1413//1413 2721//2721 1414//1414 -f 1414//1414 2721//2721 2722//2722 -f 1414//1414 2722//2722 1417//1417 -f 1417//1417 2722//2722 2723//2723 -f 1417//1417 2723//2723 1418//1418 -f 1418//1418 2723//2723 2724//2724 -f 1418//1418 2724//2724 1419//1419 -f 1419//1419 2724//2724 2725//2725 -f 1419//1419 2725//2725 1416//1416 -f 1416//1416 2725//2725 2726//2726 -f 1416//1416 2726//2726 1415//1415 -f 1415//1415 2726//2726 2706//2706 -f 1415//1415 2706//2706 1227//1227 -f 1536//1536 1534//1534 2727//2727 -f 2157//2157 2158//2158 2709//2709 -f 2157//2157 2709//2709 2728//2728 -f 2728//2728 2709//2709 2707//2707 -f 2728//2728 2707//2707 2727//2727 -f 1254//1254 1252//1252 2707//2707 -f 2707//2707 1252//1252 1250//1250 -f 2707//2707 1250//1250 2727//2727 -f 2727//2727 1250//1250 1524//1524 -f 2727//2727 1524//1524 1536//1536 -f 1431//1431 2729//2729 2730//2730 -f 2729//2729 2731//2731 2732//2732 -f 2731//2731 2156//2156 2374//2374 -f 2731//2731 2374//2374 2732//2732 -f 2732//2732 2374//2374 2375//2375 -f 2732//2732 2375//2375 2733//2733 -f 2733//2733 2375//2375 2376//2376 -f 2733//2733 2376//2376 2734//2734 -f 2734//2734 2376//2376 2377//2377 -f 2734//2734 2377//2377 2735//2735 -f 2735//2735 2377//2377 2378//2378 -f 2735//2735 2378//2378 2736//2736 -f 2736//2736 2378//2378 2379//2379 -f 2736//2736 2379//2379 2737//2737 -f 2737//2737 2379//2379 2380//2380 -f 2737//2737 2380//2380 2738//2738 -f 2738//2738 2380//2380 2381//2381 -f 2738//2738 2381//2381 2739//2739 -f 2739//2739 2381//2381 2382//2382 -f 2739//2739 2382//2382 2740//2740 -f 2740//2740 2382//2382 2157//2157 -f 2740//2740 2157//2157 2728//2728 -f 2729//2729 2732//2732 2730//2730 -f 2730//2730 2732//2732 2733//2733 -f 2730//2730 2733//2733 2741//2741 -f 2741//2741 2733//2733 2734//2734 -f 2741//2741 2734//2734 2742//2742 -f 2742//2742 2734//2734 2735//2735 -f 2742//2742 2735//2735 2743//2743 -f 2743//2743 2735//2735 2736//2736 -f 2743//2743 2736//2736 2744//2744 -f 2744//2744 2736//2736 2737//2737 -f 2744//2744 2737//2737 2745//2745 -f 2745//2745 2737//2737 2738//2738 -f 2745//2745 2738//2738 2746//2746 -f 2746//2746 2738//2738 2739//2739 -f 2746//2746 2739//2739 2747//2747 -f 2747//2747 2739//2739 2740//2740 -f 2747//2747 2740//2740 2748//2748 -f 2748//2748 2740//2740 2728//2728 -f 2748//2748 2728//2728 2727//2727 -f 1431//1431 2730//2730 1432//1432 -f 1432//1432 2730//2730 2741//2741 -f 1432//1432 2741//2741 1433//1433 -f 1433//1433 2741//2741 2742//2742 -f 1433//1433 2742//2742 1641//1641 -f 1641//1641 2742//2742 2743//2743 -f 1641//1641 2743//2743 1426//1426 -f 1426//1426 2743//2743 2744//2744 -f 1426//1426 2744//2744 1427//1427 -f 1427//1427 2744//2744 2745//2745 -f 1427//1427 2745//2745 1430//1430 -f 1430//1430 2745//2745 2746//2746 -f 1430//1430 2746//2746 1429//1429 -f 1429//1429 2746//2746 2747//2747 -f 1429//1429 2747//2747 1531//1531 -f 1531//1531 2747//2747 2748//2748 -f 1531//1531 2748//2748 1532//1532 -f 1532//1532 2748//2748 2727//2727 -f 1532//1532 2727//2727 1534//1534 -f 2155//2155 2156//2156 2731//2731 -f 2155//2155 2731//2731 2230//2230 -f 2230//2230 2731//2731 2729//2729 -f 2230//2230 2729//2729 2229//2229 -f 2229//2229 2729//2729 1431//1431 -f 2229//2229 1431//1431 1437//1437 -f 2224//2224 1434//1434 1322//1322 -f 2224//2224 1322//1322 2219//2219 -f 2219//2219 1322//1322 1329//1329 -f 2219//2219 1329//1329 1331//1331 -f 2214//2214 1313//1313 1312//1312 -f 2214//2214 1312//1312 2209//2209 -f 2209//2209 1312//1312 1223//1223 -f 2209//2209 1223//1223 1378//1378 -f 2204//2204 1340//1340 2199//2199 -f 2199//2199 1340//1340 1346//1346 -f 2199//2199 1346//1346 1348//1348 -f 2189//2189 2194//2194 1653//1653 -f 1653//1653 1659//1659 2189//2189 -f 2189//2189 1659//1659 1235//1235 -f 2189//2189 1235//1235 1234//1234 -f 1382//1382 1381//1381 2182//2182 -f 2182//2182 1381//1381 1630//1630 -f 2182//2182 1630//1630 2177//2177 -f 2177//2177 1630//1630 1387//1387 -f 2177//2177 1387//1387 1386//1386 -f 1306//1306 1398//1398 2152//2152 -f 2151//2151 1392//1392 1299//1299 -f 2151//2151 1299//1299 2152//2152 -f 2152//2152 1299//1299 1303//1303 -f 2152//2152 1303//1303 1306//1306 -f 1580//1580 2139//2139 1579//1579 -f 1579//1579 2139//2139 2138//2138 -f 1579//1579 2138//2138 1578//1578 -f 1578//1578 2138//2138 1577//1577 -f 1576//1576 2092//2092 1575//1575 -f 1575//1575 2092//2092 2091//2091 -f 1575//1575 2091//2091 1574//1574 -f 1406//1406 1411//1411 2086//2086 -f 1406//1406 2086//2086 1405//1405 -f 1405//1405 2086//2086 2085//2085 -f 1405//1405 2085//2085 1404//1404 -f 2079//2079 1570//1570 1571//1571 -f 2079//2079 1571//1571 2080//2080 -f 2080//2080 1571//1571 1572//1572 -f 2080//2080 1572//1572 1573//1573 -f 1726//1726 2081//2081 1727//1727 -f 1727//1727 2081//2081 2082//2082 -f 1736//1736 2078//2078 1737//1737 -f 1737//1737 2078//2078 2077//2077 -f 1737//1737 2077//2077 1734//1734 -f 1739//1739 2087//2087 1740//1740 -f 1740//1740 2087//2087 2088//2088 -f 1724//1724 2084//2084 1725//1725 -f 1725//1725 2084//2084 2083//2083 -f 1745//1745 2093//2093 1746//1746 -f 1746//1746 2093//2093 2094//2094 -f 2055//2055 2090//2090 2054//2054 -f 2054//2054 2090//2090 2089//2089 -f 1923//1923 2140//2140 1924//1924 -f 1924//1924 2140//2140 2141//2141 -f 1762//1762 2137//2137 1761//1761 -f 1761//1761 2137//2137 2136//2136 -f 1845//1845 2222//2222 1844//1844 -f 1844//1844 2222//2222 2221//2221 -f 1841//1841 2226//2226 1830//1830 -f 1830//1830 2226//2226 2220//2220 -f 1830//1830 2220//2220 1831//1831 -f 1836//1836 2212//2212 1837//1837 -f 1837//1837 2212//2212 2211//2211 -f 1832//1832 2216//2216 1833//1833 -f 1833//1833 2216//2216 2210//2210 -f 1822//1822 2202//2202 1821//1821 -f 1821//1821 2202//2202 2201//2201 -f 1816//1816 2206//2206 1817//1817 -f 1817//1817 2206//2206 2200//2200 -f 1721//1721 2192//2192 1722//1722 -f 1722//1722 2192//2192 2191//2191 -f 1805//1805 2196//2196 1804//1804 -f 1804//1804 2196//2196 2190//2190 -f 2047//2047 2153//2153 1771//1771 -f 1771//1771 2153//2153 2154//2154 -f 1771//1771 2154//2154 1770//1770 -f 1772//1772 2150//2150 1773//1773 -f 1773//1773 2150//2150 2149//2149 -f 1785//1785 2184//2184 1784//1784 -f 1784//1784 2184//2184 2178//2178 -f 1790//1790 2180//2180 1788//1788 -f 1788//1788 2180//2180 2179//2179 -f 2228//2228 1436//1436 2227//2227 -f 2227//2227 1436//1436 1435//1435 -f 2218//2218 1317//1317 2217//2217 -f 2217//2217 1317//1317 1315//1315 -f 2208//2208 1379//1379 2207//2207 -f 2207//2207 1379//1379 1342//1342 -f 2198//2198 1337//1337 2197//2197 -f 2197//2197 1337//1337 1335//1335 -f 2188//2188 1233//1233 2187//2187 -f 2187//2187 1233//1233 1385//1385 -f 2186//2186 1385//1385 2185//2185 -f 2185//2185 1385//1385 1383//1383 -f 2164//2164 1230//1230 2161//2161 -f 2161//2161 1230//1230 1412//1412 -f 2166//2166 1408//1408 2165//2165 -f 2165//2165 1408//1408 1258//1258 -f 2168//2168 1283//1283 2167//2167 -f 2167//2167 1283//1283 1403//1403 -f 2170//2170 1439//1439 2169//2169 -f 2169//2169 1439//1439 1274//1274 -f 2174//2174 1399//1399 2173//2173 -f 2173//2173 1399//1399 1400//1400 -f 2172//2172 1400//1400 2171//2171 -f 2171//2171 1400//1400 1397//1397 -f 1393//1393 2175//2175 1394//1394 -f 1394//1394 2175//2175 2176//2176 -f 1394//1394 2176//2176 1389//1389 -f 1389//1389 2176//2176 1388//1388 -f 2388//2388 1493//1493 1562//1562 -f 1563//1563 1480//1480 2385//2385 -f 1563//1563 2385//2385 1562//1562 -f 1562//1562 2385//2385 2386//2386 -f 1562//1562 2386//2386 2388//2388 -f 1489//1489 2387//2387 1485//1485 -f 1485//1485 2387//2387 2383//2383 -f 1485//1485 2383//2383 1486//1486 -f 1486//1486 2383//2383 2384//2384 -f 1486//1486 2384//2384 1612//1612 -f 1503//1503 1501//1501 2394//2394 -f 1602//1602 1504//1504 2390//2390 -f 2390//2390 1504//1504 1503//1503 -f 2390//2390 1503//1503 2391//2391 -f 2391//2391 1503//1503 2394//2394 -f 2393//2393 1496//1496 2392//2392 -f 2392//2392 1496//1496 1495//1495 -f 2392//2392 1495//1495 2389//2389 -f 2389//2389 1495//1495 1225//1225 -f 2389//2389 1225//1225 1224//1224 -f 2387//2387 1489//1489 1488//1488 -f 2387//2387 1488//1488 2388//2388 -f 2388//2388 1488//1488 1491//1491 -f 2388//2388 1491//1491 1493//1493 -f 2389//2389 1224//1224 1604//1604 -f 2389//2389 1604//1604 2390//2390 -f 2390//2390 1604//1604 1603//1603 -f 2390//2390 1603//1603 1602//1602 -f 2234//2234 1361//1361 1360//1360 -f 2234//2234 1360//1360 2749//2749 -f 2749//2749 1360//1360 1359//1359 -f 2749//2749 1359//1359 2750//2750 -f 2750//2750 1359//1359 1365//1365 -f 2750//2750 1365//1365 2236//2236 -f 2242//2242 2240//2240 2751//2751 -f 2242//2242 2751//2751 2752//2752 -f 2752//2752 2751//2751 2753//2753 -f 2752//2752 2753//2753 2754//2754 -f 2754//2754 2753//2753 2233//2233 -f 2754//2754 2233//2233 2234//2234 -f 2231//2231 1357//1357 1356//1356 -f 2231//2231 1356//1356 2755//2755 -f 2755//2755 1356//1356 1667//1667 -f 2755//2755 1667//1667 2756//2756 -f 2756//2756 1667//1667 1363//1363 -f 2756//2756 1363//1363 2233//2233 -f 2236//2236 2757//2757 2758//2758 -f 2242//2242 2752//2752 2759//2759 -f 2757//2757 2760//2760 2758//2758 -f 2758//2758 2760//2760 2759//2759 -f 2758//2758 2759//2759 2761//2761 -f 2761//2761 2759//2759 2752//2752 -f 2761//2761 2752//2752 2754//2754 -f 2236//2236 2758//2758 2750//2750 -f 2750//2750 2758//2758 2761//2761 -f 2750//2750 2761//2761 2749//2749 -f 2749//2749 2761//2761 2754//2754 -f 2749//2749 2754//2754 2234//2234 -f 2760//2760 2242//2242 2759//2759 -f 2757//2757 2762//2762 2760//2760 -f 2760//2760 2762//2762 2242//2242 -f 2233//2233 2753//2753 2763//2763 -f 2240//2240 2764//2764 2765//2765 -f 2753//2753 2766//2766 2763//2763 -f 2763//2763 2766//2766 2765//2765 -f 2763//2763 2765//2765 2767//2767 -f 2767//2767 2765//2765 2764//2764 -f 2767//2767 2764//2764 2768//2768 -f 2233//2233 2763//2763 2756//2756 -f 2756//2756 2763//2763 2767//2767 -f 2756//2756 2767//2767 2755//2755 -f 2755//2755 2767//2767 2768//2768 -f 2755//2755 2768//2768 2231//2231 -f 2766//2766 2240//2240 2765//2765 -f 2753//2753 2751//2751 2766//2766 -f 2766//2766 2751//2751 2240//2240 -f 2235//2235 1373//1373 1371//1371 -f 2235//2235 1371//1371 2769//2769 -f 2769//2769 1371//1371 1370//1370 -f 2769//2769 1370//1370 2770//2770 -f 2770//2770 1370//1370 1368//1368 -f 2770//2770 1368//1368 2238//2238 -f 2241//2241 2242//2242 2762//2762 -f 2241//2241 2762//2762 2771//2771 -f 2771//2771 2762//2762 2757//2757 -f 2771//2771 2757//2757 2772//2772 -f 2772//2772 2757//2757 2236//2236 -f 2772//2772 2236//2236 2235//2235 -f 2240//2240 2239//2239 2773//2773 -f 2240//2240 2773//2773 2764//2764 -f 2764//2764 2773//2773 2774//2774 -f 2764//2764 2774//2774 2768//2768 -f 2768//2768 2774//2774 2232//2232 -f 2768//2768 2232//2232 2231//2231 -f 2237//2237 1472//1472 1470//1470 -f 2237//2237 1470//1470 2775//2775 -f 2775//2775 1470//1470 1391//1391 -f 2775//2775 1391//1391 2776//2776 -f 2776//2776 1391//1391 1377//1377 -f 2776//2776 1377//1377 2232//2232 -f 2238//2238 2777//2777 2778//2778 -f 2241//2241 2771//2771 2779//2779 -f 2777//2777 2780//2780 2778//2778 -f 2778//2778 2780//2780 2779//2779 -f 2778//2778 2779//2779 2781//2781 -f 2781//2781 2779//2779 2771//2771 -f 2781//2781 2771//2771 2772//2772 -f 2238//2238 2778//2778 2770//2770 -f 2770//2770 2778//2778 2781//2781 -f 2770//2770 2781//2781 2769//2769 -f 2769//2769 2781//2781 2772//2772 -f 2769//2769 2772//2772 2235//2235 -f 2780//2780 2241//2241 2779//2779 -f 2777//2777 2782//2782 2780//2780 -f 2780//2780 2782//2782 2241//2241 -f 2232//2232 2774//2774 2783//2783 -f 2239//2239 2784//2784 2785//2785 -f 2774//2774 2786//2786 2783//2783 -f 2783//2783 2786//2786 2785//2785 -f 2783//2783 2785//2785 2787//2787 -f 2787//2787 2785//2785 2784//2784 -f 2787//2787 2784//2784 2788//2788 -f 2232//2232 2783//2783 2776//2776 -f 2776//2776 2783//2783 2787//2787 -f 2776//2776 2787//2787 2775//2775 -f 2775//2775 2787//2787 2788//2788 -f 2775//2775 2788//2788 2237//2237 -f 2786//2786 2239//2239 2785//2785 -f 2774//2774 2773//2773 2786//2786 -f 2786//2786 2773//2773 2239//2239 -f 2239//2239 2241//2241 2782//2782 -f 2239//2239 2782//2782 2784//2784 -f 2784//2784 2782//2782 2777//2777 -f 2784//2784 2777//2777 2788//2788 -f 2788//2788 2777//2777 2238//2238 -f 2788//2788 2238//2238 2237//2237 -f 2246//2246 1464//1464 1463//1463 -f 2246//2246 1463//1463 2789//2789 -f 2789//2789 1463//1463 1462//1462 -f 2789//2789 1462//1462 2790//2790 -f 2790//2790 1462//1462 1461//1461 -f 2790//2790 1461//1461 2247//2247 -f 2245//2245 2246//2246 2791//2791 -f 2245//2245 2791//2791 2792//2792 -f 2792//2792 2791//2791 2793//2793 -f 2792//2792 2793//2793 2794//2794 -f 2794//2794 2793//2793 2254//2254 -f 2794//2794 2254//2254 2252//2252 -f 2243//2243 1447//1447 1449//1449 -f 2243//2243 1449//1449 2795//2795 -f 2795//2795 1449//1449 1458//1458 -f 2795//2795 1458//1458 2796//2796 -f 2796//2796 1458//1458 1460//1460 -f 2796//2796 1460//1460 2245//2245 -f 2247//2247 2797//2797 2798//2798 -f 2254//2254 2793//2793 2799//2799 -f 2797//2797 2800//2800 2798//2798 -f 2798//2798 2800//2800 2799//2799 -f 2798//2798 2799//2799 2801//2801 -f 2801//2801 2799//2799 2793//2793 -f 2801//2801 2793//2793 2791//2791 -f 2247//2247 2798//2798 2790//2790 -f 2790//2790 2798//2798 2801//2801 -f 2790//2790 2801//2801 2789//2789 -f 2789//2789 2801//2801 2791//2791 -f 2789//2789 2791//2791 2246//2246 -f 2800//2800 2254//2254 2799//2799 -f 2797//2797 2802//2802 2800//2800 -f 2800//2800 2802//2802 2254//2254 -f 2245//2245 2792//2792 2803//2803 -f 2252//2252 2804//2804 2805//2805 -f 2792//2792 2806//2806 2803//2803 -f 2803//2803 2806//2806 2805//2805 -f 2803//2803 2805//2805 2807//2807 -f 2807//2807 2805//2805 2804//2804 -f 2807//2807 2804//2804 2808//2808 -f 2245//2245 2803//2803 2796//2796 -f 2796//2796 2803//2803 2807//2807 -f 2796//2796 2807//2807 2795//2795 -f 2795//2795 2807//2807 2808//2808 -f 2795//2795 2808//2808 2243//2243 -f 2806//2806 2252//2252 2805//2805 -f 2792//2792 2794//2794 2806//2806 -f 2806//2806 2794//2794 2252//2252 -f 2248//2248 1466//1466 1471//1471 -f 2248//2248 1471//1471 2809//2809 -f 2809//2809 1471//1471 1479//1479 -f 2809//2809 1479//1479 2810//2810 -f 2810//2810 1479//1479 1478//1478 -f 2810//2810 1478//1478 2249//2249 -f 2247//2247 2248//2248 2811//2811 -f 2247//2247 2811//2811 2797//2797 -f 2797//2797 2811//2811 2812//2812 -f 2797//2797 2812//2812 2802//2802 -f 2802//2802 2812//2812 2253//2253 -f 2802//2802 2253//2253 2254//2254 -f 2244//2244 2243//2243 2808//2808 -f 2244//2244 2808//2808 2813//2813 -f 2813//2813 2808//2808 2804//2804 -f 2813//2813 2804//2804 2814//2814 -f 2814//2814 2804//2804 2252//2252 -f 2814//2814 2252//2252 2251//2251 -f 2250//2250 1473//1473 1277//1277 -f 2250//2250 1277//1277 2815//2815 -f 2815//2815 1277//1277 1276//1276 -f 2815//2815 1276//1276 2816//2816 -f 2816//2816 1276//1276 1444//1444 -f 2816//2816 1444//1444 2244//2244 -f 2249//2249 2817//2817 2818//2818 -f 2253//2253 2812//2812 2819//2819 -f 2817//2817 2820//2820 2818//2818 -f 2818//2818 2820//2820 2819//2819 -f 2818//2818 2819//2819 2821//2821 -f 2821//2821 2819//2819 2812//2812 -f 2821//2821 2812//2812 2811//2811 -f 2249//2249 2818//2818 2810//2810 -f 2810//2810 2818//2818 2821//2821 -f 2810//2810 2821//2821 2809//2809 -f 2809//2809 2821//2821 2811//2811 -f 2809//2809 2811//2811 2248//2248 -f 2820//2820 2253//2253 2819//2819 -f 2817//2817 2822//2822 2820//2820 -f 2820//2820 2822//2822 2253//2253 -f 2244//2244 2813//2813 2823//2823 -f 2251//2251 2824//2824 2825//2825 -f 2813//2813 2826//2826 2823//2823 -f 2823//2823 2826//2826 2825//2825 -f 2823//2823 2825//2825 2827//2827 -f 2827//2827 2825//2825 2824//2824 -f 2827//2827 2824//2824 2828//2828 -f 2244//2244 2823//2823 2816//2816 -f 2816//2816 2823//2823 2827//2827 -f 2816//2816 2827//2827 2815//2815 -f 2815//2815 2827//2827 2828//2828 -f 2815//2815 2828//2828 2250//2250 -f 2826//2826 2251//2251 2825//2825 -f 2813//2813 2814//2814 2826//2826 -f 2826//2826 2814//2814 2251//2251 -f 2249//2249 2250//2250 2828//2828 -f 2249//2249 2828//2828 2817//2817 -f 2817//2817 2828//2828 2824//2824 -f 2817//2817 2824//2824 2822//2822 -f 2822//2822 2824//2824 2251//2251 -f 2822//2822 2251//2251 2253//2253 -f 2461//2461 2829//2829 2462//2462 -f 2462//2462 2829//2829 2830//2830 -f 2462//2462 2830//2830 2483//2483 -f 2483//2483 2830//2830 2831//2831 -f 2483//2483 2831//2831 2484//2484 -f 2484//2484 2831//2831 2832//2832 -f 2484//2484 2832//2832 2485//2485 -f 2485//2485 2832//2832 2833//2833 -f 2485//2485 2833//2833 2439//2439 -f 2439//2439 2833//2833 2834//2834 -f 2439//2439 2834//2834 2440//2440 -f 2440//2440 2834//2834 2835//2835 -f 2440//2440 2835//2835 2458//2458 -f 2458//2458 2835//2835 2836//2836 -f 2458//2458 2836//2836 2459//2459 -f 2459//2459 2836//2836 2837//2837 -f 2459//2459 2837//2837 2480//2480 -f 2480//2480 2837//2837 2838//2838 -f 2480//2480 2838//2838 2481//2481 -f 2481//2481 2838//2838 2839//2839 -f 2481//2481 2839//2839 2482//2482 -f 2482//2482 2839//2839 2840//2840 -f 2482//2482 2840//2840 2454//2454 -f 2454//2454 2840//2840 2841//2841 -f 2454//2454 2841//2841 2455//2455 -f 2455//2455 2841//2841 2842//2842 -f 2455//2455 2842//2842 2477//2477 -f 2477//2477 2842//2842 2843//2843 -f 2477//2477 2843//2843 2478//2478 -f 2478//2478 2843//2843 2844//2844 -f 2478//2478 2844//2844 2479//2479 -f 2479//2479 2844//2844 2845//2845 -f 2479//2479 2845//2845 2476//2476 -f 2476//2476 2845//2845 2846//2846 -f 2476//2476 2846//2846 2474//2474 -f 2474//2474 2846//2846 2847//2847 -f 2474//2474 2847//2847 2453//2453 -f 2453//2453 2847//2847 2848//2848 -f 2453//2453 2848//2848 2451//2451 -f 2451//2451 2848//2848 2849//2849 -f 2451//2451 2849//2849 2449//2449 -f 2449//2449 2849//2849 2850//2850 -f 2449//2449 2850//2850 2471//2471 -f 2471//2471 2850//2850 2851//2851 -f 2471//2471 2851//2851 2472//2472 -f 2472//2472 2851//2851 2852//2852 -f 2472//2472 2852//2852 2473//2473 -f 2473//2473 2852//2852 2853//2853 -f 2473//2473 2853//2853 2447//2447 -f 2447//2447 2853//2853 2854//2854 -f 2447//2447 2854//2854 2448//2448 -f 2448//2448 2854//2854 2855//2855 -f 2448//2448 2855//2855 2445//2445 -f 2445//2445 2855//2855 2856//2856 -f 2445//2445 2856//2856 2489//2489 -f 2489//2489 2856//2856 2857//2857 -f 2489//2489 2857//2857 2490//2490 -f 2490//2490 2857//2857 2858//2858 -f 2490//2490 2858//2858 2491//2491 -f 2491//2491 2858//2858 2859//2859 -f 2491//2491 2859//2859 2467//2467 -f 2467//2467 2859//2859 2860//2860 -f 2467//2467 2860//2860 2468//2468 -f 2468//2468 2860//2860 2861//2861 -f 2468//2468 2861//2861 2486//2486 -f 2486//2486 2861//2861 2862//2862 -f 2486//2486 2862//2862 2487//2487 -f 2487//2487 2862//2862 2863//2863 -f 2487//2487 2863//2863 2488//2488 -f 2488//2488 2863//2863 2864//2864 -f 2488//2488 2864//2864 2465//2465 -f 2465//2465 2864//2864 2865//2865 -f 2465//2465 2865//2865 2466//2466 -f 2466//2466 2865//2865 2866//2866 -f 2466//2466 2866//2866 2435//2435 -f 2435//2435 2866//2866 2867//2867 -f 2435//2435 2867//2867 2436//2436 -f 2436//2436 2867//2867 2868//2868 -f 2436//2436 2868//2868 2461//2461 -f 2461//2461 2868//2868 2829//2829 -f 2868//2868 2869//2869 2829//2829 -f 2829//2829 2869//2869 2870//2870 -f 2829//2829 2870//2870 2830//2830 -f 2830//2830 2870//2870 2871//2871 -f 2830//2830 2871//2871 2831//2831 -f 2831//2831 2871//2871 2872//2872 -f 2831//2831 2872//2872 2832//2832 -f 2832//2832 2872//2872 2873//2873 -f 2832//2832 2873//2873 2833//2833 -f 2833//2833 2873//2873 2874//2874 -f 2833//2833 2874//2874 2834//2834 -f 2834//2834 2874//2874 2875//2875 -f 2834//2834 2875//2875 2835//2835 -f 2835//2835 2875//2875 2876//2876 -f 2835//2835 2876//2876 2836//2836 -f 2836//2836 2876//2876 2877//2877 -f 2836//2836 2877//2877 2837//2837 -f 2837//2837 2877//2877 2878//2878 -f 2837//2837 2878//2878 2838//2838 -f 2838//2838 2878//2878 2879//2879 -f 2838//2838 2879//2879 2839//2839 -f 2839//2839 2879//2879 2880//2880 -f 2839//2839 2880//2880 2840//2840 -f 2840//2840 2880//2880 2881//2881 -f 2840//2840 2881//2881 2841//2841 -f 2841//2841 2881//2881 2882//2882 -f 2841//2841 2882//2882 2842//2842 -f 2842//2842 2882//2882 2883//2883 -f 2842//2842 2883//2883 2843//2843 -f 2843//2843 2883//2883 2884//2884 -f 2843//2843 2884//2884 2844//2844 -f 2844//2844 2884//2884 2885//2885 -f 2844//2844 2885//2885 2845//2845 -f 2845//2845 2885//2885 2886//2886 -f 2845//2845 2886//2886 2846//2846 -f 2846//2846 2886//2886 2887//2887 -f 2846//2846 2887//2887 2847//2847 -f 2847//2847 2887//2887 2888//2888 -f 2847//2847 2888//2888 2848//2848 -f 2848//2848 2888//2888 2889//2889 -f 2848//2848 2889//2889 2849//2849 -f 2849//2849 2889//2889 2890//2890 -f 2849//2849 2890//2890 2850//2850 -f 2850//2850 2890//2890 2891//2891 -f 2850//2850 2891//2891 2851//2851 -f 2851//2851 2891//2891 2892//2892 -f 2851//2851 2892//2892 2852//2852 -f 2852//2852 2892//2892 2893//2893 -f 2852//2852 2893//2893 2853//2853 -f 2853//2853 2893//2893 2894//2894 -f 2853//2853 2894//2894 2854//2854 -f 2854//2854 2894//2894 2895//2895 -f 2854//2854 2895//2895 2855//2855 -f 2855//2855 2895//2895 2896//2896 -f 2855//2855 2896//2896 2856//2856 -f 2856//2856 2896//2896 2897//2897 -f 2856//2856 2897//2897 2857//2857 -f 2857//2857 2897//2897 2898//2898 -f 2857//2857 2898//2898 2858//2858 -f 2858//2858 2898//2898 2899//2899 -f 2858//2858 2899//2899 2859//2859 -f 2859//2859 2899//2899 2900//2900 -f 2859//2859 2900//2900 2860//2860 -f 2860//2860 2900//2900 2901//2901 -f 2860//2860 2901//2901 2861//2861 -f 2861//2861 2901//2901 2902//2902 -f 2861//2861 2902//2902 2862//2862 -f 2862//2862 2902//2902 2903//2903 -f 2862//2862 2903//2903 2863//2863 -f 2863//2863 2903//2903 2904//2904 -f 2863//2863 2904//2904 2864//2864 -f 2864//2864 2904//2904 2905//2905 -f 2864//2864 2905//2905 2865//2865 -f 2865//2865 2905//2905 2906//2906 -f 2865//2865 2906//2906 2866//2866 -f 2866//2866 2906//2906 2907//2907 -f 2866//2866 2907//2907 2867//2867 -f 2867//2867 2907//2907 2908//2908 -f 2867//2867 2908//2908 2868//2868 -f 2868//2868 2908//2908 2869//2869 -f 2908//2908 2414//2414 2869//2869 -f 2869//2869 2414//2414 2417//2417 -f 2869//2869 2417//2417 2870//2870 -f 2870//2870 2417//2417 2416//2416 -f 2870//2870 2416//2416 2871//2871 -f 2871//2871 2416//2416 2419//2419 -f 2871//2871 2419//2419 2872//2872 -f 2872//2872 2419//2419 2418//2418 -f 2872//2872 2418//2418 2873//2873 -f 2873//2873 2418//2418 2421//2421 -f 2873//2873 2421//2421 2874//2874 -f 2874//2874 2421//2421 2420//2420 -f 2874//2874 2420//2420 2875//2875 -f 2875//2875 2420//2420 2423//2423 -f 2875//2875 2423//2423 2876//2876 -f 2876//2876 2423//2423 2422//2422 -f 2876//2876 2422//2422 2877//2877 -f 2877//2877 2422//2422 2425//2425 -f 2877//2877 2425//2425 2878//2878 -f 2878//2878 2425//2425 2424//2424 -f 2878//2878 2424//2424 2879//2879 -f 2879//2879 2424//2424 2427//2427 -f 2879//2879 2427//2427 2880//2880 -f 2880//2880 2427//2427 2426//2426 -f 2880//2880 2426//2426 2881//2881 -f 2881//2881 2426//2426 2429//2429 -f 2881//2881 2429//2429 2882//2882 -f 2882//2882 2429//2429 2428//2428 -f 2882//2882 2428//2428 2883//2883 -f 2883//2883 2428//2428 2431//2431 -f 2883//2883 2431//2431 2884//2884 -f 2884//2884 2431//2431 2430//2430 -f 2884//2884 2430//2430 2885//2885 -f 2885//2885 2430//2430 2434//2434 -f 2885//2885 2434//2434 2886//2886 -f 2886//2886 2434//2434 2433//2433 -f 2886//2886 2433//2433 2887//2887 -f 2887//2887 2433//2433 2432//2432 -f 2887//2887 2432//2432 2888//2888 -f 2888//2888 2432//2432 2395//2395 -f 2888//2888 2395//2395 2889//2889 -f 2889//2889 2395//2395 2397//2397 -f 2889//2889 2397//2397 2890//2890 -f 2890//2890 2397//2397 2396//2396 -f 2890//2890 2396//2396 2891//2891 -f 2891//2891 2396//2396 2399//2399 -f 2891//2891 2399//2399 2892//2892 -f 2892//2892 2399//2399 2398//2398 -f 2892//2892 2398//2398 2893//2893 -f 2893//2893 2398//2398 2401//2401 -f 2893//2893 2401//2401 2894//2894 -f 2894//2894 2401//2401 2400//2400 -f 2894//2894 2400//2400 2895//2895 -f 2895//2895 2400//2400 2403//2403 -f 2895//2895 2403//2403 2896//2896 -f 2896//2896 2403//2403 2402//2402 -f 2896//2896 2402//2402 2897//2897 -f 2897//2897 2402//2402 2405//2405 -f 2897//2897 2405//2405 2898//2898 -f 2898//2898 2405//2405 2404//2404 -f 2898//2898 2404//2404 2899//2899 -f 2899//2899 2404//2404 2407//2407 -f 2899//2899 2407//2407 2900//2900 -f 2900//2900 2407//2407 2406//2406 -f 2900//2900 2406//2406 2901//2901 -f 2901//2901 2406//2406 2409//2409 -f 2901//2901 2409//2409 2902//2902 -f 2902//2902 2409//2409 2408//2408 -f 2902//2902 2408//2408 2903//2903 -f 2903//2903 2408//2408 2411//2411 -f 2903//2903 2411//2411 2904//2904 -f 2904//2904 2411//2411 2410//2410 -f 2904//2904 2410//2410 2905//2905 -f 2905//2905 2410//2410 2413//2413 -f 2905//2905 2413//2413 2906//2906 -f 2906//2906 2413//2413 2412//2412 -f 2906//2906 2412//2412 2907//2907 -f 2907//2907 2412//2412 2415//2415 -f 2907//2907 2415//2415 2908//2908 -f 2908//2908 2415//2415 2414//2414 -f 2909//2909 2910//2910 2911//2911 -f 2912//2912 2913//2913 2910//2910 -f 2910//2910 2913//2913 2914//2914 -f 2910//2910 2914//2914 2911//2911 -f 2915//2915 2916//2916 2912//2912 -f 2912//2912 2916//2916 2917//2917 -f 2912//2912 2917//2917 2913//2913 -f 2918//2918 2919//2919 2915//2915 -f 2915//2915 2919//2919 2920//2920 -f 2915//2915 2920//2920 2916//2916 -f 2921//2921 2922//2922 2918//2918 -f 2918//2918 2922//2922 2923//2923 -f 2918//2918 2923//2923 2919//2919 -f 2924//2924 2925//2925 2921//2921 -f 2921//2921 2925//2925 2926//2926 -f 2921//2921 2926//2926 2922//2922 -f 2927//2927 2928//2928 2924//2924 -f 2924//2924 2928//2928 2929//2929 -f 2924//2924 2929//2929 2925//2925 -f 2930//2930 2931//2931 2927//2927 -f 2927//2927 2931//2931 2932//2932 -f 2927//2927 2932//2932 2928//2928 -f 2933//2933 2934//2934 2930//2930 -f 2930//2930 2934//2934 2935//2935 -f 2930//2930 2935//2935 2931//2931 -f 2936//2936 2937//2937 2933//2933 -f 2933//2933 2937//2937 2938//2938 -f 2933//2933 2938//2938 2934//2934 -f 2939//2939 2940//2940 2936//2936 -f 2936//2936 2940//2940 2941//2941 -f 2936//2936 2941//2941 2937//2937 -f 2942//2942 2943//2943 2939//2939 -f 2939//2939 2943//2943 2944//2944 -f 2939//2939 2944//2944 2940//2940 -f 2945//2945 2946//2946 2942//2942 -f 2942//2942 2946//2946 2947//2947 -f 2942//2942 2947//2947 2943//2943 -f 2948//2948 2949//2949 2945//2945 -f 2945//2945 2949//2949 2950//2950 -f 2945//2945 2950//2950 2946//2946 -f 2951//2951 2952//2952 2948//2948 -f 2948//2948 2952//2952 2953//2953 -f 2948//2948 2953//2953 2949//2949 -f 2954//2954 2955//2955 2951//2951 -f 2951//2951 2955//2955 2956//2956 -f 2951//2951 2956//2956 2952//2952 -f 2957//2957 2958//2958 2954//2954 -f 2954//2954 2958//2958 2959//2959 -f 2954//2954 2959//2959 2955//2955 -f 2960//2960 2961//2961 2957//2957 -f 2957//2957 2961//2961 2962//2962 -f 2957//2957 2962//2962 2958//2958 -f 2911//2911 2963//2963 2909//2909 -f 2909//2909 2963//2963 2964//2964 -f 2909//2909 2964//2964 2960//2960 -f 2960//2960 2964//2964 2965//2965 -f 2960//2960 2965//2965 2961//2961 -f 2966//2966 2967//2967 2968//2968 -f 2969//2969 2970//2970 2971//2971 -f 2971//2971 2970//2970 2972//2972 -f 2973//2973 2974//2974 2975//2975 -f 2976//2976 2977//2977 2978//2978 -f 2979//2979 2980//2980 2981//2981 -f 2981//2981 2980//2980 2982//2982 -f 2981//2981 2982//2982 2983//2983 -f 2984//2984 2985//2985 2979//2979 -f 2979//2979 2985//2985 2986//2986 -f 2979//2979 2986//2986 2980//2980 -f 2975//2975 2987//2987 2973//2973 -f 2973//2973 2987//2987 2988//2988 -f 2973//2973 2988//2988 2989//2989 -f 2983//2983 2982//2982 2972//2972 -f 2972//2972 2982//2982 2990//2990 -f 2972//2972 2990//2990 2971//2971 -f 2991//2991 2992//2992 2993//2993 -f 2993//2993 2992//2992 2994//2994 -f 2993//2993 2994//2994 2984//2984 -f 2984//2984 2994//2994 2995//2995 -f 2984//2984 2995//2995 2985//2985 -f 2996//2996 2997//2997 2993//2993 -f 2993//2993 2997//2997 2998//2998 -f 2993//2993 2998//2998 2991//2991 -f 2999//2999 2997//2997 3000//3000 -f 3000//3000 2997//2997 2996//2996 -f 3000//3000 2996//2996 3001//3001 -f 3001//3001 2996//2996 3002//3002 -f 3001//3001 3002//3002 3003//3003 -f 3003//3003 3002//3002 2977//2977 -f 3003//3003 2977//2977 3004//3004 -f 3004//3004 2977//2977 2976//2976 -f 2999//2999 3005//3005 2997//2997 -f 2997//2997 3005//3005 3006//3006 -f 2997//2997 3006//3006 3007//3007 -f 3007//3007 3006//3006 3008//3008 -f 3007//3007 3008//3008 2988//2988 -f 2988//2988 3008//3008 3009//3009 -f 2988//2988 3009//3009 2989//2989 -f 2998//2998 3010//3010 2991//2991 -f 2991//2991 3010//3010 3011//3011 -f 2991//2991 3011//3011 3012//3012 -f 3012//3012 3011//3011 3013//3013 -f 3012//3012 3013//3013 3014//3014 -f 3014//3014 3013//3013 3015//3015 -f 3014//3014 3015//3015 3016//3016 -f 3016//3016 3015//3015 3017//3017 -f 3016//3016 3017//3017 2974//2974 -f 2974//2974 3017//3017 3018//3018 -f 2974//2974 3018//3018 2975//2975 -f 3019//3019 3020//3020 3021//3021 -f 3022//3022 3023//3023 3024//3024 -f 3025//3025 2968//2968 3026//3026 -f 3024//3024 3023//3023 3020//3020 -f 3020//3020 3023//3023 3027//3027 -f 3020//3020 3027//3027 3021//3021 -f 2967//2967 3028//3028 2968//2968 -f 2968//2968 3028//3028 3029//3029 -f 2968//2968 3029//3029 3026//3026 -f 2973//2973 3030//3030 2974//2974 -f 2974//2974 3030//3030 3031//3031 -f 2974//2974 3031//3031 3032//3032 -f 3032//3032 3031//3031 3033//3033 -f 3024//3024 3034//3034 3022//3022 -f 3022//3022 3034//3034 3035//3035 -f 3022//3022 3035//3035 2967//2967 -f 2967//2967 3035//3035 3036//3036 -f 2967//2967 3036//3036 3028//3028 -f 2973//2973 3037//3037 3030//3030 -f 3030//3030 3037//3037 3038//3038 -f 3030//3030 3038//3038 3039//3039 -f 3039//3039 3038//3038 3040//3040 -f 3039//3039 3040//3040 3026//3026 -f 3026//3026 3040//3040 3041//3041 -f 3026//3026 3041//3041 3025//3025 -f 3021//3021 3042//3042 3019//3019 -f 3019//3019 3042//3042 3043//3043 -f 3019//3019 3043//3043 3031//3031 -f 3031//3031 3043//3043 3044//3044 -f 3031//3031 3044//3044 3033//3033 -f 3045//3045 3046//3046 3047//3047 -f 3047//3047 3048//3048 3045//3045 -f 3045//3045 3048//3048 3049//3049 -f 3045//3045 3049//3049 2968//2968 -f 2968//2968 3049//3049 3050//3050 -f 2968//2968 3050//3050 2966//2966 -f 3051//3051 3052//3052 3053//3053 -f 3053//3053 3052//3052 2976//2976 -f 3053//3053 2976//2976 3054//3054 -f 3051//3051 3053//3053 3055//3055 -f 3055//3055 3053//3053 3056//3056 -f 3055//3055 3056//3056 3057//3057 -f 3057//3057 3056//3056 3058//3058 -f 3057//3057 3058//3058 3059//3059 -f 3059//3059 3058//3058 3045//3045 -f 3045//3045 3058//3058 3060//3060 -f 3045//3045 3060//3060 3046//3046 -f 3060//3060 3061//3061 3046//3046 -f 3046//3046 3061//3061 3062//3062 -f 3046//3046 3062//3062 3063//3063 -f 3063//3063 3062//3062 3064//3064 -f 3063//3063 3064//3064 3065//3065 -f 3065//3065 3064//3064 3066//3066 -f 3065//3065 3066//3066 3067//3067 -f 3067//3067 3066//3066 3068//3068 -f 3067//3067 3068//3068 3069//3069 -f 3069//3069 3068//3068 3070//3070 -f 3069//3069 3070//3070 3071//3071 -f 3071//3071 3070//3070 3072//3072 -f 2978//2978 2969//2969 2976//2976 -f 2976//2976 2969//2969 2971//2971 -f 2976//2976 2971//2971 3054//3054 -f 3054//3054 2971//2971 3073//3073 -f 3054//3054 3073//3073 3074//3074 -f 3074//3074 3075//3075 3054//3054 -f 3054//3054 3075//3075 3076//3076 -f 3054//3054 3076//3076 3072//3072 -f 3072//3072 3076//3076 3077//3077 -f 3072//3072 3077//3077 3071//3071 -f 3078//3078 3079//3079 3080//3080 -f 3080//3080 3079//3079 3081//3081 -f 3080//3080 3081//3081 3082//3082 -f 3082//3082 3081//3081 3083//3083 -f 3082//3082 3083//3083 3084//3084 -f 3084//3084 3083//3083 3085//3085 -f 3084//3084 3085//3085 3086//3086 -f 3086//3086 3085//3085 3087//3087 -f 3086//3086 3087//3087 3088//3088 -f 3088//3088 3087//3087 3089//3089 -f 3088//3088 3089//3089 3090//3090 -f 3090//3090 3089//3089 3091//3091 -f 3090//3090 3091//3091 3092//3092 -f 3092//3092 3091//3091 3093//3093 -f 3092//3092 3093//3093 3094//3094 -f 3094//3094 3093//3093 3095//3095 -f 3094//3094 3095//3095 3096//3096 -f 3096//3096 3095//3095 3097//3097 -f 3096//3096 3097//3097 3098//3098 -f 3098//3098 3097//3097 3099//3099 -f 3098//3098 3099//3099 3100//3100 -f 3100//3100 3099//3099 3101//3101 -f 3100//3100 3101//3101 3102//3102 -f 3102//3102 3101//3101 3103//3103 -f 3102//3102 3103//3103 3104//3104 -f 3104//3104 3103//3103 3105//3105 -f 3104//3104 3105//3105 3106//3106 -f 3106//3106 3105//3105 3107//3107 -f 3106//3106 3107//3107 3108//3108 -f 3108//3108 3107//3107 3109//3109 -f 3108//3108 3109//3109 3110//3110 -f 3110//3110 3109//3109 3111//3111 -f 3110//3110 3111//3111 3112//3112 -f 3112//3112 3111//3111 3113//3113 -f 3112//3112 3113//3113 3114//3114 -f 3114//3114 3113//3113 3115//3115 -f 3114//3114 3115//3115 3116//3116 -f 3116//3116 3115//3115 3117//3117 -f 3116//3116 3117//3117 3118//3118 -f 3118//3118 3117//3117 3119//3119 -f 3118//3118 3119//3119 3120//3120 -f 3120//3120 3119//3119 3121//3121 -f 3120//3120 3121//3121 3122//3122 -f 3122//3122 3121//3121 3123//3123 -f 3122//3122 3123//3123 3124//3124 -f 3124//3124 3123//3123 3125//3125 -f 3124//3124 3125//3125 3126//3126 -f 3126//3126 3125//3125 3127//3127 -f 3126//3126 3127//3127 3128//3128 -f 3128//3128 3127//3127 3129//3129 -f 3128//3128 3129//3129 3130//3130 -f 3130//3130 3129//3129 3131//3131 -f 3130//3130 3131//3131 3132//3132 -f 3132//3132 3131//3131 3133//3133 -f 3132//3132 3133//3133 3134//3134 -f 3134//3134 3133//3133 3135//3135 -f 3134//3134 3135//3135 3136//3136 -f 3136//3136 3135//3135 3137//3137 -f 3136//3136 3137//3137 3138//3138 -f 3138//3138 3137//3137 3139//3139 -f 3138//3138 3139//3139 3140//3140 -f 3140//3140 3139//3139 3141//3141 -f 3140//3140 3141//3141 3142//3142 -f 3142//3142 3141//3141 3143//3143 -f 3142//3142 3143//3143 3144//3144 -f 3144//3144 3143//3143 3145//3145 -f 3144//3144 3145//3145 3146//3146 -f 3146//3146 3145//3145 3147//3147 -f 3146//3146 3147//3147 3148//3148 -f 3148//3148 3147//3147 3149//3149 -f 3148//3148 3149//3149 3150//3150 -f 3150//3150 3149//3149 3151//3151 -f 3150//3150 3151//3151 3152//3152 -f 3152//3152 3151//3151 3153//3153 -f 3152//3152 3153//3153 3078//3078 -f 3078//3078 3153//3153 3079//3079 -f 3154//3154 3155//3155 3156//3156 -f 3156//3156 3155//3155 3157//3157 -f 3157//3157 3155//3155 3158//3158 -f 3157//3157 3158//3158 3159//3159 -f 3159//3159 3158//3158 3160//3160 -f 3159//3159 3160//3160 3161//3161 -f 3161//3161 3160//3160 3162//3162 -f 3161//3161 3162//3162 3163//3163 -f 3163//3163 3162//3162 3164//3164 -f 3163//3163 3164//3164 3165//3165 -f 3165//3165 3166//3166 3167//3167 -f 3167//3167 3166//3166 3168//3168 -f 3167//3167 3168//3168 3169//3169 -f 3170//3170 3171//3171 3172//3172 -f 3156//3156 3173//3173 3154//3154 -f 3154//3154 3173//3173 3174//3174 -f 3154//3154 3174//3174 3175//3175 -f 3170//3170 3176//3176 3171//3171 -f 3171//3171 3176//3176 3177//3177 -f 3171//3171 3177//3177 3178//3178 -f 3172//3172 3179//3179 3170//3170 -f 3170//3170 3179//3179 3180//3180 -f 3170//3170 3180//3180 3181//3181 -f 3181//3181 3180//3180 3182//3182 -f 3181//3181 3182//3182 3168//3168 -f 3168//3168 3182//3182 3183//3183 -f 3168//3168 3183//3183 3169//3169 -f 3184//3184 3185//3185 3186//3186 -f 3186//3186 3185//3185 3187//3187 -f 3186//3186 3187//3187 3188//3188 -f 3188//3188 3187//3187 3189//3189 -f 3188//3188 3189//3189 3178//3178 -f 3178//3178 3189//3189 3190//3190 -f 3178//3178 3190//3190 3171//3171 -f 3191//3191 3192//3192 3193//3193 -f 3193//3193 3192//3192 3194//3194 -f 3176//3176 3154//3154 3177//3177 -f 3177//3177 3154//3154 3175//3175 -f 3177//3177 3175//3175 3195//3195 -f 3195//3195 3175//3175 3196//3196 -f 3195//3195 3196//3196 3197//3197 -f 3198//3198 3199//3199 3200//3200 -f 3200//3200 3199//3199 3194//3194 -f 3194//3194 3199//3199 3201//3201 -f 3194//3194 3201//3201 3193//3193 -f 3200//3200 3202//3202 3198//3198 -f 3198//3198 3202//3202 3203//3203 -f 3198//3198 3203//3203 3204//3204 -f 3204//3204 3203//3203 3197//3197 -f 3204//3204 3197//3197 3205//3205 -f 3205//3205 3197//3197 3196//3196 -f 3206//3206 3207//3207 3208//3208 -f 3208//3208 3207//3207 3209//3209 -f 3207//3207 3210//3210 3211//3211 -f 3211//3211 3210//3210 3212//3212 -f 3211//3211 3212//3212 3213//3213 -f 3213//3213 3212//3212 3214//3214 -f 3213//3213 3214//3214 3215//3215 -f 3215//3215 3214//3214 3216//3216 -f 3215//3215 3216//3216 3217//3217 -f 3217//3217 3216//3216 3218//3218 -f 3217//3217 3218//3218 3219//3219 -f 3219//3219 3218//3218 3220//3220 -f 3219//3219 3220//3220 3221//3221 -f 3221//3221 3220//3220 3222//3222 -f 3221//3221 3222//3222 3223//3223 -f 3186//3186 3191//3191 3184//3184 -f 3184//3184 3191//3191 3193//3193 -f 3184//3184 3193//3193 3224//3224 -f 3224//3224 3193//3193 3225//3225 -f 3223//3223 3222//3222 3226//3226 -f 3226//3226 3222//3222 3227//3227 -f 3226//3226 3227//3227 3228//3228 -f 3208//3208 3229//3229 3206//3206 -f 3206//3206 3229//3229 3230//3230 -f 3206//3206 3230//3230 3231//3231 -f 3231//3231 3230//3230 3232//3232 -f 3231//3231 3232//3232 3233//3233 -f 3233//3233 3232//3232 3234//3234 -f 3234//3234 3225//3225 3233//3233 -f 3233//3233 3225//3225 3193//3193 -f 3233//3233 3193//3193 3227//3227 -f 3227//3227 3193//3193 3235//3235 -f 3227//3227 3235//3235 3228//3228 -f 3207//3207 3211//3211 3209//3209 -f 3209//3209 3211//3211 3236//3236 -f 3209//3209 3236//3236 3237//3237 -f 3237//3237 3238//3238 3209//3209 -f 3209//3209 3238//3238 3239//3239 -f 3209//3209 3239//3239 3240//3240 -f 3241//3241 3242//3242 3243//3243 -f 3244//3244 3245//3245 3246//3246 -f 3247//3247 3209//3209 3248//3248 -f 3249//3249 3250//3250 3251//3251 -f 3246//3246 3245//3245 3242//3242 -f 3242//3242 3245//3245 3252//3252 -f 3242//3242 3252//3252 3243//3243 -f 3165//3165 3167//3167 3163//3163 -f 3163//3163 3167//3167 3253//3253 -f 3163//3163 3253//3253 3254//3254 -f 3246//3246 3255//3255 3244//3244 -f 3244//3244 3255//3255 3256//3256 -f 3244//3244 3256//3256 3257//3257 -f 3257//3257 3256//3256 3258//3258 -f 3257//3257 3258//3258 3240//3240 -f 3240//3240 3258//3258 3259//3259 -f 3240//3240 3259//3259 3209//3209 -f 3209//3209 3259//3259 3260//3260 -f 3209//3209 3260//3260 3248//3248 -f 3250//3250 3163//3163 3251//3251 -f 3251//3251 3163//3163 3254//3254 -f 3251//3251 3254//3254 3261//3261 -f 3261//3261 3254//3254 3262//3262 -f 3261//3261 3262//3262 3263//3263 -f 3263//3263 3262//3262 3264//3264 -f 3263//3263 3264//3264 3248//3248 -f 3248//3248 3264//3264 3265//3265 -f 3248//3248 3265//3265 3247//3247 -f 3243//3243 3266//3266 3241//3241 -f 3241//3241 3266//3266 3267//3267 -f 3241//3241 3267//3267 3251//3251 -f 3251//3251 3267//3267 3268//3268 -f 3251//3251 3268//3268 3249//3249 -f 3183//3183 3182//3182 3269//3269 -f 3269//3269 3270//3270 3183//3183 -f 3183//3183 3270//3270 3271//3271 -f 3183//3183 3271//3271 3169//3169 -f 3169//3169 3271//3271 3272//3272 -f 3169//3169 3272//3272 3167//3167 -f 3167//3167 3272//3272 3273//3273 -f 3167//3167 3273//3273 3253//3253 -f 3273//3273 3274//3274 3253//3253 -f 3253//3253 3274//3274 3275//3275 -f 3253//3253 3275//3275 3254//3254 -f 3275//3275 3276//3276 3254//3254 -f 3254//3254 3276//3276 3277//3277 -f 3254//3254 3277//3277 3262//3262 -f 3277//3277 3278//3278 3262//3262 -f 3262//3262 3278//3278 3279//3279 -f 3262//3262 3279//3279 3264//3264 -f 3279//3279 3280//3280 3264//3264 -f 3264//3264 3280//3280 3281//3281 -f 3264//3264 3281//3281 3265//3265 -f 3281//3281 3282//3282 3265//3265 -f 3265//3265 3282//3282 3283//3283 -f 3265//3265 3283//3283 3247//3247 -f 3283//3283 3284//3284 3247//3247 -f 3247//3247 3284//3284 3285//3285 -f 3247//3247 3285//3285 3209//3209 -f 3285//3285 3286//3286 3209//3209 -f 3209//3209 3286//3286 3287//3287 -f 3209//3209 3287//3287 3208//3208 -f 3287//3287 3288//3288 3208//3208 -f 3208//3208 3288//3288 3289//3289 -f 3208//3208 3289//3289 3229//3229 -f 3289//3289 3290//3290 3229//3229 -f 3229//3229 3290//3290 3291//3291 -f 3229//3229 3291//3291 3230//3230 -f 3291//3291 3292//3292 3230//3230 -f 3230//3230 3292//3292 3293//3293 -f 3230//3230 3293//3293 3232//3232 -f 3293//3293 3294//3294 3232//3232 -f 3232//3232 3294//3294 3295//3295 -f 3232//3232 3295//3295 3234//3234 -f 3295//3295 3296//3296 3234//3234 -f 3234//3234 3296//3296 3297//3297 -f 3234//3234 3297//3297 3225//3225 -f 3297//3297 3298//3298 3225//3225 -f 3225//3225 3298//3298 3299//3299 -f 3225//3225 3299//3299 3224//3224 -f 3224//3224 3299//3299 3300//3300 -f 3224//3224 3300//3300 3184//3184 -f 3184//3184 3300//3300 3301//3301 -f 3184//3184 3301//3301 3185//3185 -f 3301//3301 3302//3302 3185//3185 -f 3185//3185 3302//3302 3303//3303 -f 3185//3185 3303//3303 3187//3187 -f 3303//3303 3304//3304 3187//3187 -f 3187//3187 3304//3304 3305//3305 -f 3187//3187 3305//3305 3189//3189 -f 3305//3305 3306//3306 3189//3189 -f 3189//3189 3306//3306 3307//3307 -f 3189//3189 3307//3307 3190//3190 -f 3307//3307 3308//3308 3190//3190 -f 3190//3190 3308//3308 3309//3309 -f 3190//3190 3309//3309 3171//3171 -f 3309//3309 3310//3310 3171//3171 -f 3171//3171 3310//3310 3311//3311 -f 3171//3171 3311//3311 3172//3172 -f 3311//3311 3312//3312 3172//3172 -f 3172//3172 3312//3312 3313//3313 -f 3172//3172 3313//3313 3179//3179 -f 3313//3313 3314//3314 3179//3179 -f 3179//3179 3314//3314 3315//3315 -f 3179//3179 3315//3315 3180//3180 -f 3315//3315 3316//3316 3180//3180 -f 3180//3180 3316//3316 3317//3317 -f 3180//3180 3317//3317 3182//3182 -f 3182//3182 3317//3317 3318//3318 -f 3182//3182 3318//3318 3269//3269 -f 3319//3319 3320//3320 3321//3321 -f 3322//3322 3323//3323 3324//3324 -f 3324//3324 3323//3323 3325//3325 -f 3324//3324 3325//3325 3326//3326 -f 3326//3326 3325//3325 3327//3327 -f 3326//3326 3327//3327 3321//3321 -f 3321//3321 3327//3327 3328//3328 -f 3321//3321 3328//3328 3319//3319 -f 3329//3329 3330//3330 3331//3331 -f 3331//3331 3330//3330 3332//3332 -f 3331//3331 3332//3332 3333//3333 -f 3333//3333 3332//3332 3334//3334 -f 3333//3333 3334//3334 3322//3322 -f 3322//3322 3334//3334 3335//3335 -f 3322//3322 3335//3335 3323//3323 -f 3336//3336 3337//3337 3338//3338 -f 3338//3338 3337//3337 3339//3339 -f 3338//3338 3339//3339 3340//3340 -f 3340//3340 3339//3339 3341//3341 -f 3340//3340 3341//3341 3329//3329 -f 3329//3329 3341//3341 3342//3342 -f 3329//3329 3342//3342 3330//3330 -f 3319//3319 3343//3343 3320//3320 -f 3320//3320 3343//3343 3344//3344 -f 3320//3320 3344//3344 3345//3345 -f 3345//3345 3344//3344 3346//3346 -f 3345//3345 3346//3346 3347//3347 -f 3347//3347 3346//3346 3348//3348 -f 3347//3347 3348//3348 3349//3349 -f 3350//3350 3351//3351 3352//3352 -f 3352//3352 3351//3351 3353//3353 -f 3352//3352 3353//3353 3354//3354 -f 3354//3354 3353//3353 3355//3355 -f 3354//3354 3355//3355 3336//3336 -f 3336//3336 3355//3355 3356//3356 -f 3336//3336 3356//3356 3337//3337 -f 3348//3348 3357//3357 3349//3349 -f 3349//3349 3357//3357 3358//3358 -f 3349//3349 3358//3358 3359//3359 -f 3359//3359 3358//3358 3360//3360 -f 3359//3359 3360//3360 3361//3361 -f 3361//3361 3360//3360 3362//3362 -f 3361//3361 3362//3362 3350//3350 -f 3350//3350 3362//3362 3363//3363 -f 3350//3350 3363//3363 3351//3351 -f 3364//3364 3320//3320 3365//3365 -f 3365//3365 3320//3320 3345//3345 -f 3365//3365 3345//3345 3366//3366 -f 3366//3366 3345//3345 3347//3347 -f 3366//3366 3347//3347 3367//3367 -f 3367//3367 3347//3347 3349//3349 -f 3367//3367 3349//3349 3368//3368 -f 3368//3368 3349//3349 3359//3359 -f 3368//3368 3359//3359 3369//3369 -f 3369//3369 3359//3359 3361//3361 -f 3369//3369 3361//3361 3370//3370 -f 3370//3370 3361//3361 3350//3350 -f 3370//3370 3350//3350 3371//3371 -f 3371//3371 3350//3350 3352//3352 -f 3371//3371 3352//3352 3372//3372 -f 3372//3372 3352//3352 3354//3354 -f 3372//3372 3354//3354 3373//3373 -f 3373//3373 3354//3354 3336//3336 -f 3373//3373 3336//3336 3374//3374 -f 3374//3374 3336//3336 3338//3338 -f 3374//3374 3338//3338 3375//3375 -f 3375//3375 3338//3338 3340//3340 -f 3375//3375 3340//3340 3376//3376 -f 3376//3376 3340//3340 3329//3329 -f 3376//3376 3329//3329 3377//3377 -f 3377//3377 3329//3329 3331//3331 -f 3377//3377 3331//3331 3378//3378 -f 3378//3378 3331//3331 3333//3333 -f 3378//3378 3333//3333 3379//3379 -f 3379//3379 3333//3333 3322//3322 -f 3379//3379 3322//3322 3380//3380 -f 3380//3380 3322//3322 3324//3324 -f 3380//3380 3324//3324 3381//3381 -f 3381//3381 3324//3324 3326//3326 -f 3381//3381 3326//3326 3382//3382 -f 3382//3382 3326//3326 3321//3321 -f 3382//3382 3321//3321 3364//3364 -f 3364//3364 3321//3321 3320//3320 -f 3383//3383 3381//3381 3384//3384 -f 3384//3384 3381//3381 3382//3382 -f 3384//3384 3382//3382 3385//3385 -f 3385//3385 3382//3382 3364//3364 -f 3385//3385 3364//3364 3386//3386 -f 3387//3387 3375//3375 3388//3388 -f 3388//3388 3375//3375 3376//3376 -f 3388//3388 3376//3376 3389//3389 -f 3376//3376 3377//3377 3389//3389 -f 3389//3389 3377//3377 3378//3378 -f 3389//3389 3378//3378 3390//3390 -f 3390//3390 3378//3378 3379//3379 -f 3390//3390 3379//3379 3383//3383 -f 3383//3383 3379//3379 3380//3380 -f 3383//3383 3380//3380 3381//3381 -f 3391//3391 3372//3372 3392//3392 -f 3392//3392 3372//3372 3373//3373 -f 3392//3392 3373//3373 3387//3387 -f 3387//3387 3373//3373 3374//3374 -f 3387//3387 3374//3374 3375//3375 -f 3393//3393 3369//3369 3394//3394 -f 3394//3394 3369//3369 3370//3370 -f 3394//3394 3370//3370 3391//3391 -f 3391//3391 3370//3370 3371//3371 -f 3391//3391 3371//3371 3372//3372 -f 3364//3364 3365//3365 3386//3386 -f 3386//3386 3365//3365 3366//3366 -f 3386//3386 3366//3366 3395//3395 -f 3395//3395 3366//3366 3367//3367 -f 3395//3395 3367//3367 3393//3393 -f 3393//3393 3367//3367 3368//3368 -f 3393//3393 3368//3368 3369//3369 -f 3396//3396 3385//3385 3397//3397 -f 3397//3397 3385//3385 3386//3386 -f 3397//3397 3386//3386 3398//3398 -f 3398//3398 3386//3386 3395//3395 -f 3398//3398 3395//3395 3399//3399 -f 3399//3399 3395//3395 3393//3393 -f 3399//3399 3393//3393 3400//3400 -f 3400//3400 3393//3393 3394//3394 -f 3400//3400 3394//3394 3401//3401 -f 3401//3401 3394//3394 3391//3391 -f 3401//3401 3391//3391 3402//3402 -f 3402//3402 3391//3391 3392//3392 -f 3402//3402 3392//3392 3403//3403 -f 3403//3403 3392//3392 3387//3387 -f 3403//3403 3387//3387 3404//3404 -f 3404//3404 3387//3387 3388//3388 -f 3404//3404 3388//3388 3405//3405 -f 3405//3405 3388//3388 3389//3389 -f 3405//3405 3389//3389 3406//3406 -f 3406//3406 3389//3389 3390//3390 -f 3406//3406 3390//3390 3407//3407 -f 3407//3407 3390//3390 3383//3383 -f 3407//3407 3383//3383 3408//3408 -f 3408//3408 3383//3383 3384//3384 -f 3408//3408 3384//3384 3396//3396 -f 3396//3396 3384//3384 3385//3385 -f 3404//3404 2939//2939 3403//3403 -f 3403//3403 2939//2939 2936//2936 -f 3403//3403 2936//2936 3402//3402 -f 3406//3406 2948//2948 3405//3405 -f 3405//3405 2948//2948 2945//2945 -f 3405//3405 2945//2945 3404//3404 -f 3404//3404 2945//2945 2942//2942 -f 3404//3404 2942//2942 2939//2939 -f 3408//3408 2957//2957 3407//3407 -f 3407//3407 2957//2957 2954//2954 -f 3407//3407 2954//2954 3406//3406 -f 3406//3406 2954//2954 2951//2951 -f 3406//3406 2951//2951 2948//2948 -f 3398//3398 2912//2912 3397//3397 -f 3397//3397 2912//2912 2910//2910 -f 3397//3397 2910//2910 3396//3396 -f 3396//3396 2910//2910 2909//2909 -f 3396//3396 2909//2909 3408//3408 -f 3408//3408 2909//2909 2960//2960 -f 3408//3408 2960//2960 2957//2957 -f 3400//3400 2921//2921 3399//3399 -f 3399//3399 2921//2921 2918//2918 -f 3399//3399 2918//2918 3398//3398 -f 3398//3398 2918//2918 2915//2915 -f 3398//3398 2915//2915 2912//2912 -f 2936//2936 2933//2933 3402//3402 -f 3402//3402 2933//2933 2930//2930 -f 3402//3402 2930//2930 3401//3401 -f 3401//3401 2930//2930 2927//2927 -f 3401//3401 2927//2927 3400//3400 -f 3400//3400 2927//2927 2924//2924 -f 3400//3400 2924//2924 2921//2921 -f 3409//3409 3158//3158 3410//3410 -f 3410//3410 3158//3158 3155//3155 -f 3410//3410 3155//3155 3411//3411 -f 3411//3411 3155//3155 3154//3154 -f 3411//3411 3154//3154 3412//3412 -f 3412//3412 3154//3154 3176//3176 -f 3412//3412 3176//3176 3413//3413 -f 3413//3413 3176//3176 3170//3170 -f 3413//3413 3170//3170 3414//3414 -f 3414//3414 3170//3170 3181//3181 -f 3414//3414 3181//3181 3415//3415 -f 3415//3415 3181//3181 3168//3168 -f 3415//3415 3168//3168 3416//3416 -f 3416//3416 3168//3168 3166//3166 -f 3416//3416 3166//3166 3417//3417 -f 3417//3417 3166//3166 3165//3165 -f 3417//3417 3165//3165 3418//3418 -f 3418//3418 3165//3165 3164//3164 -f 3418//3418 3164//3164 3419//3419 -f 3419//3419 3164//3164 3162//3162 -f 3419//3419 3162//3162 3420//3420 -f 3420//3420 3162//3162 3160//3160 -f 3420//3420 3160//3160 3409//3409 -f 3409//3409 3160//3160 3158//3158 -f 3414//3414 3421//3421 3413//3413 -f 3413//3413 3421//3421 3422//3422 -f 3413//3413 3422//3422 3412//3412 -f 3412//3412 3422//3422 3423//3423 -f 3412//3412 3423//3423 3411//3411 -f 3411//3411 3423//3423 3424//3424 -f 3411//3411 3424//3424 3410//3410 -f 3410//3410 3424//3424 3425//3425 -f 3410//3410 3425//3425 3409//3409 -f 3409//3409 3425//3425 3426//3426 -f 3409//3409 3426//3426 3420//3420 -f 3420//3420 3426//3426 3427//3427 -f 3420//3420 3427//3427 3419//3419 -f 3419//3419 3427//3427 3428//3428 -f 3419//3419 3428//3428 3418//3418 -f 3418//3418 3428//3428 3429//3429 -f 3418//3418 3429//3429 3417//3417 -f 3417//3417 3429//3429 3430//3430 -f 3417//3417 3430//3430 3416//3416 -f 3416//3416 3430//3430 3431//3431 -f 3416//3416 3431//3431 3415//3415 -f 3415//3415 3431//3431 3432//3432 -f 3415//3415 3432//3432 3414//3414 -f 3414//3414 3432//3432 3421//3421 -f 3422//3422 3053//3053 3423//3423 -f 3423//3423 3053//3053 3054//3054 -f 3423//3423 3054//3054 3424//3424 -f 3424//3424 3054//3054 3072//3072 -f 3424//3424 3072//3072 3425//3425 -f 3425//3425 3072//3072 3070//3070 -f 3425//3425 3070//3070 3426//3426 -f 3426//3426 3070//3070 3068//3068 -f 3426//3426 3068//3068 3427//3427 -f 3427//3427 3068//3068 3066//3066 -f 3427//3427 3066//3066 3428//3428 -f 3428//3428 3066//3066 3064//3064 -f 3428//3428 3064//3064 3429//3429 -f 3429//3429 3064//3064 3062//3062 -f 3429//3429 3062//3062 3430//3430 -f 3430//3430 3062//3062 3061//3061 -f 3430//3430 3061//3061 3431//3431 -f 3431//3431 3061//3061 3060//3060 -f 3431//3431 3060//3060 3432//3432 -f 3432//3432 3060//3060 3058//3058 -f 3432//3432 3058//3058 3421//3421 -f 3421//3421 3058//3058 3056//3056 -f 3421//3421 3056//3056 3422//3422 -f 3422//3422 3056//3056 3053//3053 -f 3433//3433 3251//3251 3434//3434 -f 3434//3434 3251//3251 3261//3261 -f 3434//3434 3261//3261 3435//3435 -f 3435//3435 3261//3261 3263//3263 -f 3435//3435 3263//3263 3436//3436 -f 3436//3436 3263//3263 3248//3248 -f 3436//3436 3248//3248 3437//3437 -f 3437//3437 3248//3248 3260//3260 -f 3437//3437 3260//3260 3438//3438 -f 3438//3438 3260//3260 3259//3259 -f 3438//3438 3259//3259 3439//3439 -f 3439//3439 3259//3259 3258//3258 -f 3439//3439 3258//3258 3440//3440 -f 3440//3440 3258//3258 3256//3256 -f 3440//3440 3256//3256 3441//3441 -f 3441//3441 3256//3256 3255//3255 -f 3441//3441 3255//3255 3442//3442 -f 3442//3442 3255//3255 3246//3246 -f 3442//3442 3246//3246 3443//3443 -f 3443//3443 3246//3246 3242//3242 -f 3443//3443 3242//3242 3444//3444 -f 3444//3444 3242//3242 3241//3241 -f 3444//3444 3241//3241 3433//3433 -f 3433//3433 3241//3241 3251//3251 -f 3438//3438 3445//3445 3437//3437 -f 3437//3437 3445//3445 3446//3446 -f 3437//3437 3446//3446 3436//3436 -f 3436//3436 3446//3446 3447//3447 -f 3436//3436 3447//3447 3435//3435 -f 3435//3435 3447//3447 3448//3448 -f 3435//3435 3448//3448 3434//3434 -f 3434//3434 3448//3448 3449//3449 -f 3434//3434 3449//3449 3433//3433 -f 3433//3433 3449//3449 3450//3450 -f 3433//3433 3450//3450 3444//3444 -f 3444//3444 3450//3450 3451//3451 -f 3444//3444 3451//3451 3443//3443 -f 3443//3443 3451//3451 3452//3452 -f 3443//3443 3452//3452 3442//3442 -f 3442//3442 3452//3452 3453//3453 -f 3442//3442 3453//3453 3441//3441 -f 3441//3441 3453//3453 3454//3454 -f 3441//3441 3454//3454 3440//3440 -f 3440//3440 3454//3454 3455//3455 -f 3440//3440 3455//3455 3439//3439 -f 3439//3439 3455//3455 3456//3456 -f 3439//3439 3456//3456 3438//3438 -f 3438//3438 3456//3456 3445//3445 -f 3446//3446 3031//3031 3447//3447 -f 3447//3447 3031//3031 3030//3030 -f 3447//3447 3030//3030 3448//3448 -f 3448//3448 3030//3030 3039//3039 -f 3448//3448 3039//3039 3449//3449 -f 3449//3449 3039//3039 3026//3026 -f 3449//3449 3026//3026 3450//3450 -f 3450//3450 3026//3026 3029//3029 -f 3450//3450 3029//3029 3451//3451 -f 3451//3451 3029//3029 3028//3028 -f 3451//3451 3028//3028 3452//3452 -f 3452//3452 3028//3028 3036//3036 -f 3452//3452 3036//3036 3453//3453 -f 3453//3453 3036//3036 3035//3035 -f 3453//3453 3035//3035 3454//3454 -f 3454//3454 3035//3035 3034//3034 -f 3454//3454 3034//3034 3455//3455 -f 3455//3455 3034//3034 3024//3024 -f 3455//3455 3024//3024 3456//3456 -f 3456//3456 3024//3024 3020//3020 -f 3456//3456 3020//3020 3445//3445 -f 3445//3445 3020//3020 3019//3019 -f 3445//3445 3019//3019 3446//3446 -f 3446//3446 3019//3019 3031//3031 -f 3457//3457 3233//3233 3458//3458 -f 3458//3458 3233//3233 3227//3227 -f 3458//3458 3227//3227 3459//3459 -f 3459//3459 3227//3227 3222//3222 -f 3459//3459 3222//3222 3460//3460 -f 3460//3460 3222//3222 3220//3220 -f 3460//3460 3220//3220 3461//3461 -f 3461//3461 3220//3220 3218//3218 -f 3461//3461 3218//3218 3462//3462 -f 3462//3462 3218//3218 3216//3216 -f 3462//3462 3216//3216 3463//3463 -f 3463//3463 3216//3216 3214//3214 -f 3463//3463 3214//3214 3464//3464 -f 3464//3464 3214//3214 3212//3212 -f 3464//3464 3212//3212 3465//3465 -f 3465//3465 3212//3212 3210//3210 -f 3465//3465 3210//3210 3466//3466 -f 3466//3466 3210//3210 3207//3207 -f 3466//3466 3207//3207 3467//3467 -f 3467//3467 3207//3207 3206//3206 -f 3467//3467 3206//3206 3468//3468 -f 3468//3468 3206//3206 3231//3231 -f 3468//3468 3231//3231 3457//3457 -f 3457//3457 3231//3231 3233//3233 -f 3462//3462 3469//3469 3461//3461 -f 3461//3461 3469//3469 3470//3470 -f 3461//3461 3470//3470 3460//3460 -f 3460//3460 3470//3470 3471//3471 -f 3460//3460 3471//3471 3459//3459 -f 3459//3459 3471//3471 3472//3472 -f 3459//3459 3472//3472 3458//3458 -f 3458//3458 3472//3472 3473//3473 -f 3458//3458 3473//3473 3457//3457 -f 3457//3457 3473//3473 3474//3474 -f 3457//3457 3474//3474 3468//3468 -f 3468//3468 3474//3474 3475//3475 -f 3468//3468 3475//3475 3467//3467 -f 3467//3467 3475//3475 3476//3476 -f 3467//3467 3476//3476 3466//3466 -f 3466//3466 3476//3476 3477//3477 -f 3466//3466 3477//3477 3465//3465 -f 3465//3465 3477//3477 3478//3478 -f 3465//3465 3478//3478 3464//3464 -f 3464//3464 3478//3478 3479//3479 -f 3464//3464 3479//3479 3463//3463 -f 3463//3463 3479//3479 3480//3480 -f 3463//3463 3480//3480 3462//3462 -f 3462//3462 3480//3480 3469//3469 -f 3470//3470 3013//3013 3471//3471 -f 3471//3471 3013//3013 3011//3011 -f 3471//3471 3011//3011 3472//3472 -f 3472//3472 3011//3011 3010//3010 -f 3472//3472 3010//3010 3473//3473 -f 3473//3473 3010//3010 2998//2998 -f 3473//3473 2998//2998 3474//3474 -f 3474//3474 2998//2998 2997//2997 -f 3474//3474 2997//2997 3475//3475 -f 3475//3475 2997//2997 3007//3007 -f 3475//3475 3007//3007 3476//3476 -f 3476//3476 3007//3007 2988//2988 -f 3476//3476 2988//2988 3477//3477 -f 3477//3477 2988//2988 2987//2987 -f 3477//3477 2987//2987 3478//3478 -f 3478//3478 2987//2987 2975//2975 -f 3478//3478 2975//2975 3479//3479 -f 3479//3479 2975//2975 3018//3018 -f 3479//3479 3018//3018 3480//3480 -f 3480//3480 3018//3018 3017//3017 -f 3480//3480 3017//3017 3469//3469 -f 3469//3469 3017//3017 3015//3015 -f 3469//3469 3015//3015 3470//3470 -f 3470//3470 3015//3015 3013//3013 -f 3481//3481 3197//3197 3482//3482 -f 3482//3482 3197//3197 3203//3203 -f 3482//3482 3203//3203 3483//3483 -f 3483//3483 3203//3203 3202//3202 -f 3483//3483 3202//3202 3484//3484 -f 3484//3484 3202//3202 3200//3200 -f 3484//3484 3200//3200 3485//3485 -f 3485//3485 3200//3200 3194//3194 -f 3485//3485 3194//3194 3486//3486 -f 3486//3486 3194//3194 3192//3192 -f 3486//3486 3192//3192 3487//3487 -f 3487//3487 3192//3192 3191//3191 -f 3487//3487 3191//3191 3488//3488 -f 3488//3488 3191//3191 3186//3186 -f 3488//3488 3186//3186 3489//3489 -f 3489//3489 3186//3186 3188//3188 -f 3489//3489 3188//3188 3490//3490 -f 3490//3490 3188//3188 3178//3178 -f 3490//3490 3178//3178 3491//3491 -f 3491//3491 3178//3178 3177//3177 -f 3491//3491 3177//3177 3492//3492 -f 3492//3492 3177//3177 3195//3195 -f 3492//3492 3195//3195 3481//3481 -f 3481//3481 3195//3195 3197//3197 -f 3486//3486 3493//3493 3485//3485 -f 3485//3485 3493//3493 3494//3494 -f 3485//3485 3494//3494 3484//3484 -f 3484//3484 3494//3494 3495//3495 -f 3484//3484 3495//3495 3483//3483 -f 3483//3483 3495//3495 3496//3496 -f 3483//3483 3496//3496 3482//3482 -f 3482//3482 3496//3496 3497//3497 -f 3482//3482 3497//3497 3481//3481 -f 3481//3481 3497//3497 3498//3498 -f 3481//3481 3498//3498 3492//3492 -f 3492//3492 3498//3498 3499//3499 -f 3492//3492 3499//3499 3491//3491 -f 3491//3491 3499//3499 3500//3500 -f 3491//3491 3500//3500 3490//3490 -f 3490//3490 3500//3500 3501//3501 -f 3490//3490 3501//3501 3489//3489 -f 3489//3489 3501//3501 3502//3502 -f 3489//3489 3502//3502 3488//3488 -f 3488//3488 3502//3502 3503//3503 -f 3488//3488 3503//3503 3487//3487 -f 3487//3487 3503//3503 3504//3504 -f 3487//3487 3504//3504 3486//3486 -f 3486//3486 3504//3504 3493//3493 -f 3494//3494 2979//2979 3495//3495 -f 3495//3495 2979//2979 2981//2981 -f 3495//3495 2981//2981 3496//3496 -f 3496//3496 2981//2981 2983//2983 -f 3496//3496 2983//2983 3497//3497 -f 3497//3497 2983//2983 2972//2972 -f 3497//3497 2972//2972 3498//3498 -f 3498//3498 2972//2972 2970//2970 -f 3498//3498 2970//2970 3499//3499 -f 3499//3499 2970//2970 2969//2969 -f 3499//3499 2969//2969 3500//3500 -f 3500//3500 2969//2969 2978//2978 -f 3500//3500 2978//2978 3501//3501 -f 3501//3501 2978//2978 2977//2977 -f 3501//3501 2977//2977 3502//3502 -f 3502//3502 2977//2977 3002//3002 -f 3502//3502 3002//3002 3503//3503 -f 3503//3503 3002//3002 2996//2996 -f 3503//3503 2996//2996 3504//3504 -f 3504//3504 2996//2996 2993//2993 -f 3504//3504 2993//2993 3493//3493 -f 3493//3493 2993//2993 2984//2984 -f 3493//3493 2984//2984 3494//3494 -f 3494//3494 2984//2984 2979//2979 -f 2989//2989 3009//3009 2940//2940 -f 2940//2940 2944//2944 2989//2989 -f 2989//2989 2944//2944 2943//2943 -f 2989//2989 2943//2943 2973//2973 -f 2973//2973 2943//2943 2947//2947 -f 2973//2973 2947//2947 3037//3037 -f 3037//3037 2947//2947 2946//2946 -f 3037//3037 2946//2946 3038//3038 -f 2946//2946 2950//2950 3038//3038 -f 3038//3038 2950//2950 2949//2949 -f 3038//3038 2949//2949 3040//3040 -f 2949//2949 2953//2953 3040//3040 -f 3040//3040 2953//2953 2952//2952 -f 3040//3040 2952//2952 3041//3041 -f 2952//2952 2956//2956 3041//3041 -f 3041//3041 2956//2956 2955//2955 -f 3041//3041 2955//2955 3025//3025 -f 2955//2955 2959//2959 3025//3025 -f 3025//3025 2959//2959 2958//2958 -f 3025//3025 2958//2958 2968//2968 -f 2968//2968 2958//2958 3045//3045 -f 3045//3045 2958//2958 2962//2962 -f 3045//3045 2962//2962 3059//3059 -f 3059//3059 2962//2962 2961//2961 -f 3059//3059 2961//2961 3057//3057 -f 2961//2961 2965//2965 3057//3057 -f 3057//3057 2965//2965 2964//2964 -f 3057//3057 2964//2964 3055//3055 -f 3055//3055 2964//2964 2963//2963 -f 3055//3055 2963//2963 3051//3051 -f 2963//2963 2911//2911 3051//3051 -f 3051//3051 2911//2911 2914//2914 -f 3051//3051 2914//2914 3052//3052 -f 2914//2914 2913//2913 3052//3052 -f 3052//3052 2913//2913 2917//2917 -f 3052//3052 2917//2917 2976//2976 -f 2976//2976 2917//2917 2916//2916 -f 2976//2976 2916//2916 3004//3004 -f 3004//3004 2916//2916 2920//2920 -f 3004//3004 2920//2920 3003//3003 -f 2920//2920 2919//2919 3003//3003 -f 3003//3003 2919//2919 2923//2923 -f 3003//3003 2923//2923 3001//3001 -f 2923//2923 2922//2922 3001//3001 -f 3001//3001 2922//2922 2926//2926 -f 3001//3001 2926//2926 3000//3000 -f 2926//2926 2925//2925 3000//3000 -f 3000//3000 2925//2925 2929//2929 -f 3000//3000 2929//2929 2999//2999 -f 2929//2929 2928//2928 2999//2999 -f 2999//2999 2928//2928 2932//2932 -f 2999//2999 2932//2932 3005//3005 -f 2932//2932 2931//2931 3005//3005 -f 3005//3005 2931//2931 2935//2935 -f 3005//3005 2935//2935 3006//3006 -f 2935//2935 2934//2934 3006//3006 -f 3006//3006 2934//2934 2938//2938 -f 3006//3006 2938//2938 3008//3008 -f 3008//3008 2938//2938 2937//2937 -f 3008//3008 2937//2937 3009//3009 -f 3009//3009 2937//2937 2941//2941 -f 3009//3009 2941//2941 2940//2940 -f 3337//3337 3293//3293 3292//3292 -f 3337//3337 3292//3292 3339//3339 -f 3339//3339 3292//3292 3291//3291 -f 3339//3339 3291//3291 3341//3341 -f 3291//3291 3290//3290 3341//3341 -f 3341//3341 3290//3290 3289//3289 -f 3341//3341 3289//3289 3342//3342 -f 3289//3289 3288//3288 3342//3342 -f 3342//3342 3288//3288 3287//3287 -f 3342//3342 3287//3287 3330//3330 -f 3287//3287 3286//3286 3330//3330 -f 3330//3330 3286//3286 3285//3285 -f 3330//3330 3285//3285 3332//3332 -f 3285//3285 3284//3284 3332//3332 -f 3332//3332 3284//3284 3283//3283 -f 3332//3332 3283//3283 3334//3334 -f 3334//3334 3283//3283 3282//3282 -f 3282//3282 3281//3281 3334//3334 -f 3334//3334 3281//3281 3280//3280 -f 3334//3334 3280//3280 3335//3335 -f 3280//3280 3279//3279 3335//3335 -f 3335//3335 3279//3279 3278//3278 -f 3335//3335 3278//3278 3323//3323 -f 3323//3323 3278//3278 3277//3277 -f 3323//3323 3277//3277 3325//3325 -f 3277//3277 3276//3276 3325//3325 -f 3325//3325 3276//3276 3275//3275 -f 3325//3325 3275//3275 3327//3327 -f 3275//3275 3274//3274 3327//3327 -f 3327//3327 3274//3274 3273//3273 -f 3327//3327 3273//3273 3328//3328 -f 3273//3273 3272//3272 3328//3328 -f 3328//3328 3272//3272 3271//3271 -f 3328//3328 3271//3271 3319//3319 -f 3271//3271 3270//3270 3319//3319 -f 3319//3319 3270//3270 3269//3269 -f 3319//3319 3269//3269 3343//3343 -f 3343//3343 3269//3269 3318//3318 -f 3343//3343 3318//3318 3344//3344 -f 3318//3318 3317//3317 3344//3344 -f 3344//3344 3317//3317 3316//3316 -f 3344//3344 3316//3316 3346//3346 -f 3346//3346 3316//3316 3315//3315 -f 3346//3346 3315//3315 3348//3348 -f 3315//3315 3314//3314 3348//3348 -f 3348//3348 3314//3314 3313//3313 -f 3348//3348 3313//3313 3357//3357 -f 3357//3357 3313//3313 3312//3312 -f 3312//3312 3311//3311 3357//3357 -f 3357//3357 3311//3311 3310//3310 -f 3357//3357 3310//3310 3358//3358 -f 3358//3358 3310//3310 3309//3309 -f 3358//3358 3309//3309 3360//3360 -f 3309//3309 3308//3308 3360//3360 -f 3360//3360 3308//3308 3307//3307 -f 3360//3360 3307//3307 3362//3362 -f 3307//3307 3306//3306 3362//3362 -f 3362//3362 3306//3306 3305//3305 -f 3362//3362 3305//3305 3363//3363 -f 3305//3305 3304//3304 3363//3363 -f 3363//3363 3304//3304 3303//3303 -f 3363//3363 3303//3303 3351//3351 -f 3303//3303 3302//3302 3351//3351 -f 3351//3351 3302//3302 3301//3301 -f 3351//3351 3301//3301 3353//3353 -f 3353//3353 3301//3301 3300//3300 -f 3300//3300 3299//3299 3353//3353 -f 3353//3353 3299//3299 3298//3298 -f 3353//3353 3298//3298 3355//3355 -f 3298//3298 3297//3297 3355//3355 -f 3355//3355 3297//3297 3296//3296 -f 3355//3355 3296//3296 3356//3356 -f 3356//3356 3296//3296 3295//3295 -f 3356//3356 3295//3295 3337//3337 -f 3337//3337 3295//3295 3294//3294 -f 3337//3337 3294//3294 3293//3293 -f 3161//3161 3163//3163 3150//3150 -f 3100//3100 3199//3199 3098//3098 -f 3098//3098 3199//3199 3198//3198 -f 3098//3098 3198//3198 3096//3096 -f 3096//3096 3198//3198 3204//3204 -f 3096//3096 3204//3204 3094//3094 -f 3094//3094 3204//3204 3205//3205 -f 3094//3094 3205//3205 3092//3092 -f 3092//3092 3205//3205 3196//3196 -f 3092//3092 3196//3196 3090//3090 -f 3090//3090 3196//3196 3175//3175 -f 3090//3090 3175//3175 3088//3088 -f 3088//3088 3175//3175 3174//3174 -f 3088//3088 3174//3174 3086//3086 -f 3086//3086 3174//3174 3173//3173 -f 3086//3086 3173//3173 3084//3084 -f 3084//3084 3173//3173 3156//3156 -f 3084//3084 3156//3156 3082//3082 -f 3082//3082 3156//3156 3157//3157 -f 3082//3082 3157//3157 3080//3080 -f 3080//3080 3157//3157 3159//3159 -f 3080//3080 3159//3159 3078//3078 -f 3078//3078 3159//3159 3161//3161 -f 3078//3078 3161//3161 3152//3152 -f 3152//3152 3161//3161 3150//3150 -f 3235//3235 3193//3193 3100//3100 -f 3100//3100 3193//3193 3201//3201 -f 3100//3100 3201//3201 3199//3199 -f 3163//3163 3250//3250 3150//3150 -f 3150//3150 3250//3250 3249//3249 -f 3150//3150 3249//3249 3148//3148 -f 3148//3148 3249//3249 3268//3268 -f 3148//3148 3268//3268 3146//3146 -f 3146//3146 3268//3268 3267//3267 -f 3146//3146 3267//3267 3144//3144 -f 3144//3144 3267//3267 3266//3266 -f 3144//3144 3266//3266 3142//3142 -f 3142//3142 3266//3266 3243//3243 -f 3142//3142 3243//3243 3140//3140 -f 3140//3140 3243//3243 3252//3252 -f 3140//3140 3252//3252 3138//3138 -f 3138//3138 3252//3252 3245//3245 -f 3138//3138 3245//3245 3136//3136 -f 3136//3136 3245//3245 3244//3244 -f 3136//3136 3244//3244 3134//3134 -f 3134//3134 3244//3244 3257//3257 -f 3134//3134 3257//3257 3132//3132 -f 3132//3132 3257//3257 3240//3240 -f 3132//3132 3240//3240 3130//3130 -f 3130//3130 3240//3240 3239//3239 -f 3130//3130 3239//3239 3128//3128 -f 3128//3128 3239//3239 3238//3238 -f 3128//3128 3238//3238 3126//3126 -f 3126//3126 3238//3238 3237//3237 -f 3126//3126 3237//3237 3124//3124 -f 3124//3124 3237//3237 3236//3236 -f 3124//3124 3236//3236 3122//3122 -f 3122//3122 3236//3236 3211//3211 -f 3122//3122 3211//3211 3120//3120 -f 3120//3120 3211//3211 3213//3213 -f 3120//3120 3213//3213 3118//3118 -f 3118//3118 3213//3213 3215//3215 -f 3118//3118 3215//3215 3116//3116 -f 3116//3116 3215//3215 3217//3217 -f 3116//3116 3217//3217 3114//3114 -f 3114//3114 3217//3217 3219//3219 -f 3114//3114 3219//3219 3112//3112 -f 3112//3112 3219//3219 3221//3221 -f 3112//3112 3221//3221 3110//3110 -f 3110//3110 3221//3221 3223//3223 -f 3110//3110 3223//3223 3108//3108 -f 3108//3108 3223//3223 3226//3226 -f 3108//3108 3226//3226 3106//3106 -f 3106//3106 3226//3226 3228//3228 -f 3106//3106 3228//3228 3104//3104 -f 3104//3104 3228//3228 3235//3235 -f 3104//3104 3235//3235 3102//3102 -f 3102//3102 3235//3235 3100//3100 -f 3095//3095 2982//2982 3097//3097 -f 3097//3097 2982//2982 2980//2980 -f 3097//3097 2980//2980 3099//3099 -f 3099//3099 2980//2980 2986//2986 -f 3099//3099 2986//2986 3101//3101 -f 3101//3101 2986//2986 2985//2985 -f 3101//3101 2985//2985 3103//3103 -f 3103//3103 2985//2985 2995//2995 -f 3103//3103 2995//2995 3105//3105 -f 3105//3105 2995//2995 2994//2994 -f 3105//3105 2994//2994 3107//3107 -f 3107//3107 2994//2994 2992//2992 -f 3107//3107 2992//2992 3109//3109 -f 3109//3109 2992//2992 2991//2991 -f 3109//3109 2991//2991 3111//3111 -f 3111//3111 2991//2991 3012//3012 -f 3111//3111 3012//3012 3113//3113 -f 3113//3113 3012//3012 3014//3014 -f 3113//3113 3014//3014 3115//3115 -f 3115//3115 3014//3014 3016//3016 -f 3115//3115 3016//3016 3117//3117 -f 3117//3117 3016//3016 2974//2974 -f 3117//3117 2974//2974 3119//3119 -f 2974//2974 3032//3032 3119//3119 -f 3119//3119 3032//3032 3033//3033 -f 3119//3119 3033//3033 3121//3121 -f 3121//3121 3033//3033 3044//3044 -f 3121//3121 3044//3044 3123//3123 -f 3123//3123 3044//3044 3043//3043 -f 3123//3123 3043//3043 3125//3125 -f 3125//3125 3043//3043 3042//3042 -f 3125//3125 3042//3042 3127//3127 -f 3127//3127 3042//3042 3021//3021 -f 3127//3127 3021//3021 3129//3129 -f 3129//3129 3021//3021 3027//3027 -f 3129//3129 3027//3027 3131//3131 -f 3131//3131 3027//3027 3023//3023 -f 3131//3131 3023//3023 3133//3133 -f 3133//3133 3023//3023 3022//3022 -f 3133//3133 3022//3022 3135//3135 -f 3135//3135 3022//3022 2967//2967 -f 3135//3135 2967//2967 3137//3137 -f 3137//3137 2967//2967 2966//2966 -f 3137//3137 2966//2966 3139//3139 -f 3139//3139 2966//2966 3050//3050 -f 3139//3139 3050//3050 3141//3141 -f 3141//3141 3050//3050 3049//3049 -f 3141//3141 3049//3049 3143//3143 -f 3143//3143 3049//3049 3048//3048 -f 3143//3143 3048//3048 3145//3145 -f 3145//3145 3048//3048 3047//3047 -f 3145//3145 3047//3047 3147//3147 -f 3147//3147 3047//3047 3046//3046 -f 3147//3147 3046//3046 3149//3149 -f 3149//3149 3046//3046 3063//3063 -f 3149//3149 3063//3063 3151//3151 -f 3151//3151 3063//3063 3065//3065 -f 3151//3151 3065//3065 3153//3153 -f 3153//3153 3065//3065 3067//3067 -f 3153//3153 3067//3067 3079//3079 -f 3079//3079 3067//3067 3069//3069 -f 3079//3079 3069//3069 3081//3081 -f 3081//3081 3069//3069 3071//3071 -f 3081//3081 3071//3071 3083//3083 -f 3083//3083 3071//3071 3077//3077 -f 3083//3083 3077//3077 3085//3085 -f 3085//3085 3077//3077 3076//3076 -f 3085//3085 3076//3076 3087//3087 -f 3087//3087 3076//3076 3075//3075 -f 3087//3087 3075//3075 3089//3089 -f 3089//3089 3075//3075 3074//3074 -f 3089//3089 3074//3074 3091//3091 -f 3091//3091 3074//3074 3073//3073 -f 3091//3091 3073//3073 3093//3093 -f 3093//3093 3073//3073 2971//2971 -f 3093//3093 2971//2971 3095//3095 -f 3095//3095 2971//2971 2990//2990 -f 3095//3095 2990//2990 2982//2982 -# 7304 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_screws.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_screws.obj deleted file mode 100644 index b35494a99..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotArmMemristor2/mid_upper_screws.obj +++ /dev/null @@ -1,30812 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mid_upper_srafovi.obj -# -# Vertices: 7704 -# Faces: 15388 -# -#### -vn -0.742190 0.448556 0.497946 -v 0.054806 0.071258 0.181097 -vn -0.742746 0.498206 0.447347 -v 0.054806 0.071436 0.180919 -vn -0.865261 0.366073 0.342512 -v 0.054541 0.071111 0.180682 -vn -0.865308 0.413258 0.283656 -v 0.054541 0.071303 0.180443 -vn -0.865231 0.234646 -0.443077 -v 0.054541 0.070584 0.177537 -vn -0.865042 0.298309 -0.403378 -v 0.054541 0.070844 0.177701 -vn -0.742975 0.392567 -0.542107 -v 0.054806 0.071062 0.177365 -vn -0.865384 -0.338013 -0.369943 -v 0.054541 0.068297 0.177831 -vn -0.865516 -0.277805 -0.416781 -v 0.054541 0.068538 0.177642 -vn -0.742386 -0.394307 -0.541650 -v 0.054806 0.068236 0.177365 -vn -0.918072 -0.365753 0.152868 -v 0.054327 0.068195 0.179918 -vn -0.958825 -0.262079 0.109407 -v 0.054164 0.068612 0.179744 -vn -0.958878 -0.275505 0.068192 -v 0.054164 0.068558 0.179581 -vn -0.918071 0.193812 0.345807 -v 0.054327 0.070420 0.180685 -vn -0.957141 0.137494 0.254906 -v 0.054164 0.070199 0.180291 -vn -0.958824 0.099287 0.266082 -v 0.054164 0.070043 0.180364 -vn -0.817598 -0.193712 -0.542227 -v 0.054057 0.069879 0.179926 -vn -0.819720 -0.119252 -0.560213 -v 0.054057 0.069782 0.179954 -vn -0.990509 0.118549 0.069560 -v 0.054205 0.068729 0.180164 -vn -0.960998 -0.094485 0.259916 -v 0.054164 0.068791 0.180037 -vn -0.916743 -0.306212 0.256548 -v 0.054327 0.068446 0.180328 -vn -0.986136 0.077823 -0.146559 -v 0.054205 0.068426 0.179031 -vn -0.955900 -0.293132 -0.018127 -v 0.054164 0.068527 0.179239 -vn -0.741450 0.191151 -0.643206 -v 0.054117 0.068707 0.179194 -vn -0.741745 -0.458906 0.489101 -v 0.054117 0.069077 0.178553 -vn -0.955245 -0.157478 -0.250416 -v 0.054164 0.069026 0.178374 -vn -0.722517 -0.504810 0.472373 -v 0.054164 0.068917 0.178460 -vn -0.989992 0.122054 0.070836 -v 0.054205 0.069928 0.178087 -vn -0.960998 0.177833 -0.211798 -v 0.054164 0.069849 0.178204 -vn -0.746583 0.636530 0.193501 -v 0.054117 0.069766 0.178368 -vn -0.930928 -0.138233 0.338030 -v 0.054202 0.070536 0.178436 -vn -0.915046 0.287011 -0.283401 -v 0.054327 0.070771 0.178203 -vn -0.915925 0.238997 -0.322432 -v 0.054327 0.070588 0.178045 -vn -0.987367 0.086963 -0.132454 -v 0.054205 0.070503 0.180230 -vn -0.958030 0.186830 0.217424 -v 0.054164 0.070342 0.180196 -vn -0.916787 0.244478 0.315805 -v 0.054327 0.070620 0.180551 -vn -0.708537 0.106311 -0.697620 -v 0.054057 0.069934 0.179902 -vn -0.743661 0.457633 -0.487381 -v 0.054117 0.070221 0.180068 -vn -0.931344 -0.334835 -0.143120 -v 0.054199 0.070549 0.180157 -vn -0.958850 0.269586 -0.089050 -v 0.054164 0.070717 0.178957 -vn -0.958891 0.252610 -0.129295 -v 0.054164 0.070650 0.178799 -vn -0.710340 -0.694536 -0.114179 -v 0.054057 0.070241 0.179025 -vn -0.958593 0.232579 -0.164334 -v 0.054164 0.070561 0.178652 -vn -0.763723 -0.469162 -0.443412 -v 0.054117 0.070407 0.178738 -vn -0.986587 -0.134203 -0.092923 -v 0.054205 0.070569 0.178457 -vn -0.916877 0.324810 -0.232022 -v 0.054327 0.070926 0.178387 -vn -0.932145 -0.172218 0.318506 -v 0.054189 0.070253 0.178265 -vn -0.915798 0.187070 -0.355413 -v 0.054327 0.070384 0.177917 -vn -0.931962 -0.196535 0.304666 -v 0.054190 0.070212 0.178242 -vn -0.915633 0.132259 -0.379636 -v 0.054327 0.070163 0.177821 -vn -0.916351 0.068387 -0.394493 -v 0.054327 0.069929 0.177760 -vn -0.957930 -0.117885 -0.261673 -v 0.054164 0.069176 0.178290 -vn -0.917046 -0.219274 -0.333084 -v 0.054327 0.068776 0.177999 -vn -0.914816 -0.272386 -0.298190 -v 0.054327 0.068586 0.178147 -vn -0.986262 -0.088111 0.139730 -v 0.054205 0.068796 0.178390 -vn -0.915362 -0.314320 -0.251625 -v 0.054327 0.068421 0.178323 -vn -0.931781 0.328669 0.154144 -v 0.054193 0.068700 0.178545 -vn -0.915916 -0.347697 -0.200510 -v 0.054327 0.068284 0.178522 -vn -0.932864 0.311777 0.180443 -v 0.054189 0.068604 0.178707 -vn -0.915808 -0.374301 -0.145582 -v 0.054327 0.068180 0.178740 -vn -0.932195 0.296399 0.207750 -v 0.054193 0.068512 0.178871 -vn -0.915164 -0.393516 -0.087296 -v 0.054327 0.068110 0.178971 -vn -0.864976 -0.490237 -0.107165 -v 0.054541 0.067692 0.178879 -vn -0.813365 0.577408 -0.070975 -v 0.054057 0.068995 0.179369 -vn -0.705386 0.562215 -0.431677 -v 0.054057 0.068994 0.179359 -vn -0.957939 -0.285531 0.028729 -v 0.054164 0.068529 0.179411 -vn -0.931721 0.147928 -0.331683 -v 0.054196 0.068843 0.180235 -vn -0.957557 0.018664 0.287640 -v 0.054164 0.069707 0.180433 -vn -0.709967 -0.445029 -0.545799 -v 0.054057 0.069698 0.179966 -vn -0.742149 -0.642024 -0.192407 -v 0.054117 0.069532 0.180253 -vn -0.958850 0.057675 0.277993 -v 0.054164 0.069877 0.180412 -vn -0.815448 0.087189 0.572226 -v 0.054057 0.069565 0.178659 -vn -0.958879 -0.078695 -0.272688 -v 0.054164 0.069337 0.178230 -vn -0.820943 0.158398 0.548600 -v 0.054057 0.069467 0.178679 -vn -0.812645 0.229274 0.535763 -v 0.054057 0.069373 0.178714 -vn -0.703082 -0.092050 0.705126 -v 0.054057 0.069364 0.178718 -vn -0.986865 -0.076289 0.142398 -v 0.054205 0.070873 0.179590 -vn -0.958033 0.281698 0.053099 -v 0.054164 0.070763 0.179468 -vn -0.743659 -0.193266 0.640015 -v 0.054117 0.070591 0.179427 -vn -0.957141 0.289502 -0.008382 -v 0.054164 0.070774 0.179296 -vn -0.708534 -0.551003 0.440880 -v 0.054057 0.070304 0.179261 -vn -0.958824 0.280075 -0.047055 -v 0.054164 0.070758 0.179125 -vn -0.817599 -0.566437 0.103355 -v 0.054057 0.070297 0.179202 -vn -0.819714 -0.544793 0.176831 -v 0.054057 0.070273 0.179104 -vn -0.820946 0.554296 -0.137125 -v 0.054057 0.069011 0.179468 -vn -0.815459 0.539133 -0.210624 -v 0.054057 0.069043 0.179564 -vn -0.707129 0.699960 0.100127 -v 0.054057 0.069057 0.179596 -vn -0.918072 -0.166766 -0.359628 -v 0.054327 0.068986 0.177881 -vn -0.865252 0.308346 0.395299 -v 0.054541 0.070885 0.180889 -vn -0.746583 0.485848 0.454495 -v 0.054117 0.068892 0.179883 -vn -0.956722 -0.250934 0.147360 -v 0.054164 0.068690 0.179897 -vn -0.918071 -0.338133 0.206909 -v 0.054327 0.068305 0.180133 -vn -0.865322 -0.427837 0.261101 -v 0.054541 0.067939 0.180357 -vn -0.918073 -0.109916 -0.380868 -v 0.054327 0.069212 0.177796 -vn -0.865449 -0.139275 -0.481249 -v 0.054541 0.069093 0.177385 -vn -0.865365 -0.210496 -0.454791 -v 0.054541 0.068806 0.177492 -vn -0.865335 -0.063289 -0.497181 -v 0.054541 0.069394 0.177322 -vn -0.918071 -0.050488 -0.393188 -v 0.054327 0.069448 0.177747 -vn -0.958826 -0.036292 -0.281667 -v 0.054164 0.069506 0.178195 -vn -0.707134 0.436717 0.556094 -v 0.054057 0.069600 0.178655 -vn -0.956722 0.002152 -0.290997 -v 0.054164 0.069678 0.178186 -vn -0.918071 0.010129 -0.396288 -v 0.054327 0.069689 0.177735 -vn -0.865350 0.012247 -0.501019 -v 0.054541 0.069700 0.177307 -vn -0.742614 -0.000863 -0.669719 -v 0.054806 0.069649 0.176906 -vn -0.742145 0.070016 -0.666572 -v 0.054806 0.069900 0.176919 -vn -0.865212 0.162774 -0.474249 -v 0.054541 0.070303 0.177415 -vn -0.865292 0.089842 -0.493151 -v 0.054541 0.070006 0.177338 -vn -0.865160 0.357579 -0.351618 -v 0.054541 0.071076 0.177902 -vn -0.864834 0.406297 -0.294932 -v 0.054541 0.071274 0.178136 -vn -0.918072 0.352976 -0.180423 -v 0.054327 0.071052 0.178593 -vn -0.865552 0.445930 -0.227960 -v 0.054541 0.071434 0.178398 -vn -0.918072 0.376380 -0.124424 -v 0.054327 0.071145 0.178816 -vn -0.865388 0.475819 -0.157163 -v 0.054541 0.071552 0.178681 -vn -0.918071 0.390965 -0.065510 -v 0.054327 0.071203 0.179050 -vn -0.865531 0.493939 -0.082942 -v 0.054541 0.071626 0.178979 -vn -0.918071 0.396383 -0.005060 -v 0.054327 0.071225 0.179290 -vn -0.865375 0.501089 -0.006092 -v 0.054541 0.071653 0.179285 -vn -0.916471 0.396553 0.053170 -v 0.054327 0.071209 0.179531 -vn -0.865476 0.496062 0.069813 -v 0.054541 0.071634 0.179591 -vn -0.915268 0.385197 0.117930 -v 0.054327 0.071157 0.179767 -vn -0.865347 0.479568 0.145567 -v 0.054541 0.071568 0.179891 -vn -0.915712 0.362522 0.173346 -v 0.054327 0.071070 0.179992 -vn -0.865386 0.452089 0.216155 -v 0.054541 0.071457 0.180177 -vn -0.915761 0.331490 0.226926 -v 0.054327 0.070950 0.180200 -vn -0.915306 0.293768 0.275528 -v 0.054327 0.070798 0.180389 -vn -0.865098 0.024513 0.501003 -v 0.054541 0.069752 0.181312 -vn -0.916718 -0.038154 0.397710 -v 0.054327 0.069488 0.180878 -vn -0.864671 -0.050032 0.499840 -v 0.054541 0.069445 0.181304 -vn -0.915089 -0.102936 0.389892 -v 0.054327 0.069251 0.180835 -vn -0.865541 -0.126408 0.484623 -v 0.054541 0.069143 0.181250 -vn -0.915729 -0.159499 0.368783 -v 0.054327 0.069023 0.180756 -vn -0.865380 -0.199363 0.459752 -v 0.054541 0.068853 0.181150 -vn -0.915747 -0.214091 0.339960 -v 0.054327 0.068810 0.180644 -vn -0.865499 -0.266650 0.424039 -v 0.054541 0.068581 0.181007 -vn -0.915524 -0.263742 0.303736 -v 0.054327 0.068616 0.180500 -vn -0.865355 -0.328952 0.378088 -v 0.054541 0.068335 0.180824 -vn -0.986145 -0.146478 -0.077859 -v 0.054205 0.069370 0.180534 -vn -0.932109 0.204014 -0.299252 -v 0.054192 0.069168 0.180425 -vn -0.932642 0.177761 -0.313975 -v 0.054189 0.069046 0.180356 -vn -0.865418 -0.382170 0.324032 -v 0.054541 0.068119 0.180605 -vn -0.742553 -0.497211 0.448772 -v 0.054806 0.067862 0.180919 -vn -0.742175 -0.542232 0.393905 -v 0.054806 0.067704 0.180724 -vn -0.918072 -0.394831 0.035391 -v 0.054327 0.068080 0.179451 -vn -0.865160 -0.499425 0.045536 -v 0.054541 0.067653 0.179489 -vn -0.865272 -0.486802 0.119700 -v 0.054541 0.067703 0.179792 -vn -0.865209 -0.500331 -0.032913 -v 0.054541 0.067649 0.179182 -vn -0.917047 -0.398094 -0.023355 -v 0.054327 0.068077 0.179210 -vn -0.743047 -0.654836 -0.138098 -v 0.054806 0.067297 0.178811 -vn -0.865550 -0.390464 -0.313626 -v 0.054541 0.068087 0.178055 -vn -0.864754 -0.435484 -0.250107 -v 0.054541 0.067913 0.178308 -vn -0.865130 -0.467158 -0.182517 -v 0.054541 0.067781 0.178585 -vn -0.742198 -0.334882 -0.580515 -v 0.054806 0.068447 0.177228 -vn -0.742611 -0.069176 -0.666140 -v 0.054806 0.069398 0.176919 -vn -0.742168 -0.139249 -0.655589 -v 0.054806 0.069149 0.176959 -vn -0.742496 -0.207719 -0.636830 -v 0.054806 0.068906 0.177024 -vn -0.742499 -0.271953 -0.612157 -v 0.054806 0.068671 0.177114 -vn -0.743070 0.335799 -0.578867 -v 0.054806 0.070851 0.177228 -vn -0.742197 0.272417 -0.612317 -v 0.054806 0.070627 0.177114 -vn -0.742783 0.205996 -0.637054 -v 0.054806 0.070392 0.177024 -vn -0.742810 0.140276 -0.654642 -v 0.054806 0.070149 0.176959 -vn -0.742235 0.448159 -0.498238 -v 0.054806 0.071258 0.177524 -vn -0.742273 0.612334 -0.272173 -v 0.054806 0.071846 0.178332 -vn -0.742285 0.580079 -0.335441 -v 0.054806 0.071731 0.178108 -vn -0.743178 0.540658 -0.394177 -v 0.054806 0.071594 0.177897 -vn -0.743388 0.498156 -0.446335 -v 0.054806 0.071436 0.177702 -vn -0.742204 0.666532 -0.069769 -v 0.054806 0.072040 0.179059 -vn -0.742366 0.655229 -0.139884 -v 0.054806 0.072001 0.178811 -vn -0.742384 0.637240 -0.206859 -v 0.054806 0.071936 0.178567 -vn -0.742190 0.655516 0.139476 -v 0.054806 0.072001 0.179810 -vn -0.742455 0.666300 0.069317 -v 0.054806 0.072040 0.179562 -vn -0.742453 0.669898 0.000462 -v 0.054806 0.072053 0.179310 -vn -0.742748 0.541089 0.394397 -v 0.054806 0.071594 0.180724 -vn -0.742176 0.580418 0.335097 -v 0.054806 0.071731 0.180513 -vn -0.742600 0.612172 0.271644 -v 0.054806 0.071846 0.180288 -vn -0.742580 0.636746 0.207675 -v 0.054806 0.071936 0.180053 -vn -0.742987 0.392373 0.542231 -v 0.054806 0.071062 0.181255 -vn -0.932415 -0.316213 -0.174965 -v 0.054189 0.070694 0.179914 -vn -0.932025 -0.302031 -0.200265 -v 0.054190 0.070741 0.179833 -vn -0.918071 0.138747 0.371343 -v 0.054327 0.070201 0.180787 -vn -0.865101 0.245955 0.437157 -v 0.054541 0.070629 0.181059 -vn -0.742907 0.335573 0.579206 -v 0.054806 0.070851 0.181393 -vn -0.865182 0.174608 0.470076 -v 0.054541 0.070351 0.181188 -vn -0.743294 0.205244 0.636701 -v 0.054806 0.070392 0.181597 -vn -0.742221 0.272833 0.612104 -v 0.054806 0.070627 0.181507 -vn -0.918071 0.080437 0.388170 -v 0.054327 0.069969 0.180853 -vn -0.956363 -0.031716 0.290454 -v 0.054164 0.069534 0.180429 -vn -0.918070 0.020236 0.395902 -v 0.054327 0.069730 0.180884 -vn -0.864904 0.102837 0.491290 -v 0.054541 0.070056 0.181273 -vn -0.743133 0.140190 0.654293 -v 0.054806 0.070149 0.181662 -vn -0.742270 0.070464 0.666386 -v 0.054806 0.069900 0.181701 -vn -0.742249 -0.207390 0.637225 -v 0.054806 0.068906 0.181597 -vn -0.742354 -0.138757 0.655482 -v 0.054806 0.069149 0.181662 -vn -0.743349 -0.068775 0.665359 -v 0.054806 0.069398 0.181701 -vn -0.743619 -0.001814 0.668601 -v 0.054806 0.069649 0.181715 -vn -0.742537 -0.448676 0.497321 -v 0.054806 0.068040 0.181097 -vn -0.742178 -0.394100 0.542086 -v 0.054806 0.068236 0.181255 -vn -0.742432 -0.334370 0.580510 -v 0.054806 0.068447 0.181393 -vn -0.742441 -0.272812 0.611846 -v 0.054806 0.068671 0.181507 -vn -0.742694 -0.580380 0.334014 -v 0.054806 0.067567 0.180513 -vn -0.918072 -0.384801 0.095244 -v 0.054327 0.068120 0.179689 -vn -0.865307 -0.462240 0.193850 -v 0.054541 0.067800 0.180083 -vn -0.742680 -0.611390 0.273182 -v 0.054806 0.067453 0.180288 -vn -0.742187 -0.637363 0.207189 -v 0.054806 0.067363 0.180053 -vn -0.743176 -0.665276 -0.071396 -v 0.054806 0.067258 0.179059 -vn -0.742195 -0.670184 0.000233 -v 0.054806 0.067245 0.179310 -vn -0.742858 -0.665677 0.070963 -v 0.054806 0.067258 0.179562 -vn -0.742913 -0.655008 0.138003 -v 0.054806 0.067297 0.179810 -vn -0.742249 -0.637442 -0.206722 -v 0.054806 0.067363 0.178567 -vn -0.742421 -0.448066 -0.498045 -v 0.054806 0.068040 0.177524 -vn -0.742252 -0.497745 -0.448678 -v 0.054806 0.067862 0.177702 -vn -0.742310 -0.542388 -0.393435 -v 0.054806 0.067704 0.177897 -vn -0.743265 -0.579937 -0.333512 -v 0.054806 0.067567 0.178108 -vn -0.743489 -0.610225 -0.273586 -v 0.054806 0.067453 0.178332 -vn -0.719738 0.598599 -0.351650 -v 0.055503 0.069105 0.179423 -vn -0.676644 0.665442 -0.315182 -v 0.055503 0.068986 0.179355 -vn -0.676660 -0.059837 -0.733860 -v 0.055503 0.069942 0.179907 -vn -0.719588 0.005399 -0.694380 -v 0.055503 0.069824 0.179838 -vn -0.676650 0.059803 0.733872 -v 0.055503 0.069356 0.178714 -vn -0.719728 -0.005223 0.694237 -v 0.055503 0.069475 0.178782 -vn -0.719604 -0.598648 0.351841 -v 0.055503 0.070194 0.179197 -vn -0.676656 -0.665454 0.315132 -v 0.055503 0.070312 0.179266 -vn -0.763194 0.566413 0.310984 -v 0.055503 0.069138 0.179091 -vn -0.446271 0.775003 0.447452 -v 0.055494 0.069167 0.179032 -vn -0.763196 0.552524 0.335037 -v 0.055503 0.069204 0.178978 -vn -0.763187 -0.566416 -0.310996 -v 0.055503 0.070160 0.179530 -vn -0.446037 -0.775101 -0.447514 -v 0.055494 0.070131 0.179589 -vn -0.763189 -0.552534 -0.335035 -v 0.055503 0.070095 0.179643 -vn -0.765428 0.297494 -0.570629 -v 0.055503 0.069430 0.179821 -vn -0.676655 -0.315140 -0.665451 -v 0.055503 0.069694 0.179974 -vn -0.989931 0.012241 -0.141023 -v 0.055503 0.069608 0.179865 -vn -0.724842 -0.343230 -0.597325 -v 0.055503 0.069762 0.179855 -vn -0.989676 -0.097013 -0.105496 -v 0.055503 0.070057 0.179689 -vn -0.989473 -0.064996 -0.129305 -v 0.055503 0.069852 0.179828 -vn -0.989471 -0.144492 0.008359 -v 0.055503 0.070199 0.179228 -vn -0.989677 -0.139862 -0.031268 -v 0.055503 0.070180 0.179474 -vn -0.724835 -0.688921 0.001394 -v 0.055503 0.070177 0.179136 -vn -0.676651 -0.733871 0.059798 -v 0.055503 0.070246 0.179017 -vn -0.989930 -0.116012 0.081117 -v 0.055503 0.070109 0.178997 -vn -0.765429 -0.345428 0.542954 -v 0.055503 0.069982 0.178865 -vn -0.765431 -0.297482 0.570632 -v 0.055503 0.069868 0.178799 -vn -0.676655 0.315139 0.665451 -v 0.055503 0.069605 0.178647 -vn -0.989929 -0.012249 0.141031 -v 0.055503 0.069691 0.178756 -vn -0.724926 0.343154 0.597267 -v 0.055503 0.069536 0.178766 -vn -0.989678 0.097013 0.105483 -v 0.055503 0.069242 0.178932 -vn -0.989473 0.064989 0.129308 -v 0.055503 0.069446 0.178793 -vn -0.989473 0.144475 -0.008373 -v 0.055503 0.069099 0.179393 -vn -0.989678 0.139857 0.031275 -v 0.055503 0.069118 0.179146 -vn -0.281332 -0.479790 0.831056 -v 0.055494 0.069927 0.178828 -vn -0.281154 0.479827 -0.831095 -v 0.055494 0.069371 0.179792 -vn -0.765431 0.345436 -0.542945 -v 0.055503 0.069316 0.179756 -vn -0.676656 0.733866 -0.059822 -v 0.055503 0.069053 0.179604 -vn -0.724925 0.688826 -0.001457 -v 0.055503 0.069121 0.179485 -vn 0.131319 0.638293 -0.758510 -v 0.056203 0.070479 0.178376 -vn 0.675623 0.540431 -0.501465 -v 0.064103 0.070565 0.178460 -vn 0.675613 0.368630 -0.638482 -v 0.064103 0.070274 0.178228 -vn 0.025720 0.747243 -0.664053 -v 0.056203 0.070565 0.178460 -vn 0.123930 0.801480 -0.585040 -v 0.056203 0.070650 0.178562 -vn 0.675346 0.664634 -0.319639 -v 0.064103 0.070775 0.178768 -vn 0.126952 0.872198 -0.472392 -v 0.056203 0.070775 0.178768 -vn 0.675376 0.729178 -0.110299 -v 0.064103 0.070885 0.179124 -vn 0.133175 0.916060 -0.378284 -v 0.056203 0.070781 0.178779 -vn 0.131755 0.956442 -0.260498 -v 0.056203 0.070864 0.179018 -vn 0.037876 0.991619 -0.123520 -v 0.056203 0.070885 0.179124 -vn 0.124698 0.991851 -0.026118 -v 0.056203 0.070898 0.179268 -vn 0.675353 0.729198 0.110310 -v 0.064103 0.070885 0.179497 -vn 0.120427 0.987249 0.104095 -v 0.056203 0.070885 0.179497 -vn 0.675379 0.664613 0.319615 -v 0.064103 0.070775 0.179853 -vn 0.133040 0.968485 0.210562 -v 0.056203 0.070881 0.179521 -vn 0.131595 0.934624 0.330394 -v 0.056203 0.070814 0.179764 -vn 0.049917 0.886565 0.459902 -v 0.056203 0.070775 0.179853 -vn 0.125380 0.830988 0.541977 -v 0.056203 0.070699 0.179989 -vn 0.675362 0.540346 0.501909 -v 0.064103 0.070565 0.180161 -vn 0.113721 0.755227 0.645523 -v 0.056203 0.070565 0.180161 -vn 0.675378 0.369091 0.638464 -v 0.064103 0.070274 0.180393 -vn 0.133001 0.676331 0.724491 -v 0.056203 0.070540 0.180187 -vn 0.131521 0.580294 0.803717 -v 0.056203 0.070346 0.180348 -vn 0.105701 0.257285 0.960537 -v 0.056203 0.069927 0.180529 -vn 0.675574 0.163915 0.718841 -v 0.064103 0.069927 0.180529 -vn 0.126194 0.375864 0.918042 -v 0.056203 0.070123 0.180467 -vn 0.061768 0.469676 0.880675 -v 0.056203 0.070274 0.180393 -vn 0.131168 0.142754 0.981028 -v 0.056203 0.069880 0.180539 -vn 0.131331 0.019492 0.991147 -v 0.056203 0.069628 0.180560 -vn 0.675573 -0.054936 0.735244 -v 0.064103 0.069556 0.180557 -vn 0.099903 -0.333478 0.937450 -v 0.056203 0.069192 0.180474 -vn 0.675544 -0.269554 0.686280 -v 0.064103 0.069192 0.180474 -vn 0.126979 -0.212219 0.968937 -v 0.056203 0.069377 0.180530 -vn 0.073393 -0.111570 0.991043 -v 0.056203 0.069556 0.180557 -vn 0.131457 -0.441226 0.887716 -v 0.056203 0.069137 0.180451 -vn 0.131336 -0.548262 0.825929 -v 0.056203 0.068918 0.180324 -vn 0.675549 -0.459563 0.576572 -v 0.064103 0.068870 0.180288 -vn 0.094731 -0.807181 0.582653 -v 0.056203 0.068616 0.180015 -vn 0.675519 -0.609347 0.415175 -v 0.064103 0.068616 0.180015 -vn 0.127622 -0.725092 0.676723 -v 0.056203 0.068729 0.180156 -vn 0.084931 -0.652445 0.753062 -v 0.056203 0.068870 0.180288 -vn 0.131415 -0.868104 0.478671 -v 0.056203 0.068577 0.179954 -vn 0.131330 -0.920917 0.366966 -v 0.056203 0.068470 0.179725 -vn 0.675514 -0.704524 0.217548 -v 0.064103 0.068455 0.179679 -vn 0.090610 -0.995664 0.021051 -v 0.056203 0.068399 0.179310 -vn 0.675489 -0.737370 -0.000266 -v 0.064103 0.068399 0.179310 -vn 0.128395 -0.981079 0.144909 -v 0.056203 0.068411 0.179479 -vn 0.095899 -0.963095 0.251498 -v 0.056203 0.068455 0.179679 -vn 0.131529 -0.986186 -0.100688 -v 0.056203 0.068402 0.179226 -vn 0.131414 -0.966058 -0.222402 -v 0.056203 0.068445 0.178977 -vn 0.675472 -0.704701 -0.217103 -v 0.064103 0.068455 0.178942 -vn 0.087402 -0.831527 -0.548564 -v 0.056203 0.068616 0.178606 -vn 0.675448 -0.609098 -0.415656 -v 0.064103 0.068616 0.178606 -vn 0.129151 -0.889598 -0.438105 -v 0.056203 0.068536 0.178741 -vn 0.106336 -0.935594 -0.336684 -v 0.056203 0.068455 0.178942 -vn 0.131613 -0.753440 -0.644210 -v 0.056203 0.068674 0.178529 -vn 0.131405 -0.667412 -0.733003 -v 0.056203 0.068851 0.178348 -vn 0.675438 -0.460004 -0.576351 -v 0.064103 0.068870 0.178333 -vn 0.085298 -0.372495 -0.924106 -v 0.056203 0.069192 0.178147 -vn 0.675402 -0.269107 -0.686596 -v 0.064103 0.069192 0.178147 -vn 0.129925 -0.483134 -0.865853 -v 0.056203 0.069061 0.178207 -vn 0.115973 -0.580910 -0.805663 -v 0.056203 0.068870 0.178333 -vn 0.131844 -0.252617 -0.958541 -v 0.056203 0.069295 0.178112 -vn 0.131457 -0.131465 -0.982566 -v 0.056203 0.069544 0.178065 -vn 0.675385 -0.055446 -0.735378 -v 0.064103 0.069556 0.178064 -vn 0.124252 -0.024620 -0.991945 -v 0.056203 0.069556 0.178064 -vn 0.130602 0.094331 -0.986937 -v 0.056203 0.069797 0.178069 -vn 0.675624 0.164069 -0.718759 -v 0.064103 0.069927 0.178092 -vn 0.084096 0.218766 -0.972147 -v 0.056203 0.069927 0.178092 -vn 0.131271 0.337750 -0.932037 -v 0.056203 0.070043 0.178124 -vn 0.131662 0.495643 -0.858489 -v 0.056203 0.070274 0.178228 -vn 0.992502 -0.089999 0.082707 -v 0.056103 0.068655 0.180224 -vn 0.992498 -0.071531 0.099153 -v 0.056103 0.068859 0.180405 -vn 0.688133 -0.362794 0.628374 -v 0.056103 0.068399 0.181475 -vn 0.992500 -0.050098 0.111508 -v 0.056103 0.069096 0.180542 -vn 0.688131 -0.224217 0.690075 -v 0.056103 0.068877 0.181688 -vn 0.992500 -0.026626 0.119312 -v 0.056103 0.069355 0.180628 -vn 0.688132 -0.075841 0.721611 -v 0.056103 0.069388 0.181797 -vn 0.992499 -0.002064 0.122235 -v 0.056103 0.069626 0.180660 -vn 0.688132 0.075841 0.721611 -v 0.056103 0.069910 0.181797 -vn 0.992500 0.022580 0.120138 -v 0.056103 0.069899 0.180637 -vn 0.688130 0.224217 0.690075 -v 0.056103 0.070422 0.181688 -vn 0.992501 0.046298 0.113126 -v 0.056103 0.070161 0.180560 -vn 0.688133 0.362794 0.628374 -v 0.056103 0.070899 0.181475 -vn 0.992499 0.068132 0.101506 -v 0.056103 0.070402 0.180431 -vn 0.688133 0.485511 0.539214 -v 0.056103 0.071322 0.181168 -vn 0.992500 0.087168 0.085706 -v 0.056103 0.070612 0.180257 -vn 0.688132 0.587012 0.426487 -v 0.056103 0.071672 0.180780 -vn 0.992499 0.102642 0.066412 -v 0.056103 0.070783 0.180044 -vn 0.688131 0.662856 0.295123 -v 0.056103 0.071933 0.180327 -vn 0.992500 0.113899 0.044385 -v 0.056103 0.070907 0.179801 -vn 0.688130 0.709732 0.150858 -v 0.056103 0.072095 0.179830 -vn 0.992498 0.120519 0.020552 -v 0.056103 0.070980 0.179537 -vn 0.688132 0.725585 -0.000001 -v 0.056103 0.072149 0.179310 -vn 0.992499 0.122184 -0.004130 -v 0.056103 0.070998 0.179265 -vn 0.688131 0.709731 -0.150856 -v 0.056103 0.072095 0.178791 -vn 0.992501 0.118837 -0.028636 -v 0.056103 0.070962 0.178994 -vn 0.688130 0.662858 -0.295120 -v 0.056103 0.071933 0.178294 -vn 0.992500 0.110648 -0.051976 -v 0.056103 0.070871 0.178736 -vn 0.688131 0.587012 -0.426490 -v 0.056103 0.071672 0.177841 -vn 0.992499 0.097924 -0.073189 -v 0.056103 0.070730 0.178502 -vn 0.688130 0.485513 -0.539217 -v 0.056103 0.071322 0.177453 -vn 0.992497 0.081199 -0.091411 -v 0.056103 0.070546 0.178301 -vn 0.688128 0.362789 -0.628382 -v 0.056103 0.070899 0.177145 -vn 0.992500 0.061121 -0.105868 -v 0.056103 0.070324 0.178141 -vn 0.688136 0.224218 -0.690069 -v 0.056103 0.070422 0.176933 -vn 0.992499 0.038565 -0.116015 -v 0.056103 0.070075 0.178029 -vn 0.688130 0.075850 -0.721612 -v 0.056103 0.069910 0.176824 -vn 0.992499 0.014423 -0.121399 -v 0.056103 0.069808 0.177970 -vn 0.688130 -0.075850 -0.721612 -v 0.056103 0.069388 0.176824 -vn 0.992501 -0.010310 -0.121800 -v 0.056103 0.069535 0.177965 -vn 0.688136 -0.224219 -0.690068 -v 0.056103 0.068877 0.176933 -vn 0.992503 -0.034615 -0.117219 -v 0.056103 0.069267 0.178016 -vn 0.688128 -0.362789 -0.628382 -v 0.056103 0.068399 0.177145 -vn 0.992500 -0.057511 -0.107870 -v 0.056103 0.069014 0.178119 -vn 0.688130 -0.485513 -0.539217 -v 0.056103 0.067976 0.177453 -vn 0.992501 -0.078043 -0.094079 -v 0.056103 0.068787 0.178271 -vn 0.688131 -0.587012 -0.426490 -v 0.056103 0.067627 0.177841 -vn 0.992500 -0.095392 -0.076452 -v 0.056103 0.068596 0.178466 -vn 0.688131 -0.662857 -0.295121 -v 0.056103 0.067365 0.178294 -vn 0.992498 -0.108843 -0.055690 -v 0.056103 0.068447 0.178695 -vn 0.688132 -0.709731 -0.150854 -v 0.056103 0.067204 0.178791 -vn 0.992501 -0.117804 -0.032633 -v 0.056103 0.068348 0.178950 -vn 0.688132 -0.725585 -0.000001 -v 0.056103 0.067149 0.179310 -vn 0.992500 -0.121964 -0.008253 -v 0.056103 0.068302 0.179219 -vn 0.688131 -0.709732 0.150856 -v 0.056103 0.067204 0.179830 -vn 0.992498 -0.121151 0.016469 -v 0.056103 0.068311 0.179492 -vn 0.688132 -0.662854 0.295124 -v 0.056103 0.067365 0.180327 -vn 0.992500 -0.115337 0.040516 -v 0.056103 0.068375 0.179758 -vn 0.688132 -0.587012 0.426487 -v 0.056103 0.067627 0.180780 -vn 0.992497 -0.104841 0.062912 -v 0.056103 0.068492 0.180005 -vn 0.688133 -0.485511 0.539214 -v 0.056103 0.067976 0.181168 -vn -0.114142 0.583942 -0.803731 -v 0.054998 0.071119 0.177288 -vn -0.115040 0.664684 -0.738214 -v 0.054998 0.071322 0.177453 -vn -0.114115 0.738298 -0.664751 -v 0.054998 0.071507 0.177638 -vn -0.115074 0.803636 -0.583890 -v 0.054998 0.071672 0.177841 -vn -0.114147 0.860365 -0.496732 -v 0.054998 0.071814 0.178060 -vn -0.115057 0.907483 -0.404026 -v 0.054998 0.071933 0.178294 -vn -0.114130 0.944843 -0.306995 -v 0.054998 0.072027 0.178538 -vn -0.115044 0.971653 -0.206533 -v 0.054998 0.072095 0.178791 -vn -0.114151 0.988021 -0.103848 -v 0.054998 0.072135 0.179049 -vn -0.115046 0.993360 0.000003 -v 0.054998 0.072149 0.179310 -vn -0.114145 0.988023 0.103835 -v 0.054998 0.072135 0.179572 -vn -0.115041 0.971653 0.206534 -v 0.054998 0.072095 0.179830 -vn -0.114129 0.944841 0.307002 -v 0.054998 0.072027 0.180083 -vn -0.115032 0.907483 0.404033 -v 0.054998 0.071933 0.180327 -vn -0.114116 0.860368 0.496734 -v 0.054998 0.071814 0.180560 -vn -0.115041 0.803649 0.583878 -v 0.054998 0.071672 0.180780 -vn -0.114148 0.738289 0.664755 -v 0.054998 0.071507 0.180983 -vn -0.115045 0.664687 0.738212 -v 0.054998 0.071322 0.181168 -vn -0.114139 0.583946 0.803729 -v 0.054998 0.071119 0.181333 -vn -0.115034 0.496680 0.860277 -v 0.054998 0.070899 0.181475 -vn -0.114127 0.404088 0.907573 -v 0.054998 0.070666 0.181594 -vn -0.115014 0.306954 0.944749 -v 0.054998 0.070422 0.181688 -vn -0.114104 0.206543 0.971762 -v 0.054998 0.070169 0.181756 -vn -0.115029 0.103834 0.987920 -v 0.054998 0.069910 0.181797 -vn -0.114100 -0.000003 0.993469 -v 0.054998 0.069649 0.181810 -vn -0.115027 -0.103825 0.987922 -v 0.054998 0.069388 0.181797 -vn -0.114101 -0.206546 0.971761 -v 0.054998 0.069129 0.181756 -vn -0.115017 -0.306963 0.944746 -v 0.054998 0.068877 0.181688 -vn -0.114127 -0.404079 0.907577 -v 0.054998 0.068632 0.181594 -vn -0.115022 -0.496687 0.860274 -v 0.054998 0.068399 0.181475 -vn -0.114141 -0.583941 0.803732 -v 0.054998 0.068180 0.181333 -vn -0.115046 -0.664691 0.738208 -v 0.054998 0.067976 0.181168 -vn -0.114144 -0.738281 0.664765 -v 0.054998 0.067791 0.180983 -vn -0.115013 -0.803655 0.583875 -v 0.054998 0.067627 0.180780 -vn -0.114114 -0.860369 0.496732 -v 0.054998 0.067484 0.180560 -vn -0.115034 -0.907478 0.404043 -v 0.054998 0.067365 0.180327 -vn -0.114129 -0.944840 0.307004 -v 0.054998 0.067272 0.180083 -vn -0.115038 -0.971656 0.206522 -v 0.054998 0.067204 0.179830 -vn -0.114117 -0.988026 0.103836 -v 0.054998 0.067163 0.179572 -vn -0.115042 -0.993361 0.000002 -v 0.054998 0.067149 0.179310 -vn -0.114122 -0.988024 -0.103845 -v 0.054998 0.067163 0.179049 -vn -0.115041 -0.971655 -0.206525 -v 0.054998 0.067204 0.178791 -vn -0.114132 -0.944843 -0.306995 -v 0.054998 0.067272 0.178538 -vn -0.115059 -0.907478 -0.404036 -v 0.054998 0.067365 0.178294 -vn -0.114145 -0.860366 -0.496730 -v 0.054998 0.067484 0.178060 -vn -0.115046 -0.803642 -0.583887 -v 0.054998 0.067627 0.177841 -vn -0.114111 -0.738290 -0.664761 -v 0.054998 0.067791 0.177638 -vn -0.115045 -0.664685 -0.738213 -v 0.054998 0.067976 0.177453 -vn -0.114145 -0.583942 -0.803730 -v 0.054998 0.068180 0.177288 -vn -0.115069 -0.496681 -0.860272 -v 0.054998 0.068399 0.177145 -vn -0.114128 -0.404065 -0.907583 -v 0.054998 0.068632 0.177027 -vn -0.115022 -0.306974 -0.944742 -v 0.054998 0.068877 0.176933 -vn -0.114166 -0.206569 -0.971749 -v 0.054998 0.069129 0.176865 -vn -0.115091 -0.103829 -0.987914 -v 0.054998 0.069388 0.176824 -vn -0.114165 0.000003 -0.993462 -v 0.054998 0.069649 0.176810 -vn -0.115094 0.103827 -0.987914 -v 0.054998 0.069910 0.176824 -vn -0.114156 0.206560 -0.971752 -v 0.054998 0.070169 0.176865 -vn -0.115017 0.306985 -0.944739 -v 0.054998 0.070422 0.176933 -vn -0.114137 0.404066 -0.907581 -v 0.054998 0.070666 0.177027 -vn -0.115085 0.496672 -0.860274 -v 0.054998 0.070899 0.177145 -vn -0.443594 0.364531 -0.818744 -v 0.054891 0.070656 0.177050 -vn -0.443557 0.276969 -0.852376 -v 0.054891 0.070414 0.176957 -vn -0.443601 0.186324 -0.876642 -v 0.054891 0.070164 0.176890 -vn -0.443597 0.093677 -0.891317 -v 0.054891 0.069908 0.176849 -vn -0.443584 0.000003 -0.896233 -v 0.054891 0.069649 0.176836 -vn -0.443595 -0.093679 -0.891318 -v 0.054891 0.069390 0.176849 -vn -0.443592 -0.186339 -0.876643 -v 0.054891 0.069135 0.176890 -vn -0.443550 -0.276954 -0.852385 -v 0.054891 0.068884 0.176957 -vn -0.443601 -0.364532 -0.818740 -v 0.054891 0.068643 0.177050 -vn -0.443613 -0.448115 -0.776145 -v 0.054891 0.068412 0.177167 -vn -0.443583 -0.526785 -0.725074 -v 0.054891 0.068195 0.177308 -vn -0.443589 -0.599690 -0.666033 -v 0.054891 0.067993 0.177471 -vn -0.443579 -0.666031 -0.599700 -v 0.054891 0.067810 0.177654 -vn -0.443595 -0.725066 -0.526785 -v 0.054891 0.067647 0.177856 -vn -0.443603 -0.776155 -0.448107 -v 0.054891 0.067506 0.178073 -vn -0.443591 -0.818744 -0.364534 -v 0.054891 0.067388 0.178304 -vn -0.443587 -0.852367 -0.276950 -v 0.054891 0.067296 0.178546 -vn -0.443586 -0.876648 -0.186335 -v 0.054891 0.067228 0.178796 -vn -0.443586 -0.891323 -0.093675 -v 0.054891 0.067188 0.179052 -vn -0.443578 -0.896236 -0.000002 -v 0.054891 0.067174 0.179310 -vn -0.443578 -0.891327 0.093676 -v 0.054891 0.067188 0.179569 -vn -0.443595 -0.876643 0.186336 -v 0.054891 0.067228 0.179825 -vn -0.443602 -0.852358 0.276954 -v 0.054891 0.067296 0.180075 -vn -0.443571 -0.818754 0.364536 -v 0.054891 0.067388 0.180317 -vn -0.443570 -0.776166 0.448120 -v 0.054891 0.067506 0.180548 -vn -0.443563 -0.725076 0.526798 -v 0.054891 0.067647 0.180765 -vn -0.443613 -0.666008 0.599700 -v 0.054891 0.067810 0.180966 -vn -0.443598 -0.599697 0.666021 -v 0.054891 0.067993 0.181149 -vn -0.443580 -0.526801 0.725064 -v 0.054891 0.068195 0.181312 -vn -0.443562 -0.448128 0.776166 -v 0.054891 0.068412 0.181454 -vn -0.443595 -0.364527 0.818745 -v 0.054891 0.068643 0.181571 -vn -0.443588 -0.276950 0.852367 -v 0.054891 0.068884 0.181664 -vn -0.443591 -0.186326 0.876647 -v 0.054891 0.069135 0.181731 -vn -0.443583 -0.093679 0.891324 -v 0.054891 0.069390 0.181772 -vn -0.443570 -0.000002 0.896240 -v 0.054891 0.069649 0.181785 -vn -0.443582 0.093679 0.891325 -v 0.054891 0.069908 0.181772 -vn -0.443582 0.186325 0.876652 -v 0.054891 0.070164 0.181731 -vn -0.443592 0.276945 0.852366 -v 0.054891 0.070414 0.181664 -vn -0.443601 0.364537 0.818737 -v 0.054891 0.070656 0.181571 -vn -0.443571 0.448115 0.776168 -v 0.054891 0.070887 0.181454 -vn -0.443592 0.526797 0.725060 -v 0.054891 0.071104 0.181312 -vn -0.443597 0.599695 0.666024 -v 0.054891 0.071305 0.181149 -vn -0.443613 0.666022 0.599685 -v 0.054891 0.071488 0.180966 -vn -0.443565 0.725067 0.526808 -v 0.054891 0.071651 0.180765 -vn -0.443570 0.776165 0.448123 -v 0.054891 0.071792 0.180548 -vn -0.443587 0.818750 0.364525 -v 0.054891 0.071910 0.180317 -vn -0.443585 0.852366 0.276957 -v 0.054891 0.072003 0.180075 -vn -0.443593 0.876644 0.186336 -v 0.054891 0.072070 0.179825 -vn -0.443588 0.891321 0.093677 -v 0.054891 0.072110 0.179569 -vn -0.443577 0.896236 0.000001 -v 0.054891 0.072124 0.179310 -vn -0.443591 0.891320 -0.093678 -v 0.054891 0.072110 0.179052 -vn -0.443582 0.876649 -0.186338 -v 0.054891 0.072070 0.178796 -vn -0.443573 0.852374 -0.276950 -v 0.054891 0.072003 0.178546 -vn -0.443608 0.818739 -0.364525 -v 0.054891 0.071910 0.178304 -vn -0.443605 0.776151 -0.448112 -v 0.054891 0.071792 0.178073 -vn -0.443596 0.725064 -0.526788 -v 0.054891 0.071651 0.177856 -vn -0.443575 0.666042 -0.599691 -v 0.054891 0.071488 0.177654 -vn -0.443597 0.599683 -0.666035 -v 0.054891 0.071305 0.177471 -vn -0.443600 0.526782 -0.725065 -v 0.054891 0.071104 0.177308 -vn -0.443613 0.448107 -0.776149 -v 0.054891 0.070887 0.177167 -vn 1.000000 0.000000 0.000000 -v 0.064103 0.069649 0.179310 -vn 0.503825 -0.075345 -0.860513 -v 0.056153 0.069543 0.178051 -vn 0.500137 -0.235676 -0.833258 -v 0.056153 0.069291 0.178099 -vn 0.499652 -0.669437 -0.549729 -v 0.056153 0.068663 0.178520 -vn 0.501565 -0.555935 -0.662849 -v 0.056153 0.068843 0.178338 -vn 0.499245 -0.863710 -0.068992 -v 0.056153 0.068389 0.179225 -vn 0.500265 -0.836129 -0.224996 -v 0.056153 0.068432 0.178973 -vn 0.498980 -0.748426 0.436894 -v 0.056153 0.068566 0.179960 -vn 0.499627 -0.814749 0.294205 -v 0.056153 0.068457 0.179729 -vn 0.498886 -0.364434 0.786321 -v 0.056153 0.069131 0.180463 -vn 0.499417 -0.500152 0.707412 -v 0.056153 0.068910 0.180335 -vn 0.498962 0.150845 0.853395 -v 0.056153 0.069883 0.180552 -vn 0.499494 -0.005978 0.866297 -v 0.056153 0.069628 0.180574 -vn 0.499632 0.611993 0.613053 -v 0.056153 0.070550 0.180196 -vn 0.499751 0.489957 0.714277 -v 0.056153 0.070353 0.180359 -vn 0.500950 0.852119 0.151467 -v 0.056153 0.070895 0.179523 -vn 0.500063 0.809965 0.306420 -v 0.056153 0.070826 0.179769 -vn 0.873233 0.057483 -0.483901 -v 0.056116 0.069802 0.178019 -vn 0.873246 0.441047 -0.207170 -v 0.056116 0.070826 0.178758 -vn 0.873224 -0.041105 -0.485582 -v 0.056116 0.069539 0.178015 -vn 0.873225 -0.138017 -0.467364 -v 0.056116 0.069281 0.178064 -vn 0.873222 -0.229267 -0.430023 -v 0.056116 0.069038 0.178163 -vn 0.873222 -0.311137 -0.375069 -v 0.056116 0.068819 0.178310 -vn 0.873246 -0.380238 -0.304729 -v 0.056116 0.068635 0.178497 -vn 0.873252 -0.433787 -0.221947 -v 0.056116 0.068492 0.178718 -vn 0.873231 -0.469621 -0.130091 -v 0.056116 0.068396 0.178963 -vn 0.873234 -0.486189 -0.032899 -v 0.056116 0.068352 0.179223 -vn 0.873238 -0.482853 0.065645 -v 0.056116 0.068361 0.179486 -vn 0.873242 -0.459747 0.161499 -v 0.056116 0.068423 0.179741 -vn 0.873248 -0.417815 0.250736 -v 0.056116 0.068534 0.179979 -vn 0.873245 -0.358796 0.329709 -v 0.056116 0.068692 0.180190 -vn 0.873231 -0.285103 0.395201 -v 0.056116 0.068889 0.180365 -vn 0.873218 -0.199721 0.444524 -v 0.056116 0.069116 0.180496 -vn 0.873226 -0.106137 0.475617 -v 0.056116 0.069366 0.180579 -vn 0.873241 -0.008225 0.487219 -v 0.056116 0.069627 0.180610 -vn 0.873242 0.090009 0.478901 -v 0.056116 0.069889 0.180588 -vn 0.873230 0.184568 0.451004 -v 0.056116 0.070142 0.180514 -vn 0.873261 0.271558 0.404563 -v 0.056116 0.070374 0.180390 -vn 0.873240 0.347467 0.341640 -v 0.056116 0.070576 0.180222 -vn 0.873264 0.409090 0.264681 -v 0.056116 0.070741 0.180017 -vn 0.873261 0.453999 0.176916 -v 0.056116 0.070860 0.179782 -vn 0.873245 0.480348 0.081914 -v 0.056116 0.070931 0.179529 -vn 0.873244 0.487005 -0.016458 -v 0.056116 0.070948 0.179266 -vn 0.873244 0.473725 -0.114149 -v 0.056116 0.070913 0.179006 -vn 0.873246 0.323596 -0.364317 -v 0.056116 0.070512 0.178338 -vn 0.873232 0.243649 -0.422020 -v 0.056116 0.070299 0.178185 -vn 0.873243 0.153704 -0.462409 -v 0.056116 0.070059 0.178077 -vn 0.501779 -0.414095 -0.759437 -v 0.056153 0.069055 0.178196 -vn 0.502412 -0.773047 -0.387273 -v 0.056153 0.068524 0.178735 -vn 0.502977 -0.855516 0.122906 -v 0.056153 0.068397 0.179481 -vn 0.503529 -0.632317 0.588755 -v 0.056153 0.068719 0.180165 -vn 0.504221 -0.183395 0.843877 -v 0.056153 0.069374 0.180543 -vn 0.504795 0.330547 0.797447 -v 0.056153 0.070128 0.180480 -vn 0.505441 0.726043 0.466252 -v 0.056153 0.070710 0.179997 -vn 0.506081 0.861925 -0.031098 -v 0.056153 0.070912 0.179268 -vn 0.500489 0.839665 -0.210890 -v 0.056153 0.070877 0.179014 -vn 0.500989 0.568803 -0.652283 -v 0.056153 0.070488 0.178366 -vn 0.507375 0.430855 -0.746280 -v 0.056153 0.070281 0.178216 -vn 0.500622 0.282006 -0.818444 -v 0.056153 0.070048 0.178111 -vn 0.506719 0.689966 -0.516897 -v 0.056153 0.070661 0.178554 -vn 0.873251 0.390302 -0.291712 -v 0.056116 0.070690 0.178532 -vn 0.503427 0.783461 -0.364350 -v 0.056153 0.070793 0.178773 -vn 0.501180 0.093311 -0.860297 -v 0.056153 0.069798 0.178056 -vn -0.989929 0.116016 -0.081122 -v 0.055503 0.069190 0.179624 -vn -0.605927 -0.397739 0.688953 -v 0.055503 0.069927 0.178829 -vn -0.605762 0.397838 -0.689041 -v 0.055503 0.069371 0.179792 -vn -1.000000 -0.000001 0.000003 -v 0.055684 0.069649 0.179310 -vn -0.710389 -0.702598 -0.041261 -v 0.059703 0.077637 0.145561 -vn -0.813584 -0.399905 0.422086 -v 0.059703 0.078062 0.146039 -vn -0.994792 0.099973 0.019878 -v 0.059703 0.078154 0.145814 -vn -0.994278 0.106814 -0.001363 -v 0.059703 0.078192 0.145518 -vn -0.995324 0.095536 -0.014254 -v 0.059703 0.078146 0.145223 -vn -0.811470 -0.351324 -0.466999 -v 0.059703 0.078115 0.145135 -vn -0.710387 0.041240 -0.702602 -v 0.059703 0.077113 0.146026 -vn -0.819522 -0.426427 -0.382812 -v 0.059703 0.076635 0.146451 -vn -0.994585 -0.036926 0.097149 -v 0.059703 0.076719 0.146492 -vn -0.994278 -0.013850 0.105922 -v 0.059703 0.077006 0.146573 -vn -0.994792 0.008044 0.101612 -v 0.059703 0.077305 0.146569 -vn -0.813581 0.465987 -0.347767 -v 0.059703 0.077539 0.146504 -vn -0.710390 0.702599 0.041241 -v 0.059703 0.076648 0.145503 -vn -0.813579 0.399904 -0.422097 -v 0.059703 0.076223 0.145024 -vn -0.994792 -0.099973 -0.019878 -v 0.059703 0.076131 0.145249 -vn -0.994278 -0.106818 0.001362 -v 0.059703 0.076093 0.145545 -vn -0.995324 -0.095534 0.014255 -v 0.059703 0.076139 0.145840 -vn -0.811471 0.351324 0.466997 -v 0.059703 0.076170 0.145928 -vn -0.513801 -0.723991 -0.460267 -v 0.082409 0.076581 0.145319 -vn -0.518336 -0.808225 -0.279464 -v 0.082405 0.076573 0.145343 -vn 0.129008 -0.943420 -0.305475 -v 0.082103 0.076573 0.145343 -vn -0.562377 -0.099664 0.820853 -v 0.082198 0.077206 0.146128 -vn -0.502190 0.138735 0.853556 -v 0.082188 0.077264 0.146119 -vn 0.076978 0.194648 0.977848 -v 0.082103 0.077264 0.146119 -vn -0.623897 0.300117 0.721584 -v 0.082154 0.077441 0.146052 -vn 0.223537 0.637052 0.737696 -v 0.082103 0.077541 0.145980 -vn -0.684318 0.501502 0.529344 -v 0.082115 0.077620 0.145895 -vn -0.432508 0.722201 0.539780 -v 0.082103 0.077657 0.145840 -vn -0.535609 -0.325222 0.779329 -v 0.082240 0.076965 0.146105 -vn 0.106129 -0.306084 0.946071 -v 0.082103 0.076954 0.146101 -vn -0.531732 -0.575768 0.621090 -v 0.082281 0.076754 0.145989 -vn 0.090279 -0.741321 0.665051 -v 0.082103 0.076694 0.145930 -vn -0.497164 -0.721235 0.482336 -v 0.082296 0.076694 0.145930 -vn -0.528207 -0.799614 0.285685 -v 0.082326 0.076602 0.145793 -vn 0.112169 -0.974052 0.196573 -v 0.082103 0.076555 0.145653 -vn -0.493757 -0.860530 0.125269 -v 0.082350 0.076555 0.145653 -vn -0.537214 -0.835795 -0.113348 -v 0.082365 0.076543 0.145562 -vn -0.523351 -0.599032 -0.606024 -v 0.082452 0.076713 0.145113 -vn -0.131121 -0.696034 -0.705935 -v 0.082103 0.076744 0.145083 -vn -0.495975 -0.469446 -0.730500 -v 0.082459 0.076744 0.145083 -vn 0.486030 -0.613335 -0.622571 -v 0.082103 0.076771 0.145060 -vn 0.515104 -0.507248 -0.690918 -v 0.082109 0.076801 0.145038 -vn -0.514496 -0.266805 -0.814929 -v 0.082492 0.076910 0.144978 -vn 0.516726 -0.256295 -0.816889 -v 0.082153 0.077028 0.144943 -vn -0.496038 -0.083604 -0.864267 -v 0.082513 0.077021 0.144944 -vn -0.513380 0.125931 -0.848871 -v 0.082537 0.077154 0.144932 -vn 0.505397 0.041967 -0.861866 -v 0.082196 0.077273 0.144946 -vn -0.501038 0.306762 -0.809233 -v 0.082567 0.077331 0.144962 -vn 0.500784 0.237800 -0.832266 -v 0.082206 0.077332 0.144962 -vn -0.505353 0.480555 -0.716718 -v 0.082577 0.077387 0.144984 -vn 0.513268 0.406287 -0.755968 -v 0.082236 0.077492 0.145044 -vn -0.516683 0.692393 -0.503618 -v 0.082620 0.077586 0.145127 -vn 0.495989 0.583998 -0.642605 -v 0.082260 0.077591 0.145133 -vn 0.514537 0.701194 -0.493538 -v 0.082281 0.077660 0.145227 -vn -0.515852 0.822075 -0.241016 -v 0.082663 0.077711 0.145338 -vn 0.495910 0.813336 -0.304232 -v 0.082314 0.077730 0.145410 -vn -0.495284 0.866367 -0.064053 -v 0.082675 0.077730 0.145411 -vn 0.513807 0.847382 -0.133961 -v 0.082321 0.077737 0.145454 -vn -0.509784 0.846349 0.154315 -v 0.082703 0.077741 0.145575 -vn 0.503043 0.860689 0.078497 -v 0.082364 0.077719 0.145699 -vn -0.487313 0.808033 0.331073 -v 0.082730 0.077712 0.145721 -vn 0.505676 0.825504 0.250671 -v 0.082368 0.077712 0.145721 -vn -0.511495 0.689785 0.512415 -v 0.082748 0.077672 0.145813 -vn 0.507614 0.738451 0.443867 -v 0.082408 0.077603 0.145917 -vn -0.507253 0.557271 0.657377 -v 0.082784 0.077541 0.145980 -vn 0.493177 0.614654 0.615611 -v 0.082422 0.077541 0.145980 -vn -0.502166 0.413778 0.759353 -v 0.082788 0.077520 0.145998 -vn 0.513094 0.472988 0.716252 -v 0.082448 0.077416 0.146066 -vn -0.510667 0.204422 0.835123 -v 0.082830 0.077303 0.146110 -vn 0.494343 0.284863 0.821266 -v 0.082477 0.077264 0.146119 -vn -0.496584 0.029889 0.867474 -v 0.082838 0.077264 0.146119 -vn 0.512782 0.098222 0.852882 -v 0.082492 0.077176 0.146131 -vn -0.516332 -0.182335 0.836753 -v 0.082875 0.077057 0.146125 -vn 0.497848 -0.124352 0.858303 -v 0.082531 0.076954 0.146101 -vn -0.496505 -0.356261 0.791556 -v 0.082892 0.076953 0.146101 -vn 0.512029 -0.281796 0.811429 -v 0.082533 0.076938 0.146095 -vn -0.509817 -0.534115 0.674394 -v 0.082914 0.076833 0.146046 -vn 0.506738 -0.470831 0.722173 -v 0.082575 0.076730 0.145968 -vn -0.496614 -0.676797 0.543434 -v 0.082946 0.076694 0.145930 -vn 0.500257 -0.622775 0.601576 -v 0.082585 0.076694 0.145930 -vn -0.508766 -0.778514 0.367524 -v 0.082958 0.076652 0.145877 -vn 0.509693 -0.739924 0.439006 -v 0.082620 0.076589 0.145764 -vn -0.516843 -0.851779 0.085713 -v 0.083000 0.076555 0.145655 -vn 0.498038 -0.830522 0.249382 -v 0.082639 0.076555 0.145653 -vn 0.516890 -0.853071 0.071370 -v 0.082659 0.076542 0.145530 -vn -0.512389 -0.833447 -0.206941 -v 0.083041 0.076554 0.145414 -vn 0.495182 -0.856865 -0.143451 -v 0.082693 0.076573 0.145343 -vn -0.494535 -0.777871 -0.387753 -v 0.083055 0.076573 0.145343 -vn 0.511583 -0.798095 -0.318318 -v 0.082704 0.076594 0.145288 -vn -0.513168 -0.648201 -0.562579 -v 0.083086 0.076652 0.145186 -vn 0.516649 -0.644517 -0.563623 -v 0.082746 0.076736 0.145090 -vn -0.490116 -0.535290 -0.687933 -v 0.083109 0.076744 0.145083 -vn -0.509735 -0.344062 -0.788538 -v 0.083125 0.076824 0.145023 -vn 0.510634 -0.416605 -0.752126 -v 0.082787 0.076943 0.144966 -vn -0.503685 -0.146748 -0.851332 -v 0.083163 0.077021 0.144944 -vn 0.493242 -0.223781 -0.840615 -v 0.082802 0.077021 0.144944 -vn -0.504729 0.035842 -0.862533 -v 0.083169 0.077056 0.144938 -vn 0.509784 -0.036723 -0.859518 -v 0.082832 0.077190 0.144933 -vn -0.512918 0.242886 -0.823360 -v 0.083212 0.077299 0.144952 -vn 0.495442 0.179559 -0.849880 -v 0.082856 0.077331 0.144962 -vn -0.496586 0.403356 -0.768574 -v 0.083217 0.077332 0.144962 -vn 0.515738 0.346692 -0.783466 -v 0.082871 0.077419 0.144999 -vn -0.513019 0.578301 -0.634334 -v 0.083252 0.077513 0.145060 -vn 0.497501 0.536209 -0.681889 -v 0.082910 0.077591 0.145133 -vn -0.494470 0.711258 -0.499611 -v 0.083271 0.077591 0.145133 -vn 0.509963 0.656147 -0.556245 -v 0.082915 0.077610 0.145156 -vn -0.513331 0.801642 -0.306369 -v 0.083297 0.077672 0.145250 -vn 0.503339 0.780034 -0.371749 -v 0.082958 0.077721 0.145374 -vn -0.499020 0.856041 -0.134806 -v 0.083325 0.077730 0.145410 -vn 0.505762 0.839534 -0.198462 -v 0.082964 0.077730 0.145411 -vn -0.506887 0.859248 0.068986 -v 0.083336 0.077740 0.145479 -vn 0.513058 0.858328 -0.006689 -v 0.082998 0.077737 0.145613 -vn -0.516981 0.776276 0.360730 -v 0.083380 0.077711 0.145722 -vn 0.484936 0.847920 0.214172 -v 0.083018 0.077712 0.145721 -vn 0.510035 0.774550 0.374081 -v 0.083043 0.077653 0.145847 -vn -0.514902 0.613428 0.598817 -v 0.083423 0.077587 0.145934 -vn 0.494923 0.659974 0.565230 -v 0.083072 0.077541 0.145980 -vn -0.495040 0.483270 0.722070 -v 0.083434 0.077541 0.145980 -vn 0.515030 0.521299 0.680435 -v 0.083083 0.077489 0.146022 -vn -0.510206 0.279811 0.813262 -v 0.083463 0.077395 0.146076 -vn 0.516978 0.263899 0.814304 -v 0.083127 0.077263 0.146119 -vn -0.484867 0.113231 0.867227 -v 0.083488 0.077264 0.146119 -vn -0.513112 -0.107495 0.851564 -v 0.083508 0.077154 0.146131 -vn 0.506628 -0.035428 0.861437 -v 0.083170 0.077017 0.146118 -vn -0.505890 -0.295269 0.810488 -v 0.083542 0.076954 0.146101 -vn 0.499980 -0.235757 0.833330 -v 0.083181 0.076953 0.146101 -vn -0.503465 -0.459912 0.731440 -v 0.083548 0.076918 0.146088 -vn 0.513202 -0.400924 0.758870 -v 0.083210 0.076798 0.146023 -vn -0.509991 -0.628633 0.587137 -v 0.083591 0.076715 0.145953 -vn 0.494345 -0.582091 0.645596 -v 0.083235 0.076694 0.145930 -vn -0.497463 -0.739514 0.453486 -v 0.083596 0.076694 0.145930 -vn 0.512876 -0.699806 0.497222 -v 0.083255 0.076628 0.145841 -vn -0.515563 -0.818348 0.253970 -v 0.083635 0.076582 0.145746 -vn 0.496170 -0.811949 0.307497 -v 0.083289 0.076555 0.145653 -vn -0.495376 -0.864907 0.080859 -v 0.083650 0.076555 0.145653 -vn 0.513264 -0.846851 0.139294 -v 0.083295 0.076548 0.145614 -vn -0.510011 -0.849457 -0.135317 -v 0.083674 0.076543 0.145511 -vn 0.504176 -0.860594 -0.072006 -v 0.083338 0.076565 0.145370 -vn -0.494605 -0.808521 -0.318841 -v 0.083705 0.076573 0.145343 -vn 0.504902 -0.826645 -0.248459 -v 0.083343 0.076573 0.145343 -vn -0.510683 -0.700302 -0.498779 -v 0.083719 0.076602 0.145271 -vn 0.509461 -0.740163 -0.438872 -v 0.083382 0.076679 0.145151 -vn -0.516978 -0.488855 -0.702677 -v 0.083760 0.076749 0.145079 -vn 0.492669 -0.616544 -0.614126 -v 0.083397 0.076744 0.145083 -vn 0.513347 -0.478069 -0.712689 -v 0.083422 0.076864 0.145000 -vn -0.511589 -0.227564 -0.828548 -v 0.083801 0.076960 0.144960 -vn 0.493982 -0.288215 -0.820313 -v 0.083452 0.077021 0.144944 -vn -0.494814 -0.046188 -0.867771 -v 0.083813 0.077021 0.144944 -vn 0.512649 -0.098707 -0.852906 -v 0.083466 0.077103 0.144933 -vn -0.517053 0.167639 -0.839377 -v 0.083846 0.077206 0.144935 -vn 0.517361 0.197145 -0.832749 -v 0.083508 0.077343 0.144966 -vn 0.517182 0.649398 0.557499 -v 0.083720 0.077553 0.145969 -vn -0.513528 0.659910 0.548460 -v 0.084057 0.077646 0.145858 -vn 0.511085 0.800463 0.313133 -v 0.083678 0.077693 0.145770 -vn -0.493867 0.785706 0.372507 -v 0.084030 0.077712 0.145721 -vn 0.495548 0.857263 0.139759 -v 0.083668 0.077712 0.145721 -vn -0.512364 0.837238 0.191088 -v 0.084012 0.077735 0.145627 -vn 0.515692 0.853464 -0.075239 -v 0.083633 0.077742 0.145528 -vn -0.497448 0.867037 -0.028152 -v 0.083975 0.077730 0.145411 -vn 0.496547 0.830404 -0.252724 -v 0.083614 0.077730 0.145410 -vn -0.512304 0.837066 -0.192003 -v 0.083972 0.077725 0.145387 -vn 0.509777 0.736618 -0.444433 -v 0.083594 0.077694 0.145294 -vn -0.506494 0.768999 -0.390005 -v 0.083929 0.077619 0.145167 -vn 0.499531 0.621518 -0.603476 -v 0.083560 0.077591 0.145133 -vn -0.502115 0.667272 -0.550117 -v 0.083921 0.077591 0.145133 -vn 0.508123 0.464981 -0.724986 -v 0.083549 0.077551 0.145092 -vn -0.509738 0.518860 -0.686259 -v 0.083885 0.077432 0.145006 -vn -0.498639 0.339735 -0.797458 -v 0.083867 0.077331 0.144962 -vn 0.517835 -0.271548 -0.811239 -v 0.084101 0.077017 0.144945 -vn -0.492991 -0.123923 -0.861164 -v 0.084463 0.077021 0.144944 -vn -0.510530 -0.297862 -0.806621 -v 0.084434 0.076869 0.144997 -vn 0.514614 -0.525562 -0.677463 -v 0.084057 0.076792 0.145045 -vn -0.494819 -0.497041 -0.712814 -v 0.084409 0.076744 0.145083 -vn 0.494984 -0.662336 -0.562408 -v 0.084047 0.076744 0.145083 -vn -0.515135 -0.624640 -0.586907 -v 0.084395 0.076683 0.145146 -vn 0.512732 -0.773142 -0.373306 -v 0.084017 0.076629 0.145220 -vn -0.498798 -0.758501 -0.419378 -v 0.084355 0.076573 0.145343 -vn 0.495452 -0.845662 -0.198455 -v 0.083993 0.076573 0.145343 -vn -0.509534 -0.820009 -0.260694 -v 0.084351 0.076567 0.145363 -vn 0.513055 -0.858259 0.012883 -v 0.083972 0.076547 0.145455 -vn -0.505117 -0.861925 -0.044061 -v 0.084308 0.076547 0.145606 -vn 0.505243 -0.839331 0.200632 -v 0.083939 0.076555 0.145653 -vn -0.504572 -0.851049 0.145336 -v 0.084300 0.076555 0.145653 -vn 0.504623 -0.776472 0.377422 -v 0.083932 0.076565 0.145695 -vn -0.513200 -0.794902 0.323661 -v 0.084268 0.076624 0.145833 -vn 0.509707 -0.652391 0.560878 -v 0.083889 0.076678 0.145912 -vn -0.495166 -0.700783 0.513530 -v 0.084246 0.076694 0.145930 -vn 0.498301 -0.532681 0.684067 -v 0.083885 0.076694 0.145930 -vn -0.512745 -0.565749 0.645771 -v 0.084223 0.076790 0.146017 -vn 0.515187 -0.343351 0.785298 -v 0.083845 0.076871 0.146067 -vn -0.495327 -0.389737 0.776374 -v 0.084192 0.076953 0.146101 -vn 0.494792 -0.176246 0.850952 -v 0.083831 0.076954 0.146101 -vn -0.514224 -0.221226 0.828633 -v 0.084183 0.077007 0.146116 -vn 0.510248 0.043242 0.858940 -v 0.083806 0.077101 0.146130 -vn -0.502478 -0.010934 0.864521 -v 0.084140 0.077252 0.146122 -vn 0.492590 0.225857 0.840443 -v 0.083777 0.077264 0.146119 -vn -0.507323 0.157368 0.847265 -v 0.084138 0.077264 0.146119 -vn 0.512247 0.421799 0.748124 -v 0.083761 0.077347 0.146096 -vn -0.509408 0.361793 0.780775 -v 0.084096 0.077479 0.146028 -vn -0.497923 0.541259 0.677578 -v 0.084084 0.077541 0.145980 -vn -0.512545 0.089037 -0.854032 -v 0.084479 0.077108 0.144933 -vn 0.508144 0.028718 -0.860793 -v 0.084144 0.077263 0.144944 -vn -0.509482 0.284218 -0.812187 -v 0.084517 0.077331 0.144962 -vn 0.499467 0.233963 -0.834143 -v 0.084156 0.077332 0.144962 -vn -0.501735 0.439307 -0.745165 -v 0.084520 0.077346 0.144967 -vn 0.513513 0.395323 -0.761593 -v 0.084184 0.077483 0.145037 -vn -0.511042 0.611247 -0.604329 -v 0.084561 0.077553 0.145094 -vn 0.493750 0.579668 -0.648226 -v 0.084210 0.077591 0.145133 -vn -0.495664 0.731869 -0.467637 -v 0.084571 0.077591 0.145133 -vn 0.512270 0.697688 -0.500810 -v 0.084229 0.077654 0.145218 -vn -0.515394 0.813611 -0.269083 -v 0.084606 0.077695 0.145297 -vn 0.496809 0.810224 -0.310994 -v 0.084264 0.077730 0.145410 -vn -0.496429 0.862574 -0.097591 -v 0.084625 0.077730 0.145410 -vn 0.513033 0.846142 -0.144365 -v 0.084269 0.077736 0.145444 -vn -0.510079 0.852236 0.116247 -v 0.084645 0.077742 0.145530 -vn 0.505671 0.860254 0.065278 -v 0.084312 0.077722 0.145688 -vn -0.500713 0.809310 0.307088 -v 0.084680 0.077712 0.145721 -vn 0.504456 0.827495 0.246529 -v 0.084318 0.077712 0.145721 -vn -0.508505 0.714961 0.479847 -v 0.084689 0.077692 0.145772 -vn 0.509581 0.743305 0.433388 -v 0.084356 0.077609 0.145908 -vn -0.518040 0.513680 0.683936 -v 0.084731 0.077552 0.145970 -vn 0.491118 0.617722 0.614184 -v 0.084372 0.077541 0.145980 -vn 0.513939 0.483031 0.708906 -v 0.084396 0.077426 0.146060 -vn -0.512723 0.250693 0.821138 -v 0.084772 0.077347 0.146096 -vn 0.494125 0.291877 0.818931 -v 0.084427 0.077264 0.146119 -vn -0.493840 0.063124 0.867259 -v 0.084788 0.077264 0.146119 -vn 0.512237 0.104330 0.852484 -v 0.084440 0.077187 0.146130 -vn -0.513992 -0.154601 0.843748 -v 0.084817 0.077102 0.146130 -vn 0.518045 -0.189372 0.834127 -v 0.084482 0.076947 0.146099 -vn -0.495014 -0.319576 0.807980 -v 0.084842 0.076954 0.146101 -vn -0.509517 -0.503362 0.697868 -v 0.084856 0.076872 0.146067 -vn 0.509791 -0.458870 0.727703 -v 0.084523 0.076738 0.145975 -vn -0.506360 -0.658429 0.556840 -v 0.084896 0.076694 0.145930 -vn 0.499172 -0.620366 0.604957 -v 0.084535 0.076694 0.145930 -vn -0.504269 -0.758928 0.411996 -v 0.084900 0.076680 0.145914 -vn 0.510232 -0.732996 0.449868 -v 0.084568 0.076594 0.145774 -vn -0.513747 -0.830921 0.213619 -v 0.084943 0.076566 0.145697 -vn 0.495712 -0.829825 0.256242 -v 0.084589 0.076555 0.145653 -vn -0.495998 -0.867232 0.043536 -v 0.084950 0.076555 0.145653 -vn 0.515192 -0.853420 0.079067 -v 0.084607 0.076543 0.145541 -vn -0.512242 -0.840963 -0.174325 -v 0.084983 0.076547 0.145459 -vn 0.496251 -0.857532 -0.135548 -v 0.084643 0.076573 0.145343 -vn -0.494181 -0.792829 -0.356662 -v 0.085005 0.076573 0.145343 -vn 0.510916 -0.802594 -0.307908 -v 0.084652 0.076590 0.145298 -vn -0.513574 -0.671516 -0.534142 -v 0.085028 0.076627 0.145224 -vn 0.502735 -0.701257 -0.505466 -v 0.084694 0.076728 0.145097 -vn -0.503292 -0.548701 -0.667551 -v 0.085059 0.076744 0.145083 -vn 0.509151 -0.583439 -0.632743 -v 0.084697 0.076744 0.145083 -vn -0.507008 -0.381859 -0.772740 -v 0.085068 0.076788 0.145048 -vn 0.512560 -0.423605 -0.746887 -v 0.084735 0.076933 0.144969 -vn -0.518001 -0.093296 -0.850277 -v 0.085111 0.077011 0.144946 -vn 0.491936 -0.227219 -0.840459 -v 0.084752 0.077021 0.144944 -vn 0.511022 -0.049893 -0.858118 -v 0.084780 0.077179 0.144933 -vn -0.515633 0.199059 -0.833366 -v 0.085154 0.077256 0.144942 -vn 0.494673 0.172494 -0.851789 -v 0.084806 0.077331 0.144962 -vn -0.494780 0.375227 -0.783835 -v 0.085167 0.077332 0.144962 -vn 0.515072 0.340129 -0.786774 -v 0.084819 0.077409 0.144994 -vn -0.509611 0.556597 -0.656122 -v 0.085194 0.077477 0.145033 -vn 0.499507 0.528782 -0.686208 -v 0.084860 0.077591 0.145133 -vn -0.488899 0.688051 -0.536250 -v 0.085221 0.077591 0.145133 -vn 0.509673 0.648781 -0.565081 -v 0.084863 0.077603 0.145147 -vn -0.512839 0.787901 -0.340893 -v 0.085239 0.077650 0.145211 -vn 0.506147 0.772609 -0.383262 -v 0.084906 0.077718 0.145363 -vn -0.508711 0.846662 -0.156128 -v 0.085275 0.077730 0.145410 -vn 0.505063 0.838978 -0.202550 -v 0.084914 0.077730 0.145411 -vn -0.503488 0.863788 0.019270 -v 0.085279 0.077735 0.145435 -vn 0.513373 0.857952 -0.019145 -v 0.084946 0.077738 0.145602 -vn -0.510779 0.826368 0.237110 -v 0.085322 0.077724 0.145678 -vn 0.494577 0.846958 0.195080 -v 0.084968 0.077712 0.145721 -vn -0.496884 0.766838 0.406283 -v 0.085330 0.077712 0.145721 -vn 0.512137 0.775216 0.369805 -v 0.084991 0.077658 0.145838 -vn -0.515094 0.635464 0.575207 -v 0.085366 0.077616 0.145900 -vn 0.495466 0.664774 0.559097 -v 0.085022 0.077541 0.145980 -vn -0.495539 0.510480 0.702746 -v 0.085384 0.077541 0.145980 -vn 0.514496 0.529568 0.674427 -v 0.085031 0.077497 0.146015 -vn -0.510697 0.315764 0.799676 -v 0.085405 0.077436 0.146055 -vn 0.519178 0.279115 0.807805 -v 0.085075 0.077274 0.146117 -vn -0.499911 0.134492 0.855570 -v 0.085438 0.077264 0.146119 -vn -0.511530 -0.069112 0.856482 -v 0.085450 0.077200 0.146129 -vn 0.509555 -0.021476 0.860170 -v 0.085118 0.077027 0.146120 -vn -0.518799 -0.348040 0.780843 -v 0.085491 0.076959 0.146103 -vn 0.499069 -0.232502 0.834789 -v 0.085131 0.076953 0.146101 -vn 0.514143 -0.389547 0.764140 -v 0.085158 0.076807 0.146029 -vn -0.512309 -0.593323 0.620892 -v 0.085532 0.076749 0.145984 -vn 0.493641 -0.576717 0.650935 -v 0.085185 0.076694 0.145930 -vn -0.494361 -0.723456 0.481890 -v 0.085546 0.076694 0.145930 -vn 0.512096 -0.695509 0.504009 -v 0.085203 0.076634 0.145850 -vn -0.512228 -0.811390 0.281549 -v 0.085577 0.076599 0.145787 -vn 0.497800 -0.808181 0.314705 -v 0.085239 0.076555 0.145653 -vn -0.490212 -0.862866 0.123104 -v 0.085600 0.076555 0.145653 -vn 0.513081 -0.845283 0.149149 -v 0.085244 0.076550 0.145624 -vn -0.509940 -0.854714 -0.097082 -v 0.085616 0.076543 0.145556 -vn 0.507368 -0.859759 -0.058242 -v 0.085286 0.076562 0.145381 -vn -0.505521 -0.810588 -0.295629 -v 0.085655 0.076573 0.145343 -vn 0.504446 -0.828045 -0.244693 -v 0.085293 0.076573 0.145343 -vn -0.506390 -0.729104 -0.460409 -v 0.085660 0.076584 0.145313 -vn 0.510038 -0.746333 -0.427607 -v 0.085330 0.076672 0.145159 -vn -0.513492 -0.594017 -0.619250 -v 0.085703 0.076717 0.145108 -vn 0.487282 -0.621330 -0.613600 -v 0.085347 0.076744 0.145083 -vn -0.497179 -0.464931 -0.732565 -v 0.085709 0.076744 0.145083 -vn 0.511693 -0.486265 -0.708320 -v 0.085370 0.076854 0.145005 -vn -0.512024 -0.262682 -0.817820 -v 0.085743 0.076917 0.144976 -vn 0.494734 -0.295813 -0.817149 -v 0.085402 0.077021 0.144944 -vn -0.493800 -0.080227 -0.865867 -v 0.085763 0.077021 0.144944 -vn 0.512187 -0.109640 -0.851847 -v 0.085414 0.077092 0.144934 -vn -0.514226 0.136436 -0.846733 -v 0.085788 0.077161 0.144932 -vn 0.519283 0.181419 -0.835124 -v 0.085456 0.077333 0.144962 -vn -0.502130 0.307669 -0.808211 -v 0.085817 0.077331 0.144962 -vn -0.509081 0.487507 -0.709347 -v 0.085828 0.077393 0.144986 -vn 0.511703 0.452293 -0.730473 -v 0.085497 0.077542 0.145084 -vn -0.519384 0.697507 -0.493684 -v 0.085871 0.077590 0.145132 -vn 0.499152 0.619203 -0.606165 -v 0.085510 0.077591 0.145133 -vn 0.511018 0.729119 -0.455243 -v 0.085542 0.077689 0.145284 -vn -0.515349 0.824025 -0.235367 -v 0.085914 0.077713 0.145345 -vn 0.495319 0.828884 -0.260020 -v 0.085564 0.077730 0.145410 -vn -0.495209 0.866731 -0.059550 -v 0.085925 0.077730 0.145411 -vn 0.515033 0.853180 -0.082618 -v 0.085582 0.077742 0.145517 -vn -0.508584 0.845635 0.162003 -v 0.085954 0.077740 0.145582 -vn 0.497387 0.857584 0.130978 -v 0.085618 0.077712 0.145721 -vn -0.484618 0.808922 0.332853 -v 0.085980 0.077712 0.145721 -vn 0.511038 0.804420 0.302901 -v 0.085626 0.077697 0.145760 -vn -0.513332 0.683011 0.519602 -v 0.085999 0.077669 0.145819 -vn 0.504274 0.704644 0.499183 -v 0.085668 0.077560 0.145962 -vn -0.508107 0.555695 0.658051 -v 0.086034 0.077541 0.145980 -vn 0.509286 0.584782 0.631394 -v 0.085672 0.077541 0.145980 -vn -0.505381 0.404267 0.762337 -v 0.086039 0.077515 0.146002 -vn 0.512908 0.428939 0.743597 -v 0.085709 0.077357 0.146092 -vn -0.510740 0.198092 0.836603 -v 0.086082 0.077297 0.146111 -vn 0.488467 0.230403 0.841614 -v 0.085727 0.077264 0.146119 -vn -0.498440 0.023925 0.866594 -v 0.086088 0.077264 0.146119 -vn 0.509073 0.053322 0.859070 -v 0.085754 0.077112 0.146131 -vn -0.515155 -0.186789 0.836496 -v 0.086126 0.077050 0.146124 -vn 0.497925 -0.170431 0.850308 -v 0.085781 0.076954 0.146101 -vn -0.497410 -0.361795 0.788472 -v 0.086142 0.076953 0.146101 -vn -0.518055 -0.543495 0.660479 -v 0.086165 0.076827 0.146042 -vn 0.522503 -0.336801 0.783298 -v 0.085793 0.076880 0.146071 -vn -0.501588 -0.672859 0.543755 -v 0.086196 0.076694 0.145930 -vn 0.522540 -0.580104 0.624845 -v 0.085837 0.076685 0.145920 -vn -0.512233 -0.780959 0.357380 -v 0.086210 0.076648 0.145871 -vn 0.508288 -0.768223 0.389200 -v 0.085880 0.076568 0.145705 -vn -0.519988 -0.850873 0.075017 -v 0.086251 0.076554 0.145649 -vn 0.505350 -0.838370 0.204343 -v 0.085889 0.076555 0.145653 -vn 0.514043 -0.857389 0.025396 -v 0.085921 0.076546 0.145466 -vn -0.512194 -0.832009 -0.213118 -v 0.086292 0.076556 0.145407 -vn 0.494212 -0.848054 -0.191206 -v 0.085943 0.076573 0.145343 -vn -0.495379 -0.775054 -0.392290 -v 0.086305 0.076573 0.145343 -vn 0.511950 -0.776962 -0.366382 -v 0.085965 0.076624 0.145230 -vn -0.511404 -0.644917 -0.567933 -v 0.086337 0.076656 0.145181 -vn 0.498604 -0.665110 -0.555898 -v 0.085997 0.076744 0.145083 -vn -0.500419 0.406593 -0.764371 -v 0.086467 0.077332 0.144962 -vn -0.515965 0.249987 -0.819321 -v 0.086463 0.077305 0.144954 -vn 0.510664 0.014251 -0.859662 -v 0.086092 0.077252 0.144942 -vn -0.509741 0.045650 -0.859116 -v 0.086420 0.077063 0.144937 -vn 0.526931 -0.292327 -0.798053 -v 0.086049 0.077006 0.144947 -vn -0.510188 -0.148967 -0.847064 -v 0.086413 0.077021 0.144944 -vn 0.521569 -0.530331 -0.668367 -v 0.086006 0.076783 0.145051 -vn -0.519072 -0.324212 -0.790855 -v 0.086376 0.076830 0.145019 -vn -0.487390 -0.534226 -0.690691 -v 0.086359 0.076744 0.145083 -vn 0.497087 0.229529 -0.836792 -v 0.086106 0.077332 0.144962 -vn 0.512729 0.386688 -0.766539 -v 0.086132 0.077474 0.145031 -vn -0.512177 0.582030 -0.631598 -v 0.086503 0.077519 0.145064 -vn 0.493964 0.573267 -0.653732 -v 0.086160 0.077591 0.145133 -vn -0.493980 0.714095 -0.496037 -v 0.086521 0.077591 0.145133 -vn 0.512278 0.693240 -0.506942 -v 0.086177 0.077648 0.145208 -vn -0.513081 0.804793 -0.298423 -v 0.086548 0.077676 0.145256 -vn 0.500688 0.805388 -0.317273 -v 0.086214 0.077730 0.145410 -vn -0.499081 0.856318 -0.132809 -v 0.086575 0.077730 0.145410 -vn -0.510307 0.856317 0.079427 -v 0.086588 0.077741 0.145485 -vn 0.515644 0.842560 -0.155576 -v 0.086218 0.077734 0.145433 -vn 0.509939 0.858691 0.051113 -v 0.086260 0.077725 0.145677 -vn -0.525886 0.763880 0.374075 -v 0.086631 0.077709 0.145729 -vn 0.509055 0.824861 0.245899 -v 0.086268 0.077712 0.145721 -vn -0.521257 0.606972 0.599897 -v 0.086674 0.077583 0.145939 -vn 0.517956 0.748678 0.413767 -v 0.086304 0.077616 0.145900 -vn -0.498224 0.479029 0.722707 -v 0.086684 0.077541 0.145980 -vn 0.498467 0.627673 0.597961 -v 0.086322 0.077541 0.145980 -vn 0.514817 0.484737 0.707103 -v 0.086344 0.077435 0.146055 -vn -0.511858 0.279081 0.812475 -v 0.086714 0.077389 0.146078 -vn 0.495649 0.300124 0.815020 -v 0.086377 0.077264 0.146119 -vn -0.494807 0.097248 0.863544 -v 0.086738 0.077264 0.146119 -vn 0.512476 0.114864 0.850985 -v 0.086388 0.077198 0.146129 -vn -0.514100 -0.118140 0.849556 -v 0.086759 0.077147 0.146132 -vn 0.521008 -0.173297 0.835774 -v 0.086430 0.076957 0.146102 -vn 0.500022 -0.619237 0.605412 -v 0.086485 0.076694 0.145930 -vn -0.503579 -0.742271 0.442088 -v 0.086846 0.076694 0.145930 -vn -0.510911 -0.632196 0.582493 -v 0.086842 0.076710 0.145948 -vn 0.512250 -0.445802 0.734072 -v 0.086471 0.076747 0.145983 -vn -0.507845 -0.467652 0.723460 -v 0.086799 0.076912 0.146086 -vn -0.507741 -0.296009 0.809060 -v 0.086792 0.076954 0.146101 -vn -0.521043 -0.816648 0.248194 -v 0.086886 0.076580 0.145739 -vn 0.515966 -0.722079 0.460849 -v 0.086516 0.076598 0.145784 -vn -0.497629 -0.863900 0.077732 -v 0.086900 0.076555 0.145653 -vn 0.497357 -0.825783 0.265928 -v 0.086539 0.076555 0.145653 -vn 0.515367 -0.852656 0.085872 -v 0.086556 0.076543 0.145552 -vn -0.509494 -0.848467 -0.143250 -v 0.086925 0.076543 0.145504 -vn 0.498818 -0.857503 -0.125975 -v 0.086593 0.076573 0.145343 -vn -0.493225 -0.808720 -0.320469 -v 0.086955 0.076573 0.145343 -vn 0.511525 -0.805966 -0.297927 -v 0.086600 0.076586 0.145308 -vn -0.513177 -0.692566 -0.506954 -v 0.086970 0.076605 0.145264 -vn 0.506900 -0.707722 -0.492120 -v 0.086642 0.076721 0.145105 -vn -0.521577 -0.478248 -0.706567 -v 0.087011 0.076754 0.145075 -vn 0.510070 -0.586061 -0.629572 -v 0.086647 0.076744 0.145083 -vn 0.513607 -0.434147 -0.740084 -v 0.086683 0.076923 0.144973 -vn -0.512306 -0.221868 -0.829649 -v 0.087053 0.076966 0.144958 -vn 0.486181 -0.233235 -0.842158 -v 0.086702 0.077021 0.144944 -vn -0.496814 -0.039723 -0.866948 -v 0.087063 0.077021 0.144944 -vn 0.508593 -0.057587 -0.859079 -v 0.086728 0.077168 0.144932 -vn -0.515026 0.171043 -0.839936 -v 0.087097 0.077212 0.144936 -vn 0.497472 0.165009 -0.851641 -v 0.086756 0.077331 0.144962 -vn -0.501410 0.864933 -0.021870 -v 0.087225 0.077730 0.145411 -vn -0.515027 0.836818 -0.185697 -v 0.087223 0.077726 0.145393 -vn 0.509145 0.764357 -0.395639 -v 0.086855 0.077715 0.145353 -vn -0.510632 0.771748 -0.379026 -v 0.087181 0.077624 0.145173 -vn 0.524087 0.573737 -0.629411 -v 0.086811 0.077596 0.145139 -vn -0.506954 0.663790 -0.549891 -v 0.087171 0.077591 0.145133 -vn 0.520871 0.334227 -0.785484 -v 0.086768 0.077400 0.144989 -vn -0.516268 0.528339 -0.674037 -v 0.087136 0.077438 0.145010 -vn -0.498075 0.345736 -0.795229 -v 0.087117 0.077331 0.144962 -vn 0.504101 0.838478 -0.206969 -v 0.086864 0.077730 0.145411 -vn 0.513503 0.857568 -0.029875 -v 0.086895 0.077739 0.145592 -vn -0.512704 0.836167 0.194831 -v 0.087263 0.077734 0.145634 -vn 0.494306 0.848973 0.186836 -v 0.086918 0.077712 0.145721 -vn -0.494641 0.782825 0.377511 -v 0.087280 0.077712 0.145721 -vn 0.512207 0.778332 0.363103 -v 0.086939 0.077664 0.145828 -vn -0.512445 0.656332 0.553740 -v 0.087308 0.077642 0.145864 -vn 0.498854 0.668580 0.551493 -v 0.086972 0.077541 0.145980 -vn -0.495862 0.540410 0.679763 -v 0.087334 0.077541 0.145980 -vn -0.511071 0.351822 0.784237 -v 0.087348 0.077474 0.146032 -vn 0.517011 0.537411 0.666250 -v 0.086980 0.077506 0.146009 -vn 0.506890 0.363873 0.781446 -v 0.087023 0.077285 0.146114 -vn -0.509107 0.155962 0.846455 -v 0.087388 0.077264 0.146119 -vn 0.508900 0.192200 0.839095 -v 0.087027 0.077264 0.146119 -vn -0.506613 -0.022313 0.861885 -v 0.087391 0.077245 0.146123 -vn 0.511097 -0.011328 0.859448 -v 0.087067 0.077038 0.146122 -vn -0.517210 -0.227119 0.825173 -v 0.087434 0.077001 0.146115 -vn -0.498734 -0.393852 0.772104 -v 0.087442 0.076953 0.146101 -vn 0.495172 -0.227125 0.838582 -v 0.087081 0.076953 0.146101 -vn 0.512323 -0.383268 0.768525 -v 0.087106 0.076816 0.146035 -vn -0.512191 -0.569117 0.643247 -v 0.087474 0.076784 0.146013 -vn 0.494748 -0.569307 0.656593 -v 0.087135 0.076694 0.145930 -vn -0.494621 -0.703916 0.509756 -v 0.087496 0.076694 0.145930 -vn 0.512930 -0.690928 0.509432 -v 0.087151 0.076640 0.145859 -vn -0.513608 -0.798023 0.315224 -v 0.087519 0.076620 0.145827 -vn 0.501461 -0.802880 0.322368 -v 0.087189 0.076555 0.145653 -vn -0.505579 -0.850726 0.143719 -v 0.087550 0.076555 0.145653 -vn -0.509009 -0.858976 -0.055398 -v 0.087559 0.076546 0.145600 -vn 0.515147 -0.842197 0.159149 -v 0.087192 0.076551 0.145635 -vn 0.510558 -0.858744 -0.043472 -v 0.087234 0.076559 0.145391 -vn -0.523657 -0.780200 -0.342157 -v 0.087602 0.076569 0.145356 -vn 0.506763 -0.827093 -0.243121 -v 0.087243 0.076573 0.145343 -vn -0.520329 -0.622595 -0.584495 -v 0.087646 0.076687 0.145141 -vn 0.514892 -0.751159 -0.413094 -v 0.087278 0.076665 0.145168 -vn -0.497348 -0.492251 -0.714377 -v 0.087659 0.076744 0.145083 -vn 0.498171 -0.630677 -0.595040 -v 0.087297 0.076744 0.145083 -vn 0.515192 -0.487299 -0.705065 -v 0.087318 0.076845 0.145011 -vn -0.508999 -0.293029 -0.809354 -v 0.087685 0.076875 0.144994 -vn 0.497004 -0.304563 -0.812545 -v 0.087352 0.077021 0.144944 -vn -0.489710 -0.122173 -0.863283 -v 0.087713 0.077021 0.144944 -vn 0.513162 -0.119646 -0.849912 -v 0.087362 0.077081 0.144935 -vn -0.513749 0.099716 -0.852126 -v 0.087730 0.077115 0.144932 -vn 0.523271 0.164936 -0.836052 -v 0.087404 0.077323 0.144959 -vn 0.496883 0.617875 -0.609375 -v 0.087460 0.077591 0.145133 -vn -0.500644 0.734895 -0.457477 -v 0.087821 0.077591 0.145133 -vn -0.512749 0.614224 -0.599848 -v 0.087813 0.077558 0.145099 -vn 0.513108 0.439280 -0.737396 -v 0.087446 0.077534 0.145077 -vn -0.506600 0.447548 -0.736924 -v 0.087771 0.077353 0.144970 -vn -0.511941 0.284365 -0.810588 -v 0.087767 0.077331 0.144962 -vn -0.519255 0.812751 -0.264218 -v 0.087857 0.077697 0.145303 -vn 0.513283 0.722327 -0.463448 -v 0.087490 0.077685 0.145274 -vn -0.499223 0.861581 -0.091947 -v 0.087875 0.077730 0.145410 -vn 0.498747 0.824061 -0.268654 -v 0.087514 0.077730 0.145410 -vn -0.513865 0.848482 0.126572 -v 0.087896 0.077742 0.145537 -vn 0.519548 0.849780 -0.089132 -v 0.087530 0.077742 0.145506 -vn -0.502662 0.808402 0.306295 -v 0.087930 0.077712 0.145721 -vn 0.502652 0.856455 0.117581 -v 0.087568 0.077712 0.145721 -vn 0.512363 0.807219 0.293056 -v 0.087574 0.077701 0.145750 -vn -0.511711 0.706815 0.488431 -v 0.087941 0.077690 0.145778 -vn 0.507604 0.711819 0.485440 -v 0.087617 0.077568 0.145955 -vn -0.523593 0.502723 0.687837 -v 0.087982 0.077547 0.145974 -vn 0.510491 0.586672 0.628661 -v 0.087622 0.077541 0.145980 -vn 0.514637 0.439217 0.736368 -v 0.087657 0.077368 0.146088 -vn -0.514130 0.245520 0.821822 -v 0.088023 0.077340 0.146098 -vn 0.484317 0.236494 0.842322 -v 0.087677 0.077264 0.146119 -vn -0.495756 0.056106 0.866648 -v 0.088038 0.077264 0.146119 -vn 0.508536 0.061525 0.858840 -v 0.087702 0.077123 0.146131 -vn -0.512198 -0.158577 0.844101 -v 0.088068 0.077095 0.146130 -vn 0.497578 -0.159336 0.852660 -v 0.087731 0.076954 0.146101 -vn -0.499719 -0.865427 0.036290 -v 0.088200 0.076555 0.145653 -vn -0.516772 -0.830447 0.208097 -v 0.088194 0.076564 0.145691 -vn 0.510231 -0.760210 0.402176 -v 0.087829 0.076571 0.145715 -vn -0.508943 -0.762025 0.400369 -v 0.088151 0.076675 0.145908 -vn 0.526082 -0.567273 0.633592 -v 0.087785 0.076693 0.145929 -vn -0.511037 -0.655330 0.556224 -v 0.088146 0.076694 0.145930 -vn 0.519945 -0.331168 0.787392 -v 0.087742 0.076890 0.146076 -vn -0.514452 -0.512748 0.687334 -v 0.088107 0.076866 0.146064 -vn -0.492339 -0.323892 0.807896 -v 0.088092 0.076954 0.146101 -vn 0.502549 -0.838669 0.209949 -v 0.087839 0.076555 0.145653 -vn 0.513116 -0.857656 0.033724 -v 0.087869 0.076545 0.145477 -vn -0.512937 -0.839833 -0.177698 -v 0.088234 0.076548 0.145452 -vn 0.494808 -0.849742 -0.181946 -v 0.087893 0.076573 0.145343 -vn -0.494926 -0.789895 -0.362098 -v 0.088255 0.076573 0.145343 -vn 0.512958 -0.779347 -0.359851 -v 0.087913 0.076618 0.145239 -vn -0.513198 -0.667595 -0.539393 -v 0.088279 0.076631 0.145218 -vn 0.499579 -0.671866 -0.546824 -v 0.087947 0.076744 0.145083 -vn -0.502909 -0.546936 -0.669286 -v 0.088309 0.076744 0.145083 -vn -0.510316 -0.370184 -0.776235 -v 0.088319 0.076793 0.145044 -vn 0.516918 -0.540065 -0.664173 -v 0.087954 0.076775 0.145057 -vn 0.508781 -0.370323 -0.777176 -v 0.087997 0.076995 0.144950 -vn -0.525998 -0.079283 -0.846782 -v 0.088362 0.077017 0.144945 -vn 0.511117 -0.192003 -0.837792 -v 0.088002 0.077021 0.144944 -vn -0.519752 0.202720 -0.829917 -v 0.088406 0.077263 0.144944 -vn 0.513698 0.002560 -0.857967 -v 0.088041 0.077242 0.144940 -vn -0.497609 0.380412 -0.779533 -v 0.088417 0.077332 0.144962 -vn 0.493215 0.224750 -0.840373 -v 0.088056 0.077332 0.144962 -vn 0.512390 0.379923 -0.770140 -v 0.088080 0.077465 0.145025 -vn -0.508907 0.560245 -0.653559 -v 0.088445 0.077482 0.145037 -vn 0.495827 0.564954 -0.659532 -v 0.088110 0.077591 0.145133 -vn -0.486325 0.691330 -0.534369 -v 0.088471 0.077591 0.145133 -vn 0.514917 0.690718 -0.507709 -v 0.088125 0.077642 0.145199 -vn -0.514983 0.790944 -0.330453 -v 0.088490 0.077653 0.145217 -vn 0.524946 0.815231 -0.244602 -v 0.088166 0.077733 0.145423 -vn 0.503435 0.830088 0.239807 -v 0.088218 0.077712 0.145721 -vn -0.501875 0.759449 0.413955 -v 0.088580 0.077712 0.145721 -vn -0.513384 0.823560 0.241218 -v 0.088573 0.077723 0.145685 -vn 0.511490 0.858537 0.035933 -v 0.088208 0.077727 0.145666 -vn -0.507631 0.861000 0.031466 -v 0.088530 0.077736 0.145442 -vn -0.511992 0.844760 -0.155706 -v 0.088525 0.077730 0.145410 -vn -0.518604 0.631900 0.575979 -v 0.088617 0.077612 0.145905 -vn 0.512410 0.753480 0.411951 -v 0.088253 0.077623 0.145891 -vn -0.498221 0.504040 0.705492 -v 0.088634 0.077541 0.145980 -vn 0.498672 0.632847 0.592310 -v 0.088272 0.077541 0.145980 -vn -0.511963 0.309222 0.801421 -v 0.088656 0.077430 0.146058 -vn 0.518026 0.489113 0.701724 -v 0.088292 0.077445 0.146050 -vn -0.498805 0.133494 0.856372 -v 0.088688 0.077264 0.146119 -vn 0.494154 -0.616084 0.613394 -v 0.088435 0.076694 0.145930 -vn -0.514843 -0.595613 0.616589 -v 0.088784 0.076743 0.145980 -vn 0.514313 -0.432645 0.740473 -v 0.088420 0.076755 0.145990 -vn -0.526404 -0.356706 0.771790 -v 0.088742 0.076953 0.146101 -vn 0.526080 -0.156410 0.835928 -v 0.088378 0.076967 0.146105 -vn -0.513087 -0.081191 0.854488 -v 0.088701 0.077193 0.146129 -vn 0.514252 0.124425 0.848566 -v 0.088336 0.077210 0.146128 -vn 0.499730 0.310586 0.808583 -v 0.088327 0.077264 0.146119 -vn 0.791718 0.526843 0.309223 -v 0.088903 0.077621 0.145894 -vn 0.395053 0.881647 0.258132 -v 0.088903 0.077712 0.145721 -vn 0.674326 0.688178 0.267761 -v 0.088887 0.077669 0.145819 -vn 0.496125 0.850208 0.176087 -v 0.088868 0.077712 0.145721 -vn 0.613838 0.788425 -0.039863 -v 0.088843 0.077740 0.145581 -vn 0.394840 0.896992 -0.198762 -v 0.088903 0.077730 0.145410 -vn 0.500951 0.838887 -0.212878 -v 0.088814 0.077730 0.145411 -vn 0.386862 0.291749 -0.874769 -v 0.088903 0.077331 0.144962 -vn 0.531519 0.328325 -0.780827 -v 0.088716 0.077390 0.144985 -vn 0.367749 0.701752 -0.610167 -v 0.088903 0.077591 0.145133 -vn 0.537321 0.563677 -0.627339 -v 0.088759 0.077589 0.145130 -vn 0.574215 0.699114 -0.426047 -v 0.088803 0.077712 0.145343 -vn 0.387695 -0.188437 -0.902322 -v 0.088903 0.077021 0.144944 -vn 0.527499 -0.058510 -0.847538 -v 0.088676 0.077157 0.144932 -vn 0.498603 0.152372 -0.853334 -v 0.088706 0.077331 0.144962 -vn 0.517466 -0.716107 -0.468422 -v 0.088591 0.076713 0.145112 -vn 0.508560 -0.590024 -0.627087 -v 0.088597 0.076744 0.145083 -vn 0.376773 -0.620966 -0.687345 -v 0.088903 0.076744 0.145083 -vn 0.523179 -0.439523 -0.730139 -v 0.088631 0.076912 0.144977 -vn 0.496572 -0.250802 -0.830972 -v 0.088652 0.077021 0.144944 -vn 0.520156 -0.802810 -0.291434 -v 0.088548 0.076582 0.145318 -vn 0.373853 -0.838448 -0.396535 -v 0.088903 0.076573 0.145343 -vn 0.502397 -0.857026 -0.114468 -v 0.088543 0.076573 0.145343 -vn 0.382843 -0.900590 -0.205837 -v 0.088903 0.076570 0.145350 -vn 0.518304 -0.850244 0.091904 -v 0.088504 0.076543 0.145562 -vn -0.506604 -0.855919 -0.103702 -v 0.088867 0.076543 0.145549 -vn 0.497902 -0.822975 0.273508 -v 0.088489 0.076555 0.145653 -vn -0.512963 -0.852125 0.103690 -v 0.088850 0.076555 0.145653 -vn 0.511252 -0.722025 0.466155 -v 0.088464 0.076603 0.145794 -vn -0.518550 -0.807282 0.281783 -v 0.088828 0.076597 0.145781 -vn -0.498227 -0.726696 0.472951 -v 0.088796 0.076694 0.145930 -vn 0.004297 0.522355 -0.852717 -v 0.085338 0.077616 0.144826 -vn -0.007806 0.699231 -0.714853 -v 0.085353 0.077709 0.144898 -vn 0.861980 0.235931 -0.448695 -v 0.085425 0.077626 0.144991 -vn 0.009741 0.144352 -0.989478 -v 0.085299 0.077304 0.144697 -vn -0.007784 0.357854 -0.933745 -v 0.085312 0.077412 0.144725 -vn 0.864817 0.042870 -0.500254 -v 0.085384 0.077372 0.144844 -vn 0.006379 -0.263755 -0.964569 -v 0.085255 0.076956 0.144702 -vn -0.005446 -0.040247 -0.999175 -v 0.085270 0.077071 0.144685 -vn 0.862638 -0.160594 -0.479652 -v 0.085342 0.077082 0.144809 -vn 0.004937 -0.625105 -0.780525 -v 0.085212 0.076640 0.144846 -vn -0.008906 -0.438180 -0.898843 -v 0.085225 0.076734 0.144786 -vn 0.862472 -0.341791 -0.373257 -v 0.085298 0.076794 0.144896 -vn 0.008236 -0.882550 -0.470146 -v 0.085172 0.076412 0.145096 -vn -0.003710 -0.756931 -0.653485 -v 0.085186 0.076476 0.145004 -vn 0.862737 -0.460382 -0.209125 -v 0.085258 0.076574 0.145081 -vn 0.004346 -0.997074 -0.076322 -v 0.085127 0.076299 0.145429 -vn -0.006846 -0.954728 -0.297403 -v 0.085142 0.076320 0.145318 -vn 0.862425 -0.506166 -0.004278 -v 0.085214 0.076441 0.145349 -vn 0.009138 -0.946440 0.322752 -v 0.085087 0.076326 0.145766 -vn -0.008679 -0.994170 0.107470 -v 0.085099 0.076303 0.145663 -vn 0.863335 -0.467481 0.190039 -v 0.085171 0.076426 0.145644 -vn 0.006311 -0.739069 0.673600 -v 0.085044 0.076487 0.146073 -vn -0.004398 -0.871164 0.490972 -v 0.085059 0.076422 0.145983 -vn 0.861946 -0.353645 0.363296 -v 0.085131 0.076528 0.145916 -vn 0.003644 -0.409697 0.912215 -v 0.085001 0.076760 0.146290 -vn -0.007983 -0.600593 0.799515 -v 0.085014 0.076667 0.146236 -vn 0.861725 -0.174909 0.476274 -v 0.085086 0.076737 0.146132 -vn 0.008069 -0.016885 0.999825 -v 0.084961 0.077085 0.146380 -vn -0.003796 -0.236462 0.971633 -v 0.084974 0.076979 0.146366 -vn 0.862697 0.024455 0.505130 -v 0.085046 0.077003 0.146243 -vn 0.004254 0.386067 0.922461 -v 0.084917 0.077432 0.146331 -vn -0.005760 0.169593 0.985497 -v 0.084930 0.077328 0.146361 -vn 0.863882 0.226486 0.449901 -v 0.085002 0.077301 0.146239 -vn 0.007712 0.718901 0.695070 -v 0.084876 0.077723 0.146152 -vn -0.008705 0.549186 0.835655 -v 0.084887 0.077645 0.146217 -vn 0.862596 0.383506 0.329927 -v 0.084959 0.077571 0.146116 -vn 0.006175 0.936036 0.351851 -v 0.084834 0.077921 0.145872 -vn -0.003362 0.834061 0.551662 -v 0.084847 0.077873 0.145966 -vn 0.861597 0.485641 0.147662 -v 0.084919 0.077766 0.145902 -vn 0.002795 0.998694 -0.051016 -v 0.084789 0.077992 0.145529 -vn -0.006971 0.985293 0.170730 -v 0.084802 0.077987 0.145632 -vn 0.861202 0.504307 -0.063288 -v 0.084874 0.077862 0.145617 -vn 0.007859 0.897835 -0.440261 -v 0.084750 0.077925 0.145199 -vn -0.004267 0.972565 -0.232592 -v 0.084762 0.077958 0.145293 -vn 0.862948 0.437634 -0.252581 -v 0.084834 0.077838 0.145328 -vn 0.004181 0.645665 -0.763609 -v 0.084706 0.077724 0.144912 -vn -0.004732 0.800309 -0.599570 -v 0.084719 0.077795 0.144987 -vn 0.862983 0.298598 -0.407554 -v 0.084791 0.077699 0.145067 -vn 0.005590 0.290610 -0.956825 -v 0.084664 0.077431 0.144732 -vn -0.007979 0.493071 -0.869952 -v 0.084675 0.077521 0.144770 -vn 0.861830 0.117133 -0.493487 -v 0.084747 0.077465 0.144882 -vn 0.006037 -0.112321 -0.993654 -v 0.084623 0.077094 0.144683 -vn -0.002444 0.110615 -0.993860 -v 0.084635 0.077194 0.144683 -vn 0.862204 -0.093847 -0.497792 -v 0.084708 0.077186 0.144808 -vn 0.002338 -0.500578 -0.865688 -v 0.084578 0.076755 0.144775 -vn -0.006009 -0.296529 -0.955005 -v 0.084591 0.076846 0.144735 -vn 0.861406 -0.286653 -0.419296 -v 0.084663 0.076889 0.144852 -vn 0.007585 -0.801022 -0.598587 -v 0.084539 0.076492 0.144985 -vn -0.005088 -0.650600 -0.759404 -v 0.084550 0.076556 0.144916 -vn 0.863513 -0.424100 -0.272919 -v 0.084622 0.076642 0.145007 -vn 0.004087 -0.973747 -0.227598 -v 0.084495 0.076327 0.145292 -vn -0.003636 -0.898177 -0.439619 -v 0.084508 0.076360 0.145200 -vn 0.862208 -0.500008 -0.081179 -v 0.084580 0.076475 0.145249 -vn 0.003730 -0.984098 0.177589 -v 0.084452 0.076299 0.145637 -vn -0.007022 -0.999086 -0.042169 -v 0.084463 0.076293 0.145545 -vn 0.861173 -0.492970 0.123942 -v 0.084535 0.076418 0.145543 -vn 0.005826 -0.833801 0.552034 -v 0.084412 0.076407 0.145958 -vn -0.001849 -0.934942 0.354797 -v 0.084424 0.076365 0.145875 -vn 0.861762 -0.400436 0.311476 -v 0.084496 0.076479 0.145824 -vn 0.002113 -0.542542 0.840026 -v 0.084367 0.076643 0.146219 -vn -0.004892 -0.715430 0.698668 -v 0.084379 0.076570 0.146160 -vn 0.861430 -0.241214 0.446938 -v 0.084451 0.076654 0.146068 -vn 0.007284 -0.167509 0.985844 -v 0.084327 0.076951 0.146360 -vn -0.006084 -0.378869 0.925430 -v 0.084337 0.076866 0.146335 -vn 0.864134 -0.047982 0.500969 -v 0.084410 0.076907 0.146217 -vn 0.003951 0.240184 0.970719 -v 0.084284 0.077297 0.146367 -vn -0.002640 0.017732 0.999839 -v 0.084296 0.077206 0.146379 -vn 0.861973 0.155633 0.482474 -v 0.084368 0.077197 0.146255 -vn 0.002294 0.606588 0.795013 -v 0.084241 0.077620 0.146235 -vn -0.005998 0.417773 0.908532 -v 0.084251 0.077544 0.146281 -vn 0.861666 0.338861 0.377763 -v 0.084324 0.077485 0.146171 -vn 0.005591 0.870927 0.491380 -v 0.084201 0.077856 0.145994 -vn -0.001692 0.742035 0.670359 -v 0.084212 0.077804 0.146065 -vn 0.862013 0.459314 0.214395 -v 0.084284 0.077707 0.145987 -vn 0.001975 0.994944 0.100412 -v 0.084156 0.077982 0.145666 -vn -0.003806 0.947745 0.319007 -v 0.084168 0.077963 0.145753 -vn 0.861883 0.507013 0.009775 -v 0.084240 0.077842 0.145720 -vn 0.006320 0.953766 -0.300482 -v 0.084116 0.077967 0.145326 -vn -0.006552 0.996345 -0.085167 -v 0.084125 0.077983 0.145407 -vn 0.862399 0.470955 -0.185661 -v 0.084197 0.077860 0.145426 -vn 0.003709 0.755342 -0.655320 -v 0.084074 0.077818 0.145016 -vn -0.001616 0.881887 -0.471458 -v 0.084085 0.077867 0.145087 -vn 0.861107 0.358378 -0.360639 -v 0.084157 0.077760 0.145152 -vn 0.001121 0.431364 -0.902177 -v 0.084029 0.077553 0.144787 -vn -0.004944 0.618509 -0.785762 -v 0.084040 0.077625 0.144832 -vn 0.860890 0.180364 -0.475749 -v 0.084112 0.077554 0.144935 -vn 0.005377 0.041083 -0.999141 -v 0.083990 0.077232 0.144686 -vn -0.001894 0.258207 -0.966088 -v 0.084000 0.077313 0.144699 -vn 0.861948 -0.019396 -0.506625 -v 0.084072 0.077288 0.144821 -vn 0.001762 -0.363479 -0.931601 -v 0.083946 0.076883 0.144722 -vn -0.002786 -0.147392 -0.989074 -v 0.083956 0.076964 0.144700 -vn 0.863105 -0.222287 -0.453474 -v 0.084028 0.076990 0.144823 -vn 0.004419 -0.702405 -0.711764 -v 0.083904 0.076585 0.144890 -vn -0.005904 -0.530575 -0.847618 -v 0.083913 0.076646 0.144842 -vn 0.861661 -0.381351 -0.334832 -v 0.083985 0.076719 0.144943 -vn 0.003475 -0.927085 -0.374836 -v 0.083863 0.076377 0.145162 -vn -0.000569 -0.821718 -0.569894 -v 0.083873 0.076416 0.145091 -vn 0.860721 -0.485555 -0.152955 -v 0.083945 0.076523 0.145156 -vn 0.000326 -0.999637 0.026959 -v 0.083818 0.076293 0.145502 -vn -0.003859 -0.981231 -0.192797 -v 0.083828 0.076299 0.145423 -vn 0.860352 -0.506369 0.058178 -v 0.083900 0.076423 0.145439 -vn 0.005060 -0.908219 0.418465 -v 0.083779 0.076348 0.145835 -vn -0.002391 -0.977514 0.210859 -v 0.083788 0.076324 0.145762 -vn 0.862166 -0.441269 0.248902 -v 0.083860 0.076445 0.145729 -vn 0.001534 -0.664306 0.747460 -v 0.083735 0.076537 0.146128 -vn -0.001630 -0.813490 0.581576 -v 0.083745 0.076485 0.146070 -vn 0.861930 -0.304280 0.405575 -v 0.083817 0.076582 0.145991 -vn 0.002404 -0.313291 0.949654 -v 0.083692 0.076825 0.146320 -vn -0.004881 -0.512150 0.858882 -v 0.083701 0.076758 0.146289 -vn 0.860781 -0.122260 0.494074 -v 0.083773 0.076814 0.146178 -vn 0.003216 0.087736 0.996139 -v 0.083652 0.077159 0.146381 -vn 0.000157 -0.132407 0.991195 -v 0.083661 0.077084 0.146380 -vn 0.861195 0.089084 0.500407 -v 0.083734 0.077092 0.146255 -vn -0.000205 0.479326 0.877637 -v 0.083607 0.077501 0.146302 -vn -0.002756 0.275142 0.961400 -v 0.083617 0.077432 0.146331 -vn 0.860516 0.283133 0.423495 -v 0.083689 0.077389 0.146213 -vn 0.004770 0.786310 0.617814 -v 0.083568 0.077773 0.146102 -vn -0.003085 0.633591 0.773662 -v 0.083576 0.077724 0.146152 -vn 0.863329 0.421621 0.277306 -v 0.083648 0.077638 0.146061 -vn 0.001315 0.967790 0.251755 -v 0.083524 0.077948 0.145802 -vn -0.000597 0.888266 0.459329 -v 0.083534 0.077922 0.145870 -vn 0.861178 0.500823 0.086889 -v 0.083606 0.077808 0.145820 -vn 0.000740 0.988096 -0.153837 -v 0.083481 0.077989 0.145457 -vn -0.003817 0.997933 0.064152 -v 0.083489 0.077992 0.145526 -vn 0.860135 0.495815 -0.119728 -v 0.083561 0.077867 0.145527 -vn 0.003016 0.847234 -0.531212 -v 0.083441 0.077893 0.145133 -vn 0.000473 0.942518 -0.334154 -v 0.083450 0.077923 0.145195 -vn 0.860694 0.404969 -0.308557 -v 0.083522 0.077808 0.145245 -vn -0.000503 0.563051 -0.826422 -v 0.083396 0.077668 0.144863 -vn -0.001613 0.730696 -0.682701 -v 0.083405 0.077721 0.144908 -vn 0.860518 0.246531 -0.445792 -v 0.083477 0.077636 0.145000 -vn 0.004378 0.191187 -0.981544 -v 0.083356 0.077364 0.144711 -vn -0.003917 0.399029 -0.916930 -v 0.083363 0.077426 0.144730 -vn 0.863041 0.052904 -0.502356 -v 0.083435 0.077384 0.144848 -vn 0.001059 -0.215824 -0.976432 -v 0.083314 0.077020 0.144690 -vn 0.000422 0.004008 -0.999992 -v 0.083322 0.077087 0.144683 -vn 0.860905 -0.151169 -0.485788 -v 0.083394 0.077095 0.144808 -vn -0.000551 -0.587088 -0.809523 -v 0.083269 0.076692 0.144811 -vn -0.002705 -0.397792 -0.917471 -v 0.083277 0.076748 0.144779 -vn 0.860495 -0.336439 -0.382565 -v 0.083349 0.076806 0.144889 -vn 0.002690 -0.858481 -0.512839 -v 0.083230 0.076447 0.145043 -vn 0.000567 -0.727200 -0.686425 -v 0.083238 0.076486 0.144992 -vn 0.860876 -0.458964 -0.219645 -v 0.083310 0.076582 0.145071 -vn -0.000720 -0.992137 -0.125152 -v 0.083186 0.076309 0.145365 -vn -0.000564 -0.940528 -0.339717 -v 0.083194 0.076324 0.145302 -vn 0.860953 -0.508463 -0.015015 -v 0.083266 0.076444 0.145336 -vn 0.002996 -0.960743 0.277423 -v 0.083144 0.076311 0.145707 -vn -0.003769 -0.997966 0.063633 -v 0.083151 0.076301 0.145648 -vn 0.861042 -0.474925 0.181804 -v 0.083223 0.076424 0.145631 -vn 0.000787 -0.771685 0.636004 -v 0.083103 0.076448 0.146021 -vn 0.001419 -0.891848 0.452334 -v 0.083111 0.076414 0.145969 -vn 0.859844 -0.363349 0.358671 -v 0.083183 0.076521 0.145905 -vn -0.001569 -0.453392 0.891310 -v 0.083058 0.076704 0.146260 -vn -0.001605 -0.635462 0.772131 -v 0.083066 0.076654 0.146227 -vn 0.859677 -0.185800 0.475851 -v 0.083138 0.076726 0.146125 -vn 0.002458 -0.065887 0.997824 -v 0.083019 0.077022 0.146373 -vn 0.000270 -0.279234 0.960223 -v 0.083026 0.076965 0.146363 -vn 0.860759 0.014690 0.508801 -v 0.083098 0.076991 0.146240 -vn -0.001032 0.339859 0.940476 -v 0.082975 0.077370 0.146350 -vn 0.000540 0.125905 0.992042 -v 0.082982 0.077313 0.146364 -vn 0.861896 0.218633 0.457531 -v 0.083054 0.077288 0.146242 -vn 0.000910 0.684941 0.728598 -v 0.082932 0.077677 0.146193 -vn -0.002647 0.512378 0.858756 -v 0.082939 0.077633 0.146226 -vn 0.860332 0.379823 0.339947 -v 0.083011 0.077561 0.146124 -vn 0.000497 0.917277 0.398250 -v 0.082892 0.077893 0.145930 -vn 0.002256 0.809335 0.587343 -v 0.082899 0.077865 0.145979 -vn 0.860438 0.485472 0.154800 -v 0.082971 0.077759 0.145913 -vn -0.002387 0.999995 -0.002077 -v 0.082847 0.077990 0.145593 -vn -0.000474 0.976835 0.213991 -v 0.082854 0.077985 0.145648 -vn 0.859562 0.508328 -0.052494 -v 0.082926 0.077861 0.145630 -vn 0.002113 0.918323 -0.395826 -v 0.082808 0.077947 0.145258 -vn -0.000162 0.981832 -0.189753 -v 0.082814 0.077963 0.145308 -vn 0.860919 0.445398 -0.245846 -v 0.082886 0.077842 0.145341 -vn -0.001331 0.683109 -0.730315 -v 0.082764 0.077770 0.144958 -vn 0.001597 0.825794 -0.563969 -v 0.082771 0.077805 0.144999 -vn 0.860420 0.310136 -0.404343 -v 0.082843 0.077708 0.145077 -vn -0.000811 0.336533 -0.941671 -v 0.082721 0.077489 0.144755 -vn -0.001595 0.530366 -0.847767 -v 0.082727 0.077534 0.144777 -vn 0.859328 0.127288 -0.495331 -v 0.082799 0.077477 0.144888 -vn 0.000243 -0.062394 -0.998052 -v 0.082681 0.077159 0.144682 -vn 0.002767 0.153509 -0.988143 -v 0.082687 0.077209 0.144684 -vn 0.859683 -0.084804 -0.503739 -v 0.082759 0.077199 0.144809 -vn -0.002916 -0.456973 -0.889476 -v 0.082636 0.076814 0.144748 -vn 0.000652 -0.254308 -0.967123 -v 0.082643 0.076860 0.144730 -vn 0.859177 -0.280228 -0.428120 -v 0.082715 0.076902 0.144848 -vn 0.001893 -0.770870 -0.636990 -v 0.082596 0.076533 0.144939 -vn -0.000898 -0.617017 -0.786949 -v 0.082601 0.076567 0.144906 -vn 0.861830 -0.421256 -0.282476 -v 0.082674 0.076651 0.144998 -vn -0.001643 -0.960997 -0.276555 -v 0.082553 0.076348 0.145231 -vn 0.002551 -0.878307 -0.478090 -v 0.082559 0.076366 0.145186 -vn 0.859630 -0.502491 -0.092412 -v 0.082632 0.076480 0.145237 -vn -0.002338 -0.991613 0.129223 -v 0.082510 0.076294 0.145575 -vn -0.000459 -0.996355 -0.085307 -v 0.082515 0.076292 0.145529 -vn 0.858636 -0.499305 0.115926 -v 0.082587 0.076417 0.145530 -vn -0.000090 -0.860512 0.509430 -v 0.082470 0.076377 0.145902 -vn 0.002981 -0.949400 0.314057 -v 0.082476 0.076359 0.145861 -vn 0.859098 -0.409938 0.306435 -v 0.082548 0.076474 0.145812 -vn -0.003264 -0.583945 0.811786 -v 0.082425 0.076592 0.146179 -vn 0.001695 -0.745122 0.666926 -v 0.082431 0.076559 0.146149 -vn 0.859094 -0.252019 0.445471 -v 0.082503 0.076644 0.146058 -vn 0.001240 -0.215368 0.976532 -v 0.082384 0.076891 0.146344 -vn -0.001356 -0.418212 0.908348 -v 0.082389 0.076852 0.146330 -vn 0.860495 -0.059497 0.505973 -v 0.082461 0.076895 0.146213 -vn -0.001965 0.190262 0.981731 -v 0.082343 0.077233 0.146377 -vn 0.003581 -0.025104 0.999678 -v 0.082348 0.077190 0.146380 -vn 0.858796 0.148054 0.490459 -v 0.082420 0.077183 0.146255 -vn -0.003518 0.566519 0.824041 -v 0.082298 0.077566 0.146268 -vn 0.000694 0.378354 0.925661 -v 0.082303 0.077530 0.146288 -vn 0.858838 0.334686 0.387793 -v 0.082375 0.077473 0.146177 -vn -0.000353 0.845127 0.534566 -v 0.082259 0.077819 0.146046 -vn 0.002887 0.712513 0.701653 -v 0.082264 0.077794 0.146077 -vn 0.859167 0.459567 0.225012 -v 0.082336 0.077699 0.145997 -vn -0.003622 0.988562 0.150769 -v 0.082215 0.077969 0.145730 -vn 0.002797 0.933138 0.359507 -v 0.082220 0.077959 0.145768 -vn 0.859492 0.510758 0.019974 -v 0.082292 0.077839 0.145733 -vn -0.000656 0.967328 -0.253527 -v 0.082173 0.077980 0.145386 -vn -0.000459 0.999071 -0.043096 -v 0.082177 0.077985 0.145422 -vn 0.859166 0.479555 -0.178495 -v 0.082249 0.077861 0.145438 -vn -0.002275 0.787975 -0.615703 -v 0.082132 0.077856 0.145069 -vn 0.004418 0.901008 -0.433780 -v 0.082137 0.077875 0.145101 -vn 0.857977 0.368740 -0.357640 -v 0.082209 0.077767 0.145164 -vn -0.004466 0.475811 -0.879536 -v 0.082087 0.077608 0.144820 -vn 0.001757 0.651414 -0.758721 -v 0.082092 0.077637 0.144841 -vn 0.857915 0.191299 -0.476851 -v 0.082164 0.077565 0.144942 -vn -0.000640 0.091463 -0.995808 -v 0.082048 0.077295 0.144695 -vn 0.002652 0.299379 -0.954131 -v 0.082052 0.077328 0.144702 -vn 0.858950 -0.010287 -0.511956 -v 0.082124 0.077301 0.144824 -vn -0.003947 -0.315237 -0.949005 -v 0.082004 0.076946 0.144705 -vn 0.003808 -0.105191 -0.994445 -v 0.082008 0.076980 0.144697 -vn 0.860076 -0.215661 -0.462341 -v 0.082080 0.077004 0.144820 -vn -0.002470 -0.666379 -0.745609 -v 0.081961 0.076632 0.144852 -vn 0.000682 -0.494565 -0.869140 -v 0.081965 0.076658 0.144833 -vn 0.858903 -0.379450 -0.343953 -v 0.082037 0.076729 0.144936 -vn -0.002545 -0.906508 -0.422181 -v 0.081921 0.076407 0.145105 -vn 0.005005 -0.796927 -0.604056 -v 0.081925 0.076424 0.145078 -vn 0.857682 -0.488402 -0.160762 -v 0.081997 0.076530 0.145144 -vn -0.005128 -0.999708 -0.023605 -v 0.081876 0.076298 0.145438 -vn 0.002921 -0.972180 -0.234218 -v 0.081880 0.076302 0.145408 -vn 0.855853 -0.515305 0.044457 -v 0.081952 0.076425 0.145426 -vn -0.000884 -0.928120 0.372279 -v 0.081836 0.076328 0.145776 -vn 0.002147 -0.985556 0.169337 -v 0.081840 0.076321 0.145748 -vn 0.854628 -0.458986 0.242782 -v 0.081912 0.076441 0.145716 -vn -0.004230 -0.702080 0.712086 -v 0.081793 0.076493 0.146080 -vn 0.004725 -0.837242 0.546813 -v 0.081797 0.076475 0.146058 -vn 0.854429 -0.320897 0.408626 -v 0.081869 0.076573 0.145980 -vn -0.004028 -0.360242 0.932850 -v 0.081750 0.076768 0.146295 -vn 0.001809 -0.547472 0.836822 -v 0.081753 0.076744 0.146282 -vn 0.855352 -0.135705 0.499957 -v 0.081825 0.076803 0.146172 -vn -0.002810 0.036132 0.999343 -v 0.081710 0.077094 0.146380 -vn 0.005297 -0.173966 0.984737 -v 0.081713 0.077068 0.146378 -vn 0.857111 0.084053 0.508229 -v 0.081785 0.077079 0.146254 -vn -0.005598 0.433803 0.900991 -v 0.081665 0.077441 0.146327 -vn 0.003935 0.234397 0.972133 -v 0.081669 0.077417 0.146336 -vn 0.854128 0.276575 0.440422 -v 0.081741 0.077377 0.146218 -vn -0.001080 0.754334 0.656490 -v 0.081625 0.077730 0.146146 -vn 0.001466 0.600689 0.799481 -v 0.081627 0.077713 0.146162 -vn 0.853038 0.427064 0.299904 -v 0.081699 0.077629 0.146069 -vn -0.004635 0.953306 0.301972 -v 0.081583 0.077925 0.145863 -vn 0.005683 0.868395 0.495841 -v 0.081585 0.077916 0.145884 -vn 0.851930 0.513346 0.103402 -v 0.081658 0.077802 0.145832 -vn 0.001945 0.995813 -0.091393 -v 0.081538 0.077992 0.145519 -vn 0.002938 0.994405 0.105592 -v 0.081541 0.077992 0.145541 -vn 0.855193 0.507700 -0.104331 -v 0.081613 0.077867 0.145540 -vn 0.005478 0.880256 -0.474468 -v 0.081499 0.077921 0.145190 -vn 0.010937 0.951176 -0.308454 -v 0.081501 0.077929 0.145209 -vn 0.851087 0.426645 -0.305981 -v 0.081574 0.077813 0.145257 -vn 0.001786 0.613288 -0.789857 -v 0.081455 0.077717 0.144905 -vn 0.012263 0.747123 -0.664573 -v 0.081457 0.077732 0.144919 -vn 0.850942 0.264944 -0.453544 -v 0.081529 0.077645 0.145009 -vn 0.004121 0.249562 -0.968350 -v 0.081413 0.077423 0.144729 -vn 0.003806 0.431137 -0.902278 -v 0.081415 0.077440 0.144735 -vn 0.849053 0.077982 -0.522520 -v 0.081487 0.077396 0.144852 -vn 0.939291 0.213222 0.268829 -v 0.088903 0.077420 0.146161 -vn 0.961524 0.211757 0.175016 -v 0.088903 0.077541 0.146036 -vn 0.861549 0.400513 0.311965 -v 0.088856 0.077592 0.146101 -vn 0.572652 0.751191 -0.328301 -v 0.081598 0.077789 0.145292 -vn 0.566381 0.696674 -0.440293 -v 0.081592 0.077776 0.145257 -vn 0.571220 -0.289511 -0.768044 -v 0.081431 0.076984 0.144831 -vn 0.925650 -0.268244 -0.266865 -v 0.081401 0.076818 0.144883 -vn 0.874690 -0.253082 -0.413361 -v 0.081424 0.076959 0.144830 -vn 0.573897 -0.796307 -0.191147 -v 0.081312 0.076438 0.145305 -vn 0.573291 -0.811361 -0.114155 -v 0.081309 0.076434 0.145319 -vn 0.003636 -0.934463 -0.356042 -v 0.081246 0.076328 0.145287 -vn 0.574560 0.468687 0.670980 -v 0.081032 0.077546 0.146209 -vn 0.580644 0.517395 0.628614 -v 0.081025 0.077587 0.146185 -vn 0.000273 0.554119 0.832437 -v 0.080991 0.077621 0.146234 -vn 0.564093 0.805226 -0.182785 -v 0.080891 0.077940 0.145367 -vn 0.576845 0.776775 -0.252728 -v 0.080886 0.077932 0.145331 -vn 0.003940 0.978452 -0.206437 -v 0.080865 0.077966 0.145322 -vn 0.581200 0.311258 -0.751881 -v 0.080789 0.077539 0.144800 -vn 0.189593 0.310873 -0.931350 -v 0.080770 0.077406 0.144739 -vn -0.006464 0.460359 -0.887709 -v 0.080779 0.077548 0.144784 -vn -0.056616 0.292356 -0.954632 -v 0.080765 0.077370 0.144727 -vn 0.002644 0.126596 -0.991951 -v 0.080739 0.077225 0.144686 -vn 0.326562 0.174240 -0.928977 -v 0.080757 0.077305 0.144710 -vn 0.582121 0.005964 -0.813081 -v 0.080745 0.077223 0.144696 -vn -0.002148 0.051837 -0.998653 -v 0.080739 0.077222 0.144685 -vn 0.480243 -0.080512 -0.873433 -v 0.080726 0.077086 0.144691 -vn 0.005753 -0.114019 -0.993462 -v 0.080717 0.077049 0.144687 -vn 0.445926 -0.197172 -0.873083 -v 0.080717 0.077019 0.144696 -vn -0.043051 -0.343230 -0.938264 -v 0.080695 0.076875 0.144725 -vn -0.565595 -0.093279 -0.819391 -v 0.080710 0.076972 0.144703 -vn 0.083302 -0.419506 -0.903922 -v 0.080685 0.076806 0.144751 -vn -0.000025 0.823676 -0.567061 -v 0.080823 0.077815 0.145011 -vn 0.575282 0.609690 -0.545279 -v 0.080839 0.077793 0.145028 -vn -0.004122 0.765597 -0.643307 -v 0.080822 0.077812 0.145008 -vn 0.570106 0.591498 -0.570183 -v 0.080835 0.077780 0.145011 -vn 0.516814 0.561583 -0.646164 -v 0.080830 0.077759 0.144984 -vn 0.332337 0.562581 -0.757004 -v 0.080804 0.077625 0.144858 -vn 0.563706 0.381412 -0.732640 -v 0.080794 0.077568 0.144818 -vn -0.001900 0.956876 -0.290490 -v 0.080865 0.077965 0.145317 -vn 0.576593 0.767020 -0.281463 -v 0.080884 0.077929 0.145318 -vn 0.498980 0.772952 -0.391872 -v 0.080876 0.077911 0.145257 -vn 0.538725 0.691700 -0.480965 -v 0.080844 0.077817 0.145061 -vn 0.490274 0.867734 -0.081670 -v 0.080913 0.077952 0.145532 -vn 0.000325 0.986659 0.162802 -v 0.080906 0.077982 0.145663 -vn 0.556844 0.830614 -0.002260 -v 0.080922 0.077948 0.145597 -vn -0.004396 0.872945 0.487799 -v 0.080950 0.077861 0.145986 -vn 0.005222 0.814217 0.580538 -v 0.080951 0.077857 0.145992 -vn 0.584017 0.717576 0.379486 -v 0.080981 0.077813 0.145964 -vn 0.524426 0.798322 0.296074 -v 0.080963 0.077874 0.145859 -vn 0.495787 0.836905 0.231916 -v 0.080954 0.077897 0.145805 -vn 0.580918 0.809763 0.082569 -v 0.080931 0.077939 0.145656 -vn 0.541365 0.599554 0.589456 -v 0.081011 0.077669 0.146124 -vn 0.508485 0.653094 0.561169 -v 0.081003 0.077716 0.146081 -vn 0.551097 0.680213 0.483325 -v 0.080995 0.077756 0.146038 -vn 0.003504 0.265945 0.963982 -v 0.081033 0.077307 0.146365 -vn -0.003163 0.103642 0.994610 -v 0.081034 0.077298 0.146367 -vn 0.571446 0.276549 0.772639 -v 0.081073 0.077289 0.146299 -vn 0.573635 0.203116 0.793528 -v 0.081074 0.077285 0.146300 -vn 0.503336 0.378284 0.776887 -v 0.081041 0.077492 0.146237 -vn 0.004648 -0.277946 0.960586 -v 0.081078 0.076950 0.146359 -vn 0.576657 -0.125999 0.807212 -v 0.081122 0.076970 0.146285 -vn -0.001658 -0.153746 0.988109 -v 0.081076 0.076960 0.146362 -vn 0.559231 -0.014963 0.828877 -v 0.081114 0.077023 0.146297 -vn 0.564481 0.112650 0.817723 -v 0.081082 0.077235 0.146306 -vn -0.004819 -0.532333 0.846522 -v 0.081116 0.076651 0.146225 -vn 0.553824 -0.317831 0.769586 -v 0.081151 0.076776 0.146206 -vn 0.565742 -0.225927 0.793028 -v 0.081132 0.076900 0.146264 -vn -0.003659 -0.826545 0.562859 -v 0.081161 0.076412 0.145967 -vn 0.005110 -0.894113 0.447812 -v 0.081162 0.076406 0.145956 -vn 0.586550 -0.667195 0.459141 -v 0.081217 0.076487 0.145909 -vn 0.557939 -0.617633 0.554287 -v 0.081200 0.076542 0.145996 -vn 0.548406 -0.563423 0.617905 -v 0.081192 0.076573 0.146036 -vn 0.005213 -0.635902 0.771752 -v 0.081118 0.076641 0.146218 -vn 0.583475 -0.446929 0.678094 -v 0.081167 0.076691 0.146149 -vn 0.572099 -0.381983 0.725804 -v 0.081160 0.076728 0.146176 -vn -0.003470 -0.980809 0.194938 -v 0.081201 0.076300 0.145647 -vn 0.548000 -0.777624 0.308216 -v 0.081240 0.076427 0.145764 -vn 0.565882 -0.733447 0.376607 -v 0.081233 0.076443 0.145812 -vn 0.543747 -0.839125 -0.014418 -v 0.081278 0.076397 0.145507 -vn 0.000262 -0.998935 0.046130 -v 0.081203 0.076299 0.145634 -vn 0.001985 -0.980756 -0.195225 -v 0.081244 0.076324 0.145302 -vn 0.575546 -0.811855 0.098176 -v 0.081270 0.076396 0.145560 -vn 0.579498 -0.799108 0.160029 -v 0.081261 0.076399 0.145621 -vn 0.568744 -0.787735 0.236653 -v 0.081252 0.076408 0.145683 -vn 0.564482 -0.584788 -0.582565 -v 0.081373 0.076658 0.144987 -vn 0.004011 -0.719624 -0.694352 -v 0.081290 0.076495 0.144980 -vn 0.564649 -0.518805 -0.641883 -v 0.081390 0.076749 0.144921 -vn -0.002951 -0.519441 -0.854501 -v 0.081327 0.076747 0.144779 -vn 0.591397 -0.431046 -0.681505 -v 0.081397 0.076792 0.144898 -vn 0.005250 -0.391625 -0.920110 -v 0.081329 0.076762 0.144772 -vn 0.576855 -0.642839 -0.503980 -v 0.081359 0.076592 0.145051 -vn 0.576300 -0.668900 -0.469522 -v 0.081358 0.076586 0.145057 -vn 0.000022 -0.815938 -0.578139 -v 0.081288 0.076486 0.144992 -vn 0.573292 -0.713846 -0.402194 -v 0.081352 0.076562 0.145085 -vn 0.568981 -0.772512 -0.281932 -v 0.081319 0.076455 0.145261 -vn 0.064817 0.125080 -0.990027 -v 0.081472 0.077229 0.144826 -vn 0.581290 -0.104412 -0.806970 -v 0.081452 0.077109 0.144818 -vn 0.854798 -0.125766 -0.503491 -v 0.081446 0.077108 0.144807 -vn 0.438196 -0.184137 -0.879817 -v 0.081438 0.077026 0.144824 -vn 0.505824 -0.224211 -0.832990 -v 0.081433 0.076998 0.144828 -vn 0.551597 0.172748 -0.816026 -v 0.081494 0.077365 0.144860 -vn 0.244022 0.157439 -0.956905 -v 0.081479 0.077270 0.144833 -vn 0.364932 0.461572 -0.808564 -v 0.081517 0.077497 0.144924 -vn 0.507610 0.335568 -0.793553 -v 0.081509 0.077459 0.144902 -vn 0.577680 0.235874 -0.781440 -v 0.081498 0.077390 0.144869 -vn 0.582830 0.478879 -0.656494 -v 0.081545 0.077627 0.145028 -vn 0.572404 0.543363 -0.614094 -v 0.081550 0.077650 0.145053 -vn 0.486579 0.666375 -0.564965 -v 0.081557 0.077675 0.145083 -vn 0.522157 0.843692 0.124640 -v 0.081670 0.077792 0.145721 -vn 0.586393 0.808763 -0.045232 -v 0.081636 0.077825 0.145527 -vn 0.553407 0.820180 -0.145068 -v 0.081629 0.077825 0.145486 -vn 0.498773 0.835322 -0.231220 -v 0.081614 0.077815 0.145393 -vn 0.522405 0.735347 0.431692 -v 0.081711 0.077683 0.145926 -vn 0.579795 0.763886 0.283400 -v 0.081688 0.077755 0.145811 -vn 0.557855 0.804668 0.203244 -v 0.081677 0.077780 0.145754 -vn 0.558903 0.461615 0.688868 -v 0.081755 0.077484 0.146098 -vn 0.563920 0.526351 0.636356 -v 0.081749 0.077515 0.146079 -vn 0.579712 0.601939 0.549185 -v 0.081734 0.077589 0.146025 -vn 0.536935 0.691201 0.483675 -v 0.081717 0.077662 0.145952 -vn 0.600926 0.044920 0.798041 -v 0.081831 0.077077 0.146176 -vn 0.532169 0.169729 0.829451 -v 0.081796 0.077271 0.146173 -vn 0.571860 0.280895 0.770762 -v 0.081790 0.077303 0.146167 -vn 0.591354 0.370610 0.716204 -v 0.081780 0.077355 0.146153 -vn 0.567499 -0.483141 0.666723 -v 0.081910 0.076690 0.145975 -vn 0.601739 -0.349935 0.717952 -v 0.081875 0.076838 0.146095 -vn 0.576330 -0.269053 0.771657 -v 0.081869 0.076867 0.146110 -vn 0.552452 -0.183312 0.813138 -v 0.081856 0.076940 0.146142 -vn 0.594043 -0.052571 0.802713 -v 0.081836 0.077048 0.146172 -vn 0.601206 -0.679640 0.420286 -v 0.081951 0.076572 0.145791 -vn 0.586616 -0.605878 0.537395 -v 0.081923 0.076646 0.145923 -vn 0.566998 -0.557005 0.606843 -v 0.081915 0.076671 0.145954 -vn 0.579997 -0.757587 0.299443 -v 0.081970 0.076540 0.145690 -vn 0.599984 -0.702209 0.383305 -v 0.081956 0.076563 0.145767 -vn 0.600791 -0.795460 0.079333 -v 0.081994 0.076524 0.145554 -vn 0.575961 -0.804071 0.147442 -v 0.081989 0.076525 0.145583 -vn 0.575987 -0.786275 0.223630 -v 0.081976 0.076533 0.145657 -vn 0.669331 -0.684071 -0.289902 -v 0.082065 0.076630 0.145208 -vn 0.550071 -0.803970 -0.225952 -v 0.082035 0.076559 0.145346 -vn 0.583174 -0.804703 -0.111183 -v 0.082030 0.076552 0.145369 -vn 0.638177 -0.769864 0.006188 -v 0.082016 0.076534 0.145442 -vn 0.754990 -0.564220 -0.334135 -v 0.082076 0.076662 0.145164 -vn 0.714510 -0.625756 -0.312898 -v 0.082072 0.076649 0.145181 -vn 0.956186 0.252311 0.148485 -v 0.088903 0.077558 0.146014 -vn 0.860751 0.493271 0.125663 -v 0.088815 0.077779 0.145879 -vn 0.922841 0.219902 0.316240 -v 0.088903 0.077392 0.146182 -vn 0.906371 0.212433 0.365189 -v 0.088898 0.077327 0.146233 -vn 0.961893 0.098819 0.254944 -v 0.088903 0.077213 0.146276 -vn -0.001768 0.072216 0.997387 -v 0.088845 0.077213 0.146379 -vn -0.013542 -0.137588 0.990397 -v 0.088870 0.077009 0.146371 -vn 0.960834 0.030953 0.275391 -v 0.088903 0.077018 0.146315 -vn 0.025701 -0.335226 0.941787 -v 0.088887 0.076874 0.146338 -vn 0.238591 -0.621624 0.746095 -v 0.088903 0.076742 0.146281 -vn 0.959864 -0.017759 0.279903 -v 0.088903 0.076944 0.146316 -vn 0.962726 0.000095 0.270477 -v 0.088903 0.076979 0.146317 -vn 0.862441 0.396198 -0.314997 -v 0.085470 0.077803 0.145233 -vn 0.861097 0.492786 -0.125198 -v 0.085509 0.077867 0.145514 -vn 0.862536 0.500520 0.074237 -v 0.085554 0.077813 0.145808 -vn 0.863176 0.425475 0.271843 -v 0.085596 0.077647 0.146052 -vn 0.860740 0.289208 0.418910 -v 0.085637 0.077402 0.146209 -vn 0.862041 -0.116339 0.493306 -v 0.085721 0.076826 0.146184 -vn 0.862472 0.100364 0.496053 -v 0.085682 0.077105 0.146256 -vn 0.862102 -0.437466 0.255743 -v 0.085808 0.076448 0.145741 -vn 0.863016 -0.295583 0.409675 -v 0.085765 0.076590 0.146001 -vn 0.860686 -0.487636 -0.146390 -v 0.085893 0.076516 0.145167 -vn 0.860451 -0.505297 0.065570 -v 0.085848 0.076422 0.145452 -vn 0.861823 -0.386230 -0.328768 -v 0.085933 0.076709 0.144951 -vn 0.862936 -0.228844 -0.450524 -v 0.085976 0.076977 0.144826 -vn 0.861752 -0.027095 -0.506605 -v 0.086020 0.077275 0.144819 -vn 0.860901 0.173604 -0.478237 -v 0.086060 0.077543 0.144927 -vn 0.860928 0.353736 -0.365615 -v 0.086105 0.077753 0.145141 -vn 0.862514 0.467740 -0.193103 -v 0.086146 0.077858 0.145413 -vn 0.861208 0.508245 0.002622 -v 0.086188 0.077846 0.145707 -vn 0.861188 0.464045 0.207407 -v 0.086232 0.077715 0.145976 -vn 0.860479 0.343209 0.376542 -v 0.086272 0.077496 0.146164 -vn 0.861399 0.162769 0.481142 -v 0.086316 0.077210 0.146253 -vn 0.860748 -0.235638 0.451206 -v 0.086399 0.076664 0.146077 -vn 0.863696 -0.040856 0.502354 -v 0.086358 0.076919 0.146221 -vn 0.860805 -0.491972 0.130300 -v 0.086483 0.076418 0.145556 -vn 0.861242 -0.396654 0.317692 -v 0.086444 0.076485 0.145836 -vn 0.861634 -0.502100 -0.074039 -v 0.086528 0.076470 0.145262 -vn 0.862540 -0.429415 -0.267633 -v 0.086570 0.076633 0.145016 -vn 0.860691 -0.292865 -0.416462 -v 0.086611 0.076877 0.144857 -vn 0.861541 -0.100789 -0.497582 -v 0.086656 0.077173 0.144807 -vn 0.861611 0.111049 -0.495273 -v 0.086695 0.077453 0.144877 -vn 0.862879 0.292092 -0.412458 -v 0.086739 0.077690 0.145057 -vn 0.861912 0.435485 -0.259730 -v 0.086782 0.077835 0.145316 -vn 0.860425 0.504754 -0.069940 -v 0.086822 0.077864 0.145604 -vn 0.860576 0.489030 0.142334 -v 0.086867 0.077773 0.145890 -vn 0.861827 0.389146 0.325300 -v 0.086908 0.077582 0.146108 -vn 0.861831 0.233924 0.450031 -v 0.086950 0.077314 0.146236 -vn 0.861588 0.031636 0.506621 -v 0.086994 0.077016 0.146245 -vn 0.860852 -0.350604 0.368796 -v 0.087079 0.076535 0.145928 -vn 0.860901 -0.169508 0.479704 -v 0.087034 0.076748 0.146140 -vn 0.862598 -0.465758 0.197470 -v 0.087120 0.076428 0.145656 -vn 0.860920 -0.508737 0.001951 -v 0.087162 0.076438 0.145362 -vn 0.860406 -0.346297 -0.373872 -v 0.087246 0.076783 0.144902 -vn 0.861000 -0.466200 -0.203313 -v 0.087206 0.076566 0.145092 -vn 0.860886 0.232663 -0.452486 -v 0.087373 0.077616 0.144982 -vn 0.864857 0.030666 -0.501080 -v 0.087332 0.077360 0.144840 -vn 0.861210 -0.167416 -0.479885 -v 0.087290 0.077068 0.144810 -vn 0.862269 0.486796 -0.139722 -v 0.087458 0.077867 0.145501 -vn 0.861088 0.393931 -0.321475 -v 0.087418 0.077798 0.145221 -vn 0.863566 0.500291 0.062944 -v 0.087502 0.077818 0.145795 -vn 0.864042 0.431828 0.258759 -v 0.087544 0.077656 0.146043 -vn 0.862471 0.299299 0.408122 -v 0.087585 0.077414 0.146204 -vn 0.863467 0.110170 0.492228 -v 0.087630 0.077119 0.146256 -vn 0.863417 -0.101353 0.494205 -v 0.087670 0.076837 0.146189 -vn 0.864689 -0.281595 0.415953 -v 0.087713 0.076599 0.146011 -vn 0.863521 -0.428344 0.266184 -v 0.087757 0.076452 0.145753 -vn 0.862296 -0.500117 0.079554 -v 0.087796 0.076420 0.145466 -vn 0.862542 -0.488669 -0.131240 -v 0.087841 0.076509 0.145179 -vn 0.863715 -0.392689 -0.315898 -v 0.087882 0.076698 0.144959 -vn 0.863464 -0.242207 -0.442454 -v 0.087924 0.076964 0.144829 -vn 0.863314 -0.041165 -0.502986 -v 0.087968 0.077262 0.144817 -vn 0.863305 0.339991 -0.372976 -v 0.088053 0.077746 0.145130 -vn 0.862888 0.158794 -0.479801 -v 0.088008 0.077532 0.144920 -vn 0.862714 0.505527 -0.012950 -v 0.088136 0.077849 0.145694 -vn 0.865312 0.457009 -0.205858 -v 0.088094 0.077856 0.145401 -vn 0.862411 0.351138 0.364622 -v 0.088220 0.077508 0.146158 -vn 0.862862 0.467366 0.192451 -v 0.088180 0.077723 0.145966 -vn 0.863241 0.177177 0.472677 -v 0.088264 0.077223 0.146252 -vn 0.865247 -0.026828 0.500627 -v 0.088306 0.076931 0.146225 -vn 0.862428 -0.220377 0.455688 -v 0.088347 0.076674 0.146085 -vn 0.863091 -0.384256 0.327752 -v 0.088392 0.076490 0.145848 -vn 0.862818 -0.484870 0.142990 -v 0.088432 0.076418 0.145569 -vn 0.863679 -0.500834 -0.056777 -v 0.088476 0.076465 0.145274 -vn 0.863825 -0.434994 -0.254138 -v 0.088519 0.076624 0.145025 -vn 0.862013 -0.304906 -0.404927 -v 0.088559 0.076864 0.144862 -vn 0.862397 -0.113214 -0.493411 -v 0.088604 0.077160 0.144807 -vn 0.863379 0.095958 -0.495347 -v 0.088644 0.077442 0.144871 -vn 0.863336 0.425575 -0.271176 -v 0.088731 0.077831 0.145304 -vn 0.864638 0.276870 -0.419219 -v 0.088687 0.077681 0.145047 -vn 0.862371 0.499100 -0.084941 -v 0.088770 0.077865 0.145591 -vn -0.001139 -0.133176 -0.991092 -v 0.081372 0.077084 0.144684 -vn 0.012665 0.031988 -0.999408 -v 0.081374 0.077102 0.144682 -vn 0.008331 0.820207 -0.572006 -v 0.085383 0.077861 0.145077 -vn -0.004105 0.926731 -0.375704 -v 0.085398 0.077917 0.145181 -vn 0.006594 0.979685 -0.200434 -v 0.085424 0.077981 0.145395 -vn -0.007564 0.999689 0.023781 -v 0.085437 0.077992 0.145511 -vn 0.010125 0.980239 0.197556 -v 0.085466 0.077967 0.145740 -vn -0.010149 0.905164 0.424942 -v 0.085482 0.077928 0.145855 -vn 0.007817 0.817327 0.576122 -v 0.085510 0.077813 0.146054 -vn -0.004486 0.664652 0.747140 -v 0.085524 0.077734 0.146142 -vn 0.008158 0.526211 0.850315 -v 0.085549 0.077558 0.146273 -vn -0.010497 0.306697 0.951749 -v 0.085565 0.077447 0.146325 -vn 0.010186 0.148430 0.988871 -v 0.085594 0.077223 0.146378 -vn -0.008723 -0.094737 0.995464 -v 0.085609 0.077099 0.146380 -vn 0.006448 -0.264447 0.964379 -v 0.085635 0.076882 0.146341 -vn -0.008174 -0.477272 0.878718 -v 0.085649 0.076771 0.146296 -vn 0.010571 -0.621572 0.783286 -v 0.085677 0.076585 0.146173 -vn -0.008882 -0.794116 0.607701 -v 0.085693 0.076495 0.146082 -vn 0.012451 -0.881017 0.472921 -v 0.085721 0.076373 0.145893 -vn -0.007741 -0.969905 0.243360 -v 0.085736 0.076329 0.145777 -vn 0.006715 -0.996265 0.086083 -v 0.085761 0.076293 0.145566 -vn -0.011837 -0.986836 -0.161293 -v 0.085776 0.076298 0.145439 -vn 0.010388 -0.948509 -0.316580 -v 0.085805 0.076351 0.145221 -vn -0.007264 -0.839298 -0.543624 -v 0.085821 0.076408 0.145104 -vn 0.013158 -0.743834 -0.668235 -v 0.085847 0.076540 0.144932 -vn -0.013440 -0.556585 -0.830682 -v 0.085861 0.076634 0.144851 -vn 0.007936 -0.420149 -0.907420 -v 0.085888 0.076823 0.144744 -vn -0.010339 -0.178581 -0.983871 -v 0.085904 0.076949 0.144704 -vn 0.012820 -0.021084 -0.999696 -v 0.085932 0.077168 0.144682 -vn -0.007461 0.226525 -0.973977 -v 0.085948 0.077298 0.144696 -vn 0.008209 0.376638 -0.926324 -v 0.085972 0.077497 0.144759 -vn -0.013110 0.593865 -0.804458 -v 0.085988 0.077612 0.144823 -vn 0.010628 0.712598 -0.701492 -v 0.086015 0.077777 0.144966 -vn -0.008554 0.866945 -0.498331 -v 0.086033 0.077859 0.145074 -vn 0.014593 0.933399 -0.358543 -v 0.086059 0.077950 0.145267 -vn -0.013211 0.993197 -0.115693 -v 0.086073 0.077981 0.145393 -vn 0.008139 0.999221 0.038615 -v 0.086098 0.077990 0.145602 -vn -0.011751 0.957039 0.289721 -v 0.086116 0.077967 0.145738 -vn 0.013170 0.900233 0.435210 -v 0.086143 0.077889 0.145939 -vn -0.007643 0.762810 0.646578 -v 0.086160 0.077814 0.146053 -vn 0.010108 0.653595 0.756777 -v 0.086184 0.077670 0.146198 -vn -0.014442 0.444578 0.895624 -v 0.086199 0.077557 0.146273 -vn 0.010737 0.301544 0.953392 -v 0.086226 0.077361 0.146353 -vn -0.009950 0.047704 0.998812 -v 0.086244 0.077222 0.146378 -vn 0.015304 -0.105325 0.994320 -v 0.086270 0.077012 0.146371 -vn -0.012086 -0.350483 0.936491 -v 0.086286 0.076880 0.146340 -vn 0.008381 -0.489399 0.872020 -v 0.086309 0.076696 0.146255 -vn -0.013143 -0.694249 0.719615 -v 0.086327 0.076582 0.146170 -vn 0.013387 -0.796489 0.604504 -v 0.086354 0.076442 0.146013 -vn -0.008455 -0.923850 0.382662 -v 0.086372 0.076371 0.145889 -vn 0.012634 -0.971201 0.237928 -v 0.086395 0.076309 0.145698 -vn -0.015653 -0.999785 -0.013613 -v 0.086411 0.076293 0.145560 -vn 0.010831 -0.986346 -0.164330 -v 0.086437 0.076311 0.145355 -vn -0.011339 -0.910579 -0.413179 -v 0.086456 0.076354 0.145215 -vn 0.015671 -0.837645 -0.545990 -v 0.086481 0.076453 0.145035 -vn -0.011020 -0.673213 -0.739366 -v 0.086498 0.076545 0.144927 -vn 0.009001 -0.553439 -0.832841 -v 0.086521 0.076700 0.144806 -vn -0.014443 -0.323786 -0.946020 -v 0.086539 0.076831 0.144741 -vn 0.013617 -0.177052 -0.984107 -v 0.086565 0.077029 0.144689 -vn -0.009602 0.082207 -0.996569 -v 0.086584 0.077178 0.144682 -vn 0.015296 0.229614 -0.973162 -v 0.086607 0.077373 0.144713 -vn -0.016508 0.468883 -0.883106 -v 0.086623 0.077507 0.144764 -vn 0.010946 0.594573 -0.803967 -v 0.086648 0.077676 0.144869 -vn -0.012824 0.782997 -0.621893 -v 0.086667 0.077785 0.144975 -vn 0.016112 0.867000 -0.498048 -v 0.086692 0.077898 0.145141 -vn -0.010371 0.965199 -0.261312 -v 0.086710 0.077954 0.145279 -vn 0.010146 0.993476 -0.113589 -v 0.086732 0.077990 0.145466 -vn -0.015794 0.989529 0.143470 -v 0.086750 0.077988 0.145617 -vn 0.013778 0.957236 0.288980 -v 0.086775 0.077945 0.145811 -vn -0.010926 0.848845 0.528530 -v 0.086795 0.077881 0.145952 -vn 0.017141 0.762312 0.646983 -v 0.086819 0.077766 0.146109 -vn -0.016596 0.571600 0.820365 -v 0.086835 0.077657 0.146208 -vn 0.011055 0.445625 0.895152 -v 0.086859 0.077492 0.146306 -vn -0.014250 0.196466 0.980407 -v 0.086878 0.077344 0.146357 -vn 0.016366 0.049801 0.998625 -v 0.086903 0.077149 0.146382 -vn -0.010269 -0.208517 0.977965 -v 0.086922 0.076994 0.146369 -vn 0.011830 -0.350983 0.936307 -v 0.086943 0.076816 0.146316 -vn -0.017128 -0.579242 0.814976 -v 0.086962 0.076680 0.146244 -vn 0.013902 -0.692028 0.721737 -v 0.086986 0.076530 0.146121 -vn -0.012280 -0.857763 0.513899 -v 0.087007 0.076430 0.145996 -vn 0.018295 -0.922888 0.384635 -v 0.087030 0.076345 0.145826 -vn -0.015891 -0.990832 0.134161 -v 0.087048 0.076305 0.145678 -vn 0.011221 -0.999879 -0.010739 -v 0.087069 0.076293 0.145493 -vn -0.015719 -0.962111 -0.272204 -v 0.087090 0.076316 0.145333 -vn 0.016662 -0.912342 -0.409089 -v 0.087114 0.076381 0.145153 -vn -0.010834 -0.774370 -0.632640 -v 0.087134 0.076467 0.145016 -vn 0.014253 -0.674222 -0.738391 -v 0.087155 0.076592 0.144884 -vn -0.018389 -0.460619 -0.887407 -v 0.087174 0.076721 0.144793 -vn 0.013972 -0.328739 -0.944318 -v 0.087197 0.076893 0.144719 -vn -0.013801 -0.065857 -0.997734 -v 0.087218 0.077055 0.144686 -vn 0.018914 0.077164 -0.996839 -v 0.087241 0.077242 0.144687 -vn -0.018520 0.325623 -0.945318 -v 0.087260 0.077398 0.144721 -vn 0.003164 0.475506 -0.879707 -v 0.087281 0.077562 0.144792 -vn -0.017125 0.680977 -0.732104 -v 0.087301 0.077697 0.144887 -vn 0.016911 0.778703 -0.627165 -v 0.087325 0.077824 0.145024 -vn -0.003313 0.912026 -0.410120 -v 0.087346 0.077910 0.145167 -vn 0.021081 0.966124 -0.257217 -v 0.087367 0.077970 0.145335 -vn -0.023812 0.999635 -0.012753 -v 0.087385 0.077992 0.145495 -vn 0.004772 0.988828 0.148985 -v 0.087408 0.077980 0.145676 -vn -0.008448 0.701702 0.712420 -v 0.087472 0.077745 0.146131 -vn 0.013389 0.840600 0.541491 -v 0.087452 0.077850 0.146002 -vn -0.010658 0.926670 0.375724 -v 0.087429 0.077934 0.145841 -vn 0.007478 0.559363 0.828889 -v 0.087492 0.077612 0.146240 -vn -0.008719 -0.042059 0.999077 -v 0.087558 0.077115 0.146381 -vn 0.011747 0.182515 0.983133 -v 0.087536 0.077288 0.146369 -vn -0.012831 0.362904 0.931738 -v 0.087513 0.077461 0.146319 -vn 0.012980 -0.224942 0.974286 -v 0.087579 0.076941 0.146357 -vn -0.011481 -0.756080 0.654378 -v 0.087641 0.076505 0.146094 -vn 0.009312 -0.590232 0.807180 -v 0.087619 0.076635 0.146213 -vn -0.013481 -0.431440 0.902041 -v 0.087597 0.076785 0.146303 -vn 0.013331 -0.864916 0.501740 -v 0.087663 0.076403 0.145950 -vn -0.013436 -0.994808 -0.100879 -v 0.087724 0.076296 0.145454 -vn 0.008086 -0.992788 0.119611 -v 0.087703 0.076298 0.145628 -vn -0.007731 -0.954038 0.299585 -v 0.087684 0.076333 0.145791 -vn 0.011480 -0.958531 -0.284758 -v 0.087746 0.076330 0.145283 -vn -0.012686 -0.606195 -0.795215 -v 0.087809 0.076622 0.144860 -vn 0.013920 -0.764452 -0.644531 -v 0.087790 0.076498 0.144978 -vn -0.009623 -0.870301 -0.492426 -v 0.087769 0.076400 0.145118 -vn 0.008900 -0.449586 -0.893193 -v 0.087830 0.076764 0.144770 -vn -0.007725 0.168486 -0.985674 -v 0.087896 0.077283 0.144693 -vn 0.013205 -0.052989 -0.998508 -v 0.087874 0.077104 0.144682 -vn -0.012183 -0.238997 -0.970944 -v 0.087852 0.076933 0.144708 -vn 0.009395 0.346601 -0.937966 -v 0.087915 0.077440 0.144735 -vn -0.010398 0.834565 -0.550811 -v 0.087981 0.077850 0.145061 -vn 0.011148 0.689716 -0.723994 -v 0.087957 0.077732 0.144919 -vn -0.013952 0.542804 -0.839744 -v 0.087936 0.077599 0.144814 -vn 0.014329 0.922181 -0.386493 -v 0.088001 0.077928 0.145208 -vn -0.012817 0.973409 0.228716 -v 0.088064 0.077971 0.145723 -vn 0.008492 0.999939 0.007105 -v 0.088041 0.077992 0.145539 -vn -0.011429 0.984161 -0.176908 -v 0.088022 0.077979 0.145378 -vn 0.013066 0.913237 0.407220 -v 0.088085 0.077917 0.145881 -vn -0.014345 0.500251 0.865761 -v 0.088148 0.077571 0.146266 -vn 0.011288 0.676347 0.736497 -v 0.088127 0.077716 0.146159 -vn -0.008378 0.800313 0.599524 -v 0.088108 0.077823 0.146041 -vn 0.010772 0.330742 0.943660 -v 0.088168 0.077423 0.146334 -vn -0.009804 -0.291497 0.956521 -v 0.088234 0.076894 0.146344 -vn 0.014307 -0.076369 0.996977 -v 0.088212 0.077075 0.146379 -vn -0.011178 0.110823 0.993777 -v 0.088192 0.077237 0.146376 -vn 0.008116 -0.462528 0.886567 -v 0.088252 0.076751 0.146286 -vn -0.009162 -0.898421 0.439039 -v 0.088320 0.076378 0.145903 -vn 0.012764 -0.778162 0.627934 -v 0.088296 0.076481 0.146065 -vn -0.013410 -0.646446 0.762842 -v 0.088275 0.076594 0.146181 -vn 0.012939 -0.963958 0.265738 -v 0.088338 0.076323 0.145757 -vn -0.011880 -0.935425 -0.353325 -v 0.088403 0.076348 0.145230 -vn 0.010351 -0.990774 -0.135130 -v 0.088379 0.076300 0.145419 -vn -0.014305 -0.998606 0.050813 -v 0.088359 0.076294 0.145575 -vn 0.014223 -0.852691 -0.522222 -v 0.088423 0.076417 0.145088 -vn -0.013935 -0.385183 -0.922735 -v 0.088487 0.076816 0.144747 -vn 0.008229 -0.577841 -0.816108 -v 0.088463 0.076648 0.144840 -vn -0.008630 -0.718269 -0.695712 -v 0.088446 0.076535 0.144937 -vn 0.012421 -0.205173 -0.978647 -v 0.088506 0.076965 0.144700 -vn -0.013756 0.409851 -0.912049 -v 0.088571 0.077493 0.144757 -vn 0.014029 0.203203 -0.979036 -v 0.088550 0.077313 0.144699 -vn -0.009902 0.018420 -0.999781 -v 0.088532 0.077163 0.144682 -vn 0.009904 0.571585 -0.820483 -v 0.088590 0.077624 0.144831 -vn -0.008220 0.946760 -0.321836 -v 0.088658 0.077949 0.145265 -vn 0.014012 0.853215 -0.521370 -v 0.088634 0.077866 0.145085 -vn -0.012537 0.740056 -0.672428 -v 0.088615 0.077774 0.144963 -vn 0.009070 0.989868 -0.141699 -v 0.088675 0.077983 0.145404 -vn -0.010664 0.881770 0.471559 -v 0.088743 0.077889 0.145938 -vn 0.012019 0.964842 0.262557 -v 0.088717 0.077964 0.145749 -vn -0.014352 0.996926 0.077027 -v 0.088698 0.077990 0.145601 -vn 0.014670 0.778677 0.627254 -v 0.088761 0.077807 0.146061 -vn 0.961103 0.065822 0.268232 -v 0.088903 0.077180 0.146287 -vn -0.015547 0.266073 0.963828 -v 0.088826 0.077359 0.146353 -vn 0.009339 0.469811 0.882717 -v 0.088801 0.077549 0.146278 -vn -0.012612 0.624945 0.780567 -v 0.088784 0.077669 0.146199 -vn -0.860886 -0.073286 0.503492 -v 0.085522 0.077211 0.146253 -vn 0.222210 -0.942864 0.248254 -v 0.088903 0.076480 0.145841 -vn -0.839006 -0.537674 0.083524 -v 0.088900 0.076483 0.145832 -vn 0.253664 -0.966651 -0.035216 -v 0.088903 0.076467 0.145646 -vn -0.318109 0.893394 0.317259 -v 0.081492 0.077814 0.145754 -vn -0.426632 0.797503 0.426584 -v 0.081500 0.077792 0.145810 -vn -0.848843 0.427713 0.310690 -v 0.081510 0.077810 0.145814 -vn -0.432310 -0.202929 -0.878594 -v 0.081880 0.076979 0.144913 -vn -0.418518 -0.047831 -0.906948 -v 0.081883 0.077002 0.144908 -vn -0.857387 0.006150 -0.514635 -v 0.081932 0.076975 0.144826 -vn -0.417801 0.483229 -0.769371 -v 0.081946 0.077417 0.144967 -vn -0.428279 0.580313 -0.692686 -v 0.081958 0.077485 0.145008 -vn -0.855090 0.377682 -0.355214 -v 0.082015 0.077539 0.144925 -vn -0.417883 0.857072 -0.301333 -v 0.082008 0.077690 0.145248 -vn -0.429933 0.891513 -0.142697 -v 0.082033 0.077742 0.145408 -vn -0.858019 0.512597 0.032366 -v 0.082100 0.077857 0.145407 -vn -0.419445 0.907555 0.020271 -v 0.082038 0.077748 0.145445 -vn -0.857423 0.457891 0.234865 -v 0.082143 0.077847 0.145701 -vn -0.428698 0.880006 0.204472 -v 0.082070 0.077737 0.145650 -vn -0.421381 0.851081 0.313209 -v 0.082073 0.077731 0.145673 -vn -0.405734 0.677171 -0.613856 -v 0.081975 0.077569 0.145078 -vn -0.415030 0.740799 -0.528174 -v 0.081983 0.077607 0.145119 -vn -0.855307 0.488464 -0.172781 -v 0.082060 0.077751 0.145137 -vn -0.429479 0.800735 -0.417578 -v 0.081998 0.077661 0.145195 -vn -0.855817 0.203376 -0.475621 -v 0.081976 0.077272 0.144818 -vn -0.403699 0.362020 -0.840219 -v 0.081934 0.077341 0.144934 -vn -0.401949 0.424778 -0.811172 -v 0.081943 0.077396 0.144957 -vn -0.415629 0.106943 -0.903225 -v 0.081913 0.077193 0.144900 -vn -0.427004 0.255444 -0.867419 -v 0.081922 0.077256 0.144910 -vn -0.419273 -0.561120 -0.713691 -v 0.081836 0.076713 0.145048 -vn -0.423431 -0.483446 -0.766150 -v 0.081843 0.076755 0.145015 -vn -0.854058 -0.209219 -0.476248 -v 0.081889 0.076707 0.144952 -vn -0.417159 -0.440553 -0.794916 -v 0.081847 0.076780 0.144998 -vn -0.408062 -0.351588 -0.842539 -v 0.081851 0.076802 0.144985 -vn -0.393074 -0.646628 -0.653732 -v 0.081821 0.076635 0.145126 -vn -0.854105 -0.378675 -0.356525 -v 0.081849 0.076516 0.145167 -vn -0.408795 -0.688495 -0.599051 -v 0.081817 0.076620 0.145145 -vn -0.381890 -0.864569 -0.326621 -v 0.081785 0.076516 0.145338 -vn -0.394699 -0.825280 -0.403889 -v 0.081789 0.076524 0.145314 -vn -0.431839 -0.739192 -0.516827 -v 0.081807 0.076578 0.145204 -vn -0.396035 -0.914327 0.084629 -v 0.081738 0.076492 0.145666 -vn -0.375307 -0.926900 0.001233 -v 0.081752 0.076481 0.145558 -vn -0.853329 -0.490534 -0.176651 -v 0.081804 0.076422 0.145452 -vn -0.413554 -0.905611 -0.094033 -v 0.081756 0.076481 0.145529 -vn -0.426665 -0.880604 -0.206142 -v 0.081766 0.076487 0.145459 -vn -0.371831 -0.606913 0.702423 -v 0.081661 0.076779 0.146104 -vn -0.429420 -0.703505 0.566285 -v 0.081690 0.076633 0.145971 -vn -0.855137 -0.463548 0.232085 -v 0.081721 0.076589 0.146000 -vn -0.412918 -0.798206 0.438595 -v 0.081694 0.076616 0.145949 -vn -0.854014 -0.519013 0.035861 -v 0.081764 0.076448 0.145740 -vn -0.406201 -0.854279 0.324360 -v 0.081722 0.076522 0.145776 -vn -0.425830 -0.881875 0.202399 -v 0.081726 0.076513 0.145750 -vn -0.411596 -0.520422 0.748165 -v 0.081657 0.076806 0.146121 -vn -0.851576 -0.329682 0.407589 -v 0.081677 0.076823 0.146182 -vn -0.344326 -0.288948 0.893280 -v 0.081631 0.076988 0.146197 -vn -0.383019 -0.355624 0.852542 -v 0.081639 0.076928 0.146179 -vn -0.427980 -0.453836 0.781579 -v 0.081651 0.076843 0.146142 -vn -0.361862 0.011493 0.932161 -v 0.081599 0.077217 0.146216 -vn -0.430435 -0.125731 0.893822 -v 0.081615 0.077104 0.146216 -vn -0.852507 -0.144422 0.502368 -v 0.081638 0.077101 0.146255 -vn -0.381427 -0.233255 0.894486 -v 0.081627 0.077019 0.146204 -vn -0.299080 0.085300 0.950408 -v 0.081595 0.077248 0.146213 -vn -0.850391 0.065947 0.522002 -v 0.081593 0.077397 0.146210 -vn -0.324768 0.128063 0.937083 -v 0.081590 0.077282 0.146208 -vn -0.850232 0.272612 0.450320 -v 0.081552 0.077643 0.146056 -vn -0.396782 0.509039 0.763835 -v 0.081541 0.077607 0.146054 -vn -0.304646 0.441269 0.844081 -v 0.081562 0.077472 0.146144 -vn -0.403491 0.318604 0.857722 -v 0.081567 0.077440 0.146159 -vn -0.426864 0.220938 0.876911 -v 0.081575 0.077386 0.146180 -vn -0.349094 0.768035 0.536894 -v 0.081505 0.077777 0.145840 -vn -0.365239 0.688458 0.626599 -v 0.081532 0.077660 0.146004 -vn -0.423754 0.583751 0.692580 -v 0.081536 0.077635 0.146029 -vn 0.058682 0.982140 0.178767 -v 0.081472 0.077849 0.145616 -vn -0.853813 0.506114 0.121869 -v 0.081466 0.077867 0.145521 -vn -0.330353 0.934129 0.135164 -v 0.081467 0.077853 0.145578 -vn -0.847118 0.531402 0.001556 -v 0.081447 0.077851 0.145378 -vn -0.859255 0.504273 -0.085961 -v 0.081427 0.077806 0.145240 -vn -0.335155 0.916143 -0.219893 -v 0.081437 0.077834 0.145339 -vn -0.432875 0.853739 -0.289394 -v 0.081424 0.077802 0.145243 -vn -0.422076 0.896253 -0.136320 -v 0.081441 0.077842 0.145377 -vn -0.410727 0.909271 -0.067311 -v 0.081443 0.077844 0.145387 -vn -0.429578 0.902134 0.040216 -v 0.081459 0.077856 0.145521 -vn -0.396276 0.831803 -0.388675 -v 0.081410 0.077756 0.145150 -vn -0.855028 0.491072 -0.166657 -v 0.081411 0.077755 0.145143 -vn -0.365807 0.798707 -0.477757 -v 0.081405 0.077736 0.145119 -vn -0.417386 0.718526 -0.556336 -v 0.081393 0.077684 0.145050 -vn -0.427652 0.672206 -0.604362 -v 0.081383 0.077634 0.144996 -vn -0.425454 0.630224 -0.649467 -v 0.081378 0.077601 0.144966 -vn -0.411590 0.748154 -0.520441 -v 0.081394 0.077688 0.145054 -vn -0.892001 0.423219 -0.158809 -v 0.081402 0.077723 0.145097 -vn -0.429686 -0.005357 -0.902963 -v 0.081308 0.077092 0.144793 -vn -0.427180 0.040999 -0.903237 -v 0.081310 0.077107 0.144793 -vn -0.421143 0.131951 -0.897345 -v 0.081316 0.077147 0.144793 -vn -0.427919 0.273396 -0.861476 -v 0.081341 0.077350 0.144827 -vn -0.422466 0.354548 -0.834157 -v 0.081346 0.077384 0.144839 -vn -0.421504 0.431661 -0.797498 -v 0.081346 0.077390 0.144841 -vn -0.407292 0.545661 -0.732371 -v 0.081372 0.077569 0.144940 -vn -0.432828 -0.370592 -0.821779 -v 0.081268 0.076795 0.144870 -vn -0.417878 -0.271509 -0.866984 -v 0.081277 0.076861 0.144841 -vn -0.401880 -0.208006 -0.891755 -v 0.081283 0.076904 0.144826 -vn -0.413561 -0.113925 -0.903321 -v 0.081295 0.076993 0.144804 -vn -0.397454 -0.779112 -0.484784 -v 0.081216 0.076483 0.145161 -vn -0.414601 -0.818155 -0.398408 -v 0.081197 0.076421 0.145292 -vn -0.423124 -0.848384 -0.318138 -v 0.081192 0.076410 0.145326 -vn -0.425551 -0.861563 -0.276797 -v 0.081189 0.076402 0.145354 -vn -0.441598 -0.711126 -0.547075 -v 0.081221 0.076506 0.145125 -vn -0.438944 -0.643303 -0.627287 -v 0.081232 0.076560 0.145053 -vn -0.401818 -0.564274 -0.721205 -v 0.081246 0.076645 0.144969 -vn -0.402854 -0.494085 -0.770447 -v 0.081251 0.076681 0.144941 -vn -0.451437 -0.795175 0.404847 -v 0.081117 0.076478 0.145928 -vn -0.455849 -0.815658 0.356236 -v 0.081121 0.076464 0.145902 -vn -0.424672 -0.859020 0.285900 -v 0.081126 0.076444 0.145860 -vn -0.419896 -0.891967 0.167575 -v 0.081148 0.076390 0.145687 -vn -0.422593 -0.902299 0.085275 -v 0.081151 0.076385 0.145657 -vn -0.424137 -0.904019 0.053449 -v 0.081153 0.076382 0.145635 -vn -0.429737 -0.901627 -0.048941 -v 0.081157 0.076379 0.145609 -vn -0.417468 -0.893707 -0.164342 -v 0.081182 0.076392 0.145400 -vn -0.451159 -0.565522 0.690392 -v 0.081076 0.076691 0.146169 -vn -0.410396 -0.657728 0.631641 -v 0.081088 0.076621 0.146111 -vn -0.372828 -0.709966 0.597451 -v 0.081094 0.076585 0.146075 -vn -0.385871 -0.746057 0.542680 -v 0.081098 0.076562 0.146048 -vn -0.372224 -0.417305 0.829039 -v 0.081056 0.076841 0.146256 -vn -0.405042 -0.478287 0.779219 -v 0.081062 0.076793 0.146233 -vn -0.424099 0.039283 0.904764 -v 0.081001 0.077296 0.146311 -vn -0.356023 -0.061556 0.932447 -v 0.081026 0.077095 0.146320 -vn -0.434983 -0.175349 0.883200 -v 0.081032 0.077045 0.146314 -vn -0.434009 -0.257881 0.863211 -v 0.081040 0.076973 0.146301 -vn -0.405552 -0.349559 0.844592 -v 0.081049 0.076895 0.146277 -vn -0.412558 0.258255 0.873556 -v 0.080993 0.077361 0.146297 -vn -0.444321 0.332186 0.832004 -v 0.080967 0.077559 0.146215 -vn -0.422619 0.130209 0.896905 -v 0.080999 0.077309 0.146309 -vn -0.363394 0.595596 0.716387 -v 0.080951 0.077676 0.146132 -vn -0.373427 0.658909 0.652987 -v 0.080937 0.077766 0.146042 -vn -0.428570 0.484567 0.762576 -v 0.080961 0.077606 0.146186 -vn -0.435358 0.444430 0.782908 -v 0.080962 0.077600 0.146190 -vn -0.461064 0.867226 0.187986 -v 0.080885 0.077948 0.145652 -vn -0.353568 0.879248 0.319239 -v 0.080898 0.077923 0.145757 -vn -0.310033 0.860970 0.403249 -v 0.080905 0.077904 0.145811 -vn -0.470377 0.716672 0.514905 -v 0.080926 0.077825 0.145963 -vn -0.452702 0.682531 0.573770 -v 0.080931 0.077800 0.146000 -vn -0.279840 0.960042 -0.003117 -v 0.080866 0.077959 0.145485 -vn -0.398205 0.913817 0.079818 -v 0.080872 0.077959 0.145544 -vn -0.427055 0.747131 -0.509332 -v 0.080810 0.077795 0.145022 -vn -0.452542 0.784227 -0.424493 -v 0.080810 0.077798 0.145025 -vn -0.320352 0.872169 -0.369725 -v 0.080836 0.077903 0.145217 -vn -0.424323 0.873595 -0.238289 -v 0.080842 0.077923 0.145271 -vn -0.429131 0.886719 -0.171978 -v 0.080848 0.077937 0.145325 -vn -0.399501 0.912067 -0.092369 -v 0.080853 0.077946 0.145366 -vn -0.294030 0.600538 -0.743573 -v 0.080778 0.077598 0.144833 -vn -0.328191 0.696144 -0.638494 -v 0.080803 0.077761 0.144979 -vn -0.369711 0.211590 -0.904734 -v 0.080741 0.077282 0.144703 -vn 0.448636 0.188867 -0.873530 -v 0.080747 0.077343 0.144717 -vn 0.350356 0.272139 -0.896209 -v 0.080754 0.077406 0.144736 -vn -0.540160 0.476661 -0.693557 -v 0.080771 0.077545 0.144800 -vn -0.643117 0.111463 -0.757612 -v 0.080734 0.077222 0.144694 -vn -0.621213 0.068707 -0.780624 -v 0.080716 0.077062 0.144691 -vn -0.027935 -0.171808 -0.984734 -v 0.080708 0.077000 0.144698 -vn -0.865878 -0.267835 0.422517 -v 0.088814 0.076913 0.146219 -vn -0.864052 -0.414136 0.286192 -v 0.088856 0.076660 0.146073 -vn 0.244613 -0.864868 0.438369 -v 0.088903 0.076573 0.146084 -vn 0.262015 -0.801047 0.538212 -v 0.088903 0.076600 0.146126 -vn 0.251531 -0.750058 0.611674 -v 0.088903 0.076606 0.146134 -vn 0.181560 -0.950699 0.251409 -v 0.088903 0.076491 0.145891 -vn -0.413070 0.816035 0.404301 -v 0.082082 0.077716 0.145722 -vn -0.858272 0.324085 0.397918 -v 0.082187 0.077720 0.145970 -vn -0.861129 0.141088 0.488418 -v 0.082226 0.077504 0.146160 -vn -0.858811 -0.069045 0.507618 -v 0.082270 0.077220 0.146252 -vn -0.861371 -0.258919 0.437037 -v 0.082312 0.076928 0.146224 -vn -0.859404 -0.412882 0.301584 -v 0.082353 0.076673 0.146084 -vn -0.859182 -0.500143 0.107994 -v 0.082398 0.076490 0.145847 -vn -0.859650 -0.501718 -0.096332 -v 0.082437 0.076418 0.145569 -vn -0.860037 -0.419708 -0.290140 -v 0.082481 0.076464 0.145275 -vn -0.859997 -0.276197 -0.429093 -v 0.082524 0.076623 0.145026 -vn -0.858998 -0.081263 -0.505488 -v 0.082564 0.076862 0.144863 -vn -0.858978 0.131017 -0.494966 -v 0.082609 0.077156 0.144807 -vn -0.860317 0.311965 -0.403152 -v 0.082649 0.077438 0.144869 -vn -0.861533 0.446375 -0.241889 -v 0.082692 0.077678 0.145043 -vn -0.860087 0.507465 -0.052238 -v 0.082735 0.077829 0.145298 -vn -0.860199 0.484506 0.159098 -v 0.082775 0.077866 0.145584 -vn -0.859542 0.381482 0.340088 -v 0.082820 0.077783 0.145872 -vn -0.861362 0.217736 0.458962 -v 0.082860 0.077598 0.146095 -vn -0.860502 0.016957 0.509164 -v 0.082903 0.077337 0.146230 -vn -0.859620 -0.185324 0.476139 -v 0.082947 0.077039 0.146249 -vn -0.860177 -0.360939 0.360303 -v 0.082986 0.076769 0.146153 -vn -0.859949 -0.475491 0.185460 -v 0.083031 0.076550 0.145949 -vn -0.862702 -0.505527 -0.013707 -v 0.083072 0.076433 0.145681 -vn -0.860645 -0.462135 -0.213826 -v 0.083113 0.076432 0.145389 -vn -0.860584 -0.335860 -0.382876 -v 0.083158 0.076549 0.145115 -vn -0.860889 -0.158849 -0.483361 -v 0.083197 0.076758 0.144917 -vn -0.860878 0.049869 -0.506361 -v 0.083241 0.077038 0.144814 -vn -0.861461 0.240015 -0.447524 -v 0.083284 0.077332 0.144832 -vn -0.860299 0.400567 -0.315327 -v 0.083324 0.077591 0.144962 -vn -0.860199 0.494314 -0.125347 -v 0.083369 0.077783 0.145191 -vn -0.861353 0.502190 0.076655 -v 0.083409 0.077865 0.145468 -vn -0.862597 0.426599 0.271918 -v 0.083452 0.077830 0.145762 -vn -0.861200 0.291058 0.416678 -v 0.083495 0.077680 0.146018 -vn -0.861465 0.095700 0.498718 -v 0.083535 0.077448 0.146189 -vn -0.860578 -0.111738 0.496910 -v 0.083580 0.077156 0.146256 -vn -0.862157 -0.294657 0.412144 -v 0.083620 0.076872 0.146204 -vn -0.861708 -0.435566 0.260271 -v 0.083663 0.076626 0.146041 -vn -0.860743 -0.504282 0.069438 -v 0.083707 0.076465 0.145790 -vn -0.861264 -0.488430 -0.140214 -v 0.083746 0.076418 0.145507 -vn -0.860780 -0.391839 -0.324839 -v 0.083791 0.076490 0.145216 -vn -0.863669 -0.232896 -0.447030 -v 0.083832 0.076667 0.144985 -vn -0.861571 -0.036785 -0.506303 -v 0.083874 0.076922 0.144841 -vn -0.860590 0.168778 -0.480519 -v 0.083918 0.077219 0.144811 -vn -0.861339 0.345637 -0.372331 -v 0.083957 0.077493 0.144897 -vn -0.861459 0.466100 -0.201591 -v 0.084001 0.077719 0.145092 -vn -0.862668 0.505723 -0.006935 -v 0.084044 0.077846 0.145357 -vn -0.861286 0.468595 0.196479 -v 0.084084 0.077858 0.145647 -vn -0.861172 0.348405 0.370131 -v 0.084129 0.077751 0.145926 -vn -0.862098 0.176242 0.475106 -v 0.084169 0.077549 0.146132 -vn -0.862785 -0.031017 0.504619 -v 0.084212 0.077275 0.146244 -vn -0.862116 -0.222384 0.455303 -v 0.084255 0.076979 0.146238 -vn -0.861214 -0.387929 0.328362 -v 0.084295 0.076716 0.146118 -vn -0.860877 -0.488473 0.142427 -v 0.084340 0.076516 0.145896 -vn -0.862712 -0.502412 -0.057535 -v 0.084380 0.076423 0.145622 -vn -0.862700 -0.436990 -0.254537 -v 0.084423 0.076447 0.145327 -vn -0.861649 -0.304893 -0.405712 -v 0.084467 0.076587 0.145065 -vn -0.862093 -0.113892 -0.493786 -v 0.084506 0.076812 0.144886 -vn -0.861396 0.093848 -0.499190 -v 0.084551 0.077101 0.144808 -vn -0.863742 0.277781 -0.420462 -v 0.084592 0.077389 0.144850 -vn -0.862271 0.424240 -0.276605 -v 0.084634 0.077639 0.145003 -vn -0.861310 0.500755 -0.085962 -v 0.084678 0.077810 0.145248 -vn -0.861986 0.492141 0.121563 -v 0.084717 0.077867 0.145529 -vn -0.861855 0.401712 0.309570 -v 0.084762 0.077807 0.145822 -vn -0.864509 0.248011 0.437167 -v 0.084804 0.077638 0.146061 -vn -0.862497 0.055668 0.502991 -v 0.084844 0.077390 0.146213 -vn -0.861915 -0.154185 0.483041 -v 0.084889 0.077093 0.146255 -vn -0.862626 -0.329488 0.383817 -v 0.084929 0.076816 0.146179 -vn -0.862903 -0.456291 0.217249 -v 0.084972 0.076583 0.145993 -vn -0.862848 -0.504785 0.026174 -v 0.085015 0.076446 0.145732 -vn -0.861806 -0.474412 -0.179509 -v 0.085055 0.076423 0.145444 -vn -0.861479 -0.360698 -0.357422 -v 0.085100 0.076520 0.145160 -vn -0.863042 -0.193091 -0.466771 -v 0.085140 0.076714 0.144947 -vn -0.864086 0.012683 -0.503184 -v 0.085183 0.076983 0.144824 -vn -0.862707 0.205513 -0.462061 -v 0.085227 0.077280 0.144820 -vn -0.862713 0.376005 -0.338153 -v 0.085266 0.077546 0.144929 -vn -0.861855 0.481362 -0.159678 -v 0.085311 0.077755 0.145144 -vn -0.863883 0.502183 0.038969 -v 0.085352 0.077858 0.145415 -vn -0.862465 0.446449 0.238407 -v 0.085394 0.077845 0.145709 -vn -0.862068 0.130822 0.489617 -v 0.085477 0.077497 0.146164 -vn -0.861078 0.321630 0.393826 -v 0.085438 0.077715 0.145977 -vn -0.864131 -0.259139 0.431421 -v 0.085563 0.076921 0.146222 -vn -0.862458 -0.413929 0.291254 -v 0.085605 0.076667 0.146079 -vn -0.861299 -0.497630 0.102610 -v 0.085649 0.076486 0.145840 -vn -0.861691 -0.497482 -0.100003 -v 0.085688 0.076418 0.145561 -vn -0.861587 -0.414885 -0.292470 -v 0.085732 0.076468 0.145267 -vn -0.862085 -0.270245 -0.428693 -v 0.085775 0.076629 0.145020 -vn -0.860624 0.134845 -0.491063 -v 0.085860 0.077164 0.144807 -vn -0.860774 -0.076880 -0.503148 -v 0.085815 0.076870 0.144860 -vn -0.861886 0.313832 -0.398324 -v 0.085900 0.077445 0.144873 -vn -0.862933 0.446354 -0.236886 -v 0.085943 0.077683 0.145049 -vn -0.861653 0.505272 -0.047487 -v 0.085987 0.077831 0.145306 -vn -0.861666 0.480828 0.162284 -v 0.086026 0.077865 0.145592 -vn -0.860746 0.376901 0.342144 -v 0.086071 0.077779 0.145879 -vn -0.862475 0.212929 0.459128 -v 0.086111 0.077592 0.146100 -vn -0.861699 0.012248 0.507273 -v 0.086154 0.077329 0.146232 -vn -0.861247 -0.362651 0.356003 -v 0.086237 0.076762 0.146148 -vn -0.860858 -0.188408 0.472680 -v 0.086198 0.077031 0.146248 -vn -0.860735 -0.475844 0.180851 -v 0.086282 0.076545 0.145942 -vn -0.863654 -0.503766 -0.017944 -v 0.086323 0.076432 0.145673 -vn -0.861355 -0.459238 -0.217181 -v 0.086365 0.076433 0.145381 -vn -0.861498 -0.331594 -0.384534 -v 0.086409 0.076554 0.145108 -vn -0.861589 -0.154395 -0.483557 -v 0.086448 0.076765 0.144913 -vn -0.861205 0.054097 -0.505370 -v 0.086493 0.077046 0.144813 -vn -0.862305 0.243475 -0.444016 -v 0.086535 0.077339 0.144834 -vn -0.860713 0.494501 -0.121006 -v 0.086620 0.077787 0.145199 -vn -0.860773 0.402251 -0.311871 -v 0.086575 0.077597 0.144967 -vn -0.861684 0.500968 0.080824 -v 0.086660 0.077865 0.145476 -vn -0.862809 0.424096 0.275142 -v 0.086703 0.077827 0.145770 -vn -0.861632 0.287122 0.418510 -v 0.086746 0.077675 0.146024 -vn -0.860222 -0.116756 0.496374 -v 0.086831 0.077148 0.146257 -vn -0.862125 -0.298169 0.409678 -v 0.086871 0.076864 0.146201 -vn -0.860525 0.095281 0.500418 -v 0.086786 0.077441 0.146192 -vn -0.861813 -0.437644 0.256410 -v 0.086914 0.076620 0.146035 -vn -0.861199 -0.487415 -0.144095 -v 0.086997 0.076418 0.145498 -vn -0.860960 -0.504420 0.065637 -v 0.086958 0.076462 0.145783 -vn -0.860533 -0.389603 -0.328165 -v 0.087042 0.076493 0.145209 -vn -0.863500 -0.229392 -0.449163 -v 0.087083 0.076673 0.144979 -vn -0.861218 -0.032824 -0.507175 -v 0.087125 0.076930 0.144839 -vn -0.860947 0.349099 -0.369999 -v 0.087208 0.077500 0.144901 -vn -0.860424 0.172216 -0.479596 -v 0.087169 0.077227 0.144811 -vn -0.863890 0.503669 0.003438 -v 0.087295 0.077848 0.145364 -vn -0.861186 0.467538 -0.199417 -v 0.087253 0.077724 0.145098 -vn -0.861118 0.468077 0.198442 -v 0.087336 0.077857 0.145655 -vn -0.862678 0.340144 0.374283 -v 0.087380 0.077746 0.145933 -vn -0.863299 0.167486 0.476093 -v 0.087420 0.077543 0.146136 -vn -0.863728 -0.040296 0.502345 -v 0.087463 0.077266 0.146246 -vn -0.863525 -0.229010 0.449310 -v 0.087506 0.076971 0.146236 -vn -0.862457 -0.392063 0.320087 -v 0.087546 0.076710 0.146113 -vn -0.862110 -0.488960 0.132982 -v 0.087591 0.076511 0.145888 -vn -0.863627 -0.499820 -0.065786 -v 0.087631 0.076422 0.145614 -vn -0.864673 -0.428330 -0.262438 -v 0.087674 0.076449 0.145319 -vn -0.863386 -0.296723 -0.408069 -v 0.087718 0.076593 0.145059 -vn -0.863216 -0.104350 -0.493933 -v 0.087757 0.076820 0.144882 -vn -0.862387 0.102712 -0.495720 -v 0.087802 0.077110 0.144807 -vn -0.864385 0.284215 -0.414802 -v 0.087843 0.077396 0.144852 -vn -0.863262 0.428113 -0.267393 -v 0.087885 0.077645 0.145009 -vn -0.862470 0.500167 -0.077323 -v 0.087929 0.077813 0.145256 -vn -0.862856 0.488387 0.130224 -v 0.087968 0.077867 0.145538 -vn -0.862575 0.394867 0.316299 -v 0.088013 0.077803 0.145829 -vn -0.865241 0.239938 0.440213 -v 0.088055 0.077632 0.146067 -vn -0.863212 0.045934 0.502748 -v 0.088096 0.077382 0.146216 -vn -0.862944 -0.162183 0.478565 -v 0.088140 0.077085 0.146254 -vn -0.863231 -0.335649 0.377057 -v 0.088180 0.076809 0.146175 -vn -0.863341 -0.459672 0.208193 -v 0.088224 0.076578 0.145987 -vn -0.863644 -0.503812 0.017102 -v 0.088266 0.076444 0.145724 -vn -0.862488 -0.469935 -0.187818 -v 0.088306 0.076424 0.145436 -vn -0.862240 -0.353191 -0.363041 -v 0.088351 0.076524 0.145153 -vn -0.863401 -0.184586 -0.469539 -v 0.088391 0.076720 0.144942 -vn -0.864612 0.022286 -0.501946 -v 0.088434 0.076991 0.144822 -vn -0.863327 0.213072 -0.457456 -v 0.088478 0.077288 0.144821 -vn -0.863293 0.381628 -0.330281 -v 0.088517 0.077553 0.144934 -vn -0.862379 0.483404 -0.150411 -v 0.088562 0.077760 0.145151 -vn -0.863986 0.501249 0.047728 -v 0.088603 0.077859 0.145423 -vn -0.863337 0.440837 0.245586 -v 0.088645 0.077843 0.145717 -vn -0.862550 0.310488 0.399507 -v 0.088689 0.077710 0.145983 -vn -0.862841 0.122332 0.490450 -v 0.088728 0.077489 0.146168 -vn -0.862389 -0.085431 0.498986 -v 0.088773 0.077203 0.146254 -vn 0.202521 -0.851104 -0.484362 -v 0.088903 0.076540 0.145400 -vn 0.253924 -0.946993 -0.196790 -v 0.088903 0.076474 0.145585 -vn 0.029685 0.325100 -0.945214 -v 0.080685 0.077410 0.144725 -vn 0.103866 -0.180756 -0.978028 -v 0.080685 0.076971 0.144699 -vn 0.044858 0.748968 -0.661086 -v 0.080685 0.077778 0.144967 -vn 0.042015 0.979157 -0.198711 -v 0.080685 0.077975 0.145360 -vn 0.048767 0.946907 0.317787 -v 0.080685 0.077949 0.145799 -vn 0.055421 0.658347 0.750671 -v 0.080685 0.077707 0.146167 -vn 0.063849 0.205575 0.976556 -v 0.080685 0.077314 0.146364 -vn 0.058849 -0.315948 0.946950 -v 0.080685 0.076875 0.146338 -vn 0.062269 -0.746842 0.662079 -v 0.080685 0.076507 0.146096 -vn 0.066679 -0.977644 0.199414 -v 0.080685 0.076310 0.145703 -vn 0.067802 -0.947031 -0.313903 -v 0.080685 0.076336 0.145264 -vn 0.074238 -0.695951 -0.714242 -v 0.080685 0.076578 0.144896 -vn -0.710387 -0.041240 0.702602 -v 0.059703 0.077171 0.145037 -vn -0.819514 0.426446 0.382806 -v 0.059703 0.077650 0.144612 -vn -0.994585 0.036924 -0.097147 -v 0.059703 0.077566 0.144571 -vn -0.994277 0.013855 -0.105930 -v 0.059703 0.077279 0.144490 -vn -0.994791 -0.008046 -0.101619 -v 0.059703 0.076980 0.144494 -vn -0.813579 -0.465988 0.347771 -v 0.059703 0.076746 0.144559 -vn -0.103396 0.920279 -0.377354 -v 0.060303 0.078701 0.144991 -vn -0.101878 0.838101 -0.535917 -v 0.060303 0.078519 0.144622 -vn -0.378928 0.770320 -0.512855 -v 0.060073 0.078481 0.144647 -vn -0.112637 -0.902286 -0.416165 -v 0.060303 0.075658 0.144812 -vn -0.091250 -0.961375 -0.259677 -v 0.060303 0.075554 0.145087 -vn -0.387728 -0.888259 -0.246300 -v 0.060073 0.075598 0.145099 -vn -0.698360 0.689271 0.192870 -v 0.059879 0.078562 0.145929 -vn -0.915558 0.388830 0.102784 -v 0.059749 0.078375 0.145876 -vn -0.893586 0.380377 0.238363 -v 0.059749 0.078228 0.146210 -vn -0.985142 -0.096607 -0.141998 -v 0.059721 0.076516 0.146550 -vn -0.876801 0.367712 -0.309853 -v 0.059714 0.076409 0.146433 -vn -0.899508 -0.288695 0.327933 -v 0.059749 0.076317 0.146509 -vn -0.981681 -0.124929 0.143860 -v 0.059721 0.076640 0.144446 -vn -0.915560 -0.056583 -0.398181 -v 0.059749 0.076944 0.144267 -vn -0.983003 0.130900 0.128728 -v 0.059721 0.076057 0.146035 -vn -0.909218 -0.341939 0.237487 -v 0.059749 0.076075 0.146237 -vn -0.698364 -0.461766 0.546863 -v 0.059879 0.076191 0.146658 -vn -0.914288 -0.154076 0.374617 -v 0.059749 0.076626 0.146702 -vn -0.981681 0.124928 -0.143856 -v 0.059721 0.077645 0.146617 -vn -0.915555 0.056584 0.398193 -v 0.059749 0.077341 0.146796 -vn -0.893854 0.192471 0.404945 -v 0.059749 0.077689 0.146689 -vn -0.905683 0.279369 0.318892 -v 0.059749 0.077993 0.146488 -vn -0.880533 -0.296159 -0.370069 -v 0.059714 0.078044 0.146265 -vn -0.982298 -0.155787 0.104027 -v 0.059721 0.078161 0.146158 -vn -0.983003 -0.130898 -0.128726 -v 0.059721 0.078228 0.145029 -vn -0.912922 0.393464 -0.108443 -v 0.059749 0.078366 0.145155 -vn -0.914287 0.154074 -0.374620 -v 0.059749 0.077659 0.144361 -vn -0.698354 -0.288999 0.654814 -v 0.059879 0.076547 0.146880 -vn -0.382700 -0.368295 0.847290 -v 0.060073 0.076495 0.146999 -vn -0.917555 0.397577 -0.005074 -v 0.059749 0.078422 0.145515 -vn -0.698358 0.715691 -0.009137 -v 0.059879 0.078617 0.145513 -vn -0.385297 0.922573 -0.020134 -v 0.060073 0.078747 0.145511 -vn -0.698361 0.607012 0.379249 -v 0.059879 0.078393 0.146313 -vn -0.698366 0.475573 0.534897 -v 0.059879 0.078122 0.146633 -vn -0.698362 0.305613 0.647218 -v 0.059879 0.077772 0.146865 -vn -0.698360 0.110902 0.707103 -v 0.059879 0.077371 0.146988 -vn -0.698360 -0.597136 0.394615 -v 0.059879 0.075913 0.146344 -vn -0.378925 -0.770325 0.512850 -v 0.060073 0.075804 0.146416 -vn -0.385752 -0.593357 0.706486 -v 0.060073 0.076107 0.146757 -vn -0.382696 -0.884562 0.266633 -v 0.060073 0.075609 0.146003 -vn -0.698354 -0.684131 0.210397 -v 0.059879 0.075733 0.145965 -vn -0.912922 -0.393463 0.108441 -v 0.059749 0.075919 0.145908 -vn -0.917554 -0.397579 0.005074 -v 0.059749 0.075863 0.145548 -vn -0.698357 -0.715691 0.009138 -v 0.059879 0.075668 0.145550 -vn -0.385299 -0.922572 0.020134 -v 0.060073 0.075538 0.145552 -vn -0.381155 -0.149083 -0.912412 -v 0.060073 0.076894 0.143947 -vn -0.383971 -0.399241 -0.832570 -v 0.060073 0.076457 0.144081 -vn -0.698366 -0.110896 -0.707098 -v 0.059879 0.076914 0.144075 -vn -0.698356 -0.305617 -0.647223 -v 0.059879 0.076513 0.144198 -vn -0.893860 -0.192465 -0.404934 -v 0.059749 0.076596 0.144374 -vn -0.917555 0.051559 -0.394253 -v 0.059749 0.077308 0.144263 -vn -0.698369 0.092809 -0.709695 -v 0.059879 0.077334 0.144070 -vn -0.385294 0.127940 -0.913882 -v 0.060073 0.077351 0.143941 -vn -0.698357 0.289002 -0.654810 -v 0.059879 0.077738 0.144183 -vn -0.382695 0.368303 -0.847288 -v 0.060073 0.077790 0.144064 -vn -0.899509 0.288696 -0.327929 -v 0.059749 0.077968 0.144554 -vn -0.909216 0.341945 -0.237489 -v 0.059749 0.078210 0.144826 -vn -0.698363 0.461769 -0.546862 -v 0.059879 0.078094 0.144405 -vn -0.698357 0.597139 -0.394617 -v 0.059879 0.078372 0.144719 -vn -0.385760 0.593361 -0.706479 -v 0.060073 0.078178 0.144306 -vn -0.387724 0.888260 0.246301 -v 0.060073 0.078687 0.145964 -vn -0.385681 0.777309 0.497032 -v 0.060073 0.078503 0.146382 -vn -0.376564 0.615538 0.692324 -v 0.060073 0.078208 0.146731 -vn -0.383982 0.399235 0.832568 -v 0.060073 0.077828 0.146982 -vn -0.381154 0.149082 0.912412 -v 0.060073 0.077391 0.147116 -vn -0.132035 0.295377 0.946213 -v 0.060303 0.077683 0.147090 -vn -0.098860 0.154144 0.983090 -v 0.060303 0.077398 0.147162 -vn -0.108879 -0.020753 0.993838 -v 0.060303 0.077046 0.147179 -vn -0.089121 -0.186189 0.978464 -v 0.060303 0.076929 0.147168 -vn -0.385303 -0.127929 0.913880 -v 0.060073 0.076934 0.147122 -vn -0.698350 -0.092808 0.709714 -v 0.059879 0.076951 0.146993 -vn -0.917556 -0.051553 0.394251 -v 0.059749 0.076977 0.146800 -vn -0.091358 -0.340555 0.935776 -v 0.060303 0.076476 0.147041 -vn -0.091678 -0.621645 0.777915 -v 0.060303 0.076078 0.146792 -vn -0.103397 -0.482439 0.869805 -v 0.060303 0.076423 0.147016 -vn -0.108867 -0.989444 -0.095651 -v 0.060303 0.075495 0.145435 -vn -0.091898 -0.993436 0.068110 -v 0.060303 0.075493 0.145553 -vn -0.093825 -0.968444 0.230897 -v 0.060303 0.075565 0.146017 -vn -0.103401 -0.920264 0.377390 -v 0.060303 0.075584 0.146073 -vn -0.101879 -0.838109 0.535906 -v 0.060303 0.075766 0.146441 -vn -0.146034 -0.750118 0.644978 -v 0.060303 0.075909 0.146628 -vn -0.698360 -0.689271 -0.192870 -v 0.059879 0.075723 0.145134 -vn -0.915558 -0.388832 -0.102783 -v 0.059749 0.075910 0.145187 -vn -0.092552 -0.819895 -0.564984 -v 0.060303 0.075743 0.144657 -vn -0.385679 -0.777311 -0.497031 -v 0.060073 0.075782 0.144681 -vn -0.698360 -0.607015 -0.379244 -v 0.059879 0.075892 0.144750 -vn -0.893582 -0.380386 -0.238363 -v 0.059749 0.076057 0.144854 -vn -0.982298 0.155774 -0.104043 -v 0.059721 0.076124 0.144905 -vn -0.880543 0.296149 0.370053 -v 0.059714 0.076241 0.144798 -vn -0.905679 -0.279370 -0.318901 -v 0.059749 0.076292 0.144575 -vn -0.698359 -0.475584 -0.534897 -v 0.059879 0.076163 0.144430 -vn -0.376573 -0.615541 -0.692316 -v 0.060073 0.076076 0.144333 -vn -0.097172 -0.661309 -0.743793 -v 0.060303 0.076046 0.144298 -vn -0.092564 -0.465157 -0.880375 -v 0.060303 0.076438 0.144040 -vn -0.103397 0.482412 -0.869821 -v 0.060303 0.077862 0.144047 -vn -0.091352 0.340532 -0.935785 -v 0.060303 0.077809 0.144022 -vn -0.089094 0.186194 -0.978465 -v 0.060303 0.077356 0.143895 -vn -0.108855 0.020765 -0.993841 -v 0.060303 0.077239 0.143884 -vn -0.098857 -0.154145 -0.983090 -v 0.060303 0.076887 0.143901 -vn -0.132028 -0.295405 -0.946205 -v 0.060303 0.076601 0.143973 -vn -0.091690 0.621652 -0.777908 -v 0.060303 0.078207 0.144271 -vn -0.985150 0.096617 0.141932 -v 0.059721 0.077769 0.144513 -vn -0.146029 0.750130 -0.644965 -v 0.060303 0.078376 0.144435 -vn -0.093815 0.968458 -0.230844 -v 0.060303 0.078720 0.145047 -vn -0.382694 0.884561 -0.266640 -v 0.060073 0.078676 0.145060 -vn -0.698358 0.684125 -0.210401 -v 0.059879 0.078552 0.145098 -vn -0.876785 -0.367747 0.309855 -v 0.059714 0.077876 0.144630 -vn -0.091900 0.993436 -0.068114 -v 0.060303 0.078792 0.145510 -vn -0.108866 0.989444 0.095654 -v 0.060303 0.078790 0.145628 -vn -0.092556 0.465164 0.880372 -v 0.060303 0.077847 0.147024 -vn -0.097152 0.661309 0.743796 -v 0.060303 0.078239 0.146765 -vn -0.092549 0.819891 0.564990 -v 0.060303 0.078542 0.146406 -vn -0.112634 0.902289 0.416159 -v 0.060303 0.078627 0.146251 -vn -0.091243 0.961377 0.259670 -v 0.060303 0.078731 0.145976 -vn 0.381693 0.304299 0.872761 -v 0.061003 0.077683 0.147090 -vn 0.377164 0.615382 0.692136 -v 0.061003 0.078239 0.146765 -vn 0.378499 -0.058605 0.923744 -v 0.061003 0.077046 0.147179 -vn 0.376574 -0.400344 0.835414 -v 0.061003 0.076423 0.147016 -vn 0.382342 -0.690550 0.613967 -v 0.061003 0.075909 0.146628 -vn 0.378064 -0.875359 0.301352 -v 0.061003 0.075584 0.146073 -vn 0.379776 -0.923642 -0.051538 -v 0.061003 0.075495 0.145435 -vn 0.381690 -0.831163 -0.404327 -v 0.061003 0.075658 0.144812 -vn 0.377183 -0.615371 -0.692135 -v 0.061003 0.076046 0.144298 -vn 0.381671 -0.304307 -0.872768 -v 0.061003 0.076601 0.143973 -vn 0.378499 0.058609 -0.923744 -v 0.061003 0.077239 0.143884 -vn 0.376575 0.400343 -0.835414 -v 0.061003 0.077862 0.144047 -vn 0.382314 0.690556 -0.613978 -v 0.061003 0.078376 0.144435 -vn 0.378068 0.875355 -0.301360 -v 0.061003 0.078701 0.144991 -vn 0.379790 0.923636 0.051541 -v 0.061003 0.078790 0.145628 -vn 0.381703 0.831155 0.404332 -v 0.061003 0.078627 0.146251 -vn 0.770259 -0.624615 0.128674 -v 0.061103 0.076310 0.145703 -vn 0.906595 -0.421276 -0.024729 -v 0.061103 0.075595 0.145441 -vn 0.770262 -0.605268 -0.200865 -v 0.061103 0.076336 0.145264 -vn 0.906604 -0.379728 -0.184057 -v 0.061103 0.075748 0.144855 -vn 0.770042 -0.424126 -0.476605 -v 0.061103 0.076578 0.144896 -vn 0.906610 -0.280379 -0.315350 -v 0.061103 0.076113 0.144373 -vn 0.770032 -0.128445 -0.624943 -v 0.061103 0.076971 0.144699 -vn 0.770261 0.128678 0.624612 -v 0.061103 0.077314 0.146364 -vn 0.906596 -0.024724 0.421275 -v 0.061103 0.077052 0.147079 -vn 0.770264 -0.200867 0.605266 -v 0.061103 0.076875 0.146338 -vn 0.906603 -0.184056 0.379730 -v 0.061103 0.076466 0.146926 -vn 0.770263 -0.476594 0.423736 -v 0.061103 0.076507 0.146096 -vn 0.906616 -0.315348 0.280363 -v 0.061103 0.075984 0.146561 -vn 0.906601 -0.398659 0.138367 -v 0.061103 0.075678 0.146040 -vn 0.770263 0.624611 -0.128673 -v 0.061103 0.077975 0.145360 -vn 0.906604 0.421256 0.024731 -v 0.061103 0.078690 0.145622 -vn 0.770261 0.605267 0.200872 -v 0.061103 0.077949 0.145799 -vn 0.906610 0.379717 0.184047 -v 0.061103 0.078537 0.146208 -vn 0.770262 0.423742 0.476591 -v 0.061103 0.077707 0.146167 -vn 0.906598 0.280398 0.315369 -v 0.061103 0.078172 0.146690 -vn 0.906604 0.138359 0.398654 -v 0.061103 0.077651 0.146996 -vn 0.906587 -0.138375 -0.398688 -v 0.061103 0.076634 0.144067 -vn 0.906597 0.024732 -0.421272 -v 0.061103 0.077233 0.143984 -vn 0.770264 0.200867 -0.605266 -v 0.061103 0.077410 0.144725 -vn 0.906603 0.184057 -0.379730 -v 0.061103 0.077819 0.144137 -vn 0.770262 0.476593 -0.423741 -v 0.061103 0.077778 0.144967 -vn 0.906598 0.315369 -0.280397 -v 0.061103 0.078301 0.144502 -vn 0.906607 0.398650 -0.138354 -v 0.061103 0.078607 0.145023 -vn 0.945452 -0.102607 0.309179 -v 0.088903 0.076954 0.146101 -vn 0.945178 -0.319634 0.066883 -v 0.088903 0.076555 0.145653 -vn 0.945448 -0.243462 0.216459 -v 0.088903 0.076694 0.145930 -vn 0.938712 0.208831 0.274243 -v 0.088903 0.077541 0.145980 -vn 0.945449 0.065733 0.319070 -v 0.088903 0.077264 0.146119 -vn 0.904972 0.274889 0.324749 -v 0.089103 0.077408 0.145830 -vn 0.900743 0.087638 0.425420 -v 0.089103 0.077223 0.145923 -vn 0.900740 -0.136813 0.412250 -v 0.089103 0.077017 0.145911 -vn 0.900737 -0.324613 0.288615 -v 0.089103 0.076844 0.145797 -vn 0.901034 -0.424635 0.088449 -v 0.089103 0.076751 0.145612 -vn 0.901371 -0.410615 -0.137567 -v 0.089103 0.076763 0.145406 -vn 0.900740 -0.288613 -0.324608 -v 0.089103 0.076877 0.145233 -vn 0.900731 -0.087650 -0.425442 -v 0.089103 0.077062 0.145140 -vn 0.900744 0.136825 -0.412236 -v 0.089103 0.077268 0.145152 -vn 0.900744 0.324608 -0.288599 -v 0.089103 0.077441 0.145266 -vn 0.900740 0.425424 -0.087643 -v 0.089103 0.077534 0.145451 -vn 0.904202 0.408300 0.125338 -v 0.089103 0.077522 0.145658 -vn 1.000000 0.000000 0.000000 -v 0.089103 0.077142 0.145532 -vn -0.948595 -0.018548 0.315948 -v 0.060703 0.077149 0.145416 -vn -0.710390 -0.041245 0.702599 -v 0.060703 0.077747 0.144884 -vn -0.710388 -0.702601 -0.041244 -v 0.060703 0.077856 0.145007 -vn -0.948596 -0.315945 -0.018549 -v 0.060703 0.077258 0.145538 -vn -0.710387 -0.702602 -0.041226 -v 0.060703 0.077790 0.146136 -vn -0.710387 0.041231 -0.702603 -v 0.060703 0.077667 0.146245 -vn -0.948595 0.018548 -0.315948 -v 0.060703 0.077136 0.145647 -vn -0.710390 0.041243 -0.702599 -v 0.060703 0.076538 0.146179 -vn -0.710389 0.702600 0.041245 -v 0.060703 0.076429 0.146056 -vn -0.948596 0.315945 0.018549 -v 0.060703 0.077027 0.145525 -vn -0.710390 0.702600 0.041223 -v 0.060703 0.076495 0.144927 -vn -0.710389 -0.041234 0.702601 -v 0.060703 0.076618 0.144818 -vn -0.710388 -0.702601 -0.041245 -v 0.059703 0.057633 0.182509 -vn -0.813584 -0.399901 0.422091 -v 0.059703 0.058058 0.182987 -vn -0.994792 0.099973 0.019879 -v 0.059703 0.058150 0.182763 -vn -0.994278 0.106816 -0.001364 -v 0.059703 0.058188 0.182466 -vn -0.995324 0.095532 -0.014254 -v 0.059703 0.058142 0.182171 -vn -0.811458 -0.351315 -0.467027 -v 0.059703 0.058111 0.182083 -vn -0.710392 0.041242 -0.702597 -v 0.059703 0.057109 0.182974 -vn -0.819523 -0.426427 -0.382809 -v 0.059703 0.056631 0.183399 -vn -0.994585 -0.036924 0.097148 -v 0.059703 0.056714 0.183440 -vn -0.994278 -0.013851 0.105922 -v 0.059703 0.057002 0.183521 -vn -0.994792 0.008044 0.101612 -v 0.059703 0.057301 0.183517 -vn -0.813584 0.465984 -0.347765 -v 0.059703 0.057535 0.183452 -vn -0.710389 0.702599 0.041245 -v 0.059703 0.056644 0.182451 -vn -0.813587 0.399900 -0.422085 -v 0.059703 0.056219 0.181972 -vn -0.994791 -0.099975 -0.019879 -v 0.059703 0.056127 0.182197 -vn -0.994278 -0.106816 0.001364 -v 0.059703 0.056089 0.182493 -vn -0.995324 -0.095534 0.014254 -v 0.059703 0.056135 0.182788 -vn -0.811461 0.351315 0.467022 -v 0.059703 0.056166 0.182876 -vn -0.513786 -0.723971 -0.460316 -v 0.082409 0.056577 0.182267 -vn -0.518343 -0.808201 -0.279521 -v 0.082405 0.056569 0.182291 -vn 0.129003 -0.943419 -0.305483 -v 0.082103 0.056569 0.182291 -vn -0.562377 -0.099666 0.820853 -v 0.082198 0.057202 0.183076 -vn -0.502191 0.138731 0.853556 -v 0.082188 0.057259 0.183067 -vn 0.076975 0.194635 0.977851 -v 0.082103 0.057259 0.183067 -vn -0.623899 0.300117 0.721581 -v 0.082154 0.057437 0.183000 -vn 0.223563 0.637064 0.737678 -v 0.082103 0.057537 0.182928 -vn -0.684228 0.501568 0.529397 -v 0.082115 0.057616 0.182843 -vn -0.432505 0.722212 0.539769 -v 0.082103 0.057653 0.182788 -vn -0.535648 -0.325229 0.779299 -v 0.082240 0.056961 0.183053 -vn 0.106107 -0.306101 0.946067 -v 0.082103 0.056949 0.183049 -vn -0.531743 -0.575751 0.621096 -v 0.082281 0.056750 0.182937 -vn 0.090277 -0.741311 0.665062 -v 0.082103 0.056690 0.182878 -vn -0.497166 -0.721224 0.482350 -v 0.082296 0.056690 0.182878 -vn -0.528205 -0.799613 0.285689 -v 0.082326 0.056598 0.182741 -vn 0.112168 -0.974050 0.196581 -v 0.082103 0.056551 0.182601 -vn -0.493762 -0.860530 0.125251 -v 0.082350 0.056551 0.182601 -vn -0.537204 -0.835801 -0.113351 -v 0.082365 0.056539 0.182510 -vn -0.523345 -0.599049 -0.606011 -v 0.082452 0.056708 0.182061 -vn -0.131229 -0.695996 -0.705952 -v 0.082103 0.056740 0.182031 -vn -0.495982 -0.469467 -0.730481 -v 0.082459 0.056740 0.182031 -vn 0.485980 -0.613420 -0.622527 -v 0.082103 0.056767 0.182008 -vn 0.515119 -0.507327 -0.690848 -v 0.082109 0.056797 0.181987 -vn -0.514511 -0.266788 -0.814925 -v 0.082492 0.056906 0.181926 -vn 0.516726 -0.256277 -0.816894 -v 0.082153 0.057023 0.181891 -vn -0.496065 -0.083596 -0.864252 -v 0.082513 0.057017 0.181892 -vn -0.513400 0.125935 -0.848858 -v 0.082537 0.057150 0.181880 -vn 0.505415 0.041953 -0.861856 -v 0.082196 0.057269 0.181894 -vn -0.501061 0.306774 -0.809214 -v 0.082567 0.057327 0.181910 -vn 0.500812 0.237784 -0.832254 -v 0.082206 0.057327 0.181910 -vn -0.505365 0.480567 -0.716702 -v 0.082577 0.057383 0.181932 -vn 0.513270 0.406274 -0.755973 -v 0.082236 0.057488 0.181992 -vn -0.516679 0.692393 -0.503621 -v 0.082620 0.057581 0.182075 -vn 0.495987 0.583990 -0.642614 -v 0.082260 0.057587 0.182081 -vn 0.514544 0.701198 -0.493524 -v 0.082281 0.057656 0.182175 -vn -0.515854 0.822074 -0.241015 -v 0.082663 0.057706 0.182286 -vn 0.495905 0.813329 -0.304260 -v 0.082314 0.057726 0.182359 -vn -0.495283 0.866367 -0.064051 -v 0.082675 0.057726 0.182359 -vn 0.513793 0.847385 -0.133997 -v 0.082321 0.057733 0.182402 -vn -0.509779 0.846354 0.154308 -v 0.082703 0.057737 0.182523 -vn 0.503066 0.860673 0.078533 -v 0.082364 0.057715 0.182647 -vn -0.487312 0.808032 0.331076 -v 0.082730 0.057708 0.182669 -vn 0.505641 0.825507 0.250732 -v 0.082368 0.057708 0.182669 -vn -0.511494 0.689779 0.512424 -v 0.082748 0.057668 0.182761 -vn 0.507609 0.738449 0.443876 -v 0.082408 0.057599 0.182865 -vn -0.507246 0.557294 0.657362 -v 0.082784 0.057537 0.182928 -vn 0.493160 0.614654 0.615624 -v 0.082422 0.057537 0.182928 -vn -0.502176 0.413800 0.759335 -v 0.082788 0.057516 0.182946 -vn 0.513094 0.472993 0.716249 -v 0.082448 0.057412 0.183014 -vn -0.510669 0.204415 0.835124 -v 0.082830 0.057299 0.183058 -vn 0.494344 0.284859 0.821267 -v 0.082477 0.057259 0.183067 -vn -0.496571 0.029879 0.867482 -v 0.082838 0.057260 0.183067 -vn 0.512782 0.098223 0.852882 -v 0.082492 0.057172 0.183079 -vn -0.516308 -0.182333 0.836768 -v 0.082875 0.057053 0.183074 -vn 0.497818 -0.124347 0.858321 -v 0.082531 0.056949 0.183049 -vn -0.496490 -0.356259 0.791566 -v 0.082892 0.056949 0.183049 -vn 0.512015 -0.281782 0.811443 -v 0.082533 0.056933 0.183044 -vn -0.509813 -0.534114 0.674398 -v 0.082914 0.056829 0.182994 -vn 0.506736 -0.470842 0.722168 -v 0.082575 0.056726 0.182916 -vn -0.496615 -0.676800 0.543429 -v 0.082946 0.056690 0.182878 -vn 0.500247 -0.622791 0.601568 -v 0.082585 0.056690 0.182878 -vn -0.508765 -0.778521 0.367509 -v 0.082958 0.056648 0.182825 -vn 0.509680 -0.739930 0.439011 -v 0.082620 0.056585 0.182712 -vn -0.516842 -0.851779 0.085718 -v 0.083000 0.056551 0.182603 -vn 0.498029 -0.830529 0.249377 -v 0.082639 0.056551 0.182601 -vn 0.516893 -0.853070 0.071360 -v 0.082659 0.056538 0.182478 -vn -0.512389 -0.833443 -0.206954 -v 0.083041 0.056550 0.182362 -vn 0.495182 -0.856860 -0.143479 -v 0.082693 0.056569 0.182291 -vn -0.494531 -0.777869 -0.387761 -v 0.083055 0.056569 0.182291 -vn 0.511576 -0.798090 -0.318343 -v 0.082704 0.056590 0.182236 -vn -0.513168 -0.648190 -0.562591 -v 0.083086 0.056648 0.182134 -vn 0.516653 -0.644517 -0.563620 -v 0.082746 0.056732 0.182038 -vn -0.490128 -0.535250 -0.687955 -v 0.083109 0.056740 0.182031 -vn -0.509734 -0.344063 -0.788538 -v 0.083125 0.056820 0.181971 -vn 0.510652 -0.416615 -0.752108 -v 0.082787 0.056939 0.181914 -vn -0.503678 -0.146758 -0.851335 -v 0.083163 0.057017 0.181892 -vn 0.493272 -0.223832 -0.840584 -v 0.082802 0.057017 0.181892 -vn -0.504725 0.035812 -0.862537 -v 0.083169 0.057052 0.181886 -vn 0.509778 -0.036747 -0.859521 -v 0.082832 0.057185 0.181881 -vn -0.512911 0.243051 -0.823316 -v 0.083212 0.057295 0.181900 -vn 0.495441 0.179612 -0.849869 -v 0.082856 0.057327 0.181910 -vn -0.496517 0.403519 -0.768533 -v 0.083217 0.057327 0.181910 -vn 0.515742 0.346742 -0.783441 -v 0.082871 0.057415 0.181947 -vn -0.513018 0.578309 -0.634327 -v 0.083252 0.057509 0.182008 -vn 0.497507 0.536177 -0.681910 -v 0.082910 0.057587 0.182081 -vn -0.494463 0.711261 -0.499614 -v 0.083271 0.057587 0.182081 -vn 0.509989 0.656099 -0.556278 -v 0.082915 0.057606 0.182104 -vn -0.513317 0.801639 -0.306400 -v 0.083297 0.057668 0.182198 -vn 0.503341 0.780066 -0.371679 -v 0.082958 0.057717 0.182322 -vn -0.499029 0.856038 -0.134791 -v 0.083325 0.057726 0.182359 -vn 0.505747 0.839565 -0.198370 -v 0.082964 0.057726 0.182359 -vn -0.506873 0.859254 0.069007 -v 0.083336 0.057736 0.182427 -vn 0.513061 0.858326 -0.006689 -v 0.082998 0.057733 0.182561 -vn -0.516980 0.776276 0.360731 -v 0.083380 0.057707 0.182670 -vn 0.484931 0.847921 0.214176 -v 0.083018 0.057708 0.182669 -vn 0.510034 0.774550 0.374081 -v 0.083043 0.057649 0.182795 -vn -0.514896 0.613390 0.598861 -v 0.083423 0.057583 0.182882 -vn 0.494933 0.659970 0.565227 -v 0.083072 0.057537 0.182928 -vn -0.495035 0.483228 0.722102 -v 0.083434 0.057537 0.182928 -vn 0.515048 0.521293 0.680425 -v 0.083083 0.057485 0.182970 -vn -0.510207 0.279834 0.813254 -v 0.083463 0.057391 0.183024 -vn 0.516986 0.263906 0.814297 -v 0.083127 0.057259 0.183067 -vn -0.484853 0.113293 0.867227 -v 0.083488 0.057259 0.183067 -vn -0.513113 -0.107520 0.851560 -v 0.083508 0.057150 0.183080 -vn 0.506630 -0.035523 0.861432 -v 0.083170 0.057013 0.183066 -vn -0.505853 -0.295176 0.810546 -v 0.083542 0.056949 0.183049 -vn 0.499961 -0.235807 0.833327 -v 0.083181 0.056949 0.183049 -vn -0.503498 -0.459803 0.731485 -v 0.083548 0.056914 0.183036 -vn 0.513209 -0.400902 0.758877 -v 0.083210 0.056794 0.182971 -vn -0.509968 -0.628562 0.587233 -v 0.083591 0.056711 0.182901 -vn 0.494349 -0.582085 0.645597 -v 0.083235 0.056690 0.182878 -vn -0.497508 -0.739436 0.453563 -v 0.083596 0.056690 0.182878 -vn 0.512871 -0.699812 0.497219 -v 0.083255 0.056624 0.182789 -vn -0.515573 -0.818355 0.253929 -v 0.083635 0.056578 0.182694 -vn 0.496155 -0.811963 0.307484 -v 0.083289 0.056551 0.182601 -vn -0.495362 -0.864919 0.080824 -v 0.083650 0.056551 0.182601 -vn 0.513279 -0.846842 0.139295 -v 0.083295 0.056544 0.182562 -vn -0.510014 -0.849458 -0.135305 -v 0.083674 0.056539 0.182459 -vn 0.504177 -0.860594 -0.071999 -v 0.083338 0.056561 0.182318 -vn -0.494617 -0.808509 -0.318854 -v 0.083705 0.056569 0.182291 -vn 0.504910 -0.826641 -0.248456 -v 0.083343 0.056569 0.182291 -vn -0.510679 -0.700287 -0.498804 -v 0.083719 0.056598 0.182219 -vn 0.509469 -0.740154 -0.438877 -v 0.083382 0.056675 0.182099 -vn -0.516983 -0.488860 -0.702670 -v 0.083760 0.056745 0.182027 -vn 0.492686 -0.616545 -0.614111 -v 0.083397 0.056740 0.182031 -vn 0.513364 -0.478073 -0.712674 -v 0.083422 0.056860 0.181948 -vn -0.511608 -0.227557 -0.828538 -v 0.083801 0.056956 0.181908 -vn 0.493990 -0.288205 -0.820312 -v 0.083452 0.057017 0.181892 -vn -0.494838 -0.046212 -0.867756 -v 0.083813 0.057017 0.181892 -vn 0.512639 -0.098713 -0.852911 -v 0.083466 0.057099 0.181881 -vn -0.517074 0.167657 -0.839360 -v 0.083846 0.057202 0.181883 -vn 0.517353 0.197152 -0.832753 -v 0.083508 0.057338 0.181914 -vn 0.517169 0.649397 0.557512 -v 0.083720 0.057549 0.182917 -vn -0.513527 0.659900 0.548473 -v 0.084057 0.057642 0.182806 -vn 0.511080 0.800476 0.313108 -v 0.083678 0.057689 0.182718 -vn -0.493867 0.785706 0.372507 -v 0.084030 0.057708 0.182669 -vn 0.495534 0.857273 0.139745 -v 0.083668 0.057708 0.182669 -vn -0.512368 0.837237 0.191083 -v 0.084012 0.057731 0.182575 -vn 0.515689 0.853464 -0.075257 -v 0.083633 0.057738 0.182476 -vn -0.497462 0.867027 -0.028220 -v 0.083975 0.057726 0.182359 -vn 0.496542 0.830410 -0.252716 -v 0.083614 0.057726 0.182359 -vn -0.512294 0.837059 -0.192062 -v 0.083972 0.057721 0.182335 -vn 0.509790 0.736621 -0.444413 -v 0.083594 0.057689 0.182242 -vn -0.506462 0.769058 -0.389932 -v 0.083929 0.057615 0.182116 -vn 0.499546 0.621503 -0.603479 -v 0.083560 0.057587 0.182081 -vn -0.502137 0.667318 -0.550041 -v 0.083921 0.057587 0.182081 -vn 0.508132 0.464966 -0.724988 -v 0.083549 0.057547 0.182040 -vn -0.509732 0.518838 -0.686280 -v 0.083885 0.057428 0.181954 -vn -0.498632 0.339769 -0.797448 -v 0.083867 0.057327 0.181910 -vn 0.517836 -0.271534 -0.811243 -v 0.084101 0.057013 0.181893 -vn -0.492994 -0.123923 -0.861162 -v 0.084463 0.057017 0.181892 -vn -0.510541 -0.297845 -0.806620 -v 0.084434 0.056865 0.181945 -vn 0.514623 -0.525541 -0.677473 -v 0.084057 0.056788 0.181993 -vn -0.494818 -0.497045 -0.712812 -v 0.084409 0.056740 0.182031 -vn 0.494995 -0.662333 -0.562401 -v 0.084047 0.056740 0.182031 -vn -0.515130 -0.624648 -0.586903 -v 0.084395 0.056679 0.182094 -vn 0.512735 -0.773149 -0.373288 -v 0.084017 0.056625 0.182168 -vn -0.498779 -0.758483 -0.419431 -v 0.084355 0.056569 0.182291 -vn 0.495459 -0.845662 -0.198435 -v 0.083993 0.056569 0.182291 -vn -0.509549 -0.819977 -0.260763 -v 0.084351 0.056563 0.182311 -vn 0.513054 -0.858260 0.012887 -v 0.083972 0.056543 0.182403 -vn -0.505127 -0.861921 -0.044027 -v 0.084308 0.056543 0.182554 -vn 0.505257 -0.839307 0.200696 -v 0.083939 0.056551 0.182601 -vn -0.504547 -0.851056 0.145382 -v 0.084300 0.056551 0.182601 -vn 0.504628 -0.776437 0.377488 -v 0.083932 0.056561 0.182643 -vn -0.513211 -0.794899 0.323650 -v 0.084268 0.056620 0.182781 -vn 0.509711 -0.652520 0.560725 -v 0.083889 0.056674 0.182860 -vn -0.495166 -0.700782 0.513532 -v 0.084246 0.056690 0.182878 -vn 0.498349 -0.532778 0.683956 -v 0.083885 0.056690 0.182878 -vn -0.512741 -0.565724 0.645797 -v 0.084223 0.056786 0.182965 -vn 0.515201 -0.343381 0.785275 -v 0.083845 0.056867 0.183015 -vn -0.495292 -0.389823 0.776353 -v 0.084192 0.056949 0.183049 -vn 0.494814 -0.176295 0.850928 -v 0.083831 0.056949 0.183049 -vn -0.514230 -0.221340 0.828599 -v 0.084183 0.057003 0.183064 -vn 0.510225 0.043235 0.858953 -v 0.083806 0.057097 0.183078 -vn -0.502477 -0.010934 0.864522 -v 0.084140 0.057248 0.183070 -vn 0.492591 0.225853 0.840443 -v 0.083777 0.057260 0.183067 -vn -0.507323 0.157368 0.847265 -v 0.084138 0.057259 0.183067 -vn 0.512243 0.421799 0.748127 -v 0.083761 0.057343 0.183044 -vn -0.509410 0.361830 0.780757 -v 0.084096 0.057475 0.182976 -vn -0.497931 0.541260 0.677571 -v 0.084084 0.057537 0.182928 -vn -0.512547 0.089033 -0.854031 -v 0.084479 0.057104 0.181881 -vn 0.508141 0.028715 -0.860795 -v 0.084144 0.057259 0.181892 -vn -0.509440 0.283864 -0.812337 -v 0.084517 0.057327 0.181910 -vn 0.499462 0.233955 -0.834148 -v 0.084156 0.057327 0.181910 -vn -0.501845 0.439000 -0.745273 -v 0.084520 0.057342 0.181915 -vn 0.513499 0.395331 -0.761599 -v 0.084184 0.057479 0.181986 -vn -0.511065 0.611276 -0.604280 -v 0.084561 0.057549 0.182042 -vn 0.493735 0.579673 -0.648232 -v 0.084210 0.057587 0.182081 -vn -0.495645 0.731904 -0.467602 -v 0.084571 0.057587 0.182081 -vn 0.512264 0.697688 -0.500817 -v 0.084229 0.057650 0.182166 -vn -0.515381 0.813617 -0.269092 -v 0.084606 0.057691 0.182245 -vn 0.496794 0.810217 -0.311037 -v 0.084264 0.057726 0.182359 -vn -0.496435 0.862571 -0.097591 -v 0.084625 0.057726 0.182359 -vn 0.513013 0.846147 -0.144405 -v 0.084269 0.057732 0.182392 -vn -0.510072 0.852239 0.116254 -v 0.084645 0.057738 0.182478 -vn 0.505685 0.860242 0.065315 -v 0.084312 0.057718 0.182636 -vn -0.500710 0.809324 0.307057 -v 0.084680 0.057708 0.182669 -vn 0.504454 0.827487 0.246558 -v 0.084318 0.057708 0.182669 -vn -0.508510 0.714973 0.479825 -v 0.084689 0.057688 0.182720 -vn 0.509579 0.743303 0.433393 -v 0.084356 0.057605 0.182856 -vn -0.518035 0.513684 0.683936 -v 0.084731 0.057548 0.182918 -vn 0.491115 0.617721 0.614187 -v 0.084372 0.057537 0.182928 -vn 0.513931 0.483036 0.708908 -v 0.084396 0.057422 0.183009 -vn -0.512723 0.250691 0.821139 -v 0.084772 0.057343 0.183044 -vn 0.494122 0.291874 0.818934 -v 0.084427 0.057259 0.183067 -vn -0.493837 0.063122 0.867260 -v 0.084788 0.057260 0.183067 -vn 0.512238 0.104325 0.852484 -v 0.084440 0.057183 0.183078 -vn -0.513995 -0.154599 0.843747 -v 0.084817 0.057098 0.183078 -vn 0.518044 -0.189372 0.834128 -v 0.084482 0.056943 0.183047 -vn -0.495011 -0.319566 0.807986 -v 0.084842 0.056949 0.183049 -vn -0.509518 -0.503370 0.697861 -v 0.084856 0.056868 0.183015 -vn 0.509801 -0.458881 0.727689 -v 0.084523 0.056734 0.182923 -vn -0.506318 -0.658348 0.556974 -v 0.084896 0.056690 0.182878 -vn 0.499176 -0.620366 0.604954 -v 0.084535 0.056690 0.182878 -vn -0.504320 -0.758838 0.412100 -v 0.084900 0.056676 0.182862 -vn 0.510237 -0.733006 0.449845 -v 0.084568 0.056590 0.182722 -vn -0.513748 -0.830905 0.213679 -v 0.084943 0.056562 0.182645 -vn 0.495706 -0.829835 0.256222 -v 0.084589 0.056551 0.182601 -vn -0.496026 -0.867213 0.043592 -v 0.084950 0.056551 0.182601 -vn 0.515172 -0.853430 0.079084 -v 0.084607 0.056538 0.182489 -vn -0.512248 -0.840957 -0.174336 -v 0.084983 0.056543 0.182407 -vn 0.496257 -0.857526 -0.135567 -v 0.084643 0.056569 0.182291 -vn -0.494181 -0.792819 -0.356684 -v 0.085005 0.056569 0.182291 -vn 0.510918 -0.802583 -0.307935 -v 0.084652 0.056586 0.182246 -vn -0.513568 -0.671524 -0.534137 -v 0.085028 0.056623 0.182172 -vn 0.502751 -0.701228 -0.505491 -v 0.084694 0.056724 0.182045 -vn -0.503291 -0.548666 -0.667581 -v 0.085059 0.056740 0.182031 -vn 0.509153 -0.583415 -0.632765 -v 0.084697 0.056740 0.182031 -vn -0.506989 -0.381824 -0.772770 -v 0.085068 0.056784 0.181996 -vn 0.512566 -0.423573 -0.746902 -v 0.084735 0.056929 0.181917 -vn -0.517985 -0.093306 -0.850286 -v 0.085111 0.057007 0.181894 -vn 0.491908 -0.227207 -0.840478 -v 0.084752 0.057017 0.181892 -vn 0.511018 -0.049875 -0.858122 -v 0.084780 0.057175 0.181881 -vn -0.515615 0.199088 -0.833370 -v 0.085154 0.057252 0.181891 -vn 0.494668 0.172525 -0.851785 -v 0.084806 0.057327 0.181910 -vn -0.494773 0.375230 -0.783838 -v 0.085167 0.057327 0.181910 -vn 0.515076 0.340128 -0.786772 -v 0.084819 0.057405 0.181942 -vn -0.509603 0.556597 -0.656129 -v 0.085194 0.057473 0.181981 -vn 0.499526 0.528813 -0.686171 -v 0.084860 0.057587 0.182081 -vn -0.488881 0.688074 -0.536236 -v 0.085221 0.057587 0.182081 -vn 0.509666 0.648821 -0.565042 -v 0.084863 0.057599 0.182095 -vn -0.512817 0.787929 -0.340860 -v 0.085239 0.057645 0.182159 -vn 0.506154 0.772618 -0.383235 -v 0.084906 0.057714 0.182312 -vn -0.508696 0.846671 -0.156129 -v 0.085275 0.057726 0.182359 -vn 0.505073 0.838979 -0.202521 -v 0.084914 0.057726 0.182359 -vn -0.503470 0.863798 0.019263 -v 0.085279 0.057731 0.182383 -vn 0.513391 0.857941 -0.019139 -v 0.084946 0.057734 0.182551 -vn -0.510770 0.826382 0.237081 -v 0.085322 0.057720 0.182626 -vn 0.494569 0.846961 0.195085 -v 0.084968 0.057708 0.182669 -vn -0.496891 0.766843 0.406265 -v 0.085330 0.057708 0.182669 -vn 0.512145 0.775220 0.369786 -v 0.084991 0.057654 0.182786 -vn -0.515096 0.635483 0.575185 -v 0.085366 0.057612 0.182848 -vn 0.495479 0.664767 0.559093 -v 0.085022 0.057537 0.182928 -vn -0.495546 0.510497 0.702728 -v 0.085384 0.057537 0.182928 -vn 0.514502 0.529554 0.674434 -v 0.085031 0.057493 0.182963 -vn -0.510685 0.315759 0.799686 -v 0.085405 0.057432 0.183003 -vn 0.519167 0.279090 0.807821 -v 0.085075 0.057270 0.183065 -vn -0.499884 0.134502 0.855585 -v 0.085438 0.057259 0.183067 -vn -0.511515 -0.069114 0.856491 -v 0.085450 0.057195 0.183077 -vn 0.509543 -0.021419 0.860178 -v 0.085118 0.057023 0.183068 -vn -0.518813 -0.348034 0.780836 -v 0.085491 0.056955 0.183051 -vn 0.499082 -0.232424 0.834803 -v 0.085131 0.056949 0.183049 -vn 0.514144 -0.389548 0.764139 -v 0.085158 0.056803 0.182977 -vn -0.512324 -0.593309 0.620894 -v 0.085532 0.056745 0.182932 -vn 0.493630 -0.576720 0.650941 -v 0.085185 0.056690 0.182878 -vn -0.494374 -0.723444 0.481896 -v 0.085546 0.056690 0.182878 -vn 0.512080 -0.695505 0.504031 -v 0.085203 0.056630 0.182798 -vn -0.512229 -0.811387 0.281553 -v 0.085577 0.056595 0.182735 -vn 0.497775 -0.808174 0.314761 -v 0.085239 0.056551 0.182601 -vn -0.490202 -0.862873 0.123096 -v 0.085600 0.056551 0.182601 -vn 0.513075 -0.845277 0.149202 -v 0.085244 0.056546 0.182572 -vn -0.509928 -0.854721 -0.097085 -v 0.085616 0.056539 0.182504 -vn 0.507373 -0.859752 -0.058307 -v 0.085286 0.056558 0.182329 -vn -0.505540 -0.810557 -0.295682 -v 0.085655 0.056569 0.182291 -vn 0.504404 -0.828043 -0.244788 -v 0.085293 0.056569 0.182291 -vn -0.506395 -0.729083 -0.460436 -v 0.085660 0.056580 0.182261 -vn 0.510027 -0.746357 -0.427580 -v 0.085330 0.056668 0.182107 -vn -0.513505 -0.593904 -0.619347 -v 0.085703 0.056713 0.182056 -vn 0.487284 -0.621317 -0.613613 -v 0.085347 0.056740 0.182031 -vn -0.497144 -0.464816 -0.732662 -v 0.085709 0.056740 0.182031 -vn 0.511693 -0.486243 -0.708335 -v 0.085370 0.056850 0.181953 -vn -0.512024 -0.262684 -0.817820 -v 0.085743 0.056913 0.181924 -vn 0.494735 -0.295822 -0.817146 -v 0.085402 0.057017 0.181892 -vn -0.493802 -0.080230 -0.865865 -v 0.085763 0.057017 0.181892 -vn 0.512179 -0.109675 -0.851848 -v 0.085414 0.057088 0.181882 -vn -0.514217 0.136430 -0.846739 -v 0.085788 0.057157 0.181880 -vn 0.519278 0.181421 -0.835127 -v 0.085456 0.057329 0.181911 -vn -0.502111 0.307664 -0.808225 -v 0.085817 0.057327 0.181910 -vn -0.509070 0.487507 -0.709355 -v 0.085828 0.057389 0.181934 -vn 0.511699 0.452296 -0.730475 -v 0.085497 0.057538 0.182032 -vn -0.519389 0.697508 -0.493678 -v 0.085871 0.057586 0.182080 -vn 0.499159 0.619194 -0.606168 -v 0.085510 0.057587 0.182081 -vn 0.511015 0.729109 -0.455263 -v 0.085542 0.057685 0.182232 -vn -0.515345 0.824022 -0.235387 -v 0.085914 0.057709 0.182293 -vn 0.495324 0.828883 -0.260015 -v 0.085564 0.057726 0.182359 -vn -0.495228 0.866720 -0.059550 -v 0.085925 0.057726 0.182359 -vn 0.515038 0.853180 -0.082584 -v 0.085582 0.057738 0.182465 -vn -0.508589 0.845630 0.162009 -v 0.085954 0.057736 0.182530 -vn 0.497397 0.857580 0.130968 -v 0.085618 0.057708 0.182669 -vn -0.484620 0.808920 0.332854 -v 0.085980 0.057708 0.182669 -vn 0.511050 0.804412 0.302901 -v 0.085626 0.057693 0.182708 -vn -0.513335 0.683009 0.519601 -v 0.085999 0.057665 0.182767 -vn 0.504237 0.704718 0.499117 -v 0.085668 0.057556 0.182910 -vn -0.508134 0.555574 0.658132 -v 0.086034 0.057537 0.182928 -vn 0.509324 0.584861 0.631290 -v 0.085672 0.057537 0.182928 -vn -0.505361 0.404169 0.762403 -v 0.086039 0.057511 0.182950 -vn 0.512896 0.428944 0.743602 -v 0.085709 0.057353 0.183040 -vn -0.510744 0.198115 0.836595 -v 0.086082 0.057293 0.183059 -vn 0.488429 0.230349 0.841651 -v 0.085727 0.057259 0.183067 -vn -0.498441 0.023910 0.866594 -v 0.086088 0.057260 0.183067 -vn 0.509063 0.053336 0.859075 -v 0.085754 0.057108 0.183079 -vn -0.515136 -0.186784 0.836509 -v 0.086126 0.057046 0.183073 -vn 0.497937 -0.170405 0.850307 -v 0.085781 0.056949 0.183049 -vn -0.497408 -0.361826 0.788459 -v 0.086142 0.056949 0.183049 -vn -0.518043 -0.543507 0.660479 -v 0.086165 0.056823 0.182990 -vn 0.522516 -0.336792 0.783293 -v 0.085793 0.056876 0.183019 -vn -0.501581 -0.672854 0.543768 -v 0.086196 0.056690 0.182878 -vn 0.522538 -0.580108 0.624843 -v 0.085837 0.056681 0.182868 -vn -0.512230 -0.780966 0.357370 -v 0.086210 0.056644 0.182819 -vn 0.508265 -0.768232 0.389212 -v 0.085880 0.056564 0.182653 -vn -0.519988 -0.850873 0.075020 -v 0.086251 0.056550 0.182597 -vn 0.505353 -0.838368 0.204348 -v 0.085889 0.056551 0.182601 -vn 0.514036 -0.857393 0.025397 -v 0.085921 0.056542 0.182414 -vn -0.512195 -0.832012 -0.213101 -v 0.086292 0.056551 0.182355 -vn 0.494220 -0.848051 -0.191196 -v 0.085943 0.056569 0.182291 -vn -0.495396 -0.775054 -0.392267 -v 0.086305 0.056569 0.182291 -vn 0.511959 -0.776953 -0.366389 -v 0.085965 0.056620 0.182178 -vn -0.511427 -0.644901 -0.567930 -v 0.086337 0.056652 0.182129 -vn 0.498614 -0.665119 -0.555879 -v 0.085997 0.056740 0.182031 -vn -0.500415 0.406601 -0.764370 -v 0.086467 0.057327 0.181910 -vn -0.515946 0.249986 -0.819333 -v 0.086463 0.057301 0.181902 -vn 0.510671 0.014300 -0.859657 -v 0.086092 0.057248 0.181890 -vn -0.509731 0.045641 -0.859123 -v 0.086420 0.057059 0.181885 -vn 0.526927 -0.292341 -0.798050 -v 0.086049 0.057002 0.181895 -vn -0.510193 -0.148963 -0.847062 -v 0.086413 0.057017 0.181892 -vn 0.521588 -0.530346 -0.668341 -v 0.086006 0.056779 0.181999 -vn -0.519073 -0.324213 -0.790854 -v 0.086376 0.056826 0.181967 -vn -0.487397 -0.534222 -0.690689 -v 0.086359 0.056740 0.182031 -vn 0.497067 0.229604 -0.836784 -v 0.086106 0.057327 0.181910 -vn 0.512747 0.386672 -0.766535 -v 0.086132 0.057470 0.181979 -vn -0.512188 0.582017 -0.631601 -v 0.086503 0.057515 0.182012 -vn 0.493978 0.573267 -0.653721 -v 0.086160 0.057587 0.182081 -vn -0.493985 0.714090 -0.496039 -v 0.086521 0.057587 0.182081 -vn 0.512277 0.693252 -0.506926 -v 0.086177 0.057644 0.182157 -vn -0.513077 0.804800 -0.298411 -v 0.086548 0.057671 0.182204 -vn 0.500665 0.805360 -0.317380 -v 0.086214 0.057726 0.182359 -vn -0.499081 0.856316 -0.132821 -v 0.086575 0.057726 0.182359 -vn -0.510321 0.856311 0.079404 -v 0.086588 0.057737 0.182433 -vn 0.515644 0.842533 -0.155722 -v 0.086218 0.057730 0.182382 -vn 0.509921 0.858704 0.051065 -v 0.086260 0.057720 0.182625 -vn -0.525893 0.763874 0.374077 -v 0.086631 0.057705 0.182677 -vn 0.509084 0.824862 0.245838 -v 0.086268 0.057708 0.182669 -vn -0.521275 0.606951 0.599903 -v 0.086674 0.057579 0.182887 -vn 0.517953 0.748688 0.413753 -v 0.086304 0.057612 0.182848 -vn -0.498243 0.479023 0.722697 -v 0.086684 0.057537 0.182928 -vn 0.498502 0.627670 0.597935 -v 0.086322 0.057537 0.182928 -vn 0.514824 0.484736 0.707098 -v 0.086344 0.057431 0.183003 -vn -0.511878 0.279125 0.812447 -v 0.086714 0.057385 0.183027 -vn 0.495675 0.300069 0.815025 -v 0.086377 0.057259 0.183067 -vn -0.494833 0.097269 0.863527 -v 0.086738 0.057259 0.183067 -vn 0.512450 0.114791 0.851010 -v 0.086388 0.057194 0.183077 -vn -0.514110 -0.118134 0.849550 -v 0.086759 0.057143 0.183080 -vn 0.521008 -0.173279 0.835778 -v 0.086430 0.056953 0.183050 -vn 0.499998 -0.619259 0.605409 -v 0.086485 0.056690 0.182878 -vn -0.503581 -0.742246 0.442127 -v 0.086846 0.056690 0.182878 -vn -0.510895 -0.632163 0.582543 -v 0.086842 0.056706 0.182896 -vn 0.512228 -0.445808 0.734083 -v 0.086471 0.056743 0.182931 -vn -0.507841 -0.467647 0.723467 -v 0.086799 0.056908 0.183034 -vn -0.507738 -0.295995 0.809067 -v 0.086792 0.056949 0.183049 -vn -0.521040 -0.816646 0.248208 -v 0.086886 0.056576 0.182687 -vn 0.515965 -0.722074 0.460857 -v 0.086516 0.056594 0.182732 -vn -0.497633 -0.863897 0.077740 -v 0.086900 0.056551 0.182601 -vn 0.497364 -0.825777 0.265937 -v 0.086539 0.056551 0.182601 -vn 0.515364 -0.852660 0.085855 -v 0.086556 0.056539 0.182500 -vn -0.509496 -0.848465 -0.143250 -v 0.086925 0.056539 0.182452 -vn 0.498820 -0.857503 -0.125966 -v 0.086593 0.056569 0.182291 -vn -0.493225 -0.808724 -0.320462 -v 0.086955 0.056569 0.182291 -vn 0.511533 -0.805963 -0.297923 -v 0.086600 0.056582 0.182256 -vn -0.513174 -0.692558 -0.506968 -v 0.086970 0.056601 0.182212 -vn 0.506905 -0.707718 -0.492121 -v 0.086642 0.056717 0.182053 -vn -0.521578 -0.478242 -0.706570 -v 0.087011 0.056750 0.182023 -vn 0.510073 -0.586060 -0.629571 -v 0.086647 0.056740 0.182031 -vn 0.513624 -0.434155 -0.740068 -v 0.086683 0.056918 0.181921 -vn -0.512303 -0.221872 -0.829649 -v 0.087053 0.056962 0.181906 -vn 0.486209 -0.233246 -0.842139 -v 0.086702 0.057017 0.181892 -vn -0.496823 -0.039732 -0.866942 -v 0.087063 0.057017 0.181892 -vn 0.508593 -0.057583 -0.859079 -v 0.086728 0.057164 0.181880 -vn -0.515047 0.171046 -0.839922 -v 0.087097 0.057208 0.181884 -vn 0.497469 0.165002 -0.851645 -v 0.086756 0.057327 0.181910 -vn -0.501396 0.864943 -0.021796 -v 0.087225 0.057726 0.182359 -vn -0.515047 0.836827 -0.185598 -v 0.087223 0.057722 0.182341 -vn 0.509154 0.764359 -0.395623 -v 0.086855 0.057711 0.182301 -vn -0.510605 0.771801 -0.378953 -v 0.087181 0.057620 0.182121 -vn 0.524078 0.573744 -0.629413 -v 0.086811 0.057592 0.182087 -vn -0.506971 0.663855 -0.549797 -v 0.087171 0.057587 0.182081 -vn 0.520858 0.334238 -0.785489 -v 0.086768 0.057396 0.181938 -vn -0.516268 0.528298 -0.674068 -v 0.087136 0.057434 0.181958 -vn -0.498070 0.345697 -0.795248 -v 0.087117 0.057327 0.181910 -vn 0.504100 0.838487 -0.206936 -v 0.086864 0.057726 0.182359 -vn 0.513504 0.857567 -0.029882 -v 0.086895 0.057735 0.182540 -vn -0.512707 0.836171 0.194808 -v 0.087263 0.057730 0.182582 -vn 0.494300 0.848980 0.186818 -v 0.086918 0.057708 0.182669 -vn -0.494644 0.782830 0.377497 -v 0.087280 0.057708 0.182669 -vn 0.512195 0.778341 0.363100 -v 0.086939 0.057660 0.182776 -vn -0.512439 0.656330 0.553748 -v 0.087308 0.057638 0.182812 -vn 0.498851 0.668580 0.551496 -v 0.086972 0.057537 0.182928 -vn -0.495849 0.540374 0.679802 -v 0.087334 0.057537 0.182928 -vn -0.511053 0.351805 0.784256 -v 0.087348 0.057470 0.182980 -vn 0.517021 0.537405 0.666246 -v 0.086980 0.057502 0.182957 -vn 0.506899 0.363877 0.781439 -v 0.087023 0.057281 0.183063 -vn -0.509109 0.155986 0.846449 -v 0.087388 0.057259 0.183067 -vn 0.508902 0.192201 0.839093 -v 0.087027 0.057260 0.183067 -vn -0.506608 -0.022318 0.861888 -v 0.087391 0.057241 0.183071 -vn 0.511083 -0.011343 0.859457 -v 0.087067 0.057034 0.183070 -vn -0.517214 -0.227248 0.825135 -v 0.087434 0.056997 0.183063 -vn -0.498701 -0.393924 0.772089 -v 0.087442 0.056949 0.183049 -vn 0.495151 -0.227175 0.838580 -v 0.087081 0.056949 0.183049 -vn 0.512333 -0.383275 0.768515 -v 0.087106 0.056812 0.182983 -vn -0.512213 -0.569094 0.643249 -v 0.087474 0.056780 0.182961 -vn 0.494746 -0.569282 0.656616 -v 0.087135 0.056690 0.182878 -vn -0.494630 -0.703905 0.509763 -v 0.087496 0.056690 0.182878 -vn 0.512925 -0.690902 0.509472 -v 0.087151 0.056636 0.182807 -vn -0.513611 -0.798023 0.315220 -v 0.087519 0.056616 0.182775 -vn 0.501464 -0.802878 0.322367 -v 0.087189 0.056551 0.182601 -vn -0.505560 -0.850738 0.143716 -v 0.087550 0.056551 0.182601 -vn -0.509020 -0.858971 -0.055390 -v 0.087559 0.056542 0.182548 -vn 0.515152 -0.842194 0.159143 -v 0.087192 0.056547 0.182583 -vn 0.510555 -0.858747 -0.043446 -v 0.087234 0.056555 0.182339 -vn -0.523665 -0.780198 -0.342151 -v 0.087602 0.056565 0.182304 -vn 0.506770 -0.827100 -0.243084 -v 0.087243 0.056569 0.182291 -vn -0.520323 -0.622635 -0.584457 -v 0.087646 0.056683 0.182089 -vn 0.514885 -0.751161 -0.413098 -v 0.087278 0.056661 0.182116 -vn -0.497341 -0.492268 -0.714370 -v 0.087659 0.056740 0.182031 -vn 0.498138 -0.630706 -0.595036 -v 0.087297 0.056740 0.182031 -vn 0.515189 -0.487307 -0.705062 -v 0.087318 0.056841 0.181959 -vn -0.508984 -0.293003 -0.809373 -v 0.087685 0.056871 0.181942 -vn 0.496966 -0.304615 -0.812548 -v 0.087352 0.057017 0.181892 -vn -0.489703 -0.122184 -0.863286 -v 0.087713 0.057017 0.181892 -vn 0.513171 -0.119709 -0.849897 -v 0.087362 0.057077 0.181883 -vn -0.513738 0.099721 -0.852132 -v 0.087730 0.057111 0.181880 -vn 0.523269 0.164952 -0.836051 -v 0.087404 0.057319 0.181907 -vn 0.496876 0.617859 -0.609397 -v 0.087460 0.057587 0.182081 -vn -0.500639 0.734890 -0.457490 -v 0.087821 0.057587 0.182081 -vn -0.512738 0.614204 -0.599877 -v 0.087813 0.057554 0.182047 -vn 0.513100 0.439233 -0.737430 -v 0.087446 0.057530 0.182025 -vn -0.506600 0.447549 -0.736924 -v 0.087771 0.057349 0.181918 -vn -0.511941 0.284365 -0.810588 -v 0.087767 0.057327 0.181910 -vn -0.519257 0.812749 -0.264218 -v 0.087857 0.057693 0.182251 -vn 0.513297 0.722326 -0.463434 -v 0.087490 0.057681 0.182222 -vn -0.499226 0.861578 -0.091964 -v 0.087875 0.057726 0.182359 -vn 0.498753 0.824059 -0.268649 -v 0.087514 0.057726 0.182359 -vn -0.513866 0.848482 0.126571 -v 0.087896 0.057738 0.182485 -vn 0.519545 0.849782 -0.089130 -v 0.087530 0.057738 0.182454 -vn -0.502650 0.808414 0.306285 -v 0.087930 0.057708 0.182669 -vn 0.502676 0.856436 0.117617 -v 0.087568 0.057708 0.182669 -vn 0.512338 0.807219 0.293100 -v 0.087574 0.057697 0.182698 -vn -0.511704 0.706831 0.488415 -v 0.087941 0.057685 0.182726 -vn 0.507628 0.711772 0.485484 -v 0.087617 0.057564 0.182903 -vn -0.523580 0.502717 0.687852 -v 0.087982 0.057543 0.182922 -vn 0.510465 0.586639 0.628713 -v 0.087622 0.057537 0.182928 -vn 0.514645 0.439218 0.736361 -v 0.087657 0.057363 0.183036 -vn -0.514128 0.245575 0.821806 -v 0.088023 0.057336 0.183046 -vn 0.484323 0.236498 0.842318 -v 0.087677 0.057259 0.183067 -vn -0.495787 0.056168 0.866626 -v 0.088038 0.057260 0.183067 -vn 0.508541 0.061492 0.858839 -v 0.087702 0.057119 0.183079 -vn -0.512203 -0.158587 0.844096 -v 0.088068 0.057091 0.183078 -vn 0.497588 -0.159362 0.852649 -v 0.087731 0.056949 0.183049 -vn -0.499726 -0.865422 0.036313 -v 0.088200 0.056551 0.182601 -vn -0.516765 -0.830438 0.208149 -v 0.088194 0.056560 0.182639 -vn 0.510224 -0.760197 0.402208 -v 0.087829 0.056567 0.182663 -vn -0.508937 -0.762043 0.400341 -v 0.088151 0.056671 0.182856 -vn 0.526072 -0.567277 0.633597 -v 0.087785 0.056689 0.182877 -vn -0.511048 -0.655342 0.556199 -v 0.088146 0.056690 0.182878 -vn 0.519968 -0.331150 0.787384 -v 0.087742 0.056886 0.183024 -vn -0.514445 -0.512777 0.687317 -v 0.088107 0.056862 0.183012 -vn -0.492372 -0.323952 0.807852 -v 0.088092 0.056949 0.183049 -vn 0.502545 -0.838671 0.209952 -v 0.087839 0.056551 0.182601 -vn 0.513124 -0.857652 0.033709 -v 0.087869 0.056541 0.182425 -vn -0.512930 -0.839839 -0.177692 -v 0.088234 0.056544 0.182400 -vn 0.494804 -0.849743 -0.181951 -v 0.087893 0.056569 0.182291 -vn -0.494924 -0.789901 -0.362087 -v 0.088255 0.056569 0.182291 -vn 0.512948 -0.779356 -0.359845 -v 0.087913 0.056614 0.182188 -vn -0.513179 -0.667615 -0.539387 -v 0.088279 0.056627 0.182167 -vn 0.499598 -0.671834 -0.546846 -v 0.087947 0.056740 0.182031 -vn -0.502911 -0.546876 -0.669334 -v 0.088309 0.056740 0.182031 -vn -0.510295 -0.370121 -0.776279 -v 0.088319 0.056789 0.181992 -vn 0.516901 -0.540018 -0.664224 -v 0.087954 0.056771 0.182005 -vn 0.508790 -0.370348 -0.777158 -v 0.087997 0.056991 0.181898 -vn -0.526005 -0.079287 -0.846777 -v 0.088362 0.057013 0.181893 -vn 0.511127 -0.192016 -0.837782 -v 0.088002 0.057017 0.181892 -vn -0.519775 0.202742 -0.829898 -v 0.088406 0.057259 0.181892 -vn 0.513706 0.002570 -0.857962 -v 0.088041 0.057238 0.181888 -vn -0.497621 0.380399 -0.779532 -v 0.088417 0.057327 0.181910 -vn 0.493213 0.224751 -0.840374 -v 0.088056 0.057327 0.181910 -vn 0.512404 0.379904 -0.770139 -v 0.088080 0.057461 0.181973 -vn -0.508919 0.560232 -0.653561 -v 0.088445 0.057478 0.181985 -vn 0.495816 0.564939 -0.659553 -v 0.088110 0.057587 0.182081 -vn -0.486330 0.691348 -0.534342 -v 0.088471 0.057587 0.182081 -vn 0.514906 0.690696 -0.507750 -v 0.088125 0.057638 0.182147 -vn -0.514980 0.790944 -0.330460 -v 0.088490 0.057649 0.182165 -vn 0.524946 0.815233 -0.244596 -v 0.088166 0.057729 0.182371 -vn 0.503444 0.830082 0.239806 -v 0.088218 0.057708 0.182669 -vn -0.501880 0.759440 0.413965 -v 0.088580 0.057708 0.182669 -vn -0.513383 0.823559 0.241224 -v 0.088573 0.057718 0.182633 -vn 0.511494 0.858535 0.035938 -v 0.088208 0.057723 0.182614 -vn -0.507614 0.861009 0.031481 -v 0.088530 0.057732 0.182390 -vn -0.512007 0.844752 -0.155702 -v 0.088525 0.057726 0.182359 -vn -0.518611 0.631930 0.575940 -v 0.088617 0.057608 0.182854 -vn 0.512412 0.753483 0.411942 -v 0.088253 0.057619 0.182839 -vn -0.498223 0.504064 0.705474 -v 0.088634 0.057537 0.182928 -vn 0.498666 0.632853 0.592309 -v 0.088272 0.057537 0.182928 -vn -0.511944 0.309234 0.801428 -v 0.088656 0.057426 0.183006 -vn 0.518024 0.489106 0.701732 -v 0.088292 0.057441 0.182998 -vn -0.498819 0.133412 0.856376 -v 0.088688 0.057259 0.183067 -vn 0.494159 -0.616086 0.613388 -v 0.088435 0.056690 0.182878 -vn -0.514827 -0.595591 0.616624 -v 0.088784 0.056739 0.182928 -vn 0.514328 -0.432638 0.740467 -v 0.088420 0.056751 0.182938 -vn -0.526423 -0.356684 0.771787 -v 0.088742 0.056949 0.183049 -vn 0.526088 -0.156390 0.835927 -v 0.088378 0.056963 0.183053 -vn -0.513079 -0.081264 0.854486 -v 0.088701 0.057189 0.183078 -vn 0.514267 0.124387 0.848562 -v 0.088336 0.057205 0.183076 -vn 0.499728 0.310579 0.808587 -v 0.088327 0.057259 0.183067 -vn 0.791724 0.526847 0.309202 -v 0.088903 0.057617 0.182842 -vn 0.395071 0.881650 0.258094 -v 0.088903 0.057708 0.182669 -vn 0.674504 0.688032 0.267688 -v 0.088887 0.057665 0.182767 -vn 0.496129 0.850208 0.176078 -v 0.088868 0.057708 0.182669 -vn 0.613827 0.788434 -0.039855 -v 0.088843 0.057736 0.182529 -vn 0.394830 0.896996 -0.198765 -v 0.088903 0.057726 0.182359 -vn 0.500935 0.838899 -0.212866 -v 0.088814 0.057726 0.182359 -vn 0.386859 0.291761 -0.874766 -v 0.088903 0.057327 0.181910 -vn 0.531516 0.328320 -0.780831 -v 0.088716 0.057386 0.181933 -vn 0.367742 0.701747 -0.610178 -v 0.088903 0.057587 0.182081 -vn 0.537319 0.563673 -0.627344 -v 0.088759 0.057584 0.182078 -vn 0.574194 0.699126 -0.426055 -v 0.088803 0.057708 0.182291 -vn 0.387685 -0.188429 -0.902327 -v 0.088903 0.057017 0.181892 -vn 0.527509 -0.058503 -0.847533 -v 0.088676 0.057153 0.181880 -vn 0.498609 0.152378 -0.853329 -v 0.088706 0.057327 0.181910 -vn 0.517454 -0.716125 -0.468408 -v 0.088591 0.056709 0.182060 -vn 0.508556 -0.590045 -0.627071 -v 0.088597 0.056740 0.182031 -vn 0.376764 -0.620980 -0.687337 -v 0.088903 0.056740 0.182031 -vn 0.523165 -0.439533 -0.730143 -v 0.088631 0.056908 0.181926 -vn 0.496560 -0.250811 -0.830977 -v 0.088652 0.057017 0.181892 -vn 0.520149 -0.802771 -0.291553 -v 0.088548 0.056578 0.182267 -vn 0.373846 -0.838451 -0.396534 -v 0.088903 0.056569 0.182291 -vn 0.502429 -0.856995 -0.114567 -v 0.088543 0.056569 0.182291 -vn 0.382845 -0.900590 -0.205832 -v 0.088903 0.056566 0.182299 -vn 0.518308 -0.850239 0.091924 -v 0.088504 0.056539 0.182511 -vn -0.506624 -0.855909 -0.103688 -v 0.088867 0.056539 0.182497 -vn 0.497899 -0.822972 0.273521 -v 0.088489 0.056551 0.182601 -vn -0.512962 -0.852125 0.103695 -v 0.088850 0.056551 0.182601 -vn 0.511252 -0.722026 0.466154 -v 0.088464 0.056599 0.182742 -vn -0.518551 -0.807284 0.281775 -v 0.088828 0.056593 0.182729 -vn -0.498246 -0.726666 0.472977 -v 0.088796 0.056690 0.182878 -vn 0.004294 0.522324 -0.852736 -v 0.085338 0.057612 0.181774 -vn -0.007789 0.699218 -0.714866 -v 0.085353 0.057705 0.181846 -vn 0.861986 0.235924 -0.448687 -v 0.085425 0.057622 0.181939 -vn 0.009737 0.144361 -0.989477 -v 0.085299 0.057300 0.181645 -vn -0.007780 0.357852 -0.933746 -v 0.085312 0.057408 0.181673 -vn 0.864807 0.042880 -0.500269 -v 0.085384 0.057368 0.181792 -vn 0.006385 -0.263738 -0.964573 -v 0.085255 0.056952 0.181650 -vn -0.005441 -0.040251 -0.999175 -v 0.085270 0.057067 0.181633 -vn 0.862636 -0.160598 -0.479654 -v 0.085342 0.057077 0.181757 -vn 0.004926 -0.625153 -0.780487 -v 0.085212 0.056636 0.181794 -vn -0.008902 -0.438217 -0.898825 -v 0.085225 0.056730 0.181734 -vn 0.862480 -0.341787 -0.373243 -v 0.085298 0.056790 0.181844 -vn 0.008221 -0.882555 -0.470137 -v 0.085172 0.056408 0.182044 -vn -0.003731 -0.756931 -0.653484 -v 0.085186 0.056472 0.181952 -vn 0.862733 -0.460393 -0.209117 -v 0.085258 0.056570 0.182030 -vn 0.004355 -0.997073 -0.076332 -v 0.085127 0.056295 0.182377 -vn -0.006838 -0.954726 -0.297407 -v 0.085142 0.056316 0.182266 -vn 0.862418 -0.506178 -0.004283 -v 0.085214 0.056437 0.182297 -vn 0.009135 -0.946428 0.322786 -v 0.085087 0.056322 0.182715 -vn -0.008679 -0.994168 0.107496 -v 0.085099 0.056299 0.182611 -vn 0.863329 -0.467490 0.190043 -v 0.085171 0.056422 0.182592 -vn 0.006308 -0.739068 0.673601 -v 0.085044 0.056483 0.183021 -vn -0.004394 -0.871170 0.490961 -v 0.085059 0.056418 0.182931 -vn 0.861944 -0.353647 0.363299 -v 0.085131 0.056524 0.182864 -vn 0.003643 -0.409747 0.912192 -v 0.085001 0.056755 0.183238 -vn -0.007999 -0.600626 0.799490 -v 0.085014 0.056663 0.183184 -vn 0.861718 -0.174922 0.476282 -v 0.085086 0.056733 0.183080 -vn 0.008079 -0.016870 0.999825 -v 0.084961 0.057081 0.183328 -vn -0.003796 -0.236460 0.971634 -v 0.084974 0.056975 0.183314 -vn 0.862705 0.024473 0.505115 -v 0.085046 0.056999 0.183191 -vn 0.004279 0.386095 0.922449 -v 0.084917 0.057428 0.183279 -vn -0.005744 0.169641 0.985489 -v 0.084930 0.057324 0.183309 -vn 0.863880 0.226491 0.449904 -v 0.085002 0.057297 0.183187 -vn 0.007706 0.718910 0.695061 -v 0.084876 0.057719 0.183101 -vn -0.008702 0.549173 0.835663 -v 0.084887 0.057641 0.183165 -vn 0.862594 0.383503 0.329936 -v 0.084959 0.057567 0.183064 -vn 0.006176 0.936025 0.351880 -v 0.084834 0.057917 0.182820 -vn -0.003346 0.834055 0.551672 -v 0.084847 0.057869 0.182914 -vn 0.861597 0.485640 0.147664 -v 0.084919 0.057762 0.182850 -vn 0.002797 0.998693 -0.051026 -v 0.084789 0.057988 0.182477 -vn -0.006970 0.985296 0.170715 -v 0.084802 0.057982 0.182580 -vn 0.861203 0.504306 -0.063287 -v 0.084874 0.057858 0.182565 -vn 0.007849 0.897832 -0.440267 -v 0.084750 0.057921 0.182147 -vn -0.004270 0.972566 -0.232589 -v 0.084762 0.057954 0.182241 -vn 0.862946 0.437640 -0.252578 -v 0.084834 0.057834 0.182276 -vn 0.004198 0.645691 -0.763587 -v 0.084706 0.057720 0.181860 -vn -0.004729 0.800341 -0.599527 -v 0.084719 0.057791 0.181935 -vn 0.862984 0.298601 -0.407549 -v 0.084791 0.057695 0.182015 -vn 0.005611 0.290645 -0.956815 -v 0.084664 0.057427 0.181680 -vn -0.007969 0.493110 -0.869930 -v 0.084675 0.057517 0.181718 -vn 0.861836 0.117131 -0.493477 -v 0.084747 0.057461 0.181830 -vn 0.006037 -0.112322 -0.993654 -v 0.084623 0.057090 0.181631 -vn -0.002447 0.110588 -0.993863 -v 0.084635 0.057190 0.181631 -vn 0.862198 -0.093851 -0.497803 -v 0.084708 0.057182 0.181756 -vn 0.002344 -0.500533 -0.865714 -v 0.084578 0.056751 0.181723 -vn -0.005992 -0.296460 -0.955027 -v 0.084591 0.056841 0.181683 -vn 0.861403 -0.286641 -0.419311 -v 0.084663 0.056885 0.181800 -vn 0.007562 -0.800997 -0.598620 -v 0.084539 0.056488 0.181933 -vn -0.005101 -0.650579 -0.759422 -v 0.084550 0.056552 0.181864 -vn 0.863516 -0.424095 -0.272917 -v 0.084622 0.056638 0.181955 -vn 0.004095 -0.973744 -0.227608 -v 0.084495 0.056323 0.182240 -vn -0.003639 -0.898176 -0.439621 -v 0.084508 0.056356 0.182148 -vn 0.862208 -0.500009 -0.081172 -v 0.084580 0.056471 0.182197 -vn 0.003718 -0.984102 0.177567 -v 0.084452 0.056295 0.182585 -vn -0.007011 -0.999086 -0.042169 -v 0.084463 0.056289 0.182493 -vn 0.861176 -0.492965 0.123939 -v 0.084535 0.056414 0.182491 -vn 0.005825 -0.833810 0.552021 -v 0.084412 0.056403 0.182906 -vn -0.001849 -0.934947 0.354783 -v 0.084424 0.056361 0.182823 -vn 0.861764 -0.400439 0.311467 -v 0.084496 0.056475 0.182772 -vn 0.002085 -0.542503 0.840051 -v 0.084367 0.056639 0.183167 -vn -0.004902 -0.715386 0.698712 -v 0.084379 0.056566 0.183108 -vn 0.861426 -0.241212 0.446948 -v 0.084451 0.056650 0.183016 -vn 0.007284 -0.167577 0.985832 -v 0.084327 0.056947 0.183308 -vn -0.006096 -0.378947 0.925398 -v 0.084337 0.056862 0.183283 -vn 0.864126 -0.047994 0.500982 -v 0.084410 0.056903 0.183165 -vn 0.003949 0.240183 0.970720 -v 0.084284 0.057293 0.183315 -vn -0.002640 0.017735 0.999839 -v 0.084296 0.057202 0.183327 -vn 0.861972 0.155634 0.482476 -v 0.084368 0.057193 0.183203 -vn 0.002300 0.606585 0.795016 -v 0.084241 0.057615 0.183183 -vn -0.005993 0.417772 0.908532 -v 0.084251 0.057540 0.183229 -vn 0.861664 0.338860 0.377769 -v 0.084324 0.057481 0.183119 -vn 0.005602 0.870962 0.491318 -v 0.084201 0.057852 0.182942 -vn -0.001690 0.742081 0.670308 -v 0.084212 0.057800 0.183013 -vn 0.862009 0.459318 0.214398 -v 0.084284 0.057703 0.182935 -vn 0.001974 0.994943 0.100425 -v 0.084156 0.057978 0.182614 -vn -0.003793 0.947741 0.319018 -v 0.084168 0.057959 0.182701 -vn 0.861882 0.507015 0.009775 -v 0.084240 0.057838 0.182669 -vn 0.006322 0.953762 -0.300497 -v 0.084116 0.057963 0.182274 -vn -0.006550 0.996343 -0.085192 -v 0.084125 0.057979 0.182355 -vn 0.862394 0.470961 -0.185666 -v 0.084197 0.057856 0.182374 -vn 0.003716 0.755367 -0.655292 -v 0.084074 0.057814 0.181964 -vn -0.001614 0.881918 -0.471400 -v 0.084085 0.057863 0.182035 -vn 0.861110 0.358379 -0.360630 -v 0.084157 0.057756 0.182101 -vn 0.001125 0.431377 -0.902171 -v 0.084029 0.057549 0.181735 -vn -0.004949 0.618496 -0.785772 -v 0.084040 0.057621 0.181780 -vn 0.860892 0.180357 -0.475749 -v 0.084112 0.057550 0.181883 -vn 0.005391 0.041073 -0.999142 -v 0.083990 0.057228 0.181634 -vn -0.001862 0.258232 -0.966081 -v 0.084000 0.057309 0.181647 -vn 0.861959 -0.019395 -0.506606 -v 0.084072 0.057284 0.181769 -vn 0.001781 -0.363482 -0.931599 -v 0.083946 0.056879 0.181670 -vn -0.002766 -0.147417 -0.989071 -v 0.083956 0.056960 0.181649 -vn 0.863106 -0.222293 -0.453468 -v 0.084028 0.056986 0.181771 -vn 0.004415 -0.702394 -0.711774 -v 0.083904 0.056581 0.181838 -vn -0.005903 -0.530569 -0.847621 -v 0.083913 0.056642 0.181790 -vn 0.861658 -0.381349 -0.334841 -v 0.083985 0.056715 0.181891 -vn 0.003475 -0.927091 -0.374821 -v 0.083863 0.056373 0.182110 -vn -0.000574 -0.821729 -0.569879 -v 0.083873 0.056412 0.182039 -vn 0.860721 -0.485554 -0.152961 -v 0.083945 0.056519 0.182104 -vn 0.000326 -0.999636 0.026960 -v 0.083818 0.056289 0.182450 -vn -0.003863 -0.981232 -0.192792 -v 0.083828 0.056295 0.182371 -vn 0.860354 -0.506367 0.058172 -v 0.083900 0.056419 0.182387 -vn 0.005064 -0.908225 0.418452 -v 0.083779 0.056344 0.182783 -vn -0.002386 -0.977518 0.210837 -v 0.083788 0.056320 0.182711 -vn 0.862171 -0.441258 0.248904 -v 0.083860 0.056441 0.182677 -vn 0.001536 -0.664304 0.747461 -v 0.083735 0.056533 0.183076 -vn -0.001626 -0.813487 0.581581 -v 0.083745 0.056481 0.183018 -vn 0.861935 -0.304273 0.405569 -v 0.083817 0.056578 0.182939 -vn 0.002390 -0.313289 0.949655 -v 0.083692 0.056821 0.183268 -vn -0.004887 -0.512149 0.858883 -v 0.083701 0.056754 0.183237 -vn 0.860786 -0.122248 0.494068 -v 0.083773 0.056810 0.183126 -vn 0.003237 0.087731 0.996139 -v 0.083652 0.057155 0.183329 -vn 0.000176 -0.132415 0.991194 -v 0.083661 0.057079 0.183328 -vn 0.861195 0.089080 0.500408 -v 0.083734 0.057088 0.183203 -vn -0.000199 0.479331 0.877634 -v 0.083607 0.057497 0.183250 -vn -0.002756 0.275142 0.961400 -v 0.083617 0.057428 0.183279 -vn 0.860516 0.283136 0.423493 -v 0.083689 0.057385 0.183161 -vn 0.004786 0.786359 0.617751 -v 0.083568 0.057769 0.183050 -vn -0.003072 0.633653 0.773611 -v 0.083576 0.057720 0.183100 -vn 0.863326 0.421628 0.277304 -v 0.083648 0.057634 0.183009 -vn 0.001310 0.967786 0.251770 -v 0.083524 0.057944 0.182750 -vn -0.000580 0.888263 0.459334 -v 0.083534 0.057918 0.182818 -vn 0.861175 0.500826 0.086894 -v 0.083606 0.057803 0.182768 -vn 0.000753 0.988093 -0.153854 -v 0.083481 0.057985 0.182405 -vn -0.003827 0.997934 0.064137 -v 0.083489 0.057988 0.182474 -vn 0.860136 0.495815 -0.119725 -v 0.083561 0.057863 0.182475 -vn 0.002996 0.847239 -0.531203 -v 0.083441 0.057889 0.182081 -vn 0.000468 0.942525 -0.334135 -v 0.083450 0.057919 0.182143 -vn 0.860697 0.404968 -0.308547 -v 0.083522 0.057804 0.182193 -vn -0.000517 0.563032 -0.826435 -v 0.083396 0.057664 0.181811 -vn -0.001641 0.730681 -0.682717 -v 0.083405 0.057717 0.181857 -vn 0.860516 0.246515 -0.445806 -v 0.083477 0.057632 0.181948 -vn 0.004376 0.191188 -0.981544 -v 0.083356 0.057360 0.181659 -vn -0.003919 0.399030 -0.916929 -v 0.083363 0.057422 0.181678 -vn 0.863040 0.052900 -0.502358 -v 0.083435 0.057380 0.181796 -vn 0.001053 -0.215814 -0.976434 -v 0.083314 0.057016 0.181639 -vn 0.000425 0.004004 -0.999992 -v 0.083322 0.057083 0.181631 -vn 0.860906 -0.151160 -0.485790 -v 0.083394 0.057091 0.181756 -vn -0.000578 -0.587011 -0.809579 -v 0.083269 0.056688 0.181759 -vn -0.002724 -0.397713 -0.917506 -v 0.083277 0.056744 0.181727 -vn 0.860495 -0.336430 -0.382575 -v 0.083349 0.056802 0.181837 -vn 0.002693 -0.858515 -0.512782 -v 0.083230 0.056443 0.181991 -vn 0.000551 -0.727235 -0.686388 -v 0.083238 0.056482 0.181940 -vn 0.860880 -0.458957 -0.219647 -v 0.083310 0.056578 0.182019 -vn -0.000721 -0.992135 -0.125171 -v 0.083186 0.056305 0.182313 -vn -0.000574 -0.940521 -0.339734 -v 0.083194 0.056320 0.182250 -vn 0.860951 -0.508466 -0.015023 -v 0.083266 0.056440 0.182284 -vn 0.002991 -0.960742 0.277427 -v 0.083144 0.056307 0.182655 -vn -0.003756 -0.997965 0.063659 -v 0.083151 0.056296 0.182596 -vn 0.861042 -0.474926 0.181802 -v 0.083223 0.056420 0.182579 -vn 0.000791 -0.771667 0.636026 -v 0.083103 0.056444 0.182969 -vn 0.001425 -0.891841 0.452347 -v 0.083111 0.056410 0.182917 -vn 0.859844 -0.363353 0.358668 -v 0.083183 0.056517 0.182853 -vn -0.001559 -0.453450 0.891280 -v 0.083058 0.056700 0.183208 -vn -0.001623 -0.635519 0.772083 -v 0.083066 0.056650 0.183175 -vn 0.859671 -0.185801 0.475862 -v 0.083138 0.056722 0.183073 -vn 0.002448 -0.065905 0.997823 -v 0.083019 0.057017 0.183321 -vn 0.000276 -0.279229 0.960225 -v 0.083026 0.056960 0.183311 -vn 0.860762 0.014680 0.508796 -v 0.083098 0.056987 0.183189 -vn -0.001028 0.339855 0.940477 -v 0.082975 0.057366 0.183298 -vn 0.000534 0.125886 0.992045 -v 0.082982 0.057309 0.183312 -vn 0.861898 0.218626 0.457532 -v 0.083054 0.057284 0.183190 -vn 0.000910 0.684940 0.728599 -v 0.082932 0.057673 0.183141 -vn -0.002650 0.512378 0.858756 -v 0.082939 0.057629 0.183174 -vn 0.860332 0.379826 0.339944 -v 0.083011 0.057557 0.183072 -vn 0.000498 0.917277 0.398249 -v 0.082892 0.057889 0.182878 -vn 0.002259 0.809335 0.587344 -v 0.082899 0.057861 0.182927 -vn 0.860441 0.485468 0.154797 -v 0.082971 0.057755 0.182861 -vn -0.002394 0.999995 -0.002085 -v 0.082847 0.057986 0.182541 -vn -0.000473 0.976835 0.213994 -v 0.082854 0.057980 0.182596 -vn 0.859566 0.508321 -0.052505 -v 0.082926 0.057857 0.182579 -vn 0.002113 0.918348 -0.395769 -v 0.082808 0.057943 0.182206 -vn -0.000157 0.981842 -0.189699 -v 0.082814 0.057958 0.182256 -vn 0.860913 0.445414 -0.245836 -v 0.082886 0.057838 0.182289 -vn -0.001352 0.683141 -0.730286 -v 0.082764 0.057766 0.181906 -vn 0.001583 0.825817 -0.563936 -v 0.082771 0.057801 0.181947 -vn 0.860416 0.310132 -0.404355 -v 0.082843 0.057704 0.182025 -vn -0.000795 0.336548 -0.941666 -v 0.082721 0.057485 0.181703 -vn -0.001581 0.530382 -0.847758 -v 0.082727 0.057530 0.181725 -vn 0.859324 0.127295 -0.495337 -v 0.082799 0.057472 0.181836 -vn 0.000273 -0.062261 -0.998060 -v 0.082681 0.057154 0.181630 -vn 0.002784 0.153639 -0.988123 -v 0.082687 0.057205 0.181632 -vn 0.859678 -0.084782 -0.503751 -v 0.082759 0.057195 0.181757 -vn -0.002910 -0.457094 -0.889414 -v 0.082636 0.056810 0.181696 -vn 0.000645 -0.254428 -0.967092 -v 0.082643 0.056856 0.181678 -vn 0.859182 -0.280236 -0.428106 -v 0.082715 0.056898 0.181796 -vn 0.001889 -0.770874 -0.636985 -v 0.082596 0.056529 0.181887 -vn -0.000899 -0.617024 -0.786944 -v 0.082601 0.056563 0.181854 -vn 0.861831 -0.421260 -0.282466 -v 0.082674 0.056647 0.181946 -vn -0.001640 -0.960993 -0.276568 -v 0.082553 0.056344 0.182179 -vn 0.002551 -0.878310 -0.478085 -v 0.082559 0.056362 0.182134 -vn 0.859629 -0.502492 -0.092414 -v 0.082632 0.056476 0.182185 -vn -0.002323 -0.991607 0.129268 -v 0.082510 0.056290 0.182523 -vn -0.000475 -0.996356 -0.085293 -v 0.082515 0.056288 0.182477 -vn 0.858638 -0.499302 0.115920 -v 0.082587 0.056413 0.182478 -vn -0.000081 -0.860531 0.509398 -v 0.082470 0.056373 0.182850 -vn 0.002990 -0.949407 0.314034 -v 0.082476 0.056355 0.182809 -vn 0.859097 -0.409947 0.306425 -v 0.082548 0.056470 0.182760 -vn -0.003271 -0.583949 0.811784 -v 0.082425 0.056588 0.183127 -vn 0.001696 -0.745139 0.666907 -v 0.082431 0.056555 0.183097 -vn 0.859095 -0.252009 0.445473 -v 0.082503 0.056640 0.183006 -vn 0.001272 -0.215528 0.976497 -v 0.082384 0.056887 0.183292 -vn -0.001337 -0.418342 0.908288 -v 0.082389 0.056848 0.183278 -vn 0.860490 -0.059514 0.505979 -v 0.082461 0.056891 0.183161 -vn -0.001962 0.190272 0.981729 -v 0.082343 0.057229 0.183325 -vn 0.003573 -0.025115 0.999678 -v 0.082348 0.057186 0.183328 -vn 0.858797 0.148048 0.490458 -v 0.082420 0.057179 0.183203 -vn -0.003529 0.566438 0.824097 -v 0.082298 0.057562 0.183217 -vn 0.000706 0.378274 0.925693 -v 0.082303 0.057526 0.183236 -vn 0.858830 0.334697 0.387800 -v 0.082375 0.057469 0.183125 -vn -0.000351 0.845080 0.534639 -v 0.082259 0.057815 0.182994 -vn 0.002921 0.712471 0.701695 -v 0.082264 0.057790 0.183025 -vn 0.859163 0.459574 0.225014 -v 0.082336 0.057694 0.182945 -vn -0.003618 0.988564 0.150762 -v 0.082215 0.057965 0.182678 -vn 0.002804 0.933137 0.359511 -v 0.082220 0.057955 0.182716 -vn 0.859493 0.510757 0.019977 -v 0.082292 0.057835 0.182682 -vn -0.000649 0.967340 -0.253480 -v 0.082173 0.057976 0.182334 -vn -0.000453 0.999073 -0.043057 -v 0.082177 0.057981 0.182370 -vn 0.859161 0.479564 -0.178494 -v 0.082249 0.057857 0.182386 -vn -0.002272 0.787973 -0.615706 -v 0.082132 0.057851 0.182017 -vn 0.004419 0.901008 -0.433781 -v 0.082137 0.057871 0.182049 -vn 0.857973 0.368749 -0.357642 -v 0.082209 0.057763 0.182112 -vn -0.004438 0.475967 -0.879452 -v 0.082087 0.057604 0.181768 -vn 0.001778 0.651559 -0.758596 -v 0.082092 0.057633 0.181789 -vn 0.857919 0.191310 -0.476839 -v 0.082164 0.057561 0.181890 -vn -0.000637 0.091455 -0.995809 -v 0.082048 0.057290 0.181643 -vn 0.002644 0.299367 -0.954134 -v 0.082052 0.057324 0.181650 -vn 0.858950 -0.010301 -0.511956 -v 0.082124 0.057296 0.181772 -vn -0.003948 -0.315057 -0.949065 -v 0.082004 0.056942 0.181653 -vn 0.003824 -0.105006 -0.994464 -v 0.082008 0.056976 0.181645 -vn 0.860082 -0.215655 -0.462333 -v 0.082080 0.057000 0.181768 -vn -0.002488 -0.666268 -0.745708 -v 0.081961 0.056628 0.181800 -vn 0.000694 -0.494452 -0.869205 -v 0.081965 0.056654 0.181781 -vn 0.858905 -0.379449 -0.343948 -v 0.082037 0.056725 0.181884 -vn -0.002562 -0.906544 -0.422103 -v 0.081921 0.056403 0.182053 -vn 0.004995 -0.796988 -0.603974 -v 0.081925 0.056420 0.182026 -vn 0.857684 -0.488404 -0.160749 -v 0.081997 0.056525 0.182092 -vn -0.005112 -0.999708 -0.023620 -v 0.081876 0.056294 0.182386 -vn 0.002896 -0.972169 -0.234263 -v 0.081880 0.056297 0.182356 -vn 0.855852 -0.515307 0.044456 -v 0.081952 0.056421 0.182374 -vn -0.000873 -0.928142 0.372226 -v 0.081836 0.056324 0.182724 -vn 0.002161 -0.985565 0.169281 -v 0.081840 0.056316 0.182696 -vn 0.854627 -0.458985 0.242787 -v 0.081912 0.056437 0.182664 -vn -0.004239 -0.702107 0.712058 -v 0.081793 0.056489 0.183028 -vn 0.004726 -0.837262 0.546781 -v 0.081797 0.056471 0.183006 -vn 0.854431 -0.320900 0.408620 -v 0.081869 0.056569 0.182929 -vn -0.004011 -0.360484 0.932757 -v 0.081750 0.056764 0.183243 -vn 0.001809 -0.547685 0.836683 -v 0.081753 0.056740 0.183230 -vn 0.855347 -0.135717 0.499963 -v 0.081825 0.056799 0.183120 -vn -0.002808 0.036134 0.999343 -v 0.081710 0.057090 0.183328 -vn 0.005299 -0.173966 0.984738 -v 0.081713 0.057064 0.183326 -vn 0.857111 0.084052 0.508228 -v 0.081785 0.057075 0.183202 -vn -0.005587 0.433787 0.900998 -v 0.081665 0.057437 0.183275 -vn 0.003935 0.234374 0.972139 -v 0.081669 0.057413 0.183284 -vn 0.854132 0.276564 0.440421 -v 0.081741 0.057373 0.183166 -vn -0.001080 0.754333 0.656491 -v 0.081625 0.057726 0.183094 -vn 0.001463 0.600691 0.799480 -v 0.081627 0.057709 0.183110 -vn 0.853046 0.427060 0.299887 -v 0.081699 0.057625 0.183017 -vn -0.004630 0.953305 0.301973 -v 0.081583 0.057921 0.182811 -vn 0.005690 0.868394 0.495843 -v 0.081585 0.057912 0.182832 -vn 0.851927 0.513350 0.103405 -v 0.081658 0.057798 0.182781 -vn 0.001943 0.995813 -0.091389 -v 0.081538 0.057988 0.182467 -vn 0.002940 0.994405 0.105597 -v 0.081541 0.057988 0.182489 -vn 0.855187 0.507710 -0.104334 -v 0.081613 0.057863 0.182488 -vn 0.005457 0.880297 -0.474392 -v 0.081499 0.057917 0.182138 -vn 0.010924 0.951198 -0.308387 -v 0.081501 0.057925 0.182158 -vn 0.851101 0.426631 -0.305962 -v 0.081574 0.057809 0.182205 -vn 0.001769 0.613373 -0.789792 -v 0.081455 0.057713 0.181853 -vn 0.012267 0.747203 -0.664482 -v 0.081457 0.057728 0.181867 -vn 0.850949 0.264941 -0.453532 -v 0.081529 0.057641 0.181957 -vn 0.004127 0.249567 -0.968349 -v 0.081413 0.057419 0.181677 -vn 0.003808 0.431136 -0.902279 -v 0.081415 0.057436 0.181683 -vn 0.849037 0.078028 -0.522540 -v 0.081487 0.057392 0.181800 -vn 0.939270 0.213258 0.268874 -v 0.088903 0.057416 0.183109 -vn 0.961520 0.211757 0.175038 -v 0.088903 0.057537 0.182985 -vn 0.861544 0.400523 0.311967 -v 0.088856 0.057588 0.183049 -vn 0.572715 0.751182 -0.328213 -v 0.081598 0.057784 0.182240 -vn 0.566431 0.696682 -0.440216 -v 0.081592 0.057771 0.182205 -vn 0.571787 -0.289582 -0.767594 -v 0.081431 0.056979 0.181779 -vn 0.925655 -0.268246 -0.266846 -v 0.081401 0.056814 0.181831 -vn 0.874800 -0.253029 -0.413160 -v 0.081424 0.056955 0.181778 -vn 0.573869 -0.796289 -0.191304 -v 0.081312 0.056434 0.182253 -vn 0.573332 -0.811306 -0.114338 -v 0.081309 0.056430 0.182267 -vn 0.003646 -0.934464 -0.356038 -v 0.081246 0.056324 0.182235 -vn 0.574525 0.468702 0.670999 -v 0.081032 0.057542 0.183157 -vn 0.580609 0.517427 0.628619 -v 0.081025 0.057583 0.183133 -vn 0.000295 0.554132 0.832429 -v 0.080991 0.057616 0.183182 -vn 0.564060 0.805255 -0.182761 -v 0.080891 0.057935 0.182315 -vn 0.576805 0.776777 -0.252813 -v 0.080886 0.057928 0.182279 -vn 0.003910 0.978525 -0.206093 -v 0.080865 0.057962 0.182270 -vn 0.581328 0.311220 -0.751798 -v 0.080789 0.057535 0.181749 -vn 0.186951 0.311101 -0.931808 -v 0.080770 0.057401 0.181687 -vn -0.006411 0.460323 -0.887728 -v 0.080779 0.057544 0.181732 -vn -0.055977 0.292270 -0.954696 -v 0.080765 0.057366 0.181675 -vn 0.002453 0.123285 -0.992368 -v 0.080739 0.057220 0.181634 -vn 0.325512 0.174573 -0.929283 -v 0.080757 0.057301 0.181658 -vn 0.582232 0.005787 -0.813002 -v 0.080745 0.057219 0.181644 -vn -0.002352 0.048545 -0.998818 -v 0.080739 0.057218 0.181633 -vn 0.479505 -0.080452 -0.873844 -v 0.080726 0.057082 0.181639 -vn 0.005498 -0.114063 -0.993458 -v 0.080717 0.057045 0.181635 -vn 0.445797 -0.197225 -0.873137 -v 0.080717 0.057015 0.181644 -vn -0.043087 -0.343226 -0.938264 -v 0.080695 0.056871 0.181673 -vn -0.565569 -0.093286 -0.819408 -v 0.080710 0.056968 0.181651 -vn 0.083316 -0.419527 -0.903911 -v 0.080685 0.056802 0.181699 -vn -0.000008 0.823659 -0.567086 -v 0.080823 0.057811 0.181959 -vn 0.575353 0.609538 -0.545374 -v 0.080839 0.057789 0.181976 -vn -0.004057 0.765583 -0.643324 -v 0.080822 0.057808 0.181956 -vn 0.570219 0.591451 -0.570119 -v 0.080835 0.057776 0.181959 -vn 0.516979 0.561510 -0.646096 -v 0.080830 0.057755 0.181932 -vn 0.332760 0.562447 -0.756918 -v 0.080804 0.057621 0.181806 -vn 0.563829 0.381357 -0.732574 -v 0.080794 0.057564 0.181766 -vn -0.001940 0.956969 -0.290185 -v 0.080865 0.057961 0.182265 -vn 0.576560 0.766995 -0.281597 -v 0.080884 0.057925 0.182266 -vn 0.498998 0.772949 -0.391856 -v 0.080876 0.057907 0.182205 -vn 0.538747 0.691632 -0.481037 -v 0.080844 0.057813 0.182009 -vn 0.490214 0.867767 -0.081673 -v 0.080913 0.057948 0.182480 -vn 0.000347 0.986659 0.162798 -v 0.080906 0.057978 0.182611 -vn 0.556849 0.830611 -0.002216 -v 0.080922 0.057944 0.182545 -vn -0.004384 0.872945 0.487798 -v 0.080950 0.057857 0.182934 -vn 0.005227 0.814210 0.580547 -v 0.080951 0.057853 0.182940 -vn 0.584026 0.717572 0.379477 -v 0.080981 0.057809 0.182912 -vn 0.524398 0.798345 0.296060 -v 0.080963 0.057869 0.182807 -vn 0.495766 0.836924 0.231892 -v 0.080954 0.057893 0.182753 -vn 0.580915 0.809761 0.082615 -v 0.080931 0.057935 0.182604 -vn 0.541372 0.599523 0.589481 -v 0.081011 0.057665 0.183072 -vn 0.508469 0.653079 0.561202 -v 0.081003 0.057711 0.183029 -vn 0.551101 0.680216 0.483315 -v 0.080995 0.057751 0.182986 -vn 0.003545 0.265955 0.963979 -v 0.081033 0.057303 0.183314 -vn -0.003131 0.103657 0.994608 -v 0.081034 0.057294 0.183315 -vn 0.571472 0.276446 0.772656 -v 0.081073 0.057285 0.183247 -vn 0.573650 0.203133 0.793513 -v 0.081074 0.057281 0.183248 -vn 0.503210 0.378256 0.776983 -v 0.081041 0.057488 0.183185 -vn 0.004700 -0.278597 0.960397 -v 0.081078 0.056946 0.183307 -vn 0.576665 -0.125977 0.807209 -v 0.081122 0.056966 0.183233 -vn -0.001582 -0.154384 0.988010 -v 0.081076 0.056956 0.183310 -vn 0.559224 -0.014898 0.828883 -v 0.081114 0.057019 0.183245 -vn 0.564504 0.112725 0.817697 -v 0.081082 0.057231 0.183254 -vn -0.004829 -0.532476 0.846431 -v 0.081116 0.056647 0.183173 -vn 0.553820 -0.317795 0.769603 -v 0.081151 0.056772 0.183154 -vn 0.565727 -0.225952 0.793031 -v 0.081132 0.056895 0.183212 -vn -0.003603 -0.826766 0.562534 -v 0.081161 0.056408 0.182915 -vn 0.005103 -0.894296 0.447447 -v 0.081162 0.056402 0.182904 -vn 0.586540 -0.667207 0.459136 -v 0.081217 0.056483 0.182857 -vn 0.557948 -0.617633 0.554277 -v 0.081200 0.056538 0.182944 -vn 0.548406 -0.563420 0.617906 -v 0.081192 0.056569 0.182984 -vn 0.005246 -0.636027 0.771649 -v 0.081118 0.056637 0.183166 -vn 0.583474 -0.446932 0.678093 -v 0.081167 0.056687 0.183098 -vn 0.572106 -0.381964 0.725808 -v 0.081160 0.056724 0.183124 -vn -0.003464 -0.980808 0.194947 -v 0.081201 0.056296 0.182595 -vn 0.547991 -0.777637 0.308200 -v 0.081240 0.056423 0.182712 -vn 0.565857 -0.733476 0.376588 -v 0.081233 0.056439 0.182760 -vn 0.543748 -0.839125 -0.014394 -v 0.081278 0.056393 0.182455 -vn 0.000271 -0.998935 0.046142 -v 0.081203 0.056295 0.182582 -vn 0.001985 -0.980757 -0.195223 -v 0.081244 0.056320 0.182250 -vn 0.575549 -0.811846 0.098226 -v 0.081270 0.056392 0.182508 -vn 0.579492 -0.799107 0.160053 -v 0.081261 0.056395 0.182569 -vn 0.568745 -0.787733 0.236654 -v 0.081252 0.056404 0.182631 -vn 0.564486 -0.584787 -0.582563 -v 0.081373 0.056654 0.181935 -vn 0.004009 -0.719685 -0.694289 -v 0.081290 0.056491 0.181928 -vn 0.564648 -0.518817 -0.641874 -v 0.081390 0.056745 0.181870 -vn -0.002952 -0.519442 -0.854500 -v 0.081327 0.056743 0.181727 -vn 0.591397 -0.431060 -0.681496 -v 0.081397 0.056788 0.181846 -vn 0.005243 -0.391634 -0.920106 -v 0.081329 0.056758 0.181720 -vn 0.576852 -0.642759 -0.504086 -v 0.081359 0.056588 0.181999 -vn 0.576325 -0.668830 -0.469592 -v 0.081358 0.056582 0.182005 -vn 0.000011 -0.815984 -0.578074 -v 0.081288 0.056481 0.181940 -vn 0.573274 -0.713866 -0.402183 -v 0.081352 0.056558 0.182033 -vn 0.568985 -0.772524 -0.281890 -v 0.081319 0.056451 0.182210 -vn 0.064789 0.125088 -0.990028 -v 0.081472 0.057225 0.181774 -vn 0.581264 -0.104416 -0.806988 -v 0.081452 0.057105 0.181766 -vn 0.854793 -0.125748 -0.503504 -v 0.081446 0.057104 0.181755 -vn 0.438593 -0.184130 -0.879621 -v 0.081438 0.057022 0.181772 -vn 0.506504 -0.224280 -0.832557 -v 0.081433 0.056994 0.181776 -vn 0.551447 0.172867 -0.816102 -v 0.081494 0.057361 0.181808 -vn 0.244048 0.157416 -0.956902 -v 0.081479 0.057266 0.181781 -vn 0.365107 0.461483 -0.808536 -v 0.081517 0.057493 0.181872 -vn 0.507603 0.335575 -0.793554 -v 0.081509 0.057455 0.181850 -vn 0.577657 0.236091 -0.781392 -v 0.081498 0.057386 0.181818 -vn 0.582905 0.478950 -0.656376 -v 0.081545 0.057623 0.181976 -vn 0.572514 0.543330 -0.614019 -v 0.081550 0.057646 0.182001 -vn 0.486723 0.666266 -0.564969 -v 0.081557 0.057671 0.182032 -vn 0.522159 0.843690 0.124647 -v 0.081670 0.057788 0.182669 -vn 0.586374 0.808777 -0.045236 -v 0.081636 0.057821 0.182475 -vn 0.553397 0.820179 -0.145116 -v 0.081629 0.057820 0.182434 -vn 0.498849 0.835272 -0.231238 -v 0.081614 0.057810 0.182341 -vn 0.522445 0.735297 0.431728 -v 0.081711 0.057679 0.182874 -vn 0.579769 0.763912 0.283385 -v 0.081688 0.057751 0.182759 -vn 0.557847 0.804674 0.203238 -v 0.081677 0.057776 0.182702 -vn 0.558893 0.461625 0.688869 -v 0.081755 0.057480 0.183046 -vn 0.563944 0.526401 0.636294 -v 0.081749 0.057511 0.183027 -vn 0.579711 0.601972 0.549150 -v 0.081734 0.057585 0.182973 -vn 0.537028 0.691094 0.483726 -v 0.081717 0.057658 0.182900 -vn 0.600931 0.044920 0.798038 -v 0.081831 0.057073 0.183124 -vn 0.532213 0.169882 0.829391 -v 0.081796 0.057267 0.183121 -vn 0.571861 0.280983 0.770729 -v 0.081790 0.057298 0.183115 -vn 0.591364 0.370526 0.716240 -v 0.081780 0.057351 0.183101 -vn 0.567505 -0.483139 0.666719 -v 0.081910 0.056686 0.182924 -vn 0.601757 -0.349906 0.717951 -v 0.081875 0.056834 0.183043 -vn 0.576341 -0.269040 0.771653 -v 0.081869 0.056863 0.183059 -vn 0.552482 -0.183307 0.813119 -v 0.081856 0.056936 0.183091 -vn 0.594053 -0.052576 0.802706 -v 0.081836 0.057044 0.183120 -vn 0.601175 -0.679643 0.420327 -v 0.081951 0.056568 0.182739 -vn 0.586627 -0.605887 0.537372 -v 0.081923 0.056642 0.182871 -vn 0.567004 -0.557001 0.606841 -v 0.081915 0.056667 0.182902 -vn 0.579990 -0.757571 0.299496 -v 0.081970 0.056536 0.182638 -vn 0.599926 -0.702217 0.383380 -v 0.081956 0.056559 0.182716 -vn 0.600801 -0.795451 0.079352 -v 0.081994 0.056520 0.182503 -vn 0.575950 -0.804068 0.147500 -v 0.081989 0.056520 0.182531 -vn 0.575996 -0.786263 0.223651 -v 0.081976 0.056529 0.182605 -vn 0.669327 -0.684072 -0.289907 -v 0.082065 0.056626 0.182156 -vn 0.550067 -0.803969 -0.225965 -v 0.082035 0.056555 0.182294 -vn 0.583164 -0.804707 -0.111200 -v 0.082030 0.056547 0.182317 -vn 0.638192 -0.769853 0.006178 -v 0.082016 0.056530 0.182390 -vn 0.754984 -0.564246 -0.334106 -v 0.082076 0.056658 0.182112 -vn 0.714326 -0.625966 -0.312897 -v 0.082072 0.056645 0.182129 -vn 0.956178 0.252327 0.148510 -v 0.088903 0.057553 0.182962 -vn 0.860751 0.493272 0.125661 -v 0.088815 0.057775 0.182827 -vn 0.922799 0.219951 0.316328 -v 0.088903 0.057388 0.183130 -vn 0.906351 0.212449 0.365230 -v 0.088898 0.057323 0.183181 -vn 0.961890 0.098830 0.254953 -v 0.088903 0.057209 0.183224 -vn -0.001766 0.072253 0.997385 -v 0.088845 0.057209 0.183327 -vn -0.013486 -0.137562 0.990401 -v 0.088870 0.057005 0.183319 -vn 0.960850 0.030947 0.275334 -v 0.088903 0.057014 0.183263 -vn 0.025697 -0.335227 0.941787 -v 0.088887 0.056870 0.183286 -vn 0.238590 -0.621633 0.746088 -v 0.088903 0.056738 0.183229 -vn 0.959862 -0.017731 0.279912 -v 0.088903 0.056940 0.183264 -vn 0.962762 0.000171 0.270351 -v 0.088903 0.056975 0.183265 -vn 0.862435 0.396206 -0.315001 -v 0.085470 0.057799 0.182181 -vn 0.861097 0.492786 -0.125198 -v 0.085509 0.057863 0.182462 -vn 0.862537 0.500518 0.074235 -v 0.085554 0.057809 0.182756 -vn 0.863177 0.425469 0.271850 -v 0.085596 0.057643 0.183000 -vn 0.860740 0.289215 0.418905 -v 0.085637 0.057398 0.183157 -vn 0.862042 -0.116338 0.493305 -v 0.085721 0.056822 0.183132 -vn 0.862481 0.100379 0.496035 -v 0.085682 0.057101 0.183204 -vn 0.862101 -0.437470 0.255739 -v 0.085808 0.056444 0.182689 -vn 0.863008 -0.295602 0.409678 -v 0.085765 0.056586 0.182949 -vn 0.860688 -0.487635 -0.146384 -v 0.085893 0.056512 0.182115 -vn 0.860450 -0.505297 0.065580 -v 0.085848 0.056418 0.182401 -vn 0.861826 -0.386217 -0.328773 -v 0.085933 0.056704 0.181899 -vn 0.862933 -0.228842 -0.450531 -v 0.085976 0.056973 0.181774 -vn 0.861749 -0.027097 -0.506611 -v 0.086020 0.057271 0.181767 -vn 0.860909 0.173588 -0.478228 -v 0.086060 0.057539 0.181875 -vn 0.860930 0.353739 -0.365606 -v 0.086105 0.057749 0.182089 -vn 0.862514 0.467738 -0.193110 -v 0.086146 0.057854 0.182361 -vn 0.861210 0.508242 0.002621 -v 0.086188 0.057842 0.182656 -vn 0.861189 0.464044 0.207405 -v 0.086232 0.057711 0.182925 -vn 0.860483 0.343200 0.376541 -v 0.086272 0.057492 0.183112 -vn 0.861397 0.162766 0.481148 -v 0.086316 0.057206 0.183201 -vn 0.860751 -0.235638 0.451202 -v 0.086399 0.056660 0.183025 -vn 0.863697 -0.040853 0.502353 -v 0.086358 0.056915 0.183169 -vn 0.860808 -0.491966 0.130304 -v 0.086483 0.056414 0.182504 -vn 0.861245 -0.396640 0.317701 -v 0.086444 0.056481 0.182784 -vn 0.861636 -0.502097 -0.074045 -v 0.086528 0.056466 0.182210 -vn 0.862543 -0.429416 -0.267622 -v 0.086570 0.056629 0.181964 -vn 0.860691 -0.292853 -0.416471 -v 0.086611 0.056873 0.181805 -vn 0.861549 -0.100791 -0.497569 -v 0.086656 0.057169 0.181755 -vn 0.861611 0.111053 -0.495272 -v 0.086695 0.057449 0.181825 -vn 0.862887 0.292078 -0.412451 -v 0.086739 0.057686 0.182005 -vn 0.861914 0.435485 -0.259724 -v 0.086782 0.057831 0.182264 -vn 0.860427 0.504751 -0.069941 -v 0.086822 0.057860 0.182552 -vn 0.860577 0.489033 0.142319 -v 0.086867 0.057768 0.182838 -vn 0.861816 0.389154 0.325319 -v 0.086908 0.057577 0.183057 -vn 0.861829 0.233920 0.450037 -v 0.086950 0.057310 0.183184 -vn 0.861580 0.031628 0.506635 -v 0.086994 0.057012 0.183194 -vn 0.860854 -0.350596 0.368798 -v 0.087079 0.056531 0.182876 -vn 0.860910 -0.169484 0.479696 -v 0.087034 0.056744 0.183088 -vn 0.862596 -0.465762 0.197470 -v 0.087120 0.056424 0.182604 -vn 0.860921 -0.508735 0.001952 -v 0.087162 0.056433 0.182310 -vn 0.860402 -0.346299 -0.373879 -v 0.087246 0.056779 0.181850 -vn 0.860999 -0.466200 -0.203317 -v 0.087206 0.056562 0.182040 -vn 0.860883 0.232658 -0.452494 -v 0.087373 0.057612 0.181930 -vn 0.864857 0.030665 -0.501081 -v 0.087332 0.057356 0.181788 -vn 0.861204 -0.167418 -0.479894 -v 0.087290 0.057064 0.181758 -vn 0.862271 0.486793 -0.139716 -v 0.087458 0.057863 0.182449 -vn 0.861086 0.393935 -0.321476 -v 0.087418 0.057793 0.182169 -vn 0.863565 0.500293 0.062948 -v 0.087502 0.057814 0.182743 -vn 0.864039 0.431832 0.258763 -v 0.087544 0.057652 0.182991 -vn 0.862471 0.299296 0.408125 -v 0.087585 0.057410 0.183152 -vn 0.863462 0.110163 0.492237 -v 0.087630 0.057115 0.183204 -vn 0.863429 -0.101344 0.494186 -v 0.087670 0.056833 0.183137 -vn 0.864697 -0.281591 0.415939 -v 0.087713 0.056595 0.182960 -vn 0.863518 -0.428342 0.266196 -v 0.087757 0.056448 0.182701 -vn 0.862299 -0.500111 0.079555 -v 0.087796 0.056416 0.182414 -vn 0.862543 -0.488668 -0.131237 -v 0.087841 0.056505 0.182127 -vn 0.863712 -0.392696 -0.315897 -v 0.087882 0.056694 0.181907 -vn 0.863470 -0.242203 -0.442444 -v 0.087924 0.056960 0.181777 -vn 0.863312 -0.041160 -0.502989 -v 0.087968 0.057258 0.181765 -vn 0.863305 0.339999 -0.372968 -v 0.088053 0.057742 0.182078 -vn 0.862898 0.158774 -0.479790 -v 0.088008 0.057528 0.181868 -vn 0.862714 0.505526 -0.012947 -v 0.088136 0.057845 0.182643 -vn 0.865309 0.457014 -0.205861 -v 0.088094 0.057851 0.182349 -vn 0.862410 0.351139 0.364623 -v 0.088220 0.057504 0.183106 -vn 0.862858 0.467375 0.192448 -v 0.088180 0.057719 0.182914 -vn 0.863241 0.177164 0.472682 -v 0.088264 0.057219 0.183200 -vn 0.865253 -0.026815 0.500618 -v 0.088306 0.056927 0.183173 -vn 0.862420 -0.220388 0.455697 -v 0.088347 0.056670 0.183033 -vn 0.863089 -0.384260 0.327754 -v 0.088392 0.056486 0.182796 -vn 0.862815 -0.484875 0.142993 -v 0.088432 0.056414 0.182517 -vn 0.863681 -0.500830 -0.056778 -v 0.088476 0.056461 0.182222 -vn 0.863833 -0.434984 -0.254130 -v 0.088519 0.056620 0.181973 -vn 0.862018 -0.304910 -0.404913 -v 0.088559 0.056860 0.181810 -vn 0.862397 -0.113214 -0.493411 -v 0.088604 0.057156 0.181755 -vn 0.863387 0.095961 -0.495333 -v 0.088644 0.057438 0.181819 -vn 0.863336 0.425572 -0.271181 -v 0.088731 0.057827 0.182252 -vn 0.864636 0.276875 -0.419219 -v 0.088687 0.057677 0.181995 -vn 0.862376 0.499092 -0.084945 -v 0.088770 0.057861 0.182539 -vn -0.001126 -0.133160 -0.991094 -v 0.081372 0.057080 0.181632 -vn 0.012664 0.031986 -0.999408 -v 0.081374 0.057098 0.181631 -vn 0.008330 0.820217 -0.571992 -v 0.085383 0.057857 0.182025 -vn -0.004109 0.926730 -0.375705 -v 0.085398 0.057913 0.182129 -vn 0.006587 0.979683 -0.200446 -v 0.085424 0.057977 0.182343 -vn -0.007559 0.999689 0.023746 -v 0.085437 0.057988 0.182459 -vn 0.010135 0.980244 0.197535 -v 0.085466 0.057963 0.182688 -vn -0.010157 0.905166 0.424936 -v 0.085482 0.057924 0.182803 -vn 0.007816 0.817321 0.576129 -v 0.085510 0.057809 0.183002 -vn -0.004484 0.664640 0.747151 -v 0.085524 0.057730 0.183090 -vn 0.008169 0.526208 0.850317 -v 0.085549 0.057554 0.183221 -vn -0.010479 0.306711 0.951745 -v 0.085565 0.057443 0.183273 -vn 0.010164 0.148419 0.988872 -v 0.085594 0.057219 0.183326 -vn -0.008749 -0.094745 0.995463 -v 0.085609 0.057095 0.183329 -vn 0.006449 -0.264430 0.964383 -v 0.085635 0.056878 0.183289 -vn -0.008174 -0.477273 0.878717 -v 0.085649 0.056767 0.183244 -vn 0.010566 -0.621606 0.783259 -v 0.085677 0.056581 0.183121 -vn -0.008880 -0.794125 0.607690 -v 0.085693 0.056491 0.183030 -vn 0.012472 -0.881010 0.472934 -v 0.085721 0.056369 0.182841 -vn -0.007726 -0.969903 0.243369 -v 0.085736 0.056325 0.182725 -vn 0.006721 -0.996265 0.086084 -v 0.085761 0.056289 0.182514 -vn -0.011833 -0.986837 -0.161283 -v 0.085776 0.056293 0.182387 -vn 0.010395 -0.948514 -0.316566 -v 0.085805 0.056347 0.182169 -vn -0.007246 -0.839313 -0.543600 -v 0.085821 0.056404 0.182052 -vn 0.013159 -0.743821 -0.668249 -v 0.085847 0.056536 0.181880 -vn -0.013433 -0.556550 -0.830706 -v 0.085861 0.056630 0.181799 -vn 0.007938 -0.420135 -0.907427 -v 0.085888 0.056819 0.181692 -vn -0.010332 -0.178609 -0.983866 -v 0.085904 0.056945 0.181652 -vn 0.012820 -0.021062 -0.999696 -v 0.085932 0.057164 0.181630 -vn -0.007468 0.226567 -0.973967 -v 0.085948 0.057294 0.181644 -vn 0.008185 0.376607 -0.926337 -v 0.085972 0.057493 0.181707 -vn -0.013126 0.593851 -0.804468 -v 0.085988 0.057608 0.181771 -vn 0.010625 0.712606 -0.701484 -v 0.086015 0.057773 0.181914 -vn -0.008553 0.866948 -0.498325 -v 0.086033 0.057855 0.182022 -vn 0.014602 0.933399 -0.358544 -v 0.086059 0.057946 0.182215 -vn -0.013199 0.993195 -0.115715 -v 0.086073 0.057977 0.182341 -vn 0.008141 0.999221 0.038618 -v 0.086098 0.057985 0.182550 -vn -0.011754 0.957033 0.289740 -v 0.086116 0.057963 0.182686 -vn 0.013168 0.900233 0.435209 -v 0.086143 0.057885 0.182887 -vn -0.007644 0.762813 0.646574 -v 0.086160 0.057810 0.183001 -vn 0.010104 0.653598 0.756774 -v 0.086184 0.057666 0.183146 -vn -0.014436 0.444583 0.895621 -v 0.086199 0.057553 0.183222 -vn 0.010747 0.301496 0.953407 -v 0.086226 0.057357 0.183301 -vn -0.009927 0.047703 0.998812 -v 0.086244 0.057218 0.183326 -vn 0.015291 -0.105307 0.994322 -v 0.086270 0.057008 0.183320 -vn -0.012102 -0.350490 0.936488 -v 0.086286 0.056876 0.183288 -vn 0.008401 -0.489390 0.872025 -v 0.086309 0.056692 0.183203 -vn -0.013127 -0.694257 0.719608 -v 0.086327 0.056578 0.183119 -vn 0.013370 -0.796494 0.604499 -v 0.086354 0.056438 0.182961 -vn -0.008454 -0.923836 0.382696 -v 0.086372 0.056367 0.182837 -vn 0.012633 -0.971199 0.237933 -v 0.086395 0.056305 0.182646 -vn -0.015655 -0.999785 -0.013616 -v 0.086411 0.056289 0.182508 -vn 0.010825 -0.986347 -0.164325 -v 0.086437 0.056307 0.182303 -vn -0.011348 -0.910578 -0.413182 -v 0.086456 0.056350 0.182163 -vn 0.015687 -0.837659 -0.545968 -v 0.086481 0.056449 0.181983 -vn -0.011007 -0.673237 -0.739345 -v 0.086498 0.056541 0.181875 -vn 0.008984 -0.553400 -0.832867 -v 0.086521 0.056696 0.181754 -vn -0.014463 -0.323738 -0.946036 -v 0.086539 0.056827 0.181689 -vn 0.013617 -0.177088 -0.984101 -v 0.086565 0.057025 0.181637 -vn -0.009605 0.082191 -0.996570 -v 0.086584 0.057174 0.181630 -vn 0.015282 0.229650 -0.973153 -v 0.086607 0.057369 0.181662 -vn -0.016508 0.468881 -0.883107 -v 0.086623 0.057503 0.181712 -vn 0.010950 0.594554 -0.803981 -v 0.086648 0.057672 0.181818 -vn -0.012811 0.782984 -0.621909 -v 0.086667 0.057781 0.181923 -vn 0.016097 0.867014 -0.498024 -v 0.086692 0.057894 0.182089 -vn -0.010363 0.965198 -0.261316 -v 0.086710 0.057950 0.182227 -vn 0.010138 0.993477 -0.113584 -v 0.086732 0.057986 0.182414 -vn -0.015787 0.989532 0.143450 -v 0.086750 0.057984 0.182565 -vn 0.013774 0.957239 0.288969 -v 0.086775 0.057941 0.182759 -vn -0.010919 0.848849 0.528523 -v 0.086795 0.057877 0.182900 -vn 0.017132 0.762282 0.647018 -v 0.086819 0.057762 0.183057 -vn -0.016586 0.571606 0.820361 -v 0.086835 0.057653 0.183156 -vn 0.011062 0.445649 0.895139 -v 0.086859 0.057488 0.183254 -vn -0.014253 0.196453 0.980410 -v 0.086878 0.057340 0.183305 -vn 0.016386 0.049770 0.998626 -v 0.086903 0.057145 0.183330 -vn -0.010257 -0.208544 0.977959 -v 0.086922 0.056990 0.183317 -vn 0.011824 -0.350959 0.936316 -v 0.086943 0.056812 0.183264 -vn -0.017127 -0.579213 0.814997 -v 0.086962 0.056676 0.183193 -vn 0.013886 -0.692041 0.721725 -v 0.086986 0.056526 0.183069 -vn -0.012283 -0.857764 0.513897 -v 0.087007 0.056426 0.182944 -vn 0.018292 -0.922888 0.384635 -v 0.087030 0.056341 0.182774 -vn -0.015911 -0.990835 0.134139 -v 0.087048 0.056301 0.182626 -vn 0.011229 -0.999879 -0.010727 -v 0.087069 0.056289 0.182441 -vn -0.015711 -0.962113 -0.272199 -v 0.087090 0.056312 0.182281 -vn 0.016670 -0.912342 -0.409090 -v 0.087114 0.056377 0.182101 -vn -0.010818 -0.774388 -0.632618 -v 0.087134 0.056463 0.181964 -vn 0.014253 -0.674212 -0.738400 -v 0.087155 0.056588 0.181832 -vn -0.018389 -0.460588 -0.887424 -v 0.087174 0.056717 0.181742 -vn 0.013973 -0.328738 -0.944318 -v 0.087197 0.056889 0.181667 -vn -0.013801 -0.065858 -0.997734 -v 0.087218 0.057051 0.181634 -vn 0.018927 0.077163 -0.996839 -v 0.087241 0.057238 0.181635 -vn -0.018502 0.325620 -0.945320 -v 0.087260 0.057394 0.181669 -vn 0.003166 0.475508 -0.879706 -v 0.087281 0.057558 0.181740 -vn -0.017131 0.680973 -0.732108 -v 0.087301 0.057693 0.181836 -vn 0.016887 0.778711 -0.627155 -v 0.087325 0.057820 0.181972 -vn -0.003329 0.912026 -0.410119 -v 0.087346 0.057906 0.182115 -vn 0.021104 0.966115 -0.257248 -v 0.087367 0.057965 0.182283 -vn -0.023796 0.999635 -0.012762 -v 0.087385 0.057988 0.182443 -vn 0.004771 0.988827 0.148993 -v 0.087408 0.057976 0.182624 -vn -0.008456 0.701708 0.712414 -v 0.087472 0.057741 0.183079 -vn 0.013386 0.840590 0.541506 -v 0.087452 0.057846 0.182950 -vn -0.010660 0.926667 0.375732 -v 0.087429 0.057930 0.182789 -vn 0.007454 0.559380 0.828878 -v 0.087492 0.057608 0.183188 -vn -0.008741 -0.042074 0.999076 -v 0.087558 0.057110 0.183329 -vn 0.011751 0.182486 0.983138 -v 0.087536 0.057284 0.183317 -vn -0.012840 0.362912 0.931735 -v 0.087513 0.057457 0.183268 -vn 0.012946 -0.224922 0.974291 -v 0.087579 0.056937 0.183306 -vn -0.011455 -0.756094 0.654363 -v 0.087641 0.056501 0.183042 -vn 0.009319 -0.590233 0.807179 -v 0.087619 0.056631 0.183161 -vn -0.013488 -0.431429 0.902046 -v 0.087597 0.056781 0.183251 -vn 0.013334 -0.864923 0.501728 -v 0.087663 0.056399 0.182898 -vn -0.013433 -0.994808 -0.100884 -v 0.087724 0.056292 0.182402 -vn 0.008077 -0.992787 0.119621 -v 0.087703 0.056294 0.182576 -vn -0.007736 -0.954032 0.299604 -v 0.087684 0.056329 0.182739 -vn 0.011486 -0.958533 -0.284751 -v 0.087746 0.056326 0.182231 -vn -0.012692 -0.606197 -0.795213 -v 0.087809 0.056618 0.181808 -vn 0.013919 -0.764449 -0.644534 -v 0.087790 0.056494 0.181926 -vn -0.009617 -0.870301 -0.492427 -v 0.087769 0.056396 0.182066 -vn 0.008891 -0.449620 -0.893176 -v 0.087830 0.056760 0.181719 -vn -0.007722 0.168480 -0.985675 -v 0.087896 0.057279 0.181641 -vn 0.013204 -0.052945 -0.998510 -v 0.087874 0.057100 0.181630 -vn -0.012203 -0.238985 -0.970946 -v 0.087852 0.056929 0.181656 -vn 0.009379 0.346566 -0.937979 -v 0.087915 0.057436 0.181683 -vn -0.010399 0.834578 -0.550792 -v 0.087981 0.057846 0.182009 -vn 0.011133 0.689733 -0.723978 -v 0.087957 0.057728 0.181867 -vn -0.013970 0.542780 -0.839759 -v 0.087936 0.057595 0.181763 -vn 0.014334 0.922185 -0.386482 -v 0.088001 0.057924 0.182156 -vn -0.012828 0.973405 0.228730 -v 0.088064 0.057967 0.182671 -vn 0.008481 0.999939 0.007096 -v 0.088041 0.057988 0.182487 -vn -0.011436 0.984160 -0.176914 -v 0.088022 0.057974 0.182326 -vn 0.013046 0.913227 0.407243 -v 0.088085 0.057913 0.182829 -vn -0.014355 0.500259 0.865757 -v 0.088148 0.057567 0.183214 -vn 0.011267 0.676364 0.736481 -v 0.088127 0.057712 0.183107 -vn -0.008386 0.800318 0.599517 -v 0.088108 0.057819 0.182989 -vn 0.010774 0.330740 0.943660 -v 0.088168 0.057419 0.183282 -vn -0.009802 -0.291467 0.956531 -v 0.088234 0.056890 0.183293 -vn 0.014319 -0.076374 0.996976 -v 0.088212 0.057071 0.183327 -vn -0.011172 0.110789 0.993781 -v 0.088192 0.057233 0.183324 -vn 0.008109 -0.462547 0.886558 -v 0.088252 0.056747 0.183234 -vn -0.009161 -0.898421 0.439040 -v 0.088320 0.056374 0.182851 -vn 0.012760 -0.778154 0.627944 -v 0.088296 0.056477 0.183013 -vn -0.013432 -0.646454 0.762834 -v 0.088275 0.056590 0.183129 -vn 0.012941 -0.963955 0.265751 -v 0.088338 0.056319 0.182706 -vn -0.011894 -0.935421 -0.353336 -v 0.088403 0.056344 0.182178 -vn 0.010332 -0.990774 -0.135133 -v 0.088379 0.056296 0.182367 -vn -0.014304 -0.998606 0.050816 -v 0.088359 0.056290 0.182523 -vn 0.014227 -0.852695 -0.522215 -v 0.088423 0.056413 0.182036 -vn -0.013929 -0.385175 -0.922738 -v 0.088487 0.056812 0.181695 -vn 0.008242 -0.577837 -0.816111 -v 0.088463 0.056644 0.181789 -vn -0.008622 -0.718257 -0.695725 -v 0.088446 0.056531 0.181885 -vn 0.012422 -0.205155 -0.978651 -v 0.088506 0.056961 0.181648 -vn -0.013731 0.409857 -0.912046 -v 0.088571 0.057489 0.181705 -vn 0.014044 0.203186 -0.979039 -v 0.088550 0.057309 0.181647 -vn -0.009912 0.018407 -0.999781 -v 0.088532 0.057159 0.181630 -vn 0.009906 0.571611 -0.820465 -v 0.088590 0.057620 0.181779 -vn -0.008221 0.946754 -0.321854 -v 0.088658 0.057945 0.182213 -vn 0.014023 0.853211 -0.521377 -v 0.088634 0.057862 0.182033 -vn -0.012534 0.740061 -0.672422 -v 0.088615 0.057770 0.181911 -vn 0.009077 0.989867 -0.141707 -v 0.088675 0.057979 0.182352 -vn -0.010661 0.881778 0.471545 -v 0.088743 0.057885 0.182887 -vn 0.012041 0.964844 0.262547 -v 0.088717 0.057960 0.182697 -vn -0.014348 0.996924 0.077053 -v 0.088698 0.057986 0.182549 -vn 0.014679 0.778676 0.627255 -v 0.088761 0.057803 0.183009 -vn 0.961102 0.065805 0.268240 -v 0.088903 0.057176 0.183235 -vn -0.015565 0.266086 0.963824 -v 0.088826 0.057355 0.183302 -vn 0.009327 0.469790 0.882729 -v 0.088801 0.057545 0.183226 -vn -0.012601 0.624940 0.780571 -v 0.088784 0.057665 0.183147 -vn -0.860887 -0.073290 0.503490 -v 0.085522 0.057207 0.183201 -vn 0.222207 -0.942864 0.248256 -v 0.088903 0.056476 0.182789 -vn -0.839003 -0.537680 0.083516 -v 0.088900 0.056479 0.182780 -vn 0.253673 -0.966650 -0.035180 -v 0.088903 0.056463 0.182595 -vn -0.318038 0.893428 0.317236 -v 0.081492 0.057810 0.182703 -vn -0.426654 0.797500 0.426567 -v 0.081500 0.057788 0.182758 -vn -0.848856 0.427694 0.310681 -v 0.081510 0.057806 0.182762 -vn -0.432304 -0.202939 -0.878595 -v 0.081880 0.056975 0.181861 -vn -0.418524 -0.047871 -0.906943 -v 0.081883 0.056998 0.181857 -vn -0.857394 0.006147 -0.514624 -v 0.081932 0.056971 0.181774 -vn -0.417835 0.483266 -0.769330 -v 0.081946 0.057413 0.181915 -vn -0.428299 0.580304 -0.692681 -v 0.081958 0.057481 0.181956 -vn -0.855094 0.377681 -0.355205 -v 0.082015 0.057535 0.181873 -vn -0.417904 0.857054 -0.301356 -v 0.082008 0.057686 0.182196 -vn -0.429931 0.891513 -0.142705 -v 0.082033 0.057738 0.182356 -vn -0.858018 0.512599 0.032372 -v 0.082100 0.057853 0.182356 -vn -0.419471 0.907543 0.020262 -v 0.082038 0.057744 0.182393 -vn -0.857429 0.457880 0.234863 -v 0.082143 0.057843 0.182649 -vn -0.428706 0.880048 0.204270 -v 0.082070 0.057733 0.182598 -vn -0.421426 0.851120 0.313043 -v 0.082073 0.057727 0.182621 -vn -0.405750 0.677175 -0.613841 -v 0.081975 0.057565 0.182026 -vn -0.415043 0.740819 -0.528134 -v 0.081983 0.057603 0.182067 -vn -0.855306 0.488464 -0.172781 -v 0.082060 0.057747 0.182085 -vn -0.429485 0.800716 -0.417608 -v 0.081998 0.057657 0.182143 -vn -0.855811 0.203369 -0.475634 -v 0.081976 0.057268 0.181766 -vn -0.403746 0.362038 -0.840189 -v 0.081934 0.057337 0.181882 -vn -0.401995 0.424894 -0.811089 -v 0.081943 0.057392 0.181905 -vn -0.415654 0.106992 -0.903208 -v 0.081913 0.057189 0.181848 -vn -0.426999 0.255468 -0.867415 -v 0.081922 0.057251 0.181858 -vn -0.419280 -0.561104 -0.713699 -v 0.081836 0.056708 0.181996 -vn -0.423427 -0.483458 -0.766145 -v 0.081843 0.056751 0.181963 -vn -0.854064 -0.209209 -0.476241 -v 0.081889 0.056703 0.181900 -vn -0.417171 -0.440572 -0.794899 -v 0.081847 0.056776 0.181946 -vn -0.408063 -0.351585 -0.842540 -v 0.081851 0.056798 0.181933 -vn -0.393072 -0.646631 -0.653731 -v 0.081821 0.056631 0.182074 -vn -0.854101 -0.378680 -0.356528 -v 0.081849 0.056511 0.182116 -vn -0.408782 -0.688489 -0.599065 -v 0.081817 0.056616 0.182093 -vn -0.381884 -0.864570 -0.326626 -v 0.081785 0.056512 0.182286 -vn -0.394684 -0.825292 -0.403878 -v 0.081789 0.056520 0.182262 -vn -0.431828 -0.739193 -0.516834 -v 0.081807 0.056574 0.182152 -vn -0.396050 -0.914322 0.084615 -v 0.081738 0.056488 0.182614 -vn -0.375299 -0.926903 0.001279 -v 0.081752 0.056477 0.182506 -vn -0.853329 -0.490534 -0.176651 -v 0.081804 0.056418 0.182400 -vn -0.413556 -0.905619 -0.093945 -v 0.081756 0.056477 0.182477 -vn -0.426657 -0.880602 -0.206163 -v 0.081766 0.056483 0.182407 -vn -0.371826 -0.606916 0.702423 -v 0.081661 0.056775 0.183052 -vn -0.429408 -0.703508 0.566291 -v 0.081690 0.056629 0.182920 -vn -0.855131 -0.463552 0.232100 -v 0.081721 0.056585 0.182948 -vn -0.412906 -0.798208 0.438603 -v 0.081694 0.056612 0.182897 -vn -0.854012 -0.519016 0.035863 -v 0.081764 0.056444 0.182688 -vn -0.406218 -0.854273 0.324352 -v 0.081722 0.056518 0.182724 -vn -0.425844 -0.881865 0.202412 -v 0.081726 0.056509 0.182698 -vn -0.411646 -0.520324 0.748205 -v 0.081657 0.056802 0.183069 -vn -0.851585 -0.329681 0.407570 -v 0.081677 0.056819 0.183130 -vn -0.344332 -0.288952 0.893276 -v 0.081631 0.056984 0.183145 -vn -0.383052 -0.355673 0.852507 -v 0.081639 0.056924 0.183127 -vn -0.427996 -0.453779 0.781604 -v 0.081651 0.056839 0.183090 -vn -0.362357 0.011149 0.931973 -v 0.081599 0.057213 0.183164 -vn -0.430462 -0.125683 0.893816 -v 0.081615 0.057100 0.183165 -vn -0.852516 -0.144417 0.502354 -v 0.081638 0.057097 0.183203 -vn -0.381473 -0.233228 0.894473 -v 0.081627 0.057015 0.183152 -vn -0.299154 0.085146 0.950398 -v 0.081595 0.057244 0.183161 -vn -0.850393 0.065951 0.521999 -v 0.081593 0.057393 0.183158 -vn -0.324773 0.128069 0.937081 -v 0.081590 0.057278 0.183156 -vn -0.850227 0.272612 0.450330 -v 0.081552 0.057639 0.183004 -vn -0.396749 0.508993 0.763883 -v 0.081541 0.057603 0.183002 -vn -0.304781 0.441328 0.844002 -v 0.081562 0.057468 0.183092 -vn -0.403355 0.318881 0.857683 -v 0.081567 0.057436 0.183107 -vn -0.426872 0.220934 0.876908 -v 0.081575 0.057382 0.183128 -vn -0.349113 0.768047 0.536865 -v 0.081505 0.057773 0.182788 -vn -0.365231 0.688476 0.626584 -v 0.081532 0.057656 0.182952 -vn -0.423754 0.583757 0.692575 -v 0.081536 0.057631 0.182977 -vn 0.058174 0.982151 0.178872 -v 0.081472 0.057845 0.182564 -vn -0.853814 0.506112 0.121873 -v 0.081466 0.057863 0.182469 -vn -0.330113 0.934198 0.135272 -v 0.081467 0.057849 0.182526 -vn -0.847177 0.531308 0.001613 -v 0.081447 0.057847 0.182326 -vn -0.859114 0.504494 -0.086076 -v 0.081427 0.057802 0.182189 -vn -0.334948 0.916211 -0.219924 -v 0.081437 0.057830 0.182287 -vn -0.432585 0.853847 -0.289510 -v 0.081424 0.057798 0.182191 -vn -0.422170 0.896246 -0.136074 -v 0.081441 0.057838 0.182325 -vn -0.410865 0.909218 -0.067176 -v 0.081443 0.057840 0.182335 -vn -0.429585 0.902130 0.040222 -v 0.081459 0.057852 0.182469 -vn -0.396557 0.831718 -0.388571 -v 0.081410 0.057752 0.182098 -vn -0.855153 0.490897 -0.166535 -v 0.081411 0.057751 0.182091 -vn -0.366034 0.798656 -0.477669 -v 0.081405 0.057732 0.182067 -vn -0.417372 0.718016 -0.557004 -v 0.081393 0.057680 0.181998 -vn -0.427691 0.672165 -0.604380 -v 0.081383 0.057630 0.181944 -vn -0.425449 0.630157 -0.649535 -v 0.081378 0.057597 0.181914 -vn -0.411879 0.747685 -0.520887 -v 0.081394 0.057684 0.182002 -vn -0.891964 0.423282 -0.158849 -v 0.081402 0.057719 0.182045 -vn -0.429660 -0.005750 -0.902972 -v 0.081308 0.057088 0.181741 -vn -0.427311 0.040568 -0.903194 -v 0.081310 0.057103 0.181741 -vn -0.421127 0.131965 -0.897350 -v 0.081316 0.057143 0.181741 -vn -0.427906 0.273411 -0.861477 -v 0.081341 0.057346 0.181775 -vn -0.422459 0.354631 -0.834125 -v 0.081346 0.057380 0.181787 -vn -0.421490 0.431758 -0.797453 -v 0.081346 0.057386 0.181789 -vn -0.407297 0.545661 -0.732368 -v 0.081372 0.057565 0.181888 -vn -0.432829 -0.370586 -0.821782 -v 0.081268 0.056791 0.181818 -vn -0.417878 -0.271519 -0.866981 -v 0.081277 0.056857 0.181789 -vn -0.401885 -0.208014 -0.891750 -v 0.081283 0.056900 0.181774 -vn -0.413556 -0.113931 -0.903322 -v 0.081295 0.056989 0.181752 -vn -0.397455 -0.779093 -0.484814 -v 0.081216 0.056479 0.182109 -vn -0.414582 -0.818169 -0.398398 -v 0.081197 0.056417 0.182240 -vn -0.423125 -0.848392 -0.318114 -v 0.081192 0.056406 0.182274 -vn -0.425554 -0.861573 -0.276761 -v 0.081189 0.056398 0.182302 -vn -0.441589 -0.711099 -0.547117 -v 0.081221 0.056502 0.182073 -vn -0.438937 -0.643303 -0.627292 -v 0.081232 0.056556 0.182001 -vn -0.401822 -0.564279 -0.721200 -v 0.081246 0.056641 0.181917 -vn -0.402857 -0.494079 -0.770449 -v 0.081251 0.056676 0.181889 -vn -0.451435 -0.795183 0.404834 -v 0.081117 0.056474 0.182876 -vn -0.455836 -0.815663 0.356241 -v 0.081121 0.056460 0.182850 -vn -0.424664 -0.859024 0.285900 -v 0.081126 0.056440 0.182808 -vn -0.419901 -0.891968 0.167563 -v 0.081148 0.056386 0.182635 -vn -0.422597 -0.902292 0.085323 -v 0.081151 0.056381 0.182606 -vn -0.424125 -0.904022 0.053501 -v 0.081153 0.056378 0.182584 -vn -0.429725 -0.901632 -0.048945 -v 0.081157 0.056375 0.182557 -vn -0.417467 -0.893711 -0.164322 -v 0.081182 0.056387 0.182348 -vn -0.451160 -0.565519 0.690394 -v 0.081076 0.056687 0.183117 -vn -0.410367 -0.657748 0.631638 -v 0.081088 0.056617 0.183059 -vn -0.372810 -0.709961 0.597468 -v 0.081094 0.056581 0.183023 -vn -0.385836 -0.746041 0.542727 -v 0.081098 0.056558 0.182996 -vn -0.372162 -0.417277 0.829081 -v 0.081056 0.056837 0.183204 -vn -0.404974 -0.478201 0.779308 -v 0.081062 0.056789 0.183181 -vn -0.424111 0.039297 0.904757 -v 0.081001 0.057292 0.183259 -vn -0.356022 -0.061556 0.932448 -v 0.081026 0.057091 0.183268 -vn -0.434983 -0.175345 0.883201 -v 0.081032 0.057041 0.183263 -vn -0.433985 -0.257900 0.863218 -v 0.081040 0.056969 0.183249 -vn -0.405470 -0.349678 0.844582 -v 0.081049 0.056891 0.183225 -vn -0.412557 0.258255 0.873557 -v 0.080993 0.057357 0.183245 -vn -0.444262 0.332223 0.832021 -v 0.080967 0.057554 0.183163 -vn -0.422608 0.130224 0.896908 -v 0.080999 0.057305 0.183257 -vn -0.363316 0.595625 0.716402 -v 0.080951 0.057672 0.183080 -vn -0.373434 0.658912 0.652980 -v 0.080937 0.057762 0.182990 -vn -0.428574 0.484453 0.762647 -v 0.080961 0.057602 0.183134 -vn -0.435289 0.444390 0.782969 -v 0.080962 0.057595 0.183138 -vn -0.461034 0.867243 0.187982 -v 0.080885 0.057944 0.182600 -vn -0.353524 0.879281 0.319195 -v 0.080898 0.057919 0.182705 -vn -0.309964 0.861009 0.403220 -v 0.080905 0.057900 0.182759 -vn -0.470378 0.716647 0.514939 -v 0.080926 0.057821 0.182911 -vn -0.452687 0.682511 0.573807 -v 0.080931 0.057795 0.182948 -vn -0.279820 0.960048 -0.003115 -v 0.080866 0.057955 0.182433 -vn -0.398109 0.913861 0.079796 -v 0.080872 0.057955 0.182492 -vn -0.427367 0.747422 -0.508644 -v 0.080810 0.057791 0.181970 -vn -0.452618 0.784401 -0.424089 -v 0.080810 0.057794 0.181973 -vn -0.320321 0.872188 -0.369707 -v 0.080836 0.057899 0.182165 -vn -0.424384 0.873599 -0.238167 -v 0.080842 0.057919 0.182220 -vn -0.429148 0.886703 -0.172017 -v 0.080848 0.057933 0.182273 -vn -0.399525 0.912055 -0.092391 -v 0.080853 0.057942 0.182314 -vn -0.294040 0.600525 -0.743580 -v 0.080778 0.057594 0.181781 -vn -0.328421 0.696129 -0.638392 -v 0.080803 0.057757 0.181927 -vn -0.370295 0.211605 -0.904492 -v 0.080741 0.057278 0.181651 -vn 0.447853 0.189071 -0.873888 -v 0.080747 0.057339 0.181665 -vn 0.349714 0.272271 -0.896420 -v 0.080754 0.057402 0.181684 -vn -0.540112 0.476595 -0.693640 -v 0.080771 0.057541 0.181748 -vn -0.643242 0.111337 -0.757525 -v 0.080734 0.057218 0.181642 -vn -0.621113 0.068728 -0.780702 -v 0.080716 0.057058 0.181639 -vn -0.027270 -0.171893 -0.984738 -v 0.080708 0.056996 0.181646 -vn -0.865882 -0.267830 0.422511 -v 0.088814 0.056909 0.183167 -vn -0.864054 -0.414131 0.286193 -v 0.088856 0.056656 0.183021 -vn 0.244599 -0.864844 0.438424 -v 0.088903 0.056569 0.183032 -vn 0.262088 -0.801145 0.538031 -v 0.088903 0.056596 0.183074 -vn 0.251503 -0.750213 0.611495 -v 0.088903 0.056602 0.183082 -vn 0.181555 -0.950700 0.251410 -v 0.088903 0.056487 0.182839 -vn -0.413076 0.816019 0.404329 -v 0.082082 0.057711 0.182670 -vn -0.858268 0.324083 0.397927 -v 0.082187 0.057715 0.182919 -vn -0.861120 0.141091 0.488431 -v 0.082226 0.057500 0.183108 -vn -0.858810 -0.069038 0.507621 -v 0.082270 0.057216 0.183200 -vn -0.861364 -0.258932 0.437043 -v 0.082312 0.056924 0.183172 -vn -0.859406 -0.412877 0.301587 -v 0.082353 0.056669 0.183032 -vn -0.859179 -0.500148 0.107999 -v 0.082398 0.056486 0.182795 -vn -0.859651 -0.501718 -0.096325 -v 0.082437 0.056414 0.182517 -vn -0.860034 -0.419710 -0.290147 -v 0.082481 0.056460 0.182223 -vn -0.859998 -0.276206 -0.429084 -v 0.082524 0.056619 0.181974 -vn -0.859004 -0.081271 -0.505476 -v 0.082564 0.056858 0.181811 -vn -0.858983 0.131021 -0.494956 -v 0.082609 0.057152 0.181755 -vn -0.860316 0.311970 -0.403152 -v 0.082649 0.057434 0.181817 -vn -0.861532 0.446378 -0.241887 -v 0.082692 0.057674 0.181991 -vn -0.860086 0.507467 -0.052235 -v 0.082735 0.057825 0.182246 -vn -0.860201 0.484502 0.159096 -v 0.082775 0.057862 0.182532 -vn -0.859544 0.381479 0.340086 -v 0.082820 0.057779 0.182820 -vn -0.861363 0.217737 0.458960 -v 0.082860 0.057594 0.183043 -vn -0.860502 0.016949 0.509166 -v 0.082903 0.057333 0.183178 -vn -0.859622 -0.185321 0.476136 -v 0.082947 0.057035 0.183197 -vn -0.860176 -0.360938 0.360306 -v 0.082986 0.056765 0.183101 -vn -0.859947 -0.475493 0.185467 -v 0.083031 0.056546 0.182897 -vn -0.862701 -0.505529 -0.013705 -v 0.083072 0.056429 0.182629 -vn -0.860643 -0.462139 -0.213827 -v 0.083113 0.056428 0.182337 -vn -0.860582 -0.335872 -0.382869 -v 0.083158 0.056545 0.182063 -vn -0.860895 -0.158830 -0.483356 -v 0.083197 0.056754 0.181865 -vn -0.860879 0.049870 -0.506360 -v 0.083241 0.057034 0.181762 -vn -0.861457 0.240017 -0.447532 -v 0.083284 0.057328 0.181780 -vn -0.860299 0.400569 -0.315326 -v 0.083324 0.057587 0.181910 -vn -0.860204 0.494305 -0.125344 -v 0.083369 0.057779 0.182140 -vn -0.861351 0.502196 0.076643 -v 0.083409 0.057861 0.182416 -vn -0.862595 0.426600 0.271924 -v 0.083452 0.057826 0.182710 -vn -0.861198 0.291061 0.416679 -v 0.083495 0.057676 0.182966 -vn -0.861477 0.095691 0.498699 -v 0.083535 0.057444 0.183137 -vn -0.860579 -0.111744 0.496907 -v 0.083580 0.057152 0.183204 -vn -0.862161 -0.294658 0.412135 -v 0.083620 0.056867 0.183152 -vn -0.861712 -0.435558 0.260273 -v 0.083663 0.056622 0.182989 -vn -0.860744 -0.504281 0.069433 -v 0.083707 0.056461 0.182738 -vn -0.861266 -0.488426 -0.140214 -v 0.083746 0.056414 0.182455 -vn -0.860781 -0.391837 -0.324838 -v 0.083791 0.056486 0.182164 -vn -0.863670 -0.232901 -0.447025 -v 0.083832 0.056663 0.181933 -vn -0.861570 -0.036787 -0.506304 -v 0.083874 0.056918 0.181789 -vn -0.860593 0.168783 -0.480512 -v 0.083918 0.057215 0.181759 -vn -0.861338 0.345645 -0.372327 -v 0.083957 0.057489 0.181845 -vn -0.861461 0.466101 -0.201581 -v 0.084001 0.057715 0.182040 -vn -0.862668 0.505723 -0.006941 -v 0.084044 0.057842 0.182305 -vn -0.861282 0.468603 0.196483 -v 0.084084 0.057854 0.182595 -vn -0.861163 0.348424 0.370133 -v 0.084129 0.057747 0.182874 -vn -0.862101 0.176242 0.475101 -v 0.084169 0.057545 0.183080 -vn -0.862785 -0.031015 0.504620 -v 0.084212 0.057271 0.183192 -vn -0.862116 -0.222404 0.455294 -v 0.084255 0.056975 0.183186 -vn -0.861213 -0.387925 0.328369 -v 0.084295 0.056712 0.183066 -vn -0.860879 -0.488470 0.142423 -v 0.084340 0.056511 0.182844 -vn -0.862715 -0.502408 -0.057529 -v 0.084380 0.056419 0.182570 -vn -0.862700 -0.436989 -0.254539 -v 0.084423 0.056443 0.182275 -vn -0.861655 -0.304887 -0.405702 -v 0.084467 0.056583 0.182013 -vn -0.862101 -0.113874 -0.493776 -v 0.084506 0.056808 0.181834 -vn -0.861394 0.093840 -0.499194 -v 0.084551 0.057097 0.181756 -vn -0.863743 0.277775 -0.420464 -v 0.084592 0.057385 0.181798 -vn -0.862267 0.424248 -0.276604 -v 0.084634 0.057635 0.181951 -vn -0.861312 0.500752 -0.085963 -v 0.084678 0.057806 0.182196 -vn -0.861990 0.492133 0.121563 -v 0.084717 0.057863 0.182477 -vn -0.861853 0.401711 0.309576 -v 0.084762 0.057803 0.182770 -vn -0.864507 0.248016 0.437169 -v 0.084804 0.057634 0.183009 -vn -0.862490 0.055675 0.503002 -v 0.084844 0.057386 0.183161 -vn -0.861916 -0.154186 0.483040 -v 0.084889 0.057089 0.183203 -vn -0.862620 -0.329495 0.383822 -v 0.084929 0.056812 0.183127 -vn -0.862902 -0.456291 0.217252 -v 0.084972 0.056579 0.182941 -vn -0.862847 -0.504787 0.026175 -v 0.085015 0.056442 0.182680 -vn -0.861804 -0.474414 -0.179515 -v 0.085055 0.056419 0.182392 -vn -0.861480 -0.360694 -0.357424 -v 0.085100 0.056516 0.182108 -vn -0.863046 -0.193093 -0.466763 -v 0.085140 0.056710 0.181895 -vn -0.864079 0.012683 -0.503197 -v 0.085183 0.056979 0.181772 -vn -0.862703 0.205516 -0.462068 -v 0.085227 0.057276 0.181768 -vn -0.862714 0.376004 -0.338152 -v 0.085266 0.057542 0.181877 -vn -0.861852 0.481369 -0.159672 -v 0.085311 0.057751 0.182092 -vn -0.863882 0.502185 0.038957 -v 0.085352 0.057854 0.182363 -vn -0.862465 0.446451 0.238401 -v 0.085394 0.057841 0.182657 -vn -0.862069 0.130814 0.489617 -v 0.085477 0.057493 0.183112 -vn -0.861085 0.321620 0.393820 -v 0.085438 0.057710 0.182925 -vn -0.864132 -0.259128 0.431427 -v 0.085563 0.056917 0.183170 -vn -0.862455 -0.413936 0.291254 -v 0.085605 0.056663 0.183027 -vn -0.861294 -0.497639 0.102603 -v 0.085649 0.056482 0.182788 -vn -0.861681 -0.497500 -0.099995 -v 0.085688 0.056414 0.182509 -vn -0.861585 -0.414887 -0.292472 -v 0.085732 0.056463 0.182215 -vn -0.862090 -0.270219 -0.428698 -v 0.085775 0.056625 0.181968 -vn -0.860634 0.134857 -0.491043 -v 0.085860 0.057160 0.181755 -vn -0.860775 -0.076875 -0.503147 -v 0.085815 0.056866 0.181808 -vn -0.861887 0.313827 -0.398327 -v 0.085900 0.057441 0.181821 -vn -0.862932 0.446353 -0.236890 -v 0.085943 0.057679 0.181997 -vn -0.861650 0.505276 -0.047491 -v 0.085987 0.057827 0.182254 -vn -0.861671 0.480818 0.162288 -v 0.086026 0.057861 0.182540 -vn -0.860746 0.376900 0.342144 -v 0.086071 0.057775 0.182827 -vn -0.862480 0.212918 0.459122 -v 0.086111 0.057588 0.183048 -vn -0.861698 0.012242 0.507274 -v 0.086154 0.057325 0.183180 -vn -0.861254 -0.362643 0.355994 -v 0.086237 0.056758 0.183097 -vn -0.860860 -0.188413 0.472675 -v 0.086198 0.057027 0.183196 -vn -0.860733 -0.475846 0.180858 -v 0.086282 0.056541 0.182890 -vn -0.863658 -0.503759 -0.017945 -v 0.086323 0.056427 0.182622 -vn -0.861357 -0.459239 -0.217173 -v 0.086365 0.056429 0.182329 -vn -0.861499 -0.331599 -0.384528 -v 0.086409 0.056550 0.182056 -vn -0.861597 -0.154372 -0.483549 -v 0.086448 0.056761 0.181861 -vn -0.861208 0.054091 -0.505366 -v 0.086493 0.057042 0.181761 -vn -0.862304 0.243470 -0.444020 -v 0.086535 0.057335 0.181782 -vn -0.860714 0.494501 -0.120999 -v 0.086620 0.057783 0.182147 -vn -0.860775 0.402241 -0.311878 -v 0.086575 0.057593 0.181915 -vn -0.861682 0.500972 0.080813 -v 0.086660 0.057861 0.182424 -vn -0.862808 0.424102 0.275136 -v 0.086703 0.057823 0.182718 -vn -0.861636 0.287111 0.418511 -v 0.086746 0.057671 0.182972 -vn -0.860218 -0.116761 0.496378 -v 0.086831 0.057144 0.183205 -vn -0.862119 -0.298168 0.409690 -v 0.086871 0.056860 0.183149 -vn -0.860534 0.095278 0.500404 -v 0.086786 0.057437 0.183141 -vn -0.861817 -0.437646 0.256395 -v 0.086914 0.056616 0.182983 -vn -0.861201 -0.487412 -0.144091 -v 0.086997 0.056414 0.182446 -vn -0.860961 -0.504417 0.065643 -v 0.086958 0.056458 0.182731 -vn -0.860535 -0.389599 -0.328164 -v 0.087042 0.056489 0.182157 -vn -0.863510 -0.229375 -0.449153 -v 0.087083 0.056669 0.181927 -vn -0.861217 -0.032833 -0.507175 -v 0.087125 0.056926 0.181787 -vn -0.860943 0.349107 -0.370002 -v 0.087208 0.057496 0.181849 -vn -0.860423 0.172208 -0.479601 -v 0.087169 0.057223 0.181760 -vn -0.863891 0.503667 0.003431 -v 0.087295 0.057844 0.182312 -vn -0.861183 0.467543 -0.199417 -v 0.087253 0.057720 0.182046 -vn -0.861117 0.468079 0.198442 -v 0.087336 0.057853 0.182603 -vn -0.862672 0.340145 0.374296 -v 0.087380 0.057742 0.182881 -vn -0.863304 0.167489 0.476082 -v 0.087420 0.057539 0.183084 -vn -0.863728 -0.040301 0.502345 -v 0.087463 0.057262 0.183194 -vn -0.863527 -0.229008 0.449306 -v 0.087506 0.056967 0.183184 -vn -0.862463 -0.392050 0.320084 -v 0.087546 0.056705 0.183061 -vn -0.862109 -0.488963 0.132979 -v 0.087591 0.056507 0.182836 -vn -0.863631 -0.499813 -0.065792 -v 0.087631 0.056418 0.182562 -vn -0.864674 -0.428329 -0.262436 -v 0.087674 0.056445 0.182267 -vn -0.863383 -0.296729 -0.408070 -v 0.087718 0.056589 0.182007 -vn -0.863217 -0.104351 -0.493930 -v 0.087757 0.056816 0.181830 -vn -0.862390 0.102721 -0.495714 -v 0.087802 0.057105 0.181755 -vn -0.864388 0.284210 -0.414798 -v 0.087843 0.057392 0.181801 -vn -0.863269 0.428103 -0.267385 -v 0.087885 0.057641 0.181957 -vn -0.862470 0.500167 -0.077319 -v 0.087929 0.057809 0.182204 -vn -0.862855 0.488387 0.130226 -v 0.087968 0.057863 0.182486 -vn -0.862571 0.394872 0.316303 -v 0.088013 0.057799 0.182777 -vn -0.865239 0.239956 0.440206 -v 0.088055 0.057628 0.183015 -vn -0.863219 0.045936 0.502736 -v 0.088096 0.057378 0.183164 -vn -0.862935 -0.162185 0.478579 -v 0.088140 0.057081 0.183202 -vn -0.863235 -0.335652 0.377045 -v 0.088180 0.056805 0.183123 -vn -0.863340 -0.459671 0.208197 -v 0.088224 0.056574 0.182935 -vn -0.863641 -0.503817 0.017100 -v 0.088266 0.056440 0.182672 -vn -0.862491 -0.469930 -0.187815 -v 0.088306 0.056420 0.182384 -vn -0.862240 -0.353194 -0.363038 -v 0.088351 0.056520 0.182101 -vn -0.863403 -0.184579 -0.469538 -v 0.088391 0.056716 0.181890 -vn -0.864604 0.022278 -0.501961 -v 0.088434 0.056987 0.181771 -vn -0.863327 0.213071 -0.457457 -v 0.088478 0.057284 0.181769 -vn -0.863290 0.381636 -0.330280 -v 0.088517 0.057549 0.181882 -vn -0.862377 0.483407 -0.150412 -v 0.088562 0.057756 0.182099 -vn -0.863985 0.501251 0.047731 -v 0.088603 0.057855 0.182371 -vn -0.863331 0.440847 0.245589 -v 0.088645 0.057839 0.182665 -vn -0.862554 0.310480 0.399503 -v 0.088689 0.057705 0.182931 -vn -0.862836 0.122332 0.490457 -v 0.088728 0.057485 0.183116 -vn -0.862394 -0.085423 0.498978 -v 0.088773 0.057199 0.183202 -vn 0.202492 -0.851091 -0.484398 -v 0.088903 0.056536 0.182348 -vn 0.253903 -0.947001 -0.196781 -v 0.088903 0.056470 0.182533 -vn 0.029683 0.325104 -0.945212 -v 0.080685 0.057406 0.181673 -vn 0.104179 -0.180790 -0.977989 -v 0.080685 0.056967 0.181647 -vn 0.044833 0.748973 -0.661083 -v 0.080685 0.057774 0.181915 -vn 0.042010 0.979157 -0.198712 -v 0.080685 0.057971 0.182308 -vn 0.048770 0.946907 0.317786 -v 0.080685 0.057945 0.182747 -vn 0.055418 0.658343 0.750675 -v 0.080685 0.057703 0.183115 -vn 0.063848 0.205576 0.976556 -v 0.080685 0.057310 0.183312 -vn 0.058850 -0.315948 0.946950 -v 0.080685 0.056871 0.183286 -vn 0.062269 -0.746840 0.662082 -v 0.080685 0.056503 0.183044 -vn 0.066682 -0.977644 0.199411 -v 0.080685 0.056306 0.182651 -vn 0.067801 -0.947027 -0.313916 -v 0.080685 0.056332 0.182212 -vn 0.074239 -0.695944 -0.714248 -v 0.080685 0.056574 0.181844 -vn -0.710387 -0.041244 0.702602 -v 0.059703 0.057167 0.181985 -vn -0.819514 0.426444 0.382809 -v 0.059703 0.057646 0.181560 -vn -0.994585 0.036927 -0.097147 -v 0.059703 0.057562 0.181519 -vn -0.994278 0.013853 -0.105923 -v 0.059703 0.057275 0.181438 -vn -0.994792 -0.008046 -0.101613 -v 0.059703 0.056976 0.181442 -vn -0.813579 -0.465988 0.347770 -v 0.059703 0.056742 0.181507 -vn -0.103399 0.920270 -0.377376 -v 0.060303 0.058697 0.181939 -vn -0.101880 0.838102 -0.535916 -v 0.060303 0.058515 0.181570 -vn -0.378928 0.770319 -0.512856 -v 0.060073 0.058477 0.181595 -vn -0.112641 -0.902292 -0.416150 -v 0.060303 0.055654 0.181760 -vn -0.091250 -0.961375 -0.259677 -v 0.060303 0.055549 0.182035 -vn -0.387726 -0.888260 -0.246300 -v 0.060073 0.055593 0.182047 -vn -0.698364 0.689269 0.192865 -v 0.059879 0.058558 0.182877 -vn -0.915556 0.388835 0.102786 -v 0.059749 0.058371 0.182824 -vn -0.893588 0.380380 0.238353 -v 0.059749 0.058224 0.183158 -vn -0.985142 -0.096607 -0.141993 -v 0.059721 0.056512 0.183498 -vn -0.876799 0.367718 -0.309851 -v 0.059714 0.056405 0.183381 -vn -0.899503 -0.288705 0.327940 -v 0.059749 0.056313 0.183457 -vn -0.981678 -0.124923 0.143884 -v 0.059721 0.056635 0.181394 -vn -0.915555 -0.056586 -0.398192 -v 0.059749 0.056940 0.181215 -vn -0.983003 0.130879 0.128744 -v 0.059721 0.056053 0.182983 -vn -0.909219 -0.341937 0.237488 -v 0.059749 0.056071 0.183185 -vn -0.698360 -0.461772 0.546864 -v 0.059879 0.056187 0.183606 -vn -0.914282 -0.154085 0.374628 -v 0.059749 0.056622 0.183650 -vn -0.981682 0.124929 -0.143850 -v 0.059721 0.057641 0.183565 -vn -0.915555 0.056584 0.398193 -v 0.059749 0.057337 0.183744 -vn -0.893854 0.192470 0.404946 -v 0.059749 0.057685 0.183637 -vn -0.905684 0.279369 0.318889 -v 0.059749 0.057989 0.183436 -vn -0.880542 -0.296156 -0.370049 -v 0.059714 0.058040 0.183213 -vn -0.982296 -0.155788 0.104039 -v 0.059721 0.058157 0.183106 -vn -0.983004 -0.130868 -0.128748 -v 0.059721 0.058224 0.181977 -vn -0.912920 0.393468 -0.108442 -v 0.059749 0.058362 0.182103 -vn -0.914287 0.154078 -0.374619 -v 0.059749 0.057655 0.181309 -vn -0.698361 -0.289003 0.654804 -v 0.059879 0.056543 0.183828 -vn -0.382702 -0.368307 0.847283 -v 0.060073 0.056491 0.183947 -vn -0.917552 0.397583 -0.005072 -v 0.059749 0.058418 0.182463 -vn -0.698359 0.715689 -0.009136 -v 0.059879 0.058613 0.182461 -vn -0.385302 0.922571 -0.020132 -v 0.060073 0.058743 0.182459 -vn -0.698366 0.607012 0.379238 -v 0.059879 0.058389 0.183261 -vn -0.698362 0.475576 0.534900 -v 0.059879 0.058118 0.183581 -vn -0.698362 0.305613 0.647218 -v 0.059879 0.057768 0.183813 -vn -0.698360 0.110902 0.707103 -v 0.059879 0.057367 0.183936 -vn -0.698363 -0.597128 0.394623 -v 0.059879 0.055908 0.183292 -vn -0.378925 -0.770317 0.512863 -v 0.060073 0.055800 0.183364 -vn -0.385758 -0.593359 0.706481 -v 0.060073 0.056103 0.183705 -vn -0.382691 -0.884564 0.266636 -v 0.060073 0.055605 0.182951 -vn -0.698357 -0.684127 0.210399 -v 0.059879 0.055729 0.182913 -vn -0.912922 -0.393463 0.108443 -v 0.059749 0.055915 0.182856 -vn -0.917554 -0.397578 0.005076 -v 0.059749 0.055859 0.182496 -vn -0.698361 -0.715687 0.009132 -v 0.059879 0.055664 0.182498 -vn -0.385297 -0.922573 0.020135 -v 0.060073 0.055534 0.182500 -vn -0.381159 -0.149076 -0.912411 -v 0.060073 0.056890 0.180895 -vn -0.383971 -0.399245 -0.832568 -v 0.060073 0.056453 0.181029 -vn -0.698356 -0.110891 -0.707108 -v 0.059879 0.056910 0.181023 -vn -0.698361 -0.305623 -0.647214 -v 0.059879 0.056509 0.181147 -vn -0.893863 -0.192464 -0.404927 -v 0.059749 0.056592 0.181323 -vn -0.917548 0.051568 -0.394266 -v 0.059749 0.057304 0.181211 -vn -0.698359 0.092816 -0.709704 -v 0.059879 0.057330 0.181018 -vn -0.385304 0.127949 -0.913876 -v 0.060073 0.057346 0.180889 -vn -0.698359 0.289000 -0.654808 -v 0.059879 0.057734 0.181131 -vn -0.382697 0.368304 -0.847287 -v 0.060073 0.057786 0.181012 -vn -0.899505 0.288700 -0.327938 -v 0.059749 0.057964 0.181502 -vn -0.909216 0.341942 -0.237490 -v 0.059749 0.058206 0.181774 -vn -0.698363 0.461768 -0.546863 -v 0.059879 0.058090 0.181353 -vn -0.698358 0.597139 -0.394615 -v 0.059879 0.058368 0.181667 -vn -0.385763 0.593357 -0.706480 -v 0.060073 0.058173 0.181254 -vn -0.387732 0.888258 0.246296 -v 0.060073 0.058683 0.182912 -vn -0.385677 0.777315 0.497027 -v 0.060073 0.058499 0.183330 -vn -0.376557 0.615538 0.692328 -v 0.060073 0.058204 0.183679 -vn -0.383985 0.399236 0.832566 -v 0.060073 0.057823 0.183930 -vn -0.381156 0.149081 0.912412 -v 0.060073 0.057387 0.184065 -vn -0.132037 0.295377 0.946213 -v 0.060303 0.057679 0.184038 -vn -0.098862 0.154144 0.983090 -v 0.060303 0.057394 0.184110 -vn -0.108868 -0.020805 0.993838 -v 0.060303 0.057042 0.184127 -vn -0.089100 -0.186236 0.978457 -v 0.060303 0.056924 0.184116 -vn -0.385288 -0.127946 0.913884 -v 0.060073 0.056930 0.184070 -vn -0.698349 -0.092815 0.709714 -v 0.059879 0.056947 0.183941 -vn -0.917556 -0.051553 0.394251 -v 0.059749 0.056972 0.183748 -vn -0.091353 -0.340639 0.935746 -v 0.060303 0.056472 0.183989 -vn -0.091700 -0.621651 0.777909 -v 0.060303 0.056074 0.183740 -vn -0.103388 -0.482520 0.869761 -v 0.060303 0.056419 0.183964 -vn -0.108862 -0.989444 -0.095653 -v 0.060303 0.055491 0.182383 -vn -0.091891 -0.993437 0.068114 -v 0.060303 0.055489 0.182501 -vn -0.093812 -0.968451 0.230872 -v 0.060303 0.055561 0.182965 -vn -0.103393 -0.920273 0.377370 -v 0.060303 0.055580 0.183021 -vn -0.101876 -0.838098 0.535923 -v 0.060303 0.055762 0.183389 -vn -0.146028 -0.750115 0.644983 -v 0.060303 0.055905 0.183576 -vn -0.698362 -0.689270 -0.192868 -v 0.059879 0.055719 0.182082 -vn -0.915557 -0.388832 -0.102785 -v 0.059749 0.055906 0.182135 -vn -0.092565 -0.819900 -0.564974 -v 0.060303 0.055739 0.181605 -vn -0.385683 -0.777312 -0.497027 -v 0.060073 0.055778 0.181630 -vn -0.698354 -0.607015 -0.379255 -v 0.059879 0.055888 0.181698 -vn -0.893588 -0.380379 -0.238353 -v 0.059749 0.056053 0.181802 -vn -0.982296 0.155792 -0.104037 -v 0.059721 0.056120 0.181853 -vn -0.880543 0.296151 0.370051 -v 0.059714 0.056237 0.181746 -vn -0.905680 -0.279370 -0.318899 -v 0.059749 0.056288 0.181523 -vn -0.698358 -0.475584 -0.534898 -v 0.059879 0.056159 0.181378 -vn -0.376582 -0.615544 -0.692309 -v 0.060073 0.056072 0.181281 -vn -0.097168 -0.661304 -0.743798 -v 0.060303 0.056042 0.181247 -vn -0.092535 -0.465191 -0.880361 -v 0.060303 0.056434 0.180988 -vn -0.103400 0.482422 -0.869815 -v 0.060303 0.057858 0.180995 -vn -0.091358 0.340546 -0.935779 -v 0.060303 0.057805 0.180970 -vn -0.089100 0.186253 -0.978453 -v 0.060303 0.057352 0.180844 -vn -0.108868 0.020805 -0.993838 -v 0.060303 0.057235 0.180832 -vn -0.098862 -0.154144 -0.983090 -v 0.060303 0.056883 0.180850 -vn -0.132029 -0.295407 -0.946205 -v 0.060303 0.056597 0.180921 -vn -0.091700 0.621651 -0.777909 -v 0.060303 0.058203 0.181219 -vn -0.985146 0.096628 0.141952 -v 0.059721 0.057765 0.181461 -vn -0.146040 0.750129 -0.644964 -v 0.060303 0.058372 0.181383 -vn -0.093819 0.968451 -0.230868 -v 0.060303 0.058716 0.181995 -vn -0.382704 0.884557 -0.266638 -v 0.060073 0.058672 0.182008 -vn -0.698359 0.684125 -0.210397 -v 0.059879 0.058548 0.182046 -vn -0.876804 -0.367711 0.309843 -v 0.059714 0.057872 0.181578 -vn -0.091894 0.993436 -0.068129 -v 0.060303 0.058788 0.182459 -vn -0.108864 0.989445 0.095640 -v 0.060303 0.058786 0.182576 -vn -0.092560 0.465169 0.880370 -v 0.060303 0.057843 0.183972 -vn -0.097152 0.661309 0.743796 -v 0.060303 0.058235 0.183713 -vn -0.092547 0.819901 0.564976 -v 0.060303 0.058538 0.183354 -vn -0.112633 0.902295 0.416147 -v 0.060303 0.058623 0.183199 -vn -0.091250 0.961374 0.259680 -v 0.060303 0.058727 0.182924 -vn 0.381694 0.304301 0.872761 -v 0.061003 0.057679 0.184038 -vn 0.377164 0.615384 0.692134 -v 0.061003 0.058235 0.183713 -vn 0.378498 -0.058611 0.923745 -v 0.061003 0.057042 0.184127 -vn 0.376554 -0.400357 0.835417 -v 0.061003 0.056419 0.183964 -vn 0.382320 -0.690556 0.613974 -v 0.061003 0.055905 0.183576 -vn 0.378055 -0.875361 0.301359 -v 0.061003 0.055580 0.183021 -vn 0.379782 -0.923639 -0.051539 -v 0.061003 0.055491 0.182383 -vn 0.381686 -0.831166 -0.404325 -v 0.061003 0.055654 0.181760 -vn 0.377165 -0.615382 -0.692135 -v 0.061003 0.056042 0.181247 -vn 0.381690 -0.304304 -0.872761 -v 0.061003 0.056597 0.180921 -vn 0.378525 0.058617 -0.923733 -v 0.061003 0.057235 0.180832 -vn 0.376582 0.400348 -0.835409 -v 0.061003 0.057858 0.180995 -vn 0.382320 0.690555 -0.613975 -v 0.061003 0.058372 0.181383 -vn 0.378070 0.875355 -0.301358 -v 0.061003 0.058697 0.181939 -vn 0.379785 0.923638 0.051545 -v 0.061003 0.058786 0.182576 -vn 0.381693 0.831162 0.404327 -v 0.061003 0.058623 0.183199 -vn 0.770262 -0.624612 0.128671 -v 0.061103 0.056306 0.182651 -vn 0.906600 -0.421265 -0.024731 -v 0.061103 0.055591 0.182389 -vn 0.770262 -0.605266 -0.200873 -v 0.061103 0.056332 0.182212 -vn 0.906599 -0.379738 -0.184058 -v 0.061103 0.055744 0.181804 -vn 0.770036 -0.424136 -0.476606 -v 0.061103 0.056574 0.181844 -vn 0.906601 -0.280391 -0.315366 -v 0.061103 0.056109 0.181321 -vn 0.770040 -0.128443 -0.624932 -v 0.061103 0.056967 0.181647 -vn 0.770261 0.128679 0.624611 -v 0.061103 0.057310 0.183312 -vn 0.906595 -0.024730 0.421277 -v 0.061103 0.057048 0.184027 -vn 0.770264 -0.200867 0.605266 -v 0.061103 0.056871 0.183286 -vn 0.906588 -0.184068 0.379760 -v 0.061103 0.056462 0.183874 -vn 0.770263 -0.476594 0.423738 -v 0.061103 0.056503 0.183044 -vn 0.906602 -0.315365 0.280388 -v 0.061103 0.055980 0.183510 -vn 0.906597 -0.398667 0.138370 -v 0.061103 0.055674 0.182988 -vn 0.770262 0.624610 -0.128678 -v 0.061103 0.057971 0.182308 -vn 0.906600 0.421265 0.024724 -v 0.061103 0.058686 0.182570 -vn 0.770264 0.605264 0.200872 -v 0.061103 0.057945 0.182747 -vn 0.906603 0.379729 0.184057 -v 0.061103 0.058533 0.183156 -vn 0.770260 0.423741 0.476595 -v 0.061103 0.057703 0.183115 -vn 0.906598 0.280398 0.315368 -v 0.061103 0.058168 0.183638 -vn 0.906604 0.138361 0.398654 -v 0.061103 0.057647 0.183944 -vn 0.906604 -0.138360 -0.398655 -v 0.061103 0.056630 0.181015 -vn 0.906613 0.024734 -0.421238 -v 0.061103 0.057229 0.180932 -vn 0.770260 0.200880 -0.605266 -v 0.061103 0.057406 0.181673 -vn 0.906605 0.184053 -0.379727 -v 0.061103 0.057814 0.181085 -vn 0.770260 0.476594 -0.423743 -v 0.061103 0.057774 0.181915 -vn 0.906601 0.315364 -0.280394 -v 0.061103 0.058297 0.181450 -vn 0.906607 0.398650 -0.138354 -v 0.061103 0.058603 0.181971 -vn 0.945445 -0.102614 0.309199 -v 0.088903 0.056949 0.183049 -vn 0.945179 -0.319629 0.066883 -v 0.088903 0.056551 0.182601 -vn 0.945448 -0.243459 0.216462 -v 0.088903 0.056690 0.182878 -vn 0.938718 0.208835 0.274220 -v 0.088903 0.057537 0.182928 -vn 0.945450 0.065725 0.319067 -v 0.088903 0.057259 0.183067 -vn 0.904971 0.274894 0.324748 -v 0.089103 0.057404 0.182779 -vn 0.900741 0.087632 0.425425 -v 0.089103 0.057219 0.182871 -vn 0.900733 -0.136812 0.412265 -v 0.089103 0.057012 0.182859 -vn 0.900738 -0.324612 0.288613 -v 0.089103 0.056839 0.182745 -vn 0.901036 -0.424630 0.088451 -v 0.089103 0.056747 0.182560 -vn 0.901368 -0.410621 -0.137571 -v 0.089103 0.056759 0.182354 -vn 0.900745 -0.288602 -0.324604 -v 0.089103 0.056873 0.182181 -vn 0.900738 -0.087641 -0.425430 -v 0.089103 0.057058 0.182088 -vn 0.900745 0.136817 -0.412238 -v 0.089103 0.057264 0.182100 -vn 0.900736 0.324607 -0.288628 -v 0.089103 0.057437 0.182214 -vn 0.900738 0.425429 -0.087642 -v 0.089103 0.057530 0.182399 -vn 0.904200 0.408301 0.125346 -v 0.089103 0.057518 0.182606 -vn 1.000000 0.000000 0.000000 -v 0.089103 0.057138 0.182480 -vn -0.948596 -0.018547 0.315946 -v 0.060703 0.057145 0.182364 -vn -0.710388 -0.041237 0.702602 -v 0.060703 0.057743 0.181832 -vn -0.710388 -0.702601 -0.041240 -v 0.060703 0.057852 0.181955 -vn -0.948596 -0.315947 -0.018546 -v 0.060703 0.057254 0.182486 -vn -0.710388 -0.702600 -0.041255 -v 0.060703 0.057786 0.183084 -vn -0.710390 0.041249 -0.702598 -v 0.060703 0.057663 0.183193 -vn -0.948597 0.018545 -0.315942 -v 0.060703 0.057132 0.182595 -vn -0.710389 0.041238 -0.702600 -v 0.060703 0.056534 0.183127 -vn -0.710388 0.702601 0.041239 -v 0.060703 0.056425 0.183004 -vn -0.948596 0.315946 0.018546 -v 0.060703 0.057023 0.182473 -vn -0.710389 0.702599 0.041256 -v 0.060703 0.056491 0.181875 -vn -0.710387 -0.041254 0.702601 -v 0.060703 0.056614 0.181766 -vn -0.710384 -0.019068 0.703556 -v 0.059703 0.073173 0.191235 -vn -0.813581 0.434497 0.386391 -v 0.059703 0.073638 0.190795 -vn -0.994792 0.016715 -0.100548 -v 0.059703 0.073411 0.190710 -vn -0.994277 -0.004729 -0.106726 -v 0.059703 0.073113 0.190681 -vn -0.995324 -0.017259 -0.095035 -v 0.059703 0.072820 0.190736 -vn -0.811466 -0.455701 0.365867 -v 0.059703 0.072733 0.190770 -vn -0.710390 -0.703550 -0.019065 -v 0.059703 0.073655 0.191743 -vn -0.819514 -0.369167 0.438305 -v 0.059703 0.074095 0.192208 -vn -0.994585 0.098265 0.033844 -v 0.059703 0.074133 0.192123 -vn -0.994278 0.106306 0.010505 -v 0.059703 0.074205 0.191833 -vn -0.994791 0.101310 -0.011245 -v 0.059703 0.074192 0.191534 -vn -0.813587 -0.362295 -0.454773 -v 0.059703 0.074119 0.191303 -vn -0.710390 0.019072 -0.703550 -v 0.059703 0.073146 0.192224 -vn -0.813579 -0.434496 -0.386397 -v 0.059703 0.072682 0.192664 -vn -0.994791 -0.016718 0.100554 -v 0.059703 0.072909 0.192749 -vn -0.994278 0.004733 0.106719 -v 0.059703 0.073206 0.192779 -vn -0.995324 0.017260 0.095035 -v 0.059703 0.073500 0.192723 -vn -0.811469 0.455691 -0.365874 -v 0.059703 0.073587 0.192689 -vn -0.513780 -0.437285 0.738114 -v 0.082409 0.072965 0.192297 -vn -0.518361 -0.253940 0.816588 -v 0.082405 0.072989 0.192305 -vn 0.129046 -0.275568 0.952580 -v 0.082103 0.072989 0.192305 -vn -0.562405 0.823566 0.073757 -v 0.082198 0.073754 0.191647 -vn -0.502234 0.848736 -0.165556 -v 0.082188 0.073743 0.191590 -vn 0.076942 0.971232 -0.225364 -v 0.082103 0.073743 0.191590 -vn -0.623933 0.711732 -0.322714 -v 0.082154 0.073670 0.191414 -vn 0.223486 0.717248 -0.660007 -v 0.082103 0.073595 0.191317 -vn -0.684292 0.513285 -0.517959 -v 0.082115 0.073508 0.191241 -vn -0.432498 0.516733 -0.738872 -v 0.082103 0.073452 0.191205 -vn -0.535627 0.789183 0.300489 -v 0.082240 0.073738 0.191889 -vn 0.106137 0.955251 0.276098 -v 0.082103 0.073735 0.191901 -vn -0.531735 0.638961 0.555866 -v 0.082281 0.073629 0.192104 -vn 0.090276 0.688111 0.719967 -v 0.082103 0.073573 0.192165 -vn -0.497178 0.504854 0.705646 -v 0.082296 0.073573 0.192165 -vn -0.528218 0.310766 0.790196 -v 0.082326 0.073438 0.192261 -vn 0.112163 0.227206 0.967366 -v 0.082103 0.073299 0.192313 -vn -0.493735 0.152373 0.856159 -v 0.082350 0.073299 0.192313 -vn -0.537208 -0.086948 0.838957 -v 0.082365 0.073210 0.192328 -vn -0.523350 -0.586804 0.617872 -v 0.082452 0.072755 0.192173 -vn -0.131175 -0.683656 0.717919 -v 0.082103 0.072724 0.192142 -vn -0.495980 -0.715304 0.492284 -v 0.082459 0.072724 0.192142 -vn 0.485984 -0.602867 0.632749 -v 0.082103 0.072701 0.192116 -vn 0.515101 -0.674513 0.528870 -v 0.082109 0.072678 0.192087 -vn -0.514507 -0.806105 0.292364 -v 0.082492 0.072614 0.191979 -vn 0.516716 -0.808413 0.281910 -v 0.082153 0.072575 0.191863 -vn -0.496059 -0.861191 0.110798 -v 0.082513 0.072576 0.191869 -vn -0.513389 -0.852414 -0.099106 -v 0.082537 0.072560 0.191737 -vn 0.505402 -0.862759 -0.014726 -v 0.082196 0.072570 0.191617 -vn -0.501043 -0.818509 -0.281068 -v 0.082567 0.072585 0.191559 -vn 0.500806 -0.839346 -0.211402 -v 0.082206 0.072585 0.191559 -vn -0.505359 -0.731517 -0.457707 -v 0.082577 0.072604 0.191503 -vn 0.513265 -0.768404 -0.382249 -v 0.082236 0.072661 0.191396 -vn -0.516681 -0.525208 -0.676164 -v 0.082620 0.072741 0.191300 -vn 0.495975 -0.660730 -0.563422 -v 0.082260 0.072747 0.191294 -vn 0.514533 -0.515428 -0.685267 -v 0.082281 0.072839 0.191222 -vn -0.515840 -0.266749 -0.814097 -v 0.082663 0.072949 0.191168 -vn 0.495932 -0.329652 -0.803356 -v 0.082314 0.073020 0.191146 -vn -0.495235 -0.091294 -0.863949 -v 0.082675 0.073020 0.191146 -vn 0.513795 -0.160559 -0.842755 -v 0.082321 0.073064 0.191137 -vn -0.509778 0.127517 -0.850803 -v 0.082703 0.073184 0.191130 -vn 0.503061 0.051340 -0.862725 -v 0.082364 0.073309 0.191148 -vn -0.487327 0.305471 -0.818046 -v 0.082730 0.073331 0.191154 -vn 0.505660 0.224555 -0.832996 -v 0.082368 0.073331 0.191154 -vn -0.511488 0.490432 -0.705589 -v 0.082748 0.073424 0.191191 -vn 0.507609 0.420364 -0.752082 -v 0.082408 0.073530 0.191258 -vn -0.507292 0.639567 -0.577589 -v 0.082784 0.073595 0.191317 -vn 0.493169 0.595914 -0.633775 -v 0.082422 0.073596 0.191317 -vn -0.502125 0.746013 -0.437419 -v 0.082788 0.073614 0.191338 -vn 0.513097 0.700971 -0.495350 -v 0.082448 0.073685 0.191439 -vn -0.510653 0.828280 -0.230622 -v 0.082830 0.073733 0.191551 -vn 0.494349 0.811877 -0.310603 -v 0.082477 0.073743 0.191590 -vn -0.496560 0.866116 -0.057202 -v 0.082838 0.073743 0.191590 -vn 0.512791 0.849356 -0.125061 -v 0.082492 0.073758 0.191677 -vn -0.516315 0.842102 0.155831 -v 0.082875 0.073756 0.191796 -vn 0.497778 0.861857 0.097058 -v 0.082531 0.073735 0.191901 -vn -0.496494 0.802410 0.331109 -v 0.082892 0.073735 0.191901 -vn 0.512037 0.819964 0.255886 -v 0.082533 0.073730 0.191917 -vn -0.509815 0.690897 0.512591 -v 0.082914 0.073683 0.192023 -vn 0.506726 0.736671 0.447821 -v 0.082575 0.073609 0.192128 -vn -0.496642 0.564503 0.659305 -v 0.082946 0.073572 0.192165 -vn 0.500246 0.620957 0.603462 -v 0.082585 0.073573 0.192165 -vn -0.508777 0.391907 0.766521 -v 0.082958 0.073521 0.192209 -vn 0.509692 0.462120 0.725713 -v 0.082620 0.073410 0.192275 -vn -0.516839 0.112521 0.848655 -v 0.083000 0.073302 0.192313 -vn 0.498030 0.275420 0.822259 -v 0.082639 0.073299 0.192313 -vn 0.516890 0.098236 0.850397 -v 0.082659 0.073177 0.192329 -vn -0.512385 -0.180528 0.839566 -v 0.083041 0.073061 0.192321 -vn 0.495177 -0.116361 0.860964 -v 0.082693 0.072989 0.192305 -vn -0.494541 -0.362987 0.789728 -v 0.083055 0.072989 0.192305 -vn 0.511564 -0.293008 0.807743 -v 0.082704 0.072933 0.192285 -vn -0.513161 -0.541866 0.665618 -v 0.083086 0.072830 0.192231 -vn 0.516640 -0.543028 0.661969 -v 0.082746 0.072732 0.192150 -vn -0.490133 -0.670739 0.556669 -v 0.083109 0.072724 0.192142 -vn -0.509736 -0.777300 0.368747 -v 0.083125 0.072661 0.192064 -vn 0.510647 -0.738589 0.440144 -v 0.082787 0.072600 0.191947 -vn -0.503655 -0.846278 0.173627 -v 0.083163 0.072576 0.191869 -vn 0.493273 -0.833106 0.250233 -v 0.082802 0.072576 0.191869 -vn -0.504743 -0.863227 -0.008531 -v 0.083169 0.072569 0.191835 -vn 0.509786 -0.857930 0.063830 -v 0.082832 0.072561 0.191701 -vn -0.512918 -0.830591 -0.216874 -v 0.083212 0.072576 0.191591 -vn 0.495445 -0.855116 -0.152683 -v 0.082856 0.072585 0.191559 -vn -0.496557 -0.780901 -0.378979 -v 0.083217 0.072585 0.191559 -vn 0.515738 -0.794000 -0.321837 -v 0.082871 0.072619 0.191470 -vn -0.513025 -0.652236 -0.558026 -v 0.083252 0.072677 0.191374 -vn 0.497510 -0.698449 -0.514445 -v 0.082910 0.072747 0.191294 -vn -0.494460 -0.521778 -0.695167 -v 0.083271 0.072747 0.191294 -vn 0.509975 -0.576658 -0.638272 -v 0.082915 0.072769 0.191274 -vn -0.513322 -0.331515 -0.791580 -v 0.083297 0.072862 0.191209 -vn 0.503340 -0.396125 -0.767941 -v 0.082958 0.072984 0.191156 -vn -0.499042 -0.161678 -0.851362 -v 0.083325 0.073020 0.191146 -vn 0.505741 -0.224783 -0.832886 -v 0.082964 0.073020 0.191146 -vn -0.506886 0.041903 -0.860994 -v 0.083336 0.073088 0.191134 -vn 0.513070 -0.033782 -0.857682 -v 0.082998 0.073223 0.191133 -vn -0.516986 0.336060 -0.787267 -v 0.083380 0.073333 0.191155 -vn 0.484951 0.187320 -0.854244 -v 0.083018 0.073331 0.191154 -vn 0.510037 0.349454 -0.785967 -v 0.083043 0.073459 0.191210 -vn -0.514903 0.579199 -0.631983 -v 0.083423 0.073548 0.191272 -vn 0.494960 0.544147 -0.677436 -v 0.083072 0.073595 0.191317 -vn -0.495037 0.706506 -0.505755 -v 0.083434 0.073596 0.191317 -vn 0.515043 0.663689 -0.542446 -v 0.083083 0.073639 0.191368 -vn -0.510207 0.804028 -0.305333 -v 0.083463 0.073696 0.191460 -vn 0.516980 0.805571 -0.289459 -v 0.083127 0.073744 0.191591 -vn -0.484851 0.863225 -0.140576 -v 0.083488 0.073743 0.191590 -vn -0.513108 0.854531 0.080609 -v 0.083508 0.073759 0.191699 -vn 0.506621 0.862129 0.008279 -v 0.083170 0.073750 0.191837 -vn -0.505880 0.819412 0.269536 -v 0.083542 0.073735 0.191901 -vn 0.499973 0.840352 0.209367 -v 0.083181 0.073735 0.191901 -vn -0.503484 0.745590 0.436576 -v 0.083548 0.073723 0.191936 -vn 0.513203 0.771144 0.376775 -v 0.083210 0.073661 0.192059 -vn -0.509977 0.606751 0.609735 -v 0.083591 0.073594 0.192143 -vn 0.494345 0.663649 0.561421 -v 0.083235 0.073572 0.192165 -vn -0.497500 0.476645 0.724778 -v 0.083596 0.073573 0.192165 -vn 0.512867 0.519047 0.683782 -v 0.083255 0.073485 0.192234 -vn -0.515561 0.279567 0.809963 -v 0.083635 0.073391 0.192283 -vn 0.496123 0.333014 0.801850 -v 0.083289 0.073299 0.192313 -vn -0.495331 0.108049 0.861958 -v 0.083650 0.073299 0.192313 -vn 0.513288 0.166025 0.842004 -v 0.083295 0.073261 0.192321 -vn -0.510003 -0.108441 0.853310 -v 0.083674 0.073158 0.192330 -vn 0.504159 -0.044734 0.862452 -v 0.083338 0.073016 0.192312 -vn -0.494618 -0.293242 0.818146 -v 0.083705 0.072989 0.192305 -vn 0.504930 -0.222132 0.834088 -v 0.083343 0.072989 0.192305 -vn -0.510662 -0.476490 0.715669 -v 0.083719 0.072916 0.192278 -vn 0.509481 -0.415360 0.753594 -v 0.083382 0.072794 0.192205 -vn -0.516980 -0.686907 0.510774 -v 0.083760 0.072720 0.192137 -vn 0.492670 -0.594404 0.635579 -v 0.083397 0.072724 0.192142 -vn 0.513370 -0.697241 0.500306 -v 0.083422 0.072637 0.192025 -vn -0.511605 -0.820943 0.253598 -v 0.083801 0.072594 0.191930 -vn 0.493988 -0.810814 0.313937 -v 0.083452 0.072576 0.191869 -vn -0.494843 -0.865862 0.073578 -v 0.083813 0.072576 0.191869 -vn 0.512633 -0.849374 0.125588 -v 0.083466 0.072563 0.191788 -vn -0.517061 -0.844240 -0.141091 -v 0.083846 0.072562 0.191685 -vn 0.517350 -0.838558 -0.170791 -v 0.083508 0.072588 0.191548 -vn 0.517164 0.536755 -0.666660 -v 0.083720 0.073585 0.191306 -vn -0.513525 0.527388 -0.676871 -v 0.084057 0.073470 0.191216 -vn 0.511082 0.287695 -0.809955 -v 0.083678 0.073381 0.191172 -vn -0.493850 0.347576 -0.797059 -v 0.084030 0.073331 0.191154 -vn 0.495521 0.112611 -0.861265 -v 0.083668 0.073331 0.191154 -vn -0.512376 0.164602 -0.842838 -v 0.084012 0.073236 0.191134 -vn 0.515691 -0.102124 -0.850667 -v 0.083633 0.073137 0.191130 -vn -0.497434 -0.055447 -0.865728 -v 0.083975 0.073020 0.191146 -vn 0.496563 -0.278777 -0.822015 -v 0.083614 0.073020 0.191146 -vn -0.512321 -0.218228 -0.830604 -v 0.083972 0.072997 0.191152 -vn 0.509765 -0.467444 -0.722243 -v 0.083594 0.072905 0.191186 -vn -0.506485 -0.414051 -0.756330 -v 0.083929 0.072781 0.191264 -vn 0.499530 -0.622759 -0.602196 -v 0.083560 0.072747 0.191294 -vn -0.502116 -0.570869 -0.649606 -v 0.083921 0.072747 0.191294 -vn 0.508125 -0.739276 -0.441905 -v 0.083549 0.072707 0.191336 -vn -0.509741 -0.702288 -0.496947 -v 0.083885 0.072626 0.191456 -vn -0.498630 -0.807778 -0.314425 -v 0.083867 0.072585 0.191559 -vn 0.517828 -0.802283 0.296977 -v 0.084101 0.072577 0.191874 -vn -0.493016 -0.856814 0.151013 -v 0.084463 0.072576 0.191869 -vn -0.510540 -0.796830 0.323126 -v 0.084434 0.072635 0.192020 -vn 0.514629 -0.660545 0.546660 -v 0.084057 0.072684 0.192095 -vn -0.494831 -0.696784 0.519264 -v 0.084409 0.072724 0.192142 -vn 0.494999 -0.541220 0.679747 -v 0.084047 0.072724 0.192142 -vn -0.515151 -0.566916 0.642826 -v 0.084395 0.072789 0.192201 -vn 0.512738 -0.348725 0.784532 -v 0.084017 0.072865 0.192252 -vn -0.498851 -0.395113 0.771384 -v 0.084355 0.072989 0.192305 -vn 0.495455 -0.171684 0.851498 -v 0.083993 0.072989 0.192305 -vn -0.509536 -0.234551 0.827864 -v 0.084351 0.073009 0.192310 -vn 0.513061 0.039926 0.857423 -v 0.083972 0.073102 0.192327 -vn -0.505128 -0.016798 0.862881 -v 0.084308 0.073253 0.192322 -vn 0.505258 0.227067 0.832560 -v 0.083939 0.073299 0.192313 -vn -0.504542 0.172162 0.846048 -v 0.084300 0.073299 0.192313 -vn 0.504615 0.401777 0.764159 -v 0.083932 0.073341 0.192302 -vn -0.513198 0.348548 0.784310 -v 0.084268 0.073477 0.192239 -vn 0.509708 0.581105 0.634440 -v 0.083889 0.073555 0.192182 -vn -0.495167 0.535386 0.684231 -v 0.084246 0.073573 0.192165 -vn 0.498322 0.700483 0.510880 -v 0.083885 0.073572 0.192165 -vn -0.512741 0.663322 0.545069 -v 0.084223 0.073656 0.192067 -vn 0.515190 0.795731 0.318420 -v 0.083845 0.073703 0.191984 -vn -0.495314 0.788271 0.365094 -v 0.084192 0.073735 0.191901 -vn 0.494799 0.856078 0.149348 -v 0.083831 0.073735 0.191901 -vn -0.514227 0.835182 0.195040 -v 0.084183 0.073748 0.191847 -vn 0.510237 0.857155 -0.070315 -v 0.083806 0.073759 0.191752 -vn -0.502470 0.864442 -0.016238 -v 0.084140 0.073746 0.191602 -vn 0.492582 0.832908 -0.252243 -v 0.083777 0.073743 0.191590 -vn -0.507338 0.841897 -0.183898 -v 0.084138 0.073743 0.191590 -vn 0.512241 0.734470 -0.445154 -v 0.083761 0.073717 0.191508 -vn -0.509415 0.768952 -0.386275 -v 0.084096 0.073646 0.191377 -vn -0.497918 0.660157 -0.562379 -v 0.084084 0.073595 0.191317 -vn -0.512562 -0.856407 -0.062035 -v 0.084479 0.072562 0.191783 -vn 0.508124 -0.861283 -0.001511 -v 0.084144 0.072569 0.191628 -vn -0.509452 -0.820826 -0.258270 -v 0.084517 0.072585 0.191559 -vn 0.499466 -0.841117 -0.207501 -v 0.084156 0.072585 0.191559 -vn -0.501790 -0.758703 -0.415423 -v 0.084520 0.072589 0.191544 -vn 0.513502 -0.773699 -0.371088 -v 0.084184 0.072655 0.191405 -vn -0.511054 -0.623286 -0.591894 -v 0.084561 0.072710 0.191333 -vn 0.493768 -0.666178 -0.558927 -v 0.084210 0.072747 0.191294 -vn -0.495657 -0.490460 -0.716779 -v 0.084571 0.072747 0.191294 -vn 0.512269 -0.522532 -0.681572 -v 0.084229 0.072830 0.191228 -vn -0.515385 -0.294623 -0.804721 -v 0.084606 0.072908 0.191185 -vn 0.496810 -0.336424 -0.799999 -v 0.084264 0.073020 0.191146 -vn -0.496426 -0.124762 -0.859067 -v 0.084625 0.073020 0.191146 -vn 0.513021 -0.171012 -0.841168 -v 0.084269 0.073054 0.191139 -vn -0.510064 0.089304 -0.855488 -v 0.084645 0.073139 0.191130 -vn 0.505686 0.038240 -0.861870 -v 0.084312 0.073298 0.191146 -vn -0.500703 0.281395 -0.818604 -v 0.084680 0.073331 0.191154 -vn 0.504433 0.220449 -0.834835 -v 0.084318 0.073331 0.191154 -vn -0.508505 0.457052 -0.729744 -v 0.084689 0.073383 0.191172 -vn 0.509587 0.409722 -0.756604 -v 0.084356 0.073522 0.191251 -vn -0.518041 0.667400 -0.534987 -v 0.084731 0.073585 0.191306 -vn 0.491146 0.594354 -0.636804 -v 0.084372 0.073596 0.191317 -vn 0.513946 0.693310 -0.505154 -v 0.084396 0.073680 0.191430 -vn -0.512728 0.812822 -0.276462 -v 0.084772 0.073717 0.191507 -vn 0.494147 0.809315 -0.317534 -v 0.084427 0.073743 0.191590 -vn -0.493842 0.864834 -0.090457 -v 0.084788 0.073743 0.191590 -vn 0.512255 0.848763 -0.131134 -v 0.084440 0.073756 0.191666 -vn -0.514003 0.848199 0.127907 -v 0.084817 0.073759 0.191752 -vn 0.518041 0.839684 0.162983 -v 0.084482 0.073733 0.191907 -vn -0.495013 0.817663 0.293921 -v 0.084842 0.073735 0.191901 -vn -0.509523 0.713386 0.481109 -v 0.084856 0.073704 0.191983 -vn 0.509790 0.741812 0.435693 -v 0.084523 0.073616 0.192119 -vn -0.506308 0.577571 0.640363 -v 0.084896 0.073572 0.192165 -vn 0.499160 0.624246 0.600963 -v 0.084535 0.073573 0.192165 -vn -0.504337 0.435933 0.745390 -v 0.084900 0.073556 0.192180 -vn 0.510225 0.472754 0.718453 -v 0.084568 0.073419 0.192271 -vn -0.513751 0.239762 0.823756 -v 0.084943 0.073344 0.192301 -vn 0.495718 0.282256 0.821337 -v 0.084589 0.073299 0.192313 -vn -0.496033 0.070908 0.865403 -v 0.084950 0.073299 0.192313 -vn 0.515193 0.105930 0.850503 -v 0.084607 0.073188 0.192329 -vn -0.512254 -0.147745 0.846030 -v 0.084983 0.073106 0.192327 -vn 0.496281 -0.108466 0.861360 -v 0.084643 0.072989 0.192305 -vn -0.494171 -0.331506 0.803679 -v 0.085005 0.072989 0.192305 -vn 0.510915 -0.282485 0.811892 -v 0.084652 0.072944 0.192289 -vn -0.513575 -0.512690 0.688033 -v 0.085028 0.072869 0.192254 -vn 0.502740 -0.483111 0.716838 -v 0.084694 0.072739 0.192157 -vn -0.503271 -0.649929 0.569483 -v 0.085059 0.072724 0.192142 -vn 0.509170 -0.614033 0.603084 -v 0.084697 0.072724 0.192142 -vn -0.506992 -0.760321 0.406044 -v 0.085068 0.072687 0.192099 -vn 0.512554 -0.733165 0.446942 -v 0.084735 0.072605 0.191957 -vn -0.517988 -0.846918 0.120079 -v 0.085111 0.072579 0.191880 -vn 0.491921 -0.832882 0.253615 -v 0.084752 0.072576 0.191869 -vn 0.511012 -0.856127 0.076902 -v 0.084780 0.072560 0.191712 -vn -0.515613 -0.839235 -0.172704 -v 0.085154 0.072568 0.191634 -vn 0.494657 -0.856811 -0.145567 -v 0.084806 0.072585 0.191559 -vn -0.494767 -0.795287 -0.350321 -v 0.085167 0.072585 0.191559 -vn 0.515071 -0.797115 -0.315134 -v 0.084819 0.072614 0.191480 -vn -0.509603 -0.673360 -0.535623 -v 0.085194 0.072651 0.191411 -vn 0.499560 -0.702420 -0.506997 -v 0.084860 0.072747 0.191294 -vn -0.488881 -0.557661 -0.670828 -v 0.085221 0.072747 0.191294 -vn 0.509650 -0.585111 -0.630795 -v 0.084863 0.072761 0.191281 -vn -0.512821 -0.365524 -0.776792 -v 0.085239 0.072823 0.191233 -vn 0.506141 -0.407499 -0.760109 -v 0.084906 0.072974 0.191159 -vn -0.508679 -0.182755 -0.841336 -v 0.085275 0.073020 0.191146 -vn 0.505100 -0.228987 -0.832129 -v 0.084914 0.073020 0.191146 -vn -0.503456 -0.007994 -0.863984 -v 0.085279 0.073045 0.191141 -vn 0.513378 -0.046157 -0.856921 -v 0.084946 0.073212 0.191132 -vn -0.510784 0.210947 -0.833427 -v 0.085322 0.073288 0.191144 -vn 0.494568 0.168288 -0.852691 -v 0.084968 0.073331 0.191154 -vn -0.496886 0.381905 -0.779264 -v 0.085330 0.073331 0.191154 -vn 0.512145 0.345148 -0.786499 -v 0.084991 0.073450 0.191204 -vn -0.515096 0.554873 -0.653293 -v 0.085366 0.073513 0.191245 -vn 0.495470 0.537845 -0.682079 -v 0.085022 0.073595 0.191317 -vn -0.495538 0.686280 -0.532411 -v 0.085384 0.073596 0.191317 -vn 0.514488 0.657393 -0.550579 -v 0.085031 0.073632 0.191360 -vn -0.510684 0.789318 -0.340850 -v 0.085405 0.073674 0.191420 -vn 0.519170 0.798613 -0.304433 -v 0.085075 0.073741 0.191580 -vn -0.499896 0.850914 -0.161397 -v 0.085438 0.073743 0.191590 -vn -0.511526 0.858236 0.042084 -v 0.085450 0.073755 0.191654 -vn 0.509547 0.860424 -0.005650 -v 0.085118 0.073752 0.191826 -vn -0.518827 0.791411 0.323244 -v 0.085491 0.073737 0.191895 -vn 0.499075 0.841708 0.206037 -v 0.085131 0.073735 0.191901 -vn 0.514141 0.776046 0.365255 -v 0.085158 0.073667 0.192050 -vn -0.512335 0.639311 0.573407 -v 0.085532 0.073625 0.192109 -vn 0.493626 0.668792 0.555924 -v 0.085185 0.073572 0.192165 -vn -0.494395 0.504458 0.707881 -v 0.085546 0.073573 0.192165 -vn 0.512066 0.525699 0.679286 -v 0.085203 0.073494 0.192228 -vn -0.512231 0.307006 0.802101 -v 0.085577 0.073432 0.192264 -vn 0.497758 0.340153 0.797830 -v 0.085239 0.073299 0.192313 -vn -0.490213 0.150297 0.858547 -v 0.085600 0.073299 0.192313 -vn 0.513074 0.175842 0.840140 -v 0.085244 0.073271 0.192319 -vn -0.509942 -0.070087 0.857349 -v 0.085616 0.073203 0.192328 -vn 0.507348 -0.031100 0.861180 -v 0.085286 0.073027 0.192315 -vn -0.505541 -0.270025 0.819460 -v 0.085655 0.072989 0.192305 -vn 0.504408 -0.218461 0.835373 -v 0.085293 0.072989 0.192305 -vn -0.506382 -0.437259 0.743224 -v 0.085660 0.072959 0.192295 -vn 0.510042 -0.403856 0.759445 -v 0.085330 0.072802 0.192212 -vn -0.513491 -0.600286 0.613175 -v 0.085703 0.072750 0.192168 -vn 0.487282 -0.593728 0.640347 -v 0.085347 0.072724 0.192142 -vn -0.497148 -0.717601 0.487743 -v 0.085709 0.072724 0.192142 -vn 0.511702 -0.692634 0.508349 -v 0.085370 0.072643 0.192034 -vn -0.512033 -0.809112 0.288374 -v 0.085743 0.072611 0.191973 -vn 0.494727 -0.807415 0.321443 -v 0.085402 0.072576 0.191869 -vn -0.493803 -0.862904 0.107497 -v 0.085763 0.072576 0.191869 -vn 0.512162 -0.847975 0.136484 -v 0.085414 0.072564 0.191799 -vn -0.514214 -0.850622 -0.109664 -v 0.085788 0.072560 0.191730 -vn 0.519273 -0.840435 -0.154998 -v 0.085456 0.072585 0.191557 -vn -0.502115 -0.817518 -0.282037 -v 0.085817 0.072585 0.191559 -vn -0.509064 -0.724366 -0.464917 -v 0.085828 0.072607 0.191497 -vn 0.511694 -0.744356 -0.429072 -v 0.085497 0.072700 0.191344 -vn -0.519393 -0.515432 -0.681587 -v 0.085871 0.072747 0.191295 -vn 0.499131 -0.625376 -0.599811 -v 0.085510 0.072747 0.191294 -vn 0.511003 -0.478016 -0.714407 -v 0.085542 0.072896 0.191191 -vn -0.515352 -0.261180 -0.816209 -v 0.085914 0.072955 0.191166 -vn 0.495320 -0.286028 -0.820272 -v 0.085564 0.073020 0.191146 -vn -0.495211 -0.086806 -0.864425 -v 0.085925 0.073020 0.191146 -vn 0.515048 -0.109496 -0.850139 -v 0.085582 0.073126 0.191131 -vn -0.508599 0.135244 -0.850315 -v 0.085954 0.073191 0.191130 -vn 0.497420 0.103925 -0.861263 -v 0.085618 0.073331 0.191154 -vn -0.484617 0.307147 -0.819028 -v 0.085980 0.073331 0.191154 -vn 0.511049 0.277475 -0.813534 -v 0.085626 0.073371 0.191168 -vn -0.513343 0.497788 -0.699061 -v 0.085999 0.073431 0.191194 -vn 0.504266 0.476694 -0.720055 -v 0.085668 0.073577 0.191298 -vn -0.508142 0.640285 -0.576044 -v 0.086034 0.073595 0.191317 -vn 0.509316 0.612598 -0.604418 -v 0.085672 0.073596 0.191317 -vn -0.505352 0.749291 -0.427999 -v 0.086039 0.073619 0.191343 -vn 0.512901 0.729706 -0.452175 -v 0.085709 0.073713 0.191497 -vn -0.510742 0.829928 -0.224414 -v 0.086082 0.073735 0.191557 -vn 0.488454 0.833939 -0.256822 -v 0.085727 0.073743 0.191590 -vn -0.498434 0.865409 -0.051282 -v 0.086088 0.073743 0.191590 -vn 0.509062 0.856964 -0.080431 -v 0.085754 0.073760 0.191741 -vn -0.515138 0.841979 0.160325 -v 0.086126 0.073755 0.191803 -vn 0.497939 0.855250 0.143541 -v 0.085781 0.073735 0.191901 -vn -0.497397 0.799484 0.336781 -v 0.086142 0.073735 0.191901 -vn -0.518059 0.677285 0.522398 -v 0.086165 0.073680 0.192029 -vn 0.522502 0.793512 0.311977 -v 0.085793 0.073708 0.191975 -vn -0.501582 0.564697 0.655388 -v 0.086196 0.073572 0.192165 -vn 0.522560 0.642821 0.560100 -v 0.085837 0.073563 0.192174 -vn -0.512219 0.381811 0.769319 -v 0.086210 0.073515 0.192213 -vn 0.508262 0.413299 0.755548 -v 0.085880 0.073351 0.192298 -vn -0.519992 0.101829 0.848080 -v 0.086251 0.073296 0.192314 -vn 0.505367 0.230734 0.831484 -v 0.085889 0.073299 0.192313 -vn 0.514047 0.052411 0.856159 -v 0.085921 0.073113 0.192328 -vn -0.512198 -0.186761 0.838316 -v 0.086292 0.073054 0.192320 -vn 0.494229 -0.164362 0.853653 -v 0.085943 0.072989 0.192305 -vn -0.495408 -0.367626 0.787034 -v 0.086305 0.072989 0.192305 -vn 0.511955 -0.341697 0.788128 -v 0.085965 0.072875 0.192258 -vn -0.511431 -0.547309 0.662489 -v 0.086337 0.072825 0.192227 -vn 0.498634 -0.534671 0.682269 -v 0.085997 0.072724 0.192142 -vn -0.500422 -0.776796 -0.382316 -v 0.086467 0.072585 0.191559 -vn -0.515957 -0.826793 -0.224056 -v 0.086463 0.072578 0.191585 -vn 0.510672 -0.859679 0.012857 -v 0.086092 0.072567 0.191638 -vn -0.509731 -0.860134 -0.018542 -v 0.086420 0.072568 0.191828 -vn 0.526948 -0.788420 0.317365 -v 0.086049 0.072580 0.191885 -vn -0.510193 -0.841943 0.175599 -v 0.086413 0.072576 0.191869 -vn 0.521569 -0.651347 0.551101 -v 0.086006 0.072691 0.192104 -vn -0.519068 -0.780247 0.348975 -v 0.086376 0.072658 0.192058 -vn -0.487386 -0.673515 0.555727 -v 0.086359 0.072724 0.192142 -vn 0.497091 -0.843607 -0.203049 -v 0.086106 0.072585 0.191559 -vn 0.512744 -0.778348 -0.362310 -v 0.086132 0.072649 0.191414 -vn -0.512195 -0.649660 -0.561781 -v 0.086503 0.072681 0.191368 -vn 0.493989 -0.671476 -0.552354 -v 0.086160 0.072747 0.191294 -vn -0.494001 -0.518312 -0.698080 -v 0.086521 0.072747 0.191294 -vn 0.512288 -0.528522 -0.676924 -v 0.086177 0.072821 0.191234 -vn -0.513078 -0.323628 -0.794994 -v 0.086548 0.072868 0.191206 -vn 0.500660 -0.342626 -0.794951 -v 0.086214 0.073020 0.191146 -vn -0.499086 -0.159735 -0.851703 -v 0.086575 0.073020 0.191146 -vn -0.510303 0.052378 -0.858398 -v 0.086588 0.073095 0.191133 -vn 0.515656 -0.182239 -0.837191 -v 0.086218 0.073043 0.191141 -vn 0.509954 0.024066 -0.859865 -v 0.086260 0.073287 0.191143 -vn -0.525897 0.349793 -0.775292 -v 0.086631 0.073339 0.191157 -vn 0.509068 0.219822 -0.832182 -v 0.086268 0.073331 0.191154 -vn -0.521269 0.580469 -0.625567 -v 0.086674 0.073553 0.191277 -vn 0.517953 0.389948 -0.761357 -v 0.086304 0.073513 0.191245 -vn -0.498233 0.707244 -0.501567 -v 0.086684 0.073596 0.191317 -vn 0.498465 0.577869 -0.646220 -v 0.086322 0.073596 0.191317 -vn 0.514812 0.691460 -0.506805 -v 0.086344 0.073674 0.191420 -vn -0.511880 0.803243 -0.304598 -v 0.086714 0.073699 0.191466 -vn 0.495674 0.805153 -0.325630 -v 0.086377 0.073743 0.191590 -vn -0.494831 0.860034 -0.124436 -v 0.086738 0.073743 0.191590 -vn 0.512467 0.846955 -0.141580 -v 0.086388 0.073755 0.191655 -vn -0.514107 0.852853 0.091303 -v 0.086759 0.073759 0.191706 -vn 0.521015 0.840821 0.146844 -v 0.086430 0.073736 0.191897 -vn 0.500027 0.624668 0.599802 -v 0.086485 0.073573 0.192165 -vn -0.503543 0.465249 0.728002 -v 0.086846 0.073573 0.192165 -vn -0.510909 0.602124 0.613529 -v 0.086842 0.073590 0.192148 -vn 0.512223 0.747808 0.422387 -v 0.086471 0.073623 0.192111 -vn -0.507850 0.737859 0.444581 -v 0.086799 0.073721 0.191942 -vn -0.507721 0.818011 0.270328 -v 0.086792 0.073735 0.191901 -vn -0.521027 0.273886 0.808404 -v 0.086886 0.073385 0.192286 -vn 0.515956 0.483401 0.707187 -v 0.086516 0.073429 0.192266 -vn -0.497646 0.104975 0.861005 -v 0.086900 0.073299 0.192313 -vn 0.497345 0.291843 0.816992 -v 0.086539 0.073299 0.192313 -vn 0.515356 0.112684 0.849536 -v 0.086556 0.073199 0.192328 -vn -0.509496 -0.116437 0.852558 -v 0.086925 0.073151 0.192330 -vn 0.498831 -0.098919 0.861036 -v 0.086593 0.072989 0.192305 -vn -0.493225 -0.294795 0.818429 -v 0.086955 0.072989 0.192305 -vn 0.511523 -0.272416 0.814944 -v 0.086600 0.072954 0.192293 -vn -0.513176 -0.484855 0.708213 -v 0.086970 0.072910 0.192275 -vn 0.506924 -0.469660 0.722805 -v 0.086642 0.072746 0.192164 -vn -0.521579 -0.691141 0.500279 -v 0.087011 0.072715 0.192133 -vn 0.510045 -0.610899 0.605522 -v 0.086647 0.072724 0.192142 -vn 0.513608 -0.725998 0.457311 -v 0.086683 0.072609 0.191967 -vn -0.512296 -0.822249 0.247911 -v 0.087053 0.072592 0.191924 -vn 0.486198 -0.834368 0.259695 -v 0.086702 0.072576 0.191869 -vn -0.496807 -0.865269 0.067033 -v 0.087063 0.072576 0.191869 -vn 0.508595 -0.856836 0.084636 -v 0.086728 0.072560 0.191723 -vn -0.515036 -0.844906 -0.144469 -v 0.087097 0.072562 0.191678 -vn 0.497480 -0.856419 -0.138061 -v 0.086756 0.072585 0.191559 -vn -0.501406 -0.049086 -0.863818 -v 0.087225 0.073020 0.191146 -vn -0.515020 -0.211933 -0.830565 -v 0.087223 0.073003 0.191150 -vn 0.509150 -0.419584 -0.751476 -v 0.086855 0.072964 0.191163 -vn -0.510612 -0.403133 -0.759447 -v 0.087181 0.072786 0.191260 -vn 0.524090 -0.647188 -0.553604 -v 0.086811 0.072753 0.191289 -vn -0.506959 -0.570494 -0.646165 -v 0.087171 0.072747 0.191294 -vn 0.520877 -0.795630 -0.309291 -v 0.086768 0.072610 0.191490 -vn -0.516265 -0.690379 -0.506801 -v 0.087136 0.072629 0.191450 -vn -0.498082 -0.805739 -0.320466 -v 0.087117 0.072585 0.191559 -vn 0.504110 -0.233316 -0.831527 -v 0.086864 0.073020 0.191146 -vn 0.513507 -0.056892 -0.856198 -v 0.086895 0.073201 0.191131 -vn -0.512703 0.168372 -0.841894 -v 0.087263 0.073243 0.191135 -vn 0.494303 0.159976 -0.854443 -v 0.086918 0.073331 0.191154 -vn -0.494628 0.352632 -0.794351 -v 0.087280 0.073331 0.191154 -vn 0.512196 0.338369 -0.789406 -v 0.086939 0.073440 0.191199 -vn -0.512449 0.532757 -0.673473 -v 0.087308 0.073476 0.191220 -vn 0.498847 0.530141 -0.685640 -v 0.086972 0.073595 0.191317 -vn -0.495852 0.662411 -0.561555 -v 0.087334 0.073595 0.191317 -vn -0.511061 0.772749 -0.376397 -v 0.087348 0.073650 0.191383 -vn 0.517016 0.648964 -0.558158 -v 0.086980 0.073626 0.191351 -vn 0.506925 0.769635 -0.388188 -v 0.087023 0.073738 0.191569 -vn -0.509074 0.841102 -0.182734 -v 0.087388 0.073743 0.191590 -vn 0.508878 0.832673 -0.218400 -v 0.087027 0.073743 0.191590 -vn -0.506642 0.862142 -0.004986 -v 0.087391 0.073748 0.191609 -vn 0.511081 0.859388 -0.015755 -v 0.087067 0.073754 0.191816 -vn -0.517213 0.831896 0.201094 -v 0.087434 0.073747 0.191853 -vn -0.498712 0.784133 0.369353 -v 0.087442 0.073735 0.191901 -vn 0.495157 0.845330 0.200592 -v 0.087081 0.073735 0.191901 -vn 0.512338 0.780219 0.358843 -v 0.087106 0.073673 0.192040 -vn -0.512214 0.660868 0.548535 -v 0.087474 0.073652 0.192073 -vn 0.494749 0.674223 0.548313 -v 0.087135 0.073572 0.192165 -vn -0.494633 0.531714 0.687473 -v 0.087496 0.073573 0.192165 -vn 0.512928 0.531013 0.674485 -v 0.087151 0.073503 0.192222 -vn -0.513615 0.340251 0.787673 -v 0.087519 0.073472 0.192242 -vn 0.501510 0.347335 0.792367 -v 0.087189 0.073299 0.192313 -vn -0.505543 0.170531 0.845781 -v 0.087550 0.073299 0.192313 -vn -0.509029 -0.028230 0.860286 -v 0.087559 0.073247 0.192323 -vn 0.515104 0.185342 0.836849 -v 0.087192 0.073282 0.192317 -vn 0.510538 -0.016294 0.859701 -v 0.087234 0.073038 0.192317 -vn -0.523661 -0.317379 0.790601 -v 0.087602 0.073002 0.192309 -vn 0.506767 -0.216811 0.834374 -v 0.087243 0.072989 0.192305 -vn -0.520323 -0.564582 0.640711 -v 0.087646 0.072783 0.192197 -vn 0.514884 -0.389239 0.763798 -v 0.087278 0.072811 0.192218 -vn -0.497336 -0.698512 0.514526 -v 0.087659 0.072724 0.192142 -vn 0.498130 -0.574882 0.649136 -v 0.087297 0.072724 0.192142 -vn 0.515184 -0.689339 0.509310 -v 0.087318 0.072649 0.192043 -vn -0.509005 -0.799717 0.318382 -v 0.087685 0.072631 0.192014 -vn 0.496973 -0.802534 0.330086 -v 0.087352 0.072576 0.191869 -vn -0.489716 -0.858996 0.149346 -v 0.087713 0.072576 0.191869 -vn 0.513167 -0.845700 0.146465 -v 0.087362 0.072565 0.191810 -vn -0.513755 -0.854846 -0.072766 -v 0.087730 0.072562 0.191776 -vn 0.523278 -0.840831 -0.138504 -v 0.087404 0.072582 0.191567 -vn 0.496894 -0.628577 -0.598321 -v 0.087460 0.072747 0.191294 -vn -0.500617 -0.480365 -0.720161 -v 0.087821 0.072747 0.191294 -vn -0.512761 -0.618863 -0.595051 -v 0.087813 0.072714 0.191328 -vn 0.513110 -0.750894 -0.415784 -v 0.087446 0.072693 0.191353 -vn -0.506606 -0.750684 -0.424056 -v 0.087771 0.072592 0.191537 -vn -0.511949 -0.819157 -0.258632 -v 0.087767 0.072585 0.191559 -vn -0.519256 -0.289755 -0.803999 -v 0.087857 0.072914 0.191182 -vn 0.513304 -0.485994 -0.707339 -v 0.087490 0.072886 0.191196 -vn -0.499234 -0.119098 -0.858243 -v 0.087875 0.073020 0.191146 -vn 0.498743 -0.294492 -0.815187 -v 0.087514 0.073020 0.191146 -vn -0.513858 0.099745 -0.852057 -v 0.087896 0.073146 0.191130 -vn 0.519552 -0.115909 -0.846540 -v 0.087530 0.073115 0.191131 -vn -0.502672 0.280697 -0.817637 -v 0.087930 0.073331 0.191154 -vn 0.502699 0.090661 -0.859694 -v 0.087568 0.073331 0.191154 -vn 0.512333 0.267640 -0.816017 -v 0.087574 0.073360 0.191164 -vn -0.511703 0.465934 -0.721849 -v 0.087941 0.073389 0.191175 -vn 0.507625 0.462753 -0.726758 -v 0.087617 0.073569 0.191291 -vn -0.523588 0.671644 -0.524165 -v 0.087982 0.073590 0.191311 -vn 0.510489 0.609863 -0.606191 -v 0.087622 0.073596 0.191317 -vn 0.514641 0.722149 -0.462217 -v 0.087657 0.073709 0.191487 -vn -0.514146 0.813654 -0.271331 -v 0.088023 0.073720 0.191514 -vn 0.484320 0.834439 -0.262956 -v 0.087677 0.073743 0.191590 -vn -0.495780 0.864430 -0.083443 -v 0.088038 0.073743 0.191590 -vn 0.508545 0.856468 -0.088573 -v 0.087702 0.073760 0.191730 -vn -0.512204 0.848678 0.131885 -v 0.088068 0.073759 0.191758 -vn 0.497582 0.857254 0.132396 -v 0.087731 0.073735 0.191901 -vn -0.499701 0.063552 0.863864 -v 0.088200 0.073299 0.192313 -vn -0.516761 0.234182 0.823479 -v 0.088194 0.073338 0.192303 -vn 0.510222 0.425961 0.747149 -v 0.087829 0.073361 0.192295 -vn -0.508940 0.424189 0.749029 -v 0.088151 0.073551 0.192185 -vn 0.526073 0.651169 0.547017 -v 0.087785 0.073571 0.192167 -vn -0.511055 0.576590 0.637469 -v 0.088146 0.073572 0.192165 -vn 0.519955 0.797435 0.306176 -v 0.087742 0.073712 0.191965 -vn -0.514442 0.703166 0.490822 -v 0.088107 0.073701 0.191989 -vn -0.492356 0.817684 0.298292 -v 0.088092 0.073735 0.191901 -vn 0.502536 0.236287 0.831641 -v 0.087839 0.073299 0.192313 -vn 0.513122 0.060730 0.856164 -v 0.087869 0.073124 0.192329 -vn -0.512919 -0.151165 0.845023 -v 0.088234 0.073099 0.192327 -vn 0.494820 -0.155073 0.855047 -v 0.087893 0.072989 0.192305 -vn -0.494902 -0.337002 0.800938 -v 0.088255 0.072989 0.192305 -vn 0.512964 -0.335082 0.790309 -v 0.087913 0.072884 0.192263 -vn -0.513197 -0.518043 0.684296 -v 0.088279 0.072863 0.192251 -vn 0.499561 -0.525339 0.688809 -v 0.087947 0.072724 0.192142 -vn -0.502927 -0.651747 0.567706 -v 0.088309 0.072724 0.192142 -vn -0.510310 -0.764200 0.394439 -v 0.088319 0.072683 0.192094 -vn 0.516918 -0.646764 0.560795 -v 0.087954 0.072697 0.192112 -vn 0.508793 -0.765101 0.394651 -v 0.087997 0.072583 0.191895 -vn -0.526004 -0.843857 0.105949 -v 0.088362 0.072577 0.191873 -vn 0.511104 -0.831329 0.218322 -v 0.088002 0.072576 0.191869 -vn -0.519751 -0.835901 -0.176432 -v 0.088406 0.072569 0.191628 -vn 0.513700 -0.857620 0.024524 -v 0.088041 0.072565 0.191649 -vn -0.497612 -0.791145 -0.355628 -v 0.088417 0.072585 0.191559 -vn 0.493213 -0.847044 -0.198136 -v 0.088056 0.072585 0.191559 -vn 0.512388 -0.781731 -0.355466 -v 0.088080 0.072644 0.191424 -vn -0.508908 -0.670911 -0.539344 -v 0.088445 0.072655 0.191406 -vn 0.495808 -0.677052 -0.543851 -v 0.088110 0.072747 0.191294 -vn -0.486298 -0.555935 -0.674130 -v 0.088471 0.072747 0.191294 -vn 0.514915 -0.529263 -0.674346 -v 0.088125 0.072812 0.191241 -vn -0.514961 -0.355216 -0.780151 -v 0.088490 0.072829 0.191229 -vn 0.524948 -0.270180 -0.807114 -v 0.088166 0.073033 0.191143 -vn 0.503458 0.213548 -0.837214 -v 0.088218 0.073331 0.191154 -vn -0.501851 0.389870 -0.772105 -v 0.088580 0.073331 0.191154 -vn -0.513410 0.215211 -0.830719 -v 0.088573 0.073295 0.191145 -vn 0.511518 0.008895 -0.859227 -v 0.088208 0.073276 0.191141 -vn -0.507624 0.004336 -0.861568 -v 0.088530 0.073051 0.191139 -vn -0.512013 -0.182218 -0.839428 -v 0.088525 0.073020 0.191146 -vn -0.518608 0.555713 -0.649791 -v 0.088617 0.073519 0.191249 -vn 0.512427 0.387973 -0.766091 -v 0.088253 0.073504 0.191238 -vn -0.498244 0.689234 -0.526033 -v 0.088634 0.073596 0.191317 -vn 0.498677 0.572077 -0.651191 -v 0.088272 0.073595 0.191317 -vn -0.511947 0.791282 -0.334340 -v 0.088656 0.073677 0.191426 -vn 0.518038 0.685941 -0.511000 -v 0.088292 0.073668 0.191411 -vn -0.498801 0.851746 -0.160394 -v 0.088688 0.073743 0.191590 -vn 0.494147 0.632520 0.596438 -v 0.088435 0.073573 0.192165 -vn -0.514828 0.635108 0.575838 -v 0.088784 0.073620 0.192114 -vn 0.514314 0.753752 0.409071 -v 0.088420 0.073630 0.192102 -vn -0.526421 0.782649 0.332177 -v 0.088742 0.073735 0.191901 -vn 0.526096 0.840434 0.129976 -v 0.088378 0.073739 0.191887 -vn -0.513063 0.856635 0.054259 -v 0.088701 0.073756 0.191661 -vn 0.514260 0.844218 -0.151103 -v 0.088336 0.073754 0.191644 -vn 0.499735 0.798379 -0.335941 -v 0.088327 0.073743 0.191590 -vn 0.791730 0.292432 -0.536328 -v 0.088903 0.073507 0.191240 -vn 0.395084 0.230183 -0.889339 -v 0.088903 0.073331 0.191154 -vn 0.674372 0.245895 -0.696246 -v 0.088887 0.073430 0.191194 -vn 0.496149 0.149187 -0.855324 -v 0.088868 0.073331 0.191154 -vn 0.613842 -0.064704 -0.786773 -v 0.088843 0.073190 0.191130 -vn 0.394806 -0.226951 -0.890293 -v 0.088903 0.073020 0.191146 -vn 0.500895 -0.239213 -0.831794 -v 0.088814 0.073020 0.191146 -vn 0.386857 -0.883532 -0.264032 -v 0.088903 0.072585 0.191559 -vn 0.531537 -0.790777 -0.303546 -v 0.088716 0.072606 0.191499 -vn 0.367757 -0.631993 -0.682158 -v 0.088903 0.072747 0.191294 -vn 0.537334 -0.644801 -0.543604 -v 0.088759 0.072745 0.191296 -vn 0.574188 -0.447868 -0.685363 -v 0.088803 0.072954 0.191166 -vn 0.387694 -0.895929 0.216806 -v 0.088903 0.072576 0.191869 -vn 0.527507 -0.845269 0.085193 -v 0.088676 0.072560 0.191734 -vn 0.498605 -0.857713 -0.125384 -v 0.088706 0.072585 0.191559 -vn 0.517468 -0.445611 0.730519 -v 0.088591 0.072754 0.192172 -vn 0.508551 -0.608195 0.609487 -v 0.088597 0.072724 0.192142 -vn 0.376762 -0.667412 0.642349 -v 0.088903 0.072724 0.192142 -vn 0.523160 -0.715912 0.462357 -v 0.088631 0.072613 0.191977 -vn 0.496577 -0.822637 0.276910 -v 0.088652 0.072576 0.191869 -vn 0.520152 -0.266057 0.811576 -v 0.088548 0.072965 0.192297 -vn 0.373863 -0.370115 0.850436 -v 0.088903 0.072989 0.192305 -vn 0.502437 -0.087456 0.860179 -v 0.088543 0.072989 0.192305 -vn 0.382827 -0.177569 0.906594 -v 0.088903 0.072997 0.192307 -vn 0.518315 0.118636 0.846921 -v 0.088504 0.073210 0.192328 -vn -0.506630 -0.076654 0.858750 -v 0.088867 0.073196 0.192329 -vn 0.497918 0.299328 0.813929 -v 0.088489 0.073299 0.192313 -vn -0.512966 0.130514 0.848430 -v 0.088850 0.073299 0.192313 -vn 0.511245 0.488711 0.706958 -v 0.088464 0.073439 0.192261 -vn -0.518548 0.307101 0.797995 -v 0.088828 0.073426 0.192267 -vn -0.498244 0.495644 0.711400 -v 0.088796 0.073573 0.192165 -vn 0.004324 -0.868774 -0.495191 -v 0.085338 0.072439 0.191279 -vn -0.007779 -0.736551 -0.676338 -v 0.085353 0.072509 0.191183 -vn 0.861986 -0.455903 -0.221659 -v 0.085425 0.072604 0.191264 -vn 0.009743 -0.993537 -0.113087 -v 0.085299 0.072321 0.191595 -vn -0.007777 -0.944560 -0.328246 -v 0.085312 0.072346 0.191486 -vn 0.864814 -0.501362 -0.027079 -v 0.085384 0.072465 0.191522 -vn 0.006393 -0.955777 0.294023 -v 0.085255 0.072337 0.191942 -vn -0.005427 -0.997406 0.071771 -v 0.085270 0.072316 0.191828 -vn 0.862635 -0.474352 0.175647 -v 0.085342 0.072440 0.191813 -vn 0.004919 -0.760412 0.649422 -v 0.085212 0.072491 0.192254 -vn -0.008909 -0.884588 0.466288 -v 0.085225 0.072428 0.192161 -vn 0.862479 -0.362286 0.353382 -v 0.085298 0.072535 0.192098 -vn 0.008232 -0.442095 0.896930 -v 0.085172 0.072748 0.192473 -vn -0.003733 -0.629312 0.777144 -v 0.085186 0.072653 0.192412 -vn 0.862733 -0.194495 0.466759 -v 0.085258 0.072728 0.192312 -vn 0.004363 -0.044828 0.998985 -v 0.085127 0.073084 0.192576 -vn -0.006818 -0.267112 0.963641 -v 0.085142 0.072972 0.192559 -vn 0.862420 0.011689 0.506058 -v 0.085214 0.073000 0.192437 -vn 0.009147 0.352489 0.935771 -v 0.085087 0.073420 0.192539 -vn -0.008666 0.138799 0.990283 -v 0.085099 0.073318 0.192565 -vn 0.863330 0.204692 0.461262 -v 0.085171 0.073295 0.192442 -vn 0.006313 0.696558 0.717473 -v 0.085044 0.073721 0.192368 -vn -0.004379 0.518191 0.855254 -v 0.085059 0.073633 0.192435 -vn 0.861948 0.374265 0.342010 -v 0.085131 0.073564 0.192332 -vn 0.003636 0.924666 0.380761 -v 0.085001 0.073930 0.192088 -vn -0.007992 0.818046 0.575097 -v 0.085014 0.073879 0.192183 -vn 0.861724 0.481553 0.159807 -v 0.085086 0.073773 0.192116 -vn 0.008070 0.999860 -0.014646 -v 0.084961 0.074009 0.191761 -vn -0.003790 0.978603 0.205725 -v 0.084974 0.073999 0.191866 -vn 0.862705 0.504093 -0.040372 -v 0.085046 0.073875 0.191846 -vn 0.004258 0.909826 -0.414969 -v 0.084917 0.073949 0.191415 -vn -0.005756 0.979653 -0.200616 -v 0.084930 0.073983 0.191518 -vn 0.863878 0.442539 -0.240570 -v 0.085002 0.073862 0.191549 -vn 0.007714 0.672053 -0.740463 -v 0.084876 0.073762 0.191130 -vn -0.008702 0.817924 -0.575261 -v 0.084887 0.073829 0.191206 -vn 0.862589 0.317677 -0.393727 -v 0.084959 0.073731 0.191283 -vn 0.006171 0.322120 -0.946679 -v 0.084834 0.073475 0.190940 -vn -0.003352 0.525052 -0.851063 -v 0.084847 0.073571 0.190985 -vn 0.861596 0.132262 -0.490060 -v 0.084919 0.073510 0.191095 -vn 0.002797 -0.082467 -0.996590 -v 0.084789 0.073131 0.190880 -vn -0.006969 0.139586 -0.990185 -v 0.084802 0.073234 0.190883 -vn 0.861196 -0.079144 -0.502074 -v 0.084874 0.073223 0.191007 -vn 0.007850 -0.468355 -0.883505 -v 0.084750 0.072803 0.190958 -vn -0.004283 -0.263151 -0.964745 -v 0.084762 0.072896 0.190922 -vn 0.862944 -0.266257 -0.429458 -v 0.084834 0.072935 0.191040 -vn 0.004195 -0.783582 -0.621275 -v 0.084706 0.072522 0.191167 -vn -0.004717 -0.624476 -0.781029 -v 0.084719 0.072595 0.191095 -vn 0.862988 -0.416757 -0.285598 -v 0.084791 0.072678 0.191188 -vn 0.005598 -0.965507 -0.260317 -v 0.084664 0.072352 0.191466 -vn -0.007972 -0.885066 -0.465398 -v 0.084675 0.072387 0.191376 -vn 0.861834 -0.496930 -0.101504 -v 0.084747 0.072501 0.191428 -vn 0.006041 -0.989615 0.143615 -v 0.084623 0.072313 0.191805 -vn -0.002444 -0.996854 -0.079217 -v 0.084635 0.072310 0.191705 -vn 0.862199 -0.494592 0.109503 -v 0.084708 0.072435 0.191709 -vn 0.002338 -0.849503 0.527580 -v 0.084578 0.072416 0.192140 -vn -0.005995 -0.945196 0.326448 -v 0.084591 0.072373 0.192052 -vn 0.861403 -0.410060 0.299727 -v 0.084663 0.072489 0.192004 -vn 0.007588 -0.573031 0.819498 -v 0.084539 0.072634 0.192397 -vn -0.005084 -0.738507 0.674227 -v 0.084550 0.072563 0.192335 -vn 0.863512 -0.259410 0.432497 -v 0.084622 0.072651 0.192246 -vn 0.004092 -0.196777 0.980440 -v 0.084495 0.072946 0.192552 -vn -0.003642 -0.411084 0.911590 -v 0.084508 0.072854 0.192523 -vn 0.862208 -0.065372 0.502318 -v 0.084580 0.072899 0.192406 -vn 0.003719 0.208550 0.978005 -v 0.084452 0.073292 0.192569 -vn -0.007028 -0.010602 0.999919 -v 0.084463 0.073200 0.192579 -vn 0.861175 0.139434 0.488810 -v 0.084535 0.073194 0.192454 -vn 0.005825 0.578059 0.815974 -v 0.084412 0.073610 0.192451 -vn -0.001847 0.384087 0.923295 -v 0.084424 0.073527 0.192496 -vn 0.861764 0.323942 0.390415 -v 0.084496 0.073473 0.192383 -vn 0.002106 0.856720 0.515777 -v 0.084367 0.073863 0.192207 -vn -0.004894 0.720895 0.693027 -v 0.084379 0.073806 0.192282 -vn 0.861427 0.454330 0.226996 -v 0.084451 0.073711 0.192201 -vn 0.007286 0.990626 0.136408 -v 0.084327 0.073994 0.191895 -vn -0.006080 0.936898 0.349550 -v 0.084337 0.073972 0.191981 -vn 0.864129 0.502241 0.032173 -v 0.084410 0.073853 0.191944 -vn 0.003953 0.962657 -0.270694 -v 0.084284 0.073990 0.191548 -vn -0.002651 0.998783 -0.049250 -v 0.084296 0.074005 0.191639 -vn 0.861976 0.477323 -0.170766 -v 0.084368 0.073881 0.191653 -vn 0.002289 0.775494 -0.631350 -v 0.084241 0.073848 0.191231 -vn -0.005997 0.894903 -0.446220 -v 0.084251 0.073896 0.191305 -vn 0.861663 0.366895 -0.350605 -v 0.084324 0.073788 0.191367 -vn 0.005590 0.463621 -0.886016 -v 0.084201 0.073600 0.191002 -vn -0.001694 0.646590 -0.762836 -v 0.084212 0.073672 0.191052 -vn 0.862017 0.199788 -0.465844 -v 0.084284 0.073597 0.191151 -vn 0.001987 0.069008 -0.997614 -v 0.084156 0.073268 0.190887 -vn -0.003788 0.288971 -0.957330 -v 0.084168 0.073355 0.190902 -vn 0.861882 -0.006213 -0.507071 -v 0.084240 0.073327 0.191024 -vn 0.006325 -0.330454 -0.943801 -v 0.084116 0.072929 0.190912 -vn -0.006544 -0.116601 -0.993157 -v 0.084125 0.073009 0.190893 -vn 0.862397 -0.200430 -0.464865 -v 0.084197 0.073031 0.191016 -vn 0.003708 -0.678830 -0.734286 -v 0.084074 0.072623 0.191071 -vn -0.001607 -0.499044 -0.866575 -v 0.084085 0.072693 0.191019 -vn 0.861108 -0.371757 -0.346829 -v 0.084157 0.072762 0.191124 -vn 0.001126 -0.915332 -0.402697 -v 0.084029 0.072403 0.191342 -vn -0.004945 -0.804870 -0.593431 -v 0.084040 0.072445 0.191270 -vn 0.860892 -0.481202 -0.165257 -v 0.084112 0.072550 0.191337 -vn 0.005393 -0.999940 -0.009546 -v 0.083990 0.072312 0.191667 -vn -0.001854 -0.973751 -0.227609 -v 0.084000 0.072322 0.191585 -vn 0.861957 -0.505746 0.035373 -v 0.084072 0.072445 0.191607 -vn 0.001777 -0.919692 0.392636 -v 0.083946 0.072359 0.192014 -vn -0.002754 -0.983936 0.178503 -v 0.083956 0.072335 0.191934 -vn 0.863110 -0.446235 0.236465 -v 0.084028 0.072456 0.191904 -vn 0.004409 -0.689269 0.724493 -v 0.083904 0.072536 0.192307 -vn -0.005916 -0.830468 0.557035 -v 0.083913 0.072486 0.192248 -vn 0.861662 -0.322640 0.391716 -v 0.083985 0.072585 0.192172 -vn 0.003470 -0.345387 0.938454 -v 0.083863 0.072814 0.192506 -vn -0.000588 -0.543683 0.839290 -v 0.083873 0.072742 0.192470 -vn 0.860727 -0.137563 0.490128 -v 0.083945 0.072804 0.192361 -vn 0.000311 0.058490 0.998288 -v 0.083818 0.073157 0.192580 -vn -0.003863 -0.161738 0.986826 -v 0.083828 0.073078 0.192576 -vn 0.860357 0.074120 0.504274 -v 0.083900 0.073090 0.192451 -vn 0.005060 0.446854 0.894593 -v 0.083779 0.073488 0.192514 -vn -0.002390 0.241541 0.970388 -v 0.083788 0.073417 0.192540 -vn 0.862167 0.262691 0.433199 -v 0.083860 0.073379 0.192421 -vn 0.001540 0.768049 0.640390 -v 0.083735 0.073775 0.192316 -vn -0.001630 0.606937 0.794748 -v 0.083745 0.073719 0.192370 -vn 0.861935 0.414962 0.291332 -v 0.083817 0.073637 0.192276 -vn 0.002395 0.959049 0.283231 -v 0.083692 0.073958 0.192022 -vn -0.004869 0.874590 0.484839 -v 0.083701 0.073930 0.192090 -vn 0.860784 0.497678 0.106616 -v 0.083773 0.073816 0.192037 -vn 0.003221 0.992875 -0.119113 -v 0.083652 0.074009 0.191687 -vn 0.000161 0.994879 0.101070 -v 0.083661 0.074009 0.191762 -vn 0.861192 0.497355 -0.104820 -v 0.083734 0.073884 0.191757 -vn -0.000192 0.862082 -0.506768 -v 0.083607 0.073919 0.191347 -vn -0.002740 0.952238 -0.305346 -v 0.083617 0.073950 0.191415 -vn 0.860515 0.414356 -0.296351 -v 0.083689 0.073833 0.191461 -vn 0.004785 0.592629 -0.805461 -v 0.083568 0.073710 0.191082 -vn -0.003070 0.753241 -0.657738 -v 0.083576 0.073762 0.191129 -vn 0.863331 0.263870 -0.430154 -v 0.083648 0.073673 0.191217 -vn 0.001319 0.221089 -0.975253 -v 0.083524 0.073405 0.190916 -vn -0.000581 0.431043 -0.902331 -v 0.083534 0.073474 0.190940 -vn 0.861170 0.071059 -0.503326 -v 0.083606 0.073427 0.191056 -vn 0.000761 -0.184995 -0.982739 -v 0.083481 0.073058 0.190886 -vn -0.003827 0.032602 -0.999461 -v 0.083489 0.073128 0.190880 -vn 0.860138 -0.135306 -0.491787 -v 0.083561 0.073132 0.191005 -vn 0.003011 -0.557675 -0.830054 -v 0.083441 0.072738 0.190992 -vn 0.000479 -0.363711 -0.931512 -v 0.083450 0.072799 0.190960 -vn 0.860701 -0.321167 -0.395026 -v 0.083522 0.072852 0.191073 -vn -0.000485 -0.843787 -0.536678 -v 0.083396 0.072475 0.191226 -vn -0.001625 -0.705410 -0.708797 -v 0.083405 0.072519 0.191171 -vn 0.860519 -0.453348 -0.232343 -v 0.083477 0.072613 0.191253 -vn 0.004389 -0.987082 -0.160156 -v 0.083356 0.072333 0.191534 -vn -0.003909 -0.929051 -0.369930 -v 0.083363 0.072350 0.191472 -vn 0.863037 -0.503782 -0.037032 -v 0.083435 0.072469 0.191510 -vn 0.001041 -0.969164 0.246413 -v 0.083314 0.072323 0.191879 -vn 0.000431 -0.999623 0.027461 -v 0.083322 0.072314 0.191812 -vn 0.860906 -0.480781 0.166402 -v 0.083394 0.072438 0.191800 -vn -0.000571 -0.790631 0.612293 -v 0.083269 0.072454 0.192203 -vn -0.002730 -0.904487 0.426492 -v 0.083277 0.072420 0.192148 -vn 0.860493 -0.371771 0.348337 -v 0.083349 0.072529 0.192086 -vn 0.002682 -0.485530 0.874216 -v 0.083230 0.072693 0.192440 -vn 0.000556 -0.663176 0.748463 -v 0.083238 0.072641 0.192403 -vn 0.860873 -0.205080 0.465662 -v 0.083310 0.072718 0.192304 -vn -0.000725 -0.093825 0.995588 -v 0.083186 0.073020 0.192568 -vn -0.000581 -0.309893 0.950771 -v 0.083194 0.072957 0.192555 -vn 0.860949 0.001030 0.508691 -v 0.083266 0.072987 0.192434 -vn 0.002996 0.307667 0.951489 -v 0.083144 0.073361 0.192555 -vn -0.003754 0.095176 0.995453 -v 0.083151 0.073303 0.192567 -vn 0.861043 0.196690 0.468953 -v 0.083223 0.073282 0.192444 -vn 0.000805 0.660108 0.751171 -v 0.083103 0.073671 0.192409 -vn 0.001429 0.480308 0.877099 -v 0.083111 0.073620 0.192444 -vn 0.859840 0.369957 0.351861 -v 0.083183 0.073553 0.192339 -vn -0.001569 0.905146 0.425098 -v 0.083058 0.073902 0.192145 -vn -0.001603 0.791758 0.610833 -v 0.083066 0.073870 0.192196 -vn 0.859674 0.481480 0.170699 -v 0.083138 0.073766 0.192127 -vn 0.002461 0.999407 0.034336 -v 0.083019 0.074005 0.191824 -vn 0.000278 0.968569 0.248746 -v 0.083026 0.073996 0.191881 -vn 0.860761 0.508081 -0.030726 -v 0.083098 0.073873 0.191859 -vn -0.001038 0.929305 -0.369313 -v 0.082975 0.073971 0.191476 -vn 0.000530 0.987585 -0.157085 -v 0.082982 0.073987 0.191533 -vn 0.861894 0.450420 -0.232940 -v 0.083054 0.073865 0.191562 -vn 0.000905 0.706657 -0.707556 -v 0.082932 0.073804 0.191175 -vn -0.002647 0.842180 -0.539189 -v 0.082939 0.073838 0.191217 -vn 0.860330 0.327800 -0.390358 -v 0.083011 0.073739 0.191293 -vn 0.000503 0.369058 -0.929406 -v 0.082892 0.073535 0.190967 -vn 0.002246 0.561469 -0.827495 -v 0.082899 0.073584 0.190993 -vn 0.860442 0.139402 -0.490109 -v 0.082971 0.073522 0.191101 -vn -0.002400 -0.033672 -0.999430 -v 0.082847 0.073194 0.190880 -vn -0.000498 0.183046 -0.983104 -v 0.082854 0.073249 0.190884 -vn 0.859571 -0.068512 -0.506402 -v 0.082926 0.073236 0.191009 -vn 0.002108 -0.424626 -0.905366 -v 0.082808 0.072861 0.190934 -vn -0.000164 -0.220666 -0.975349 -v 0.082814 0.072910 0.190917 -vn 0.860921 -0.259766 -0.437421 -v 0.082886 0.072947 0.191037 -vn -0.001332 -0.751489 -0.659744 -v 0.082764 0.072567 0.191120 -vn 0.001586 -0.589715 -0.807610 -v 0.082771 0.072607 0.191084 -vn 0.860418 -0.413923 -0.297236 -v 0.082843 0.072688 0.191179 -vn -0.000813 -0.951804 -0.306705 -v 0.082721 0.072373 0.191408 -vn -0.001593 -0.864061 -0.503385 -v 0.082727 0.072394 0.191362 -vn 0.859322 -0.499105 -0.111619 -v 0.082799 0.072506 0.191416 -vn 0.000250 -0.995589 0.093822 -v 0.082681 0.072310 0.191740 -vn 0.002750 -0.992489 -0.122299 -v 0.082687 0.072311 0.191690 -vn 0.859682 -0.500819 0.100636 -v 0.082759 0.072436 0.191696 -vn -0.002921 -0.874563 0.484903 -v 0.082636 0.072387 0.192083 -vn 0.000641 -0.958591 0.284786 -v 0.082643 0.072367 0.192037 -vn 0.859178 -0.419059 0.293605 -v 0.082715 0.072484 0.191992 -vn 0.001900 -0.612347 0.790587 -v 0.082596 0.072587 0.192357 -vn -0.000890 -0.767084 0.641546 -v 0.082601 0.072553 0.192325 -vn 0.861827 -0.269048 0.429963 -v 0.082674 0.072642 0.192237 -vn -0.001627 -0.246158 0.969228 -v 0.082553 0.072884 0.192534 -vn 0.002562 -0.450193 0.892927 -v 0.082559 0.072839 0.192517 -vn 0.859628 -0.076529 0.505157 -v 0.082632 0.072886 0.192401 -vn -0.002338 0.160459 0.987040 -v 0.082510 0.073230 0.192577 -vn -0.000483 -0.053827 0.998550 -v 0.082515 0.073185 0.192579 -vn 0.858638 0.131606 0.495399 -v 0.082587 0.073181 0.192454 -vn -0.000078 0.536200 0.844091 -v 0.082470 0.073554 0.192483 -vn 0.002975 0.343710 0.939071 -v 0.082476 0.073514 0.192503 -vn 0.859093 0.319204 0.400085 -v 0.082548 0.073462 0.192389 -vn -0.003264 0.829858 0.557965 -v 0.082425 0.073825 0.192259 -vn 0.001690 0.690162 0.723653 -v 0.082431 0.073796 0.192294 -vn 0.859100 0.453198 0.237821 -v 0.082503 0.073702 0.192211 -vn 0.001264 0.982837 0.184472 -v 0.082384 0.073979 0.191955 -vn -0.001340 0.921089 0.389349 -v 0.082389 0.073968 0.191995 -vn 0.860489 0.507607 0.043521 -v 0.082461 0.073849 0.191956 -vn -0.001970 0.975225 -0.221208 -v 0.082343 0.074002 0.191612 -vn 0.003569 0.999973 -0.006500 -v 0.082348 0.074007 0.191655 -vn 0.858796 0.485545 -0.163451 -v 0.082420 0.073882 0.191666 -vn -0.003530 0.805776 -0.592210 -v 0.082298 0.073883 0.191283 -vn 0.000705 0.913276 -0.407342 -v 0.082303 0.073904 0.191318 -vn 0.858830 0.377053 -0.346759 -v 0.082375 0.073794 0.191379 -vn -0.000363 0.507778 -0.861488 -v 0.082259 0.073653 0.191037 -vn 0.002902 0.678923 -0.734203 -v 0.082264 0.073684 0.191061 -vn 0.859161 0.210421 -0.466438 -v 0.082336 0.073607 0.191159 -vn -0.003623 0.119586 -0.992817 -v 0.082215 0.073332 0.190897 -vn 0.002798 0.329980 -0.943984 -v 0.082220 0.073371 0.190906 -vn 0.859497 0.003858 -0.511127 -v 0.082292 0.073340 0.191027 -vn -0.000645 -0.283963 -0.958835 -v 0.082173 0.072988 0.190897 -vn -0.000457 -0.074638 -0.997211 -v 0.082177 0.073024 0.190891 -vn 0.859166 -0.193532 -0.473687 -v 0.082249 0.073044 0.191014 -vn -0.002283 -0.640134 -0.768260 -v 0.082132 0.072675 0.191032 -vn 0.004421 -0.461865 -0.886939 -v 0.082137 0.072706 0.191011 -vn 0.857967 -0.369096 -0.357296 -v 0.082209 0.072773 0.191117 -vn -0.004452 -0.894040 -0.447964 -v 0.082087 0.072434 0.191287 -vn 0.001751 -0.778794 -0.627277 -v 0.082092 0.072454 0.191257 -vn 0.857918 -0.482635 -0.176181 -v 0.082164 0.072557 0.191326 -vn -0.000657 -0.998207 -0.059856 -v 0.082048 0.072319 0.191604 -vn 0.002639 -0.963140 -0.268988 -v 0.082052 0.072325 0.191571 -vn 0.858953 -0.511372 0.026446 -v 0.082124 0.072448 0.191594 -vn -0.003937 -0.938609 0.344960 -v 0.082004 0.072339 0.191952 -vn 0.003822 -0.990639 0.136455 -v 0.082008 0.072331 0.191919 -vn 0.860084 -0.455299 0.230128 -v 0.082080 0.072453 0.191891 -vn -0.002487 -0.724150 0.689638 -v 0.081961 0.072496 0.192261 -vn 0.000687 -0.853050 0.521830 -v 0.081965 0.072477 0.192236 -vn 0.858904 -0.331810 0.390111 -v 0.082037 0.072577 0.192161 -vn -0.002567 -0.393220 0.919441 -v 0.081921 0.072756 0.192478 -vn 0.005002 -0.578471 0.815688 -v 0.081925 0.072729 0.192462 -vn 0.857679 -0.145276 0.493235 -v 0.081997 0.072792 0.192354 -vn -0.005097 0.007901 0.999956 -v 0.081876 0.073093 0.192577 -vn 0.002914 -0.203502 0.979070 -v 0.081880 0.073063 0.192574 -vn 0.855845 0.060681 0.513661 -v 0.081952 0.073077 0.192450 -vn -0.000865 0.401278 0.915956 -v 0.081836 0.073429 0.192536 -vn 0.002167 0.200240 0.979745 -v 0.081840 0.073402 0.192544 -vn 0.854626 0.257135 0.451106 -v 0.081912 0.073367 0.192425 -vn -0.004231 0.733787 0.679367 -v 0.081793 0.073729 0.192361 -vn 0.004712 0.572844 0.819651 -v 0.081797 0.073707 0.192380 -vn 0.854428 0.418540 0.307858 -v 0.081869 0.073627 0.192284 -vn -0.004016 0.943710 0.330750 -v 0.081750 0.073934 0.192080 -vn 0.001837 0.853619 0.520894 -v 0.081753 0.073923 0.192104 -vn 0.855348 0.503992 0.119883 -v 0.081825 0.073811 0.192049 -vn -0.002812 0.997707 -0.067617 -v 0.081710 0.074010 0.191751 -vn 0.005280 0.989732 0.142840 -v 0.081713 0.074009 0.191777 -vn 0.857116 0.505318 -0.100030 -v 0.081785 0.073884 0.191770 -vn -0.005597 0.886853 -0.462018 -v 0.081665 0.073946 0.191406 -vn 0.003900 0.964256 -0.264945 -v 0.081669 0.073955 0.191430 -vn 0.854126 0.431483 -0.290329 -v 0.081741 0.073838 0.191474 -vn -0.001065 0.632328 -0.774700 -v 0.081625 0.073756 0.191123 -vn 0.001445 0.780113 -0.625637 -v 0.081627 0.073772 0.191140 -vn 0.853044 0.286270 -0.436308 -v 0.081699 0.073682 0.191226 -vn -0.004618 0.271848 -0.962329 -v 0.081583 0.073466 0.190937 -vn 0.005689 0.468301 -0.883551 -v 0.081585 0.073488 0.190946 -vn 0.851918 0.087179 -0.516367 -v 0.081658 0.073440 0.191061 -vn 0.001943 -0.122618 -0.992452 -v 0.081538 0.073121 0.190881 -vn 0.002919 0.074320 -0.997230 -v 0.081541 0.073143 0.190880 -vn 0.855197 -0.120296 -0.504149 -v 0.081613 0.073145 0.191005 -vn 0.005482 -0.501825 -0.864952 -v 0.081499 0.072794 0.190962 -vn 0.010925 -0.338127 -0.941037 -v 0.081501 0.072813 0.190954 -vn 0.851086 -0.319264 -0.416801 -v 0.081574 0.072864 0.191068 -vn 0.001742 -0.808836 -0.588032 -v 0.081455 0.072516 0.191175 -vn 0.012266 -0.687857 -0.725742 -v 0.081457 0.072529 0.191160 -vn 0.850934 -0.461680 -0.250526 -v 0.081529 0.072622 0.191243 -vn 0.004109 -0.975687 -0.219131 -v 0.081413 0.072349 0.191475 -vn 0.003835 -0.915338 -0.402668 -v 0.081415 0.072355 0.191458 -vn 0.849025 -0.524762 -0.061497 -v 0.081487 0.072473 0.191498 -vn 0.939246 0.262087 -0.221648 -v 0.088903 0.073780 0.191432 -vn 0.961533 0.168262 -0.217121 -v 0.088903 0.073652 0.191315 -vn 0.861549 0.299176 -0.410156 -v 0.088856 0.073715 0.191263 -vn 0.572688 -0.351720 -0.740488 -v 0.081598 0.072900 0.191091 -vn 0.566419 -0.461903 -0.682507 -v 0.081592 0.072865 0.191106 -vn 0.571008 -0.758836 0.313239 -v 0.081431 0.072465 0.191911 -vn 0.925666 -0.258222 0.276521 -v 0.081401 0.072522 0.192075 -vn 0.874765 -0.405041 0.265949 -v 0.081424 0.072465 0.191936 -vn 0.573926 -0.165843 0.801938 -v 0.081312 0.072956 0.192441 -vn 0.573278 -0.088439 0.814574 -v 0.081309 0.072970 0.192445 -vn 0.003634 -0.326217 0.945288 -v 0.081246 0.072941 0.192551 -vn 0.574537 0.655895 -0.489601 -v 0.081032 0.073825 0.191305 -vn 0.580623 0.612052 -0.536906 -v 0.081025 0.073799 0.191265 -vn 0.000273 0.814551 -0.580092 -v 0.080991 0.073847 0.191230 -vn 0.564097 -0.208087 -0.799058 -v 0.080891 0.072971 0.190938 -vn 0.576849 -0.276850 -0.768505 -v 0.080886 0.072935 0.190947 -vn 0.003962 -0.236633 -0.971591 -v 0.080865 0.072925 0.190913 -vn 0.581288 -0.761261 -0.287376 -v 0.080789 0.072417 0.191356 -vn 0.188895 -0.940820 -0.281382 -v 0.080770 0.072359 0.191492 -vn -0.006582 -0.901780 -0.432146 -v 0.080779 0.072400 0.191348 -vn -0.056175 -0.963412 -0.262072 -v 0.080765 0.072349 0.191527 -vn 0.002884 -0.995781 -0.091712 -v 0.080739 0.072312 0.191674 -vn 0.325866 -0.934221 -0.145056 -v 0.080757 0.072334 0.191593 -vn 0.582282 -0.812744 0.019881 -v 0.080745 0.072322 0.191675 -vn -0.002070 -0.999857 -0.016810 -v 0.080739 0.072312 0.191676 -vn 0.479798 -0.870710 0.107971 -v 0.080726 0.072321 0.191813 -vn 0.005599 -0.989375 0.145280 -v 0.080717 0.072318 0.191850 -vn 0.445652 -0.866567 0.224625 -v 0.080717 0.072329 0.191879 -vn -0.043199 -0.926976 0.372626 -v 0.080695 0.072362 0.192022 -vn -0.565379 -0.816184 0.119125 -v 0.080710 0.072337 0.191926 -vn 0.083315 -0.890234 0.447819 -v 0.080685 0.072391 0.192091 -vn -0.000073 -0.593011 -0.805195 -v 0.080823 0.072619 0.191074 -vn 0.575311 -0.564286 -0.592113 -v 0.080839 0.072636 0.191095 -vn -0.004031 -0.667434 -0.744658 -v 0.080822 0.072616 0.191077 -vn 0.570206 -0.588469 -0.573211 -v 0.080835 0.072619 0.191109 -vn 0.516851 -0.663519 -0.540932 -v 0.080830 0.072593 0.191131 -vn 0.332634 -0.774310 -0.538330 -v 0.080804 0.072471 0.191268 -vn 0.563846 -0.744230 -0.358050 -v 0.080794 0.072433 0.191326 -vn -0.001859 -0.319965 -0.947427 -v 0.080865 0.072920 0.190914 -vn 0.576663 -0.305325 -0.757783 -v 0.080884 0.072921 0.190950 -vn 0.499033 -0.416063 -0.760170 -v 0.080876 0.072861 0.190970 -vn 0.538793 -0.502562 -0.676117 -v 0.080844 0.072669 0.191071 -vn 0.490265 -0.109026 -0.864728 -v 0.080913 0.073134 0.190920 -vn 0.000367 0.131616 -0.991301 -v 0.080906 0.073265 0.190886 -vn 0.556858 -0.028421 -0.830122 -v 0.080922 0.073199 0.190922 -vn -0.004323 0.460335 -0.887735 -v 0.080950 0.073591 0.190997 -vn 0.005292 0.554888 -0.831908 -v 0.080951 0.073598 0.191001 -vn 0.584024 0.356673 -0.729178 -v 0.080981 0.073571 0.191046 -vn 0.524434 0.270749 -0.807257 -v 0.080963 0.073464 0.190989 -vn 0.495801 0.205374 -0.843803 -v 0.080954 0.073410 0.190967 -vn 0.580954 0.057030 -0.811936 -v 0.080931 0.073259 0.190929 -vn 0.541274 0.570269 -0.617912 -v 0.081011 0.073735 0.191185 -vn 0.508437 0.540324 -0.670479 -v 0.081003 0.073691 0.191140 -vn 0.551054 0.461688 -0.695114 -v 0.080995 0.073647 0.191101 -vn 0.003566 0.955218 -0.295881 -v 0.081033 0.073988 0.191539 -vn -0.003096 0.990893 -0.134618 -v 0.081034 0.073990 0.191548 -vn 0.571550 0.763558 -0.300516 -v 0.081073 0.073923 0.191559 -vn 0.573543 0.786843 -0.227872 -v 0.081074 0.073923 0.191563 -vn 0.503281 0.764598 -0.402614 -v 0.081041 0.073854 0.191358 -vn 0.004694 0.968670 0.248308 -v 0.081078 0.073993 0.191896 -vn 0.576667 0.810770 0.100535 -v 0.081122 0.073919 0.191878 -vn -0.001584 0.992368 0.123302 -v 0.081076 0.073995 0.191886 -vn 0.559239 0.828930 -0.011211 -v 0.081114 0.073928 0.191825 -vn 0.564467 0.813759 -0.138469 -v 0.081082 0.073931 0.191613 -vn -0.004829 0.862943 0.505279 -v 0.081116 0.073868 0.192199 -vn 0.553804 0.779253 0.293370 -v 0.081151 0.073846 0.192074 -vn 0.565721 0.799760 0.200859 -v 0.081132 0.073899 0.191949 -vn -0.003579 0.588214 0.808697 -v 0.081161 0.073618 0.192446 -vn 0.005141 0.475309 0.879804 -v 0.081162 0.073607 0.192452 -vn 0.586529 0.479964 0.652394 -v 0.081217 0.073558 0.192373 -vn 0.557997 0.573391 0.599885 -v 0.081200 0.073643 0.192315 -vn 0.548431 0.635336 0.543665 -v 0.081192 0.073682 0.192283 -vn 0.005226 0.791492 0.611158 -v 0.081118 0.073862 0.192209 -vn 0.583467 0.691868 0.425306 -v 0.081167 0.073792 0.192161 -vn 0.572082 0.737518 0.358872 -v 0.081160 0.073817 0.192123 -vn -0.003448 0.225660 0.974200 -v 0.081201 0.073301 0.192568 -vn 0.547994 0.332535 0.767544 -v 0.081240 0.073415 0.192437 -vn 0.565846 0.399529 0.721245 -v 0.081233 0.073462 0.192420 -vn 0.543717 0.012034 0.839183 -v 0.081278 0.073159 0.192475 -vn 0.000292 0.077484 0.996994 -v 0.081203 0.073288 0.192570 -vn 0.001978 -0.164012 0.986456 -v 0.081244 0.072956 0.192555 -vn 0.575544 0.123770 0.808350 -v 0.081270 0.073212 0.192475 -vn 0.579487 0.185218 0.793656 -v 0.081261 0.073273 0.192469 -vn 0.568739 0.261379 0.779883 -v 0.081252 0.073334 0.192459 -vn 0.564473 -0.563842 0.602870 -v 0.081373 0.072631 0.192231 -vn 0.004013 -0.671359 0.741122 -v 0.081290 0.072629 0.192394 -vn 0.564644 -0.625221 0.538773 -v 0.081390 0.072562 0.192142 -vn -0.002929 -0.837717 0.546097 -v 0.081327 0.072420 0.192149 -vn 0.591395 -0.667566 0.452336 -v 0.081397 0.072537 0.192100 -vn 0.005242 -0.907315 0.420418 -v 0.081329 0.072412 0.192134 -vn 0.576829 -0.483714 0.658247 -v 0.081359 0.072696 0.192295 -vn 0.576383 -0.448331 0.683214 -v 0.081358 0.072703 0.192301 -vn 0.000019 -0.552169 0.833732 -v 0.081288 0.072642 0.192403 -vn 0.573251 -0.379392 0.726255 -v 0.081352 0.072732 0.192324 -vn 0.568986 -0.257441 0.781012 -v 0.081319 0.072912 0.192425 -vn 0.064616 -0.993491 -0.093807 -v 0.081472 0.072452 0.191665 -vn 0.581280 -0.803282 0.129817 -v 0.081452 0.072447 0.191786 -vn 0.854804 -0.499263 0.141588 -v 0.081446 0.072437 0.191787 -vn 0.438670 -0.873331 0.211807 -v 0.081438 0.072456 0.191868 -vn 0.506745 -0.824973 0.250257 -v 0.081433 0.072461 0.191897 -vn 0.551522 -0.821122 -0.146906 -v 0.081494 0.072482 0.191528 -vn 0.243977 -0.961405 -0.127181 -v 0.081479 0.072458 0.191624 -vn 0.365167 -0.822659 -0.435759 -v 0.081517 0.072542 0.191394 -vn 0.507638 -0.803706 -0.310420 -v 0.081509 0.072521 0.191433 -vn 0.577639 -0.788512 -0.211142 -v 0.081498 0.072490 0.191503 -vn 0.582860 -0.671188 -0.458019 -v 0.081545 0.072642 0.191261 -vn 0.572447 -0.630878 -0.523734 -v 0.081550 0.072666 0.191237 -vn 0.486635 -0.585719 -0.648167 -v 0.081557 0.072695 0.191211 -vn 0.522173 0.098039 -0.847186 -v 0.081670 0.073328 0.191075 -vn 0.586419 -0.070697 -0.806917 -v 0.081636 0.073133 0.191048 -vn 0.553479 -0.170818 -0.815158 -v 0.081629 0.073093 0.191049 -vn 0.498805 -0.257478 -0.827586 -v 0.081614 0.073000 0.191062 -vn 0.522385 0.408306 -0.748599 -v 0.081711 0.073537 0.191177 -vn 0.579757 0.259136 -0.772483 -v 0.081688 0.073420 0.191109 -vn 0.557901 0.177846 -0.810628 -v 0.081677 0.073363 0.191086 -vn 0.558896 0.673960 -0.483129 -v 0.081755 0.073715 0.191371 -vn 0.563910 0.619404 -0.546208 -v 0.081749 0.073696 0.191340 -vn 0.579707 0.529910 -0.618979 -v 0.081734 0.073639 0.191268 -vn 0.536934 0.461651 -0.706102 -v 0.081717 0.073563 0.191197 -vn 0.600979 0.796191 -0.070024 -v 0.081831 0.073806 0.191774 -vn 0.532223 0.823630 -0.195888 -v 0.081796 0.073797 0.191581 -vn 0.571883 0.761492 -0.305089 -v 0.081790 0.073790 0.191550 -vn 0.591379 0.704175 -0.392949 -v 0.081780 0.073775 0.191498 -vn 0.567506 0.681626 0.461868 -v 0.081910 0.073618 0.192168 -vn 0.601726 0.728650 0.327100 -v 0.081875 0.073733 0.192016 -vn 0.576319 0.779780 0.244540 -v 0.081869 0.073747 0.191987 -vn 0.552456 0.818513 0.157570 -v 0.081856 0.073777 0.191913 -vn 0.594065 0.803955 0.027253 -v 0.081836 0.073803 0.191804 -vn 0.601152 0.441569 0.666058 -v 0.081951 0.073437 0.192292 -vn 0.586651 0.556202 0.588625 -v 0.081923 0.073567 0.192213 -vn 0.567004 0.624104 0.537587 -v 0.081915 0.073597 0.192188 -vn 0.580008 0.323183 0.747759 -v 0.081970 0.073338 0.192327 -vn 0.599919 0.405353 0.689773 -v 0.081956 0.073414 0.192302 -vn 0.600803 0.104398 0.792551 -v 0.081994 0.073202 0.192347 -vn 0.575952 0.172815 0.799008 -v 0.081989 0.073231 0.192346 -vn 0.575942 0.248260 0.778882 -v 0.081976 0.073305 0.192335 -vn 0.669341 -0.268186 0.692863 -v 0.082065 0.072852 0.192252 -vn 0.550116 -0.200473 0.810668 -v 0.082035 0.072993 0.192318 -vn 0.583224 -0.085705 0.807777 -v 0.082030 0.073016 0.192325 -vn 0.638203 0.030471 0.769265 -v 0.082016 0.073090 0.192341 -vn 0.754993 -0.316157 0.574483 -v 0.082076 0.072808 0.192221 -vn 0.714404 -0.293001 0.635435 -v 0.082072 0.072825 0.192234 -vn 0.956178 0.140487 -0.256881 -v 0.088903 0.073629 0.191300 -vn 0.860751 0.110036 -0.496990 -v 0.088815 0.073487 0.191082 -vn 0.922797 0.309248 -0.229806 -v 0.088903 0.073802 0.191460 -vn 0.906353 0.358345 -0.223859 -v 0.088898 0.073855 0.191523 -vn 0.961891 0.251715 -0.106799 -v 0.088903 0.073901 0.191635 -vn -0.001766 0.994614 -0.103629 -v 0.088845 0.074004 0.191632 -vn -0.013497 0.994248 0.106249 -v 0.088870 0.074003 0.191836 -vn 0.960850 0.274220 -0.039638 -v 0.088903 0.073947 0.191829 -vn 0.025678 0.951892 0.305355 -v 0.088887 0.073974 0.191973 -vn 0.238589 0.765327 0.597788 -v 0.088903 0.073922 0.192106 -vn 0.959857 0.280349 0.008920 -v 0.088903 0.073950 0.191903 -vn 0.962742 0.270283 -0.008677 -v 0.088903 0.073950 0.191868 -vn 0.862441 -0.327335 -0.386067 -v 0.085470 0.072840 0.191079 -vn 0.861096 -0.140685 -0.488591 -v 0.085509 0.073119 0.191006 -vn 0.862538 0.058416 -0.502609 -v 0.085554 0.073415 0.191051 -vn 0.863174 0.258300 -0.433833 -v 0.085596 0.073664 0.191209 -vn 0.860746 0.409566 -0.302277 -v 0.085637 0.073828 0.191449 -vn 0.862044 0.496724 0.100726 -v 0.085721 0.073822 0.192026 -vn 0.862474 0.492636 -0.115969 -v 0.085682 0.073885 0.191744 -vn 0.862100 0.269411 0.429188 -v 0.085808 0.073391 0.192417 -vn 0.863011 0.418795 0.282529 -v 0.085765 0.073647 0.192267 -vn 0.860691 -0.130932 0.492004 -v 0.085893 0.072815 0.192368 -vn 0.860457 0.081476 0.502966 -v 0.085848 0.073104 0.192452 -vn 0.861833 -0.316403 0.396400 -v 0.085933 0.072593 0.192182 -vn 0.862930 -0.443094 0.242939 -v 0.085976 0.072460 0.191917 -vn 0.861752 -0.505500 0.043053 -v 0.086020 0.072443 0.191619 -vn 0.860907 -0.483468 -0.158424 -v 0.086060 0.072543 0.191349 -vn 0.860926 -0.376580 -0.342043 -v 0.086105 0.072750 0.191131 -vn 0.862515 -0.207769 -0.461411 -v 0.086146 0.073019 0.191018 -vn 0.861213 -0.013404 -0.508068 -v 0.086188 0.073314 0.191021 -vn 0.861186 0.192675 -0.470356 -v 0.086232 0.073587 0.191143 -vn 0.860481 0.365524 -0.354914 -v 0.086272 0.073781 0.191356 -vn 0.861396 0.475774 -0.177867 -v 0.086316 0.073879 0.191639 -vn 0.860747 0.458411 0.221302 -v 0.086399 0.073720 0.192190 -vn 0.863693 0.503398 0.024994 -v 0.086358 0.073856 0.191932 -vn 0.860805 0.145753 0.487618 -v 0.086483 0.073207 0.192453 -vn 0.861239 0.330049 0.386440 -v 0.086444 0.073485 0.192378 -vn 0.861638 -0.058166 0.504178 -v 0.086528 0.072911 0.192411 -vn 0.862544 -0.253961 0.437633 -v 0.086570 0.072660 0.192255 -vn 0.860694 -0.407012 0.305853 -v 0.086611 0.072494 0.192017 -vn 0.861545 -0.494150 0.116429 -v 0.086656 0.072435 0.191722 -vn 0.861607 -0.498534 -0.095382 -v 0.086695 0.072495 0.191440 -vn 0.862887 -0.421454 -0.278932 -v 0.086739 0.072668 0.191197 -vn 0.861908 -0.273333 -0.427087 -v 0.086782 0.072923 0.191044 -vn 0.860430 -0.085825 -0.502288 -v 0.086822 0.073210 0.191006 -vn 0.860577 0.126837 -0.493275 -v 0.086867 0.073499 0.191089 -vn 0.861823 0.312874 -0.399212 -v 0.086908 0.073723 0.191273 -vn 0.861823 0.442447 -0.247995 -v 0.086950 0.073858 0.191536 -vn 0.861583 0.505381 -0.047595 -v 0.086994 0.073877 0.191833 -vn 0.860849 0.379672 0.338805 -v 0.087079 0.073575 0.192324 -vn 0.860907 0.484804 0.154284 -v 0.087034 0.073780 0.192105 -vn 0.862595 0.212056 0.459306 -v 0.087120 0.073307 0.192440 -vn 0.860926 0.018004 0.508412 -v 0.087162 0.073013 0.192440 -vn 0.860403 -0.362765 0.357921 -v 0.087246 0.072542 0.192109 -vn 0.860997 -0.188522 0.472380 -v 0.087206 0.072739 0.192320 -vn 0.860887 -0.459600 -0.218271 -v 0.087373 0.072596 0.191274 -vn 0.864858 -0.501797 -0.014852 -v 0.087332 0.072462 0.191534 -vn 0.861207 -0.474367 0.182478 -v 0.087290 0.072441 0.191827 -vn 0.862267 -0.154999 -0.482153 -v 0.087458 0.073106 0.191007 -vn 0.861082 -0.333734 -0.383613 -v 0.087418 0.072829 0.191085 -vn 0.863567 0.047138 -0.502027 -v 0.087502 0.073402 0.191046 -vn 0.864045 0.245001 -0.439773 -v 0.087544 0.073655 0.191200 -vn 0.862469 0.398488 -0.312016 -v 0.087585 0.073823 0.191437 -vn 0.863465 0.488512 -0.125634 -v 0.087630 0.073885 0.191731 -vn 0.863421 0.497148 0.085722 -v 0.087670 0.073827 0.192014 -vn 0.864691 0.424623 0.268336 -v 0.087713 0.073657 0.192258 -vn 0.863515 0.279574 0.419737 -v 0.087757 0.073403 0.192413 -vn 0.862293 0.095293 0.497362 -v 0.087796 0.073117 0.192453 -vn 0.862543 -0.115768 0.492563 -v 0.087841 0.072827 0.192374 -vn 0.863717 -0.303354 0.402454 -v 0.087882 0.072601 0.192192 -vn 0.863466 -0.434593 0.256037 -v 0.087924 0.072463 0.191930 -vn 0.863308 -0.501449 0.057001 -v 0.087968 0.072441 0.191632 -vn 0.863305 -0.383511 -0.328061 -v 0.088053 0.072739 0.191139 -vn 0.862891 -0.484567 -0.143576 -v 0.088008 0.072536 0.191360 -vn 0.862715 -0.028884 -0.504864 -v 0.088136 0.073300 0.191018 -vn 0.865317 -0.220172 -0.450279 -v 0.088094 0.073007 0.191021 -vn 0.862410 0.353367 -0.362466 -v 0.088220 0.073774 0.191345 -vn 0.862861 0.177620 -0.473203 -v 0.088180 0.073576 0.191136 -vn 0.863241 0.466859 -0.191984 -v 0.088264 0.073877 0.191626 -vn 0.865249 0.501221 0.011028 -v 0.088306 0.073860 0.191919 -vn 0.862423 0.462418 0.205901 -v 0.088347 0.073728 0.192180 -vn 0.863090 0.339720 0.373719 -v 0.088392 0.073497 0.192371 -vn 0.862813 0.158208 0.480129 -v 0.088432 0.073220 0.192452 -vn 0.863680 -0.040953 0.502374 -v 0.088476 0.072924 0.192415 -vn 0.863832 -0.240298 0.442776 -v 0.088519 0.072670 0.192264 -vn 0.862018 -0.395093 0.317531 -v 0.088559 0.072499 0.192029 -vn 0.862395 -0.489597 0.128723 -v 0.088604 0.072435 0.191735 -vn 0.863384 -0.498118 -0.080288 -v 0.088644 0.072490 0.191451 -vn 0.863335 -0.284468 -0.416810 -v 0.088731 0.072911 0.191049 -vn 0.864637 -0.427736 -0.263526 -v 0.088687 0.072658 0.191206 -vn 0.862373 -0.100644 -0.496169 -v 0.088770 0.073196 0.191006 -vn -0.001142 -0.986354 0.164634 -v 0.081372 0.072314 0.191815 -vn 0.012651 -0.999920 -0.000178 -v 0.081374 0.072313 0.191797 -vn 0.008344 -0.597581 -0.801765 -v 0.085383 0.072683 0.191026 -vn -0.004098 -0.404719 -0.914432 -v 0.085398 0.072785 0.190967 -vn 0.006571 -0.231234 -0.972876 -v 0.085424 0.072997 0.190895 -vn -0.007573 -0.007784 -0.999941 -v 0.085437 0.073112 0.190881 -vn 0.010140 0.166530 -0.985984 -v 0.085466 0.073342 0.190899 -vn -0.010141 0.396189 -0.918113 -v 0.085482 0.073459 0.190934 -vn 0.007816 0.550070 -0.835082 -v 0.085510 0.073661 0.191043 -vn -0.004493 0.725823 -0.687867 -v 0.085524 0.073751 0.191119 -vn 0.008156 0.833282 -0.552788 -v 0.085549 0.073888 0.191291 -vn -0.010492 0.941601 -0.336566 -v 0.085565 0.073944 0.191400 -vn 0.010167 0.983703 -0.179515 -v 0.085594 0.074003 0.191622 -vn -0.008755 0.997956 0.063307 -v 0.085609 0.074010 0.191746 -vn 0.006455 0.972242 0.233888 -v 0.085635 0.073977 0.191964 -vn -0.008171 0.893327 0.449334 -v 0.085649 0.073936 0.192077 -vn 0.010565 0.802492 0.596569 -v 0.085677 0.073818 0.192267 -vn -0.008894 0.632427 0.774569 -v 0.085693 0.073731 0.192359 -vn 0.012451 0.500481 0.865658 -v 0.085721 0.073545 0.192487 -vn -0.007750 0.273864 0.961737 -v 0.085736 0.073431 0.192535 -vn 0.006718 0.117469 0.993054 -v 0.085761 0.073221 0.192577 -vn -0.011847 -0.130119 0.991428 -v 0.085776 0.073094 0.192577 -vn 0.010385 -0.286503 0.958023 -v 0.085805 0.072875 0.192530 -vn -0.007253 -0.516861 0.856039 -v 0.085821 0.072756 0.192477 -vn 0.013152 -0.644425 0.764554 -v 0.085847 0.072580 0.192351 -vn -0.013446 -0.812711 0.582512 -v 0.085861 0.072495 0.192260 -vn 0.007916 -0.893728 0.448540 -v 0.085888 0.072383 0.192074 -vn -0.010346 -0.977745 0.209544 -v 0.085904 0.072339 0.191949 -vn 0.012811 -0.998534 0.052591 -v 0.085932 0.072310 0.191731 -vn -0.007477 -0.980634 -0.195707 -v 0.085948 0.072320 0.191600 -vn 0.008189 -0.937742 -0.347236 -v 0.085972 0.072377 0.191399 -vn -0.013115 -0.822785 -0.568201 -v 0.085988 0.072437 0.191283 -vn 0.010617 -0.723608 -0.690130 -v 0.086015 0.072574 0.191114 -vn -0.008557 -0.525407 -0.850808 -v 0.086033 0.072680 0.191028 -vn 0.014608 -0.387830 -0.921615 -v 0.086059 0.072870 0.190931 -vn -0.013201 -0.147001 -0.989048 -v 0.086073 0.072995 0.190896 -vn 0.008143 0.007075 -0.999942 -v 0.086098 0.073204 0.190881 -vn -0.011747 0.259411 -0.965696 -v 0.086116 0.073340 0.190899 -vn 0.013174 0.406617 -0.913504 -v 0.086143 0.073543 0.190971 -vn -0.007634 0.622196 -0.782824 -v 0.086160 0.073660 0.191042 -vn 0.010119 0.735782 -0.677143 -v 0.086184 0.073810 0.191182 -vn -0.014422 0.881145 -0.472627 -v 0.086199 0.073888 0.191292 -vn 0.010718 0.943420 -0.331427 -v 0.086226 0.073974 0.191485 -vn -0.009956 0.996811 -0.079175 -v 0.086244 0.074003 0.191624 -vn 0.015292 0.997149 0.073895 -v 0.086270 0.074004 0.191833 -vn -0.012105 0.947077 0.320777 -v 0.086286 0.073976 0.191966 -vn 0.008400 0.887025 0.461645 -v 0.086309 0.073897 0.192153 -vn -0.013130 0.741146 0.671216 -v 0.086327 0.073816 0.192270 -vn 0.013384 0.629312 0.777038 -v 0.086354 0.073663 0.192415 -vn -0.008449 0.411627 0.911313 -v 0.086372 0.073541 0.192489 -vn 0.012645 0.268431 0.963216 -v 0.086395 0.073352 0.192558 -vn -0.015645 0.017907 0.999717 -v 0.086411 0.073215 0.192578 -vn 0.010828 -0.133131 0.991039 -v 0.086437 0.073010 0.192566 -vn -0.011330 -0.384244 0.923162 -v 0.086456 0.072868 0.192528 -vn 0.015688 -0.519304 0.854445 -v 0.086481 0.072685 0.192435 -vn -0.011015 -0.717784 0.696178 -v 0.086498 0.072574 0.192346 -vn 0.008986 -0.814987 0.579410 -v 0.086521 0.072449 0.192195 -vn -0.014472 -0.935347 0.353435 -v 0.086539 0.072379 0.192066 -vn 0.013611 -0.978032 0.208012 -v 0.086565 0.072321 0.191869 -vn -0.009610 -0.998666 -0.050735 -v 0.086584 0.072310 0.191721 -vn 0.015281 -0.979910 -0.198856 -v 0.086607 0.072335 0.191525 -vn -0.016504 -0.897459 -0.440788 -v 0.086623 0.072381 0.191390 -vn 0.010962 -0.822336 -0.568897 -v 0.086648 0.072481 0.191218 -vn -0.012823 -0.646261 -0.763008 -v 0.086667 0.072583 0.191105 -vn 0.016118 -0.525128 -0.850871 -v 0.086692 0.072746 0.190987 -vn -0.010355 -0.291635 -0.956474 -v 0.086710 0.072882 0.190926 -vn 0.010137 -0.144871 -0.989399 -v 0.086732 0.073068 0.190885 -vn -0.015803 0.112204 -0.993560 -v 0.086750 0.073218 0.190882 -vn 0.013786 0.258644 -0.965874 -v 0.086775 0.073414 0.190919 -vn -0.010909 0.501482 -0.865099 -v 0.086795 0.073557 0.190978 -vn 0.017145 0.622638 -0.782322 -v 0.086819 0.073717 0.191088 -vn -0.016589 0.801936 -0.597180 -v 0.086835 0.073820 0.191194 -vn 0.011057 0.880655 -0.473630 -v 0.086859 0.073923 0.191356 -vn -0.014243 0.973726 -0.227277 -v 0.086878 0.073979 0.191502 -vn 0.016393 0.996557 -0.081278 -v 0.086903 0.074009 0.191696 -vn -0.010251 0.984055 0.177568 -v 0.086922 0.074001 0.191851 -vn 0.011822 0.946916 0.321265 -v 0.086943 0.073955 0.192031 -vn -0.017133 0.832848 0.553236 -v 0.086962 0.073887 0.192170 -vn 0.013875 0.743164 0.668965 -v 0.086986 0.073769 0.192323 -vn -0.012293 0.540669 0.841146 -v 0.087007 0.073646 0.192427 -vn 0.018302 0.413580 0.910284 -v 0.087030 0.073479 0.192517 -vn -0.015901 0.165338 0.986109 -v 0.087048 0.073332 0.192562 -vn 0.011240 0.020822 0.999720 -v 0.087069 0.073148 0.192580 -vn -0.015703 -0.241705 0.970223 -v 0.087090 0.072987 0.192562 -vn 0.016674 -0.380138 0.924779 -v 0.087114 0.072806 0.192502 -vn -0.010818 -0.607906 0.793936 -v 0.087134 0.072666 0.192421 -vn 0.014265 -0.716765 0.697169 -v 0.087155 0.072530 0.192301 -vn -0.018389 -0.872458 0.488342 -v 0.087174 0.072435 0.192174 -vn 0.013973 -0.933474 0.358372 -v 0.087197 0.072356 0.192005 -vn -0.013801 -0.995158 0.097314 -v 0.087218 0.072318 0.191843 -vn 0.018917 -0.998777 -0.045681 -v 0.087241 0.072313 0.191657 -vn -0.018521 -0.955112 -0.295664 -v 0.087260 0.072342 0.191500 -vn 0.003157 -0.894262 -0.447532 -v 0.087281 0.072408 0.191334 -vn -0.017122 -0.753232 -0.657533 -v 0.087301 0.072499 0.191196 -vn 0.016891 -0.651391 -0.758554 -v 0.087325 0.072631 0.191064 -vn -0.003333 -0.438654 -0.898650 -v 0.087346 0.072772 0.190974 -vn 0.021089 -0.287564 -0.957529 -v 0.087367 0.072938 0.190909 -vn -0.023815 -0.044271 -0.998736 -v 0.087385 0.073097 0.190882 -vn 0.004768 0.117718 -0.993036 -v 0.087408 0.073278 0.190888 -vn -0.008453 0.689924 -0.723833 -v 0.087472 0.073740 0.191108 -vn 0.013383 0.514709 -0.857261 -v 0.087452 0.073608 0.191007 -vn -0.010645 0.346303 -0.938062 -v 0.087429 0.073444 0.190929 -vn 0.007467 0.810842 -0.585217 -v 0.087492 0.073854 0.191238 -vn -0.008735 0.999906 0.010536 -v 0.087558 0.074010 0.191731 -vn 0.011741 0.976891 -0.213417 -v 0.087536 0.073992 0.191558 -vn -0.012841 0.919833 -0.392100 -v 0.087513 0.073937 0.191386 -vn 0.012960 0.980894 0.194112 -v 0.087579 0.073992 0.191904 -vn -0.011452 0.677900 0.735065 -v 0.087641 0.073742 0.192349 -vn 0.009326 0.825395 0.564479 -v 0.087619 0.073857 0.192215 -vn -0.013475 0.915197 0.402782 -v 0.087597 0.073942 0.192063 -vn 0.013337 0.528763 0.848665 -v 0.087663 0.073601 0.192456 -vn -0.013447 -0.069441 0.997495 -v 0.087724 0.073109 0.192578 -vn 0.008077 0.150855 0.988523 -v 0.087703 0.073283 0.192571 -vn -0.007732 0.329530 0.944114 -v 0.087684 0.073445 0.192530 -vn 0.011464 -0.254386 0.967035 -v 0.087746 0.072937 0.192550 -vn -0.012673 -0.775695 0.630981 -v 0.087809 0.072505 0.192271 -vn 0.013904 -0.620104 0.784396 -v 0.087790 0.072627 0.192391 -vn -0.009634 -0.464747 0.885391 -v 0.087769 0.072770 0.192485 -vn 0.008908 -0.878565 0.477539 -v 0.087830 0.072411 0.192132 -vn -0.007720 -0.990497 -0.137316 -v 0.087896 0.072318 0.191615 -vn 0.013218 -0.996341 0.084436 -v 0.087874 0.072312 0.191795 -vn -0.012187 -0.962932 0.269469 -v 0.087852 0.072343 0.191964 -vn 0.009408 -0.948440 -0.316819 -v 0.087915 0.072355 0.191457 -vn -0.010400 -0.576858 -0.816778 -v 0.087981 0.072667 0.191037 -vn 0.011149 -0.745382 -0.666544 -v 0.087957 0.072529 0.191160 -vn -0.013943 -0.856449 -0.516043 -v 0.087936 0.072429 0.191296 -vn 0.014339 -0.415376 -0.909537 -v 0.088001 0.072812 0.190954 -vn -0.012840 0.197920 -0.980134 -v 0.088064 0.073325 0.190896 -vn 0.008467 -0.024425 -0.999666 -v 0.088041 0.073140 0.190880 -vn -0.011430 -0.207878 -0.978088 -v 0.088022 0.072980 0.190899 -vn 0.013042 0.378218 -0.925625 -v 0.088085 0.073485 0.190944 -vn -0.014363 0.849547 -0.527317 -v 0.088148 0.073880 0.191278 -vn 0.011257 0.714814 -0.699224 -v 0.088127 0.073769 0.191136 -vn -0.008386 0.573989 -0.818820 -v 0.088108 0.073648 0.191033 -vn 0.010773 0.932751 -0.360361 -v 0.088168 0.073953 0.191424 -vn -0.009801 0.965238 0.261188 -v 0.088234 0.073980 0.191952 -vn 0.014310 0.998888 0.044922 -v 0.088212 0.074009 0.191770 -vn -0.011174 0.989793 -0.142072 -v 0.088192 0.074001 0.191608 -vn 0.008114 0.900704 0.434357 -v 0.088252 0.073926 0.192097 -vn -0.009159 0.467170 0.884120 -v 0.088320 0.073555 0.192482 -vn 0.012779 0.652180 0.757957 -v 0.088296 0.073714 0.192374 -vn -0.013413 0.782852 0.622063 -v 0.088275 0.073826 0.192258 -vn 0.012932 0.296006 0.955098 -v 0.088338 0.073412 0.192542 -vn -0.011915 -0.323636 0.946107 -v 0.088403 0.072883 0.192533 -vn 0.010320 -0.103814 0.994543 -v 0.088379 0.073074 0.192575 -vn -0.014327 0.082269 0.996507 -v 0.088359 0.073230 0.192577 -vn 0.014210 -0.495061 0.868742 -v 0.088423 0.072739 0.192468 -vn -0.013918 -0.910124 0.414102 -v 0.088487 0.072386 0.192080 -vn 0.008246 -0.797490 0.603275 -v 0.088463 0.072485 0.192246 -vn -0.008618 -0.672741 0.739828 -v 0.088446 0.072585 0.192356 -vn 0.012423 -0.971692 0.235926 -v 0.088506 0.072335 0.191933 -vn -0.013757 -0.924519 -0.380887 -v 0.088571 0.072375 0.191403 -vn 0.014025 -0.984964 -0.172191 -v 0.088550 0.072322 0.191585 -vn -0.009906 -0.999865 0.013130 -v 0.088532 0.072310 0.191736 -vn 0.009900 -0.838083 -0.545453 -v 0.088590 0.072445 0.191271 -vn -0.008215 -0.351558 -0.936130 -v 0.088658 0.072868 0.190931 -vn 0.014015 -0.548007 -0.836356 -v 0.088634 0.072691 0.191021 -vn -0.012536 -0.695412 -0.718502 -v 0.088615 0.072572 0.191116 -vn 0.009083 -0.172876 -0.984902 -v 0.088675 0.073006 0.190894 -vn -0.010657 0.443499 -0.896212 -v 0.088743 0.073543 0.190971 -vn 0.012027 0.232001 -0.972641 -v 0.088717 0.073351 0.190901 -vn -0.014350 0.045558 -0.998859 -v 0.088698 0.073203 0.190881 -vn 0.014671 0.602376 -0.798078 -v 0.088761 0.073668 0.191048 -vn 0.961109 0.266011 -0.074217 -v 0.088903 0.073913 0.191668 -vn -0.015554 0.954959 -0.296329 -v 0.088826 0.073975 0.191487 -vn 0.009330 0.867469 -0.497405 -v 0.088801 0.073893 0.191299 -vn -0.012611 0.760475 -0.649244 -v 0.088784 0.073810 0.191182 -vn -0.860886 0.505553 0.057366 -v 0.085522 0.073879 0.191638 -vn 0.222221 0.277888 0.934557 -v 0.088903 0.073490 0.192382 -vn -0.838999 0.100439 0.534783 -v 0.088900 0.073481 0.192379 -vn 0.253665 -0.004697 0.967281 -v 0.088903 0.073296 0.192401 -vn -0.318210 0.288868 -0.902938 -v 0.081492 0.073362 0.191051 -vn -0.426605 0.401307 -0.810531 -v 0.081500 0.073417 0.191072 -vn -0.848836 0.297063 -0.437301 -v 0.081510 0.073421 0.191053 -vn -0.432306 -0.871761 0.230531 -v 0.081880 0.072547 0.191912 -vn -0.418526 -0.904985 0.076411 -v 0.081883 0.072542 0.191890 -vn -0.857391 -0.514568 0.010087 -v 0.081932 0.072460 0.191919 -vn -0.417829 -0.784181 -0.458779 -v 0.081946 0.072587 0.191473 -vn -0.428282 -0.710671 -0.558142 -v 0.081958 0.072626 0.191404 -vn -0.855093 -0.366944 -0.366289 -v 0.082015 0.072541 0.191352 -vn -0.417878 -0.328223 -0.847141 -v 0.082008 0.072860 0.191191 -vn -0.429952 -0.170616 -0.886584 -v 0.082033 0.073017 0.191134 -vn -0.858018 0.016188 -0.513364 -v 0.082100 0.073013 0.191020 -vn -0.419436 -0.008229 -0.907748 -v 0.082038 0.073054 0.191127 -vn -0.857431 0.220312 -0.465053 -v 0.082143 0.073307 0.191020 -vn -0.428694 0.176440 -0.886053 -v 0.082070 0.073260 0.191132 -vn -0.421428 0.286069 -0.860560 -v 0.082073 0.073283 0.191137 -vn -0.405727 -0.634908 -0.657478 -v 0.081975 0.072693 0.191318 -vn -0.415016 -0.551275 -0.723780 -v 0.081983 0.072733 0.191279 -vn -0.855305 -0.188099 -0.482776 -v 0.082060 0.072746 0.191134 -vn -0.429476 -0.442610 -0.787176 -v 0.081998 0.072807 0.191222 -vn -0.855815 -0.481804 -0.188268 -v 0.081976 0.072443 0.191622 -vn -0.403709 -0.851202 -0.335371 -v 0.081934 0.072556 0.191550 -vn -0.401969 -0.824107 -0.399085 -v 0.081943 0.072577 0.191494 -vn -0.415637 -0.906144 -0.078414 -v 0.081913 0.072527 0.191699 -vn -0.426994 -0.875043 -0.227985 -v 0.081922 0.072535 0.191636 -vn -0.419271 -0.695616 0.583378 -v 0.081836 0.072690 0.192175 -vn -0.423442 -0.750560 0.507303 -v 0.081843 0.072656 0.192133 -vn -0.854066 -0.469403 0.224125 -v 0.081889 0.072594 0.192183 -vn -0.417137 -0.780678 0.465337 -v 0.081847 0.072638 0.192109 -vn -0.408084 -0.831018 0.377991 -v 0.081851 0.072624 0.192088 -vn -0.393082 -0.632993 0.666938 -v 0.081821 0.072770 0.192249 -vn -0.854103 -0.344401 0.389739 -v 0.081849 0.072816 0.192368 -vn -0.408824 -0.577005 0.707056 -v 0.081817 0.072790 0.192264 -vn -0.381897 -0.299129 0.874458 -v 0.081785 0.072986 0.192362 -vn -0.394688 -0.377602 0.837639 -v 0.081789 0.072961 0.192354 -vn -0.431824 -0.493279 0.755118 -v 0.081807 0.072850 0.192304 -vn -0.396063 0.113411 0.911193 -v 0.081738 0.073314 0.192376 -vn -0.375351 0.030493 0.926381 -v 0.081752 0.073207 0.192390 -vn -0.853338 -0.161103 0.495844 -v 0.081804 0.073103 0.192452 -vn -0.413564 -0.065366 0.908126 -v 0.081756 0.073178 0.192391 -vn -0.426708 -0.178309 0.886638 -v 0.081766 0.073108 0.192387 -vn -0.371830 0.721154 0.584533 -v 0.081661 0.073743 0.192075 -vn -0.429409 0.588333 0.685180 -v 0.081690 0.073616 0.192225 -vn -0.855129 0.246612 0.456001 -v 0.081721 0.073645 0.192268 -vn -0.412936 0.463675 0.783893 -v 0.081694 0.073594 0.192243 -vn -0.854017 0.052220 0.517618 -v 0.081764 0.073390 0.192417 -vn -0.406224 0.351193 0.843591 -v 0.081722 0.073424 0.192342 -vn -0.425857 0.230239 0.875006 -v 0.081726 0.073398 0.192352 -vn -0.411612 0.764160 0.496623 -v 0.081657 0.073759 0.192048 -vn -0.851582 0.417763 0.316673 -v 0.081677 0.073820 0.192028 -vn -0.344304 0.901960 0.260620 -v 0.081631 0.073830 0.191863 -vn -0.383118 0.863253 0.328656 -v 0.081639 0.073813 0.191924 -vn -0.428008 0.795502 0.428935 -v 0.081651 0.073779 0.192010 -vn -0.361974 0.931295 -0.040803 -v 0.081599 0.073842 0.191633 -vn -0.430435 0.897346 0.097445 -v 0.081615 0.073846 0.191747 -vn -0.852505 0.506678 0.128500 -v 0.081638 0.073885 0.191748 -vn -0.381510 0.901390 0.204808 -v 0.081627 0.073836 0.191832 -vn -0.299032 0.947261 -0.115226 -v 0.081595 0.073838 0.191602 -vn -0.850357 0.519714 -0.082402 -v 0.081593 0.073830 0.191453 -vn -0.324818 0.932561 -0.157553 -v 0.081590 0.073831 0.191569 -vn -0.850230 0.441494 -0.286691 -v 0.081552 0.073668 0.191212 -vn -0.396726 0.747408 -0.532907 -v 0.081541 0.073667 0.191249 -vn -0.304652 0.829713 -0.467722 -v 0.081562 0.073762 0.191381 -vn -0.403360 0.847218 -0.345719 -v 0.081567 0.073778 0.191412 -vn -0.426805 0.869526 -0.248521 -v 0.081575 0.073801 0.191466 -vn -0.349165 0.512510 -0.784485 -v 0.081505 0.073448 0.191086 -vn -0.365228 0.604580 -0.707878 -v 0.081532 0.073616 0.191198 -vn -0.423751 0.673795 -0.605339 -v 0.081536 0.073642 0.191222 -vn 0.058346 0.147771 -0.987299 -v 0.081472 0.073222 0.191021 -vn -0.853772 0.105852 -0.509773 -v 0.081466 0.073127 0.191005 -vn -0.330259 0.105719 -0.937951 -v 0.081467 0.073184 0.191018 -vn -0.847075 -0.015247 -0.531254 -v 0.081447 0.072984 0.191026 -vn -0.859026 -0.102014 -0.501665 -v 0.081427 0.072848 0.191075 -vn -0.334484 -0.248764 -0.908976 -v 0.081437 0.072946 0.191045 -vn -0.432409 -0.316314 -0.844374 -v 0.081424 0.072850 0.191080 -vn -0.421981 -0.164651 -0.891528 -v 0.081441 0.072983 0.191035 -vn -0.410671 -0.096205 -0.906694 -v 0.081443 0.072993 0.191033 -vn -0.429500 0.011795 -0.902990 -v 0.081459 0.073127 0.191017 -vn -0.396381 -0.414631 -0.819123 -v 0.081410 0.072759 0.191129 -vn -0.855063 -0.182013 -0.485530 -v 0.081411 0.072752 0.191130 -vn -0.365364 -0.502889 -0.783334 -v 0.081405 0.072729 0.191149 -vn -0.417407 -0.579200 -0.700214 -v 0.081393 0.072661 0.191203 -vn -0.427654 -0.625212 -0.652857 -v 0.081383 0.072609 0.191255 -vn -0.425450 -0.669063 -0.609383 -v 0.081378 0.072580 0.191289 -vn -0.411818 -0.544147 -0.730965 -v 0.081394 0.072665 0.191200 -vn -0.891994 -0.172113 -0.418001 -v 0.081402 0.072707 0.191163 -vn -0.429675 -0.902343 0.034008 -v 0.081308 0.072423 0.191804 -vn -0.427255 -0.904047 -0.012313 -v 0.081310 0.072422 0.191788 -vn -0.421153 -0.901056 -0.103583 -v 0.081316 0.072421 0.191749 -vn -0.427931 -0.869657 -0.246113 -v 0.081341 0.072449 0.191544 -vn -0.422415 -0.844988 -0.327965 -v 0.081346 0.072460 0.191510 -vn -0.421553 -0.810731 -0.406211 -v 0.081346 0.072462 0.191504 -vn -0.407279 -0.749260 -0.522239 -v 0.081372 0.072556 0.191322 -vn -0.432823 -0.809708 0.396280 -v 0.081268 0.072510 0.192098 -vn -0.417872 -0.857991 0.298720 -v 0.081277 0.072479 0.192032 -vn -0.401883 -0.884743 0.236052 -v 0.081283 0.072463 0.191991 -vn -0.413547 -0.899281 0.142381 -v 0.081295 0.072438 0.191902 -vn -0.397495 -0.459974 0.793991 -v 0.081216 0.072810 0.192400 -vn -0.414622 -0.372382 0.830313 -v 0.081197 0.072943 0.192458 -vn -0.423152 -0.291100 0.858023 -v 0.081192 0.072977 0.192468 -vn -0.425570 -0.249416 0.869875 -v 0.081189 0.073005 0.192475 -vn -0.441616 -0.524326 0.728051 -v 0.081221 0.072774 0.192379 -vn -0.438935 -0.606702 0.662758 -v 0.081232 0.072700 0.192327 -vn -0.401797 -0.703020 0.586790 -v 0.081246 0.072613 0.192245 -vn -0.402815 -0.754465 0.518192 -v 0.081251 0.072584 0.192210 -vn -0.451414 0.429673 0.782053 -v 0.081117 0.073577 0.192382 -vn -0.455792 0.381750 0.804065 -v 0.081121 0.073551 0.192396 -vn -0.424676 0.312875 0.849564 -v 0.081126 0.073510 0.192418 -vn -0.419892 0.195669 0.886231 -v 0.081148 0.073339 0.192477 -vn -0.422553 0.113953 0.899146 -v 0.081151 0.073310 0.192483 -vn -0.424144 0.082061 0.901869 -v 0.081153 0.073288 0.192486 -vn -0.429720 -0.020508 0.902729 -v 0.081157 0.073261 0.192490 -vn -0.417484 -0.136085 0.898437 -v 0.081182 0.073052 0.192484 -vn -0.451139 0.707913 0.543445 -v 0.081076 0.073811 0.192161 -vn -0.410352 0.652071 0.637506 -v 0.081088 0.073755 0.192232 -vn -0.372820 0.619502 0.690813 -v 0.081094 0.073720 0.192269 -vn -0.385943 0.565865 0.728591 -v 0.081098 0.073694 0.192294 -vn -0.372169 0.841816 0.390942 -v 0.081056 0.073893 0.192008 -vn -0.404989 0.793976 0.453415 -v 0.081062 0.073872 0.192056 -vn -0.424131 0.903040 -0.068059 -v 0.081001 0.073934 0.191551 -vn -0.356106 0.933893 0.032123 -v 0.081026 0.073950 0.191752 -vn -0.434998 0.888293 0.147350 -v 0.081032 0.073945 0.191802 -vn -0.433994 0.870907 0.230587 -v 0.081040 0.073934 0.191875 -vn -0.405495 0.855195 0.322825 -v 0.081049 0.073913 0.191953 -vn -0.412596 0.864960 -0.285675 -v 0.080993 0.073918 0.191487 -vn -0.444282 0.821142 -0.358245 -v 0.080967 0.073830 0.191292 -vn -0.422597 0.892302 -0.158775 -v 0.080999 0.073931 0.191539 -vn -0.363325 0.697279 -0.617897 -v 0.080951 0.073743 0.191177 -vn -0.373385 0.631883 -0.679196 -v 0.080937 0.073650 0.191091 -vn -0.428280 0.746619 -0.509055 -v 0.080961 0.073799 0.191246 -vn -0.435340 0.768240 -0.469347 -v 0.080962 0.073803 0.191252 -vn -0.461066 0.160542 -0.872723 -v 0.080885 0.073254 0.190920 -vn -0.353660 0.291333 -0.888847 -v 0.080898 0.073361 0.190942 -vn -0.310068 0.375849 -0.873267 -v 0.080905 0.073415 0.190959 -vn -0.470336 0.492115 -0.732535 -v 0.080926 0.073570 0.191034 -vn -0.452601 0.552074 -0.700262 -v 0.080931 0.073607 0.191058 -vn -0.279828 -0.033384 -0.959470 -v 0.080866 0.073088 0.190915 -vn -0.398271 0.050980 -0.915850 -v 0.080872 0.073147 0.190913 -vn -0.427191 -0.532346 -0.730832 -v 0.080810 0.072630 0.191094 -vn -0.452649 -0.448769 -0.770529 -v 0.080810 0.072633 0.191091 -vn -0.320342 -0.397020 -0.860091 -v 0.080836 0.072821 0.190979 -vn -0.424393 -0.265576 -0.865656 -v 0.080842 0.072875 0.190958 -vn -0.429146 -0.199884 -0.880841 -v 0.080848 0.072928 0.190942 -vn -0.399494 -0.121120 -0.908699 -v 0.080853 0.072969 0.190932 -vn -0.294373 -0.762035 -0.576756 -v 0.080778 0.072448 0.191296 -vn -0.328298 -0.660116 -0.675624 -v 0.080803 0.072588 0.191129 -vn -0.370632 -0.910571 -0.183009 -v 0.080741 0.072327 0.191616 -vn 0.448912 -0.878924 -0.161152 -v 0.080747 0.072339 0.191555 -vn 0.349740 -0.904541 -0.243900 -v 0.080754 0.072357 0.191491 -vn -0.540190 -0.708268 -0.454479 -v 0.080771 0.072416 0.191350 -vn -0.643023 -0.760844 -0.087399 -v 0.080734 0.072320 0.191677 -vn -0.621034 -0.782545 -0.044058 -v 0.080716 0.072322 0.191837 -vn -0.026565 -0.978832 0.202933 -v 0.080708 0.072331 0.191898 -vn -0.865879 0.430751 0.254377 -v 0.088814 0.073855 0.191937 -vn -0.864058 0.299106 0.404893 -v 0.088856 0.073716 0.192194 -vn 0.244594 0.465409 0.850628 -v 0.088903 0.073730 0.192281 -vn 0.262044 0.562987 0.783823 -v 0.088903 0.073771 0.192253 -vn 0.251474 0.634879 0.730541 -v 0.088903 0.073779 0.192247 -vn 0.181567 0.281289 0.942290 -v 0.088903 0.073539 0.192369 -vn -0.413070 0.378378 -0.828374 -v 0.082082 0.073332 0.191151 -vn -0.858270 0.387508 -0.336467 -v 0.082187 0.073580 0.191139 -vn -0.861124 0.483733 -0.156425 -v 0.082226 0.073777 0.191349 -vn -0.858808 0.509549 0.052987 -v 0.082270 0.073878 0.191630 -vn -0.861368 0.444984 0.245019 -v 0.082312 0.073859 0.191922 -vn -0.859410 0.314463 0.403148 -v 0.082353 0.073727 0.192181 -vn -0.859182 0.123693 0.496494 -v 0.082398 0.073496 0.192372 -vn -0.859646 -0.080449 0.504517 -v 0.082437 0.073220 0.192452 -vn -0.860036 -0.276763 0.428649 -v 0.082481 0.072925 0.192415 -vn -0.859995 -0.420165 0.289603 -v 0.082524 0.072671 0.192265 -vn -0.858995 -0.502677 0.097176 -v 0.082564 0.072501 0.192031 -vn -0.858981 -0.498847 -0.115340 -v 0.082609 0.072435 0.191739 -vn -0.860314 -0.412795 -0.299098 -v 0.082649 0.072489 0.191455 -vn -0.861530 -0.255839 -0.438534 -v 0.082692 0.072654 0.191210 -vn -0.860085 -0.068210 -0.505570 -v 0.082735 0.072905 0.191051 -vn -0.860201 0.143727 -0.489282 -v 0.082775 0.073189 0.191005 -vn -0.859541 0.327886 -0.392021 -v 0.082820 0.073480 0.191079 -vn -0.861361 0.451873 -0.232096 -v 0.082860 0.073709 0.191256 -vn -0.860502 0.508377 -0.033008 -v 0.082903 0.073852 0.191513 -vn -0.859615 0.481758 0.170209 -v 0.082947 0.073880 0.191810 -vn -0.860171 0.371517 0.349402 -v 0.082986 0.073793 0.192084 -vn -0.859943 0.200379 0.469411 -v 0.083031 0.073596 0.192309 -vn -0.862698 0.002245 0.505714 -v 0.083072 0.073332 0.192434 -vn -0.860643 -0.199150 0.468650 -v 0.083113 0.073040 0.192445 -vn -0.860581 -0.372092 0.347776 -v 0.083158 0.072762 0.192336 -vn -0.860892 -0.478111 0.173997 -v 0.083197 0.072558 0.192133 -vn -0.860877 -0.507684 -0.033875 -v 0.083241 0.072446 0.191857 -vn -0.861452 -0.454888 -0.225780 -v 0.083284 0.072454 0.191563 -vn -0.860294 -0.327808 -0.390431 -v 0.083324 0.072576 0.191300 -vn -0.860203 -0.140878 -0.490107 -v 0.083369 0.072800 0.191100 -vn -0.861356 0.060777 -0.504353 -v 0.083409 0.073073 0.191010 -vn -0.862595 0.258337 -0.434963 -v 0.083452 0.073369 0.191035 -vn -0.861201 0.407285 -0.304058 -v 0.083495 0.073629 0.191177 -vn -0.861472 0.495442 -0.111367 -v 0.083535 0.073807 0.191403 -vn -0.860576 0.500190 0.096016 -v 0.083580 0.073884 0.191693 -vn -0.862160 0.421224 0.281514 -v 0.083620 0.073841 0.191979 -vn -0.861708 0.273884 0.427139 -v 0.083663 0.073685 0.192230 -vn -0.860739 0.085294 0.501851 -v 0.083707 0.073440 0.192398 -vn -0.861266 -0.124741 0.492607 -v 0.083746 0.073158 0.192455 -vn -0.860787 -0.312312 0.401880 -v 0.083791 0.072865 0.192392 -vn -0.863672 -0.439453 0.246883 -v 0.083832 0.072628 0.192222 -vn -0.861572 -0.504889 0.052731 -v 0.083874 0.072477 0.191972 -vn -0.860587 -0.485609 -0.153541 -v 0.083918 0.072437 0.191676 -vn -0.861338 -0.383045 -0.333728 -v 0.083957 0.072514 0.191399 -vn -0.861458 -0.216188 -0.459513 -v 0.084001 0.072702 0.191167 -vn -0.862669 -0.022881 -0.505250 -v 0.084044 0.072963 0.191032 -vn -0.861283 0.181611 -0.474563 -v 0.084084 0.073252 0.191011 -vn -0.861170 0.358961 -0.359906 -v 0.084129 0.073535 0.191109 -vn -0.862099 0.469310 -0.191138 -v 0.084169 0.073747 0.191304 -vn -0.862787 0.505343 0.015082 -v 0.084212 0.073868 0.191575 -vn -0.862117 0.462080 0.207931 -v 0.084255 0.073871 0.191871 -vn -0.861209 0.340443 0.377383 -v 0.084295 0.073760 0.192137 -vn -0.860875 0.157762 0.483741 -v 0.084340 0.073544 0.192345 -vn -0.862711 -0.041654 0.503978 -v 0.084380 0.073273 0.192446 -vn -0.862702 -0.240615 0.444803 -v 0.084423 0.072978 0.192431 -vn -0.861648 -0.395898 0.317534 -v 0.084467 0.072711 0.192299 -vn -0.862092 -0.489953 0.129396 -v 0.084506 0.072525 0.192080 -vn -0.861396 -0.501900 -0.078055 -v 0.084551 0.072438 0.191794 -vn -0.863741 -0.429016 -0.264379 -v 0.084592 0.072471 0.191505 -vn -0.862273 -0.289840 -0.415306 -v 0.084634 0.072616 0.191250 -vn -0.861309 -0.101709 -0.497797 -v 0.084678 0.072855 0.191072 -vn -0.861986 0.105983 -0.495730 -v 0.084717 0.073135 0.191005 -vn -0.861850 0.296743 -0.411288 -v 0.084762 0.073429 0.191056 -vn -0.864507 0.429132 -0.261675 -v 0.084804 0.073674 0.191218 -vn -0.862496 0.500987 -0.071500 -v 0.084844 0.073833 0.191461 -vn -0.861917 0.487661 0.138875 -v 0.084889 0.073884 0.191756 -vn -0.862619 0.394026 0.317225 -v 0.084929 0.073817 0.192036 -vn -0.862898 0.231546 0.449214 -v 0.084972 0.073639 0.192274 -vn -0.862843 0.042089 0.503717 -v 0.085015 0.073382 0.192420 -vn -0.861801 -0.164466 0.479844 -v 0.085055 0.073095 0.192452 -vn -0.861482 -0.345876 0.371777 -v 0.085100 0.072808 0.192364 -vn -0.863045 -0.460444 0.207712 -v 0.085140 0.072589 0.192176 -vn -0.864070 -0.503362 0.003193 -v 0.085183 0.072458 0.191911 -vn -0.862699 -0.468329 -0.190838 -v 0.085227 0.072444 0.191614 -vn -0.862704 -0.349854 -0.365164 -v 0.085266 0.072545 0.191345 -vn -0.861849 -0.174770 -0.476100 -v 0.085311 0.072753 0.191129 -vn -0.863882 0.023104 -0.503163 -v 0.085352 0.073021 0.191018 -vn -0.862469 0.224202 -0.453742 -v 0.085394 0.073315 0.191021 -vn -0.862071 0.485242 -0.146197 -v 0.085477 0.073781 0.191356 -vn -0.861079 0.383492 -0.333882 -v 0.085438 0.073587 0.191144 -vn -0.864135 0.439376 0.245396 -v 0.085563 0.073857 0.191930 -vn -0.862455 0.304159 0.404548 -v 0.085605 0.073722 0.192188 -vn -0.861293 0.118254 0.494155 -v 0.085649 0.073489 0.192376 -vn -0.861684 -0.084249 0.500402 -v 0.085688 0.073212 0.192453 -vn -0.861585 -0.279246 0.423902 -v 0.085732 0.072917 0.192413 -vn -0.862092 -0.419954 0.283612 -v 0.085775 0.072665 0.192259 -vn -0.860627 -0.495065 -0.119297 -v 0.085860 0.072435 0.191730 -vn -0.860772 -0.500475 0.092719 -v 0.085815 0.072497 0.192023 -vn -0.861886 -0.408024 -0.301114 -v 0.085900 0.072492 0.191448 -vn -0.862927 -0.250849 -0.438670 -v 0.085943 0.072660 0.191204 -vn -0.861648 -0.063404 -0.503530 -v 0.085987 0.072913 0.191048 -vn -0.861674 0.147041 -0.485693 -v 0.086026 0.073198 0.191006 -vn -0.860741 0.330092 -0.387510 -v 0.086071 0.073487 0.191083 -vn -0.862474 0.452189 -0.227296 -v 0.086111 0.073714 0.191262 -vn -0.861702 0.506629 -0.028227 -v 0.086154 0.073854 0.191521 -vn -0.861252 0.367260 0.351235 -v 0.086237 0.073789 0.192091 -vn -0.860856 0.478391 0.173403 -v 0.086198 0.073879 0.191818 -vn -0.860741 0.195753 0.469901 -v 0.086282 0.073589 0.192314 -vn -0.863658 -0.002051 0.504074 -v 0.086323 0.073324 0.192436 -vn -0.861359 -0.202584 0.465854 -v 0.086365 0.073032 0.192443 -vn -0.861505 -0.373881 0.343544 -v 0.086409 0.072755 0.192331 -vn -0.861594 -0.478442 0.169557 -v 0.086448 0.072553 0.192126 -vn -0.861207 -0.506824 -0.038121 -v 0.086493 0.072445 0.191849 -vn -0.862302 -0.451481 -0.229346 -v 0.086535 0.072456 0.191555 -vn -0.860710 -0.136533 -0.490446 -v 0.086620 0.072807 0.191096 -vn -0.860780 -0.324398 -0.392204 -v 0.086575 0.072581 0.191293 -vn -0.861690 0.064986 -0.503256 -v 0.086660 0.073081 0.191009 -vn -0.862807 0.261621 -0.432571 -v 0.086703 0.073377 0.191038 -vn -0.861636 0.409251 -0.300162 -v 0.086746 0.073635 0.191182 -vn -0.860219 0.499813 0.101052 -v 0.086831 0.073884 0.191701 -vn -0.862127 0.418871 0.285104 -v 0.086871 0.073838 0.191987 -vn -0.860525 0.497163 -0.111020 -v 0.086786 0.073811 0.191411 -vn -0.861813 0.270075 0.429346 -v 0.086914 0.073679 0.192236 -vn -0.861195 -0.128642 0.491726 -v 0.086997 0.073150 0.192455 -vn -0.860955 0.081534 0.502104 -v 0.086958 0.073432 0.192402 -vn -0.860532 -0.315722 0.399756 -v 0.087042 0.072858 0.192389 -vn -0.863499 -0.441709 0.243438 -v 0.087083 0.072623 0.192217 -vn -0.861212 -0.505897 0.048812 -v 0.087125 0.072474 0.191964 -vn -0.860947 -0.380823 -0.337259 -v 0.087208 0.072518 0.191392 -vn -0.860425 -0.484787 -0.157003 -v 0.087169 0.072438 0.191668 -vn -0.863890 -0.012451 -0.503527 -v 0.087295 0.072970 0.191030 -vn -0.861192 -0.214046 -0.461012 -v 0.087253 0.072709 0.191162 -vn -0.861117 0.183576 -0.474108 -v 0.087336 0.073261 0.191012 -vn -0.862677 0.363374 -0.351778 -v 0.087380 0.073542 0.191114 -vn -0.863304 0.470567 -0.182410 -v 0.087420 0.073752 0.191311 -vn -0.863726 0.503370 0.024425 -v 0.087463 0.073870 0.191583 -vn -0.863527 0.456305 0.214726 -v 0.087506 0.073869 0.191879 -vn -0.862458 0.332294 0.381770 -v 0.087546 0.073755 0.192144 -vn -0.862107 0.148341 0.484528 -v 0.087591 0.073536 0.192349 -vn -0.863625 -0.049991 0.501650 -v 0.087631 0.073265 0.192447 -vn -0.864676 -0.248800 0.436387 -v 0.087674 0.072970 0.192429 -vn -0.863385 -0.398504 0.309451 -v 0.087718 0.072705 0.192294 -vn -0.863221 -0.490388 0.119870 -v 0.087757 0.072521 0.192073 -vn -0.862389 -0.498709 -0.087032 -v 0.087802 0.072437 0.191785 -vn -0.864387 -0.423559 -0.270986 -v 0.087843 0.072473 0.191497 -vn -0.863263 -0.280760 -0.419465 -v 0.087885 0.072622 0.191244 -vn -0.862475 -0.093056 -0.497470 -v 0.087929 0.072863 0.191068 -vn -0.862856 0.114761 -0.492249 -v 0.087968 0.073143 0.191005 -vn -0.862575 0.303692 -0.404643 -v 0.088013 0.073437 0.191060 -vn -0.865244 0.432420 -0.253706 -v 0.088055 0.073679 0.191224 -vn -0.863221 0.501034 -0.061771 -v 0.088096 0.073836 0.191469 -vn -0.862939 0.483447 0.147020 -v 0.088140 0.073884 0.191764 -vn -0.863226 0.387460 0.323597 -v 0.088180 0.073814 0.192043 -vn -0.863337 0.222593 0.452881 -v 0.088224 0.073633 0.192279 -vn -0.863641 0.032978 0.503028 -v 0.088266 0.073375 0.192422 -vn -0.862489 -0.172904 0.475623 -v 0.088306 0.073087 0.192451 -vn -0.862245 -0.351708 0.364465 -v 0.088351 0.072801 0.192360 -vn -0.863404 -0.463483 0.199294 -v 0.088391 0.072584 0.192170 -vn -0.864611 -0.502401 -0.006446 -v 0.088434 0.072456 0.191903 -vn -0.863328 -0.463949 -0.198534 -v 0.088478 0.072445 0.191607 -vn -0.863297 -0.342137 -0.371026 -v 0.088517 0.072550 0.191338 -vn -0.862371 -0.165588 -0.478432 -v 0.088562 0.072760 0.191125 -vn -0.863983 0.031897 -0.502510 -v 0.088603 0.073029 0.191017 -vn -0.863336 0.231563 -0.448364 -v 0.088645 0.073323 0.191023 -vn -0.862556 0.389506 -0.322929 -v 0.088689 0.073594 0.191149 -vn -0.862844 0.486345 -0.137726 -v 0.088728 0.073785 0.191363 -vn -0.862391 0.501428 0.069651 -v 0.088773 0.073880 0.191646 -vn 0.202432 -0.457382 0.865924 -v 0.088903 0.073047 0.192336 -vn 0.253906 -0.166857 0.952728 -v 0.088903 0.073234 0.192396 -vn 0.029740 -0.954991 -0.295141 -v 0.080685 0.072345 0.191487 -vn 0.104036 -0.971819 0.211529 -v 0.080685 0.072333 0.191927 -vn 0.044828 -0.684383 -0.727744 -v 0.080685 0.072575 0.191113 -vn 0.042010 -0.229489 -0.972404 -v 0.080685 0.072962 0.190903 -vn 0.048771 0.287763 -0.956459 -v 0.080685 0.073402 0.190915 -vn 0.055424 0.729543 -0.681685 -v 0.080685 0.073777 0.191145 -vn 0.063858 0.969588 -0.236267 -v 0.080685 0.073987 0.191532 -vn 0.058849 0.956441 0.285934 -v 0.080685 0.073975 0.191972 -vn 0.062266 0.685303 0.725592 -v 0.080685 0.073744 0.192347 -vn 0.066677 0.230138 0.970871 -v 0.080685 0.073358 0.192556 -vn 0.067799 -0.283888 0.956457 -v 0.080685 0.072918 0.192544 -vn 0.074236 -0.691936 0.718132 -v 0.080685 0.072543 0.192314 -vn -0.710386 0.703554 0.019072 -v 0.059703 0.072665 0.191716 -vn -0.819520 0.369176 -0.438288 -v 0.059703 0.072225 0.191252 -vn -0.994584 -0.098266 -0.033848 -v 0.059703 0.072186 0.191336 -vn -0.994278 -0.106309 -0.010505 -v 0.059703 0.072115 0.191626 -vn -0.994792 -0.101308 0.011245 -v 0.059703 0.072128 0.191925 -vn -0.813591 0.362287 0.454773 -v 0.059703 0.072200 0.192156 -vn -0.103396 -0.406194 -0.907918 -v 0.060303 0.072570 0.190189 -vn -0.101871 -0.562077 -0.820787 -v 0.060303 0.072207 0.190382 -vn -0.378926 -0.536897 -0.753762 -v 0.060073 0.072234 0.190420 -vn -0.112633 -0.387502 0.914962 -v 0.060303 0.072487 0.193236 -vn -0.091250 -0.229236 0.969084 -v 0.060303 0.072766 0.193332 -vn -0.387719 -0.218173 0.895586 -v 0.060073 0.072777 0.193287 -vn -0.698363 0.171028 -0.695009 -v 0.059879 0.073512 0.190298 -vn -0.915553 0.090469 -0.391890 -v 0.059749 0.073466 0.190487 -vn -0.893582 0.226253 -0.387712 -v 0.059749 0.073803 0.190624 -vn -0.985144 -0.138853 0.101048 -v 0.059721 0.074198 0.192324 -vn -0.876799 -0.321296 -0.357760 -v 0.059714 0.074084 0.192434 -vn -0.899508 0.336877 0.278207 -v 0.059749 0.074163 0.192524 -vn -0.981680 0.147740 0.120320 -v 0.059721 0.072091 0.192267 -vn -0.915556 -0.396207 0.069111 -v 0.059749 0.071903 0.191968 -vn -0.983004 0.124537 -0.134883 -v 0.059721 0.073697 0.192798 -vn -0.909213 0.248155 0.334292 -v 0.059749 0.073899 0.192774 -vn -0.698356 0.561153 0.444304 -v 0.059879 0.074316 0.192645 -vn -0.914288 0.379289 0.142185 -v 0.059749 0.074346 0.192209 -vn -0.981679 -0.147743 -0.120323 -v 0.059721 0.074229 0.191193 -vn -0.915557 0.396206 -0.069114 -v 0.059749 0.074417 0.191492 -vn -0.893860 0.398660 -0.205144 -v 0.059749 0.074299 0.191147 -vn -0.905684 0.309923 -0.289282 -v 0.059749 0.074089 0.190850 -vn -0.880536 -0.360545 0.307675 -v 0.059714 0.073865 0.190806 -vn -0.982299 0.108898 0.152414 -v 0.059721 0.073754 0.190692 -vn -0.983003 -0.124557 0.134869 -v 0.059721 0.072623 0.190661 -vn -0.912916 -0.120797 -0.389863 -v 0.059749 0.072745 0.190519 -vn -0.914285 -0.379296 -0.142190 -v 0.059749 0.071974 0.191250 -vn -0.698365 0.663592 0.268199 -v 0.059879 0.074527 0.192282 -vn -0.382692 0.858480 0.341406 -v 0.060073 0.074647 0.192331 -vn -0.917551 -0.017611 -0.397227 -v 0.059749 0.073103 0.190451 -vn -0.698361 -0.031700 -0.715043 -v 0.059879 0.073095 0.190257 -vn -0.385304 -0.049215 -0.921476 -v 0.060073 0.073089 0.190127 -vn -0.698365 0.359910 -0.618669 -v 0.059879 0.073901 0.190455 -vn -0.698364 0.519632 -0.492210 -v 0.059879 0.074230 0.190716 -vn -0.698358 0.637261 -0.325875 -v 0.059879 0.074472 0.191058 -vn -0.698359 0.703256 -0.133139 -v 0.059879 0.074608 0.191455 -vn -0.698361 0.413254 0.584391 -v 0.059879 0.074011 0.192933 -vn -0.378948 0.536890 0.753755 -v 0.060073 0.074086 0.193040 -vn -0.385758 0.724840 0.570788 -v 0.060073 0.074418 0.192725 -vn -0.382693 0.294406 0.875712 -v 0.060073 0.073680 0.193247 -vn -0.698353 0.231872 0.677155 -v 0.059879 0.073637 0.193124 -vn -0.912924 0.120799 0.389842 -v 0.059749 0.073574 0.192940 -vn -0.917552 0.017608 0.397225 -v 0.059749 0.073217 0.193008 -vn -0.698360 0.031701 0.715044 -v 0.059879 0.073225 0.193202 -vn -0.385302 0.049224 0.921477 -v 0.060073 0.073231 0.193332 -vn -0.381155 -0.907257 0.177777 -v 0.060073 0.071584 0.192028 -vn -0.383967 -0.819567 0.425298 -v 0.060073 0.071731 0.192460 -vn -0.698362 -0.703253 0.133138 -v 0.059879 0.071711 0.192004 -vn -0.698367 -0.637252 0.325874 -v 0.059879 0.071847 0.192401 -vn -0.893859 -0.398666 0.205139 -v 0.059749 0.072021 0.192312 -vn -0.917555 -0.395682 -0.039098 -v 0.059749 0.071886 0.191604 -vn -0.698362 -0.712277 -0.070379 -v 0.059879 0.071693 0.191585 -vn -0.385292 -0.917462 -0.099061 -v 0.060073 0.071563 0.191572 -vn -0.698356 -0.663599 -0.268208 -v 0.059879 0.071793 0.191177 -vn -0.382704 -0.858480 -0.341394 -v 0.060073 0.071672 0.191128 -vn -0.899507 -0.336874 -0.278213 -v 0.059749 0.072157 0.190935 -vn -0.909217 -0.248155 -0.334280 -v 0.059749 0.072421 0.190685 -vn -0.698361 -0.561153 -0.444296 -v 0.059879 0.072004 0.190814 -vn -0.698368 -0.413244 -0.584390 -v 0.059879 0.072309 0.190526 -vn -0.385750 -0.724846 -0.570785 -v 0.060073 0.071902 0.190734 -vn -0.387738 0.218154 -0.895583 -v 0.060073 0.073543 0.190172 -vn -0.385677 0.472272 -0.792598 -v 0.060073 0.073967 0.190343 -vn -0.376564 0.672570 -0.637063 -v 0.060073 0.074325 0.190626 -vn -0.383976 0.819564 -0.425297 -v 0.060073 0.074588 0.190999 -vn -0.381157 0.907256 -0.177783 -v 0.060073 0.074736 0.191431 -vn -0.132030 0.936421 -0.325092 -v 0.060303 0.074701 0.191140 -vn -0.098859 0.977739 -0.185077 -v 0.060303 0.074781 0.191423 -vn -0.108872 0.994000 -0.010565 -v 0.060303 0.074809 0.191774 -vn -0.089108 0.983845 0.155272 -v 0.060303 0.074802 0.191892 -vn -0.385305 0.917458 0.099056 -v 0.060073 0.074756 0.191887 -vn -0.698357 0.712280 0.070389 -v 0.059879 0.074627 0.191875 -vn -0.917553 0.395686 0.039102 -v 0.059749 0.074433 0.191855 -vn -0.091345 0.946042 0.310904 -v 0.060303 0.074690 0.192348 -vn -0.091701 0.797127 0.596807 -v 0.060303 0.074454 0.192754 -vn -0.103386 0.884577 0.454792 -v 0.060303 0.074667 0.192402 -vn -0.108866 -0.064407 0.991968 -v 0.060303 0.073115 0.193379 -vn -0.091892 0.099424 0.990793 -v 0.060303 0.073233 0.193378 -vn -0.093822 0.261304 0.960686 -v 0.060303 0.073694 0.193291 -vn -0.103404 0.406200 0.907915 -v 0.060303 0.073750 0.193271 -vn -0.101891 0.562078 0.820784 -v 0.060303 0.074113 0.193077 -vn -0.146032 0.668319 0.729400 -v 0.060303 0.074295 0.192928 -vn -0.698354 -0.171046 0.695015 -v 0.059879 0.072808 0.193161 -vn -0.915558 -0.090473 0.391878 -v 0.059749 0.072854 0.192972 -vn -0.092537 -0.538859 0.837298 -v 0.060303 0.072330 0.193156 -vn -0.385675 -0.472270 0.792601 -v 0.060073 0.072353 0.193116 -vn -0.698362 -0.359917 0.618669 -v 0.059879 0.072419 0.193004 -vn -0.893587 -0.226243 0.387707 -v 0.059749 0.072516 0.192836 -vn -0.982297 -0.108902 -0.152422 -v 0.059721 0.072566 0.192768 -vn -0.880536 0.360538 -0.307681 -v 0.059714 0.072455 0.192654 -vn -0.905679 -0.309931 0.289289 -v 0.059749 0.072231 0.192610 -vn -0.698366 -0.519629 0.492210 -v 0.059879 0.072090 0.192743 -vn -0.376571 -0.672555 0.637075 -v 0.060073 0.071995 0.192833 -vn -0.097151 -0.722571 0.684436 -v 0.060303 0.071962 0.192864 -vn -0.092532 -0.865257 0.492715 -v 0.060303 0.071691 0.192481 -vn -0.103405 -0.884575 -0.454792 -v 0.060303 0.071653 0.191057 -vn -0.091369 -0.946042 -0.310897 -v 0.060303 0.071630 0.191111 -vn -0.089098 -0.983846 -0.155268 -v 0.060303 0.071518 0.191567 -vn -0.108862 -0.994001 0.010574 -v 0.060303 0.071510 0.191685 -vn -0.098860 -0.977741 0.185067 -v 0.060303 0.071539 0.192037 -vn -0.132023 -0.936421 0.325092 -v 0.060303 0.071619 0.192320 -vn -0.091685 -0.797136 -0.596798 -v 0.060303 0.071866 0.190705 -vn -0.985143 0.138863 -0.101042 -v 0.059721 0.072122 0.191136 -vn -0.146049 -0.668298 -0.729416 -v 0.060303 0.072025 0.190532 -vn -0.093819 -0.261268 -0.960696 -v 0.060303 0.072625 0.190169 -vn -0.382713 -0.294392 -0.875708 -v 0.060073 0.072640 0.190212 -vn -0.698362 -0.231860 -0.677150 -v 0.059879 0.072682 0.190335 -vn -0.876804 0.321289 0.357753 -v 0.059714 0.072236 0.191025 -vn -0.091893 -0.099411 -0.990794 -v 0.060303 0.073087 0.190081 -vn -0.108863 0.064386 -0.991969 -v 0.060303 0.073205 0.190080 -vn -0.092559 0.865261 -0.492703 -v 0.060303 0.074629 0.190978 -vn -0.097164 0.722570 -0.684435 -v 0.060303 0.074358 0.190595 -vn -0.092545 0.538857 -0.837299 -v 0.060303 0.073990 0.190303 -vn -0.112634 0.387498 -0.914964 -v 0.060303 0.073832 0.190223 -vn -0.091248 0.229220 -0.969088 -v 0.060303 0.073554 0.190127 -vn 0.381688 0.862730 -0.331679 -v 0.061003 0.074701 0.191140 -vn 0.377167 0.672384 -0.636902 -v 0.061003 0.074358 0.190595 -vn 0.378510 0.925128 0.029455 -v 0.061003 0.074809 0.191774 -vn 0.376570 0.847623 0.373805 -v 0.061003 0.074667 0.192402 -vn 0.382319 0.635448 0.670849 -v 0.061003 0.074295 0.192928 -vn 0.378051 0.328815 0.865424 -v 0.061003 0.073750 0.193271 -vn 0.379800 -0.022393 0.924798 -v 0.061003 0.073115 0.193379 -vn 0.381680 -0.377918 0.843503 -v 0.061003 0.072487 0.193236 -vn 0.377173 -0.672386 0.636896 -v 0.061003 0.071962 0.192864 -vn 0.381690 -0.862731 0.331674 -v 0.061003 0.071619 0.192320 -vn 0.378511 -0.925128 -0.029448 -v 0.061003 0.071510 0.191685 -vn 0.376581 -0.847621 -0.373799 -v 0.061003 0.071653 0.191057 -vn 0.382335 -0.635439 -0.670848 -v 0.061003 0.072025 0.190532 -vn 0.378081 -0.328803 -0.865415 -v 0.061003 0.072570 0.190189 -vn 0.379775 0.022387 -0.924808 -v 0.061003 0.073205 0.190080 -vn 0.381707 0.377911 -0.843495 -v 0.061003 0.073832 0.190223 -vn 0.770260 0.148303 0.620246 -v 0.061103 0.073358 0.192556 -vn 0.906612 -0.011435 0.421810 -v 0.061103 0.073118 0.193279 -vn 0.770261 -0.181682 0.611302 -v 0.061103 0.072918 0.192544 -vn 0.906597 -0.171994 0.385358 -v 0.061103 0.072528 0.193145 -vn 0.770038 -0.462991 0.438955 -v 0.061103 0.072543 0.192314 -vn 0.906607 -0.306357 0.290188 -v 0.061103 0.072035 0.192796 -vn 0.770037 -0.620574 0.148091 -v 0.061103 0.072333 0.191927 -vn 0.770262 0.620243 -0.148307 -v 0.061103 0.073987 0.191532 -vn 0.906603 0.421830 0.011434 -v 0.061103 0.074709 0.191772 -vn 0.770262 0.611300 0.181685 -v 0.061103 0.073975 0.191972 -vn 0.906598 0.385355 0.171994 -v 0.061103 0.074575 0.192361 -vn 0.770264 0.438554 0.462995 -v 0.061103 0.073744 0.192347 -vn 0.906600 0.290198 0.306368 -v 0.061103 0.074226 0.192855 -vn 0.906595 0.150874 0.394110 -v 0.061103 0.073714 0.193177 -vn 0.770264 -0.148311 -0.620239 -v 0.061103 0.072962 0.190903 -vn 0.906595 0.011427 -0.421847 -v 0.061103 0.073202 0.190180 -vn 0.770262 0.181685 -0.611300 -v 0.061103 0.073402 0.190915 -vn 0.906613 0.171987 -0.385322 -v 0.061103 0.073792 0.190314 -vn 0.770262 0.462993 -0.438559 -v 0.061103 0.073777 0.191145 -vn 0.906600 0.306366 -0.290201 -v 0.061103 0.074285 0.190664 -vn 0.906601 0.394100 -0.150861 -v 0.061103 0.074607 0.191175 -vn 0.906602 -0.394095 0.150869 -v 0.061103 0.071712 0.192284 -vn 0.906604 -0.421828 -0.011430 -v 0.061103 0.071610 0.191688 -vn 0.770263 -0.611296 -0.181689 -v 0.061103 0.072345 0.191487 -vn 0.906605 -0.385340 -0.171987 -v 0.061103 0.071744 0.191098 -vn 0.770258 -0.438563 -0.462996 -v 0.061103 0.072575 0.191113 -vn 0.906612 -0.290182 -0.306346 -v 0.061103 0.072094 0.190604 -vn 0.906613 -0.150854 -0.394076 -v 0.061103 0.072606 0.190282 -vn 0.945449 0.312270 0.092811 -v 0.088903 0.073735 0.191901 -vn 0.945181 0.076930 0.317357 -v 0.088903 0.073299 0.192313 -vn 0.945447 0.224036 0.236513 -v 0.088903 0.073573 0.192165 -vn 0.938714 0.267518 -0.217370 -v 0.088903 0.073595 0.191317 -vn 0.945447 0.316845 -0.075762 -v 0.088903 0.073743 0.191590 -vn 0.904974 0.315914 -0.284993 -v 0.089103 0.073450 0.191455 -vn 0.900735 0.422459 -0.101019 -v 0.089103 0.073549 0.191637 -vn 0.900738 0.416362 0.123747 -v 0.089103 0.073543 0.191844 -vn 0.900737 0.298710 0.315348 -v 0.089103 0.073435 0.192020 -vn 0.901039 0.101796 0.421624 -v 0.089103 0.073253 0.192119 -vn 0.901367 -0.124539 0.414762 -v 0.089103 0.073046 0.192113 -vn 0.900740 -0.315347 0.298705 -v 0.089103 0.072869 0.192005 -vn 0.900743 -0.422444 0.101007 -v 0.089103 0.072771 0.191823 -vn 0.900736 -0.416368 -0.123746 -v 0.089103 0.072776 0.191616 -vn 0.900739 -0.298703 -0.315351 -v 0.089103 0.072885 0.191439 -vn 0.900740 -0.101004 -0.422451 -v 0.089103 0.073067 0.191341 -vn 0.904209 0.112410 -0.412033 -v 0.089103 0.073274 0.191346 -vn 1.000000 0.000000 0.000000 -v 0.089103 0.073160 0.191730 -vn -0.948596 0.316372 0.008575 -v 0.060703 0.073044 0.191726 -vn -0.710392 0.703549 0.019042 -v 0.060703 0.072494 0.191146 -vn -0.710390 -0.019047 0.703550 -v 0.060703 0.072613 0.191033 -vn -0.948595 -0.008574 0.316375 -v 0.060703 0.073163 0.191614 -vn -0.710385 -0.019094 0.703554 -v 0.060703 0.073744 0.191063 -vn -0.710387 -0.703552 -0.019089 -v 0.060703 0.073857 0.191183 -vn -0.948596 -0.316373 -0.008574 -v 0.060703 0.073276 0.191733 -vn -0.710388 -0.703551 -0.019071 -v 0.060703 0.073826 0.192314 -vn -0.710389 0.019068 -0.703551 -v 0.060703 0.073707 0.192426 -vn -0.948596 0.008575 -0.316373 -v 0.060703 0.073157 0.191846 -vn -0.710388 0.019057 -0.703552 -v 0.060703 0.072576 0.192396 -vn -0.710390 0.703550 0.019056 -v 0.060703 0.072463 0.192277 -vn -0.710390 -0.702599 -0.041241 -v 0.059703 0.095650 0.155961 -vn -0.813584 -0.399904 0.422087 -v 0.059703 0.096075 0.156439 -vn -0.994792 0.099974 0.019879 -v 0.059703 0.096167 0.156214 -vn -0.994278 0.106818 -0.001362 -v 0.059703 0.096206 0.155918 -vn -0.995324 0.095534 -0.014255 -v 0.059703 0.096159 0.155623 -vn -0.811471 -0.351324 -0.466997 -v 0.059703 0.096128 0.155535 -vn -0.710387 0.041240 -0.702602 -v 0.059703 0.095127 0.156426 -vn -0.819513 -0.426447 -0.382807 -v 0.059703 0.094649 0.156851 -vn -0.994585 -0.036926 0.097149 -v 0.059703 0.094732 0.156892 -vn -0.994278 -0.013850 0.105922 -v 0.059703 0.095020 0.156973 -vn -0.994792 0.008044 0.101612 -v 0.059703 0.095318 0.156969 -vn -0.813581 0.465987 -0.347767 -v 0.059703 0.095552 0.156904 -vn -0.710390 0.702599 0.041241 -v 0.059703 0.094662 0.155903 -vn -0.813579 0.399904 -0.422097 -v 0.059703 0.094236 0.155424 -vn -0.994792 -0.099973 -0.019878 -v 0.059703 0.094145 0.155649 -vn -0.994278 -0.106818 0.001362 -v 0.059703 0.094106 0.155945 -vn -0.995324 -0.095534 0.014255 -v 0.059703 0.094152 0.156240 -vn -0.811471 0.351324 0.466997 -v 0.059703 0.094183 0.156328 -vn -0.513806 -0.723981 -0.460277 -v 0.082409 0.094595 0.155719 -vn -0.518336 -0.808225 -0.279464 -v 0.082405 0.094586 0.155743 -vn 0.128983 -0.943419 -0.305490 -v 0.082103 0.094586 0.155743 -vn -0.562371 -0.099741 0.820847 -v 0.082198 0.095220 0.156528 -vn -0.502259 0.138608 0.853536 -v 0.082188 0.095277 0.156519 -vn 0.076921 0.194609 0.977860 -v 0.082103 0.095277 0.156519 -vn -0.623907 0.300110 0.721577 -v 0.082154 0.095455 0.156452 -vn 0.223592 0.637065 0.737669 -v 0.082103 0.095554 0.156380 -vn -0.684236 0.501580 0.529376 -v 0.082115 0.095633 0.156295 -vn -0.432503 0.722212 0.539770 -v 0.082103 0.095671 0.156240 -vn -0.535608 -0.325224 0.779329 -v 0.082240 0.094978 0.156505 -vn 0.106129 -0.306084 0.946071 -v 0.082103 0.094967 0.156501 -vn -0.531723 -0.575771 0.621095 -v 0.082281 0.094767 0.156389 -vn 0.090274 -0.741319 0.665054 -v 0.082103 0.094707 0.156330 -vn -0.497150 -0.721228 0.482360 -v 0.082296 0.094707 0.156330 -vn -0.528218 -0.799604 0.285689 -v 0.082326 0.094616 0.156193 -vn 0.112167 -0.974053 0.196570 -v 0.082103 0.094568 0.156053 -vn -0.493755 -0.860533 0.125258 -v 0.082350 0.094568 0.156053 -vn -0.537209 -0.835798 -0.113348 -v 0.082365 0.094557 0.155962 -vn -0.523366 -0.599095 -0.605948 -v 0.082452 0.094726 0.155513 -vn -0.130397 -0.696245 -0.705861 -v 0.082103 0.094757 0.155483 -vn -0.496012 -0.469517 -0.730428 -v 0.082459 0.094757 0.155483 -vn 0.486061 -0.613394 -0.622489 -v 0.082103 0.094784 0.155460 -vn 0.515107 -0.507232 -0.690927 -v 0.082109 0.094814 0.155438 -vn -0.514505 -0.266794 -0.814927 -v 0.082492 0.094924 0.155378 -vn 0.516724 -0.256304 -0.816887 -v 0.082153 0.095041 0.155343 -vn -0.496055 -0.083599 -0.864257 -v 0.082513 0.095035 0.155344 -vn -0.513389 0.125926 -0.848867 -v 0.082537 0.095167 0.155332 -vn 0.505401 0.041948 -0.861864 -v 0.082196 0.095287 0.155346 -vn -0.501038 0.306762 -0.809233 -v 0.082567 0.095345 0.155362 -vn 0.500784 0.237800 -0.832266 -v 0.082206 0.095345 0.155362 -vn -0.505353 0.480555 -0.716718 -v 0.082577 0.095400 0.155384 -vn 0.513268 0.406287 -0.755968 -v 0.082236 0.095505 0.155444 -vn -0.516683 0.692393 -0.503618 -v 0.082620 0.095599 0.155527 -vn 0.495993 0.583994 -0.642606 -v 0.082260 0.095604 0.155533 -vn 0.514545 0.701188 -0.493538 -v 0.082281 0.095673 0.155627 -vn -0.515857 0.822077 -0.241001 -v 0.082663 0.095724 0.155738 -vn 0.495915 0.813335 -0.304228 -v 0.082314 0.095743 0.155810 -vn -0.495270 0.866376 -0.064041 -v 0.082675 0.095743 0.155811 -vn 0.513809 0.847381 -0.133962 -v 0.082321 0.095751 0.155854 -vn -0.509786 0.846348 0.154317 -v 0.082703 0.095754 0.155975 -vn 0.503014 0.860717 0.078378 -v 0.082364 0.095732 0.156099 -vn -0.487308 0.808037 0.331070 -v 0.082730 0.095725 0.156121 -vn 0.505692 0.825532 0.250543 -v 0.082368 0.095725 0.156121 -vn -0.511489 0.689795 0.512408 -v 0.082748 0.095686 0.156213 -vn 0.507606 0.738452 0.443874 -v 0.082408 0.095616 0.156317 -vn -0.507269 0.557136 0.657478 -v 0.082784 0.095555 0.156380 -vn 0.493173 0.614677 0.615591 -v 0.082422 0.095554 0.156380 -vn -0.502126 0.413649 0.759450 -v 0.082788 0.095533 0.156398 -vn 0.513102 0.472979 0.716252 -v 0.082448 0.095429 0.156466 -vn -0.510660 0.204418 0.835128 -v 0.082830 0.095317 0.156510 -vn 0.494335 0.284835 0.821281 -v 0.082477 0.095277 0.156519 -vn -0.496584 0.029889 0.867474 -v 0.082838 0.095277 0.156519 -vn 0.512782 0.098222 0.852882 -v 0.082492 0.095190 0.156531 -vn -0.516332 -0.182335 0.836753 -v 0.082875 0.095070 0.156525 -vn 0.497752 -0.124043 0.858403 -v 0.082531 0.094967 0.156501 -vn -0.496486 -0.356223 0.791585 -v 0.082892 0.094967 0.156501 -vn 0.512049 -0.281442 0.811540 -v 0.082533 0.094951 0.156495 -vn -0.509821 -0.534102 0.674402 -v 0.082914 0.094846 0.156446 -vn 0.506715 -0.470789 0.722217 -v 0.082575 0.094744 0.156368 -vn -0.496622 -0.676810 0.543411 -v 0.082946 0.094707 0.156330 -vn 0.500263 -0.622709 0.601640 -v 0.082585 0.094707 0.156330 -vn -0.508763 -0.778517 0.367522 -v 0.082958 0.094665 0.156277 -vn 0.509684 -0.739937 0.438994 -v 0.082620 0.094603 0.156164 -vn -0.516840 -0.851781 0.085709 -v 0.083000 0.094569 0.156055 -vn 0.498035 -0.830529 0.249366 -v 0.082639 0.094568 0.156053 -vn 0.516890 -0.853071 0.071370 -v 0.082659 0.094556 0.155930 -vn -0.512389 -0.833447 -0.206941 -v 0.083041 0.094567 0.155814 -vn 0.495181 -0.856865 -0.143452 -v 0.082693 0.094586 0.155743 -vn -0.494535 -0.777871 -0.387753 -v 0.083055 0.094586 0.155743 -vn 0.511578 -0.798097 -0.318323 -v 0.082704 0.094608 0.155688 -vn -0.513168 -0.648201 -0.562579 -v 0.083086 0.094665 0.155586 -vn 0.516651 -0.644506 -0.563634 -v 0.082746 0.094749 0.155490 -vn -0.490116 -0.535290 -0.687933 -v 0.083109 0.094757 0.155483 -vn -0.509747 -0.344034 -0.788543 -v 0.083125 0.094838 0.155423 -vn 0.510629 -0.416643 -0.752108 -v 0.082787 0.094957 0.155366 -vn -0.503668 -0.146910 -0.851314 -v 0.083163 0.095035 0.155344 -vn 0.493271 -0.223856 -0.840579 -v 0.082802 0.095035 0.155344 -vn -0.504766 0.035682 -0.862518 -v 0.083169 0.095069 0.155338 -vn 0.509784 -0.036723 -0.859518 -v 0.082832 0.095203 0.155333 -vn -0.512918 0.242886 -0.823360 -v 0.083212 0.095312 0.155352 -vn 0.495442 0.179559 -0.849880 -v 0.082856 0.095345 0.155362 -vn -0.496586 0.403356 -0.768574 -v 0.083217 0.095345 0.155362 -vn 0.515740 0.346711 -0.783456 -v 0.082871 0.095432 0.155399 -vn -0.513026 0.578303 -0.634326 -v 0.083252 0.095527 0.155460 -vn 0.497469 0.536132 -0.681973 -v 0.082910 0.095604 0.155533 -vn -0.494477 0.711253 -0.499612 -v 0.083271 0.095604 0.155533 -vn 0.509966 0.656043 -0.556366 -v 0.082915 0.095623 0.155556 -vn -0.513331 0.801642 -0.306369 -v 0.083297 0.095686 0.155650 -vn 0.503339 0.780034 -0.371749 -v 0.082958 0.095735 0.155774 -vn -0.499020 0.856041 -0.134806 -v 0.083325 0.095743 0.155810 -vn 0.505762 0.839534 -0.198462 -v 0.082964 0.095743 0.155811 -vn -0.506889 0.859247 0.068984 -v 0.083336 0.095753 0.155879 -vn 0.513058 0.858328 -0.006689 -v 0.082998 0.095750 0.156013 -vn -0.516992 0.776269 0.360730 -v 0.083380 0.095725 0.156122 -vn 0.484936 0.847920 0.214172 -v 0.083018 0.095725 0.156121 -vn 0.510035 0.774550 0.374081 -v 0.083043 0.095666 0.156247 -vn -0.514902 0.613428 0.598817 -v 0.083423 0.095601 0.156334 -vn 0.494923 0.659974 0.565230 -v 0.083072 0.095555 0.156380 -vn -0.495049 0.483272 0.722063 -v 0.083434 0.095554 0.156380 -vn 0.515030 0.521299 0.680435 -v 0.083083 0.095502 0.156422 -vn -0.510227 0.279798 0.813254 -v 0.083463 0.095409 0.156476 -vn 0.516978 0.263899 0.814304 -v 0.083127 0.095276 0.156519 -vn -0.484867 0.113231 0.867227 -v 0.083488 0.095277 0.156519 -vn -0.513112 -0.107495 0.851564 -v 0.083508 0.095167 0.156531 -vn 0.506628 -0.035428 0.861437 -v 0.083170 0.095030 0.156518 -vn -0.505890 -0.295269 0.810488 -v 0.083542 0.094967 0.156501 -vn 0.499980 -0.235757 0.833330 -v 0.083181 0.094967 0.156501 -vn -0.503468 -0.459908 0.731440 -v 0.083548 0.094932 0.156488 -vn 0.513221 -0.400910 0.758864 -v 0.083210 0.094811 0.156423 -vn -0.510003 -0.628631 0.587128 -v 0.083591 0.094729 0.156353 -vn 0.494355 -0.582090 0.645588 -v 0.083235 0.094707 0.156330 -vn -0.497468 -0.739509 0.453489 -v 0.083596 0.094707 0.156330 -vn 0.512872 -0.699799 0.497236 -v 0.083255 0.094641 0.156241 -vn -0.515570 -0.818344 0.253971 -v 0.083635 0.094595 0.156146 -vn 0.496166 -0.811961 0.307471 -v 0.083289 0.094568 0.156053 -vn -0.495367 -0.864913 0.080848 -v 0.083650 0.094568 0.156053 -vn 0.513270 -0.846855 0.139253 -v 0.083295 0.094562 0.156014 -vn -0.510011 -0.849457 -0.135317 -v 0.083674 0.094556 0.155911 -vn 0.504176 -0.860594 -0.072006 -v 0.083338 0.094578 0.155770 -vn -0.494605 -0.808521 -0.318841 -v 0.083705 0.094586 0.155743 -vn 0.504902 -0.826645 -0.248459 -v 0.083343 0.094586 0.155743 -vn -0.510683 -0.700302 -0.498779 -v 0.083719 0.094616 0.155671 -vn 0.509461 -0.740163 -0.438872 -v 0.083382 0.094692 0.155551 -vn -0.516978 -0.488855 -0.702677 -v 0.083760 0.094762 0.155479 -vn 0.492669 -0.616544 -0.614126 -v 0.083397 0.094757 0.155483 -vn 0.513352 -0.478044 -0.712702 -v 0.083422 0.094877 0.155400 -vn -0.511598 -0.227554 -0.828545 -v 0.083801 0.094973 0.155360 -vn 0.493982 -0.288189 -0.820322 -v 0.083452 0.095035 0.155344 -vn -0.494832 -0.046183 -0.867761 -v 0.083813 0.095035 0.155344 -vn 0.512651 -0.098731 -0.852901 -v 0.083466 0.095116 0.155333 -vn -0.517061 0.167633 -0.839373 -v 0.083846 0.095219 0.155335 -vn 0.517365 0.197127 -0.832751 -v 0.083508 0.095356 0.155366 -vn 0.517170 0.649400 0.557507 -v 0.083720 0.095566 0.156369 -vn -0.513530 0.659902 0.548468 -v 0.084057 0.095659 0.156258 -vn 0.511094 0.800484 0.313064 -v 0.083678 0.095706 0.156170 -vn -0.493871 0.785714 0.372485 -v 0.084030 0.095725 0.156121 -vn 0.495516 0.857292 0.139694 -v 0.083668 0.095725 0.156121 -vn -0.512374 0.837233 0.191086 -v 0.084012 0.095748 0.156027 -vn 0.515683 0.853469 -0.075250 -v 0.083633 0.095756 0.155928 -vn -0.497451 0.867035 -0.028155 -v 0.083975 0.095743 0.155811 -vn 0.496545 0.830410 -0.252710 -v 0.083614 0.095743 0.155810 -vn -0.512307 0.837065 -0.192000 -v 0.083972 0.095738 0.155787 -vn 0.509780 0.736620 -0.444427 -v 0.083594 0.095707 0.155694 -vn -0.506494 0.768995 -0.390012 -v 0.083929 0.095633 0.155567 -vn 0.499530 0.621559 -0.603435 -v 0.083560 0.095604 0.155533 -vn -0.502109 0.667275 -0.550119 -v 0.083921 0.095604 0.155533 -vn 0.508134 0.465041 -0.724939 -v 0.083549 0.095564 0.155492 -vn -0.509736 0.518863 -0.686259 -v 0.083885 0.095446 0.155406 -vn -0.498639 0.339735 -0.797458 -v 0.083867 0.095345 0.155362 -vn 0.517822 -0.271529 -0.811254 -v 0.084101 0.095030 0.155345 -vn -0.493009 -0.123936 -0.861151 -v 0.084463 0.095035 0.155344 -vn -0.510542 -0.297828 -0.806626 -v 0.084434 0.094883 0.155397 -vn 0.514618 -0.525546 -0.677473 -v 0.084057 0.094805 0.155445 -vn -0.494819 -0.497041 -0.712814 -v 0.084409 0.094757 0.155483 -vn 0.494984 -0.662336 -0.562408 -v 0.084047 0.094757 0.155483 -vn -0.515135 -0.624640 -0.586907 -v 0.084395 0.094696 0.155546 -vn 0.512734 -0.773147 -0.373293 -v 0.084017 0.094643 0.155620 -vn -0.498809 -0.758551 -0.419274 -v 0.084355 0.094586 0.155743 -vn 0.495440 -0.845669 -0.198450 -v 0.083993 0.094586 0.155743 -vn -0.509541 -0.820040 -0.260581 -v 0.084351 0.094580 0.155763 -vn 0.513060 -0.858256 0.012879 -v 0.083972 0.094561 0.155855 -vn -0.505116 -0.861926 -0.044065 -v 0.084308 0.094560 0.156006 -vn 0.505243 -0.839331 0.200632 -v 0.083939 0.094568 0.156053 -vn -0.504572 -0.851049 0.145336 -v 0.084300 0.094568 0.156053 -vn 0.504626 -0.776472 0.377418 -v 0.083932 0.094578 0.156095 -vn -0.513200 -0.794902 0.323661 -v 0.084268 0.094637 0.156233 -vn 0.509722 -0.652512 0.560724 -v 0.083889 0.094692 0.156312 -vn -0.495160 -0.700789 0.513529 -v 0.084246 0.094707 0.156330 -vn 0.498356 -0.532770 0.683957 -v 0.083885 0.094707 0.156330 -vn -0.512738 -0.565747 0.645779 -v 0.084223 0.094803 0.156417 -vn 0.515185 -0.343331 0.785308 -v 0.083845 0.094884 0.156467 -vn -0.495327 -0.389737 0.776374 -v 0.084192 0.094967 0.156501 -vn 0.494792 -0.176246 0.850952 -v 0.083831 0.094967 0.156501 -vn -0.514224 -0.221226 0.828633 -v 0.084183 0.095020 0.156516 -vn 0.510248 0.043242 0.858940 -v 0.083806 0.095114 0.156530 -vn -0.502478 -0.010934 0.864521 -v 0.084140 0.095265 0.156521 -vn 0.492572 0.225794 0.840470 -v 0.083777 0.095277 0.156519 -vn -0.507317 0.157364 0.847270 -v 0.084138 0.095277 0.156519 -vn 0.512258 0.421757 0.748139 -v 0.083761 0.095360 0.156496 -vn -0.509400 0.361802 0.780775 -v 0.084096 0.095493 0.156428 -vn -0.497929 0.541229 0.677597 -v 0.084084 0.095555 0.156380 -vn -0.512576 0.088998 -0.854017 -v 0.084479 0.095122 0.155333 -vn 0.508122 0.028652 -0.860809 -v 0.084144 0.095276 0.155344 -vn -0.509424 0.283881 -0.812341 -v 0.084517 0.095345 0.155362 -vn 0.499469 0.233878 -0.834165 -v 0.084156 0.095345 0.155362 -vn -0.501825 0.439002 -0.745284 -v 0.084520 0.095360 0.155367 -vn 0.513509 0.395319 -0.761598 -v 0.084184 0.095496 0.155437 -vn -0.511051 0.611297 -0.604271 -v 0.084561 0.095567 0.155494 -vn 0.493756 0.579668 -0.648221 -v 0.084210 0.095604 0.155533 -vn -0.495633 0.731909 -0.467608 -v 0.084571 0.095604 0.155533 -vn 0.512276 0.697690 -0.500802 -v 0.084229 0.095667 0.155618 -vn -0.515400 0.813605 -0.269090 -v 0.084606 0.095708 0.155697 -vn 0.496809 0.810212 -0.311025 -v 0.084264 0.095743 0.155810 -vn -0.496432 0.862572 -0.097593 -v 0.084625 0.095743 0.155810 -vn 0.513026 0.846137 -0.144414 -v 0.084269 0.095749 0.155844 -vn -0.510079 0.852236 0.116247 -v 0.084645 0.095756 0.155930 -vn 0.505654 0.860265 0.065254 -v 0.084312 0.095735 0.156088 -vn -0.500710 0.809314 0.307085 -v 0.084680 0.095725 0.156121 -vn 0.504478 0.827491 0.246497 -v 0.084318 0.095725 0.156121 -vn -0.508500 0.714969 0.479841 -v 0.084689 0.095706 0.156172 -vn 0.509573 0.743325 0.433363 -v 0.084356 0.095623 0.156308 -vn -0.518026 0.513690 0.683938 -v 0.084731 0.095566 0.156370 -vn 0.491129 0.617745 0.614152 -v 0.084372 0.095554 0.156380 -vn 0.513938 0.482998 0.708930 -v 0.084396 0.095439 0.156460 -vn -0.512713 0.250670 0.821151 -v 0.084772 0.095360 0.156496 -vn 0.494120 0.291853 0.818943 -v 0.084427 0.095277 0.156519 -vn -0.493840 0.063124 0.867259 -v 0.084788 0.095277 0.156519 -vn 0.512237 0.104330 0.852484 -v 0.084440 0.095201 0.156530 -vn -0.513992 -0.154601 0.843748 -v 0.084817 0.095115 0.156530 -vn 0.518045 -0.189372 0.834127 -v 0.084482 0.094961 0.156499 -vn -0.495014 -0.319576 0.807980 -v 0.084842 0.094967 0.156501 -vn -0.509517 -0.503362 0.697868 -v 0.084856 0.094885 0.156467 -vn 0.509781 -0.458815 0.727745 -v 0.084523 0.094752 0.156375 -vn -0.506353 -0.658428 0.556847 -v 0.084896 0.094707 0.156330 -vn 0.499173 -0.620332 0.604991 -v 0.084535 0.094707 0.156330 -vn -0.504262 -0.758933 0.411995 -v 0.084900 0.094693 0.156314 -vn 0.510230 -0.733003 0.449857 -v 0.084568 0.094607 0.156174 -vn -0.513747 -0.830921 0.213619 -v 0.084943 0.094579 0.156097 -vn 0.495712 -0.829825 0.256242 -v 0.084589 0.094568 0.156053 -vn -0.495998 -0.867232 0.043536 -v 0.084950 0.094568 0.156053 -vn 0.515192 -0.853420 0.079067 -v 0.084607 0.094556 0.155941 -vn -0.512242 -0.840963 -0.174325 -v 0.084983 0.094560 0.155859 -vn 0.496251 -0.857532 -0.135548 -v 0.084643 0.094586 0.155743 -vn -0.494185 -0.792819 -0.356679 -v 0.085005 0.094586 0.155743 -vn 0.510920 -0.802591 -0.307910 -v 0.084652 0.094603 0.155698 -vn -0.513576 -0.671509 -0.534149 -v 0.085028 0.094640 0.155624 -vn 0.502740 -0.701258 -0.505460 -v 0.084694 0.094742 0.155497 -vn -0.503267 -0.548737 -0.667540 -v 0.085059 0.094757 0.155483 -vn 0.509151 -0.583439 -0.632743 -v 0.084697 0.094757 0.155483 -vn -0.506989 -0.381872 -0.772746 -v 0.085068 0.094801 0.155448 -vn 0.512545 -0.423602 -0.746900 -v 0.084735 0.094946 0.155369 -vn -0.518001 -0.093296 -0.850277 -v 0.085111 0.095024 0.155346 -vn 0.491908 -0.227215 -0.840476 -v 0.084752 0.095035 0.155344 -vn 0.511024 -0.049863 -0.858119 -v 0.084780 0.095192 0.155333 -vn -0.515642 0.199066 -0.833358 -v 0.085154 0.095270 0.155342 -vn 0.494653 0.172474 -0.851804 -v 0.084806 0.095345 0.155362 -vn -0.494789 0.375220 -0.783833 -v 0.085167 0.095345 0.155362 -vn 0.515070 0.340059 -0.786805 -v 0.084819 0.095423 0.155394 -vn -0.509609 0.556596 -0.656125 -v 0.085194 0.095490 0.155433 -vn 0.499530 0.528855 -0.686136 -v 0.084860 0.095604 0.155533 -vn -0.488896 0.688053 -0.536249 -v 0.085221 0.095604 0.155533 -vn 0.509636 0.648884 -0.564997 -v 0.084863 0.095616 0.155547 -vn -0.512839 0.787901 -0.340893 -v 0.085239 0.095663 0.155611 -vn 0.506132 0.772618 -0.383265 -v 0.084906 0.095732 0.155763 -vn -0.508711 0.846662 -0.156128 -v 0.085275 0.095743 0.155810 -vn 0.505054 0.838984 -0.202551 -v 0.084914 0.095743 0.155811 -vn -0.503489 0.863787 0.019268 -v 0.085279 0.095748 0.155835 -vn 0.513368 0.857955 -0.019147 -v 0.084946 0.095752 0.156002 -vn -0.510790 0.826361 0.237109 -v 0.085322 0.095738 0.156078 -vn 0.494578 0.846957 0.195079 -v 0.084968 0.095725 0.156121 -vn -0.496895 0.766829 0.406285 -v 0.085330 0.095725 0.156121 -vn 0.512137 0.775216 0.369805 -v 0.084991 0.095672 0.156238 -vn -0.515094 0.635464 0.575207 -v 0.085366 0.095629 0.156300 -vn 0.495466 0.664774 0.559097 -v 0.085022 0.095555 0.156380 -vn -0.495539 0.510480 0.702746 -v 0.085384 0.095554 0.156380 -vn 0.514492 0.529585 0.674417 -v 0.085031 0.095511 0.156415 -vn -0.510686 0.315794 0.799671 -v 0.085405 0.095449 0.156455 -vn 0.519176 0.279104 0.807810 -v 0.085075 0.095287 0.156517 -vn -0.499905 0.134441 0.855582 -v 0.085438 0.095277 0.156519 -vn -0.511504 -0.069201 0.856490 -v 0.085450 0.095213 0.156529 -vn 0.509573 -0.021482 0.860159 -v 0.085118 0.095041 0.156520 -vn -0.518799 -0.348040 0.780843 -v 0.085491 0.094972 0.156503 -vn 0.499096 -0.232491 0.834776 -v 0.085131 0.094967 0.156501 -vn 0.514147 -0.389551 0.764135 -v 0.085158 0.094820 0.156429 -vn -0.512309 -0.593323 0.620892 -v 0.085532 0.094762 0.156384 -vn 0.493641 -0.576717 0.650935 -v 0.085185 0.094707 0.156330 -vn -0.494361 -0.723456 0.481890 -v 0.085546 0.094707 0.156330 -vn 0.512096 -0.695509 0.504009 -v 0.085203 0.094647 0.156250 -vn -0.512228 -0.811390 0.281549 -v 0.085577 0.094613 0.156187 -vn 0.497800 -0.808181 0.314705 -v 0.085239 0.094568 0.156053 -vn -0.490214 -0.862865 0.123102 -v 0.085600 0.094568 0.156053 -vn 0.513081 -0.845283 0.149149 -v 0.085244 0.094563 0.156024 -vn -0.509934 -0.854718 -0.097082 -v 0.085616 0.094556 0.155956 -vn 0.507384 -0.859749 -0.058262 -v 0.085286 0.094575 0.155781 -vn -0.505524 -0.810584 -0.295632 -v 0.085655 0.094586 0.155743 -vn 0.504423 -0.828051 -0.244722 -v 0.085293 0.094586 0.155743 -vn -0.506394 -0.729103 -0.460407 -v 0.085660 0.094597 0.155713 -vn 0.510039 -0.746338 -0.427599 -v 0.085330 0.094685 0.155559 -vn -0.513492 -0.594017 -0.619250 -v 0.085703 0.094731 0.155508 -vn 0.487276 -0.621302 -0.613633 -v 0.085347 0.094757 0.155483 -vn -0.497186 -0.464923 -0.732566 -v 0.085709 0.094757 0.155483 -vn 0.511690 -0.486247 -0.708334 -v 0.085370 0.094868 0.155405 -vn -0.512040 -0.262675 -0.817812 -v 0.085743 0.094930 0.155376 -vn 0.494711 -0.295881 -0.817139 -v 0.085402 0.095035 0.155344 -vn -0.493796 -0.080227 -0.865869 -v 0.085763 0.095035 0.155344 -vn 0.512190 -0.109726 -0.851835 -v 0.085414 0.095105 0.155334 -vn -0.514207 0.136427 -0.846746 -v 0.085788 0.095174 0.155332 -vn 0.519262 0.181432 -0.835134 -v 0.085456 0.095346 0.155362 -vn -0.502130 0.307669 -0.808211 -v 0.085817 0.095345 0.155362 -vn -0.509081 0.487507 -0.709347 -v 0.085828 0.095406 0.155386 -vn 0.511682 0.452337 -0.730460 -v 0.085497 0.095556 0.155484 -vn -0.519388 0.697508 -0.493679 -v 0.085871 0.095604 0.155532 -vn 0.499134 0.619252 -0.606129 -v 0.085510 0.095604 0.155533 -vn 0.511008 0.729121 -0.455251 -v 0.085542 0.095703 0.155684 -vn -0.515353 0.824022 -0.235369 -v 0.085914 0.095726 0.155745 -vn 0.495315 0.828881 -0.260038 -v 0.085564 0.095743 0.155810 -vn -0.495210 0.866730 -0.059551 -v 0.085925 0.095743 0.155811 -vn 0.515033 0.853180 -0.082618 -v 0.085582 0.095756 0.155917 -vn -0.508591 0.845630 0.162003 -v 0.085954 0.095754 0.155982 -vn 0.497369 0.857599 0.130951 -v 0.085618 0.095725 0.156121 -vn -0.484611 0.808936 0.332829 -v 0.085980 0.095725 0.156121 -vn 0.511051 0.804423 0.302869 -v 0.085626 0.095711 0.156160 -vn -0.513322 0.683022 0.519597 -v 0.085999 0.095682 0.156219 -vn 0.504269 0.704639 0.499196 -v 0.085668 0.095574 0.156362 -vn -0.508107 0.555677 0.658065 -v 0.086034 0.095555 0.156380 -vn 0.509286 0.584782 0.631394 -v 0.085672 0.095554 0.156380 -vn -0.505381 0.404267 0.762337 -v 0.086039 0.095528 0.156402 -vn 0.512908 0.428939 0.743597 -v 0.085709 0.095371 0.156492 -vn -0.510740 0.198092 0.836603 -v 0.086082 0.095310 0.156511 -vn 0.488467 0.230403 0.841614 -v 0.085727 0.095277 0.156519 -vn -0.498437 0.023945 0.866595 -v 0.086088 0.095277 0.156519 -vn 0.509057 0.053362 0.859077 -v 0.085754 0.095125 0.156531 -vn -0.515146 -0.186810 0.836497 -v 0.086126 0.095064 0.156524 -vn 0.497927 -0.170460 0.850301 -v 0.085781 0.094967 0.156501 -vn -0.497382 -0.361835 0.788471 -v 0.086142 0.094967 0.156501 -vn -0.518052 -0.543486 0.660488 -v 0.086165 0.094841 0.156442 -vn 0.522484 -0.336886 0.783274 -v 0.085793 0.094894 0.156471 -vn -0.501594 -0.672869 0.543738 -v 0.086196 0.094707 0.156330 -vn 0.522550 -0.580100 0.624841 -v 0.085837 0.094699 0.156320 -vn -0.512221 -0.780980 0.357350 -v 0.086210 0.094661 0.156271 -vn 0.508291 -0.768223 0.389196 -v 0.085880 0.094581 0.156105 -vn -0.519988 -0.850873 0.075016 -v 0.086251 0.094567 0.156049 -vn 0.505350 -0.838370 0.204343 -v 0.085889 0.094568 0.156053 -vn 0.514044 -0.857388 0.025395 -v 0.085920 0.094559 0.155866 -vn -0.512202 -0.832004 -0.213118 -v 0.086292 0.094569 0.155807 -vn 0.494218 -0.848050 -0.191205 -v 0.085943 0.094586 0.155743 -vn -0.495389 -0.775049 -0.392287 -v 0.086305 0.094586 0.155743 -vn 0.511959 -0.776958 -0.366380 -v 0.085965 0.094637 0.155630 -vn -0.511406 -0.644930 -0.567917 -v 0.086337 0.094669 0.155581 -vn 0.498629 -0.665063 -0.555932 -v 0.085997 0.094757 0.155483 -vn -0.500428 0.406613 -0.764354 -v 0.086467 0.095345 0.155362 -vn -0.515965 0.249987 -0.819321 -v 0.086463 0.095319 0.155354 -vn 0.510664 0.014251 -0.859662 -v 0.086092 0.095266 0.155342 -vn -0.509768 0.045520 -0.859107 -v 0.086420 0.095076 0.155337 -vn 0.526949 -0.292351 -0.798033 -v 0.086049 0.095019 0.155347 -vn -0.510173 -0.149101 -0.847049 -v 0.086413 0.095035 0.155344 -vn 0.521549 -0.530267 -0.668434 -v 0.086006 0.094797 0.155451 -vn -0.519074 -0.324186 -0.790864 -v 0.086376 0.094843 0.155419 -vn -0.487351 -0.534283 -0.690675 -v 0.086359 0.094757 0.155483 -vn 0.497081 0.229574 -0.836783 -v 0.086106 0.095345 0.155362 -vn 0.512737 0.386684 -0.766535 -v 0.086132 0.095487 0.155431 -vn -0.512178 0.582015 -0.631611 -v 0.086503 0.095532 0.155464 -vn 0.493974 0.573238 -0.653749 -v 0.086160 0.095604 0.155533 -vn -0.493999 0.714079 -0.496040 -v 0.086521 0.095604 0.155533 -vn 0.512282 0.693239 -0.506939 -v 0.086177 0.095661 0.155608 -vn -0.513070 0.804803 -0.298414 -v 0.086548 0.095689 0.155656 -vn 0.500681 0.805392 -0.317274 -v 0.086214 0.095743 0.155810 -vn -0.499084 0.856315 -0.132817 -v 0.086575 0.095743 0.155810 -vn -0.510309 0.856316 0.079425 -v 0.086588 0.095754 0.155885 -vn 0.515636 0.842565 -0.155577 -v 0.086218 0.095748 0.155833 -vn 0.509936 0.858692 0.051112 -v 0.086260 0.095738 0.156077 -vn -0.525898 0.763871 0.374075 -v 0.086631 0.095722 0.156129 -vn 0.509059 0.824860 0.245895 -v 0.086268 0.095725 0.156121 -vn -0.521257 0.606972 0.599897 -v 0.086674 0.095596 0.156339 -vn 0.517957 0.748677 0.413768 -v 0.086304 0.095630 0.156300 -vn -0.498224 0.479029 0.722707 -v 0.086684 0.095554 0.156380 -vn 0.498467 0.627673 0.597961 -v 0.086322 0.095554 0.156380 -vn 0.514810 0.484761 0.707091 -v 0.086344 0.095449 0.156455 -vn -0.511850 0.279091 0.812476 -v 0.086714 0.095403 0.156478 -vn 0.495679 0.300071 0.815021 -v 0.086377 0.095277 0.156519 -vn -0.494813 0.097248 0.863541 -v 0.086738 0.095277 0.156519 -vn 0.512472 0.114771 0.851000 -v 0.086388 0.095212 0.156529 -vn -0.514119 -0.118149 0.849543 -v 0.086759 0.095160 0.156532 -vn 0.521008 -0.173297 0.835774 -v 0.086430 0.094971 0.156502 -vn 0.500022 -0.619237 0.605412 -v 0.086485 0.094707 0.156330 -vn -0.503581 -0.742269 0.442089 -v 0.086846 0.094707 0.156330 -vn -0.510911 -0.632196 0.582493 -v 0.086842 0.094724 0.156348 -vn 0.512250 -0.445802 0.734072 -v 0.086471 0.094760 0.156383 -vn -0.507845 -0.467652 0.723460 -v 0.086799 0.094925 0.156486 -vn -0.507741 -0.296009 0.809060 -v 0.086792 0.094967 0.156501 -vn -0.521046 -0.816647 0.248190 -v 0.086886 0.094593 0.156139 -vn 0.515966 -0.722070 0.460863 -v 0.086516 0.094611 0.156184 -vn -0.497627 -0.863901 0.077732 -v 0.086900 0.094568 0.156053 -vn 0.497361 -0.825778 0.265939 -v 0.086539 0.094568 0.156053 -vn 0.515377 -0.852652 0.085859 -v 0.086556 0.094556 0.155952 -vn -0.509494 -0.848467 -0.143250 -v 0.086925 0.094556 0.155904 -vn 0.498818 -0.857502 -0.125975 -v 0.086593 0.094586 0.155743 -vn -0.493225 -0.808720 -0.320469 -v 0.086955 0.094586 0.155743 -vn 0.511525 -0.805966 -0.297927 -v 0.086600 0.094599 0.155708 -vn -0.513177 -0.692566 -0.506954 -v 0.086970 0.094619 0.155664 -vn 0.506933 -0.707641 -0.492202 -v 0.086642 0.094734 0.155505 -vn -0.521580 -0.478246 -0.706566 -v 0.087011 0.094767 0.155475 -vn 0.510033 -0.585988 -0.629670 -v 0.086647 0.094757 0.155483 -vn 0.513609 -0.434159 -0.740075 -v 0.086683 0.094936 0.155373 -vn -0.512306 -0.221868 -0.829649 -v 0.087053 0.094980 0.155358 -vn 0.486181 -0.233235 -0.842158 -v 0.086702 0.095035 0.155344 -vn -0.496814 -0.039723 -0.866948 -v 0.087063 0.095035 0.155344 -vn 0.508593 -0.057587 -0.859079 -v 0.086728 0.095181 0.155332 -vn -0.515026 0.171043 -0.839936 -v 0.087097 0.095226 0.155336 -vn 0.497489 0.165061 -0.851622 -v 0.086756 0.095345 0.155362 -vn -0.501435 0.864918 -0.021900 -v 0.087225 0.095743 0.155811 -vn -0.514997 0.836823 -0.185757 -v 0.087223 0.095740 0.155793 -vn 0.509155 0.764338 -0.395662 -v 0.086855 0.095729 0.155753 -vn -0.510614 0.771784 -0.378976 -v 0.087181 0.095637 0.155573 -vn 0.524100 0.573731 -0.629406 -v 0.086811 0.095609 0.155539 -vn -0.506976 0.663824 -0.549830 -v 0.087171 0.095604 0.155533 -vn 0.520868 0.334297 -0.785457 -v 0.086768 0.095413 0.155390 -vn -0.516277 0.528341 -0.674028 -v 0.087136 0.095452 0.155410 -vn -0.498075 0.345736 -0.795229 -v 0.087117 0.095345 0.155362 -vn 0.504102 0.838472 -0.206994 -v 0.086864 0.095743 0.155811 -vn 0.513513 0.857562 -0.029867 -v 0.086895 0.095753 0.155992 -vn -0.512704 0.836167 0.194831 -v 0.087263 0.095747 0.156034 -vn 0.494303 0.848972 0.186842 -v 0.086918 0.095725 0.156121 -vn -0.494641 0.782825 0.377511 -v 0.087280 0.095725 0.156121 -vn 0.512207 0.778332 0.363103 -v 0.086939 0.095677 0.156228 -vn -0.512445 0.656332 0.553740 -v 0.087308 0.095655 0.156264 -vn 0.498864 0.668580 0.551485 -v 0.086972 0.095555 0.156380 -vn -0.495862 0.540410 0.679763 -v 0.087334 0.095555 0.156380 -vn -0.511071 0.351822 0.784237 -v 0.087348 0.095487 0.156432 -vn 0.517027 0.537409 0.666239 -v 0.086980 0.095519 0.156409 -vn 0.506894 0.363869 0.781446 -v 0.087023 0.095298 0.156514 -vn -0.509056 0.156320 0.846420 -v 0.087388 0.095277 0.156519 -vn 0.508888 0.192234 0.839094 -v 0.087027 0.095277 0.156519 -vn -0.506676 -0.022020 0.861855 -v 0.087391 0.095258 0.156523 -vn 0.511096 -0.011382 0.859448 -v 0.087067 0.095051 0.156522 -vn -0.517188 -0.227141 0.825181 -v 0.087434 0.095014 0.156515 -vn -0.498727 -0.393859 0.772105 -v 0.087442 0.094967 0.156501 -vn 0.495155 -0.227194 0.838573 -v 0.087081 0.094967 0.156501 -vn 0.512343 -0.383255 0.768518 -v 0.087106 0.094829 0.156435 -vn -0.512189 -0.569107 0.643257 -v 0.087474 0.094798 0.156413 -vn 0.494755 -0.569307 0.656587 -v 0.087135 0.094707 0.156330 -vn -0.494637 -0.703890 0.509777 -v 0.087496 0.094707 0.156330 -vn 0.512925 -0.690931 0.509434 -v 0.087151 0.094653 0.156259 -vn -0.513621 -0.798011 0.315232 -v 0.087519 0.094634 0.156227 -vn 0.501457 -0.802883 0.322366 -v 0.087189 0.094568 0.156053 -vn -0.505569 -0.850731 0.143723 -v 0.087550 0.094568 0.156053 -vn -0.509023 -0.858969 -0.055390 -v 0.087559 0.094560 0.156000 -vn 0.515147 -0.842197 0.159150 -v 0.087192 0.094565 0.156035 -vn 0.510553 -0.858747 -0.043469 -v 0.087234 0.094572 0.155791 -vn -0.523662 -0.780198 -0.342154 -v 0.087602 0.094582 0.155756 -vn 0.506760 -0.827098 -0.243111 -v 0.087243 0.094586 0.155743 -vn -0.520331 -0.622595 -0.584492 -v 0.087646 0.094701 0.155541 -vn 0.514890 -0.751163 -0.413088 -v 0.087278 0.094679 0.155568 -vn -0.497348 -0.492251 -0.714377 -v 0.087659 0.094757 0.155483 -vn 0.498155 -0.630680 -0.595050 -v 0.087297 0.094757 0.155483 -vn 0.515182 -0.487276 -0.705088 -v 0.087318 0.094858 0.155411 -vn -0.509011 -0.292994 -0.809359 -v 0.087685 0.094889 0.155394 -vn 0.496975 -0.304624 -0.812539 -v 0.087352 0.095035 0.155344 -vn -0.489729 -0.122179 -0.863271 -v 0.087713 0.095035 0.155344 -vn 0.513176 -0.119758 -0.849887 -v 0.087362 0.095094 0.155335 -vn -0.513763 0.099657 -0.852125 -v 0.087730 0.095129 0.155332 -vn 0.523275 0.164958 -0.836045 -v 0.087404 0.095336 0.155359 -vn 0.496897 0.617833 -0.609407 -v 0.087460 0.095604 0.155533 -vn -0.500612 0.734946 -0.457429 -v 0.087821 0.095604 0.155533 -vn -0.512767 0.614274 -0.599781 -v 0.087813 0.095572 0.155499 -vn 0.513105 0.439244 -0.737420 -v 0.087445 0.095547 0.155477 -vn -0.506606 0.447552 -0.736917 -v 0.087771 0.095366 0.155370 -vn -0.511941 0.284365 -0.810588 -v 0.087767 0.095345 0.155362 -vn -0.519245 0.812753 -0.264230 -v 0.087857 0.095711 0.155703 -vn 0.513289 0.722321 -0.463451 -v 0.087490 0.095698 0.155674 -vn -0.499226 0.861579 -0.091954 -v 0.087875 0.095743 0.155810 -vn 0.498742 0.824068 -0.268642 -v 0.087514 0.095743 0.155810 -vn -0.513863 0.848484 0.126570 -v 0.087896 0.095756 0.155937 -vn 0.519551 0.849779 -0.089116 -v 0.087530 0.095755 0.155906 -vn -0.502661 0.808402 0.306295 -v 0.087930 0.095725 0.156121 -vn 0.502651 0.856456 0.117584 -v 0.087568 0.095725 0.156121 -vn 0.512363 0.807219 0.293056 -v 0.087574 0.095715 0.156150 -vn -0.511711 0.706815 0.488431 -v 0.087941 0.095703 0.156178 -vn 0.507612 0.711818 0.485433 -v 0.087617 0.095581 0.156355 -vn -0.523597 0.502725 0.687832 -v 0.087982 0.095561 0.156374 -vn 0.510507 0.586670 0.628651 -v 0.087622 0.095554 0.156380 -vn 0.514640 0.439213 0.736368 -v 0.087657 0.095381 0.156488 -vn -0.514154 0.245510 0.821809 -v 0.088023 0.095354 0.156498 -vn 0.484330 0.236548 0.842301 -v 0.087677 0.095277 0.156519 -vn -0.495775 0.056109 0.866637 -v 0.088038 0.095277 0.156519 -vn 0.508563 0.061530 0.858824 -v 0.087702 0.095136 0.156531 -vn -0.512208 -0.158591 0.844093 -v 0.088068 0.095108 0.156530 -vn 0.497583 -0.159368 0.852651 -v 0.087731 0.094967 0.156501 -vn -0.499718 -0.865428 0.036289 -v 0.088200 0.094568 0.156053 -vn -0.516769 -0.830451 0.208090 -v 0.088194 0.094577 0.156091 -vn 0.510240 -0.760205 0.402174 -v 0.087829 0.094585 0.156115 -vn -0.508946 -0.762025 0.400365 -v 0.088151 0.094689 0.156308 -vn 0.526070 -0.567282 0.633594 -v 0.087785 0.094706 0.156329 -vn -0.511036 -0.655317 0.556239 -v 0.088146 0.094707 0.156330 -vn 0.519941 -0.331165 0.787395 -v 0.087742 0.094903 0.156476 -vn -0.514444 -0.512734 0.687350 -v 0.088107 0.094880 0.156464 -vn -0.492339 -0.323892 0.807896 -v 0.088092 0.094967 0.156501 -vn 0.502559 -0.838664 0.209948 -v 0.087839 0.094568 0.156053 -vn 0.513122 -0.857653 0.033723 -v 0.087869 0.094558 0.155877 -vn -0.512924 -0.839837 -0.177717 -v 0.088234 0.094561 0.155852 -vn 0.494811 -0.849739 -0.181948 -v 0.087893 0.094586 0.155743 -vn -0.494921 -0.789902 -0.362089 -v 0.088255 0.094586 0.155743 -vn 0.512961 -0.779347 -0.359847 -v 0.087913 0.094632 0.155639 -vn -0.513201 -0.667608 -0.539374 -v 0.088279 0.094644 0.155618 -vn 0.499569 -0.671866 -0.546833 -v 0.087947 0.094757 0.155483 -vn -0.502909 -0.546936 -0.669286 -v 0.088309 0.094757 0.155483 -vn -0.510317 -0.370182 -0.776236 -v 0.088319 0.094806 0.155444 -vn 0.516902 -0.540067 -0.664184 -v 0.087954 0.094788 0.155457 -vn 0.508779 -0.370326 -0.777176 -v 0.087997 0.095008 0.155350 -vn -0.526002 -0.079254 -0.846783 -v 0.088362 0.095031 0.155345 -vn 0.511123 -0.191998 -0.837789 -v 0.088002 0.095035 0.155344 -vn -0.519741 0.202651 -0.829940 -v 0.088406 0.095276 0.155344 -vn 0.513710 0.002551 -0.857960 -v 0.088041 0.095255 0.155340 -vn -0.497629 0.380355 -0.779548 -v 0.088417 0.095345 0.155362 -vn 0.493215 0.224750 -0.840373 -v 0.088056 0.095345 0.155362 -vn 0.512390 0.379923 -0.770140 -v 0.088080 0.095478 0.155425 -vn -0.508907 0.560245 -0.653559 -v 0.088445 0.095496 0.155437 -vn 0.495827 0.564954 -0.659532 -v 0.088110 0.095604 0.155533 -vn -0.486325 0.691330 -0.534369 -v 0.088471 0.095604 0.155533 -vn 0.514919 0.690725 -0.507699 -v 0.088125 0.095655 0.155599 -vn -0.514986 0.790944 -0.330449 -v 0.088490 0.095667 0.155617 -vn 0.524953 0.815230 -0.244590 -v 0.088166 0.095746 0.155823 -vn 0.503426 0.830087 0.239829 -v 0.088218 0.095725 0.156121 -vn -0.501882 0.759465 0.413917 -v 0.088580 0.095725 0.156121 -vn -0.513389 0.823576 0.241154 -v 0.088573 0.095736 0.156085 -vn 0.511506 0.858527 0.035949 -v 0.088208 0.095740 0.156066 -vn -0.507633 0.860999 0.031464 -v 0.088530 0.095749 0.155842 -vn -0.511997 0.844757 -0.155706 -v 0.088525 0.095743 0.155810 -vn -0.518604 0.631890 0.575990 -v 0.088617 0.095625 0.156305 -vn 0.512410 0.753480 0.411951 -v 0.088253 0.095636 0.156291 -vn -0.498221 0.504040 0.705492 -v 0.088634 0.095554 0.156380 -vn 0.498680 0.632849 0.592301 -v 0.088272 0.095554 0.156380 -vn -0.511953 0.309253 0.801415 -v 0.088656 0.095443 0.156458 -vn 0.518036 0.489137 0.701701 -v 0.088292 0.095458 0.156450 -vn -0.498795 0.133454 0.856384 -v 0.088688 0.095277 0.156519 -vn 0.494151 -0.616084 0.613397 -v 0.088435 0.094707 0.156330 -vn -0.514838 -0.595629 0.616578 -v 0.088784 0.094757 0.156380 -vn 0.514307 -0.432653 0.740472 -v 0.088420 0.094768 0.156390 -vn -0.526408 -0.356692 0.771794 -v 0.088742 0.094966 0.156501 -vn 0.526070 -0.156407 0.835935 -v 0.088378 0.094981 0.156505 -vn -0.513065 -0.081256 0.854495 -v 0.088701 0.095206 0.156529 -vn 0.514237 0.124303 0.848593 -v 0.088336 0.095223 0.156528 -vn 0.499760 0.310514 0.808592 -v 0.088327 0.095277 0.156519 -vn 0.791714 0.526854 0.309217 -v 0.088903 0.095634 0.156294 -vn 0.395053 0.881647 0.258132 -v 0.088903 0.095725 0.156121 -vn 0.674326 0.688178 0.267761 -v 0.088887 0.095683 0.156219 -vn 0.496125 0.850208 0.176087 -v 0.088868 0.095725 0.156121 -vn 0.613838 0.788425 -0.039863 -v 0.088843 0.095754 0.155981 -vn 0.394834 0.896993 -0.198772 -v 0.088903 0.095743 0.155810 -vn 0.500954 0.838878 -0.212905 -v 0.088814 0.095743 0.155811 -vn 0.386868 0.291759 -0.874763 -v 0.088903 0.095345 0.155362 -vn 0.531527 0.328330 -0.780819 -v 0.088716 0.095403 0.155385 -vn 0.367768 0.701750 -0.610158 -v 0.088903 0.095604 0.155533 -vn 0.537346 0.563662 -0.627330 -v 0.088759 0.095602 0.155530 -vn 0.574187 0.699132 -0.426056 -v 0.088803 0.095725 0.155743 -vn 0.387705 -0.188444 -0.902316 -v 0.088903 0.095035 0.155344 -vn 0.527499 -0.058510 -0.847538 -v 0.088676 0.095170 0.155332 -vn 0.498603 0.152372 -0.853334 -v 0.088706 0.095345 0.155362 -vn 0.517484 -0.716106 -0.468405 -v 0.088591 0.094727 0.155512 -vn 0.508576 -0.590019 -0.627079 -v 0.088597 0.094757 0.155483 -vn 0.376772 -0.620979 -0.687334 -v 0.088903 0.094757 0.155483 -vn 0.523172 -0.439525 -0.730143 -v 0.088631 0.094926 0.155377 -vn 0.496559 -0.250809 -0.830978 -v 0.088652 0.095035 0.155344 -vn 0.520134 -0.802803 -0.291494 -v 0.088548 0.094595 0.155718 -vn 0.373847 -0.838443 -0.396550 -v 0.088903 0.094586 0.155743 -vn 0.502426 -0.857004 -0.114511 -v 0.088543 0.094586 0.155743 -vn 0.382842 -0.900591 -0.205835 -v 0.088903 0.094584 0.155750 -vn 0.518303 -0.850245 0.091903 -v 0.088504 0.094557 0.155962 -vn -0.506622 -0.855910 -0.103691 -v 0.088867 0.094556 0.155949 -vn 0.497896 -0.822977 0.273512 -v 0.088489 0.094568 0.156053 -vn -0.512958 -0.852129 0.103688 -v 0.088850 0.094568 0.156053 -vn 0.511238 -0.722037 0.466152 -v 0.088464 0.094616 0.156194 -vn -0.518564 -0.807274 0.281778 -v 0.088828 0.094610 0.156181 -vn -0.498225 -0.726687 0.472967 -v 0.088796 0.094707 0.156330 -vn 0.004314 0.522337 -0.852728 -v 0.085338 0.095629 0.155226 -vn -0.007785 0.699228 -0.714856 -v 0.085353 0.095722 0.155298 -vn 0.861984 0.235931 -0.448687 -v 0.085425 0.095639 0.155391 -vn 0.009757 0.144413 -0.989469 -v 0.085299 0.095317 0.155097 -vn -0.007773 0.357885 -0.933733 -v 0.085312 0.095425 0.155125 -vn 0.864811 0.042886 -0.500263 -v 0.085384 0.095386 0.155244 -vn 0.006392 -0.263789 -0.964559 -v 0.085255 0.094969 0.155102 -vn -0.005445 -0.040298 -0.999173 -v 0.085270 0.095084 0.155085 -vn 0.862638 -0.160602 -0.479648 -v 0.085342 0.095095 0.155209 -vn 0.004909 -0.625115 -0.780517 -v 0.085212 0.094653 0.155246 -vn -0.008916 -0.438172 -0.898847 -v 0.085225 0.094748 0.155186 -vn 0.862479 -0.341781 -0.373250 -v 0.085298 0.094808 0.155296 -vn 0.008231 -0.882540 -0.470166 -v 0.085172 0.094426 0.155496 -vn -0.003711 -0.756918 -0.653500 -v 0.085186 0.094489 0.155404 -vn 0.862734 -0.460385 -0.209128 -v 0.085258 0.094587 0.155481 -vn 0.004339 -0.997073 -0.076334 -v 0.085127 0.094312 0.155829 -vn -0.006832 -0.954728 -0.297401 -v 0.085142 0.094333 0.155718 -vn 0.862426 -0.506166 -0.004270 -v 0.085214 0.094454 0.155749 -vn 0.009137 -0.946439 0.322755 -v 0.085087 0.094339 0.156166 -vn -0.008664 -0.994169 0.107489 -v 0.085099 0.094316 0.156063 -vn 0.863337 -0.467477 0.190039 -v 0.085171 0.094440 0.156044 -vn 0.006310 -0.739049 0.673622 -v 0.085044 0.094500 0.156473 -vn -0.004381 -0.871149 0.490999 -v 0.085059 0.094435 0.156383 -vn 0.861951 -0.353637 0.363293 -v 0.085131 0.094541 0.156316 -vn 0.003637 -0.409708 0.912209 -v 0.085001 0.094773 0.156690 -vn -0.007983 -0.600593 0.799515 -v 0.085014 0.094680 0.156636 -vn 0.861725 -0.174920 0.476271 -v 0.085086 0.094750 0.156532 -vn 0.008045 -0.016914 0.999825 -v 0.084961 0.095098 0.156780 -vn -0.003822 -0.236520 0.971619 -v 0.084974 0.094993 0.156766 -vn 0.862701 0.024453 0.505122 -v 0.085046 0.095017 0.156643 -vn 0.004254 0.386067 0.922461 -v 0.084917 0.095445 0.156731 -vn -0.005766 0.169611 0.985494 -v 0.084930 0.095342 0.156761 -vn 0.863875 0.226495 0.449911 -v 0.085002 0.095314 0.156639 -vn 0.007712 0.718901 0.695070 -v 0.084876 0.095736 0.156552 -vn -0.008705 0.549186 0.835655 -v 0.084887 0.095659 0.156617 -vn 0.862594 0.383509 0.329928 -v 0.084959 0.095585 0.156516 -vn 0.006174 0.936036 0.351851 -v 0.084834 0.095935 0.156272 -vn -0.003362 0.834061 0.551662 -v 0.084847 0.095887 0.156366 -vn 0.861597 0.485641 0.147662 -v 0.084919 0.095779 0.156302 -vn 0.002802 0.998694 -0.051019 -v 0.084789 0.096006 0.155929 -vn -0.006970 0.985294 0.170726 -v 0.084802 0.096000 0.156032 -vn 0.861202 0.504308 -0.063282 -v 0.084874 0.095876 0.156017 -vn 0.007874 0.897834 -0.440265 -v 0.084750 0.095938 0.155599 -vn -0.004257 0.972564 -0.232595 -v 0.084762 0.095972 0.155693 -vn 0.862948 0.437636 -0.252577 -v 0.084834 0.095852 0.155728 -vn 0.004196 0.645671 -0.763604 -v 0.084706 0.095738 0.155312 -vn -0.004713 0.800306 -0.599573 -v 0.084719 0.095808 0.155387 -vn 0.862983 0.298609 -0.407546 -v 0.084791 0.095712 0.155467 -vn 0.005590 0.290610 -0.956825 -v 0.084664 0.095445 0.155132 -vn -0.007979 0.493071 -0.869952 -v 0.084675 0.095534 0.155170 -vn 0.861834 0.117126 -0.493481 -v 0.084747 0.095478 0.155282 -vn 0.006037 -0.112349 -0.993650 -v 0.084623 0.095107 0.155083 -vn -0.002444 0.110615 -0.993860 -v 0.084635 0.095207 0.155083 -vn 0.862208 -0.093853 -0.497784 -v 0.084708 0.095199 0.155208 -vn 0.002349 -0.500520 -0.865722 -v 0.084578 0.094769 0.155175 -vn -0.005990 -0.296494 -0.955016 -v 0.084591 0.094859 0.155135 -vn 0.861400 -0.286654 -0.419307 -v 0.084663 0.094903 0.155252 -vn 0.007585 -0.801022 -0.598587 -v 0.084539 0.094505 0.155385 -vn -0.005088 -0.650600 -0.759404 -v 0.084550 0.094569 0.155316 -vn 0.863513 -0.424098 -0.272921 -v 0.084622 0.094656 0.155407 -vn 0.004093 -0.973752 -0.227575 -v 0.084495 0.094340 0.155692 -vn -0.003650 -0.898187 -0.439599 -v 0.084507 0.094373 0.155600 -vn 0.862208 -0.500008 -0.081179 -v 0.084580 0.094488 0.155649 -vn 0.003730 -0.984098 0.177589 -v 0.084452 0.094312 0.156037 -vn -0.007024 -0.999086 -0.042174 -v 0.084463 0.094306 0.155945 -vn 0.861173 -0.492970 0.123943 -v 0.084535 0.094431 0.155943 -vn 0.005835 -0.833808 0.552024 -v 0.084412 0.094421 0.156358 -vn -0.001852 -0.934954 0.354765 -v 0.084424 0.094378 0.156275 -vn 0.861766 -0.400434 0.311468 -v 0.084496 0.094493 0.156224 -vn 0.002113 -0.542542 0.840026 -v 0.084367 0.094656 0.156619 -vn -0.004896 -0.715421 0.698676 -v 0.084379 0.094583 0.156560 -vn 0.861429 -0.241210 0.446944 -v 0.084451 0.094668 0.156468 -vn 0.007289 -0.167527 0.985841 -v 0.084327 0.094964 0.156760 -vn -0.006084 -0.378869 0.925430 -v 0.084337 0.094879 0.156735 -vn 0.864134 -0.047982 0.500969 -v 0.084410 0.094920 0.156617 -vn 0.003942 0.240198 0.970716 -v 0.084284 0.095311 0.156767 -vn -0.002634 0.017714 0.999840 -v 0.084296 0.095219 0.156779 -vn 0.861984 0.155628 0.482456 -v 0.084368 0.095210 0.156655 -vn 0.002290 0.606583 0.795017 -v 0.084241 0.095633 0.156635 -vn -0.006003 0.417787 0.908525 -v 0.084251 0.095557 0.156681 -vn 0.861661 0.338862 0.377773 -v 0.084324 0.095498 0.156571 -vn 0.005602 0.870931 0.491373 -v 0.084201 0.095869 0.156394 -vn -0.001690 0.742032 0.670363 -v 0.084212 0.095817 0.156465 -vn 0.862010 0.459316 0.214401 -v 0.084284 0.095720 0.156387 -vn 0.001983 0.994944 0.100408 -v 0.084156 0.095995 0.156066 -vn -0.003794 0.947746 0.319003 -v 0.084168 0.095976 0.156153 -vn 0.861882 0.507014 0.009774 -v 0.084240 0.095856 0.156120 -vn 0.006320 0.953766 -0.300482 -v 0.084116 0.095981 0.155726 -vn -0.006551 0.996345 -0.085170 -v 0.084125 0.095997 0.155807 -vn 0.862401 0.470949 -0.185665 -v 0.084197 0.095873 0.155826 -vn 0.003698 0.755341 -0.655321 -v 0.084074 0.095831 0.155416 -vn -0.001621 0.881885 -0.471461 -v 0.084085 0.095880 0.155487 -vn 0.861108 0.358377 -0.360636 -v 0.084157 0.095774 0.155552 -vn 0.001126 0.431353 -0.902182 -v 0.084029 0.095567 0.155187 -vn -0.004947 0.618514 -0.785758 -v 0.084040 0.095638 0.155232 -vn 0.860890 0.180354 -0.475752 -v 0.084112 0.095567 0.155335 -vn 0.005387 0.041075 -0.999142 -v 0.083990 0.095245 0.155086 -vn -0.001867 0.258208 -0.966088 -v 0.084000 0.095326 0.155099 -vn 0.861956 -0.019412 -0.506612 -v 0.084072 0.095301 0.155221 -vn 0.001776 -0.363402 -0.931631 -v 0.083946 0.094897 0.155122 -vn -0.002766 -0.147338 -0.989082 -v 0.083956 0.094978 0.155100 -vn 0.863110 -0.222276 -0.453469 -v 0.084028 0.095004 0.155223 -vn 0.004419 -0.702405 -0.711764 -v 0.083904 0.094598 0.155290 -vn -0.005904 -0.530575 -0.847618 -v 0.083913 0.094659 0.155242 -vn 0.861663 -0.381345 -0.334833 -v 0.083985 0.094732 0.155343 -vn 0.003490 -0.927102 -0.374792 -v 0.083863 0.094390 0.155562 -vn -0.000573 -0.821737 -0.569866 -v 0.083873 0.094429 0.155491 -vn 0.860721 -0.485556 -0.152954 -v 0.083945 0.094536 0.155556 -vn 0.000321 -0.999637 0.026948 -v 0.083818 0.094306 0.155902 -vn -0.003843 -0.981232 -0.192793 -v 0.083828 0.094313 0.155823 -vn 0.860352 -0.506369 0.058177 -v 0.083900 0.094437 0.155839 -vn 0.005056 -0.908222 0.418458 -v 0.083779 0.094362 0.156235 -vn -0.002391 -0.977514 0.210859 -v 0.083788 0.094338 0.156162 -vn 0.862165 -0.441273 0.248896 -v 0.083860 0.094458 0.156129 -vn 0.001543 -0.664336 0.747432 -v 0.083735 0.094551 0.156528 -vn -0.001644 -0.813529 0.581522 -v 0.083745 0.094498 0.156470 -vn 0.861929 -0.304284 0.405573 -v 0.083817 0.094595 0.156391 -vn 0.002402 -0.313273 0.949660 -v 0.083692 0.094838 0.156720 -vn -0.004872 -0.512141 0.858888 -v 0.083701 0.094771 0.156689 -vn 0.860791 -0.122244 0.494060 -v 0.083773 0.094828 0.156578 -vn 0.003216 0.087736 0.996139 -v 0.083652 0.095172 0.156781 -vn 0.000151 -0.132391 0.991198 -v 0.083661 0.095097 0.156779 -vn 0.861196 0.089091 0.500404 -v 0.083734 0.095106 0.156655 -vn -0.000177 0.479316 0.877642 -v 0.083607 0.095514 0.156702 -vn -0.002737 0.275134 0.961402 -v 0.083617 0.095445 0.156731 -vn 0.860510 0.283132 0.423507 -v 0.083689 0.095403 0.156613 -vn 0.004773 0.786352 0.617761 -v 0.083568 0.095786 0.156502 -vn -0.003087 0.633634 0.773627 -v 0.083576 0.095737 0.156552 -vn 0.863332 0.421620 0.277298 -v 0.083648 0.095651 0.156461 -vn 0.001328 0.967790 0.251754 -v 0.083524 0.095962 0.156202 -vn -0.000585 0.888264 0.459333 -v 0.083533 0.095936 0.156270 -vn 0.861174 0.500829 0.086890 -v 0.083606 0.095821 0.156220 -vn 0.000751 0.988096 -0.153835 -v 0.083481 0.096003 0.155857 -vn -0.003827 0.997932 0.064161 -v 0.083489 0.096006 0.155926 -vn 0.860136 0.495815 -0.119722 -v 0.083561 0.095881 0.155927 -vn 0.003016 0.847234 -0.531212 -v 0.083441 0.095906 0.155533 -vn 0.000473 0.942518 -0.334154 -v 0.083450 0.095936 0.155595 -vn 0.860696 0.404968 -0.308551 -v 0.083522 0.095822 0.155645 -vn -0.000507 0.563040 -0.826430 -v 0.083396 0.095681 0.155263 -vn -0.001613 0.730696 -0.682701 -v 0.083405 0.095734 0.155308 -vn 0.860521 0.246530 -0.445788 -v 0.083477 0.095649 0.155400 -vn 0.004376 0.191267 -0.981528 -v 0.083356 0.095378 0.155111 -vn -0.003927 0.399109 -0.916895 -v 0.083363 0.095439 0.155130 -vn 0.863035 0.052911 -0.502366 -v 0.083435 0.095398 0.155248 -vn 0.001060 -0.215729 -0.976453 -v 0.083313 0.095033 0.155090 -vn 0.000419 0.004088 -0.999992 -v 0.083322 0.095100 0.155083 -vn 0.860908 -0.151169 -0.485783 -v 0.083394 0.095108 0.155208 -vn -0.000551 -0.587088 -0.809523 -v 0.083269 0.094705 0.155211 -vn -0.002705 -0.397792 -0.917471 -v 0.083277 0.094761 0.155179 -vn 0.860498 -0.336434 -0.382564 -v 0.083349 0.094819 0.155289 -vn 0.002690 -0.858481 -0.512839 -v 0.083230 0.094461 0.155443 -vn 0.000567 -0.727200 -0.686425 -v 0.083238 0.094499 0.155392 -vn 0.860876 -0.458964 -0.219645 -v 0.083310 0.094596 0.155471 -vn -0.000721 -0.992138 -0.125150 -v 0.083186 0.094322 0.155765 -vn -0.000564 -0.940528 -0.339717 -v 0.083194 0.094337 0.155702 -vn 0.860953 -0.508463 -0.015015 -v 0.083266 0.094458 0.155736 -vn 0.002992 -0.960740 0.277435 -v 0.083144 0.094324 0.156107 -vn -0.003755 -0.997965 0.063661 -v 0.083151 0.094314 0.156048 -vn 0.861041 -0.474927 0.181801 -v 0.083223 0.094438 0.156031 -vn 0.000794 -0.771692 0.635996 -v 0.083103 0.094461 0.156421 -vn 0.001425 -0.891849 0.452332 -v 0.083111 0.094427 0.156369 -vn 0.859844 -0.363354 0.358668 -v 0.083183 0.094534 0.156305 -vn -0.001588 -0.453385 0.891313 -v 0.083058 0.094718 0.156660 -vn -0.001624 -0.635460 0.772132 -v 0.083066 0.094667 0.156627 -vn 0.859676 -0.185792 0.475855 -v 0.083138 0.094739 0.156525 -vn 0.002458 -0.065887 0.997824 -v 0.083019 0.095035 0.156773 -vn 0.000270 -0.279234 0.960223 -v 0.083026 0.094978 0.156763 -vn 0.860758 0.014694 0.508803 -v 0.083098 0.095004 0.156640 -vn -0.001040 0.339766 0.940509 -v 0.082975 0.095384 0.156750 -vn 0.000545 0.125798 0.992056 -v 0.082982 0.095326 0.156764 -vn 0.861901 0.218625 0.457526 -v 0.083054 0.095301 0.156642 -vn 0.000910 0.684941 0.728598 -v 0.082932 0.095690 0.156593 -vn -0.002651 0.512389 0.858749 -v 0.082939 0.095646 0.156626 -vn 0.860333 0.379826 0.339941 -v 0.083011 0.095574 0.156524 -vn 0.000497 0.917277 0.398250 -v 0.082892 0.095907 0.156330 -vn 0.002256 0.809335 0.587343 -v 0.082899 0.095879 0.156379 -vn 0.860438 0.485472 0.154800 -v 0.082971 0.095772 0.156313 -vn -0.002387 0.999995 -0.002077 -v 0.082847 0.096004 0.155993 -vn -0.000474 0.976835 0.213991 -v 0.082854 0.095998 0.156048 -vn 0.859562 0.508328 -0.052494 -v 0.082926 0.095874 0.156030 -vn 0.002113 0.918323 -0.395826 -v 0.082808 0.095961 0.155658 -vn -0.000162 0.981832 -0.189753 -v 0.082814 0.095976 0.155708 -vn 0.860919 0.445398 -0.245846 -v 0.082886 0.095855 0.155741 -vn -0.001331 0.683109 -0.730315 -v 0.082764 0.095783 0.155358 -vn 0.001597 0.825794 -0.563969 -v 0.082771 0.095818 0.155399 -vn 0.860424 0.310125 -0.404343 -v 0.082843 0.095721 0.155477 -vn -0.000811 0.336533 -0.941671 -v 0.082721 0.095502 0.155155 -vn -0.001595 0.530366 -0.847767 -v 0.082727 0.095547 0.155177 -vn 0.859330 0.127289 -0.495327 -v 0.082799 0.095490 0.155288 -vn 0.000243 -0.062394 -0.998052 -v 0.082681 0.095172 0.155082 -vn 0.002767 0.153509 -0.988143 -v 0.082687 0.095222 0.155084 -vn 0.859683 -0.084804 -0.503739 -v 0.082759 0.095213 0.155209 -vn -0.002912 -0.457088 -0.889417 -v 0.082636 0.094827 0.155148 -vn 0.000645 -0.254427 -0.967092 -v 0.082643 0.094874 0.155130 -vn 0.859178 -0.280237 -0.428112 -v 0.082715 0.094915 0.155248 -vn 0.001892 -0.770804 -0.637070 -v 0.082596 0.094547 0.155339 -vn -0.000884 -0.616941 -0.787009 -v 0.082601 0.094580 0.155306 -vn 0.861826 -0.421257 -0.282485 -v 0.082674 0.094665 0.155398 -vn -0.001641 -0.960996 -0.276558 -v 0.082553 0.094361 0.155631 -vn 0.002558 -0.878306 -0.478092 -v 0.082559 0.094379 0.155586 -vn 0.859630 -0.502492 -0.092404 -v 0.082632 0.094493 0.155637 -vn -0.002340 -0.991613 0.129219 -v 0.082510 0.094307 0.155975 -vn -0.000465 -0.996355 -0.085307 -v 0.082515 0.094306 0.155929 -vn 0.858636 -0.499305 0.115926 -v 0.082587 0.094431 0.155930 -vn -0.000070 -0.860538 0.509387 -v 0.082470 0.094391 0.156302 -vn 0.002975 -0.949420 0.313994 -v 0.082476 0.094372 0.156261 -vn 0.859097 -0.409946 0.306426 -v 0.082548 0.094487 0.156212 -vn -0.003284 -0.583859 0.811849 -v 0.082425 0.094605 0.156579 -vn 0.001697 -0.745039 0.667019 -v 0.082431 0.094572 0.156549 -vn 0.859096 -0.252005 0.445475 -v 0.082503 0.094658 0.156458 -vn 0.001244 -0.215382 0.976529 -v 0.082384 0.094904 0.156744 -vn -0.001357 -0.418216 0.908347 -v 0.082389 0.094865 0.156730 -vn 0.860491 -0.059498 0.505980 -v 0.082461 0.094908 0.156613 -vn -0.001971 0.190419 0.981701 -v 0.082343 0.095246 0.156777 -vn 0.003578 -0.024960 0.999682 -v 0.082348 0.095204 0.156780 -vn 0.858802 0.148059 0.490447 -v 0.082420 0.095197 0.156655 -vn -0.003518 0.566519 0.824041 -v 0.082298 0.095579 0.156668 -vn 0.000694 0.378354 0.925661 -v 0.082303 0.095543 0.156688 -vn 0.858831 0.334688 0.387805 -v 0.082375 0.095486 0.156577 -vn -0.000368 0.845067 0.534660 -v 0.082259 0.095832 0.156446 -vn 0.002899 0.712440 0.701727 -v 0.082264 0.095808 0.156477 -vn 0.859168 0.459565 0.225011 -v 0.082336 0.095712 0.156397 -vn -0.003622 0.988562 0.150769 -v 0.082215 0.095982 0.156130 -vn 0.002796 0.933140 0.359502 -v 0.082220 0.095972 0.156168 -vn 0.859491 0.510761 0.019972 -v 0.082292 0.095852 0.156133 -vn -0.000659 0.967328 -0.253529 -v 0.082173 0.095993 0.155786 -vn -0.000456 0.999071 -0.043097 -v 0.082177 0.095999 0.155822 -vn 0.859167 0.479556 -0.178491 -v 0.082249 0.095875 0.155838 -vn -0.002269 0.788025 -0.615639 -v 0.082132 0.095869 0.155469 -vn 0.004391 0.901053 -0.433686 -v 0.082137 0.095888 0.155501 -vn 0.857973 0.368749 -0.357640 -v 0.082209 0.095781 0.155564 -vn -0.004451 0.475947 -0.879463 -v 0.082087 0.095621 0.155220 -vn 0.001747 0.651532 -0.758619 -v 0.082092 0.095651 0.155241 -vn 0.857909 0.191308 -0.476857 -v 0.082164 0.095578 0.155342 -vn -0.000640 0.091463 -0.995808 -v 0.082048 0.095308 0.155095 -vn 0.002652 0.299379 -0.954131 -v 0.082052 0.095341 0.155102 -vn 0.858950 -0.010287 -0.511956 -v 0.082124 0.095314 0.155224 -vn -0.003947 -0.315237 -0.949005 -v 0.082004 0.094959 0.155105 -vn 0.003808 -0.105191 -0.994445 -v 0.082008 0.094993 0.155097 -vn 0.860084 -0.215662 -0.462325 -v 0.082080 0.095017 0.155220 -vn -0.002468 -0.666382 -0.745606 -v 0.081961 0.094646 0.155252 -vn 0.000682 -0.494565 -0.869140 -v 0.081965 0.094672 0.155233 -vn 0.858904 -0.379451 -0.343949 -v 0.082037 0.094743 0.155336 -vn -0.002540 -0.906506 -0.422185 -v 0.081921 0.094421 0.155505 -vn 0.005015 -0.796925 -0.604057 -v 0.081925 0.094437 0.155478 -vn 0.857683 -0.488404 -0.160755 -v 0.081997 0.094543 0.155544 -vn -0.005128 -0.999708 -0.023605 -v 0.081876 0.094311 0.155838 -vn 0.002921 -0.972180 -0.234218 -v 0.081880 0.094315 0.155808 -vn 0.855853 -0.515305 0.044457 -v 0.081952 0.094439 0.155826 -vn -0.000884 -0.928120 0.372279 -v 0.081836 0.094342 0.156176 -vn 0.002147 -0.985556 0.169337 -v 0.081840 0.094334 0.156148 -vn 0.854627 -0.458987 0.242784 -v 0.081912 0.094455 0.156116 -vn -0.004230 -0.702080 0.712086 -v 0.081793 0.094507 0.156480 -vn 0.004725 -0.837242 0.546813 -v 0.081797 0.094488 0.156458 -vn 0.854429 -0.320897 0.408626 -v 0.081869 0.094587 0.156380 -vn -0.004007 -0.360242 0.932850 -v 0.081750 0.094781 0.156695 -vn 0.001824 -0.547478 0.836818 -v 0.081753 0.094757 0.156682 -vn 0.855352 -0.135705 0.499957 -v 0.081825 0.094816 0.156572 -vn -0.002813 0.036123 0.999343 -v 0.081710 0.095108 0.156780 -vn 0.005300 -0.173958 0.984739 -v 0.081713 0.095081 0.156778 -vn 0.857111 0.084041 0.508230 -v 0.081785 0.095092 0.156654 -vn -0.005611 0.433798 0.900993 -v 0.081665 0.095455 0.156727 -vn 0.003913 0.234396 0.972133 -v 0.081669 0.095431 0.156736 -vn 0.854134 0.276573 0.440411 -v 0.081741 0.095390 0.156618 -vn -0.001080 0.754484 0.656318 -v 0.081625 0.095743 0.156546 -vn 0.001438 0.600852 0.799359 -v 0.081627 0.095726 0.156562 -vn 0.853042 0.427064 0.299894 -v 0.081699 0.095642 0.156469 -vn -0.004621 0.953306 0.301971 -v 0.081583 0.095939 0.156263 -vn 0.005697 0.868393 0.495843 -v 0.081585 0.095929 0.156284 -vn 0.851930 0.513346 0.103402 -v 0.081658 0.095815 0.156232 -vn 0.001965 0.995812 -0.091400 -v 0.081538 0.096006 0.155919 -vn 0.002908 0.994404 0.105605 -v 0.081541 0.096006 0.155941 -vn 0.855195 0.507697 -0.104337 -v 0.081613 0.095881 0.155940 -vn 0.005477 0.880255 -0.474469 -v 0.081499 0.095934 0.155590 -vn 0.010937 0.951177 -0.308453 -v 0.081501 0.095942 0.155609 -vn 0.851089 0.426641 -0.305980 -v 0.081574 0.095827 0.155657 -vn 0.001743 0.613100 -0.790003 -v 0.081455 0.095731 0.155305 -vn 0.012262 0.746951 -0.664766 -v 0.081457 0.095745 0.155319 -vn 0.850937 0.264947 -0.453551 -v 0.081529 0.095659 0.155409 -vn 0.004108 0.249576 -0.968346 -v 0.081413 0.095436 0.155129 -vn 0.003795 0.431141 -0.902276 -v 0.081415 0.095453 0.155135 -vn 0.849052 0.077989 -0.522521 -v 0.081487 0.095409 0.155252 -vn 0.939187 0.213320 0.269115 -v 0.088903 0.095434 0.156561 -vn 0.961525 0.211759 0.175008 -v 0.088903 0.095554 0.156436 -vn 0.861553 0.400509 0.311958 -v 0.088856 0.095605 0.156501 -vn 0.572647 0.751204 -0.328279 -v 0.081598 0.095802 0.155692 -vn 0.566376 0.696667 -0.440311 -v 0.081592 0.095789 0.155657 -vn 0.570577 -0.288992 -0.768717 -v 0.081431 0.094997 0.155231 -vn 0.925650 -0.268244 -0.266865 -v 0.081401 0.094831 0.155283 -vn 0.874685 -0.253070 -0.413378 -v 0.081424 0.094972 0.155230 -vn 0.573911 -0.796291 -0.191172 -v 0.081312 0.094452 0.155705 -vn 0.573292 -0.811360 -0.114154 -v 0.081309 0.094447 0.155719 -vn 0.003627 -0.934466 -0.356035 -v 0.081246 0.094342 0.155687 -vn 0.574560 0.468687 0.670980 -v 0.081032 0.095560 0.156609 -vn 0.580642 0.517362 0.628643 -v 0.081025 0.095600 0.156585 -vn 0.000269 0.554107 0.832445 -v 0.080991 0.095634 0.156634 -vn 0.564093 0.805226 -0.182785 -v 0.080891 0.095953 0.155767 -vn 0.576845 0.776775 -0.252728 -v 0.080886 0.095945 0.155731 -vn 0.003940 0.978452 -0.206437 -v 0.080865 0.095980 0.155722 -vn 0.581246 0.311392 -0.751790 -v 0.080789 0.095552 0.155200 -vn 0.189593 0.310873 -0.931350 -v 0.080770 0.095419 0.155139 -vn -0.006590 0.460383 -0.887696 -v 0.080779 0.095561 0.155184 -vn -0.056616 0.292356 -0.954632 -v 0.080765 0.095384 0.155127 -vn 0.002906 0.126580 -0.991952 -v 0.080739 0.095238 0.155086 -vn 0.326578 0.174195 -0.928979 -v 0.080757 0.095319 0.155110 -vn 0.582344 0.005880 -0.812922 -v 0.080745 0.095237 0.155096 -vn -0.001858 0.051823 -0.998655 -v 0.080739 0.095236 0.155085 -vn 0.480258 -0.080488 -0.873426 -v 0.080726 0.095099 0.155091 -vn 0.005753 -0.114019 -0.993462 -v 0.080717 0.095062 0.155087 -vn 0.445926 -0.197172 -0.873083 -v 0.080717 0.095033 0.155096 -vn -0.043051 -0.343230 -0.938264 -v 0.080695 0.094888 0.155125 -vn -0.565592 -0.093285 -0.819393 -v 0.080710 0.094985 0.155103 -vn 0.083308 -0.419503 -0.903923 -v 0.080685 0.094819 0.155151 -vn -0.000025 0.823675 -0.567063 -v 0.080823 0.095828 0.155411 -vn 0.575282 0.609690 -0.545279 -v 0.080839 0.095807 0.155428 -vn -0.004122 0.765597 -0.643307 -v 0.080822 0.095825 0.155408 -vn 0.570106 0.591498 -0.570183 -v 0.080835 0.095794 0.155411 -vn 0.516818 0.561579 -0.646165 -v 0.080830 0.095772 0.155384 -vn 0.332367 0.562532 -0.757027 -v 0.080804 0.095639 0.155258 -vn 0.563893 0.381332 -0.732537 -v 0.080794 0.095582 0.155218 -vn -0.001905 0.956880 -0.290479 -v 0.080865 0.095978 0.155717 -vn 0.576594 0.767034 -0.281420 -v 0.080884 0.095942 0.155718 -vn 0.498944 0.772983 -0.391856 -v 0.080876 0.095925 0.155657 -vn 0.538733 0.691686 -0.480976 -v 0.080844 0.095830 0.155461 -vn 0.490274 0.867733 -0.081671 -v 0.080913 0.095966 0.155932 -vn 0.000325 0.986659 0.162802 -v 0.080906 0.095996 0.156063 -vn 0.556844 0.830614 -0.002260 -v 0.080922 0.095961 0.155997 -vn -0.004367 0.872957 0.487778 -v 0.080950 0.095874 0.156386 -vn 0.005241 0.814209 0.580548 -v 0.080951 0.095870 0.156392 -vn 0.584008 0.717588 0.379477 -v 0.080981 0.095826 0.156364 -vn 0.524417 0.798332 0.296063 -v 0.080963 0.095887 0.156259 -vn 0.495787 0.836905 0.231916 -v 0.080954 0.095910 0.156205 -vn 0.580918 0.809763 0.082569 -v 0.080931 0.095953 0.156056 -vn 0.541301 0.599613 0.589455 -v 0.081011 0.095682 0.156524 -vn 0.508440 0.653106 0.561196 -v 0.081003 0.095729 0.156481 -vn 0.551028 0.680195 0.483428 -v 0.080995 0.095769 0.156438 -vn 0.003535 0.265981 0.963972 -v 0.081033 0.095320 0.156765 -vn -0.003118 0.103675 0.994606 -v 0.081034 0.095311 0.156767 -vn 0.571441 0.276545 0.772644 -v 0.081073 0.095303 0.156699 -vn 0.573612 0.203223 0.793517 -v 0.081074 0.095298 0.156700 -vn 0.503332 0.378288 0.776888 -v 0.081041 0.095505 0.156637 -vn 0.004683 -0.278582 0.960401 -v 0.081078 0.094963 0.156759 -vn 0.576669 -0.126006 0.807202 -v 0.081122 0.094984 0.156685 -vn -0.001604 -0.154402 0.988007 -v 0.081076 0.094973 0.156762 -vn 0.559260 -0.014971 0.828857 -v 0.081114 0.095037 0.156697 -vn 0.564465 0.112717 0.817725 -v 0.081082 0.095248 0.156706 -vn -0.004819 -0.532333 0.846522 -v 0.081116 0.094664 0.156625 -vn 0.553824 -0.317831 0.769586 -v 0.081151 0.094790 0.156606 -vn 0.565736 -0.225933 0.793030 -v 0.081132 0.094913 0.156664 -vn -0.003617 -0.826684 0.562655 -v 0.081161 0.094426 0.156367 -vn 0.005084 -0.894246 0.447547 -v 0.081162 0.094419 0.156356 -vn 0.586551 -0.667196 0.459138 -v 0.081217 0.094500 0.156309 -vn 0.557954 -0.617605 0.554303 -v 0.081200 0.094555 0.156396 -vn 0.548422 -0.563407 0.617904 -v 0.081192 0.094586 0.156436 -vn 0.005218 -0.635891 0.771761 -v 0.081118 0.094655 0.156618 -vn 0.583475 -0.446929 0.678094 -v 0.081167 0.094705 0.156549 -vn 0.572099 -0.381983 0.725804 -v 0.081160 0.094741 0.156576 -vn -0.003469 -0.980810 0.194937 -v 0.081201 0.094314 0.156047 -vn 0.548000 -0.777624 0.308216 -v 0.081240 0.094441 0.156164 -vn 0.565880 -0.733457 0.376590 -v 0.081233 0.094456 0.156212 -vn 0.543748 -0.839125 -0.014419 -v 0.081278 0.094411 0.155907 -vn 0.000262 -0.998935 0.046130 -v 0.081203 0.094312 0.156034 -vn 0.001972 -0.980755 -0.195234 -v 0.081244 0.094337 0.155702 -vn 0.575546 -0.811855 0.098176 -v 0.081270 0.094410 0.155960 -vn 0.579498 -0.799108 0.160029 -v 0.081261 0.094413 0.156021 -vn 0.568744 -0.787735 0.236653 -v 0.081252 0.094421 0.156083 -vn 0.564500 -0.584813 -0.582524 -v 0.081373 0.094672 0.155387 -vn 0.004014 -0.719618 -0.694359 -v 0.081290 0.094509 0.155380 -vn 0.564642 -0.518799 -0.641893 -v 0.081390 0.094763 0.155321 -vn -0.002973 -0.519773 -0.854299 -v 0.081327 0.094760 0.155179 -vn 0.591398 -0.431051 -0.681500 -v 0.081397 0.094805 0.155298 -vn 0.005193 -0.391924 -0.919983 -v 0.081329 0.094775 0.155172 -vn 0.576803 -0.642641 -0.504293 -v 0.081359 0.094605 0.155451 -vn 0.576425 -0.668619 -0.469770 -v 0.081358 0.094599 0.155457 -vn 0.000021 -0.815940 -0.578137 -v 0.081288 0.094499 0.155392 -vn 0.573295 -0.713850 -0.402183 -v 0.081352 0.094575 0.155485 -vn 0.568975 -0.772510 -0.281950 -v 0.081319 0.094469 0.155662 -vn 0.064834 0.125044 -0.990031 -v 0.081472 0.095243 0.155226 -vn 0.581527 -0.104500 -0.806788 -v 0.081452 0.095122 0.155218 -vn 0.854935 -0.125806 -0.503248 -v 0.081446 0.095122 0.155207 -vn 0.439005 -0.184193 -0.879402 -v 0.081438 0.095040 0.155224 -vn 0.506448 -0.223976 -0.832674 -v 0.081433 0.095011 0.155228 -vn 0.551597 0.172748 -0.816026 -v 0.081494 0.095379 0.155260 -vn 0.244022 0.157439 -0.956905 -v 0.081479 0.095284 0.155233 -vn 0.364939 0.461566 -0.808565 -v 0.081517 0.095510 0.155324 -vn 0.507617 0.335570 -0.793548 -v 0.081509 0.095472 0.155302 -vn 0.577680 0.235874 -0.781440 -v 0.081498 0.095403 0.155269 -vn 0.582830 0.478879 -0.656494 -v 0.081545 0.095640 0.155428 -vn 0.572362 0.543495 -0.614016 -v 0.081550 0.095663 0.155453 -vn 0.486674 0.666364 -0.564896 -v 0.081557 0.095689 0.155483 -vn 0.522157 0.843692 0.124640 -v 0.081670 0.095805 0.156121 -vn 0.586383 0.808769 -0.045251 -v 0.081636 0.095838 0.155927 -vn 0.553429 0.820163 -0.145079 -v 0.081629 0.095838 0.155886 -vn 0.498811 0.835302 -0.231210 -v 0.081614 0.095828 0.155793 -vn 0.522405 0.735347 0.431692 -v 0.081711 0.095696 0.156326 -vn 0.579795 0.763886 0.283400 -v 0.081688 0.095768 0.156211 -vn 0.557855 0.804668 0.203244 -v 0.081676 0.095793 0.156154 -vn 0.558910 0.461620 0.688859 -v 0.081755 0.095497 0.156498 -vn 0.563907 0.526354 0.636365 -v 0.081749 0.095528 0.156479 -vn 0.579700 0.601943 0.549192 -v 0.081734 0.095602 0.156425 -vn 0.536930 0.691206 0.483674 -v 0.081717 0.095675 0.156352 -vn 0.600929 0.044915 0.798039 -v 0.081831 0.095091 0.156576 -vn 0.532231 0.169741 0.829408 -v 0.081796 0.095284 0.156573 -vn 0.571897 0.280897 0.770734 -v 0.081790 0.095316 0.156567 -vn 0.591381 0.370604 0.716185 -v 0.081780 0.095368 0.156553 -vn 0.567499 -0.483141 0.666723 -v 0.081910 0.094703 0.156375 -vn 0.601739 -0.349935 0.717952 -v 0.081875 0.094852 0.156495 -vn 0.576330 -0.269053 0.771657 -v 0.081869 0.094880 0.156510 -vn 0.552452 -0.183312 0.813138 -v 0.081855 0.094953 0.156542 -vn 0.594043 -0.052571 0.802713 -v 0.081836 0.095062 0.156572 -vn 0.601206 -0.679640 0.420286 -v 0.081951 0.094585 0.156191 -vn 0.586616 -0.605878 0.537395 -v 0.081923 0.094660 0.156323 -vn 0.566998 -0.557005 0.606843 -v 0.081915 0.094684 0.156354 -vn 0.579997 -0.757567 0.299492 -v 0.081970 0.094553 0.156090 -vn 0.599984 -0.702209 0.383305 -v 0.081956 0.094576 0.156167 -vn 0.600791 -0.795460 0.079333 -v 0.081994 0.094537 0.155954 -vn 0.575961 -0.804072 0.147432 -v 0.081989 0.094538 0.155983 -vn 0.575982 -0.786270 0.223661 -v 0.081976 0.094546 0.156057 -vn 0.669327 -0.684074 -0.289904 -v 0.082065 0.094643 0.155608 -vn 0.550047 -0.803989 -0.225944 -v 0.082035 0.094573 0.155746 -vn 0.583145 -0.804720 -0.111204 -v 0.082030 0.094565 0.155769 -vn 0.638179 -0.769863 0.006189 -v 0.082015 0.094547 0.155842 -vn 0.755016 -0.564189 -0.334129 -v 0.082076 0.094675 0.155564 -vn 0.714504 -0.625760 -0.312903 -v 0.082072 0.094662 0.155581 -vn 0.956186 0.252311 0.148485 -v 0.088903 0.095571 0.156414 -vn 0.860752 0.493270 0.125659 -v 0.088815 0.095792 0.156279 -vn 0.922841 0.219891 0.316247 -v 0.088903 0.095405 0.156582 -vn 0.906371 0.212433 0.365189 -v 0.088898 0.095341 0.156633 -vn 0.961893 0.098819 0.254944 -v 0.088903 0.095227 0.156676 -vn -0.001768 0.072216 0.997387 -v 0.088845 0.095227 0.156779 -vn -0.013542 -0.137588 0.990397 -v 0.088870 0.095023 0.156771 -vn 0.960834 0.030953 0.275391 -v 0.088903 0.095032 0.156715 -vn 0.025701 -0.335226 0.941787 -v 0.088886 0.094887 0.156738 -vn 0.238591 -0.621619 0.746100 -v 0.088903 0.094755 0.156681 -vn 0.959864 -0.017759 0.279903 -v 0.088903 0.094958 0.156716 -vn 0.962726 0.000095 0.270477 -v 0.088903 0.094992 0.156717 -vn 0.862442 0.396194 -0.314997 -v 0.085470 0.095816 0.155633 -vn 0.861097 0.492786 -0.125201 -v 0.085509 0.095881 0.155914 -vn 0.862535 0.500522 0.074237 -v 0.085554 0.095826 0.156208 -vn 0.863176 0.425475 0.271843 -v 0.085596 0.095661 0.156452 -vn 0.860743 0.289204 0.418907 -v 0.085637 0.095415 0.156609 -vn 0.862042 -0.116343 0.493303 -v 0.085721 0.094839 0.156584 -vn 0.862471 0.100376 0.496053 -v 0.085682 0.095119 0.156656 -vn 0.862101 -0.437470 0.255739 -v 0.085808 0.094462 0.156141 -vn 0.863016 -0.295582 0.409678 -v 0.085765 0.094604 0.156401 -vn 0.860682 -0.487641 -0.146398 -v 0.085893 0.094529 0.155567 -vn 0.860451 -0.505297 0.065570 -v 0.085848 0.094435 0.155852 -vn 0.861826 -0.386226 -0.328764 -v 0.085933 0.094722 0.155351 -vn 0.862936 -0.228844 -0.450524 -v 0.085976 0.094991 0.155226 -vn 0.861754 -0.027093 -0.506603 -v 0.086020 0.095289 0.155219 -vn 0.860910 0.173590 -0.478227 -v 0.086060 0.095556 0.155327 -vn 0.860925 0.353742 -0.365616 -v 0.086105 0.095767 0.155541 -vn 0.862513 0.467744 -0.193095 -v 0.086146 0.095871 0.155813 -vn 0.861207 0.508247 0.002630 -v 0.086188 0.095859 0.156108 -vn 0.861188 0.464045 0.207408 -v 0.086232 0.095728 0.156376 -vn 0.860476 0.343213 0.376543 -v 0.086272 0.095510 0.156564 -vn 0.861395 0.162763 0.481151 -v 0.086316 0.095223 0.156653 -vn 0.860748 -0.235638 0.451206 -v 0.086399 0.094678 0.156476 -vn 0.863696 -0.040856 0.502354 -v 0.086358 0.094932 0.156621 -vn 0.860805 -0.491971 0.130302 -v 0.086483 0.094431 0.155956 -vn 0.861240 -0.396652 0.317700 -v 0.086444 0.094498 0.156236 -vn 0.861634 -0.502100 -0.074039 -v 0.086528 0.094483 0.155662 -vn 0.862542 -0.429411 -0.267632 -v 0.086570 0.094646 0.155416 -vn 0.860691 -0.292865 -0.416462 -v 0.086611 0.094890 0.155257 -vn 0.861541 -0.100789 -0.497582 -v 0.086656 0.095186 0.155207 -vn 0.861603 0.111065 -0.495283 -v 0.086695 0.095467 0.155277 -vn 0.862880 0.292092 -0.412457 -v 0.086739 0.095704 0.155457 -vn 0.861917 0.435475 -0.259731 -v 0.086782 0.095848 0.155716 -vn 0.860426 0.504752 -0.069944 -v 0.086822 0.095877 0.156004 -vn 0.860576 0.489031 0.142329 -v 0.086867 0.095786 0.156290 -vn 0.861827 0.389138 0.325309 -v 0.086907 0.095595 0.156508 -vn 0.861828 0.233923 0.450037 -v 0.086950 0.095328 0.156636 -vn 0.861581 0.031638 0.506634 -v 0.086994 0.095029 0.156645 -vn 0.860852 -0.350608 0.368793 -v 0.087079 0.094549 0.156328 -vn 0.860901 -0.169509 0.479704 -v 0.087034 0.094761 0.156540 -vn 0.862597 -0.465758 0.197471 -v 0.087120 0.094442 0.156056 -vn 0.860919 -0.508739 0.001947 -v 0.087162 0.094451 0.155762 -vn 0.860410 -0.346301 -0.373859 -v 0.087246 0.094796 0.155302 -vn 0.861002 -0.466200 -0.203307 -v 0.087206 0.094579 0.155492 -vn 0.860889 0.232647 -0.452487 -v 0.087373 0.095629 0.155382 -vn 0.864858 0.030677 -0.501079 -v 0.087332 0.095374 0.155240 -vn 0.861211 -0.167431 -0.479877 -v 0.087290 0.095082 0.155210 -vn 0.862270 0.486795 -0.139716 -v 0.087458 0.095880 0.155901 -vn 0.861082 0.393946 -0.321472 -v 0.087418 0.095811 0.155621 -vn 0.863566 0.500292 0.062942 -v 0.087502 0.095831 0.156195 -vn 0.864042 0.431825 0.258764 -v 0.087544 0.095670 0.156443 -vn 0.862469 0.299301 0.408126 -v 0.087585 0.095428 0.156604 -vn 0.863461 0.110173 0.492237 -v 0.087630 0.095132 0.156656 -vn 0.863421 -0.101364 0.494196 -v 0.087670 0.094851 0.156589 -vn 0.864695 -0.281585 0.415948 -v 0.087713 0.094612 0.156411 -vn 0.863521 -0.428337 0.266193 -v 0.087756 0.094466 0.156153 -vn 0.862297 -0.500114 0.079558 -v 0.087796 0.094434 0.155866 -vn 0.862540 -0.488671 -0.131244 -v 0.087841 0.094523 0.155579 -vn 0.863716 -0.392691 -0.315895 -v 0.087882 0.094712 0.155359 -vn 0.863463 -0.242206 -0.442457 -v 0.087924 0.094978 0.155229 -vn 0.863308 -0.041162 -0.502996 -v 0.087968 0.095276 0.155217 -vn 0.863306 0.339990 -0.372973 -v 0.088053 0.095759 0.155530 -vn 0.862884 0.158791 -0.479809 -v 0.088008 0.095545 0.155320 -vn 0.862715 0.505525 -0.012952 -v 0.088136 0.095862 0.156094 -vn 0.865317 0.456999 -0.205859 -v 0.088094 0.095869 0.155801 -vn 0.862412 0.351139 0.364618 -v 0.088220 0.095521 0.156558 -vn 0.862863 0.467369 0.192443 -v 0.088180 0.095736 0.156366 -vn 0.863247 0.177158 0.472672 -v 0.088264 0.095237 0.156652 -vn 0.865247 -0.026828 0.500627 -v 0.088306 0.094944 0.156625 -vn 0.862429 -0.220378 0.455687 -v 0.088347 0.094688 0.156485 -vn 0.863092 -0.384250 0.327756 -v 0.088392 0.094504 0.156248 -vn 0.862819 -0.484868 0.142990 -v 0.088432 0.094432 0.155969 -vn 0.863680 -0.500832 -0.056777 -v 0.088476 0.094478 0.155674 -vn 0.863826 -0.434992 -0.254141 -v 0.088519 0.094637 0.155425 -vn 0.862013 -0.304909 -0.404926 -v 0.088559 0.094878 0.155262 -vn 0.862389 -0.113219 -0.493424 -v 0.088604 0.095173 0.155207 -vn 0.863379 0.095958 -0.495347 -v 0.088644 0.095455 0.155271 -vn 0.863341 0.425564 -0.271177 -v 0.088731 0.095844 0.155704 -vn 0.864639 0.276870 -0.419216 -v 0.088687 0.095695 0.155447 -vn 0.862371 0.499100 -0.084941 -v 0.088770 0.095878 0.155991 -vn -0.001160 -0.133552 -0.991041 -v 0.081372 0.095098 0.155084 -vn 0.012640 0.031601 -0.999421 -v 0.081374 0.095116 0.155082 -vn 0.008350 0.820217 -0.571991 -v 0.085383 0.095874 0.155477 -vn -0.004107 0.926739 -0.375685 -v 0.085398 0.095930 0.155581 -vn 0.006597 0.979683 -0.200445 -v 0.085424 0.095995 0.155795 -vn -0.007561 0.999689 0.023777 -v 0.085437 0.096006 0.155911 -vn 0.010135 0.980240 0.197552 -v 0.085466 0.095980 0.156140 -vn -0.010135 0.905165 0.424940 -v 0.085481 0.095942 0.156255 -vn 0.007819 0.817324 0.576126 -v 0.085510 0.095827 0.156454 -vn -0.004487 0.664660 0.747133 -v 0.085524 0.095748 0.156542 -vn 0.008148 0.526193 0.850326 -v 0.085549 0.095571 0.156673 -vn -0.010497 0.306656 0.951763 -v 0.085565 0.095460 0.156725 -vn 0.010186 0.148430 0.988871 -v 0.085594 0.095237 0.156778 -vn -0.008721 -0.094701 0.995468 -v 0.085609 0.095112 0.156780 -vn 0.006447 -0.264479 0.964370 -v 0.085635 0.094896 0.156741 -vn -0.008180 -0.477308 0.878698 -v 0.085649 0.094785 0.156696 -vn 0.010552 -0.621573 0.783285 -v 0.085677 0.094598 0.156573 -vn -0.008897 -0.794122 0.607693 -v 0.085693 0.094508 0.156482 -vn 0.012451 -0.881017 0.472921 -v 0.085721 0.094387 0.156293 -vn -0.007741 -0.969905 0.243360 -v 0.085736 0.094342 0.156177 -vn 0.006712 -0.996266 0.086079 -v 0.085761 0.094307 0.155966 -vn -0.011846 -0.986835 -0.161295 -v 0.085776 0.094311 0.155839 -vn 0.010384 -0.948503 -0.316598 -v 0.085805 0.094364 0.155621 -vn -0.007248 -0.839302 -0.543617 -v 0.085821 0.094421 0.155504 -vn 0.013161 -0.743843 -0.668225 -v 0.085847 0.094553 0.155332 -vn -0.013440 -0.556585 -0.830682 -v 0.085861 0.094647 0.155251 -vn 0.007936 -0.420149 -0.907420 -v 0.085888 0.094836 0.155144 -vn -0.010339 -0.178581 -0.983871 -v 0.085904 0.094962 0.155104 -vn 0.012800 -0.021074 -0.999696 -v 0.085932 0.095182 0.155082 -vn -0.007480 0.226525 -0.973977 -v 0.085948 0.095312 0.155096 -vn 0.008206 0.376632 -0.926327 -v 0.085972 0.095511 0.155159 -vn -0.013115 0.593880 -0.804447 -v 0.085988 0.095625 0.155223 -vn 0.010614 0.712601 -0.701490 -v 0.086015 0.095790 0.155366 -vn -0.008549 0.866932 -0.498352 -v 0.086033 0.095872 0.155474 -vn 0.014605 0.933398 -0.358545 -v 0.086059 0.095964 0.155667 -vn -0.013204 0.993197 -0.115697 -v 0.086073 0.095994 0.155793 -vn 0.008149 0.999221 0.038607 -v 0.086098 0.096003 0.156002 -vn -0.011741 0.957040 0.289716 -v 0.086116 0.095980 0.156138 -vn 0.013172 0.900231 0.435213 -v 0.086143 0.095902 0.156339 -vn -0.007643 0.762810 0.646578 -v 0.086160 0.095827 0.156453 -vn 0.010108 0.653595 0.756777 -v 0.086184 0.095683 0.156598 -vn -0.014442 0.444578 0.895624 -v 0.086199 0.095571 0.156673 -vn 0.010737 0.301544 0.953392 -v 0.086226 0.095374 0.156753 -vn -0.009950 0.047704 0.998812 -v 0.086244 0.095235 0.156778 -vn 0.015304 -0.105325 0.994320 -v 0.086270 0.095025 0.156771 -vn -0.012086 -0.350483 0.936491 -v 0.086286 0.094893 0.156740 -vn 0.008396 -0.489394 0.872022 -v 0.086309 0.094709 0.156655 -vn -0.013132 -0.694250 0.719614 -v 0.086327 0.094595 0.156570 -vn 0.013389 -0.796492 0.604501 -v 0.086354 0.094455 0.156413 -vn -0.008456 -0.923846 0.382670 -v 0.086372 0.094385 0.156289 -vn 0.012640 -0.971197 0.237942 -v 0.086395 0.094322 0.156098 -vn -0.015659 -0.999785 -0.013625 -v 0.086411 0.094306 0.155960 -vn 0.010831 -0.986346 -0.164330 -v 0.086437 0.094324 0.155755 -vn -0.011339 -0.910579 -0.413179 -v 0.086455 0.094367 0.155615 -vn 0.015671 -0.837645 -0.545990 -v 0.086481 0.094466 0.155435 -vn -0.011020 -0.673213 -0.739366 -v 0.086498 0.094559 0.155327 -vn 0.008982 -0.553430 -0.832847 -v 0.086521 0.094713 0.155206 -vn -0.014463 -0.323785 -0.946020 -v 0.086539 0.094844 0.155141 -vn 0.013613 -0.177059 -0.984106 -v 0.086565 0.095043 0.155089 -vn -0.009612 0.082237 -0.996566 -v 0.086583 0.095192 0.155082 -vn 0.015287 0.229643 -0.973155 -v 0.086607 0.095387 0.155114 -vn -0.016512 0.468866 -0.883115 -v 0.086623 0.095520 0.155164 -vn 0.010956 0.594549 -0.803985 -v 0.086648 0.095689 0.155269 -vn -0.012824 0.782997 -0.621893 -v 0.086667 0.095798 0.155375 -vn 0.016112 0.867000 -0.498048 -v 0.086692 0.095911 0.155541 -vn -0.010370 0.965199 -0.261311 -v 0.086710 0.095967 0.155679 -vn 0.010130 0.993478 -0.113570 -v 0.086732 0.096003 0.155866 -vn -0.015792 0.989529 0.143468 -v 0.086750 0.096002 0.156017 -vn 0.013788 0.957238 0.288973 -v 0.086775 0.095958 0.156211 -vn -0.010904 0.848860 0.528506 -v 0.086795 0.095894 0.156352 -vn 0.017126 0.762295 0.647003 -v 0.086819 0.095780 0.156509 -vn -0.016610 0.571573 0.820383 -v 0.086835 0.095671 0.156608 -vn 0.011055 0.445625 0.895152 -v 0.086858 0.095505 0.156706 -vn -0.014250 0.196466 0.980407 -v 0.086878 0.095357 0.156757 -vn 0.016386 0.049811 0.998624 -v 0.086903 0.095162 0.156782 -vn -0.010254 -0.208510 0.977966 -v 0.086922 0.095008 0.156769 -vn 0.011813 -0.350991 0.936305 -v 0.086943 0.094830 0.156716 -vn -0.017147 -0.579251 0.814969 -v 0.086962 0.094693 0.156644 -vn 0.013902 -0.692028 0.721737 -v 0.086986 0.094544 0.156521 -vn -0.012280 -0.857763 0.513899 -v 0.087007 0.094444 0.156396 -vn 0.018299 -0.922888 0.384634 -v 0.087030 0.094358 0.156226 -vn -0.015894 -0.990832 0.134159 -v 0.087048 0.094319 0.156078 -vn 0.011221 -0.999879 -0.010738 -v 0.087069 0.094307 0.155893 -vn -0.015718 -0.962111 -0.272205 -v 0.087090 0.094329 0.155733 -vn 0.016664 -0.912341 -0.409091 -v 0.087114 0.094395 0.155553 -vn -0.010823 -0.774370 -0.632641 -v 0.087134 0.094480 0.155416 -vn 0.014264 -0.674221 -0.738392 -v 0.087155 0.094605 0.155284 -vn -0.018385 -0.460596 -0.887420 -v 0.087174 0.094734 0.155193 -vn 0.013972 -0.328748 -0.944314 -v 0.087197 0.094906 0.155119 -vn -0.013799 -0.065890 -0.997731 -v 0.087218 0.095069 0.155086 -vn 0.018914 0.077164 -0.996839 -v 0.087241 0.095255 0.155087 -vn -0.018523 0.325662 -0.945305 -v 0.087260 0.095411 0.155121 -vn 0.003162 0.475498 -0.879711 -v 0.087281 0.095575 0.155192 -vn -0.017123 0.680955 -0.732125 -v 0.087301 0.095711 0.155287 -vn 0.016911 0.778713 -0.627153 -v 0.087325 0.095837 0.155424 -vn -0.003324 0.912036 -0.410097 -v 0.087346 0.095924 0.155567 -vn 0.021097 0.966118 -0.257237 -v 0.087367 0.095983 0.155735 -vn -0.023806 0.999635 -0.012756 -v 0.087385 0.096005 0.155895 -vn 0.004773 0.988828 0.148983 -v 0.087408 0.095993 0.156076 -vn -0.008461 0.701703 0.712420 -v 0.087472 0.095758 0.156531 -vn 0.013385 0.840602 0.541487 -v 0.087452 0.095864 0.156402 -vn -0.010658 0.926670 0.375724 -v 0.087429 0.095948 0.156241 -vn 0.007472 0.559356 0.828894 -v 0.087492 0.095625 0.156640 -vn -0.008752 -0.042033 0.999078 -v 0.087558 0.095128 0.156781 -vn 0.011736 0.182524 0.983131 -v 0.087536 0.095301 0.156769 -vn -0.012831 0.362904 0.931738 -v 0.087513 0.095475 0.156719 -vn 0.012961 -0.224956 0.974283 -v 0.087579 0.094955 0.156757 -vn -0.011459 -0.756070 0.654391 -v 0.087641 0.094519 0.156494 -vn 0.009313 -0.590215 0.807192 -v 0.087619 0.094648 0.156613 -vn -0.013483 -0.431470 0.902027 -v 0.087597 0.094798 0.156703 -vn 0.013334 -0.864921 0.501730 -v 0.087663 0.094416 0.156350 -vn -0.013427 -0.994809 -0.100870 -v 0.087724 0.094309 0.155854 -vn 0.008077 -0.992788 0.119607 -v 0.087703 0.094311 0.156028 -vn -0.007742 -0.954040 0.299580 -v 0.087684 0.094346 0.156191 -vn 0.011475 -0.958529 -0.284766 -v 0.087746 0.094343 0.155683 -vn -0.012670 -0.606195 -0.795215 -v 0.087809 0.094635 0.155260 -vn 0.013920 -0.764460 -0.644521 -v 0.087790 0.094511 0.155378 -vn -0.009618 -0.870307 -0.492417 -v 0.087769 0.094413 0.155518 -vn 0.008908 -0.449594 -0.893188 -v 0.087830 0.094777 0.155170 -vn -0.007714 0.168486 -0.985674 -v 0.087896 0.095297 0.155093 -vn 0.013218 -0.052990 -0.998508 -v 0.087874 0.095117 0.155082 -vn -0.012175 -0.238969 -0.970951 -v 0.087852 0.094947 0.155108 -vn 0.009402 0.346606 -0.937964 -v 0.087915 0.095453 0.155135 -vn -0.010398 0.834565 -0.550811 -v 0.087981 0.095863 0.155461 -vn 0.011148 0.689716 -0.723994 -v 0.087957 0.095745 0.155319 -vn -0.013950 0.542779 -0.839760 -v 0.087936 0.095612 0.155214 -vn 0.014329 0.922181 -0.386493 -v 0.088001 0.095942 0.155608 -vn -0.012817 0.973409 0.228716 -v 0.088064 0.095984 0.156123 -vn 0.008492 0.999939 0.007105 -v 0.088041 0.096006 0.155939 -vn -0.011429 0.984161 -0.176908 -v 0.088022 0.095992 0.155778 -vn 0.013066 0.913237 0.407220 -v 0.088085 0.095931 0.156281 -vn -0.014361 0.500267 0.865752 -v 0.088148 0.095584 0.156666 -vn 0.011264 0.676347 0.736497 -v 0.088127 0.095730 0.156559 -vn -0.008382 0.800325 0.599508 -v 0.088108 0.095836 0.156441 -vn 0.010773 0.330762 0.943653 -v 0.088168 0.095436 0.156734 -vn -0.009794 -0.291506 0.956519 -v 0.088234 0.094907 0.156744 -vn 0.014339 -0.076399 0.996974 -v 0.088212 0.095088 0.156779 -vn -0.011146 0.110793 0.993781 -v 0.088192 0.095251 0.156776 -vn 0.008116 -0.462528 0.886567 -v 0.088252 0.094764 0.156686 -vn -0.009157 -0.898415 0.439052 -v 0.088320 0.094391 0.156303 -vn 0.012767 -0.778164 0.627931 -v 0.088296 0.094494 0.156465 -vn -0.013410 -0.646446 0.762842 -v 0.088275 0.094607 0.156581 -vn 0.012952 -0.963953 0.265757 -v 0.088338 0.094336 0.156157 -vn -0.011887 -0.935427 -0.353320 -v 0.088403 0.094361 0.155630 -vn 0.010342 -0.990773 -0.135134 -v 0.088379 0.094313 0.155819 -vn -0.014309 -0.998606 0.050803 -v 0.088359 0.094307 0.155975 -vn 0.014223 -0.852691 -0.522222 -v 0.088423 0.094431 0.155488 -vn -0.013915 -0.385183 -0.922735 -v 0.088487 0.094830 0.155147 -vn 0.008237 -0.577835 -0.816112 -v 0.088463 0.094661 0.155240 -vn -0.008630 -0.718269 -0.695712 -v 0.088446 0.094548 0.155337 -vn 0.012430 -0.205158 -0.978650 -v 0.088506 0.094979 0.155100 -vn -0.013756 0.409851 -0.912049 -v 0.088571 0.095507 0.155157 -vn 0.014021 0.203169 -0.979043 -v 0.088550 0.095326 0.155099 -vn -0.009915 0.018412 -0.999781 -v 0.088532 0.095176 0.155082 -vn 0.009904 0.571585 -0.820483 -v 0.088590 0.095637 0.155231 -vn -0.008220 0.946760 -0.321836 -v 0.088658 0.095963 0.155665 -vn 0.014012 0.853215 -0.521370 -v 0.088634 0.095879 0.155485 -vn -0.012537 0.740056 -0.672428 -v 0.088615 0.095788 0.155363 -vn 0.009070 0.989868 -0.141699 -v 0.088675 0.095996 0.155804 -vn -0.010667 0.881779 0.471542 -v 0.088743 0.095902 0.156338 -vn 0.012019 0.964842 0.262557 -v 0.088717 0.095978 0.156149 -vn -0.014352 0.996926 0.077027 -v 0.088698 0.096003 0.156001 -vn 0.014654 0.778688 0.627241 -v 0.088761 0.095821 0.156461 -vn 0.961103 0.065822 0.268232 -v 0.088903 0.095193 0.156687 -vn -0.015547 0.266073 0.963828 -v 0.088826 0.095372 0.156753 -vn 0.009348 0.469783 0.882733 -v 0.088801 0.095563 0.156678 -vn -0.012609 0.624918 0.780589 -v 0.088784 0.095682 0.156599 -vn -0.860884 -0.073285 0.503496 -v 0.085522 0.095225 0.156653 -vn 0.222207 -0.942863 0.248259 -v 0.088903 0.094493 0.156241 -vn -0.839005 -0.537674 0.083525 -v 0.088900 0.094496 0.156232 -vn 0.253662 -0.966652 -0.035219 -v 0.088903 0.094480 0.156046 -vn -0.318234 0.893347 0.317266 -v 0.081492 0.095828 0.156154 -vn -0.426730 0.797458 0.426572 -v 0.081500 0.095805 0.156210 -vn -0.848886 0.427633 0.310679 -v 0.081510 0.095824 0.156214 -vn -0.432309 -0.202972 -0.878585 -v 0.081880 0.094993 0.155313 -vn -0.418545 -0.047844 -0.906935 -v 0.081883 0.095015 0.155308 -vn -0.857390 0.006147 -0.514630 -v 0.081932 0.094988 0.155226 -vn -0.417806 0.482976 -0.769527 -v 0.081946 0.095430 0.155367 -vn -0.428279 0.580313 -0.692686 -v 0.081958 0.095498 0.155408 -vn -0.855087 0.377687 -0.355215 -v 0.082015 0.095553 0.155325 -vn -0.417884 0.857075 -0.301323 -v 0.082008 0.095704 0.155648 -vn -0.429916 0.891519 -0.142708 -v 0.082033 0.095756 0.155808 -vn -0.858019 0.512597 0.032376 -v 0.082100 0.095870 0.155807 -vn -0.419461 0.907547 0.020260 -v 0.082038 0.095761 0.155845 -vn -0.857423 0.457891 0.234866 -v 0.082143 0.095861 0.156101 -vn -0.428698 0.880006 0.204472 -v 0.082070 0.095750 0.156050 -vn -0.421381 0.851081 0.313209 -v 0.082073 0.095744 0.156073 -vn -0.405738 0.677173 -0.613851 -v 0.081975 0.095582 0.155478 -vn -0.415040 0.740796 -0.528170 -v 0.081983 0.095620 0.155519 -vn -0.855305 0.488467 -0.172783 -v 0.082060 0.095764 0.155537 -vn -0.429483 0.800732 -0.417580 -v 0.081998 0.095675 0.155595 -vn -0.855817 0.203376 -0.475621 -v 0.081976 0.095285 0.155218 -vn -0.403716 0.362089 -0.840181 -v 0.081934 0.095354 0.155334 -vn -0.401942 0.424703 -0.811215 -v 0.081943 0.095410 0.155357 -vn -0.415635 0.106938 -0.903223 -v 0.081913 0.095206 0.155300 -vn -0.427004 0.255444 -0.867419 -v 0.081922 0.095269 0.155310 -vn -0.419292 -0.561149 -0.713656 -v 0.081836 0.094726 0.155448 -vn -0.423446 -0.483355 -0.766200 -v 0.081843 0.094768 0.155415 -vn -0.854070 -0.209200 -0.476235 -v 0.081889 0.094721 0.155352 -vn -0.417132 -0.440412 -0.795008 -v 0.081847 0.094793 0.155398 -vn -0.408091 -0.351594 -0.842522 -v 0.081851 0.094815 0.155385 -vn -0.393093 -0.646596 -0.653752 -v 0.081821 0.094649 0.155526 -vn -0.854107 -0.378674 -0.356521 -v 0.081849 0.094529 0.155567 -vn -0.408799 -0.688490 -0.599053 -v 0.081817 0.094633 0.155545 -vn -0.381914 -0.864536 -0.326678 -v 0.081785 0.094529 0.155738 -vn -0.394842 -0.825158 -0.403998 -v 0.081789 0.094538 0.155714 -vn -0.431843 -0.739206 -0.516804 -v 0.081807 0.094592 0.155604 -vn -0.396035 -0.914327 0.084629 -v 0.081738 0.094505 0.156066 -vn -0.375307 -0.926900 0.001233 -v 0.081752 0.094494 0.155958 -vn -0.853335 -0.490524 -0.176652 -v 0.081804 0.094435 0.155852 -vn -0.413554 -0.905610 -0.094042 -v 0.081756 0.094495 0.155929 -vn -0.426687 -0.880594 -0.206139 -v 0.081766 0.094500 0.155859 -vn -0.371877 -0.606914 0.702398 -v 0.081661 0.094792 0.156504 -vn -0.429420 -0.703505 0.566285 -v 0.081690 0.094647 0.156371 -vn -0.855137 -0.463550 0.232084 -v 0.081721 0.094602 0.156400 -vn -0.412917 -0.798207 0.438596 -v 0.081694 0.094629 0.156349 -vn -0.854014 -0.519013 0.035861 -v 0.081764 0.094461 0.156140 -vn -0.406201 -0.854279 0.324360 -v 0.081722 0.094535 0.156176 -vn -0.425830 -0.881875 0.202399 -v 0.081726 0.094526 0.156150 -vn -0.411647 -0.520415 0.748141 -v 0.081657 0.094819 0.156521 -vn -0.851591 -0.329673 0.407564 -v 0.081677 0.094836 0.156582 -vn -0.344369 -0.288874 0.893287 -v 0.081631 0.095001 0.156597 -vn -0.383201 -0.355746 0.852409 -v 0.081639 0.094941 0.156579 -vn -0.428031 -0.453833 0.781553 -v 0.081651 0.094856 0.156542 -vn -0.361849 0.011496 0.932166 -v 0.081599 0.095231 0.156616 -vn -0.430429 -0.125735 0.893824 -v 0.081615 0.095117 0.156616 -vn -0.852509 -0.144411 0.502368 -v 0.081638 0.095115 0.156655 -vn -0.381665 -0.232995 0.894452 -v 0.081627 0.095032 0.156604 -vn -0.299073 0.085306 0.950410 -v 0.081595 0.095262 0.156613 -vn -0.850356 0.065970 0.522056 -v 0.081593 0.095411 0.156610 -vn -0.324747 0.128029 0.937096 -v 0.081590 0.095295 0.156608 -vn -0.850239 0.272611 0.450308 -v 0.081552 0.095657 0.156456 -vn -0.396777 0.509038 0.763838 -v 0.081541 0.095620 0.156454 -vn -0.304646 0.441269 0.844081 -v 0.081562 0.095485 0.156544 -vn -0.403460 0.318699 0.857701 -v 0.081567 0.095453 0.156559 -vn -0.426793 0.220997 0.876931 -v 0.081575 0.095400 0.156580 -vn -0.349253 0.767970 0.536884 -v 0.081505 0.095790 0.156240 -vn -0.365231 0.688462 0.626599 -v 0.081532 0.095673 0.156404 -vn -0.423745 0.583755 0.692582 -v 0.081536 0.095648 0.156429 -vn 0.058626 0.982143 0.178771 -v 0.081472 0.095862 0.156016 -vn -0.853817 0.506109 0.121865 -v 0.081466 0.095881 0.155921 -vn -0.330353 0.934129 0.135164 -v 0.081467 0.095866 0.155978 -vn -0.847118 0.531403 0.001561 -v 0.081447 0.095864 0.155778 -vn -0.859254 0.504275 -0.085965 -v 0.081427 0.095820 0.155640 -vn -0.335076 0.916174 -0.219883 -v 0.081437 0.095847 0.155739 -vn -0.432872 0.853741 -0.289393 -v 0.081424 0.095815 0.155643 -vn -0.422059 0.896264 -0.136296 -v 0.081441 0.095856 0.155777 -vn -0.410721 0.909273 -0.067312 -v 0.081443 0.095858 0.155787 -vn -0.429581 0.902132 0.040215 -v 0.081459 0.095869 0.155921 -vn -0.395907 0.831916 -0.388810 -v 0.081410 0.095769 0.155550 -vn -0.854866 0.491305 -0.166804 -v 0.081411 0.095768 0.155543 -vn -0.365355 0.798838 -0.477885 -v 0.081405 0.095750 0.155519 -vn -0.417386 0.718526 -0.556336 -v 0.081393 0.095698 0.155450 -vn -0.427681 0.672122 -0.604434 -v 0.081383 0.095647 0.155396 -vn -0.425420 0.630248 -0.649465 -v 0.081378 0.095614 0.155366 -vn -0.411590 0.748154 -0.520441 -v 0.081394 0.095701 0.155454 -vn -0.892000 0.423223 -0.158805 -v 0.081402 0.095736 0.155497 -vn -0.429677 -0.005366 -0.902967 -v 0.081308 0.095105 0.155193 -vn -0.427191 0.041001 -0.903231 -v 0.081310 0.095121 0.155193 -vn -0.421150 0.131947 -0.897342 -v 0.081316 0.095160 0.155193 -vn -0.427951 0.273554 -0.861410 -v 0.081341 0.095364 0.155227 -vn -0.422277 0.353790 -0.834575 -v 0.081346 0.095398 0.155239 -vn -0.421705 0.430831 -0.797841 -v 0.081346 0.095404 0.155241 -vn -0.407307 0.545743 -0.732302 -v 0.081372 0.095582 0.155340 -vn -0.432820 -0.370528 -0.821812 -v 0.081268 0.094808 0.155270 -vn -0.417912 -0.271582 -0.866945 -v 0.081277 0.094875 0.155241 -vn -0.401925 -0.208104 -0.891711 -v 0.081283 0.094917 0.155226 -vn -0.413529 -0.113934 -0.903334 -v 0.081295 0.095006 0.155204 -vn -0.397491 -0.779109 -0.484757 -v 0.081216 0.094496 0.155561 -vn -0.414618 -0.818168 -0.398364 -v 0.081197 0.094435 0.155692 -vn -0.423138 -0.848401 -0.318072 -v 0.081192 0.094424 0.155726 -vn -0.425565 -0.861542 -0.276839 -v 0.081188 0.094416 0.155754 -vn -0.441590 -0.711206 -0.546978 -v 0.081221 0.094519 0.155525 -vn -0.438944 -0.643303 -0.627287 -v 0.081232 0.094573 0.155453 -vn -0.401805 -0.564272 -0.721214 -v 0.081246 0.094658 0.155369 -vn -0.402822 -0.494098 -0.770456 -v 0.081251 0.094694 0.155341 -vn -0.451444 -0.795143 0.404902 -v 0.081117 0.094491 0.156328 -vn -0.455913 -0.815588 0.356314 -v 0.081121 0.094477 0.156302 -vn -0.424672 -0.859021 0.285895 -v 0.081126 0.094457 0.156260 -vn -0.419894 -0.891970 0.167566 -v 0.081148 0.094403 0.156087 -vn -0.422593 -0.902299 0.085275 -v 0.081151 0.094398 0.156057 -vn -0.424137 -0.904019 0.053449 -v 0.081153 0.094395 0.156035 -vn -0.429737 -0.901627 -0.048941 -v 0.081157 0.094393 0.156009 -vn -0.417470 -0.893701 -0.164369 -v 0.081182 0.094405 0.155800 -vn -0.451159 -0.565487 0.690420 -v 0.081076 0.094704 0.156569 -vn -0.410369 -0.657771 0.631613 -v 0.081088 0.094635 0.156511 -vn -0.372806 -0.710011 0.597412 -v 0.081094 0.094599 0.156475 -vn -0.385901 -0.746051 0.542668 -v 0.081098 0.094575 0.156448 -vn -0.372224 -0.417305 0.829039 -v 0.081056 0.094854 0.156656 -vn -0.405042 -0.478287 0.779219 -v 0.081062 0.094807 0.156633 -vn -0.424186 0.039747 0.904702 -v 0.081001 0.095310 0.156711 -vn -0.356182 -0.061621 0.932383 -v 0.081026 0.095109 0.156720 -vn -0.435034 -0.175352 0.883175 -v 0.081032 0.095059 0.156714 -vn -0.434032 -0.257899 0.863194 -v 0.081040 0.094987 0.156701 -vn -0.405552 -0.349559 0.844592 -v 0.081049 0.094908 0.156677 -vn -0.412552 0.258251 0.873560 -v 0.080993 0.095374 0.156697 -vn -0.444298 0.332194 0.832013 -v 0.080967 0.095572 0.156615 -vn -0.422547 0.130742 0.896862 -v 0.080999 0.095322 0.156709 -vn -0.363432 0.595541 0.716413 -v 0.080951 0.095689 0.156532 -vn -0.373393 0.658954 0.652961 -v 0.080937 0.095779 0.156442 -vn -0.428550 0.484574 0.762583 -v 0.080961 0.095619 0.156586 -vn -0.435338 0.444438 0.782915 -v 0.080962 0.095613 0.156590 -vn -0.461064 0.867226 0.187986 -v 0.080885 0.095962 0.156052 -vn -0.353568 0.879248 0.319239 -v 0.080898 0.095936 0.156157 -vn -0.310026 0.860978 0.403237 -v 0.080905 0.095918 0.156211 -vn -0.470324 0.716672 0.514953 -v 0.080926 0.095838 0.156363 -vn -0.452665 0.682539 0.573790 -v 0.080931 0.095813 0.156400 -vn -0.279842 0.960041 -0.003118 -v 0.080866 0.095973 0.155885 -vn -0.398204 0.913817 0.079818 -v 0.080872 0.095973 0.155944 -vn -0.427055 0.747131 -0.509332 -v 0.080810 0.095808 0.155422 -vn -0.452542 0.784227 -0.424493 -v 0.080810 0.095811 0.155425 -vn -0.320367 0.872171 -0.369706 -v 0.080836 0.095917 0.155617 -vn -0.424332 0.873599 -0.238258 -v 0.080842 0.095936 0.155671 -vn -0.429156 0.886702 -0.172002 -v 0.080848 0.095951 0.155725 -vn -0.399508 0.912064 -0.092370 -v 0.080853 0.095959 0.155766 -vn -0.294032 0.600528 -0.743580 -v 0.080778 0.095611 0.155233 -vn -0.328191 0.696144 -0.638494 -v 0.080803 0.095774 0.155379 -vn -0.370880 0.211588 -0.904256 -v 0.080741 0.095295 0.155103 -vn 0.449725 0.188592 -0.873029 -v 0.080747 0.095356 0.155117 -vn 0.349791 0.272308 -0.896379 -v 0.080754 0.095420 0.155136 -vn -0.540059 0.476587 -0.693687 -v 0.080771 0.095558 0.155200 -vn -0.643106 0.111504 -0.757616 -v 0.080734 0.095235 0.155094 -vn -0.621213 0.068707 -0.780624 -v 0.080716 0.095075 0.155091 -vn -0.027935 -0.171808 -0.984734 -v 0.080708 0.095013 0.155098 -vn -0.865870 -0.267836 0.422531 -v 0.088814 0.094926 0.156619 -vn -0.864055 -0.414134 0.286185 -v 0.088856 0.094674 0.156473 -vn 0.244617 -0.864861 0.438382 -v 0.088903 0.094586 0.156484 -vn 0.262091 -0.801268 0.537846 -v 0.088903 0.094613 0.156526 -vn 0.251457 -0.750280 0.611432 -v 0.088903 0.094619 0.156534 -vn 0.181555 -0.950699 0.251416 -v 0.088903 0.094505 0.156291 -vn -0.413070 0.816035 0.404301 -v 0.082082 0.095729 0.156122 -vn -0.858276 0.324077 0.397916 -v 0.082187 0.095733 0.156370 -vn -0.861119 0.141101 0.488430 -v 0.082226 0.095517 0.156560 -vn -0.858813 -0.069042 0.507616 -v 0.082270 0.095233 0.156652 -vn -0.861372 -0.258927 0.437030 -v 0.082312 0.094941 0.156624 -vn -0.859408 -0.412872 0.301586 -v 0.082353 0.094686 0.156484 -vn -0.859184 -0.500140 0.107990 -v 0.082398 0.094503 0.156247 -vn -0.859650 -0.501721 -0.096321 -v 0.082437 0.094432 0.155969 -vn -0.860037 -0.419709 -0.290139 -v 0.082481 0.094478 0.155675 -vn -0.859995 -0.276193 -0.429099 -v 0.082524 0.094636 0.155426 -vn -0.858991 -0.081279 -0.505498 -v 0.082564 0.094875 0.155263 -vn -0.858978 0.131017 -0.494966 -v 0.082609 0.095170 0.155207 -vn -0.860317 0.311965 -0.403152 -v 0.082649 0.095451 0.155269 -vn -0.861533 0.446375 -0.241889 -v 0.082692 0.095691 0.155443 -vn -0.860087 0.507466 -0.052239 -v 0.082735 0.095842 0.155698 -vn -0.860199 0.484506 0.159098 -v 0.082775 0.095879 0.155984 -vn -0.859542 0.381482 0.340088 -v 0.082820 0.095796 0.156272 -vn -0.861359 0.217738 0.458967 -v 0.082860 0.095612 0.156495 -vn -0.860509 0.016950 0.509154 -v 0.082903 0.095350 0.156630 -vn -0.859620 -0.185324 0.476139 -v 0.082947 0.095053 0.156649 -vn -0.860172 -0.360937 0.360317 -v 0.082986 0.094782 0.156553 -vn -0.859948 -0.475491 0.185468 -v 0.083031 0.094563 0.156349 -vn -0.862700 -0.505530 -0.013699 -v 0.083072 0.094446 0.156081 -vn -0.860645 -0.462136 -0.213824 -v 0.083113 0.094445 0.155789 -vn -0.860584 -0.335860 -0.382876 -v 0.083158 0.094563 0.155515 -vn -0.860889 -0.158849 -0.483361 -v 0.083197 0.094771 0.155317 -vn -0.860876 0.049874 -0.506364 -v 0.083241 0.095051 0.155214 -vn -0.861455 0.240019 -0.447534 -v 0.083284 0.095345 0.155232 -vn -0.860298 0.400565 -0.315333 -v 0.083324 0.095604 0.155362 -vn -0.860199 0.494314 -0.125347 -v 0.083369 0.095796 0.155591 -vn -0.861355 0.502188 0.076649 -v 0.083409 0.095878 0.155868 -vn -0.862598 0.426591 0.271930 -v 0.083452 0.095843 0.156162 -vn -0.861205 0.291063 0.416664 -v 0.083495 0.095693 0.156418 -vn -0.861466 0.095687 0.498719 -v 0.083535 0.095461 0.156589 -vn -0.860577 -0.111742 0.496911 -v 0.083580 0.095170 0.156656 -vn -0.862166 -0.294643 0.412134 -v 0.083620 0.094885 0.156604 -vn -0.861713 -0.435562 0.260263 -v 0.083663 0.094640 0.156441 -vn -0.860742 -0.504284 0.069437 -v 0.083707 0.094478 0.156190 -vn -0.861262 -0.488433 -0.140218 -v 0.083746 0.094431 0.155907 -vn -0.860775 -0.391849 -0.324839 -v 0.083791 0.094503 0.155616 -vn -0.863669 -0.232896 -0.447030 -v 0.083832 0.094680 0.155385 -vn -0.861566 -0.036779 -0.506312 -v 0.083874 0.094935 0.155241 -vn -0.860590 0.168772 -0.480522 -v 0.083918 0.095232 0.155211 -vn -0.861339 0.345642 -0.372326 -v 0.083957 0.095506 0.155297 -vn -0.861459 0.466102 -0.201585 -v 0.084001 0.095732 0.155492 -vn -0.862669 0.505722 -0.006938 -v 0.084044 0.095859 0.155757 -vn -0.861286 0.468594 0.196484 -v 0.084084 0.095872 0.156047 -vn -0.861164 0.348411 0.370143 -v 0.084129 0.095764 0.156326 -vn -0.862096 0.176238 0.475111 -v 0.084169 0.095563 0.156532 -vn -0.862797 -0.031017 0.504599 -v 0.084212 0.095288 0.156644 -vn -0.862118 -0.222389 0.455298 -v 0.084255 0.094992 0.156638 -vn -0.861214 -0.387929 0.328362 -v 0.084295 0.094730 0.156518 -vn -0.860879 -0.488470 0.142423 -v 0.084340 0.094529 0.156296 -vn -0.862712 -0.502411 -0.057538 -v 0.084380 0.094436 0.156022 -vn -0.862699 -0.436998 -0.254527 -v 0.084423 0.094460 0.155727 -vn -0.861649 -0.304894 -0.405710 -v 0.084467 0.094601 0.155465 -vn -0.862088 -0.113888 -0.493796 -v 0.084506 0.094826 0.155286 -vn -0.861397 0.093839 -0.499189 -v 0.084551 0.095114 0.155208 -vn -0.863745 0.277777 -0.420457 -v 0.084592 0.095402 0.155250 -vn -0.862272 0.424239 -0.276600 -v 0.084634 0.095652 0.155403 -vn -0.861311 0.500754 -0.085963 -v 0.084678 0.095823 0.155648 -vn -0.861986 0.492141 0.121563 -v 0.084717 0.095881 0.155929 -vn -0.861855 0.401712 0.309570 -v 0.084762 0.095820 0.156222 -vn -0.864501 0.248026 0.437175 -v 0.084803 0.095651 0.156461 -vn -0.862495 0.055666 0.502995 -v 0.084844 0.095403 0.156613 -vn -0.861922 -0.154187 0.483028 -v 0.084889 0.095107 0.156655 -vn -0.862626 -0.329488 0.383817 -v 0.084929 0.094829 0.156579 -vn -0.862904 -0.456288 0.217250 -v 0.084972 0.094597 0.156393 -vn -0.862848 -0.504786 0.026171 -v 0.085015 0.094459 0.156132 -vn -0.861804 -0.474415 -0.179513 -v 0.085055 0.094436 0.155844 -vn -0.861482 -0.360683 -0.357431 -v 0.085100 0.094533 0.155560 -vn -0.863041 -0.193107 -0.466765 -v 0.085140 0.094727 0.155347 -vn -0.864080 0.012673 -0.503195 -v 0.085183 0.094997 0.155224 -vn -0.862703 0.205520 -0.462065 -v 0.085227 0.095293 0.155220 -vn -0.862711 0.376003 -0.338159 -v 0.085266 0.095560 0.155329 -vn -0.861854 0.481364 -0.159678 -v 0.085311 0.095769 0.155544 -vn -0.863883 0.502184 0.038965 -v 0.085352 0.095871 0.155815 -vn -0.862465 0.446445 0.238414 -v 0.085394 0.095859 0.156109 -vn -0.862075 0.130814 0.489607 -v 0.085477 0.095510 0.156564 -vn -0.861078 0.321624 0.393830 -v 0.085438 0.095728 0.156377 -vn -0.864140 -0.259143 0.431401 -v 0.085563 0.094934 0.156622 -vn -0.862458 -0.413929 0.291254 -v 0.085605 0.094680 0.156479 -vn -0.861299 -0.497630 0.102610 -v 0.085649 0.094500 0.156240 -vn -0.861690 -0.497486 -0.099994 -v 0.085688 0.094431 0.155961 -vn -0.861584 -0.414889 -0.292471 -v 0.085732 0.094481 0.155667 -vn -0.862085 -0.270245 -0.428693 -v 0.085775 0.094642 0.155420 -vn -0.860625 0.134852 -0.491059 -v 0.085860 0.095178 0.155207 -vn -0.860774 -0.076875 -0.503149 -v 0.085815 0.094883 0.155260 -vn -0.861885 0.313826 -0.398331 -v 0.085900 0.095458 0.155273 -vn -0.862927 0.446358 -0.236899 -v 0.085943 0.095697 0.155449 -vn -0.861653 0.505272 -0.047488 -v 0.085987 0.095845 0.155706 -vn -0.861667 0.480824 0.162292 -v 0.086026 0.095878 0.155992 -vn -0.860740 0.376910 0.342149 -v 0.086071 0.095792 0.156279 -vn -0.862473 0.212928 0.459131 -v 0.086111 0.095605 0.156500 -vn -0.861699 0.012248 0.507273 -v 0.086154 0.095342 0.156632 -vn -0.861246 -0.362644 0.356013 -v 0.086237 0.094775 0.156548 -vn -0.860852 -0.188406 0.472691 -v 0.086198 0.095045 0.156648 -vn -0.860734 -0.475848 0.180846 -v 0.086282 0.094558 0.156342 -vn -0.863654 -0.503765 -0.017947 -v 0.086323 0.094445 0.156073 -vn -0.861360 -0.459229 -0.217183 -v 0.086365 0.094447 0.155781 -vn -0.861508 -0.331572 -0.384530 -v 0.086409 0.094568 0.155508 -vn -0.861590 -0.154395 -0.483554 -v 0.086448 0.094778 0.155313 -vn -0.861207 0.054087 -0.505367 -v 0.086493 0.095059 0.155213 -vn -0.862294 0.243475 -0.444038 -v 0.086535 0.095353 0.155234 -vn -0.860714 0.494499 -0.121005 -v 0.086620 0.095800 0.155599 -vn -0.860777 0.402247 -0.311866 -v 0.086575 0.095611 0.155367 -vn -0.861684 0.500968 0.080820 -v 0.086660 0.095879 0.155876 -vn -0.862810 0.424093 0.275145 -v 0.086703 0.095840 0.156170 -vn -0.861640 0.287100 0.418508 -v 0.086746 0.095688 0.156424 -vn -0.860221 -0.116749 0.496376 -v 0.086831 0.095161 0.156657 -vn -0.862125 -0.298176 0.409672 -v 0.086871 0.094877 0.156601 -vn -0.860525 0.095285 0.500418 -v 0.086786 0.095454 0.156592 -vn -0.861812 -0.437644 0.256413 -v 0.086914 0.094634 0.156435 -vn -0.861199 -0.487415 -0.144094 -v 0.086997 0.094432 0.155898 -vn -0.860959 -0.504420 0.065647 -v 0.086958 0.094476 0.156183 -vn -0.860533 -0.389603 -0.328165 -v 0.087042 0.094507 0.155609 -vn -0.863499 -0.229390 -0.449165 -v 0.087083 0.094686 0.155379 -vn -0.861208 -0.032839 -0.507191 -v 0.087125 0.094943 0.155239 -vn -0.860939 0.349100 -0.370017 -v 0.087208 0.095513 0.155301 -vn -0.860423 0.172218 -0.479597 -v 0.087169 0.095240 0.155211 -vn -0.863891 0.503668 0.003436 -v 0.087295 0.095861 0.155764 -vn -0.861187 0.467538 -0.199414 -v 0.087253 0.095737 0.155498 -vn -0.861118 0.468077 0.198442 -v 0.087336 0.095870 0.156055 -vn -0.862678 0.340144 0.374283 -v 0.087380 0.095760 0.156333 -vn -0.863299 0.167486 0.476093 -v 0.087420 0.095556 0.156536 -vn -0.863722 -0.040287 0.502356 -v 0.087463 0.095280 0.156646 -vn -0.863529 -0.229011 0.449301 -v 0.087506 0.094984 0.156636 -vn -0.862458 -0.392057 0.320089 -v 0.087546 0.094723 0.156513 -vn -0.862110 -0.488959 0.132987 -v 0.087591 0.094525 0.156288 -vn -0.863628 -0.499818 -0.065791 -v 0.087631 0.094436 0.156014 -vn -0.864671 -0.428334 -0.262439 -v 0.087674 0.094463 0.155719 -vn -0.863384 -0.296729 -0.408068 -v 0.087718 0.094606 0.155459 -vn -0.863216 -0.104350 -0.493933 -v 0.087757 0.094833 0.155282 -vn -0.862383 0.102709 -0.495729 -v 0.087802 0.095123 0.155207 -vn -0.864379 0.284219 -0.414813 -v 0.087843 0.095410 0.155252 -vn -0.863263 0.428112 -0.267388 -v 0.087885 0.095658 0.155409 -vn -0.862471 0.500164 -0.077324 -v 0.087929 0.095826 0.155656 -vn -0.862856 0.488387 0.130224 -v 0.087968 0.095881 0.155938 -vn -0.862575 0.394867 0.316299 -v 0.088013 0.095817 0.156229 -vn -0.865247 0.239939 0.440202 -v 0.088055 0.095645 0.156467 -vn -0.863222 0.045938 0.502730 -v 0.088096 0.095395 0.156616 -vn -0.862945 -0.162197 0.478558 -v 0.088140 0.095098 0.156654 -vn -0.863230 -0.335654 0.377055 -v 0.088180 0.094822 0.156575 -vn -0.863337 -0.459677 0.208197 -v 0.088224 0.094591 0.156387 -vn -0.863644 -0.503812 0.017100 -v 0.088266 0.094457 0.156124 -vn -0.862490 -0.469932 -0.187813 -v 0.088306 0.094437 0.155836 -vn -0.862242 -0.353191 -0.363034 -v 0.088351 0.094537 0.155553 -vn -0.863401 -0.184586 -0.469539 -v 0.088391 0.094734 0.155342 -vn -0.864608 0.022290 -0.501952 -v 0.088434 0.095005 0.155222 -vn -0.863330 0.213063 -0.457456 -v 0.088478 0.095301 0.155221 -vn -0.863293 0.381628 -0.330281 -v 0.088517 0.095566 0.155334 -vn -0.862379 0.483404 -0.150411 -v 0.088562 0.095773 0.155551 -vn -0.863986 0.501249 0.047728 -v 0.088603 0.095873 0.155823 -vn -0.863334 0.440844 0.245583 -v 0.088645 0.095857 0.156117 -vn -0.862557 0.310481 0.399497 -v 0.088689 0.095723 0.156383 -vn -0.862843 0.122322 0.490448 -v 0.088728 0.095503 0.156568 -vn -0.862386 -0.085433 0.498991 -v 0.088773 0.095216 0.156654 -vn 0.202504 -0.851107 -0.484364 -v 0.088903 0.094553 0.155800 -vn 0.253919 -0.946991 -0.196807 -v 0.088903 0.094487 0.155985 -vn 0.029759 0.325107 -0.945209 -v 0.080685 0.095424 0.155125 -vn 0.103866 -0.180756 -0.978028 -v 0.080685 0.094984 0.155099 -vn 0.044855 0.748971 -0.661082 -v 0.080685 0.095791 0.155367 -vn 0.042010 0.979160 -0.198700 -v 0.080685 0.095988 0.155760 -vn 0.048766 0.946911 0.317777 -v 0.080685 0.095963 0.156199 -vn 0.055430 0.658340 0.750677 -v 0.080685 0.095721 0.156567 -vn 0.063846 0.205562 0.976559 -v 0.080685 0.095327 0.156764 -vn 0.058849 -0.315948 0.946950 -v 0.080685 0.094888 0.156738 -vn 0.062268 -0.746843 0.662079 -v 0.080685 0.094521 0.156496 -vn 0.066678 -0.977644 0.199414 -v 0.080685 0.094323 0.156103 -vn 0.067806 -0.947030 -0.313905 -v 0.080685 0.094349 0.155664 -vn 0.074240 -0.695952 -0.714240 -v 0.080685 0.094591 0.155296 -vn -0.710387 -0.041240 0.702602 -v 0.059703 0.095185 0.155437 -vn -0.819522 0.426426 0.382811 -v 0.059703 0.095663 0.155012 -vn -0.994585 0.036923 -0.097147 -v 0.059703 0.095580 0.154971 -vn -0.994278 0.013851 -0.105922 -v 0.059703 0.095292 0.154890 -vn -0.994792 -0.008044 -0.101612 -v 0.059703 0.094993 0.154894 -vn -0.813581 -0.465987 0.347767 -v 0.059703 0.094760 0.154959 -vn -0.103391 0.920268 -0.377382 -v 0.060303 0.096715 0.155391 -vn -0.101877 0.838105 -0.535911 -v 0.060303 0.096532 0.155022 -vn -0.378926 0.770322 -0.512854 -v 0.060073 0.096494 0.155047 -vn -0.112637 -0.902286 -0.416165 -v 0.060303 0.093671 0.155212 -vn -0.091250 -0.961375 -0.259677 -v 0.060303 0.093567 0.155487 -vn -0.387728 -0.888259 -0.246300 -v 0.060073 0.093611 0.155499 -vn -0.698360 0.689271 0.192870 -v 0.059879 0.096576 0.156329 -vn -0.915558 0.388831 0.102784 -v 0.059749 0.096388 0.156276 -vn -0.893587 0.380378 0.238358 -v 0.059749 0.096241 0.156610 -vn -0.985150 -0.096617 -0.141932 -v 0.059721 0.094529 0.156950 -vn -0.876785 0.367747 -0.309855 -v 0.059714 0.094422 0.156833 -vn -0.899509 -0.288696 0.327929 -v 0.059749 0.094330 0.156909 -vn -0.981682 -0.124924 0.143856 -v 0.059721 0.094653 0.154846 -vn -0.915556 -0.056580 -0.398192 -v 0.059749 0.094958 0.154667 -vn -0.983003 0.130898 0.128726 -v 0.059721 0.094071 0.156435 -vn -0.909218 -0.341939 0.237487 -v 0.059749 0.094088 0.156637 -vn -0.698364 -0.461766 0.546863 -v 0.059879 0.094205 0.157058 -vn -0.914287 -0.154074 0.374620 -v 0.059749 0.094639 0.157102 -vn -0.981682 0.124924 -0.143856 -v 0.059721 0.095659 0.157017 -vn -0.915562 0.056582 0.398176 -v 0.059749 0.095354 0.157196 -vn -0.893860 0.192466 0.404934 -v 0.059749 0.095702 0.157089 -vn -0.905680 0.279369 0.318900 -v 0.059749 0.096006 0.156888 -vn -0.880530 -0.296161 -0.370075 -v 0.059714 0.096057 0.156665 -vn -0.982298 -0.155787 0.104028 -v 0.059721 0.096175 0.156558 -vn -0.983003 -0.130898 -0.128726 -v 0.059721 0.096241 0.155429 -vn -0.912922 0.393464 -0.108443 -v 0.059749 0.096379 0.155555 -vn -0.914288 0.154075 -0.374617 -v 0.059749 0.095672 0.154761 -vn -0.698356 -0.289003 0.654810 -v 0.059879 0.094561 0.157280 -vn -0.382697 -0.368303 0.847288 -v 0.060073 0.094508 0.157399 -vn -0.917554 0.397579 -0.005074 -v 0.059749 0.096435 0.155915 -vn -0.698358 0.715691 -0.009137 -v 0.059879 0.096630 0.155913 -vn -0.385297 0.922573 -0.020134 -v 0.060073 0.096760 0.155911 -vn -0.698359 0.607014 0.379248 -v 0.059879 0.096406 0.156713 -vn -0.698362 0.475581 0.534896 -v 0.059879 0.096135 0.157033 -vn -0.698356 0.305619 0.647222 -v 0.059879 0.095785 0.157265 -vn -0.698366 0.110896 0.707098 -v 0.059879 0.095384 0.157388 -vn -0.698360 -0.597136 0.394615 -v 0.059879 0.093926 0.156744 -vn -0.378927 -0.770321 0.512854 -v 0.060073 0.093817 0.156816 -vn -0.385766 -0.593355 0.706481 -v 0.060073 0.094121 0.157157 -vn -0.382702 -0.884558 0.266638 -v 0.060073 0.093622 0.156403 -vn -0.698358 -0.684127 0.210396 -v 0.059879 0.093747 0.156365 -vn -0.912922 -0.393463 0.108441 -v 0.059749 0.093933 0.156308 -vn -0.917554 -0.397579 0.005074 -v 0.059749 0.093876 0.155948 -vn -0.698358 -0.715691 0.009137 -v 0.059879 0.093682 0.155950 -vn -0.385299 -0.922572 0.020132 -v 0.060073 0.093552 0.155952 -vn -0.381157 -0.149085 -0.912411 -v 0.060073 0.094907 0.154347 -vn -0.383974 -0.399229 -0.832575 -v 0.060073 0.094471 0.154481 -vn -0.698358 -0.110895 -0.707106 -v 0.059879 0.094927 0.154475 -vn -0.698353 -0.305610 -0.647229 -v 0.059879 0.094526 0.154598 -vn -0.893860 -0.192465 -0.404934 -v 0.059749 0.094609 0.154774 -vn -0.917555 0.051554 -0.394252 -v 0.059749 0.095322 0.154663 -vn -0.698368 0.092797 -0.709698 -v 0.059879 0.095347 0.154470 -vn -0.385296 0.127928 -0.913883 -v 0.060073 0.095364 0.154341 -vn -0.698357 0.289002 -0.654810 -v 0.059879 0.095751 0.154583 -vn -0.382695 0.368303 -0.847288 -v 0.060073 0.095804 0.154464 -vn -0.899510 0.288692 -0.327930 -v 0.059749 0.095981 0.154954 -vn -0.909216 0.341945 -0.237489 -v 0.059749 0.096223 0.155226 -vn -0.698363 0.461769 -0.546862 -v 0.059879 0.096107 0.154805 -vn -0.698357 0.597139 -0.394617 -v 0.059879 0.096386 0.155119 -vn -0.385746 0.593363 -0.706484 -v 0.060073 0.096191 0.154706 -vn -0.387728 0.888259 0.246300 -v 0.060073 0.096701 0.156364 -vn -0.385681 0.777309 0.497032 -v 0.060073 0.096516 0.156782 -vn -0.376580 0.615541 0.692312 -v 0.060073 0.096222 0.157131 -vn -0.383966 0.399241 0.832572 -v 0.060073 0.095841 0.157382 -vn -0.381152 0.149085 0.912413 -v 0.060073 0.095404 0.157517 -vn -0.132024 0.295405 0.946206 -v 0.060303 0.095697 0.157490 -vn -0.098855 0.154144 0.983091 -v 0.060303 0.095411 0.157562 -vn -0.108854 -0.020768 0.993841 -v 0.060303 0.095059 0.157579 -vn -0.089095 -0.186195 0.978465 -v 0.060303 0.094942 0.157568 -vn -0.385293 -0.127940 0.913882 -v 0.060073 0.094948 0.157522 -vn -0.698368 -0.092812 0.709696 -v 0.059879 0.094965 0.157393 -vn -0.917557 -0.051556 0.394248 -v 0.059749 0.094990 0.157200 -vn -0.091358 -0.340555 0.935776 -v 0.060303 0.094490 0.157441 -vn -0.091700 -0.621649 0.777910 -v 0.060303 0.094091 0.157192 -vn -0.103401 -0.482430 0.869810 -v 0.060303 0.094436 0.157416 -vn -0.108867 -0.989444 -0.095651 -v 0.060303 0.093509 0.155835 -vn -0.091898 -0.993436 0.068108 -v 0.060303 0.093506 0.155953 -vn -0.093824 -0.968444 0.230895 -v 0.060303 0.093579 0.156417 -vn -0.103402 -0.920261 0.377397 -v 0.060303 0.093597 0.156473 -vn -0.101879 -0.838104 0.535912 -v 0.060303 0.093779 0.156841 -vn -0.146040 -0.750129 0.644964 -v 0.060303 0.093923 0.157028 -vn -0.698360 -0.689271 -0.192870 -v 0.059879 0.093736 0.155534 -vn -0.915558 -0.388832 -0.102783 -v 0.059749 0.093924 0.155587 -vn -0.092552 -0.819895 -0.564984 -v 0.060303 0.093756 0.155057 -vn -0.385679 -0.777311 -0.497031 -v 0.060073 0.093795 0.155081 -vn -0.698360 -0.607015 -0.379244 -v 0.059879 0.093906 0.155150 -vn -0.893583 -0.380383 -0.238364 -v 0.059749 0.094071 0.155254 -vn -0.982301 0.155760 -0.104040 -v 0.059721 0.094137 0.155305 -vn -0.880527 0.296157 0.370085 -v 0.059714 0.094254 0.155198 -vn -0.905682 -0.279367 -0.318896 -v 0.059749 0.094306 0.154975 -vn -0.698359 -0.475584 -0.534897 -v 0.059879 0.094176 0.154830 -vn -0.376573 -0.615541 -0.692316 -v 0.060073 0.094090 0.154733 -vn -0.097172 -0.661309 -0.743793 -v 0.060303 0.094059 0.154698 -vn -0.092564 -0.465157 -0.880375 -v 0.060303 0.094451 0.154440 -vn -0.103393 0.482421 -0.869816 -v 0.060303 0.095875 0.154447 -vn -0.091352 0.340532 -0.935785 -v 0.060303 0.095822 0.154422 -vn -0.089094 0.186194 -0.978465 -v 0.060303 0.095370 0.154295 -vn -0.108858 0.020743 -0.993841 -v 0.060303 0.095253 0.154284 -vn -0.098863 -0.154145 -0.983090 -v 0.060303 0.094900 0.154301 -vn -0.132039 -0.295377 -0.946212 -v 0.060303 0.094615 0.154373 -vn -0.091669 0.621649 -0.777914 -v 0.060303 0.096220 0.154671 -vn -0.985143 0.096602 0.141990 -v 0.059721 0.095782 0.154913 -vn -0.146023 0.750120 -0.644979 -v 0.060303 0.096389 0.154835 -vn -0.093814 0.968449 -0.230881 -v 0.060303 0.096733 0.155447 -vn -0.382689 0.884562 -0.266645 -v 0.060073 0.096689 0.155460 -vn -0.698358 0.684125 -0.210401 -v 0.059879 0.096565 0.155498 -vn -0.876792 -0.367728 0.309858 -v 0.059714 0.095889 0.155030 -vn -0.091899 0.993436 -0.068115 -v 0.060303 0.096806 0.155910 -vn -0.108867 0.989444 0.095651 -v 0.060303 0.096803 0.156028 -vn -0.092557 0.465153 0.880378 -v 0.060303 0.095860 0.157424 -vn -0.097171 0.661307 0.743795 -v 0.060303 0.096252 0.157165 -vn -0.092552 0.819895 0.564984 -v 0.060303 0.096555 0.156806 -vn -0.112637 0.902286 0.416165 -v 0.060303 0.096641 0.156651 -vn -0.091250 0.961375 0.259677 -v 0.060303 0.096745 0.156376 -vn 0.381694 0.304296 0.872762 -v 0.061003 0.095697 0.157490 -vn 0.377182 0.615369 0.692137 -v 0.061003 0.096252 0.157165 -vn 0.378502 -0.058608 0.923743 -v 0.061003 0.095059 0.157579 -vn 0.376576 -0.400341 0.835414 -v 0.061003 0.094436 0.157416 -vn 0.382325 -0.690555 0.613972 -v 0.061003 0.093923 0.157028 -vn 0.378071 -0.875355 0.301356 -v 0.061003 0.093597 0.156473 -vn 0.379776 -0.923642 -0.051539 -v 0.061003 0.093509 0.155835 -vn 0.381690 -0.831163 -0.404327 -v 0.061003 0.093671 0.155212 -vn 0.377183 -0.615371 -0.692135 -v 0.061003 0.094059 0.154698 -vn 0.381695 -0.304296 -0.872762 -v 0.061003 0.094615 0.154373 -vn 0.378498 0.058602 -0.923745 -v 0.061003 0.095253 0.154284 -vn 0.376572 0.400346 -0.835414 -v 0.061003 0.095875 0.154447 -vn 0.382311 0.690558 -0.613978 -v 0.061003 0.096389 0.154835 -vn 0.378061 0.875360 -0.301354 -v 0.061003 0.096715 0.155391 -vn 0.379790 0.923636 0.051539 -v 0.061003 0.096803 0.156028 -vn 0.381691 0.831164 0.404326 -v 0.061003 0.096641 0.156651 -vn 0.770259 -0.624615 0.128674 -v 0.061103 0.094323 0.156103 -vn 0.906595 -0.421276 -0.024729 -v 0.061103 0.093608 0.155841 -vn 0.770262 -0.605268 -0.200865 -v 0.061103 0.094349 0.155664 -vn 0.906604 -0.379728 -0.184057 -v 0.061103 0.093761 0.155255 -vn 0.770042 -0.424126 -0.476605 -v 0.061103 0.094591 0.155296 -vn 0.906610 -0.280378 -0.315350 -v 0.061103 0.094126 0.154773 -vn 0.770032 -0.128445 -0.624943 -v 0.061103 0.094984 0.155099 -vn 0.770257 0.128670 0.624619 -v 0.061103 0.095327 0.156764 -vn 0.906596 -0.024724 0.421274 -v 0.061103 0.095065 0.157479 -vn 0.770264 -0.200867 0.605266 -v 0.061103 0.094888 0.156738 -vn 0.906603 -0.184055 0.379730 -v 0.061103 0.094480 0.157326 -vn 0.770264 -0.476594 0.423736 -v 0.061103 0.094521 0.156496 -vn 0.906604 -0.315359 0.280389 -v 0.061103 0.093997 0.156961 -vn 0.906607 -0.398650 0.138354 -v 0.061103 0.093692 0.156440 -vn 0.770261 0.624614 -0.128668 -v 0.061103 0.095988 0.155760 -vn 0.906604 0.421256 0.024731 -v 0.061103 0.096703 0.156022 -vn 0.770258 0.605272 0.200868 -v 0.061103 0.095963 0.156199 -vn 0.906603 0.379730 0.184055 -v 0.061103 0.096551 0.156608 -vn 0.770268 0.423734 0.476588 -v 0.061103 0.095721 0.156567 -vn 0.906610 0.280378 0.315351 -v 0.061103 0.096186 0.157090 -vn 0.906601 0.138365 0.398659 -v 0.061103 0.095664 0.157396 -vn 0.906604 -0.138361 -0.398654 -v 0.061103 0.094648 0.154467 -vn 0.906596 0.024727 -0.421275 -v 0.061103 0.095247 0.154384 -vn 0.770264 0.200867 -0.605266 -v 0.061103 0.095424 0.155125 -vn 0.906603 0.184057 -0.379730 -v 0.061103 0.095832 0.154537 -vn 0.770264 0.476594 -0.423736 -v 0.061103 0.095791 0.155367 -vn 0.906598 0.315371 -0.280396 -v 0.061103 0.096314 0.154902 -vn 0.906602 0.398659 -0.138364 -v 0.061103 0.096620 0.155423 -vn 0.945451 -0.102613 0.309183 -v 0.088903 0.094967 0.156501 -vn 0.945178 -0.319634 0.066883 -v 0.088903 0.094568 0.156053 -vn 0.945448 -0.243462 0.216459 -v 0.088903 0.094707 0.156330 -vn 0.938722 0.208819 0.274218 -v 0.088903 0.095554 0.156380 -vn 0.945444 0.065736 0.319083 -v 0.088903 0.095277 0.156519 -vn 0.904975 0.274891 0.324739 -v 0.089103 0.095422 0.156230 -vn 0.900731 0.087650 0.425442 -v 0.089103 0.095237 0.156323 -vn 0.900743 -0.136827 0.412238 -v 0.089103 0.095030 0.156311 -vn 0.900737 -0.324613 0.288615 -v 0.089103 0.094857 0.156197 -vn 0.901034 -0.424635 0.088449 -v 0.089103 0.094764 0.156012 -vn 0.901370 -0.410616 -0.137571 -v 0.089103 0.094776 0.155806 -vn 0.900735 -0.288617 -0.324618 -v 0.089103 0.094890 0.155633 -vn 0.900743 -0.087638 -0.425420 -v 0.089103 0.095075 0.155540 -vn 0.900739 0.136817 -0.412250 -v 0.089103 0.095282 0.155552 -vn 0.900739 0.324611 -0.288611 -v 0.089103 0.095455 0.155666 -vn 0.900740 0.425424 -0.087643 -v 0.089103 0.095548 0.155851 -vn 0.904202 0.408300 0.125338 -v 0.089103 0.095535 0.156058 -vn 1.000000 0.000000 0.000000 -v 0.089103 0.095156 0.155932 -vn -0.948595 -0.018548 0.315948 -v 0.060703 0.095163 0.155816 -vn -0.710389 -0.041245 0.702600 -v 0.060703 0.095760 0.155284 -vn -0.710388 -0.702601 -0.041244 -v 0.060703 0.095870 0.155407 -vn -0.948596 -0.315945 -0.018549 -v 0.060703 0.095272 0.155938 -vn -0.710387 -0.702602 -0.041226 -v 0.060703 0.095803 0.156536 -vn -0.710387 0.041231 -0.702603 -v 0.060703 0.095681 0.156645 -vn -0.948595 0.018548 -0.315948 -v 0.060703 0.095149 0.156047 -vn -0.710390 0.041245 -0.702599 -v 0.060703 0.094551 0.156579 -vn -0.710388 0.702601 0.041244 -v 0.060703 0.094442 0.156456 -vn -0.948596 0.315945 0.018549 -v 0.060703 0.095040 0.155925 -vn -0.710388 0.702602 0.041226 -v 0.060703 0.094508 0.155327 -vn -0.710387 -0.041231 0.702603 -v 0.060703 0.094631 0.155218 -# 7704 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 7//7 -f 8//8 9//9 10//10 -f 11//11 12//12 13//13 -f 14//14 15//15 16//16 -f 16//16 17//17 18//18 -f 19//19 20//20 21//21 -f 22//22 23//23 24//24 -f 25//25 26//26 27//27 -f 28//28 29//29 30//30 -f 31//31 32//32 33//33 -f 34//34 35//35 36//36 -f 17//17 16//16 37//37 -f 37//37 16//16 15//15 -f 37//37 15//15 38//38 -f 34//34 36//36 39//39 -f 40//40 41//41 42//42 -f 42//42 41//41 43//43 -f 42//42 43//43 44//44 -f 31//31 45//45 46//46 -f 31//31 33//33 47//47 -f 47//47 33//33 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 28//28 -f 28//28 50//50 51//51 -f 28//28 51//51 29//29 -f 26//26 25//25 52//52 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 60//60 61//61 59//59 -f 22//22 61//61 62//62 -f 62//62 61//61 60//60 -f 62//62 60//60 63//63 -f 64//64 65//65 66//66 -f 66//66 65//65 24//24 -f 19//19 21//21 67//67 -f 68//68 69//69 70//70 -f 71//71 18//18 69//69 -f 72//72 73//73 74//74 -f 74//74 73//73 52//52 -f 74//74 52//52 75//75 -f 75//75 52//52 25//25 -f 75//75 25//25 76//76 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 40//40 -f 83//83 40//40 84//84 -f 84//84 40//40 42//42 -f 64//64 13//13 85//85 -f 85//85 13//13 12//12 -f 85//85 12//12 86//86 -f 86//86 12//12 87//87 -f 73//73 88//88 52//52 -f 52//52 88//88 53//53 -f 52//52 53//53 26//26 -f 26//26 53//53 55//55 -f 26//26 55//55 27//27 -f 34//34 38//38 35//35 -f 35//35 38//38 15//15 -f 35//35 15//15 36//36 -f 36//36 15//15 14//14 -f 36//36 14//14 89//89 -f 90//90 87//87 91//91 -f 91//91 87//87 12//12 -f 91//91 12//12 92//92 -f 92//92 12//12 11//11 -f 92//92 11//11 93//93 -f 94//94 95//95 96//96 -f 97//97 95//95 98//98 -f 98//98 95//95 94//94 -f 98//98 94//94 99//99 -f 72//72 100//100 99//99 -f 99//99 100//100 101//101 -f 99//99 101//101 98//98 -f 98//98 101//101 102//102 -f 98//98 102//102 97//97 -f 97//97 102//102 103//103 -f 97//97 103//103 104//104 -f 104//104 103//103 105//105 -f 32//32 6//6 33//33 -f 33//33 6//6 5//5 -f 33//33 5//5 48//48 -f 48//48 5//5 106//106 -f 48//48 106//106 50//50 -f 50//50 106//106 107//107 -f 50//50 107//107 51//51 -f 108//108 46//46 109//109 -f 109//109 46//46 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 4//4 -f 4//4 124//124 125//125 -f 4//4 125//125 3//3 -f 126//126 127//127 128//128 -f 128//128 127//127 129//129 -f 128//128 129//129 130//130 -f 130//130 129//129 131//131 -f 130//130 131//131 132//132 -f 132//132 131//131 133//133 -f 132//132 133//133 134//134 -f 134//134 133//133 135//135 -f 134//134 135//135 136//136 -f 127//127 137//137 129//129 -f 129//129 137//137 138//138 -f 129//129 138//138 131//131 -f 131//131 138//138 139//139 -f 131//131 139//139 133//133 -f 133//133 139//139 67//67 -f 133//133 67//67 135//135 -f 135//135 67//67 21//21 -f 135//135 21//21 136//136 -f 136//136 21//21 140//140 -f 136//136 140//140 141//141 -f 141//141 140//140 142//142 -f 143//143 144//144 145//145 -f 146//146 144//144 147//147 -f 147//147 144//144 143//143 -f 147//147 143//143 23//23 -f 23//23 22//22 147//147 -f 147//147 22//22 62//62 -f 147//147 62//62 146//146 -f 146//146 62//62 63//63 -f 146//146 63//63 148//148 -f 88//88 9//9 53//53 -f 53//53 9//9 8//8 -f 53//53 8//8 54//54 -f 54//54 8//8 149//149 -f 54//54 149//149 56//56 -f 56//56 149//149 150//150 -f 56//56 150//150 58//58 -f 58//58 150//150 151//151 -f 72//72 99//99 73//73 -f 73//73 99//99 94//94 -f 73//73 94//94 88//88 -f 88//88 94//94 96//96 -f 88//88 96//96 9//9 -f 9//9 96//96 152//152 -f 9//9 152//152 10//10 -f 104//104 153//153 97//97 -f 97//97 153//153 154//154 -f 97//97 154//154 95//95 -f 95//95 154//154 155//155 -f 95//95 155//155 96//96 -f 96//96 155//155 156//156 -f 96//96 156//156 152//152 -f 100//100 30//30 101//101 -f 101//101 30//30 29//29 -f 101//101 29//29 102//102 -f 102//102 29//29 51//51 -f 102//102 51//51 103//103 -f 103//103 51//51 107//107 -f 103//103 107//107 105//105 -f 7//7 157//157 5//5 -f 5//5 157//157 158//158 -f 5//5 158//158 106//106 -f 106//106 158//158 159//159 -f 106//106 159//159 107//107 -f 107//107 159//159 160//160 -f 107//107 160//160 105//105 -f 31//31 46//46 32//32 -f 32//32 46//46 108//108 -f 32//32 108//108 6//6 -f 6//6 108//108 161//161 -f 6//6 161//161 7//7 -f 113//113 162//162 111//111 -f 111//111 162//162 163//163 -f 111//111 163//163 109//109 -f 109//109 163//163 164//164 -f 109//109 164//164 108//108 -f 108//108 164//164 165//165 -f 108//108 165//165 161//161 -f 117//117 166//166 115//115 -f 115//115 166//166 167//167 -f 115//115 167//167 113//113 -f 113//113 167//167 168//168 -f 113//113 168//168 162//162 -f 121//121 169//169 119//119 -f 119//119 169//169 170//170 -f 119//119 170//170 117//117 -f 117//117 170//170 171//171 -f 117//117 171//171 166//166 -f 2//2 172//172 4//4 -f 4//4 172//172 173//173 -f 4//4 173//173 123//123 -f 123//123 173//173 174//174 -f 123//123 174//174 121//121 -f 121//121 174//174 175//175 -f 121//121 175//175 169//169 -f 176//176 1//1 89//89 -f 89//89 1//1 3//3 -f 89//89 3//3 36//36 -f 36//36 3//3 125//125 -f 36//36 125//125 39//39 -f 39//39 125//125 124//124 -f 39//39 124//124 177//177 -f 177//177 124//124 122//122 -f 177//177 122//122 178//178 -f 178//178 122//122 120//120 -f 178//178 120//120 77//77 -f 77//77 120//120 118//118 -f 77//77 118//118 78//78 -f 78//78 118//118 116//116 -f 78//78 116//116 80//80 -f 80//80 116//116 114//114 -f 80//80 114//114 82//82 -f 82//82 114//114 112//112 -f 82//82 112//112 40//40 -f 40//40 112//112 110//110 -f 40//40 110//110 41//41 -f 41//41 110//110 46//46 -f 41//41 46//46 43//43 -f 43//43 46//46 45//45 -f 43//43 45//45 44//44 -f 18//18 71//71 16//16 -f 16//16 71//71 179//179 -f 16//16 179//179 14//14 -f 14//14 179//179 180//180 -f 14//14 180//180 89//89 -f 89//89 180//180 181//181 -f 89//89 181//181 176//176 -f 182//182 183//183 184//184 -f 69//69 68//68 71//71 -f 71//71 68//68 185//185 -f 71//71 185//185 179//179 -f 179//179 185//185 182//182 -f 179//179 182//182 180//180 -f 180//180 182//182 184//184 -f 180//180 184//184 181//181 -f 70//70 186//186 68//68 -f 68//68 186//186 187//187 -f 68//68 187//187 185//185 -f 185//185 187//187 188//188 -f 185//185 188//188 182//182 -f 182//182 188//188 189//189 -f 182//182 189//189 183//183 -f 70//70 137//137 186//186 -f 186//186 137//137 127//127 -f 186//186 127//127 187//187 -f 187//187 127//127 126//126 -f 187//187 126//126 188//188 -f 188//188 126//126 190//190 -f 188//188 190//190 189//189 -f 132//132 191//191 130//130 -f 130//130 191//191 192//192 -f 130//130 192//192 128//128 -f 128//128 192//192 193//193 -f 128//128 193//193 126//126 -f 126//126 193//193 194//194 -f 126//126 194//194 190//190 -f 141//141 195//195 136//136 -f 136//136 195//195 196//196 -f 136//136 196//196 134//134 -f 134//134 196//196 197//197 -f 134//134 197//197 132//132 -f 132//132 197//197 198//198 -f 132//132 198//198 191//191 -f 199//199 142//142 93//93 -f 93//93 142//142 140//140 -f 93//93 140//140 92//92 -f 92//92 140//140 21//21 -f 92//92 21//21 91//91 -f 91//91 21//21 20//20 -f 91//91 20//20 90//90 -f 90//90 20//20 19//19 -f 64//64 66//66 13//13 -f 13//13 66//66 200//200 -f 13//13 200//200 11//11 -f 11//11 200//200 201//201 -f 11//11 201//201 93//93 -f 93//93 201//201 202//202 -f 93//93 202//202 199//199 -f 24//24 23//23 66//66 -f 66//66 23//23 143//143 -f 66//66 143//143 200//200 -f 200//200 143//143 145//145 -f 200//200 145//145 201//201 -f 201//201 145//145 203//203 -f 201//201 203//203 202//202 -f 148//148 204//204 146//146 -f 146//146 204//204 205//205 -f 146//146 205//205 144//144 -f 144//144 205//205 206//206 -f 144//144 206//206 145//145 -f 145//145 206//206 207//207 -f 145//145 207//207 203//203 -f 59//59 58//58 60//60 -f 60//60 58//58 151//151 -f 60//60 151//151 63//63 -f 63//63 151//151 208//208 -f 63//63 208//208 148//148 -f 10//10 209//209 8//8 -f 8//8 209//209 210//210 -f 8//8 210//210 149//149 -f 149//149 210//210 211//211 -f 149//149 211//211 150//150 -f 150//150 211//211 212//212 -f 150//150 212//212 151//151 -f 151//151 212//212 213//213 -f 151//151 213//213 208//208 -f 65//65 214//214 24//24 -f 24//24 214//214 215//215 -f 24//24 215//215 22//22 -f 34//34 216//216 38//38 -f 38//38 216//216 217//217 -f 38//38 217//217 37//37 -f 27//27 55//55 218//218 -f 27//27 218//218 25//25 -f 25//25 218//218 219//219 -f 25//25 219//219 76//76 -f 81//81 220//220 79//79 -f 79//79 220//220 221//221 -f 79//79 221//221 77//77 -f 22//22 215//215 61//61 -f 61//61 215//215 222//222 -f 61//61 222//222 59//59 -f 59//59 222//222 223//223 -f 59//59 223//223 57//57 -f 57//57 223//223 224//224 -f 57//57 224//224 55//55 -f 55//55 224//224 218//218 -f 77//77 221//221 178//178 -f 178//178 221//221 225//225 -f 178//178 225//225 177//177 -f 177//177 225//225 226//226 -f 177//177 226//226 39//39 -f 39//39 226//226 227//227 -f 39//39 227//227 34//34 -f 34//34 227//227 216//216 -f 228//228 229//229 230//230 -f 230//230 229//229 231//231 -f 227//227 232//232 216//216 -f 216//216 232//232 233//233 -f 216//216 233//233 217//217 -f 220//220 234//234 221//221 -f 221//221 234//234 235//235 -f 221//221 235//235 225//225 -f 236//236 237//237 238//238 -f 238//238 237//237 239//239 -f 240//240 241//241 242//242 -f 242//242 241//241 243//243 -f 224//224 244//244 218//218 -f 218//218 244//244 245//245 -f 218//218 245//245 219//219 -f 214//214 246//246 215//215 -f 215//215 246//246 247//247 -f 215//215 247//247 222//222 -f 45//45 237//237 44//44 -f 44//44 237//237 236//236 -f 44//44 236//236 42//42 -f 100//100 243//243 30//30 -f 30//30 243//243 241//241 -f 30//30 241//241 28//28 -f 237//237 45//45 31//31 -f 237//237 31//31 239//239 -f 239//239 31//31 47//47 -f 239//239 47//47 248//248 -f 248//248 47//47 49//49 -f 248//248 49//49 240//240 -f 240//240 49//49 28//28 -f 240//240 28//28 241//241 -f 137//137 229//229 138//138 -f 138//138 229//229 228//228 -f 138//138 228//228 139//139 -f 139//139 228//228 249//249 -f 139//139 249//249 67//67 -f 67//67 249//249 250//250 -f 67//67 250//250 19//19 -f 19//19 250//250 251//251 -f 19//19 251//251 90//90 -f 90//90 251//251 252//252 -f 90//90 252//252 87//87 -f 69//69 231//231 70//70 -f 70//70 231//231 229//229 -f 70//70 229//229 137//137 -f 253//253 254//254 255//255 -f 253//253 256//256 254//254 -f 254//254 256//256 257//257 -f 254//254 257//257 258//258 -f 258//258 257//257 259//259 -f 258//258 259//259 260//260 -f 260//260 259//259 261//261 -f 260//260 261//261 262//262 -f 262//262 263//263 260//260 -f 260//260 263//263 264//264 -f 260//260 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 267//267 -f 267//267 266//266 268//268 -f 267//267 268//268 269//269 -f 269//269 270//270 267//267 -f 267//267 270//270 271//271 -f 267//267 271//271 272//272 -f 272//272 271//271 273//273 -f 272//272 273//273 274//274 -f 274//274 273//273 275//275 -f 274//274 275//275 276//276 -f 277//277 278//278 279//279 -f 279//279 278//278 274//274 -f 279//279 274//274 280//280 -f 280//280 274//274 276//276 -f 277//277 281//281 278//278 -f 278//278 281//281 282//282 -f 278//278 282//282 283//283 -f 284//284 285//285 286//286 -f 286//286 285//285 283//283 -f 286//286 283//283 287//287 -f 287//287 283//283 282//282 -f 284//284 288//288 285//285 -f 285//285 288//288 289//289 -f 285//285 289//289 290//290 -f 291//291 292//292 293//293 -f 293//293 292//292 290//290 -f 293//293 290//290 294//294 -f 294//294 290//290 289//289 -f 291//291 295//295 292//292 -f 292//292 295//295 296//296 -f 292//292 296//296 297//297 -f 298//298 299//299 300//300 -f 300//300 299//299 297//297 -f 300//300 297//297 301//301 -f 301//301 297//297 296//296 -f 298//298 302//302 299//299 -f 299//299 302//302 303//303 -f 299//299 303//303 304//304 -f 305//305 306//306 307//307 -f 307//307 306//306 304//304 -f 307//307 304//304 308//308 -f 308//308 304//304 303//303 -f 305//305 309//309 306//306 -f 306//306 309//309 310//310 -f 306//306 310//310 311//311 -f 312//312 313//313 314//314 -f 314//314 313//313 311//311 -f 314//314 311//311 315//315 -f 315//315 311//311 310//310 -f 312//312 316//316 313//313 -f 313//313 316//316 317//317 -f 313//313 317//317 318//318 -f 317//317 319//319 318//318 -f 318//318 319//319 320//320 -f 318//318 320//320 321//321 -f 320//320 322//322 321//321 -f 321//321 322//322 323//323 -f 321//321 323//323 255//255 -f 255//255 323//323 324//324 -f 255//255 324//324 253//253 -f 325//325 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 331//331 -f 331//331 330//330 332//332 -f 331//331 332//332 333//333 -f 333//333 332//332 334//334 -f 333//333 334//334 335//335 -f 335//335 334//334 336//336 -f 335//335 336//336 337//337 -f 337//337 336//336 338//338 -f 337//337 338//338 339//339 -f 339//339 338//338 340//340 -f 339//339 340//340 341//341 -f 341//341 340//340 342//342 -f 341//341 342//342 343//343 -f 343//343 342//342 344//344 -f 343//343 344//344 345//345 -f 345//345 344//344 346//346 -f 345//345 346//346 347//347 -f 347//347 346//346 348//348 -f 347//347 348//348 349//349 -f 349//349 348//348 350//350 -f 349//349 350//350 351//351 -f 351//351 350//350 352//352 -f 351//351 352//352 353//353 -f 353//353 352//352 354//354 -f 353//353 354//354 355//355 -f 355//355 354//354 356//356 -f 355//355 356//356 357//357 -f 357//357 356//356 358//358 -f 357//357 358//358 359//359 -f 359//359 358//358 360//360 -f 359//359 360//360 361//361 -f 361//361 360//360 362//362 -f 361//361 362//362 363//363 -f 363//363 362//362 364//364 -f 363//363 364//364 365//365 -f 365//365 364//364 366//366 -f 365//365 366//366 367//367 -f 367//367 366//366 368//368 -f 367//367 368//368 369//369 -f 369//369 368//368 370//370 -f 369//369 370//370 371//371 -f 371//371 370//370 372//372 -f 371//371 372//372 373//373 -f 373//373 372//372 374//374 -f 373//373 374//374 375//375 -f 375//375 374//374 376//376 -f 375//375 376//376 377//377 -f 377//377 376//376 378//378 -f 377//377 378//378 379//379 -f 379//379 378//378 380//380 -f 379//379 380//380 381//381 -f 381//381 380//380 382//382 -f 381//381 382//382 383//383 -f 383//383 382//382 384//384 -f 383//383 384//384 385//385 -f 385//385 384//384 325//325 -f 385//385 325//325 327//327 -f 355//355 357//357 386//386 -f 386//386 387//387 355//355 -f 355//355 387//387 388//388 -f 355//355 388//388 353//353 -f 388//388 389//389 353//353 -f 353//353 389//389 390//390 -f 353//353 390//390 351//351 -f 390//390 391//391 351//351 -f 351//351 391//391 392//392 -f 351//351 392//392 349//349 -f 392//392 393//393 349//349 -f 349//349 393//393 394//394 -f 349//349 394//394 347//347 -f 394//394 395//395 347//347 -f 347//347 395//395 396//396 -f 347//347 396//396 345//345 -f 396//396 397//397 345//345 -f 345//345 397//397 398//398 -f 345//345 398//398 343//343 -f 398//398 399//399 343//343 -f 343//343 399//399 400//400 -f 343//343 400//400 341//341 -f 400//400 401//401 341//341 -f 341//341 401//401 402//402 -f 341//341 402//402 339//339 -f 402//402 403//403 339//339 -f 339//339 403//403 404//404 -f 339//339 404//404 337//337 -f 404//404 405//405 337//337 -f 337//337 405//405 406//406 -f 337//337 406//406 335//335 -f 406//406 407//407 335//335 -f 335//335 407//407 408//408 -f 335//335 408//408 333//333 -f 408//408 409//409 333//333 -f 333//333 409//409 410//410 -f 333//333 410//410 331//331 -f 410//410 411//411 331//331 -f 331//331 411//411 412//412 -f 331//331 412//412 329//329 -f 412//412 413//413 329//329 -f 329//329 413//413 414//414 -f 329//329 414//414 327//327 -f 414//414 415//415 327//327 -f 327//327 415//415 416//416 -f 327//327 416//416 385//385 -f 416//416 417//417 385//385 -f 385//385 417//417 418//418 -f 385//385 418//418 383//383 -f 418//418 419//419 383//383 -f 383//383 419//419 420//420 -f 383//383 420//420 381//381 -f 420//420 421//421 381//381 -f 381//381 421//421 422//422 -f 381//381 422//422 379//379 -f 422//422 423//423 379//379 -f 379//379 423//423 424//424 -f 379//379 424//424 377//377 -f 424//424 425//425 377//377 -f 377//377 425//425 426//426 -f 377//377 426//426 375//375 -f 426//426 427//427 375//375 -f 375//375 427//427 428//428 -f 375//375 428//428 373//373 -f 428//428 429//429 373//373 -f 373//373 429//429 430//430 -f 373//373 430//430 371//371 -f 430//430 431//431 371//371 -f 371//371 431//431 432//432 -f 371//371 432//432 369//369 -f 432//432 433//433 369//369 -f 369//369 433//433 434//434 -f 369//369 434//434 367//367 -f 434//434 435//435 367//367 -f 367//367 435//435 436//436 -f 367//367 436//436 365//365 -f 436//436 437//437 365//365 -f 365//365 437//437 438//438 -f 365//365 438//438 363//363 -f 438//438 439//439 363//363 -f 363//363 439//439 440//440 -f 363//363 440//440 361//361 -f 440//440 441//441 361//361 -f 361//361 441//441 442//442 -f 361//361 442//442 359//359 -f 442//442 443//443 359//359 -f 359//359 443//443 444//444 -f 359//359 444//444 357//357 -f 357//357 444//444 445//445 -f 357//357 445//445 386//386 -f 157//157 446//446 158//158 -f 158//158 446//446 447//447 -f 158//158 447//447 159//159 -f 159//159 447//447 448//448 -f 159//159 448//448 160//160 -f 160//160 448//448 449//449 -f 160//160 449//449 105//105 -f 105//105 449//449 450//450 -f 105//105 450//450 104//104 -f 104//104 450//450 451//451 -f 104//104 451//451 153//153 -f 153//153 451//451 452//452 -f 153//153 452//452 154//154 -f 154//154 452//452 453//453 -f 154//154 453//453 155//155 -f 155//155 453//453 454//454 -f 155//155 454//454 156//156 -f 156//156 454//454 455//455 -f 156//156 455//455 152//152 -f 152//152 455//455 456//456 -f 152//152 456//456 10//10 -f 10//10 456//456 457//457 -f 10//10 457//457 209//209 -f 209//209 457//457 458//458 -f 209//209 458//458 210//210 -f 210//210 458//458 459//459 -f 210//210 459//459 211//211 -f 211//211 459//459 460//460 -f 211//211 460//460 212//212 -f 212//212 460//460 461//461 -f 212//212 461//461 213//213 -f 213//213 461//461 462//462 -f 213//213 462//462 208//208 -f 208//208 462//462 463//463 -f 208//208 463//463 148//148 -f 148//148 463//463 464//464 -f 148//148 464//464 204//204 -f 204//204 464//464 465//465 -f 204//204 465//465 205//205 -f 205//205 465//465 466//466 -f 205//205 466//466 206//206 -f 206//206 466//466 467//467 -f 206//206 467//467 207//207 -f 207//207 467//467 468//468 -f 207//207 468//468 203//203 -f 203//203 468//468 469//469 -f 203//203 469//469 202//202 -f 202//202 469//469 470//470 -f 202//202 470//470 199//199 -f 199//199 470//470 471//471 -f 199//199 471//471 142//142 -f 142//142 471//471 472//472 -f 142//142 472//472 141//141 -f 141//141 472//472 473//473 -f 141//141 473//473 195//195 -f 195//195 473//473 474//474 -f 195//195 474//474 196//196 -f 196//196 474//474 475//475 -f 196//196 475//475 197//197 -f 197//197 475//475 476//476 -f 197//197 476//476 198//198 -f 198//198 476//476 477//477 -f 198//198 477//477 191//191 -f 191//191 477//477 478//478 -f 191//191 478//478 192//192 -f 192//192 478//478 479//479 -f 192//192 479//479 193//193 -f 193//193 479//479 480//480 -f 193//193 480//480 194//194 -f 194//194 480//480 481//481 -f 194//194 481//481 190//190 -f 190//190 481//481 482//482 -f 190//190 482//482 189//189 -f 189//189 482//482 483//483 -f 189//189 483//483 183//183 -f 183//183 483//483 484//484 -f 183//183 484//484 184//184 -f 184//184 484//484 485//485 -f 184//184 485//485 181//181 -f 181//181 485//485 486//486 -f 181//181 486//486 176//176 -f 176//176 486//486 487//487 -f 176//176 487//487 1//1 -f 1//1 487//487 488//488 -f 1//1 488//488 2//2 -f 2//2 488//488 489//489 -f 2//2 489//489 172//172 -f 172//172 489//489 490//490 -f 172//172 490//490 173//173 -f 173//173 490//490 491//491 -f 173//173 491//491 174//174 -f 174//174 491//491 492//492 -f 174//174 492//492 175//175 -f 175//175 492//492 493//493 -f 175//175 493//493 169//169 -f 169//169 493//493 494//494 -f 169//169 494//494 170//170 -f 170//170 494//494 495//495 -f 170//170 495//495 171//171 -f 171//171 495//495 496//496 -f 171//171 496//496 166//166 -f 166//166 496//496 497//497 -f 166//166 497//497 167//167 -f 167//167 497//497 498//498 -f 167//167 498//498 168//168 -f 168//168 498//498 499//499 -f 168//168 499//499 162//162 -f 162//162 499//499 500//500 -f 162//162 500//500 163//163 -f 163//163 500//500 501//501 -f 163//163 501//501 164//164 -f 164//164 501//501 502//502 -f 164//164 502//502 165//165 -f 165//165 502//502 503//503 -f 165//165 503//503 161//161 -f 161//161 503//503 504//504 -f 161//161 504//504 7//7 -f 7//7 504//504 505//505 -f 7//7 505//505 157//157 -f 157//157 505//505 446//446 -f 505//505 444//444 446//446 -f 446//446 444//444 443//443 -f 446//446 443//443 447//447 -f 447//447 443//443 442//442 -f 447//447 442//442 448//448 -f 448//448 442//442 441//441 -f 448//448 441//441 449//449 -f 449//449 441//441 440//440 -f 449//449 440//440 450//450 -f 450//450 440//440 439//439 -f 450//450 439//439 451//451 -f 451//451 439//439 438//438 -f 451//451 438//438 452//452 -f 452//452 438//438 437//437 -f 452//452 437//437 453//453 -f 453//453 437//437 436//436 -f 453//453 436//436 454//454 -f 454//454 436//436 435//435 -f 454//454 435//435 455//455 -f 455//455 435//435 434//434 -f 455//455 434//434 456//456 -f 456//456 434//434 433//433 -f 456//456 433//433 457//457 -f 457//457 433//433 432//432 -f 457//457 432//432 458//458 -f 458//458 432//432 431//431 -f 458//458 431//431 459//459 -f 459//459 431//431 430//430 -f 459//459 430//430 460//460 -f 460//460 430//430 429//429 -f 460//460 429//429 461//461 -f 461//461 429//429 428//428 -f 461//461 428//428 462//462 -f 462//462 428//428 427//427 -f 462//462 427//427 463//463 -f 463//463 427//427 426//426 -f 463//463 426//426 464//464 -f 464//464 426//426 425//425 -f 464//464 425//425 465//465 -f 465//465 425//425 424//424 -f 465//465 424//424 466//466 -f 466//466 424//424 423//423 -f 466//466 423//423 467//467 -f 467//467 423//423 422//422 -f 467//467 422//422 468//468 -f 468//468 422//422 421//421 -f 468//468 421//421 469//469 -f 469//469 421//421 420//420 -f 469//469 420//420 470//470 -f 470//470 420//420 419//419 -f 470//470 419//419 471//471 -f 471//471 419//419 418//418 -f 471//471 418//418 472//472 -f 472//472 418//418 417//417 -f 472//472 417//417 473//473 -f 473//473 417//417 416//416 -f 473//473 416//416 474//474 -f 474//474 416//416 415//415 -f 474//474 415//415 475//475 -f 475//475 415//415 414//414 -f 475//475 414//414 476//476 -f 476//476 414//414 413//413 -f 476//476 413//413 477//477 -f 477//477 413//413 412//412 -f 477//477 412//412 478//478 -f 478//478 412//412 411//411 -f 478//478 411//411 479//479 -f 479//479 411//411 410//410 -f 479//479 410//410 480//480 -f 480//480 410//410 409//409 -f 480//480 409//409 481//481 -f 481//481 409//409 408//408 -f 481//481 408//408 482//482 -f 482//482 408//408 407//407 -f 482//482 407//407 483//483 -f 483//483 407//407 406//406 -f 483//483 406//406 484//484 -f 484//484 406//406 405//405 -f 484//484 405//405 485//485 -f 485//485 405//405 404//404 -f 485//485 404//404 486//486 -f 486//486 404//404 403//403 -f 486//486 403//403 487//487 -f 487//487 403//403 402//402 -f 487//487 402//402 488//488 -f 488//488 402//402 401//401 -f 488//488 401//401 489//489 -f 489//489 401//401 400//400 -f 489//489 400//400 490//490 -f 490//490 400//400 399//399 -f 490//490 399//399 491//491 -f 491//491 399//399 398//398 -f 491//491 398//398 492//492 -f 492//492 398//398 397//397 -f 492//492 397//397 493//493 -f 493//493 397//397 396//396 -f 493//493 396//396 494//494 -f 494//494 396//396 395//395 -f 494//494 395//395 495//495 -f 495//495 395//395 394//394 -f 495//495 394//394 496//496 -f 496//496 394//394 393//393 -f 496//496 393//393 497//497 -f 497//497 393//393 392//392 -f 497//497 392//392 498//498 -f 498//498 392//392 391//391 -f 498//498 391//391 499//499 -f 499//499 391//391 390//390 -f 499//499 390//390 500//500 -f 500//500 390//390 389//389 -f 500//500 389//389 501//501 -f 501//501 389//389 388//388 -f 501//501 388//388 502//502 -f 502//502 388//388 387//387 -f 502//502 387//387 503//503 -f 503//503 387//387 386//386 -f 503//503 386//386 504//504 -f 504//504 386//386 445//445 -f 504//504 445//445 505//505 -f 505//505 445//445 444//444 -f 318//318 321//321 506//506 -f 506//506 321//321 255//255 -f 506//506 255//255 254//254 -f 306//306 311//311 506//506 -f 506//506 311//311 313//313 -f 506//506 313//313 318//318 -f 297//297 299//299 506//506 -f 506//506 299//299 304//304 -f 506//506 304//304 306//306 -f 285//285 290//290 506//506 -f 506//506 290//290 292//292 -f 506//506 292//292 297//297 -f 274//274 278//278 506//506 -f 506//506 278//278 283//283 -f 506//506 283//283 285//285 -f 265//265 267//267 506//506 -f 506//506 267//267 272//272 -f 506//506 272//272 274//274 -f 254//254 258//258 506//506 -f 506//506 258//258 260//260 -f 506//506 260//260 265//265 -f 319//319 317//317 507//507 -f 507//507 317//317 508//508 -f 509//509 510//510 310//310 -f 511//511 512//512 303//303 -f 513//513 514//514 296//296 -f 515//515 516//516 289//289 -f 517//517 518//518 282//282 -f 519//519 520//520 276//276 -f 521//521 522//522 269//269 -f 364//364 362//362 523//523 -f 354//354 352//352 524//524 -f 364//364 525//525 366//366 -f 366//366 525//525 526//526 -f 366//366 526//526 368//368 -f 368//368 526//526 527//527 -f 368//368 527//527 370//370 -f 370//370 527//527 528//528 -f 370//370 528//528 372//372 -f 372//372 528//528 529//529 -f 372//372 529//529 374//374 -f 374//374 529//529 530//530 -f 374//374 530//530 376//376 -f 376//376 530//530 531//531 -f 376//376 531//531 378//378 -f 378//378 531//531 532//532 -f 378//378 532//532 380//380 -f 380//380 532//532 533//533 -f 380//380 533//533 382//382 -f 382//382 533//533 534//534 -f 382//382 534//534 384//384 -f 384//384 534//534 535//535 -f 384//384 535//535 325//325 -f 325//325 535//535 536//536 -f 325//325 536//536 326//326 -f 326//326 536//536 537//537 -f 326//326 537//537 328//328 -f 328//328 537//537 538//538 -f 328//328 538//538 330//330 -f 330//330 538//538 539//539 -f 330//330 539//539 332//332 -f 332//332 539//539 540//540 -f 332//332 540//540 334//334 -f 334//334 540//540 541//541 -f 334//334 541//541 336//336 -f 336//336 541//541 542//542 -f 336//336 542//542 338//338 -f 338//338 542//542 543//543 -f 338//338 543//543 340//340 -f 340//340 543//543 544//544 -f 340//340 544//544 342//342 -f 342//342 544//544 545//545 -f 342//342 545//545 344//344 -f 344//344 545//545 546//546 -f 344//344 546//546 346//346 -f 346//346 546//546 547//547 -f 346//346 547//547 348//348 -f 348//348 547//547 548//548 -f 348//348 548//548 350//350 -f 350//350 548//548 549//549 -f 350//350 549//549 352//352 -f 356//356 550//550 358//358 -f 358//358 550//550 551//551 -f 358//358 551//551 360//360 -f 360//360 551//551 552//552 -f 360//360 552//552 362//362 -f 525//525 507//507 526//526 -f 526//526 507//507 508//508 -f 526//526 508//508 527//527 -f 527//527 508//508 553//553 -f 527//527 553//553 528//528 -f 528//528 553//553 510//510 -f 528//528 510//510 529//529 -f 529//529 510//510 509//509 -f 529//529 509//509 530//530 -f 530//530 509//509 554//554 -f 530//530 554//554 531//531 -f 531//531 554//554 512//512 -f 531//531 512//512 532//532 -f 532//532 512//512 511//511 -f 532//532 511//511 533//533 -f 533//533 511//511 555//555 -f 533//533 555//555 534//534 -f 534//534 555//555 514//514 -f 534//534 514//514 535//535 -f 535//535 514//514 513//513 -f 535//535 513//513 536//536 -f 536//536 513//513 556//556 -f 536//536 556//556 537//537 -f 537//537 556//556 516//516 -f 537//537 516//516 538//538 -f 538//538 516//516 515//515 -f 538//538 515//515 539//539 -f 539//539 515//515 557//557 -f 539//539 557//557 540//540 -f 540//540 557//557 518//518 -f 540//540 518//518 541//541 -f 541//541 518//518 517//517 -f 541//541 517//517 542//542 -f 542//542 517//517 558//558 -f 542//542 558//558 543//543 -f 543//543 558//558 520//520 -f 543//543 520//520 544//544 -f 544//544 520//520 519//519 -f 544//544 519//519 545//545 -f 545//545 519//519 559//559 -f 545//545 559//559 546//546 -f 546//546 559//559 522//522 -f 546//546 522//522 547//547 -f 547//547 522//522 521//521 -f 547//547 521//521 548//548 -f 548//548 521//521 560//560 -f 548//548 560//560 549//549 -f 549//549 560//560 561//561 -f 550//550 562//562 551//551 -f 551//551 562//562 563//563 -f 551//551 563//563 552//552 -f 552//552 563//563 564//564 -f 257//257 562//562 565//565 -f 565//565 562//562 550//550 -f 565//565 550//550 566//566 -f 566//566 550//550 356//356 -f 566//566 356//356 354//354 -f 567//567 261//261 259//259 -f 354//354 524//524 566//566 -f 566//566 524//524 567//567 -f 566//566 567//567 565//565 -f 565//565 567//567 259//259 -f 565//565 259//259 257//257 -f 352//352 549//549 524//524 -f 524//524 549//549 561//561 -f 524//524 561//561 567//567 -f 567//567 561//561 262//262 -f 567//567 262//262 261//261 -f 269//269 268//268 521//521 -f 521//521 268//268 266//266 -f 521//521 266//266 560//560 -f 560//560 266//266 264//264 -f 560//560 264//264 561//561 -f 561//561 264//264 263//263 -f 561//561 263//263 262//262 -f 276//276 275//275 519//519 -f 519//519 275//275 273//273 -f 519//519 273//273 559//559 -f 559//559 273//273 271//271 -f 559//559 271//271 522//522 -f 522//522 271//271 270//270 -f 522//522 270//270 269//269 -f 282//282 281//281 517//517 -f 517//517 281//281 277//277 -f 517//517 277//277 558//558 -f 558//558 277//277 279//279 -f 558//558 279//279 520//520 -f 520//520 279//279 280//280 -f 520//520 280//280 276//276 -f 289//289 288//288 515//515 -f 515//515 288//288 284//284 -f 515//515 284//284 557//557 -f 557//557 284//284 286//286 -f 557//557 286//286 518//518 -f 518//518 286//286 287//287 -f 518//518 287//287 282//282 -f 296//296 295//295 513//513 -f 513//513 295//295 291//291 -f 513//513 291//291 556//556 -f 556//556 291//291 293//293 -f 556//556 293//293 516//516 -f 516//516 293//293 294//294 -f 516//516 294//294 289//289 -f 303//303 302//302 511//511 -f 511//511 302//302 298//298 -f 511//511 298//298 555//555 -f 555//555 298//298 300//300 -f 555//555 300//300 514//514 -f 514//514 300//300 301//301 -f 514//514 301//301 296//296 -f 310//310 309//309 509//509 -f 509//509 309//309 305//305 -f 509//509 305//305 554//554 -f 554//554 305//305 307//307 -f 554//554 307//307 512//512 -f 512//512 307//307 308//308 -f 512//512 308//308 303//303 -f 317//317 316//316 508//508 -f 508//508 316//316 312//312 -f 508//508 312//312 553//553 -f 553//553 312//312 314//314 -f 553//553 314//314 510//510 -f 510//510 314//314 315//315 -f 510//510 315//315 310//310 -f 364//364 523//523 525//525 -f 525//525 523//523 568//568 -f 525//525 568//568 507//507 -f 507//507 568//568 320//320 -f 507//507 320//320 319//319 -f 362//362 552//552 523//523 -f 523//523 552//552 564//564 -f 523//523 564//564 568//568 -f 568//568 564//564 322//322 -f 568//568 322//322 320//320 -f 257//257 256//256 562//562 -f 562//562 256//256 253//253 -f 562//562 253//253 563//563 -f 563//563 253//253 324//324 -f 563//563 324//324 564//564 -f 564//564 324//324 323//323 -f 564//564 323//323 322//322 -f 252//252 251//251 569//569 -f 569//569 251//251 250//250 -f 222//222 224//224 223//223 -f 225//225 227//227 226//226 -f 42//42 236//236 84//84 -f 84//84 236//236 220//220 -f 84//84 220//220 83//83 -f 83//83 220//220 81//81 -f 239//239 248//248 570//570 -f 570//570 248//248 240//240 -f 250//250 249//249 571//571 -f 571//571 249//249 228//228 -f 100//100 72//72 243//243 -f 243//243 72//72 74//74 -f 243//243 74//74 219//219 -f 219//219 74//74 75//75 -f 219//219 75//75 76//76 -f 65//65 64//64 214//214 -f 214//214 64//64 85//85 -f 214//214 85//85 252//252 -f 252//252 85//85 86//86 -f 252//252 86//86 87//87 -f 17//17 37//37 217//217 -f 17//17 217//217 18//18 -f 18//18 217//217 231//231 -f 18//18 231//231 69//69 -f 240//240 242//242 572//572 -f 252//252 569//569 572//572 -f 250//250 571//571 572//572 -f 228//228 230//230 572//572 -f 572//572 238//238 239//239 -f 570//570 572//572 239//239 -f 236//236 238//238 572//572 -f 572//572 234//234 220//220 -f 235//235 234//234 572//572 -f 225//225 235//235 572//572 -f 220//220 236//236 572//572 -f 572//572 232//232 227//227 -f 233//233 232//232 572//572 -f 217//217 233//233 572//572 -f 227//227 225//225 572//572 -f 231//231 217//217 572//572 -f 230//230 231//231 572//572 -f 571//571 228//228 572//572 -f 569//569 250//250 572//572 -f 572//572 246//246 214//214 -f 247//247 246//246 572//572 -f 222//222 247//247 572//572 -f 214//214 252//252 572//572 -f 572//572 244//244 224//224 -f 245//245 244//244 572//572 -f 219//219 245//245 572//572 -f 224//224 222//222 572//572 -f 243//243 219//219 572//572 -f 242//242 243//243 572//572 -f 570//570 240//240 572//572 -f 573//573 574//574 575//575 -f 575//575 576//576 573//573 -f 573//573 576//576 577//577 -f 573//573 577//577 578//578 -f 579//579 580//580 581//581 -f 581//581 582//582 579//579 -f 579//579 582//582 583//583 -f 579//579 583//583 584//584 -f 585//585 586//586 587//587 -f 587//587 588//588 585//585 -f 585//585 588//588 589//589 -f 585//585 589//589 590//590 -f 591//591 592//592 593//593 -f 594//594 595//595 596//596 -f 596//596 595//595 597//597 -f 596//596 597//597 598//598 -f 598//598 597//597 599//599 -f 598//598 599//599 600//600 -f 594//594 596//596 601//601 -f 601//601 596//596 602//602 -f 601//601 602//602 603//603 -f 603//603 602//602 604//604 -f 603//603 604//604 605//605 -f 605//605 604//604 606//606 -f 606//606 604//604 607//607 -f 606//606 607//607 608//608 -f 593//593 592//592 607//607 -f 607//607 592//592 609//609 -f 607//607 609//609 608//608 -f 591//591 593//593 610//610 -f 610//610 593//593 611//611 -f 610//610 611//611 612//612 -f 611//611 613//613 612//612 -f 612//612 613//613 614//614 -f 612//612 614//614 615//615 -f 615//615 614//614 616//616 -f 615//615 616//616 617//617 -f 617//617 616//616 618//618 -f 618//618 616//616 619//619 -f 618//618 619//619 620//620 -f 620//620 619//619 621//621 -f 620//620 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 623//623 625//625 624//624 -f 624//624 625//625 626//626 -f 624//624 626//626 627//627 -f 627//627 626//626 628//628 -f 627//627 628//628 629//629 -f 629//629 628//628 630//630 -f 629//629 630//630 631//631 -f 631//631 630//630 632//632 -f 631//631 632//632 633//633 -f 633//633 632//632 634//634 -f 633//633 634//634 635//635 -f 635//635 634//634 636//636 -f 635//635 636//636 637//637 -f 637//637 636//636 638//638 -f 637//637 638//638 639//639 -f 639//639 638//638 640//640 -f 639//639 640//640 641//641 -f 641//641 640//640 642//642 -f 641//641 642//642 643//643 -f 643//643 642//642 644//644 -f 643//643 644//644 645//645 -f 645//645 644//644 646//646 -f 645//645 646//646 647//647 -f 647//647 646//646 648//648 -f 647//647 648//648 649//649 -f 649//649 648//648 650//650 -f 649//649 650//650 651//651 -f 651//651 650//650 652//652 -f 651//651 652//652 653//653 -f 653//653 652//652 654//654 -f 653//653 654//654 655//655 -f 654//654 656//656 655//655 -f 655//655 656//656 657//657 -f 655//655 657//657 658//658 -f 658//658 657//657 659//659 -f 658//658 659//659 660//660 -f 660//660 659//659 661//661 -f 660//660 661//661 662//662 -f 662//662 661//661 663//663 -f 662//662 663//663 664//664 -f 664//664 663//663 665//665 -f 665//665 663//663 666//666 -f 665//665 666//666 667//667 -f 667//667 666//666 668//668 -f 667//667 668//668 669//669 -f 669//669 668//668 670//670 -f 669//669 670//670 671//671 -f 671//671 670//670 672//672 -f 671//671 672//672 673//673 -f 673//673 672//672 674//674 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 677//677 -f 677//677 676//676 678//678 -f 677//677 678//678 679//679 -f 679//679 678//678 680//680 -f 679//679 680//680 681//681 -f 681//681 680//680 682//682 -f 681//681 682//682 683//683 -f 683//683 682//682 684//684 -f 683//683 684//684 685//685 -f 684//684 686//686 685//685 -f 685//685 686//686 687//687 -f 685//685 687//687 688//688 -f 688//688 687//687 689//689 -f 688//688 689//689 690//690 -f 690//690 689//689 691//691 -f 690//690 691//691 692//692 -f 692//692 691//691 693//693 -f 692//692 693//693 694//694 -f 694//694 693//693 695//695 -f 695//695 693//693 696//696 -f 695//695 696//696 697//697 -f 697//697 696//696 698//698 -f 697//697 698//698 699//699 -f 699//699 698//698 700//700 -f 699//699 700//700 701//701 -f 701//701 700//700 702//702 -f 701//701 702//702 703//703 -f 703//703 702//702 704//704 -f 703//703 704//704 705//705 -f 705//705 704//704 706//706 -f 705//705 706//706 707//707 -f 707//707 706//706 708//708 -f 707//707 708//708 709//709 -f 709//709 708//708 710//710 -f 709//709 710//710 711//711 -f 711//711 710//710 712//712 -f 711//711 712//712 713//713 -f 713//713 712//712 714//714 -f 713//713 714//714 715//715 -f 714//714 716//716 715//715 -f 715//715 716//716 717//717 -f 715//715 717//717 718//718 -f 718//718 717//717 719//719 -f 718//718 719//719 720//720 -f 720//720 719//719 721//721 -f 720//720 721//721 722//722 -f 722//722 721//721 723//723 -f 724//724 725//725 726//726 -f 726//726 725//725 727//727 -f 726//726 727//727 728//728 -f 728//728 727//727 729//729 -f 728//728 729//729 730//730 -f 730//730 729//729 731//731 -f 730//730 731//731 732//732 -f 732//732 731//731 733//733 -f 732//732 733//733 734//734 -f 734//734 733//733 735//735 -f 734//734 735//735 736//736 -f 736//736 735//735 737//737 -f 736//736 737//737 738//738 -f 738//738 737//737 739//739 -f 738//738 739//739 723//723 -f 723//723 739//739 740//740 -f 723//723 740//740 722//722 -f 741//741 742//742 743//743 -f 741//741 743//743 744//744 -f 744//744 743//743 745//745 -f 744//744 745//745 746//746 -f 746//746 745//745 747//747 -f 746//746 747//747 748//748 -f 748//748 747//747 749//749 -f 748//748 749//749 750//750 -f 750//750 749//749 751//751 -f 750//750 751//751 752//752 -f 752//752 751//751 753//753 -f 752//752 753//753 754//754 -f 754//754 753//753 755//755 -f 754//754 755//755 756//756 -f 756//756 755//755 757//757 -f 756//756 757//757 758//758 -f 758//758 757//757 759//759 -f 758//758 759//759 760//760 -f 760//760 759//759 761//761 -f 760//760 761//761 762//762 -f 762//762 761//761 763//763 -f 762//762 763//763 764//764 -f 764//764 763//763 765//765 -f 764//764 765//765 766//766 -f 766//766 765//765 767//767 -f 766//766 767//767 768//768 -f 768//768 767//767 769//769 -f 768//768 769//769 770//770 -f 770//770 769//769 771//771 -f 770//770 771//771 724//724 -f 724//724 771//771 772//772 -f 724//724 772//772 725//725 -f 742//742 741//741 773//773 -f 773//773 741//741 774//774 -f 773//773 774//774 775//775 -f 775//775 774//774 776//776 -f 775//775 776//776 777//777 -f 777//777 776//776 778//778 -f 777//777 778//778 779//779 -f 779//779 778//778 780//780 -f 779//779 780//780 781//781 -f 781//781 780//780 782//782 -f 781//781 782//782 783//783 -f 783//783 782//782 784//784 -f 783//783 784//784 785//785 -f 785//785 784//784 786//786 -f 785//785 786//786 787//787 -f 787//787 786//786 788//788 -f 787//787 788//788 789//789 -f 789//789 788//788 790//790 -f 789//789 790//790 791//791 -f 791//791 790//790 792//792 -f 791//791 792//792 793//793 -f 792//792 794//794 793//793 -f 793//793 794//794 795//795 -f 793//793 795//795 796//796 -f 796//796 795//795 797//797 -f 796//796 797//797 798//798 -f 798//798 797//797 799//799 -f 798//798 799//799 800//800 -f 800//800 799//799 801//801 -f 800//800 801//801 802//802 -f 802//802 801//801 803//803 -f 803//803 801//801 804//804 -f 803//803 804//804 805//805 -f 805//805 804//804 806//806 -f 805//805 806//806 807//807 -f 807//807 806//806 808//808 -f 807//807 808//808 809//809 -f 809//809 808//808 810//810 -f 809//809 810//810 811//811 -f 811//811 810//810 812//812 -f 811//811 812//812 813//813 -f 813//813 812//812 814//814 -f 813//813 814//814 815//815 -f 815//815 814//814 816//816 -f 815//815 816//816 817//817 -f 817//817 816//816 818//818 -f 817//817 818//818 819//819 -f 819//819 818//818 820//820 -f 819//819 820//820 821//821 -f 821//821 820//820 822//822 -f 821//821 822//822 823//823 -f 822//822 824//824 823//823 -f 823//823 824//824 825//825 -f 823//823 825//825 826//826 -f 826//826 825//825 827//827 -f 826//826 827//827 828//828 -f 828//828 827//827 829//829 -f 828//828 829//829 830//830 -f 830//830 829//829 831//831 -f 830//830 831//831 832//832 -f 832//832 831//831 833//833 -f 832//832 833//833 834//834 -f 834//834 833//833 835//835 -f 834//834 835//835 836//836 -f 836//836 835//835 837//837 -f 836//836 837//837 838//838 -f 838//838 837//837 839//839 -f 838//838 839//839 840//840 -f 840//840 839//839 841//841 -f 840//840 841//841 842//842 -f 842//842 841//841 843//843 -f 842//842 843//843 844//844 -f 844//844 843//843 845//845 -f 844//844 845//845 846//846 -f 846//846 845//845 847//847 -f 846//846 847//847 848//848 -f 848//848 847//847 849//849 -f 848//848 849//849 850//850 -f 850//850 849//849 851//851 -f 851//851 849//849 852//852 -f 851//851 852//852 853//853 -f 852//852 854//854 853//853 -f 853//853 854//854 855//855 -f 853//853 855//855 856//856 -f 856//856 855//855 857//857 -f 856//856 857//857 858//858 -f 858//858 857//857 859//859 -f 858//858 859//859 860//860 -f 860//860 859//859 861//861 -f 860//860 861//861 862//862 -f 862//862 861//861 863//863 -f 862//862 863//863 864//864 -f 864//864 863//863 865//865 -f 864//864 865//865 866//866 -f 866//866 865//865 867//867 -f 866//866 867//867 868//868 -f 868//868 867//867 869//869 -f 868//868 869//869 870//870 -f 870//870 869//869 871//871 -f 870//870 871//871 872//872 -f 872//872 871//871 873//873 -f 872//872 873//873 874//874 -f 874//874 873//873 875//875 -f 874//874 875//875 876//876 -f 876//876 875//875 877//877 -f 876//876 877//877 878//878 -f 878//878 877//877 879//879 -f 878//878 879//879 880//880 -f 880//880 879//879 881//881 -f 881//881 879//879 882//882 -f 881//881 882//882 883//883 -f 882//882 884//884 883//883 -f 883//883 884//884 885//885 -f 883//883 885//885 886//886 -f 886//886 885//885 887//887 -f 886//886 887//887 888//888 -f 888//888 887//887 889//889 -f 888//888 889//889 890//890 -f 890//890 889//889 891//891 -f 890//890 891//891 892//892 -f 892//892 891//891 893//893 -f 892//892 893//893 894//894 -f 894//894 893//893 895//895 -f 894//894 895//895 896//896 -f 896//896 895//895 897//897 -f 896//896 897//897 898//898 -f 898//898 897//897 899//899 -f 898//898 899//899 900//900 -f 900//900 899//899 901//901 -f 900//900 901//901 902//902 -f 902//902 901//901 903//903 -f 902//902 903//903 904//904 -f 904//904 903//903 905//905 -f 904//904 905//905 906//906 -f 906//906 905//905 907//907 -f 907//907 905//905 908//908 -f 907//907 908//908 909//909 -f 909//909 908//908 910//910 -f 909//909 910//910 911//911 -f 911//911 910//910 912//912 -f 911//911 912//912 913//913 -f 912//912 914//914 913//913 -f 913//913 914//914 915//915 -f 913//913 915//915 916//916 -f 916//916 915//915 917//917 -f 916//916 917//917 918//918 -f 918//918 917//917 919//919 -f 918//918 919//919 920//920 -f 920//920 919//919 921//921 -f 922//922 923//923 924//924 -f 924//924 923//923 925//925 -f 924//924 925//925 926//926 -f 926//926 925//925 927//927 -f 926//926 927//927 928//928 -f 928//928 927//927 929//929 -f 928//928 929//929 921//921 -f 921//921 929//929 930//930 -f 921//921 930//930 920//920 -f 924//924 931//931 922//922 -f 922//922 931//931 932//932 -f 922//922 932//932 933//933 -f 933//933 932//932 934//934 -f 933//933 934//934 935//935 -f 935//935 934//934 936//936 -f 935//935 936//936 937//937 -f 937//937 936//936 938//938 -f 937//937 938//938 939//939 -f 939//939 938//938 940//940 -f 938//938 941//941 940//940 -f 940//940 941//941 942//942 -f 940//940 942//942 943//943 -f 943//943 942//942 944//944 -f 943//943 944//944 945//945 -f 945//945 944//944 946//946 -f 945//945 946//946 947//947 -f 946//946 948//948 947//947 -f 947//947 948//948 949//949 -f 947//947 949//949 950//950 -f 950//950 949//949 951//951 -f 950//950 951//951 952//952 -f 952//952 951//951 953//953 -f 952//952 953//953 954//954 -f 954//954 953//953 955//955 -f 956//956 957//957 958//958 -f 956//956 958//958 959//959 -f 959//959 958//958 960//960 -f 959//959 960//960 955//955 -f 955//955 960//960 961//961 -f 955//955 961//961 954//954 -f 957//957 956//956 962//962 -f 962//962 956//956 963//963 -f 962//962 963//963 964//964 -f 963//963 965//965 964//964 -f 964//964 965//965 966//966 -f 964//964 966//966 967//967 -f 967//967 966//966 968//968 -f 967//967 968//968 969//969 -f 969//969 968//968 970//970 -f 969//969 970//970 971//971 -f 971//971 970//970 972//972 -f 971//971 972//972 973//973 -f 972//972 974//974 973//973 -f 973//973 974//974 975//975 -f 973//973 975//975 976//976 -f 976//976 975//975 977//977 -f 976//976 977//977 978//978 -f 978//978 977//977 979//979 -f 978//978 979//979 980//980 -f 980//980 979//979 981//981 -f 982//982 983//983 984//984 -f 984//984 983//983 985//985 -f 984//984 985//985 986//986 -f 986//986 985//985 987//987 -f 986//986 987//987 988//988 -f 988//988 987//987 989//989 -f 988//988 989//989 981//981 -f 981//981 989//989 990//990 -f 981//981 990//990 980//980 -f 984//984 991//991 982//982 -f 982//982 991//991 992//992 -f 982//982 992//992 993//993 -f 993//993 992//992 994//994 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 997//997 996//996 998//998 -f 997//997 998//998 999//999 -f 999//999 998//998 1000//1000 -f 998//998 1001//1001 1000//1000 -f 1000//1000 1001//1001 1002//1002 -f 1000//1000 1002//1002 1003//1003 -f 1003//1003 1002//1002 1004//1004 -f 1003//1003 1004//1004 1005//1005 -f 1005//1005 1004//1004 1006//1006 -f 1005//1005 1006//1006 1007//1007 -f 1007//1007 1006//1006 1008//1008 -f 1006//1006 1009//1009 1008//1008 -f 1008//1008 1009//1009 1010//1010 -f 1008//1008 1010//1010 1011//1011 -f 1011//1011 1010//1010 1012//1012 -f 1011//1011 1012//1012 1013//1013 -f 1013//1013 1012//1012 1014//1014 -f 1013//1013 1014//1014 1015//1015 -f 1015//1015 1014//1014 1016//1016 -f 1015//1015 1016//1016 1017//1017 -f 1017//1017 1016//1016 1018//1018 -f 1016//1016 1019//1019 1018//1018 -f 1018//1018 1019//1019 1020//1020 -f 1018//1018 1020//1020 1021//1021 -f 1021//1021 1020//1020 1022//1022 -f 1021//1021 1022//1022 1023//1023 -f 1023//1023 1022//1022 1024//1024 -f 1023//1023 1024//1024 1025//1025 -f 1024//1024 1026//1026 1025//1025 -f 1025//1025 1026//1026 1027//1027 -f 1025//1025 1027//1027 1028//1028 -f 1028//1028 1027//1027 1029//1029 -f 1028//1028 1029//1029 1030//1030 -f 1030//1030 1029//1029 1031//1031 -f 1030//1030 1031//1031 1032//1032 -f 1032//1032 1031//1031 1033//1033 -f 1034//1034 1035//1035 1036//1036 -f 1034//1034 1036//1036 1037//1037 -f 1037//1037 1036//1036 1038//1038 -f 1037//1037 1038//1038 1033//1033 -f 1033//1033 1038//1038 1039//1039 -f 1033//1033 1039//1039 1032//1032 -f 1035//1035 1034//1034 1040//1040 -f 1040//1040 1034//1034 1041//1041 -f 1040//1040 1041//1041 1042//1042 -f 1042//1042 1041//1041 1043//1043 -f 1042//1042 1043//1043 1044//1044 -f 1044//1044 1043//1043 1045//1045 -f 1044//1044 1045//1045 1046//1046 -f 1045//1045 1047//1047 1046//1046 -f 1046//1046 1047//1047 1048//1048 -f 1046//1046 1048//1048 1049//1049 -f 1049//1049 1048//1048 1050//1050 -f 1049//1049 1050//1050 1051//1051 -f 1050//1050 1052//1052 1051//1051 -f 1051//1051 1052//1052 1053//1053 -f 1051//1051 1053//1053 1054//1054 -f 1054//1054 1053//1053 1055//1055 -f 1054//1054 1055//1055 1056//1056 -f 1056//1056 1055//1055 1057//1057 -f 1056//1056 1057//1057 1058//1058 -f 1058//1058 1057//1057 1059//1059 -f 1060//1060 1061//1061 1062//1062 -f 1062//1062 1061//1061 1063//1063 -f 1062//1062 1063//1063 1064//1064 -f 1064//1064 1063//1063 1065//1065 -f 1064//1064 1065//1065 1066//1066 -f 1066//1066 1065//1065 1067//1067 -f 1066//1066 1067//1067 1059//1059 -f 1059//1059 1067//1067 1068//1068 -f 1059//1059 1068//1068 1058//1058 -f 1062//1062 1069//1069 1060//1060 -f 1060//1060 1069//1069 1070//1070 -f 1060//1060 1070//1070 1071//1071 -f 1071//1071 1070//1070 1072//1072 -f 1071//1071 1072//1072 1073//1073 -f 1073//1073 1072//1072 1074//1074 -f 1073//1073 1074//1074 1075//1075 -f 1075//1075 1074//1074 1076//1076 -f 1075//1075 1076//1076 1077//1077 -f 1077//1077 1076//1076 1078//1078 -f 1076//1076 1079//1079 1078//1078 -f 1078//1078 1079//1079 1080//1080 -f 1078//1078 1080//1080 1081//1081 -f 1081//1081 1080//1080 1082//1082 -f 1081//1081 1082//1082 1083//1083 -f 1083//1083 1082//1082 1084//1084 -f 1083//1083 1084//1084 1085//1085 -f 1084//1084 1086//1086 1085//1085 -f 1085//1085 1086//1086 1087//1087 -f 1085//1085 1087//1087 1088//1088 -f 1088//1088 1087//1087 1089//1089 -f 1088//1088 1089//1089 1090//1090 -f 1090//1090 1089//1089 1091//1091 -f 1090//1090 1091//1091 1092//1092 -f 1092//1092 1091//1091 1093//1093 -f 1094//1094 1095//1095 1096//1096 -f 1094//1094 1096//1096 1097//1097 -f 1097//1097 1096//1096 1098//1098 -f 1097//1097 1098//1098 1093//1093 -f 1093//1093 1098//1098 1099//1099 -f 1093//1093 1099//1099 1092//1092 -f 1095//1095 1094//1094 1100//1100 -f 1100//1100 1094//1094 1101//1101 -f 1100//1100 1101//1101 1102//1102 -f 1102//1102 1101//1101 1103//1103 -f 1102//1102 1103//1103 1104//1104 -f 1104//1104 1103//1103 1105//1105 -f 1104//1104 1105//1105 1106//1106 -f 1107//1107 1108//1108 1109//1109 -f 1109//1109 1108//1108 1110//1110 -f 1109//1109 1110//1110 1111//1111 -f 1111//1111 1110//1110 1112//1112 -f 1111//1111 1112//1112 1113//1113 -f 1113//1113 1112//1112 1106//1106 -f 1113//1113 1106//1106 1114//1114 -f 1114//1114 1106//1106 1105//1105 -f 1115//1115 1116//1116 1117//1117 -f 1117//1117 1116//1116 1118//1118 -f 1118//1118 1116//1116 1119//1119 -f 1119//1119 1116//1116 1120//1120 -f 1119//1119 1120//1120 1121//1121 -f 1122//1122 1123//1123 1124//1124 -f 1124//1124 1123//1123 1125//1125 -f 1124//1124 1125//1125 1120//1120 -f 1120//1120 1125//1125 1126//1126 -f 1120//1120 1126//1126 1121//1121 -f 1127//1127 1128//1128 1122//1122 -f 1122//1122 1128//1128 1129//1129 -f 1122//1122 1129//1129 1123//1123 -f 1130//1130 1131//1131 1132//1132 -f 1132//1132 1131//1131 1133//1133 -f 1132//1132 1133//1133 1127//1127 -f 1127//1127 1133//1133 1134//1134 -f 1127//1127 1134//1134 1128//1128 -f 1130//1130 1132//1132 1135//1135 -f 1135//1135 1132//1132 1136//1136 -f 1135//1135 1136//1136 1137//1137 -f 1137//1137 1136//1136 1138//1138 -f 1137//1137 1138//1138 1139//1139 -f 1139//1139 1138//1138 1140//1140 -f 1139//1139 1140//1140 1141//1141 -f 1141//1141 1140//1140 1142//1142 -f 1141//1141 1142//1142 1143//1143 -f 1143//1143 1142//1142 1144//1144 -f 1143//1143 1144//1144 1107//1107 -f 1107//1107 1144//1144 1145//1145 -f 1107//1107 1145//1145 1108//1108 -f 1146//1146 1147//1147 1148//1148 -f 1149//1149 1150//1150 1151//1151 -f 1152//1152 1153//1153 1154//1154 -f 1155//1155 1156//1156 1157//1157 -f 1158//1158 1159//1159 1160//1160 -f 1161//1161 1162//1162 1163//1163 -f 1164//1164 1165//1165 1166//1166 -f 1167//1167 1168//1168 1169//1169 -f 1170//1170 1171//1171 1172//1172 -f 1173//1173 1174//1174 1175//1175 -f 1176//1176 1177//1177 1178//1178 -f 1179//1179 1180//1180 1181//1181 -f 1182//1182 1183//1183 1184//1184 -f 1185//1185 1186//1186 1187//1187 -f 1188//1188 1189//1189 1190//1190 -f 1191//1191 1192//1192 1193//1193 -f 1194//1194 1195//1195 1196//1196 -f 1197//1197 1198//1198 1199//1199 -f 1200//1200 1201//1201 1202//1202 -f 1203//1203 1204//1204 1205//1205 -f 1206//1206 1207//1207 1208//1208 -f 1209//1209 1210//1210 1211//1211 -f 1212//1212 1213//1213 1214//1214 -f 1215//1215 1216//1216 1217//1217 -f 1218//1218 1219//1219 1220//1220 -f 1221//1221 1222//1222 1223//1223 -f 1224//1224 1225//1225 1226//1226 -f 1227//1227 1228//1228 1229//1229 -f 1230//1230 1231//1231 1232//1232 -f 1233//1233 1234//1234 1235//1235 -f 1236//1236 1237//1237 1238//1238 -f 1239//1239 1240//1240 1241//1241 -f 1242//1242 1243//1243 1244//1244 -f 1245//1245 1246//1246 1247//1247 -f 1248//1248 1249//1249 1250//1250 -f 1251//1251 1252//1252 1253//1253 -f 1254//1254 1255//1255 1256//1256 -f 1257//1257 1258//1258 1259//1259 -f 1260//1260 1261//1261 1262//1262 -f 1263//1263 1264//1264 1265//1265 -f 1266//1266 1267//1267 1268//1268 -f 1269//1269 1270//1270 1271//1271 -f 1272//1272 1273//1273 1274//1274 -f 1275//1275 1276//1276 1277//1277 -f 1278//1278 1279//1279 1280//1280 -f 1281//1281 1282//1282 1283//1283 -f 1284//1284 1285//1285 1286//1286 -f 1287//1287 1288//1288 1289//1289 -f 1290//1290 1291//1291 1292//1292 -f 1293//1293 1294//1294 1295//1295 -f 1296//1296 1297//1297 1298//1298 -f 1299//1299 1300//1300 1301//1301 -f 1302//1302 1303//1303 1304//1304 -f 1305//1305 1306//1306 1307//1307 -f 1308//1308 1309//1309 1310//1310 -f 1311//1311 1312//1312 1313//1313 -f 1314//1314 1315//1315 1316//1316 -f 1317//1317 1318//1318 1319//1319 -f 1320//1320 1321//1321 1322//1322 -f 1323//1323 1324//1324 1325//1325 -f 1326//1326 1327//1327 1328//1328 -f 1329//1329 1330//1330 1331//1331 -f 1332//1332 1333//1333 1334//1334 -f 1335//1335 1336//1336 1337//1337 -f 1338//1338 1339//1339 1340//1340 -f 1341//1341 1342//1342 1343//1343 -f 1344//1344 1345//1345 1346//1346 -f 1347//1347 1348//1348 1349//1349 -f 1350//1350 1351//1351 1352//1352 -f 1353//1353 1354//1354 1355//1355 -f 1356//1356 1357//1357 1358//1358 -f 1359//1359 1360//1360 1361//1361 -f 1362//1362 1363//1363 1364//1364 -f 1365//1365 1366//1366 1367//1367 -f 1368//1368 1369//1369 1370//1370 -f 1371//1371 1372//1372 1373//1373 -f 1374//1374 1375//1375 1376//1376 -f 1377//1377 1378//1378 1379//1379 -f 1380//1380 1381//1381 1382//1382 -f 1383//1383 1384//1384 1385//1385 -f 1386//1386 1387//1387 1388//1388 -f 1389//1389 1390//1390 1391//1391 -f 1392//1392 1393//1393 1394//1394 -f 1395//1395 1396//1396 1397//1397 -f 1398//1398 1399//1399 1400//1400 -f 1401//1401 1402//1402 1403//1403 -f 1404//1404 1405//1405 1406//1406 -f 1407//1407 1408//1408 1409//1409 -f 1410//1410 1411//1411 1412//1412 -f 1413//1413 1414//1414 1415//1415 -f 1416//1416 1417//1417 1418//1418 -f 1419//1419 1420//1420 1421//1421 -f 1422//1422 1423//1423 1424//1424 -f 1425//1425 1426//1426 1427//1427 -f 861//861 859//859 1169//1169 -f 845//845 843//843 1184//1184 -f 831//831 829//829 1196//1196 -f 814//814 812//812 1211//1211 -f 784//784 782//782 1238//1238 -f 746//746 748//748 1253//1253 -f 760//760 762//762 1265//1265 -f 728//728 730//730 1280//1280 -f 706//706 704//704 1307//1307 -f 676//676 674//674 1334//1334 -f 659//659 657//657 1349//1349 -f 646//646 644//644 1361//1361 -f 628//628 626//626 1376//1376 -f 1428//1428 1429//1429 1430//1430 -f 1431//1431 1432//1432 1421//1421 -f 1433//1433 1434//1434 1435//1435 -f 1436//1436 1437//1437 1438//1438 -f 1439//1439 1440//1440 1441//1441 -f 1442//1442 1443//1443 1444//1444 -f 1445//1445 1446//1446 1447//1447 -f 1447//1447 1446//1446 1448//1448 -f 1447//1447 1448//1448 1449//1449 -f 1448//1448 1450//1450 1449//1449 -f 1449//1449 1450//1450 1451//1451 -f 1449//1449 1451//1451 1452//1452 -f 1452//1452 1451//1451 1453//1453 -f 1452//1452 1453//1453 1454//1454 -f 1454//1454 1453//1453 1455//1455 -f 1454//1454 1455//1455 1456//1456 -f 1456//1456 1455//1455 1457//1457 -f 1456//1456 1457//1457 1458//1458 -f 1459//1459 1460//1460 1461//1461 -f 1461//1461 1460//1460 1462//1462 -f 1462//1462 1463//1463 1461//1461 -f 1461//1461 1463//1463 1464//1464 -f 1461//1461 1464//1464 1447//1447 -f 1447//1447 1464//1464 1465//1465 -f 1447//1447 1465//1465 1445//1445 -f 1444//1444 1443//1443 1466//1466 -f 1443//1443 1467//1467 1466//1466 -f 1466//1466 1467//1467 1468//1468 -f 1466//1466 1468//1468 1459//1459 -f 1459//1459 1468//1468 1469//1469 -f 1459//1459 1469//1469 1460//1460 -f 1442//1442 1444//1444 1470//1470 -f 1470//1470 1444//1444 1471//1471 -f 1470//1470 1471//1471 1472//1472 -f 1473//1473 1474//1474 1475//1475 -f 1475//1475 1476//1476 1473//1473 -f 1473//1473 1476//1476 1477//1477 -f 1473//1473 1477//1477 1471//1471 -f 1471//1471 1477//1477 1478//1478 -f 1471//1471 1478//1478 1472//1472 -f 1440//1440 1479//1479 1441//1441 -f 1441//1441 1479//1479 1480//1480 -f 1441//1441 1480//1480 1474//1474 -f 1474//1474 1480//1480 1481//1481 -f 1474//1474 1481//1481 1475//1475 -f 1482//1482 1483//1483 1484//1484 -f 1484//1484 1483//1483 1485//1485 -f 1482//1482 1484//1484 1441//1441 -f 1441//1441 1484//1484 1486//1486 -f 1441//1441 1486//1486 1439//1439 -f 1487//1487 1488//1488 1489//1489 -f 1489//1489 1488//1488 1490//1490 -f 1489//1489 1490//1490 1483//1483 -f 1483//1483 1490//1490 1491//1491 -f 1483//1483 1491//1491 1485//1485 -f 1492//1492 1493//1493 1487//1487 -f 1487//1487 1493//1493 1494//1494 -f 1487//1487 1494//1494 1488//1488 -f 1495//1495 1496//1496 1497//1497 -f 1497//1497 1498//1498 1495//1495 -f 1495//1495 1498//1498 1499//1499 -f 1495//1495 1499//1499 1500//1500 -f 1500//1500 1499//1499 1501//1501 -f 1500//1500 1501//1501 1492//1492 -f 1492//1492 1501//1501 1502//1502 -f 1492//1492 1502//1502 1493//1493 -f 1503//1503 1504//1504 1496//1496 -f 1496//1496 1504//1504 1505//1505 -f 1496//1496 1505//1505 1497//1497 -f 1506//1506 1507//1507 1437//1437 -f 1437//1437 1507//1507 1508//1508 -f 1437//1437 1508//1508 1438//1438 -f 1506//1506 1509//1509 1507//1507 -f 1507//1507 1509//1509 1510//1510 -f 1507//1507 1510//1510 1503//1503 -f 1503//1503 1510//1510 1511//1511 -f 1503//1503 1511//1511 1504//1504 -f 1512//1512 1513//1513 1514//1514 -f 1514//1514 1513//1513 1515//1515 -f 1514//1514 1515//1515 1516//1516 -f 1516//1516 1515//1515 1517//1517 -f 1512//1512 1518//1518 1513//1513 -f 1513//1513 1518//1518 1519//1519 -f 1513//1513 1519//1519 1520//1520 -f 1520//1520 1519//1519 1521//1521 -f 1520//1520 1521//1521 1438//1438 -f 1438//1438 1521//1521 1522//1522 -f 1438//1438 1522//1522 1436//1436 -f 1523//1523 1524//1524 1525//1525 -f 1525//1525 1524//1524 1526//1526 -f 1525//1525 1526//1526 1435//1435 -f 1435//1435 1526//1526 1527//1527 -f 1435//1435 1527//1527 1433//1433 -f 1528//1528 1529//1529 1427//1427 -f 1530//1530 1531//1531 1427//1427 -f 1427//1427 1531//1531 1532//1532 -f 1427//1427 1532//1532 1528//1528 -f 1533//1533 1424//1424 1534//1534 -f 1534//1534 1424//1424 1535//1535 -f 1536//1536 1537//1537 1418//1418 -f 1418//1418 1537//1537 1538//1538 -f 1431//1431 1421//1421 1539//1539 -f 1540//1540 1541//1541 1415//1415 -f 1415//1415 1541//1541 1542//1542 -f 1543//1543 1544//1544 1412//1412 -f 1412//1412 1544//1544 1545//1545 -f 1412//1412 1545//1545 1546//1546 -f 1547//1547 1548//1548 1409//1409 -f 1409//1409 1548//1548 1549//1549 -f 1409//1409 1549//1549 1550//1550 -f 1551//1551 1552//1552 1403//1403 -f 1403//1403 1552//1552 1553//1553 -f 1554//1554 1555//1555 1406//1406 -f 1556//1556 1557//1557 1400//1400 -f 1400//1400 1557//1557 1558//1558 -f 1397//1397 1559//1559 1560//1560 -f 1561//1561 1562//1562 1397//1397 -f 1397//1397 1562//1562 1563//1563 -f 1397//1397 1563//1563 1559//1559 -f 1564//1564 1565//1565 1394//1394 -f 1394//1394 1565//1565 1566//1566 -f 1394//1394 1566//1566 1567//1567 -f 613//613 1568//1568 1391//1391 -f 1391//1391 1568//1568 1569//1569 -f 1570//1570 1115//1115 1571//1571 -f 1428//1428 1430//1430 1572//1572 -f 1572//1572 1430//1430 1573//1573 -f 1572//1572 1573//1573 1574//1574 -f 1575//1575 1576//1576 1577//1577 -f 1578//1578 1579//1579 1580//1580 -f 1578//1578 1580//1580 1576//1576 -f 1576//1576 1580//1580 1581//1581 -f 1576//1576 1581//1581 1577//1577 -f 616//616 614//614 1388//1388 -f 623//623 621//621 1382//1382 -f 632//632 630//630 1373//1373 -f 636//636 634//634 1370//1370 -f 640//640 638//638 1367//1367 -f 650//650 648//648 1358//1358 -f 654//654 652//652 1355//1355 -f 663//663 661//661 1346//1346 -f 670//670 668//668 1340//1340 -f 680//680 678//678 1331//1331 -f 684//684 682//682 1328//1328 -f 687//687 686//686 1325//1325 -f 693//693 691//691 1319//1319 -f 700//700 698//698 1313//1313 -f 710//710 708//708 1304//1304 -f 714//714 712//712 1301//1301 -f 717//717 716//716 1298//1298 -f 723//723 721//721 1292//1292 -f 734//734 736//736 1286//1286 -f 724//724 726//726 1277//1277 -f 766//766 768//768 1271//1271 -f 756//756 758//758 1262//1262 -f 752//752 754//754 1259//1259 -f 741//741 744//744 1250//1250 -f 778//778 776//776 1244//1244 -f 788//788 786//786 1235//1235 -f 792//792 790//790 1232//1232 -f 795//795 794//794 1229//1229 -f 801//801 799//799 1223//1223 -f 808//808 806//806 1217//1217 -f 818//818 816//816 1208//1208 -f 822//822 820//820 1205//1205 -f 825//825 824//824 1202//1202 -f 835//835 833//833 1193//1193 -f 839//839 837//837 1190//1190 -f 849//849 847//847 1181//1181 -f 855//855 854//854 1175//1175 -f 865//865 863//863 1166//1166 -f 869//869 867//867 1163//1163 -f 873//873 871//871 1160//1160 -f 879//879 877//877 1154//1154 -f 885//885 884//884 1148//1148 -f 1582//1582 1583//1583 887//887 -f 1584//1584 891//891 1583//1583 -f 1583//1583 891//891 889//889 -f 1583//1583 889//889 887//887 -f 1585//1585 1586//1586 899//899 -f 899//899 897//897 1585//1585 -f 1585//1585 897//897 895//895 -f 1585//1585 895//895 1584//1584 -f 1584//1584 895//895 893//893 -f 1584//1584 893//893 891//891 -f 1587//1587 905//905 1588//1588 -f 1588//1588 905//905 903//903 -f 1588//1588 903//903 1586//1586 -f 1586//1586 903//903 901//901 -f 1586//1586 901//901 899//899 -f 915//915 914//914 1589//1589 -f 1589//1589 914//914 912//912 -f 1589//1589 912//912 1590//1590 -f 1590//1590 912//912 910//910 -f 1590//1590 910//910 1587//1587 -f 1587//1587 910//910 908//908 -f 1587//1587 908//908 905//905 -f 921//921 919//919 1591//1591 -f 1591//1591 919//919 917//917 -f 1591//1591 917//917 1592//1592 -f 928//928 1593//1593 926//926 -f 926//926 1593//1593 1594//1594 -f 926//926 1594//1594 924//924 -f 931//931 1595//1595 932//932 -f 932//932 1595//1595 1596//1596 -f 932//932 1596//1596 934//934 -f 936//936 1597//1597 938//938 -f 938//938 1597//1597 1598//1598 -f 938//938 1598//1598 941//941 -f 941//941 1598//1598 942//942 -f 944//944 1599//1599 946//946 -f 946//946 1599//1599 1600//1600 -f 946//946 1600//1600 948//948 -f 949//949 1601//1601 951//951 -f 951//951 1601//1601 1602//1602 -f 951//951 1602//1602 953//953 -f 953//953 1602//1602 955//955 -f 963//963 956//956 1603//1603 -f 1603//1603 956//956 959//959 -f 1603//1603 959//959 1604//1604 -f 968//968 966//966 1605//1605 -f 1605//1605 966//966 965//965 -f 1605//1605 965//965 1606//1606 -f 970//970 1607//1607 972//972 -f 972//972 1607//1607 1608//1608 -f 972//972 1608//1608 974//974 -f 974//974 1608//1608 975//975 -f 977//977 1609//1609 979//979 -f 979//979 1609//1609 1610//1610 -f 979//979 1610//1610 981//981 -f 988//988 1611//1611 986//986 -f 986//986 1611//1611 1612//1612 -f 986//986 1612//1612 984//984 -f 991//991 1613//1613 992//992 -f 992//992 1613//1613 1614//1614 -f 992//992 1614//1614 994//994 -f 996//996 1615//1615 998//998 -f 998//998 1615//1615 1616//1616 -f 998//998 1616//1616 1001//1001 -f 1001//1001 1616//1616 1002//1002 -f 1004//1004 1617//1617 1006//1006 -f 1006//1006 1617//1617 1618//1618 -f 1006//1006 1618//1618 1009//1009 -f 1009//1009 1618//1618 1010//1010 -f 1016//1016 1014//1014 1619//1619 -f 1619//1619 1014//1014 1012//1012 -f 1619//1619 1012//1012 1620//1620 -f 1019//1019 1621//1621 1020//1020 -f 1020//1020 1621//1621 1622//1622 -f 1020//1020 1622//1622 1022//1022 -f 1022//1022 1622//1622 1024//1024 -f 1029//1029 1027//1027 1623//1623 -f 1623//1623 1027//1027 1026//1026 -f 1623//1623 1026//1026 1624//1624 -f 1625//1625 1037//1037 1626//1626 -f 1626//1626 1037//1037 1033//1033 -f 1626//1626 1033//1033 1627//1627 -f 1627//1627 1033//1033 1031//1031 -f 1047//1047 1045//1045 1628//1628 -f 1628//1628 1045//1045 1043//1043 -f 1628//1628 1043//1043 1629//1629 -f 1629//1629 1043//1043 1041//1041 -f 1629//1629 1041//1041 1625//1625 -f 1625//1625 1041//1041 1034//1034 -f 1625//1625 1034//1034 1037//1037 -f 1048//1048 1630//1630 1050//1050 -f 1050//1050 1630//1630 1631//1631 -f 1050//1050 1631//1631 1052//1052 -f 1052//1052 1631//1631 1053//1053 -f 1055//1055 1632//1632 1057//1057 -f 1057//1057 1632//1632 1633//1633 -f 1057//1057 1633//1633 1059//1059 -f 1066//1066 1634//1634 1064//1064 -f 1064//1064 1634//1634 1635//1635 -f 1064//1064 1635//1635 1062//1062 -f 1069//1069 1636//1636 1070//1070 -f 1070//1070 1636//1636 1637//1637 -f 1070//1070 1637//1637 1072//1072 -f 1074//1074 1638//1638 1076//1076 -f 1076//1076 1638//1638 1639//1639 -f 1076//1076 1639//1639 1079//1079 -f 1079//1079 1639//1639 1080//1080 -f 1082//1082 1640//1640 1084//1084 -f 1084//1084 1640//1640 1641//1641 -f 1084//1084 1641//1641 1086//1086 -f 1086//1086 1641//1641 1087//1087 -f 1093//1093 1091//1091 1642//1642 -f 1642//1642 1091//1091 1089//1089 -f 1642//1642 1089//1089 1643//1643 -f 1101//1101 1094//1094 1644//1644 -f 1644//1644 1094//1094 1097//1097 -f 1644//1644 1097//1097 1645//1645 -f 1114//1114 1105//1105 1646//1646 -f 1646//1646 1105//1105 1103//1103 -f 1646//1646 1103//1103 1647//1647 -f 1113//1113 1648//1648 1111//1111 -f 1111//1111 1648//1648 1649//1649 -f 1111//1111 1649//1649 1109//1109 -f 1107//1107 1650//1650 1143//1143 -f 1143//1143 1650//1650 1651//1651 -f 1143//1143 1651//1651 1141//1141 -f 1139//1139 1652//1652 1137//1137 -f 1137//1137 1652//1652 1653//1653 -f 1137//1137 1653//1653 1135//1135 -f 1135//1135 1653//1653 1130//1130 -f 1131//1131 1654//1654 1133//1133 -f 1133//1133 1654//1654 1655//1655 -f 1133//1133 1655//1655 1134//1134 -f 1128//1128 1656//1656 1129//1129 -f 1129//1129 1656//1656 1657//1657 -f 1129//1129 1657//1657 1123//1123 -f 1123//1123 1657//1657 1125//1125 -f 1119//1119 1121//1121 1658//1658 -f 1658//1658 1121//1121 1126//1126 -f 1658//1658 1126//1126 1659//1659 -f 1115//1115 1117//1117 1571//1571 -f 1571//1571 1117//1117 1118//1118 -f 1571//1571 1118//1118 1660//1660 -f 1433//1433 1516//1516 1434//1434 -f 1434//1434 1516//1516 1517//1517 -f 1434//1434 1517//1517 1435//1435 -f 1435//1435 1517//1517 1661//1661 -f 1435//1435 1661//1661 1525//1525 -f 1525//1525 1661//1661 1662//1662 -f 1662//1662 1425//1425 1525//1525 -f 1525//1525 1425//1425 1427//1427 -f 1525//1525 1427//1427 1523//1523 -f 1523//1523 1427//1427 1529//1529 -f 1426//1426 1422//1422 1427//1427 -f 1427//1427 1422//1422 1424//1424 -f 1427//1427 1424//1424 1530//1530 -f 1530//1530 1424//1424 1533//1533 -f 1423//1423 1419//1419 1424//1424 -f 1424//1424 1419//1419 1421//1421 -f 1424//1424 1421//1421 1535//1535 -f 1535//1535 1421//1421 1432//1432 -f 1420//1420 1416//1416 1421//1421 -f 1421//1421 1416//1416 1418//1418 -f 1421//1421 1418//1418 1539//1539 -f 1539//1539 1418//1418 1538//1538 -f 1417//1417 1413//1413 1418//1418 -f 1418//1418 1413//1413 1415//1415 -f 1418//1418 1415//1415 1536//1536 -f 1536//1536 1415//1415 1542//1542 -f 1414//1414 1410//1410 1415//1415 -f 1415//1415 1410//1410 1412//1412 -f 1415//1415 1412//1412 1540//1540 -f 1540//1540 1412//1412 1546//1546 -f 1411//1411 1407//1407 1412//1412 -f 1412//1412 1407//1407 1409//1409 -f 1412//1412 1409//1409 1543//1543 -f 1543//1543 1409//1409 1550//1550 -f 1408//1408 1404//1404 1409//1409 -f 1409//1409 1404//1404 1406//1406 -f 1409//1409 1406//1406 1547//1547 -f 1547//1547 1406//1406 1555//1555 -f 1405//1405 1401//1401 1406//1406 -f 1406//1406 1401//1401 1403//1403 -f 1406//1406 1403//1403 1554//1554 -f 1554//1554 1403//1403 1553//1553 -f 1402//1402 1398//1398 1403//1403 -f 1403//1403 1398//1398 1400//1400 -f 1403//1403 1400//1400 1551//1551 -f 1551//1551 1400//1400 1558//1558 -f 1399//1399 1395//1395 1400//1400 -f 1400//1400 1395//1395 1397//1397 -f 1400//1400 1397//1397 1556//1556 -f 1556//1556 1397//1397 1560//1560 -f 1396//1396 1392//1392 1397//1397 -f 1397//1397 1392//1392 1394//1394 -f 1397//1397 1394//1394 1561//1561 -f 1561//1561 1394//1394 1567//1567 -f 1393//1393 1389//1389 1394//1394 -f 1394//1394 1389//1389 1391//1391 -f 1394//1394 1391//1391 1564//1564 -f 1564//1564 1391//1391 1569//1569 -f 1390//1390 1386//1386 1391//1391 -f 1391//1391 1386//1386 1388//1388 -f 1391//1391 1388//1388 613//613 -f 613//613 1388//1388 614//614 -f 1387//1387 1383//1383 1388//1388 -f 1388//1388 1383//1383 1385//1385 -f 1388//1388 1385//1385 616//616 -f 616//616 1385//1385 619//619 -f 1384//1384 1380//1380 1385//1385 -f 1385//1385 1380//1380 1382//1382 -f 1385//1385 1382//1382 619//619 -f 619//619 1382//1382 621//621 -f 1381//1381 1377//1377 1382//1382 -f 1382//1382 1377//1377 1379//1379 -f 1382//1382 1379//1379 623//623 -f 623//623 1379//1379 625//625 -f 1378//1378 1374//1374 1379//1379 -f 1379//1379 1374//1374 1376//1376 -f 1379//1379 1376//1376 625//625 -f 625//625 1376//1376 626//626 -f 1375//1375 1371//1371 1376//1376 -f 1376//1376 1371//1371 1373//1373 -f 1376//1376 1373//1373 628//628 -f 628//628 1373//1373 630//630 -f 1372//1372 1368//1368 1373//1373 -f 1373//1373 1368//1368 1370//1370 -f 1373//1373 1370//1370 632//632 -f 632//632 1370//1370 634//634 -f 1369//1369 1365//1365 1370//1370 -f 1370//1370 1365//1365 1367//1367 -f 1370//1370 1367//1367 636//636 -f 636//636 1367//1367 638//638 -f 1366//1366 1362//1362 1367//1367 -f 1367//1367 1362//1362 1364//1364 -f 1367//1367 1364//1364 640//640 -f 640//640 1364//1364 642//642 -f 1363//1363 1359//1359 1364//1364 -f 1364//1364 1359//1359 1361//1361 -f 1364//1364 1361//1361 642//642 -f 642//642 1361//1361 644//644 -f 1360//1360 1356//1356 1361//1361 -f 1361//1361 1356//1356 1358//1358 -f 1361//1361 1358//1358 646//646 -f 646//646 1358//1358 648//648 -f 1357//1357 1353//1353 1358//1358 -f 1358//1358 1353//1353 1355//1355 -f 1358//1358 1355//1355 650//650 -f 650//650 1355//1355 652//652 -f 1354//1354 1350//1350 1355//1355 -f 1355//1355 1350//1350 1352//1352 -f 1355//1355 1352//1352 654//654 -f 654//654 1352//1352 656//656 -f 1351//1351 1347//1347 1352//1352 -f 1352//1352 1347//1347 1349//1349 -f 1352//1352 1349//1349 656//656 -f 656//656 1349//1349 657//657 -f 1348//1348 1344//1344 1349//1349 -f 1349//1349 1344//1344 1346//1346 -f 1349//1349 1346//1346 659//659 -f 659//659 1346//1346 661//661 -f 1345//1345 1341//1341 1346//1346 -f 1346//1346 1341//1341 1343//1343 -f 1346//1346 1343//1343 663//663 -f 663//663 1343//1343 666//666 -f 1342//1342 1338//1338 1343//1343 -f 1343//1343 1338//1338 1340//1340 -f 1343//1343 1340//1340 666//666 -f 666//666 1340//1340 668//668 -f 1339//1339 1335//1335 1340//1340 -f 1340//1340 1335//1335 1337//1337 -f 1340//1340 1337//1337 670//670 -f 670//670 1337//1337 672//672 -f 1336//1336 1332//1332 1337//1337 -f 1337//1337 1332//1332 1334//1334 -f 1337//1337 1334//1334 672//672 -f 672//672 1334//1334 674//674 -f 1333//1333 1329//1329 1334//1334 -f 1334//1334 1329//1329 1331//1331 -f 1334//1334 1331//1331 676//676 -f 676//676 1331//1331 678//678 -f 1330//1330 1326//1326 1331//1331 -f 1331//1331 1326//1326 1328//1328 -f 1331//1331 1328//1328 680//680 -f 680//680 1328//1328 682//682 -f 1327//1327 1323//1323 1328//1328 -f 1328//1328 1323//1323 1325//1325 -f 1328//1328 1325//1325 684//684 -f 684//684 1325//1325 686//686 -f 1324//1324 1320//1320 1325//1325 -f 1325//1325 1320//1320 1322//1322 -f 1325//1325 1322//1322 687//687 -f 687//687 1322//1322 689//689 -f 1321//1321 1317//1317 1322//1322 -f 1322//1322 1317//1317 1319//1319 -f 1322//1322 1319//1319 689//689 -f 689//689 1319//1319 691//691 -f 1318//1318 1314//1314 1319//1319 -f 1319//1319 1314//1314 1316//1316 -f 1319//1319 1316//1316 693//693 -f 693//693 1316//1316 696//696 -f 1315//1315 1311//1311 1316//1316 -f 1316//1316 1311//1311 1313//1313 -f 1316//1316 1313//1313 696//696 -f 696//696 1313//1313 698//698 -f 1312//1312 1308//1308 1313//1313 -f 1313//1313 1308//1308 1310//1310 -f 1313//1313 1310//1310 700//700 -f 700//700 1310//1310 702//702 -f 1309//1309 1305//1305 1310//1310 -f 1310//1310 1305//1305 1307//1307 -f 1310//1310 1307//1307 702//702 -f 702//702 1307//1307 704//704 -f 1306//1306 1302//1302 1307//1307 -f 1307//1307 1302//1302 1304//1304 -f 1307//1307 1304//1304 706//706 -f 706//706 1304//1304 708//708 -f 1303//1303 1299//1299 1304//1304 -f 1304//1304 1299//1299 1301//1301 -f 1304//1304 1301//1301 710//710 -f 710//710 1301//1301 712//712 -f 1300//1300 1296//1296 1301//1301 -f 1301//1301 1296//1296 1298//1298 -f 1301//1301 1298//1298 714//714 -f 714//714 1298//1298 716//716 -f 1297//1297 1293//1293 1298//1298 -f 1298//1298 1293//1293 1295//1295 -f 1298//1298 1295//1295 717//717 -f 717//717 1295//1295 719//719 -f 1294//1294 1290//1290 1295//1295 -f 1295//1295 1290//1290 1292//1292 -f 1295//1295 1292//1292 719//719 -f 719//719 1292//1292 721//721 -f 1291//1291 1287//1287 1292//1292 -f 1292//1292 1287//1287 1289//1289 -f 1292//1292 1289//1289 723//723 -f 723//723 1289//1289 738//738 -f 1288//1288 1284//1284 1289//1289 -f 1289//1289 1284//1284 1286//1286 -f 1289//1289 1286//1286 738//738 -f 738//738 1286//1286 736//736 -f 1285//1285 1281//1281 1286//1286 -f 1286//1286 1281//1281 1283//1283 -f 1286//1286 1283//1283 734//734 -f 734//734 1283//1283 732//732 -f 1282//1282 1278//1278 1283//1283 -f 1283//1283 1278//1278 1280//1280 -f 1283//1283 1280//1280 732//732 -f 732//732 1280//1280 730//730 -f 1279//1279 1275//1275 1280//1280 -f 1280//1280 1275//1275 1277//1277 -f 1280//1280 1277//1277 728//728 -f 728//728 1277//1277 726//726 -f 1276//1276 1272//1272 1277//1277 -f 1277//1277 1272//1272 1274//1274 -f 1277//1277 1274//1274 724//724 -f 724//724 1274//1274 770//770 -f 1273//1273 1269//1269 1274//1274 -f 1274//1274 1269//1269 1271//1271 -f 1274//1274 1271//1271 770//770 -f 770//770 1271//1271 768//768 -f 1270//1270 1266//1266 1271//1271 -f 1271//1271 1266//1266 1268//1268 -f 1271//1271 1268//1268 766//766 -f 766//766 1268//1268 764//764 -f 1267//1267 1263//1263 1268//1268 -f 1268//1268 1263//1263 1265//1265 -f 1268//1268 1265//1265 764//764 -f 764//764 1265//1265 762//762 -f 1264//1264 1260//1260 1265//1265 -f 1265//1265 1260//1260 1262//1262 -f 1265//1265 1262//1262 760//760 -f 760//760 1262//1262 758//758 -f 1261//1261 1257//1257 1262//1262 -f 1262//1262 1257//1257 1259//1259 -f 1262//1262 1259//1259 756//756 -f 756//756 1259//1259 754//754 -f 1258//1258 1254//1254 1259//1259 -f 1259//1259 1254//1254 1256//1256 -f 1259//1259 1256//1256 752//752 -f 752//752 1256//1256 750//750 -f 1255//1255 1251//1251 1256//1256 -f 1256//1256 1251//1251 1253//1253 -f 1256//1256 1253//1253 750//750 -f 750//750 1253//1253 748//748 -f 1252//1252 1248//1248 1253//1253 -f 1253//1253 1248//1248 1250//1250 -f 1253//1253 1250//1250 746//746 -f 746//746 1250//1250 744//744 -f 1249//1249 1245//1245 1250//1250 -f 1250//1250 1245//1245 1247//1247 -f 1250//1250 1247//1247 741//741 -f 741//741 1247//1247 774//774 -f 1246//1246 1242//1242 1247//1247 -f 1247//1247 1242//1242 1244//1244 -f 1247//1247 1244//1244 774//774 -f 774//774 1244//1244 776//776 -f 1243//1243 1239//1239 1244//1244 -f 1244//1244 1239//1239 1241//1241 -f 1244//1244 1241//1241 778//778 -f 778//778 1241//1241 780//780 -f 1240//1240 1236//1236 1241//1241 -f 1241//1241 1236//1236 1238//1238 -f 1241//1241 1238//1238 780//780 -f 780//780 1238//1238 782//782 -f 1237//1237 1233//1233 1238//1238 -f 1238//1238 1233//1233 1235//1235 -f 1238//1238 1235//1235 784//784 -f 784//784 1235//1235 786//786 -f 1234//1234 1230//1230 1235//1235 -f 1235//1235 1230//1230 1232//1232 -f 1235//1235 1232//1232 788//788 -f 788//788 1232//1232 790//790 -f 1231//1231 1227//1227 1232//1232 -f 1232//1232 1227//1227 1229//1229 -f 1232//1232 1229//1229 792//792 -f 792//792 1229//1229 794//794 -f 1228//1228 1224//1224 1229//1229 -f 1229//1229 1224//1224 1226//1226 -f 1229//1229 1226//1226 795//795 -f 795//795 1226//1226 797//797 -f 1225//1225 1221//1221 1226//1226 -f 1226//1226 1221//1221 1223//1223 -f 1226//1226 1223//1223 797//797 -f 797//797 1223//1223 799//799 -f 1222//1222 1218//1218 1223//1223 -f 1223//1223 1218//1218 1220//1220 -f 1223//1223 1220//1220 801//801 -f 801//801 1220//1220 804//804 -f 1219//1219 1215//1215 1220//1220 -f 1220//1220 1215//1215 1217//1217 -f 1220//1220 1217//1217 804//804 -f 804//804 1217//1217 806//806 -f 1216//1216 1212//1212 1217//1217 -f 1217//1217 1212//1212 1214//1214 -f 1217//1217 1214//1214 808//808 -f 808//808 1214//1214 810//810 -f 1213//1213 1209//1209 1214//1214 -f 1214//1214 1209//1209 1211//1211 -f 1214//1214 1211//1211 810//810 -f 810//810 1211//1211 812//812 -f 1210//1210 1206//1206 1211//1211 -f 1211//1211 1206//1206 1208//1208 -f 1211//1211 1208//1208 814//814 -f 814//814 1208//1208 816//816 -f 1207//1207 1203//1203 1208//1208 -f 1208//1208 1203//1203 1205//1205 -f 1208//1208 1205//1205 818//818 -f 818//818 1205//1205 820//820 -f 1204//1204 1200//1200 1205//1205 -f 1205//1205 1200//1200 1202//1202 -f 1205//1205 1202//1202 822//822 -f 822//822 1202//1202 824//824 -f 1201//1201 1197//1197 1202//1202 -f 1202//1202 1197//1197 1199//1199 -f 1202//1202 1199//1199 825//825 -f 825//825 1199//1199 827//827 -f 1198//1198 1194//1194 1199//1199 -f 1199//1199 1194//1194 1196//1196 -f 1199//1199 1196//1196 827//827 -f 827//827 1196//1196 829//829 -f 1195//1195 1191//1191 1196//1196 -f 1196//1196 1191//1191 1193//1193 -f 1196//1196 1193//1193 831//831 -f 831//831 1193//1193 833//833 -f 1192//1192 1188//1188 1193//1193 -f 1193//1193 1188//1188 1190//1190 -f 1193//1193 1190//1190 835//835 -f 835//835 1190//1190 837//837 -f 1189//1189 1185//1185 1190//1190 -f 1190//1190 1185//1185 1187//1187 -f 1190//1190 1187//1187 839//839 -f 839//839 1187//1187 841//841 -f 1186//1186 1182//1182 1187//1187 -f 1187//1187 1182//1182 1184//1184 -f 1187//1187 1184//1184 841//841 -f 841//841 1184//1184 843//843 -f 1183//1183 1179//1179 1184//1184 -f 1184//1184 1179//1179 1181//1181 -f 1184//1184 1181//1181 845//845 -f 845//845 1181//1181 847//847 -f 1180//1180 1176//1176 1181//1181 -f 1181//1181 1176//1176 1178//1178 -f 1181//1181 1178//1178 849//849 -f 849//849 1178//1178 852//852 -f 1177//1177 1173//1173 1178//1178 -f 1178//1178 1173//1173 1175//1175 -f 1178//1178 1175//1175 852//852 -f 852//852 1175//1175 854//854 -f 1174//1174 1170//1170 1175//1175 -f 1175//1175 1170//1170 1172//1172 -f 1175//1175 1172//1172 855//855 -f 855//855 1172//1172 857//857 -f 1171//1171 1167//1167 1172//1172 -f 1172//1172 1167//1167 1169//1169 -f 1172//1172 1169//1169 857//857 -f 857//857 1169//1169 859//859 -f 1168//1168 1164//1164 1169//1169 -f 1169//1169 1164//1164 1166//1166 -f 1169//1169 1166//1166 861//861 -f 861//861 1166//1166 863//863 -f 1165//1165 1161//1161 1166//1166 -f 1166//1166 1161//1161 1163//1163 -f 1166//1166 1163//1163 865//865 -f 865//865 1163//1163 867//867 -f 1162//1162 1158//1158 1163//1163 -f 1163//1163 1158//1158 1160//1160 -f 1163//1163 1160//1160 869//869 -f 869//869 1160//1160 871//871 -f 1159//1159 1155//1155 1160//1160 -f 1160//1160 1155//1155 1157//1157 -f 1160//1160 1157//1157 873//873 -f 873//873 1157//1157 875//875 -f 1156//1156 1152//1152 1157//1157 -f 1157//1157 1152//1152 1154//1154 -f 1157//1157 1154//1154 875//875 -f 875//875 1154//1154 877//877 -f 1153//1153 1149//1149 1154//1154 -f 1154//1154 1149//1149 1151//1151 -f 1154//1154 1151//1151 879//879 -f 879//879 1151//1151 882//882 -f 1150//1150 1146//1146 1151//1151 -f 1151//1151 1146//1146 1148//1148 -f 1151//1151 1148//1148 882//882 -f 882//882 1148//1148 884//884 -f 1147//1147 1663//1663 1148//1148 -f 1148//1148 1663//1663 1582//1582 -f 1148//1148 1582//1582 885//885 -f 885//885 1582//1582 887//887 -f 1663//1663 1664//1664 1582//1582 -f 1582//1582 1664//1664 1665//1665 -f 1582//1582 1665//1665 1583//1583 -f 1583//1583 1665//1665 1666//1666 -f 1583//1583 1666//1666 1584//1584 -f 1584//1584 1666//1666 1667//1667 -f 1667//1667 1668//1668 1584//1584 -f 1584//1584 1668//1668 1669//1669 -f 1584//1584 1669//1669 1585//1585 -f 1585//1585 1669//1669 1670//1670 -f 1585//1585 1670//1670 1586//1586 -f 1670//1670 1671//1671 1586//1586 -f 1586//1586 1671//1671 1672//1672 -f 1586//1586 1672//1672 1588//1588 -f 1588//1588 1672//1672 1673//1673 -f 1673//1673 1674//1674 1588//1588 -f 1588//1588 1674//1674 1675//1675 -f 1588//1588 1675//1675 1587//1587 -f 1587//1587 1675//1675 1676//1676 -f 1587//1587 1676//1676 1590//1590 -f 1676//1676 1677//1677 1590//1590 -f 1590//1590 1677//1677 1678//1678 -f 1590//1590 1678//1678 1589//1589 -f 1589//1589 1678//1678 1679//1679 -f 1679//1679 1680//1680 1589//1589 -f 1589//1589 1680//1680 1592//1592 -f 1589//1589 1592//1592 915//915 -f 915//915 1592//1592 917//917 -f 1680//1680 1681//1681 1592//1592 -f 1592//1592 1681//1681 1682//1682 -f 1592//1592 1682//1682 1591//1591 -f 1591//1591 1682//1682 1683//1683 -f 1683//1683 1684//1684 1591//1591 -f 1591//1591 1684//1684 1593//1593 -f 1591//1591 1593//1593 921//921 -f 921//921 1593//1593 928//928 -f 1684//1684 1685//1685 1593//1593 -f 1593//1593 1685//1685 1686//1686 -f 1593//1593 1686//1686 1594//1594 -f 1594//1594 1686//1686 1687//1687 -f 1687//1687 1688//1688 1594//1594 -f 1594//1594 1688//1688 1595//1595 -f 1594//1594 1595//1595 924//924 -f 924//924 1595//1595 931//931 -f 1688//1688 1689//1689 1595//1595 -f 1595//1595 1689//1689 1690//1690 -f 1595//1595 1690//1690 1596//1596 -f 1596//1596 1690//1690 1691//1691 -f 1691//1691 1692//1692 1596//1596 -f 1596//1596 1692//1692 1597//1597 -f 1596//1596 1597//1597 934//934 -f 934//934 1597//1597 936//936 -f 1692//1692 1693//1693 1597//1597 -f 1597//1597 1693//1693 1694//1694 -f 1597//1597 1694//1694 1598//1598 -f 1598//1598 1694//1694 1695//1695 -f 1695//1695 1696//1696 1598//1598 -f 1598//1598 1696//1696 1599//1599 -f 1598//1598 1599//1599 942//942 -f 942//942 1599//1599 944//944 -f 1696//1696 1697//1697 1599//1599 -f 1599//1599 1697//1697 1698//1698 -f 1599//1599 1698//1698 1600//1600 -f 1600//1600 1698//1698 1699//1699 -f 1699//1699 1700//1700 1600//1600 -f 1600//1600 1700//1700 1601//1601 -f 1600//1600 1601//1601 948//948 -f 948//948 1601//1601 949//949 -f 1700//1700 1701//1701 1601//1601 -f 1601//1601 1701//1701 1702//1702 -f 1601//1601 1702//1702 1602//1602 -f 1602//1602 1702//1702 1703//1703 -f 1703//1703 1704//1704 1602//1602 -f 1602//1602 1704//1704 1604//1604 -f 1602//1602 1604//1604 955//955 -f 955//955 1604//1604 959//959 -f 1704//1704 1705//1705 1604//1604 -f 1604//1604 1705//1705 1706//1706 -f 1604//1604 1706//1706 1603//1603 -f 1603//1603 1706//1706 1707//1707 -f 1707//1707 1708//1708 1603//1603 -f 1603//1603 1708//1708 1606//1606 -f 1603//1603 1606//1606 963//963 -f 963//963 1606//1606 965//965 -f 1708//1708 1709//1709 1606//1606 -f 1606//1606 1709//1709 1710//1710 -f 1606//1606 1710//1710 1605//1605 -f 1605//1605 1710//1710 1711//1711 -f 1711//1711 1712//1712 1605//1605 -f 1605//1605 1712//1712 1607//1607 -f 1605//1605 1607//1607 968//968 -f 968//968 1607//1607 970//970 -f 1712//1712 1713//1713 1607//1607 -f 1607//1607 1713//1713 1714//1714 -f 1607//1607 1714//1714 1608//1608 -f 1608//1608 1714//1714 1715//1715 -f 1715//1715 1716//1716 1608//1608 -f 1608//1608 1716//1716 1609//1609 -f 1608//1608 1609//1609 975//975 -f 975//975 1609//1609 977//977 -f 1716//1716 1717//1717 1609//1609 -f 1609//1609 1717//1717 1718//1718 -f 1609//1609 1718//1718 1610//1610 -f 1610//1610 1718//1718 1719//1719 -f 1719//1719 1720//1720 1610//1610 -f 1610//1610 1720//1720 1611//1611 -f 1610//1610 1611//1611 981//981 -f 981//981 1611//1611 988//988 -f 1720//1720 1721//1721 1611//1611 -f 1611//1611 1721//1721 1722//1722 -f 1611//1611 1722//1722 1612//1612 -f 1612//1612 1722//1722 1723//1723 -f 1723//1723 1724//1724 1612//1612 -f 1612//1612 1724//1724 1613//1613 -f 1612//1612 1613//1613 984//984 -f 984//984 1613//1613 991//991 -f 1724//1724 1725//1725 1613//1613 -f 1613//1613 1725//1725 1726//1726 -f 1613//1613 1726//1726 1614//1614 -f 1614//1614 1726//1726 1727//1727 -f 1727//1727 1728//1728 1614//1614 -f 1614//1614 1728//1728 1615//1615 -f 1614//1614 1615//1615 994//994 -f 994//994 1615//1615 996//996 -f 1728//1728 1729//1729 1615//1615 -f 1615//1615 1729//1729 1730//1730 -f 1615//1615 1730//1730 1616//1616 -f 1616//1616 1730//1730 1731//1731 -f 1731//1731 1732//1732 1616//1616 -f 1616//1616 1732//1732 1617//1617 -f 1616//1616 1617//1617 1002//1002 -f 1002//1002 1617//1617 1004//1004 -f 1732//1732 1733//1733 1617//1617 -f 1617//1617 1733//1733 1734//1734 -f 1617//1617 1734//1734 1618//1618 -f 1618//1618 1734//1734 1735//1735 -f 1735//1735 1736//1736 1618//1618 -f 1618//1618 1736//1736 1620//1620 -f 1618//1618 1620//1620 1010//1010 -f 1010//1010 1620//1620 1012//1012 -f 1736//1736 1737//1737 1620//1620 -f 1620//1620 1737//1737 1738//1738 -f 1620//1620 1738//1738 1619//1619 -f 1619//1619 1738//1738 1739//1739 -f 1739//1739 1740//1740 1619//1619 -f 1619//1619 1740//1740 1621//1621 -f 1619//1619 1621//1621 1016//1016 -f 1016//1016 1621//1621 1019//1019 -f 1740//1740 1741//1741 1621//1621 -f 1621//1621 1741//1741 1742//1742 -f 1621//1621 1742//1742 1622//1622 -f 1622//1622 1742//1742 1743//1743 -f 1743//1743 1744//1744 1622//1622 -f 1622//1622 1744//1744 1624//1624 -f 1622//1622 1624//1624 1024//1024 -f 1024//1024 1624//1624 1026//1026 -f 1744//1744 1745//1745 1624//1624 -f 1624//1624 1745//1745 1746//1746 -f 1624//1624 1746//1746 1623//1623 -f 1623//1623 1746//1746 1747//1747 -f 1747//1747 1748//1748 1623//1623 -f 1623//1623 1748//1748 1627//1627 -f 1623//1623 1627//1627 1029//1029 -f 1029//1029 1627//1627 1031//1031 -f 1748//1748 1749//1749 1627//1627 -f 1627//1627 1749//1749 1750//1750 -f 1627//1627 1750//1750 1626//1626 -f 1626//1626 1750//1750 1751//1751 -f 1751//1751 1752//1752 1626//1626 -f 1626//1626 1752//1752 1753//1753 -f 1626//1626 1753//1753 1625//1625 -f 1625//1625 1753//1753 1754//1754 -f 1625//1625 1754//1754 1629//1629 -f 1754//1754 1755//1755 1629//1629 -f 1629//1629 1755//1755 1756//1756 -f 1629//1629 1756//1756 1628//1628 -f 1628//1628 1756//1756 1757//1757 -f 1628//1628 1757//1757 1758//1758 -f 1758//1758 1759//1759 1628//1628 -f 1628//1628 1759//1759 1630//1630 -f 1628//1628 1630//1630 1047//1047 -f 1047//1047 1630//1630 1048//1048 -f 1760//1760 1631//1631 1761//1761 -f 1761//1761 1631//1631 1630//1630 -f 1761//1761 1630//1630 1762//1762 -f 1762//1762 1630//1630 1759//1759 -f 1760//1760 1763//1763 1631//1631 -f 1631//1631 1763//1763 1632//1632 -f 1631//1631 1632//1632 1053//1053 -f 1053//1053 1632//1632 1055//1055 -f 1764//1764 1633//1633 1765//1765 -f 1765//1765 1633//1633 1632//1632 -f 1765//1765 1632//1632 1766//1766 -f 1766//1766 1632//1632 1763//1763 -f 1764//1764 1767//1767 1633//1633 -f 1633//1633 1767//1767 1634//1634 -f 1633//1633 1634//1634 1059//1059 -f 1059//1059 1634//1634 1066//1066 -f 1768//1768 1635//1635 1769//1769 -f 1769//1769 1635//1635 1634//1634 -f 1769//1769 1634//1634 1770//1770 -f 1770//1770 1634//1634 1767//1767 -f 1768//1768 1771//1771 1635//1635 -f 1635//1635 1771//1771 1636//1636 -f 1635//1635 1636//1636 1062//1062 -f 1062//1062 1636//1636 1069//1069 -f 1772//1772 1637//1637 1773//1773 -f 1773//1773 1637//1637 1636//1636 -f 1773//1773 1636//1636 1774//1774 -f 1774//1774 1636//1636 1771//1771 -f 1772//1772 1775//1775 1637//1637 -f 1637//1637 1775//1775 1638//1638 -f 1637//1637 1638//1638 1072//1072 -f 1072//1072 1638//1638 1074//1074 -f 1776//1776 1639//1639 1777//1777 -f 1777//1777 1639//1639 1638//1638 -f 1777//1777 1638//1638 1778//1778 -f 1778//1778 1638//1638 1775//1775 -f 1776//1776 1779//1779 1639//1639 -f 1639//1639 1779//1779 1640//1640 -f 1639//1639 1640//1640 1080//1080 -f 1080//1080 1640//1640 1082//1082 -f 1780//1780 1641//1641 1781//1781 -f 1781//1781 1641//1641 1640//1640 -f 1781//1781 1640//1640 1782//1782 -f 1782//1782 1640//1640 1779//1779 -f 1780//1780 1783//1783 1641//1641 -f 1641//1641 1783//1783 1643//1643 -f 1641//1641 1643//1643 1087//1087 -f 1087//1087 1643//1643 1089//1089 -f 1784//1784 1642//1642 1785//1785 -f 1785//1785 1642//1642 1643//1643 -f 1785//1785 1643//1643 1786//1786 -f 1786//1786 1643//1643 1783//1783 -f 1784//1784 1787//1787 1642//1642 -f 1642//1642 1787//1787 1645//1645 -f 1642//1642 1645//1645 1093//1093 -f 1093//1093 1645//1645 1097//1097 -f 1788//1788 1644//1644 1789//1789 -f 1789//1789 1644//1644 1645//1645 -f 1789//1789 1645//1645 1790//1790 -f 1790//1790 1645//1645 1787//1787 -f 1788//1788 1791//1791 1644//1644 -f 1644//1644 1791//1791 1647//1647 -f 1644//1644 1647//1647 1101//1101 -f 1101//1101 1647//1647 1103//1103 -f 1792//1792 1646//1646 1793//1793 -f 1793//1793 1646//1646 1647//1647 -f 1793//1793 1647//1647 1794//1794 -f 1794//1794 1647//1647 1791//1791 -f 1792//1792 1795//1795 1646//1646 -f 1646//1646 1795//1795 1648//1648 -f 1646//1646 1648//1648 1114//1114 -f 1114//1114 1648//1648 1113//1113 -f 1796//1796 1649//1649 1797//1797 -f 1797//1797 1649//1649 1648//1648 -f 1797//1797 1648//1648 1798//1798 -f 1798//1798 1648//1648 1795//1795 -f 1796//1796 1799//1799 1649//1649 -f 1649//1649 1799//1799 1650//1650 -f 1649//1649 1650//1650 1109//1109 -f 1109//1109 1650//1650 1107//1107 -f 1800//1800 1651//1651 1801//1801 -f 1801//1801 1651//1651 1650//1650 -f 1801//1801 1650//1650 1802//1802 -f 1802//1802 1650//1650 1799//1799 -f 1800//1800 1803//1803 1651//1651 -f 1651//1651 1803//1803 1652//1652 -f 1651//1651 1652//1652 1141//1141 -f 1141//1141 1652//1652 1139//1139 -f 1804//1804 1653//1653 1805//1805 -f 1805//1805 1653//1653 1652//1652 -f 1805//1805 1652//1652 1806//1806 -f 1806//1806 1652//1652 1803//1803 -f 1804//1804 1807//1807 1653//1653 -f 1653//1653 1807//1807 1654//1654 -f 1653//1653 1654//1654 1130//1130 -f 1130//1130 1654//1654 1131//1131 -f 1808//1808 1655//1655 1809//1809 -f 1809//1809 1655//1655 1654//1654 -f 1809//1809 1654//1654 1810//1810 -f 1810//1810 1654//1654 1807//1807 -f 1808//1808 1811//1811 1655//1655 -f 1655//1655 1811//1811 1656//1656 -f 1655//1655 1656//1656 1134//1134 -f 1134//1134 1656//1656 1128//1128 -f 1812//1812 1657//1657 1813//1813 -f 1813//1813 1657//1657 1656//1656 -f 1813//1813 1656//1656 1814//1814 -f 1814//1814 1656//1656 1811//1811 -f 1812//1812 1815//1815 1657//1657 -f 1657//1657 1815//1815 1659//1659 -f 1657//1657 1659//1659 1125//1125 -f 1125//1125 1659//1659 1126//1126 -f 1816//1816 1658//1658 1817//1817 -f 1817//1817 1658//1658 1659//1659 -f 1817//1817 1659//1659 1818//1818 -f 1818//1818 1659//1659 1815//1815 -f 1816//1816 1819//1819 1658//1658 -f 1658//1658 1819//1819 1660//1660 -f 1658//1658 1660//1660 1119//1119 -f 1119//1119 1660//1660 1118//1118 -f 1820//1820 1571//1571 1821//1821 -f 1821//1821 1571//1571 1660//1660 -f 1821//1821 1660//1660 1822//1822 -f 1822//1822 1660//1660 1819//1819 -f 1820//1820 1823//1823 1571//1571 -f 1571//1571 1823//1823 1430//1430 -f 1571//1571 1430//1430 1570//1570 -f 1570//1570 1430//1430 1429//1429 -f 1577//1577 1824//1824 1575//1575 -f 1575//1575 1824//1824 1574//1574 -f 1575//1575 1574//1574 1825//1825 -f 1825//1825 1574//1574 1573//1573 -f 1825//1825 1573//1573 1826//1826 -f 1826//1826 1573//1573 1430//1430 -f 1826//1826 1430//1430 1827//1827 -f 1827//1827 1430//1430 1823//1823 -f 1674//1674 1673//1673 1828//1828 -f 1829//1829 1830//1830 1831//1831 -f 1832//1832 1833//1833 1834//1834 -f 1835//1835 1836//1836 1837//1837 -f 1838//1838 1839//1839 1840//1840 -f 1841//1841 1842//1842 1843//1843 -f 1843//1843 1842//1842 1844//1844 -f 1843//1843 1844//1844 1845//1845 -f 1845//1845 1844//1844 1846//1846 -f 1845//1845 1846//1846 1847//1847 -f 1848//1848 1849//1849 1850//1850 -f 1850//1850 1849//1849 1851//1851 -f 1850//1850 1851//1851 1841//1841 -f 1852//1852 1853//1853 1840//1840 -f 1840//1840 1853//1853 1854//1854 -f 1840//1840 1854//1854 1838//1838 -f 1836//1836 1855//1855 1852//1852 -f 1852//1852 1855//1855 1856//1856 -f 1852//1852 1856//1856 1853//1853 -f 1857//1857 1858//1858 1859//1859 -f 1859//1859 1858//1858 1860//1860 -f 1835//1835 1837//1837 1861//1861 -f 1857//1857 1859//1859 1862//1862 -f 1862//1862 1859//1859 1863//1863 -f 1862//1862 1863//1863 1864//1864 -f 1865//1865 1866//1866 1863//1863 -f 1863//1863 1866//1866 1867//1867 -f 1863//1863 1867//1867 1864//1864 -f 1868//1868 1869//1869 1870//1870 -f 1869//1869 1871//1871 1870//1870 -f 1870//1870 1871//1871 1872//1872 -f 1870//1870 1872//1872 1865//1865 -f 1873//1873 1874//1874 1875//1875 -f 1875//1875 1874//1874 1876//1876 -f 1875//1875 1876//1876 1877//1877 -f 1877//1877 1876//1876 1878//1878 -f 1877//1877 1878//1878 1879//1879 -f 1880//1880 1873//1873 1881//1881 -f 1882//1882 1883//1883 1881//1881 -f 1881//1881 1883//1883 1884//1884 -f 1881//1881 1884//1884 1880//1880 -f 1885//1885 1886//1886 1887//1887 -f 1887//1887 1886//1886 1888//1888 -f 1885//1885 1887//1887 1889//1889 -f 1889//1889 1887//1887 1890//1890 -f 1889//1889 1890//1890 1891//1891 -f 1892//1892 1893//1893 1894//1894 -f 1894//1894 1895//1895 1890//1890 -f 1890//1890 1895//1895 1896//1896 -f 1890//1890 1896//1896 1891//1891 -f 1897//1897 1898//1898 1892//1892 -f 1892//1892 1898//1898 1899//1899 -f 1892//1892 1899//1899 1893//1893 -f 1832//1832 1834//1834 1900//1900 -f 1900//1900 1834//1834 1901//1901 -f 1900//1900 1901//1901 1902//1902 -f 1903//1903 1904//1904 1905//1905 -f 1905//1905 1904//1904 1906//1906 -f 1905//1905 1907//1907 1903//1903 -f 1903//1903 1907//1907 1908//1908 -f 1903//1903 1908//1908 1901//1901 -f 1901//1901 1908//1908 1909//1909 -f 1901//1901 1909//1909 1902//1902 -f 1906//1906 1904//1904 1910//1910 -f 1910//1910 1904//1904 1911//1911 -f 1910//1910 1911//1911 1912//1912 -f 1913//1913 1423//1423 1914//1914 -f 1914//1914 1423//1423 1422//1422 -f 1914//1914 1422//1422 1915//1915 -f 1913//1913 1916//1916 1423//1423 -f 1423//1423 1916//1916 1917//1917 -f 1423//1423 1917//1917 1419//1419 -f 1662//1662 1661//1661 1918//1918 -f 1918//1918 1919//1919 1662//1662 -f 1662//1662 1919//1919 1920//1920 -f 1662//1662 1920//1920 1425//1425 -f 1920//1920 1921//1921 1425//1425 -f 1425//1425 1921//1921 1922//1922 -f 1425//1425 1922//1922 1426//1426 -f 1426//1426 1922//1922 1923//1923 -f 1426//1426 1923//1923 1422//1422 -f 1422//1422 1923//1923 1924//1924 -f 1422//1422 1924//1924 1915//1915 -f 1517//1517 1515//1515 1925//1925 -f 1925//1925 1926//1926 1517//1517 -f 1517//1517 1926//1926 1927//1927 -f 1517//1517 1927//1927 1661//1661 -f 1661//1661 1927//1927 1928//1928 -f 1661//1661 1928//1928 1918//1918 -f 1929//1929 1520//1520 1930//1930 -f 1930//1930 1520//1520 1438//1438 -f 1930//1930 1438//1438 1931//1931 -f 1931//1931 1438//1438 1508//1508 -f 1931//1931 1508//1508 1932//1932 -f 1929//1929 1933//1933 1520//1520 -f 1520//1520 1933//1933 1934//1934 -f 1520//1520 1934//1934 1513//1513 -f 1513//1513 1934//1934 1935//1935 -f 1513//1513 1935//1935 1515//1515 -f 1515//1515 1935//1935 1936//1936 -f 1515//1515 1936//1936 1925//1925 -f 1496//1496 1495//1495 1937//1937 -f 1937//1937 1938//1938 1496//1496 -f 1496//1496 1938//1938 1939//1939 -f 1496//1496 1939//1939 1503//1503 -f 1503//1503 1939//1939 1940//1940 -f 1940//1940 1941//1941 1503//1503 -f 1503//1503 1941//1941 1942//1942 -f 1503//1503 1942//1942 1507//1507 -f 1507//1507 1942//1942 1943//1943 -f 1507//1507 1943//1943 1508//1508 -f 1508//1508 1943//1943 1944//1944 -f 1508//1508 1944//1944 1932//1932 -f 1500//1500 1492//1492 1945//1945 -f 1945//1945 1946//1946 1500//1500 -f 1500//1500 1946//1946 1947//1947 -f 1500//1500 1947//1947 1495//1495 -f 1495//1495 1947//1947 1948//1948 -f 1495//1495 1948//1948 1937//1937 -f 1487//1487 1949//1949 1492//1492 -f 1492//1492 1949//1949 1950//1950 -f 1492//1492 1950//1950 1945//1945 -f 1951//1951 1952//1952 1489//1489 -f 1952//1952 1953//1953 1489//1489 -f 1489//1489 1953//1953 1954//1954 -f 1489//1489 1954//1954 1487//1487 -f 1487//1487 1954//1954 1955//1955 -f 1487//1487 1955//1955 1949//1949 -f 1956//1956 1482//1482 1957//1957 -f 1957//1957 1482//1482 1441//1441 -f 1489//1489 1483//1483 1951//1951 -f 1951//1951 1483//1483 1482//1482 -f 1951//1951 1482//1482 1958//1958 -f 1958//1958 1482//1482 1956//1956 -f 1959//1959 1441//1441 1960//1960 -f 1960//1960 1441//1441 1474//1474 -f 1959//1959 1961//1961 1441//1441 -f 1441//1441 1961//1961 1962//1962 -f 1441//1441 1962//1962 1957//1957 -f 1963//1963 1964//1964 1471//1471 -f 1471//1471 1964//1964 1965//1965 -f 1471//1471 1965//1965 1473//1473 -f 1473//1473 1965//1965 1966//1966 -f 1473//1473 1966//1966 1474//1474 -f 1474//1474 1966//1966 1967//1967 -f 1474//1474 1967//1967 1960//1960 -f 1444//1444 1968//1968 1471//1471 -f 1471//1471 1968//1968 1969//1969 -f 1471//1471 1969//1969 1963//1963 -f 1459//1459 1461//1461 1970//1970 -f 1970//1970 1971//1971 1459//1459 -f 1459//1459 1971//1971 1972//1972 -f 1459//1459 1972//1972 1466//1466 -f 1972//1972 1973//1973 1466//1466 -f 1466//1466 1973//1973 1974//1974 -f 1466//1466 1974//1974 1444//1444 -f 1444//1444 1974//1974 1975//1975 -f 1444//1444 1975//1975 1968//1968 -f 1447//1447 1976//1976 1461//1461 -f 1461//1461 1976//1976 1977//1977 -f 1461//1461 1977//1977 1970//1970 -f 1978//1978 1979//1979 1449//1449 -f 1449//1449 1979//1979 1980//1980 -f 1449//1449 1980//1980 1447//1447 -f 1447//1447 1980//1980 1981//1981 -f 1447//1447 1981//1981 1976//1976 -f 1978//1978 1449//1449 1982//1982 -f 1982//1982 1449//1449 1452//1452 -f 1982//1982 1452//1452 1983//1983 -f 1983//1983 1452//1452 1454//1454 -f 1983//1983 1454//1454 1984//1984 -f 1984//1984 1454//1454 1456//1456 -f 1984//1984 1456//1456 1458//1458 -f 1579//1579 1985//1985 1986//1986 -f 1987//1987 1988//1988 1986//1986 -f 1986//1986 1988//1988 1989//1989 -f 1986//1986 1989//1989 1579//1579 -f 1830//1830 1829//1829 1986//1986 -f 1986//1986 1829//1829 1990//1990 -f 1986//1986 1990//1990 1987//1987 -f 1916//1916 1912//1912 1917//1917 -f 1917//1917 1912//1912 1911//1911 -f 1917//1917 1911//1911 1419//1419 -f 1419//1419 1911//1911 1904//1904 -f 1419//1419 1904//1904 1420//1420 -f 1420//1420 1904//1904 1903//1903 -f 1420//1420 1903//1903 1416//1416 -f 1416//1416 1903//1903 1901//1901 -f 1416//1416 1901//1901 1417//1417 -f 1417//1417 1901//1901 1834//1834 -f 1417//1417 1834//1834 1413//1413 -f 1413//1413 1834//1834 1414//1414 -f 1410//1410 1414//1414 1892//1892 -f 1892//1892 1414//1414 1834//1834 -f 1892//1892 1834//1834 1897//1897 -f 1897//1897 1834//1834 1833//1833 -f 1894//1894 1890//1890 1892//1892 -f 1892//1892 1890//1890 1411//1411 -f 1892//1892 1411//1411 1410//1410 -f 1405//1405 1404//1404 1887//1887 -f 1887//1887 1404//1404 1408//1408 -f 1887//1887 1408//1408 1890//1890 -f 1890//1890 1408//1408 1407//1407 -f 1890//1890 1407//1407 1411//1411 -f 1401//1401 1405//1405 1881//1881 -f 1881//1881 1405//1405 1887//1887 -f 1881//1881 1887//1887 1882//1882 -f 1882//1882 1887//1887 1888//1888 -f 1873//1873 1875//1875 1881//1881 -f 1881//1881 1875//1875 1402//1402 -f 1881//1881 1402//1402 1401//1401 -f 1396//1396 1395//1395 1877//1877 -f 1877//1877 1395//1395 1399//1399 -f 1877//1877 1399//1399 1875//1875 -f 1875//1875 1399//1399 1398//1398 -f 1875//1875 1398//1398 1402//1402 -f 1392//1392 1396//1396 1870//1870 -f 1870//1870 1396//1396 1877//1877 -f 1870//1870 1877//1877 1868//1868 -f 1868//1868 1877//1877 1879//1879 -f 1865//1865 1863//1863 1870//1870 -f 1870//1870 1863//1863 1393//1393 -f 1870//1870 1393//1393 1392//1392 -f 1387//1387 1386//1386 1859//1859 -f 1859//1859 1386//1386 1390//1390 -f 1859//1859 1390//1390 1863//1863 -f 1863//1863 1390//1390 1389//1389 -f 1863//1863 1389//1389 1393//1393 -f 1383//1383 1387//1387 1837//1837 -f 1837//1837 1387//1387 1859//1859 -f 1837//1837 1859//1859 1861//1861 -f 1861//1861 1859//1859 1860//1860 -f 1836//1836 1852//1852 1837//1837 -f 1837//1837 1852//1852 1384//1384 -f 1837//1837 1384//1384 1383//1383 -f 1378//1378 1377//1377 1840//1840 -f 1840//1840 1377//1377 1381//1381 -f 1840//1840 1381//1381 1852//1852 -f 1852//1852 1381//1381 1380//1380 -f 1852//1852 1380//1380 1384//1384 -f 1374//1374 1378//1378 1850//1850 -f 1850//1850 1378//1378 1840//1840 -f 1850//1850 1840//1840 1848//1848 -f 1848//1848 1840//1840 1839//1839 -f 1841//1841 1843//1843 1850//1850 -f 1850//1850 1843//1843 1375//1375 -f 1850//1850 1375//1375 1374//1374 -f 1369//1369 1368//1368 1845//1845 -f 1845//1845 1368//1368 1372//1372 -f 1845//1845 1372//1372 1843//1843 -f 1843//1843 1372//1372 1371//1371 -f 1843//1843 1371//1371 1375//1375 -f 1847//1847 1991//1991 1845//1845 -f 1845//1845 1991//1991 1992//1992 -f 1845//1845 1992//1992 1369//1369 -f 1993//1993 1366//1366 1992//1992 -f 1992//1992 1366//1366 1365//1365 -f 1992//1992 1365//1365 1369//1369 -f 1994//1994 1363//1363 1993//1993 -f 1993//1993 1363//1363 1362//1362 -f 1993//1993 1362//1362 1366//1366 -f 1995//1995 1360//1360 1994//1994 -f 1994//1994 1360//1360 1359//1359 -f 1994//1994 1359//1359 1363//1363 -f 1996//1996 1357//1357 1995//1995 -f 1995//1995 1357//1357 1356//1356 -f 1995//1995 1356//1356 1360//1360 -f 1997//1997 1354//1354 1996//1996 -f 1996//1996 1354//1354 1353//1353 -f 1996//1996 1353//1353 1357//1357 -f 1348//1348 1347//1347 1998//1998 -f 1998//1998 1347//1347 1351//1351 -f 1998//1998 1351//1351 1997//1997 -f 1997//1997 1351//1351 1350//1350 -f 1997//1997 1350//1350 1354//1354 -f 1344//1344 1999//1999 1345//1345 -f 1345//1345 1999//1999 2000//2000 -f 1345//1345 2000//2000 1341//1341 -f 1341//1341 2000//2000 1342//1342 -f 1338//1338 2001//2001 1339//1339 -f 1339//1339 2001//2001 2002//2002 -f 2003//2003 1336//1336 2002//2002 -f 2002//2002 1336//1336 1335//1335 -f 2002//2002 1335//1335 1339//1339 -f 2004//2004 1333//1333 2003//2003 -f 2003//2003 1333//1333 1332//1332 -f 2003//2003 1332//1332 1336//1336 -f 2005//2005 1330//1330 2004//2004 -f 2004//2004 1330//1330 1329//1329 -f 2004//2004 1329//1329 1333//1333 -f 2006//2006 1327//1327 2005//2005 -f 2005//2005 1327//1327 1326//1326 -f 2005//2005 1326//1326 1330//1330 -f 1321//1321 1320//1320 2007//2007 -f 2007//2007 1320//1320 1324//1324 -f 2007//2007 1324//1324 2006//2006 -f 2006//2006 1324//1324 1323//1323 -f 2006//2006 1323//1323 1327//1327 -f 1317//1317 2008//2008 1318//1318 -f 1318//1318 2008//2008 2009//2009 -f 1318//1318 2009//2009 1314//1314 -f 1314//1314 2009//2009 1315//1315 -f 1311//1311 2010//2010 1312//1312 -f 1312//1312 2010//2010 2011//2011 -f 2012//2012 1309//1309 2011//2011 -f 2011//2011 1309//1309 1308//1308 -f 2011//2011 1308//1308 1312//1312 -f 2013//2013 1306//1306 2012//2012 -f 2012//2012 1306//1306 1305//1305 -f 2012//2012 1305//1305 1309//1309 -f 2014//2014 1303//1303 2013//2013 -f 2013//2013 1303//1303 1302//1302 -f 2013//2013 1302//1302 1306//1306 -f 2015//2015 1300//1300 2014//2014 -f 2014//2014 1300//1300 1299//1299 -f 2014//2014 1299//1299 1303//1303 -f 1294//1294 1293//1293 2016//2016 -f 2016//2016 1293//1293 1297//1297 -f 2016//2016 1297//1297 2015//2015 -f 2015//2015 1297//1297 1296//1296 -f 2015//2015 1296//1296 1300//1300 -f 1290//1290 2017//2017 1291//1291 -f 1291//1291 2017//2017 2018//2018 -f 1291//1291 2018//2018 1287//1287 -f 1287//1287 2018//2018 1288//1288 -f 1284//1284 2019//2019 1285//1285 -f 1285//1285 2019//2019 2020//2020 -f 2021//2021 1282//1282 2020//2020 -f 2020//2020 1282//1282 1281//1281 -f 2020//2020 1281//1281 1285//1285 -f 2022//2022 1279//1279 2021//2021 -f 2021//2021 1279//1279 1278//1278 -f 2021//2021 1278//1278 1282//1282 -f 2023//2023 1276//1276 2022//2022 -f 2022//2022 1276//1276 1275//1275 -f 2022//2022 1275//1275 1279//1279 -f 2024//2024 1273//1273 2023//2023 -f 2023//2023 1273//1273 1272//1272 -f 2023//2023 1272//1272 1276//1276 -f 1267//1267 1266//1266 2025//2025 -f 2025//2025 1266//1266 1270//1270 -f 2025//2025 1270//1270 2024//2024 -f 2024//2024 1270//1270 1269//1269 -f 2024//2024 1269//1269 1273//1273 -f 1263//1263 2026//2026 1264//1264 -f 1264//1264 2026//2026 2027//2027 -f 1264//1264 2027//2027 1260//1260 -f 1260//1260 2027//2027 1261//1261 -f 1257//1257 2028//2028 1258//1258 -f 1258//1258 2028//2028 2029//2029 -f 2030//2030 1255//1255 2029//2029 -f 2029//2029 1255//1255 1254//1254 -f 2029//2029 1254//1254 1258//1258 -f 2031//2031 1252//1252 2030//2030 -f 2030//2030 1252//1252 1251//1251 -f 2030//2030 1251//1251 1255//1255 -f 1246//1246 1245//1245 2032//2032 -f 2032//2032 1245//1245 1249//1249 -f 2032//2032 1249//1249 2031//2031 -f 2031//2031 1249//1249 1248//1248 -f 2031//2031 1248//1248 1252//1252 -f 1242//1242 2033//2033 1243//1243 -f 1243//1243 2033//2033 2034//2034 -f 2035//2035 1240//1240 2034//2034 -f 2034//2034 1240//1240 1239//1239 -f 2034//2034 1239//1239 1243//1243 -f 1234//1234 1233//1233 2036//2036 -f 2036//2036 1233//1233 1237//1237 -f 2036//2036 1237//1237 2035//2035 -f 2035//2035 1237//1237 1236//1236 -f 2035//2035 1236//1236 1240//1240 -f 1230//1230 2037//2037 1231//1231 -f 1231//1231 2037//2037 2038//2038 -f 1225//1225 1224//1224 2039//2039 -f 2039//2039 1224//1224 1228//1228 -f 2039//2039 1228//1228 2038//2038 -f 2038//2038 1228//1228 1227//1227 -f 2038//2038 1227//1227 1231//1231 -f 1221//1221 2040//2040 1222//1222 -f 1222//1222 2040//2040 2041//2041 -f 1222//1222 2041//2041 1218//1218 -f 1218//1218 2041//2041 1219//1219 -f 1215//1215 2042//2042 1216//1216 -f 1216//1216 2042//2042 2043//2043 -f 2044//2044 1213//1213 2043//2043 -f 2043//2043 1213//1213 1212//1212 -f 2043//2043 1212//1212 1216//1216 -f 1207//1207 1206//1206 2045//2045 -f 2045//2045 1206//1206 1210//1210 -f 2045//2045 1210//1210 2044//2044 -f 2044//2044 1210//1210 1209//1209 -f 2044//2044 1209//1209 1213//1213 -f 1203//1203 2046//2046 1204//1204 -f 1204//1204 2046//2046 2047//2047 -f 1198//1198 1197//1197 2048//2048 -f 2048//2048 1197//1197 1201//1201 -f 2048//2048 1201//1201 2047//2047 -f 2047//2047 1201//1201 1200//1200 -f 2047//2047 1200//1200 1204//1204 -f 1194//1194 2049//2049 1195//1195 -f 1195//1195 2049//2049 2050//2050 -f 1195//1195 2050//2050 1191//1191 -f 1191//1191 2050//2050 1192//1192 -f 1188//1188 2051//2051 1189//1189 -f 1189//1189 2051//2051 2052//2052 -f 2053//2053 1186//1186 2052//2052 -f 2052//2052 1186//1186 1185//1185 -f 2052//2052 1185//1185 1189//1189 -f 2054//2054 1183//1183 2053//2053 -f 2053//2053 1183//1183 1182//1182 -f 2053//2053 1182//1182 1186//1186 -f 2055//2055 1180//1180 2054//2054 -f 2054//2054 1180//1180 1179//1179 -f 2054//2054 1179//1179 1183//1183 -f 2056//2056 1177//1177 2055//2055 -f 2055//2055 1177//1177 1176//1176 -f 2055//2055 1176//1176 1180//1180 -f 1171//1171 1170//1170 2057//2057 -f 2057//2057 1170//1170 1174//1174 -f 2057//2057 1174//1174 2056//2056 -f 2056//2056 1174//1174 1173//1173 -f 2056//2056 1173//1173 1177//1177 -f 1167//1167 2058//2058 1168//1168 -f 1168//1168 2058//2058 2059//2059 -f 1168//1168 2059//2059 1164//1164 -f 1164//1164 2059//2059 1165//1165 -f 1161//1161 2060//2060 1162//1162 -f 1162//1162 2060//2060 2061//2061 -f 2062//2062 1159//1159 2061//2061 -f 2061//2061 1159//1159 1158//1158 -f 2061//2061 1158//1158 1162//1162 -f 2063//2063 1156//1156 2062//2062 -f 2062//2062 1156//1156 1155//1155 -f 2062//2062 1155//1155 1159//1159 -f 2064//2064 1153//1153 2063//2063 -f 2063//2063 1153//1153 1152//1152 -f 2063//2063 1152//1152 1156//1156 -f 2065//2065 1150//1150 2064//2064 -f 2064//2064 1150//1150 1149//1149 -f 2064//2064 1149//1149 1153//1153 -f 1664//1664 1663//1663 2066//2066 -f 2066//2066 1663//1663 1147//1147 -f 2066//2066 1147//1147 2065//2065 -f 2065//2065 1147//1147 1146//1146 -f 2065//2065 1146//1146 1150//1150 -f 1665//1665 2067//2067 1666//1666 -f 1666//1666 2067//2067 2068//2068 -f 1669//1669 1668//1668 2068//2068 -f 2068//2068 1668//1668 1667//1667 -f 2068//2068 1667//1667 1666//1666 -f 1671//1671 1670//1670 2069//2069 -f 2069//2069 1670//1670 2070//2070 -f 1828//1828 1673//1673 2069//2069 -f 2069//2069 1673//1673 1672//1672 -f 2069//2069 1672//1672 1671//1671 -f 1674//1674 1828//1828 1675//1675 -f 1675//1675 1828//1828 2071//2071 -f 1675//1675 2071//2071 1676//1676 -f 1676//1676 2071//2071 2072//2072 -f 1676//1676 2072//2072 1677//1677 -f 2073//2073 1679//1679 2072//2072 -f 2072//2072 1679//1679 1678//1678 -f 2072//2072 1678//1678 1677//1677 -f 1683//1683 1682//1682 2074//2074 -f 2074//2074 1682//1682 1681//1681 -f 2074//2074 1681//1681 2073//2073 -f 2073//2073 1681//1681 1680//1680 -f 2073//2073 1680//1680 1679//1679 -f 1684//1684 2075//2075 1685//1685 -f 1685//1685 2075//2075 2076//2076 -f 1685//1685 2076//2076 1686//1686 -f 1686//1686 2076//2076 1687//1687 -f 2077//2077 1689//1689 2078//2078 -f 2078//2078 1689//1689 1688//1688 -f 2079//2079 2080//2080 1693//1693 -f 1693//1693 1692//1692 2079//2079 -f 2079//2079 1692//1692 1691//1691 -f 2079//2079 1691//1691 2077//2077 -f 2077//2077 1691//1691 1690//1690 -f 2077//2077 1690//1690 1689//1689 -f 2081//2081 2082//2082 1697//1697 -f 1697//1697 1696//1696 2081//2081 -f 2081//2081 1696//1696 1695//1695 -f 2081//2081 1695//1695 2080//2080 -f 2080//2080 1695//1695 1694//1694 -f 2080//2080 1694//1694 1693//1693 -f 1701//1701 1700//1700 2083//2083 -f 2083//2083 1700//1700 1699//1699 -f 2083//2083 1699//1699 2082//2082 -f 2082//2082 1699//1699 1698//1698 -f 2082//2082 1698//1698 1697//1697 -f 1702//1702 2084//2084 1703//1703 -f 1703//1703 2084//2084 2085//2085 -f 1703//1703 2085//2085 1704//1704 -f 1704//1704 2085//2085 1705//1705 -f 2086//2086 1707//1707 2087//2087 -f 2087//2087 1707//1707 1706//1706 -f 2088//2088 2089//2089 1711//1711 -f 1711//1711 1710//1710 2088//2088 -f 2088//2088 1710//1710 1709//1709 -f 2088//2088 1709//1709 2086//2086 -f 2086//2086 1709//1709 1708//1708 -f 2086//2086 1708//1708 1707//1707 -f 2090//2090 2091//2091 1715//1715 -f 1715//1715 1714//1714 2090//2090 -f 2090//2090 1714//1714 1713//1713 -f 2090//2090 1713//1713 2089//2089 -f 2089//2089 1713//1713 1712//1712 -f 2089//2089 1712//1712 1711//1711 -f 1719//1719 1718//1718 2092//2092 -f 2092//2092 1718//1718 1717//1717 -f 2092//2092 1717//1717 2091//2091 -f 2091//2091 1717//1717 1716//1716 -f 2091//2091 1716//1716 1715//1715 -f 1720//1720 2093//2093 1721//1721 -f 1721//1721 2093//2093 2094//2094 -f 1721//1721 2094//2094 1722//1722 -f 1722//1722 2094//2094 1723//1723 -f 2095//2095 1725//1725 2096//2096 -f 2096//2096 1725//1725 1724//1724 -f 2097//2097 2098//2098 1729//1729 -f 1729//1729 1728//1728 2097//2097 -f 2097//2097 1728//1728 1727//1727 -f 2097//2097 1727//1727 2095//2095 -f 2095//2095 1727//1727 1726//1726 -f 2095//2095 1726//1726 1725//1725 -f 1733//1733 1732//1732 2099//2099 -f 2099//2099 1732//1732 1731//1731 -f 2099//2099 1731//1731 2098//2098 -f 2098//2098 1731//1731 1730//1730 -f 2098//2098 1730//1730 1729//1729 -f 2100//2100 2101//2101 1737//1737 -f 1734//1734 2102//2102 1735//1735 -f 1735//1735 2102//2102 2100//2100 -f 1735//1735 2100//2100 1736//1736 -f 1736//1736 2100//2100 1737//1737 -f 1741//1741 1740//1740 2103//2103 -f 2103//2103 1740//1740 1739//1739 -f 2103//2103 1739//1739 2101//2101 -f 2101//2101 1739//1739 1738//1738 -f 2101//2101 1738//1738 1737//1737 -f 2104//2104 1743//1743 2105//2105 -f 2105//2105 1743//1743 1742//1742 -f 2106//2106 2107//2107 1747//1747 -f 1747//1747 1746//1746 2106//2106 -f 2106//2106 1746//1746 1745//1745 -f 2106//2106 1745//1745 2104//2104 -f 2104//2104 1745//1745 1744//1744 -f 2104//2104 1744//1744 1743//1743 -f 1751//1751 1750//1750 2108//2108 -f 2108//2108 1750//1750 1749//1749 -f 2108//2108 1749//1749 2107//2107 -f 2107//2107 1749//1749 1748//1748 -f 2107//2107 1748//1748 1747//1747 -f 2109//2109 1753//1753 2110//2110 -f 2110//2110 1753//1753 1752//1752 -f 2111//2111 1756//1756 2112//2112 -f 2112//2112 1756//1756 1755//1755 -f 2112//2112 1755//1755 2109//2109 -f 2109//2109 1755//1755 1754//1754 -f 2109//2109 1754//1754 1753//1753 -f 1759//1759 1758//1758 2111//2111 -f 2111//2111 1758//1758 1757//1757 -f 2111//2111 1757//1757 1756//1756 -f 2113//2113 2114//2114 1762//1762 -f 1766//1766 1763//1763 2115//2115 -f 2115//2115 1763//1763 1760//1760 -f 2115//2115 1760//1760 2114//2114 -f 2114//2114 1760//1760 1761//1761 -f 2114//2114 1761//1761 1762//1762 -f 1765//1765 2116//2116 1764//1764 -f 1764//1764 2116//2116 2117//2117 -f 1764//1764 2117//2117 1767//1767 -f 1767//1767 2117//2117 1770//1770 -f 1769//1769 2118//2118 1768//1768 -f 1768//1768 2118//2118 2119//2119 -f 2120//2120 1774//1774 2119//2119 -f 2119//2119 1774//1774 1771//1771 -f 2119//2119 1771//1771 1768//1768 -f 2121//2121 1772//1772 2120//2120 -f 2120//2120 1772//1772 1773//1773 -f 2120//2120 1773//1773 1774//1774 -f 2122//2122 1778//1778 2121//2121 -f 2121//2121 1778//1778 1775//1775 -f 2121//2121 1775//1775 1772//1772 -f 2123//2123 1776//1776 2122//2122 -f 2122//2122 1776//1776 1777//1777 -f 2122//2122 1777//1777 1778//1778 -f 1780//1780 1781//1781 2124//2124 -f 2124//2124 1781//1781 1782//1782 -f 2124//2124 1782//1782 2123//2123 -f 2123//2123 1782//1782 1779//1779 -f 2123//2123 1779//1779 1776//1776 -f 1783//1783 2125//2125 1786//1786 -f 1786//1786 2125//2125 2126//2126 -f 1786//1786 2126//2126 1785//1785 -f 1785//1785 2126//2126 1784//1784 -f 1787//1787 2127//2127 1790//1790 -f 1790//1790 2127//2127 2128//2128 -f 2129//2129 1788//1788 2128//2128 -f 2128//2128 1788//1788 1789//1789 -f 2128//2128 1789//1789 1790//1790 -f 2130//2130 1794//1794 2129//2129 -f 2129//2129 1794//1794 1791//1791 -f 2129//2129 1791//1791 1788//1788 -f 2131//2131 1792//1792 2130//2130 -f 2130//2130 1792//1792 1793//1793 -f 2130//2130 1793//1793 1794//1794 -f 2132//2132 1798//1798 2131//2131 -f 2131//2131 1798//1798 1795//1795 -f 2131//2131 1795//1795 1792//1792 -f 1802//1802 1799//1799 2133//2133 -f 2133//2133 1799//1799 1796//1796 -f 2133//2133 1796//1796 2132//2132 -f 2132//2132 1796//1796 1797//1797 -f 2132//2132 1797//1797 1798//1798 -f 1801//1801 2134//2134 1800//1800 -f 1800//1800 2134//2134 2135//2135 -f 1800//1800 2135//2135 1803//1803 -f 1803//1803 2135//2135 1806//1806 -f 1805//1805 2136//2136 1804//1804 -f 1804//1804 2136//2136 2137//2137 -f 2138//2138 1810//1810 2137//2137 -f 2137//2137 1810//1810 1807//1807 -f 2137//2137 1807//1807 1804//1804 -f 2139//2139 1808//1808 2138//2138 -f 2138//2138 1808//1808 1809//1809 -f 2138//2138 1809//1809 1810//1810 -f 2140//2140 1814//1814 2139//2139 -f 2139//2139 1814//1814 1811//1811 -f 2139//2139 1811//1811 1808//1808 -f 2141//2141 1812//1812 2140//2140 -f 2140//2140 1812//1812 1813//1813 -f 2140//2140 1813//1813 1814//1814 -f 1816//1816 1817//1817 2142//2142 -f 2142//2142 1817//1817 1818//1818 -f 2142//2142 1818//1818 2141//2141 -f 2141//2141 1818//1818 1815//1815 -f 2141//2141 1815//1815 1812//1812 -f 1819//1819 2143//2143 1822//1822 -f 1822//1822 2143//2143 2144//2144 -f 1822//1822 2144//2144 1821//1821 -f 1821//1821 2144//2144 1820//1820 -f 1823//1823 2145//2145 1827//1827 -f 1827//1827 2145//2145 2146//2146 -f 2147//2147 1825//1825 2146//2146 -f 2146//2146 1825//1825 1826//1826 -f 2146//2146 1826//1826 1827//1827 -f 1579//1579 1578//1578 1985//1985 -f 1985//1985 1578//1578 1576//1576 -f 1985//1985 1576//1576 2147//2147 -f 2147//2147 1576//1576 1575//1575 -f 2147//2147 1575//1575 1825//1825 -f 1991//1991 600//600 1992//1992 -f 1992//1992 600//600 599//599 -f 1992//1992 599//599 1993//1993 -f 1993//1993 599//599 597//597 -f 1993//1993 597//597 1994//1994 -f 597//597 595//595 1994//1994 -f 1994//1994 595//595 594//594 -f 1994//1994 594//594 1995//1995 -f 1995//1995 594//594 601//601 -f 1995//1995 601//601 1996//1996 -f 601//601 603//603 1996//1996 -f 1996//1996 603//603 605//605 -f 1996//1996 605//605 1997//1997 -f 1997//1997 605//605 606//606 -f 1997//1997 606//606 1998//1998 -f 1998//1998 606//606 608//608 -f 608//608 609//609 1998//1998 -f 1998//1998 609//609 1999//1999 -f 1998//1998 1999//1999 1348//1348 -f 1348//1348 1999//1999 1344//1344 -f 610//610 2000//2000 591//591 -f 591//591 2000//2000 1999//1999 -f 591//591 1999//1999 592//592 -f 592//592 1999//1999 609//609 -f 610//610 612//612 2000//2000 -f 2000//2000 612//612 2001//2001 -f 2000//2000 2001//2001 1342//1342 -f 1342//1342 2001//2001 1338//1338 -f 612//612 615//615 2001//2001 -f 2001//2001 615//615 617//617 -f 2001//2001 617//617 2002//2002 -f 2002//2002 617//617 618//618 -f 2002//2002 618//618 2003//2003 -f 618//618 620//620 2003//2003 -f 2003//2003 620//620 622//622 -f 2003//2003 622//622 2004//2004 -f 2004//2004 622//622 624//624 -f 2004//2004 624//624 2005//2005 -f 624//624 627//627 2005//2005 -f 2005//2005 627//627 629//629 -f 2005//2005 629//629 2006//2006 -f 2006//2006 629//629 631//631 -f 2006//2006 631//631 2007//2007 -f 2007//2007 631//631 633//633 -f 633//633 635//635 2007//2007 -f 2007//2007 635//635 2008//2008 -f 2007//2007 2008//2008 1321//1321 -f 1321//1321 2008//2008 1317//1317 -f 641//641 2009//2009 639//639 -f 639//639 2009//2009 2008//2008 -f 639//639 2008//2008 637//637 -f 637//637 2008//2008 635//635 -f 641//641 643//643 2009//2009 -f 2009//2009 643//643 2010//2010 -f 2009//2009 2010//2010 1315//1315 -f 1315//1315 2010//2010 1311//1311 -f 643//643 645//645 2010//2010 -f 2010//2010 645//645 647//647 -f 2010//2010 647//647 2011//2011 -f 2011//2011 647//647 649//649 -f 2011//2011 649//649 2012//2012 -f 649//649 651//651 2012//2012 -f 2012//2012 651//651 653//653 -f 2012//2012 653//653 2013//2013 -f 2013//2013 653//653 655//655 -f 2013//2013 655//655 2014//2014 -f 655//655 658//658 2014//2014 -f 2014//2014 658//658 660//660 -f 2014//2014 660//660 2015//2015 -f 2015//2015 660//660 662//662 -f 2015//2015 662//662 2016//2016 -f 2016//2016 662//662 664//664 -f 664//664 665//665 2016//2016 -f 2016//2016 665//665 2017//2017 -f 2016//2016 2017//2017 1294//1294 -f 1294//1294 2017//2017 1290//1290 -f 671//671 2018//2018 669//669 -f 669//669 2018//2018 2017//2017 -f 669//669 2017//2017 667//667 -f 667//667 2017//2017 665//665 -f 671//671 673//673 2018//2018 -f 2018//2018 673//673 2019//2019 -f 2018//2018 2019//2019 1288//1288 -f 1288//1288 2019//2019 1284//1284 -f 673//673 675//675 2019//2019 -f 2019//2019 675//675 677//677 -f 2019//2019 677//677 2020//2020 -f 2020//2020 677//677 679//679 -f 2020//2020 679//679 2021//2021 -f 679//679 681//681 2021//2021 -f 2021//2021 681//681 683//683 -f 2021//2021 683//683 2022//2022 -f 2022//2022 683//683 685//685 -f 2022//2022 685//685 2023//2023 -f 685//685 688//688 2023//2023 -f 2023//2023 688//688 690//690 -f 2023//2023 690//690 2024//2024 -f 2024//2024 690//690 692//692 -f 2024//2024 692//692 2025//2025 -f 2025//2025 692//692 694//694 -f 694//694 695//695 2025//2025 -f 2025//2025 695//695 2026//2026 -f 2025//2025 2026//2026 1267//1267 -f 1267//1267 2026//2026 1263//1263 -f 701//701 2027//2027 699//699 -f 699//699 2027//2027 2026//2026 -f 699//699 2026//2026 697//697 -f 697//697 2026//2026 695//695 -f 701//701 703//703 2027//2027 -f 2027//2027 703//703 2028//2028 -f 2027//2027 2028//2028 1261//1261 -f 1261//1261 2028//2028 1257//1257 -f 703//703 705//705 2028//2028 -f 2028//2028 705//705 707//707 -f 2028//2028 707//707 2029//2029 -f 2029//2029 707//707 709//709 -f 2029//2029 709//709 2030//2030 -f 718//718 2032//2032 715//715 -f 715//715 2032//2032 2031//2031 -f 715//715 2031//2031 713//713 -f 713//713 2031//2031 2030//2030 -f 713//713 2030//2030 711//711 -f 711//711 2030//2030 709//709 -f 718//718 720//720 2032//2032 -f 2032//2032 720//720 2033//2033 -f 2032//2032 2033//2033 1246//1246 -f 1246//1246 2033//2033 1242//1242 -f 720//720 722//722 2033//2033 -f 2033//2033 722//722 740//740 -f 2033//2033 740//740 2034//2034 -f 2034//2034 740//740 739//739 -f 2034//2034 739//739 2035//2035 -f 733//733 2036//2036 735//735 -f 735//735 2036//2036 2035//2035 -f 735//735 2035//2035 737//737 -f 737//737 2035//2035 739//739 -f 733//733 731//731 2036//2036 -f 2036//2036 731//731 2037//2037 -f 2036//2036 2037//2037 1234//1234 -f 1234//1234 2037//2037 1230//1230 -f 731//731 729//729 2037//2037 -f 2037//2037 729//729 727//727 -f 2037//2037 727//727 2038//2038 -f 2038//2038 727//727 725//725 -f 2038//2038 725//725 2039//2039 -f 2039//2039 725//725 772//772 -f 772//772 771//771 2039//2039 -f 2039//2039 771//771 2040//2040 -f 2039//2039 2040//2040 1225//1225 -f 1225//1225 2040//2040 1221//1221 -f 765//765 2041//2041 767//767 -f 767//767 2041//2041 2040//2040 -f 767//767 2040//2040 769//769 -f 769//769 2040//2040 771//771 -f 765//765 763//763 2041//2041 -f 2041//2041 763//763 2042//2042 -f 2041//2041 2042//2042 1219//1219 -f 1219//1219 2042//2042 1215//1215 -f 763//763 761//761 2042//2042 -f 2042//2042 761//761 759//759 -f 2042//2042 759//759 2043//2043 -f 2043//2043 759//759 757//757 -f 2043//2043 757//757 2044//2044 -f 751//751 2045//2045 753//753 -f 753//753 2045//2045 2044//2044 -f 753//753 2044//2044 755//755 -f 755//755 2044//2044 757//757 -f 751//751 749//749 2045//2045 -f 2045//2045 749//749 2046//2046 -f 2045//2045 2046//2046 1207//1207 -f 1207//1207 2046//2046 1203//1203 -f 749//749 747//747 2046//2046 -f 2046//2046 747//747 745//745 -f 2046//2046 745//745 2047//2047 -f 2047//2047 745//745 743//743 -f 2047//2047 743//743 2048//2048 -f 2048//2048 743//743 742//742 -f 742//742 773//773 2048//2048 -f 2048//2048 773//773 2049//2049 -f 2048//2048 2049//2049 1198//1198 -f 1198//1198 2049//2049 1194//1194 -f 779//779 2050//2050 777//777 -f 777//777 2050//2050 2049//2049 -f 777//777 2049//2049 775//775 -f 775//775 2049//2049 773//773 -f 779//779 781//781 2050//2050 -f 2050//2050 781//781 2051//2051 -f 2050//2050 2051//2051 1192//1192 -f 1192//1192 2051//2051 1188//1188 -f 781//781 783//783 2051//2051 -f 2051//2051 783//783 785//785 -f 2051//2051 785//785 2052//2052 -f 2052//2052 785//785 787//787 -f 2052//2052 787//787 2053//2053 -f 787//787 789//789 2053//2053 -f 2053//2053 789//789 791//791 -f 2053//2053 791//791 2054//2054 -f 2054//2054 791//791 793//793 -f 2054//2054 793//793 2055//2055 -f 793//793 796//796 2055//2055 -f 2055//2055 796//796 798//798 -f 2055//2055 798//798 2056//2056 -f 2056//2056 798//798 800//800 -f 2056//2056 800//800 2057//2057 -f 2057//2057 800//800 802//802 -f 802//802 803//803 2057//2057 -f 2057//2057 803//803 2058//2058 -f 2057//2057 2058//2058 1171//1171 -f 1171//1171 2058//2058 1167//1167 -f 809//809 2059//2059 807//807 -f 807//807 2059//2059 2058//2058 -f 807//807 2058//2058 805//805 -f 805//805 2058//2058 803//803 -f 809//809 811//811 2059//2059 -f 2059//2059 811//811 2060//2060 -f 2059//2059 2060//2060 1165//1165 -f 1165//1165 2060//2060 1161//1161 -f 811//811 813//813 2060//2060 -f 2060//2060 813//813 815//815 -f 2060//2060 815//815 2061//2061 -f 2061//2061 815//815 817//817 -f 2061//2061 817//817 2062//2062 -f 817//817 819//819 2062//2062 -f 2062//2062 819//819 821//821 -f 2062//2062 821//821 2063//2063 -f 2063//2063 821//821 823//823 -f 2063//2063 823//823 2064//2064 -f 823//823 826//826 2064//2064 -f 2064//2064 826//826 828//828 -f 2064//2064 828//828 2065//2065 -f 2065//2065 828//828 830//830 -f 2065//2065 830//830 2066//2066 -f 2066//2066 830//830 832//832 -f 832//832 834//834 2066//2066 -f 2066//2066 834//834 2067//2067 -f 2066//2066 2067//2067 1664//1664 -f 1664//1664 2067//2067 1665//1665 -f 840//840 2068//2068 838//838 -f 838//838 2068//2068 2067//2067 -f 838//838 2067//2067 836//836 -f 836//836 2067//2067 834//834 -f 840//840 842//842 2068//2068 -f 2068//2068 842//842 2070//2070 -f 2068//2068 2070//2070 1669//1669 -f 1669//1669 2070//2070 1670//1670 -f 842//842 844//844 2070//2070 -f 2070//2070 844//844 846//846 -f 2070//2070 846//846 2069//2069 -f 2069//2069 846//846 848//848 -f 2069//2069 848//848 1828//1828 -f 848//848 850//850 1828//1828 -f 1828//1828 850//850 851//851 -f 1828//1828 851//851 2071//2071 -f 2071//2071 851//851 853//853 -f 2071//2071 853//853 2072//2072 -f 853//853 856//856 2072//2072 -f 2072//2072 856//856 858//858 -f 2072//2072 858//858 2073//2073 -f 2073//2073 858//858 860//860 -f 2073//2073 860//860 2074//2074 -f 2074//2074 860//860 862//862 -f 862//862 864//864 2074//2074 -f 2074//2074 864//864 2075//2075 -f 2074//2074 2075//2075 1683//1683 -f 1683//1683 2075//2075 1684//1684 -f 870//870 2076//2076 868//868 -f 868//868 2076//2076 2075//2075 -f 868//868 2075//2075 866//866 -f 866//866 2075//2075 864//864 -f 870//870 872//872 2076//2076 -f 2076//2076 872//872 2078//2078 -f 2076//2076 2078//2078 1687//1687 -f 1687//1687 2078//2078 1688//1688 -f 872//872 874//874 2078//2078 -f 2078//2078 874//874 876//876 -f 2078//2078 876//876 2077//2077 -f 2077//2077 876//876 878//878 -f 2077//2077 878//878 2079//2079 -f 878//878 880//880 2079//2079 -f 2079//2079 880//880 881//881 -f 2079//2079 881//881 2080//2080 -f 2080//2080 881//881 883//883 -f 2080//2080 883//883 2081//2081 -f 883//883 886//886 2081//2081 -f 2081//2081 886//886 888//888 -f 2081//2081 888//888 2082//2082 -f 2082//2082 888//888 890//890 -f 2082//2082 890//890 2083//2083 -f 2083//2083 890//890 892//892 -f 892//892 894//894 2083//2083 -f 2083//2083 894//894 2084//2084 -f 2083//2083 2084//2084 1701//1701 -f 1701//1701 2084//2084 1702//1702 -f 900//900 2085//2085 898//898 -f 898//898 2085//2085 2084//2084 -f 898//898 2084//2084 896//896 -f 896//896 2084//2084 894//894 -f 900//900 902//902 2085//2085 -f 2085//2085 902//902 2087//2087 -f 2085//2085 2087//2087 1705//1705 -f 1705//1705 2087//2087 1706//1706 -f 902//902 904//904 2087//2087 -f 2087//2087 904//904 906//906 -f 2087//2087 906//906 2086//2086 -f 2086//2086 906//906 907//907 -f 2086//2086 907//907 2088//2088 -f 907//907 909//909 2088//2088 -f 2088//2088 909//909 911//911 -f 2088//2088 911//911 2089//2089 -f 2089//2089 911//911 913//913 -f 2089//2089 913//913 2090//2090 -f 913//913 916//916 2090//2090 -f 2090//2090 916//916 918//918 -f 2090//2090 918//918 2091//2091 -f 2091//2091 918//918 920//920 -f 2091//2091 920//920 2092//2092 -f 2092//2092 920//920 930//930 -f 930//930 929//929 2092//2092 -f 2092//2092 929//929 2093//2093 -f 2092//2092 2093//2093 1719//1719 -f 1719//1719 2093//2093 1720//1720 -f 923//923 2094//2094 925//925 -f 925//925 2094//2094 2093//2093 -f 925//925 2093//2093 927//927 -f 927//927 2093//2093 929//929 -f 923//923 922//922 2094//2094 -f 2094//2094 922//922 2096//2096 -f 2094//2094 2096//2096 1723//1723 -f 1723//1723 2096//2096 1724//1724 -f 922//922 933//933 2096//2096 -f 2096//2096 933//933 935//935 -f 2096//2096 935//935 2095//2095 -f 2095//2095 935//935 937//937 -f 2095//2095 937//937 2097//2097 -f 945//945 2099//2099 943//943 -f 943//943 2099//2099 2098//2098 -f 943//943 2098//2098 940//940 -f 940//940 2098//2098 2097//2097 -f 940//940 2097//2097 939//939 -f 939//939 2097//2097 937//937 -f 945//945 947//947 2099//2099 -f 2099//2099 947//947 2102//2102 -f 2099//2099 2102//2102 1733//1733 -f 1733//1733 2102//2102 1734//1734 -f 947//947 950//950 2102//2102 -f 2102//2102 950//950 952//952 -f 2102//2102 952//952 2100//2100 -f 2100//2100 952//952 954//954 -f 2100//2100 954//954 2101//2101 -f 958//958 2103//2103 960//960 -f 960//960 2103//2103 2101//2101 -f 960//960 2101//2101 961//961 -f 961//961 2101//2101 954//954 -f 958//958 957//957 2103//2103 -f 2103//2103 957//957 2105//2105 -f 2103//2103 2105//2105 1741//1741 -f 1741//1741 2105//2105 1742//1742 -f 957//957 962//962 2105//2105 -f 2105//2105 962//962 964//964 -f 2105//2105 964//964 2104//2104 -f 2104//2104 964//964 967//967 -f 2104//2104 967//967 2106//2106 -f 976//976 2108//2108 973//973 -f 973//973 2108//2108 2107//2107 -f 973//973 2107//2107 971//971 -f 971//971 2107//2107 2106//2106 -f 971//971 2106//2106 969//969 -f 969//969 2106//2106 967//967 -f 976//976 978//978 2108//2108 -f 2108//2108 978//978 2110//2110 -f 2108//2108 2110//2110 1751//1751 -f 1751//1751 2110//2110 1752//1752 -f 978//978 980//980 2110//2110 -f 2110//2110 980//980 990//990 -f 2110//2110 990//990 2109//2109 -f 2109//2109 990//990 989//989 -f 2109//2109 989//989 2112//2112 -f 983//983 2111//2111 985//985 -f 985//985 2111//2111 2112//2112 -f 985//985 2112//2112 987//987 -f 987//987 2112//2112 989//989 -f 983//983 982//982 2111//2111 -f 2111//2111 982//982 2113//2113 -f 2111//2111 2113//2113 1759//1759 -f 1759//1759 2113//2113 1762//1762 -f 982//982 993//993 2113//2113 -f 2113//2113 993//993 995//995 -f 2113//2113 995//995 2114//2114 -f 2114//2114 995//995 997//997 -f 2114//2114 997//997 2115//2115 -f 2115//2115 997//997 999//999 -f 999//999 1000//1000 2115//2115 -f 2115//2115 1000//1000 2116//2116 -f 2115//2115 2116//2116 1766//1766 -f 1766//1766 2116//2116 1765//1765 -f 1007//1007 2117//2117 1005//1005 -f 1005//1005 2117//2117 2116//2116 -f 1005//1005 2116//2116 1003//1003 -f 1003//1003 2116//2116 1000//1000 -f 1007//1007 1008//1008 2117//2117 -f 2117//2117 1008//1008 2118//2118 -f 2117//2117 2118//2118 1770//1770 -f 1770//1770 2118//2118 1769//1769 -f 1008//1008 1011//1011 2118//2118 -f 2118//2118 1011//1011 1013//1013 -f 2118//2118 1013//1013 2119//2119 -f 2119//2119 1013//1013 1015//1015 -f 2119//2119 1015//1015 2120//2120 -f 1015//1015 1017//1017 2120//2120 -f 2120//2120 1017//1017 1018//1018 -f 2120//2120 1018//1018 2121//2121 -f 2121//2121 1018//1018 1021//1021 -f 2121//2121 1021//1021 2122//2122 -f 1021//1021 1023//1023 2122//2122 -f 2122//2122 1023//1023 1025//1025 -f 2122//2122 1025//1025 2123//2123 -f 2123//2123 1025//1025 1028//1028 -f 2123//2123 1028//1028 2124//2124 -f 2124//2124 1028//1028 1030//1030 -f 1030//1030 1032//1032 2124//2124 -f 2124//2124 1032//1032 2125//2125 -f 2124//2124 2125//2125 1780//1780 -f 1780//1780 2125//2125 1783//1783 -f 1036//1036 2126//2126 1038//1038 -f 1038//1038 2126//2126 2125//2125 -f 1038//1038 2125//2125 1039//1039 -f 1039//1039 2125//2125 1032//1032 -f 1036//1036 1035//1035 2126//2126 -f 2126//2126 1035//1035 2127//2127 -f 2126//2126 2127//2127 1784//1784 -f 1784//1784 2127//2127 1787//1787 -f 1035//1035 1040//1040 2127//2127 -f 2127//2127 1040//1040 1042//1042 -f 2127//2127 1042//1042 2128//2128 -f 2128//2128 1042//1042 1044//1044 -f 2128//2128 1044//1044 2129//2129 -f 1044//1044 1046//1046 2129//2129 -f 2129//2129 1046//1046 1049//1049 -f 2129//2129 1049//1049 2130//2130 -f 2130//2130 1049//1049 1051//1051 -f 2130//2130 1051//1051 2131//2131 -f 1051//1051 1054//1054 2131//2131 -f 2131//2131 1054//1054 1056//1056 -f 2131//2131 1056//1056 2132//2132 -f 2132//2132 1056//1056 1058//1058 -f 2132//2132 1058//1058 2133//2133 -f 2133//2133 1058//1058 1068//1068 -f 1068//1068 1067//1067 2133//2133 -f 2133//2133 1067//1067 2134//2134 -f 2133//2133 2134//2134 1802//1802 -f 1802//1802 2134//2134 1801//1801 -f 1061//1061 2135//2135 1063//1063 -f 1063//1063 2135//2135 2134//2134 -f 1063//1063 2134//2134 1065//1065 -f 1065//1065 2134//2134 1067//1067 -f 1061//1061 1060//1060 2135//2135 -f 2135//2135 1060//1060 2136//2136 -f 2135//2135 2136//2136 1806//1806 -f 1806//1806 2136//2136 1805//1805 -f 1060//1060 1071//1071 2136//2136 -f 2136//2136 1071//1071 1073//1073 -f 2136//2136 1073//1073 2137//2137 -f 2137//2137 1073//1073 1075//1075 -f 2137//2137 1075//1075 2138//2138 -f 1075//1075 1077//1077 2138//2138 -f 2138//2138 1077//1077 1078//1078 -f 2138//2138 1078//1078 2139//2139 -f 2139//2139 1078//1078 1081//1081 -f 2139//2139 1081//1081 2140//2140 -f 1081//1081 1083//1083 2140//2140 -f 2140//2140 1083//1083 1085//1085 -f 2140//2140 1085//1085 2141//2141 -f 2141//2141 1085//1085 1088//1088 -f 2141//2141 1088//1088 2142//2142 -f 2142//2142 1088//1088 1090//1090 -f 1090//1090 1092//1092 2142//2142 -f 2142//2142 1092//1092 2143//2143 -f 2142//2142 2143//2143 1816//1816 -f 1816//1816 2143//2143 1819//1819 -f 1096//1096 2144//2144 1098//1098 -f 1098//1098 2144//2144 2143//2143 -f 1098//1098 2143//2143 1099//1099 -f 1099//1099 2143//2143 1092//1092 -f 1096//1096 1095//1095 2144//2144 -f 2144//2144 1095//1095 2145//2145 -f 2144//2144 2145//2145 1820//1820 -f 1820//1820 2145//2145 1823//1823 -f 1095//1095 1100//1100 2145//2145 -f 2145//2145 1100//1100 1102//1102 -f 2145//2145 1102//1102 2146//2146 -f 2146//2146 1102//1102 1104//1104 -f 2146//2146 1104//1104 2147//2147 -f 1104//1104 1106//1106 2147//2147 -f 2147//2147 1106//1106 1112//1112 -f 2147//2147 1112//1112 1985//1985 -f 1985//1985 1112//1112 1110//1110 -f 1985//1985 1110//1110 1986//1986 -f 1138//1138 2148//2148 1140//1140 -f 1140//1140 2148//2148 2149//2149 -f 1140//1140 2149//2149 1142//1142 -f 1142//1142 2149//2149 1831//1831 -f 1142//1142 1831//1831 1144//1144 -f 1144//1144 1831//1831 1830//1830 -f 1144//1144 1830//1830 1145//1145 -f 1145//1145 1830//1830 1986//1986 -f 1145//1145 1986//1986 1108//1108 -f 1108//1108 1986//1986 1110//1110 -f 1980//1980 1979//1979 2150//2150 -f 2150//2150 1979//1979 1978//1978 -f 1978//1978 1982//1982 2150//2150 -f 2150//2150 1982//1982 1983//1983 -f 2150//2150 1983//1983 2151//2151 -f 2151//2151 1983//1983 1984//1984 -f 2151//2151 1984//1984 1458//1458 -f 1970//1970 1977//1977 2152//2152 -f 2152//2152 1977//1977 1976//1976 -f 2152//2152 1976//1976 2150//2150 -f 2150//2150 1976//1976 1981//1981 -f 2150//2150 1981//1981 1980//1980 -f 2153//2153 1975//1975 1974//1974 -f 1974//1974 1973//1973 2153//2153 -f 2153//2153 1973//1973 1972//1972 -f 2153//2153 1972//1972 2152//2152 -f 2152//2152 1972//1972 1971//1971 -f 2152//2152 1971//1971 1970//1970 -f 1964//1964 1963//1963 2154//2154 -f 2154//2154 1963//1963 1969//1969 -f 2154//2154 1969//1969 2153//2153 -f 2153//2153 1969//1969 1968//1968 -f 2153//2153 1968//1968 1975//1975 -f 1960//1960 1967//1967 2155//2155 -f 2155//2155 1967//1967 1966//1966 -f 2155//2155 1966//1966 2154//2154 -f 2154//2154 1966//1966 1965//1965 -f 2154//2154 1965//1965 1964//1964 -f 2156//2156 1958//1958 1956//1956 -f 1962//1962 1961//1961 2155//2155 -f 2155//2155 1961//1961 1959//1959 -f 2155//2155 1959//1959 1960//1960 -f 2156//2156 1956//1956 2155//2155 -f 2155//2155 1956//1956 1957//1957 -f 2155//2155 1957//1957 1962//1962 -f 1949//1949 1955//1955 2157//2157 -f 2157//2157 1955//1955 1954//1954 -f 1954//1954 1953//1953 2157//2157 -f 2157//2157 1953//1953 1952//1952 -f 2157//2157 1952//1952 2156//2156 -f 2156//2156 1952//1952 1951//1951 -f 2156//2156 1951//1951 1958//1958 -f 1947//1947 1946//1946 2158//2158 -f 2158//2158 1946//1946 1945//1945 -f 2158//2158 1945//1945 2157//2157 -f 2157//2157 1945//1945 1950//1950 -f 2157//2157 1950//1950 1949//1949 -f 1939//1939 1938//1938 2159//2159 -f 2159//2159 1938//1938 1937//1937 -f 2159//2159 1937//1937 2158//2158 -f 2158//2158 1937//1937 1948//1948 -f 2158//2158 1948//1948 1947//1947 -f 1942//1942 1941//1941 2159//2159 -f 2159//2159 1941//1941 1940//1940 -f 2159//2159 1940//1940 1939//1939 -f 1931//1931 1932//1932 2160//2160 -f 2160//2160 1932//1932 1944//1944 -f 2160//2160 1944//1944 2159//2159 -f 2159//2159 1944//1944 1943//1943 -f 2159//2159 1943//1943 1942//1942 -f 2161//2161 1935//1935 1934//1934 -f 1934//1934 1933//1933 2161//2161 -f 2161//2161 1933//1933 1929//1929 -f 2161//2161 1929//1929 2160//2160 -f 2160//2160 1929//1929 1930//1930 -f 2160//2160 1930//1930 1931//1931 -f 1928//1928 1927//1927 1457//1457 -f 1457//1457 1927//1927 1926//1926 -f 1457//1457 1926//1926 1458//1458 -f 1458//1458 1926//1926 1925//1925 -f 1458//1458 1925//1925 2161//2161 -f 2161//2161 1925//1925 1936//1936 -f 2161//2161 1936//1936 1935//1935 -f 1923//1923 1922//1922 1446//1446 -f 1446//1446 1922//1922 1921//1921 -f 1446//1446 1921//1921 1448//1448 -f 1448//1448 1921//1921 1450//1450 -f 1450//1450 1921//1921 1920//1920 -f 1450//1450 1920//1920 1451//1451 -f 1920//1920 1919//1919 1451//1451 -f 1451//1451 1919//1919 1918//1918 -f 1451//1451 1918//1918 1453//1453 -f 1453//1453 1918//1918 1928//1928 -f 1453//1453 1928//1928 1455//1455 -f 1455//1455 1928//1928 1457//1457 -f 1913//1913 1914//1914 1463//1463 -f 1463//1463 1914//1914 1915//1915 -f 1463//1463 1915//1915 1464//1464 -f 1464//1464 1915//1915 1924//1924 -f 1464//1464 1924//1924 1465//1465 -f 1465//1465 1924//1924 1923//1923 -f 1465//1465 1923//1923 1445//1445 -f 1445//1445 1923//1923 1446//1446 -f 1442//1442 1905//1905 1443//1443 -f 1443//1443 1905//1905 1906//1906 -f 1443//1443 1906//1906 1467//1467 -f 1467//1467 1906//1906 1468//1468 -f 1468//1468 1906//1906 1910//1910 -f 1468//1468 1910//1910 1469//1469 -f 1910//1910 1912//1912 1469//1469 -f 1469//1469 1912//1912 1916//1916 -f 1469//1469 1916//1916 1460//1460 -f 1460//1460 1916//1916 1913//1913 -f 1460//1460 1913//1913 1462//1462 -f 1462//1462 1913//1913 1463//1463 -f 1832//1832 1900//1900 1478//1478 -f 1478//1478 1900//1900 1902//1902 -f 1478//1478 1902//1902 1472//1472 -f 1472//1472 1902//1902 1909//1909 -f 1472//1472 1909//1909 1470//1470 -f 1470//1470 1909//1909 1908//1908 -f 1470//1470 1908//1908 1442//1442 -f 1442//1442 1908//1908 1907//1907 -f 1442//1442 1907//1907 1905//1905 -f 1898//1898 1479//1479 1899//1899 -f 1899//1899 1479//1479 1893//1893 -f 1478//1478 1477//1477 1832//1832 -f 1832//1832 1477//1477 1476//1476 -f 1832//1832 1476//1476 1833//1833 -f 1833//1833 1476//1476 1475//1475 -f 1833//1833 1475//1475 1897//1897 -f 1897//1897 1475//1475 1481//1481 -f 1897//1897 1481//1481 1898//1898 -f 1898//1898 1481//1481 1480//1480 -f 1898//1898 1480//1480 1479//1479 -f 1486//1486 1894//1894 1439//1439 -f 1439//1439 1894//1894 1893//1893 -f 1439//1439 1893//1893 1440//1440 -f 1440//1440 1893//1893 1479//1479 -f 1491//1491 1889//1889 1485//1485 -f 1485//1485 1889//1889 1891//1891 -f 1485//1485 1891//1891 1484//1484 -f 1484//1484 1891//1891 1896//1896 -f 1484//1484 1896//1896 1486//1486 -f 1486//1486 1896//1896 1895//1895 -f 1486//1486 1895//1895 1894//1894 -f 1874//1874 1873//1873 1501//1501 -f 1501//1501 1873//1873 1880//1880 -f 1501//1501 1880//1880 1502//1502 -f 1502//1502 1880//1880 1884//1884 -f 1502//1502 1884//1884 1493//1493 -f 1493//1493 1884//1884 1883//1883 -f 1493//1493 1883//1883 1494//1494 -f 1494//1494 1883//1883 1882//1882 -f 1494//1494 1882//1882 1488//1488 -f 1488//1488 1882//1882 1888//1888 -f 1488//1488 1888//1888 1490//1490 -f 1490//1490 1888//1888 1886//1886 -f 1490//1490 1886//1886 1491//1491 -f 1491//1491 1886//1886 1885//1885 -f 1491//1491 1885//1885 1889//1889 -f 1876//1876 1505//1505 1878//1878 -f 1878//1878 1505//1505 1504//1504 -f 1878//1878 1504//1504 1879//1879 -f 1879//1879 1504//1504 1511//1511 -f 1879//1879 1511//1511 1868//1868 -f 1501//1501 1499//1499 1874//1874 -f 1874//1874 1499//1499 1498//1498 -f 1874//1874 1498//1498 1876//1876 -f 1876//1876 1498//1498 1497//1497 -f 1876//1876 1497//1497 1505//1505 -f 1506//1506 1869//1869 1509//1509 -f 1509//1509 1869//1869 1868//1868 -f 1509//1509 1868//1868 1510//1510 -f 1510//1510 1868//1868 1511//1511 -f 1518//1518 1862//1862 1864//1864 -f 1518//1518 1864//1864 1519//1519 -f 1519//1519 1864//1864 1867//1867 -f 1519//1519 1867//1867 1521//1521 -f 1521//1521 1867//1867 1522//1522 -f 1522//1522 1867//1867 1866//1866 -f 1522//1522 1866//1866 1436//1436 -f 1436//1436 1866//1866 1865//1865 -f 1436//1436 1865//1865 1437//1437 -f 1437//1437 1865//1865 1872//1872 -f 1437//1437 1872//1872 1506//1506 -f 1506//1506 1872//1872 1871//1871 -f 1506//1506 1871//1871 1869//1869 -f 1862//1862 1518//1518 1857//1857 -f 1857//1857 1518//1518 1512//1512 -f 1857//1857 1512//1512 1858//1858 -f 1858//1858 1512//1512 1514//1514 -f 1858//1858 1514//1514 1860//1860 -f 1860//1860 1514//1514 1516//1516 -f 1860//1860 1516//1516 1861//1861 -f 1861//1861 1516//1516 1433//1433 -f 1861//1861 1433//1433 1835//1835 -f 1835//1835 1433//1433 1527//1527 -f 1835//1835 1527//1527 1836//1836 -f 1855//1855 1529//1529 1856//1856 -f 1856//1856 1529//1529 1528//1528 -f 1856//1856 1528//1528 1853//1853 -f 1527//1527 1526//1526 1836//1836 -f 1836//1836 1526//1526 1524//1524 -f 1836//1836 1524//1524 1855//1855 -f 1855//1855 1524//1524 1523//1523 -f 1855//1855 1523//1523 1529//1529 -f 1530//1530 1533//1533 1839//1839 -f 1839//1839 1533//1533 1534//1534 -f 1839//1839 1534//1534 1848//1848 -f 1848//1848 1534//1534 1535//1535 -f 1848//1848 1535//1535 1849//1849 -f 1839//1839 1838//1838 1530//1530 -f 1530//1530 1838//1838 1854//1854 -f 1530//1530 1854//1854 1531//1531 -f 1531//1531 1854//1854 1853//1853 -f 1531//1531 1853//1853 1532//1532 -f 1532//1532 1853//1853 1528//1528 -f 1849//1849 1535//1535 1851//1851 -f 1851//1851 1535//1535 1432//1432 -f 1851//1851 1432//1432 1841//1841 -f 1841//1841 1432//1432 1431//1431 -f 1841//1841 1431//1431 1842//1842 -f 1842//1842 1431//1431 1539//1539 -f 1842//1842 1539//1539 1844//1844 -f 1539//1539 1538//1538 1844//1844 -f 1844//1844 1538//1538 1537//1537 -f 1844//1844 1537//1537 1846//1846 -f 1846//1846 1537//1537 1536//1536 -f 1846//1846 1536//1536 1847//1847 -f 1847//1847 1536//1536 1542//1542 -f 1847//1847 1542//1542 1991//1991 -f 1991//1991 1542//1542 1541//1541 -f 1991//1991 1541//1541 600//600 -f 593//593 1565//1565 1564//1564 -f 1564//1564 1569//1569 593//593 -f 593//593 1569//1569 1568//1568 -f 593//593 1568//1568 611//611 -f 611//611 1568//1568 613//613 -f 607//607 1563//1563 1562//1562 -f 1562//1562 1561//1561 607//607 -f 607//607 1561//1561 1567//1567 -f 607//607 1567//1567 593//593 -f 593//593 1567//1567 1566//1566 -f 593//593 1566//1566 1565//1565 -f 1551//1551 1558//1558 604//604 -f 604//604 1558//1558 1557//1557 -f 1557//1557 1556//1556 604//604 -f 604//604 1556//1556 1560//1560 -f 604//604 1560//1560 607//607 -f 607//607 1560//1560 1559//1559 -f 607//607 1559//1559 1563//1563 -f 1551//1551 604//604 1552//1552 -f 1552//1552 604//604 602//602 -f 1552//1552 602//602 1553//1553 -f 1548//1548 1547//1547 596//596 -f 596//596 1547//1547 1555//1555 -f 596//596 1555//1555 602//602 -f 602//602 1555//1555 1554//1554 -f 602//602 1554//1554 1553//1553 -f 1541//1541 1540//1540 600//600 -f 600//600 1540//1540 1546//1546 -f 600//600 1546//1546 598//598 -f 598//598 1546//1546 1545//1545 -f 598//598 1545//1545 1544//1544 -f 1544//1544 1543//1543 598//598 -f 598//598 1543//1543 1550//1550 -f 598//598 1550//1550 596//596 -f 596//596 1550//1550 1549//1549 -f 596//596 1549//1549 1548//1548 -f 2162//2162 2163//2163 2164//2164 -f 2164//2164 2165//2165 2162//2162 -f 2162//2162 2165//2165 2166//2166 -f 2162//2162 2166//2166 2167//2167 -f 2168//2168 2169//2169 2170//2170 -f 2171//2171 2172//2172 2173//2173 -f 2174//2174 2175//2175 2176//2176 -f 2177//2177 2178//2178 2179//2179 -f 2167//2167 2166//2166 2180//2180 -f 2180//2180 2166//2166 2181//2181 -f 2178//2178 2182//2182 2179//2179 -f 2179//2179 2182//2182 2183//2183 -f 2179//2179 2183//2183 2184//2184 -f 2185//2185 581//581 580//580 -f 584//584 583//583 2186//2186 -f 2186//2186 583//583 2187//2187 -f 2187//2187 2188//2188 2186//2186 -f 2186//2186 2188//2188 2189//2189 -f 2186//2186 2189//2189 2190//2190 -f 2176//2176 2191//2191 2190//2190 -f 2176//2176 2175//2175 2191//2191 -f 2191//2191 2175//2175 575//575 -f 2191//2191 575//575 574//574 -f 578//578 577//577 2192//2192 -f 2192//2192 577//577 2193//2193 -f 2194//2194 2164//2164 2163//2163 -f 580//580 2177//2177 2185//2185 -f 2185//2185 2177//2177 2179//2179 -f 2185//2185 2179//2179 2195//2195 -f 2195//2195 2179//2179 2184//2184 -f 2195//2195 2184//2184 2196//2196 -f 576//576 575//575 2197//2197 -f 2197//2197 575//575 2175//2175 -f 2197//2197 2175//2175 2198//2198 -f 2198//2198 2175//2175 2174//2174 -f 2198//2198 2174//2174 2199//2199 -f 2200//2200 2189//2189 2201//2201 -f 2201//2201 2189//2189 2188//2188 -f 2201//2201 2188//2188 2202//2202 -f 2202//2202 2188//2188 2187//2187 -f 2202//2202 2187//2187 2203//2203 -f 2204//2204 2205//2205 2206//2206 -f 2207//2207 2205//2205 2208//2208 -f 2208//2208 2205//2205 2204//2204 -f 2208//2208 2204//2204 2209//2209 -f 589//589 588//588 2209//2209 -f 2209//2209 588//588 2210//2210 -f 2209//2209 2210//2210 2208//2208 -f 2208//2208 2210//2210 2211//2211 -f 2208//2208 2211//2211 2207//2207 -f 2207//2207 2211//2211 2212//2212 -f 2213//2213 2214//2214 2215//2215 -f 2215//2215 2214//2214 2216//2216 -f 2215//2215 2216//2216 2181//2181 -f 2181//2181 2216//2216 2217//2217 -f 2181//2181 2217//2217 2180//2180 -f 2166//2166 2165//2165 2181//2181 -f 2181//2181 2165//2165 2218//2218 -f 2181//2181 2218//2218 2215//2215 -f 2215//2215 2218//2218 2219//2219 -f 2215//2215 2219//2219 2213//2213 -f 2213//2213 2219//2219 2220//2220 -f 2165//2165 2164//2164 2218//2218 -f 2218//2218 2164//2164 2194//2194 -f 2218//2218 2194//2194 2219//2219 -f 2219//2219 2194//2194 2221//2221 -f 2219//2219 2221//2221 2220//2220 -f 2220//2220 2221//2221 2222//2222 -f 2223//2223 2224//2224 2225//2225 -f 2225//2225 2224//2224 2226//2226 -f 2225//2225 2226//2226 2227//2227 -f 2227//2227 2226//2226 2170//2170 -f 2228//2228 2200//2200 2229//2229 -f 2229//2229 2200//2200 2201//2201 -f 2229//2229 2201//2201 2230//2230 -f 2230//2230 2201//2201 2202//2202 -f 2230//2230 2202//2202 2231//2231 -f 2231//2231 2202//2202 2203//2203 -f 2231//2231 2203//2203 2232//2232 -f 2233//2233 2231//2231 2234//2234 -f 2234//2234 2231//2231 2232//2232 -f 2234//2234 2232//2232 2235//2235 -f 2236//2236 2235//2235 2237//2237 -f 2237//2237 2235//2235 2232//2232 -f 2237//2237 2232//2232 2238//2238 -f 2238//2238 2232//2232 2203//2203 -f 2238//2238 2203//2203 2239//2239 -f 2239//2239 2203//2203 2187//2187 -f 2239//2239 2187//2187 582//582 -f 582//582 2187//2187 583//583 -f 582//582 581//581 2239//2239 -f 2239//2239 581//581 2185//2185 -f 2239//2239 2185//2185 2238//2238 -f 2238//2238 2185//2185 2195//2195 -f 2238//2238 2195//2195 2237//2237 -f 2237//2237 2195//2195 2196//2196 -f 2237//2237 2196//2196 2236//2236 -f 2236//2236 2196//2196 2240//2240 -f 2206//2206 2241//2241 2242//2242 -f 590//590 589//589 2182//2182 -f 2182//2182 589//589 2209//2209 -f 2182//2182 2209//2209 2183//2183 -f 2183//2183 2209//2209 2204//2204 -f 2183//2183 2204//2204 2184//2184 -f 2184//2184 2204//2204 2206//2206 -f 2184//2184 2206//2206 2196//2196 -f 2196//2196 2206//2206 2242//2242 -f 2196//2196 2242//2242 2240//2240 -f 2243//2243 2244//2244 2212//2212 -f 2212//2212 2244//2244 2245//2245 -f 2212//2212 2245//2245 2207//2207 -f 2207//2207 2245//2245 2246//2246 -f 2207//2207 2246//2246 2205//2205 -f 2205//2205 2246//2246 2247//2247 -f 2205//2205 2247//2247 2206//2206 -f 2206//2206 2247//2247 2248//2248 -f 2206//2206 2248//2248 2241//2241 -f 2172//2172 2243//2243 2173//2173 -f 2173//2173 2243//2243 2212//2212 -f 2173//2173 2212//2212 2249//2249 -f 2249//2249 2212//2212 2211//2211 -f 2249//2249 2211//2211 2250//2250 -f 2250//2250 2211//2211 2210//2210 -f 2250//2250 2210//2210 587//587 -f 587//587 2210//2210 588//588 -f 2251//2251 2171//2171 2252//2252 -f 2252//2252 2171//2171 2173//2173 -f 2252//2252 2173//2173 2253//2253 -f 2253//2253 2173//2173 2249//2249 -f 2253//2253 2249//2249 2254//2254 -f 2254//2254 2249//2249 2250//2250 -f 2254//2254 2250//2250 2255//2255 -f 2255//2255 2250//2250 587//587 -f 2255//2255 587//587 586//586 -f 2255//2255 2256//2256 2254//2254 -f 2254//2254 2256//2256 2257//2257 -f 2254//2254 2257//2257 2253//2253 -f 2253//2253 2257//2257 2258//2258 -f 2253//2253 2258//2258 2252//2252 -f 2252//2252 2258//2258 2259//2259 -f 2252//2252 2259//2259 2251//2251 -f 2251//2251 2259//2259 2260//2260 -f 2256//2256 2180//2180 2257//2257 -f 2257//2257 2180//2180 2217//2217 -f 2257//2257 2217//2217 2258//2258 -f 2258//2258 2217//2217 2216//2216 -f 2258//2258 2216//2216 2259//2259 -f 2259//2259 2216//2216 2214//2214 -f 2259//2259 2214//2214 2260//2260 -f 2260//2260 2214//2214 2261//2261 -f 2262//2262 2263//2263 2222//2222 -f 2222//2222 2263//2263 2264//2264 -f 2222//2222 2264//2264 2220//2220 -f 2220//2220 2264//2264 2265//2265 -f 2220//2220 2265//2265 2213//2213 -f 2213//2213 2265//2265 2266//2266 -f 2213//2213 2266//2266 2214//2214 -f 2214//2214 2266//2266 2267//2267 -f 2214//2214 2267//2267 2261//2261 -f 2268//2268 2262//2262 2227//2227 -f 2227//2227 2262//2262 2222//2222 -f 2227//2227 2222//2222 2225//2225 -f 2225//2225 2222//2222 2221//2221 -f 2225//2225 2221//2221 2223//2223 -f 2223//2223 2221//2221 2194//2194 -f 2223//2223 2194//2194 2269//2269 -f 2269//2269 2194//2194 2163//2163 -f 2170//2170 2169//2169 2227//2227 -f 2227//2227 2169//2169 2270//2270 -f 2227//2227 2270//2270 2268//2268 -f 2271//2271 2168//2168 2272//2272 -f 2272//2272 2168//2168 2170//2170 -f 2272//2272 2170//2170 2273//2273 -f 2273//2273 2170//2170 2226//2226 -f 2273//2273 2226//2226 2193//2193 -f 2193//2193 2226//2226 2224//2224 -f 2193//2193 2224//2224 2192//2192 -f 2192//2192 2224//2224 2223//2223 -f 2192//2192 2223//2223 2274//2274 -f 2274//2274 2223//2223 2269//2269 -f 577//577 576//576 2193//2193 -f 2193//2193 576//576 2197//2197 -f 2193//2193 2197//2197 2273//2273 -f 2273//2273 2197//2197 2198//2198 -f 2273//2273 2198//2198 2272//2272 -f 2272//2272 2198//2198 2199//2199 -f 2272//2272 2199//2199 2271//2271 -f 2271//2271 2199//2199 2275//2275 -f 2190//2190 2189//2189 2176//2176 -f 2176//2176 2189//2189 2200//2200 -f 2176//2176 2200//2200 2174//2174 -f 2174//2174 2200//2200 2228//2228 -f 2174//2174 2228//2228 2199//2199 -f 2199//2199 2228//2228 2276//2276 -f 2199//2199 2276//2276 2275//2275 -f 2233//2233 2277//2277 2231//2231 -f 2231//2231 2277//2277 2278//2278 -f 2231//2231 2278//2278 2230//2230 -f 2230//2230 2278//2278 2279//2279 -f 2230//2230 2279//2279 2229//2229 -f 2229//2229 2279//2279 2280//2280 -f 2229//2229 2280//2280 2228//2228 -f 2228//2228 2280//2280 2281//2281 -f 2228//2228 2281//2281 2276//2276 -f 2277//2277 2282//2282 2283//2283 -f 2235//2235 2284//2284 2234//2234 -f 2234//2234 2284//2284 2282//2282 -f 2234//2234 2282//2282 2233//2233 -f 2233//2233 2282//2282 2277//2277 -f 2235//2235 2236//2236 2284//2284 -f 2284//2284 2236//2236 2240//2240 -f 2284//2284 2240//2240 2285//2285 -f 2240//2240 2242//2242 2285//2285 -f 2285//2285 2242//2242 2241//2241 -f 2285//2285 2241//2241 2286//2286 -f 2246//2246 2287//2287 2247//2247 -f 2247//2247 2287//2287 2286//2286 -f 2247//2247 2286//2286 2248//2248 -f 2248//2248 2286//2286 2241//2241 -f 2246//2246 2245//2245 2287//2287 -f 2287//2287 2245//2245 2244//2244 -f 2287//2287 2244//2244 2288//2288 -f 2244//2244 2243//2243 2288//2288 -f 2288//2288 2243//2243 2172//2172 -f 2288//2288 2172//2172 2289//2289 -f 2172//2172 2171//2171 2289//2289 -f 2289//2289 2171//2171 2251//2251 -f 2289//2289 2251//2251 2290//2290 -f 2251//2251 2260//2260 2290//2290 -f 2290//2290 2260//2260 2261//2261 -f 2290//2290 2261//2261 2291//2291 -f 2265//2265 2292//2292 2266//2266 -f 2266//2266 2292//2292 2291//2291 -f 2266//2266 2291//2291 2267//2267 -f 2267//2267 2291//2291 2261//2261 -f 2265//2265 2264//2264 2292//2292 -f 2292//2292 2264//2264 2263//2263 -f 2292//2292 2263//2263 2293//2293 -f 2263//2263 2262//2262 2293//2293 -f 2293//2293 2262//2262 2268//2268 -f 2293//2293 2268//2268 2294//2294 -f 2168//2168 2295//2295 2169//2169 -f 2169//2169 2295//2295 2294//2294 -f 2169//2169 2294//2294 2270//2270 -f 2270//2270 2294//2294 2268//2268 -f 2168//2168 2271//2271 2295//2295 -f 2295//2295 2271//2271 2275//2275 -f 2295//2295 2275//2275 2296//2296 -f 2275//2275 2276//2276 2296//2296 -f 2296//2296 2276//2276 2281//2281 -f 2296//2296 2281//2281 2297//2297 -f 2281//2281 2280//2280 2297//2297 -f 2297//2297 2280//2280 2279//2279 -f 2297//2297 2279//2279 2283//2283 -f 2283//2283 2279//2279 2278//2278 -f 2283//2283 2278//2278 2277//2277 -f 2298//2298 2299//2299 2300//2300 -f 2300//2300 2299//2299 2301//2301 -f 2300//2300 2301//2301 2302//2302 -f 2302//2302 2301//2301 2303//2303 -f 2302//2302 2303//2303 2304//2304 -f 2305//2305 2306//2306 2307//2307 -f 2307//2307 2306//2306 2308//2308 -f 2307//2307 2308//2308 2309//2309 -f 2309//2309 2308//2308 2310//2310 -f 2309//2309 2310//2310 2298//2298 -f 2298//2298 2310//2310 2311//2311 -f 2298//2298 2311//2311 2299//2299 -f 2312//2312 2313//2313 2314//2314 -f 2314//2314 2313//2313 2315//2315 -f 2314//2314 2315//2315 2316//2316 -f 2316//2316 2315//2315 2317//2317 -f 2316//2316 2317//2317 2305//2305 -f 2305//2305 2317//2317 2318//2318 -f 2305//2305 2318//2318 2306//2306 -f 2303//2303 2319//2319 2304//2304 -f 2304//2304 2319//2319 2320//2320 -f 2304//2304 2320//2320 2321//2321 -f 2321//2321 2320//2320 2322//2322 -f 2321//2321 2322//2322 2323//2323 -f 2323//2323 2322//2322 2324//2324 -f 2323//2323 2324//2324 2312//2312 -f 2312//2312 2324//2324 2325//2325 -f 2312//2312 2325//2325 2313//2313 -f 1458//1458 2161//2161 2302//2302 -f 2302//2302 2161//2161 2160//2160 -f 2302//2302 2160//2160 2300//2300 -f 2300//2300 2160//2160 2159//2159 -f 2300//2300 2159//2159 2298//2298 -f 2298//2298 2159//2159 2158//2158 -f 2298//2298 2158//2158 2309//2309 -f 2309//2309 2158//2158 2157//2157 -f 2309//2309 2157//2157 2307//2307 -f 2307//2307 2157//2157 2156//2156 -f 2307//2307 2156//2156 2305//2305 -f 2305//2305 2156//2156 2155//2155 -f 2305//2305 2155//2155 2316//2316 -f 2316//2316 2155//2155 2154//2154 -f 2316//2316 2154//2154 2314//2314 -f 2314//2314 2154//2154 2153//2153 -f 2314//2314 2153//2153 2312//2312 -f 2312//2312 2153//2153 2152//2152 -f 2312//2312 2152//2152 2323//2323 -f 2323//2323 2152//2152 2150//2150 -f 2323//2323 2150//2150 2321//2321 -f 2321//2321 2150//2150 2151//2151 -f 2321//2321 2151//2151 2304//2304 -f 2304//2304 2151//2151 1458//1458 -f 2304//2304 1458//1458 2302//2302 -f 1577//1577 1581//1581 2326//2326 -f 2326//2326 1581//1581 1580//1580 -f 2326//2326 1580//1580 1579//1579 -f 1831//1831 2149//2149 2327//2327 -f 2327//2327 2149//2149 2148//2148 -f 2327//2327 2148//2148 1138//1138 -f 1831//1831 2327//2327 1829//1829 -f 1829//1829 2327//2327 2328//2328 -f 1829//1829 2328//2328 1990//1990 -f 1579//1579 1989//1989 2326//2326 -f 2326//2326 1989//1989 1988//1988 -f 2326//2326 1988//1988 2328//2328 -f 2328//2328 1988//1988 1987//1987 -f 2328//2328 1987//1987 1990//1990 -f 1115//1115 1570//1570 2329//2329 -f 2329//2329 1570//1570 1429//1429 -f 2329//2329 1429//1429 2330//2330 -f 2330//2330 1429//1429 1428//1428 -f 1428//1428 1572//1572 2330//2330 -f 2330//2330 1572//1572 1574//1574 -f 2330//2330 1574//1574 2326//2326 -f 2326//2326 1574//1574 1824//1824 -f 2326//2326 1824//1824 1577//1577 -f 2331//2331 2330//2330 2332//2332 -f 2332//2332 2330//2330 2326//2326 -f 2332//2332 2326//2326 2333//2333 -f 2333//2333 2326//2326 2328//2328 -f 2333//2333 2328//2328 2334//2334 -f 2334//2334 2328//2328 2327//2327 -f 2334//2334 2327//2327 2335//2335 -f 2335//2335 2327//2327 1138//1138 -f 2335//2335 1138//1138 2336//2336 -f 1138//1138 1136//1136 2336//2336 -f 2336//2336 1136//1136 1132//1132 -f 2336//2336 1132//1132 2337//2337 -f 2337//2337 1132//1132 1127//1127 -f 2337//2337 1127//1127 2338//2338 -f 2338//2338 1127//1127 1122//1122 -f 2338//2338 1122//1122 2339//2339 -f 2339//2339 1122//1122 1124//1124 -f 2339//2339 1124//1124 2340//2340 -f 2340//2340 1124//1124 1120//1120 -f 2340//2340 1120//1120 2341//2341 -f 2341//2341 1120//1120 1116//1116 -f 2341//2341 1116//1116 2342//2342 -f 2342//2342 1116//1116 1115//1115 -f 2342//2342 1115//1115 2331//2331 -f 2331//2331 1115//1115 2329//2329 -f 2331//2331 2329//2329 2330//2330 -f 2341//2341 2342//2342 2343//2343 -f 2343//2343 2342//2342 2331//2331 -f 2343//2343 2331//2331 2332//2332 -f 2338//2338 2339//2339 2343//2343 -f 2343//2343 2339//2339 2340//2340 -f 2343//2343 2340//2340 2341//2341 -f 2335//2335 2336//2336 2343//2343 -f 2343//2343 2336//2336 2337//2337 -f 2343//2343 2337//2337 2338//2338 -f 2332//2332 2333//2333 2343//2343 -f 2343//2343 2333//2333 2334//2334 -f 2343//2343 2334//2334 2335//2335 -f 2283//2283 2315//2315 2297//2297 -f 2297//2297 2315//2315 2313//2313 -f 2297//2297 2313//2313 2296//2296 -f 2296//2296 2313//2313 2325//2325 -f 2296//2296 2325//2325 2295//2295 -f 2295//2295 2325//2325 2324//2324 -f 2295//2295 2324//2324 2294//2294 -f 2294//2294 2324//2324 2322//2322 -f 2294//2294 2322//2322 2293//2293 -f 2293//2293 2322//2322 2320//2320 -f 2293//2293 2320//2320 2292//2292 -f 2292//2292 2320//2320 2319//2319 -f 2292//2292 2319//2319 2291//2291 -f 2291//2291 2319//2319 2303//2303 -f 2291//2291 2303//2303 2290//2290 -f 2290//2290 2303//2303 2301//2301 -f 2290//2290 2301//2301 2289//2289 -f 2289//2289 2301//2301 2299//2299 -f 2289//2289 2299//2299 2288//2288 -f 2288//2288 2299//2299 2311//2311 -f 2288//2288 2311//2311 2287//2287 -f 2287//2287 2311//2311 2310//2310 -f 2287//2287 2310//2310 2286//2286 -f 2286//2286 2310//2310 2308//2308 -f 2286//2286 2308//2308 2285//2285 -f 2285//2285 2308//2308 2306//2306 -f 2285//2285 2306//2306 2284//2284 -f 2284//2284 2306//2306 2318//2318 -f 2284//2284 2318//2318 2282//2282 -f 2282//2282 2318//2318 2317//2317 -f 2282//2282 2317//2317 2283//2283 -f 2283//2283 2317//2317 2315//2315 -f 2162//2162 2344//2344 2163//2163 -f 2163//2163 2344//2344 2345//2345 -f 2163//2163 2345//2345 2269//2269 -f 2269//2269 2345//2345 2274//2274 -f 2274//2274 2345//2345 2346//2346 -f 2274//2274 2346//2346 2192//2192 -f 2192//2192 2346//2346 578//578 -f 578//578 2346//2346 2347//2347 -f 578//578 2347//2347 573//573 -f 573//573 2347//2347 574//574 -f 574//574 2347//2347 2348//2348 -f 574//574 2348//2348 2191//2191 -f 2191//2191 2348//2348 2190//2190 -f 2190//2190 2348//2348 2349//2349 -f 2190//2190 2349//2349 2186//2186 -f 2186//2186 2349//2349 584//584 -f 584//584 2349//2349 2350//2350 -f 584//584 2350//2350 579//579 -f 579//579 2350//2350 580//580 -f 580//580 2350//2350 2351//2351 -f 580//580 2351//2351 2177//2177 -f 2177//2177 2351//2351 2178//2178 -f 2178//2178 2351//2351 2352//2352 -f 2178//2178 2352//2352 2182//2182 -f 2182//2182 2352//2352 590//590 -f 590//590 2352//2352 2353//2353 -f 590//590 2353//2353 585//585 -f 585//585 2353//2353 586//586 -f 586//586 2353//2353 2354//2354 -f 586//586 2354//2354 2255//2255 -f 2255//2255 2354//2354 2256//2256 -f 2256//2256 2354//2354 2355//2355 -f 2256//2256 2355//2355 2180//2180 -f 2180//2180 2355//2355 2167//2167 -f 2167//2167 2355//2355 2344//2344 -f 2167//2167 2344//2344 2162//2162 -f 2349//2349 2348//2348 2350//2350 -f 2350//2350 2348//2348 2347//2347 -f 2355//2355 2354//2354 2344//2344 -f 2344//2344 2354//2354 2353//2353 -f 2352//2352 2351//2351 2353//2353 -f 2353//2353 2351//2351 2350//2350 -f 2353//2353 2350//2350 2344//2344 -f 2344//2344 2350//2350 2347//2347 -f 2344//2344 2347//2347 2345//2345 -f 2345//2345 2347//2347 2346//2346 -f 2356//2356 2357//2357 2358//2358 -f 2358//2358 2359//2359 2356//2356 -f 2356//2356 2359//2359 2360//2360 -f 2356//2356 2360//2360 2361//2361 -f 2362//2362 2363//2363 2364//2364 -f 2364//2364 2365//2365 2362//2362 -f 2362//2362 2365//2365 2366//2366 -f 2362//2362 2366//2366 2367//2367 -f 2368//2368 2369//2369 2370//2370 -f 2370//2370 2371//2371 2368//2368 -f 2368//2368 2371//2371 2372//2372 -f 2368//2368 2372//2372 2373//2373 -f 2374//2374 2375//2375 2376//2376 -f 2377//2377 2378//2378 2379//2379 -f 2379//2379 2378//2378 2380//2380 -f 2379//2379 2380//2380 2381//2381 -f 2381//2381 2380//2380 2382//2382 -f 2381//2381 2382//2382 2383//2383 -f 2377//2377 2379//2379 2384//2384 -f 2384//2384 2379//2379 2385//2385 -f 2384//2384 2385//2385 2386//2386 -f 2386//2386 2385//2385 2387//2387 -f 2386//2386 2387//2387 2388//2388 -f 2388//2388 2387//2387 2389//2389 -f 2389//2389 2387//2387 2390//2390 -f 2389//2389 2390//2390 2391//2391 -f 2376//2376 2375//2375 2390//2390 -f 2390//2390 2375//2375 2392//2392 -f 2390//2390 2392//2392 2391//2391 -f 2374//2374 2376//2376 2393//2393 -f 2393//2393 2376//2376 2394//2394 -f 2393//2393 2394//2394 2395//2395 -f 2394//2394 2396//2396 2395//2395 -f 2395//2395 2396//2396 2397//2397 -f 2395//2395 2397//2397 2398//2398 -f 2398//2398 2397//2397 2399//2399 -f 2398//2398 2399//2399 2400//2400 -f 2400//2400 2399//2399 2401//2401 -f 2401//2401 2399//2399 2402//2402 -f 2401//2401 2402//2402 2403//2403 -f 2403//2403 2402//2402 2404//2404 -f 2403//2403 2404//2404 2405//2405 -f 2405//2405 2404//2404 2406//2406 -f 2405//2405 2406//2406 2407//2407 -f 2406//2406 2408//2408 2407//2407 -f 2407//2407 2408//2408 2409//2409 -f 2407//2407 2409//2409 2410//2410 -f 2410//2410 2409//2409 2411//2411 -f 2410//2410 2411//2411 2412//2412 -f 2412//2412 2411//2411 2413//2413 -f 2412//2412 2413//2413 2414//2414 -f 2414//2414 2413//2413 2415//2415 -f 2414//2414 2415//2415 2416//2416 -f 2416//2416 2415//2415 2417//2417 -f 2416//2416 2417//2417 2418//2418 -f 2418//2418 2417//2417 2419//2419 -f 2418//2418 2419//2419 2420//2420 -f 2420//2420 2419//2419 2421//2421 -f 2420//2420 2421//2421 2422//2422 -f 2422//2422 2421//2421 2423//2423 -f 2422//2422 2423//2423 2424//2424 -f 2424//2424 2423//2423 2425//2425 -f 2424//2424 2425//2425 2426//2426 -f 2426//2426 2425//2425 2427//2427 -f 2426//2426 2427//2427 2428//2428 -f 2428//2428 2427//2427 2429//2429 -f 2428//2428 2429//2429 2430//2430 -f 2430//2430 2429//2429 2431//2431 -f 2430//2430 2431//2431 2432//2432 -f 2432//2432 2431//2431 2433//2433 -f 2432//2432 2433//2433 2434//2434 -f 2434//2434 2433//2433 2435//2435 -f 2434//2434 2435//2435 2436//2436 -f 2436//2436 2435//2435 2437//2437 -f 2436//2436 2437//2437 2438//2438 -f 2437//2437 2439//2439 2438//2438 -f 2438//2438 2439//2439 2440//2440 -f 2438//2438 2440//2440 2441//2441 -f 2441//2441 2440//2440 2442//2442 -f 2441//2441 2442//2442 2443//2443 -f 2443//2443 2442//2442 2444//2444 -f 2443//2443 2444//2444 2445//2445 -f 2445//2445 2444//2444 2446//2446 -f 2445//2445 2446//2446 2447//2447 -f 2447//2447 2446//2446 2448//2448 -f 2448//2448 2446//2446 2449//2449 -f 2448//2448 2449//2449 2450//2450 -f 2450//2450 2449//2449 2451//2451 -f 2450//2450 2451//2451 2452//2452 -f 2452//2452 2451//2451 2453//2453 -f 2452//2452 2453//2453 2454//2454 -f 2454//2454 2453//2453 2455//2455 -f 2454//2454 2455//2455 2456//2456 -f 2456//2456 2455//2455 2457//2457 -f 2456//2456 2457//2457 2458//2458 -f 2458//2458 2457//2457 2459//2459 -f 2458//2458 2459//2459 2460//2460 -f 2460//2460 2459//2459 2461//2461 -f 2460//2460 2461//2461 2462//2462 -f 2462//2462 2461//2461 2463//2463 -f 2462//2462 2463//2463 2464//2464 -f 2464//2464 2463//2463 2465//2465 -f 2464//2464 2465//2465 2466//2466 -f 2466//2466 2465//2465 2467//2467 -f 2466//2466 2467//2467 2468//2468 -f 2467//2467 2469//2469 2468//2468 -f 2468//2468 2469//2469 2470//2470 -f 2468//2468 2470//2470 2471//2471 -f 2471//2471 2470//2470 2472//2472 -f 2471//2471 2472//2472 2473//2473 -f 2473//2473 2472//2472 2474//2474 -f 2473//2473 2474//2474 2475//2475 -f 2475//2475 2474//2474 2476//2476 -f 2475//2475 2476//2476 2477//2477 -f 2477//2477 2476//2476 2478//2478 -f 2478//2478 2476//2476 2479//2479 -f 2478//2478 2479//2479 2480//2480 -f 2480//2480 2479//2479 2481//2481 -f 2480//2480 2481//2481 2482//2482 -f 2482//2482 2481//2481 2483//2483 -f 2482//2482 2483//2483 2484//2484 -f 2484//2484 2483//2483 2485//2485 -f 2484//2484 2485//2485 2486//2486 -f 2486//2486 2485//2485 2487//2487 -f 2486//2486 2487//2487 2488//2488 -f 2488//2488 2487//2487 2489//2489 -f 2488//2488 2489//2489 2490//2490 -f 2490//2490 2489//2489 2491//2491 -f 2490//2490 2491//2491 2492//2492 -f 2492//2492 2491//2491 2493//2493 -f 2492//2492 2493//2493 2494//2494 -f 2494//2494 2493//2493 2495//2495 -f 2494//2494 2495//2495 2496//2496 -f 2496//2496 2495//2495 2497//2497 -f 2496//2496 2497//2497 2498//2498 -f 2497//2497 2499//2499 2498//2498 -f 2498//2498 2499//2499 2500//2500 -f 2498//2498 2500//2500 2501//2501 -f 2501//2501 2500//2500 2502//2502 -f 2501//2501 2502//2502 2503//2503 -f 2503//2503 2502//2502 2504//2504 -f 2503//2503 2504//2504 2505//2505 -f 2505//2505 2504//2504 2506//2506 -f 2507//2507 2508//2508 2509//2509 -f 2509//2509 2508//2508 2510//2510 -f 2509//2509 2510//2510 2511//2511 -f 2511//2511 2510//2510 2512//2512 -f 2511//2511 2512//2512 2513//2513 -f 2513//2513 2512//2512 2514//2514 -f 2513//2513 2514//2514 2515//2515 -f 2515//2515 2514//2514 2516//2516 -f 2515//2515 2516//2516 2517//2517 -f 2517//2517 2516//2516 2518//2518 -f 2517//2517 2518//2518 2519//2519 -f 2519//2519 2518//2518 2520//2520 -f 2519//2519 2520//2520 2521//2521 -f 2521//2521 2520//2520 2522//2522 -f 2521//2521 2522//2522 2506//2506 -f 2506//2506 2522//2522 2523//2523 -f 2506//2506 2523//2523 2505//2505 -f 2524//2524 2525//2525 2526//2526 -f 2524//2524 2526//2526 2527//2527 -f 2527//2527 2526//2526 2528//2528 -f 2527//2527 2528//2528 2529//2529 -f 2529//2529 2528//2528 2530//2530 -f 2529//2529 2530//2530 2531//2531 -f 2531//2531 2530//2530 2532//2532 -f 2531//2531 2532//2532 2533//2533 -f 2533//2533 2532//2532 2534//2534 -f 2533//2533 2534//2534 2535//2535 -f 2535//2535 2534//2534 2536//2536 -f 2535//2535 2536//2536 2537//2537 -f 2537//2537 2536//2536 2538//2538 -f 2537//2537 2538//2538 2539//2539 -f 2539//2539 2538//2538 2540//2540 -f 2539//2539 2540//2540 2541//2541 -f 2541//2541 2540//2540 2542//2542 -f 2541//2541 2542//2542 2543//2543 -f 2543//2543 2542//2542 2544//2544 -f 2543//2543 2544//2544 2545//2545 -f 2545//2545 2544//2544 2546//2546 -f 2545//2545 2546//2546 2547//2547 -f 2547//2547 2546//2546 2548//2548 -f 2547//2547 2548//2548 2549//2549 -f 2549//2549 2548//2548 2550//2550 -f 2549//2549 2550//2550 2551//2551 -f 2551//2551 2550//2550 2552//2552 -f 2551//2551 2552//2552 2553//2553 -f 2553//2553 2552//2552 2554//2554 -f 2553//2553 2554//2554 2507//2507 -f 2507//2507 2554//2554 2555//2555 -f 2507//2507 2555//2555 2508//2508 -f 2525//2525 2524//2524 2556//2556 -f 2556//2556 2524//2524 2557//2557 -f 2556//2556 2557//2557 2558//2558 -f 2558//2558 2557//2557 2559//2559 -f 2558//2558 2559//2559 2560//2560 -f 2560//2560 2559//2559 2561//2561 -f 2560//2560 2561//2561 2562//2562 -f 2562//2562 2561//2561 2563//2563 -f 2562//2562 2563//2563 2564//2564 -f 2564//2564 2563//2563 2565//2565 -f 2564//2564 2565//2565 2566//2566 -f 2566//2566 2565//2565 2567//2567 -f 2566//2566 2567//2567 2568//2568 -f 2568//2568 2567//2567 2569//2569 -f 2568//2568 2569//2569 2570//2570 -f 2570//2570 2569//2569 2571//2571 -f 2570//2570 2571//2571 2572//2572 -f 2572//2572 2571//2571 2573//2573 -f 2572//2572 2573//2573 2574//2574 -f 2574//2574 2573//2573 2575//2575 -f 2574//2574 2575//2575 2576//2576 -f 2575//2575 2577//2577 2576//2576 -f 2576//2576 2577//2577 2578//2578 -f 2576//2576 2578//2578 2579//2579 -f 2579//2579 2578//2578 2580//2580 -f 2579//2579 2580//2580 2581//2581 -f 2581//2581 2580//2580 2582//2582 -f 2581//2581 2582//2582 2583//2583 -f 2583//2583 2582//2582 2584//2584 -f 2583//2583 2584//2584 2585//2585 -f 2585//2585 2584//2584 2586//2586 -f 2586//2586 2584//2584 2587//2587 -f 2586//2586 2587//2587 2588//2588 -f 2588//2588 2587//2587 2589//2589 -f 2588//2588 2589//2589 2590//2590 -f 2590//2590 2589//2589 2591//2591 -f 2590//2590 2591//2591 2592//2592 -f 2592//2592 2591//2591 2593//2593 -f 2592//2592 2593//2593 2594//2594 -f 2594//2594 2593//2593 2595//2595 -f 2594//2594 2595//2595 2596//2596 -f 2596//2596 2595//2595 2597//2597 -f 2596//2596 2597//2597 2598//2598 -f 2598//2598 2597//2597 2599//2599 -f 2598//2598 2599//2599 2600//2600 -f 2600//2600 2599//2599 2601//2601 -f 2600//2600 2601//2601 2602//2602 -f 2602//2602 2601//2601 2603//2603 -f 2602//2602 2603//2603 2604//2604 -f 2604//2604 2603//2603 2605//2605 -f 2604//2604 2605//2605 2606//2606 -f 2605//2605 2607//2607 2606//2606 -f 2606//2606 2607//2607 2608//2608 -f 2606//2606 2608//2608 2609//2609 -f 2609//2609 2608//2608 2610//2610 -f 2609//2609 2610//2610 2611//2611 -f 2611//2611 2610//2610 2612//2612 -f 2611//2611 2612//2612 2613//2613 -f 2613//2613 2612//2612 2614//2614 -f 2613//2613 2614//2614 2615//2615 -f 2615//2615 2614//2614 2616//2616 -f 2615//2615 2616//2616 2617//2617 -f 2617//2617 2616//2616 2618//2618 -f 2617//2617 2618//2618 2619//2619 -f 2619//2619 2618//2618 2620//2620 -f 2619//2619 2620//2620 2621//2621 -f 2621//2621 2620//2620 2622//2622 -f 2621//2621 2622//2622 2623//2623 -f 2623//2623 2622//2622 2624//2624 -f 2623//2623 2624//2624 2625//2625 -f 2625//2625 2624//2624 2626//2626 -f 2625//2625 2626//2626 2627//2627 -f 2627//2627 2626//2626 2628//2628 -f 2627//2627 2628//2628 2629//2629 -f 2629//2629 2628//2628 2630//2630 -f 2629//2629 2630//2630 2631//2631 -f 2631//2631 2630//2630 2632//2632 -f 2631//2631 2632//2632 2633//2633 -f 2633//2633 2632//2632 2634//2634 -f 2634//2634 2632//2632 2635//2635 -f 2634//2634 2635//2635 2636//2636 -f 2635//2635 2637//2637 2636//2636 -f 2636//2636 2637//2637 2638//2638 -f 2636//2636 2638//2638 2639//2639 -f 2639//2639 2638//2638 2640//2640 -f 2639//2639 2640//2640 2641//2641 -f 2641//2641 2640//2640 2642//2642 -f 2641//2641 2642//2642 2643//2643 -f 2643//2643 2642//2642 2644//2644 -f 2643//2643 2644//2644 2645//2645 -f 2645//2645 2644//2644 2646//2646 -f 2645//2645 2646//2646 2647//2647 -f 2647//2647 2646//2646 2648//2648 -f 2647//2647 2648//2648 2649//2649 -f 2649//2649 2648//2648 2650//2650 -f 2649//2649 2650//2650 2651//2651 -f 2651//2651 2650//2650 2652//2652 -f 2651//2651 2652//2652 2653//2653 -f 2653//2653 2652//2652 2654//2654 -f 2653//2653 2654//2654 2655//2655 -f 2655//2655 2654//2654 2656//2656 -f 2655//2655 2656//2656 2657//2657 -f 2657//2657 2656//2656 2658//2658 -f 2657//2657 2658//2658 2659//2659 -f 2659//2659 2658//2658 2660//2660 -f 2659//2659 2660//2660 2661//2661 -f 2661//2661 2660//2660 2662//2662 -f 2661//2661 2662//2662 2663//2663 -f 2663//2663 2662//2662 2664//2664 -f 2664//2664 2662//2662 2665//2665 -f 2664//2664 2665//2665 2666//2666 -f 2665//2665 2667//2667 2666//2666 -f 2666//2666 2667//2667 2668//2668 -f 2666//2666 2668//2668 2669//2669 -f 2669//2669 2668//2668 2670//2670 -f 2669//2669 2670//2670 2671//2671 -f 2671//2671 2670//2670 2672//2672 -f 2671//2671 2672//2672 2673//2673 -f 2673//2673 2672//2672 2674//2674 -f 2673//2673 2674//2674 2675//2675 -f 2675//2675 2674//2674 2676//2676 -f 2675//2675 2676//2676 2677//2677 -f 2677//2677 2676//2676 2678//2678 -f 2677//2677 2678//2678 2679//2679 -f 2679//2679 2678//2678 2680//2680 -f 2679//2679 2680//2680 2681//2681 -f 2681//2681 2680//2680 2682//2682 -f 2681//2681 2682//2682 2683//2683 -f 2683//2683 2682//2682 2684//2684 -f 2683//2683 2684//2684 2685//2685 -f 2685//2685 2684//2684 2686//2686 -f 2685//2685 2686//2686 2687//2687 -f 2687//2687 2686//2686 2688//2688 -f 2687//2687 2688//2688 2689//2689 -f 2689//2689 2688//2688 2690//2690 -f 2690//2690 2688//2688 2691//2691 -f 2690//2690 2691//2691 2692//2692 -f 2692//2692 2691//2691 2693//2693 -f 2692//2692 2693//2693 2694//2694 -f 2694//2694 2693//2693 2695//2695 -f 2694//2694 2695//2695 2696//2696 -f 2695//2695 2697//2697 2696//2696 -f 2696//2696 2697//2697 2698//2698 -f 2696//2696 2698//2698 2699//2699 -f 2699//2699 2698//2698 2700//2700 -f 2699//2699 2700//2700 2701//2701 -f 2701//2701 2700//2700 2702//2702 -f 2701//2701 2702//2702 2703//2703 -f 2703//2703 2702//2702 2704//2704 -f 2705//2705 2706//2706 2707//2707 -f 2707//2707 2706//2706 2708//2708 -f 2707//2707 2708//2708 2709//2709 -f 2709//2709 2708//2708 2710//2710 -f 2709//2709 2710//2710 2711//2711 -f 2711//2711 2710//2710 2712//2712 -f 2711//2711 2712//2712 2704//2704 -f 2704//2704 2712//2712 2713//2713 -f 2704//2704 2713//2713 2703//2703 -f 2707//2707 2714//2714 2705//2705 -f 2705//2705 2714//2714 2715//2715 -f 2705//2705 2715//2715 2716//2716 -f 2716//2716 2715//2715 2717//2717 -f 2716//2716 2717//2717 2718//2718 -f 2718//2718 2717//2717 2719//2719 -f 2718//2718 2719//2719 2720//2720 -f 2720//2720 2719//2719 2721//2721 -f 2720//2720 2721//2721 2722//2722 -f 2722//2722 2721//2721 2723//2723 -f 2721//2721 2724//2724 2723//2723 -f 2723//2723 2724//2724 2725//2725 -f 2723//2723 2725//2725 2726//2726 -f 2726//2726 2725//2725 2727//2727 -f 2726//2726 2727//2727 2728//2728 -f 2728//2728 2727//2727 2729//2729 -f 2728//2728 2729//2729 2730//2730 -f 2729//2729 2731//2731 2730//2730 -f 2730//2730 2731//2731 2732//2732 -f 2730//2730 2732//2732 2733//2733 -f 2733//2733 2732//2732 2734//2734 -f 2733//2733 2734//2734 2735//2735 -f 2735//2735 2734//2734 2736//2736 -f 2735//2735 2736//2736 2737//2737 -f 2737//2737 2736//2736 2738//2738 -f 2739//2739 2740//2740 2741//2741 -f 2739//2739 2741//2741 2742//2742 -f 2742//2742 2741//2741 2743//2743 -f 2742//2742 2743//2743 2738//2738 -f 2738//2738 2743//2743 2744//2744 -f 2738//2738 2744//2744 2737//2737 -f 2740//2740 2739//2739 2745//2745 -f 2745//2745 2739//2739 2746//2746 -f 2745//2745 2746//2746 2747//2747 -f 2746//2746 2748//2748 2747//2747 -f 2747//2747 2748//2748 2749//2749 -f 2747//2747 2749//2749 2750//2750 -f 2750//2750 2749//2749 2751//2751 -f 2750//2750 2751//2751 2752//2752 -f 2752//2752 2751//2751 2753//2753 -f 2752//2752 2753//2753 2754//2754 -f 2754//2754 2753//2753 2755//2755 -f 2754//2754 2755//2755 2756//2756 -f 2755//2755 2757//2757 2756//2756 -f 2756//2756 2757//2757 2758//2758 -f 2756//2756 2758//2758 2759//2759 -f 2759//2759 2758//2758 2760//2760 -f 2759//2759 2760//2760 2761//2761 -f 2761//2761 2760//2760 2762//2762 -f 2761//2761 2762//2762 2763//2763 -f 2763//2763 2762//2762 2764//2764 -f 2765//2765 2766//2766 2767//2767 -f 2767//2767 2766//2766 2768//2768 -f 2767//2767 2768//2768 2769//2769 -f 2769//2769 2768//2768 2770//2770 -f 2769//2769 2770//2770 2771//2771 -f 2771//2771 2770//2770 2772//2772 -f 2771//2771 2772//2772 2764//2764 -f 2764//2764 2772//2772 2773//2773 -f 2764//2764 2773//2773 2763//2763 -f 2767//2767 2774//2774 2765//2765 -f 2765//2765 2774//2774 2775//2775 -f 2765//2765 2775//2775 2776//2776 -f 2776//2776 2775//2775 2777//2777 -f 2776//2776 2777//2777 2778//2778 -f 2778//2778 2777//2777 2779//2779 -f 2778//2778 2779//2779 2780//2780 -f 2780//2780 2779//2779 2781//2781 -f 2780//2780 2781//2781 2782//2782 -f 2782//2782 2781//2781 2783//2783 -f 2781//2781 2784//2784 2783//2783 -f 2783//2783 2784//2784 2785//2785 -f 2783//2783 2785//2785 2786//2786 -f 2786//2786 2785//2785 2787//2787 -f 2786//2786 2787//2787 2788//2788 -f 2788//2788 2787//2787 2789//2789 -f 2788//2788 2789//2789 2790//2790 -f 2790//2790 2789//2789 2791//2791 -f 2789//2789 2792//2792 2791//2791 -f 2791//2791 2792//2792 2793//2793 -f 2791//2791 2793//2793 2794//2794 -f 2794//2794 2793//2793 2795//2795 -f 2794//2794 2795//2795 2796//2796 -f 2796//2796 2795//2795 2797//2797 -f 2796//2796 2797//2797 2798//2798 -f 2798//2798 2797//2797 2799//2799 -f 2798//2798 2799//2799 2800//2800 -f 2800//2800 2799//2799 2801//2801 -f 2799//2799 2802//2802 2801//2801 -f 2801//2801 2802//2802 2803//2803 -f 2801//2801 2803//2803 2804//2804 -f 2804//2804 2803//2803 2805//2805 -f 2804//2804 2805//2805 2806//2806 -f 2806//2806 2805//2805 2807//2807 -f 2806//2806 2807//2807 2808//2808 -f 2807//2807 2809//2809 2808//2808 -f 2808//2808 2809//2809 2810//2810 -f 2808//2808 2810//2810 2811//2811 -f 2811//2811 2810//2810 2812//2812 -f 2811//2811 2812//2812 2813//2813 -f 2813//2813 2812//2812 2814//2814 -f 2813//2813 2814//2814 2815//2815 -f 2815//2815 2814//2814 2816//2816 -f 2817//2817 2818//2818 2819//2819 -f 2817//2817 2819//2819 2820//2820 -f 2820//2820 2819//2819 2821//2821 -f 2820//2820 2821//2821 2816//2816 -f 2816//2816 2821//2821 2822//2822 -f 2816//2816 2822//2822 2815//2815 -f 2818//2818 2817//2817 2823//2823 -f 2823//2823 2817//2817 2824//2824 -f 2823//2823 2824//2824 2825//2825 -f 2825//2825 2824//2824 2826//2826 -f 2825//2825 2826//2826 2827//2827 -f 2827//2827 2826//2826 2828//2828 -f 2827//2827 2828//2828 2829//2829 -f 2828//2828 2830//2830 2829//2829 -f 2829//2829 2830//2830 2831//2831 -f 2829//2829 2831//2831 2832//2832 -f 2832//2832 2831//2831 2833//2833 -f 2832//2832 2833//2833 2834//2834 -f 2833//2833 2835//2835 2834//2834 -f 2834//2834 2835//2835 2836//2836 -f 2834//2834 2836//2836 2837//2837 -f 2837//2837 2836//2836 2838//2838 -f 2837//2837 2838//2838 2839//2839 -f 2839//2839 2838//2838 2840//2840 -f 2839//2839 2840//2840 2841//2841 -f 2841//2841 2840//2840 2842//2842 -f 2843//2843 2844//2844 2845//2845 -f 2845//2845 2844//2844 2846//2846 -f 2845//2845 2846//2846 2847//2847 -f 2847//2847 2846//2846 2848//2848 -f 2847//2847 2848//2848 2849//2849 -f 2849//2849 2848//2848 2850//2850 -f 2849//2849 2850//2850 2842//2842 -f 2842//2842 2850//2850 2851//2851 -f 2842//2842 2851//2851 2841//2841 -f 2845//2845 2852//2852 2843//2843 -f 2843//2843 2852//2852 2853//2853 -f 2843//2843 2853//2853 2854//2854 -f 2854//2854 2853//2853 2855//2855 -f 2854//2854 2855//2855 2856//2856 -f 2856//2856 2855//2855 2857//2857 -f 2856//2856 2857//2857 2858//2858 -f 2858//2858 2857//2857 2859//2859 -f 2858//2858 2859//2859 2860//2860 -f 2860//2860 2859//2859 2861//2861 -f 2859//2859 2862//2862 2861//2861 -f 2861//2861 2862//2862 2863//2863 -f 2861//2861 2863//2863 2864//2864 -f 2864//2864 2863//2863 2865//2865 -f 2864//2864 2865//2865 2866//2866 -f 2866//2866 2865//2865 2867//2867 -f 2866//2866 2867//2867 2868//2868 -f 2867//2867 2869//2869 2868//2868 -f 2868//2868 2869//2869 2870//2870 -f 2868//2868 2870//2870 2871//2871 -f 2871//2871 2870//2870 2872//2872 -f 2871//2871 2872//2872 2873//2873 -f 2873//2873 2872//2872 2874//2874 -f 2873//2873 2874//2874 2875//2875 -f 2875//2875 2874//2874 2876//2876 -f 2877//2877 2878//2878 2879//2879 -f 2877//2877 2879//2879 2880//2880 -f 2880//2880 2879//2879 2881//2881 -f 2880//2880 2881//2881 2876//2876 -f 2876//2876 2881//2881 2882//2882 -f 2876//2876 2882//2882 2875//2875 -f 2878//2878 2877//2877 2883//2883 -f 2883//2883 2877//2877 2884//2884 -f 2883//2883 2884//2884 2885//2885 -f 2885//2885 2884//2884 2886//2886 -f 2885//2885 2886//2886 2887//2887 -f 2887//2887 2886//2886 2888//2888 -f 2887//2887 2888//2888 2889//2889 -f 2890//2890 2891//2891 2892//2892 -f 2892//2892 2891//2891 2893//2893 -f 2892//2892 2893//2893 2894//2894 -f 2894//2894 2893//2893 2895//2895 -f 2894//2894 2895//2895 2896//2896 -f 2896//2896 2895//2895 2889//2889 -f 2896//2896 2889//2889 2897//2897 -f 2897//2897 2889//2889 2888//2888 -f 2898//2898 2899//2899 2900//2900 -f 2900//2900 2899//2899 2901//2901 -f 2901//2901 2899//2899 2902//2902 -f 2902//2902 2899//2899 2903//2903 -f 2902//2902 2903//2903 2904//2904 -f 2905//2905 2906//2906 2907//2907 -f 2907//2907 2906//2906 2908//2908 -f 2907//2907 2908//2908 2903//2903 -f 2903//2903 2908//2908 2909//2909 -f 2903//2903 2909//2909 2904//2904 -f 2910//2910 2911//2911 2905//2905 -f 2905//2905 2911//2911 2912//2912 -f 2905//2905 2912//2912 2906//2906 -f 2913//2913 2914//2914 2915//2915 -f 2915//2915 2914//2914 2916//2916 -f 2915//2915 2916//2916 2910//2910 -f 2910//2910 2916//2916 2917//2917 -f 2910//2910 2917//2917 2911//2911 -f 2913//2913 2915//2915 2918//2918 -f 2918//2918 2915//2915 2919//2919 -f 2918//2918 2919//2919 2920//2920 -f 2920//2920 2919//2919 2921//2921 -f 2920//2920 2921//2921 2922//2922 -f 2922//2922 2921//2921 2923//2923 -f 2922//2922 2923//2923 2924//2924 -f 2924//2924 2923//2923 2925//2925 -f 2924//2924 2925//2925 2926//2926 -f 2926//2926 2925//2925 2927//2927 -f 2926//2926 2927//2927 2890//2890 -f 2890//2890 2927//2927 2928//2928 -f 2890//2890 2928//2928 2891//2891 -f 2929//2929 2930//2930 2931//2931 -f 2932//2932 2933//2933 2934//2934 -f 2935//2935 2936//2936 2937//2937 -f 2938//2938 2939//2939 2940//2940 -f 2941//2941 2942//2942 2943//2943 -f 2944//2944 2945//2945 2946//2946 -f 2947//2947 2948//2948 2949//2949 -f 2950//2950 2951//2951 2952//2952 -f 2953//2953 2954//2954 2955//2955 -f 2956//2956 2957//2957 2958//2958 -f 2959//2959 2960//2960 2961//2961 -f 2962//2962 2963//2963 2964//2964 -f 2965//2965 2966//2966 2967//2967 -f 2968//2968 2969//2969 2970//2970 -f 2971//2971 2972//2972 2973//2973 -f 2974//2974 2975//2975 2976//2976 -f 2977//2977 2978//2978 2979//2979 -f 2980//2980 2981//2981 2982//2982 -f 2983//2983 2984//2984 2985//2985 -f 2986//2986 2987//2987 2988//2988 -f 2989//2989 2990//2990 2991//2991 -f 2992//2992 2993//2993 2994//2994 -f 2995//2995 2996//2996 2997//2997 -f 2998//2998 2999//2999 3000//3000 -f 3001//3001 3002//3002 3003//3003 -f 3004//3004 3005//3005 3006//3006 -f 3007//3007 3008//3008 3009//3009 -f 3010//3010 3011//3011 3012//3012 -f 3013//3013 3014//3014 3015//3015 -f 3016//3016 3017//3017 3018//3018 -f 3019//3019 3020//3020 3021//3021 -f 3022//3022 3023//3023 3024//3024 -f 3025//3025 3026//3026 3027//3027 -f 3028//3028 3029//3029 3030//3030 -f 3031//3031 3032//3032 3033//3033 -f 3034//3034 3035//3035 3036//3036 -f 3037//3037 3038//3038 3039//3039 -f 3040//3040 3041//3041 3042//3042 -f 3043//3043 3044//3044 3045//3045 -f 3046//3046 3047//3047 3048//3048 -f 3049//3049 3050//3050 3051//3051 -f 3052//3052 3053//3053 3054//3054 -f 3055//3055 3056//3056 3057//3057 -f 3058//3058 3059//3059 3060//3060 -f 3061//3061 3062//3062 3063//3063 -f 3064//3064 3065//3065 3066//3066 -f 3067//3067 3068//3068 3069//3069 -f 3070//3070 3071//3071 3072//3072 -f 3073//3073 3074//3074 3075//3075 -f 3076//3076 3077//3077 3078//3078 -f 3079//3079 3080//3080 3081//3081 -f 3082//3082 3083//3083 3084//3084 -f 3085//3085 3086//3086 3087//3087 -f 3088//3088 3089//3089 3090//3090 -f 3091//3091 3092//3092 3093//3093 -f 3094//3094 3095//3095 3096//3096 -f 3097//3097 3098//3098 3099//3099 -f 3100//3100 3101//3101 3102//3102 -f 3103//3103 3104//3104 3105//3105 -f 3106//3106 3107//3107 3108//3108 -f 3109//3109 3110//3110 3111//3111 -f 3112//3112 3113//3113 3114//3114 -f 3115//3115 3116//3116 3117//3117 -f 3118//3118 3119//3119 3120//3120 -f 3121//3121 3122//3122 3123//3123 -f 3124//3124 3125//3125 3126//3126 -f 3127//3127 3128//3128 3129//3129 -f 3130//3130 3131//3131 3132//3132 -f 3133//3133 3134//3134 3135//3135 -f 3136//3136 3137//3137 3138//3138 -f 3139//3139 3140//3140 3141//3141 -f 3142//3142 3143//3143 3144//3144 -f 3145//3145 3146//3146 3147//3147 -f 3148//3148 3149//3149 3150//3150 -f 3151//3151 3152//3152 3153//3153 -f 3154//3154 3155//3155 3156//3156 -f 3157//3157 3158//3158 3159//3159 -f 3160//3160 3161//3161 3162//3162 -f 3163//3163 3164//3164 3165//3165 -f 3166//3166 3167//3167 3168//3168 -f 3169//3169 3170//3170 3171//3171 -f 3172//3172 3173//3173 3174//3174 -f 3175//3175 3176//3176 3177//3177 -f 3178//3178 3179//3179 3180//3180 -f 3181//3181 3182//3182 3183//3183 -f 3184//3184 3185//3185 3186//3186 -f 3187//3187 3188//3188 3189//3189 -f 3190//3190 3191//3191 3192//3192 -f 3193//3193 3194//3194 3195//3195 -f 3196//3196 3197//3197 3198//3198 -f 3199//3199 3200//3200 3201//3201 -f 3202//3202 3203//3203 3204//3204 -f 3205//3205 3206//3206 3207//3207 -f 3208//3208 3209//3209 3210//3210 -f 2644//2644 2642//2642 2952//2952 -f 2628//2628 2626//2626 2967//2967 -f 2614//2614 2612//2612 2979//2979 -f 2597//2597 2595//2595 2994//2994 -f 2567//2567 2565//2565 3021//3021 -f 2529//2529 2531//2531 3036//3036 -f 2543//2543 2545//2545 3048//3048 -f 2511//2511 2513//2513 3063//3063 -f 2489//2489 2487//2487 3090//3090 -f 2459//2459 2457//2457 3117//3117 -f 2442//2442 2440//2440 3132//3132 -f 2429//2429 2427//2427 3144//3144 -f 2411//2411 2409//2409 3159//3159 -f 3211//3211 3212//3212 3213//3213 -f 3214//3214 3215//3215 3204//3204 -f 3216//3216 3217//3217 3218//3218 -f 3219//3219 3220//3220 3221//3221 -f 3222//3222 3223//3223 3224//3224 -f 3225//3225 3226//3226 3227//3227 -f 3228//3228 3229//3229 3230//3230 -f 3230//3230 3229//3229 3231//3231 -f 3230//3230 3231//3231 3232//3232 -f 3231//3231 3233//3233 3232//3232 -f 3232//3232 3233//3233 3234//3234 -f 3232//3232 3234//3234 3235//3235 -f 3235//3235 3234//3234 3236//3236 -f 3235//3235 3236//3236 3237//3237 -f 3237//3237 3236//3236 3238//3238 -f 3237//3237 3238//3238 3239//3239 -f 3239//3239 3238//3238 3240//3240 -f 3239//3239 3240//3240 3241//3241 -f 3242//3242 3243//3243 3244//3244 -f 3244//3244 3243//3243 3245//3245 -f 3245//3245 3246//3246 3244//3244 -f 3244//3244 3246//3246 3247//3247 -f 3244//3244 3247//3247 3230//3230 -f 3230//3230 3247//3247 3248//3248 -f 3230//3230 3248//3248 3228//3228 -f 3227//3227 3226//3226 3249//3249 -f 3226//3226 3250//3250 3249//3249 -f 3249//3249 3250//3250 3251//3251 -f 3249//3249 3251//3251 3242//3242 -f 3242//3242 3251//3251 3252//3252 -f 3242//3242 3252//3252 3243//3243 -f 3225//3225 3227//3227 3253//3253 -f 3253//3253 3227//3227 3254//3254 -f 3253//3253 3254//3254 3255//3255 -f 3256//3256 3257//3257 3258//3258 -f 3258//3258 3259//3259 3256//3256 -f 3256//3256 3259//3259 3260//3260 -f 3256//3256 3260//3260 3254//3254 -f 3254//3254 3260//3260 3261//3261 -f 3254//3254 3261//3261 3255//3255 -f 3223//3223 3262//3262 3224//3224 -f 3224//3224 3262//3262 3263//3263 -f 3224//3224 3263//3263 3257//3257 -f 3257//3257 3263//3263 3264//3264 -f 3257//3257 3264//3264 3258//3258 -f 3265//3265 3266//3266 3267//3267 -f 3267//3267 3266//3266 3268//3268 -f 3265//3265 3267//3267 3224//3224 -f 3224//3224 3267//3267 3269//3269 -f 3224//3224 3269//3269 3222//3222 -f 3270//3270 3271//3271 3272//3272 -f 3272//3272 3271//3271 3273//3273 -f 3272//3272 3273//3273 3266//3266 -f 3266//3266 3273//3273 3274//3274 -f 3266//3266 3274//3274 3268//3268 -f 3275//3275 3276//3276 3270//3270 -f 3270//3270 3276//3276 3277//3277 -f 3270//3270 3277//3277 3271//3271 -f 3278//3278 3279//3279 3280//3280 -f 3280//3280 3281//3281 3278//3278 -f 3278//3278 3281//3281 3282//3282 -f 3278//3278 3282//3282 3283//3283 -f 3283//3283 3282//3282 3284//3284 -f 3283//3283 3284//3284 3275//3275 -f 3275//3275 3284//3284 3285//3285 -f 3275//3275 3285//3285 3276//3276 -f 3286//3286 3287//3287 3279//3279 -f 3279//3279 3287//3287 3288//3288 -f 3279//3279 3288//3288 3280//3280 -f 3289//3289 3290//3290 3220//3220 -f 3220//3220 3290//3290 3291//3291 -f 3220//3220 3291//3291 3221//3221 -f 3289//3289 3292//3292 3290//3290 -f 3290//3290 3292//3292 3293//3293 -f 3290//3290 3293//3293 3286//3286 -f 3286//3286 3293//3293 3294//3294 -f 3286//3286 3294//3294 3287//3287 -f 3295//3295 3296//3296 3297//3297 -f 3297//3297 3296//3296 3298//3298 -f 3297//3297 3298//3298 3299//3299 -f 3299//3299 3298//3298 3300//3300 -f 3295//3295 3301//3301 3296//3296 -f 3296//3296 3301//3301 3302//3302 -f 3296//3296 3302//3302 3303//3303 -f 3303//3303 3302//3302 3304//3304 -f 3303//3303 3304//3304 3221//3221 -f 3221//3221 3304//3304 3305//3305 -f 3221//3221 3305//3305 3219//3219 -f 3306//3306 3307//3307 3308//3308 -f 3308//3308 3307//3307 3309//3309 -f 3308//3308 3309//3309 3218//3218 -f 3218//3218 3309//3309 3310//3310 -f 3218//3218 3310//3310 3216//3216 -f 3311//3311 3312//3312 3210//3210 -f 3313//3313 3314//3314 3210//3210 -f 3210//3210 3314//3314 3315//3315 -f 3210//3210 3315//3315 3311//3311 -f 3316//3316 3207//3207 3317//3317 -f 3317//3317 3207//3207 3318//3318 -f 3319//3319 3320//3320 3201//3201 -f 3201//3201 3320//3320 3321//3321 -f 3214//3214 3204//3204 3322//3322 -f 3323//3323 3324//3324 3198//3198 -f 3198//3198 3324//3324 3325//3325 -f 3326//3326 3327//3327 3195//3195 -f 3195//3195 3327//3327 3328//3328 -f 3195//3195 3328//3328 3329//3329 -f 3330//3330 3331//3331 3192//3192 -f 3192//3192 3331//3331 3332//3332 -f 3192//3192 3332//3332 3333//3333 -f 3334//3334 3335//3335 3186//3186 -f 3186//3186 3335//3335 3336//3336 -f 3337//3337 3338//3338 3189//3189 -f 3339//3339 3340//3340 3183//3183 -f 3183//3183 3340//3340 3341//3341 -f 3180//3180 3342//3342 3343//3343 -f 3344//3344 3345//3345 3180//3180 -f 3180//3180 3345//3345 3346//3346 -f 3180//3180 3346//3346 3342//3342 -f 3347//3347 3348//3348 3177//3177 -f 3177//3177 3348//3348 3349//3349 -f 3177//3177 3349//3349 3350//3350 -f 2396//2396 3351//3351 3174//3174 -f 3174//3174 3351//3351 3352//3352 -f 3353//3353 2898//2898 3354//3354 -f 3211//3211 3213//3213 3355//3355 -f 3355//3355 3213//3213 3356//3356 -f 3355//3355 3356//3356 3357//3357 -f 3358//3358 3359//3359 3360//3360 -f 3361//3361 3362//3362 3363//3363 -f 3361//3361 3363//3363 3359//3359 -f 3359//3359 3363//3363 3364//3364 -f 3359//3359 3364//3364 3360//3360 -f 2399//2399 2397//2397 3171//3171 -f 2406//2406 2404//2404 3165//3165 -f 2415//2415 2413//2413 3156//3156 -f 2419//2419 2417//2417 3153//3153 -f 2423//2423 2421//2421 3150//3150 -f 2433//2433 2431//2431 3141//3141 -f 2437//2437 2435//2435 3138//3138 -f 2446//2446 2444//2444 3129//3129 -f 2453//2453 2451//2451 3123//3123 -f 2463//2463 2461//2461 3114//3114 -f 2467//2467 2465//2465 3111//3111 -f 2470//2470 2469//2469 3108//3108 -f 2476//2476 2474//2474 3102//3102 -f 2483//2483 2481//2481 3096//3096 -f 2493//2493 2491//2491 3087//3087 -f 2497//2497 2495//2495 3084//3084 -f 2500//2500 2499//2499 3081//3081 -f 2506//2506 2504//2504 3075//3075 -f 2517//2517 2519//2519 3069//3069 -f 2507//2507 2509//2509 3060//3060 -f 2549//2549 2551//2551 3054//3054 -f 2539//2539 2541//2541 3045//3045 -f 2535//2535 2537//2537 3042//3042 -f 2524//2524 2527//2527 3033//3033 -f 2561//2561 2559//2559 3027//3027 -f 2571//2571 2569//2569 3018//3018 -f 2575//2575 2573//2573 3015//3015 -f 2578//2578 2577//2577 3012//3012 -f 2584//2584 2582//2582 3006//3006 -f 2591//2591 2589//2589 3000//3000 -f 2601//2601 2599//2599 2991//2991 -f 2605//2605 2603//2603 2988//2988 -f 2608//2608 2607//2607 2985//2985 -f 2618//2618 2616//2616 2976//2976 -f 2622//2622 2620//2620 2973//2973 -f 2632//2632 2630//2630 2964//2964 -f 2638//2638 2637//2637 2958//2958 -f 2648//2648 2646//2646 2949//2949 -f 2652//2652 2650//2650 2946//2946 -f 2656//2656 2654//2654 2943//2943 -f 2662//2662 2660//2660 2937//2937 -f 2668//2668 2667//2667 2931//2931 -f 3365//3365 3366//3366 2670//2670 -f 3367//3367 2674//2674 3366//3366 -f 3366//3366 2674//2674 2672//2672 -f 3366//3366 2672//2672 2670//2670 -f 3368//3368 3369//3369 2682//2682 -f 2682//2682 2680//2680 3368//3368 -f 3368//3368 2680//2680 2678//2678 -f 3368//3368 2678//2678 3367//3367 -f 3367//3367 2678//2678 2676//2676 -f 3367//3367 2676//2676 2674//2674 -f 3370//3370 2688//2688 3371//3371 -f 3371//3371 2688//2688 2686//2686 -f 3371//3371 2686//2686 3369//3369 -f 3369//3369 2686//2686 2684//2684 -f 3369//3369 2684//2684 2682//2682 -f 2698//2698 2697//2697 3372//3372 -f 3372//3372 2697//2697 2695//2695 -f 3372//3372 2695//2695 3373//3373 -f 3373//3373 2695//2695 2693//2693 -f 3373//3373 2693//2693 3370//3370 -f 3370//3370 2693//2693 2691//2691 -f 3370//3370 2691//2691 2688//2688 -f 2704//2704 2702//2702 3374//3374 -f 3374//3374 2702//2702 2700//2700 -f 3374//3374 2700//2700 3375//3375 -f 2711//2711 3376//3376 2709//2709 -f 2709//2709 3376//3376 3377//3377 -f 2709//2709 3377//3377 2707//2707 -f 2714//2714 3378//3378 2715//2715 -f 2715//2715 3378//3378 3379//3379 -f 2715//2715 3379//3379 2717//2717 -f 2719//2719 3380//3380 2721//2721 -f 2721//2721 3380//3380 3381//3381 -f 2721//2721 3381//3381 2724//2724 -f 2724//2724 3381//3381 2725//2725 -f 2727//2727 3382//3382 2729//2729 -f 2729//2729 3382//3382 3383//3383 -f 2729//2729 3383//3383 2731//2731 -f 2732//2732 3384//3384 2734//2734 -f 2734//2734 3384//3384 3385//3385 -f 2734//2734 3385//3385 2736//2736 -f 2736//2736 3385//3385 2738//2738 -f 2746//2746 2739//2739 3386//3386 -f 3386//3386 2739//2739 2742//2742 -f 3386//3386 2742//2742 3387//3387 -f 2751//2751 2749//2749 3388//3388 -f 3388//3388 2749//2749 2748//2748 -f 3388//3388 2748//2748 3389//3389 -f 2753//2753 3390//3390 2755//2755 -f 2755//2755 3390//3390 3391//3391 -f 2755//2755 3391//3391 2757//2757 -f 2757//2757 3391//3391 2758//2758 -f 2760//2760 3392//3392 2762//2762 -f 2762//2762 3392//3392 3393//3393 -f 2762//2762 3393//3393 2764//2764 -f 2771//2771 3394//3394 2769//2769 -f 2769//2769 3394//3394 3395//3395 -f 2769//2769 3395//3395 2767//2767 -f 2774//2774 3396//3396 2775//2775 -f 2775//2775 3396//3396 3397//3397 -f 2775//2775 3397//3397 2777//2777 -f 2779//2779 3398//3398 2781//2781 -f 2781//2781 3398//3398 3399//3399 -f 2781//2781 3399//3399 2784//2784 -f 2784//2784 3399//3399 2785//2785 -f 2787//2787 3400//3400 2789//2789 -f 2789//2789 3400//3400 3401//3401 -f 2789//2789 3401//3401 2792//2792 -f 2792//2792 3401//3401 2793//2793 -f 2799//2799 2797//2797 3402//3402 -f 3402//3402 2797//2797 2795//2795 -f 3402//3402 2795//2795 3403//3403 -f 2802//2802 3404//3404 2803//2803 -f 2803//2803 3404//3404 3405//3405 -f 2803//2803 3405//3405 2805//2805 -f 2805//2805 3405//3405 2807//2807 -f 2812//2812 2810//2810 3406//3406 -f 3406//3406 2810//2810 2809//2809 -f 3406//3406 2809//2809 3407//3407 -f 3408//3408 2820//2820 3409//3409 -f 3409//3409 2820//2820 2816//2816 -f 3409//3409 2816//2816 3410//3410 -f 3410//3410 2816//2816 2814//2814 -f 2830//2830 2828//2828 3411//3411 -f 3411//3411 2828//2828 2826//2826 -f 3411//3411 2826//2826 3412//3412 -f 3412//3412 2826//2826 2824//2824 -f 3412//3412 2824//2824 3408//3408 -f 3408//3408 2824//2824 2817//2817 -f 3408//3408 2817//2817 2820//2820 -f 2831//2831 3413//3413 2833//2833 -f 2833//2833 3413//3413 3414//3414 -f 2833//2833 3414//3414 2835//2835 -f 2835//2835 3414//3414 2836//2836 -f 2838//2838 3415//3415 2840//2840 -f 2840//2840 3415//3415 3416//3416 -f 2840//2840 3416//3416 2842//2842 -f 2849//2849 3417//3417 2847//2847 -f 2847//2847 3417//3417 3418//3418 -f 2847//2847 3418//3418 2845//2845 -f 2852//2852 3419//3419 2853//2853 -f 2853//2853 3419//3419 3420//3420 -f 2853//2853 3420//3420 2855//2855 -f 2857//2857 3421//3421 2859//2859 -f 2859//2859 3421//3421 3422//3422 -f 2859//2859 3422//3422 2862//2862 -f 2862//2862 3422//3422 2863//2863 -f 2865//2865 3423//3423 2867//2867 -f 2867//2867 3423//3423 3424//3424 -f 2867//2867 3424//3424 2869//2869 -f 2869//2869 3424//3424 2870//2870 -f 2876//2876 2874//2874 3425//3425 -f 3425//3425 2874//2874 2872//2872 -f 3425//3425 2872//2872 3426//3426 -f 2884//2884 2877//2877 3427//3427 -f 3427//3427 2877//2877 2880//2880 -f 3427//3427 2880//2880 3428//3428 -f 2897//2897 2888//2888 3429//3429 -f 3429//3429 2888//2888 2886//2886 -f 3429//3429 2886//2886 3430//3430 -f 2896//2896 3431//3431 2894//2894 -f 2894//2894 3431//3431 3432//3432 -f 2894//2894 3432//3432 2892//2892 -f 2890//2890 3433//3433 2926//2926 -f 2926//2926 3433//3433 3434//3434 -f 2926//2926 3434//3434 2924//2924 -f 2922//2922 3435//3435 2920//2920 -f 2920//2920 3435//3435 3436//3436 -f 2920//2920 3436//3436 2918//2918 -f 2918//2918 3436//3436 2913//2913 -f 2914//2914 3437//3437 2916//2916 -f 2916//2916 3437//3437 3438//3438 -f 2916//2916 3438//3438 2917//2917 -f 2911//2911 3439//3439 2912//2912 -f 2912//2912 3439//3439 3440//3440 -f 2912//2912 3440//3440 2906//2906 -f 2906//2906 3440//3440 2908//2908 -f 2902//2902 2904//2904 3441//3441 -f 3441//3441 2904//2904 2909//2909 -f 3441//3441 2909//2909 3442//3442 -f 2898//2898 2900//2900 3354//3354 -f 3354//3354 2900//2900 2901//2901 -f 3354//3354 2901//2901 3443//3443 -f 3216//3216 3299//3299 3217//3217 -f 3217//3217 3299//3299 3300//3300 -f 3217//3217 3300//3300 3218//3218 -f 3218//3218 3300//3300 3444//3444 -f 3218//3218 3444//3444 3308//3308 -f 3308//3308 3444//3444 3445//3445 -f 3445//3445 3208//3208 3308//3308 -f 3308//3308 3208//3208 3210//3210 -f 3308//3308 3210//3210 3306//3306 -f 3306//3306 3210//3210 3312//3312 -f 3209//3209 3205//3205 3210//3210 -f 3210//3210 3205//3205 3207//3207 -f 3210//3210 3207//3207 3313//3313 -f 3313//3313 3207//3207 3316//3316 -f 3206//3206 3202//3202 3207//3207 -f 3207//3207 3202//3202 3204//3204 -f 3207//3207 3204//3204 3318//3318 -f 3318//3318 3204//3204 3215//3215 -f 3203//3203 3199//3199 3204//3204 -f 3204//3204 3199//3199 3201//3201 -f 3204//3204 3201//3201 3322//3322 -f 3322//3322 3201//3201 3321//3321 -f 3200//3200 3196//3196 3201//3201 -f 3201//3201 3196//3196 3198//3198 -f 3201//3201 3198//3198 3319//3319 -f 3319//3319 3198//3198 3325//3325 -f 3197//3197 3193//3193 3198//3198 -f 3198//3198 3193//3193 3195//3195 -f 3198//3198 3195//3195 3323//3323 -f 3323//3323 3195//3195 3329//3329 -f 3194//3194 3190//3190 3195//3195 -f 3195//3195 3190//3190 3192//3192 -f 3195//3195 3192//3192 3326//3326 -f 3326//3326 3192//3192 3333//3333 -f 3191//3191 3187//3187 3192//3192 -f 3192//3192 3187//3187 3189//3189 -f 3192//3192 3189//3189 3330//3330 -f 3330//3330 3189//3189 3338//3338 -f 3188//3188 3184//3184 3189//3189 -f 3189//3189 3184//3184 3186//3186 -f 3189//3189 3186//3186 3337//3337 -f 3337//3337 3186//3186 3336//3336 -f 3185//3185 3181//3181 3186//3186 -f 3186//3186 3181//3181 3183//3183 -f 3186//3186 3183//3183 3334//3334 -f 3334//3334 3183//3183 3341//3341 -f 3182//3182 3178//3178 3183//3183 -f 3183//3183 3178//3178 3180//3180 -f 3183//3183 3180//3180 3339//3339 -f 3339//3339 3180//3180 3343//3343 -f 3179//3179 3175//3175 3180//3180 -f 3180//3180 3175//3175 3177//3177 -f 3180//3180 3177//3177 3344//3344 -f 3344//3344 3177//3177 3350//3350 -f 3176//3176 3172//3172 3177//3177 -f 3177//3177 3172//3172 3174//3174 -f 3177//3177 3174//3174 3347//3347 -f 3347//3347 3174//3174 3352//3352 -f 3173//3173 3169//3169 3174//3174 -f 3174//3174 3169//3169 3171//3171 -f 3174//3174 3171//3171 2396//2396 -f 2396//2396 3171//3171 2397//2397 -f 3170//3170 3166//3166 3171//3171 -f 3171//3171 3166//3166 3168//3168 -f 3171//3171 3168//3168 2399//2399 -f 2399//2399 3168//3168 2402//2402 -f 3167//3167 3163//3163 3168//3168 -f 3168//3168 3163//3163 3165//3165 -f 3168//3168 3165//3165 2402//2402 -f 2402//2402 3165//3165 2404//2404 -f 3164//3164 3160//3160 3165//3165 -f 3165//3165 3160//3160 3162//3162 -f 3165//3165 3162//3162 2406//2406 -f 2406//2406 3162//3162 2408//2408 -f 3161//3161 3157//3157 3162//3162 -f 3162//3162 3157//3157 3159//3159 -f 3162//3162 3159//3159 2408//2408 -f 2408//2408 3159//3159 2409//2409 -f 3158//3158 3154//3154 3159//3159 -f 3159//3159 3154//3154 3156//3156 -f 3159//3159 3156//3156 2411//2411 -f 2411//2411 3156//3156 2413//2413 -f 3155//3155 3151//3151 3156//3156 -f 3156//3156 3151//3151 3153//3153 -f 3156//3156 3153//3153 2415//2415 -f 2415//2415 3153//3153 2417//2417 -f 3152//3152 3148//3148 3153//3153 -f 3153//3153 3148//3148 3150//3150 -f 3153//3153 3150//3150 2419//2419 -f 2419//2419 3150//3150 2421//2421 -f 3149//3149 3145//3145 3150//3150 -f 3150//3150 3145//3145 3147//3147 -f 3150//3150 3147//3147 2423//2423 -f 2423//2423 3147//3147 2425//2425 -f 3146//3146 3142//3142 3147//3147 -f 3147//3147 3142//3142 3144//3144 -f 3147//3147 3144//3144 2425//2425 -f 2425//2425 3144//3144 2427//2427 -f 3143//3143 3139//3139 3144//3144 -f 3144//3144 3139//3139 3141//3141 -f 3144//3144 3141//3141 2429//2429 -f 2429//2429 3141//3141 2431//2431 -f 3140//3140 3136//3136 3141//3141 -f 3141//3141 3136//3136 3138//3138 -f 3141//3141 3138//3138 2433//2433 -f 2433//2433 3138//3138 2435//2435 -f 3137//3137 3133//3133 3138//3138 -f 3138//3138 3133//3133 3135//3135 -f 3138//3138 3135//3135 2437//2437 -f 2437//2437 3135//3135 2439//2439 -f 3134//3134 3130//3130 3135//3135 -f 3135//3135 3130//3130 3132//3132 -f 3135//3135 3132//3132 2439//2439 -f 2439//2439 3132//3132 2440//2440 -f 3131//3131 3127//3127 3132//3132 -f 3132//3132 3127//3127 3129//3129 -f 3132//3132 3129//3129 2442//2442 -f 2442//2442 3129//3129 2444//2444 -f 3128//3128 3124//3124 3129//3129 -f 3129//3129 3124//3124 3126//3126 -f 3129//3129 3126//3126 2446//2446 -f 2446//2446 3126//3126 2449//2449 -f 3125//3125 3121//3121 3126//3126 -f 3126//3126 3121//3121 3123//3123 -f 3126//3126 3123//3123 2449//2449 -f 2449//2449 3123//3123 2451//2451 -f 3122//3122 3118//3118 3123//3123 -f 3123//3123 3118//3118 3120//3120 -f 3123//3123 3120//3120 2453//2453 -f 2453//2453 3120//3120 2455//2455 -f 3119//3119 3115//3115 3120//3120 -f 3120//3120 3115//3115 3117//3117 -f 3120//3120 3117//3117 2455//2455 -f 2455//2455 3117//3117 2457//2457 -f 3116//3116 3112//3112 3117//3117 -f 3117//3117 3112//3112 3114//3114 -f 3117//3117 3114//3114 2459//2459 -f 2459//2459 3114//3114 2461//2461 -f 3113//3113 3109//3109 3114//3114 -f 3114//3114 3109//3109 3111//3111 -f 3114//3114 3111//3111 2463//2463 -f 2463//2463 3111//3111 2465//2465 -f 3110//3110 3106//3106 3111//3111 -f 3111//3111 3106//3106 3108//3108 -f 3111//3111 3108//3108 2467//2467 -f 2467//2467 3108//3108 2469//2469 -f 3107//3107 3103//3103 3108//3108 -f 3108//3108 3103//3103 3105//3105 -f 3108//3108 3105//3105 2470//2470 -f 2470//2470 3105//3105 2472//2472 -f 3104//3104 3100//3100 3105//3105 -f 3105//3105 3100//3100 3102//3102 -f 3105//3105 3102//3102 2472//2472 -f 2472//2472 3102//3102 2474//2474 -f 3101//3101 3097//3097 3102//3102 -f 3102//3102 3097//3097 3099//3099 -f 3102//3102 3099//3099 2476//2476 -f 2476//2476 3099//3099 2479//2479 -f 3098//3098 3094//3094 3099//3099 -f 3099//3099 3094//3094 3096//3096 -f 3099//3099 3096//3096 2479//2479 -f 2479//2479 3096//3096 2481//2481 -f 3095//3095 3091//3091 3096//3096 -f 3096//3096 3091//3091 3093//3093 -f 3096//3096 3093//3093 2483//2483 -f 2483//2483 3093//3093 2485//2485 -f 3092//3092 3088//3088 3093//3093 -f 3093//3093 3088//3088 3090//3090 -f 3093//3093 3090//3090 2485//2485 -f 2485//2485 3090//3090 2487//2487 -f 3089//3089 3085//3085 3090//3090 -f 3090//3090 3085//3085 3087//3087 -f 3090//3090 3087//3087 2489//2489 -f 2489//2489 3087//3087 2491//2491 -f 3086//3086 3082//3082 3087//3087 -f 3087//3087 3082//3082 3084//3084 -f 3087//3087 3084//3084 2493//2493 -f 2493//2493 3084//3084 2495//2495 -f 3083//3083 3079//3079 3084//3084 -f 3084//3084 3079//3079 3081//3081 -f 3084//3084 3081//3081 2497//2497 -f 2497//2497 3081//3081 2499//2499 -f 3080//3080 3076//3076 3081//3081 -f 3081//3081 3076//3076 3078//3078 -f 3081//3081 3078//3078 2500//2500 -f 2500//2500 3078//3078 2502//2502 -f 3077//3077 3073//3073 3078//3078 -f 3078//3078 3073//3073 3075//3075 -f 3078//3078 3075//3075 2502//2502 -f 2502//2502 3075//3075 2504//2504 -f 3074//3074 3070//3070 3075//3075 -f 3075//3075 3070//3070 3072//3072 -f 3075//3075 3072//3072 2506//2506 -f 2506//2506 3072//3072 2521//2521 -f 3071//3071 3067//3067 3072//3072 -f 3072//3072 3067//3067 3069//3069 -f 3072//3072 3069//3069 2521//2521 -f 2521//2521 3069//3069 2519//2519 -f 3068//3068 3064//3064 3069//3069 -f 3069//3069 3064//3064 3066//3066 -f 3069//3069 3066//3066 2517//2517 -f 2517//2517 3066//3066 2515//2515 -f 3065//3065 3061//3061 3066//3066 -f 3066//3066 3061//3061 3063//3063 -f 3066//3066 3063//3063 2515//2515 -f 2515//2515 3063//3063 2513//2513 -f 3062//3062 3058//3058 3063//3063 -f 3063//3063 3058//3058 3060//3060 -f 3063//3063 3060//3060 2511//2511 -f 2511//2511 3060//3060 2509//2509 -f 3059//3059 3055//3055 3060//3060 -f 3060//3060 3055//3055 3057//3057 -f 3060//3060 3057//3057 2507//2507 -f 2507//2507 3057//3057 2553//2553 -f 3056//3056 3052//3052 3057//3057 -f 3057//3057 3052//3052 3054//3054 -f 3057//3057 3054//3054 2553//2553 -f 2553//2553 3054//3054 2551//2551 -f 3053//3053 3049//3049 3054//3054 -f 3054//3054 3049//3049 3051//3051 -f 3054//3054 3051//3051 2549//2549 -f 2549//2549 3051//3051 2547//2547 -f 3050//3050 3046//3046 3051//3051 -f 3051//3051 3046//3046 3048//3048 -f 3051//3051 3048//3048 2547//2547 -f 2547//2547 3048//3048 2545//2545 -f 3047//3047 3043//3043 3048//3048 -f 3048//3048 3043//3043 3045//3045 -f 3048//3048 3045//3045 2543//2543 -f 2543//2543 3045//3045 2541//2541 -f 3044//3044 3040//3040 3045//3045 -f 3045//3045 3040//3040 3042//3042 -f 3045//3045 3042//3042 2539//2539 -f 2539//2539 3042//3042 2537//2537 -f 3041//3041 3037//3037 3042//3042 -f 3042//3042 3037//3037 3039//3039 -f 3042//3042 3039//3039 2535//2535 -f 2535//2535 3039//3039 2533//2533 -f 3038//3038 3034//3034 3039//3039 -f 3039//3039 3034//3034 3036//3036 -f 3039//3039 3036//3036 2533//2533 -f 2533//2533 3036//3036 2531//2531 -f 3035//3035 3031//3031 3036//3036 -f 3036//3036 3031//3031 3033//3033 -f 3036//3036 3033//3033 2529//2529 -f 2529//2529 3033//3033 2527//2527 -f 3032//3032 3028//3028 3033//3033 -f 3033//3033 3028//3028 3030//3030 -f 3033//3033 3030//3030 2524//2524 -f 2524//2524 3030//3030 2557//2557 -f 3029//3029 3025//3025 3030//3030 -f 3030//3030 3025//3025 3027//3027 -f 3030//3030 3027//3027 2557//2557 -f 2557//2557 3027//3027 2559//2559 -f 3026//3026 3022//3022 3027//3027 -f 3027//3027 3022//3022 3024//3024 -f 3027//3027 3024//3024 2561//2561 -f 2561//2561 3024//3024 2563//2563 -f 3023//3023 3019//3019 3024//3024 -f 3024//3024 3019//3019 3021//3021 -f 3024//3024 3021//3021 2563//2563 -f 2563//2563 3021//3021 2565//2565 -f 3020//3020 3016//3016 3021//3021 -f 3021//3021 3016//3016 3018//3018 -f 3021//3021 3018//3018 2567//2567 -f 2567//2567 3018//3018 2569//2569 -f 3017//3017 3013//3013 3018//3018 -f 3018//3018 3013//3013 3015//3015 -f 3018//3018 3015//3015 2571//2571 -f 2571//2571 3015//3015 2573//2573 -f 3014//3014 3010//3010 3015//3015 -f 3015//3015 3010//3010 3012//3012 -f 3015//3015 3012//3012 2575//2575 -f 2575//2575 3012//3012 2577//2577 -f 3011//3011 3007//3007 3012//3012 -f 3012//3012 3007//3007 3009//3009 -f 3012//3012 3009//3009 2578//2578 -f 2578//2578 3009//3009 2580//2580 -f 3008//3008 3004//3004 3009//3009 -f 3009//3009 3004//3004 3006//3006 -f 3009//3009 3006//3006 2580//2580 -f 2580//2580 3006//3006 2582//2582 -f 3005//3005 3001//3001 3006//3006 -f 3006//3006 3001//3001 3003//3003 -f 3006//3006 3003//3003 2584//2584 -f 2584//2584 3003//3003 2587//2587 -f 3002//3002 2998//2998 3003//3003 -f 3003//3003 2998//2998 3000//3000 -f 3003//3003 3000//3000 2587//2587 -f 2587//2587 3000//3000 2589//2589 -f 2999//2999 2995//2995 3000//3000 -f 3000//3000 2995//2995 2997//2997 -f 3000//3000 2997//2997 2591//2591 -f 2591//2591 2997//2997 2593//2593 -f 2996//2996 2992//2992 2997//2997 -f 2997//2997 2992//2992 2994//2994 -f 2997//2997 2994//2994 2593//2593 -f 2593//2593 2994//2994 2595//2595 -f 2993//2993 2989//2989 2994//2994 -f 2994//2994 2989//2989 2991//2991 -f 2994//2994 2991//2991 2597//2597 -f 2597//2597 2991//2991 2599//2599 -f 2990//2990 2986//2986 2991//2991 -f 2991//2991 2986//2986 2988//2988 -f 2991//2991 2988//2988 2601//2601 -f 2601//2601 2988//2988 2603//2603 -f 2987//2987 2983//2983 2988//2988 -f 2988//2988 2983//2983 2985//2985 -f 2988//2988 2985//2985 2605//2605 -f 2605//2605 2985//2985 2607//2607 -f 2984//2984 2980//2980 2985//2985 -f 2985//2985 2980//2980 2982//2982 -f 2985//2985 2982//2982 2608//2608 -f 2608//2608 2982//2982 2610//2610 -f 2981//2981 2977//2977 2982//2982 -f 2982//2982 2977//2977 2979//2979 -f 2982//2982 2979//2979 2610//2610 -f 2610//2610 2979//2979 2612//2612 -f 2978//2978 2974//2974 2979//2979 -f 2979//2979 2974//2974 2976//2976 -f 2979//2979 2976//2976 2614//2614 -f 2614//2614 2976//2976 2616//2616 -f 2975//2975 2971//2971 2976//2976 -f 2976//2976 2971//2971 2973//2973 -f 2976//2976 2973//2973 2618//2618 -f 2618//2618 2973//2973 2620//2620 -f 2972//2972 2968//2968 2973//2973 -f 2973//2973 2968//2968 2970//2970 -f 2973//2973 2970//2970 2622//2622 -f 2622//2622 2970//2970 2624//2624 -f 2969//2969 2965//2965 2970//2970 -f 2970//2970 2965//2965 2967//2967 -f 2970//2970 2967//2967 2624//2624 -f 2624//2624 2967//2967 2626//2626 -f 2966//2966 2962//2962 2967//2967 -f 2967//2967 2962//2962 2964//2964 -f 2967//2967 2964//2964 2628//2628 -f 2628//2628 2964//2964 2630//2630 -f 2963//2963 2959//2959 2964//2964 -f 2964//2964 2959//2959 2961//2961 -f 2964//2964 2961//2961 2632//2632 -f 2632//2632 2961//2961 2635//2635 -f 2960//2960 2956//2956 2961//2961 -f 2961//2961 2956//2956 2958//2958 -f 2961//2961 2958//2958 2635//2635 -f 2635//2635 2958//2958 2637//2637 -f 2957//2957 2953//2953 2958//2958 -f 2958//2958 2953//2953 2955//2955 -f 2958//2958 2955//2955 2638//2638 -f 2638//2638 2955//2955 2640//2640 -f 2954//2954 2950//2950 2955//2955 -f 2955//2955 2950//2950 2952//2952 -f 2955//2955 2952//2952 2640//2640 -f 2640//2640 2952//2952 2642//2642 -f 2951//2951 2947//2947 2952//2952 -f 2952//2952 2947//2947 2949//2949 -f 2952//2952 2949//2949 2644//2644 -f 2644//2644 2949//2949 2646//2646 -f 2948//2948 2944//2944 2949//2949 -f 2949//2949 2944//2944 2946//2946 -f 2949//2949 2946//2946 2648//2648 -f 2648//2648 2946//2946 2650//2650 -f 2945//2945 2941//2941 2946//2946 -f 2946//2946 2941//2941 2943//2943 -f 2946//2946 2943//2943 2652//2652 -f 2652//2652 2943//2943 2654//2654 -f 2942//2942 2938//2938 2943//2943 -f 2943//2943 2938//2938 2940//2940 -f 2943//2943 2940//2940 2656//2656 -f 2656//2656 2940//2940 2658//2658 -f 2939//2939 2935//2935 2940//2940 -f 2940//2940 2935//2935 2937//2937 -f 2940//2940 2937//2937 2658//2658 -f 2658//2658 2937//2937 2660//2660 -f 2936//2936 2932//2932 2937//2937 -f 2937//2937 2932//2932 2934//2934 -f 2937//2937 2934//2934 2662//2662 -f 2662//2662 2934//2934 2665//2665 -f 2933//2933 2929//2929 2934//2934 -f 2934//2934 2929//2929 2931//2931 -f 2934//2934 2931//2931 2665//2665 -f 2665//2665 2931//2931 2667//2667 -f 2930//2930 3446//3446 2931//2931 -f 2931//2931 3446//3446 3365//3365 -f 2931//2931 3365//3365 2668//2668 -f 2668//2668 3365//3365 2670//2670 -f 3446//3446 3447//3447 3365//3365 -f 3365//3365 3447//3447 3448//3448 -f 3365//3365 3448//3448 3366//3366 -f 3366//3366 3448//3448 3449//3449 -f 3366//3366 3449//3449 3367//3367 -f 3367//3367 3449//3449 3450//3450 -f 3450//3450 3451//3451 3367//3367 -f 3367//3367 3451//3451 3452//3452 -f 3367//3367 3452//3452 3368//3368 -f 3368//3368 3452//3452 3453//3453 -f 3368//3368 3453//3453 3369//3369 -f 3453//3453 3454//3454 3369//3369 -f 3369//3369 3454//3454 3455//3455 -f 3369//3369 3455//3455 3371//3371 -f 3371//3371 3455//3455 3456//3456 -f 3456//3456 3457//3457 3371//3371 -f 3371//3371 3457//3457 3458//3458 -f 3371//3371 3458//3458 3370//3370 -f 3370//3370 3458//3458 3459//3459 -f 3370//3370 3459//3459 3373//3373 -f 3459//3459 3460//3460 3373//3373 -f 3373//3373 3460//3460 3461//3461 -f 3373//3373 3461//3461 3372//3372 -f 3372//3372 3461//3461 3462//3462 -f 3462//3462 3463//3463 3372//3372 -f 3372//3372 3463//3463 3375//3375 -f 3372//3372 3375//3375 2698//2698 -f 2698//2698 3375//3375 2700//2700 -f 3463//3463 3464//3464 3375//3375 -f 3375//3375 3464//3464 3465//3465 -f 3375//3375 3465//3465 3374//3374 -f 3374//3374 3465//3465 3466//3466 -f 3466//3466 3467//3467 3374//3374 -f 3374//3374 3467//3467 3376//3376 -f 3374//3374 3376//3376 2704//2704 -f 2704//2704 3376//3376 2711//2711 -f 3467//3467 3468//3468 3376//3376 -f 3376//3376 3468//3468 3469//3469 -f 3376//3376 3469//3469 3377//3377 -f 3377//3377 3469//3469 3470//3470 -f 3470//3470 3471//3471 3377//3377 -f 3377//3377 3471//3471 3378//3378 -f 3377//3377 3378//3378 2707//2707 -f 2707//2707 3378//3378 2714//2714 -f 3471//3471 3472//3472 3378//3378 -f 3378//3378 3472//3472 3473//3473 -f 3378//3378 3473//3473 3379//3379 -f 3379//3379 3473//3473 3474//3474 -f 3474//3474 3475//3475 3379//3379 -f 3379//3379 3475//3475 3380//3380 -f 3379//3379 3380//3380 2717//2717 -f 2717//2717 3380//3380 2719//2719 -f 3475//3475 3476//3476 3380//3380 -f 3380//3380 3476//3476 3477//3477 -f 3380//3380 3477//3477 3381//3381 -f 3381//3381 3477//3477 3478//3478 -f 3478//3478 3479//3479 3381//3381 -f 3381//3381 3479//3479 3382//3382 -f 3381//3381 3382//3382 2725//2725 -f 2725//2725 3382//3382 2727//2727 -f 3479//3479 3480//3480 3382//3382 -f 3382//3382 3480//3480 3481//3481 -f 3382//3382 3481//3481 3383//3383 -f 3383//3383 3481//3481 3482//3482 -f 3482//3482 3483//3483 3383//3383 -f 3383//3383 3483//3483 3384//3384 -f 3383//3383 3384//3384 2731//2731 -f 2731//2731 3384//3384 2732//2732 -f 3483//3483 3484//3484 3384//3384 -f 3384//3384 3484//3484 3485//3485 -f 3384//3384 3485//3485 3385//3385 -f 3385//3385 3485//3485 3486//3486 -f 3486//3486 3487//3487 3385//3385 -f 3385//3385 3487//3487 3387//3387 -f 3385//3385 3387//3387 2738//2738 -f 2738//2738 3387//3387 2742//2742 -f 3487//3487 3488//3488 3387//3387 -f 3387//3387 3488//3488 3489//3489 -f 3387//3387 3489//3489 3386//3386 -f 3386//3386 3489//3489 3490//3490 -f 3490//3490 3491//3491 3386//3386 -f 3386//3386 3491//3491 3389//3389 -f 3386//3386 3389//3389 2746//2746 -f 2746//2746 3389//3389 2748//2748 -f 3491//3491 3492//3492 3389//3389 -f 3389//3389 3492//3492 3493//3493 -f 3389//3389 3493//3493 3388//3388 -f 3388//3388 3493//3493 3494//3494 -f 3494//3494 3495//3495 3388//3388 -f 3388//3388 3495//3495 3390//3390 -f 3388//3388 3390//3390 2751//2751 -f 2751//2751 3390//3390 2753//2753 -f 3495//3495 3496//3496 3390//3390 -f 3390//3390 3496//3496 3497//3497 -f 3390//3390 3497//3497 3391//3391 -f 3391//3391 3497//3497 3498//3498 -f 3498//3498 3499//3499 3391//3391 -f 3391//3391 3499//3499 3392//3392 -f 3391//3391 3392//3392 2758//2758 -f 2758//2758 3392//3392 2760//2760 -f 3499//3499 3500//3500 3392//3392 -f 3392//3392 3500//3500 3501//3501 -f 3392//3392 3501//3501 3393//3393 -f 3393//3393 3501//3501 3502//3502 -f 3502//3502 3503//3503 3393//3393 -f 3393//3393 3503//3503 3394//3394 -f 3393//3393 3394//3394 2764//2764 -f 2764//2764 3394//3394 2771//2771 -f 3503//3503 3504//3504 3394//3394 -f 3394//3394 3504//3504 3505//3505 -f 3394//3394 3505//3505 3395//3395 -f 3395//3395 3505//3505 3506//3506 -f 3506//3506 3507//3507 3395//3395 -f 3395//3395 3507//3507 3396//3396 -f 3395//3395 3396//3396 2767//2767 -f 2767//2767 3396//3396 2774//2774 -f 3507//3507 3508//3508 3396//3396 -f 3396//3396 3508//3508 3509//3509 -f 3396//3396 3509//3509 3397//3397 -f 3397//3397 3509//3509 3510//3510 -f 3510//3510 3511//3511 3397//3397 -f 3397//3397 3511//3511 3398//3398 -f 3397//3397 3398//3398 2777//2777 -f 2777//2777 3398//3398 2779//2779 -f 3511//3511 3512//3512 3398//3398 -f 3398//3398 3512//3512 3513//3513 -f 3398//3398 3513//3513 3399//3399 -f 3399//3399 3513//3513 3514//3514 -f 3514//3514 3515//3515 3399//3399 -f 3399//3399 3515//3515 3400//3400 -f 3399//3399 3400//3400 2785//2785 -f 2785//2785 3400//3400 2787//2787 -f 3515//3515 3516//3516 3400//3400 -f 3400//3400 3516//3516 3517//3517 -f 3400//3400 3517//3517 3401//3401 -f 3401//3401 3517//3517 3518//3518 -f 3518//3518 3519//3519 3401//3401 -f 3401//3401 3519//3519 3403//3403 -f 3401//3401 3403//3403 2793//2793 -f 2793//2793 3403//3403 2795//2795 -f 3519//3519 3520//3520 3403//3403 -f 3403//3403 3520//3520 3521//3521 -f 3403//3403 3521//3521 3402//3402 -f 3402//3402 3521//3521 3522//3522 -f 3522//3522 3523//3523 3402//3402 -f 3402//3402 3523//3523 3404//3404 -f 3402//3402 3404//3404 2799//2799 -f 2799//2799 3404//3404 2802//2802 -f 3523//3523 3524//3524 3404//3404 -f 3404//3404 3524//3524 3525//3525 -f 3404//3404 3525//3525 3405//3405 -f 3405//3405 3525//3525 3526//3526 -f 3526//3526 3527//3527 3405//3405 -f 3405//3405 3527//3527 3407//3407 -f 3405//3405 3407//3407 2807//2807 -f 2807//2807 3407//3407 2809//2809 -f 3527//3527 3528//3528 3407//3407 -f 3407//3407 3528//3528 3529//3529 -f 3407//3407 3529//3529 3406//3406 -f 3406//3406 3529//3529 3530//3530 -f 3530//3530 3531//3531 3406//3406 -f 3406//3406 3531//3531 3410//3410 -f 3406//3406 3410//3410 2812//2812 -f 2812//2812 3410//3410 2814//2814 -f 3531//3531 3532//3532 3410//3410 -f 3410//3410 3532//3532 3533//3533 -f 3410//3410 3533//3533 3409//3409 -f 3409//3409 3533//3533 3534//3534 -f 3534//3534 3535//3535 3409//3409 -f 3409//3409 3535//3535 3536//3536 -f 3409//3409 3536//3536 3408//3408 -f 3408//3408 3536//3536 3537//3537 -f 3408//3408 3537//3537 3412//3412 -f 3537//3537 3538//3538 3412//3412 -f 3412//3412 3538//3538 3539//3539 -f 3412//3412 3539//3539 3411//3411 -f 3411//3411 3539//3539 3540//3540 -f 3411//3411 3540//3540 3541//3541 -f 3541//3541 3542//3542 3411//3411 -f 3411//3411 3542//3542 3413//3413 -f 3411//3411 3413//3413 2830//2830 -f 2830//2830 3413//3413 2831//2831 -f 3543//3543 3414//3414 3544//3544 -f 3544//3544 3414//3414 3413//3413 -f 3544//3544 3413//3413 3545//3545 -f 3545//3545 3413//3413 3542//3542 -f 3543//3543 3546//3546 3414//3414 -f 3414//3414 3546//3546 3415//3415 -f 3414//3414 3415//3415 2836//2836 -f 2836//2836 3415//3415 2838//2838 -f 3547//3547 3416//3416 3548//3548 -f 3548//3548 3416//3416 3415//3415 -f 3548//3548 3415//3415 3549//3549 -f 3549//3549 3415//3415 3546//3546 -f 3547//3547 3550//3550 3416//3416 -f 3416//3416 3550//3550 3417//3417 -f 3416//3416 3417//3417 2842//2842 -f 2842//2842 3417//3417 2849//2849 -f 3551//3551 3418//3418 3552//3552 -f 3552//3552 3418//3418 3417//3417 -f 3552//3552 3417//3417 3553//3553 -f 3553//3553 3417//3417 3550//3550 -f 3551//3551 3554//3554 3418//3418 -f 3418//3418 3554//3554 3419//3419 -f 3418//3418 3419//3419 2845//2845 -f 2845//2845 3419//3419 2852//2852 -f 3555//3555 3420//3420 3556//3556 -f 3556//3556 3420//3420 3419//3419 -f 3556//3556 3419//3419 3557//3557 -f 3557//3557 3419//3419 3554//3554 -f 3555//3555 3558//3558 3420//3420 -f 3420//3420 3558//3558 3421//3421 -f 3420//3420 3421//3421 2855//2855 -f 2855//2855 3421//3421 2857//2857 -f 3559//3559 3422//3422 3560//3560 -f 3560//3560 3422//3422 3421//3421 -f 3560//3560 3421//3421 3561//3561 -f 3561//3561 3421//3421 3558//3558 -f 3559//3559 3562//3562 3422//3422 -f 3422//3422 3562//3562 3423//3423 -f 3422//3422 3423//3423 2863//2863 -f 2863//2863 3423//3423 2865//2865 -f 3563//3563 3424//3424 3564//3564 -f 3564//3564 3424//3424 3423//3423 -f 3564//3564 3423//3423 3565//3565 -f 3565//3565 3423//3423 3562//3562 -f 3563//3563 3566//3566 3424//3424 -f 3424//3424 3566//3566 3426//3426 -f 3424//3424 3426//3426 2870//2870 -f 2870//2870 3426//3426 2872//2872 -f 3567//3567 3425//3425 3568//3568 -f 3568//3568 3425//3425 3426//3426 -f 3568//3568 3426//3426 3569//3569 -f 3569//3569 3426//3426 3566//3566 -f 3567//3567 3570//3570 3425//3425 -f 3425//3425 3570//3570 3428//3428 -f 3425//3425 3428//3428 2876//2876 -f 2876//2876 3428//3428 2880//2880 -f 3571//3571 3427//3427 3572//3572 -f 3572//3572 3427//3427 3428//3428 -f 3572//3572 3428//3428 3573//3573 -f 3573//3573 3428//3428 3570//3570 -f 3571//3571 3574//3574 3427//3427 -f 3427//3427 3574//3574 3430//3430 -f 3427//3427 3430//3430 2884//2884 -f 2884//2884 3430//3430 2886//2886 -f 3575//3575 3429//3429 3576//3576 -f 3576//3576 3429//3429 3430//3430 -f 3576//3576 3430//3430 3577//3577 -f 3577//3577 3430//3430 3574//3574 -f 3575//3575 3578//3578 3429//3429 -f 3429//3429 3578//3578 3431//3431 -f 3429//3429 3431//3431 2897//2897 -f 2897//2897 3431//3431 2896//2896 -f 3579//3579 3432//3432 3580//3580 -f 3580//3580 3432//3432 3431//3431 -f 3580//3580 3431//3431 3581//3581 -f 3581//3581 3431//3431 3578//3578 -f 3579//3579 3582//3582 3432//3432 -f 3432//3432 3582//3582 3433//3433 -f 3432//3432 3433//3433 2892//2892 -f 2892//2892 3433//3433 2890//2890 -f 3583//3583 3434//3434 3584//3584 -f 3584//3584 3434//3434 3433//3433 -f 3584//3584 3433//3433 3585//3585 -f 3585//3585 3433//3433 3582//3582 -f 3583//3583 3586//3586 3434//3434 -f 3434//3434 3586//3586 3435//3435 -f 3434//3434 3435//3435 2924//2924 -f 2924//2924 3435//3435 2922//2922 -f 3587//3587 3436//3436 3588//3588 -f 3588//3588 3436//3436 3435//3435 -f 3588//3588 3435//3435 3589//3589 -f 3589//3589 3435//3435 3586//3586 -f 3587//3587 3590//3590 3436//3436 -f 3436//3436 3590//3590 3437//3437 -f 3436//3436 3437//3437 2913//2913 -f 2913//2913 3437//3437 2914//2914 -f 3591//3591 3438//3438 3592//3592 -f 3592//3592 3438//3438 3437//3437 -f 3592//3592 3437//3437 3593//3593 -f 3593//3593 3437//3437 3590//3590 -f 3591//3591 3594//3594 3438//3438 -f 3438//3438 3594//3594 3439//3439 -f 3438//3438 3439//3439 2917//2917 -f 2917//2917 3439//3439 2911//2911 -f 3595//3595 3440//3440 3596//3596 -f 3596//3596 3440//3440 3439//3439 -f 3596//3596 3439//3439 3597//3597 -f 3597//3597 3439//3439 3594//3594 -f 3595//3595 3598//3598 3440//3440 -f 3440//3440 3598//3598 3442//3442 -f 3440//3440 3442//3442 2908//2908 -f 2908//2908 3442//3442 2909//2909 -f 3599//3599 3441//3441 3600//3600 -f 3600//3600 3441//3441 3442//3442 -f 3600//3600 3442//3442 3601//3601 -f 3601//3601 3442//3442 3598//3598 -f 3599//3599 3602//3602 3441//3441 -f 3441//3441 3602//3602 3443//3443 -f 3441//3441 3443//3443 2902//2902 -f 2902//2902 3443//3443 2901//2901 -f 3603//3603 3354//3354 3604//3604 -f 3604//3604 3354//3354 3443//3443 -f 3604//3604 3443//3443 3605//3605 -f 3605//3605 3443//3443 3602//3602 -f 3603//3603 3606//3606 3354//3354 -f 3354//3354 3606//3606 3213//3213 -f 3354//3354 3213//3213 3353//3353 -f 3353//3353 3213//3213 3212//3212 -f 3360//3360 3607//3607 3358//3358 -f 3358//3358 3607//3607 3357//3357 -f 3358//3358 3357//3357 3608//3608 -f 3608//3608 3357//3357 3356//3356 -f 3608//3608 3356//3356 3609//3609 -f 3609//3609 3356//3356 3213//3213 -f 3609//3609 3213//3213 3610//3610 -f 3610//3610 3213//3213 3606//3606 -f 3457//3457 3456//3456 3611//3611 -f 3612//3612 3613//3613 3614//3614 -f 3615//3615 3616//3616 3617//3617 -f 3618//3618 3619//3619 3620//3620 -f 3621//3621 3622//3622 3623//3623 -f 3624//3624 3625//3625 3626//3626 -f 3626//3626 3625//3625 3627//3627 -f 3626//3626 3627//3627 3628//3628 -f 3628//3628 3627//3627 3629//3629 -f 3628//3628 3629//3629 3630//3630 -f 3631//3631 3632//3632 3633//3633 -f 3633//3633 3632//3632 3634//3634 -f 3633//3633 3634//3634 3624//3624 -f 3635//3635 3636//3636 3623//3623 -f 3623//3623 3636//3636 3637//3637 -f 3623//3623 3637//3637 3621//3621 -f 3619//3619 3638//3638 3635//3635 -f 3635//3635 3638//3638 3639//3639 -f 3635//3635 3639//3639 3636//3636 -f 3640//3640 3641//3641 3642//3642 -f 3642//3642 3641//3641 3643//3643 -f 3618//3618 3620//3620 3644//3644 -f 3640//3640 3642//3642 3645//3645 -f 3645//3645 3642//3642 3646//3646 -f 3645//3645 3646//3646 3647//3647 -f 3648//3648 3649//3649 3646//3646 -f 3646//3646 3649//3649 3650//3650 -f 3646//3646 3650//3650 3647//3647 -f 3651//3651 3652//3652 3653//3653 -f 3652//3652 3654//3654 3653//3653 -f 3653//3653 3654//3654 3655//3655 -f 3653//3653 3655//3655 3648//3648 -f 3656//3656 3657//3657 3658//3658 -f 3658//3658 3657//3657 3659//3659 -f 3658//3658 3659//3659 3660//3660 -f 3660//3660 3659//3659 3661//3661 -f 3660//3660 3661//3661 3662//3662 -f 3663//3663 3656//3656 3664//3664 -f 3665//3665 3666//3666 3664//3664 -f 3664//3664 3666//3666 3667//3667 -f 3664//3664 3667//3667 3663//3663 -f 3668//3668 3669//3669 3670//3670 -f 3670//3670 3669//3669 3671//3671 -f 3668//3668 3670//3670 3672//3672 -f 3672//3672 3670//3670 3673//3673 -f 3672//3672 3673//3673 3674//3674 -f 3675//3675 3676//3676 3677//3677 -f 3677//3677 3678//3678 3673//3673 -f 3673//3673 3678//3678 3679//3679 -f 3673//3673 3679//3679 3674//3674 -f 3680//3680 3681//3681 3675//3675 -f 3675//3675 3681//3681 3682//3682 -f 3675//3675 3682//3682 3676//3676 -f 3615//3615 3617//3617 3683//3683 -f 3683//3683 3617//3617 3684//3684 -f 3683//3683 3684//3684 3685//3685 -f 3686//3686 3687//3687 3688//3688 -f 3688//3688 3687//3687 3689//3689 -f 3688//3688 3690//3690 3686//3686 -f 3686//3686 3690//3690 3691//3691 -f 3686//3686 3691//3691 3684//3684 -f 3684//3684 3691//3691 3692//3692 -f 3684//3684 3692//3692 3685//3685 -f 3689//3689 3687//3687 3693//3693 -f 3693//3693 3687//3687 3694//3694 -f 3693//3693 3694//3694 3695//3695 -f 3696//3696 3206//3206 3697//3697 -f 3697//3697 3206//3206 3205//3205 -f 3697//3697 3205//3205 3698//3698 -f 3696//3696 3699//3699 3206//3206 -f 3206//3206 3699//3699 3700//3700 -f 3206//3206 3700//3700 3202//3202 -f 3445//3445 3444//3444 3701//3701 -f 3701//3701 3702//3702 3445//3445 -f 3445//3445 3702//3702 3703//3703 -f 3445//3445 3703//3703 3208//3208 -f 3703//3703 3704//3704 3208//3208 -f 3208//3208 3704//3704 3705//3705 -f 3208//3208 3705//3705 3209//3209 -f 3209//3209 3705//3705 3706//3706 -f 3209//3209 3706//3706 3205//3205 -f 3205//3205 3706//3706 3707//3707 -f 3205//3205 3707//3707 3698//3698 -f 3300//3300 3298//3298 3708//3708 -f 3708//3708 3709//3709 3300//3300 -f 3300//3300 3709//3709 3710//3710 -f 3300//3300 3710//3710 3444//3444 -f 3444//3444 3710//3710 3711//3711 -f 3444//3444 3711//3711 3701//3701 -f 3712//3712 3303//3303 3713//3713 -f 3713//3713 3303//3303 3221//3221 -f 3713//3713 3221//3221 3714//3714 -f 3714//3714 3221//3221 3291//3291 -f 3714//3714 3291//3291 3715//3715 -f 3712//3712 3716//3716 3303//3303 -f 3303//3303 3716//3716 3717//3717 -f 3303//3303 3717//3717 3296//3296 -f 3296//3296 3717//3717 3718//3718 -f 3296//3296 3718//3718 3298//3298 -f 3298//3298 3718//3718 3719//3719 -f 3298//3298 3719//3719 3708//3708 -f 3279//3279 3278//3278 3720//3720 -f 3720//3720 3721//3721 3279//3279 -f 3279//3279 3721//3721 3722//3722 -f 3279//3279 3722//3722 3286//3286 -f 3286//3286 3722//3722 3723//3723 -f 3723//3723 3724//3724 3286//3286 -f 3286//3286 3724//3724 3725//3725 -f 3286//3286 3725//3725 3290//3290 -f 3290//3290 3725//3725 3726//3726 -f 3290//3290 3726//3726 3291//3291 -f 3291//3291 3726//3726 3727//3727 -f 3291//3291 3727//3727 3715//3715 -f 3283//3283 3275//3275 3728//3728 -f 3728//3728 3729//3729 3283//3283 -f 3283//3283 3729//3729 3730//3730 -f 3283//3283 3730//3730 3278//3278 -f 3278//3278 3730//3730 3731//3731 -f 3278//3278 3731//3731 3720//3720 -f 3270//3270 3732//3732 3275//3275 -f 3275//3275 3732//3732 3733//3733 -f 3275//3275 3733//3733 3728//3728 -f 3734//3734 3735//3735 3272//3272 -f 3735//3735 3736//3736 3272//3272 -f 3272//3272 3736//3736 3737//3737 -f 3272//3272 3737//3737 3270//3270 -f 3270//3270 3737//3737 3738//3738 -f 3270//3270 3738//3738 3732//3732 -f 3739//3739 3265//3265 3740//3740 -f 3740//3740 3265//3265 3224//3224 -f 3272//3272 3266//3266 3734//3734 -f 3734//3734 3266//3266 3265//3265 -f 3734//3734 3265//3265 3741//3741 -f 3741//3741 3265//3265 3739//3739 -f 3742//3742 3224//3224 3743//3743 -f 3743//3743 3224//3224 3257//3257 -f 3742//3742 3744//3744 3224//3224 -f 3224//3224 3744//3744 3745//3745 -f 3224//3224 3745//3745 3740//3740 -f 3746//3746 3747//3747 3254//3254 -f 3254//3254 3747//3747 3748//3748 -f 3254//3254 3748//3748 3256//3256 -f 3256//3256 3748//3748 3749//3749 -f 3256//3256 3749//3749 3257//3257 -f 3257//3257 3749//3749 3750//3750 -f 3257//3257 3750//3750 3743//3743 -f 3227//3227 3751//3751 3254//3254 -f 3254//3254 3751//3751 3752//3752 -f 3254//3254 3752//3752 3746//3746 -f 3242//3242 3244//3244 3753//3753 -f 3753//3753 3754//3754 3242//3242 -f 3242//3242 3754//3754 3755//3755 -f 3242//3242 3755//3755 3249//3249 -f 3755//3755 3756//3756 3249//3249 -f 3249//3249 3756//3756 3757//3757 -f 3249//3249 3757//3757 3227//3227 -f 3227//3227 3757//3757 3758//3758 -f 3227//3227 3758//3758 3751//3751 -f 3230//3230 3759//3759 3244//3244 -f 3244//3244 3759//3759 3760//3760 -f 3244//3244 3760//3760 3753//3753 -f 3761//3761 3762//3762 3232//3232 -f 3232//3232 3762//3762 3763//3763 -f 3232//3232 3763//3763 3230//3230 -f 3230//3230 3763//3763 3764//3764 -f 3230//3230 3764//3764 3759//3759 -f 3761//3761 3232//3232 3765//3765 -f 3765//3765 3232//3232 3235//3235 -f 3765//3765 3235//3235 3766//3766 -f 3766//3766 3235//3235 3237//3237 -f 3766//3766 3237//3237 3767//3767 -f 3767//3767 3237//3237 3239//3239 -f 3767//3767 3239//3239 3241//3241 -f 3362//3362 3768//3768 3769//3769 -f 3770//3770 3771//3771 3769//3769 -f 3769//3769 3771//3771 3772//3772 -f 3769//3769 3772//3772 3362//3362 -f 3613//3613 3612//3612 3769//3769 -f 3769//3769 3612//3612 3773//3773 -f 3769//3769 3773//3773 3770//3770 -f 3699//3699 3695//3695 3700//3700 -f 3700//3700 3695//3695 3694//3694 -f 3700//3700 3694//3694 3202//3202 -f 3202//3202 3694//3694 3687//3687 -f 3202//3202 3687//3687 3203//3203 -f 3203//3203 3687//3687 3686//3686 -f 3203//3203 3686//3686 3199//3199 -f 3199//3199 3686//3686 3684//3684 -f 3199//3199 3684//3684 3200//3200 -f 3200//3200 3684//3684 3617//3617 -f 3200//3200 3617//3617 3196//3196 -f 3196//3196 3617//3617 3197//3197 -f 3193//3193 3197//3197 3675//3675 -f 3675//3675 3197//3197 3617//3617 -f 3675//3675 3617//3617 3680//3680 -f 3680//3680 3617//3617 3616//3616 -f 3677//3677 3673//3673 3675//3675 -f 3675//3675 3673//3673 3194//3194 -f 3675//3675 3194//3194 3193//3193 -f 3188//3188 3187//3187 3670//3670 -f 3670//3670 3187//3187 3191//3191 -f 3670//3670 3191//3191 3673//3673 -f 3673//3673 3191//3191 3190//3190 -f 3673//3673 3190//3190 3194//3194 -f 3184//3184 3188//3188 3664//3664 -f 3664//3664 3188//3188 3670//3670 -f 3664//3664 3670//3670 3665//3665 -f 3665//3665 3670//3670 3671//3671 -f 3656//3656 3658//3658 3664//3664 -f 3664//3664 3658//3658 3185//3185 -f 3664//3664 3185//3185 3184//3184 -f 3179//3179 3178//3178 3660//3660 -f 3660//3660 3178//3178 3182//3182 -f 3660//3660 3182//3182 3658//3658 -f 3658//3658 3182//3182 3181//3181 -f 3658//3658 3181//3181 3185//3185 -f 3175//3175 3179//3179 3653//3653 -f 3653//3653 3179//3179 3660//3660 -f 3653//3653 3660//3660 3651//3651 -f 3651//3651 3660//3660 3662//3662 -f 3648//3648 3646//3646 3653//3653 -f 3653//3653 3646//3646 3176//3176 -f 3653//3653 3176//3176 3175//3175 -f 3170//3170 3169//3169 3642//3642 -f 3642//3642 3169//3169 3173//3173 -f 3642//3642 3173//3173 3646//3646 -f 3646//3646 3173//3173 3172//3172 -f 3646//3646 3172//3172 3176//3176 -f 3166//3166 3170//3170 3620//3620 -f 3620//3620 3170//3170 3642//3642 -f 3620//3620 3642//3642 3644//3644 -f 3644//3644 3642//3642 3643//3643 -f 3619//3619 3635//3635 3620//3620 -f 3620//3620 3635//3635 3167//3167 -f 3620//3620 3167//3167 3166//3166 -f 3161//3161 3160//3160 3623//3623 -f 3623//3623 3160//3160 3164//3164 -f 3623//3623 3164//3164 3635//3635 -f 3635//3635 3164//3164 3163//3163 -f 3635//3635 3163//3163 3167//3167 -f 3157//3157 3161//3161 3633//3633 -f 3633//3633 3161//3161 3623//3623 -f 3633//3633 3623//3623 3631//3631 -f 3631//3631 3623//3623 3622//3622 -f 3624//3624 3626//3626 3633//3633 -f 3633//3633 3626//3626 3158//3158 -f 3633//3633 3158//3158 3157//3157 -f 3152//3152 3151//3151 3628//3628 -f 3628//3628 3151//3151 3155//3155 -f 3628//3628 3155//3155 3626//3626 -f 3626//3626 3155//3155 3154//3154 -f 3626//3626 3154//3154 3158//3158 -f 3630//3630 3774//3774 3628//3628 -f 3628//3628 3774//3774 3775//3775 -f 3628//3628 3775//3775 3152//3152 -f 3776//3776 3149//3149 3775//3775 -f 3775//3775 3149//3149 3148//3148 -f 3775//3775 3148//3148 3152//3152 -f 3777//3777 3146//3146 3776//3776 -f 3776//3776 3146//3146 3145//3145 -f 3776//3776 3145//3145 3149//3149 -f 3778//3778 3143//3143 3777//3777 -f 3777//3777 3143//3143 3142//3142 -f 3777//3777 3142//3142 3146//3146 -f 3779//3779 3140//3140 3778//3778 -f 3778//3778 3140//3140 3139//3139 -f 3778//3778 3139//3139 3143//3143 -f 3780//3780 3137//3137 3779//3779 -f 3779//3779 3137//3137 3136//3136 -f 3779//3779 3136//3136 3140//3140 -f 3131//3131 3130//3130 3781//3781 -f 3781//3781 3130//3130 3134//3134 -f 3781//3781 3134//3134 3780//3780 -f 3780//3780 3134//3134 3133//3133 -f 3780//3780 3133//3133 3137//3137 -f 3127//3127 3782//3782 3128//3128 -f 3128//3128 3782//3782 3783//3783 -f 3128//3128 3783//3783 3124//3124 -f 3124//3124 3783//3783 3125//3125 -f 3121//3121 3784//3784 3122//3122 -f 3122//3122 3784//3784 3785//3785 -f 3786//3786 3119//3119 3785//3785 -f 3785//3785 3119//3119 3118//3118 -f 3785//3785 3118//3118 3122//3122 -f 3787//3787 3116//3116 3786//3786 -f 3786//3786 3116//3116 3115//3115 -f 3786//3786 3115//3115 3119//3119 -f 3788//3788 3113//3113 3787//3787 -f 3787//3787 3113//3113 3112//3112 -f 3787//3787 3112//3112 3116//3116 -f 3789//3789 3110//3110 3788//3788 -f 3788//3788 3110//3110 3109//3109 -f 3788//3788 3109//3109 3113//3113 -f 3104//3104 3103//3103 3790//3790 -f 3790//3790 3103//3103 3107//3107 -f 3790//3790 3107//3107 3789//3789 -f 3789//3789 3107//3107 3106//3106 -f 3789//3789 3106//3106 3110//3110 -f 3100//3100 3791//3791 3101//3101 -f 3101//3101 3791//3791 3792//3792 -f 3101//3101 3792//3792 3097//3097 -f 3097//3097 3792//3792 3098//3098 -f 3094//3094 3793//3793 3095//3095 -f 3095//3095 3793//3793 3794//3794 -f 3795//3795 3092//3092 3794//3794 -f 3794//3794 3092//3092 3091//3091 -f 3794//3794 3091//3091 3095//3095 -f 3796//3796 3089//3089 3795//3795 -f 3795//3795 3089//3089 3088//3088 -f 3795//3795 3088//3088 3092//3092 -f 3797//3797 3086//3086 3796//3796 -f 3796//3796 3086//3086 3085//3085 -f 3796//3796 3085//3085 3089//3089 -f 3798//3798 3083//3083 3797//3797 -f 3797//3797 3083//3083 3082//3082 -f 3797//3797 3082//3082 3086//3086 -f 3077//3077 3076//3076 3799//3799 -f 3799//3799 3076//3076 3080//3080 -f 3799//3799 3080//3080 3798//3798 -f 3798//3798 3080//3080 3079//3079 -f 3798//3798 3079//3079 3083//3083 -f 3073//3073 3800//3800 3074//3074 -f 3074//3074 3800//3800 3801//3801 -f 3074//3074 3801//3801 3070//3070 -f 3070//3070 3801//3801 3071//3071 -f 3067//3067 3802//3802 3068//3068 -f 3068//3068 3802//3802 3803//3803 -f 3804//3804 3065//3065 3803//3803 -f 3803//3803 3065//3065 3064//3064 -f 3803//3803 3064//3064 3068//3068 -f 3805//3805 3062//3062 3804//3804 -f 3804//3804 3062//3062 3061//3061 -f 3804//3804 3061//3061 3065//3065 -f 3806//3806 3059//3059 3805//3805 -f 3805//3805 3059//3059 3058//3058 -f 3805//3805 3058//3058 3062//3062 -f 3807//3807 3056//3056 3806//3806 -f 3806//3806 3056//3056 3055//3055 -f 3806//3806 3055//3055 3059//3059 -f 3050//3050 3049//3049 3808//3808 -f 3808//3808 3049//3049 3053//3053 -f 3808//3808 3053//3053 3807//3807 -f 3807//3807 3053//3053 3052//3052 -f 3807//3807 3052//3052 3056//3056 -f 3046//3046 3809//3809 3047//3047 -f 3047//3047 3809//3809 3810//3810 -f 3047//3047 3810//3810 3043//3043 -f 3043//3043 3810//3810 3044//3044 -f 3040//3040 3811//3811 3041//3041 -f 3041//3041 3811//3811 3812//3812 -f 3813//3813 3038//3038 3812//3812 -f 3812//3812 3038//3038 3037//3037 -f 3812//3812 3037//3037 3041//3041 -f 3814//3814 3035//3035 3813//3813 -f 3813//3813 3035//3035 3034//3034 -f 3813//3813 3034//3034 3038//3038 -f 3029//3029 3028//3028 3815//3815 -f 3815//3815 3028//3028 3032//3032 -f 3815//3815 3032//3032 3814//3814 -f 3814//3814 3032//3032 3031//3031 -f 3814//3814 3031//3031 3035//3035 -f 3025//3025 3816//3816 3026//3026 -f 3026//3026 3816//3816 3817//3817 -f 3818//3818 3023//3023 3817//3817 -f 3817//3817 3023//3023 3022//3022 -f 3817//3817 3022//3022 3026//3026 -f 3017//3017 3016//3016 3819//3819 -f 3819//3819 3016//3016 3020//3020 -f 3819//3819 3020//3020 3818//3818 -f 3818//3818 3020//3020 3019//3019 -f 3818//3818 3019//3019 3023//3023 -f 3013//3013 3820//3820 3014//3014 -f 3014//3014 3820//3820 3821//3821 -f 3008//3008 3007//3007 3822//3822 -f 3822//3822 3007//3007 3011//3011 -f 3822//3822 3011//3011 3821//3821 -f 3821//3821 3011//3011 3010//3010 -f 3821//3821 3010//3010 3014//3014 -f 3004//3004 3823//3823 3005//3005 -f 3005//3005 3823//3823 3824//3824 -f 3005//3005 3824//3824 3001//3001 -f 3001//3001 3824//3824 3002//3002 -f 2998//2998 3825//3825 2999//2999 -f 2999//2999 3825//3825 3826//3826 -f 3827//3827 2996//2996 3826//3826 -f 3826//3826 2996//2996 2995//2995 -f 3826//3826 2995//2995 2999//2999 -f 2990//2990 2989//2989 3828//3828 -f 3828//3828 2989//2989 2993//2993 -f 3828//3828 2993//2993 3827//3827 -f 3827//3827 2993//2993 2992//2992 -f 3827//3827 2992//2992 2996//2996 -f 2986//2986 3829//3829 2987//2987 -f 2987//2987 3829//3829 3830//3830 -f 2981//2981 2980//2980 3831//3831 -f 3831//3831 2980//2980 2984//2984 -f 3831//3831 2984//2984 3830//3830 -f 3830//3830 2984//2984 2983//2983 -f 3830//3830 2983//2983 2987//2987 -f 2977//2977 3832//3832 2978//2978 -f 2978//2978 3832//3832 3833//3833 -f 2978//2978 3833//3833 2974//2974 -f 2974//2974 3833//3833 2975//2975 -f 2971//2971 3834//3834 2972//2972 -f 2972//2972 3834//3834 3835//3835 -f 3836//3836 2969//2969 3835//3835 -f 3835//3835 2969//2969 2968//2968 -f 3835//3835 2968//2968 2972//2972 -f 3837//3837 2966//2966 3836//3836 -f 3836//3836 2966//2966 2965//2965 -f 3836//3836 2965//2965 2969//2969 -f 3838//3838 2963//2963 3837//3837 -f 3837//3837 2963//2963 2962//2962 -f 3837//3837 2962//2962 2966//2966 -f 3839//3839 2960//2960 3838//3838 -f 3838//3838 2960//2960 2959//2959 -f 3838//3838 2959//2959 2963//2963 -f 2954//2954 2953//2953 3840//3840 -f 3840//3840 2953//2953 2957//2957 -f 3840//3840 2957//2957 3839//3839 -f 3839//3839 2957//2957 2956//2956 -f 3839//3839 2956//2956 2960//2960 -f 2950//2950 3841//3841 2951//2951 -f 2951//2951 3841//3841 3842//3842 -f 2951//2951 3842//3842 2947//2947 -f 2947//2947 3842//3842 2948//2948 -f 2944//2944 3843//3843 2945//2945 -f 2945//2945 3843//3843 3844//3844 -f 3845//3845 2942//2942 3844//3844 -f 3844//3844 2942//2942 2941//2941 -f 3844//3844 2941//2941 2945//2945 -f 3846//3846 2939//2939 3845//3845 -f 3845//3845 2939//2939 2938//2938 -f 3845//3845 2938//2938 2942//2942 -f 3847//3847 2936//2936 3846//3846 -f 3846//3846 2936//2936 2935//2935 -f 3846//3846 2935//2935 2939//2939 -f 3848//3848 2933//2933 3847//3847 -f 3847//3847 2933//2933 2932//2932 -f 3847//3847 2932//2932 2936//2936 -f 3447//3447 3446//3446 3849//3849 -f 3849//3849 3446//3446 2930//2930 -f 3849//3849 2930//2930 3848//3848 -f 3848//3848 2930//2930 2929//2929 -f 3848//3848 2929//2929 2933//2933 -f 3448//3448 3850//3850 3449//3449 -f 3449//3449 3850//3850 3851//3851 -f 3452//3452 3451//3451 3851//3851 -f 3851//3851 3451//3451 3450//3450 -f 3851//3851 3450//3450 3449//3449 -f 3454//3454 3453//3453 3852//3852 -f 3852//3852 3453//3453 3853//3853 -f 3611//3611 3456//3456 3852//3852 -f 3852//3852 3456//3456 3455//3455 -f 3852//3852 3455//3455 3454//3454 -f 3457//3457 3611//3611 3458//3458 -f 3458//3458 3611//3611 3854//3854 -f 3458//3458 3854//3854 3459//3459 -f 3459//3459 3854//3854 3855//3855 -f 3459//3459 3855//3855 3460//3460 -f 3856//3856 3462//3462 3855//3855 -f 3855//3855 3462//3462 3461//3461 -f 3855//3855 3461//3461 3460//3460 -f 3466//3466 3465//3465 3857//3857 -f 3857//3857 3465//3465 3464//3464 -f 3857//3857 3464//3464 3856//3856 -f 3856//3856 3464//3464 3463//3463 -f 3856//3856 3463//3463 3462//3462 -f 3467//3467 3858//3858 3468//3468 -f 3468//3468 3858//3858 3859//3859 -f 3468//3468 3859//3859 3469//3469 -f 3469//3469 3859//3859 3470//3470 -f 3860//3860 3472//3472 3861//3861 -f 3861//3861 3472//3472 3471//3471 -f 3862//3862 3863//3863 3476//3476 -f 3476//3476 3475//3475 3862//3862 -f 3862//3862 3475//3475 3474//3474 -f 3862//3862 3474//3474 3860//3860 -f 3860//3860 3474//3474 3473//3473 -f 3860//3860 3473//3473 3472//3472 -f 3864//3864 3865//3865 3480//3480 -f 3480//3480 3479//3479 3864//3864 -f 3864//3864 3479//3479 3478//3478 -f 3864//3864 3478//3478 3863//3863 -f 3863//3863 3478//3478 3477//3477 -f 3863//3863 3477//3477 3476//3476 -f 3484//3484 3483//3483 3866//3866 -f 3866//3866 3483//3483 3482//3482 -f 3866//3866 3482//3482 3865//3865 -f 3865//3865 3482//3482 3481//3481 -f 3865//3865 3481//3481 3480//3480 -f 3485//3485 3867//3867 3486//3486 -f 3486//3486 3867//3867 3868//3868 -f 3486//3486 3868//3868 3487//3487 -f 3487//3487 3868//3868 3488//3488 -f 3869//3869 3490//3490 3870//3870 -f 3870//3870 3490//3490 3489//3489 -f 3871//3871 3872//3872 3494//3494 -f 3494//3494 3493//3493 3871//3871 -f 3871//3871 3493//3493 3492//3492 -f 3871//3871 3492//3492 3869//3869 -f 3869//3869 3492//3492 3491//3491 -f 3869//3869 3491//3491 3490//3490 -f 3873//3873 3874//3874 3498//3498 -f 3498//3498 3497//3497 3873//3873 -f 3873//3873 3497//3497 3496//3496 -f 3873//3873 3496//3496 3872//3872 -f 3872//3872 3496//3496 3495//3495 -f 3872//3872 3495//3495 3494//3494 -f 3502//3502 3501//3501 3875//3875 -f 3875//3875 3501//3501 3500//3500 -f 3875//3875 3500//3500 3874//3874 -f 3874//3874 3500//3500 3499//3499 -f 3874//3874 3499//3499 3498//3498 -f 3503//3503 3876//3876 3504//3504 -f 3504//3504 3876//3876 3877//3877 -f 3504//3504 3877//3877 3505//3505 -f 3505//3505 3877//3877 3506//3506 -f 3878//3878 3508//3508 3879//3879 -f 3879//3879 3508//3508 3507//3507 -f 3880//3880 3881//3881 3512//3512 -f 3512//3512 3511//3511 3880//3880 -f 3880//3880 3511//3511 3510//3510 -f 3880//3880 3510//3510 3878//3878 -f 3878//3878 3510//3510 3509//3509 -f 3878//3878 3509//3509 3508//3508 -f 3516//3516 3515//3515 3882//3882 -f 3882//3882 3515//3515 3514//3514 -f 3882//3882 3514//3514 3881//3881 -f 3881//3881 3514//3514 3513//3513 -f 3881//3881 3513//3513 3512//3512 -f 3883//3883 3884//3884 3520//3520 -f 3517//3517 3885//3885 3518//3518 -f 3518//3518 3885//3885 3883//3883 -f 3518//3518 3883//3883 3519//3519 -f 3519//3519 3883//3883 3520//3520 -f 3524//3524 3523//3523 3886//3886 -f 3886//3886 3523//3523 3522//3522 -f 3886//3886 3522//3522 3884//3884 -f 3884//3884 3522//3522 3521//3521 -f 3884//3884 3521//3521 3520//3520 -f 3887//3887 3526//3526 3888//3888 -f 3888//3888 3526//3526 3525//3525 -f 3889//3889 3890//3890 3530//3530 -f 3530//3530 3529//3529 3889//3889 -f 3889//3889 3529//3529 3528//3528 -f 3889//3889 3528//3528 3887//3887 -f 3887//3887 3528//3528 3527//3527 -f 3887//3887 3527//3527 3526//3526 -f 3534//3534 3533//3533 3891//3891 -f 3891//3891 3533//3533 3532//3532 -f 3891//3891 3532//3532 3890//3890 -f 3890//3890 3532//3532 3531//3531 -f 3890//3890 3531//3531 3530//3530 -f 3892//3892 3536//3536 3893//3893 -f 3893//3893 3536//3536 3535//3535 -f 3894//3894 3539//3539 3895//3895 -f 3895//3895 3539//3539 3538//3538 -f 3895//3895 3538//3538 3892//3892 -f 3892//3892 3538//3538 3537//3537 -f 3892//3892 3537//3537 3536//3536 -f 3542//3542 3541//3541 3894//3894 -f 3894//3894 3541//3541 3540//3540 -f 3894//3894 3540//3540 3539//3539 -f 3896//3896 3897//3897 3545//3545 -f 3549//3549 3546//3546 3898//3898 -f 3898//3898 3546//3546 3543//3543 -f 3898//3898 3543//3543 3897//3897 -f 3897//3897 3543//3543 3544//3544 -f 3897//3897 3544//3544 3545//3545 -f 3548//3548 3899//3899 3547//3547 -f 3547//3547 3899//3899 3900//3900 -f 3547//3547 3900//3900 3550//3550 -f 3550//3550 3900//3900 3553//3553 -f 3552//3552 3901//3901 3551//3551 -f 3551//3551 3901//3901 3902//3902 -f 3903//3903 3557//3557 3902//3902 -f 3902//3902 3557//3557 3554//3554 -f 3902//3902 3554//3554 3551//3551 -f 3904//3904 3555//3555 3903//3903 -f 3903//3903 3555//3555 3556//3556 -f 3903//3903 3556//3556 3557//3557 -f 3905//3905 3561//3561 3904//3904 -f 3904//3904 3561//3561 3558//3558 -f 3904//3904 3558//3558 3555//3555 -f 3906//3906 3559//3559 3905//3905 -f 3905//3905 3559//3559 3560//3560 -f 3905//3905 3560//3560 3561//3561 -f 3563//3563 3564//3564 3907//3907 -f 3907//3907 3564//3564 3565//3565 -f 3907//3907 3565//3565 3906//3906 -f 3906//3906 3565//3565 3562//3562 -f 3906//3906 3562//3562 3559//3559 -f 3566//3566 3908//3908 3569//3569 -f 3569//3569 3908//3908 3909//3909 -f 3569//3569 3909//3909 3568//3568 -f 3568//3568 3909//3909 3567//3567 -f 3570//3570 3910//3910 3573//3573 -f 3573//3573 3910//3910 3911//3911 -f 3912//3912 3571//3571 3911//3911 -f 3911//3911 3571//3571 3572//3572 -f 3911//3911 3572//3572 3573//3573 -f 3913//3913 3577//3577 3912//3912 -f 3912//3912 3577//3577 3574//3574 -f 3912//3912 3574//3574 3571//3571 -f 3914//3914 3575//3575 3913//3913 -f 3913//3913 3575//3575 3576//3576 -f 3913//3913 3576//3576 3577//3577 -f 3915//3915 3581//3581 3914//3914 -f 3914//3914 3581//3581 3578//3578 -f 3914//3914 3578//3578 3575//3575 -f 3585//3585 3582//3582 3916//3916 -f 3916//3916 3582//3582 3579//3579 -f 3916//3916 3579//3579 3915//3915 -f 3915//3915 3579//3579 3580//3580 -f 3915//3915 3580//3580 3581//3581 -f 3584//3584 3917//3917 3583//3583 -f 3583//3583 3917//3917 3918//3918 -f 3583//3583 3918//3918 3586//3586 -f 3586//3586 3918//3918 3589//3589 -f 3588//3588 3919//3919 3587//3587 -f 3587//3587 3919//3919 3920//3920 -f 3921//3921 3593//3593 3920//3920 -f 3920//3920 3593//3593 3590//3590 -f 3920//3920 3590//3590 3587//3587 -f 3922//3922 3591//3591 3921//3921 -f 3921//3921 3591//3591 3592//3592 -f 3921//3921 3592//3592 3593//3593 -f 3923//3923 3597//3597 3922//3922 -f 3922//3922 3597//3597 3594//3594 -f 3922//3922 3594//3594 3591//3591 -f 3924//3924 3595//3595 3923//3923 -f 3923//3923 3595//3595 3596//3596 -f 3923//3923 3596//3596 3597//3597 -f 3599//3599 3600//3600 3925//3925 -f 3925//3925 3600//3600 3601//3601 -f 3925//3925 3601//3601 3924//3924 -f 3924//3924 3601//3601 3598//3598 -f 3924//3924 3598//3598 3595//3595 -f 3602//3602 3926//3926 3605//3605 -f 3605//3605 3926//3926 3927//3927 -f 3605//3605 3927//3927 3604//3604 -f 3604//3604 3927//3927 3603//3603 -f 3606//3606 3928//3928 3610//3610 -f 3610//3610 3928//3928 3929//3929 -f 3930//3930 3608//3608 3929//3929 -f 3929//3929 3608//3608 3609//3609 -f 3929//3929 3609//3609 3610//3610 -f 3362//3362 3361//3361 3768//3768 -f 3768//3768 3361//3361 3359//3359 -f 3768//3768 3359//3359 3930//3930 -f 3930//3930 3359//3359 3358//3358 -f 3930//3930 3358//3358 3608//3608 -f 3774//3774 2383//2383 3775//3775 -f 3775//3775 2383//2383 2382//2382 -f 3775//3775 2382//2382 3776//3776 -f 3776//3776 2382//2382 2380//2380 -f 3776//3776 2380//2380 3777//3777 -f 2380//2380 2378//2378 3777//3777 -f 3777//3777 2378//2378 2377//2377 -f 3777//3777 2377//2377 3778//3778 -f 3778//3778 2377//2377 2384//2384 -f 3778//3778 2384//2384 3779//3779 -f 2384//2384 2386//2386 3779//3779 -f 3779//3779 2386//2386 2388//2388 -f 3779//3779 2388//2388 3780//3780 -f 3780//3780 2388//2388 2389//2389 -f 3780//3780 2389//2389 3781//3781 -f 3781//3781 2389//2389 2391//2391 -f 2391//2391 2392//2392 3781//3781 -f 3781//3781 2392//2392 3782//3782 -f 3781//3781 3782//3782 3131//3131 -f 3131//3131 3782//3782 3127//3127 -f 2393//2393 3783//3783 2374//2374 -f 2374//2374 3783//3783 3782//3782 -f 2374//2374 3782//3782 2375//2375 -f 2375//2375 3782//3782 2392//2392 -f 2393//2393 2395//2395 3783//3783 -f 3783//3783 2395//2395 3784//3784 -f 3783//3783 3784//3784 3125//3125 -f 3125//3125 3784//3784 3121//3121 -f 2395//2395 2398//2398 3784//3784 -f 3784//3784 2398//2398 2400//2400 -f 3784//3784 2400//2400 3785//3785 -f 3785//3785 2400//2400 2401//2401 -f 3785//3785 2401//2401 3786//3786 -f 2401//2401 2403//2403 3786//3786 -f 3786//3786 2403//2403 2405//2405 -f 3786//3786 2405//2405 3787//3787 -f 3787//3787 2405//2405 2407//2407 -f 3787//3787 2407//2407 3788//3788 -f 2407//2407 2410//2410 3788//3788 -f 3788//3788 2410//2410 2412//2412 -f 3788//3788 2412//2412 3789//3789 -f 3789//3789 2412//2412 2414//2414 -f 3789//3789 2414//2414 3790//3790 -f 3790//3790 2414//2414 2416//2416 -f 2416//2416 2418//2418 3790//3790 -f 3790//3790 2418//2418 3791//3791 -f 3790//3790 3791//3791 3104//3104 -f 3104//3104 3791//3791 3100//3100 -f 2424//2424 3792//3792 2422//2422 -f 2422//2422 3792//3792 3791//3791 -f 2422//2422 3791//3791 2420//2420 -f 2420//2420 3791//3791 2418//2418 -f 2424//2424 2426//2426 3792//3792 -f 3792//3792 2426//2426 3793//3793 -f 3792//3792 3793//3793 3098//3098 -f 3098//3098 3793//3793 3094//3094 -f 2426//2426 2428//2428 3793//3793 -f 3793//3793 2428//2428 2430//2430 -f 3793//3793 2430//2430 3794//3794 -f 3794//3794 2430//2430 2432//2432 -f 3794//3794 2432//2432 3795//3795 -f 2432//2432 2434//2434 3795//3795 -f 3795//3795 2434//2434 2436//2436 -f 3795//3795 2436//2436 3796//3796 -f 3796//3796 2436//2436 2438//2438 -f 3796//3796 2438//2438 3797//3797 -f 2438//2438 2441//2441 3797//3797 -f 3797//3797 2441//2441 2443//2443 -f 3797//3797 2443//2443 3798//3798 -f 3798//3798 2443//2443 2445//2445 -f 3798//3798 2445//2445 3799//3799 -f 3799//3799 2445//2445 2447//2447 -f 2447//2447 2448//2448 3799//3799 -f 3799//3799 2448//2448 3800//3800 -f 3799//3799 3800//3800 3077//3077 -f 3077//3077 3800//3800 3073//3073 -f 2454//2454 3801//3801 2452//2452 -f 2452//2452 3801//3801 3800//3800 -f 2452//2452 3800//3800 2450//2450 -f 2450//2450 3800//3800 2448//2448 -f 2454//2454 2456//2456 3801//3801 -f 3801//3801 2456//2456 3802//3802 -f 3801//3801 3802//3802 3071//3071 -f 3071//3071 3802//3802 3067//3067 -f 2456//2456 2458//2458 3802//3802 -f 3802//3802 2458//2458 2460//2460 -f 3802//3802 2460//2460 3803//3803 -f 3803//3803 2460//2460 2462//2462 -f 3803//3803 2462//2462 3804//3804 -f 2462//2462 2464//2464 3804//3804 -f 3804//3804 2464//2464 2466//2466 -f 3804//3804 2466//2466 3805//3805 -f 3805//3805 2466//2466 2468//2468 -f 3805//3805 2468//2468 3806//3806 -f 2468//2468 2471//2471 3806//3806 -f 3806//3806 2471//2471 2473//2473 -f 3806//3806 2473//2473 3807//3807 -f 3807//3807 2473//2473 2475//2475 -f 3807//3807 2475//2475 3808//3808 -f 3808//3808 2475//2475 2477//2477 -f 2477//2477 2478//2478 3808//3808 -f 3808//3808 2478//2478 3809//3809 -f 3808//3808 3809//3809 3050//3050 -f 3050//3050 3809//3809 3046//3046 -f 2484//2484 3810//3810 2482//2482 -f 2482//2482 3810//3810 3809//3809 -f 2482//2482 3809//3809 2480//2480 -f 2480//2480 3809//3809 2478//2478 -f 2484//2484 2486//2486 3810//3810 -f 3810//3810 2486//2486 3811//3811 -f 3810//3810 3811//3811 3044//3044 -f 3044//3044 3811//3811 3040//3040 -f 2486//2486 2488//2488 3811//3811 -f 3811//3811 2488//2488 2490//2490 -f 3811//3811 2490//2490 3812//3812 -f 3812//3812 2490//2490 2492//2492 -f 3812//3812 2492//2492 3813//3813 -f 2501//2501 3815//3815 2498//2498 -f 2498//2498 3815//3815 3814//3814 -f 2498//2498 3814//3814 2496//2496 -f 2496//2496 3814//3814 3813//3813 -f 2496//2496 3813//3813 2494//2494 -f 2494//2494 3813//3813 2492//2492 -f 2501//2501 2503//2503 3815//3815 -f 3815//3815 2503//2503 3816//3816 -f 3815//3815 3816//3816 3029//3029 -f 3029//3029 3816//3816 3025//3025 -f 2503//2503 2505//2505 3816//3816 -f 3816//3816 2505//2505 2523//2523 -f 3816//3816 2523//2523 3817//3817 -f 3817//3817 2523//2523 2522//2522 -f 3817//3817 2522//2522 3818//3818 -f 2516//2516 3819//3819 2518//2518 -f 2518//2518 3819//3819 3818//3818 -f 2518//2518 3818//3818 2520//2520 -f 2520//2520 3818//3818 2522//2522 -f 2516//2516 2514//2514 3819//3819 -f 3819//3819 2514//2514 3820//3820 -f 3819//3819 3820//3820 3017//3017 -f 3017//3017 3820//3820 3013//3013 -f 2514//2514 2512//2512 3820//3820 -f 3820//3820 2512//2512 2510//2510 -f 3820//3820 2510//2510 3821//3821 -f 3821//3821 2510//2510 2508//2508 -f 3821//3821 2508//2508 3822//3822 -f 3822//3822 2508//2508 2555//2555 -f 2555//2555 2554//2554 3822//3822 -f 3822//3822 2554//2554 3823//3823 -f 3822//3822 3823//3823 3008//3008 -f 3008//3008 3823//3823 3004//3004 -f 2548//2548 3824//3824 2550//2550 -f 2550//2550 3824//3824 3823//3823 -f 2550//2550 3823//3823 2552//2552 -f 2552//2552 3823//3823 2554//2554 -f 2548//2548 2546//2546 3824//3824 -f 3824//3824 2546//2546 3825//3825 -f 3824//3824 3825//3825 3002//3002 -f 3002//3002 3825//3825 2998//2998 -f 2546//2546 2544//2544 3825//3825 -f 3825//3825 2544//2544 2542//2542 -f 3825//3825 2542//2542 3826//3826 -f 3826//3826 2542//2542 2540//2540 -f 3826//3826 2540//2540 3827//3827 -f 2534//2534 3828//3828 2536//2536 -f 2536//2536 3828//3828 3827//3827 -f 2536//2536 3827//3827 2538//2538 -f 2538//2538 3827//3827 2540//2540 -f 2534//2534 2532//2532 3828//3828 -f 3828//3828 2532//2532 3829//3829 -f 3828//3828 3829//3829 2990//2990 -f 2990//2990 3829//3829 2986//2986 -f 2532//2532 2530//2530 3829//3829 -f 3829//3829 2530//2530 2528//2528 -f 3829//3829 2528//2528 3830//3830 -f 3830//3830 2528//2528 2526//2526 -f 3830//3830 2526//2526 3831//3831 -f 3831//3831 2526//2526 2525//2525 -f 2525//2525 2556//2556 3831//3831 -f 3831//3831 2556//2556 3832//3832 -f 3831//3831 3832//3832 2981//2981 -f 2981//2981 3832//3832 2977//2977 -f 2562//2562 3833//3833 2560//2560 -f 2560//2560 3833//3833 3832//3832 -f 2560//2560 3832//3832 2558//2558 -f 2558//2558 3832//3832 2556//2556 -f 2562//2562 2564//2564 3833//3833 -f 3833//3833 2564//2564 3834//3834 -f 3833//3833 3834//3834 2975//2975 -f 2975//2975 3834//3834 2971//2971 -f 2564//2564 2566//2566 3834//3834 -f 3834//3834 2566//2566 2568//2568 -f 3834//3834 2568//2568 3835//3835 -f 3835//3835 2568//2568 2570//2570 -f 3835//3835 2570//2570 3836//3836 -f 2570//2570 2572//2572 3836//3836 -f 3836//3836 2572//2572 2574//2574 -f 3836//3836 2574//2574 3837//3837 -f 3837//3837 2574//2574 2576//2576 -f 3837//3837 2576//2576 3838//3838 -f 2576//2576 2579//2579 3838//3838 -f 3838//3838 2579//2579 2581//2581 -f 3838//3838 2581//2581 3839//3839 -f 3839//3839 2581//2581 2583//2583 -f 3839//3839 2583//2583 3840//3840 -f 3840//3840 2583//2583 2585//2585 -f 2585//2585 2586//2586 3840//3840 -f 3840//3840 2586//2586 3841//3841 -f 3840//3840 3841//3841 2954//2954 -f 2954//2954 3841//3841 2950//2950 -f 2592//2592 3842//3842 2590//2590 -f 2590//2590 3842//3842 3841//3841 -f 2590//2590 3841//3841 2588//2588 -f 2588//2588 3841//3841 2586//2586 -f 2592//2592 2594//2594 3842//3842 -f 3842//3842 2594//2594 3843//3843 -f 3842//3842 3843//3843 2948//2948 -f 2948//2948 3843//3843 2944//2944 -f 2594//2594 2596//2596 3843//3843 -f 3843//3843 2596//2596 2598//2598 -f 3843//3843 2598//2598 3844//3844 -f 3844//3844 2598//2598 2600//2600 -f 3844//3844 2600//2600 3845//3845 -f 2600//2600 2602//2602 3845//3845 -f 3845//3845 2602//2602 2604//2604 -f 3845//3845 2604//2604 3846//3846 -f 3846//3846 2604//2604 2606//2606 -f 3846//3846 2606//2606 3847//3847 -f 2606//2606 2609//2609 3847//3847 -f 3847//3847 2609//2609 2611//2611 -f 3847//3847 2611//2611 3848//3848 -f 3848//3848 2611//2611 2613//2613 -f 3848//3848 2613//2613 3849//3849 -f 3849//3849 2613//2613 2615//2615 -f 2615//2615 2617//2617 3849//3849 -f 3849//3849 2617//2617 3850//3850 -f 3849//3849 3850//3850 3447//3447 -f 3447//3447 3850//3850 3448//3448 -f 2623//2623 3851//3851 2621//2621 -f 2621//2621 3851//3851 3850//3850 -f 2621//2621 3850//3850 2619//2619 -f 2619//2619 3850//3850 2617//2617 -f 2623//2623 2625//2625 3851//3851 -f 3851//3851 2625//2625 3853//3853 -f 3851//3851 3853//3853 3452//3452 -f 3452//3452 3853//3853 3453//3453 -f 2625//2625 2627//2627 3853//3853 -f 3853//3853 2627//2627 2629//2629 -f 3853//3853 2629//2629 3852//3852 -f 3852//3852 2629//2629 2631//2631 -f 3852//3852 2631//2631 3611//3611 -f 2631//2631 2633//2633 3611//3611 -f 3611//3611 2633//2633 2634//2634 -f 3611//3611 2634//2634 3854//3854 -f 3854//3854 2634//2634 2636//2636 -f 3854//3854 2636//2636 3855//3855 -f 2636//2636 2639//2639 3855//3855 -f 3855//3855 2639//2639 2641//2641 -f 3855//3855 2641//2641 3856//3856 -f 3856//3856 2641//2641 2643//2643 -f 3856//3856 2643//2643 3857//3857 -f 3857//3857 2643//2643 2645//2645 -f 2645//2645 2647//2647 3857//3857 -f 3857//3857 2647//2647 3858//3858 -f 3857//3857 3858//3858 3466//3466 -f 3466//3466 3858//3858 3467//3467 -f 2653//2653 3859//3859 2651//2651 -f 2651//2651 3859//3859 3858//3858 -f 2651//2651 3858//3858 2649//2649 -f 2649//2649 3858//3858 2647//2647 -f 2653//2653 2655//2655 3859//3859 -f 3859//3859 2655//2655 3861//3861 -f 3859//3859 3861//3861 3470//3470 -f 3470//3470 3861//3861 3471//3471 -f 2655//2655 2657//2657 3861//3861 -f 3861//3861 2657//2657 2659//2659 -f 3861//3861 2659//2659 3860//3860 -f 3860//3860 2659//2659 2661//2661 -f 3860//3860 2661//2661 3862//3862 -f 2661//2661 2663//2663 3862//3862 -f 3862//3862 2663//2663 2664//2664 -f 3862//3862 2664//2664 3863//3863 -f 3863//3863 2664//2664 2666//2666 -f 3863//3863 2666//2666 3864//3864 -f 2666//2666 2669//2669 3864//3864 -f 3864//3864 2669//2669 2671//2671 -f 3864//3864 2671//2671 3865//3865 -f 3865//3865 2671//2671 2673//2673 -f 3865//3865 2673//2673 3866//3866 -f 3866//3866 2673//2673 2675//2675 -f 2675//2675 2677//2677 3866//3866 -f 3866//3866 2677//2677 3867//3867 -f 3866//3866 3867//3867 3484//3484 -f 3484//3484 3867//3867 3485//3485 -f 2683//2683 3868//3868 2681//2681 -f 2681//2681 3868//3868 3867//3867 -f 2681//2681 3867//3867 2679//2679 -f 2679//2679 3867//3867 2677//2677 -f 2683//2683 2685//2685 3868//3868 -f 3868//3868 2685//2685 3870//3870 -f 3868//3868 3870//3870 3488//3488 -f 3488//3488 3870//3870 3489//3489 -f 2685//2685 2687//2687 3870//3870 -f 3870//3870 2687//2687 2689//2689 -f 3870//3870 2689//2689 3869//3869 -f 3869//3869 2689//2689 2690//2690 -f 3869//3869 2690//2690 3871//3871 -f 2690//2690 2692//2692 3871//3871 -f 3871//3871 2692//2692 2694//2694 -f 3871//3871 2694//2694 3872//3872 -f 3872//3872 2694//2694 2696//2696 -f 3872//3872 2696//2696 3873//3873 -f 2696//2696 2699//2699 3873//3873 -f 3873//3873 2699//2699 2701//2701 -f 3873//3873 2701//2701 3874//3874 -f 3874//3874 2701//2701 2703//2703 -f 3874//3874 2703//2703 3875//3875 -f 3875//3875 2703//2703 2713//2713 -f 2713//2713 2712//2712 3875//3875 -f 3875//3875 2712//2712 3876//3876 -f 3875//3875 3876//3876 3502//3502 -f 3502//3502 3876//3876 3503//3503 -f 2706//2706 3877//3877 2708//2708 -f 2708//2708 3877//3877 3876//3876 -f 2708//2708 3876//3876 2710//2710 -f 2710//2710 3876//3876 2712//2712 -f 2706//2706 2705//2705 3877//3877 -f 3877//3877 2705//2705 3879//3879 -f 3877//3877 3879//3879 3506//3506 -f 3506//3506 3879//3879 3507//3507 -f 2705//2705 2716//2716 3879//3879 -f 3879//3879 2716//2716 2718//2718 -f 3879//3879 2718//2718 3878//3878 -f 3878//3878 2718//2718 2720//2720 -f 3878//3878 2720//2720 3880//3880 -f 2728//2728 3882//3882 2726//2726 -f 2726//2726 3882//3882 3881//3881 -f 2726//2726 3881//3881 2723//2723 -f 2723//2723 3881//3881 3880//3880 -f 2723//2723 3880//3880 2722//2722 -f 2722//2722 3880//3880 2720//2720 -f 2728//2728 2730//2730 3882//3882 -f 3882//3882 2730//2730 3885//3885 -f 3882//3882 3885//3885 3516//3516 -f 3516//3516 3885//3885 3517//3517 -f 2730//2730 2733//2733 3885//3885 -f 3885//3885 2733//2733 2735//2735 -f 3885//3885 2735//2735 3883//3883 -f 3883//3883 2735//2735 2737//2737 -f 3883//3883 2737//2737 3884//3884 -f 2741//2741 3886//3886 2743//2743 -f 2743//2743 3886//3886 3884//3884 -f 2743//2743 3884//3884 2744//2744 -f 2744//2744 3884//3884 2737//2737 -f 2741//2741 2740//2740 3886//3886 -f 3886//3886 2740//2740 3888//3888 -f 3886//3886 3888//3888 3524//3524 -f 3524//3524 3888//3888 3525//3525 -f 2740//2740 2745//2745 3888//3888 -f 3888//3888 2745//2745 2747//2747 -f 3888//3888 2747//2747 3887//3887 -f 3887//3887 2747//2747 2750//2750 -f 3887//3887 2750//2750 3889//3889 -f 2759//2759 3891//3891 2756//2756 -f 2756//2756 3891//3891 3890//3890 -f 2756//2756 3890//3890 2754//2754 -f 2754//2754 3890//3890 3889//3889 -f 2754//2754 3889//3889 2752//2752 -f 2752//2752 3889//3889 2750//2750 -f 2759//2759 2761//2761 3891//3891 -f 3891//3891 2761//2761 3893//3893 -f 3891//3891 3893//3893 3534//3534 -f 3534//3534 3893//3893 3535//3535 -f 2761//2761 2763//2763 3893//3893 -f 3893//3893 2763//2763 2773//2773 -f 3893//3893 2773//2773 3892//3892 -f 3892//3892 2773//2773 2772//2772 -f 3892//3892 2772//2772 3895//3895 -f 2766//2766 3894//3894 2768//2768 -f 2768//2768 3894//3894 3895//3895 -f 2768//2768 3895//3895 2770//2770 -f 2770//2770 3895//3895 2772//2772 -f 2766//2766 2765//2765 3894//3894 -f 3894//3894 2765//2765 3896//3896 -f 3894//3894 3896//3896 3542//3542 -f 3542//3542 3896//3896 3545//3545 -f 2765//2765 2776//2776 3896//3896 -f 3896//3896 2776//2776 2778//2778 -f 3896//3896 2778//2778 3897//3897 -f 3897//3897 2778//2778 2780//2780 -f 3897//3897 2780//2780 3898//3898 -f 3898//3898 2780//2780 2782//2782 -f 2782//2782 2783//2783 3898//3898 -f 3898//3898 2783//2783 3899//3899 -f 3898//3898 3899//3899 3549//3549 -f 3549//3549 3899//3899 3548//3548 -f 2790//2790 3900//3900 2788//2788 -f 2788//2788 3900//3900 3899//3899 -f 2788//2788 3899//3899 2786//2786 -f 2786//2786 3899//3899 2783//2783 -f 2790//2790 2791//2791 3900//3900 -f 3900//3900 2791//2791 3901//3901 -f 3900//3900 3901//3901 3553//3553 -f 3553//3553 3901//3901 3552//3552 -f 2791//2791 2794//2794 3901//3901 -f 3901//3901 2794//2794 2796//2796 -f 3901//3901 2796//2796 3902//3902 -f 3902//3902 2796//2796 2798//2798 -f 3902//3902 2798//2798 3903//3903 -f 2798//2798 2800//2800 3903//3903 -f 3903//3903 2800//2800 2801//2801 -f 3903//3903 2801//2801 3904//3904 -f 3904//3904 2801//2801 2804//2804 -f 3904//3904 2804//2804 3905//3905 -f 2804//2804 2806//2806 3905//3905 -f 3905//3905 2806//2806 2808//2808 -f 3905//3905 2808//2808 3906//3906 -f 3906//3906 2808//2808 2811//2811 -f 3906//3906 2811//2811 3907//3907 -f 3907//3907 2811//2811 2813//2813 -f 2813//2813 2815//2815 3907//3907 -f 3907//3907 2815//2815 3908//3908 -f 3907//3907 3908//3908 3563//3563 -f 3563//3563 3908//3908 3566//3566 -f 2819//2819 3909//3909 2821//2821 -f 2821//2821 3909//3909 3908//3908 -f 2821//2821 3908//3908 2822//2822 -f 2822//2822 3908//3908 2815//2815 -f 2819//2819 2818//2818 3909//3909 -f 3909//3909 2818//2818 3910//3910 -f 3909//3909 3910//3910 3567//3567 -f 3567//3567 3910//3910 3570//3570 -f 2818//2818 2823//2823 3910//3910 -f 3910//3910 2823//2823 2825//2825 -f 3910//3910 2825//2825 3911//3911 -f 3911//3911 2825//2825 2827//2827 -f 3911//3911 2827//2827 3912//3912 -f 2827//2827 2829//2829 3912//3912 -f 3912//3912 2829//2829 2832//2832 -f 3912//3912 2832//2832 3913//3913 -f 3913//3913 2832//2832 2834//2834 -f 3913//3913 2834//2834 3914//3914 -f 2834//2834 2837//2837 3914//3914 -f 3914//3914 2837//2837 2839//2839 -f 3914//3914 2839//2839 3915//3915 -f 3915//3915 2839//2839 2841//2841 -f 3915//3915 2841//2841 3916//3916 -f 3916//3916 2841//2841 2851//2851 -f 2851//2851 2850//2850 3916//3916 -f 3916//3916 2850//2850 3917//3917 -f 3916//3916 3917//3917 3585//3585 -f 3585//3585 3917//3917 3584//3584 -f 2844//2844 3918//3918 2846//2846 -f 2846//2846 3918//3918 3917//3917 -f 2846//2846 3917//3917 2848//2848 -f 2848//2848 3917//3917 2850//2850 -f 2844//2844 2843//2843 3918//3918 -f 3918//3918 2843//2843 3919//3919 -f 3918//3918 3919//3919 3589//3589 -f 3589//3589 3919//3919 3588//3588 -f 2843//2843 2854//2854 3919//3919 -f 3919//3919 2854//2854 2856//2856 -f 3919//3919 2856//2856 3920//3920 -f 3920//3920 2856//2856 2858//2858 -f 3920//3920 2858//2858 3921//3921 -f 2858//2858 2860//2860 3921//3921 -f 3921//3921 2860//2860 2861//2861 -f 3921//3921 2861//2861 3922//3922 -f 3922//3922 2861//2861 2864//2864 -f 3922//3922 2864//2864 3923//3923 -f 2864//2864 2866//2866 3923//3923 -f 3923//3923 2866//2866 2868//2868 -f 3923//3923 2868//2868 3924//3924 -f 3924//3924 2868//2868 2871//2871 -f 3924//3924 2871//2871 3925//3925 -f 3925//3925 2871//2871 2873//2873 -f 2873//2873 2875//2875 3925//3925 -f 3925//3925 2875//2875 3926//3926 -f 3925//3925 3926//3926 3599//3599 -f 3599//3599 3926//3926 3602//3602 -f 2879//2879 3927//3927 2881//2881 -f 2881//2881 3927//3927 3926//3926 -f 2881//2881 3926//3926 2882//2882 -f 2882//2882 3926//3926 2875//2875 -f 2879//2879 2878//2878 3927//3927 -f 3927//3927 2878//2878 3928//3928 -f 3927//3927 3928//3928 3603//3603 -f 3603//3603 3928//3928 3606//3606 -f 2878//2878 2883//2883 3928//3928 -f 3928//3928 2883//2883 2885//2885 -f 3928//3928 2885//2885 3929//3929 -f 3929//3929 2885//2885 2887//2887 -f 3929//3929 2887//2887 3930//3930 -f 2887//2887 2889//2889 3930//3930 -f 3930//3930 2889//2889 2895//2895 -f 3930//3930 2895//2895 3768//3768 -f 3768//3768 2895//2895 2893//2893 -f 3768//3768 2893//2893 3769//3769 -f 2921//2921 3931//3931 2923//2923 -f 2923//2923 3931//3931 3932//3932 -f 2923//2923 3932//3932 2925//2925 -f 2925//2925 3932//3932 3614//3614 -f 2925//2925 3614//3614 2927//2927 -f 2927//2927 3614//3614 3613//3613 -f 2927//2927 3613//3613 2928//2928 -f 2928//2928 3613//3613 3769//3769 -f 2928//2928 3769//3769 2891//2891 -f 2891//2891 3769//3769 2893//2893 -f 3763//3763 3762//3762 3933//3933 -f 3933//3933 3762//3762 3761//3761 -f 3761//3761 3765//3765 3933//3933 -f 3933//3933 3765//3765 3766//3766 -f 3933//3933 3766//3766 3934//3934 -f 3934//3934 3766//3766 3767//3767 -f 3934//3934 3767//3767 3241//3241 -f 3753//3753 3760//3760 3935//3935 -f 3935//3935 3760//3760 3759//3759 -f 3935//3935 3759//3759 3933//3933 -f 3933//3933 3759//3759 3764//3764 -f 3933//3933 3764//3764 3763//3763 -f 3936//3936 3758//3758 3757//3757 -f 3757//3757 3756//3756 3936//3936 -f 3936//3936 3756//3756 3755//3755 -f 3936//3936 3755//3755 3935//3935 -f 3935//3935 3755//3755 3754//3754 -f 3935//3935 3754//3754 3753//3753 -f 3747//3747 3746//3746 3937//3937 -f 3937//3937 3746//3746 3752//3752 -f 3937//3937 3752//3752 3936//3936 -f 3936//3936 3752//3752 3751//3751 -f 3936//3936 3751//3751 3758//3758 -f 3743//3743 3750//3750 3938//3938 -f 3938//3938 3750//3750 3749//3749 -f 3938//3938 3749//3749 3937//3937 -f 3937//3937 3749//3749 3748//3748 -f 3937//3937 3748//3748 3747//3747 -f 3939//3939 3741//3741 3739//3739 -f 3745//3745 3744//3744 3938//3938 -f 3938//3938 3744//3744 3742//3742 -f 3938//3938 3742//3742 3743//3743 -f 3939//3939 3739//3739 3938//3938 -f 3938//3938 3739//3739 3740//3740 -f 3938//3938 3740//3740 3745//3745 -f 3732//3732 3738//3738 3940//3940 -f 3940//3940 3738//3738 3737//3737 -f 3737//3737 3736//3736 3940//3940 -f 3940//3940 3736//3736 3735//3735 -f 3940//3940 3735//3735 3939//3939 -f 3939//3939 3735//3735 3734//3734 -f 3939//3939 3734//3734 3741//3741 -f 3730//3730 3729//3729 3941//3941 -f 3941//3941 3729//3729 3728//3728 -f 3941//3941 3728//3728 3940//3940 -f 3940//3940 3728//3728 3733//3733 -f 3940//3940 3733//3733 3732//3732 -f 3722//3722 3721//3721 3942//3942 -f 3942//3942 3721//3721 3720//3720 -f 3942//3942 3720//3720 3941//3941 -f 3941//3941 3720//3720 3731//3731 -f 3941//3941 3731//3731 3730//3730 -f 3725//3725 3724//3724 3942//3942 -f 3942//3942 3724//3724 3723//3723 -f 3942//3942 3723//3723 3722//3722 -f 3714//3714 3715//3715 3943//3943 -f 3943//3943 3715//3715 3727//3727 -f 3943//3943 3727//3727 3942//3942 -f 3942//3942 3727//3727 3726//3726 -f 3942//3942 3726//3726 3725//3725 -f 3944//3944 3718//3718 3717//3717 -f 3717//3717 3716//3716 3944//3944 -f 3944//3944 3716//3716 3712//3712 -f 3944//3944 3712//3712 3943//3943 -f 3943//3943 3712//3712 3713//3713 -f 3943//3943 3713//3713 3714//3714 -f 3711//3711 3710//3710 3240//3240 -f 3240//3240 3710//3710 3709//3709 -f 3240//3240 3709//3709 3241//3241 -f 3241//3241 3709//3709 3708//3708 -f 3241//3241 3708//3708 3944//3944 -f 3944//3944 3708//3708 3719//3719 -f 3944//3944 3719//3719 3718//3718 -f 3706//3706 3705//3705 3229//3229 -f 3229//3229 3705//3705 3704//3704 -f 3229//3229 3704//3704 3231//3231 -f 3231//3231 3704//3704 3233//3233 -f 3233//3233 3704//3704 3703//3703 -f 3233//3233 3703//3703 3234//3234 -f 3703//3703 3702//3702 3234//3234 -f 3234//3234 3702//3702 3701//3701 -f 3234//3234 3701//3701 3236//3236 -f 3236//3236 3701//3701 3711//3711 -f 3236//3236 3711//3711 3238//3238 -f 3238//3238 3711//3711 3240//3240 -f 3696//3696 3697//3697 3246//3246 -f 3246//3246 3697//3697 3698//3698 -f 3246//3246 3698//3698 3247//3247 -f 3247//3247 3698//3698 3707//3707 -f 3247//3247 3707//3707 3248//3248 -f 3248//3248 3707//3707 3706//3706 -f 3248//3248 3706//3706 3228//3228 -f 3228//3228 3706//3706 3229//3229 -f 3225//3225 3688//3688 3226//3226 -f 3226//3226 3688//3688 3689//3689 -f 3226//3226 3689//3689 3250//3250 -f 3250//3250 3689//3689 3251//3251 -f 3251//3251 3689//3689 3693//3693 -f 3251//3251 3693//3693 3252//3252 -f 3693//3693 3695//3695 3252//3252 -f 3252//3252 3695//3695 3699//3699 -f 3252//3252 3699//3699 3243//3243 -f 3243//3243 3699//3699 3696//3696 -f 3243//3243 3696//3696 3245//3245 -f 3245//3245 3696//3696 3246//3246 -f 3615//3615 3683//3683 3261//3261 -f 3261//3261 3683//3683 3685//3685 -f 3261//3261 3685//3685 3255//3255 -f 3255//3255 3685//3685 3692//3692 -f 3255//3255 3692//3692 3253//3253 -f 3253//3253 3692//3692 3691//3691 -f 3253//3253 3691//3691 3225//3225 -f 3225//3225 3691//3691 3690//3690 -f 3225//3225 3690//3690 3688//3688 -f 3681//3681 3262//3262 3682//3682 -f 3682//3682 3262//3262 3676//3676 -f 3261//3261 3260//3260 3615//3615 -f 3615//3615 3260//3260 3259//3259 -f 3615//3615 3259//3259 3616//3616 -f 3616//3616 3259//3259 3258//3258 -f 3616//3616 3258//3258 3680//3680 -f 3680//3680 3258//3258 3264//3264 -f 3680//3680 3264//3264 3681//3681 -f 3681//3681 3264//3264 3263//3263 -f 3681//3681 3263//3263 3262//3262 -f 3269//3269 3677//3677 3222//3222 -f 3222//3222 3677//3677 3676//3676 -f 3222//3222 3676//3676 3223//3223 -f 3223//3223 3676//3676 3262//3262 -f 3274//3274 3672//3672 3268//3268 -f 3268//3268 3672//3672 3674//3674 -f 3268//3268 3674//3674 3267//3267 -f 3267//3267 3674//3674 3679//3679 -f 3267//3267 3679//3679 3269//3269 -f 3269//3269 3679//3679 3678//3678 -f 3269//3269 3678//3678 3677//3677 -f 3657//3657 3656//3656 3284//3284 -f 3284//3284 3656//3656 3663//3663 -f 3284//3284 3663//3663 3285//3285 -f 3285//3285 3663//3663 3667//3667 -f 3285//3285 3667//3667 3276//3276 -f 3276//3276 3667//3667 3666//3666 -f 3276//3276 3666//3666 3277//3277 -f 3277//3277 3666//3666 3665//3665 -f 3277//3277 3665//3665 3271//3271 -f 3271//3271 3665//3665 3671//3671 -f 3271//3271 3671//3671 3273//3273 -f 3273//3273 3671//3671 3669//3669 -f 3273//3273 3669//3669 3274//3274 -f 3274//3274 3669//3669 3668//3668 -f 3274//3274 3668//3668 3672//3672 -f 3659//3659 3288//3288 3661//3661 -f 3661//3661 3288//3288 3287//3287 -f 3661//3661 3287//3287 3662//3662 -f 3662//3662 3287//3287 3294//3294 -f 3662//3662 3294//3294 3651//3651 -f 3284//3284 3282//3282 3657//3657 -f 3657//3657 3282//3282 3281//3281 -f 3657//3657 3281//3281 3659//3659 -f 3659//3659 3281//3281 3280//3280 -f 3659//3659 3280//3280 3288//3288 -f 3289//3289 3652//3652 3292//3292 -f 3292//3292 3652//3652 3651//3651 -f 3292//3292 3651//3651 3293//3293 -f 3293//3293 3651//3651 3294//3294 -f 3301//3301 3645//3645 3647//3647 -f 3301//3301 3647//3647 3302//3302 -f 3302//3302 3647//3647 3650//3650 -f 3302//3302 3650//3650 3304//3304 -f 3304//3304 3650//3650 3305//3305 -f 3305//3305 3650//3650 3649//3649 -f 3305//3305 3649//3649 3219//3219 -f 3219//3219 3649//3649 3648//3648 -f 3219//3219 3648//3648 3220//3220 -f 3220//3220 3648//3648 3655//3655 -f 3220//3220 3655//3655 3289//3289 -f 3289//3289 3655//3655 3654//3654 -f 3289//3289 3654//3654 3652//3652 -f 3645//3645 3301//3301 3640//3640 -f 3640//3640 3301//3301 3295//3295 -f 3640//3640 3295//3295 3641//3641 -f 3641//3641 3295//3295 3297//3297 -f 3641//3641 3297//3297 3643//3643 -f 3643//3643 3297//3297 3299//3299 -f 3643//3643 3299//3299 3644//3644 -f 3644//3644 3299//3299 3216//3216 -f 3644//3644 3216//3216 3618//3618 -f 3618//3618 3216//3216 3310//3310 -f 3618//3618 3310//3310 3619//3619 -f 3638//3638 3312//3312 3639//3639 -f 3639//3639 3312//3312 3311//3311 -f 3639//3639 3311//3311 3636//3636 -f 3310//3310 3309//3309 3619//3619 -f 3619//3619 3309//3309 3307//3307 -f 3619//3619 3307//3307 3638//3638 -f 3638//3638 3307//3307 3306//3306 -f 3638//3638 3306//3306 3312//3312 -f 3313//3313 3316//3316 3622//3622 -f 3622//3622 3316//3316 3317//3317 -f 3622//3622 3317//3317 3631//3631 -f 3631//3631 3317//3317 3318//3318 -f 3631//3631 3318//3318 3632//3632 -f 3622//3622 3621//3621 3313//3313 -f 3313//3313 3621//3621 3637//3637 -f 3313//3313 3637//3637 3314//3314 -f 3314//3314 3637//3637 3636//3636 -f 3314//3314 3636//3636 3315//3315 -f 3315//3315 3636//3636 3311//3311 -f 3632//3632 3318//3318 3634//3634 -f 3634//3634 3318//3318 3215//3215 -f 3634//3634 3215//3215 3624//3624 -f 3624//3624 3215//3215 3214//3214 -f 3624//3624 3214//3214 3625//3625 -f 3625//3625 3214//3214 3322//3322 -f 3625//3625 3322//3322 3627//3627 -f 3322//3322 3321//3321 3627//3627 -f 3627//3627 3321//3321 3320//3320 -f 3627//3627 3320//3320 3629//3629 -f 3629//3629 3320//3320 3319//3319 -f 3629//3629 3319//3319 3630//3630 -f 3630//3630 3319//3319 3325//3325 -f 3630//3630 3325//3325 3774//3774 -f 3774//3774 3325//3325 3324//3324 -f 3774//3774 3324//3324 2383//2383 -f 2376//2376 3348//3348 3347//3347 -f 3347//3347 3352//3352 2376//2376 -f 2376//2376 3352//3352 3351//3351 -f 2376//2376 3351//3351 2394//2394 -f 2394//2394 3351//3351 2396//2396 -f 2390//2390 3346//3346 3345//3345 -f 3345//3345 3344//3344 2390//2390 -f 2390//2390 3344//3344 3350//3350 -f 2390//2390 3350//3350 2376//2376 -f 2376//2376 3350//3350 3349//3349 -f 2376//2376 3349//3349 3348//3348 -f 3334//3334 3341//3341 2387//2387 -f 2387//2387 3341//3341 3340//3340 -f 3340//3340 3339//3339 2387//2387 -f 2387//2387 3339//3339 3343//3343 -f 2387//2387 3343//3343 2390//2390 -f 2390//2390 3343//3343 3342//3342 -f 2390//2390 3342//3342 3346//3346 -f 3334//3334 2387//2387 3335//3335 -f 3335//3335 2387//2387 2385//2385 -f 3335//3335 2385//2385 3336//3336 -f 3331//3331 3330//3330 2379//2379 -f 2379//2379 3330//3330 3338//3338 -f 2379//2379 3338//3338 2385//2385 -f 2385//2385 3338//3338 3337//3337 -f 2385//2385 3337//3337 3336//3336 -f 3324//3324 3323//3323 2383//2383 -f 2383//2383 3323//3323 3329//3329 -f 2383//2383 3329//3329 2381//2381 -f 2381//2381 3329//3329 3328//3328 -f 2381//2381 3328//3328 3327//3327 -f 3327//3327 3326//3326 2381//2381 -f 2381//2381 3326//3326 3333//3333 -f 2381//2381 3333//3333 2379//2379 -f 2379//2379 3333//3333 3332//3332 -f 2379//2379 3332//3332 3331//3331 -f 3945//3945 3946//3946 3947//3947 -f 3947//3947 3948//3948 3945//3945 -f 3945//3945 3948//3948 3949//3949 -f 3945//3945 3949//3949 3950//3950 -f 3951//3951 3952//3952 3953//3953 -f 3954//3954 3955//3955 3956//3956 -f 3957//3957 3958//3958 3959//3959 -f 3960//3960 3961//3961 3962//3962 -f 3950//3950 3949//3949 3963//3963 -f 3963//3963 3949//3949 3964//3964 -f 3961//3961 3965//3965 3962//3962 -f 3962//3962 3965//3965 3966//3966 -f 3962//3962 3966//3966 3967//3967 -f 3968//3968 2364//2364 2363//2363 -f 2367//2367 2366//2366 3969//3969 -f 3969//3969 2366//2366 3970//3970 -f 3970//3970 3971//3971 3969//3969 -f 3969//3969 3971//3971 3972//3972 -f 3969//3969 3972//3972 3973//3973 -f 3959//3959 3974//3974 3973//3973 -f 3959//3959 3958//3958 3974//3974 -f 3974//3974 3958//3958 2358//2358 -f 3974//3974 2358//2358 2357//2357 -f 2361//2361 2360//2360 3975//3975 -f 3975//3975 2360//2360 3976//3976 -f 3977//3977 3947//3947 3946//3946 -f 2363//2363 3960//3960 3968//3968 -f 3968//3968 3960//3960 3962//3962 -f 3968//3968 3962//3962 3978//3978 -f 3978//3978 3962//3962 3967//3967 -f 3978//3978 3967//3967 3979//3979 -f 2359//2359 2358//2358 3980//3980 -f 3980//3980 2358//2358 3958//3958 -f 3980//3980 3958//3958 3981//3981 -f 3981//3981 3958//3958 3957//3957 -f 3981//3981 3957//3957 3982//3982 -f 3983//3983 3972//3972 3984//3984 -f 3984//3984 3972//3972 3971//3971 -f 3984//3984 3971//3971 3985//3985 -f 3985//3985 3971//3971 3970//3970 -f 3985//3985 3970//3970 3986//3986 -f 3987//3987 3988//3988 3989//3989 -f 3990//3990 3988//3988 3991//3991 -f 3991//3991 3988//3988 3987//3987 -f 3991//3991 3987//3987 3992//3992 -f 2372//2372 2371//2371 3992//3992 -f 3992//3992 2371//2371 3993//3993 -f 3992//3992 3993//3993 3991//3991 -f 3991//3991 3993//3993 3994//3994 -f 3991//3991 3994//3994 3990//3990 -f 3990//3990 3994//3994 3995//3995 -f 3996//3996 3997//3997 3998//3998 -f 3998//3998 3997//3997 3999//3999 -f 3998//3998 3999//3999 3964//3964 -f 3964//3964 3999//3999 4000//4000 -f 3964//3964 4000//4000 3963//3963 -f 3949//3949 3948//3948 3964//3964 -f 3964//3964 3948//3948 4001//4001 -f 3964//3964 4001//4001 3998//3998 -f 3998//3998 4001//4001 4002//4002 -f 3998//3998 4002//4002 3996//3996 -f 3996//3996 4002//4002 4003//4003 -f 3948//3948 3947//3947 4001//4001 -f 4001//4001 3947//3947 3977//3977 -f 4001//4001 3977//3977 4002//4002 -f 4002//4002 3977//3977 4004//4004 -f 4002//4002 4004//4004 4003//4003 -f 4003//4003 4004//4004 4005//4005 -f 4006//4006 4007//4007 4008//4008 -f 4008//4008 4007//4007 4009//4009 -f 4008//4008 4009//4009 4010//4010 -f 4010//4010 4009//4009 3953//3953 -f 4011//4011 3983//3983 4012//4012 -f 4012//4012 3983//3983 3984//3984 -f 4012//4012 3984//3984 4013//4013 -f 4013//4013 3984//3984 3985//3985 -f 4013//4013 3985//3985 4014//4014 -f 4014//4014 3985//3985 3986//3986 -f 4014//4014 3986//3986 4015//4015 -f 4016//4016 4014//4014 4017//4017 -f 4017//4017 4014//4014 4015//4015 -f 4017//4017 4015//4015 4018//4018 -f 4019//4019 4018//4018 4020//4020 -f 4020//4020 4018//4018 4015//4015 -f 4020//4020 4015//4015 4021//4021 -f 4021//4021 4015//4015 3986//3986 -f 4021//4021 3986//3986 4022//4022 -f 4022//4022 3986//3986 3970//3970 -f 4022//4022 3970//3970 2365//2365 -f 2365//2365 3970//3970 2366//2366 -f 2365//2365 2364//2364 4022//4022 -f 4022//4022 2364//2364 3968//3968 -f 4022//4022 3968//3968 4021//4021 -f 4021//4021 3968//3968 3978//3978 -f 4021//4021 3978//3978 4020//4020 -f 4020//4020 3978//3978 3979//3979 -f 4020//4020 3979//3979 4019//4019 -f 4019//4019 3979//3979 4023//4023 -f 3989//3989 4024//4024 4025//4025 -f 2373//2373 2372//2372 3965//3965 -f 3965//3965 2372//2372 3992//3992 -f 3965//3965 3992//3992 3966//3966 -f 3966//3966 3992//3992 3987//3987 -f 3966//3966 3987//3987 3967//3967 -f 3967//3967 3987//3987 3989//3989 -f 3967//3967 3989//3989 3979//3979 -f 3979//3979 3989//3989 4025//4025 -f 3979//3979 4025//4025 4023//4023 -f 4026//4026 4027//4027 3995//3995 -f 3995//3995 4027//4027 4028//4028 -f 3995//3995 4028//4028 3990//3990 -f 3990//3990 4028//4028 4029//4029 -f 3990//3990 4029//4029 3988//3988 -f 3988//3988 4029//4029 4030//4030 -f 3988//3988 4030//4030 3989//3989 -f 3989//3989 4030//4030 4031//4031 -f 3989//3989 4031//4031 4024//4024 -f 3955//3955 4026//4026 3956//3956 -f 3956//3956 4026//4026 3995//3995 -f 3956//3956 3995//3995 4032//4032 -f 4032//4032 3995//3995 3994//3994 -f 4032//4032 3994//3994 4033//4033 -f 4033//4033 3994//3994 3993//3993 -f 4033//4033 3993//3993 2370//2370 -f 2370//2370 3993//3993 2371//2371 -f 4034//4034 3954//3954 4035//4035 -f 4035//4035 3954//3954 3956//3956 -f 4035//4035 3956//3956 4036//4036 -f 4036//4036 3956//3956 4032//4032 -f 4036//4036 4032//4032 4037//4037 -f 4037//4037 4032//4032 4033//4033 -f 4037//4037 4033//4033 4038//4038 -f 4038//4038 4033//4033 2370//2370 -f 4038//4038 2370//2370 2369//2369 -f 4038//4038 4039//4039 4037//4037 -f 4037//4037 4039//4039 4040//4040 -f 4037//4037 4040//4040 4036//4036 -f 4036//4036 4040//4040 4041//4041 -f 4036//4036 4041//4041 4035//4035 -f 4035//4035 4041//4041 4042//4042 -f 4035//4035 4042//4042 4034//4034 -f 4034//4034 4042//4042 4043//4043 -f 4039//4039 3963//3963 4040//4040 -f 4040//4040 3963//3963 4000//4000 -f 4040//4040 4000//4000 4041//4041 -f 4041//4041 4000//4000 3999//3999 -f 4041//4041 3999//3999 4042//4042 -f 4042//4042 3999//3999 3997//3997 -f 4042//4042 3997//3997 4043//4043 -f 4043//4043 3997//3997 4044//4044 -f 4045//4045 4046//4046 4005//4005 -f 4005//4005 4046//4046 4047//4047 -f 4005//4005 4047//4047 4003//4003 -f 4003//4003 4047//4047 4048//4048 -f 4003//4003 4048//4048 3996//3996 -f 3996//3996 4048//4048 4049//4049 -f 3996//3996 4049//4049 3997//3997 -f 3997//3997 4049//4049 4050//4050 -f 3997//3997 4050//4050 4044//4044 -f 4051//4051 4045//4045 4010//4010 -f 4010//4010 4045//4045 4005//4005 -f 4010//4010 4005//4005 4008//4008 -f 4008//4008 4005//4005 4004//4004 -f 4008//4008 4004//4004 4006//4006 -f 4006//4006 4004//4004 3977//3977 -f 4006//4006 3977//3977 4052//4052 -f 4052//4052 3977//3977 3946//3946 -f 3953//3953 3952//3952 4010//4010 -f 4010//4010 3952//3952 4053//4053 -f 4010//4010 4053//4053 4051//4051 -f 4054//4054 3951//3951 4055//4055 -f 4055//4055 3951//3951 3953//3953 -f 4055//4055 3953//3953 4056//4056 -f 4056//4056 3953//3953 4009//4009 -f 4056//4056 4009//4009 3976//3976 -f 3976//3976 4009//4009 4007//4007 -f 3976//3976 4007//4007 3975//3975 -f 3975//3975 4007//4007 4006//4006 -f 3975//3975 4006//4006 4057//4057 -f 4057//4057 4006//4006 4052//4052 -f 2360//2360 2359//2359 3976//3976 -f 3976//3976 2359//2359 3980//3980 -f 3976//3976 3980//3980 4056//4056 -f 4056//4056 3980//3980 3981//3981 -f 4056//4056 3981//3981 4055//4055 -f 4055//4055 3981//3981 3982//3982 -f 4055//4055 3982//3982 4054//4054 -f 4054//4054 3982//3982 4058//4058 -f 3973//3973 3972//3972 3959//3959 -f 3959//3959 3972//3972 3983//3983 -f 3959//3959 3983//3983 3957//3957 -f 3957//3957 3983//3983 4011//4011 -f 3957//3957 4011//4011 3982//3982 -f 3982//3982 4011//4011 4059//4059 -f 3982//3982 4059//4059 4058//4058 -f 4016//4016 4060//4060 4014//4014 -f 4014//4014 4060//4060 4061//4061 -f 4014//4014 4061//4061 4013//4013 -f 4013//4013 4061//4061 4062//4062 -f 4013//4013 4062//4062 4012//4012 -f 4012//4012 4062//4062 4063//4063 -f 4012//4012 4063//4063 4011//4011 -f 4011//4011 4063//4063 4064//4064 -f 4011//4011 4064//4064 4059//4059 -f 4060//4060 4065//4065 4066//4066 -f 4018//4018 4067//4067 4017//4017 -f 4017//4017 4067//4067 4065//4065 -f 4017//4017 4065//4065 4016//4016 -f 4016//4016 4065//4065 4060//4060 -f 4018//4018 4019//4019 4067//4067 -f 4067//4067 4019//4019 4023//4023 -f 4067//4067 4023//4023 4068//4068 -f 4023//4023 4025//4025 4068//4068 -f 4068//4068 4025//4025 4024//4024 -f 4068//4068 4024//4024 4069//4069 -f 4029//4029 4070//4070 4030//4030 -f 4030//4030 4070//4070 4069//4069 -f 4030//4030 4069//4069 4031//4031 -f 4031//4031 4069//4069 4024//4024 -f 4029//4029 4028//4028 4070//4070 -f 4070//4070 4028//4028 4027//4027 -f 4070//4070 4027//4027 4071//4071 -f 4027//4027 4026//4026 4071//4071 -f 4071//4071 4026//4026 3955//3955 -f 4071//4071 3955//3955 4072//4072 -f 3955//3955 3954//3954 4072//4072 -f 4072//4072 3954//3954 4034//4034 -f 4072//4072 4034//4034 4073//4073 -f 4034//4034 4043//4043 4073//4073 -f 4073//4073 4043//4043 4044//4044 -f 4073//4073 4044//4044 4074//4074 -f 4048//4048 4075//4075 4049//4049 -f 4049//4049 4075//4075 4074//4074 -f 4049//4049 4074//4074 4050//4050 -f 4050//4050 4074//4074 4044//4044 -f 4048//4048 4047//4047 4075//4075 -f 4075//4075 4047//4047 4046//4046 -f 4075//4075 4046//4046 4076//4076 -f 4046//4046 4045//4045 4076//4076 -f 4076//4076 4045//4045 4051//4051 -f 4076//4076 4051//4051 4077//4077 -f 3951//3951 4078//4078 3952//3952 -f 3952//3952 4078//4078 4077//4077 -f 3952//3952 4077//4077 4053//4053 -f 4053//4053 4077//4077 4051//4051 -f 3951//3951 4054//4054 4078//4078 -f 4078//4078 4054//4054 4058//4058 -f 4078//4078 4058//4058 4079//4079 -f 4058//4058 4059//4059 4079//4079 -f 4079//4079 4059//4059 4064//4064 -f 4079//4079 4064//4064 4080//4080 -f 4064//4064 4063//4063 4080//4080 -f 4080//4080 4063//4063 4062//4062 -f 4080//4080 4062//4062 4066//4066 -f 4066//4066 4062//4062 4061//4061 -f 4066//4066 4061//4061 4060//4060 -f 4081//4081 4082//4082 4083//4083 -f 4083//4083 4082//4082 4084//4084 -f 4083//4083 4084//4084 4085//4085 -f 4085//4085 4084//4084 4086//4086 -f 4085//4085 4086//4086 4087//4087 -f 4088//4088 4089//4089 4090//4090 -f 4090//4090 4089//4089 4091//4091 -f 4090//4090 4091//4091 4092//4092 -f 4092//4092 4091//4091 4093//4093 -f 4092//4092 4093//4093 4081//4081 -f 4081//4081 4093//4093 4094//4094 -f 4081//4081 4094//4094 4082//4082 -f 4095//4095 4096//4096 4097//4097 -f 4097//4097 4096//4096 4098//4098 -f 4097//4097 4098//4098 4099//4099 -f 4099//4099 4098//4098 4100//4100 -f 4099//4099 4100//4100 4088//4088 -f 4088//4088 4100//4100 4101//4101 -f 4088//4088 4101//4101 4089//4089 -f 4086//4086 4102//4102 4087//4087 -f 4087//4087 4102//4102 4103//4103 -f 4087//4087 4103//4103 4104//4104 -f 4104//4104 4103//4103 4105//4105 -f 4104//4104 4105//4105 4106//4106 -f 4106//4106 4105//4105 4107//4107 -f 4106//4106 4107//4107 4095//4095 -f 4095//4095 4107//4107 4108//4108 -f 4095//4095 4108//4108 4096//4096 -f 3241//3241 3944//3944 4085//4085 -f 4085//4085 3944//3944 3943//3943 -f 4085//4085 3943//3943 4083//4083 -f 4083//4083 3943//3943 3942//3942 -f 4083//4083 3942//3942 4081//4081 -f 4081//4081 3942//3942 3941//3941 -f 4081//4081 3941//3941 4092//4092 -f 4092//4092 3941//3941 3940//3940 -f 4092//4092 3940//3940 4090//4090 -f 4090//4090 3940//3940 3939//3939 -f 4090//4090 3939//3939 4088//4088 -f 4088//4088 3939//3939 3938//3938 -f 4088//4088 3938//3938 4099//4099 -f 4099//4099 3938//3938 3937//3937 -f 4099//4099 3937//3937 4097//4097 -f 4097//4097 3937//3937 3936//3936 -f 4097//4097 3936//3936 4095//4095 -f 4095//4095 3936//3936 3935//3935 -f 4095//4095 3935//3935 4106//4106 -f 4106//4106 3935//3935 3933//3933 -f 4106//4106 3933//3933 4104//4104 -f 4104//4104 3933//3933 3934//3934 -f 4104//4104 3934//3934 4087//4087 -f 4087//4087 3934//3934 3241//3241 -f 4087//4087 3241//3241 4085//4085 -f 3360//3360 3364//3364 4109//4109 -f 4109//4109 3364//3364 3363//3363 -f 4109//4109 3363//3363 3362//3362 -f 3614//3614 3932//3932 4110//4110 -f 4110//4110 3932//3932 3931//3931 -f 4110//4110 3931//3931 2921//2921 -f 3614//3614 4110//4110 3612//3612 -f 3612//3612 4110//4110 4111//4111 -f 3612//3612 4111//4111 3773//3773 -f 3362//3362 3772//3772 4109//4109 -f 4109//4109 3772//3772 3771//3771 -f 4109//4109 3771//3771 4111//4111 -f 4111//4111 3771//3771 3770//3770 -f 4111//4111 3770//3770 3773//3773 -f 2898//2898 3353//3353 4112//4112 -f 4112//4112 3353//3353 3212//3212 -f 4112//4112 3212//3212 4113//4113 -f 4113//4113 3212//3212 3211//3211 -f 3211//3211 3355//3355 4113//4113 -f 4113//4113 3355//3355 3357//3357 -f 4113//4113 3357//3357 4109//4109 -f 4109//4109 3357//3357 3607//3607 -f 4109//4109 3607//3607 3360//3360 -f 4114//4114 4113//4113 4115//4115 -f 4115//4115 4113//4113 4109//4109 -f 4115//4115 4109//4109 4116//4116 -f 4116//4116 4109//4109 4111//4111 -f 4116//4116 4111//4111 4117//4117 -f 4117//4117 4111//4111 4110//4110 -f 4117//4117 4110//4110 4118//4118 -f 4118//4118 4110//4110 2921//2921 -f 4118//4118 2921//2921 4119//4119 -f 2921//2921 2919//2919 4119//4119 -f 4119//4119 2919//2919 2915//2915 -f 4119//4119 2915//2915 4120//4120 -f 4120//4120 2915//2915 2910//2910 -f 4120//4120 2910//2910 4121//4121 -f 4121//4121 2910//2910 2905//2905 -f 4121//4121 2905//2905 4122//4122 -f 4122//4122 2905//2905 2907//2907 -f 4122//4122 2907//2907 4123//4123 -f 4123//4123 2907//2907 2903//2903 -f 4123//4123 2903//2903 4124//4124 -f 4124//4124 2903//2903 2899//2899 -f 4124//4124 2899//2899 4125//4125 -f 4125//4125 2899//2899 2898//2898 -f 4125//4125 2898//2898 4114//4114 -f 4114//4114 2898//2898 4112//4112 -f 4114//4114 4112//4112 4113//4113 -f 4124//4124 4125//4125 4126//4126 -f 4126//4126 4125//4125 4114//4114 -f 4126//4126 4114//4114 4115//4115 -f 4121//4121 4122//4122 4126//4126 -f 4126//4126 4122//4122 4123//4123 -f 4126//4126 4123//4123 4124//4124 -f 4118//4118 4119//4119 4126//4126 -f 4126//4126 4119//4119 4120//4120 -f 4126//4126 4120//4120 4121//4121 -f 4115//4115 4116//4116 4126//4126 -f 4126//4126 4116//4116 4117//4117 -f 4126//4126 4117//4117 4118//4118 -f 4066//4066 4098//4098 4080//4080 -f 4080//4080 4098//4098 4096//4096 -f 4080//4080 4096//4096 4079//4079 -f 4079//4079 4096//4096 4108//4108 -f 4079//4079 4108//4108 4078//4078 -f 4078//4078 4108//4108 4107//4107 -f 4078//4078 4107//4107 4077//4077 -f 4077//4077 4107//4107 4105//4105 -f 4077//4077 4105//4105 4076//4076 -f 4076//4076 4105//4105 4103//4103 -f 4076//4076 4103//4103 4075//4075 -f 4075//4075 4103//4103 4102//4102 -f 4075//4075 4102//4102 4074//4074 -f 4074//4074 4102//4102 4086//4086 -f 4074//4074 4086//4086 4073//4073 -f 4073//4073 4086//4086 4084//4084 -f 4073//4073 4084//4084 4072//4072 -f 4072//4072 4084//4084 4082//4082 -f 4072//4072 4082//4082 4071//4071 -f 4071//4071 4082//4082 4094//4094 -f 4071//4071 4094//4094 4070//4070 -f 4070//4070 4094//4094 4093//4093 -f 4070//4070 4093//4093 4069//4069 -f 4069//4069 4093//4093 4091//4091 -f 4069//4069 4091//4091 4068//4068 -f 4068//4068 4091//4091 4089//4089 -f 4068//4068 4089//4089 4067//4067 -f 4067//4067 4089//4089 4101//4101 -f 4067//4067 4101//4101 4065//4065 -f 4065//4065 4101//4101 4100//4100 -f 4065//4065 4100//4100 4066//4066 -f 4066//4066 4100//4100 4098//4098 -f 3945//3945 4127//4127 3946//3946 -f 3946//3946 4127//4127 4128//4128 -f 3946//3946 4128//4128 4052//4052 -f 4052//4052 4128//4128 4057//4057 -f 4057//4057 4128//4128 4129//4129 -f 4057//4057 4129//4129 3975//3975 -f 3975//3975 4129//4129 2361//2361 -f 2361//2361 4129//4129 4130//4130 -f 2361//2361 4130//4130 2356//2356 -f 2356//2356 4130//4130 2357//2357 -f 2357//2357 4130//4130 4131//4131 -f 2357//2357 4131//4131 3974//3974 -f 3974//3974 4131//4131 3973//3973 -f 3973//3973 4131//4131 4132//4132 -f 3973//3973 4132//4132 3969//3969 -f 3969//3969 4132//4132 2367//2367 -f 2367//2367 4132//4132 4133//4133 -f 2367//2367 4133//4133 2362//2362 -f 2362//2362 4133//4133 2363//2363 -f 2363//2363 4133//4133 4134//4134 -f 2363//2363 4134//4134 3960//3960 -f 3960//3960 4134//4134 3961//3961 -f 3961//3961 4134//4134 4135//4135 -f 3961//3961 4135//4135 3965//3965 -f 3965//3965 4135//4135 2373//2373 -f 2373//2373 4135//4135 4136//4136 -f 2373//2373 4136//4136 2368//2368 -f 2368//2368 4136//4136 2369//2369 -f 2369//2369 4136//4136 4137//4137 -f 2369//2369 4137//4137 4038//4038 -f 4038//4038 4137//4137 4039//4039 -f 4039//4039 4137//4137 4138//4138 -f 4039//4039 4138//4138 3963//3963 -f 3963//3963 4138//4138 3950//3950 -f 3950//3950 4138//4138 4127//4127 -f 3950//3950 4127//4127 3945//3945 -f 4132//4132 4131//4131 4133//4133 -f 4133//4133 4131//4131 4130//4130 -f 4138//4138 4137//4137 4127//4127 -f 4127//4127 4137//4137 4136//4136 -f 4135//4135 4134//4134 4136//4136 -f 4136//4136 4134//4134 4133//4133 -f 4136//4136 4133//4133 4127//4127 -f 4127//4127 4133//4133 4130//4130 -f 4127//4127 4130//4130 4128//4128 -f 4128//4128 4130//4130 4129//4129 -f 4139//4139 4140//4140 4141//4141 -f 4141//4141 4142//4142 4139//4139 -f 4139//4139 4142//4142 4143//4143 -f 4139//4139 4143//4143 4144//4144 -f 4145//4145 4146//4146 4147//4147 -f 4147//4147 4148//4148 4145//4145 -f 4145//4145 4148//4148 4149//4149 -f 4145//4145 4149//4149 4150//4150 -f 4151//4151 4152//4152 4153//4153 -f 4153//4153 4154//4154 4151//4151 -f 4151//4151 4154//4154 4155//4155 -f 4151//4151 4155//4155 4156//4156 -f 4157//4157 4158//4158 4159//4159 -f 4160//4160 4161//4161 4162//4162 -f 4162//4162 4161//4161 4163//4163 -f 4162//4162 4163//4163 4164//4164 -f 4164//4164 4163//4163 4165//4165 -f 4164//4164 4165//4165 4166//4166 -f 4160//4160 4162//4162 4167//4167 -f 4167//4167 4162//4162 4168//4168 -f 4167//4167 4168//4168 4169//4169 -f 4169//4169 4168//4168 4170//4170 -f 4169//4169 4170//4170 4171//4171 -f 4171//4171 4170//4170 4172//4172 -f 4172//4172 4170//4170 4173//4173 -f 4172//4172 4173//4173 4174//4174 -f 4159//4159 4158//4158 4173//4173 -f 4173//4173 4158//4158 4175//4175 -f 4173//4173 4175//4175 4174//4174 -f 4157//4157 4159//4159 4176//4176 -f 4176//4176 4159//4159 4177//4177 -f 4176//4176 4177//4177 4178//4178 -f 4177//4177 4179//4179 4178//4178 -f 4178//4178 4179//4179 4180//4180 -f 4178//4178 4180//4180 4181//4181 -f 4181//4181 4180//4180 4182//4182 -f 4181//4181 4182//4182 4183//4183 -f 4183//4183 4182//4182 4184//4184 -f 4184//4184 4182//4182 4185//4185 -f 4184//4184 4185//4185 4186//4186 -f 4186//4186 4185//4185 4187//4187 -f 4186//4186 4187//4187 4188//4188 -f 4188//4188 4187//4187 4189//4189 -f 4188//4188 4189//4189 4190//4190 -f 4189//4189 4191//4191 4190//4190 -f 4190//4190 4191//4191 4192//4192 -f 4190//4190 4192//4192 4193//4193 -f 4193//4193 4192//4192 4194//4194 -f 4193//4193 4194//4194 4195//4195 -f 4195//4195 4194//4194 4196//4196 -f 4195//4195 4196//4196 4197//4197 -f 4197//4197 4196//4196 4198//4198 -f 4197//4197 4198//4198 4199//4199 -f 4199//4199 4198//4198 4200//4200 -f 4199//4199 4200//4200 4201//4201 -f 4201//4201 4200//4200 4202//4202 -f 4201//4201 4202//4202 4203//4203 -f 4203//4203 4202//4202 4204//4204 -f 4203//4203 4204//4204 4205//4205 -f 4205//4205 4204//4204 4206//4206 -f 4205//4205 4206//4206 4207//4207 -f 4207//4207 4206//4206 4208//4208 -f 4207//4207 4208//4208 4209//4209 -f 4209//4209 4208//4208 4210//4210 -f 4209//4209 4210//4210 4211//4211 -f 4211//4211 4210//4210 4212//4212 -f 4211//4211 4212//4212 4213//4213 -f 4213//4213 4212//4212 4214//4214 -f 4213//4213 4214//4214 4215//4215 -f 4215//4215 4214//4214 4216//4216 -f 4215//4215 4216//4216 4217//4217 -f 4217//4217 4216//4216 4218//4218 -f 4217//4217 4218//4218 4219//4219 -f 4219//4219 4218//4218 4220//4220 -f 4219//4219 4220//4220 4221//4221 -f 4220//4220 4222//4222 4221//4221 -f 4221//4221 4222//4222 4223//4223 -f 4221//4221 4223//4223 4224//4224 -f 4224//4224 4223//4223 4225//4225 -f 4224//4224 4225//4225 4226//4226 -f 4226//4226 4225//4225 4227//4227 -f 4226//4226 4227//4227 4228//4228 -f 4228//4228 4227//4227 4229//4229 -f 4228//4228 4229//4229 4230//4230 -f 4230//4230 4229//4229 4231//4231 -f 4231//4231 4229//4229 4232//4232 -f 4231//4231 4232//4232 4233//4233 -f 4233//4233 4232//4232 4234//4234 -f 4233//4233 4234//4234 4235//4235 -f 4235//4235 4234//4234 4236//4236 -f 4235//4235 4236//4236 4237//4237 -f 4237//4237 4236//4236 4238//4238 -f 4237//4237 4238//4238 4239//4239 -f 4239//4239 4238//4238 4240//4240 -f 4239//4239 4240//4240 4241//4241 -f 4241//4241 4240//4240 4242//4242 -f 4241//4241 4242//4242 4243//4243 -f 4243//4243 4242//4242 4244//4244 -f 4243//4243 4244//4244 4245//4245 -f 4245//4245 4244//4244 4246//4246 -f 4245//4245 4246//4246 4247//4247 -f 4247//4247 4246//4246 4248//4248 -f 4247//4247 4248//4248 4249//4249 -f 4249//4249 4248//4248 4250//4250 -f 4249//4249 4250//4250 4251//4251 -f 4250//4250 4252//4252 4251//4251 -f 4251//4251 4252//4252 4253//4253 -f 4251//4251 4253//4253 4254//4254 -f 4254//4254 4253//4253 4255//4255 -f 4254//4254 4255//4255 4256//4256 -f 4256//4256 4255//4255 4257//4257 -f 4256//4256 4257//4257 4258//4258 -f 4258//4258 4257//4257 4259//4259 -f 4258//4258 4259//4259 4260//4260 -f 4260//4260 4259//4259 4261//4261 -f 4261//4261 4259//4259 4262//4262 -f 4261//4261 4262//4262 4263//4263 -f 4263//4263 4262//4262 4264//4264 -f 4263//4263 4264//4264 4265//4265 -f 4265//4265 4264//4264 4266//4266 -f 4265//4265 4266//4266 4267//4267 -f 4267//4267 4266//4266 4268//4268 -f 4267//4267 4268//4268 4269//4269 -f 4269//4269 4268//4268 4270//4270 -f 4269//4269 4270//4270 4271//4271 -f 4271//4271 4270//4270 4272//4272 -f 4271//4271 4272//4272 4273//4273 -f 4273//4273 4272//4272 4274//4274 -f 4273//4273 4274//4274 4275//4275 -f 4275//4275 4274//4274 4276//4276 -f 4275//4275 4276//4276 4277//4277 -f 4277//4277 4276//4276 4278//4278 -f 4277//4277 4278//4278 4279//4279 -f 4279//4279 4278//4278 4280//4280 -f 4279//4279 4280//4280 4281//4281 -f 4280//4280 4282//4282 4281//4281 -f 4281//4281 4282//4282 4283//4283 -f 4281//4281 4283//4283 4284//4284 -f 4284//4284 4283//4283 4285//4285 -f 4284//4284 4285//4285 4286//4286 -f 4286//4286 4285//4285 4287//4287 -f 4286//4286 4287//4287 4288//4288 -f 4288//4288 4287//4287 4289//4289 -f 4290//4290 4291//4291 4292//4292 -f 4292//4292 4291//4291 4293//4293 -f 4292//4292 4293//4293 4294//4294 -f 4294//4294 4293//4293 4295//4295 -f 4294//4294 4295//4295 4296//4296 -f 4296//4296 4295//4295 4297//4297 -f 4296//4296 4297//4297 4298//4298 -f 4298//4298 4297//4297 4299//4299 -f 4298//4298 4299//4299 4300//4300 -f 4300//4300 4299//4299 4301//4301 -f 4300//4300 4301//4301 4302//4302 -f 4302//4302 4301//4301 4303//4303 -f 4302//4302 4303//4303 4304//4304 -f 4304//4304 4303//4303 4305//4305 -f 4304//4304 4305//4305 4289//4289 -f 4289//4289 4305//4305 4306//4306 -f 4289//4289 4306//4306 4288//4288 -f 4307//4307 4308//4308 4309//4309 -f 4307//4307 4309//4309 4310//4310 -f 4310//4310 4309//4309 4311//4311 -f 4310//4310 4311//4311 4312//4312 -f 4312//4312 4311//4311 4313//4313 -f 4312//4312 4313//4313 4314//4314 -f 4314//4314 4313//4313 4315//4315 -f 4314//4314 4315//4315 4316//4316 -f 4316//4316 4315//4315 4317//4317 -f 4316//4316 4317//4317 4318//4318 -f 4318//4318 4317//4317 4319//4319 -f 4318//4318 4319//4319 4320//4320 -f 4320//4320 4319//4319 4321//4321 -f 4320//4320 4321//4321 4322//4322 -f 4322//4322 4321//4321 4323//4323 -f 4322//4322 4323//4323 4324//4324 -f 4324//4324 4323//4323 4325//4325 -f 4324//4324 4325//4325 4326//4326 -f 4326//4326 4325//4325 4327//4327 -f 4326//4326 4327//4327 4328//4328 -f 4328//4328 4327//4327 4329//4329 -f 4328//4328 4329//4329 4330//4330 -f 4330//4330 4329//4329 4331//4331 -f 4330//4330 4331//4331 4332//4332 -f 4332//4332 4331//4331 4333//4333 -f 4332//4332 4333//4333 4334//4334 -f 4334//4334 4333//4333 4335//4335 -f 4334//4334 4335//4335 4336//4336 -f 4336//4336 4335//4335 4337//4337 -f 4336//4336 4337//4337 4290//4290 -f 4290//4290 4337//4337 4338//4338 -f 4290//4290 4338//4338 4291//4291 -f 4308//4308 4307//4307 4339//4339 -f 4339//4339 4307//4307 4340//4340 -f 4339//4339 4340//4340 4341//4341 -f 4341//4341 4340//4340 4342//4342 -f 4341//4341 4342//4342 4343//4343 -f 4343//4343 4342//4342 4344//4344 -f 4343//4343 4344//4344 4345//4345 -f 4345//4345 4344//4344 4346//4346 -f 4345//4345 4346//4346 4347//4347 -f 4347//4347 4346//4346 4348//4348 -f 4347//4347 4348//4348 4349//4349 -f 4349//4349 4348//4348 4350//4350 -f 4349//4349 4350//4350 4351//4351 -f 4351//4351 4350//4350 4352//4352 -f 4351//4351 4352//4352 4353//4353 -f 4353//4353 4352//4352 4354//4354 -f 4353//4353 4354//4354 4355//4355 -f 4355//4355 4354//4354 4356//4356 -f 4355//4355 4356//4356 4357//4357 -f 4357//4357 4356//4356 4358//4358 -f 4357//4357 4358//4358 4359//4359 -f 4358//4358 4360//4360 4359//4359 -f 4359//4359 4360//4360 4361//4361 -f 4359//4359 4361//4361 4362//4362 -f 4362//4362 4361//4361 4363//4363 -f 4362//4362 4363//4363 4364//4364 -f 4364//4364 4363//4363 4365//4365 -f 4364//4364 4365//4365 4366//4366 -f 4366//4366 4365//4365 4367//4367 -f 4366//4366 4367//4367 4368//4368 -f 4368//4368 4367//4367 4369//4369 -f 4369//4369 4367//4367 4370//4370 -f 4369//4369 4370//4370 4371//4371 -f 4371//4371 4370//4370 4372//4372 -f 4371//4371 4372//4372 4373//4373 -f 4373//4373 4372//4372 4374//4374 -f 4373//4373 4374//4374 4375//4375 -f 4375//4375 4374//4374 4376//4376 -f 4375//4375 4376//4376 4377//4377 -f 4377//4377 4376//4376 4378//4378 -f 4377//4377 4378//4378 4379//4379 -f 4379//4379 4378//4378 4380//4380 -f 4379//4379 4380//4380 4381//4381 -f 4381//4381 4380//4380 4382//4382 -f 4381//4381 4382//4382 4383//4383 -f 4383//4383 4382//4382 4384//4384 -f 4383//4383 4384//4384 4385//4385 -f 4385//4385 4384//4384 4386//4386 -f 4385//4385 4386//4386 4387//4387 -f 4387//4387 4386//4386 4388//4388 -f 4387//4387 4388//4388 4389//4389 -f 4388//4388 4390//4390 4389//4389 -f 4389//4389 4390//4390 4391//4391 -f 4389//4389 4391//4391 4392//4392 -f 4392//4392 4391//4391 4393//4393 -f 4392//4392 4393//4393 4394//4394 -f 4394//4394 4393//4393 4395//4395 -f 4394//4394 4395//4395 4396//4396 -f 4396//4396 4395//4395 4397//4397 -f 4396//4396 4397//4397 4398//4398 -f 4398//4398 4397//4397 4399//4399 -f 4398//4398 4399//4399 4400//4400 -f 4400//4400 4399//4399 4401//4401 -f 4400//4400 4401//4401 4402//4402 -f 4402//4402 4401//4401 4403//4403 -f 4402//4402 4403//4403 4404//4404 -f 4404//4404 4403//4403 4405//4405 -f 4404//4404 4405//4405 4406//4406 -f 4406//4406 4405//4405 4407//4407 -f 4406//4406 4407//4407 4408//4408 -f 4408//4408 4407//4407 4409//4409 -f 4408//4408 4409//4409 4410//4410 -f 4410//4410 4409//4409 4411//4411 -f 4410//4410 4411//4411 4412//4412 -f 4412//4412 4411//4411 4413//4413 -f 4412//4412 4413//4413 4414//4414 -f 4414//4414 4413//4413 4415//4415 -f 4414//4414 4415//4415 4416//4416 -f 4416//4416 4415//4415 4417//4417 -f 4417//4417 4415//4415 4418//4418 -f 4417//4417 4418//4418 4419//4419 -f 4418//4418 4420//4420 4419//4419 -f 4419//4419 4420//4420 4421//4421 -f 4419//4419 4421//4421 4422//4422 -f 4422//4422 4421//4421 4423//4423 -f 4422//4422 4423//4423 4424//4424 -f 4424//4424 4423//4423 4425//4425 -f 4424//4424 4425//4425 4426//4426 -f 4426//4426 4425//4425 4427//4427 -f 4426//4426 4427//4427 4428//4428 -f 4428//4428 4427//4427 4429//4429 -f 4428//4428 4429//4429 4430//4430 -f 4430//4430 4429//4429 4431//4431 -f 4430//4430 4431//4431 4432//4432 -f 4432//4432 4431//4431 4433//4433 -f 4432//4432 4433//4433 4434//4434 -f 4434//4434 4433//4433 4435//4435 -f 4434//4434 4435//4435 4436//4436 -f 4436//4436 4435//4435 4437//4437 -f 4436//4436 4437//4437 4438//4438 -f 4438//4438 4437//4437 4439//4439 -f 4438//4438 4439//4439 4440//4440 -f 4440//4440 4439//4439 4441//4441 -f 4440//4440 4441//4441 4442//4442 -f 4442//4442 4441//4441 4443//4443 -f 4442//4442 4443//4443 4444//4444 -f 4444//4444 4443//4443 4445//4445 -f 4444//4444 4445//4445 4446//4446 -f 4446//4446 4445//4445 4447//4447 -f 4447//4447 4445//4445 4448//4448 -f 4447//4447 4448//4448 4449//4449 -f 4448//4448 4450//4450 4449//4449 -f 4449//4449 4450//4450 4451//4451 -f 4449//4449 4451//4451 4452//4452 -f 4452//4452 4451//4451 4453//4453 -f 4452//4452 4453//4453 4454//4454 -f 4454//4454 4453//4453 4455//4455 -f 4454//4454 4455//4455 4456//4456 -f 4456//4456 4455//4455 4457//4457 -f 4456//4456 4457//4457 4458//4458 -f 4458//4458 4457//4457 4459//4459 -f 4458//4458 4459//4459 4460//4460 -f 4460//4460 4459//4459 4461//4461 -f 4460//4460 4461//4461 4462//4462 -f 4462//4462 4461//4461 4463//4463 -f 4462//4462 4463//4463 4464//4464 -f 4464//4464 4463//4463 4465//4465 -f 4464//4464 4465//4465 4466//4466 -f 4466//4466 4465//4465 4467//4467 -f 4466//4466 4467//4467 4468//4468 -f 4468//4468 4467//4467 4469//4469 -f 4468//4468 4469//4469 4470//4470 -f 4470//4470 4469//4469 4471//4471 -f 4470//4470 4471//4471 4472//4472 -f 4472//4472 4471//4471 4473//4473 -f 4473//4473 4471//4471 4474//4474 -f 4473//4473 4474//4474 4475//4475 -f 4475//4475 4474//4474 4476//4476 -f 4475//4475 4476//4476 4477//4477 -f 4477//4477 4476//4476 4478//4478 -f 4477//4477 4478//4478 4479//4479 -f 4478//4478 4480//4480 4479//4479 -f 4479//4479 4480//4480 4481//4481 -f 4479//4479 4481//4481 4482//4482 -f 4482//4482 4481//4481 4483//4483 -f 4482//4482 4483//4483 4484//4484 -f 4484//4484 4483//4483 4485//4485 -f 4484//4484 4485//4485 4486//4486 -f 4486//4486 4485//4485 4487//4487 -f 4488//4488 4489//4489 4490//4490 -f 4490//4490 4489//4489 4491//4491 -f 4490//4490 4491//4491 4492//4492 -f 4492//4492 4491//4491 4493//4493 -f 4492//4492 4493//4493 4494//4494 -f 4494//4494 4493//4493 4495//4495 -f 4494//4494 4495//4495 4487//4487 -f 4487//4487 4495//4495 4496//4496 -f 4487//4487 4496//4496 4486//4486 -f 4490//4490 4497//4497 4488//4488 -f 4488//4488 4497//4497 4498//4498 -f 4488//4488 4498//4498 4499//4499 -f 4499//4499 4498//4498 4500//4500 -f 4499//4499 4500//4500 4501//4501 -f 4501//4501 4500//4500 4502//4502 -f 4501//4501 4502//4502 4503//4503 -f 4503//4503 4502//4502 4504//4504 -f 4503//4503 4504//4504 4505//4505 -f 4505//4505 4504//4504 4506//4506 -f 4504//4504 4507//4507 4506//4506 -f 4506//4506 4507//4507 4508//4508 -f 4506//4506 4508//4508 4509//4509 -f 4509//4509 4508//4508 4510//4510 -f 4509//4509 4510//4510 4511//4511 -f 4511//4511 4510//4510 4512//4512 -f 4511//4511 4512//4512 4513//4513 -f 4512//4512 4514//4514 4513//4513 -f 4513//4513 4514//4514 4515//4515 -f 4513//4513 4515//4515 4516//4516 -f 4516//4516 4515//4515 4517//4517 -f 4516//4516 4517//4517 4518//4518 -f 4518//4518 4517//4517 4519//4519 -f 4518//4518 4519//4519 4520//4520 -f 4520//4520 4519//4519 4521//4521 -f 4522//4522 4523//4523 4524//4524 -f 4522//4522 4524//4524 4525//4525 -f 4525//4525 4524//4524 4526//4526 -f 4525//4525 4526//4526 4521//4521 -f 4521//4521 4526//4526 4527//4527 -f 4521//4521 4527//4527 4520//4520 -f 4523//4523 4522//4522 4528//4528 -f 4528//4528 4522//4522 4529//4529 -f 4528//4528 4529//4529 4530//4530 -f 4529//4529 4531//4531 4530//4530 -f 4530//4530 4531//4531 4532//4532 -f 4530//4530 4532//4532 4533//4533 -f 4533//4533 4532//4532 4534//4534 -f 4533//4533 4534//4534 4535//4535 -f 4535//4535 4534//4534 4536//4536 -f 4535//4535 4536//4536 4537//4537 -f 4537//4537 4536//4536 4538//4538 -f 4537//4537 4538//4538 4539//4539 -f 4538//4538 4540//4540 4539//4539 -f 4539//4539 4540//4540 4541//4541 -f 4539//4539 4541//4541 4542//4542 -f 4542//4542 4541//4541 4543//4543 -f 4542//4542 4543//4543 4544//4544 -f 4544//4544 4543//4543 4545//4545 -f 4544//4544 4545//4545 4546//4546 -f 4546//4546 4545//4545 4547//4547 -f 4548//4548 4549//4549 4550//4550 -f 4550//4550 4549//4549 4551//4551 -f 4550//4550 4551//4551 4552//4552 -f 4552//4552 4551//4551 4553//4553 -f 4552//4552 4553//4553 4554//4554 -f 4554//4554 4553//4553 4555//4555 -f 4554//4554 4555//4555 4547//4547 -f 4547//4547 4555//4555 4556//4556 -f 4547//4547 4556//4556 4546//4546 -f 4550//4550 4557//4557 4548//4548 -f 4548//4548 4557//4557 4558//4558 -f 4548//4548 4558//4558 4559//4559 -f 4559//4559 4558//4558 4560//4560 -f 4559//4559 4560//4560 4561//4561 -f 4561//4561 4560//4560 4562//4562 -f 4561//4561 4562//4562 4563//4563 -f 4563//4563 4562//4562 4564//4564 -f 4563//4563 4564//4564 4565//4565 -f 4565//4565 4564//4564 4566//4566 -f 4564//4564 4567//4567 4566//4566 -f 4566//4566 4567//4567 4568//4568 -f 4566//4566 4568//4568 4569//4569 -f 4569//4569 4568//4568 4570//4570 -f 4569//4569 4570//4570 4571//4571 -f 4571//4571 4570//4570 4572//4572 -f 4571//4571 4572//4572 4573//4573 -f 4573//4573 4572//4572 4574//4574 -f 4572//4572 4575//4575 4574//4574 -f 4574//4574 4575//4575 4576//4576 -f 4574//4574 4576//4576 4577//4577 -f 4577//4577 4576//4576 4578//4578 -f 4577//4577 4578//4578 4579//4579 -f 4579//4579 4578//4578 4580//4580 -f 4579//4579 4580//4580 4581//4581 -f 4581//4581 4580//4580 4582//4582 -f 4581//4581 4582//4582 4583//4583 -f 4583//4583 4582//4582 4584//4584 -f 4582//4582 4585//4585 4584//4584 -f 4584//4584 4585//4585 4586//4586 -f 4584//4584 4586//4586 4587//4587 -f 4587//4587 4586//4586 4588//4588 -f 4587//4587 4588//4588 4589//4589 -f 4589//4589 4588//4588 4590//4590 -f 4589//4589 4590//4590 4591//4591 -f 4590//4590 4592//4592 4591//4591 -f 4591//4591 4592//4592 4593//4593 -f 4591//4591 4593//4593 4594//4594 -f 4594//4594 4593//4593 4595//4595 -f 4594//4594 4595//4595 4596//4596 -f 4596//4596 4595//4595 4597//4597 -f 4596//4596 4597//4597 4598//4598 -f 4598//4598 4597//4597 4599//4599 -f 4600//4600 4601//4601 4602//4602 -f 4600//4600 4602//4602 4603//4603 -f 4603//4603 4602//4602 4604//4604 -f 4603//4603 4604//4604 4599//4599 -f 4599//4599 4604//4604 4605//4605 -f 4599//4599 4605//4605 4598//4598 -f 4601//4601 4600//4600 4606//4606 -f 4606//4606 4600//4600 4607//4607 -f 4606//4606 4607//4607 4608//4608 -f 4608//4608 4607//4607 4609//4609 -f 4608//4608 4609//4609 4610//4610 -f 4610//4610 4609//4609 4611//4611 -f 4610//4610 4611//4611 4612//4612 -f 4611//4611 4613//4613 4612//4612 -f 4612//4612 4613//4613 4614//4614 -f 4612//4612 4614//4614 4615//4615 -f 4615//4615 4614//4614 4616//4616 -f 4615//4615 4616//4616 4617//4617 -f 4616//4616 4618//4618 4617//4617 -f 4617//4617 4618//4618 4619//4619 -f 4617//4617 4619//4619 4620//4620 -f 4620//4620 4619//4619 4621//4621 -f 4620//4620 4621//4621 4622//4622 -f 4622//4622 4621//4621 4623//4623 -f 4622//4622 4623//4623 4624//4624 -f 4624//4624 4623//4623 4625//4625 -f 4626//4626 4627//4627 4628//4628 -f 4628//4628 4627//4627 4629//4629 -f 4628//4628 4629//4629 4630//4630 -f 4630//4630 4629//4629 4631//4631 -f 4630//4630 4631//4631 4632//4632 -f 4632//4632 4631//4631 4633//4633 -f 4632//4632 4633//4633 4625//4625 -f 4625//4625 4633//4633 4634//4634 -f 4625//4625 4634//4634 4624//4624 -f 4628//4628 4635//4635 4626//4626 -f 4626//4626 4635//4635 4636//4636 -f 4626//4626 4636//4636 4637//4637 -f 4637//4637 4636//4636 4638//4638 -f 4637//4637 4638//4638 4639//4639 -f 4639//4639 4638//4638 4640//4640 -f 4639//4639 4640//4640 4641//4641 -f 4641//4641 4640//4640 4642//4642 -f 4641//4641 4642//4642 4643//4643 -f 4643//4643 4642//4642 4644//4644 -f 4642//4642 4645//4645 4644//4644 -f 4644//4644 4645//4645 4646//4646 -f 4644//4644 4646//4646 4647//4647 -f 4647//4647 4646//4646 4648//4648 -f 4647//4647 4648//4648 4649//4649 -f 4649//4649 4648//4648 4650//4650 -f 4649//4649 4650//4650 4651//4651 -f 4650//4650 4652//4652 4651//4651 -f 4651//4651 4652//4652 4653//4653 -f 4651//4651 4653//4653 4654//4654 -f 4654//4654 4653//4653 4655//4655 -f 4654//4654 4655//4655 4656//4656 -f 4656//4656 4655//4655 4657//4657 -f 4656//4656 4657//4657 4658//4658 -f 4658//4658 4657//4657 4659//4659 -f 4660//4660 4661//4661 4662//4662 -f 4660//4660 4662//4662 4663//4663 -f 4663//4663 4662//4662 4664//4664 -f 4663//4663 4664//4664 4659//4659 -f 4659//4659 4664//4664 4665//4665 -f 4659//4659 4665//4665 4658//4658 -f 4661//4661 4660//4660 4666//4666 -f 4666//4666 4660//4660 4667//4667 -f 4666//4666 4667//4667 4668//4668 -f 4668//4668 4667//4667 4669//4669 -f 4668//4668 4669//4669 4670//4670 -f 4670//4670 4669//4669 4671//4671 -f 4670//4670 4671//4671 4672//4672 -f 4673//4673 4674//4674 4675//4675 -f 4675//4675 4674//4674 4676//4676 -f 4675//4675 4676//4676 4677//4677 -f 4677//4677 4676//4676 4678//4678 -f 4677//4677 4678//4678 4679//4679 -f 4679//4679 4678//4678 4672//4672 -f 4679//4679 4672//4672 4680//4680 -f 4680//4680 4672//4672 4671//4671 -f 4681//4681 4682//4682 4683//4683 -f 4683//4683 4682//4682 4684//4684 -f 4684//4684 4682//4682 4685//4685 -f 4685//4685 4682//4682 4686//4686 -f 4685//4685 4686//4686 4687//4687 -f 4688//4688 4689//4689 4690//4690 -f 4690//4690 4689//4689 4691//4691 -f 4690//4690 4691//4691 4686//4686 -f 4686//4686 4691//4691 4692//4692 -f 4686//4686 4692//4692 4687//4687 -f 4693//4693 4694//4694 4688//4688 -f 4688//4688 4694//4694 4695//4695 -f 4688//4688 4695//4695 4689//4689 -f 4696//4696 4697//4697 4698//4698 -f 4698//4698 4697//4697 4699//4699 -f 4698//4698 4699//4699 4693//4693 -f 4693//4693 4699//4699 4700//4700 -f 4693//4693 4700//4700 4694//4694 -f 4696//4696 4698//4698 4701//4701 -f 4701//4701 4698//4698 4702//4702 -f 4701//4701 4702//4702 4703//4703 -f 4703//4703 4702//4702 4704//4704 -f 4703//4703 4704//4704 4705//4705 -f 4705//4705 4704//4704 4706//4706 -f 4705//4705 4706//4706 4707//4707 -f 4707//4707 4706//4706 4708//4708 -f 4707//4707 4708//4708 4709//4709 -f 4709//4709 4708//4708 4710//4710 -f 4709//4709 4710//4710 4673//4673 -f 4673//4673 4710//4710 4711//4711 -f 4673//4673 4711//4711 4674//4674 -f 4712//4712 4713//4713 4714//4714 -f 4715//4715 4716//4716 4717//4717 -f 4718//4718 4719//4719 4720//4720 -f 4721//4721 4722//4722 4723//4723 -f 4724//4724 4725//4725 4726//4726 -f 4727//4727 4728//4728 4729//4729 -f 4730//4730 4731//4731 4732//4732 -f 4733//4733 4734//4734 4735//4735 -f 4736//4736 4737//4737 4738//4738 -f 4739//4739 4740//4740 4741//4741 -f 4742//4742 4743//4743 4744//4744 -f 4745//4745 4746//4746 4747//4747 -f 4748//4748 4749//4749 4750//4750 -f 4751//4751 4752//4752 4753//4753 -f 4754//4754 4755//4755 4756//4756 -f 4757//4757 4758//4758 4759//4759 -f 4760//4760 4761//4761 4762//4762 -f 4763//4763 4764//4764 4765//4765 -f 4766//4766 4767//4767 4768//4768 -f 4769//4769 4770//4770 4771//4771 -f 4772//4772 4773//4773 4774//4774 -f 4775//4775 4776//4776 4777//4777 -f 4778//4778 4779//4779 4780//4780 -f 4781//4781 4782//4782 4783//4783 -f 4784//4784 4785//4785 4786//4786 -f 4787//4787 4788//4788 4789//4789 -f 4790//4790 4791//4791 4792//4792 -f 4793//4793 4794//4794 4795//4795 -f 4796//4796 4797//4797 4798//4798 -f 4799//4799 4800//4800 4801//4801 -f 4802//4802 4803//4803 4804//4804 -f 4805//4805 4806//4806 4807//4807 -f 4808//4808 4809//4809 4810//4810 -f 4811//4811 4812//4812 4813//4813 -f 4814//4814 4815//4815 4816//4816 -f 4817//4817 4818//4818 4819//4819 -f 4820//4820 4821//4821 4822//4822 -f 4823//4823 4824//4824 4825//4825 -f 4826//4826 4827//4827 4828//4828 -f 4829//4829 4830//4830 4831//4831 -f 4832//4832 4833//4833 4834//4834 -f 4835//4835 4836//4836 4837//4837 -f 4838//4838 4839//4839 4840//4840 -f 4841//4841 4842//4842 4843//4843 -f 4844//4844 4845//4845 4846//4846 -f 4847//4847 4848//4848 4849//4849 -f 4850//4850 4851//4851 4852//4852 -f 4853//4853 4854//4854 4855//4855 -f 4856//4856 4857//4857 4858//4858 -f 4859//4859 4860//4860 4861//4861 -f 4862//4862 4863//4863 4864//4864 -f 4865//4865 4866//4866 4867//4867 -f 4868//4868 4869//4869 4870//4870 -f 4871//4871 4872//4872 4873//4873 -f 4874//4874 4875//4875 4876//4876 -f 4877//4877 4878//4878 4879//4879 -f 4880//4880 4881//4881 4882//4882 -f 4883//4883 4884//4884 4885//4885 -f 4886//4886 4887//4887 4888//4888 -f 4889//4889 4890//4890 4891//4891 -f 4892//4892 4893//4893 4894//4894 -f 4895//4895 4896//4896 4897//4897 -f 4898//4898 4899//4899 4900//4900 -f 4901//4901 4902//4902 4903//4903 -f 4904//4904 4905//4905 4906//4906 -f 4907//4907 4908//4908 4909//4909 -f 4910//4910 4911//4911 4912//4912 -f 4913//4913 4914//4914 4915//4915 -f 4916//4916 4917//4917 4918//4918 -f 4919//4919 4920//4920 4921//4921 -f 4922//4922 4923//4923 4924//4924 -f 4925//4925 4926//4926 4927//4927 -f 4928//4928 4929//4929 4930//4930 -f 4931//4931 4932//4932 4933//4933 -f 4934//4934 4935//4935 4936//4936 -f 4937//4937 4938//4938 4939//4939 -f 4940//4940 4941//4941 4942//4942 -f 4943//4943 4944//4944 4945//4945 -f 4946//4946 4947//4947 4948//4948 -f 4949//4949 4950//4950 4951//4951 -f 4952//4952 4953//4953 4954//4954 -f 4955//4955 4956//4956 4957//4957 -f 4958//4958 4959//4959 4960//4960 -f 4961//4961 4962//4962 4963//4963 -f 4964//4964 4965//4965 4966//4966 -f 4967//4967 4968//4968 4969//4969 -f 4970//4970 4971//4971 4972//4972 -f 4973//4973 4974//4974 4975//4975 -f 4976//4976 4977//4977 4978//4978 -f 4979//4979 4980//4980 4981//4981 -f 4982//4982 4983//4983 4984//4984 -f 4985//4985 4986//4986 4987//4987 -f 4988//4988 4989//4989 4990//4990 -f 4991//4991 4992//4992 4993//4993 -f 4427//4427 4425//4425 4735//4735 -f 4411//4411 4409//4409 4750//4750 -f 4397//4397 4395//4395 4762//4762 -f 4380//4380 4378//4378 4777//4777 -f 4350//4350 4348//4348 4804//4804 -f 4312//4312 4314//4314 4819//4819 -f 4326//4326 4328//4328 4831//4831 -f 4294//4294 4296//4296 4846//4846 -f 4272//4272 4270//4270 4873//4873 -f 4242//4242 4240//4240 4900//4900 -f 4225//4225 4223//4223 4915//4915 -f 4212//4212 4210//4210 4927//4927 -f 4194//4194 4192//4192 4942//4942 -f 4994//4994 4995//4995 4996//4996 -f 4997//4997 4998//4998 4987//4987 -f 4999//4999 5000//5000 5001//5001 -f 5002//5002 5003//5003 5004//5004 -f 5005//5005 5006//5006 5007//5007 -f 5008//5008 5009//5009 5010//5010 -f 5011//5011 5012//5012 5013//5013 -f 5013//5013 5012//5012 5014//5014 -f 5013//5013 5014//5014 5015//5015 -f 5014//5014 5016//5016 5015//5015 -f 5015//5015 5016//5016 5017//5017 -f 5015//5015 5017//5017 5018//5018 -f 5018//5018 5017//5017 5019//5019 -f 5018//5018 5019//5019 5020//5020 -f 5020//5020 5019//5019 5021//5021 -f 5020//5020 5021//5021 5022//5022 -f 5022//5022 5021//5021 5023//5023 -f 5022//5022 5023//5023 5024//5024 -f 5025//5025 5026//5026 5027//5027 -f 5027//5027 5026//5026 5028//5028 -f 5028//5028 5029//5029 5027//5027 -f 5027//5027 5029//5029 5030//5030 -f 5027//5027 5030//5030 5013//5013 -f 5013//5013 5030//5030 5031//5031 -f 5013//5013 5031//5031 5011//5011 -f 5010//5010 5009//5009 5032//5032 -f 5009//5009 5033//5033 5032//5032 -f 5032//5032 5033//5033 5034//5034 -f 5032//5032 5034//5034 5025//5025 -f 5025//5025 5034//5034 5035//5035 -f 5025//5025 5035//5035 5026//5026 -f 5008//5008 5010//5010 5036//5036 -f 5036//5036 5010//5010 5037//5037 -f 5036//5036 5037//5037 5038//5038 -f 5039//5039 5040//5040 5041//5041 -f 5041//5041 5042//5042 5039//5039 -f 5039//5039 5042//5042 5043//5043 -f 5039//5039 5043//5043 5037//5037 -f 5037//5037 5043//5043 5044//5044 -f 5037//5037 5044//5044 5038//5038 -f 5006//5006 5045//5045 5007//5007 -f 5007//5007 5045//5045 5046//5046 -f 5007//5007 5046//5046 5040//5040 -f 5040//5040 5046//5046 5047//5047 -f 5040//5040 5047//5047 5041//5041 -f 5048//5048 5049//5049 5050//5050 -f 5050//5050 5049//5049 5051//5051 -f 5048//5048 5050//5050 5007//5007 -f 5007//5007 5050//5050 5052//5052 -f 5007//5007 5052//5052 5005//5005 -f 5053//5053 5054//5054 5055//5055 -f 5055//5055 5054//5054 5056//5056 -f 5055//5055 5056//5056 5049//5049 -f 5049//5049 5056//5056 5057//5057 -f 5049//5049 5057//5057 5051//5051 -f 5058//5058 5059//5059 5053//5053 -f 5053//5053 5059//5059 5060//5060 -f 5053//5053 5060//5060 5054//5054 -f 5061//5061 5062//5062 5063//5063 -f 5063//5063 5064//5064 5061//5061 -f 5061//5061 5064//5064 5065//5065 -f 5061//5061 5065//5065 5066//5066 -f 5066//5066 5065//5065 5067//5067 -f 5066//5066 5067//5067 5058//5058 -f 5058//5058 5067//5067 5068//5068 -f 5058//5058 5068//5068 5059//5059 -f 5069//5069 5070//5070 5062//5062 -f 5062//5062 5070//5070 5071//5071 -f 5062//5062 5071//5071 5063//5063 -f 5072//5072 5073//5073 5003//5003 -f 5003//5003 5073//5073 5074//5074 -f 5003//5003 5074//5074 5004//5004 -f 5072//5072 5075//5075 5073//5073 -f 5073//5073 5075//5075 5076//5076 -f 5073//5073 5076//5076 5069//5069 -f 5069//5069 5076//5076 5077//5077 -f 5069//5069 5077//5077 5070//5070 -f 5078//5078 5079//5079 5080//5080 -f 5080//5080 5079//5079 5081//5081 -f 5080//5080 5081//5081 5082//5082 -f 5082//5082 5081//5081 5083//5083 -f 5078//5078 5084//5084 5079//5079 -f 5079//5079 5084//5084 5085//5085 -f 5079//5079 5085//5085 5086//5086 -f 5086//5086 5085//5085 5087//5087 -f 5086//5086 5087//5087 5004//5004 -f 5004//5004 5087//5087 5088//5088 -f 5004//5004 5088//5088 5002//5002 -f 5089//5089 5090//5090 5091//5091 -f 5091//5091 5090//5090 5092//5092 -f 5091//5091 5092//5092 5001//5001 -f 5001//5001 5092//5092 5093//5093 -f 5001//5001 5093//5093 4999//4999 -f 5094//5094 5095//5095 4993//4993 -f 5096//5096 5097//5097 4993//4993 -f 4993//4993 5097//5097 5098//5098 -f 4993//4993 5098//5098 5094//5094 -f 5099//5099 4990//4990 5100//5100 -f 5100//5100 4990//4990 5101//5101 -f 5102//5102 5103//5103 4984//4984 -f 4984//4984 5103//5103 5104//5104 -f 4997//4997 4987//4987 5105//5105 -f 5106//5106 5107//5107 4981//4981 -f 4981//4981 5107//5107 5108//5108 -f 5109//5109 5110//5110 4978//4978 -f 4978//4978 5110//5110 5111//5111 -f 4978//4978 5111//5111 5112//5112 -f 5113//5113 5114//5114 4975//4975 -f 4975//4975 5114//5114 5115//5115 -f 4975//4975 5115//5115 5116//5116 -f 5117//5117 5118//5118 4969//4969 -f 4969//4969 5118//5118 5119//5119 -f 5120//5120 5121//5121 4972//4972 -f 5122//5122 5123//5123 4966//4966 -f 4966//4966 5123//5123 5124//5124 -f 4963//4963 5125//5125 5126//5126 -f 5127//5127 5128//5128 4963//4963 -f 4963//4963 5128//5128 5129//5129 -f 4963//4963 5129//5129 5125//5125 -f 5130//5130 5131//5131 4960//4960 -f 4960//4960 5131//5131 5132//5132 -f 4960//4960 5132//5132 5133//5133 -f 4179//4179 5134//5134 4957//4957 -f 4957//4957 5134//5134 5135//5135 -f 5136//5136 4681//4681 5137//5137 -f 4994//4994 4996//4996 5138//5138 -f 5138//5138 4996//4996 5139//5139 -f 5138//5138 5139//5139 5140//5140 -f 5141//5141 5142//5142 5143//5143 -f 5144//5144 5145//5145 5146//5146 -f 5144//5144 5146//5146 5142//5142 -f 5142//5142 5146//5146 5147//5147 -f 5142//5142 5147//5147 5143//5143 -f 4182//4182 4180//4180 4954//4954 -f 4189//4189 4187//4187 4948//4948 -f 4198//4198 4196//4196 4939//4939 -f 4202//4202 4200//4200 4936//4936 -f 4206//4206 4204//4204 4933//4933 -f 4216//4216 4214//4214 4924//4924 -f 4220//4220 4218//4218 4921//4921 -f 4229//4229 4227//4227 4912//4912 -f 4236//4236 4234//4234 4906//4906 -f 4246//4246 4244//4244 4897//4897 -f 4250//4250 4248//4248 4894//4894 -f 4253//4253 4252//4252 4891//4891 -f 4259//4259 4257//4257 4885//4885 -f 4266//4266 4264//4264 4879//4879 -f 4276//4276 4274//4274 4870//4870 -f 4280//4280 4278//4278 4867//4867 -f 4283//4283 4282//4282 4864//4864 -f 4289//4289 4287//4287 4858//4858 -f 4300//4300 4302//4302 4852//4852 -f 4290//4290 4292//4292 4843//4843 -f 4332//4332 4334//4334 4837//4837 -f 4322//4322 4324//4324 4828//4828 -f 4318//4318 4320//4320 4825//4825 -f 4307//4307 4310//4310 4816//4816 -f 4344//4344 4342//4342 4810//4810 -f 4354//4354 4352//4352 4801//4801 -f 4358//4358 4356//4356 4798//4798 -f 4361//4361 4360//4360 4795//4795 -f 4367//4367 4365//4365 4789//4789 -f 4374//4374 4372//4372 4783//4783 -f 4384//4384 4382//4382 4774//4774 -f 4388//4388 4386//4386 4771//4771 -f 4391//4391 4390//4390 4768//4768 -f 4401//4401 4399//4399 4759//4759 -f 4405//4405 4403//4403 4756//4756 -f 4415//4415 4413//4413 4747//4747 -f 4421//4421 4420//4420 4741//4741 -f 4431//4431 4429//4429 4732//4732 -f 4435//4435 4433//4433 4729//4729 -f 4439//4439 4437//4437 4726//4726 -f 4445//4445 4443//4443 4720//4720 -f 4451//4451 4450//4450 4714//4714 -f 5148//5148 5149//5149 4453//4453 -f 5150//5150 4457//4457 5149//5149 -f 5149//5149 4457//4457 4455//4455 -f 5149//5149 4455//4455 4453//4453 -f 5151//5151 5152//5152 4465//4465 -f 4465//4465 4463//4463 5151//5151 -f 5151//5151 4463//4463 4461//4461 -f 5151//5151 4461//4461 5150//5150 -f 5150//5150 4461//4461 4459//4459 -f 5150//5150 4459//4459 4457//4457 -f 5153//5153 4471//4471 5154//5154 -f 5154//5154 4471//4471 4469//4469 -f 5154//5154 4469//4469 5152//5152 -f 5152//5152 4469//4469 4467//4467 -f 5152//5152 4467//4467 4465//4465 -f 4481//4481 4480//4480 5155//5155 -f 5155//5155 4480//4480 4478//4478 -f 5155//5155 4478//4478 5156//5156 -f 5156//5156 4478//4478 4476//4476 -f 5156//5156 4476//4476 5153//5153 -f 5153//5153 4476//4476 4474//4474 -f 5153//5153 4474//4474 4471//4471 -f 4487//4487 4485//4485 5157//5157 -f 5157//5157 4485//4485 4483//4483 -f 5157//5157 4483//4483 5158//5158 -f 4494//4494 5159//5159 4492//4492 -f 4492//4492 5159//5159 5160//5160 -f 4492//4492 5160//5160 4490//4490 -f 4497//4497 5161//5161 4498//4498 -f 4498//4498 5161//5161 5162//5162 -f 4498//4498 5162//5162 4500//4500 -f 4502//4502 5163//5163 4504//4504 -f 4504//4504 5163//5163 5164//5164 -f 4504//4504 5164//5164 4507//4507 -f 4507//4507 5164//5164 4508//4508 -f 4510//4510 5165//5165 4512//4512 -f 4512//4512 5165//5165 5166//5166 -f 4512//4512 5166//5166 4514//4514 -f 4515//4515 5167//5167 4517//4517 -f 4517//4517 5167//5167 5168//5168 -f 4517//4517 5168//5168 4519//4519 -f 4519//4519 5168//5168 4521//4521 -f 4529//4529 4522//4522 5169//5169 -f 5169//5169 4522//4522 4525//4525 -f 5169//5169 4525//4525 5170//5170 -f 4534//4534 4532//4532 5171//5171 -f 5171//5171 4532//4532 4531//4531 -f 5171//5171 4531//4531 5172//5172 -f 4536//4536 5173//5173 4538//4538 -f 4538//4538 5173//5173 5174//5174 -f 4538//4538 5174//5174 4540//4540 -f 4540//4540 5174//5174 4541//4541 -f 4543//4543 5175//5175 4545//4545 -f 4545//4545 5175//5175 5176//5176 -f 4545//4545 5176//5176 4547//4547 -f 4554//4554 5177//5177 4552//4552 -f 4552//4552 5177//5177 5178//5178 -f 4552//4552 5178//5178 4550//4550 -f 4557//4557 5179//5179 4558//4558 -f 4558//4558 5179//5179 5180//5180 -f 4558//4558 5180//5180 4560//4560 -f 4562//4562 5181//5181 4564//4564 -f 4564//4564 5181//5181 5182//5182 -f 4564//4564 5182//5182 4567//4567 -f 4567//4567 5182//5182 4568//4568 -f 4570//4570 5183//5183 4572//4572 -f 4572//4572 5183//5183 5184//5184 -f 4572//4572 5184//5184 4575//4575 -f 4575//4575 5184//5184 4576//4576 -f 4582//4582 4580//4580 5185//5185 -f 5185//5185 4580//4580 4578//4578 -f 5185//5185 4578//4578 5186//5186 -f 4585//4585 5187//5187 4586//4586 -f 4586//4586 5187//5187 5188//5188 -f 4586//4586 5188//5188 4588//4588 -f 4588//4588 5188//5188 4590//4590 -f 4595//4595 4593//4593 5189//5189 -f 5189//5189 4593//4593 4592//4592 -f 5189//5189 4592//4592 5190//5190 -f 5191//5191 4603//4603 5192//5192 -f 5192//5192 4603//4603 4599//4599 -f 5192//5192 4599//4599 5193//5193 -f 5193//5193 4599//4599 4597//4597 -f 4613//4613 4611//4611 5194//5194 -f 5194//5194 4611//4611 4609//4609 -f 5194//5194 4609//4609 5195//5195 -f 5195//5195 4609//4609 4607//4607 -f 5195//5195 4607//4607 5191//5191 -f 5191//5191 4607//4607 4600//4600 -f 5191//5191 4600//4600 4603//4603 -f 4614//4614 5196//5196 4616//4616 -f 4616//4616 5196//5196 5197//5197 -f 4616//4616 5197//5197 4618//4618 -f 4618//4618 5197//5197 4619//4619 -f 4621//4621 5198//5198 4623//4623 -f 4623//4623 5198//5198 5199//5199 -f 4623//4623 5199//5199 4625//4625 -f 4632//4632 5200//5200 4630//4630 -f 4630//4630 5200//5200 5201//5201 -f 4630//4630 5201//5201 4628//4628 -f 4635//4635 5202//5202 4636//4636 -f 4636//4636 5202//5202 5203//5203 -f 4636//4636 5203//5203 4638//4638 -f 4640//4640 5204//5204 4642//4642 -f 4642//4642 5204//5204 5205//5205 -f 4642//4642 5205//5205 4645//4645 -f 4645//4645 5205//5205 4646//4646 -f 4648//4648 5206//5206 4650//4650 -f 4650//4650 5206//5206 5207//5207 -f 4650//4650 5207//5207 4652//4652 -f 4652//4652 5207//5207 4653//4653 -f 4659//4659 4657//4657 5208//5208 -f 5208//5208 4657//4657 4655//4655 -f 5208//5208 4655//4655 5209//5209 -f 4667//4667 4660//4660 5210//5210 -f 5210//5210 4660//4660 4663//4663 -f 5210//5210 4663//4663 5211//5211 -f 4680//4680 4671//4671 5212//5212 -f 5212//5212 4671//4671 4669//4669 -f 5212//5212 4669//4669 5213//5213 -f 4679//4679 5214//5214 4677//4677 -f 4677//4677 5214//5214 5215//5215 -f 4677//4677 5215//5215 4675//4675 -f 4673//4673 5216//5216 4709//4709 -f 4709//4709 5216//5216 5217//5217 -f 4709//4709 5217//5217 4707//4707 -f 4705//4705 5218//5218 4703//4703 -f 4703//4703 5218//5218 5219//5219 -f 4703//4703 5219//5219 4701//4701 -f 4701//4701 5219//5219 4696//4696 -f 4697//4697 5220//5220 4699//4699 -f 4699//4699 5220//5220 5221//5221 -f 4699//4699 5221//5221 4700//4700 -f 4694//4694 5222//5222 4695//4695 -f 4695//4695 5222//5222 5223//5223 -f 4695//4695 5223//5223 4689//4689 -f 4689//4689 5223//5223 4691//4691 -f 4685//4685 4687//4687 5224//5224 -f 5224//5224 4687//4687 4692//4692 -f 5224//5224 4692//4692 5225//5225 -f 4681//4681 4683//4683 5137//5137 -f 5137//5137 4683//4683 4684//4684 -f 5137//5137 4684//4684 5226//5226 -f 4999//4999 5082//5082 5000//5000 -f 5000//5000 5082//5082 5083//5083 -f 5000//5000 5083//5083 5001//5001 -f 5001//5001 5083//5083 5227//5227 -f 5001//5001 5227//5227 5091//5091 -f 5091//5091 5227//5227 5228//5228 -f 5228//5228 4991//4991 5091//5091 -f 5091//5091 4991//4991 4993//4993 -f 5091//5091 4993//4993 5089//5089 -f 5089//5089 4993//4993 5095//5095 -f 4992//4992 4988//4988 4993//4993 -f 4993//4993 4988//4988 4990//4990 -f 4993//4993 4990//4990 5096//5096 -f 5096//5096 4990//4990 5099//5099 -f 4989//4989 4985//4985 4990//4990 -f 4990//4990 4985//4985 4987//4987 -f 4990//4990 4987//4987 5101//5101 -f 5101//5101 4987//4987 4998//4998 -f 4986//4986 4982//4982 4987//4987 -f 4987//4987 4982//4982 4984//4984 -f 4987//4987 4984//4984 5105//5105 -f 5105//5105 4984//4984 5104//5104 -f 4983//4983 4979//4979 4984//4984 -f 4984//4984 4979//4979 4981//4981 -f 4984//4984 4981//4981 5102//5102 -f 5102//5102 4981//4981 5108//5108 -f 4980//4980 4976//4976 4981//4981 -f 4981//4981 4976//4976 4978//4978 -f 4981//4981 4978//4978 5106//5106 -f 5106//5106 4978//4978 5112//5112 -f 4977//4977 4973//4973 4978//4978 -f 4978//4978 4973//4973 4975//4975 -f 4978//4978 4975//4975 5109//5109 -f 5109//5109 4975//4975 5116//5116 -f 4974//4974 4970//4970 4975//4975 -f 4975//4975 4970//4970 4972//4972 -f 4975//4975 4972//4972 5113//5113 -f 5113//5113 4972//4972 5121//5121 -f 4971//4971 4967//4967 4972//4972 -f 4972//4972 4967//4967 4969//4969 -f 4972//4972 4969//4969 5120//5120 -f 5120//5120 4969//4969 5119//5119 -f 4968//4968 4964//4964 4969//4969 -f 4969//4969 4964//4964 4966//4966 -f 4969//4969 4966//4966 5117//5117 -f 5117//5117 4966//4966 5124//5124 -f 4965//4965 4961//4961 4966//4966 -f 4966//4966 4961//4961 4963//4963 -f 4966//4966 4963//4963 5122//5122 -f 5122//5122 4963//4963 5126//5126 -f 4962//4962 4958//4958 4963//4963 -f 4963//4963 4958//4958 4960//4960 -f 4963//4963 4960//4960 5127//5127 -f 5127//5127 4960//4960 5133//5133 -f 4959//4959 4955//4955 4960//4960 -f 4960//4960 4955//4955 4957//4957 -f 4960//4960 4957//4957 5130//5130 -f 5130//5130 4957//4957 5135//5135 -f 4956//4956 4952//4952 4957//4957 -f 4957//4957 4952//4952 4954//4954 -f 4957//4957 4954//4954 4179//4179 -f 4179//4179 4954//4954 4180//4180 -f 4953//4953 4949//4949 4954//4954 -f 4954//4954 4949//4949 4951//4951 -f 4954//4954 4951//4951 4182//4182 -f 4182//4182 4951//4951 4185//4185 -f 4950//4950 4946//4946 4951//4951 -f 4951//4951 4946//4946 4948//4948 -f 4951//4951 4948//4948 4185//4185 -f 4185//4185 4948//4948 4187//4187 -f 4947//4947 4943//4943 4948//4948 -f 4948//4948 4943//4943 4945//4945 -f 4948//4948 4945//4945 4189//4189 -f 4189//4189 4945//4945 4191//4191 -f 4944//4944 4940//4940 4945//4945 -f 4945//4945 4940//4940 4942//4942 -f 4945//4945 4942//4942 4191//4191 -f 4191//4191 4942//4942 4192//4192 -f 4941//4941 4937//4937 4942//4942 -f 4942//4942 4937//4937 4939//4939 -f 4942//4942 4939//4939 4194//4194 -f 4194//4194 4939//4939 4196//4196 -f 4938//4938 4934//4934 4939//4939 -f 4939//4939 4934//4934 4936//4936 -f 4939//4939 4936//4936 4198//4198 -f 4198//4198 4936//4936 4200//4200 -f 4935//4935 4931//4931 4936//4936 -f 4936//4936 4931//4931 4933//4933 -f 4936//4936 4933//4933 4202//4202 -f 4202//4202 4933//4933 4204//4204 -f 4932//4932 4928//4928 4933//4933 -f 4933//4933 4928//4928 4930//4930 -f 4933//4933 4930//4930 4206//4206 -f 4206//4206 4930//4930 4208//4208 -f 4929//4929 4925//4925 4930//4930 -f 4930//4930 4925//4925 4927//4927 -f 4930//4930 4927//4927 4208//4208 -f 4208//4208 4927//4927 4210//4210 -f 4926//4926 4922//4922 4927//4927 -f 4927//4927 4922//4922 4924//4924 -f 4927//4927 4924//4924 4212//4212 -f 4212//4212 4924//4924 4214//4214 -f 4923//4923 4919//4919 4924//4924 -f 4924//4924 4919//4919 4921//4921 -f 4924//4924 4921//4921 4216//4216 -f 4216//4216 4921//4921 4218//4218 -f 4920//4920 4916//4916 4921//4921 -f 4921//4921 4916//4916 4918//4918 -f 4921//4921 4918//4918 4220//4220 -f 4220//4220 4918//4918 4222//4222 -f 4917//4917 4913//4913 4918//4918 -f 4918//4918 4913//4913 4915//4915 -f 4918//4918 4915//4915 4222//4222 -f 4222//4222 4915//4915 4223//4223 -f 4914//4914 4910//4910 4915//4915 -f 4915//4915 4910//4910 4912//4912 -f 4915//4915 4912//4912 4225//4225 -f 4225//4225 4912//4912 4227//4227 -f 4911//4911 4907//4907 4912//4912 -f 4912//4912 4907//4907 4909//4909 -f 4912//4912 4909//4909 4229//4229 -f 4229//4229 4909//4909 4232//4232 -f 4908//4908 4904//4904 4909//4909 -f 4909//4909 4904//4904 4906//4906 -f 4909//4909 4906//4906 4232//4232 -f 4232//4232 4906//4906 4234//4234 -f 4905//4905 4901//4901 4906//4906 -f 4906//4906 4901//4901 4903//4903 -f 4906//4906 4903//4903 4236//4236 -f 4236//4236 4903//4903 4238//4238 -f 4902//4902 4898//4898 4903//4903 -f 4903//4903 4898//4898 4900//4900 -f 4903//4903 4900//4900 4238//4238 -f 4238//4238 4900//4900 4240//4240 -f 4899//4899 4895//4895 4900//4900 -f 4900//4900 4895//4895 4897//4897 -f 4900//4900 4897//4897 4242//4242 -f 4242//4242 4897//4897 4244//4244 -f 4896//4896 4892//4892 4897//4897 -f 4897//4897 4892//4892 4894//4894 -f 4897//4897 4894//4894 4246//4246 -f 4246//4246 4894//4894 4248//4248 -f 4893//4893 4889//4889 4894//4894 -f 4894//4894 4889//4889 4891//4891 -f 4894//4894 4891//4891 4250//4250 -f 4250//4250 4891//4891 4252//4252 -f 4890//4890 4886//4886 4891//4891 -f 4891//4891 4886//4886 4888//4888 -f 4891//4891 4888//4888 4253//4253 -f 4253//4253 4888//4888 4255//4255 -f 4887//4887 4883//4883 4888//4888 -f 4888//4888 4883//4883 4885//4885 -f 4888//4888 4885//4885 4255//4255 -f 4255//4255 4885//4885 4257//4257 -f 4884//4884 4880//4880 4885//4885 -f 4885//4885 4880//4880 4882//4882 -f 4885//4885 4882//4882 4259//4259 -f 4259//4259 4882//4882 4262//4262 -f 4881//4881 4877//4877 4882//4882 -f 4882//4882 4877//4877 4879//4879 -f 4882//4882 4879//4879 4262//4262 -f 4262//4262 4879//4879 4264//4264 -f 4878//4878 4874//4874 4879//4879 -f 4879//4879 4874//4874 4876//4876 -f 4879//4879 4876//4876 4266//4266 -f 4266//4266 4876//4876 4268//4268 -f 4875//4875 4871//4871 4876//4876 -f 4876//4876 4871//4871 4873//4873 -f 4876//4876 4873//4873 4268//4268 -f 4268//4268 4873//4873 4270//4270 -f 4872//4872 4868//4868 4873//4873 -f 4873//4873 4868//4868 4870//4870 -f 4873//4873 4870//4870 4272//4272 -f 4272//4272 4870//4870 4274//4274 -f 4869//4869 4865//4865 4870//4870 -f 4870//4870 4865//4865 4867//4867 -f 4870//4870 4867//4867 4276//4276 -f 4276//4276 4867//4867 4278//4278 -f 4866//4866 4862//4862 4867//4867 -f 4867//4867 4862//4862 4864//4864 -f 4867//4867 4864//4864 4280//4280 -f 4280//4280 4864//4864 4282//4282 -f 4863//4863 4859//4859 4864//4864 -f 4864//4864 4859//4859 4861//4861 -f 4864//4864 4861//4861 4283//4283 -f 4283//4283 4861//4861 4285//4285 -f 4860//4860 4856//4856 4861//4861 -f 4861//4861 4856//4856 4858//4858 -f 4861//4861 4858//4858 4285//4285 -f 4285//4285 4858//4858 4287//4287 -f 4857//4857 4853//4853 4858//4858 -f 4858//4858 4853//4853 4855//4855 -f 4858//4858 4855//4855 4289//4289 -f 4289//4289 4855//4855 4304//4304 -f 4854//4854 4850//4850 4855//4855 -f 4855//4855 4850//4850 4852//4852 -f 4855//4855 4852//4852 4304//4304 -f 4304//4304 4852//4852 4302//4302 -f 4851//4851 4847//4847 4852//4852 -f 4852//4852 4847//4847 4849//4849 -f 4852//4852 4849//4849 4300//4300 -f 4300//4300 4849//4849 4298//4298 -f 4848//4848 4844//4844 4849//4849 -f 4849//4849 4844//4844 4846//4846 -f 4849//4849 4846//4846 4298//4298 -f 4298//4298 4846//4846 4296//4296 -f 4845//4845 4841//4841 4846//4846 -f 4846//4846 4841//4841 4843//4843 -f 4846//4846 4843//4843 4294//4294 -f 4294//4294 4843//4843 4292//4292 -f 4842//4842 4838//4838 4843//4843 -f 4843//4843 4838//4838 4840//4840 -f 4843//4843 4840//4840 4290//4290 -f 4290//4290 4840//4840 4336//4336 -f 4839//4839 4835//4835 4840//4840 -f 4840//4840 4835//4835 4837//4837 -f 4840//4840 4837//4837 4336//4336 -f 4336//4336 4837//4837 4334//4334 -f 4836//4836 4832//4832 4837//4837 -f 4837//4837 4832//4832 4834//4834 -f 4837//4837 4834//4834 4332//4332 -f 4332//4332 4834//4834 4330//4330 -f 4833//4833 4829//4829 4834//4834 -f 4834//4834 4829//4829 4831//4831 -f 4834//4834 4831//4831 4330//4330 -f 4330//4330 4831//4831 4328//4328 -f 4830//4830 4826//4826 4831//4831 -f 4831//4831 4826//4826 4828//4828 -f 4831//4831 4828//4828 4326//4326 -f 4326//4326 4828//4828 4324//4324 -f 4827//4827 4823//4823 4828//4828 -f 4828//4828 4823//4823 4825//4825 -f 4828//4828 4825//4825 4322//4322 -f 4322//4322 4825//4825 4320//4320 -f 4824//4824 4820//4820 4825//4825 -f 4825//4825 4820//4820 4822//4822 -f 4825//4825 4822//4822 4318//4318 -f 4318//4318 4822//4822 4316//4316 -f 4821//4821 4817//4817 4822//4822 -f 4822//4822 4817//4817 4819//4819 -f 4822//4822 4819//4819 4316//4316 -f 4316//4316 4819//4819 4314//4314 -f 4818//4818 4814//4814 4819//4819 -f 4819//4819 4814//4814 4816//4816 -f 4819//4819 4816//4816 4312//4312 -f 4312//4312 4816//4816 4310//4310 -f 4815//4815 4811//4811 4816//4816 -f 4816//4816 4811//4811 4813//4813 -f 4816//4816 4813//4813 4307//4307 -f 4307//4307 4813//4813 4340//4340 -f 4812//4812 4808//4808 4813//4813 -f 4813//4813 4808//4808 4810//4810 -f 4813//4813 4810//4810 4340//4340 -f 4340//4340 4810//4810 4342//4342 -f 4809//4809 4805//4805 4810//4810 -f 4810//4810 4805//4805 4807//4807 -f 4810//4810 4807//4807 4344//4344 -f 4344//4344 4807//4807 4346//4346 -f 4806//4806 4802//4802 4807//4807 -f 4807//4807 4802//4802 4804//4804 -f 4807//4807 4804//4804 4346//4346 -f 4346//4346 4804//4804 4348//4348 -f 4803//4803 4799//4799 4804//4804 -f 4804//4804 4799//4799 4801//4801 -f 4804//4804 4801//4801 4350//4350 -f 4350//4350 4801//4801 4352//4352 -f 4800//4800 4796//4796 4801//4801 -f 4801//4801 4796//4796 4798//4798 -f 4801//4801 4798//4798 4354//4354 -f 4354//4354 4798//4798 4356//4356 -f 4797//4797 4793//4793 4798//4798 -f 4798//4798 4793//4793 4795//4795 -f 4798//4798 4795//4795 4358//4358 -f 4358//4358 4795//4795 4360//4360 -f 4794//4794 4790//4790 4795//4795 -f 4795//4795 4790//4790 4792//4792 -f 4795//4795 4792//4792 4361//4361 -f 4361//4361 4792//4792 4363//4363 -f 4791//4791 4787//4787 4792//4792 -f 4792//4792 4787//4787 4789//4789 -f 4792//4792 4789//4789 4363//4363 -f 4363//4363 4789//4789 4365//4365 -f 4788//4788 4784//4784 4789//4789 -f 4789//4789 4784//4784 4786//4786 -f 4789//4789 4786//4786 4367//4367 -f 4367//4367 4786//4786 4370//4370 -f 4785//4785 4781//4781 4786//4786 -f 4786//4786 4781//4781 4783//4783 -f 4786//4786 4783//4783 4370//4370 -f 4370//4370 4783//4783 4372//4372 -f 4782//4782 4778//4778 4783//4783 -f 4783//4783 4778//4778 4780//4780 -f 4783//4783 4780//4780 4374//4374 -f 4374//4374 4780//4780 4376//4376 -f 4779//4779 4775//4775 4780//4780 -f 4780//4780 4775//4775 4777//4777 -f 4780//4780 4777//4777 4376//4376 -f 4376//4376 4777//4777 4378//4378 -f 4776//4776 4772//4772 4777//4777 -f 4777//4777 4772//4772 4774//4774 -f 4777//4777 4774//4774 4380//4380 -f 4380//4380 4774//4774 4382//4382 -f 4773//4773 4769//4769 4774//4774 -f 4774//4774 4769//4769 4771//4771 -f 4774//4774 4771//4771 4384//4384 -f 4384//4384 4771//4771 4386//4386 -f 4770//4770 4766//4766 4771//4771 -f 4771//4771 4766//4766 4768//4768 -f 4771//4771 4768//4768 4388//4388 -f 4388//4388 4768//4768 4390//4390 -f 4767//4767 4763//4763 4768//4768 -f 4768//4768 4763//4763 4765//4765 -f 4768//4768 4765//4765 4391//4391 -f 4391//4391 4765//4765 4393//4393 -f 4764//4764 4760//4760 4765//4765 -f 4765//4765 4760//4760 4762//4762 -f 4765//4765 4762//4762 4393//4393 -f 4393//4393 4762//4762 4395//4395 -f 4761//4761 4757//4757 4762//4762 -f 4762//4762 4757//4757 4759//4759 -f 4762//4762 4759//4759 4397//4397 -f 4397//4397 4759//4759 4399//4399 -f 4758//4758 4754//4754 4759//4759 -f 4759//4759 4754//4754 4756//4756 -f 4759//4759 4756//4756 4401//4401 -f 4401//4401 4756//4756 4403//4403 -f 4755//4755 4751//4751 4756//4756 -f 4756//4756 4751//4751 4753//4753 -f 4756//4756 4753//4753 4405//4405 -f 4405//4405 4753//4753 4407//4407 -f 4752//4752 4748//4748 4753//4753 -f 4753//4753 4748//4748 4750//4750 -f 4753//4753 4750//4750 4407//4407 -f 4407//4407 4750//4750 4409//4409 -f 4749//4749 4745//4745 4750//4750 -f 4750//4750 4745//4745 4747//4747 -f 4750//4750 4747//4747 4411//4411 -f 4411//4411 4747//4747 4413//4413 -f 4746//4746 4742//4742 4747//4747 -f 4747//4747 4742//4742 4744//4744 -f 4747//4747 4744//4744 4415//4415 -f 4415//4415 4744//4744 4418//4418 -f 4743//4743 4739//4739 4744//4744 -f 4744//4744 4739//4739 4741//4741 -f 4744//4744 4741//4741 4418//4418 -f 4418//4418 4741//4741 4420//4420 -f 4740//4740 4736//4736 4741//4741 -f 4741//4741 4736//4736 4738//4738 -f 4741//4741 4738//4738 4421//4421 -f 4421//4421 4738//4738 4423//4423 -f 4737//4737 4733//4733 4738//4738 -f 4738//4738 4733//4733 4735//4735 -f 4738//4738 4735//4735 4423//4423 -f 4423//4423 4735//4735 4425//4425 -f 4734//4734 4730//4730 4735//4735 -f 4735//4735 4730//4730 4732//4732 -f 4735//4735 4732//4732 4427//4427 -f 4427//4427 4732//4732 4429//4429 -f 4731//4731 4727//4727 4732//4732 -f 4732//4732 4727//4727 4729//4729 -f 4732//4732 4729//4729 4431//4431 -f 4431//4431 4729//4729 4433//4433 -f 4728//4728 4724//4724 4729//4729 -f 4729//4729 4724//4724 4726//4726 -f 4729//4729 4726//4726 4435//4435 -f 4435//4435 4726//4726 4437//4437 -f 4725//4725 4721//4721 4726//4726 -f 4726//4726 4721//4721 4723//4723 -f 4726//4726 4723//4723 4439//4439 -f 4439//4439 4723//4723 4441//4441 -f 4722//4722 4718//4718 4723//4723 -f 4723//4723 4718//4718 4720//4720 -f 4723//4723 4720//4720 4441//4441 -f 4441//4441 4720//4720 4443//4443 -f 4719//4719 4715//4715 4720//4720 -f 4720//4720 4715//4715 4717//4717 -f 4720//4720 4717//4717 4445//4445 -f 4445//4445 4717//4717 4448//4448 -f 4716//4716 4712//4712 4717//4717 -f 4717//4717 4712//4712 4714//4714 -f 4717//4717 4714//4714 4448//4448 -f 4448//4448 4714//4714 4450//4450 -f 4713//4713 5229//5229 4714//4714 -f 4714//4714 5229//5229 5148//5148 -f 4714//4714 5148//5148 4451//4451 -f 4451//4451 5148//5148 4453//4453 -f 5229//5229 5230//5230 5148//5148 -f 5148//5148 5230//5230 5231//5231 -f 5148//5148 5231//5231 5149//5149 -f 5149//5149 5231//5231 5232//5232 -f 5149//5149 5232//5232 5150//5150 -f 5150//5150 5232//5232 5233//5233 -f 5233//5233 5234//5234 5150//5150 -f 5150//5150 5234//5234 5235//5235 -f 5150//5150 5235//5235 5151//5151 -f 5151//5151 5235//5235 5236//5236 -f 5151//5151 5236//5236 5152//5152 -f 5236//5236 5237//5237 5152//5152 -f 5152//5152 5237//5237 5238//5238 -f 5152//5152 5238//5238 5154//5154 -f 5154//5154 5238//5238 5239//5239 -f 5239//5239 5240//5240 5154//5154 -f 5154//5154 5240//5240 5241//5241 -f 5154//5154 5241//5241 5153//5153 -f 5153//5153 5241//5241 5242//5242 -f 5153//5153 5242//5242 5156//5156 -f 5242//5242 5243//5243 5156//5156 -f 5156//5156 5243//5243 5244//5244 -f 5156//5156 5244//5244 5155//5155 -f 5155//5155 5244//5244 5245//5245 -f 5245//5245 5246//5246 5155//5155 -f 5155//5155 5246//5246 5158//5158 -f 5155//5155 5158//5158 4481//4481 -f 4481//4481 5158//5158 4483//4483 -f 5246//5246 5247//5247 5158//5158 -f 5158//5158 5247//5247 5248//5248 -f 5158//5158 5248//5248 5157//5157 -f 5157//5157 5248//5248 5249//5249 -f 5249//5249 5250//5250 5157//5157 -f 5157//5157 5250//5250 5159//5159 -f 5157//5157 5159//5159 4487//4487 -f 4487//4487 5159//5159 4494//4494 -f 5250//5250 5251//5251 5159//5159 -f 5159//5159 5251//5251 5252//5252 -f 5159//5159 5252//5252 5160//5160 -f 5160//5160 5252//5252 5253//5253 -f 5253//5253 5254//5254 5160//5160 -f 5160//5160 5254//5254 5161//5161 -f 5160//5160 5161//5161 4490//4490 -f 4490//4490 5161//5161 4497//4497 -f 5254//5254 5255//5255 5161//5161 -f 5161//5161 5255//5255 5256//5256 -f 5161//5161 5256//5256 5162//5162 -f 5162//5162 5256//5256 5257//5257 -f 5257//5257 5258//5258 5162//5162 -f 5162//5162 5258//5258 5163//5163 -f 5162//5162 5163//5163 4500//4500 -f 4500//4500 5163//5163 4502//4502 -f 5258//5258 5259//5259 5163//5163 -f 5163//5163 5259//5259 5260//5260 -f 5163//5163 5260//5260 5164//5164 -f 5164//5164 5260//5260 5261//5261 -f 5261//5261 5262//5262 5164//5164 -f 5164//5164 5262//5262 5165//5165 -f 5164//5164 5165//5165 4508//4508 -f 4508//4508 5165//5165 4510//4510 -f 5262//5262 5263//5263 5165//5165 -f 5165//5165 5263//5263 5264//5264 -f 5165//5165 5264//5264 5166//5166 -f 5166//5166 5264//5264 5265//5265 -f 5265//5265 5266//5266 5166//5166 -f 5166//5166 5266//5266 5167//5167 -f 5166//5166 5167//5167 4514//4514 -f 4514//4514 5167//5167 4515//4515 -f 5266//5266 5267//5267 5167//5167 -f 5167//5167 5267//5267 5268//5268 -f 5167//5167 5268//5268 5168//5168 -f 5168//5168 5268//5268 5269//5269 -f 5269//5269 5270//5270 5168//5168 -f 5168//5168 5270//5270 5170//5170 -f 5168//5168 5170//5170 4521//4521 -f 4521//4521 5170//5170 4525//4525 -f 5270//5270 5271//5271 5170//5170 -f 5170//5170 5271//5271 5272//5272 -f 5170//5170 5272//5272 5169//5169 -f 5169//5169 5272//5272 5273//5273 -f 5273//5273 5274//5274 5169//5169 -f 5169//5169 5274//5274 5172//5172 -f 5169//5169 5172//5172 4529//4529 -f 4529//4529 5172//5172 4531//4531 -f 5274//5274 5275//5275 5172//5172 -f 5172//5172 5275//5275 5276//5276 -f 5172//5172 5276//5276 5171//5171 -f 5171//5171 5276//5276 5277//5277 -f 5277//5277 5278//5278 5171//5171 -f 5171//5171 5278//5278 5173//5173 -f 5171//5171 5173//5173 4534//4534 -f 4534//4534 5173//5173 4536//4536 -f 5278//5278 5279//5279 5173//5173 -f 5173//5173 5279//5279 5280//5280 -f 5173//5173 5280//5280 5174//5174 -f 5174//5174 5280//5280 5281//5281 -f 5281//5281 5282//5282 5174//5174 -f 5174//5174 5282//5282 5175//5175 -f 5174//5174 5175//5175 4541//4541 -f 4541//4541 5175//5175 4543//4543 -f 5282//5282 5283//5283 5175//5175 -f 5175//5175 5283//5283 5284//5284 -f 5175//5175 5284//5284 5176//5176 -f 5176//5176 5284//5284 5285//5285 -f 5285//5285 5286//5286 5176//5176 -f 5176//5176 5286//5286 5177//5177 -f 5176//5176 5177//5177 4547//4547 -f 4547//4547 5177//5177 4554//4554 -f 5286//5286 5287//5287 5177//5177 -f 5177//5177 5287//5287 5288//5288 -f 5177//5177 5288//5288 5178//5178 -f 5178//5178 5288//5288 5289//5289 -f 5289//5289 5290//5290 5178//5178 -f 5178//5178 5290//5290 5179//5179 -f 5178//5178 5179//5179 4550//4550 -f 4550//4550 5179//5179 4557//4557 -f 5290//5290 5291//5291 5179//5179 -f 5179//5179 5291//5291 5292//5292 -f 5179//5179 5292//5292 5180//5180 -f 5180//5180 5292//5292 5293//5293 -f 5293//5293 5294//5294 5180//5180 -f 5180//5180 5294//5294 5181//5181 -f 5180//5180 5181//5181 4560//4560 -f 4560//4560 5181//5181 4562//4562 -f 5294//5294 5295//5295 5181//5181 -f 5181//5181 5295//5295 5296//5296 -f 5181//5181 5296//5296 5182//5182 -f 5182//5182 5296//5296 5297//5297 -f 5297//5297 5298//5298 5182//5182 -f 5182//5182 5298//5298 5183//5183 -f 5182//5182 5183//5183 4568//4568 -f 4568//4568 5183//5183 4570//4570 -f 5298//5298 5299//5299 5183//5183 -f 5183//5183 5299//5299 5300//5300 -f 5183//5183 5300//5300 5184//5184 -f 5184//5184 5300//5300 5301//5301 -f 5301//5301 5302//5302 5184//5184 -f 5184//5184 5302//5302 5186//5186 -f 5184//5184 5186//5186 4576//4576 -f 4576//4576 5186//5186 4578//4578 -f 5302//5302 5303//5303 5186//5186 -f 5186//5186 5303//5303 5304//5304 -f 5186//5186 5304//5304 5185//5185 -f 5185//5185 5304//5304 5305//5305 -f 5305//5305 5306//5306 5185//5185 -f 5185//5185 5306//5306 5187//5187 -f 5185//5185 5187//5187 4582//4582 -f 4582//4582 5187//5187 4585//4585 -f 5306//5306 5307//5307 5187//5187 -f 5187//5187 5307//5307 5308//5308 -f 5187//5187 5308//5308 5188//5188 -f 5188//5188 5308//5308 5309//5309 -f 5309//5309 5310//5310 5188//5188 -f 5188//5188 5310//5310 5190//5190 -f 5188//5188 5190//5190 4590//4590 -f 4590//4590 5190//5190 4592//4592 -f 5310//5310 5311//5311 5190//5190 -f 5190//5190 5311//5311 5312//5312 -f 5190//5190 5312//5312 5189//5189 -f 5189//5189 5312//5312 5313//5313 -f 5313//5313 5314//5314 5189//5189 -f 5189//5189 5314//5314 5193//5193 -f 5189//5189 5193//5193 4595//4595 -f 4595//4595 5193//5193 4597//4597 -f 5314//5314 5315//5315 5193//5193 -f 5193//5193 5315//5315 5316//5316 -f 5193//5193 5316//5316 5192//5192 -f 5192//5192 5316//5316 5317//5317 -f 5317//5317 5318//5318 5192//5192 -f 5192//5192 5318//5318 5319//5319 -f 5192//5192 5319//5319 5191//5191 -f 5191//5191 5319//5319 5320//5320 -f 5191//5191 5320//5320 5195//5195 -f 5320//5320 5321//5321 5195//5195 -f 5195//5195 5321//5321 5322//5322 -f 5195//5195 5322//5322 5194//5194 -f 5194//5194 5322//5322 5323//5323 -f 5194//5194 5323//5323 5324//5324 -f 5324//5324 5325//5325 5194//5194 -f 5194//5194 5325//5325 5196//5196 -f 5194//5194 5196//5196 4613//4613 -f 4613//4613 5196//5196 4614//4614 -f 5326//5326 5197//5197 5327//5327 -f 5327//5327 5197//5197 5196//5196 -f 5327//5327 5196//5196 5328//5328 -f 5328//5328 5196//5196 5325//5325 -f 5326//5326 5329//5329 5197//5197 -f 5197//5197 5329//5329 5198//5198 -f 5197//5197 5198//5198 4619//4619 -f 4619//4619 5198//5198 4621//4621 -f 5330//5330 5199//5199 5331//5331 -f 5331//5331 5199//5199 5198//5198 -f 5331//5331 5198//5198 5332//5332 -f 5332//5332 5198//5198 5329//5329 -f 5330//5330 5333//5333 5199//5199 -f 5199//5199 5333//5333 5200//5200 -f 5199//5199 5200//5200 4625//4625 -f 4625//4625 5200//5200 4632//4632 -f 5334//5334 5201//5201 5335//5335 -f 5335//5335 5201//5201 5200//5200 -f 5335//5335 5200//5200 5336//5336 -f 5336//5336 5200//5200 5333//5333 -f 5334//5334 5337//5337 5201//5201 -f 5201//5201 5337//5337 5202//5202 -f 5201//5201 5202//5202 4628//4628 -f 4628//4628 5202//5202 4635//4635 -f 5338//5338 5203//5203 5339//5339 -f 5339//5339 5203//5203 5202//5202 -f 5339//5339 5202//5202 5340//5340 -f 5340//5340 5202//5202 5337//5337 -f 5338//5338 5341//5341 5203//5203 -f 5203//5203 5341//5341 5204//5204 -f 5203//5203 5204//5204 4638//4638 -f 4638//4638 5204//5204 4640//4640 -f 5342//5342 5205//5205 5343//5343 -f 5343//5343 5205//5205 5204//5204 -f 5343//5343 5204//5204 5344//5344 -f 5344//5344 5204//5204 5341//5341 -f 5342//5342 5345//5345 5205//5205 -f 5205//5205 5345//5345 5206//5206 -f 5205//5205 5206//5206 4646//4646 -f 4646//4646 5206//5206 4648//4648 -f 5346//5346 5207//5207 5347//5347 -f 5347//5347 5207//5207 5206//5206 -f 5347//5347 5206//5206 5348//5348 -f 5348//5348 5206//5206 5345//5345 -f 5346//5346 5349//5349 5207//5207 -f 5207//5207 5349//5349 5209//5209 -f 5207//5207 5209//5209 4653//4653 -f 4653//4653 5209//5209 4655//4655 -f 5350//5350 5208//5208 5351//5351 -f 5351//5351 5208//5208 5209//5209 -f 5351//5351 5209//5209 5352//5352 -f 5352//5352 5209//5209 5349//5349 -f 5350//5350 5353//5353 5208//5208 -f 5208//5208 5353//5353 5211//5211 -f 5208//5208 5211//5211 4659//4659 -f 4659//4659 5211//5211 4663//4663 -f 5354//5354 5210//5210 5355//5355 -f 5355//5355 5210//5210 5211//5211 -f 5355//5355 5211//5211 5356//5356 -f 5356//5356 5211//5211 5353//5353 -f 5354//5354 5357//5357 5210//5210 -f 5210//5210 5357//5357 5213//5213 -f 5210//5210 5213//5213 4667//4667 -f 4667//4667 5213//5213 4669//4669 -f 5358//5358 5212//5212 5359//5359 -f 5359//5359 5212//5212 5213//5213 -f 5359//5359 5213//5213 5360//5360 -f 5360//5360 5213//5213 5357//5357 -f 5358//5358 5361//5361 5212//5212 -f 5212//5212 5361//5361 5214//5214 -f 5212//5212 5214//5214 4680//4680 -f 4680//4680 5214//5214 4679//4679 -f 5362//5362 5215//5215 5363//5363 -f 5363//5363 5215//5215 5214//5214 -f 5363//5363 5214//5214 5364//5364 -f 5364//5364 5214//5214 5361//5361 -f 5362//5362 5365//5365 5215//5215 -f 5215//5215 5365//5365 5216//5216 -f 5215//5215 5216//5216 4675//4675 -f 4675//4675 5216//5216 4673//4673 -f 5366//5366 5217//5217 5367//5367 -f 5367//5367 5217//5217 5216//5216 -f 5367//5367 5216//5216 5368//5368 -f 5368//5368 5216//5216 5365//5365 -f 5366//5366 5369//5369 5217//5217 -f 5217//5217 5369//5369 5218//5218 -f 5217//5217 5218//5218 4707//4707 -f 4707//4707 5218//5218 4705//4705 -f 5370//5370 5219//5219 5371//5371 -f 5371//5371 5219//5219 5218//5218 -f 5371//5371 5218//5218 5372//5372 -f 5372//5372 5218//5218 5369//5369 -f 5370//5370 5373//5373 5219//5219 -f 5219//5219 5373//5373 5220//5220 -f 5219//5219 5220//5220 4696//4696 -f 4696//4696 5220//5220 4697//4697 -f 5374//5374 5221//5221 5375//5375 -f 5375//5375 5221//5221 5220//5220 -f 5375//5375 5220//5220 5376//5376 -f 5376//5376 5220//5220 5373//5373 -f 5374//5374 5377//5377 5221//5221 -f 5221//5221 5377//5377 5222//5222 -f 5221//5221 5222//5222 4700//4700 -f 4700//4700 5222//5222 4694//4694 -f 5378//5378 5223//5223 5379//5379 -f 5379//5379 5223//5223 5222//5222 -f 5379//5379 5222//5222 5380//5380 -f 5380//5380 5222//5222 5377//5377 -f 5378//5378 5381//5381 5223//5223 -f 5223//5223 5381//5381 5225//5225 -f 5223//5223 5225//5225 4691//4691 -f 4691//4691 5225//5225 4692//4692 -f 5382//5382 5224//5224 5383//5383 -f 5383//5383 5224//5224 5225//5225 -f 5383//5383 5225//5225 5384//5384 -f 5384//5384 5225//5225 5381//5381 -f 5382//5382 5385//5385 5224//5224 -f 5224//5224 5385//5385 5226//5226 -f 5224//5224 5226//5226 4685//4685 -f 4685//4685 5226//5226 4684//4684 -f 5386//5386 5137//5137 5387//5387 -f 5387//5387 5137//5137 5226//5226 -f 5387//5387 5226//5226 5388//5388 -f 5388//5388 5226//5226 5385//5385 -f 5386//5386 5389//5389 5137//5137 -f 5137//5137 5389//5389 4996//4996 -f 5137//5137 4996//4996 5136//5136 -f 5136//5136 4996//4996 4995//4995 -f 5143//5143 5390//5390 5141//5141 -f 5141//5141 5390//5390 5140//5140 -f 5141//5141 5140//5140 5391//5391 -f 5391//5391 5140//5140 5139//5139 -f 5391//5391 5139//5139 5392//5392 -f 5392//5392 5139//5139 4996//4996 -f 5392//5392 4996//4996 5393//5393 -f 5393//5393 4996//4996 5389//5389 -f 5240//5240 5239//5239 5394//5394 -f 5395//5395 5396//5396 5397//5397 -f 5398//5398 5399//5399 5400//5400 -f 5401//5401 5402//5402 5403//5403 -f 5404//5404 5405//5405 5406//5406 -f 5407//5407 5408//5408 5409//5409 -f 5409//5409 5408//5408 5410//5410 -f 5409//5409 5410//5410 5411//5411 -f 5411//5411 5410//5410 5412//5412 -f 5411//5411 5412//5412 5413//5413 -f 5414//5414 5415//5415 5416//5416 -f 5416//5416 5415//5415 5417//5417 -f 5416//5416 5417//5417 5407//5407 -f 5418//5418 5419//5419 5406//5406 -f 5406//5406 5419//5419 5420//5420 -f 5406//5406 5420//5420 5404//5404 -f 5402//5402 5421//5421 5418//5418 -f 5418//5418 5421//5421 5422//5422 -f 5418//5418 5422//5422 5419//5419 -f 5423//5423 5424//5424 5425//5425 -f 5425//5425 5424//5424 5426//5426 -f 5401//5401 5403//5403 5427//5427 -f 5423//5423 5425//5425 5428//5428 -f 5428//5428 5425//5425 5429//5429 -f 5428//5428 5429//5429 5430//5430 -f 5431//5431 5432//5432 5429//5429 -f 5429//5429 5432//5432 5433//5433 -f 5429//5429 5433//5433 5430//5430 -f 5434//5434 5435//5435 5436//5436 -f 5435//5435 5437//5437 5436//5436 -f 5436//5436 5437//5437 5438//5438 -f 5436//5436 5438//5438 5431//5431 -f 5439//5439 5440//5440 5441//5441 -f 5441//5441 5440//5440 5442//5442 -f 5441//5441 5442//5442 5443//5443 -f 5443//5443 5442//5442 5444//5444 -f 5443//5443 5444//5444 5445//5445 -f 5446//5446 5439//5439 5447//5447 -f 5448//5448 5449//5449 5447//5447 -f 5447//5447 5449//5449 5450//5450 -f 5447//5447 5450//5450 5446//5446 -f 5451//5451 5452//5452 5453//5453 -f 5453//5453 5452//5452 5454//5454 -f 5451//5451 5453//5453 5455//5455 -f 5455//5455 5453//5453 5456//5456 -f 5455//5455 5456//5456 5457//5457 -f 5458//5458 5459//5459 5460//5460 -f 5460//5460 5461//5461 5456//5456 -f 5456//5456 5461//5461 5462//5462 -f 5456//5456 5462//5462 5457//5457 -f 5463//5463 5464//5464 5458//5458 -f 5458//5458 5464//5464 5465//5465 -f 5458//5458 5465//5465 5459//5459 -f 5398//5398 5400//5400 5466//5466 -f 5466//5466 5400//5400 5467//5467 -f 5466//5466 5467//5467 5468//5468 -f 5469//5469 5470//5470 5471//5471 -f 5471//5471 5470//5470 5472//5472 -f 5471//5471 5473//5473 5469//5469 -f 5469//5469 5473//5473 5474//5474 -f 5469//5469 5474//5474 5467//5467 -f 5467//5467 5474//5474 5475//5475 -f 5467//5467 5475//5475 5468//5468 -f 5472//5472 5470//5470 5476//5476 -f 5476//5476 5470//5470 5477//5477 -f 5476//5476 5477//5477 5478//5478 -f 5479//5479 4989//4989 5480//5480 -f 5480//5480 4989//4989 4988//4988 -f 5480//5480 4988//4988 5481//5481 -f 5479//5479 5482//5482 4989//4989 -f 4989//4989 5482//5482 5483//5483 -f 4989//4989 5483//5483 4985//4985 -f 5228//5228 5227//5227 5484//5484 -f 5484//5484 5485//5485 5228//5228 -f 5228//5228 5485//5485 5486//5486 -f 5228//5228 5486//5486 4991//4991 -f 5486//5486 5487//5487 4991//4991 -f 4991//4991 5487//5487 5488//5488 -f 4991//4991 5488//5488 4992//4992 -f 4992//4992 5488//5488 5489//5489 -f 4992//4992 5489//5489 4988//4988 -f 4988//4988 5489//5489 5490//5490 -f 4988//4988 5490//5490 5481//5481 -f 5083//5083 5081//5081 5491//5491 -f 5491//5491 5492//5492 5083//5083 -f 5083//5083 5492//5492 5493//5493 -f 5083//5083 5493//5493 5227//5227 -f 5227//5227 5493//5493 5494//5494 -f 5227//5227 5494//5494 5484//5484 -f 5495//5495 5086//5086 5496//5496 -f 5496//5496 5086//5086 5004//5004 -f 5496//5496 5004//5004 5497//5497 -f 5497//5497 5004//5004 5074//5074 -f 5497//5497 5074//5074 5498//5498 -f 5495//5495 5499//5499 5086//5086 -f 5086//5086 5499//5499 5500//5500 -f 5086//5086 5500//5500 5079//5079 -f 5079//5079 5500//5500 5501//5501 -f 5079//5079 5501//5501 5081//5081 -f 5081//5081 5501//5501 5502//5502 -f 5081//5081 5502//5502 5491//5491 -f 5062//5062 5061//5061 5503//5503 -f 5503//5503 5504//5504 5062//5062 -f 5062//5062 5504//5504 5505//5505 -f 5062//5062 5505//5505 5069//5069 -f 5069//5069 5505//5505 5506//5506 -f 5506//5506 5507//5507 5069//5069 -f 5069//5069 5507//5507 5508//5508 -f 5069//5069 5508//5508 5073//5073 -f 5073//5073 5508//5508 5509//5509 -f 5073//5073 5509//5509 5074//5074 -f 5074//5074 5509//5509 5510//5510 -f 5074//5074 5510//5510 5498//5498 -f 5066//5066 5058//5058 5511//5511 -f 5511//5511 5512//5512 5066//5066 -f 5066//5066 5512//5512 5513//5513 -f 5066//5066 5513//5513 5061//5061 -f 5061//5061 5513//5513 5514//5514 -f 5061//5061 5514//5514 5503//5503 -f 5053//5053 5515//5515 5058//5058 -f 5058//5058 5515//5515 5516//5516 -f 5058//5058 5516//5516 5511//5511 -f 5517//5517 5518//5518 5055//5055 -f 5518//5518 5519//5519 5055//5055 -f 5055//5055 5519//5519 5520//5520 -f 5055//5055 5520//5520 5053//5053 -f 5053//5053 5520//5520 5521//5521 -f 5053//5053 5521//5521 5515//5515 -f 5522//5522 5048//5048 5523//5523 -f 5523//5523 5048//5048 5007//5007 -f 5055//5055 5049//5049 5517//5517 -f 5517//5517 5049//5049 5048//5048 -f 5517//5517 5048//5048 5524//5524 -f 5524//5524 5048//5048 5522//5522 -f 5525//5525 5007//5007 5526//5526 -f 5526//5526 5007//5007 5040//5040 -f 5525//5525 5527//5527 5007//5007 -f 5007//5007 5527//5527 5528//5528 -f 5007//5007 5528//5528 5523//5523 -f 5529//5529 5530//5530 5037//5037 -f 5037//5037 5530//5530 5531//5531 -f 5037//5037 5531//5531 5039//5039 -f 5039//5039 5531//5531 5532//5532 -f 5039//5039 5532//5532 5040//5040 -f 5040//5040 5532//5532 5533//5533 -f 5040//5040 5533//5533 5526//5526 -f 5010//5010 5534//5534 5037//5037 -f 5037//5037 5534//5534 5535//5535 -f 5037//5037 5535//5535 5529//5529 -f 5025//5025 5027//5027 5536//5536 -f 5536//5536 5537//5537 5025//5025 -f 5025//5025 5537//5537 5538//5538 -f 5025//5025 5538//5538 5032//5032 -f 5538//5538 5539//5539 5032//5032 -f 5032//5032 5539//5539 5540//5540 -f 5032//5032 5540//5540 5010//5010 -f 5010//5010 5540//5540 5541//5541 -f 5010//5010 5541//5541 5534//5534 -f 5013//5013 5542//5542 5027//5027 -f 5027//5027 5542//5542 5543//5543 -f 5027//5027 5543//5543 5536//5536 -f 5544//5544 5545//5545 5015//5015 -f 5015//5015 5545//5545 5546//5546 -f 5015//5015 5546//5546 5013//5013 -f 5013//5013 5546//5546 5547//5547 -f 5013//5013 5547//5547 5542//5542 -f 5544//5544 5015//5015 5548//5548 -f 5548//5548 5015//5015 5018//5018 -f 5548//5548 5018//5018 5549//5549 -f 5549//5549 5018//5018 5020//5020 -f 5549//5549 5020//5020 5550//5550 -f 5550//5550 5020//5020 5022//5022 -f 5550//5550 5022//5022 5024//5024 -f 5145//5145 5551//5551 5552//5552 -f 5553//5553 5554//5554 5552//5552 -f 5552//5552 5554//5554 5555//5555 -f 5552//5552 5555//5555 5145//5145 -f 5396//5396 5395//5395 5552//5552 -f 5552//5552 5395//5395 5556//5556 -f 5552//5552 5556//5556 5553//5553 -f 5482//5482 5478//5478 5483//5483 -f 5483//5483 5478//5478 5477//5477 -f 5483//5483 5477//5477 4985//4985 -f 4985//4985 5477//5477 5470//5470 -f 4985//4985 5470//5470 4986//4986 -f 4986//4986 5470//5470 5469//5469 -f 4986//4986 5469//5469 4982//4982 -f 4982//4982 5469//5469 5467//5467 -f 4982//4982 5467//5467 4983//4983 -f 4983//4983 5467//5467 5400//5400 -f 4983//4983 5400//5400 4979//4979 -f 4979//4979 5400//5400 4980//4980 -f 4976//4976 4980//4980 5458//5458 -f 5458//5458 4980//4980 5400//5400 -f 5458//5458 5400//5400 5463//5463 -f 5463//5463 5400//5400 5399//5399 -f 5460//5460 5456//5456 5458//5458 -f 5458//5458 5456//5456 4977//4977 -f 5458//5458 4977//4977 4976//4976 -f 4971//4971 4970//4970 5453//5453 -f 5453//5453 4970//4970 4974//4974 -f 5453//5453 4974//4974 5456//5456 -f 5456//5456 4974//4974 4973//4973 -f 5456//5456 4973//4973 4977//4977 -f 4967//4967 4971//4971 5447//5447 -f 5447//5447 4971//4971 5453//5453 -f 5447//5447 5453//5453 5448//5448 -f 5448//5448 5453//5453 5454//5454 -f 5439//5439 5441//5441 5447//5447 -f 5447//5447 5441//5441 4968//4968 -f 5447//5447 4968//4968 4967//4967 -f 4962//4962 4961//4961 5443//5443 -f 5443//5443 4961//4961 4965//4965 -f 5443//5443 4965//4965 5441//5441 -f 5441//5441 4965//4965 4964//4964 -f 5441//5441 4964//4964 4968//4968 -f 4958//4958 4962//4962 5436//5436 -f 5436//5436 4962//4962 5443//5443 -f 5436//5436 5443//5443 5434//5434 -f 5434//5434 5443//5443 5445//5445 -f 5431//5431 5429//5429 5436//5436 -f 5436//5436 5429//5429 4959//4959 -f 5436//5436 4959//4959 4958//4958 -f 4953//4953 4952//4952 5425//5425 -f 5425//5425 4952//4952 4956//4956 -f 5425//5425 4956//4956 5429//5429 -f 5429//5429 4956//4956 4955//4955 -f 5429//5429 4955//4955 4959//4959 -f 4949//4949 4953//4953 5403//5403 -f 5403//5403 4953//4953 5425//5425 -f 5403//5403 5425//5425 5427//5427 -f 5427//5427 5425//5425 5426//5426 -f 5402//5402 5418//5418 5403//5403 -f 5403//5403 5418//5418 4950//4950 -f 5403//5403 4950//4950 4949//4949 -f 4944//4944 4943//4943 5406//5406 -f 5406//5406 4943//4943 4947//4947 -f 5406//5406 4947//4947 5418//5418 -f 5418//5418 4947//4947 4946//4946 -f 5418//5418 4946//4946 4950//4950 -f 4940//4940 4944//4944 5416//5416 -f 5416//5416 4944//4944 5406//5406 -f 5416//5416 5406//5406 5414//5414 -f 5414//5414 5406//5406 5405//5405 -f 5407//5407 5409//5409 5416//5416 -f 5416//5416 5409//5409 4941//4941 -f 5416//5416 4941//4941 4940//4940 -f 4935//4935 4934//4934 5411//5411 -f 5411//5411 4934//4934 4938//4938 -f 5411//5411 4938//4938 5409//5409 -f 5409//5409 4938//4938 4937//4937 -f 5409//5409 4937//4937 4941//4941 -f 5413//5413 5557//5557 5411//5411 -f 5411//5411 5557//5557 5558//5558 -f 5411//5411 5558//5558 4935//4935 -f 5559//5559 4932//4932 5558//5558 -f 5558//5558 4932//4932 4931//4931 -f 5558//5558 4931//4931 4935//4935 -f 5560//5560 4929//4929 5559//5559 -f 5559//5559 4929//4929 4928//4928 -f 5559//5559 4928//4928 4932//4932 -f 5561//5561 4926//4926 5560//5560 -f 5560//5560 4926//4926 4925//4925 -f 5560//5560 4925//4925 4929//4929 -f 5562//5562 4923//4923 5561//5561 -f 5561//5561 4923//4923 4922//4922 -f 5561//5561 4922//4922 4926//4926 -f 5563//5563 4920//4920 5562//5562 -f 5562//5562 4920//4920 4919//4919 -f 5562//5562 4919//4919 4923//4923 -f 4914//4914 4913//4913 5564//5564 -f 5564//5564 4913//4913 4917//4917 -f 5564//5564 4917//4917 5563//5563 -f 5563//5563 4917//4917 4916//4916 -f 5563//5563 4916//4916 4920//4920 -f 4910//4910 5565//5565 4911//4911 -f 4911//4911 5565//5565 5566//5566 -f 4911//4911 5566//5566 4907//4907 -f 4907//4907 5566//5566 4908//4908 -f 4904//4904 5567//5567 4905//4905 -f 4905//4905 5567//5567 5568//5568 -f 5569//5569 4902//4902 5568//5568 -f 5568//5568 4902//4902 4901//4901 -f 5568//5568 4901//4901 4905//4905 -f 5570//5570 4899//4899 5569//5569 -f 5569//5569 4899//4899 4898//4898 -f 5569//5569 4898//4898 4902//4902 -f 5571//5571 4896//4896 5570//5570 -f 5570//5570 4896//4896 4895//4895 -f 5570//5570 4895//4895 4899//4899 -f 5572//5572 4893//4893 5571//5571 -f 5571//5571 4893//4893 4892//4892 -f 5571//5571 4892//4892 4896//4896 -f 4887//4887 4886//4886 5573//5573 -f 5573//5573 4886//4886 4890//4890 -f 5573//5573 4890//4890 5572//5572 -f 5572//5572 4890//4890 4889//4889 -f 5572//5572 4889//4889 4893//4893 -f 4883//4883 5574//5574 4884//4884 -f 4884//4884 5574//5574 5575//5575 -f 4884//4884 5575//5575 4880//4880 -f 4880//4880 5575//5575 4881//4881 -f 4877//4877 5576//5576 4878//4878 -f 4878//4878 5576//5576 5577//5577 -f 5578//5578 4875//4875 5577//5577 -f 5577//5577 4875//4875 4874//4874 -f 5577//5577 4874//4874 4878//4878 -f 5579//5579 4872//4872 5578//5578 -f 5578//5578 4872//4872 4871//4871 -f 5578//5578 4871//4871 4875//4875 -f 5580//5580 4869//4869 5579//5579 -f 5579//5579 4869//4869 4868//4868 -f 5579//5579 4868//4868 4872//4872 -f 5581//5581 4866//4866 5580//5580 -f 5580//5580 4866//4866 4865//4865 -f 5580//5580 4865//4865 4869//4869 -f 4860//4860 4859//4859 5582//5582 -f 5582//5582 4859//4859 4863//4863 -f 5582//5582 4863//4863 5581//5581 -f 5581//5581 4863//4863 4862//4862 -f 5581//5581 4862//4862 4866//4866 -f 4856//4856 5583//5583 4857//4857 -f 4857//4857 5583//5583 5584//5584 -f 4857//4857 5584//5584 4853//4853 -f 4853//4853 5584//5584 4854//4854 -f 4850//4850 5585//5585 4851//4851 -f 4851//4851 5585//5585 5586//5586 -f 5587//5587 4848//4848 5586//5586 -f 5586//5586 4848//4848 4847//4847 -f 5586//5586 4847//4847 4851//4851 -f 5588//5588 4845//4845 5587//5587 -f 5587//5587 4845//4845 4844//4844 -f 5587//5587 4844//4844 4848//4848 -f 5589//5589 4842//4842 5588//5588 -f 5588//5588 4842//4842 4841//4841 -f 5588//5588 4841//4841 4845//4845 -f 5590//5590 4839//4839 5589//5589 -f 5589//5589 4839//4839 4838//4838 -f 5589//5589 4838//4838 4842//4842 -f 4833//4833 4832//4832 5591//5591 -f 5591//5591 4832//4832 4836//4836 -f 5591//5591 4836//4836 5590//5590 -f 5590//5590 4836//4836 4835//4835 -f 5590//5590 4835//4835 4839//4839 -f 4829//4829 5592//5592 4830//4830 -f 4830//4830 5592//5592 5593//5593 -f 4830//4830 5593//5593 4826//4826 -f 4826//4826 5593//5593 4827//4827 -f 4823//4823 5594//5594 4824//4824 -f 4824//4824 5594//5594 5595//5595 -f 5596//5596 4821//4821 5595//5595 -f 5595//5595 4821//4821 4820//4820 -f 5595//5595 4820//4820 4824//4824 -f 5597//5597 4818//4818 5596//5596 -f 5596//5596 4818//4818 4817//4817 -f 5596//5596 4817//4817 4821//4821 -f 4812//4812 4811//4811 5598//5598 -f 5598//5598 4811//4811 4815//4815 -f 5598//5598 4815//4815 5597//5597 -f 5597//5597 4815//4815 4814//4814 -f 5597//5597 4814//4814 4818//4818 -f 4808//4808 5599//5599 4809//4809 -f 4809//4809 5599//5599 5600//5600 -f 5601//5601 4806//4806 5600//5600 -f 5600//5600 4806//4806 4805//4805 -f 5600//5600 4805//4805 4809//4809 -f 4800//4800 4799//4799 5602//5602 -f 5602//5602 4799//4799 4803//4803 -f 5602//5602 4803//4803 5601//5601 -f 5601//5601 4803//4803 4802//4802 -f 5601//5601 4802//4802 4806//4806 -f 4796//4796 5603//5603 4797//4797 -f 4797//4797 5603//5603 5604//5604 -f 4791//4791 4790//4790 5605//5605 -f 5605//5605 4790//4790 4794//4794 -f 5605//5605 4794//4794 5604//5604 -f 5604//5604 4794//4794 4793//4793 -f 5604//5604 4793//4793 4797//4797 -f 4787//4787 5606//5606 4788//4788 -f 4788//4788 5606//5606 5607//5607 -f 4788//4788 5607//5607 4784//4784 -f 4784//4784 5607//5607 4785//4785 -f 4781//4781 5608//5608 4782//4782 -f 4782//4782 5608//5608 5609//5609 -f 5610//5610 4779//4779 5609//5609 -f 5609//5609 4779//4779 4778//4778 -f 5609//5609 4778//4778 4782//4782 -f 4773//4773 4772//4772 5611//5611 -f 5611//5611 4772//4772 4776//4776 -f 5611//5611 4776//4776 5610//5610 -f 5610//5610 4776//4776 4775//4775 -f 5610//5610 4775//4775 4779//4779 -f 4769//4769 5612//5612 4770//4770 -f 4770//4770 5612//5612 5613//5613 -f 4764//4764 4763//4763 5614//5614 -f 5614//5614 4763//4763 4767//4767 -f 5614//5614 4767//4767 5613//5613 -f 5613//5613 4767//4767 4766//4766 -f 5613//5613 4766//4766 4770//4770 -f 4760//4760 5615//5615 4761//4761 -f 4761//4761 5615//5615 5616//5616 -f 4761//4761 5616//5616 4757//4757 -f 4757//4757 5616//5616 4758//4758 -f 4754//4754 5617//5617 4755//4755 -f 4755//4755 5617//5617 5618//5618 -f 5619//5619 4752//4752 5618//5618 -f 5618//5618 4752//4752 4751//4751 -f 5618//5618 4751//4751 4755//4755 -f 5620//5620 4749//4749 5619//5619 -f 5619//5619 4749//4749 4748//4748 -f 5619//5619 4748//4748 4752//4752 -f 5621//5621 4746//4746 5620//5620 -f 5620//5620 4746//4746 4745//4745 -f 5620//5620 4745//4745 4749//4749 -f 5622//5622 4743//4743 5621//5621 -f 5621//5621 4743//4743 4742//4742 -f 5621//5621 4742//4742 4746//4746 -f 4737//4737 4736//4736 5623//5623 -f 5623//5623 4736//4736 4740//4740 -f 5623//5623 4740//4740 5622//5622 -f 5622//5622 4740//4740 4739//4739 -f 5622//5622 4739//4739 4743//4743 -f 4733//4733 5624//5624 4734//4734 -f 4734//4734 5624//5624 5625//5625 -f 4734//4734 5625//5625 4730//4730 -f 4730//4730 5625//5625 4731//4731 -f 4727//4727 5626//5626 4728//4728 -f 4728//4728 5626//5626 5627//5627 -f 5628//5628 4725//4725 5627//5627 -f 5627//5627 4725//4725 4724//4724 -f 5627//5627 4724//4724 4728//4728 -f 5629//5629 4722//4722 5628//5628 -f 5628//5628 4722//4722 4721//4721 -f 5628//5628 4721//4721 4725//4725 -f 5630//5630 4719//4719 5629//5629 -f 5629//5629 4719//4719 4718//4718 -f 5629//5629 4718//4718 4722//4722 -f 5631//5631 4716//4716 5630//5630 -f 5630//5630 4716//4716 4715//4715 -f 5630//5630 4715//4715 4719//4719 -f 5230//5230 5229//5229 5632//5632 -f 5632//5632 5229//5229 4713//4713 -f 5632//5632 4713//4713 5631//5631 -f 5631//5631 4713//4713 4712//4712 -f 5631//5631 4712//4712 4716//4716 -f 5231//5231 5633//5633 5232//5232 -f 5232//5232 5633//5633 5634//5634 -f 5235//5235 5234//5234 5634//5634 -f 5634//5634 5234//5234 5233//5233 -f 5634//5634 5233//5233 5232//5232 -f 5237//5237 5236//5236 5635//5635 -f 5635//5635 5236//5236 5636//5636 -f 5394//5394 5239//5239 5635//5635 -f 5635//5635 5239//5239 5238//5238 -f 5635//5635 5238//5238 5237//5237 -f 5240//5240 5394//5394 5241//5241 -f 5241//5241 5394//5394 5637//5637 -f 5241//5241 5637//5637 5242//5242 -f 5242//5242 5637//5637 5638//5638 -f 5242//5242 5638//5638 5243//5243 -f 5639//5639 5245//5245 5638//5638 -f 5638//5638 5245//5245 5244//5244 -f 5638//5638 5244//5244 5243//5243 -f 5249//5249 5248//5248 5640//5640 -f 5640//5640 5248//5248 5247//5247 -f 5640//5640 5247//5247 5639//5639 -f 5639//5639 5247//5247 5246//5246 -f 5639//5639 5246//5246 5245//5245 -f 5250//5250 5641//5641 5251//5251 -f 5251//5251 5641//5641 5642//5642 -f 5251//5251 5642//5642 5252//5252 -f 5252//5252 5642//5642 5253//5253 -f 5643//5643 5255//5255 5644//5644 -f 5644//5644 5255//5255 5254//5254 -f 5645//5645 5646//5646 5259//5259 -f 5259//5259 5258//5258 5645//5645 -f 5645//5645 5258//5258 5257//5257 -f 5645//5645 5257//5257 5643//5643 -f 5643//5643 5257//5257 5256//5256 -f 5643//5643 5256//5256 5255//5255 -f 5647//5647 5648//5648 5263//5263 -f 5263//5263 5262//5262 5647//5647 -f 5647//5647 5262//5262 5261//5261 -f 5647//5647 5261//5261 5646//5646 -f 5646//5646 5261//5261 5260//5260 -f 5646//5646 5260//5260 5259//5259 -f 5267//5267 5266//5266 5649//5649 -f 5649//5649 5266//5266 5265//5265 -f 5649//5649 5265//5265 5648//5648 -f 5648//5648 5265//5265 5264//5264 -f 5648//5648 5264//5264 5263//5263 -f 5268//5268 5650//5650 5269//5269 -f 5269//5269 5650//5650 5651//5651 -f 5269//5269 5651//5651 5270//5270 -f 5270//5270 5651//5651 5271//5271 -f 5652//5652 5273//5273 5653//5653 -f 5653//5653 5273//5273 5272//5272 -f 5654//5654 5655//5655 5277//5277 -f 5277//5277 5276//5276 5654//5654 -f 5654//5654 5276//5276 5275//5275 -f 5654//5654 5275//5275 5652//5652 -f 5652//5652 5275//5275 5274//5274 -f 5652//5652 5274//5274 5273//5273 -f 5656//5656 5657//5657 5281//5281 -f 5281//5281 5280//5280 5656//5656 -f 5656//5656 5280//5280 5279//5279 -f 5656//5656 5279//5279 5655//5655 -f 5655//5655 5279//5279 5278//5278 -f 5655//5655 5278//5278 5277//5277 -f 5285//5285 5284//5284 5658//5658 -f 5658//5658 5284//5284 5283//5283 -f 5658//5658 5283//5283 5657//5657 -f 5657//5657 5283//5283 5282//5282 -f 5657//5657 5282//5282 5281//5281 -f 5286//5286 5659//5659 5287//5287 -f 5287//5287 5659//5659 5660//5660 -f 5287//5287 5660//5660 5288//5288 -f 5288//5288 5660//5660 5289//5289 -f 5661//5661 5291//5291 5662//5662 -f 5662//5662 5291//5291 5290//5290 -f 5663//5663 5664//5664 5295//5295 -f 5295//5295 5294//5294 5663//5663 -f 5663//5663 5294//5294 5293//5293 -f 5663//5663 5293//5293 5661//5661 -f 5661//5661 5293//5293 5292//5292 -f 5661//5661 5292//5292 5291//5291 -f 5299//5299 5298//5298 5665//5665 -f 5665//5665 5298//5298 5297//5297 -f 5665//5665 5297//5297 5664//5664 -f 5664//5664 5297//5297 5296//5296 -f 5664//5664 5296//5296 5295//5295 -f 5666//5666 5667//5667 5303//5303 -f 5300//5300 5668//5668 5301//5301 -f 5301//5301 5668//5668 5666//5666 -f 5301//5301 5666//5666 5302//5302 -f 5302//5302 5666//5666 5303//5303 -f 5307//5307 5306//5306 5669//5669 -f 5669//5669 5306//5306 5305//5305 -f 5669//5669 5305//5305 5667//5667 -f 5667//5667 5305//5305 5304//5304 -f 5667//5667 5304//5304 5303//5303 -f 5670//5670 5309//5309 5671//5671 -f 5671//5671 5309//5309 5308//5308 -f 5672//5672 5673//5673 5313//5313 -f 5313//5313 5312//5312 5672//5672 -f 5672//5672 5312//5312 5311//5311 -f 5672//5672 5311//5311 5670//5670 -f 5670//5670 5311//5311 5310//5310 -f 5670//5670 5310//5310 5309//5309 -f 5317//5317 5316//5316 5674//5674 -f 5674//5674 5316//5316 5315//5315 -f 5674//5674 5315//5315 5673//5673 -f 5673//5673 5315//5315 5314//5314 -f 5673//5673 5314//5314 5313//5313 -f 5675//5675 5319//5319 5676//5676 -f 5676//5676 5319//5319 5318//5318 -f 5677//5677 5322//5322 5678//5678 -f 5678//5678 5322//5322 5321//5321 -f 5678//5678 5321//5321 5675//5675 -f 5675//5675 5321//5321 5320//5320 -f 5675//5675 5320//5320 5319//5319 -f 5325//5325 5324//5324 5677//5677 -f 5677//5677 5324//5324 5323//5323 -f 5677//5677 5323//5323 5322//5322 -f 5679//5679 5680//5680 5328//5328 -f 5332//5332 5329//5329 5681//5681 -f 5681//5681 5329//5329 5326//5326 -f 5681//5681 5326//5326 5680//5680 -f 5680//5680 5326//5326 5327//5327 -f 5680//5680 5327//5327 5328//5328 -f 5331//5331 5682//5682 5330//5330 -f 5330//5330 5682//5682 5683//5683 -f 5330//5330 5683//5683 5333//5333 -f 5333//5333 5683//5683 5336//5336 -f 5335//5335 5684//5684 5334//5334 -f 5334//5334 5684//5684 5685//5685 -f 5686//5686 5340//5340 5685//5685 -f 5685//5685 5340//5340 5337//5337 -f 5685//5685 5337//5337 5334//5334 -f 5687//5687 5338//5338 5686//5686 -f 5686//5686 5338//5338 5339//5339 -f 5686//5686 5339//5339 5340//5340 -f 5688//5688 5344//5344 5687//5687 -f 5687//5687 5344//5344 5341//5341 -f 5687//5687 5341//5341 5338//5338 -f 5689//5689 5342//5342 5688//5688 -f 5688//5688 5342//5342 5343//5343 -f 5688//5688 5343//5343 5344//5344 -f 5346//5346 5347//5347 5690//5690 -f 5690//5690 5347//5347 5348//5348 -f 5690//5690 5348//5348 5689//5689 -f 5689//5689 5348//5348 5345//5345 -f 5689//5689 5345//5345 5342//5342 -f 5349//5349 5691//5691 5352//5352 -f 5352//5352 5691//5691 5692//5692 -f 5352//5352 5692//5692 5351//5351 -f 5351//5351 5692//5692 5350//5350 -f 5353//5353 5693//5693 5356//5356 -f 5356//5356 5693//5693 5694//5694 -f 5695//5695 5354//5354 5694//5694 -f 5694//5694 5354//5354 5355//5355 -f 5694//5694 5355//5355 5356//5356 -f 5696//5696 5360//5360 5695//5695 -f 5695//5695 5360//5360 5357//5357 -f 5695//5695 5357//5357 5354//5354 -f 5697//5697 5358//5358 5696//5696 -f 5696//5696 5358//5358 5359//5359 -f 5696//5696 5359//5359 5360//5360 -f 5698//5698 5364//5364 5697//5697 -f 5697//5697 5364//5364 5361//5361 -f 5697//5697 5361//5361 5358//5358 -f 5368//5368 5365//5365 5699//5699 -f 5699//5699 5365//5365 5362//5362 -f 5699//5699 5362//5362 5698//5698 -f 5698//5698 5362//5362 5363//5363 -f 5698//5698 5363//5363 5364//5364 -f 5367//5367 5700//5700 5366//5366 -f 5366//5366 5700//5700 5701//5701 -f 5366//5366 5701//5701 5369//5369 -f 5369//5369 5701//5701 5372//5372 -f 5371//5371 5702//5702 5370//5370 -f 5370//5370 5702//5702 5703//5703 -f 5704//5704 5376//5376 5703//5703 -f 5703//5703 5376//5376 5373//5373 -f 5703//5703 5373//5373 5370//5370 -f 5705//5705 5374//5374 5704//5704 -f 5704//5704 5374//5374 5375//5375 -f 5704//5704 5375//5375 5376//5376 -f 5706//5706 5380//5380 5705//5705 -f 5705//5705 5380//5380 5377//5377 -f 5705//5705 5377//5377 5374//5374 -f 5707//5707 5378//5378 5706//5706 -f 5706//5706 5378//5378 5379//5379 -f 5706//5706 5379//5379 5380//5380 -f 5382//5382 5383//5383 5708//5708 -f 5708//5708 5383//5383 5384//5384 -f 5708//5708 5384//5384 5707//5707 -f 5707//5707 5384//5384 5381//5381 -f 5707//5707 5381//5381 5378//5378 -f 5385//5385 5709//5709 5388//5388 -f 5388//5388 5709//5709 5710//5710 -f 5388//5388 5710//5710 5387//5387 -f 5387//5387 5710//5710 5386//5386 -f 5389//5389 5711//5711 5393//5393 -f 5393//5393 5711//5711 5712//5712 -f 5713//5713 5391//5391 5712//5712 -f 5712//5712 5391//5391 5392//5392 -f 5712//5712 5392//5392 5393//5393 -f 5145//5145 5144//5144 5551//5551 -f 5551//5551 5144//5144 5142//5142 -f 5551//5551 5142//5142 5713//5713 -f 5713//5713 5142//5142 5141//5141 -f 5713//5713 5141//5141 5391//5391 -f 5557//5557 4166//4166 5558//5558 -f 5558//5558 4166//4166 4165//4165 -f 5558//5558 4165//4165 5559//5559 -f 5559//5559 4165//4165 4163//4163 -f 5559//5559 4163//4163 5560//5560 -f 4163//4163 4161//4161 5560//5560 -f 5560//5560 4161//4161 4160//4160 -f 5560//5560 4160//4160 5561//5561 -f 5561//5561 4160//4160 4167//4167 -f 5561//5561 4167//4167 5562//5562 -f 4167//4167 4169//4169 5562//5562 -f 5562//5562 4169//4169 4171//4171 -f 5562//5562 4171//4171 5563//5563 -f 5563//5563 4171//4171 4172//4172 -f 5563//5563 4172//4172 5564//5564 -f 5564//5564 4172//4172 4174//4174 -f 4174//4174 4175//4175 5564//5564 -f 5564//5564 4175//4175 5565//5565 -f 5564//5564 5565//5565 4914//4914 -f 4914//4914 5565//5565 4910//4910 -f 4176//4176 5566//5566 4157//4157 -f 4157//4157 5566//5566 5565//5565 -f 4157//4157 5565//5565 4158//4158 -f 4158//4158 5565//5565 4175//4175 -f 4176//4176 4178//4178 5566//5566 -f 5566//5566 4178//4178 5567//5567 -f 5566//5566 5567//5567 4908//4908 -f 4908//4908 5567//5567 4904//4904 -f 4178//4178 4181//4181 5567//5567 -f 5567//5567 4181//4181 4183//4183 -f 5567//5567 4183//4183 5568//5568 -f 5568//5568 4183//4183 4184//4184 -f 5568//5568 4184//4184 5569//5569 -f 4184//4184 4186//4186 5569//5569 -f 5569//5569 4186//4186 4188//4188 -f 5569//5569 4188//4188 5570//5570 -f 5570//5570 4188//4188 4190//4190 -f 5570//5570 4190//4190 5571//5571 -f 4190//4190 4193//4193 5571//5571 -f 5571//5571 4193//4193 4195//4195 -f 5571//5571 4195//4195 5572//5572 -f 5572//5572 4195//4195 4197//4197 -f 5572//5572 4197//4197 5573//5573 -f 5573//5573 4197//4197 4199//4199 -f 4199//4199 4201//4201 5573//5573 -f 5573//5573 4201//4201 5574//5574 -f 5573//5573 5574//5574 4887//4887 -f 4887//4887 5574//5574 4883//4883 -f 4207//4207 5575//5575 4205//4205 -f 4205//4205 5575//5575 5574//5574 -f 4205//4205 5574//5574 4203//4203 -f 4203//4203 5574//5574 4201//4201 -f 4207//4207 4209//4209 5575//5575 -f 5575//5575 4209//4209 5576//5576 -f 5575//5575 5576//5576 4881//4881 -f 4881//4881 5576//5576 4877//4877 -f 4209//4209 4211//4211 5576//5576 -f 5576//5576 4211//4211 4213//4213 -f 5576//5576 4213//4213 5577//5577 -f 5577//5577 4213//4213 4215//4215 -f 5577//5577 4215//4215 5578//5578 -f 4215//4215 4217//4217 5578//5578 -f 5578//5578 4217//4217 4219//4219 -f 5578//5578 4219//4219 5579//5579 -f 5579//5579 4219//4219 4221//4221 -f 5579//5579 4221//4221 5580//5580 -f 4221//4221 4224//4224 5580//5580 -f 5580//5580 4224//4224 4226//4226 -f 5580//5580 4226//4226 5581//5581 -f 5581//5581 4226//4226 4228//4228 -f 5581//5581 4228//4228 5582//5582 -f 5582//5582 4228//4228 4230//4230 -f 4230//4230 4231//4231 5582//5582 -f 5582//5582 4231//4231 5583//5583 -f 5582//5582 5583//5583 4860//4860 -f 4860//4860 5583//5583 4856//4856 -f 4237//4237 5584//5584 4235//4235 -f 4235//4235 5584//5584 5583//5583 -f 4235//4235 5583//5583 4233//4233 -f 4233//4233 5583//5583 4231//4231 -f 4237//4237 4239//4239 5584//5584 -f 5584//5584 4239//4239 5585//5585 -f 5584//5584 5585//5585 4854//4854 -f 4854//4854 5585//5585 4850//4850 -f 4239//4239 4241//4241 5585//5585 -f 5585//5585 4241//4241 4243//4243 -f 5585//5585 4243//4243 5586//5586 -f 5586//5586 4243//4243 4245//4245 -f 5586//5586 4245//4245 5587//5587 -f 4245//4245 4247//4247 5587//5587 -f 5587//5587 4247//4247 4249//4249 -f 5587//5587 4249//4249 5588//5588 -f 5588//5588 4249//4249 4251//4251 -f 5588//5588 4251//4251 5589//5589 -f 4251//4251 4254//4254 5589//5589 -f 5589//5589 4254//4254 4256//4256 -f 5589//5589 4256//4256 5590//5590 -f 5590//5590 4256//4256 4258//4258 -f 5590//5590 4258//4258 5591//5591 -f 5591//5591 4258//4258 4260//4260 -f 4260//4260 4261//4261 5591//5591 -f 5591//5591 4261//4261 5592//5592 -f 5591//5591 5592//5592 4833//4833 -f 4833//4833 5592//5592 4829//4829 -f 4267//4267 5593//5593 4265//4265 -f 4265//4265 5593//5593 5592//5592 -f 4265//4265 5592//5592 4263//4263 -f 4263//4263 5592//5592 4261//4261 -f 4267//4267 4269//4269 5593//5593 -f 5593//5593 4269//4269 5594//5594 -f 5593//5593 5594//5594 4827//4827 -f 4827//4827 5594//5594 4823//4823 -f 4269//4269 4271//4271 5594//5594 -f 5594//5594 4271//4271 4273//4273 -f 5594//5594 4273//4273 5595//5595 -f 5595//5595 4273//4273 4275//4275 -f 5595//5595 4275//4275 5596//5596 -f 4284//4284 5598//5598 4281//4281 -f 4281//4281 5598//5598 5597//5597 -f 4281//4281 5597//5597 4279//4279 -f 4279//4279 5597//5597 5596//5596 -f 4279//4279 5596//5596 4277//4277 -f 4277//4277 5596//5596 4275//4275 -f 4284//4284 4286//4286 5598//5598 -f 5598//5598 4286//4286 5599//5599 -f 5598//5598 5599//5599 4812//4812 -f 4812//4812 5599//5599 4808//4808 -f 4286//4286 4288//4288 5599//5599 -f 5599//5599 4288//4288 4306//4306 -f 5599//5599 4306//4306 5600//5600 -f 5600//5600 4306//4306 4305//4305 -f 5600//5600 4305//4305 5601//5601 -f 4299//4299 5602//5602 4301//4301 -f 4301//4301 5602//5602 5601//5601 -f 4301//4301 5601//5601 4303//4303 -f 4303//4303 5601//5601 4305//4305 -f 4299//4299 4297//4297 5602//5602 -f 5602//5602 4297//4297 5603//5603 -f 5602//5602 5603//5603 4800//4800 -f 4800//4800 5603//5603 4796//4796 -f 4297//4297 4295//4295 5603//5603 -f 5603//5603 4295//4295 4293//4293 -f 5603//5603 4293//4293 5604//5604 -f 5604//5604 4293//4293 4291//4291 -f 5604//5604 4291//4291 5605//5605 -f 5605//5605 4291//4291 4338//4338 -f 4338//4338 4337//4337 5605//5605 -f 5605//5605 4337//4337 5606//5606 -f 5605//5605 5606//5606 4791//4791 -f 4791//4791 5606//5606 4787//4787 -f 4331//4331 5607//5607 4333//4333 -f 4333//4333 5607//5607 5606//5606 -f 4333//4333 5606//5606 4335//4335 -f 4335//4335 5606//5606 4337//4337 -f 4331//4331 4329//4329 5607//5607 -f 5607//5607 4329//4329 5608//5608 -f 5607//5607 5608//5608 4785//4785 -f 4785//4785 5608//5608 4781//4781 -f 4329//4329 4327//4327 5608//5608 -f 5608//5608 4327//4327 4325//4325 -f 5608//5608 4325//4325 5609//5609 -f 5609//5609 4325//4325 4323//4323 -f 5609//5609 4323//4323 5610//5610 -f 4317//4317 5611//5611 4319//4319 -f 4319//4319 5611//5611 5610//5610 -f 4319//4319 5610//5610 4321//4321 -f 4321//4321 5610//5610 4323//4323 -f 4317//4317 4315//4315 5611//5611 -f 5611//5611 4315//4315 5612//5612 -f 5611//5611 5612//5612 4773//4773 -f 4773//4773 5612//5612 4769//4769 -f 4315//4315 4313//4313 5612//5612 -f 5612//5612 4313//4313 4311//4311 -f 5612//5612 4311//4311 5613//5613 -f 5613//5613 4311//4311 4309//4309 -f 5613//5613 4309//4309 5614//5614 -f 5614//5614 4309//4309 4308//4308 -f 4308//4308 4339//4339 5614//5614 -f 5614//5614 4339//4339 5615//5615 -f 5614//5614 5615//5615 4764//4764 -f 4764//4764 5615//5615 4760//4760 -f 4345//4345 5616//5616 4343//4343 -f 4343//4343 5616//5616 5615//5615 -f 4343//4343 5615//5615 4341//4341 -f 4341//4341 5615//5615 4339//4339 -f 4345//4345 4347//4347 5616//5616 -f 5616//5616 4347//4347 5617//5617 -f 5616//5616 5617//5617 4758//4758 -f 4758//4758 5617//5617 4754//4754 -f 4347//4347 4349//4349 5617//5617 -f 5617//5617 4349//4349 4351//4351 -f 5617//5617 4351//4351 5618//5618 -f 5618//5618 4351//4351 4353//4353 -f 5618//5618 4353//4353 5619//5619 -f 4353//4353 4355//4355 5619//5619 -f 5619//5619 4355//4355 4357//4357 -f 5619//5619 4357//4357 5620//5620 -f 5620//5620 4357//4357 4359//4359 -f 5620//5620 4359//4359 5621//5621 -f 4359//4359 4362//4362 5621//5621 -f 5621//5621 4362//4362 4364//4364 -f 5621//5621 4364//4364 5622//5622 -f 5622//5622 4364//4364 4366//4366 -f 5622//5622 4366//4366 5623//5623 -f 5623//5623 4366//4366 4368//4368 -f 4368//4368 4369//4369 5623//5623 -f 5623//5623 4369//4369 5624//5624 -f 5623//5623 5624//5624 4737//4737 -f 4737//4737 5624//5624 4733//4733 -f 4375//4375 5625//5625 4373//4373 -f 4373//4373 5625//5625 5624//5624 -f 4373//4373 5624//5624 4371//4371 -f 4371//4371 5624//5624 4369//4369 -f 4375//4375 4377//4377 5625//5625 -f 5625//5625 4377//4377 5626//5626 -f 5625//5625 5626//5626 4731//4731 -f 4731//4731 5626//5626 4727//4727 -f 4377//4377 4379//4379 5626//5626 -f 5626//5626 4379//4379 4381//4381 -f 5626//5626 4381//4381 5627//5627 -f 5627//5627 4381//4381 4383//4383 -f 5627//5627 4383//4383 5628//5628 -f 4383//4383 4385//4385 5628//5628 -f 5628//5628 4385//4385 4387//4387 -f 5628//5628 4387//4387 5629//5629 -f 5629//5629 4387//4387 4389//4389 -f 5629//5629 4389//4389 5630//5630 -f 4389//4389 4392//4392 5630//5630 -f 5630//5630 4392//4392 4394//4394 -f 5630//5630 4394//4394 5631//5631 -f 5631//5631 4394//4394 4396//4396 -f 5631//5631 4396//4396 5632//5632 -f 5632//5632 4396//4396 4398//4398 -f 4398//4398 4400//4400 5632//5632 -f 5632//5632 4400//4400 5633//5633 -f 5632//5632 5633//5633 5230//5230 -f 5230//5230 5633//5633 5231//5231 -f 4406//4406 5634//5634 4404//4404 -f 4404//4404 5634//5634 5633//5633 -f 4404//4404 5633//5633 4402//4402 -f 4402//4402 5633//5633 4400//4400 -f 4406//4406 4408//4408 5634//5634 -f 5634//5634 4408//4408 5636//5636 -f 5634//5634 5636//5636 5235//5235 -f 5235//5235 5636//5636 5236//5236 -f 4408//4408 4410//4410 5636//5636 -f 5636//5636 4410//4410 4412//4412 -f 5636//5636 4412//4412 5635//5635 -f 5635//5635 4412//4412 4414//4414 -f 5635//5635 4414//4414 5394//5394 -f 4414//4414 4416//4416 5394//5394 -f 5394//5394 4416//4416 4417//4417 -f 5394//5394 4417//4417 5637//5637 -f 5637//5637 4417//4417 4419//4419 -f 5637//5637 4419//4419 5638//5638 -f 4419//4419 4422//4422 5638//5638 -f 5638//5638 4422//4422 4424//4424 -f 5638//5638 4424//4424 5639//5639 -f 5639//5639 4424//4424 4426//4426 -f 5639//5639 4426//4426 5640//5640 -f 5640//5640 4426//4426 4428//4428 -f 4428//4428 4430//4430 5640//5640 -f 5640//5640 4430//4430 5641//5641 -f 5640//5640 5641//5641 5249//5249 -f 5249//5249 5641//5641 5250//5250 -f 4436//4436 5642//5642 4434//4434 -f 4434//4434 5642//5642 5641//5641 -f 4434//4434 5641//5641 4432//4432 -f 4432//4432 5641//5641 4430//4430 -f 4436//4436 4438//4438 5642//5642 -f 5642//5642 4438//4438 5644//5644 -f 5642//5642 5644//5644 5253//5253 -f 5253//5253 5644//5644 5254//5254 -f 4438//4438 4440//4440 5644//5644 -f 5644//5644 4440//4440 4442//4442 -f 5644//5644 4442//4442 5643//5643 -f 5643//5643 4442//4442 4444//4444 -f 5643//5643 4444//4444 5645//5645 -f 4444//4444 4446//4446 5645//5645 -f 5645//5645 4446//4446 4447//4447 -f 5645//5645 4447//4447 5646//5646 -f 5646//5646 4447//4447 4449//4449 -f 5646//5646 4449//4449 5647//5647 -f 4449//4449 4452//4452 5647//5647 -f 5647//5647 4452//4452 4454//4454 -f 5647//5647 4454//4454 5648//5648 -f 5648//5648 4454//4454 4456//4456 -f 5648//5648 4456//4456 5649//5649 -f 5649//5649 4456//4456 4458//4458 -f 4458//4458 4460//4460 5649//5649 -f 5649//5649 4460//4460 5650//5650 -f 5649//5649 5650//5650 5267//5267 -f 5267//5267 5650//5650 5268//5268 -f 4466//4466 5651//5651 4464//4464 -f 4464//4464 5651//5651 5650//5650 -f 4464//4464 5650//5650 4462//4462 -f 4462//4462 5650//5650 4460//4460 -f 4466//4466 4468//4468 5651//5651 -f 5651//5651 4468//4468 5653//5653 -f 5651//5651 5653//5653 5271//5271 -f 5271//5271 5653//5653 5272//5272 -f 4468//4468 4470//4470 5653//5653 -f 5653//5653 4470//4470 4472//4472 -f 5653//5653 4472//4472 5652//5652 -f 5652//5652 4472//4472 4473//4473 -f 5652//5652 4473//4473 5654//5654 -f 4473//4473 4475//4475 5654//5654 -f 5654//5654 4475//4475 4477//4477 -f 5654//5654 4477//4477 5655//5655 -f 5655//5655 4477//4477 4479//4479 -f 5655//5655 4479//4479 5656//5656 -f 4479//4479 4482//4482 5656//5656 -f 5656//5656 4482//4482 4484//4484 -f 5656//5656 4484//4484 5657//5657 -f 5657//5657 4484//4484 4486//4486 -f 5657//5657 4486//4486 5658//5658 -f 5658//5658 4486//4486 4496//4496 -f 4496//4496 4495//4495 5658//5658 -f 5658//5658 4495//4495 5659//5659 -f 5658//5658 5659//5659 5285//5285 -f 5285//5285 5659//5659 5286//5286 -f 4489//4489 5660//5660 4491//4491 -f 4491//4491 5660//5660 5659//5659 -f 4491//4491 5659//5659 4493//4493 -f 4493//4493 5659//5659 4495//4495 -f 4489//4489 4488//4488 5660//5660 -f 5660//5660 4488//4488 5662//5662 -f 5660//5660 5662//5662 5289//5289 -f 5289//5289 5662//5662 5290//5290 -f 4488//4488 4499//4499 5662//5662 -f 5662//5662 4499//4499 4501//4501 -f 5662//5662 4501//4501 5661//5661 -f 5661//5661 4501//4501 4503//4503 -f 5661//5661 4503//4503 5663//5663 -f 4511//4511 5665//5665 4509//4509 -f 4509//4509 5665//5665 5664//5664 -f 4509//4509 5664//5664 4506//4506 -f 4506//4506 5664//5664 5663//5663 -f 4506//4506 5663//5663 4505//4505 -f 4505//4505 5663//5663 4503//4503 -f 4511//4511 4513//4513 5665//5665 -f 5665//5665 4513//4513 5668//5668 -f 5665//5665 5668//5668 5299//5299 -f 5299//5299 5668//5668 5300//5300 -f 4513//4513 4516//4516 5668//5668 -f 5668//5668 4516//4516 4518//4518 -f 5668//5668 4518//4518 5666//5666 -f 5666//5666 4518//4518 4520//4520 -f 5666//5666 4520//4520 5667//5667 -f 4524//4524 5669//5669 4526//4526 -f 4526//4526 5669//5669 5667//5667 -f 4526//4526 5667//5667 4527//4527 -f 4527//4527 5667//5667 4520//4520 -f 4524//4524 4523//4523 5669//5669 -f 5669//5669 4523//4523 5671//5671 -f 5669//5669 5671//5671 5307//5307 -f 5307//5307 5671//5671 5308//5308 -f 4523//4523 4528//4528 5671//5671 -f 5671//5671 4528//4528 4530//4530 -f 5671//5671 4530//4530 5670//5670 -f 5670//5670 4530//4530 4533//4533 -f 5670//5670 4533//4533 5672//5672 -f 4542//4542 5674//5674 4539//4539 -f 4539//4539 5674//5674 5673//5673 -f 4539//4539 5673//5673 4537//4537 -f 4537//4537 5673//5673 5672//5672 -f 4537//4537 5672//5672 4535//4535 -f 4535//4535 5672//5672 4533//4533 -f 4542//4542 4544//4544 5674//5674 -f 5674//5674 4544//4544 5676//5676 -f 5674//5674 5676//5676 5317//5317 -f 5317//5317 5676//5676 5318//5318 -f 4544//4544 4546//4546 5676//5676 -f 5676//5676 4546//4546 4556//4556 -f 5676//5676 4556//4556 5675//5675 -f 5675//5675 4556//4556 4555//4555 -f 5675//5675 4555//4555 5678//5678 -f 4549//4549 5677//5677 4551//4551 -f 4551//4551 5677//5677 5678//5678 -f 4551//4551 5678//5678 4553//4553 -f 4553//4553 5678//5678 4555//4555 -f 4549//4549 4548//4548 5677//5677 -f 5677//5677 4548//4548 5679//5679 -f 5677//5677 5679//5679 5325//5325 -f 5325//5325 5679//5679 5328//5328 -f 4548//4548 4559//4559 5679//5679 -f 5679//5679 4559//4559 4561//4561 -f 5679//5679 4561//4561 5680//5680 -f 5680//5680 4561//4561 4563//4563 -f 5680//5680 4563//4563 5681//5681 -f 5681//5681 4563//4563 4565//4565 -f 4565//4565 4566//4566 5681//5681 -f 5681//5681 4566//4566 5682//5682 -f 5681//5681 5682//5682 5332//5332 -f 5332//5332 5682//5682 5331//5331 -f 4573//4573 5683//5683 4571//4571 -f 4571//4571 5683//5683 5682//5682 -f 4571//4571 5682//5682 4569//4569 -f 4569//4569 5682//5682 4566//4566 -f 4573//4573 4574//4574 5683//5683 -f 5683//5683 4574//4574 5684//5684 -f 5683//5683 5684//5684 5336//5336 -f 5336//5336 5684//5684 5335//5335 -f 4574//4574 4577//4577 5684//5684 -f 5684//5684 4577//4577 4579//4579 -f 5684//5684 4579//4579 5685//5685 -f 5685//5685 4579//4579 4581//4581 -f 5685//5685 4581//4581 5686//5686 -f 4581//4581 4583//4583 5686//5686 -f 5686//5686 4583//4583 4584//4584 -f 5686//5686 4584//4584 5687//5687 -f 5687//5687 4584//4584 4587//4587 -f 5687//5687 4587//4587 5688//5688 -f 4587//4587 4589//4589 5688//5688 -f 5688//5688 4589//4589 4591//4591 -f 5688//5688 4591//4591 5689//5689 -f 5689//5689 4591//4591 4594//4594 -f 5689//5689 4594//4594 5690//5690 -f 5690//5690 4594//4594 4596//4596 -f 4596//4596 4598//4598 5690//5690 -f 5690//5690 4598//4598 5691//5691 -f 5690//5690 5691//5691 5346//5346 -f 5346//5346 5691//5691 5349//5349 -f 4602//4602 5692//5692 4604//4604 -f 4604//4604 5692//5692 5691//5691 -f 4604//4604 5691//5691 4605//4605 -f 4605//4605 5691//5691 4598//4598 -f 4602//4602 4601//4601 5692//5692 -f 5692//5692 4601//4601 5693//5693 -f 5692//5692 5693//5693 5350//5350 -f 5350//5350 5693//5693 5353//5353 -f 4601//4601 4606//4606 5693//5693 -f 5693//5693 4606//4606 4608//4608 -f 5693//5693 4608//4608 5694//5694 -f 5694//5694 4608//4608 4610//4610 -f 5694//5694 4610//4610 5695//5695 -f 4610//4610 4612//4612 5695//5695 -f 5695//5695 4612//4612 4615//4615 -f 5695//5695 4615//4615 5696//5696 -f 5696//5696 4615//4615 4617//4617 -f 5696//5696 4617//4617 5697//5697 -f 4617//4617 4620//4620 5697//5697 -f 5697//5697 4620//4620 4622//4622 -f 5697//5697 4622//4622 5698//5698 -f 5698//5698 4622//4622 4624//4624 -f 5698//5698 4624//4624 5699//5699 -f 5699//5699 4624//4624 4634//4634 -f 4634//4634 4633//4633 5699//5699 -f 5699//5699 4633//4633 5700//5700 -f 5699//5699 5700//5700 5368//5368 -f 5368//5368 5700//5700 5367//5367 -f 4627//4627 5701//5701 4629//4629 -f 4629//4629 5701//5701 5700//5700 -f 4629//4629 5700//5700 4631//4631 -f 4631//4631 5700//5700 4633//4633 -f 4627//4627 4626//4626 5701//5701 -f 5701//5701 4626//4626 5702//5702 -f 5701//5701 5702//5702 5372//5372 -f 5372//5372 5702//5702 5371//5371 -f 4626//4626 4637//4637 5702//5702 -f 5702//5702 4637//4637 4639//4639 -f 5702//5702 4639//4639 5703//5703 -f 5703//5703 4639//4639 4641//4641 -f 5703//5703 4641//4641 5704//5704 -f 4641//4641 4643//4643 5704//5704 -f 5704//5704 4643//4643 4644//4644 -f 5704//5704 4644//4644 5705//5705 -f 5705//5705 4644//4644 4647//4647 -f 5705//5705 4647//4647 5706//5706 -f 4647//4647 4649//4649 5706//5706 -f 5706//5706 4649//4649 4651//4651 -f 5706//5706 4651//4651 5707//5707 -f 5707//5707 4651//4651 4654//4654 -f 5707//5707 4654//4654 5708//5708 -f 5708//5708 4654//4654 4656//4656 -f 4656//4656 4658//4658 5708//5708 -f 5708//5708 4658//4658 5709//5709 -f 5708//5708 5709//5709 5382//5382 -f 5382//5382 5709//5709 5385//5385 -f 4662//4662 5710//5710 4664//4664 -f 4664//4664 5710//5710 5709//5709 -f 4664//4664 5709//5709 4665//4665 -f 4665//4665 5709//5709 4658//4658 -f 4662//4662 4661//4661 5710//5710 -f 5710//5710 4661//4661 5711//5711 -f 5710//5710 5711//5711 5386//5386 -f 5386//5386 5711//5711 5389//5389 -f 4661//4661 4666//4666 5711//5711 -f 5711//5711 4666//4666 4668//4668 -f 5711//5711 4668//4668 5712//5712 -f 5712//5712 4668//4668 4670//4670 -f 5712//5712 4670//4670 5713//5713 -f 4670//4670 4672//4672 5713//5713 -f 5713//5713 4672//4672 4678//4678 -f 5713//5713 4678//4678 5551//5551 -f 5551//5551 4678//4678 4676//4676 -f 5551//5551 4676//4676 5552//5552 -f 4704//4704 5714//5714 4706//4706 -f 4706//4706 5714//5714 5715//5715 -f 4706//4706 5715//5715 4708//4708 -f 4708//4708 5715//5715 5397//5397 -f 4708//4708 5397//5397 4710//4710 -f 4710//4710 5397//5397 5396//5396 -f 4710//4710 5396//5396 4711//4711 -f 4711//4711 5396//5396 5552//5552 -f 4711//4711 5552//5552 4674//4674 -f 4674//4674 5552//5552 4676//4676 -f 5546//5546 5545//5545 5716//5716 -f 5716//5716 5545//5545 5544//5544 -f 5544//5544 5548//5548 5716//5716 -f 5716//5716 5548//5548 5549//5549 -f 5716//5716 5549//5549 5717//5717 -f 5717//5717 5549//5549 5550//5550 -f 5717//5717 5550//5550 5024//5024 -f 5536//5536 5543//5543 5718//5718 -f 5718//5718 5543//5543 5542//5542 -f 5718//5718 5542//5542 5716//5716 -f 5716//5716 5542//5542 5547//5547 -f 5716//5716 5547//5547 5546//5546 -f 5719//5719 5541//5541 5540//5540 -f 5540//5540 5539//5539 5719//5719 -f 5719//5719 5539//5539 5538//5538 -f 5719//5719 5538//5538 5718//5718 -f 5718//5718 5538//5538 5537//5537 -f 5718//5718 5537//5537 5536//5536 -f 5530//5530 5529//5529 5720//5720 -f 5720//5720 5529//5529 5535//5535 -f 5720//5720 5535//5535 5719//5719 -f 5719//5719 5535//5535 5534//5534 -f 5719//5719 5534//5534 5541//5541 -f 5526//5526 5533//5533 5721//5721 -f 5721//5721 5533//5533 5532//5532 -f 5721//5721 5532//5532 5720//5720 -f 5720//5720 5532//5532 5531//5531 -f 5720//5720 5531//5531 5530//5530 -f 5722//5722 5524//5524 5522//5522 -f 5528//5528 5527//5527 5721//5721 -f 5721//5721 5527//5527 5525//5525 -f 5721//5721 5525//5525 5526//5526 -f 5722//5722 5522//5522 5721//5721 -f 5721//5721 5522//5522 5523//5523 -f 5721//5721 5523//5523 5528//5528 -f 5515//5515 5521//5521 5723//5723 -f 5723//5723 5521//5521 5520//5520 -f 5520//5520 5519//5519 5723//5723 -f 5723//5723 5519//5519 5518//5518 -f 5723//5723 5518//5518 5722//5722 -f 5722//5722 5518//5518 5517//5517 -f 5722//5722 5517//5517 5524//5524 -f 5513//5513 5512//5512 5724//5724 -f 5724//5724 5512//5512 5511//5511 -f 5724//5724 5511//5511 5723//5723 -f 5723//5723 5511//5511 5516//5516 -f 5723//5723 5516//5516 5515//5515 -f 5505//5505 5504//5504 5725//5725 -f 5725//5725 5504//5504 5503//5503 -f 5725//5725 5503//5503 5724//5724 -f 5724//5724 5503//5503 5514//5514 -f 5724//5724 5514//5514 5513//5513 -f 5508//5508 5507//5507 5725//5725 -f 5725//5725 5507//5507 5506//5506 -f 5725//5725 5506//5506 5505//5505 -f 5497//5497 5498//5498 5726//5726 -f 5726//5726 5498//5498 5510//5510 -f 5726//5726 5510//5510 5725//5725 -f 5725//5725 5510//5510 5509//5509 -f 5725//5725 5509//5509 5508//5508 -f 5727//5727 5501//5501 5500//5500 -f 5500//5500 5499//5499 5727//5727 -f 5727//5727 5499//5499 5495//5495 -f 5727//5727 5495//5495 5726//5726 -f 5726//5726 5495//5495 5496//5496 -f 5726//5726 5496//5496 5497//5497 -f 5494//5494 5493//5493 5023//5023 -f 5023//5023 5493//5493 5492//5492 -f 5023//5023 5492//5492 5024//5024 -f 5024//5024 5492//5492 5491//5491 -f 5024//5024 5491//5491 5727//5727 -f 5727//5727 5491//5491 5502//5502 -f 5727//5727 5502//5502 5501//5501 -f 5489//5489 5488//5488 5012//5012 -f 5012//5012 5488//5488 5487//5487 -f 5012//5012 5487//5487 5014//5014 -f 5014//5014 5487//5487 5016//5016 -f 5016//5016 5487//5487 5486//5486 -f 5016//5016 5486//5486 5017//5017 -f 5486//5486 5485//5485 5017//5017 -f 5017//5017 5485//5485 5484//5484 -f 5017//5017 5484//5484 5019//5019 -f 5019//5019 5484//5484 5494//5494 -f 5019//5019 5494//5494 5021//5021 -f 5021//5021 5494//5494 5023//5023 -f 5479//5479 5480//5480 5029//5029 -f 5029//5029 5480//5480 5481//5481 -f 5029//5029 5481//5481 5030//5030 -f 5030//5030 5481//5481 5490//5490 -f 5030//5030 5490//5490 5031//5031 -f 5031//5031 5490//5490 5489//5489 -f 5031//5031 5489//5489 5011//5011 -f 5011//5011 5489//5489 5012//5012 -f 5008//5008 5471//5471 5009//5009 -f 5009//5009 5471//5471 5472//5472 -f 5009//5009 5472//5472 5033//5033 -f 5033//5033 5472//5472 5034//5034 -f 5034//5034 5472//5472 5476//5476 -f 5034//5034 5476//5476 5035//5035 -f 5476//5476 5478//5478 5035//5035 -f 5035//5035 5478//5478 5482//5482 -f 5035//5035 5482//5482 5026//5026 -f 5026//5026 5482//5482 5479//5479 -f 5026//5026 5479//5479 5028//5028 -f 5028//5028 5479//5479 5029//5029 -f 5398//5398 5466//5466 5044//5044 -f 5044//5044 5466//5466 5468//5468 -f 5044//5044 5468//5468 5038//5038 -f 5038//5038 5468//5468 5475//5475 -f 5038//5038 5475//5475 5036//5036 -f 5036//5036 5475//5475 5474//5474 -f 5036//5036 5474//5474 5008//5008 -f 5008//5008 5474//5474 5473//5473 -f 5008//5008 5473//5473 5471//5471 -f 5464//5464 5045//5045 5465//5465 -f 5465//5465 5045//5045 5459//5459 -f 5044//5044 5043//5043 5398//5398 -f 5398//5398 5043//5043 5042//5042 -f 5398//5398 5042//5042 5399//5399 -f 5399//5399 5042//5042 5041//5041 -f 5399//5399 5041//5041 5463//5463 -f 5463//5463 5041//5041 5047//5047 -f 5463//5463 5047//5047 5464//5464 -f 5464//5464 5047//5047 5046//5046 -f 5464//5464 5046//5046 5045//5045 -f 5052//5052 5460//5460 5005//5005 -f 5005//5005 5460//5460 5459//5459 -f 5005//5005 5459//5459 5006//5006 -f 5006//5006 5459//5459 5045//5045 -f 5057//5057 5455//5455 5051//5051 -f 5051//5051 5455//5455 5457//5457 -f 5051//5051 5457//5457 5050//5050 -f 5050//5050 5457//5457 5462//5462 -f 5050//5050 5462//5462 5052//5052 -f 5052//5052 5462//5462 5461//5461 -f 5052//5052 5461//5461 5460//5460 -f 5440//5440 5439//5439 5067//5067 -f 5067//5067 5439//5439 5446//5446 -f 5067//5067 5446//5446 5068//5068 -f 5068//5068 5446//5446 5450//5450 -f 5068//5068 5450//5450 5059//5059 -f 5059//5059 5450//5450 5449//5449 -f 5059//5059 5449//5449 5060//5060 -f 5060//5060 5449//5449 5448//5448 -f 5060//5060 5448//5448 5054//5054 -f 5054//5054 5448//5448 5454//5454 -f 5054//5054 5454//5454 5056//5056 -f 5056//5056 5454//5454 5452//5452 -f 5056//5056 5452//5452 5057//5057 -f 5057//5057 5452//5452 5451//5451 -f 5057//5057 5451//5451 5455//5455 -f 5442//5442 5071//5071 5444//5444 -f 5444//5444 5071//5071 5070//5070 -f 5444//5444 5070//5070 5445//5445 -f 5445//5445 5070//5070 5077//5077 -f 5445//5445 5077//5077 5434//5434 -f 5067//5067 5065//5065 5440//5440 -f 5440//5440 5065//5065 5064//5064 -f 5440//5440 5064//5064 5442//5442 -f 5442//5442 5064//5064 5063//5063 -f 5442//5442 5063//5063 5071//5071 -f 5072//5072 5435//5435 5075//5075 -f 5075//5075 5435//5435 5434//5434 -f 5075//5075 5434//5434 5076//5076 -f 5076//5076 5434//5434 5077//5077 -f 5084//5084 5428//5428 5430//5430 -f 5084//5084 5430//5430 5085//5085 -f 5085//5085 5430//5430 5433//5433 -f 5085//5085 5433//5433 5087//5087 -f 5087//5087 5433//5433 5088//5088 -f 5088//5088 5433//5433 5432//5432 -f 5088//5088 5432//5432 5002//5002 -f 5002//5002 5432//5432 5431//5431 -f 5002//5002 5431//5431 5003//5003 -f 5003//5003 5431//5431 5438//5438 -f 5003//5003 5438//5438 5072//5072 -f 5072//5072 5438//5438 5437//5437 -f 5072//5072 5437//5437 5435//5435 -f 5428//5428 5084//5084 5423//5423 -f 5423//5423 5084//5084 5078//5078 -f 5423//5423 5078//5078 5424//5424 -f 5424//5424 5078//5078 5080//5080 -f 5424//5424 5080//5080 5426//5426 -f 5426//5426 5080//5080 5082//5082 -f 5426//5426 5082//5082 5427//5427 -f 5427//5427 5082//5082 4999//4999 -f 5427//5427 4999//4999 5401//5401 -f 5401//5401 4999//4999 5093//5093 -f 5401//5401 5093//5093 5402//5402 -f 5421//5421 5095//5095 5422//5422 -f 5422//5422 5095//5095 5094//5094 -f 5422//5422 5094//5094 5419//5419 -f 5093//5093 5092//5092 5402//5402 -f 5402//5402 5092//5092 5090//5090 -f 5402//5402 5090//5090 5421//5421 -f 5421//5421 5090//5090 5089//5089 -f 5421//5421 5089//5089 5095//5095 -f 5096//5096 5099//5099 5405//5405 -f 5405//5405 5099//5099 5100//5100 -f 5405//5405 5100//5100 5414//5414 -f 5414//5414 5100//5100 5101//5101 -f 5414//5414 5101//5101 5415//5415 -f 5405//5405 5404//5404 5096//5096 -f 5096//5096 5404//5404 5420//5420 -f 5096//5096 5420//5420 5097//5097 -f 5097//5097 5420//5420 5419//5419 -f 5097//5097 5419//5419 5098//5098 -f 5098//5098 5419//5419 5094//5094 -f 5415//5415 5101//5101 5417//5417 -f 5417//5417 5101//5101 4998//4998 -f 5417//5417 4998//4998 5407//5407 -f 5407//5407 4998//4998 4997//4997 -f 5407//5407 4997//4997 5408//5408 -f 5408//5408 4997//4997 5105//5105 -f 5408//5408 5105//5105 5410//5410 -f 5105//5105 5104//5104 5410//5410 -f 5410//5410 5104//5104 5103//5103 -f 5410//5410 5103//5103 5412//5412 -f 5412//5412 5103//5103 5102//5102 -f 5412//5412 5102//5102 5413//5413 -f 5413//5413 5102//5102 5108//5108 -f 5413//5413 5108//5108 5557//5557 -f 5557//5557 5108//5108 5107//5107 -f 5557//5557 5107//5107 4166//4166 -f 4159//4159 5131//5131 5130//5130 -f 5130//5130 5135//5135 4159//4159 -f 4159//4159 5135//5135 5134//5134 -f 4159//4159 5134//5134 4177//4177 -f 4177//4177 5134//5134 4179//4179 -f 4173//4173 5129//5129 5128//5128 -f 5128//5128 5127//5127 4173//4173 -f 4173//4173 5127//5127 5133//5133 -f 4173//4173 5133//5133 4159//4159 -f 4159//4159 5133//5133 5132//5132 -f 4159//4159 5132//5132 5131//5131 -f 5117//5117 5124//5124 4170//4170 -f 4170//4170 5124//5124 5123//5123 -f 5123//5123 5122//5122 4170//4170 -f 4170//4170 5122//5122 5126//5126 -f 4170//4170 5126//5126 4173//4173 -f 4173//4173 5126//5126 5125//5125 -f 4173//4173 5125//5125 5129//5129 -f 5117//5117 4170//4170 5118//5118 -f 5118//5118 4170//4170 4168//4168 -f 5118//5118 4168//4168 5119//5119 -f 5114//5114 5113//5113 4162//4162 -f 4162//4162 5113//5113 5121//5121 -f 4162//4162 5121//5121 4168//4168 -f 4168//4168 5121//5121 5120//5120 -f 4168//4168 5120//5120 5119//5119 -f 5107//5107 5106//5106 4166//4166 -f 4166//4166 5106//5106 5112//5112 -f 4166//4166 5112//5112 4164//4164 -f 4164//4164 5112//5112 5111//5111 -f 4164//4164 5111//5111 5110//5110 -f 5110//5110 5109//5109 4164//4164 -f 4164//4164 5109//5109 5116//5116 -f 4164//4164 5116//5116 4162//4162 -f 4162//4162 5116//5116 5115//5115 -f 4162//4162 5115//5115 5114//5114 -f 5728//5728 5729//5729 5730//5730 -f 5730//5730 5731//5731 5728//5728 -f 5728//5728 5731//5731 5732//5732 -f 5728//5728 5732//5732 5733//5733 -f 5734//5734 5735//5735 5736//5736 -f 5737//5737 5738//5738 5739//5739 -f 5740//5740 5741//5741 5742//5742 -f 5743//5743 5744//5744 5745//5745 -f 5733//5733 5732//5732 5746//5746 -f 5746//5746 5732//5732 5747//5747 -f 5744//5744 5748//5748 5745//5745 -f 5745//5745 5748//5748 5749//5749 -f 5745//5745 5749//5749 5750//5750 -f 5751//5751 4147//4147 4146//4146 -f 4150//4150 4149//4149 5752//5752 -f 5752//5752 4149//4149 5753//5753 -f 5753//5753 5754//5754 5752//5752 -f 5752//5752 5754//5754 5755//5755 -f 5752//5752 5755//5755 5756//5756 -f 5742//5742 5757//5757 5756//5756 -f 5742//5742 5741//5741 5757//5757 -f 5757//5757 5741//5741 4141//4141 -f 5757//5757 4141//4141 4140//4140 -f 4144//4144 4143//4143 5758//5758 -f 5758//5758 4143//4143 5759//5759 -f 5760//5760 5730//5730 5729//5729 -f 4146//4146 5743//5743 5751//5751 -f 5751//5751 5743//5743 5745//5745 -f 5751//5751 5745//5745 5761//5761 -f 5761//5761 5745//5745 5750//5750 -f 5761//5761 5750//5750 5762//5762 -f 4142//4142 4141//4141 5763//5763 -f 5763//5763 4141//4141 5741//5741 -f 5763//5763 5741//5741 5764//5764 -f 5764//5764 5741//5741 5740//5740 -f 5764//5764 5740//5740 5765//5765 -f 5766//5766 5755//5755 5767//5767 -f 5767//5767 5755//5755 5754//5754 -f 5767//5767 5754//5754 5768//5768 -f 5768//5768 5754//5754 5753//5753 -f 5768//5768 5753//5753 5769//5769 -f 5770//5770 5771//5771 5772//5772 -f 5773//5773 5771//5771 5774//5774 -f 5774//5774 5771//5771 5770//5770 -f 5774//5774 5770//5770 5775//5775 -f 4155//4155 4154//4154 5775//5775 -f 5775//5775 4154//4154 5776//5776 -f 5775//5775 5776//5776 5774//5774 -f 5774//5774 5776//5776 5777//5777 -f 5774//5774 5777//5777 5773//5773 -f 5773//5773 5777//5777 5778//5778 -f 5779//5779 5780//5780 5781//5781 -f 5781//5781 5780//5780 5782//5782 -f 5781//5781 5782//5782 5747//5747 -f 5747//5747 5782//5782 5783//5783 -f 5747//5747 5783//5783 5746//5746 -f 5732//5732 5731//5731 5747//5747 -f 5747//5747 5731//5731 5784//5784 -f 5747//5747 5784//5784 5781//5781 -f 5781//5781 5784//5784 5785//5785 -f 5781//5781 5785//5785 5779//5779 -f 5779//5779 5785//5785 5786//5786 -f 5731//5731 5730//5730 5784//5784 -f 5784//5784 5730//5730 5760//5760 -f 5784//5784 5760//5760 5785//5785 -f 5785//5785 5760//5760 5787//5787 -f 5785//5785 5787//5787 5786//5786 -f 5786//5786 5787//5787 5788//5788 -f 5789//5789 5790//5790 5791//5791 -f 5791//5791 5790//5790 5792//5792 -f 5791//5791 5792//5792 5793//5793 -f 5793//5793 5792//5792 5736//5736 -f 5794//5794 5766//5766 5795//5795 -f 5795//5795 5766//5766 5767//5767 -f 5795//5795 5767//5767 5796//5796 -f 5796//5796 5767//5767 5768//5768 -f 5796//5796 5768//5768 5797//5797 -f 5797//5797 5768//5768 5769//5769 -f 5797//5797 5769//5769 5798//5798 -f 5799//5799 5797//5797 5800//5800 -f 5800//5800 5797//5797 5798//5798 -f 5800//5800 5798//5798 5801//5801 -f 5802//5802 5801//5801 5803//5803 -f 5803//5803 5801//5801 5798//5798 -f 5803//5803 5798//5798 5804//5804 -f 5804//5804 5798//5798 5769//5769 -f 5804//5804 5769//5769 5805//5805 -f 5805//5805 5769//5769 5753//5753 -f 5805//5805 5753//5753 4148//4148 -f 4148//4148 5753//5753 4149//4149 -f 4148//4148 4147//4147 5805//5805 -f 5805//5805 4147//4147 5751//5751 -f 5805//5805 5751//5751 5804//5804 -f 5804//5804 5751//5751 5761//5761 -f 5804//5804 5761//5761 5803//5803 -f 5803//5803 5761//5761 5762//5762 -f 5803//5803 5762//5762 5802//5802 -f 5802//5802 5762//5762 5806//5806 -f 5772//5772 5807//5807 5808//5808 -f 4156//4156 4155//4155 5748//5748 -f 5748//5748 4155//4155 5775//5775 -f 5748//5748 5775//5775 5749//5749 -f 5749//5749 5775//5775 5770//5770 -f 5749//5749 5770//5770 5750//5750 -f 5750//5750 5770//5770 5772//5772 -f 5750//5750 5772//5772 5762//5762 -f 5762//5762 5772//5772 5808//5808 -f 5762//5762 5808//5808 5806//5806 -f 5809//5809 5810//5810 5778//5778 -f 5778//5778 5810//5810 5811//5811 -f 5778//5778 5811//5811 5773//5773 -f 5773//5773 5811//5811 5812//5812 -f 5773//5773 5812//5812 5771//5771 -f 5771//5771 5812//5812 5813//5813 -f 5771//5771 5813//5813 5772//5772 -f 5772//5772 5813//5813 5814//5814 -f 5772//5772 5814//5814 5807//5807 -f 5738//5738 5809//5809 5739//5739 -f 5739//5739 5809//5809 5778//5778 -f 5739//5739 5778//5778 5815//5815 -f 5815//5815 5778//5778 5777//5777 -f 5815//5815 5777//5777 5816//5816 -f 5816//5816 5777//5777 5776//5776 -f 5816//5816 5776//5776 4153//4153 -f 4153//4153 5776//5776 4154//4154 -f 5817//5817 5737//5737 5818//5818 -f 5818//5818 5737//5737 5739//5739 -f 5818//5818 5739//5739 5819//5819 -f 5819//5819 5739//5739 5815//5815 -f 5819//5819 5815//5815 5820//5820 -f 5820//5820 5815//5815 5816//5816 -f 5820//5820 5816//5816 5821//5821 -f 5821//5821 5816//5816 4153//4153 -f 5821//5821 4153//4153 4152//4152 -f 5821//5821 5822//5822 5820//5820 -f 5820//5820 5822//5822 5823//5823 -f 5820//5820 5823//5823 5819//5819 -f 5819//5819 5823//5823 5824//5824 -f 5819//5819 5824//5824 5818//5818 -f 5818//5818 5824//5824 5825//5825 -f 5818//5818 5825//5825 5817//5817 -f 5817//5817 5825//5825 5826//5826 -f 5822//5822 5746//5746 5823//5823 -f 5823//5823 5746//5746 5783//5783 -f 5823//5823 5783//5783 5824//5824 -f 5824//5824 5783//5783 5782//5782 -f 5824//5824 5782//5782 5825//5825 -f 5825//5825 5782//5782 5780//5780 -f 5825//5825 5780//5780 5826//5826 -f 5826//5826 5780//5780 5827//5827 -f 5828//5828 5829//5829 5788//5788 -f 5788//5788 5829//5829 5830//5830 -f 5788//5788 5830//5830 5786//5786 -f 5786//5786 5830//5830 5831//5831 -f 5786//5786 5831//5831 5779//5779 -f 5779//5779 5831//5831 5832//5832 -f 5779//5779 5832//5832 5780//5780 -f 5780//5780 5832//5832 5833//5833 -f 5780//5780 5833//5833 5827//5827 -f 5834//5834 5828//5828 5793//5793 -f 5793//5793 5828//5828 5788//5788 -f 5793//5793 5788//5788 5791//5791 -f 5791//5791 5788//5788 5787//5787 -f 5791//5791 5787//5787 5789//5789 -f 5789//5789 5787//5787 5760//5760 -f 5789//5789 5760//5760 5835//5835 -f 5835//5835 5760//5760 5729//5729 -f 5736//5736 5735//5735 5793//5793 -f 5793//5793 5735//5735 5836//5836 -f 5793//5793 5836//5836 5834//5834 -f 5837//5837 5734//5734 5838//5838 -f 5838//5838 5734//5734 5736//5736 -f 5838//5838 5736//5736 5839//5839 -f 5839//5839 5736//5736 5792//5792 -f 5839//5839 5792//5792 5759//5759 -f 5759//5759 5792//5792 5790//5790 -f 5759//5759 5790//5790 5758//5758 -f 5758//5758 5790//5790 5789//5789 -f 5758//5758 5789//5789 5840//5840 -f 5840//5840 5789//5789 5835//5835 -f 4143//4143 4142//4142 5759//5759 -f 5759//5759 4142//4142 5763//5763 -f 5759//5759 5763//5763 5839//5839 -f 5839//5839 5763//5763 5764//5764 -f 5839//5839 5764//5764 5838//5838 -f 5838//5838 5764//5764 5765//5765 -f 5838//5838 5765//5765 5837//5837 -f 5837//5837 5765//5765 5841//5841 -f 5756//5756 5755//5755 5742//5742 -f 5742//5742 5755//5755 5766//5766 -f 5742//5742 5766//5766 5740//5740 -f 5740//5740 5766//5766 5794//5794 -f 5740//5740 5794//5794 5765//5765 -f 5765//5765 5794//5794 5842//5842 -f 5765//5765 5842//5842 5841//5841 -f 5799//5799 5843//5843 5797//5797 -f 5797//5797 5843//5843 5844//5844 -f 5797//5797 5844//5844 5796//5796 -f 5796//5796 5844//5844 5845//5845 -f 5796//5796 5845//5845 5795//5795 -f 5795//5795 5845//5845 5846//5846 -f 5795//5795 5846//5846 5794//5794 -f 5794//5794 5846//5846 5847//5847 -f 5794//5794 5847//5847 5842//5842 -f 5843//5843 5848//5848 5849//5849 -f 5801//5801 5850//5850 5800//5800 -f 5800//5800 5850//5850 5848//5848 -f 5800//5800 5848//5848 5799//5799 -f 5799//5799 5848//5848 5843//5843 -f 5801//5801 5802//5802 5850//5850 -f 5850//5850 5802//5802 5806//5806 -f 5850//5850 5806//5806 5851//5851 -f 5806//5806 5808//5808 5851//5851 -f 5851//5851 5808//5808 5807//5807 -f 5851//5851 5807//5807 5852//5852 -f 5812//5812 5853//5853 5813//5813 -f 5813//5813 5853//5853 5852//5852 -f 5813//5813 5852//5852 5814//5814 -f 5814//5814 5852//5852 5807//5807 -f 5812//5812 5811//5811 5853//5853 -f 5853//5853 5811//5811 5810//5810 -f 5853//5853 5810//5810 5854//5854 -f 5810//5810 5809//5809 5854//5854 -f 5854//5854 5809//5809 5738//5738 -f 5854//5854 5738//5738 5855//5855 -f 5738//5738 5737//5737 5855//5855 -f 5855//5855 5737//5737 5817//5817 -f 5855//5855 5817//5817 5856//5856 -f 5817//5817 5826//5826 5856//5856 -f 5856//5856 5826//5826 5827//5827 -f 5856//5856 5827//5827 5857//5857 -f 5831//5831 5858//5858 5832//5832 -f 5832//5832 5858//5858 5857//5857 -f 5832//5832 5857//5857 5833//5833 -f 5833//5833 5857//5857 5827//5827 -f 5831//5831 5830//5830 5858//5858 -f 5858//5858 5830//5830 5829//5829 -f 5858//5858 5829//5829 5859//5859 -f 5829//5829 5828//5828 5859//5859 -f 5859//5859 5828//5828 5834//5834 -f 5859//5859 5834//5834 5860//5860 -f 5734//5734 5861//5861 5735//5735 -f 5735//5735 5861//5861 5860//5860 -f 5735//5735 5860//5860 5836//5836 -f 5836//5836 5860//5860 5834//5834 -f 5734//5734 5837//5837 5861//5861 -f 5861//5861 5837//5837 5841//5841 -f 5861//5861 5841//5841 5862//5862 -f 5841//5841 5842//5842 5862//5862 -f 5862//5862 5842//5842 5847//5847 -f 5862//5862 5847//5847 5863//5863 -f 5847//5847 5846//5846 5863//5863 -f 5863//5863 5846//5846 5845//5845 -f 5863//5863 5845//5845 5849//5849 -f 5849//5849 5845//5845 5844//5844 -f 5849//5849 5844//5844 5843//5843 -f 5864//5864 5865//5865 5866//5866 -f 5866//5866 5865//5865 5867//5867 -f 5866//5866 5867//5867 5868//5868 -f 5868//5868 5867//5867 5869//5869 -f 5868//5868 5869//5869 5870//5870 -f 5871//5871 5872//5872 5873//5873 -f 5873//5873 5872//5872 5874//5874 -f 5873//5873 5874//5874 5875//5875 -f 5875//5875 5874//5874 5876//5876 -f 5875//5875 5876//5876 5864//5864 -f 5864//5864 5876//5876 5877//5877 -f 5864//5864 5877//5877 5865//5865 -f 5878//5878 5879//5879 5880//5880 -f 5880//5880 5879//5879 5881//5881 -f 5880//5880 5881//5881 5882//5882 -f 5882//5882 5881//5881 5883//5883 -f 5882//5882 5883//5883 5871//5871 -f 5871//5871 5883//5883 5884//5884 -f 5871//5871 5884//5884 5872//5872 -f 5869//5869 5885//5885 5870//5870 -f 5870//5870 5885//5885 5886//5886 -f 5870//5870 5886//5886 5887//5887 -f 5887//5887 5886//5886 5888//5888 -f 5887//5887 5888//5888 5889//5889 -f 5889//5889 5888//5888 5890//5890 -f 5889//5889 5890//5890 5878//5878 -f 5878//5878 5890//5890 5891//5891 -f 5878//5878 5891//5891 5879//5879 -f 5024//5024 5727//5727 5868//5868 -f 5868//5868 5727//5727 5726//5726 -f 5868//5868 5726//5726 5866//5866 -f 5866//5866 5726//5726 5725//5725 -f 5866//5866 5725//5725 5864//5864 -f 5864//5864 5725//5725 5724//5724 -f 5864//5864 5724//5724 5875//5875 -f 5875//5875 5724//5724 5723//5723 -f 5875//5875 5723//5723 5873//5873 -f 5873//5873 5723//5723 5722//5722 -f 5873//5873 5722//5722 5871//5871 -f 5871//5871 5722//5722 5721//5721 -f 5871//5871 5721//5721 5882//5882 -f 5882//5882 5721//5721 5720//5720 -f 5882//5882 5720//5720 5880//5880 -f 5880//5880 5720//5720 5719//5719 -f 5880//5880 5719//5719 5878//5878 -f 5878//5878 5719//5719 5718//5718 -f 5878//5878 5718//5718 5889//5889 -f 5889//5889 5718//5718 5716//5716 -f 5889//5889 5716//5716 5887//5887 -f 5887//5887 5716//5716 5717//5717 -f 5887//5887 5717//5717 5870//5870 -f 5870//5870 5717//5717 5024//5024 -f 5870//5870 5024//5024 5868//5868 -f 5143//5143 5147//5147 5892//5892 -f 5892//5892 5147//5147 5146//5146 -f 5892//5892 5146//5146 5145//5145 -f 5397//5397 5715//5715 5893//5893 -f 5893//5893 5715//5715 5714//5714 -f 5893//5893 5714//5714 4704//4704 -f 5397//5397 5893//5893 5395//5395 -f 5395//5395 5893//5893 5894//5894 -f 5395//5395 5894//5894 5556//5556 -f 5145//5145 5555//5555 5892//5892 -f 5892//5892 5555//5555 5554//5554 -f 5892//5892 5554//5554 5894//5894 -f 5894//5894 5554//5554 5553//5553 -f 5894//5894 5553//5553 5556//5556 -f 4681//4681 5136//5136 5895//5895 -f 5895//5895 5136//5136 4995//4995 -f 5895//5895 4995//4995 5896//5896 -f 5896//5896 4995//4995 4994//4994 -f 4994//4994 5138//5138 5896//5896 -f 5896//5896 5138//5138 5140//5140 -f 5896//5896 5140//5140 5892//5892 -f 5892//5892 5140//5140 5390//5390 -f 5892//5892 5390//5390 5143//5143 -f 5897//5897 5896//5896 5898//5898 -f 5898//5898 5896//5896 5892//5892 -f 5898//5898 5892//5892 5899//5899 -f 5899//5899 5892//5892 5894//5894 -f 5899//5899 5894//5894 5900//5900 -f 5900//5900 5894//5894 5893//5893 -f 5900//5900 5893//5893 5901//5901 -f 5901//5901 5893//5893 4704//4704 -f 5901//5901 4704//4704 5902//5902 -f 4704//4704 4702//4702 5902//5902 -f 5902//5902 4702//4702 4698//4698 -f 5902//5902 4698//4698 5903//5903 -f 5903//5903 4698//4698 4693//4693 -f 5903//5903 4693//4693 5904//5904 -f 5904//5904 4693//4693 4688//4688 -f 5904//5904 4688//4688 5905//5905 -f 5905//5905 4688//4688 4690//4690 -f 5905//5905 4690//4690 5906//5906 -f 5906//5906 4690//4690 4686//4686 -f 5906//5906 4686//4686 5907//5907 -f 5907//5907 4686//4686 4682//4682 -f 5907//5907 4682//4682 5908//5908 -f 5908//5908 4682//4682 4681//4681 -f 5908//5908 4681//4681 5897//5897 -f 5897//5897 4681//4681 5895//5895 -f 5897//5897 5895//5895 5896//5896 -f 5907//5907 5908//5908 5909//5909 -f 5909//5909 5908//5908 5897//5897 -f 5909//5909 5897//5897 5898//5898 -f 5904//5904 5905//5905 5909//5909 -f 5909//5909 5905//5905 5906//5906 -f 5909//5909 5906//5906 5907//5907 -f 5901//5901 5902//5902 5909//5909 -f 5909//5909 5902//5902 5903//5903 -f 5909//5909 5903//5903 5904//5904 -f 5898//5898 5899//5899 5909//5909 -f 5909//5909 5899//5899 5900//5900 -f 5909//5909 5900//5900 5901//5901 -f 5849//5849 5881//5881 5863//5863 -f 5863//5863 5881//5881 5879//5879 -f 5863//5863 5879//5879 5862//5862 -f 5862//5862 5879//5879 5891//5891 -f 5862//5862 5891//5891 5861//5861 -f 5861//5861 5891//5891 5890//5890 -f 5861//5861 5890//5890 5860//5860 -f 5860//5860 5890//5890 5888//5888 -f 5860//5860 5888//5888 5859//5859 -f 5859//5859 5888//5888 5886//5886 -f 5859//5859 5886//5886 5858//5858 -f 5858//5858 5886//5886 5885//5885 -f 5858//5858 5885//5885 5857//5857 -f 5857//5857 5885//5885 5869//5869 -f 5857//5857 5869//5869 5856//5856 -f 5856//5856 5869//5869 5867//5867 -f 5856//5856 5867//5867 5855//5855 -f 5855//5855 5867//5867 5865//5865 -f 5855//5855 5865//5865 5854//5854 -f 5854//5854 5865//5865 5877//5877 -f 5854//5854 5877//5877 5853//5853 -f 5853//5853 5877//5877 5876//5876 -f 5853//5853 5876//5876 5852//5852 -f 5852//5852 5876//5876 5874//5874 -f 5852//5852 5874//5874 5851//5851 -f 5851//5851 5874//5874 5872//5872 -f 5851//5851 5872//5872 5850//5850 -f 5850//5850 5872//5872 5884//5884 -f 5850//5850 5884//5884 5848//5848 -f 5848//5848 5884//5884 5883//5883 -f 5848//5848 5883//5883 5849//5849 -f 5849//5849 5883//5883 5881//5881 -f 5728//5728 5910//5910 5729//5729 -f 5729//5729 5910//5910 5911//5911 -f 5729//5729 5911//5911 5835//5835 -f 5835//5835 5911//5911 5840//5840 -f 5840//5840 5911//5911 5912//5912 -f 5840//5840 5912//5912 5758//5758 -f 5758//5758 5912//5912 4144//4144 -f 4144//4144 5912//5912 5913//5913 -f 4144//4144 5913//5913 4139//4139 -f 4139//4139 5913//5913 4140//4140 -f 4140//4140 5913//5913 5914//5914 -f 4140//4140 5914//5914 5757//5757 -f 5757//5757 5914//5914 5756//5756 -f 5756//5756 5914//5914 5915//5915 -f 5756//5756 5915//5915 5752//5752 -f 5752//5752 5915//5915 4150//4150 -f 4150//4150 5915//5915 5916//5916 -f 4150//4150 5916//5916 4145//4145 -f 4145//4145 5916//5916 4146//4146 -f 4146//4146 5916//5916 5917//5917 -f 4146//4146 5917//5917 5743//5743 -f 5743//5743 5917//5917 5744//5744 -f 5744//5744 5917//5917 5918//5918 -f 5744//5744 5918//5918 5748//5748 -f 5748//5748 5918//5918 4156//4156 -f 4156//4156 5918//5918 5919//5919 -f 4156//4156 5919//5919 4151//4151 -f 4151//4151 5919//5919 4152//4152 -f 4152//4152 5919//5919 5920//5920 -f 4152//4152 5920//5920 5821//5821 -f 5821//5821 5920//5920 5822//5822 -f 5822//5822 5920//5920 5921//5921 -f 5822//5822 5921//5921 5746//5746 -f 5746//5746 5921//5921 5733//5733 -f 5733//5733 5921//5921 5910//5910 -f 5733//5733 5910//5910 5728//5728 -f 5915//5915 5914//5914 5916//5916 -f 5916//5916 5914//5914 5913//5913 -f 5921//5921 5920//5920 5910//5910 -f 5910//5910 5920//5920 5919//5919 -f 5918//5918 5917//5917 5919//5919 -f 5919//5919 5917//5917 5916//5916 -f 5919//5919 5916//5916 5910//5910 -f 5910//5910 5916//5916 5913//5913 -f 5910//5910 5913//5913 5911//5911 -f 5911//5911 5913//5913 5912//5912 -f 5922//5922 5923//5923 5924//5924 -f 5924//5924 5925//5925 5922//5922 -f 5922//5922 5925//5925 5926//5926 -f 5922//5922 5926//5926 5927//5927 -f 5928//5928 5929//5929 5930//5930 -f 5930//5930 5931//5931 5928//5928 -f 5928//5928 5931//5931 5932//5932 -f 5928//5928 5932//5932 5933//5933 -f 5934//5934 5935//5935 5936//5936 -f 5936//5936 5937//5937 5934//5934 -f 5934//5934 5937//5937 5938//5938 -f 5934//5934 5938//5938 5939//5939 -f 5940//5940 5941//5941 5942//5942 -f 5943//5943 5944//5944 5945//5945 -f 5945//5945 5944//5944 5946//5946 -f 5945//5945 5946//5946 5947//5947 -f 5947//5947 5946//5946 5948//5948 -f 5947//5947 5948//5948 5949//5949 -f 5943//5943 5945//5945 5950//5950 -f 5950//5950 5945//5945 5951//5951 -f 5950//5950 5951//5951 5952//5952 -f 5952//5952 5951//5951 5953//5953 -f 5952//5952 5953//5953 5954//5954 -f 5954//5954 5953//5953 5955//5955 -f 5955//5955 5953//5953 5956//5956 -f 5955//5955 5956//5956 5957//5957 -f 5942//5942 5941//5941 5956//5956 -f 5956//5956 5941//5941 5958//5958 -f 5956//5956 5958//5958 5957//5957 -f 5940//5940 5942//5942 5959//5959 -f 5959//5959 5942//5942 5960//5960 -f 5959//5959 5960//5960 5961//5961 -f 5960//5960 5962//5962 5961//5961 -f 5961//5961 5962//5962 5963//5963 -f 5961//5961 5963//5963 5964//5964 -f 5964//5964 5963//5963 5965//5965 -f 5964//5964 5965//5965 5966//5966 -f 5966//5966 5965//5965 5967//5967 -f 5967//5967 5965//5965 5968//5968 -f 5967//5967 5968//5968 5969//5969 -f 5969//5969 5968//5968 5970//5970 -f 5969//5969 5970//5970 5971//5971 -f 5971//5971 5970//5970 5972//5972 -f 5971//5971 5972//5972 5973//5973 -f 5972//5972 5974//5974 5973//5973 -f 5973//5973 5974//5974 5975//5975 -f 5973//5973 5975//5975 5976//5976 -f 5976//5976 5975//5975 5977//5977 -f 5976//5976 5977//5977 5978//5978 -f 5978//5978 5977//5977 5979//5979 -f 5978//5978 5979//5979 5980//5980 -f 5980//5980 5979//5979 5981//5981 -f 5980//5980 5981//5981 5982//5982 -f 5982//5982 5981//5981 5983//5983 -f 5982//5982 5983//5983 5984//5984 -f 5984//5984 5983//5983 5985//5985 -f 5984//5984 5985//5985 5986//5986 -f 5986//5986 5985//5985 5987//5987 -f 5986//5986 5987//5987 5988//5988 -f 5988//5988 5987//5987 5989//5989 -f 5988//5988 5989//5989 5990//5990 -f 5990//5990 5989//5989 5991//5991 -f 5990//5990 5991//5991 5992//5992 -f 5992//5992 5991//5991 5993//5993 -f 5992//5992 5993//5993 5994//5994 -f 5994//5994 5993//5993 5995//5995 -f 5994//5994 5995//5995 5996//5996 -f 5996//5996 5995//5995 5997//5997 -f 5996//5996 5997//5997 5998//5998 -f 5998//5998 5997//5997 5999//5999 -f 5998//5998 5999//5999 6000//6000 -f 6000//6000 5999//5999 6001//6001 -f 6000//6000 6001//6001 6002//6002 -f 6002//6002 6001//6001 6003//6003 -f 6002//6002 6003//6003 6004//6004 -f 6003//6003 6005//6005 6004//6004 -f 6004//6004 6005//6005 6006//6006 -f 6004//6004 6006//6006 6007//6007 -f 6007//6007 6006//6006 6008//6008 -f 6007//6007 6008//6008 6009//6009 -f 6009//6009 6008//6008 6010//6010 -f 6009//6009 6010//6010 6011//6011 -f 6011//6011 6010//6010 6012//6012 -f 6011//6011 6012//6012 6013//6013 -f 6013//6013 6012//6012 6014//6014 -f 6014//6014 6012//6012 6015//6015 -f 6014//6014 6015//6015 6016//6016 -f 6016//6016 6015//6015 6017//6017 -f 6016//6016 6017//6017 6018//6018 -f 6018//6018 6017//6017 6019//6019 -f 6018//6018 6019//6019 6020//6020 -f 6020//6020 6019//6019 6021//6021 -f 6020//6020 6021//6021 6022//6022 -f 6022//6022 6021//6021 6023//6023 -f 6022//6022 6023//6023 6024//6024 -f 6024//6024 6023//6023 6025//6025 -f 6024//6024 6025//6025 6026//6026 -f 6026//6026 6025//6025 6027//6027 -f 6026//6026 6027//6027 6028//6028 -f 6028//6028 6027//6027 6029//6029 -f 6028//6028 6029//6029 6030//6030 -f 6030//6030 6029//6029 6031//6031 -f 6030//6030 6031//6031 6032//6032 -f 6032//6032 6031//6031 6033//6033 -f 6032//6032 6033//6033 6034//6034 -f 6033//6033 6035//6035 6034//6034 -f 6034//6034 6035//6035 6036//6036 -f 6034//6034 6036//6036 6037//6037 -f 6037//6037 6036//6036 6038//6038 -f 6037//6037 6038//6038 6039//6039 -f 6039//6039 6038//6038 6040//6040 -f 6039//6039 6040//6040 6041//6041 -f 6041//6041 6040//6040 6042//6042 -f 6041//6041 6042//6042 6043//6043 -f 6043//6043 6042//6042 6044//6044 -f 6044//6044 6042//6042 6045//6045 -f 6044//6044 6045//6045 6046//6046 -f 6046//6046 6045//6045 6047//6047 -f 6046//6046 6047//6047 6048//6048 -f 6048//6048 6047//6047 6049//6049 -f 6048//6048 6049//6049 6050//6050 -f 6050//6050 6049//6049 6051//6051 -f 6050//6050 6051//6051 6052//6052 -f 6052//6052 6051//6051 6053//6053 -f 6052//6052 6053//6053 6054//6054 -f 6054//6054 6053//6053 6055//6055 -f 6054//6054 6055//6055 6056//6056 -f 6056//6056 6055//6055 6057//6057 -f 6056//6056 6057//6057 6058//6058 -f 6058//6058 6057//6057 6059//6059 -f 6058//6058 6059//6059 6060//6060 -f 6060//6060 6059//6059 6061//6061 -f 6060//6060 6061//6061 6062//6062 -f 6062//6062 6061//6061 6063//6063 -f 6062//6062 6063//6063 6064//6064 -f 6063//6063 6065//6065 6064//6064 -f 6064//6064 6065//6065 6066//6066 -f 6064//6064 6066//6066 6067//6067 -f 6067//6067 6066//6066 6068//6068 -f 6067//6067 6068//6068 6069//6069 -f 6069//6069 6068//6068 6070//6070 -f 6069//6069 6070//6070 6071//6071 -f 6071//6071 6070//6070 6072//6072 -f 6073//6073 6074//6074 6075//6075 -f 6075//6075 6074//6074 6076//6076 -f 6075//6075 6076//6076 6077//6077 -f 6077//6077 6076//6076 6078//6078 -f 6077//6077 6078//6078 6079//6079 -f 6079//6079 6078//6078 6080//6080 -f 6079//6079 6080//6080 6081//6081 -f 6081//6081 6080//6080 6082//6082 -f 6081//6081 6082//6082 6083//6083 -f 6083//6083 6082//6082 6084//6084 -f 6083//6083 6084//6084 6085//6085 -f 6085//6085 6084//6084 6086//6086 -f 6085//6085 6086//6086 6087//6087 -f 6087//6087 6086//6086 6088//6088 -f 6087//6087 6088//6088 6072//6072 -f 6072//6072 6088//6088 6089//6089 -f 6072//6072 6089//6089 6071//6071 -f 6090//6090 6091//6091 6092//6092 -f 6090//6090 6092//6092 6093//6093 -f 6093//6093 6092//6092 6094//6094 -f 6093//6093 6094//6094 6095//6095 -f 6095//6095 6094//6094 6096//6096 -f 6095//6095 6096//6096 6097//6097 -f 6097//6097 6096//6096 6098//6098 -f 6097//6097 6098//6098 6099//6099 -f 6099//6099 6098//6098 6100//6100 -f 6099//6099 6100//6100 6101//6101 -f 6101//6101 6100//6100 6102//6102 -f 6101//6101 6102//6102 6103//6103 -f 6103//6103 6102//6102 6104//6104 -f 6103//6103 6104//6104 6105//6105 -f 6105//6105 6104//6104 6106//6106 -f 6105//6105 6106//6106 6107//6107 -f 6107//6107 6106//6106 6108//6108 -f 6107//6107 6108//6108 6109//6109 -f 6109//6109 6108//6108 6110//6110 -f 6109//6109 6110//6110 6111//6111 -f 6111//6111 6110//6110 6112//6112 -f 6111//6111 6112//6112 6113//6113 -f 6113//6113 6112//6112 6114//6114 -f 6113//6113 6114//6114 6115//6115 -f 6115//6115 6114//6114 6116//6116 -f 6115//6115 6116//6116 6117//6117 -f 6117//6117 6116//6116 6118//6118 -f 6117//6117 6118//6118 6119//6119 -f 6119//6119 6118//6118 6120//6120 -f 6119//6119 6120//6120 6073//6073 -f 6073//6073 6120//6120 6121//6121 -f 6073//6073 6121//6121 6074//6074 -f 6091//6091 6090//6090 6122//6122 -f 6122//6122 6090//6090 6123//6123 -f 6122//6122 6123//6123 6124//6124 -f 6124//6124 6123//6123 6125//6125 -f 6124//6124 6125//6125 6126//6126 -f 6126//6126 6125//6125 6127//6127 -f 6126//6126 6127//6127 6128//6128 -f 6128//6128 6127//6127 6129//6129 -f 6128//6128 6129//6129 6130//6130 -f 6130//6130 6129//6129 6131//6131 -f 6130//6130 6131//6131 6132//6132 -f 6132//6132 6131//6131 6133//6133 -f 6132//6132 6133//6133 6134//6134 -f 6134//6134 6133//6133 6135//6135 -f 6134//6134 6135//6135 6136//6136 -f 6136//6136 6135//6135 6137//6137 -f 6136//6136 6137//6137 6138//6138 -f 6138//6138 6137//6137 6139//6139 -f 6138//6138 6139//6139 6140//6140 -f 6140//6140 6139//6139 6141//6141 -f 6140//6140 6141//6141 6142//6142 -f 6141//6141 6143//6143 6142//6142 -f 6142//6142 6143//6143 6144//6144 -f 6142//6142 6144//6144 6145//6145 -f 6145//6145 6144//6144 6146//6146 -f 6145//6145 6146//6146 6147//6147 -f 6147//6147 6146//6146 6148//6148 -f 6147//6147 6148//6148 6149//6149 -f 6149//6149 6148//6148 6150//6150 -f 6149//6149 6150//6150 6151//6151 -f 6151//6151 6150//6150 6152//6152 -f 6152//6152 6150//6150 6153//6153 -f 6152//6152 6153//6153 6154//6154 -f 6154//6154 6153//6153 6155//6155 -f 6154//6154 6155//6155 6156//6156 -f 6156//6156 6155//6155 6157//6157 -f 6156//6156 6157//6157 6158//6158 -f 6158//6158 6157//6157 6159//6159 -f 6158//6158 6159//6159 6160//6160 -f 6160//6160 6159//6159 6161//6161 -f 6160//6160 6161//6161 6162//6162 -f 6162//6162 6161//6161 6163//6163 -f 6162//6162 6163//6163 6164//6164 -f 6164//6164 6163//6163 6165//6165 -f 6164//6164 6165//6165 6166//6166 -f 6166//6166 6165//6165 6167//6167 -f 6166//6166 6167//6167 6168//6168 -f 6168//6168 6167//6167 6169//6169 -f 6168//6168 6169//6169 6170//6170 -f 6170//6170 6169//6169 6171//6171 -f 6170//6170 6171//6171 6172//6172 -f 6171//6171 6173//6173 6172//6172 -f 6172//6172 6173//6173 6174//6174 -f 6172//6172 6174//6174 6175//6175 -f 6175//6175 6174//6174 6176//6176 -f 6175//6175 6176//6176 6177//6177 -f 6177//6177 6176//6176 6178//6178 -f 6177//6177 6178//6178 6179//6179 -f 6179//6179 6178//6178 6180//6180 -f 6179//6179 6180//6180 6181//6181 -f 6181//6181 6180//6180 6182//6182 -f 6181//6181 6182//6182 6183//6183 -f 6183//6183 6182//6182 6184//6184 -f 6183//6183 6184//6184 6185//6185 -f 6185//6185 6184//6184 6186//6186 -f 6185//6185 6186//6186 6187//6187 -f 6187//6187 6186//6186 6188//6188 -f 6187//6187 6188//6188 6189//6189 -f 6189//6189 6188//6188 6190//6190 -f 6189//6189 6190//6190 6191//6191 -f 6191//6191 6190//6190 6192//6192 -f 6191//6191 6192//6192 6193//6193 -f 6193//6193 6192//6192 6194//6194 -f 6193//6193 6194//6194 6195//6195 -f 6195//6195 6194//6194 6196//6196 -f 6195//6195 6196//6196 6197//6197 -f 6197//6197 6196//6196 6198//6198 -f 6197//6197 6198//6198 6199//6199 -f 6199//6199 6198//6198 6200//6200 -f 6200//6200 6198//6198 6201//6201 -f 6200//6200 6201//6201 6202//6202 -f 6201//6201 6203//6203 6202//6202 -f 6202//6202 6203//6203 6204//6204 -f 6202//6202 6204//6204 6205//6205 -f 6205//6205 6204//6204 6206//6206 -f 6205//6205 6206//6206 6207//6207 -f 6207//6207 6206//6206 6208//6208 -f 6207//6207 6208//6208 6209//6209 -f 6209//6209 6208//6208 6210//6210 -f 6209//6209 6210//6210 6211//6211 -f 6211//6211 6210//6210 6212//6212 -f 6211//6211 6212//6212 6213//6213 -f 6213//6213 6212//6212 6214//6214 -f 6213//6213 6214//6214 6215//6215 -f 6215//6215 6214//6214 6216//6216 -f 6215//6215 6216//6216 6217//6217 -f 6217//6217 6216//6216 6218//6218 -f 6217//6217 6218//6218 6219//6219 -f 6219//6219 6218//6218 6220//6220 -f 6219//6219 6220//6220 6221//6221 -f 6221//6221 6220//6220 6222//6222 -f 6221//6221 6222//6222 6223//6223 -f 6223//6223 6222//6222 6224//6224 -f 6223//6223 6224//6224 6225//6225 -f 6225//6225 6224//6224 6226//6226 -f 6225//6225 6226//6226 6227//6227 -f 6227//6227 6226//6226 6228//6228 -f 6227//6227 6228//6228 6229//6229 -f 6229//6229 6228//6228 6230//6230 -f 6230//6230 6228//6228 6231//6231 -f 6230//6230 6231//6231 6232//6232 -f 6231//6231 6233//6233 6232//6232 -f 6232//6232 6233//6233 6234//6234 -f 6232//6232 6234//6234 6235//6235 -f 6235//6235 6234//6234 6236//6236 -f 6235//6235 6236//6236 6237//6237 -f 6237//6237 6236//6236 6238//6238 -f 6237//6237 6238//6238 6239//6239 -f 6239//6239 6238//6238 6240//6240 -f 6239//6239 6240//6240 6241//6241 -f 6241//6241 6240//6240 6242//6242 -f 6241//6241 6242//6242 6243//6243 -f 6243//6243 6242//6242 6244//6244 -f 6243//6243 6244//6244 6245//6245 -f 6245//6245 6244//6244 6246//6246 -f 6245//6245 6246//6246 6247//6247 -f 6247//6247 6246//6246 6248//6248 -f 6247//6247 6248//6248 6249//6249 -f 6249//6249 6248//6248 6250//6250 -f 6249//6249 6250//6250 6251//6251 -f 6251//6251 6250//6250 6252//6252 -f 6251//6251 6252//6252 6253//6253 -f 6253//6253 6252//6252 6254//6254 -f 6253//6253 6254//6254 6255//6255 -f 6255//6255 6254//6254 6256//6256 -f 6256//6256 6254//6254 6257//6257 -f 6256//6256 6257//6257 6258//6258 -f 6258//6258 6257//6257 6259//6259 -f 6258//6258 6259//6259 6260//6260 -f 6260//6260 6259//6259 6261//6261 -f 6260//6260 6261//6261 6262//6262 -f 6261//6261 6263//6263 6262//6262 -f 6262//6262 6263//6263 6264//6264 -f 6262//6262 6264//6264 6265//6265 -f 6265//6265 6264//6264 6266//6266 -f 6265//6265 6266//6266 6267//6267 -f 6267//6267 6266//6266 6268//6268 -f 6267//6267 6268//6268 6269//6269 -f 6269//6269 6268//6268 6270//6270 -f 6271//6271 6272//6272 6273//6273 -f 6273//6273 6272//6272 6274//6274 -f 6273//6273 6274//6274 6275//6275 -f 6275//6275 6274//6274 6276//6276 -f 6275//6275 6276//6276 6277//6277 -f 6277//6277 6276//6276 6278//6278 -f 6277//6277 6278//6278 6270//6270 -f 6270//6270 6278//6278 6279//6279 -f 6270//6270 6279//6279 6269//6269 -f 6273//6273 6280//6280 6271//6271 -f 6271//6271 6280//6280 6281//6281 -f 6271//6271 6281//6281 6282//6282 -f 6282//6282 6281//6281 6283//6283 -f 6282//6282 6283//6283 6284//6284 -f 6284//6284 6283//6283 6285//6285 -f 6284//6284 6285//6285 6286//6286 -f 6286//6286 6285//6285 6287//6287 -f 6286//6286 6287//6287 6288//6288 -f 6288//6288 6287//6287 6289//6289 -f 6287//6287 6290//6290 6289//6289 -f 6289//6289 6290//6290 6291//6291 -f 6289//6289 6291//6291 6292//6292 -f 6292//6292 6291//6291 6293//6293 -f 6292//6292 6293//6293 6294//6294 -f 6294//6294 6293//6293 6295//6295 -f 6294//6294 6295//6295 6296//6296 -f 6295//6295 6297//6297 6296//6296 -f 6296//6296 6297//6297 6298//6298 -f 6296//6296 6298//6298 6299//6299 -f 6299//6299 6298//6298 6300//6300 -f 6299//6299 6300//6300 6301//6301 -f 6301//6301 6300//6300 6302//6302 -f 6301//6301 6302//6302 6303//6303 -f 6303//6303 6302//6302 6304//6304 -f 6305//6305 6306//6306 6307//6307 -f 6305//6305 6307//6307 6308//6308 -f 6308//6308 6307//6307 6309//6309 -f 6308//6308 6309//6309 6304//6304 -f 6304//6304 6309//6309 6310//6310 -f 6304//6304 6310//6310 6303//6303 -f 6306//6306 6305//6305 6311//6311 -f 6311//6311 6305//6305 6312//6312 -f 6311//6311 6312//6312 6313//6313 -f 6312//6312 6314//6314 6313//6313 -f 6313//6313 6314//6314 6315//6315 -f 6313//6313 6315//6315 6316//6316 -f 6316//6316 6315//6315 6317//6317 -f 6316//6316 6317//6317 6318//6318 -f 6318//6318 6317//6317 6319//6319 -f 6318//6318 6319//6319 6320//6320 -f 6320//6320 6319//6319 6321//6321 -f 6320//6320 6321//6321 6322//6322 -f 6321//6321 6323//6323 6322//6322 -f 6322//6322 6323//6323 6324//6324 -f 6322//6322 6324//6324 6325//6325 -f 6325//6325 6324//6324 6326//6326 -f 6325//6325 6326//6326 6327//6327 -f 6327//6327 6326//6326 6328//6328 -f 6327//6327 6328//6328 6329//6329 -f 6329//6329 6328//6328 6330//6330 -f 6331//6331 6332//6332 6333//6333 -f 6333//6333 6332//6332 6334//6334 -f 6333//6333 6334//6334 6335//6335 -f 6335//6335 6334//6334 6336//6336 -f 6335//6335 6336//6336 6337//6337 -f 6337//6337 6336//6336 6338//6338 -f 6337//6337 6338//6338 6330//6330 -f 6330//6330 6338//6338 6339//6339 -f 6330//6330 6339//6339 6329//6329 -f 6333//6333 6340//6340 6331//6331 -f 6331//6331 6340//6340 6341//6341 -f 6331//6331 6341//6341 6342//6342 -f 6342//6342 6341//6341 6343//6343 -f 6342//6342 6343//6343 6344//6344 -f 6344//6344 6343//6343 6345//6345 -f 6344//6344 6345//6345 6346//6346 -f 6346//6346 6345//6345 6347//6347 -f 6346//6346 6347//6347 6348//6348 -f 6348//6348 6347//6347 6349//6349 -f 6347//6347 6350//6350 6349//6349 -f 6349//6349 6350//6350 6351//6351 -f 6349//6349 6351//6351 6352//6352 -f 6352//6352 6351//6351 6353//6353 -f 6352//6352 6353//6353 6354//6354 -f 6354//6354 6353//6353 6355//6355 -f 6354//6354 6355//6355 6356//6356 -f 6356//6356 6355//6355 6357//6357 -f 6355//6355 6358//6358 6357//6357 -f 6357//6357 6358//6358 6359//6359 -f 6357//6357 6359//6359 6360//6360 -f 6360//6360 6359//6359 6361//6361 -f 6360//6360 6361//6361 6362//6362 -f 6362//6362 6361//6361 6363//6363 -f 6362//6362 6363//6363 6364//6364 -f 6364//6364 6363//6363 6365//6365 -f 6364//6364 6365//6365 6366//6366 -f 6366//6366 6365//6365 6367//6367 -f 6365//6365 6368//6368 6367//6367 -f 6367//6367 6368//6368 6369//6369 -f 6367//6367 6369//6369 6370//6370 -f 6370//6370 6369//6369 6371//6371 -f 6370//6370 6371//6371 6372//6372 -f 6372//6372 6371//6371 6373//6373 -f 6372//6372 6373//6373 6374//6374 -f 6373//6373 6375//6375 6374//6374 -f 6374//6374 6375//6375 6376//6376 -f 6374//6374 6376//6376 6377//6377 -f 6377//6377 6376//6376 6378//6378 -f 6377//6377 6378//6378 6379//6379 -f 6379//6379 6378//6378 6380//6380 -f 6379//6379 6380//6380 6381//6381 -f 6381//6381 6380//6380 6382//6382 -f 6383//6383 6384//6384 6385//6385 -f 6383//6383 6385//6385 6386//6386 -f 6386//6386 6385//6385 6387//6387 -f 6386//6386 6387//6387 6382//6382 -f 6382//6382 6387//6387 6388//6388 -f 6382//6382 6388//6388 6381//6381 -f 6384//6384 6383//6383 6389//6389 -f 6389//6389 6383//6383 6390//6390 -f 6389//6389 6390//6390 6391//6391 -f 6391//6391 6390//6390 6392//6392 -f 6391//6391 6392//6392 6393//6393 -f 6393//6393 6392//6392 6394//6394 -f 6393//6393 6394//6394 6395//6395 -f 6394//6394 6396//6396 6395//6395 -f 6395//6395 6396//6396 6397//6397 -f 6395//6395 6397//6397 6398//6398 -f 6398//6398 6397//6397 6399//6399 -f 6398//6398 6399//6399 6400//6400 -f 6399//6399 6401//6401 6400//6400 -f 6400//6400 6401//6401 6402//6402 -f 6400//6400 6402//6402 6403//6403 -f 6403//6403 6402//6402 6404//6404 -f 6403//6403 6404//6404 6405//6405 -f 6405//6405 6404//6404 6406//6406 -f 6405//6405 6406//6406 6407//6407 -f 6407//6407 6406//6406 6408//6408 -f 6409//6409 6410//6410 6411//6411 -f 6411//6411 6410//6410 6412//6412 -f 6411//6411 6412//6412 6413//6413 -f 6413//6413 6412//6412 6414//6414 -f 6413//6413 6414//6414 6415//6415 -f 6415//6415 6414//6414 6416//6416 -f 6415//6415 6416//6416 6408//6408 -f 6408//6408 6416//6416 6417//6417 -f 6408//6408 6417//6417 6407//6407 -f 6411//6411 6418//6418 6409//6409 -f 6409//6409 6418//6418 6419//6419 -f 6409//6409 6419//6419 6420//6420 -f 6420//6420 6419//6419 6421//6421 -f 6420//6420 6421//6421 6422//6422 -f 6422//6422 6421//6421 6423//6423 -f 6422//6422 6423//6423 6424//6424 -f 6424//6424 6423//6423 6425//6425 -f 6424//6424 6425//6425 6426//6426 -f 6426//6426 6425//6425 6427//6427 -f 6425//6425 6428//6428 6427//6427 -f 6427//6427 6428//6428 6429//6429 -f 6427//6427 6429//6429 6430//6430 -f 6430//6430 6429//6429 6431//6431 -f 6430//6430 6431//6431 6432//6432 -f 6432//6432 6431//6431 6433//6433 -f 6432//6432 6433//6433 6434//6434 -f 6433//6433 6435//6435 6434//6434 -f 6434//6434 6435//6435 6436//6436 -f 6434//6434 6436//6436 6437//6437 -f 6437//6437 6436//6436 6438//6438 -f 6437//6437 6438//6438 6439//6439 -f 6439//6439 6438//6438 6440//6440 -f 6439//6439 6440//6440 6441//6441 -f 6441//6441 6440//6440 6442//6442 -f 6443//6443 6444//6444 6445//6445 -f 6443//6443 6445//6445 6446//6446 -f 6446//6446 6445//6445 6447//6447 -f 6446//6446 6447//6447 6442//6442 -f 6442//6442 6447//6447 6448//6448 -f 6442//6442 6448//6448 6441//6441 -f 6444//6444 6443//6443 6449//6449 -f 6449//6449 6443//6443 6450//6450 -f 6449//6449 6450//6450 6451//6451 -f 6451//6451 6450//6450 6452//6452 -f 6451//6451 6452//6452 6453//6453 -f 6453//6453 6452//6452 6454//6454 -f 6453//6453 6454//6454 6455//6455 -f 6456//6456 6457//6457 6458//6458 -f 6458//6458 6457//6457 6459//6459 -f 6458//6458 6459//6459 6460//6460 -f 6460//6460 6459//6459 6461//6461 -f 6460//6460 6461//6461 6462//6462 -f 6462//6462 6461//6461 6455//6455 -f 6462//6462 6455//6455 6463//6463 -f 6463//6463 6455//6455 6454//6454 -f 6464//6464 6465//6465 6466//6466 -f 6466//6466 6465//6465 6467//6467 -f 6467//6467 6465//6465 6468//6468 -f 6468//6468 6465//6465 6469//6469 -f 6468//6468 6469//6469 6470//6470 -f 6471//6471 6472//6472 6473//6473 -f 6473//6473 6472//6472 6474//6474 -f 6473//6473 6474//6474 6469//6469 -f 6469//6469 6474//6474 6475//6475 -f 6469//6469 6475//6475 6470//6470 -f 6476//6476 6477//6477 6471//6471 -f 6471//6471 6477//6477 6478//6478 -f 6471//6471 6478//6478 6472//6472 -f 6479//6479 6480//6480 6481//6481 -f 6481//6481 6480//6480 6482//6482 -f 6481//6481 6482//6482 6476//6476 -f 6476//6476 6482//6482 6483//6483 -f 6476//6476 6483//6483 6477//6477 -f 6479//6479 6481//6481 6484//6484 -f 6484//6484 6481//6481 6485//6485 -f 6484//6484 6485//6485 6486//6486 -f 6486//6486 6485//6485 6487//6487 -f 6486//6486 6487//6487 6488//6488 -f 6488//6488 6487//6487 6489//6489 -f 6488//6488 6489//6489 6490//6490 -f 6490//6490 6489//6489 6491//6491 -f 6490//6490 6491//6491 6492//6492 -f 6492//6492 6491//6491 6493//6493 -f 6492//6492 6493//6493 6456//6456 -f 6456//6456 6493//6493 6494//6494 -f 6456//6456 6494//6494 6457//6457 -f 6495//6495 6496//6496 6497//6497 -f 6498//6498 6499//6499 6500//6500 -f 6501//6501 6502//6502 6503//6503 -f 6504//6504 6505//6505 6506//6506 -f 6507//6507 6508//6508 6509//6509 -f 6510//6510 6511//6511 6512//6512 -f 6513//6513 6514//6514 6515//6515 -f 6516//6516 6517//6517 6518//6518 -f 6519//6519 6520//6520 6521//6521 -f 6522//6522 6523//6523 6524//6524 -f 6525//6525 6526//6526 6527//6527 -f 6528//6528 6529//6529 6530//6530 -f 6531//6531 6532//6532 6533//6533 -f 6534//6534 6535//6535 6536//6536 -f 6537//6537 6538//6538 6539//6539 -f 6540//6540 6541//6541 6542//6542 -f 6543//6543 6544//6544 6545//6545 -f 6546//6546 6547//6547 6548//6548 -f 6549//6549 6550//6550 6551//6551 -f 6552//6552 6553//6553 6554//6554 -f 6555//6555 6556//6556 6557//6557 -f 6558//6558 6559//6559 6560//6560 -f 6561//6561 6562//6562 6563//6563 -f 6564//6564 6565//6565 6566//6566 -f 6567//6567 6568//6568 6569//6569 -f 6570//6570 6571//6571 6572//6572 -f 6573//6573 6574//6574 6575//6575 -f 6576//6576 6577//6577 6578//6578 -f 6579//6579 6580//6580 6581//6581 -f 6582//6582 6583//6583 6584//6584 -f 6585//6585 6586//6586 6587//6587 -f 6588//6588 6589//6589 6590//6590 -f 6591//6591 6592//6592 6593//6593 -f 6594//6594 6595//6595 6596//6596 -f 6597//6597 6598//6598 6599//6599 -f 6600//6600 6601//6601 6602//6602 -f 6603//6603 6604//6604 6605//6605 -f 6606//6606 6607//6607 6608//6608 -f 6609//6609 6610//6610 6611//6611 -f 6612//6612 6613//6613 6614//6614 -f 6615//6615 6616//6616 6617//6617 -f 6618//6618 6619//6619 6620//6620 -f 6621//6621 6622//6622 6623//6623 -f 6624//6624 6625//6625 6626//6626 -f 6627//6627 6628//6628 6629//6629 -f 6630//6630 6631//6631 6632//6632 -f 6633//6633 6634//6634 6635//6635 -f 6636//6636 6637//6637 6638//6638 -f 6639//6639 6640//6640 6641//6641 -f 6642//6642 6643//6643 6644//6644 -f 6645//6645 6646//6646 6647//6647 -f 6648//6648 6649//6649 6650//6650 -f 6651//6651 6652//6652 6653//6653 -f 6654//6654 6655//6655 6656//6656 -f 6657//6657 6658//6658 6659//6659 -f 6660//6660 6661//6661 6662//6662 -f 6663//6663 6664//6664 6665//6665 -f 6666//6666 6667//6667 6668//6668 -f 6669//6669 6670//6670 6671//6671 -f 6672//6672 6673//6673 6674//6674 -f 6675//6675 6676//6676 6677//6677 -f 6678//6678 6679//6679 6680//6680 -f 6681//6681 6682//6682 6683//6683 -f 6684//6684 6685//6685 6686//6686 -f 6687//6687 6688//6688 6689//6689 -f 6690//6690 6691//6691 6692//6692 -f 6693//6693 6694//6694 6695//6695 -f 6696//6696 6697//6697 6698//6698 -f 6699//6699 6700//6700 6701//6701 -f 6702//6702 6703//6703 6704//6704 -f 6705//6705 6706//6706 6707//6707 -f 6708//6708 6709//6709 6710//6710 -f 6711//6711 6712//6712 6713//6713 -f 6714//6714 6715//6715 6716//6716 -f 6717//6717 6718//6718 6719//6719 -f 6720//6720 6721//6721 6722//6722 -f 6723//6723 6724//6724 6725//6725 -f 6726//6726 6727//6727 6728//6728 -f 6729//6729 6730//6730 6731//6731 -f 6732//6732 6733//6733 6734//6734 -f 6735//6735 6736//6736 6737//6737 -f 6738//6738 6739//6739 6740//6740 -f 6741//6741 6742//6742 6743//6743 -f 6744//6744 6745//6745 6746//6746 -f 6747//6747 6748//6748 6749//6749 -f 6750//6750 6751//6751 6752//6752 -f 6753//6753 6754//6754 6755//6755 -f 6756//6756 6757//6757 6758//6758 -f 6759//6759 6760//6760 6761//6761 -f 6762//6762 6763//6763 6764//6764 -f 6765//6765 6766//6766 6767//6767 -f 6768//6768 6769//6769 6770//6770 -f 6771//6771 6772//6772 6773//6773 -f 6774//6774 6775//6775 6776//6776 -f 6210//6210 6208//6208 6518//6518 -f 6194//6194 6192//6192 6533//6533 -f 6180//6180 6178//6178 6545//6545 -f 6163//6163 6161//6161 6560//6560 -f 6133//6133 6131//6131 6587//6587 -f 6095//6095 6097//6097 6602//6602 -f 6109//6109 6111//6111 6614//6614 -f 6077//6077 6079//6079 6629//6629 -f 6055//6055 6053//6053 6656//6656 -f 6025//6025 6023//6023 6683//6683 -f 6008//6008 6006//6006 6698//6698 -f 5995//5995 5993//5993 6710//6710 -f 5977//5977 5975//5975 6725//6725 -f 6777//6777 6778//6778 6779//6779 -f 6780//6780 6781//6781 6770//6770 -f 6782//6782 6783//6783 6784//6784 -f 6785//6785 6786//6786 6787//6787 -f 6788//6788 6789//6789 6790//6790 -f 6791//6791 6792//6792 6793//6793 -f 6794//6794 6795//6795 6796//6796 -f 6796//6796 6795//6795 6797//6797 -f 6796//6796 6797//6797 6798//6798 -f 6797//6797 6799//6799 6798//6798 -f 6798//6798 6799//6799 6800//6800 -f 6798//6798 6800//6800 6801//6801 -f 6801//6801 6800//6800 6802//6802 -f 6801//6801 6802//6802 6803//6803 -f 6803//6803 6802//6802 6804//6804 -f 6803//6803 6804//6804 6805//6805 -f 6805//6805 6804//6804 6806//6806 -f 6805//6805 6806//6806 6807//6807 -f 6808//6808 6809//6809 6810//6810 -f 6810//6810 6809//6809 6811//6811 -f 6811//6811 6812//6812 6810//6810 -f 6810//6810 6812//6812 6813//6813 -f 6810//6810 6813//6813 6796//6796 -f 6796//6796 6813//6813 6814//6814 -f 6796//6796 6814//6814 6794//6794 -f 6793//6793 6792//6792 6815//6815 -f 6792//6792 6816//6816 6815//6815 -f 6815//6815 6816//6816 6817//6817 -f 6815//6815 6817//6817 6808//6808 -f 6808//6808 6817//6817 6818//6818 -f 6808//6808 6818//6818 6809//6809 -f 6791//6791 6793//6793 6819//6819 -f 6819//6819 6793//6793 6820//6820 -f 6819//6819 6820//6820 6821//6821 -f 6822//6822 6823//6823 6824//6824 -f 6824//6824 6825//6825 6822//6822 -f 6822//6822 6825//6825 6826//6826 -f 6822//6822 6826//6826 6820//6820 -f 6820//6820 6826//6826 6827//6827 -f 6820//6820 6827//6827 6821//6821 -f 6789//6789 6828//6828 6790//6790 -f 6790//6790 6828//6828 6829//6829 -f 6790//6790 6829//6829 6823//6823 -f 6823//6823 6829//6829 6830//6830 -f 6823//6823 6830//6830 6824//6824 -f 6831//6831 6832//6832 6833//6833 -f 6833//6833 6832//6832 6834//6834 -f 6831//6831 6833//6833 6790//6790 -f 6790//6790 6833//6833 6835//6835 -f 6790//6790 6835//6835 6788//6788 -f 6836//6836 6837//6837 6838//6838 -f 6838//6838 6837//6837 6839//6839 -f 6838//6838 6839//6839 6832//6832 -f 6832//6832 6839//6839 6840//6840 -f 6832//6832 6840//6840 6834//6834 -f 6841//6841 6842//6842 6836//6836 -f 6836//6836 6842//6842 6843//6843 -f 6836//6836 6843//6843 6837//6837 -f 6844//6844 6845//6845 6846//6846 -f 6846//6846 6847//6847 6844//6844 -f 6844//6844 6847//6847 6848//6848 -f 6844//6844 6848//6848 6849//6849 -f 6849//6849 6848//6848 6850//6850 -f 6849//6849 6850//6850 6841//6841 -f 6841//6841 6850//6850 6851//6851 -f 6841//6841 6851//6851 6842//6842 -f 6852//6852 6853//6853 6845//6845 -f 6845//6845 6853//6853 6854//6854 -f 6845//6845 6854//6854 6846//6846 -f 6855//6855 6856//6856 6786//6786 -f 6786//6786 6856//6856 6857//6857 -f 6786//6786 6857//6857 6787//6787 -f 6855//6855 6858//6858 6856//6856 -f 6856//6856 6858//6858 6859//6859 -f 6856//6856 6859//6859 6852//6852 -f 6852//6852 6859//6859 6860//6860 -f 6852//6852 6860//6860 6853//6853 -f 6861//6861 6862//6862 6863//6863 -f 6863//6863 6862//6862 6864//6864 -f 6863//6863 6864//6864 6865//6865 -f 6865//6865 6864//6864 6866//6866 -f 6861//6861 6867//6867 6862//6862 -f 6862//6862 6867//6867 6868//6868 -f 6862//6862 6868//6868 6869//6869 -f 6869//6869 6868//6868 6870//6870 -f 6869//6869 6870//6870 6787//6787 -f 6787//6787 6870//6870 6871//6871 -f 6787//6787 6871//6871 6785//6785 -f 6872//6872 6873//6873 6874//6874 -f 6874//6874 6873//6873 6875//6875 -f 6874//6874 6875//6875 6784//6784 -f 6784//6784 6875//6875 6876//6876 -f 6784//6784 6876//6876 6782//6782 -f 6877//6877 6878//6878 6776//6776 -f 6879//6879 6880//6880 6776//6776 -f 6776//6776 6880//6880 6881//6881 -f 6776//6776 6881//6881 6877//6877 -f 6882//6882 6773//6773 6883//6883 -f 6883//6883 6773//6773 6884//6884 -f 6885//6885 6886//6886 6767//6767 -f 6767//6767 6886//6886 6887//6887 -f 6780//6780 6770//6770 6888//6888 -f 6889//6889 6890//6890 6764//6764 -f 6764//6764 6890//6890 6891//6891 -f 6892//6892 6893//6893 6761//6761 -f 6761//6761 6893//6893 6894//6894 -f 6761//6761 6894//6894 6895//6895 -f 6896//6896 6897//6897 6758//6758 -f 6758//6758 6897//6897 6898//6898 -f 6758//6758 6898//6898 6899//6899 -f 6900//6900 6901//6901 6752//6752 -f 6752//6752 6901//6901 6902//6902 -f 6903//6903 6904//6904 6755//6755 -f 6905//6905 6906//6906 6749//6749 -f 6749//6749 6906//6906 6907//6907 -f 6746//6746 6908//6908 6909//6909 -f 6910//6910 6911//6911 6746//6746 -f 6746//6746 6911//6911 6912//6912 -f 6746//6746 6912//6912 6908//6908 -f 6913//6913 6914//6914 6743//6743 -f 6743//6743 6914//6914 6915//6915 -f 6743//6743 6915//6915 6916//6916 -f 5962//5962 6917//6917 6740//6740 -f 6740//6740 6917//6917 6918//6918 -f 6919//6919 6464//6464 6920//6920 -f 6777//6777 6779//6779 6921//6921 -f 6921//6921 6779//6779 6922//6922 -f 6921//6921 6922//6922 6923//6923 -f 6924//6924 6925//6925 6926//6926 -f 6927//6927 6928//6928 6929//6929 -f 6927//6927 6929//6929 6925//6925 -f 6925//6925 6929//6929 6930//6930 -f 6925//6925 6930//6930 6926//6926 -f 5965//5965 5963//5963 6737//6737 -f 5972//5972 5970//5970 6731//6731 -f 5981//5981 5979//5979 6722//6722 -f 5985//5985 5983//5983 6719//6719 -f 5989//5989 5987//5987 6716//6716 -f 5999//5999 5997//5997 6707//6707 -f 6003//6003 6001//6001 6704//6704 -f 6012//6012 6010//6010 6695//6695 -f 6019//6019 6017//6017 6689//6689 -f 6029//6029 6027//6027 6680//6680 -f 6033//6033 6031//6031 6677//6677 -f 6036//6036 6035//6035 6674//6674 -f 6042//6042 6040//6040 6668//6668 -f 6049//6049 6047//6047 6662//6662 -f 6059//6059 6057//6057 6653//6653 -f 6063//6063 6061//6061 6650//6650 -f 6066//6066 6065//6065 6647//6647 -f 6072//6072 6070//6070 6641//6641 -f 6083//6083 6085//6085 6635//6635 -f 6073//6073 6075//6075 6626//6626 -f 6115//6115 6117//6117 6620//6620 -f 6105//6105 6107//6107 6611//6611 -f 6101//6101 6103//6103 6608//6608 -f 6090//6090 6093//6093 6599//6599 -f 6127//6127 6125//6125 6593//6593 -f 6137//6137 6135//6135 6584//6584 -f 6141//6141 6139//6139 6581//6581 -f 6144//6144 6143//6143 6578//6578 -f 6150//6150 6148//6148 6572//6572 -f 6157//6157 6155//6155 6566//6566 -f 6167//6167 6165//6165 6557//6557 -f 6171//6171 6169//6169 6554//6554 -f 6174//6174 6173//6173 6551//6551 -f 6184//6184 6182//6182 6542//6542 -f 6188//6188 6186//6186 6539//6539 -f 6198//6198 6196//6196 6530//6530 -f 6204//6204 6203//6203 6524//6524 -f 6214//6214 6212//6212 6515//6515 -f 6218//6218 6216//6216 6512//6512 -f 6222//6222 6220//6220 6509//6509 -f 6228//6228 6226//6226 6503//6503 -f 6234//6234 6233//6233 6497//6497 -f 6931//6931 6932//6932 6236//6236 -f 6933//6933 6240//6240 6932//6932 -f 6932//6932 6240//6240 6238//6238 -f 6932//6932 6238//6238 6236//6236 -f 6934//6934 6935//6935 6248//6248 -f 6248//6248 6246//6246 6934//6934 -f 6934//6934 6246//6246 6244//6244 -f 6934//6934 6244//6244 6933//6933 -f 6933//6933 6244//6244 6242//6242 -f 6933//6933 6242//6242 6240//6240 -f 6936//6936 6254//6254 6937//6937 -f 6937//6937 6254//6254 6252//6252 -f 6937//6937 6252//6252 6935//6935 -f 6935//6935 6252//6252 6250//6250 -f 6935//6935 6250//6250 6248//6248 -f 6264//6264 6263//6263 6938//6938 -f 6938//6938 6263//6263 6261//6261 -f 6938//6938 6261//6261 6939//6939 -f 6939//6939 6261//6261 6259//6259 -f 6939//6939 6259//6259 6936//6936 -f 6936//6936 6259//6259 6257//6257 -f 6936//6936 6257//6257 6254//6254 -f 6270//6270 6268//6268 6940//6940 -f 6940//6940 6268//6268 6266//6266 -f 6940//6940 6266//6266 6941//6941 -f 6277//6277 6942//6942 6275//6275 -f 6275//6275 6942//6942 6943//6943 -f 6275//6275 6943//6943 6273//6273 -f 6280//6280 6944//6944 6281//6281 -f 6281//6281 6944//6944 6945//6945 -f 6281//6281 6945//6945 6283//6283 -f 6285//6285 6946//6946 6287//6287 -f 6287//6287 6946//6946 6947//6947 -f 6287//6287 6947//6947 6290//6290 -f 6290//6290 6947//6947 6291//6291 -f 6293//6293 6948//6948 6295//6295 -f 6295//6295 6948//6948 6949//6949 -f 6295//6295 6949//6949 6297//6297 -f 6298//6298 6950//6950 6300//6300 -f 6300//6300 6950//6950 6951//6951 -f 6300//6300 6951//6951 6302//6302 -f 6302//6302 6951//6951 6304//6304 -f 6312//6312 6305//6305 6952//6952 -f 6952//6952 6305//6305 6308//6308 -f 6952//6952 6308//6308 6953//6953 -f 6317//6317 6315//6315 6954//6954 -f 6954//6954 6315//6315 6314//6314 -f 6954//6954 6314//6314 6955//6955 -f 6319//6319 6956//6956 6321//6321 -f 6321//6321 6956//6956 6957//6957 -f 6321//6321 6957//6957 6323//6323 -f 6323//6323 6957//6957 6324//6324 -f 6326//6326 6958//6958 6328//6328 -f 6328//6328 6958//6958 6959//6959 -f 6328//6328 6959//6959 6330//6330 -f 6337//6337 6960//6960 6335//6335 -f 6335//6335 6960//6960 6961//6961 -f 6335//6335 6961//6961 6333//6333 -f 6340//6340 6962//6962 6341//6341 -f 6341//6341 6962//6962 6963//6963 -f 6341//6341 6963//6963 6343//6343 -f 6345//6345 6964//6964 6347//6347 -f 6347//6347 6964//6964 6965//6965 -f 6347//6347 6965//6965 6350//6350 -f 6350//6350 6965//6965 6351//6351 -f 6353//6353 6966//6966 6355//6355 -f 6355//6355 6966//6966 6967//6967 -f 6355//6355 6967//6967 6358//6358 -f 6358//6358 6967//6967 6359//6359 -f 6365//6365 6363//6363 6968//6968 -f 6968//6968 6363//6363 6361//6361 -f 6968//6968 6361//6361 6969//6969 -f 6368//6368 6970//6970 6369//6369 -f 6369//6369 6970//6970 6971//6971 -f 6369//6369 6971//6971 6371//6371 -f 6371//6371 6971//6971 6373//6373 -f 6378//6378 6376//6376 6972//6972 -f 6972//6972 6376//6376 6375//6375 -f 6972//6972 6375//6375 6973//6973 -f 6974//6974 6386//6386 6975//6975 -f 6975//6975 6386//6386 6382//6382 -f 6975//6975 6382//6382 6976//6976 -f 6976//6976 6382//6382 6380//6380 -f 6396//6396 6394//6394 6977//6977 -f 6977//6977 6394//6394 6392//6392 -f 6977//6977 6392//6392 6978//6978 -f 6978//6978 6392//6392 6390//6390 -f 6978//6978 6390//6390 6974//6974 -f 6974//6974 6390//6390 6383//6383 -f 6974//6974 6383//6383 6386//6386 -f 6397//6397 6979//6979 6399//6399 -f 6399//6399 6979//6979 6980//6980 -f 6399//6399 6980//6980 6401//6401 -f 6401//6401 6980//6980 6402//6402 -f 6404//6404 6981//6981 6406//6406 -f 6406//6406 6981//6981 6982//6982 -f 6406//6406 6982//6982 6408//6408 -f 6415//6415 6983//6983 6413//6413 -f 6413//6413 6983//6983 6984//6984 -f 6413//6413 6984//6984 6411//6411 -f 6418//6418 6985//6985 6419//6419 -f 6419//6419 6985//6985 6986//6986 -f 6419//6419 6986//6986 6421//6421 -f 6423//6423 6987//6987 6425//6425 -f 6425//6425 6987//6987 6988//6988 -f 6425//6425 6988//6988 6428//6428 -f 6428//6428 6988//6988 6429//6429 -f 6431//6431 6989//6989 6433//6433 -f 6433//6433 6989//6989 6990//6990 -f 6433//6433 6990//6990 6435//6435 -f 6435//6435 6990//6990 6436//6436 -f 6442//6442 6440//6440 6991//6991 -f 6991//6991 6440//6440 6438//6438 -f 6991//6991 6438//6438 6992//6992 -f 6450//6450 6443//6443 6993//6993 -f 6993//6993 6443//6443 6446//6446 -f 6993//6993 6446//6446 6994//6994 -f 6463//6463 6454//6454 6995//6995 -f 6995//6995 6454//6454 6452//6452 -f 6995//6995 6452//6452 6996//6996 -f 6462//6462 6997//6997 6460//6460 -f 6460//6460 6997//6997 6998//6998 -f 6460//6460 6998//6998 6458//6458 -f 6456//6456 6999//6999 6492//6492 -f 6492//6492 6999//6999 7000//7000 -f 6492//6492 7000//7000 6490//6490 -f 6488//6488 7001//7001 6486//6486 -f 6486//6486 7001//7001 7002//7002 -f 6486//6486 7002//7002 6484//6484 -f 6484//6484 7002//7002 6479//6479 -f 6480//6480 7003//7003 6482//6482 -f 6482//6482 7003//7003 7004//7004 -f 6482//6482 7004//7004 6483//6483 -f 6477//6477 7005//7005 6478//6478 -f 6478//6478 7005//7005 7006//7006 -f 6478//6478 7006//7006 6472//6472 -f 6472//6472 7006//7006 6474//6474 -f 6468//6468 6470//6470 7007//7007 -f 7007//7007 6470//6470 6475//6475 -f 7007//7007 6475//6475 7008//7008 -f 6464//6464 6466//6466 6920//6920 -f 6920//6920 6466//6466 6467//6467 -f 6920//6920 6467//6467 7009//7009 -f 6782//6782 6865//6865 6783//6783 -f 6783//6783 6865//6865 6866//6866 -f 6783//6783 6866//6866 6784//6784 -f 6784//6784 6866//6866 7010//7010 -f 6784//6784 7010//7010 6874//6874 -f 6874//6874 7010//7010 7011//7011 -f 7011//7011 6774//6774 6874//6874 -f 6874//6874 6774//6774 6776//6776 -f 6874//6874 6776//6776 6872//6872 -f 6872//6872 6776//6776 6878//6878 -f 6775//6775 6771//6771 6776//6776 -f 6776//6776 6771//6771 6773//6773 -f 6776//6776 6773//6773 6879//6879 -f 6879//6879 6773//6773 6882//6882 -f 6772//6772 6768//6768 6773//6773 -f 6773//6773 6768//6768 6770//6770 -f 6773//6773 6770//6770 6884//6884 -f 6884//6884 6770//6770 6781//6781 -f 6769//6769 6765//6765 6770//6770 -f 6770//6770 6765//6765 6767//6767 -f 6770//6770 6767//6767 6888//6888 -f 6888//6888 6767//6767 6887//6887 -f 6766//6766 6762//6762 6767//6767 -f 6767//6767 6762//6762 6764//6764 -f 6767//6767 6764//6764 6885//6885 -f 6885//6885 6764//6764 6891//6891 -f 6763//6763 6759//6759 6764//6764 -f 6764//6764 6759//6759 6761//6761 -f 6764//6764 6761//6761 6889//6889 -f 6889//6889 6761//6761 6895//6895 -f 6760//6760 6756//6756 6761//6761 -f 6761//6761 6756//6756 6758//6758 -f 6761//6761 6758//6758 6892//6892 -f 6892//6892 6758//6758 6899//6899 -f 6757//6757 6753//6753 6758//6758 -f 6758//6758 6753//6753 6755//6755 -f 6758//6758 6755//6755 6896//6896 -f 6896//6896 6755//6755 6904//6904 -f 6754//6754 6750//6750 6755//6755 -f 6755//6755 6750//6750 6752//6752 -f 6755//6755 6752//6752 6903//6903 -f 6903//6903 6752//6752 6902//6902 -f 6751//6751 6747//6747 6752//6752 -f 6752//6752 6747//6747 6749//6749 -f 6752//6752 6749//6749 6900//6900 -f 6900//6900 6749//6749 6907//6907 -f 6748//6748 6744//6744 6749//6749 -f 6749//6749 6744//6744 6746//6746 -f 6749//6749 6746//6746 6905//6905 -f 6905//6905 6746//6746 6909//6909 -f 6745//6745 6741//6741 6746//6746 -f 6746//6746 6741//6741 6743//6743 -f 6746//6746 6743//6743 6910//6910 -f 6910//6910 6743//6743 6916//6916 -f 6742//6742 6738//6738 6743//6743 -f 6743//6743 6738//6738 6740//6740 -f 6743//6743 6740//6740 6913//6913 -f 6913//6913 6740//6740 6918//6918 -f 6739//6739 6735//6735 6740//6740 -f 6740//6740 6735//6735 6737//6737 -f 6740//6740 6737//6737 5962//5962 -f 5962//5962 6737//6737 5963//5963 -f 6736//6736 6732//6732 6737//6737 -f 6737//6737 6732//6732 6734//6734 -f 6737//6737 6734//6734 5965//5965 -f 5965//5965 6734//6734 5968//5968 -f 6733//6733 6729//6729 6734//6734 -f 6734//6734 6729//6729 6731//6731 -f 6734//6734 6731//6731 5968//5968 -f 5968//5968 6731//6731 5970//5970 -f 6730//6730 6726//6726 6731//6731 -f 6731//6731 6726//6726 6728//6728 -f 6731//6731 6728//6728 5972//5972 -f 5972//5972 6728//6728 5974//5974 -f 6727//6727 6723//6723 6728//6728 -f 6728//6728 6723//6723 6725//6725 -f 6728//6728 6725//6725 5974//5974 -f 5974//5974 6725//6725 5975//5975 -f 6724//6724 6720//6720 6725//6725 -f 6725//6725 6720//6720 6722//6722 -f 6725//6725 6722//6722 5977//5977 -f 5977//5977 6722//6722 5979//5979 -f 6721//6721 6717//6717 6722//6722 -f 6722//6722 6717//6717 6719//6719 -f 6722//6722 6719//6719 5981//5981 -f 5981//5981 6719//6719 5983//5983 -f 6718//6718 6714//6714 6719//6719 -f 6719//6719 6714//6714 6716//6716 -f 6719//6719 6716//6716 5985//5985 -f 5985//5985 6716//6716 5987//5987 -f 6715//6715 6711//6711 6716//6716 -f 6716//6716 6711//6711 6713//6713 -f 6716//6716 6713//6713 5989//5989 -f 5989//5989 6713//6713 5991//5991 -f 6712//6712 6708//6708 6713//6713 -f 6713//6713 6708//6708 6710//6710 -f 6713//6713 6710//6710 5991//5991 -f 5991//5991 6710//6710 5993//5993 -f 6709//6709 6705//6705 6710//6710 -f 6710//6710 6705//6705 6707//6707 -f 6710//6710 6707//6707 5995//5995 -f 5995//5995 6707//6707 5997//5997 -f 6706//6706 6702//6702 6707//6707 -f 6707//6707 6702//6702 6704//6704 -f 6707//6707 6704//6704 5999//5999 -f 5999//5999 6704//6704 6001//6001 -f 6703//6703 6699//6699 6704//6704 -f 6704//6704 6699//6699 6701//6701 -f 6704//6704 6701//6701 6003//6003 -f 6003//6003 6701//6701 6005//6005 -f 6700//6700 6696//6696 6701//6701 -f 6701//6701 6696//6696 6698//6698 -f 6701//6701 6698//6698 6005//6005 -f 6005//6005 6698//6698 6006//6006 -f 6697//6697 6693//6693 6698//6698 -f 6698//6698 6693//6693 6695//6695 -f 6698//6698 6695//6695 6008//6008 -f 6008//6008 6695//6695 6010//6010 -f 6694//6694 6690//6690 6695//6695 -f 6695//6695 6690//6690 6692//6692 -f 6695//6695 6692//6692 6012//6012 -f 6012//6012 6692//6692 6015//6015 -f 6691//6691 6687//6687 6692//6692 -f 6692//6692 6687//6687 6689//6689 -f 6692//6692 6689//6689 6015//6015 -f 6015//6015 6689//6689 6017//6017 -f 6688//6688 6684//6684 6689//6689 -f 6689//6689 6684//6684 6686//6686 -f 6689//6689 6686//6686 6019//6019 -f 6019//6019 6686//6686 6021//6021 -f 6685//6685 6681//6681 6686//6686 -f 6686//6686 6681//6681 6683//6683 -f 6686//6686 6683//6683 6021//6021 -f 6021//6021 6683//6683 6023//6023 -f 6682//6682 6678//6678 6683//6683 -f 6683//6683 6678//6678 6680//6680 -f 6683//6683 6680//6680 6025//6025 -f 6025//6025 6680//6680 6027//6027 -f 6679//6679 6675//6675 6680//6680 -f 6680//6680 6675//6675 6677//6677 -f 6680//6680 6677//6677 6029//6029 -f 6029//6029 6677//6677 6031//6031 -f 6676//6676 6672//6672 6677//6677 -f 6677//6677 6672//6672 6674//6674 -f 6677//6677 6674//6674 6033//6033 -f 6033//6033 6674//6674 6035//6035 -f 6673//6673 6669//6669 6674//6674 -f 6674//6674 6669//6669 6671//6671 -f 6674//6674 6671//6671 6036//6036 -f 6036//6036 6671//6671 6038//6038 -f 6670//6670 6666//6666 6671//6671 -f 6671//6671 6666//6666 6668//6668 -f 6671//6671 6668//6668 6038//6038 -f 6038//6038 6668//6668 6040//6040 -f 6667//6667 6663//6663 6668//6668 -f 6668//6668 6663//6663 6665//6665 -f 6668//6668 6665//6665 6042//6042 -f 6042//6042 6665//6665 6045//6045 -f 6664//6664 6660//6660 6665//6665 -f 6665//6665 6660//6660 6662//6662 -f 6665//6665 6662//6662 6045//6045 -f 6045//6045 6662//6662 6047//6047 -f 6661//6661 6657//6657 6662//6662 -f 6662//6662 6657//6657 6659//6659 -f 6662//6662 6659//6659 6049//6049 -f 6049//6049 6659//6659 6051//6051 -f 6658//6658 6654//6654 6659//6659 -f 6659//6659 6654//6654 6656//6656 -f 6659//6659 6656//6656 6051//6051 -f 6051//6051 6656//6656 6053//6053 -f 6655//6655 6651//6651 6656//6656 -f 6656//6656 6651//6651 6653//6653 -f 6656//6656 6653//6653 6055//6055 -f 6055//6055 6653//6653 6057//6057 -f 6652//6652 6648//6648 6653//6653 -f 6653//6653 6648//6648 6650//6650 -f 6653//6653 6650//6650 6059//6059 -f 6059//6059 6650//6650 6061//6061 -f 6649//6649 6645//6645 6650//6650 -f 6650//6650 6645//6645 6647//6647 -f 6650//6650 6647//6647 6063//6063 -f 6063//6063 6647//6647 6065//6065 -f 6646//6646 6642//6642 6647//6647 -f 6647//6647 6642//6642 6644//6644 -f 6647//6647 6644//6644 6066//6066 -f 6066//6066 6644//6644 6068//6068 -f 6643//6643 6639//6639 6644//6644 -f 6644//6644 6639//6639 6641//6641 -f 6644//6644 6641//6641 6068//6068 -f 6068//6068 6641//6641 6070//6070 -f 6640//6640 6636//6636 6641//6641 -f 6641//6641 6636//6636 6638//6638 -f 6641//6641 6638//6638 6072//6072 -f 6072//6072 6638//6638 6087//6087 -f 6637//6637 6633//6633 6638//6638 -f 6638//6638 6633//6633 6635//6635 -f 6638//6638 6635//6635 6087//6087 -f 6087//6087 6635//6635 6085//6085 -f 6634//6634 6630//6630 6635//6635 -f 6635//6635 6630//6630 6632//6632 -f 6635//6635 6632//6632 6083//6083 -f 6083//6083 6632//6632 6081//6081 -f 6631//6631 6627//6627 6632//6632 -f 6632//6632 6627//6627 6629//6629 -f 6632//6632 6629//6629 6081//6081 -f 6081//6081 6629//6629 6079//6079 -f 6628//6628 6624//6624 6629//6629 -f 6629//6629 6624//6624 6626//6626 -f 6629//6629 6626//6626 6077//6077 -f 6077//6077 6626//6626 6075//6075 -f 6625//6625 6621//6621 6626//6626 -f 6626//6626 6621//6621 6623//6623 -f 6626//6626 6623//6623 6073//6073 -f 6073//6073 6623//6623 6119//6119 -f 6622//6622 6618//6618 6623//6623 -f 6623//6623 6618//6618 6620//6620 -f 6623//6623 6620//6620 6119//6119 -f 6119//6119 6620//6620 6117//6117 -f 6619//6619 6615//6615 6620//6620 -f 6620//6620 6615//6615 6617//6617 -f 6620//6620 6617//6617 6115//6115 -f 6115//6115 6617//6617 6113//6113 -f 6616//6616 6612//6612 6617//6617 -f 6617//6617 6612//6612 6614//6614 -f 6617//6617 6614//6614 6113//6113 -f 6113//6113 6614//6614 6111//6111 -f 6613//6613 6609//6609 6614//6614 -f 6614//6614 6609//6609 6611//6611 -f 6614//6614 6611//6611 6109//6109 -f 6109//6109 6611//6611 6107//6107 -f 6610//6610 6606//6606 6611//6611 -f 6611//6611 6606//6606 6608//6608 -f 6611//6611 6608//6608 6105//6105 -f 6105//6105 6608//6608 6103//6103 -f 6607//6607 6603//6603 6608//6608 -f 6608//6608 6603//6603 6605//6605 -f 6608//6608 6605//6605 6101//6101 -f 6101//6101 6605//6605 6099//6099 -f 6604//6604 6600//6600 6605//6605 -f 6605//6605 6600//6600 6602//6602 -f 6605//6605 6602//6602 6099//6099 -f 6099//6099 6602//6602 6097//6097 -f 6601//6601 6597//6597 6602//6602 -f 6602//6602 6597//6597 6599//6599 -f 6602//6602 6599//6599 6095//6095 -f 6095//6095 6599//6599 6093//6093 -f 6598//6598 6594//6594 6599//6599 -f 6599//6599 6594//6594 6596//6596 -f 6599//6599 6596//6596 6090//6090 -f 6090//6090 6596//6596 6123//6123 -f 6595//6595 6591//6591 6596//6596 -f 6596//6596 6591//6591 6593//6593 -f 6596//6596 6593//6593 6123//6123 -f 6123//6123 6593//6593 6125//6125 -f 6592//6592 6588//6588 6593//6593 -f 6593//6593 6588//6588 6590//6590 -f 6593//6593 6590//6590 6127//6127 -f 6127//6127 6590//6590 6129//6129 -f 6589//6589 6585//6585 6590//6590 -f 6590//6590 6585//6585 6587//6587 -f 6590//6590 6587//6587 6129//6129 -f 6129//6129 6587//6587 6131//6131 -f 6586//6586 6582//6582 6587//6587 -f 6587//6587 6582//6582 6584//6584 -f 6587//6587 6584//6584 6133//6133 -f 6133//6133 6584//6584 6135//6135 -f 6583//6583 6579//6579 6584//6584 -f 6584//6584 6579//6579 6581//6581 -f 6584//6584 6581//6581 6137//6137 -f 6137//6137 6581//6581 6139//6139 -f 6580//6580 6576//6576 6581//6581 -f 6581//6581 6576//6576 6578//6578 -f 6581//6581 6578//6578 6141//6141 -f 6141//6141 6578//6578 6143//6143 -f 6577//6577 6573//6573 6578//6578 -f 6578//6578 6573//6573 6575//6575 -f 6578//6578 6575//6575 6144//6144 -f 6144//6144 6575//6575 6146//6146 -f 6574//6574 6570//6570 6575//6575 -f 6575//6575 6570//6570 6572//6572 -f 6575//6575 6572//6572 6146//6146 -f 6146//6146 6572//6572 6148//6148 -f 6571//6571 6567//6567 6572//6572 -f 6572//6572 6567//6567 6569//6569 -f 6572//6572 6569//6569 6150//6150 -f 6150//6150 6569//6569 6153//6153 -f 6568//6568 6564//6564 6569//6569 -f 6569//6569 6564//6564 6566//6566 -f 6569//6569 6566//6566 6153//6153 -f 6153//6153 6566//6566 6155//6155 -f 6565//6565 6561//6561 6566//6566 -f 6566//6566 6561//6561 6563//6563 -f 6566//6566 6563//6563 6157//6157 -f 6157//6157 6563//6563 6159//6159 -f 6562//6562 6558//6558 6563//6563 -f 6563//6563 6558//6558 6560//6560 -f 6563//6563 6560//6560 6159//6159 -f 6159//6159 6560//6560 6161//6161 -f 6559//6559 6555//6555 6560//6560 -f 6560//6560 6555//6555 6557//6557 -f 6560//6560 6557//6557 6163//6163 -f 6163//6163 6557//6557 6165//6165 -f 6556//6556 6552//6552 6557//6557 -f 6557//6557 6552//6552 6554//6554 -f 6557//6557 6554//6554 6167//6167 -f 6167//6167 6554//6554 6169//6169 -f 6553//6553 6549//6549 6554//6554 -f 6554//6554 6549//6549 6551//6551 -f 6554//6554 6551//6551 6171//6171 -f 6171//6171 6551//6551 6173//6173 -f 6550//6550 6546//6546 6551//6551 -f 6551//6551 6546//6546 6548//6548 -f 6551//6551 6548//6548 6174//6174 -f 6174//6174 6548//6548 6176//6176 -f 6547//6547 6543//6543 6548//6548 -f 6548//6548 6543//6543 6545//6545 -f 6548//6548 6545//6545 6176//6176 -f 6176//6176 6545//6545 6178//6178 -f 6544//6544 6540//6540 6545//6545 -f 6545//6545 6540//6540 6542//6542 -f 6545//6545 6542//6542 6180//6180 -f 6180//6180 6542//6542 6182//6182 -f 6541//6541 6537//6537 6542//6542 -f 6542//6542 6537//6537 6539//6539 -f 6542//6542 6539//6539 6184//6184 -f 6184//6184 6539//6539 6186//6186 -f 6538//6538 6534//6534 6539//6539 -f 6539//6539 6534//6534 6536//6536 -f 6539//6539 6536//6536 6188//6188 -f 6188//6188 6536//6536 6190//6190 -f 6535//6535 6531//6531 6536//6536 -f 6536//6536 6531//6531 6533//6533 -f 6536//6536 6533//6533 6190//6190 -f 6190//6190 6533//6533 6192//6192 -f 6532//6532 6528//6528 6533//6533 -f 6533//6533 6528//6528 6530//6530 -f 6533//6533 6530//6530 6194//6194 -f 6194//6194 6530//6530 6196//6196 -f 6529//6529 6525//6525 6530//6530 -f 6530//6530 6525//6525 6527//6527 -f 6530//6530 6527//6527 6198//6198 -f 6198//6198 6527//6527 6201//6201 -f 6526//6526 6522//6522 6527//6527 -f 6527//6527 6522//6522 6524//6524 -f 6527//6527 6524//6524 6201//6201 -f 6201//6201 6524//6524 6203//6203 -f 6523//6523 6519//6519 6524//6524 -f 6524//6524 6519//6519 6521//6521 -f 6524//6524 6521//6521 6204//6204 -f 6204//6204 6521//6521 6206//6206 -f 6520//6520 6516//6516 6521//6521 -f 6521//6521 6516//6516 6518//6518 -f 6521//6521 6518//6518 6206//6206 -f 6206//6206 6518//6518 6208//6208 -f 6517//6517 6513//6513 6518//6518 -f 6518//6518 6513//6513 6515//6515 -f 6518//6518 6515//6515 6210//6210 -f 6210//6210 6515//6515 6212//6212 -f 6514//6514 6510//6510 6515//6515 -f 6515//6515 6510//6510 6512//6512 -f 6515//6515 6512//6512 6214//6214 -f 6214//6214 6512//6512 6216//6216 -f 6511//6511 6507//6507 6512//6512 -f 6512//6512 6507//6507 6509//6509 -f 6512//6512 6509//6509 6218//6218 -f 6218//6218 6509//6509 6220//6220 -f 6508//6508 6504//6504 6509//6509 -f 6509//6509 6504//6504 6506//6506 -f 6509//6509 6506//6506 6222//6222 -f 6222//6222 6506//6506 6224//6224 -f 6505//6505 6501//6501 6506//6506 -f 6506//6506 6501//6501 6503//6503 -f 6506//6506 6503//6503 6224//6224 -f 6224//6224 6503//6503 6226//6226 -f 6502//6502 6498//6498 6503//6503 -f 6503//6503 6498//6498 6500//6500 -f 6503//6503 6500//6500 6228//6228 -f 6228//6228 6500//6500 6231//6231 -f 6499//6499 6495//6495 6500//6500 -f 6500//6500 6495//6495 6497//6497 -f 6500//6500 6497//6497 6231//6231 -f 6231//6231 6497//6497 6233//6233 -f 6496//6496 7012//7012 6497//6497 -f 6497//6497 7012//7012 6931//6931 -f 6497//6497 6931//6931 6234//6234 -f 6234//6234 6931//6931 6236//6236 -f 7012//7012 7013//7013 6931//6931 -f 6931//6931 7013//7013 7014//7014 -f 6931//6931 7014//7014 6932//6932 -f 6932//6932 7014//7014 7015//7015 -f 6932//6932 7015//7015 6933//6933 -f 6933//6933 7015//7015 7016//7016 -f 7016//7016 7017//7017 6933//6933 -f 6933//6933 7017//7017 7018//7018 -f 6933//6933 7018//7018 6934//6934 -f 6934//6934 7018//7018 7019//7019 -f 6934//6934 7019//7019 6935//6935 -f 7019//7019 7020//7020 6935//6935 -f 6935//6935 7020//7020 7021//7021 -f 6935//6935 7021//7021 6937//6937 -f 6937//6937 7021//7021 7022//7022 -f 7022//7022 7023//7023 6937//6937 -f 6937//6937 7023//7023 7024//7024 -f 6937//6937 7024//7024 6936//6936 -f 6936//6936 7024//7024 7025//7025 -f 6936//6936 7025//7025 6939//6939 -f 7025//7025 7026//7026 6939//6939 -f 6939//6939 7026//7026 7027//7027 -f 6939//6939 7027//7027 6938//6938 -f 6938//6938 7027//7027 7028//7028 -f 7028//7028 7029//7029 6938//6938 -f 6938//6938 7029//7029 6941//6941 -f 6938//6938 6941//6941 6264//6264 -f 6264//6264 6941//6941 6266//6266 -f 7029//7029 7030//7030 6941//6941 -f 6941//6941 7030//7030 7031//7031 -f 6941//6941 7031//7031 6940//6940 -f 6940//6940 7031//7031 7032//7032 -f 7032//7032 7033//7033 6940//6940 -f 6940//6940 7033//7033 6942//6942 -f 6940//6940 6942//6942 6270//6270 -f 6270//6270 6942//6942 6277//6277 -f 7033//7033 7034//7034 6942//6942 -f 6942//6942 7034//7034 7035//7035 -f 6942//6942 7035//7035 6943//6943 -f 6943//6943 7035//7035 7036//7036 -f 7036//7036 7037//7037 6943//6943 -f 6943//6943 7037//7037 6944//6944 -f 6943//6943 6944//6944 6273//6273 -f 6273//6273 6944//6944 6280//6280 -f 7037//7037 7038//7038 6944//6944 -f 6944//6944 7038//7038 7039//7039 -f 6944//6944 7039//7039 6945//6945 -f 6945//6945 7039//7039 7040//7040 -f 7040//7040 7041//7041 6945//6945 -f 6945//6945 7041//7041 6946//6946 -f 6945//6945 6946//6946 6283//6283 -f 6283//6283 6946//6946 6285//6285 -f 7041//7041 7042//7042 6946//6946 -f 6946//6946 7042//7042 7043//7043 -f 6946//6946 7043//7043 6947//6947 -f 6947//6947 7043//7043 7044//7044 -f 7044//7044 7045//7045 6947//6947 -f 6947//6947 7045//7045 6948//6948 -f 6947//6947 6948//6948 6291//6291 -f 6291//6291 6948//6948 6293//6293 -f 7045//7045 7046//7046 6948//6948 -f 6948//6948 7046//7046 7047//7047 -f 6948//6948 7047//7047 6949//6949 -f 6949//6949 7047//7047 7048//7048 -f 7048//7048 7049//7049 6949//6949 -f 6949//6949 7049//7049 6950//6950 -f 6949//6949 6950//6950 6297//6297 -f 6297//6297 6950//6950 6298//6298 -f 7049//7049 7050//7050 6950//6950 -f 6950//6950 7050//7050 7051//7051 -f 6950//6950 7051//7051 6951//6951 -f 6951//6951 7051//7051 7052//7052 -f 7052//7052 7053//7053 6951//6951 -f 6951//6951 7053//7053 6953//6953 -f 6951//6951 6953//6953 6304//6304 -f 6304//6304 6953//6953 6308//6308 -f 7053//7053 7054//7054 6953//6953 -f 6953//6953 7054//7054 7055//7055 -f 6953//6953 7055//7055 6952//6952 -f 6952//6952 7055//7055 7056//7056 -f 7056//7056 7057//7057 6952//6952 -f 6952//6952 7057//7057 6955//6955 -f 6952//6952 6955//6955 6312//6312 -f 6312//6312 6955//6955 6314//6314 -f 7057//7057 7058//7058 6955//6955 -f 6955//6955 7058//7058 7059//7059 -f 6955//6955 7059//7059 6954//6954 -f 6954//6954 7059//7059 7060//7060 -f 7060//7060 7061//7061 6954//6954 -f 6954//6954 7061//7061 6956//6956 -f 6954//6954 6956//6956 6317//6317 -f 6317//6317 6956//6956 6319//6319 -f 7061//7061 7062//7062 6956//6956 -f 6956//6956 7062//7062 7063//7063 -f 6956//6956 7063//7063 6957//6957 -f 6957//6957 7063//7063 7064//7064 -f 7064//7064 7065//7065 6957//6957 -f 6957//6957 7065//7065 6958//6958 -f 6957//6957 6958//6958 6324//6324 -f 6324//6324 6958//6958 6326//6326 -f 7065//7065 7066//7066 6958//6958 -f 6958//6958 7066//7066 7067//7067 -f 6958//6958 7067//7067 6959//6959 -f 6959//6959 7067//7067 7068//7068 -f 7068//7068 7069//7069 6959//6959 -f 6959//6959 7069//7069 6960//6960 -f 6959//6959 6960//6960 6330//6330 -f 6330//6330 6960//6960 6337//6337 -f 7069//7069 7070//7070 6960//6960 -f 6960//6960 7070//7070 7071//7071 -f 6960//6960 7071//7071 6961//6961 -f 6961//6961 7071//7071 7072//7072 -f 7072//7072 7073//7073 6961//6961 -f 6961//6961 7073//7073 6962//6962 -f 6961//6961 6962//6962 6333//6333 -f 6333//6333 6962//6962 6340//6340 -f 7073//7073 7074//7074 6962//6962 -f 6962//6962 7074//7074 7075//7075 -f 6962//6962 7075//7075 6963//6963 -f 6963//6963 7075//7075 7076//7076 -f 7076//7076 7077//7077 6963//6963 -f 6963//6963 7077//7077 6964//6964 -f 6963//6963 6964//6964 6343//6343 -f 6343//6343 6964//6964 6345//6345 -f 7077//7077 7078//7078 6964//6964 -f 6964//6964 7078//7078 7079//7079 -f 6964//6964 7079//7079 6965//6965 -f 6965//6965 7079//7079 7080//7080 -f 7080//7080 7081//7081 6965//6965 -f 6965//6965 7081//7081 6966//6966 -f 6965//6965 6966//6966 6351//6351 -f 6351//6351 6966//6966 6353//6353 -f 7081//7081 7082//7082 6966//6966 -f 6966//6966 7082//7082 7083//7083 -f 6966//6966 7083//7083 6967//6967 -f 6967//6967 7083//7083 7084//7084 -f 7084//7084 7085//7085 6967//6967 -f 6967//6967 7085//7085 6969//6969 -f 6967//6967 6969//6969 6359//6359 -f 6359//6359 6969//6969 6361//6361 -f 7085//7085 7086//7086 6969//6969 -f 6969//6969 7086//7086 7087//7087 -f 6969//6969 7087//7087 6968//6968 -f 6968//6968 7087//7087 7088//7088 -f 7088//7088 7089//7089 6968//6968 -f 6968//6968 7089//7089 6970//6970 -f 6968//6968 6970//6970 6365//6365 -f 6365//6365 6970//6970 6368//6368 -f 7089//7089 7090//7090 6970//6970 -f 6970//6970 7090//7090 7091//7091 -f 6970//6970 7091//7091 6971//6971 -f 6971//6971 7091//7091 7092//7092 -f 7092//7092 7093//7093 6971//6971 -f 6971//6971 7093//7093 6973//6973 -f 6971//6971 6973//6973 6373//6373 -f 6373//6373 6973//6973 6375//6375 -f 7093//7093 7094//7094 6973//6973 -f 6973//6973 7094//7094 7095//7095 -f 6973//6973 7095//7095 6972//6972 -f 6972//6972 7095//7095 7096//7096 -f 7096//7096 7097//7097 6972//6972 -f 6972//6972 7097//7097 6976//6976 -f 6972//6972 6976//6976 6378//6378 -f 6378//6378 6976//6976 6380//6380 -f 7097//7097 7098//7098 6976//6976 -f 6976//6976 7098//7098 7099//7099 -f 6976//6976 7099//7099 6975//6975 -f 6975//6975 7099//7099 7100//7100 -f 7100//7100 7101//7101 6975//6975 -f 6975//6975 7101//7101 7102//7102 -f 6975//6975 7102//7102 6974//6974 -f 6974//6974 7102//7102 7103//7103 -f 6974//6974 7103//7103 6978//6978 -f 7103//7103 7104//7104 6978//6978 -f 6978//6978 7104//7104 7105//7105 -f 6978//6978 7105//7105 6977//6977 -f 6977//6977 7105//7105 7106//7106 -f 6977//6977 7106//7106 7107//7107 -f 7107//7107 7108//7108 6977//6977 -f 6977//6977 7108//7108 6979//6979 -f 6977//6977 6979//6979 6396//6396 -f 6396//6396 6979//6979 6397//6397 -f 7109//7109 6980//6980 7110//7110 -f 7110//7110 6980//6980 6979//6979 -f 7110//7110 6979//6979 7111//7111 -f 7111//7111 6979//6979 7108//7108 -f 7109//7109 7112//7112 6980//6980 -f 6980//6980 7112//7112 6981//6981 -f 6980//6980 6981//6981 6402//6402 -f 6402//6402 6981//6981 6404//6404 -f 7113//7113 6982//6982 7114//7114 -f 7114//7114 6982//6982 6981//6981 -f 7114//7114 6981//6981 7115//7115 -f 7115//7115 6981//6981 7112//7112 -f 7113//7113 7116//7116 6982//6982 -f 6982//6982 7116//7116 6983//6983 -f 6982//6982 6983//6983 6408//6408 -f 6408//6408 6983//6983 6415//6415 -f 7117//7117 6984//6984 7118//7118 -f 7118//7118 6984//6984 6983//6983 -f 7118//7118 6983//6983 7119//7119 -f 7119//7119 6983//6983 7116//7116 -f 7117//7117 7120//7120 6984//6984 -f 6984//6984 7120//7120 6985//6985 -f 6984//6984 6985//6985 6411//6411 -f 6411//6411 6985//6985 6418//6418 -f 7121//7121 6986//6986 7122//7122 -f 7122//7122 6986//6986 6985//6985 -f 7122//7122 6985//6985 7123//7123 -f 7123//7123 6985//6985 7120//7120 -f 7121//7121 7124//7124 6986//6986 -f 6986//6986 7124//7124 6987//6987 -f 6986//6986 6987//6987 6421//6421 -f 6421//6421 6987//6987 6423//6423 -f 7125//7125 6988//6988 7126//7126 -f 7126//7126 6988//6988 6987//6987 -f 7126//7126 6987//6987 7127//7127 -f 7127//7127 6987//6987 7124//7124 -f 7125//7125 7128//7128 6988//6988 -f 6988//6988 7128//7128 6989//6989 -f 6988//6988 6989//6989 6429//6429 -f 6429//6429 6989//6989 6431//6431 -f 7129//7129 6990//6990 7130//7130 -f 7130//7130 6990//6990 6989//6989 -f 7130//7130 6989//6989 7131//7131 -f 7131//7131 6989//6989 7128//7128 -f 7129//7129 7132//7132 6990//6990 -f 6990//6990 7132//7132 6992//6992 -f 6990//6990 6992//6992 6436//6436 -f 6436//6436 6992//6992 6438//6438 -f 7133//7133 6991//6991 7134//7134 -f 7134//7134 6991//6991 6992//6992 -f 7134//7134 6992//6992 7135//7135 -f 7135//7135 6992//6992 7132//7132 -f 7133//7133 7136//7136 6991//6991 -f 6991//6991 7136//7136 6994//6994 -f 6991//6991 6994//6994 6442//6442 -f 6442//6442 6994//6994 6446//6446 -f 7137//7137 6993//6993 7138//7138 -f 7138//7138 6993//6993 6994//6994 -f 7138//7138 6994//6994 7139//7139 -f 7139//7139 6994//6994 7136//7136 -f 7137//7137 7140//7140 6993//6993 -f 6993//6993 7140//7140 6996//6996 -f 6993//6993 6996//6996 6450//6450 -f 6450//6450 6996//6996 6452//6452 -f 7141//7141 6995//6995 7142//7142 -f 7142//7142 6995//6995 6996//6996 -f 7142//7142 6996//6996 7143//7143 -f 7143//7143 6996//6996 7140//7140 -f 7141//7141 7144//7144 6995//6995 -f 6995//6995 7144//7144 6997//6997 -f 6995//6995 6997//6997 6463//6463 -f 6463//6463 6997//6997 6462//6462 -f 7145//7145 6998//6998 7146//7146 -f 7146//7146 6998//6998 6997//6997 -f 7146//7146 6997//6997 7147//7147 -f 7147//7147 6997//6997 7144//7144 -f 7145//7145 7148//7148 6998//6998 -f 6998//6998 7148//7148 6999//6999 -f 6998//6998 6999//6999 6458//6458 -f 6458//6458 6999//6999 6456//6456 -f 7149//7149 7000//7000 7150//7150 -f 7150//7150 7000//7000 6999//6999 -f 7150//7150 6999//6999 7151//7151 -f 7151//7151 6999//6999 7148//7148 -f 7149//7149 7152//7152 7000//7000 -f 7000//7000 7152//7152 7001//7001 -f 7000//7000 7001//7001 6490//6490 -f 6490//6490 7001//7001 6488//6488 -f 7153//7153 7002//7002 7154//7154 -f 7154//7154 7002//7002 7001//7001 -f 7154//7154 7001//7001 7155//7155 -f 7155//7155 7001//7001 7152//7152 -f 7153//7153 7156//7156 7002//7002 -f 7002//7002 7156//7156 7003//7003 -f 7002//7002 7003//7003 6479//6479 -f 6479//6479 7003//7003 6480//6480 -f 7157//7157 7004//7004 7158//7158 -f 7158//7158 7004//7004 7003//7003 -f 7158//7158 7003//7003 7159//7159 -f 7159//7159 7003//7003 7156//7156 -f 7157//7157 7160//7160 7004//7004 -f 7004//7004 7160//7160 7005//7005 -f 7004//7004 7005//7005 6483//6483 -f 6483//6483 7005//7005 6477//6477 -f 7161//7161 7006//7006 7162//7162 -f 7162//7162 7006//7006 7005//7005 -f 7162//7162 7005//7005 7163//7163 -f 7163//7163 7005//7005 7160//7160 -f 7161//7161 7164//7164 7006//7006 -f 7006//7006 7164//7164 7008//7008 -f 7006//7006 7008//7008 6474//6474 -f 6474//6474 7008//7008 6475//6475 -f 7165//7165 7007//7007 7166//7166 -f 7166//7166 7007//7007 7008//7008 -f 7166//7166 7008//7008 7167//7167 -f 7167//7167 7008//7008 7164//7164 -f 7165//7165 7168//7168 7007//7007 -f 7007//7007 7168//7168 7009//7009 -f 7007//7007 7009//7009 6468//6468 -f 6468//6468 7009//7009 6467//6467 -f 7169//7169 6920//6920 7170//7170 -f 7170//7170 6920//6920 7009//7009 -f 7170//7170 7009//7009 7171//7171 -f 7171//7171 7009//7009 7168//7168 -f 7169//7169 7172//7172 6920//6920 -f 6920//6920 7172//7172 6779//6779 -f 6920//6920 6779//6779 6919//6919 -f 6919//6919 6779//6779 6778//6778 -f 6926//6926 7173//7173 6924//6924 -f 6924//6924 7173//7173 6923//6923 -f 6924//6924 6923//6923 7174//7174 -f 7174//7174 6923//6923 6922//6922 -f 7174//7174 6922//6922 7175//7175 -f 7175//7175 6922//6922 6779//6779 -f 7175//7175 6779//6779 7176//7176 -f 7176//7176 6779//6779 7172//7172 -f 7023//7023 7022//7022 7177//7177 -f 7178//7178 7179//7179 7180//7180 -f 7181//7181 7182//7182 7183//7183 -f 7184//7184 7185//7185 7186//7186 -f 7187//7187 7188//7188 7189//7189 -f 7190//7190 7191//7191 7192//7192 -f 7192//7192 7191//7191 7193//7193 -f 7192//7192 7193//7193 7194//7194 -f 7194//7194 7193//7193 7195//7195 -f 7194//7194 7195//7195 7196//7196 -f 7197//7197 7198//7198 7199//7199 -f 7199//7199 7198//7198 7200//7200 -f 7199//7199 7200//7200 7190//7190 -f 7201//7201 7202//7202 7189//7189 -f 7189//7189 7202//7202 7203//7203 -f 7189//7189 7203//7203 7187//7187 -f 7185//7185 7204//7204 7201//7201 -f 7201//7201 7204//7204 7205//7205 -f 7201//7201 7205//7205 7202//7202 -f 7206//7206 7207//7207 7208//7208 -f 7208//7208 7207//7207 7209//7209 -f 7184//7184 7186//7186 7210//7210 -f 7206//7206 7208//7208 7211//7211 -f 7211//7211 7208//7208 7212//7212 -f 7211//7211 7212//7212 7213//7213 -f 7214//7214 7215//7215 7212//7212 -f 7212//7212 7215//7215 7216//7216 -f 7212//7212 7216//7216 7213//7213 -f 7217//7217 7218//7218 7219//7219 -f 7218//7218 7220//7220 7219//7219 -f 7219//7219 7220//7220 7221//7221 -f 7219//7219 7221//7221 7214//7214 -f 7222//7222 7223//7223 7224//7224 -f 7224//7224 7223//7223 7225//7225 -f 7224//7224 7225//7225 7226//7226 -f 7226//7226 7225//7225 7227//7227 -f 7226//7226 7227//7227 7228//7228 -f 7229//7229 7222//7222 7230//7230 -f 7231//7231 7232//7232 7230//7230 -f 7230//7230 7232//7232 7233//7233 -f 7230//7230 7233//7233 7229//7229 -f 7234//7234 7235//7235 7236//7236 -f 7236//7236 7235//7235 7237//7237 -f 7234//7234 7236//7236 7238//7238 -f 7238//7238 7236//7236 7239//7239 -f 7238//7238 7239//7239 7240//7240 -f 7241//7241 7242//7242 7243//7243 -f 7243//7243 7244//7244 7239//7239 -f 7239//7239 7244//7244 7245//7245 -f 7239//7239 7245//7245 7240//7240 -f 7246//7246 7247//7247 7241//7241 -f 7241//7241 7247//7247 7248//7248 -f 7241//7241 7248//7248 7242//7242 -f 7181//7181 7183//7183 7249//7249 -f 7249//7249 7183//7183 7250//7250 -f 7249//7249 7250//7250 7251//7251 -f 7252//7252 7253//7253 7254//7254 -f 7254//7254 7253//7253 7255//7255 -f 7254//7254 7256//7256 7252//7252 -f 7252//7252 7256//7256 7257//7257 -f 7252//7252 7257//7257 7250//7250 -f 7250//7250 7257//7257 7258//7258 -f 7250//7250 7258//7258 7251//7251 -f 7255//7255 7253//7253 7259//7259 -f 7259//7259 7253//7253 7260//7260 -f 7259//7259 7260//7260 7261//7261 -f 7262//7262 6772//6772 7263//7263 -f 7263//7263 6772//6772 6771//6771 -f 7263//7263 6771//6771 7264//7264 -f 7262//7262 7265//7265 6772//6772 -f 6772//6772 7265//7265 7266//7266 -f 6772//6772 7266//7266 6768//6768 -f 7011//7011 7010//7010 7267//7267 -f 7267//7267 7268//7268 7011//7011 -f 7011//7011 7268//7268 7269//7269 -f 7011//7011 7269//7269 6774//6774 -f 7269//7269 7270//7270 6774//6774 -f 6774//6774 7270//7270 7271//7271 -f 6774//6774 7271//7271 6775//6775 -f 6775//6775 7271//7271 7272//7272 -f 6775//6775 7272//7272 6771//6771 -f 6771//6771 7272//7272 7273//7273 -f 6771//6771 7273//7273 7264//7264 -f 6866//6866 6864//6864 7274//7274 -f 7274//7274 7275//7275 6866//6866 -f 6866//6866 7275//7275 7276//7276 -f 6866//6866 7276//7276 7010//7010 -f 7010//7010 7276//7276 7277//7277 -f 7010//7010 7277//7277 7267//7267 -f 7278//7278 6869//6869 7279//7279 -f 7279//7279 6869//6869 6787//6787 -f 7279//7279 6787//6787 7280//7280 -f 7280//7280 6787//6787 6857//6857 -f 7280//7280 6857//6857 7281//7281 -f 7278//7278 7282//7282 6869//6869 -f 6869//6869 7282//7282 7283//7283 -f 6869//6869 7283//7283 6862//6862 -f 6862//6862 7283//7283 7284//7284 -f 6862//6862 7284//7284 6864//6864 -f 6864//6864 7284//7284 7285//7285 -f 6864//6864 7285//7285 7274//7274 -f 6845//6845 6844//6844 7286//7286 -f 7286//7286 7287//7287 6845//6845 -f 6845//6845 7287//7287 7288//7288 -f 6845//6845 7288//7288 6852//6852 -f 6852//6852 7288//7288 7289//7289 -f 7289//7289 7290//7290 6852//6852 -f 6852//6852 7290//7290 7291//7291 -f 6852//6852 7291//7291 6856//6856 -f 6856//6856 7291//7291 7292//7292 -f 6856//6856 7292//7292 6857//6857 -f 6857//6857 7292//7292 7293//7293 -f 6857//6857 7293//7293 7281//7281 -f 6849//6849 6841//6841 7294//7294 -f 7294//7294 7295//7295 6849//6849 -f 6849//6849 7295//7295 7296//7296 -f 6849//6849 7296//7296 6844//6844 -f 6844//6844 7296//7296 7297//7297 -f 6844//6844 7297//7297 7286//7286 -f 6836//6836 7298//7298 6841//6841 -f 6841//6841 7298//7298 7299//7299 -f 6841//6841 7299//7299 7294//7294 -f 7300//7300 7301//7301 6838//6838 -f 7301//7301 7302//7302 6838//6838 -f 6838//6838 7302//7302 7303//7303 -f 6838//6838 7303//7303 6836//6836 -f 6836//6836 7303//7303 7304//7304 -f 6836//6836 7304//7304 7298//7298 -f 7305//7305 6831//6831 7306//7306 -f 7306//7306 6831//6831 6790//6790 -f 6838//6838 6832//6832 7300//7300 -f 7300//7300 6832//6832 6831//6831 -f 7300//7300 6831//6831 7307//7307 -f 7307//7307 6831//6831 7305//7305 -f 7308//7308 6790//6790 7309//7309 -f 7309//7309 6790//6790 6823//6823 -f 7308//7308 7310//7310 6790//6790 -f 6790//6790 7310//7310 7311//7311 -f 6790//6790 7311//7311 7306//7306 -f 7312//7312 7313//7313 6820//6820 -f 6820//6820 7313//7313 7314//7314 -f 6820//6820 7314//7314 6822//6822 -f 6822//6822 7314//7314 7315//7315 -f 6822//6822 7315//7315 6823//6823 -f 6823//6823 7315//7315 7316//7316 -f 6823//6823 7316//7316 7309//7309 -f 6793//6793 7317//7317 6820//6820 -f 6820//6820 7317//7317 7318//7318 -f 6820//6820 7318//7318 7312//7312 -f 6808//6808 6810//6810 7319//7319 -f 7319//7319 7320//7320 6808//6808 -f 6808//6808 7320//7320 7321//7321 -f 6808//6808 7321//7321 6815//6815 -f 7321//7321 7322//7322 6815//6815 -f 6815//6815 7322//7322 7323//7323 -f 6815//6815 7323//7323 6793//6793 -f 6793//6793 7323//7323 7324//7324 -f 6793//6793 7324//7324 7317//7317 -f 6796//6796 7325//7325 6810//6810 -f 6810//6810 7325//7325 7326//7326 -f 6810//6810 7326//7326 7319//7319 -f 7327//7327 7328//7328 6798//6798 -f 6798//6798 7328//7328 7329//7329 -f 6798//6798 7329//7329 6796//6796 -f 6796//6796 7329//7329 7330//7330 -f 6796//6796 7330//7330 7325//7325 -f 7327//7327 6798//6798 7331//7331 -f 7331//7331 6798//6798 6801//6801 -f 7331//7331 6801//6801 7332//7332 -f 7332//7332 6801//6801 6803//6803 -f 7332//7332 6803//6803 7333//7333 -f 7333//7333 6803//6803 6805//6805 -f 7333//7333 6805//6805 6807//6807 -f 6928//6928 7334//7334 7335//7335 -f 7336//7336 7337//7337 7335//7335 -f 7335//7335 7337//7337 7338//7338 -f 7335//7335 7338//7338 6928//6928 -f 7179//7179 7178//7178 7335//7335 -f 7335//7335 7178//7178 7339//7339 -f 7335//7335 7339//7339 7336//7336 -f 7265//7265 7261//7261 7266//7266 -f 7266//7266 7261//7261 7260//7260 -f 7266//7266 7260//7260 6768//6768 -f 6768//6768 7260//7260 7253//7253 -f 6768//6768 7253//7253 6769//6769 -f 6769//6769 7253//7253 7252//7252 -f 6769//6769 7252//7252 6765//6765 -f 6765//6765 7252//7252 7250//7250 -f 6765//6765 7250//7250 6766//6766 -f 6766//6766 7250//7250 7183//7183 -f 6766//6766 7183//7183 6762//6762 -f 6762//6762 7183//7183 6763//6763 -f 6759//6759 6763//6763 7241//7241 -f 7241//7241 6763//6763 7183//7183 -f 7241//7241 7183//7183 7246//7246 -f 7246//7246 7183//7183 7182//7182 -f 7243//7243 7239//7239 7241//7241 -f 7241//7241 7239//7239 6760//6760 -f 7241//7241 6760//6760 6759//6759 -f 6754//6754 6753//6753 7236//7236 -f 7236//7236 6753//6753 6757//6757 -f 7236//7236 6757//6757 7239//7239 -f 7239//7239 6757//6757 6756//6756 -f 7239//7239 6756//6756 6760//6760 -f 6750//6750 6754//6754 7230//7230 -f 7230//7230 6754//6754 7236//7236 -f 7230//7230 7236//7236 7231//7231 -f 7231//7231 7236//7236 7237//7237 -f 7222//7222 7224//7224 7230//7230 -f 7230//7230 7224//7224 6751//6751 -f 7230//7230 6751//6751 6750//6750 -f 6745//6745 6744//6744 7226//7226 -f 7226//7226 6744//6744 6748//6748 -f 7226//7226 6748//6748 7224//7224 -f 7224//7224 6748//6748 6747//6747 -f 7224//7224 6747//6747 6751//6751 -f 6741//6741 6745//6745 7219//7219 -f 7219//7219 6745//6745 7226//7226 -f 7219//7219 7226//7226 7217//7217 -f 7217//7217 7226//7226 7228//7228 -f 7214//7214 7212//7212 7219//7219 -f 7219//7219 7212//7212 6742//6742 -f 7219//7219 6742//6742 6741//6741 -f 6736//6736 6735//6735 7208//7208 -f 7208//7208 6735//6735 6739//6739 -f 7208//7208 6739//6739 7212//7212 -f 7212//7212 6739//6739 6738//6738 -f 7212//7212 6738//6738 6742//6742 -f 6732//6732 6736//6736 7186//7186 -f 7186//7186 6736//6736 7208//7208 -f 7186//7186 7208//7208 7210//7210 -f 7210//7210 7208//7208 7209//7209 -f 7185//7185 7201//7201 7186//7186 -f 7186//7186 7201//7201 6733//6733 -f 7186//7186 6733//6733 6732//6732 -f 6727//6727 6726//6726 7189//7189 -f 7189//7189 6726//6726 6730//6730 -f 7189//7189 6730//6730 7201//7201 -f 7201//7201 6730//6730 6729//6729 -f 7201//7201 6729//6729 6733//6733 -f 6723//6723 6727//6727 7199//7199 -f 7199//7199 6727//6727 7189//7189 -f 7199//7199 7189//7189 7197//7197 -f 7197//7197 7189//7189 7188//7188 -f 7190//7190 7192//7192 7199//7199 -f 7199//7199 7192//7192 6724//6724 -f 7199//7199 6724//6724 6723//6723 -f 6718//6718 6717//6717 7194//7194 -f 7194//7194 6717//6717 6721//6721 -f 7194//7194 6721//6721 7192//7192 -f 7192//7192 6721//6721 6720//6720 -f 7192//7192 6720//6720 6724//6724 -f 7196//7196 7340//7340 7194//7194 -f 7194//7194 7340//7340 7341//7341 -f 7194//7194 7341//7341 6718//6718 -f 7342//7342 6715//6715 7341//7341 -f 7341//7341 6715//6715 6714//6714 -f 7341//7341 6714//6714 6718//6718 -f 7343//7343 6712//6712 7342//7342 -f 7342//7342 6712//6712 6711//6711 -f 7342//7342 6711//6711 6715//6715 -f 7344//7344 6709//6709 7343//7343 -f 7343//7343 6709//6709 6708//6708 -f 7343//7343 6708//6708 6712//6712 -f 7345//7345 6706//6706 7344//7344 -f 7344//7344 6706//6706 6705//6705 -f 7344//7344 6705//6705 6709//6709 -f 7346//7346 6703//6703 7345//7345 -f 7345//7345 6703//6703 6702//6702 -f 7345//7345 6702//6702 6706//6706 -f 6697//6697 6696//6696 7347//7347 -f 7347//7347 6696//6696 6700//6700 -f 7347//7347 6700//6700 7346//7346 -f 7346//7346 6700//6700 6699//6699 -f 7346//7346 6699//6699 6703//6703 -f 6693//6693 7348//7348 6694//6694 -f 6694//6694 7348//7348 7349//7349 -f 6694//6694 7349//7349 6690//6690 -f 6690//6690 7349//7349 6691//6691 -f 6687//6687 7350//7350 6688//6688 -f 6688//6688 7350//7350 7351//7351 -f 7352//7352 6685//6685 7351//7351 -f 7351//7351 6685//6685 6684//6684 -f 7351//7351 6684//6684 6688//6688 -f 7353//7353 6682//6682 7352//7352 -f 7352//7352 6682//6682 6681//6681 -f 7352//7352 6681//6681 6685//6685 -f 7354//7354 6679//6679 7353//7353 -f 7353//7353 6679//6679 6678//6678 -f 7353//7353 6678//6678 6682//6682 -f 7355//7355 6676//6676 7354//7354 -f 7354//7354 6676//6676 6675//6675 -f 7354//7354 6675//6675 6679//6679 -f 6670//6670 6669//6669 7356//7356 -f 7356//7356 6669//6669 6673//6673 -f 7356//7356 6673//6673 7355//7355 -f 7355//7355 6673//6673 6672//6672 -f 7355//7355 6672//6672 6676//6676 -f 6666//6666 7357//7357 6667//6667 -f 6667//6667 7357//7357 7358//7358 -f 6667//6667 7358//7358 6663//6663 -f 6663//6663 7358//7358 6664//6664 -f 6660//6660 7359//7359 6661//6661 -f 6661//6661 7359//7359 7360//7360 -f 7361//7361 6658//6658 7360//7360 -f 7360//7360 6658//6658 6657//6657 -f 7360//7360 6657//6657 6661//6661 -f 7362//7362 6655//6655 7361//7361 -f 7361//7361 6655//6655 6654//6654 -f 7361//7361 6654//6654 6658//6658 -f 7363//7363 6652//6652 7362//7362 -f 7362//7362 6652//6652 6651//6651 -f 7362//7362 6651//6651 6655//6655 -f 7364//7364 6649//6649 7363//7363 -f 7363//7363 6649//6649 6648//6648 -f 7363//7363 6648//6648 6652//6652 -f 6643//6643 6642//6642 7365//7365 -f 7365//7365 6642//6642 6646//6646 -f 7365//7365 6646//6646 7364//7364 -f 7364//7364 6646//6646 6645//6645 -f 7364//7364 6645//6645 6649//6649 -f 6639//6639 7366//7366 6640//6640 -f 6640//6640 7366//7366 7367//7367 -f 6640//6640 7367//7367 6636//6636 -f 6636//6636 7367//7367 6637//6637 -f 6633//6633 7368//7368 6634//6634 -f 6634//6634 7368//7368 7369//7369 -f 7370//7370 6631//6631 7369//7369 -f 7369//7369 6631//6631 6630//6630 -f 7369//7369 6630//6630 6634//6634 -f 7371//7371 6628//6628 7370//7370 -f 7370//7370 6628//6628 6627//6627 -f 7370//7370 6627//6627 6631//6631 -f 7372//7372 6625//6625 7371//7371 -f 7371//7371 6625//6625 6624//6624 -f 7371//7371 6624//6624 6628//6628 -f 7373//7373 6622//6622 7372//7372 -f 7372//7372 6622//6622 6621//6621 -f 7372//7372 6621//6621 6625//6625 -f 6616//6616 6615//6615 7374//7374 -f 7374//7374 6615//6615 6619//6619 -f 7374//7374 6619//6619 7373//7373 -f 7373//7373 6619//6619 6618//6618 -f 7373//7373 6618//6618 6622//6622 -f 6612//6612 7375//7375 6613//6613 -f 6613//6613 7375//7375 7376//7376 -f 6613//6613 7376//7376 6609//6609 -f 6609//6609 7376//7376 6610//6610 -f 6606//6606 7377//7377 6607//6607 -f 6607//6607 7377//7377 7378//7378 -f 7379//7379 6604//6604 7378//7378 -f 7378//7378 6604//6604 6603//6603 -f 7378//7378 6603//6603 6607//6607 -f 7380//7380 6601//6601 7379//7379 -f 7379//7379 6601//6601 6600//6600 -f 7379//7379 6600//6600 6604//6604 -f 6595//6595 6594//6594 7381//7381 -f 7381//7381 6594//6594 6598//6598 -f 7381//7381 6598//6598 7380//7380 -f 7380//7380 6598//6598 6597//6597 -f 7380//7380 6597//6597 6601//6601 -f 6591//6591 7382//7382 6592//6592 -f 6592//6592 7382//7382 7383//7383 -f 7384//7384 6589//6589 7383//7383 -f 7383//7383 6589//6589 6588//6588 -f 7383//7383 6588//6588 6592//6592 -f 6583//6583 6582//6582 7385//7385 -f 7385//7385 6582//6582 6586//6586 -f 7385//7385 6586//6586 7384//7384 -f 7384//7384 6586//6586 6585//6585 -f 7384//7384 6585//6585 6589//6589 -f 6579//6579 7386//7386 6580//6580 -f 6580//6580 7386//7386 7387//7387 -f 6574//6574 6573//6573 7388//7388 -f 7388//7388 6573//6573 6577//6577 -f 7388//7388 6577//6577 7387//7387 -f 7387//7387 6577//6577 6576//6576 -f 7387//7387 6576//6576 6580//6580 -f 6570//6570 7389//7389 6571//6571 -f 6571//6571 7389//7389 7390//7390 -f 6571//6571 7390//7390 6567//6567 -f 6567//6567 7390//7390 6568//6568 -f 6564//6564 7391//7391 6565//6565 -f 6565//6565 7391//7391 7392//7392 -f 7393//7393 6562//6562 7392//7392 -f 7392//7392 6562//6562 6561//6561 -f 7392//7392 6561//6561 6565//6565 -f 6556//6556 6555//6555 7394//7394 -f 7394//7394 6555//6555 6559//6559 -f 7394//7394 6559//6559 7393//7393 -f 7393//7393 6559//6559 6558//6558 -f 7393//7393 6558//6558 6562//6562 -f 6552//6552 7395//7395 6553//6553 -f 6553//6553 7395//7395 7396//7396 -f 6547//6547 6546//6546 7397//7397 -f 7397//7397 6546//6546 6550//6550 -f 7397//7397 6550//6550 7396//7396 -f 7396//7396 6550//6550 6549//6549 -f 7396//7396 6549//6549 6553//6553 -f 6543//6543 7398//7398 6544//6544 -f 6544//6544 7398//7398 7399//7399 -f 6544//6544 7399//7399 6540//6540 -f 6540//6540 7399//7399 6541//6541 -f 6537//6537 7400//7400 6538//6538 -f 6538//6538 7400//7400 7401//7401 -f 7402//7402 6535//6535 7401//7401 -f 7401//7401 6535//6535 6534//6534 -f 7401//7401 6534//6534 6538//6538 -f 7403//7403 6532//6532 7402//7402 -f 7402//7402 6532//6532 6531//6531 -f 7402//7402 6531//6531 6535//6535 -f 7404//7404 6529//6529 7403//7403 -f 7403//7403 6529//6529 6528//6528 -f 7403//7403 6528//6528 6532//6532 -f 7405//7405 6526//6526 7404//7404 -f 7404//7404 6526//6526 6525//6525 -f 7404//7404 6525//6525 6529//6529 -f 6520//6520 6519//6519 7406//7406 -f 7406//7406 6519//6519 6523//6523 -f 7406//7406 6523//6523 7405//7405 -f 7405//7405 6523//6523 6522//6522 -f 7405//7405 6522//6522 6526//6526 -f 6516//6516 7407//7407 6517//6517 -f 6517//6517 7407//7407 7408//7408 -f 6517//6517 7408//7408 6513//6513 -f 6513//6513 7408//7408 6514//6514 -f 6510//6510 7409//7409 6511//6511 -f 6511//6511 7409//7409 7410//7410 -f 7411//7411 6508//6508 7410//7410 -f 7410//7410 6508//6508 6507//6507 -f 7410//7410 6507//6507 6511//6511 -f 7412//7412 6505//6505 7411//7411 -f 7411//7411 6505//6505 6504//6504 -f 7411//7411 6504//6504 6508//6508 -f 7413//7413 6502//6502 7412//7412 -f 7412//7412 6502//6502 6501//6501 -f 7412//7412 6501//6501 6505//6505 -f 7414//7414 6499//6499 7413//7413 -f 7413//7413 6499//6499 6498//6498 -f 7413//7413 6498//6498 6502//6502 -f 7013//7013 7012//7012 7415//7415 -f 7415//7415 7012//7012 6496//6496 -f 7415//7415 6496//6496 7414//7414 -f 7414//7414 6496//6496 6495//6495 -f 7414//7414 6495//6495 6499//6499 -f 7014//7014 7416//7416 7015//7015 -f 7015//7015 7416//7416 7417//7417 -f 7018//7018 7017//7017 7417//7417 -f 7417//7417 7017//7017 7016//7016 -f 7417//7417 7016//7016 7015//7015 -f 7020//7020 7019//7019 7418//7418 -f 7418//7418 7019//7019 7419//7419 -f 7177//7177 7022//7022 7418//7418 -f 7418//7418 7022//7022 7021//7021 -f 7418//7418 7021//7021 7020//7020 -f 7023//7023 7177//7177 7024//7024 -f 7024//7024 7177//7177 7420//7420 -f 7024//7024 7420//7420 7025//7025 -f 7025//7025 7420//7420 7421//7421 -f 7025//7025 7421//7421 7026//7026 -f 7422//7422 7028//7028 7421//7421 -f 7421//7421 7028//7028 7027//7027 -f 7421//7421 7027//7027 7026//7026 -f 7032//7032 7031//7031 7423//7423 -f 7423//7423 7031//7031 7030//7030 -f 7423//7423 7030//7030 7422//7422 -f 7422//7422 7030//7030 7029//7029 -f 7422//7422 7029//7029 7028//7028 -f 7033//7033 7424//7424 7034//7034 -f 7034//7034 7424//7424 7425//7425 -f 7034//7034 7425//7425 7035//7035 -f 7035//7035 7425//7425 7036//7036 -f 7426//7426 7038//7038 7427//7427 -f 7427//7427 7038//7038 7037//7037 -f 7428//7428 7429//7429 7042//7042 -f 7042//7042 7041//7041 7428//7428 -f 7428//7428 7041//7041 7040//7040 -f 7428//7428 7040//7040 7426//7426 -f 7426//7426 7040//7040 7039//7039 -f 7426//7426 7039//7039 7038//7038 -f 7430//7430 7431//7431 7046//7046 -f 7046//7046 7045//7045 7430//7430 -f 7430//7430 7045//7045 7044//7044 -f 7430//7430 7044//7044 7429//7429 -f 7429//7429 7044//7044 7043//7043 -f 7429//7429 7043//7043 7042//7042 -f 7050//7050 7049//7049 7432//7432 -f 7432//7432 7049//7049 7048//7048 -f 7432//7432 7048//7048 7431//7431 -f 7431//7431 7048//7048 7047//7047 -f 7431//7431 7047//7047 7046//7046 -f 7051//7051 7433//7433 7052//7052 -f 7052//7052 7433//7433 7434//7434 -f 7052//7052 7434//7434 7053//7053 -f 7053//7053 7434//7434 7054//7054 -f 7435//7435 7056//7056 7436//7436 -f 7436//7436 7056//7056 7055//7055 -f 7437//7437 7438//7438 7060//7060 -f 7060//7060 7059//7059 7437//7437 -f 7437//7437 7059//7059 7058//7058 -f 7437//7437 7058//7058 7435//7435 -f 7435//7435 7058//7058 7057//7057 -f 7435//7435 7057//7057 7056//7056 -f 7439//7439 7440//7440 7064//7064 -f 7064//7064 7063//7063 7439//7439 -f 7439//7439 7063//7063 7062//7062 -f 7439//7439 7062//7062 7438//7438 -f 7438//7438 7062//7062 7061//7061 -f 7438//7438 7061//7061 7060//7060 -f 7068//7068 7067//7067 7441//7441 -f 7441//7441 7067//7067 7066//7066 -f 7441//7441 7066//7066 7440//7440 -f 7440//7440 7066//7066 7065//7065 -f 7440//7440 7065//7065 7064//7064 -f 7069//7069 7442//7442 7070//7070 -f 7070//7070 7442//7442 7443//7443 -f 7070//7070 7443//7443 7071//7071 -f 7071//7071 7443//7443 7072//7072 -f 7444//7444 7074//7074 7445//7445 -f 7445//7445 7074//7074 7073//7073 -f 7446//7446 7447//7447 7078//7078 -f 7078//7078 7077//7077 7446//7446 -f 7446//7446 7077//7077 7076//7076 -f 7446//7446 7076//7076 7444//7444 -f 7444//7444 7076//7076 7075//7075 -f 7444//7444 7075//7075 7074//7074 -f 7082//7082 7081//7081 7448//7448 -f 7448//7448 7081//7081 7080//7080 -f 7448//7448 7080//7080 7447//7447 -f 7447//7447 7080//7080 7079//7079 -f 7447//7447 7079//7079 7078//7078 -f 7449//7449 7450//7450 7086//7086 -f 7083//7083 7451//7451 7084//7084 -f 7084//7084 7451//7451 7449//7449 -f 7084//7084 7449//7449 7085//7085 -f 7085//7085 7449//7449 7086//7086 -f 7090//7090 7089//7089 7452//7452 -f 7452//7452 7089//7089 7088//7088 -f 7452//7452 7088//7088 7450//7450 -f 7450//7450 7088//7088 7087//7087 -f 7450//7450 7087//7087 7086//7086 -f 7453//7453 7092//7092 7454//7454 -f 7454//7454 7092//7092 7091//7091 -f 7455//7455 7456//7456 7096//7096 -f 7096//7096 7095//7095 7455//7455 -f 7455//7455 7095//7095 7094//7094 -f 7455//7455 7094//7094 7453//7453 -f 7453//7453 7094//7094 7093//7093 -f 7453//7453 7093//7093 7092//7092 -f 7100//7100 7099//7099 7457//7457 -f 7457//7457 7099//7099 7098//7098 -f 7457//7457 7098//7098 7456//7456 -f 7456//7456 7098//7098 7097//7097 -f 7456//7456 7097//7097 7096//7096 -f 7458//7458 7102//7102 7459//7459 -f 7459//7459 7102//7102 7101//7101 -f 7460//7460 7105//7105 7461//7461 -f 7461//7461 7105//7105 7104//7104 -f 7461//7461 7104//7104 7458//7458 -f 7458//7458 7104//7104 7103//7103 -f 7458//7458 7103//7103 7102//7102 -f 7108//7108 7107//7107 7460//7460 -f 7460//7460 7107//7107 7106//7106 -f 7460//7460 7106//7106 7105//7105 -f 7462//7462 7463//7463 7111//7111 -f 7115//7115 7112//7112 7464//7464 -f 7464//7464 7112//7112 7109//7109 -f 7464//7464 7109//7109 7463//7463 -f 7463//7463 7109//7109 7110//7110 -f 7463//7463 7110//7110 7111//7111 -f 7114//7114 7465//7465 7113//7113 -f 7113//7113 7465//7465 7466//7466 -f 7113//7113 7466//7466 7116//7116 -f 7116//7116 7466//7466 7119//7119 -f 7118//7118 7467//7467 7117//7117 -f 7117//7117 7467//7467 7468//7468 -f 7469//7469 7123//7123 7468//7468 -f 7468//7468 7123//7123 7120//7120 -f 7468//7468 7120//7120 7117//7117 -f 7470//7470 7121//7121 7469//7469 -f 7469//7469 7121//7121 7122//7122 -f 7469//7469 7122//7122 7123//7123 -f 7471//7471 7127//7127 7470//7470 -f 7470//7470 7127//7127 7124//7124 -f 7470//7470 7124//7124 7121//7121 -f 7472//7472 7125//7125 7471//7471 -f 7471//7471 7125//7125 7126//7126 -f 7471//7471 7126//7126 7127//7127 -f 7129//7129 7130//7130 7473//7473 -f 7473//7473 7130//7130 7131//7131 -f 7473//7473 7131//7131 7472//7472 -f 7472//7472 7131//7131 7128//7128 -f 7472//7472 7128//7128 7125//7125 -f 7132//7132 7474//7474 7135//7135 -f 7135//7135 7474//7474 7475//7475 -f 7135//7135 7475//7475 7134//7134 -f 7134//7134 7475//7475 7133//7133 -f 7136//7136 7476//7476 7139//7139 -f 7139//7139 7476//7476 7477//7477 -f 7478//7478 7137//7137 7477//7477 -f 7477//7477 7137//7137 7138//7138 -f 7477//7477 7138//7138 7139//7139 -f 7479//7479 7143//7143 7478//7478 -f 7478//7478 7143//7143 7140//7140 -f 7478//7478 7140//7140 7137//7137 -f 7480//7480 7141//7141 7479//7479 -f 7479//7479 7141//7141 7142//7142 -f 7479//7479 7142//7142 7143//7143 -f 7481//7481 7147//7147 7480//7480 -f 7480//7480 7147//7147 7144//7144 -f 7480//7480 7144//7144 7141//7141 -f 7151//7151 7148//7148 7482//7482 -f 7482//7482 7148//7148 7145//7145 -f 7482//7482 7145//7145 7481//7481 -f 7481//7481 7145//7145 7146//7146 -f 7481//7481 7146//7146 7147//7147 -f 7150//7150 7483//7483 7149//7149 -f 7149//7149 7483//7483 7484//7484 -f 7149//7149 7484//7484 7152//7152 -f 7152//7152 7484//7484 7155//7155 -f 7154//7154 7485//7485 7153//7153 -f 7153//7153 7485//7485 7486//7486 -f 7487//7487 7159//7159 7486//7486 -f 7486//7486 7159//7159 7156//7156 -f 7486//7486 7156//7156 7153//7153 -f 7488//7488 7157//7157 7487//7487 -f 7487//7487 7157//7157 7158//7158 -f 7487//7487 7158//7158 7159//7159 -f 7489//7489 7163//7163 7488//7488 -f 7488//7488 7163//7163 7160//7160 -f 7488//7488 7160//7160 7157//7157 -f 7490//7490 7161//7161 7489//7489 -f 7489//7489 7161//7161 7162//7162 -f 7489//7489 7162//7162 7163//7163 -f 7165//7165 7166//7166 7491//7491 -f 7491//7491 7166//7166 7167//7167 -f 7491//7491 7167//7167 7490//7490 -f 7490//7490 7167//7167 7164//7164 -f 7490//7490 7164//7164 7161//7161 -f 7168//7168 7492//7492 7171//7171 -f 7171//7171 7492//7492 7493//7493 -f 7171//7171 7493//7493 7170//7170 -f 7170//7170 7493//7493 7169//7169 -f 7172//7172 7494//7494 7176//7176 -f 7176//7176 7494//7494 7495//7495 -f 7496//7496 7174//7174 7495//7495 -f 7495//7495 7174//7174 7175//7175 -f 7495//7495 7175//7175 7176//7176 -f 6928//6928 6927//6927 7334//7334 -f 7334//7334 6927//6927 6925//6925 -f 7334//7334 6925//6925 7496//7496 -f 7496//7496 6925//6925 6924//6924 -f 7496//7496 6924//6924 7174//7174 -f 7340//7340 5949//5949 7341//7341 -f 7341//7341 5949//5949 5948//5948 -f 7341//7341 5948//5948 7342//7342 -f 7342//7342 5948//5948 5946//5946 -f 7342//7342 5946//5946 7343//7343 -f 5946//5946 5944//5944 7343//7343 -f 7343//7343 5944//5944 5943//5943 -f 7343//7343 5943//5943 7344//7344 -f 7344//7344 5943//5943 5950//5950 -f 7344//7344 5950//5950 7345//7345 -f 5950//5950 5952//5952 7345//7345 -f 7345//7345 5952//5952 5954//5954 -f 7345//7345 5954//5954 7346//7346 -f 7346//7346 5954//5954 5955//5955 -f 7346//7346 5955//5955 7347//7347 -f 7347//7347 5955//5955 5957//5957 -f 5957//5957 5958//5958 7347//7347 -f 7347//7347 5958//5958 7348//7348 -f 7347//7347 7348//7348 6697//6697 -f 6697//6697 7348//7348 6693//6693 -f 5959//5959 7349//7349 5940//5940 -f 5940//5940 7349//7349 7348//7348 -f 5940//5940 7348//7348 5941//5941 -f 5941//5941 7348//7348 5958//5958 -f 5959//5959 5961//5961 7349//7349 -f 7349//7349 5961//5961 7350//7350 -f 7349//7349 7350//7350 6691//6691 -f 6691//6691 7350//7350 6687//6687 -f 5961//5961 5964//5964 7350//7350 -f 7350//7350 5964//5964 5966//5966 -f 7350//7350 5966//5966 7351//7351 -f 7351//7351 5966//5966 5967//5967 -f 7351//7351 5967//5967 7352//7352 -f 5967//5967 5969//5969 7352//7352 -f 7352//7352 5969//5969 5971//5971 -f 7352//7352 5971//5971 7353//7353 -f 7353//7353 5971//5971 5973//5973 -f 7353//7353 5973//5973 7354//7354 -f 5973//5973 5976//5976 7354//7354 -f 7354//7354 5976//5976 5978//5978 -f 7354//7354 5978//5978 7355//7355 -f 7355//7355 5978//5978 5980//5980 -f 7355//7355 5980//5980 7356//7356 -f 7356//7356 5980//5980 5982//5982 -f 5982//5982 5984//5984 7356//7356 -f 7356//7356 5984//5984 7357//7357 -f 7356//7356 7357//7357 6670//6670 -f 6670//6670 7357//7357 6666//6666 -f 5990//5990 7358//7358 5988//5988 -f 5988//5988 7358//7358 7357//7357 -f 5988//5988 7357//7357 5986//5986 -f 5986//5986 7357//7357 5984//5984 -f 5990//5990 5992//5992 7358//7358 -f 7358//7358 5992//5992 7359//7359 -f 7358//7358 7359//7359 6664//6664 -f 6664//6664 7359//7359 6660//6660 -f 5992//5992 5994//5994 7359//7359 -f 7359//7359 5994//5994 5996//5996 -f 7359//7359 5996//5996 7360//7360 -f 7360//7360 5996//5996 5998//5998 -f 7360//7360 5998//5998 7361//7361 -f 5998//5998 6000//6000 7361//7361 -f 7361//7361 6000//6000 6002//6002 -f 7361//7361 6002//6002 7362//7362 -f 7362//7362 6002//6002 6004//6004 -f 7362//7362 6004//6004 7363//7363 -f 6004//6004 6007//6007 7363//7363 -f 7363//7363 6007//6007 6009//6009 -f 7363//7363 6009//6009 7364//7364 -f 7364//7364 6009//6009 6011//6011 -f 7364//7364 6011//6011 7365//7365 -f 7365//7365 6011//6011 6013//6013 -f 6013//6013 6014//6014 7365//7365 -f 7365//7365 6014//6014 7366//7366 -f 7365//7365 7366//7366 6643//6643 -f 6643//6643 7366//7366 6639//6639 -f 6020//6020 7367//7367 6018//6018 -f 6018//6018 7367//7367 7366//7366 -f 6018//6018 7366//7366 6016//6016 -f 6016//6016 7366//7366 6014//6014 -f 6020//6020 6022//6022 7367//7367 -f 7367//7367 6022//6022 7368//7368 -f 7367//7367 7368//7368 6637//6637 -f 6637//6637 7368//7368 6633//6633 -f 6022//6022 6024//6024 7368//7368 -f 7368//7368 6024//6024 6026//6026 -f 7368//7368 6026//6026 7369//7369 -f 7369//7369 6026//6026 6028//6028 -f 7369//7369 6028//6028 7370//7370 -f 6028//6028 6030//6030 7370//7370 -f 7370//7370 6030//6030 6032//6032 -f 7370//7370 6032//6032 7371//7371 -f 7371//7371 6032//6032 6034//6034 -f 7371//7371 6034//6034 7372//7372 -f 6034//6034 6037//6037 7372//7372 -f 7372//7372 6037//6037 6039//6039 -f 7372//7372 6039//6039 7373//7373 -f 7373//7373 6039//6039 6041//6041 -f 7373//7373 6041//6041 7374//7374 -f 7374//7374 6041//6041 6043//6043 -f 6043//6043 6044//6044 7374//7374 -f 7374//7374 6044//6044 7375//7375 -f 7374//7374 7375//7375 6616//6616 -f 6616//6616 7375//7375 6612//6612 -f 6050//6050 7376//7376 6048//6048 -f 6048//6048 7376//7376 7375//7375 -f 6048//6048 7375//7375 6046//6046 -f 6046//6046 7375//7375 6044//6044 -f 6050//6050 6052//6052 7376//7376 -f 7376//7376 6052//6052 7377//7377 -f 7376//7376 7377//7377 6610//6610 -f 6610//6610 7377//7377 6606//6606 -f 6052//6052 6054//6054 7377//7377 -f 7377//7377 6054//6054 6056//6056 -f 7377//7377 6056//6056 7378//7378 -f 7378//7378 6056//6056 6058//6058 -f 7378//7378 6058//6058 7379//7379 -f 6067//6067 7381//7381 6064//6064 -f 6064//6064 7381//7381 7380//7380 -f 6064//6064 7380//7380 6062//6062 -f 6062//6062 7380//7380 7379//7379 -f 6062//6062 7379//7379 6060//6060 -f 6060//6060 7379//7379 6058//6058 -f 6067//6067 6069//6069 7381//7381 -f 7381//7381 6069//6069 7382//7382 -f 7381//7381 7382//7382 6595//6595 -f 6595//6595 7382//7382 6591//6591 -f 6069//6069 6071//6071 7382//7382 -f 7382//7382 6071//6071 6089//6089 -f 7382//7382 6089//6089 7383//7383 -f 7383//7383 6089//6089 6088//6088 -f 7383//7383 6088//6088 7384//7384 -f 6082//6082 7385//7385 6084//6084 -f 6084//6084 7385//7385 7384//7384 -f 6084//6084 7384//7384 6086//6086 -f 6086//6086 7384//7384 6088//6088 -f 6082//6082 6080//6080 7385//7385 -f 7385//7385 6080//6080 7386//7386 -f 7385//7385 7386//7386 6583//6583 -f 6583//6583 7386//7386 6579//6579 -f 6080//6080 6078//6078 7386//7386 -f 7386//7386 6078//6078 6076//6076 -f 7386//7386 6076//6076 7387//7387 -f 7387//7387 6076//6076 6074//6074 -f 7387//7387 6074//6074 7388//7388 -f 7388//7388 6074//6074 6121//6121 -f 6121//6121 6120//6120 7388//7388 -f 7388//7388 6120//6120 7389//7389 -f 7388//7388 7389//7389 6574//6574 -f 6574//6574 7389//7389 6570//6570 -f 6114//6114 7390//7390 6116//6116 -f 6116//6116 7390//7390 7389//7389 -f 6116//6116 7389//7389 6118//6118 -f 6118//6118 7389//7389 6120//6120 -f 6114//6114 6112//6112 7390//7390 -f 7390//7390 6112//6112 7391//7391 -f 7390//7390 7391//7391 6568//6568 -f 6568//6568 7391//7391 6564//6564 -f 6112//6112 6110//6110 7391//7391 -f 7391//7391 6110//6110 6108//6108 -f 7391//7391 6108//6108 7392//7392 -f 7392//7392 6108//6108 6106//6106 -f 7392//7392 6106//6106 7393//7393 -f 6100//6100 7394//7394 6102//6102 -f 6102//6102 7394//7394 7393//7393 -f 6102//6102 7393//7393 6104//6104 -f 6104//6104 7393//7393 6106//6106 -f 6100//6100 6098//6098 7394//7394 -f 7394//7394 6098//6098 7395//7395 -f 7394//7394 7395//7395 6556//6556 -f 6556//6556 7395//7395 6552//6552 -f 6098//6098 6096//6096 7395//7395 -f 7395//7395 6096//6096 6094//6094 -f 7395//7395 6094//6094 7396//7396 -f 7396//7396 6094//6094 6092//6092 -f 7396//7396 6092//6092 7397//7397 -f 7397//7397 6092//6092 6091//6091 -f 6091//6091 6122//6122 7397//7397 -f 7397//7397 6122//6122 7398//7398 -f 7397//7397 7398//7398 6547//6547 -f 6547//6547 7398//7398 6543//6543 -f 6128//6128 7399//7399 6126//6126 -f 6126//6126 7399//7399 7398//7398 -f 6126//6126 7398//7398 6124//6124 -f 6124//6124 7398//7398 6122//6122 -f 6128//6128 6130//6130 7399//7399 -f 7399//7399 6130//6130 7400//7400 -f 7399//7399 7400//7400 6541//6541 -f 6541//6541 7400//7400 6537//6537 -f 6130//6130 6132//6132 7400//7400 -f 7400//7400 6132//6132 6134//6134 -f 7400//7400 6134//6134 7401//7401 -f 7401//7401 6134//6134 6136//6136 -f 7401//7401 6136//6136 7402//7402 -f 6136//6136 6138//6138 7402//7402 -f 7402//7402 6138//6138 6140//6140 -f 7402//7402 6140//6140 7403//7403 -f 7403//7403 6140//6140 6142//6142 -f 7403//7403 6142//6142 7404//7404 -f 6142//6142 6145//6145 7404//7404 -f 7404//7404 6145//6145 6147//6147 -f 7404//7404 6147//6147 7405//7405 -f 7405//7405 6147//6147 6149//6149 -f 7405//7405 6149//6149 7406//7406 -f 7406//7406 6149//6149 6151//6151 -f 6151//6151 6152//6152 7406//7406 -f 7406//7406 6152//6152 7407//7407 -f 7406//7406 7407//7407 6520//6520 -f 6520//6520 7407//7407 6516//6516 -f 6158//6158 7408//7408 6156//6156 -f 6156//6156 7408//7408 7407//7407 -f 6156//6156 7407//7407 6154//6154 -f 6154//6154 7407//7407 6152//6152 -f 6158//6158 6160//6160 7408//7408 -f 7408//7408 6160//6160 7409//7409 -f 7408//7408 7409//7409 6514//6514 -f 6514//6514 7409//7409 6510//6510 -f 6160//6160 6162//6162 7409//7409 -f 7409//7409 6162//6162 6164//6164 -f 7409//7409 6164//6164 7410//7410 -f 7410//7410 6164//6164 6166//6166 -f 7410//7410 6166//6166 7411//7411 -f 6166//6166 6168//6168 7411//7411 -f 7411//7411 6168//6168 6170//6170 -f 7411//7411 6170//6170 7412//7412 -f 7412//7412 6170//6170 6172//6172 -f 7412//7412 6172//6172 7413//7413 -f 6172//6172 6175//6175 7413//7413 -f 7413//7413 6175//6175 6177//6177 -f 7413//7413 6177//6177 7414//7414 -f 7414//7414 6177//6177 6179//6179 -f 7414//7414 6179//6179 7415//7415 -f 7415//7415 6179//6179 6181//6181 -f 6181//6181 6183//6183 7415//7415 -f 7415//7415 6183//6183 7416//7416 -f 7415//7415 7416//7416 7013//7013 -f 7013//7013 7416//7416 7014//7014 -f 6189//6189 7417//7417 6187//6187 -f 6187//6187 7417//7417 7416//7416 -f 6187//6187 7416//7416 6185//6185 -f 6185//6185 7416//7416 6183//6183 -f 6189//6189 6191//6191 7417//7417 -f 7417//7417 6191//6191 7419//7419 -f 7417//7417 7419//7419 7018//7018 -f 7018//7018 7419//7419 7019//7019 -f 6191//6191 6193//6193 7419//7419 -f 7419//7419 6193//6193 6195//6195 -f 7419//7419 6195//6195 7418//7418 -f 7418//7418 6195//6195 6197//6197 -f 7418//7418 6197//6197 7177//7177 -f 6197//6197 6199//6199 7177//7177 -f 7177//7177 6199//6199 6200//6200 -f 7177//7177 6200//6200 7420//7420 -f 7420//7420 6200//6200 6202//6202 -f 7420//7420 6202//6202 7421//7421 -f 6202//6202 6205//6205 7421//7421 -f 7421//7421 6205//6205 6207//6207 -f 7421//7421 6207//6207 7422//7422 -f 7422//7422 6207//6207 6209//6209 -f 7422//7422 6209//6209 7423//7423 -f 7423//7423 6209//6209 6211//6211 -f 6211//6211 6213//6213 7423//7423 -f 7423//7423 6213//6213 7424//7424 -f 7423//7423 7424//7424 7032//7032 -f 7032//7032 7424//7424 7033//7033 -f 6219//6219 7425//7425 6217//6217 -f 6217//6217 7425//7425 7424//7424 -f 6217//6217 7424//7424 6215//6215 -f 6215//6215 7424//7424 6213//6213 -f 6219//6219 6221//6221 7425//7425 -f 7425//7425 6221//6221 7427//7427 -f 7425//7425 7427//7427 7036//7036 -f 7036//7036 7427//7427 7037//7037 -f 6221//6221 6223//6223 7427//7427 -f 7427//7427 6223//6223 6225//6225 -f 7427//7427 6225//6225 7426//7426 -f 7426//7426 6225//6225 6227//6227 -f 7426//7426 6227//6227 7428//7428 -f 6227//6227 6229//6229 7428//7428 -f 7428//7428 6229//6229 6230//6230 -f 7428//7428 6230//6230 7429//7429 -f 7429//7429 6230//6230 6232//6232 -f 7429//7429 6232//6232 7430//7430 -f 6232//6232 6235//6235 7430//7430 -f 7430//7430 6235//6235 6237//6237 -f 7430//7430 6237//6237 7431//7431 -f 7431//7431 6237//6237 6239//6239 -f 7431//7431 6239//6239 7432//7432 -f 7432//7432 6239//6239 6241//6241 -f 6241//6241 6243//6243 7432//7432 -f 7432//7432 6243//6243 7433//7433 -f 7432//7432 7433//7433 7050//7050 -f 7050//7050 7433//7433 7051//7051 -f 6249//6249 7434//7434 6247//6247 -f 6247//6247 7434//7434 7433//7433 -f 6247//6247 7433//7433 6245//6245 -f 6245//6245 7433//7433 6243//6243 -f 6249//6249 6251//6251 7434//7434 -f 7434//7434 6251//6251 7436//7436 -f 7434//7434 7436//7436 7054//7054 -f 7054//7054 7436//7436 7055//7055 -f 6251//6251 6253//6253 7436//7436 -f 7436//7436 6253//6253 6255//6255 -f 7436//7436 6255//6255 7435//7435 -f 7435//7435 6255//6255 6256//6256 -f 7435//7435 6256//6256 7437//7437 -f 6256//6256 6258//6258 7437//7437 -f 7437//7437 6258//6258 6260//6260 -f 7437//7437 6260//6260 7438//7438 -f 7438//7438 6260//6260 6262//6262 -f 7438//7438 6262//6262 7439//7439 -f 6262//6262 6265//6265 7439//7439 -f 7439//7439 6265//6265 6267//6267 -f 7439//7439 6267//6267 7440//7440 -f 7440//7440 6267//6267 6269//6269 -f 7440//7440 6269//6269 7441//7441 -f 7441//7441 6269//6269 6279//6279 -f 6279//6279 6278//6278 7441//7441 -f 7441//7441 6278//6278 7442//7442 -f 7441//7441 7442//7442 7068//7068 -f 7068//7068 7442//7442 7069//7069 -f 6272//6272 7443//7443 6274//6274 -f 6274//6274 7443//7443 7442//7442 -f 6274//6274 7442//7442 6276//6276 -f 6276//6276 7442//7442 6278//6278 -f 6272//6272 6271//6271 7443//7443 -f 7443//7443 6271//6271 7445//7445 -f 7443//7443 7445//7445 7072//7072 -f 7072//7072 7445//7445 7073//7073 -f 6271//6271 6282//6282 7445//7445 -f 7445//7445 6282//6282 6284//6284 -f 7445//7445 6284//6284 7444//7444 -f 7444//7444 6284//6284 6286//6286 -f 7444//7444 6286//6286 7446//7446 -f 6294//6294 7448//7448 6292//6292 -f 6292//6292 7448//7448 7447//7447 -f 6292//6292 7447//7447 6289//6289 -f 6289//6289 7447//7447 7446//7446 -f 6289//6289 7446//7446 6288//6288 -f 6288//6288 7446//7446 6286//6286 -f 6294//6294 6296//6296 7448//7448 -f 7448//7448 6296//6296 7451//7451 -f 7448//7448 7451//7451 7082//7082 -f 7082//7082 7451//7451 7083//7083 -f 6296//6296 6299//6299 7451//7451 -f 7451//7451 6299//6299 6301//6301 -f 7451//7451 6301//6301 7449//7449 -f 7449//7449 6301//6301 6303//6303 -f 7449//7449 6303//6303 7450//7450 -f 6307//6307 7452//7452 6309//6309 -f 6309//6309 7452//7452 7450//7450 -f 6309//6309 7450//7450 6310//6310 -f 6310//6310 7450//7450 6303//6303 -f 6307//6307 6306//6306 7452//7452 -f 7452//7452 6306//6306 7454//7454 -f 7452//7452 7454//7454 7090//7090 -f 7090//7090 7454//7454 7091//7091 -f 6306//6306 6311//6311 7454//7454 -f 7454//7454 6311//6311 6313//6313 -f 7454//7454 6313//6313 7453//7453 -f 7453//7453 6313//6313 6316//6316 -f 7453//7453 6316//6316 7455//7455 -f 6325//6325 7457//7457 6322//6322 -f 6322//6322 7457//7457 7456//7456 -f 6322//6322 7456//7456 6320//6320 -f 6320//6320 7456//7456 7455//7455 -f 6320//6320 7455//7455 6318//6318 -f 6318//6318 7455//7455 6316//6316 -f 6325//6325 6327//6327 7457//7457 -f 7457//7457 6327//6327 7459//7459 -f 7457//7457 7459//7459 7100//7100 -f 7100//7100 7459//7459 7101//7101 -f 6327//6327 6329//6329 7459//7459 -f 7459//7459 6329//6329 6339//6339 -f 7459//7459 6339//6339 7458//7458 -f 7458//7458 6339//6339 6338//6338 -f 7458//7458 6338//6338 7461//7461 -f 6332//6332 7460//7460 6334//6334 -f 6334//6334 7460//7460 7461//7461 -f 6334//6334 7461//7461 6336//6336 -f 6336//6336 7461//7461 6338//6338 -f 6332//6332 6331//6331 7460//7460 -f 7460//7460 6331//6331 7462//7462 -f 7460//7460 7462//7462 7108//7108 -f 7108//7108 7462//7462 7111//7111 -f 6331//6331 6342//6342 7462//7462 -f 7462//7462 6342//6342 6344//6344 -f 7462//7462 6344//6344 7463//7463 -f 7463//7463 6344//6344 6346//6346 -f 7463//7463 6346//6346 7464//7464 -f 7464//7464 6346//6346 6348//6348 -f 6348//6348 6349//6349 7464//7464 -f 7464//7464 6349//6349 7465//7465 -f 7464//7464 7465//7465 7115//7115 -f 7115//7115 7465//7465 7114//7114 -f 6356//6356 7466//7466 6354//6354 -f 6354//6354 7466//7466 7465//7465 -f 6354//6354 7465//7465 6352//6352 -f 6352//6352 7465//7465 6349//6349 -f 6356//6356 6357//6357 7466//7466 -f 7466//7466 6357//6357 7467//7467 -f 7466//7466 7467//7467 7119//7119 -f 7119//7119 7467//7467 7118//7118 -f 6357//6357 6360//6360 7467//7467 -f 7467//7467 6360//6360 6362//6362 -f 7467//7467 6362//6362 7468//7468 -f 7468//7468 6362//6362 6364//6364 -f 7468//7468 6364//6364 7469//7469 -f 6364//6364 6366//6366 7469//7469 -f 7469//7469 6366//6366 6367//6367 -f 7469//7469 6367//6367 7470//7470 -f 7470//7470 6367//6367 6370//6370 -f 7470//7470 6370//6370 7471//7471 -f 6370//6370 6372//6372 7471//7471 -f 7471//7471 6372//6372 6374//6374 -f 7471//7471 6374//6374 7472//7472 -f 7472//7472 6374//6374 6377//6377 -f 7472//7472 6377//6377 7473//7473 -f 7473//7473 6377//6377 6379//6379 -f 6379//6379 6381//6381 7473//7473 -f 7473//7473 6381//6381 7474//7474 -f 7473//7473 7474//7474 7129//7129 -f 7129//7129 7474//7474 7132//7132 -f 6385//6385 7475//7475 6387//6387 -f 6387//6387 7475//7475 7474//7474 -f 6387//6387 7474//7474 6388//6388 -f 6388//6388 7474//7474 6381//6381 -f 6385//6385 6384//6384 7475//7475 -f 7475//7475 6384//6384 7476//7476 -f 7475//7475 7476//7476 7133//7133 -f 7133//7133 7476//7476 7136//7136 -f 6384//6384 6389//6389 7476//7476 -f 7476//7476 6389//6389 6391//6391 -f 7476//7476 6391//6391 7477//7477 -f 7477//7477 6391//6391 6393//6393 -f 7477//7477 6393//6393 7478//7478 -f 6393//6393 6395//6395 7478//7478 -f 7478//7478 6395//6395 6398//6398 -f 7478//7478 6398//6398 7479//7479 -f 7479//7479 6398//6398 6400//6400 -f 7479//7479 6400//6400 7480//7480 -f 6400//6400 6403//6403 7480//7480 -f 7480//7480 6403//6403 6405//6405 -f 7480//7480 6405//6405 7481//7481 -f 7481//7481 6405//6405 6407//6407 -f 7481//7481 6407//6407 7482//7482 -f 7482//7482 6407//6407 6417//6417 -f 6417//6417 6416//6416 7482//7482 -f 7482//7482 6416//6416 7483//7483 -f 7482//7482 7483//7483 7151//7151 -f 7151//7151 7483//7483 7150//7150 -f 6410//6410 7484//7484 6412//6412 -f 6412//6412 7484//7484 7483//7483 -f 6412//6412 7483//7483 6414//6414 -f 6414//6414 7483//7483 6416//6416 -f 6410//6410 6409//6409 7484//7484 -f 7484//7484 6409//6409 7485//7485 -f 7484//7484 7485//7485 7155//7155 -f 7155//7155 7485//7485 7154//7154 -f 6409//6409 6420//6420 7485//7485 -f 7485//7485 6420//6420 6422//6422 -f 7485//7485 6422//6422 7486//7486 -f 7486//7486 6422//6422 6424//6424 -f 7486//7486 6424//6424 7487//7487 -f 6424//6424 6426//6426 7487//7487 -f 7487//7487 6426//6426 6427//6427 -f 7487//7487 6427//6427 7488//7488 -f 7488//7488 6427//6427 6430//6430 -f 7488//7488 6430//6430 7489//7489 -f 6430//6430 6432//6432 7489//7489 -f 7489//7489 6432//6432 6434//6434 -f 7489//7489 6434//6434 7490//7490 -f 7490//7490 6434//6434 6437//6437 -f 7490//7490 6437//6437 7491//7491 -f 7491//7491 6437//6437 6439//6439 -f 6439//6439 6441//6441 7491//7491 -f 7491//7491 6441//6441 7492//7492 -f 7491//7491 7492//7492 7165//7165 -f 7165//7165 7492//7492 7168//7168 -f 6445//6445 7493//7493 6447//6447 -f 6447//6447 7493//7493 7492//7492 -f 6447//6447 7492//7492 6448//6448 -f 6448//6448 7492//7492 6441//6441 -f 6445//6445 6444//6444 7493//7493 -f 7493//7493 6444//6444 7494//7494 -f 7493//7493 7494//7494 7169//7169 -f 7169//7169 7494//7494 7172//7172 -f 6444//6444 6449//6449 7494//7494 -f 7494//7494 6449//6449 6451//6451 -f 7494//7494 6451//6451 7495//7495 -f 7495//7495 6451//6451 6453//6453 -f 7495//7495 6453//6453 7496//7496 -f 6453//6453 6455//6455 7496//7496 -f 7496//7496 6455//6455 6461//6461 -f 7496//7496 6461//6461 7334//7334 -f 7334//7334 6461//6461 6459//6459 -f 7334//7334 6459//6459 7335//7335 -f 6487//6487 7497//7497 6489//6489 -f 6489//6489 7497//7497 7498//7498 -f 6489//6489 7498//7498 6491//6491 -f 6491//6491 7498//7498 7180//7180 -f 6491//6491 7180//7180 6493//6493 -f 6493//6493 7180//7180 7179//7179 -f 6493//6493 7179//7179 6494//6494 -f 6494//6494 7179//7179 7335//7335 -f 6494//6494 7335//7335 6457//6457 -f 6457//6457 7335//7335 6459//6459 -f 7329//7329 7328//7328 7499//7499 -f 7499//7499 7328//7328 7327//7327 -f 7327//7327 7331//7331 7499//7499 -f 7499//7499 7331//7331 7332//7332 -f 7499//7499 7332//7332 7500//7500 -f 7500//7500 7332//7332 7333//7333 -f 7500//7500 7333//7333 6807//6807 -f 7319//7319 7326//7326 7501//7501 -f 7501//7501 7326//7326 7325//7325 -f 7501//7501 7325//7325 7499//7499 -f 7499//7499 7325//7325 7330//7330 -f 7499//7499 7330//7330 7329//7329 -f 7502//7502 7324//7324 7323//7323 -f 7323//7323 7322//7322 7502//7502 -f 7502//7502 7322//7322 7321//7321 -f 7502//7502 7321//7321 7501//7501 -f 7501//7501 7321//7321 7320//7320 -f 7501//7501 7320//7320 7319//7319 -f 7313//7313 7312//7312 7503//7503 -f 7503//7503 7312//7312 7318//7318 -f 7503//7503 7318//7318 7502//7502 -f 7502//7502 7318//7318 7317//7317 -f 7502//7502 7317//7317 7324//7324 -f 7309//7309 7316//7316 7504//7504 -f 7504//7504 7316//7316 7315//7315 -f 7504//7504 7315//7315 7503//7503 -f 7503//7503 7315//7315 7314//7314 -f 7503//7503 7314//7314 7313//7313 -f 7505//7505 7307//7307 7305//7305 -f 7311//7311 7310//7310 7504//7504 -f 7504//7504 7310//7310 7308//7308 -f 7504//7504 7308//7308 7309//7309 -f 7505//7505 7305//7305 7504//7504 -f 7504//7504 7305//7305 7306//7306 -f 7504//7504 7306//7306 7311//7311 -f 7298//7298 7304//7304 7506//7506 -f 7506//7506 7304//7304 7303//7303 -f 7303//7303 7302//7302 7506//7506 -f 7506//7506 7302//7302 7301//7301 -f 7506//7506 7301//7301 7505//7505 -f 7505//7505 7301//7301 7300//7300 -f 7505//7505 7300//7300 7307//7307 -f 7296//7296 7295//7295 7507//7507 -f 7507//7507 7295//7295 7294//7294 -f 7507//7507 7294//7294 7506//7506 -f 7506//7506 7294//7294 7299//7299 -f 7506//7506 7299//7299 7298//7298 -f 7288//7288 7287//7287 7508//7508 -f 7508//7508 7287//7287 7286//7286 -f 7508//7508 7286//7286 7507//7507 -f 7507//7507 7286//7286 7297//7297 -f 7507//7507 7297//7297 7296//7296 -f 7291//7291 7290//7290 7508//7508 -f 7508//7508 7290//7290 7289//7289 -f 7508//7508 7289//7289 7288//7288 -f 7280//7280 7281//7281 7509//7509 -f 7509//7509 7281//7281 7293//7293 -f 7509//7509 7293//7293 7508//7508 -f 7508//7508 7293//7293 7292//7292 -f 7508//7508 7292//7292 7291//7291 -f 7510//7510 7284//7284 7283//7283 -f 7283//7283 7282//7282 7510//7510 -f 7510//7510 7282//7282 7278//7278 -f 7510//7510 7278//7278 7509//7509 -f 7509//7509 7278//7278 7279//7279 -f 7509//7509 7279//7279 7280//7280 -f 7277//7277 7276//7276 6806//6806 -f 6806//6806 7276//7276 7275//7275 -f 6806//6806 7275//7275 6807//6807 -f 6807//6807 7275//7275 7274//7274 -f 6807//6807 7274//7274 7510//7510 -f 7510//7510 7274//7274 7285//7285 -f 7510//7510 7285//7285 7284//7284 -f 7272//7272 7271//7271 6795//6795 -f 6795//6795 7271//7271 7270//7270 -f 6795//6795 7270//7270 6797//6797 -f 6797//6797 7270//7270 6799//6799 -f 6799//6799 7270//7270 7269//7269 -f 6799//6799 7269//7269 6800//6800 -f 7269//7269 7268//7268 6800//6800 -f 6800//6800 7268//7268 7267//7267 -f 6800//6800 7267//7267 6802//6802 -f 6802//6802 7267//7267 7277//7277 -f 6802//6802 7277//7277 6804//6804 -f 6804//6804 7277//7277 6806//6806 -f 7262//7262 7263//7263 6812//6812 -f 6812//6812 7263//7263 7264//7264 -f 6812//6812 7264//7264 6813//6813 -f 6813//6813 7264//7264 7273//7273 -f 6813//6813 7273//7273 6814//6814 -f 6814//6814 7273//7273 7272//7272 -f 6814//6814 7272//7272 6794//6794 -f 6794//6794 7272//7272 6795//6795 -f 6791//6791 7254//7254 6792//6792 -f 6792//6792 7254//7254 7255//7255 -f 6792//6792 7255//7255 6816//6816 -f 6816//6816 7255//7255 6817//6817 -f 6817//6817 7255//7255 7259//7259 -f 6817//6817 7259//7259 6818//6818 -f 7259//7259 7261//7261 6818//6818 -f 6818//6818 7261//7261 7265//7265 -f 6818//6818 7265//7265 6809//6809 -f 6809//6809 7265//7265 7262//7262 -f 6809//6809 7262//7262 6811//6811 -f 6811//6811 7262//7262 6812//6812 -f 7181//7181 7249//7249 6827//6827 -f 6827//6827 7249//7249 7251//7251 -f 6827//6827 7251//7251 6821//6821 -f 6821//6821 7251//7251 7258//7258 -f 6821//6821 7258//7258 6819//6819 -f 6819//6819 7258//7258 7257//7257 -f 6819//6819 7257//7257 6791//6791 -f 6791//6791 7257//7257 7256//7256 -f 6791//6791 7256//7256 7254//7254 -f 7247//7247 6828//6828 7248//7248 -f 7248//7248 6828//6828 7242//7242 -f 6827//6827 6826//6826 7181//7181 -f 7181//7181 6826//6826 6825//6825 -f 7181//7181 6825//6825 7182//7182 -f 7182//7182 6825//6825 6824//6824 -f 7182//7182 6824//6824 7246//7246 -f 7246//7246 6824//6824 6830//6830 -f 7246//7246 6830//6830 7247//7247 -f 7247//7247 6830//6830 6829//6829 -f 7247//7247 6829//6829 6828//6828 -f 6835//6835 7243//7243 6788//6788 -f 6788//6788 7243//7243 7242//7242 -f 6788//6788 7242//7242 6789//6789 -f 6789//6789 7242//7242 6828//6828 -f 6840//6840 7238//7238 6834//6834 -f 6834//6834 7238//7238 7240//7240 -f 6834//6834 7240//7240 6833//6833 -f 6833//6833 7240//7240 7245//7245 -f 6833//6833 7245//7245 6835//6835 -f 6835//6835 7245//7245 7244//7244 -f 6835//6835 7244//7244 7243//7243 -f 7223//7223 7222//7222 6850//6850 -f 6850//6850 7222//7222 7229//7229 -f 6850//6850 7229//7229 6851//6851 -f 6851//6851 7229//7229 7233//7233 -f 6851//6851 7233//7233 6842//6842 -f 6842//6842 7233//7233 7232//7232 -f 6842//6842 7232//7232 6843//6843 -f 6843//6843 7232//7232 7231//7231 -f 6843//6843 7231//7231 6837//6837 -f 6837//6837 7231//7231 7237//7237 -f 6837//6837 7237//7237 6839//6839 -f 6839//6839 7237//7237 7235//7235 -f 6839//6839 7235//7235 6840//6840 -f 6840//6840 7235//7235 7234//7234 -f 6840//6840 7234//7234 7238//7238 -f 7225//7225 6854//6854 7227//7227 -f 7227//7227 6854//6854 6853//6853 -f 7227//7227 6853//6853 7228//7228 -f 7228//7228 6853//6853 6860//6860 -f 7228//7228 6860//6860 7217//7217 -f 6850//6850 6848//6848 7223//7223 -f 7223//7223 6848//6848 6847//6847 -f 7223//7223 6847//6847 7225//7225 -f 7225//7225 6847//6847 6846//6846 -f 7225//7225 6846//6846 6854//6854 -f 6855//6855 7218//7218 6858//6858 -f 6858//6858 7218//7218 7217//7217 -f 6858//6858 7217//7217 6859//6859 -f 6859//6859 7217//7217 6860//6860 -f 6867//6867 7211//7211 7213//7213 -f 6867//6867 7213//7213 6868//6868 -f 6868//6868 7213//7213 7216//7216 -f 6868//6868 7216//7216 6870//6870 -f 6870//6870 7216//7216 6871//6871 -f 6871//6871 7216//7216 7215//7215 -f 6871//6871 7215//7215 6785//6785 -f 6785//6785 7215//7215 7214//7214 -f 6785//6785 7214//7214 6786//6786 -f 6786//6786 7214//7214 7221//7221 -f 6786//6786 7221//7221 6855//6855 -f 6855//6855 7221//7221 7220//7220 -f 6855//6855 7220//7220 7218//7218 -f 7211//7211 6867//6867 7206//7206 -f 7206//7206 6867//6867 6861//6861 -f 7206//7206 6861//6861 7207//7207 -f 7207//7207 6861//6861 6863//6863 -f 7207//7207 6863//6863 7209//7209 -f 7209//7209 6863//6863 6865//6865 -f 7209//7209 6865//6865 7210//7210 -f 7210//7210 6865//6865 6782//6782 -f 7210//7210 6782//6782 7184//7184 -f 7184//7184 6782//6782 6876//6876 -f 7184//7184 6876//6876 7185//7185 -f 7204//7204 6878//6878 7205//7205 -f 7205//7205 6878//6878 6877//6877 -f 7205//7205 6877//6877 7202//7202 -f 6876//6876 6875//6875 7185//7185 -f 7185//7185 6875//6875 6873//6873 -f 7185//7185 6873//6873 7204//7204 -f 7204//7204 6873//6873 6872//6872 -f 7204//7204 6872//6872 6878//6878 -f 6879//6879 6882//6882 7188//7188 -f 7188//7188 6882//6882 6883//6883 -f 7188//7188 6883//6883 7197//7197 -f 7197//7197 6883//6883 6884//6884 -f 7197//7197 6884//6884 7198//7198 -f 7188//7188 7187//7187 6879//6879 -f 6879//6879 7187//7187 7203//7203 -f 6879//6879 7203//7203 6880//6880 -f 6880//6880 7203//7203 7202//7202 -f 6880//6880 7202//7202 6881//6881 -f 6881//6881 7202//7202 6877//6877 -f 7198//7198 6884//6884 7200//7200 -f 7200//7200 6884//6884 6781//6781 -f 7200//7200 6781//6781 7190//7190 -f 7190//7190 6781//6781 6780//6780 -f 7190//7190 6780//6780 7191//7191 -f 7191//7191 6780//6780 6888//6888 -f 7191//7191 6888//6888 7193//7193 -f 6888//6888 6887//6887 7193//7193 -f 7193//7193 6887//6887 6886//6886 -f 7193//7193 6886//6886 7195//7195 -f 7195//7195 6886//6886 6885//6885 -f 7195//7195 6885//6885 7196//7196 -f 7196//7196 6885//6885 6891//6891 -f 7196//7196 6891//6891 7340//7340 -f 7340//7340 6891//6891 6890//6890 -f 7340//7340 6890//6890 5949//5949 -f 5942//5942 6914//6914 6913//6913 -f 6913//6913 6918//6918 5942//5942 -f 5942//5942 6918//6918 6917//6917 -f 5942//5942 6917//6917 5960//5960 -f 5960//5960 6917//6917 5962//5962 -f 5956//5956 6912//6912 6911//6911 -f 6911//6911 6910//6910 5956//5956 -f 5956//5956 6910//6910 6916//6916 -f 5956//5956 6916//6916 5942//5942 -f 5942//5942 6916//6916 6915//6915 -f 5942//5942 6915//6915 6914//6914 -f 6900//6900 6907//6907 5953//5953 -f 5953//5953 6907//6907 6906//6906 -f 6906//6906 6905//6905 5953//5953 -f 5953//5953 6905//6905 6909//6909 -f 5953//5953 6909//6909 5956//5956 -f 5956//5956 6909//6909 6908//6908 -f 5956//5956 6908//6908 6912//6912 -f 6900//6900 5953//5953 6901//6901 -f 6901//6901 5953//5953 5951//5951 -f 6901//6901 5951//5951 6902//6902 -f 6897//6897 6896//6896 5945//5945 -f 5945//5945 6896//6896 6904//6904 -f 5945//5945 6904//6904 5951//5951 -f 5951//5951 6904//6904 6903//6903 -f 5951//5951 6903//6903 6902//6902 -f 6890//6890 6889//6889 5949//5949 -f 5949//5949 6889//6889 6895//6895 -f 5949//5949 6895//6895 5947//5947 -f 5947//5947 6895//6895 6894//6894 -f 5947//5947 6894//6894 6893//6893 -f 6893//6893 6892//6892 5947//5947 -f 5947//5947 6892//6892 6899//6899 -f 5947//5947 6899//6899 5945//5945 -f 5945//5945 6899//6899 6898//6898 -f 5945//5945 6898//6898 6897//6897 -f 7511//7511 7512//7512 7513//7513 -f 7513//7513 7514//7514 7511//7511 -f 7511//7511 7514//7514 7515//7515 -f 7511//7511 7515//7515 7516//7516 -f 7517//7517 7518//7518 7519//7519 -f 7520//7520 7521//7521 7522//7522 -f 7523//7523 7524//7524 7525//7525 -f 7526//7526 7527//7527 7528//7528 -f 7516//7516 7515//7515 7529//7529 -f 7529//7529 7515//7515 7530//7530 -f 7527//7527 7531//7531 7528//7528 -f 7528//7528 7531//7531 7532//7532 -f 7528//7528 7532//7532 7533//7533 -f 7534//7534 5930//5930 5929//5929 -f 5933//5933 5932//5932 7535//7535 -f 7535//7535 5932//5932 7536//7536 -f 7536//7536 7537//7537 7535//7535 -f 7535//7535 7537//7537 7538//7538 -f 7535//7535 7538//7538 7539//7539 -f 7525//7525 7540//7540 7539//7539 -f 7525//7525 7524//7524 7540//7540 -f 7540//7540 7524//7524 5924//5924 -f 7540//7540 5924//5924 5923//5923 -f 5927//5927 5926//5926 7541//7541 -f 7541//7541 5926//5926 7542//7542 -f 7543//7543 7513//7513 7512//7512 -f 5929//5929 7526//7526 7534//7534 -f 7534//7534 7526//7526 7528//7528 -f 7534//7534 7528//7528 7544//7544 -f 7544//7544 7528//7528 7533//7533 -f 7544//7544 7533//7533 7545//7545 -f 5925//5925 5924//5924 7546//7546 -f 7546//7546 5924//5924 7524//7524 -f 7546//7546 7524//7524 7547//7547 -f 7547//7547 7524//7524 7523//7523 -f 7547//7547 7523//7523 7548//7548 -f 7549//7549 7538//7538 7550//7550 -f 7550//7550 7538//7538 7537//7537 -f 7550//7550 7537//7537 7551//7551 -f 7551//7551 7537//7537 7536//7536 -f 7551//7551 7536//7536 7552//7552 -f 7553//7553 7554//7554 7555//7555 -f 7556//7556 7554//7554 7557//7557 -f 7557//7557 7554//7554 7553//7553 -f 7557//7557 7553//7553 7558//7558 -f 5938//5938 5937//5937 7558//7558 -f 7558//7558 5937//5937 7559//7559 -f 7558//7558 7559//7559 7557//7557 -f 7557//7557 7559//7559 7560//7560 -f 7557//7557 7560//7560 7556//7556 -f 7556//7556 7560//7560 7561//7561 -f 7562//7562 7563//7563 7564//7564 -f 7564//7564 7563//7563 7565//7565 -f 7564//7564 7565//7565 7530//7530 -f 7530//7530 7565//7565 7566//7566 -f 7530//7530 7566//7566 7529//7529 -f 7515//7515 7514//7514 7530//7530 -f 7530//7530 7514//7514 7567//7567 -f 7530//7530 7567//7567 7564//7564 -f 7564//7564 7567//7567 7568//7568 -f 7564//7564 7568//7568 7562//7562 -f 7562//7562 7568//7568 7569//7569 -f 7514//7514 7513//7513 7567//7567 -f 7567//7567 7513//7513 7543//7543 -f 7567//7567 7543//7543 7568//7568 -f 7568//7568 7543//7543 7570//7570 -f 7568//7568 7570//7570 7569//7569 -f 7569//7569 7570//7570 7571//7571 -f 7572//7572 7573//7573 7574//7574 -f 7574//7574 7573//7573 7575//7575 -f 7574//7574 7575//7575 7576//7576 -f 7576//7576 7575//7575 7519//7519 -f 7577//7577 7549//7549 7578//7578 -f 7578//7578 7549//7549 7550//7550 -f 7578//7578 7550//7550 7579//7579 -f 7579//7579 7550//7550 7551//7551 -f 7579//7579 7551//7551 7580//7580 -f 7580//7580 7551//7551 7552//7552 -f 7580//7580 7552//7552 7581//7581 -f 7582//7582 7580//7580 7583//7583 -f 7583//7583 7580//7580 7581//7581 -f 7583//7583 7581//7581 7584//7584 -f 7585//7585 7584//7584 7586//7586 -f 7586//7586 7584//7584 7581//7581 -f 7586//7586 7581//7581 7587//7587 -f 7587//7587 7581//7581 7552//7552 -f 7587//7587 7552//7552 7588//7588 -f 7588//7588 7552//7552 7536//7536 -f 7588//7588 7536//7536 5931//5931 -f 5931//5931 7536//7536 5932//5932 -f 5931//5931 5930//5930 7588//7588 -f 7588//7588 5930//5930 7534//7534 -f 7588//7588 7534//7534 7587//7587 -f 7587//7587 7534//7534 7544//7544 -f 7587//7587 7544//7544 7586//7586 -f 7586//7586 7544//7544 7545//7545 -f 7586//7586 7545//7545 7585//7585 -f 7585//7585 7545//7545 7589//7589 -f 7555//7555 7590//7590 7591//7591 -f 5939//5939 5938//5938 7531//7531 -f 7531//7531 5938//5938 7558//7558 -f 7531//7531 7558//7558 7532//7532 -f 7532//7532 7558//7558 7553//7553 -f 7532//7532 7553//7553 7533//7533 -f 7533//7533 7553//7553 7555//7555 -f 7533//7533 7555//7555 7545//7545 -f 7545//7545 7555//7555 7591//7591 -f 7545//7545 7591//7591 7589//7589 -f 7592//7592 7593//7593 7561//7561 -f 7561//7561 7593//7593 7594//7594 -f 7561//7561 7594//7594 7556//7556 -f 7556//7556 7594//7594 7595//7595 -f 7556//7556 7595//7595 7554//7554 -f 7554//7554 7595//7595 7596//7596 -f 7554//7554 7596//7596 7555//7555 -f 7555//7555 7596//7596 7597//7597 -f 7555//7555 7597//7597 7590//7590 -f 7521//7521 7592//7592 7522//7522 -f 7522//7522 7592//7592 7561//7561 -f 7522//7522 7561//7561 7598//7598 -f 7598//7598 7561//7561 7560//7560 -f 7598//7598 7560//7560 7599//7599 -f 7599//7599 7560//7560 7559//7559 -f 7599//7599 7559//7559 5936//5936 -f 5936//5936 7559//7559 5937//5937 -f 7600//7600 7520//7520 7601//7601 -f 7601//7601 7520//7520 7522//7522 -f 7601//7601 7522//7522 7602//7602 -f 7602//7602 7522//7522 7598//7598 -f 7602//7602 7598//7598 7603//7603 -f 7603//7603 7598//7598 7599//7599 -f 7603//7603 7599//7599 7604//7604 -f 7604//7604 7599//7599 5936//5936 -f 7604//7604 5936//5936 5935//5935 -f 7604//7604 7605//7605 7603//7603 -f 7603//7603 7605//7605 7606//7606 -f 7603//7603 7606//7606 7602//7602 -f 7602//7602 7606//7606 7607//7607 -f 7602//7602 7607//7607 7601//7601 -f 7601//7601 7607//7607 7608//7608 -f 7601//7601 7608//7608 7600//7600 -f 7600//7600 7608//7608 7609//7609 -f 7605//7605 7529//7529 7606//7606 -f 7606//7606 7529//7529 7566//7566 -f 7606//7606 7566//7566 7607//7607 -f 7607//7607 7566//7566 7565//7565 -f 7607//7607 7565//7565 7608//7608 -f 7608//7608 7565//7565 7563//7563 -f 7608//7608 7563//7563 7609//7609 -f 7609//7609 7563//7563 7610//7610 -f 7611//7611 7612//7612 7571//7571 -f 7571//7571 7612//7612 7613//7613 -f 7571//7571 7613//7613 7569//7569 -f 7569//7569 7613//7613 7614//7614 -f 7569//7569 7614//7614 7562//7562 -f 7562//7562 7614//7614 7615//7615 -f 7562//7562 7615//7615 7563//7563 -f 7563//7563 7615//7615 7616//7616 -f 7563//7563 7616//7616 7610//7610 -f 7617//7617 7611//7611 7576//7576 -f 7576//7576 7611//7611 7571//7571 -f 7576//7576 7571//7571 7574//7574 -f 7574//7574 7571//7571 7570//7570 -f 7574//7574 7570//7570 7572//7572 -f 7572//7572 7570//7570 7543//7543 -f 7572//7572 7543//7543 7618//7618 -f 7618//7618 7543//7543 7512//7512 -f 7519//7519 7518//7518 7576//7576 -f 7576//7576 7518//7518 7619//7619 -f 7576//7576 7619//7619 7617//7617 -f 7620//7620 7517//7517 7621//7621 -f 7621//7621 7517//7517 7519//7519 -f 7621//7621 7519//7519 7622//7622 -f 7622//7622 7519//7519 7575//7575 -f 7622//7622 7575//7575 7542//7542 -f 7542//7542 7575//7575 7573//7573 -f 7542//7542 7573//7573 7541//7541 -f 7541//7541 7573//7573 7572//7572 -f 7541//7541 7572//7572 7623//7623 -f 7623//7623 7572//7572 7618//7618 -f 5926//5926 5925//5925 7542//7542 -f 7542//7542 5925//5925 7546//7546 -f 7542//7542 7546//7546 7622//7622 -f 7622//7622 7546//7546 7547//7547 -f 7622//7622 7547//7547 7621//7621 -f 7621//7621 7547//7547 7548//7548 -f 7621//7621 7548//7548 7620//7620 -f 7620//7620 7548//7548 7624//7624 -f 7539//7539 7538//7538 7525//7525 -f 7525//7525 7538//7538 7549//7549 -f 7525//7525 7549//7549 7523//7523 -f 7523//7523 7549//7549 7577//7577 -f 7523//7523 7577//7577 7548//7548 -f 7548//7548 7577//7577 7625//7625 -f 7548//7548 7625//7625 7624//7624 -f 7582//7582 7626//7626 7580//7580 -f 7580//7580 7626//7626 7627//7627 -f 7580//7580 7627//7627 7579//7579 -f 7579//7579 7627//7627 7628//7628 -f 7579//7579 7628//7628 7578//7578 -f 7578//7578 7628//7628 7629//7629 -f 7578//7578 7629//7629 7577//7577 -f 7577//7577 7629//7629 7630//7630 -f 7577//7577 7630//7630 7625//7625 -f 7626//7626 7631//7631 7632//7632 -f 7584//7584 7633//7633 7583//7583 -f 7583//7583 7633//7633 7631//7631 -f 7583//7583 7631//7631 7582//7582 -f 7582//7582 7631//7631 7626//7626 -f 7584//7584 7585//7585 7633//7633 -f 7633//7633 7585//7585 7589//7589 -f 7633//7633 7589//7589 7634//7634 -f 7589//7589 7591//7591 7634//7634 -f 7634//7634 7591//7591 7590//7590 -f 7634//7634 7590//7590 7635//7635 -f 7595//7595 7636//7636 7596//7596 -f 7596//7596 7636//7636 7635//7635 -f 7596//7596 7635//7635 7597//7597 -f 7597//7597 7635//7635 7590//7590 -f 7595//7595 7594//7594 7636//7636 -f 7636//7636 7594//7594 7593//7593 -f 7636//7636 7593//7593 7637//7637 -f 7593//7593 7592//7592 7637//7637 -f 7637//7637 7592//7592 7521//7521 -f 7637//7637 7521//7521 7638//7638 -f 7521//7521 7520//7520 7638//7638 -f 7638//7638 7520//7520 7600//7600 -f 7638//7638 7600//7600 7639//7639 -f 7600//7600 7609//7609 7639//7639 -f 7639//7639 7609//7609 7610//7610 -f 7639//7639 7610//7610 7640//7640 -f 7614//7614 7641//7641 7615//7615 -f 7615//7615 7641//7641 7640//7640 -f 7615//7615 7640//7640 7616//7616 -f 7616//7616 7640//7640 7610//7610 -f 7614//7614 7613//7613 7641//7641 -f 7641//7641 7613//7613 7612//7612 -f 7641//7641 7612//7612 7642//7642 -f 7612//7612 7611//7611 7642//7642 -f 7642//7642 7611//7611 7617//7617 -f 7642//7642 7617//7617 7643//7643 -f 7517//7517 7644//7644 7518//7518 -f 7518//7518 7644//7644 7643//7643 -f 7518//7518 7643//7643 7619//7619 -f 7619//7619 7643//7643 7617//7617 -f 7517//7517 7620//7620 7644//7644 -f 7644//7644 7620//7620 7624//7624 -f 7644//7644 7624//7624 7645//7645 -f 7624//7624 7625//7625 7645//7645 -f 7645//7645 7625//7625 7630//7630 -f 7645//7645 7630//7630 7646//7646 -f 7630//7630 7629//7629 7646//7646 -f 7646//7646 7629//7629 7628//7628 -f 7646//7646 7628//7628 7632//7632 -f 7632//7632 7628//7628 7627//7627 -f 7632//7632 7627//7627 7626//7626 -f 7647//7647 7648//7648 7649//7649 -f 7649//7649 7648//7648 7650//7650 -f 7649//7649 7650//7650 7651//7651 -f 7651//7651 7650//7650 7652//7652 -f 7651//7651 7652//7652 7653//7653 -f 7654//7654 7655//7655 7656//7656 -f 7656//7656 7655//7655 7657//7657 -f 7656//7656 7657//7657 7658//7658 -f 7658//7658 7657//7657 7659//7659 -f 7658//7658 7659//7659 7647//7647 -f 7647//7647 7659//7659 7660//7660 -f 7647//7647 7660//7660 7648//7648 -f 7661//7661 7662//7662 7663//7663 -f 7663//7663 7662//7662 7664//7664 -f 7663//7663 7664//7664 7665//7665 -f 7665//7665 7664//7664 7666//7666 -f 7665//7665 7666//7666 7654//7654 -f 7654//7654 7666//7666 7667//7667 -f 7654//7654 7667//7667 7655//7655 -f 7652//7652 7668//7668 7653//7653 -f 7653//7653 7668//7668 7669//7669 -f 7653//7653 7669//7669 7670//7670 -f 7670//7670 7669//7669 7671//7671 -f 7670//7670 7671//7671 7672//7672 -f 7672//7672 7671//7671 7673//7673 -f 7672//7672 7673//7673 7661//7661 -f 7661//7661 7673//7673 7674//7674 -f 7661//7661 7674//7674 7662//7662 -f 6807//6807 7510//7510 7651//7651 -f 7651//7651 7510//7510 7509//7509 -f 7651//7651 7509//7509 7649//7649 -f 7649//7649 7509//7509 7508//7508 -f 7649//7649 7508//7508 7647//7647 -f 7647//7647 7508//7508 7507//7507 -f 7647//7647 7507//7507 7658//7658 -f 7658//7658 7507//7507 7506//7506 -f 7658//7658 7506//7506 7656//7656 -f 7656//7656 7506//7506 7505//7505 -f 7656//7656 7505//7505 7654//7654 -f 7654//7654 7505//7505 7504//7504 -f 7654//7654 7504//7504 7665//7665 -f 7665//7665 7504//7504 7503//7503 -f 7665//7665 7503//7503 7663//7663 -f 7663//7663 7503//7503 7502//7502 -f 7663//7663 7502//7502 7661//7661 -f 7661//7661 7502//7502 7501//7501 -f 7661//7661 7501//7501 7672//7672 -f 7672//7672 7501//7501 7499//7499 -f 7672//7672 7499//7499 7670//7670 -f 7670//7670 7499//7499 7500//7500 -f 7670//7670 7500//7500 7653//7653 -f 7653//7653 7500//7500 6807//6807 -f 7653//7653 6807//6807 7651//7651 -f 6926//6926 6930//6930 7675//7675 -f 7675//7675 6930//6930 6929//6929 -f 7675//7675 6929//6929 6928//6928 -f 7180//7180 7498//7498 7676//7676 -f 7676//7676 7498//7498 7497//7497 -f 7676//7676 7497//7497 6487//6487 -f 7180//7180 7676//7676 7178//7178 -f 7178//7178 7676//7676 7677//7677 -f 7178//7178 7677//7677 7339//7339 -f 6928//6928 7338//7338 7675//7675 -f 7675//7675 7338//7338 7337//7337 -f 7675//7675 7337//7337 7677//7677 -f 7677//7677 7337//7337 7336//7336 -f 7677//7677 7336//7336 7339//7339 -f 6464//6464 6919//6919 7678//7678 -f 7678//7678 6919//6919 6778//6778 -f 7678//7678 6778//6778 7679//7679 -f 7679//7679 6778//6778 6777//6777 -f 6777//6777 6921//6921 7679//7679 -f 7679//7679 6921//6921 6923//6923 -f 7679//7679 6923//6923 7675//7675 -f 7675//7675 6923//6923 7173//7173 -f 7675//7675 7173//7173 6926//6926 -f 7680//7680 7679//7679 7681//7681 -f 7681//7681 7679//7679 7675//7675 -f 7681//7681 7675//7675 7682//7682 -f 7682//7682 7675//7675 7677//7677 -f 7682//7682 7677//7677 7683//7683 -f 7683//7683 7677//7677 7676//7676 -f 7683//7683 7676//7676 7684//7684 -f 7684//7684 7676//7676 6487//6487 -f 7684//7684 6487//6487 7685//7685 -f 6487//6487 6485//6485 7685//7685 -f 7685//7685 6485//6485 6481//6481 -f 7685//7685 6481//6481 7686//7686 -f 7686//7686 6481//6481 6476//6476 -f 7686//7686 6476//6476 7687//7687 -f 7687//7687 6476//6476 6471//6471 -f 7687//7687 6471//6471 7688//7688 -f 7688//7688 6471//6471 6473//6473 -f 7688//7688 6473//6473 7689//7689 -f 7689//7689 6473//6473 6469//6469 -f 7689//7689 6469//6469 7690//7690 -f 7690//7690 6469//6469 6465//6465 -f 7690//7690 6465//6465 7691//7691 -f 7691//7691 6465//6465 6464//6464 -f 7691//7691 6464//6464 7680//7680 -f 7680//7680 6464//6464 7678//7678 -f 7680//7680 7678//7678 7679//7679 -f 7690//7690 7691//7691 7692//7692 -f 7692//7692 7691//7691 7680//7680 -f 7692//7692 7680//7680 7681//7681 -f 7687//7687 7688//7688 7692//7692 -f 7692//7692 7688//7688 7689//7689 -f 7692//7692 7689//7689 7690//7690 -f 7684//7684 7685//7685 7692//7692 -f 7692//7692 7685//7685 7686//7686 -f 7692//7692 7686//7686 7687//7687 -f 7681//7681 7682//7682 7692//7692 -f 7692//7692 7682//7682 7683//7683 -f 7692//7692 7683//7683 7684//7684 -f 7632//7632 7664//7664 7646//7646 -f 7646//7646 7664//7664 7662//7662 -f 7646//7646 7662//7662 7645//7645 -f 7645//7645 7662//7662 7674//7674 -f 7645//7645 7674//7674 7644//7644 -f 7644//7644 7674//7674 7673//7673 -f 7644//7644 7673//7673 7643//7643 -f 7643//7643 7673//7673 7671//7671 -f 7643//7643 7671//7671 7642//7642 -f 7642//7642 7671//7671 7669//7669 -f 7642//7642 7669//7669 7641//7641 -f 7641//7641 7669//7669 7668//7668 -f 7641//7641 7668//7668 7640//7640 -f 7640//7640 7668//7668 7652//7652 -f 7640//7640 7652//7652 7639//7639 -f 7639//7639 7652//7652 7650//7650 -f 7639//7639 7650//7650 7638//7638 -f 7638//7638 7650//7650 7648//7648 -f 7638//7638 7648//7648 7637//7637 -f 7637//7637 7648//7648 7660//7660 -f 7637//7637 7660//7660 7636//7636 -f 7636//7636 7660//7660 7659//7659 -f 7636//7636 7659//7659 7635//7635 -f 7635//7635 7659//7659 7657//7657 -f 7635//7635 7657//7657 7634//7634 -f 7634//7634 7657//7657 7655//7655 -f 7634//7634 7655//7655 7633//7633 -f 7633//7633 7655//7655 7667//7667 -f 7633//7633 7667//7667 7631//7631 -f 7631//7631 7667//7667 7666//7666 -f 7631//7631 7666//7666 7632//7632 -f 7632//7632 7666//7666 7664//7664 -f 7511//7511 7693//7693 7512//7512 -f 7512//7512 7693//7693 7694//7694 -f 7512//7512 7694//7694 7618//7618 -f 7618//7618 7694//7694 7623//7623 -f 7623//7623 7694//7694 7695//7695 -f 7623//7623 7695//7695 7541//7541 -f 7541//7541 7695//7695 5927//5927 -f 5927//5927 7695//7695 7696//7696 -f 5927//5927 7696//7696 5922//5922 -f 5922//5922 7696//7696 5923//5923 -f 5923//5923 7696//7696 7697//7697 -f 5923//5923 7697//7697 7540//7540 -f 7540//7540 7697//7697 7539//7539 -f 7539//7539 7697//7697 7698//7698 -f 7539//7539 7698//7698 7535//7535 -f 7535//7535 7698//7698 5933//5933 -f 5933//5933 7698//7698 7699//7699 -f 5933//5933 7699//7699 5928//5928 -f 5928//5928 7699//7699 5929//5929 -f 5929//5929 7699//7699 7700//7700 -f 5929//5929 7700//7700 7526//7526 -f 7526//7526 7700//7700 7527//7527 -f 7527//7527 7700//7700 7701//7701 -f 7527//7527 7701//7701 7531//7531 -f 7531//7531 7701//7701 5939//5939 -f 5939//5939 7701//7701 7702//7702 -f 5939//5939 7702//7702 5934//5934 -f 5934//5934 7702//7702 5935//5935 -f 5935//5935 7702//7702 7703//7703 -f 5935//5935 7703//7703 7604//7604 -f 7604//7604 7703//7703 7605//7605 -f 7605//7605 7703//7703 7704//7704 -f 7605//7605 7704//7704 7529//7529 -f 7529//7529 7704//7704 7516//7516 -f 7516//7516 7704//7704 7693//7693 -f 7516//7516 7693//7693 7511//7511 -f 7698//7698 7697//7697 7699//7699 -f 7699//7699 7697//7697 7696//7696 -f 7704//7704 7703//7703 7693//7693 -f 7693//7693 7703//7703 7702//7702 -f 7701//7701 7700//7700 7702//7702 -f 7702//7702 7700//7700 7699//7699 -f 7702//7702 7699//7699 7693//7693 -f 7693//7693 7699//7699 7696//7696 -f 7693//7693 7696//7696 7694//7694 -f 7694//7694 7696//7696 7695//7695 -# 15388 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand.obj deleted file mode 100644 index a68e17890..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand.obj +++ /dev/null @@ -1,1392 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sablja.obj -# -# Vertices: 336 -# Faces: 704 -# -#### -vn -4.013411 -0.684889 4.573501 -v 0.077198 0.021500 0.044019 -vn -1.596641 -2.607676 2.575562 -v 0.077198 0.018500 0.044019 -vn -0.383869 -2.813968 3.075673 -v 0.080638 0.018500 0.045038 -vn -0.383869 -3.469219 3.075673 -v 0.080638 0.021500 0.045038 -vn 0.626285 -2.813969 3.035603 -v 0.084223 0.018500 0.044896 -vn 0.626285 -3.469218 3.035603 -v 0.084223 0.021500 0.044896 -vn 1.569817 -2.813965 2.672600 -v 0.087571 0.018500 0.043608 -vn 1.569817 -3.469221 2.672600 -v 0.087571 0.021500 0.043608 -vn 2.346350 -2.813968 2.025280 -v 0.090327 0.018500 0.041310 -vn 2.346350 -3.469217 2.025280 -v 0.090327 0.021500 0.041310 -vn 2.905138 -2.504320 0.679108 -v 0.092197 0.018500 0.038248 -vn 5.994989 -0.912319 0.192600 -v 0.092197 0.021500 0.038248 -vn -2.682949 -3.336426 1.605623 -v 0.079146 0.021500 0.046655 -vn 2.931146 -2.617995 0.785398 -v 0.101000 0.021500 0.067783 -vn 2.931146 -3.665192 0.785398 -v 0.077906 0.021500 0.107783 -vn 4.712389 -1.570796 -1.570796 -v 0.077906 0.021500 0.129940 -vn -4.712389 -1.570796 -1.570796 -v 0.055906 0.021500 0.129940 -vn -2.931146 -2.617994 -0.785398 -v 0.055906 0.021500 0.107783 -vn -2.770830 -3.209461 -1.476735 -v 0.079000 0.021500 0.067783 -vn 2.581446 -3.326361 -1.766846 -v 0.097227 0.021500 0.051367 -vn 2.766234 -2.579901 -1.208035 -v 0.100796 0.021500 0.055667 -vn 3.128155 -3.010694 -0.205029 -v 0.101000 0.021500 0.057220 -vn 3.042102 -3.322815 -0.736186 -v 0.092735 0.021500 0.041184 -vn 2.862110 -3.326361 -1.262512 -v 0.094510 0.021500 0.046483 -vn -2.939434 -3.365992 -1.051478 -v 0.080957 0.021500 0.063790 -vn -3.099712 -3.365992 -0.371031 -v 0.081976 0.021500 0.059462 -vn -3.104558 -3.365994 0.328023 -v 0.082007 0.021500 0.055016 -vn -2.953729 -3.365990 1.010627 -v 0.081048 0.021500 0.050674 -vn -0.000004 -3.665187 -3.034547 -v 0.082000 0.018500 0.043623 -vn -1.517272 -3.665192 -2.627994 -v 0.082750 0.018500 0.043422 -vn -1.517268 -3.665189 2.627998 -v 0.082750 0.018500 0.040824 -vn -0.000004 -3.665186 -3.034547 -v 0.082000 0.018500 0.027623 -vn -2.627993 -3.665201 1.517267 -v 0.083299 0.018500 0.041373 -vn -3.034550 -3.665180 -0.000002 -v 0.083500 0.018500 0.042123 -vn -1.517270 -3.665191 -2.627996 -v 0.082750 0.018500 0.027422 -vn 1.517276 -3.665200 2.627987 -v 0.089250 0.018500 0.032824 -vn -1.517268 -3.665192 -2.627998 -v 0.074750 0.018500 0.035422 -vn -2.138377 -3.283359 2.290730 -v 0.076398 0.018500 0.043159 -vn 0.000000 -3.665190 -3.034546 -v 0.074000 0.018500 0.035623 -vn -2.402188 -2.701069 1.904721 -v 0.072941 0.018500 0.040363 -vn 1.517268 -3.665189 -2.627998 -v 0.073250 0.018500 0.035422 -vn -2.968852 -2.835493 0.908921 -v 0.071482 0.018500 0.037343 -vn 2.627988 -3.665192 -1.517281 -v 0.072701 0.018500 0.034873 -vn 3.034543 -3.665198 0.000002 -v 0.072500 0.018500 0.034123 -vn -3.104744 -2.835494 -0.027968 -v 0.071000 0.018500 0.034024 -vn 2.627992 -3.665187 1.517279 -v 0.072701 0.018500 0.033373 -vn -2.951997 -2.835495 -0.962254 -v 0.071542 0.018500 0.030714 -vn 1.517272 -3.665192 2.627994 -v 0.073250 0.018500 0.032824 -vn 1.517272 -3.665198 -2.627991 -v 0.089250 0.018500 0.035422 -vn -2.627996 -3.665198 -1.517265 -v 0.083299 0.018500 0.042873 -vn 2.627996 -3.665186 -1.517273 -v 0.088701 0.018500 0.034873 -vn 3.034543 -3.665198 0.000002 -v 0.088500 0.018500 0.034123 -vn 2.628000 -3.665181 1.517272 -v 0.088701 0.018500 0.033373 -vn -0.000004 -3.665187 -3.034547 -v 0.090000 0.018500 0.035623 -vn -1.517276 -3.665195 -2.627990 -v 0.090750 0.018500 0.035422 -vn 3.133679 -3.277075 -0.066624 -v 0.091965 0.018500 0.035649 -vn 2.406844 -2.835492 -1.961457 -v 0.090527 0.018500 0.027174 -vn 2.923806 -2.564369 -0.722102 -v 0.092225 0.018500 0.030066 -vn -1.517280 -3.665199 2.627987 -v 0.090750 0.018500 0.032824 -vn 2.627996 -3.665185 1.517273 -v 0.080701 0.018500 0.041373 -vn 1.517272 -3.665199 2.627991 -v 0.081250 0.018500 0.040824 -vn -2.627992 -3.665201 -1.517267 -v 0.075299 0.018500 0.034873 -vn -3.034551 -3.665180 -0.000000 -v 0.083500 0.018500 0.026123 -vn -2.627995 -3.665199 1.517266 -v 0.083299 0.018500 0.025373 -vn 0.842544 -2.835494 -2.988367 -v 0.084985 0.018500 0.023535 -vn -1.517270 -3.665190 2.627995 -v 0.082750 0.018500 0.024824 -vn -0.097141 -2.835493 -3.103350 -v 0.081656 0.018500 0.023128 -vn -0.000004 -3.665188 3.034547 -v 0.082000 0.018500 0.024623 -vn -1.027794 -2.835493 -2.929822 -v 0.078359 0.018500 0.023743 -vn 3.034543 -3.665198 -0.000002 -v 0.080500 0.018500 0.042123 -vn 2.627999 -3.665181 -1.517271 -v 0.080701 0.018500 0.042873 -vn 1.517276 -3.665201 -2.627988 -v 0.081250 0.018500 0.043422 -vn -2.627996 -3.665185 -1.517273 -v 0.091299 0.018500 0.034873 -vn -3.034543 -3.665198 0.000002 -v 0.091500 0.018500 0.034123 -vn -2.627999 -3.665181 1.517271 -v 0.091299 0.018500 0.033373 -vn 1.517274 -3.665200 -2.627989 -v 0.081250 0.018500 0.027422 -vn -0.000004 -3.665188 3.034547 -v 0.082000 0.018500 0.040623 -vn 1.703897 -2.835495 -2.595564 -v 0.088037 0.018500 0.024927 -vn -2.627994 -3.665199 -1.517266 -v 0.083299 0.018500 0.026873 -vn -0.000004 -3.665188 3.034547 -v 0.090000 0.018500 0.032623 -vn -3.034550 -3.665179 0.000002 -v 0.075500 0.018500 0.034123 -vn -2.627996 -3.665198 1.517265 -v 0.075299 0.018500 0.033373 -vn 2.627998 -3.665184 -1.517272 -v 0.080701 0.018500 0.026873 -vn -1.517272 -3.665192 2.627994 -v 0.074750 0.018500 0.032824 -vn -0.000000 -3.665190 3.034546 -v 0.074000 0.018500 0.032623 -vn 1.517274 -3.665200 2.627989 -v 0.081250 0.018500 0.024824 -vn 2.627998 -3.665183 1.517272 -v 0.080701 0.018500 0.025373 -vn -1.862895 -2.835494 -2.483916 -v 0.075400 0.018500 0.025323 -vn 3.034543 -3.665198 0.000000 -v 0.080500 0.018500 0.026123 -vn -2.524809 -2.835491 -1.807084 -v 0.073055 0.018500 0.027721 -vn 2.923805 2.564369 -0.722102 -v 0.092225 0.024500 0.030066 -vn 2.406844 2.835492 -1.961457 -v 0.090527 0.024500 0.027174 -vn 1.703897 2.835495 -2.595564 -v 0.088037 0.024500 0.024927 -vn 0.842544 2.835493 -2.988367 -v 0.084985 0.024500 0.023535 -vn -0.097141 2.835493 -3.103350 -v 0.081656 0.024500 0.023128 -vn -1.027794 2.835494 -2.929822 -v 0.078359 0.024500 0.023743 -vn -1.862895 2.835494 -2.483916 -v 0.075400 0.024500 0.025323 -vn -2.524809 2.835491 -1.807084 -v 0.073055 0.024500 0.027721 -vn -2.951997 2.835495 -0.962253 -v 0.071542 0.024500 0.030714 -vn -3.104744 2.835494 -0.027968 -v 0.071000 0.024500 0.034024 -vn -2.968852 2.835493 0.908921 -v 0.071482 0.024500 0.037343 -vn -2.402188 2.701068 1.904721 -v 0.072941 0.024500 0.040363 -vn -0.000000 3.665190 -3.034546 -v 0.074000 0.024500 0.035623 -vn 1.517268 3.665189 -2.627998 -v 0.073250 0.024500 0.035422 -vn 2.627989 3.665192 -1.517281 -v 0.072701 0.024500 0.034873 -vn 3.034543 3.665198 0.000002 -v 0.072500 0.024500 0.034123 -vn 2.627992 3.665187 1.517279 -v 0.072701 0.024500 0.033373 -vn 1.517272 3.665192 2.627994 -v 0.073250 0.024500 0.032824 -vn 0.000000 3.665190 3.034546 -v 0.074000 0.024500 0.032623 -vn -1.517272 3.665191 2.627994 -v 0.074750 0.024500 0.032824 -vn -2.627996 3.665197 1.517265 -v 0.075299 0.024500 0.033373 -vn -3.034550 3.665179 0.000002 -v 0.075500 0.024500 0.034123 -vn -2.627993 3.665201 -1.517267 -v 0.075299 0.024500 0.034873 -vn -1.517268 3.665189 -2.627998 -v 0.074750 0.024500 0.035422 -vn -0.000004 3.665188 -3.034547 -v 0.082000 0.024500 0.027623 -vn 1.517274 3.665201 -2.627989 -v 0.081250 0.024500 0.027422 -vn 2.627998 3.665184 -1.517272 -v 0.080701 0.024500 0.026873 -vn 3.034543 3.665198 -0.000000 -v 0.080500 0.024500 0.026123 -vn 2.627998 3.665183 1.517272 -v 0.080701 0.024500 0.025373 -vn 1.517274 3.665200 2.627989 -v 0.081250 0.024500 0.024824 -vn -0.000004 3.665188 3.034547 -v 0.082000 0.024500 0.024623 -vn -1.517270 3.665190 2.627996 -v 0.082750 0.024500 0.024824 -vn -2.627994 3.665200 1.517266 -v 0.083299 0.024500 0.025373 -vn -3.034551 3.665179 0.000000 -v 0.083500 0.024500 0.026123 -vn -2.627995 3.665199 -1.517266 -v 0.083299 0.024500 0.026873 -vn -1.517270 3.665190 -2.627995 -v 0.082750 0.024500 0.027422 -vn -0.000004 3.665188 -3.034547 -v 0.090000 0.024500 0.035623 -vn 1.517272 3.665198 -2.627991 -v 0.089250 0.024500 0.035422 -vn 2.627996 3.665185 -1.517273 -v 0.088701 0.024500 0.034873 -vn 3.034543 3.665198 0.000002 -v 0.088500 0.024500 0.034123 -vn 2.627999 3.665180 1.517271 -v 0.088701 0.024500 0.033373 -vn 1.517276 3.665201 2.627988 -v 0.089250 0.024500 0.032824 -vn -0.000004 3.665188 3.034547 -v 0.090000 0.024500 0.032623 -vn -1.517279 3.665199 2.627986 -v 0.090750 0.024500 0.032824 -vn -2.628000 3.665181 1.517272 -v 0.091299 0.024500 0.033373 -vn -3.034543 3.665198 0.000002 -v 0.091500 0.024500 0.034123 -vn -2.627996 3.665185 -1.517273 -v 0.091299 0.024500 0.034873 -vn -1.517276 3.665195 -2.627990 -v 0.090750 0.024500 0.035422 -vn -0.000004 3.665188 -3.034547 -v 0.082000 0.024500 0.043623 -vn 1.517276 3.665201 -2.627987 -v 0.081250 0.024500 0.043422 -vn 2.628000 3.665180 -1.517272 -v 0.080701 0.024500 0.042873 -vn 3.034543 3.665198 -0.000002 -v 0.080500 0.024500 0.042123 -vn 2.627996 3.665185 1.517273 -v 0.080701 0.024500 0.041373 -vn 1.517272 3.665198 2.627991 -v 0.081250 0.024500 0.040824 -vn -0.000004 3.665188 3.034547 -v 0.082000 0.024500 0.040623 -vn -1.517268 3.665185 2.627998 -v 0.082750 0.024500 0.040824 -vn -2.627992 3.665201 1.517267 -v 0.083299 0.024500 0.041373 -vn -3.034550 3.665179 -0.000002 -v 0.083500 0.024500 0.042123 -vn -2.627996 3.665197 -1.517265 -v 0.083299 0.024500 0.042873 -vn -1.517272 3.665191 -2.627994 -v 0.082750 0.024500 0.043422 -vn 3.045341 3.326360 -0.715199 -v 0.092735 0.024500 0.041184 -vn 2.931146 2.617994 0.785398 -v 0.101000 0.024500 0.067783 -vn -1.570796 1.570796 1.570797 -v 0.055906 0.024500 0.134440 -vn 1.570796 1.570796 1.570796 -v 0.077906 0.024500 0.134440 -vn -2.931146 2.617994 -0.785398 -v 0.055906 0.024500 0.107783 -vn 2.931146 3.665191 0.785398 -v 0.077906 0.024500 0.107783 -vn -2.770830 3.209461 -1.476735 -v 0.079000 0.024500 0.067783 -vn -2.939434 3.365992 -1.051478 -v 0.080957 0.024500 0.063790 -vn -3.099712 3.365992 -0.371031 -v 0.081976 0.024500 0.059462 -vn 3.127215 3.297231 -0.124033 -v 0.091965 0.024500 0.035649 -vn -3.104558 3.365993 0.328023 -v 0.082007 0.024500 0.055016 -vn -2.953729 3.365991 1.010627 -v 0.081048 0.024500 0.050674 -vn -2.669732 3.342050 1.623105 -v 0.079146 0.024500 0.046655 -vn -2.203250 3.327277 2.215976 -v 0.076398 0.024500 0.043159 -vn 3.128154 3.010694 -0.205029 -v 0.101000 0.024500 0.057220 -vn 2.766234 2.579901 -1.208035 -v 0.100796 0.024500 0.055667 -vn 2.581446 3.326362 -1.766846 -v 0.097227 0.024500 0.051367 -vn 2.862110 3.326361 -1.262512 -v 0.094510 0.024500 0.046483 -vn -2.931146 2.617994 -0.785398 -v 0.055906 -0.022000 0.107783 -vn -2.931146 -2.617994 -0.785399 -v 0.055906 -0.026000 0.107783 -vn -4.712389 1.570796 -1.570795 -v 0.055906 -0.022000 0.129940 -vn -1.570796 -1.570796 1.570797 -v 0.055906 -0.026000 0.134440 -vn 1.570796 -1.570796 1.570794 -v 0.077906 -0.026000 0.134440 -vn -2.356195 -1.360349 4.188790 -v 0.071156 0.001704 0.134440 -vn -2.356195 1.360349 4.188790 -v 0.071156 -0.003204 0.134440 -vn -0.000001 2.720699 4.188790 -v 0.066906 -0.005657 0.134440 -vn 2.356194 1.360350 4.188790 -v 0.062656 -0.003204 0.134440 -vn 2.356194 -1.360350 4.188791 -v 0.062656 0.001704 0.134440 -vn -0.000001 -2.720699 4.188790 -v 0.066906 0.004157 0.134440 -vn 4.712388 1.570796 -1.570796 -v 0.077906 -0.022000 0.129940 -vn 2.931146 3.665191 0.785398 -v 0.077906 -0.022000 0.107783 -vn 2.931146 -3.665191 0.785398 -v 0.077906 -0.026000 0.107783 -vn -2.356195 1.360349 -4.188790 -v 0.071156 -0.003204 0.129940 -vn -2.356194 -1.360349 -4.188790 -v 0.071156 0.001704 0.129940 -vn -0.000001 -2.720699 -4.188790 -v 0.066906 0.004157 0.129940 -vn 2.356194 -1.360350 -4.188791 -v 0.062656 0.001704 0.129940 -vn 2.356194 1.360350 -4.188791 -v 0.062656 -0.003204 0.129940 -vn -0.000001 2.720699 -4.188790 -v 0.066906 -0.005657 0.129940 -vn -2.968852 2.835493 0.908921 -v 0.071482 -0.022000 0.037343 -vn 1.517268 3.665189 -2.627998 -v 0.073250 -0.022000 0.035422 -vn 2.627989 3.665192 -1.517281 -v 0.072701 -0.022000 0.034873 -vn -1.517270 3.665190 -2.627995 -v 0.082750 -0.022000 0.027422 -vn -0.000004 3.665188 3.034547 -v 0.082000 -0.022000 0.040623 -vn -2.627994 3.665199 -1.517266 -v 0.083299 -0.022000 0.026873 -vn -3.034551 3.665178 0.000000 -v 0.083500 -0.022000 0.026123 -vn -3.104744 2.835494 -0.027968 -v 0.071000 -0.022000 0.034024 -vn 3.034543 3.665198 0.000002 -v 0.072500 -0.022000 0.034123 -vn -2.951997 2.835495 -0.962253 -v 0.071542 -0.022000 0.030714 -vn 2.627992 3.665187 1.517279 -v 0.072701 -0.022000 0.033373 -vn 1.517272 3.665192 2.627994 -v 0.073250 -0.022000 0.032824 -vn -2.524809 2.835491 -1.807084 -v 0.073055 -0.022000 0.027721 -vn 0.000000 3.665190 3.034546 -v 0.074000 -0.022000 0.032623 -vn 3.034543 3.665198 -0.000002 -v 0.080500 -0.022000 0.042123 -vn -2.627995 3.665194 1.517265 -v 0.075299 -0.022000 0.033373 -vn 2.628000 3.665180 -1.517272 -v 0.080701 -0.022000 0.042873 -vn -3.034550 3.665180 0.000002 -v 0.075500 -0.022000 0.034123 -vn -2.627993 3.665201 -1.517267 -v 0.075299 -0.022000 0.034873 -vn 2.627998 3.665184 -1.517272 -v 0.080701 -0.022000 0.026873 -vn 3.034543 3.665198 -0.000000 -v 0.080500 -0.022000 0.026123 -vn -1.862895 2.835494 -2.483916 -v 0.075400 -0.022000 0.025323 -vn -1.027794 2.835494 -2.929822 -v 0.078359 -0.022000 0.023743 -vn -2.654787 3.365994 1.642555 -v 0.079146 -0.022000 0.046655 -vn -2.953729 3.365988 1.010627 -v 0.081048 -0.022000 0.050674 -vn -1.517268 3.665186 -2.627998 -v 0.074750 -0.022000 0.035422 -vn -1.517280 3.665199 2.627986 -v 0.090750 -0.022000 0.032824 -vn -2.628000 3.665181 1.517272 -v 0.091299 -0.022000 0.033373 -vn 2.923805 2.564369 -0.722102 -v 0.092225 -0.022000 0.030066 -vn -3.034543 3.665198 0.000002 -v 0.091500 -0.022000 0.034123 -vn -1.517276 3.665196 -2.627990 -v 0.090750 -0.022000 0.035422 -vn -2.627993 3.665201 1.517267 -v 0.083299 -0.022000 0.041373 -vn -3.034551 3.665180 -0.000002 -v 0.083500 -0.022000 0.042123 -vn 2.627998 3.665183 1.517272 -v 0.080701 -0.022000 0.025373 -vn 1.517274 3.665200 2.627989 -v 0.081250 -0.022000 0.024824 -vn -0.097141 2.835493 -3.103350 -v 0.081656 -0.022000 0.023128 -vn -0.000004 3.665188 3.034547 -v 0.082000 -0.022000 0.024623 -vn 0.842544 2.835494 -2.988367 -v 0.084985 -0.022000 0.023535 -vn -1.517270 3.665190 2.627996 -v 0.082750 -0.022000 0.024824 -vn 1.517274 3.665199 -2.627989 -v 0.081250 -0.022000 0.027422 -vn -1.517272 3.665190 2.627994 -v 0.074750 -0.022000 0.032824 -vn -2.627996 3.665185 -1.517273 -v 0.091299 -0.022000 0.034873 -vn 3.045341 3.326360 -0.715199 -v 0.092735 -0.022000 0.041184 -vn 3.124901 3.326362 -0.143537 -v 0.091965 -0.022000 0.035649 -vn 1.517276 3.665201 -2.627987 -v 0.081250 -0.022000 0.043422 -vn -0.000004 3.665188 -3.034547 -v 0.082000 -0.022000 0.043623 -vn -0.000000 3.665190 -3.034546 -v 0.074000 -0.022000 0.035623 -vn -2.402188 2.701068 1.904721 -v 0.072941 -0.022000 0.040363 -vn -2.222723 3.365991 2.192119 -v 0.076398 -0.022000 0.043159 -vn 2.627996 3.665185 1.517273 -v 0.080701 -0.022000 0.041373 -vn 1.517272 3.665198 2.627991 -v 0.081250 -0.022000 0.040824 -vn -0.000004 3.665188 -3.034547 -v 0.082000 -0.022000 0.027623 -vn 2.862110 3.326361 -1.262511 -v 0.094510 -0.022000 0.046483 -vn -2.627996 3.665197 -1.517265 -v 0.083299 -0.022000 0.042873 -vn 2.581446 3.326362 -1.766846 -v 0.097227 -0.022000 0.051367 -vn -1.517272 3.665191 -2.627994 -v 0.082750 -0.022000 0.043422 -vn -0.000004 3.665188 3.034547 -v 0.090000 -0.022000 0.032623 -vn 2.406844 2.835492 -1.961457 -v 0.090527 -0.022000 0.027174 -vn 1.517276 3.665200 2.627988 -v 0.089250 -0.022000 0.032824 -vn 1.703897 2.835495 -2.595564 -v 0.088037 -0.022000 0.024927 -vn -3.104558 3.365993 0.328023 -v 0.082007 -0.022000 0.055016 -vn -3.099712 3.365992 -0.371030 -v 0.081976 -0.022000 0.059462 -vn 2.931146 2.617994 0.785398 -v 0.101000 -0.022000 0.067783 -vn -0.000004 3.665188 -3.034547 -v 0.090000 -0.022000 0.035623 -vn 1.517272 3.665198 -2.627991 -v 0.089250 -0.022000 0.035422 -vn -1.517268 3.665189 2.627998 -v 0.082750 -0.022000 0.040824 -vn 2.627996 3.665185 -1.517273 -v 0.088701 -0.022000 0.034873 -vn 3.034543 3.665198 0.000002 -v 0.088500 -0.022000 0.034123 -vn 2.628000 3.665181 1.517271 -v 0.088701 -0.022000 0.033373 -vn -2.770830 3.209461 -1.476735 -v 0.079000 -0.022000 0.067783 -vn -2.939434 3.365992 -1.051478 -v 0.080957 -0.022000 0.063790 -vn -2.627994 3.665199 1.517266 -v 0.083299 -0.022000 0.025373 -vn 3.128154 3.010694 -0.205029 -v 0.101000 -0.022000 0.057220 -vn 2.766234 2.579901 -1.208035 -v 0.100796 -0.022000 0.055667 -vn 2.627996 -3.665186 1.517273 -v 0.080701 -0.026000 0.041373 -vn 0.000000 -3.665190 -3.034546 -v 0.074000 -0.026000 0.035623 -vn -1.517268 -3.665189 -2.627998 -v 0.074750 -0.026000 0.035422 -vn -2.402188 -2.701068 1.904721 -v 0.072941 -0.026000 0.040363 -vn 1.517268 -3.665189 -2.627998 -v 0.073250 -0.026000 0.035422 -vn -2.968852 -2.835493 0.908921 -v 0.071482 -0.026000 0.037343 -vn 2.627989 -3.665192 -1.517281 -v 0.072701 -0.026000 0.034873 -vn -0.000004 -3.665187 -3.034547 -v 0.082000 -0.026000 0.027623 -vn -1.517268 -3.665189 2.627998 -v 0.082750 -0.026000 0.040824 -vn 1.517274 -3.665200 -2.627989 -v 0.081250 -0.026000 0.027422 -vn -0.000004 -3.665187 3.034548 -v 0.082000 -0.026000 0.040623 -vn 1.517272 -3.665198 2.627991 -v 0.081250 -0.026000 0.040824 -vn -2.627993 -3.665202 -1.517267 -v 0.075299 -0.026000 0.034873 -vn -3.034551 -3.665180 0.000002 -v 0.075500 -0.026000 0.034123 -vn -2.627996 -3.665197 1.517265 -v 0.075299 -0.026000 0.033373 -vn 2.581446 -3.326361 -1.766846 -v 0.097227 -0.026000 0.051367 -vn 2.766233 -2.579901 -1.208035 -v 0.100796 -0.026000 0.055667 -vn 3.128155 -3.010694 -0.205029 -v 0.101000 -0.026000 0.057220 -vn -2.627994 -3.665199 1.517266 -v 0.083299 -0.026000 0.025373 -vn -1.517270 -3.665190 2.627995 -v 0.082750 -0.026000 0.024824 -vn 0.842544 -2.835494 -2.988367 -v 0.084985 -0.026000 0.023535 -vn 2.931146 -2.617994 0.785398 -v 0.101000 -0.026000 0.067783 -vn -1.517276 -3.665195 -2.627990 -v 0.090750 -0.026000 0.035422 -vn -2.627996 -3.665185 -1.517273 -v 0.091299 -0.026000 0.034873 -vn 3.124901 -3.326363 -0.143537 -v 0.091965 -0.026000 0.035649 -vn -3.034543 -3.665198 0.000002 -v 0.091500 -0.026000 0.034123 -vn 2.923806 -2.564369 -0.722102 -v 0.092225 -0.026000 0.030066 -vn -1.517270 -3.665187 -2.627996 -v 0.082750 -0.026000 0.027422 -vn -3.034550 -3.665179 -0.000002 -v 0.083500 -0.026000 0.042123 -vn -2.627993 -3.665201 1.517267 -v 0.083299 -0.026000 0.041373 -vn 3.045341 -3.326361 -0.715199 -v 0.092735 -0.026000 0.041184 -vn 2.862110 -3.326362 -1.262512 -v 0.094510 -0.026000 0.046483 -vn -3.104558 -3.365991 0.328023 -v 0.082007 -0.026000 0.055016 -vn -0.097141 -2.835493 -3.103350 -v 0.081656 -0.026000 0.023128 -vn -0.000004 -3.665188 3.034548 -v 0.082000 -0.026000 0.024623 -vn -1.027794 -2.835492 -2.929822 -v 0.078359 -0.026000 0.023743 -vn 1.517274 -3.665200 2.627989 -v 0.081250 -0.026000 0.024824 -vn 2.627998 -3.665183 1.517272 -v 0.080701 -0.026000 0.025373 -vn 3.034543 -3.665198 0.000000 -v 0.080500 -0.026000 0.026123 -vn -3.099712 -3.365992 -0.371031 -v 0.081976 -0.026000 0.059462 -vn 3.034543 -3.665198 -0.000002 -v 0.080500 -0.026000 0.042123 -vn -2.222723 -3.365991 2.192119 -v 0.076398 -0.026000 0.043159 -vn 2.628000 -3.665181 -1.517271 -v 0.080701 -0.026000 0.042873 -vn -2.654787 -3.365994 1.642555 -v 0.079146 -0.026000 0.046655 -vn 1.517276 -3.665201 -2.627988 -v 0.081250 -0.026000 0.043422 -vn -2.953729 -3.365990 1.010627 -v 0.081048 -0.026000 0.050674 -vn -0.000004 -3.665188 -3.034547 -v 0.082000 -0.026000 0.043623 -vn -1.517272 -3.665192 -2.627994 -v 0.082750 -0.026000 0.043422 -vn -2.627995 -3.665198 -1.517265 -v 0.083299 -0.026000 0.042873 -vn -3.034551 -3.665179 -0.000000 -v 0.083500 -0.026000 0.026123 -vn 1.703897 -2.835495 -2.595564 -v 0.088037 -0.026000 0.024927 -vn 2.406844 -2.835491 -1.961457 -v 0.090527 -0.026000 0.027174 -vn -2.939434 -3.365992 -1.051478 -v 0.080957 -0.026000 0.063790 -vn -2.770830 -3.209461 -1.476735 -v 0.079000 -0.026000 0.067783 -vn 1.517276 -3.665201 2.627987 -v 0.089250 -0.026000 0.032824 -vn 2.628000 -3.665181 1.517272 -v 0.088701 -0.026000 0.033373 -vn 2.627996 -3.665186 -1.517273 -v 0.088701 -0.026000 0.034873 -vn 3.034543 -3.665198 0.000002 -v 0.088500 -0.026000 0.034123 -vn -0.000004 -3.665188 -3.034547 -v 0.090000 -0.026000 0.035623 -vn 1.517272 -3.665198 -2.627991 -v 0.089250 -0.026000 0.035422 -vn 3.034543 -3.665198 0.000002 -v 0.072500 -0.026000 0.034123 -vn -3.104744 -2.835494 -0.027968 -v 0.071000 -0.026000 0.034024 -vn 2.627992 -3.665187 1.517279 -v 0.072701 -0.026000 0.033373 -vn -2.951997 -2.835495 -0.962254 -v 0.071542 -0.026000 0.030714 -vn 1.517272 -3.665192 2.627994 -v 0.073250 -0.026000 0.032824 -vn -2.524809 -2.835491 -1.807084 -v 0.073055 -0.026000 0.027721 -vn -0.000000 -3.665190 3.034546 -v 0.074000 -0.026000 0.032623 -vn -1.862895 -2.835493 -2.483916 -v 0.075400 -0.026000 0.025323 -vn -1.517272 -3.665192 2.627994 -v 0.074750 -0.026000 0.032824 -vn 2.627998 -3.665183 -1.517272 -v 0.080701 -0.026000 0.026873 -vn -2.628000 -3.665181 1.517271 -v 0.091299 -0.026000 0.033373 -vn -1.517280 -3.665199 2.627986 -v 0.090750 -0.026000 0.032824 -vn -0.000004 -3.665188 3.034548 -v 0.090000 -0.026000 0.032623 -vn -2.627994 -3.665199 -1.517266 -v 0.083299 -0.026000 0.026873 -# 336 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 1//1 3//3 4//4 -f 4//4 3//3 5//5 -f 4//4 5//5 6//6 -f 6//6 5//5 7//7 -f 6//6 7//7 8//8 -f 8//8 7//7 9//9 -f 8//8 9//9 10//10 -f 10//10 9//9 11//11 -f 10//10 11//11 12//12 -f 13//13 1//1 4//4 -f 8//8 14//14 6//6 -f 6//6 14//14 15//15 -f 16//16 17//17 15//15 -f 15//15 17//17 18//18 -f 15//15 18//18 19//19 -f 20//20 21//21 22//22 -f 12//12 23//23 10//10 -f 10//10 23//23 24//24 -f 10//10 24//24 8//8 -f 8//8 24//24 20//20 -f 8//8 20//20 14//14 -f 14//14 20//20 22//22 -f 19//19 25//25 15//15 -f 15//15 25//25 26//26 -f 15//15 26//26 6//6 -f 6//6 26//26 27//27 -f 6//6 27//27 4//4 -f 4//4 27//27 28//28 -f 4//4 28//28 13//13 -f 3//3 29//29 5//5 -f 5//5 29//29 30//30 -f 5//5 30//30 7//7 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 32//32 35//35 36//36 -f 3//3 2//2 37//37 -f 37//37 2//2 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 44//44 42//42 45//45 -f 44//44 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 48//48 -f 49//49 50//50 51//51 -f 51//51 50//50 34//34 -f 51//51 34//34 52//52 -f 52//52 34//34 32//32 -f 52//52 32//32 53//53 -f 53//53 32//32 36//36 -f 30//30 50//50 7//7 -f 7//7 50//50 49//49 -f 7//7 49//49 9//9 -f 9//9 49//49 54//54 -f 9//9 54//54 11//11 -f 11//11 54//54 55//55 -f 11//11 55//55 56//56 -f 57//57 58//58 59//59 -f 60//60 37//37 61//61 -f 61//61 37//37 62//62 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 60//60 70//70 37//37 -f 37//37 70//70 71//71 -f 37//37 71//71 3//3 -f 3//3 71//71 72//72 -f 3//3 72//72 29//29 -f 55//55 73//73 56//56 -f 56//56 73//73 74//74 -f 56//56 74//74 58//58 -f 58//58 74//74 75//75 -f 58//58 75//75 59//59 -f 62//62 76//76 61//61 -f 61//61 76//76 32//32 -f 61//61 32//32 77//77 -f 77//77 32//32 31//31 -f 65//65 78//78 63//63 -f 63//63 78//78 57//57 -f 63//63 57//57 79//79 -f 79//79 57//57 59//59 -f 79//79 59//59 35//35 -f 35//35 59//59 80//80 -f 35//35 80//80 36//36 -f 62//62 81//81 76//76 -f 76//76 81//81 82//82 -f 76//76 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 68//68 86//86 69//69 -f 69//69 86//86 87//87 -f 69//69 87//87 88//88 -f 88//88 87//87 89//89 -f 88//88 89//89 90//90 -f 90//90 89//89 83//83 -f 90//90 83//83 47//47 -f 47//47 83//83 85//85 -f 47//47 85//85 48//48 -f 91//91 58//58 57//57 -f 91//91 57//57 92//92 -f 92//92 57//57 78//78 -f 92//92 78//78 93//93 -f 93//93 78//78 65//65 -f 93//93 65//65 94//94 -f 94//94 65//65 67//67 -f 94//94 67//67 95//95 -f 95//95 67//67 69//69 -f 95//95 69//69 96//96 -f 96//96 69//69 88//88 -f 96//96 88//88 97//97 -f 97//97 88//88 90//90 -f 97//97 90//90 98//98 -f 98//98 90//90 47//47 -f 98//98 47//47 99//99 -f 99//99 47//47 45//45 -f 99//99 45//45 100//100 -f 100//100 45//45 42//42 -f 100//100 42//42 101//101 -f 101//101 42//42 40//40 -f 101//101 40//40 102//102 -f 103//103 39//39 104//104 -f 104//104 39//39 41//41 -f 104//104 41//41 105//105 -f 105//105 41//41 43//43 -f 105//105 43//43 106//106 -f 106//106 43//43 44//44 -f 106//106 44//44 107//107 -f 107//107 44//44 46//46 -f 107//107 46//46 108//108 -f 108//108 46//46 48//48 -f 108//108 48//48 109//109 -f 109//109 48//48 85//85 -f 109//109 85//85 110//110 -f 110//110 85//85 84//84 -f 110//110 84//84 111//111 -f 111//111 84//84 82//82 -f 111//111 82//82 112//112 -f 112//112 82//82 81//81 -f 112//112 81//81 113//113 -f 113//113 81//81 62//62 -f 113//113 62//62 114//114 -f 114//114 62//62 37//37 -f 114//114 37//37 103//103 -f 103//103 37//37 39//39 -f 115//115 32//32 116//116 -f 116//116 32//32 76//76 -f 116//116 76//76 117//117 -f 117//117 76//76 83//83 -f 117//117 83//83 118//118 -f 118//118 83//83 89//89 -f 118//118 89//89 119//119 -f 119//119 89//89 87//87 -f 119//119 87//87 120//120 -f 120//120 87//87 86//86 -f 120//120 86//86 121//121 -f 121//121 86//86 68//68 -f 121//121 68//68 122//122 -f 122//122 68//68 66//66 -f 122//122 66//66 123//123 -f 123//123 66//66 64//64 -f 123//123 64//64 124//124 -f 124//124 64//64 63//63 -f 124//124 63//63 125//125 -f 125//125 63//63 79//79 -f 125//125 79//79 126//126 -f 126//126 79//79 35//35 -f 126//126 35//35 115//115 -f 115//115 35//35 32//32 -f 127//127 54//54 128//128 -f 128//128 54//54 49//49 -f 128//128 49//49 129//129 -f 129//129 49//49 51//51 -f 129//129 51//51 130//130 -f 130//130 51//51 52//52 -f 130//130 52//52 131//131 -f 131//131 52//52 53//53 -f 131//131 53//53 132//132 -f 132//132 53//53 36//36 -f 132//132 36//36 133//133 -f 133//133 36//36 80//80 -f 133//133 80//80 134//134 -f 134//134 80//80 59//59 -f 134//134 59//59 135//135 -f 135//135 59//59 75//75 -f 135//135 75//75 136//136 -f 136//136 75//75 74//74 -f 136//136 74//74 137//137 -f 137//137 74//74 73//73 -f 137//137 73//73 138//138 -f 138//138 73//73 55//55 -f 138//138 55//55 127//127 -f 127//127 55//55 54//54 -f 139//139 29//29 140//140 -f 140//140 29//29 72//72 -f 140//140 72//72 141//141 -f 141//141 72//72 71//71 -f 141//141 71//71 142//142 -f 142//142 71//71 70//70 -f 142//142 70//70 143//143 -f 143//143 70//70 60//60 -f 143//143 60//60 144//144 -f 144//144 60//60 61//61 -f 144//144 61//61 145//145 -f 145//145 61//61 77//77 -f 145//145 77//77 146//146 -f 146//146 77//77 31//31 -f 146//146 31//31 147//147 -f 147//147 31//31 33//33 -f 147//147 33//33 148//148 -f 148//148 33//33 34//34 -f 148//148 34//34 149//149 -f 149//149 34//34 50//50 -f 149//149 50//50 150//150 -f 150//150 50//50 30//30 -f 150//150 30//30 139//139 -f 139//139 30//30 29//29 -f 145//145 129//129 130//130 -f 129//129 145//145 128//128 -f 128//128 145//145 146//146 -f 128//128 146//146 127//127 -f 151//151 136//136 137//137 -f 134//134 91//91 133//133 -f 133//133 91//91 92//92 -f 133//133 92//92 132//132 -f 132//132 92//92 93//93 -f 102//102 114//114 103//103 -f 99//99 108//108 98//98 -f 98//98 108//108 109//109 -f 98//98 109//109 97//97 -f 93//93 94//94 132//132 -f 132//132 94//94 123//123 -f 132//132 123//123 131//131 -f 131//131 123//123 124//124 -f 152//152 150//150 139//139 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 152//152 -f 157//157 152//152 158//158 -f 158//158 152//152 159//159 -f 125//125 145//145 124//124 -f 124//124 145//145 130//130 -f 124//124 130//130 131//131 -f 102//102 103//103 101//101 -f 134//134 135//135 91//91 -f 91//91 135//135 136//136 -f 91//91 136//136 160//160 -f 160//160 136//136 151//151 -f 127//127 146//146 138//138 -f 138//138 146//146 147//147 -f 138//138 147//147 148//148 -f 159//159 152//152 161//161 -f 161//161 152//152 139//139 -f 161//161 139//139 162//162 -f 162//162 139//139 163//163 -f 163//163 139//139 140//140 -f 163//163 140//140 164//164 -f 164//164 140//140 141//141 -f 164//164 141//141 102//102 -f 114//114 102//102 113//113 -f 113//113 102//102 116//116 -f 113//113 116//116 112//112 -f 125//125 126//126 145//145 -f 145//145 126//126 115//115 -f 145//145 115//115 144//144 -f 144//144 115//115 116//116 -f 144//144 116//116 143//143 -f 143//143 116//116 102//102 -f 143//143 102//102 142//142 -f 142//142 102//102 141//141 -f 117//117 118//118 97//97 -f 97//97 118//118 96//96 -f 165//165 166//166 167//167 -f 97//97 109//109 117//117 -f 117//117 109//109 110//110 -f 117//117 110//110 116//116 -f 116//116 110//110 111//111 -f 116//116 111//111 112//112 -f 118//118 119//119 96//96 -f 96//96 119//119 120//120 -f 96//96 120//120 95//95 -f 95//95 120//120 121//121 -f 95//95 121//121 94//94 -f 94//94 121//121 122//122 -f 94//94 122//122 123//123 -f 103//103 104//104 101//101 -f 101//101 104//104 105//105 -f 101//101 105//105 100//100 -f 100//100 105//105 106//106 -f 100//100 106//106 99//99 -f 99//99 106//106 107//107 -f 99//99 107//107 108//108 -f 152//152 165//165 150//150 -f 150//150 165//165 167//167 -f 150//150 167//167 149//149 -f 149//149 167//167 168//168 -f 149//149 168//168 148//148 -f 148//148 168//168 151//151 -f 148//148 151//151 138//138 -f 138//138 151//151 137//137 -f 155//155 157//157 18//18 -f 18//18 157//157 19//19 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 17//17 -f 17//17 172//172 153//153 -f 17//17 153//153 18//18 -f 18//18 153//153 155//155 -f 173//173 154//154 174//174 -f 174//174 175//175 173//173 -f 173//173 175//175 176//176 -f 173//173 176//176 172//172 -f 172//172 176//176 177//177 -f 172//172 177//177 153//153 -f 153//153 177//177 178//178 -f 153//153 178//178 154//154 -f 154//154 178//178 179//179 -f 154//154 179//179 174//174 -f 15//15 156//156 16//16 -f 16//16 156//156 154//154 -f 16//16 154//154 180//180 -f 180//180 154//154 173//173 -f 180//180 173//173 181//181 -f 181//181 173//173 182//182 -f 152//152 156//156 14//14 -f 14//14 156//156 15//15 -f 165//165 152//152 22//22 -f 22//22 152//152 14//14 -f 16//16 180//180 183//183 -f 183//183 184//184 16//16 -f 16//16 184//184 185//185 -f 16//16 185//185 17//17 -f 17//17 185//185 186//186 -f 17//17 186//186 171//171 -f 171//171 186//186 187//187 -f 171//171 187//187 180//180 -f 180//180 187//187 188//188 -f 180//180 188//188 183//183 -f 189//189 190//190 191//191 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 189//189 191//191 196//196 -f 196//196 191//191 197//197 -f 196//196 197//197 198//198 -f 197//197 199//199 198//198 -f 198//198 199//199 200//200 -f 198//198 200//200 201//201 -f 201//201 200//200 202//202 -f 203//203 204//204 205//205 -f 205//205 204//204 206//206 -f 205//205 206//206 207//207 -f 208//208 209//209 210//210 -f 210//210 209//209 211//211 -f 212//212 213//213 214//214 -f 215//215 216//216 217//217 -f 217//217 216//216 218//218 -f 219//219 220//220 221//221 -f 209//209 222//222 211//211 -f 211//211 222//222 223//223 -f 211//211 223//223 224//224 -f 224//224 223//223 225//225 -f 224//224 225//225 226//226 -f 226//226 225//225 227//227 -f 204//204 228//228 229//229 -f 229//229 228//228 208//208 -f 229//229 208//208 202//202 -f 202//202 208//208 210//210 -f 202//202 210//210 201//201 -f 230//230 231//231 218//218 -f 218//218 231//231 232//232 -f 218//218 232//232 217//217 -f 207//207 214//214 205//205 -f 205//205 214//214 213//213 -f 205//205 213//213 233//233 -f 233//233 213//213 234//234 -f 190//190 189//189 235//235 -f 235//235 189//189 236//236 -f 235//235 236//236 214//214 -f 214//214 236//236 237//237 -f 214//214 237//237 212//212 -f 203//203 238//238 204//204 -f 204//204 238//238 239//239 -f 204//204 239//239 228//228 -f 228//228 239//239 193//193 -f 228//228 193//193 240//240 -f 240//240 193//193 192//192 -f 230//230 219//219 231//231 -f 231//231 219//219 221//221 -f 231//231 221//221 241//241 -f 241//241 221//221 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 215//215 217//217 245//245 -f 245//245 217//217 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 226//226 -f 249//249 250//250 251//251 -f 219//219 252//252 220//220 -f 220//220 252//252 253//253 -f 220//220 253//253 254//254 -f 254//254 253//253 255//255 -f 254//254 255//255 193//193 -f 193//193 255//255 256//256 -f 193//193 256//256 195//195 -f 195//195 256//256 257//257 -f 171//171 180//180 169//169 -f 169//169 180//180 181//181 -f 169//169 181//181 258//258 -f 258//258 181//181 251//251 -f 258//258 251//251 259//259 -f 259//259 251//251 250//250 -f 257//257 247//247 195//195 -f 195//195 247//247 226//226 -f 195//195 226//226 260//260 -f 260//260 226//226 227//227 -f 213//213 249//249 234//234 -f 234//234 249//249 251//251 -f 234//234 251//251 244//244 -f 244//244 251//251 261//261 -f 244//244 261//261 243//243 -f 243//243 261//261 262//262 -f 263//263 264//264 265//265 -f 264//264 266//266 267//267 -f 267//267 266//266 268//268 -f 267//267 268//268 269//269 -f 270//270 271//271 272//272 -f 272//272 271//271 273//273 -f 263//263 265//265 274//274 -f 274//274 265//265 275//275 -f 274//274 275//275 273//273 -f 273//273 275//275 276//276 -f 273//273 276//276 277//277 -f 278//278 279//279 280//280 -f 281//281 282//282 283//283 -f 173//173 172//172 182//182 -f 182//182 172//172 170//170 -f 182//182 170//170 284//284 -f 285//285 286//286 287//287 -f 287//287 286//286 288//288 -f 287//287 288//288 289//289 -f 290//290 291//291 270//270 -f 270//270 291//291 292//292 -f 270//270 292//292 271//271 -f 293//293 294//294 295//295 -f 283//283 282//282 296//296 -f 296//296 282//282 297//297 -f 296//296 297//297 298//298 -f 297//297 299//299 298//298 -f 298//298 299//299 300//300 -f 298//298 300//300 301//301 -f 295//295 294//294 302//302 -f 264//264 263//263 266//266 -f 266//266 263//263 303//303 -f 266//266 303//303 304//304 -f 304//304 303//303 305//305 -f 304//304 305//305 306//306 -f 306//306 305//305 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 309//309 -f 308//308 309//309 295//295 -f 295//295 309//309 310//310 -f 295//295 310//310 311//311 -f 281//281 283//283 312//312 -f 312//312 283//283 313//313 -f 312//312 313//313 314//314 -f 294//294 278//278 302//302 -f 302//302 278//278 280//280 -f 302//302 280//280 315//315 -f 315//315 280//280 284//284 -f 315//315 284//284 316//316 -f 316//316 284//284 170//170 -f 317//317 318//318 290//290 -f 311//311 291//291 319//319 -f 319//319 291//291 290//290 -f 319//319 290//290 320//320 -f 320//320 290//290 318//318 -f 287//287 293//293 285//285 -f 285//285 293//293 295//295 -f 285//285 295//295 321//321 -f 321//321 295//295 311//311 -f 321//321 311//311 322//322 -f 322//322 311//311 319//319 -f 269//269 268//268 323//323 -f 323//323 268//268 324//324 -f 323//323 324//324 325//325 -f 325//325 324//324 326//326 -f 325//325 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 331//331 -f 331//331 330//330 298//298 -f 331//331 298//298 277//277 -f 277//277 298//298 301//301 -f 277//277 301//301 273//273 -f 273//273 301//301 332//332 -f 273//273 332//332 272//272 -f 288//288 333//333 289//289 -f 289//289 333//333 334//334 -f 289//289 334//334 314//314 -f 314//314 334//334 335//335 -f 314//314 335//335 312//312 -f 312//312 335//335 317//317 -f 312//312 317//317 336//336 -f 336//336 317//317 290//290 -f 266//266 236//236 189//189 -f 266//266 189//189 268//268 -f 268//268 189//189 196//196 -f 268//268 196//196 324//324 -f 324//324 196//196 198//198 -f 324//324 198//198 326//326 -f 326//326 198//198 201//201 -f 326//326 201//201 328//328 -f 328//328 201//201 210//210 -f 328//328 210//210 330//330 -f 330//330 210//210 211//211 -f 330//330 211//211 298//298 -f 298//298 211//211 224//224 -f 298//298 224//224 296//296 -f 296//296 224//224 226//226 -f 296//296 226//226 283//283 -f 283//283 226//226 248//248 -f 283//283 248//248 313//313 -f 313//313 248//248 246//246 -f 313//313 246//246 314//314 -f 314//314 246//246 217//217 -f 314//314 217//217 289//289 -f 261//261 251//251 280//280 -f 280//280 251//251 284//284 -f 182//182 284//284 181//181 -f 181//181 284//284 251//251 -f 316//316 170//170 258//258 -f 258//258 170//170 169//169 -f 297//297 225//225 299//299 -f 299//299 225//225 223//223 -f 299//299 223//223 300//300 -f 300//300 223//223 222//222 -f 300//300 222//222 301//301 -f 301//301 222//222 209//209 -f 301//301 209//209 332//332 -f 332//332 209//209 208//208 -f 332//332 208//208 272//272 -f 272//272 208//208 228//228 -f 272//272 228//228 270//270 -f 270//270 228//228 240//240 -f 270//270 240//240 290//290 -f 290//290 240//240 192//192 -f 290//290 192//192 336//336 -f 336//336 192//192 194//194 -f 336//336 194//194 312//312 -f 312//312 194//194 195//195 -f 312//312 195//195 281//281 -f 281//281 195//195 260//260 -f 281//281 260//260 282//282 -f 282//282 260//260 227//227 -f 282//282 227//227 297//297 -f 297//297 227//227 225//225 -f 335//335 245//245 317//317 -f 317//317 245//245 247//247 -f 317//317 247//247 318//318 -f 318//318 247//247 257//257 -f 318//318 257//257 320//320 -f 320//320 257//257 256//256 -f 320//320 256//256 319//319 -f 319//319 256//256 255//255 -f 319//319 255//255 322//322 -f 322//322 255//255 253//253 -f 322//322 253//253 321//321 -f 321//321 253//253 252//252 -f 321//321 252//252 285//285 -f 285//285 252//252 219//219 -f 285//285 219//219 286//286 -f 286//286 219//219 230//230 -f 286//286 230//230 288//288 -f 288//288 230//230 218//218 -f 288//288 218//218 333//333 -f 333//333 218//218 216//216 -f 333//333 216//216 334//334 -f 334//334 216//216 215//215 -f 334//334 215//215 335//335 -f 335//335 215//215 245//245 -f 273//273 193//193 274//274 -f 274//274 193//193 239//239 -f 274//274 239//239 263//263 -f 263//263 239//239 238//238 -f 263//263 238//238 303//303 -f 303//303 238//238 203//203 -f 303//303 203//203 305//305 -f 305//305 203//203 205//205 -f 305//305 205//205 307//307 -f 307//307 205//205 233//233 -f 307//307 233//233 309//309 -f 309//309 233//233 234//234 -f 309//309 234//234 310//310 -f 310//310 234//234 244//244 -f 310//310 244//244 311//311 -f 311//311 244//244 242//242 -f 311//311 242//242 291//291 -f 291//291 242//242 221//221 -f 291//291 221//221 292//292 -f 292//292 221//221 220//220 -f 292//292 220//220 271//271 -f 271//271 220//220 254//254 -f 271//271 254//254 273//273 -f 273//273 254//254 193//193 -f 329//329 202//202 327//327 -f 327//327 202//202 200//200 -f 327//327 200//200 325//325 -f 325//325 200//200 199//199 -f 325//325 199//199 323//323 -f 323//323 199//199 197//197 -f 323//323 197//197 269//269 -f 269//269 197//197 191//191 -f 269//269 191//191 267//267 -f 267//267 191//191 190//190 -f 267//267 190//190 264//264 -f 264//264 190//190 235//235 -f 264//264 235//235 265//265 -f 265//265 235//235 214//214 -f 265//265 214//214 275//275 -f 275//275 214//214 207//207 -f 275//275 207//207 276//276 -f 276//276 207//207 206//206 -f 276//276 206//206 277//277 -f 277//277 206//206 204//204 -f 277//277 204//204 331//331 -f 331//331 204//204 229//229 -f 331//331 229//229 329//329 -f 329//329 229//229 202//202 -f 262//262 261//261 279//279 -f 279//279 261//261 280//280 -f 22//22 21//21 165//165 -f 165//165 21//21 166//166 -f 12//12 11//11 56//56 -f 166//166 21//21 167//167 -f 167//167 21//21 20//20 -f 167//167 20//20 168//168 -f 168//168 20//20 24//24 -f 168//168 24//24 151//151 -f 151//151 24//24 23//23 -f 151//151 23//23 160//160 -f 23//23 12//12 160//160 -f 160//160 12//12 56//56 -f 160//160 56//56 91//91 -f 91//91 56//56 58//58 -f 262//262 279//279 243//243 -f 243//243 279//279 278//278 -f 243//243 278//278 241//241 -f 241//241 278//278 294//294 -f 241//241 294//294 231//231 -f 231//231 294//294 293//293 -f 231//231 293//293 232//232 -f 232//232 293//293 287//287 -f 232//232 287//287 217//217 -f 217//217 287//287 289//289 -f 19//19 157//157 25//25 -f 25//25 157//157 158//158 -f 25//25 158//158 26//26 -f 26//26 158//158 159//159 -f 26//26 159//159 27//27 -f 27//27 159//159 161//161 -f 27//27 161//161 28//28 -f 28//28 161//161 162//162 -f 28//28 162//162 13//13 -f 13//13 162//162 163//163 -f 13//13 163//163 1//1 -f 1//1 163//163 164//164 -f 1//1 164//164 2//2 -f 102//102 40//40 164//164 -f 164//164 40//40 38//38 -f 164//164 38//38 2//2 -f 236//236 266//266 237//237 -f 237//237 266//266 304//304 -f 237//237 304//304 212//212 -f 212//212 304//304 306//306 -f 212//212 306//306 213//213 -f 213//213 306//306 308//308 -f 213//213 308//308 249//249 -f 249//249 308//308 295//295 -f 249//249 295//295 250//250 -f 250//250 295//295 302//302 -f 250//250 302//302 259//259 -f 259//259 302//302 315//315 -f 259//259 315//315 258//258 -f 258//258 315//315 316//316 -f 179//179 185//185 174//174 -f 174//174 185//185 184//184 -f 174//174 184//184 175//175 -f 175//175 184//184 183//183 -f 175//175 183//183 176//176 -f 176//176 183//183 188//188 -f 176//176 188//188 177//177 -f 177//177 188//188 187//187 -f 177//177 187//187 178//178 -f 178//178 187//187 186//186 -f 178//178 186//186 179//179 -f 179//179 186//186 185//185 -# 704 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_Dz_left.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_Dz_left.obj deleted file mode 100644 index 9a5684b26..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_Dz_left.obj +++ /dev/null @@ -1,3212 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object hand_Dz_left.obj -# -# Vertices: 792 -# Faces: 1612 -# -#### -vn -0.348278 0.673707 6.214987 -v -0.025000 0.138500 0.176250 -vn 0.343655 0.679764 6.214165 -v -0.047000 0.138500 0.176250 -vn -0.343655 -0.679764 6.214165 -v -0.025000 0.120500 0.176250 -vn 0.348278 -0.673707 6.214986 -v -0.047000 0.120500 0.176250 -vn 3.665194 1.517270 2.627994 -v -0.026000 0.120875 0.115167 -vn 3.665194 2.627994 1.517270 -v -0.026000 0.120417 0.115625 -vn 2.827434 -2.951047 -0.958853 -v -0.026000 0.119038 0.112851 -vn 2.827435 0.958853 -2.951047 -v -0.026000 0.132899 0.105788 -vn 2.827433 1.823846 -2.510311 -v -0.026000 0.135966 0.107351 -vn 3.665209 -3.034538 0.000000 -v -0.026000 0.130750 0.108250 -vn 3.665174 -2.627999 -1.517278 -v -0.026000 0.130583 0.124875 -vn 3.122246 3.298672 -0.245727 -v -0.026000 0.140500 0.161250 -vn 3.665213 -1.517262 -2.627990 -v -0.026000 0.130125 0.125333 -vn 3.665165 0.000000 -3.034556 -v -0.026000 0.129500 0.125500 -vn 3.665165 3.034556 0.000000 -v -0.026000 0.136250 0.116250 -vn 3.665216 2.627990 -1.517262 -v -0.026000 0.136417 0.116875 -vn 3.665210 -3.034538 0.000000 -v -0.026000 0.130750 0.124250 -vn 2.984513 -3.122253 -0.245727 -v -0.026000 0.118500 0.116250 -vn 2.827434 2.951048 -0.958853 -v -0.026000 0.139962 0.112851 -vn 2.984512 3.122253 -0.245727 -v -0.026000 0.140500 0.116250 -vn 3.665210 -3.034538 0.000000 -v -0.026000 0.138750 0.116250 -vn 3.665185 1.517261 -2.628003 -v -0.026000 0.136875 0.117333 -vn 3.665187 3.034547 -0.000000 -v -0.026000 0.120250 0.116250 -vn 3.665194 2.627994 -1.517270 -v -0.026000 0.120417 0.116875 -vn 3.122259 -3.298673 -0.245727 -v -0.026000 0.118500 0.161250 -vn 3.665194 1.517270 -2.627994 -v -0.026000 0.120875 0.117333 -vn 3.665187 -0.000000 -3.034547 -v -0.026000 0.121500 0.117500 -vn 3.665187 -0.000000 -3.034547 -v -0.026000 0.137500 0.117500 -vn 3.665202 -1.517279 -2.627985 -v -0.026000 0.138125 0.117333 -vn 3.665174 -2.627999 -1.517278 -v -0.026000 0.138583 0.116875 -vn 3.665175 -2.627999 -1.517278 -v -0.026000 0.130583 0.108875 -vn 3.665196 1.517244 -2.628008 -v -0.026000 0.128875 0.125333 -vn 3.665213 2.627990 -1.517262 -v -0.026000 0.128417 0.124875 -vn 3.665174 -2.627999 1.517278 -v -0.026000 0.130583 0.107625 -vn 3.665202 -1.517279 2.627985 -v -0.026000 0.130125 0.107167 -vn 2.827432 0.000001 -3.102914 -v -0.026000 0.129500 0.105250 -vn 3.665187 0.000000 3.034547 -v -0.026000 0.129500 0.107000 -vn 3.665185 1.517261 2.628003 -v -0.026000 0.128875 0.107167 -vn 3.665213 2.627990 1.517262 -v -0.026000 0.128417 0.107625 -vn 3.665193 -1.517270 2.627994 -v -0.026000 0.122125 0.115167 -vn 2.827433 -0.958853 -2.951047 -v -0.026000 0.126101 0.105788 -vn 3.665188 0.000000 3.034547 -v -0.026000 0.137500 0.115000 -vn 2.827433 2.510311 -1.823846 -v -0.026000 0.138399 0.109784 -vn 3.665202 -1.517279 2.627985 -v -0.026000 0.138125 0.115167 -vn 3.665174 -2.627999 1.517278 -v -0.026000 0.138583 0.115625 -vn 3.665187 0.000000 3.034547 -v -0.026000 0.121500 0.115000 -vn 2.827433 -2.510311 -1.823846 -v -0.026000 0.120601 0.109784 -vn 2.827434 -1.823848 -2.510310 -v -0.026000 0.123034 0.107351 -vn 3.665193 -0.000000 -3.034547 -v -0.026000 0.129500 0.109500 -vn 3.665212 2.627990 1.517262 -v -0.026000 0.136417 0.115625 -vn 3.665201 -1.517279 -2.627985 -v -0.026000 0.130125 0.109333 -vn 3.665185 1.517261 2.628003 -v -0.026000 0.136875 0.115167 -vn 3.665174 -2.627999 1.517278 -v -0.026000 0.130583 0.123625 -vn 3.665201 -1.517279 2.627985 -v -0.026000 0.130125 0.123167 -vn 3.665165 3.034556 0.000000 -v -0.026000 0.128250 0.108250 -vn 3.665212 2.627990 -1.517262 -v -0.026000 0.128417 0.108875 -vn 3.665194 -2.627994 1.517270 -v -0.026000 0.122583 0.115625 -vn 3.665186 1.517261 -2.628003 -v -0.026000 0.128875 0.109333 -vn 3.665188 -3.034547 0.000000 -v -0.026000 0.122750 0.116250 -vn 3.665165 3.034556 0.000000 -v -0.026000 0.128250 0.124250 -vn 3.665212 2.627990 1.517262 -v -0.026000 0.128417 0.123625 -vn 3.665193 -1.517270 -2.627994 -v -0.026000 0.122125 0.117333 -vn 3.665185 1.517261 2.628003 -v -0.026000 0.128875 0.123167 -vn 3.665194 -2.627994 -1.517270 -v -0.026000 0.122583 0.116875 -vn 3.665188 0.000000 3.034547 -v -0.026000 0.129500 0.123000 -vn -2.827432 0.000001 -3.102915 -v -0.030000 0.129500 0.105250 -vn -3.665187 -0.000000 3.034547 -v -0.030000 0.129500 0.107000 -vn -2.827435 0.958853 -2.951047 -v -0.030000 0.132899 0.105788 -vn -3.665202 -1.517279 2.627985 -v -0.030000 0.130125 0.107167 -vn -2.827433 1.823846 -2.510311 -v -0.030000 0.135966 0.107351 -vn -3.665185 1.517261 2.628003 -v -0.030000 0.136875 0.115167 -vn -3.665210 -3.034538 0.000000 -v -0.030000 0.130750 0.124250 -vn -3.665174 -2.627999 -1.517278 -v -0.030000 0.130583 0.124875 -vn -3.122223 3.298673 -0.245727 -v -0.030000 0.140500 0.161250 -vn -3.665213 -1.517262 -2.627990 -v -0.030000 0.130125 0.125333 -vn -3.665165 -0.000000 -3.034556 -v -0.030000 0.129500 0.125500 -vn -3.122258 -3.298672 -0.245727 -v -0.030000 0.118500 0.161250 -vn -2.984513 3.122253 -0.245727 -v -0.030000 0.140500 0.116250 -vn -2.827434 2.951047 -0.958853 -v -0.030000 0.139962 0.112851 -vn -3.665174 -2.627999 1.517278 -v -0.030000 0.138583 0.115625 -vn -3.665174 -2.627999 1.517278 -v -0.030000 0.130583 0.107625 -vn -3.665211 -3.034538 0.000000 -v -0.030000 0.130750 0.108250 -vn -3.665196 1.517244 -2.628008 -v -0.030000 0.128875 0.125333 -vn -3.665213 2.627990 -1.517262 -v -0.030000 0.128417 0.124875 -vn -2.984509 -3.122253 -0.245727 -v -0.030000 0.118500 0.116250 -vn -2.827432 2.510311 -1.823846 -v -0.030000 0.138399 0.109784 -vn -3.665187 -0.000000 3.034547 -v -0.030000 0.137500 0.115000 -vn -3.665202 -1.517279 2.627985 -v -0.030000 0.138125 0.115167 -vn -2.827434 -2.951048 -0.958853 -v -0.030000 0.119038 0.112851 -vn -3.665194 1.517270 2.627994 -v -0.030000 0.120875 0.115167 -vn -2.827433 -2.510311 -1.823846 -v -0.030000 0.120601 0.109784 -vn -3.665187 -0.000000 3.034547 -v -0.030000 0.121500 0.115000 -vn -2.827434 -1.823848 -2.510310 -v -0.030000 0.123034 0.107351 -vn -3.665192 -1.517270 2.627994 -v -0.030000 0.122125 0.115167 -vn -2.827433 -0.958853 -2.951047 -v -0.030000 0.126101 0.105788 -vn -3.665213 2.627990 -1.517262 -v -0.030000 0.128417 0.108875 -vn -3.665186 1.517261 -2.628003 -v -0.030000 0.128875 0.109333 -vn -3.665194 -2.627994 1.517270 -v -0.030000 0.122583 0.115625 -vn -3.665188 -3.034547 -0.000000 -v -0.030000 0.122750 0.116250 -vn -3.665165 3.034556 -0.000000 -v -0.030000 0.128250 0.108250 -vn -3.665213 2.627990 1.517262 -v -0.030000 0.128417 0.107625 -vn -3.665185 1.517261 2.628003 -v -0.030000 0.128875 0.107167 -vn -3.665174 -2.627999 -1.517278 -v -0.030000 0.130583 0.108875 -vn -3.665193 -0.000000 3.034547 -v -0.030000 0.129500 0.123000 -vn -3.665198 -1.517279 -2.627985 -v -0.030000 0.130125 0.109333 -vn -3.665187 0.000000 -3.034547 -v -0.030000 0.121500 0.117500 -vn -3.665194 1.517270 -2.627994 -v -0.030000 0.120875 0.117333 -vn -3.665214 2.627990 1.517262 -v -0.030000 0.128417 0.123625 -vn -3.665165 3.034556 -0.000000 -v -0.030000 0.128250 0.124250 -vn -3.665174 -2.627999 1.517278 -v -0.030000 0.130583 0.123625 -vn -3.665202 -1.517279 -2.627985 -v -0.030000 0.138125 0.117333 -vn -3.665174 -2.627999 -1.517278 -v -0.030000 0.138583 0.116875 -vn -3.665210 -3.034538 0.000000 -v -0.030000 0.138750 0.116250 -vn -3.665185 1.517261 2.628003 -v -0.030000 0.128875 0.123167 -vn -3.665194 -2.627994 -1.517270 -v -0.030000 0.122583 0.116875 -vn -3.665187 0.000000 -3.034547 -v -0.030000 0.129500 0.109500 -vn -3.665194 2.627994 -1.517270 -v -0.030000 0.120417 0.116875 -vn -3.665187 3.034547 0.000000 -v -0.030000 0.120250 0.116250 -vn -3.665194 2.627994 1.517270 -v -0.030000 0.120417 0.115625 -vn -3.665187 0.000000 -3.034547 -v -0.030000 0.137500 0.117500 -vn -3.665185 1.517261 -2.628003 -v -0.030000 0.136875 0.117333 -vn -3.665201 -1.517279 2.627985 -v -0.030000 0.130125 0.123167 -vn -3.665212 2.627990 -1.517262 -v -0.030000 0.136417 0.116875 -vn -3.665165 3.034556 -0.000000 -v -0.030000 0.136250 0.116250 -vn -3.665213 2.627990 1.517262 -v -0.030000 0.136417 0.115625 -vn -3.665194 -1.517270 -2.627994 -v -0.030000 0.122125 0.117333 -vn -1.823847 3.455753 -2.510311 -v -0.034122 0.140500 0.169340 -vn -0.958857 3.455749 -2.951047 -v -0.036910 0.140500 0.170761 -vn 0.958857 3.455749 -2.951046 -v -0.019090 0.140500 0.170761 -vn -0.245731 3.298675 -3.122256 -v -0.040000 0.140500 0.171250 -vn 0.275964 3.116870 -2.985470 -v -0.009000 0.140500 0.171250 -vn 0.245731 3.298675 -3.122255 -v -0.016000 0.140500 0.171250 -vn 0.303342 6.192941 0.592426 -v -0.009000 0.140500 0.174250 -vn -0.303335 6.192941 0.592420 -v -0.063000 0.140500 0.174250 -vn -0.275965 3.116870 -2.985467 -v -0.063000 0.140500 0.171250 -vn 2.951047 3.455752 -0.958854 -v -0.025511 0.140500 0.164340 -vn -2.951046 3.455752 -0.958854 -v -0.030489 0.140500 0.164340 -vn -2.510310 3.455751 -1.823848 -v -0.031910 0.140500 0.167128 -vn 2.510310 3.455752 -1.823848 -v -0.024090 0.140500 0.167128 -vn 1.823846 3.455752 -2.510311 -v -0.021878 0.140500 0.169340 -vn 0.245731 -3.298675 -3.122252 -v -0.016000 0.118500 0.171250 -vn 0.275971 -3.116869 -2.985464 -v -0.009000 0.118500 0.171250 -vn 0.303358 -6.192935 0.592449 -v -0.009000 0.118500 0.174250 -vn 0.958857 -3.455749 -2.951047 -v -0.019090 0.118500 0.170761 -vn 1.823846 -3.455752 -2.510311 -v -0.021878 0.118500 0.169340 -vn -0.958857 -3.455749 -2.951047 -v -0.036910 0.118500 0.170761 -vn -0.245731 -3.298675 -3.122256 -v -0.040000 0.118500 0.171250 -vn -0.303358 -6.192931 0.592448 -v -0.063000 0.118500 0.174250 -vn -0.275972 -3.116869 -2.985464 -v -0.063000 0.118500 0.171250 -vn -2.951046 -3.455752 -0.958854 -v -0.030489 0.118500 0.164340 -vn 2.951047 -3.455751 -0.958854 -v -0.025511 0.118500 0.164340 -vn 2.510310 -3.455753 -1.823848 -v -0.024090 0.118500 0.167128 -vn -2.510310 -3.455751 -1.823848 -v -0.031910 0.118500 0.167128 -vn -1.823847 -3.455752 -2.510311 -v -0.034122 0.118500 0.169340 -vn -1.517576 2.627897 -3.662236 -v -0.055375 0.121051 0.171250 -vn -0.013577 3.038037 -3.644606 -v -0.056500 0.120750 0.171250 -vn -2.628177 1.517073 -3.662529 -v -0.054551 0.121875 0.171250 -vn -3.034580 -0.000140 -3.663934 -v -0.054250 0.123000 0.171250 -vn -2.856772 1.183307 -2.829340 -v -0.067619 0.137413 0.171250 -vn 1.522748 -2.626503 -3.656446 -v -0.057625 0.124949 0.171250 -vn -3.116870 0.275969 -2.985467 -v -0.068000 0.135500 0.171250 -vn 2.626486 -1.522806 -3.656339 -v -0.058449 0.124125 0.171250 -vn -3.116869 -0.275970 -2.985467 -v -0.068000 0.123500 0.171250 -vn 3.037741 -0.001103 -3.647017 -v -0.058750 0.123000 0.171250 -vn -2.856769 -1.183311 -2.829334 -v -0.067619 0.121587 0.171250 -vn -2.186476 -2.186477 -2.829336 -v -0.066536 0.119964 0.171250 -vn -1.183310 -2.856769 -2.829331 -v -0.064913 0.118881 0.171250 -vn 2.635305 1.514621 -3.635290 -v -0.058449 0.121875 0.171250 -vn 1.521478 2.633355 -3.625373 -v -0.057625 0.121051 0.171250 -vn -2.627967 -1.517362 -3.663842 -v -0.054551 0.124125 0.171250 -vn -1.517234 -2.628028 -3.664242 -v -0.055375 0.124949 0.171250 -vn -0.005438 -3.036008 -3.655535 -v -0.056500 0.125250 0.171250 -vn -1.183305 2.856770 -2.829328 -v -0.064913 0.140119 0.171250 -vn -2.186477 2.186476 -2.829336 -v -0.066536 0.139036 0.171250 -vn 6.200032 -0.303750 0.560080 -v -0.004000 0.123500 0.174250 -vn 3.116868 -0.275975 -2.985463 -v -0.004000 0.123500 0.171250 -vn 6.200032 0.303745 0.560080 -v -0.004000 0.135500 0.174250 -vn 3.116868 0.275974 -2.985464 -v -0.004000 0.135500 0.171250 -vn -6.200037 0.303728 0.560072 -v -0.068000 0.135500 0.174250 -vn -6.200036 -0.303732 0.560072 -v -0.068000 0.123500 0.174250 -vn 3.038684 -0.005938 -3.640686 -v -0.012750 0.123000 0.171250 -vn 2.629121 -1.519752 -3.651658 -v -0.012449 0.124125 0.171250 -vn 1.518949 -2.629348 -3.652791 -v -0.011625 0.124949 0.171250 -vn -0.004214 -3.035645 -3.657593 -v -0.010500 0.125250 0.171250 -vn 1.183306 2.856770 -2.829327 -v -0.007087 0.140119 0.171250 -vn 2.630333 1.522735 -3.636384 -v -0.012449 0.121875 0.171250 -vn 1.525339 2.629580 -3.632898 -v -0.011625 0.121051 0.171250 -vn -0.010275 3.038892 -3.639466 -v -0.010500 0.120750 0.171250 -vn 1.183310 -2.856769 -2.829329 -v -0.007087 0.118881 0.171250 -vn -1.520597 2.627156 -3.657987 -v -0.009375 0.121051 0.171250 -vn 2.186478 -2.186475 -2.829334 -v -0.005464 0.119964 0.171250 -vn -2.627964 1.518179 -3.660183 -v -0.008551 0.121875 0.171250 -vn 2.856769 -1.183314 -2.829336 -v -0.004381 0.121587 0.171250 -vn -3.034990 -0.001099 -3.660949 -v -0.008250 0.123000 0.171250 -vn -2.627994 -1.517574 -3.662812 -v -0.008551 0.124125 0.171250 -vn -1.517029 -2.628184 -3.663849 -v -0.009375 0.124949 0.171250 -vn 2.856771 1.183310 -2.829343 -v -0.004381 0.137413 0.171250 -vn 2.186478 2.186474 -2.829334 -v -0.005464 0.139036 0.171250 -vn -3.082218 -2.869782 0.177305 -v -0.015000 0.124321 0.214723 -vn -3.093905 2.869781 0.635809 -v -0.015000 0.132321 0.214723 -vn -3.228858 -3.135617 -0.136903 -v -0.015000 0.125500 0.201250 -vn -3.054327 3.135617 0.136903 -v -0.015000 0.133500 0.201250 -vn -3.139246 -3.196270 0.085838 -v -0.015000 0.125500 0.186250 -vn -3.139246 3.196270 0.085838 -v -0.015000 0.133500 0.186250 -vn 0.082889 -6.261097 0.356582 -v -0.007412 0.125500 0.185086 -vn 3.237085 -3.135665 0.135875 -v -0.007000 0.125500 0.185042 -vn 3.228858 -3.135615 -0.136903 -v -0.007000 0.125500 0.201250 -vn -0.015159 -6.256047 0.410698 -v -0.009000 0.125500 0.185159 -vn -3.227315 -3.284306 0.653133 -v -0.015060 0.125500 0.185159 -vn 3.343559 -3.054588 0.962786 -v -0.007000 0.125091 0.182187 -vn 3.476039 3.017973 1.131283 -v -0.007000 0.133909 0.182187 -vn 4.174000 2.955142 0.239862 -v -0.007000 0.133576 0.183800 -vn 3.093899 2.869782 0.635808 -v -0.007000 0.132321 0.214723 -vn 3.082222 -2.869783 0.177304 -v -0.007000 0.124321 0.214723 -vn 3.054327 3.135615 0.136903 -v -0.007000 0.133500 0.201250 -vn 3.306092 3.125880 0.216836 -v -0.007000 0.133500 0.185042 -vn 3.735356 -3.053699 0.426483 -v -0.007000 0.125366 0.183401 -vn -0.006566 6.253873 0.427612 -v -0.009000 0.133500 0.185159 -vn -3.200356 3.288620 0.615620 -v -0.015060 0.133500 0.185159 -vn 0.033606 6.252626 0.435726 -v -0.007412 0.133500 0.185086 -vn -3.343559 3.054592 0.962796 -v -0.065000 0.133909 0.182187 -vn -3.476042 -3.017974 1.131293 -v -0.065000 0.125091 0.182187 -vn -4.174073 -2.955119 0.239830 -v -0.065000 0.125424 0.183800 -vn -3.082219 -2.869785 0.177302 -v -0.065000 0.124321 0.214723 -vn -3.093906 2.869783 0.635806 -v -0.065000 0.132321 0.214723 -vn -3.228858 -3.135617 -0.136903 -v -0.065000 0.125500 0.201250 -vn -3.054327 3.135617 0.136903 -v -0.065000 0.133500 0.201250 -vn -3.306086 -3.125881 0.216826 -v -0.065000 0.125500 0.185042 -vn -3.237096 3.135666 0.135891 -v -0.065000 0.133500 0.185042 -vn -3.735327 3.053703 0.426499 -v -0.065000 0.133634 0.183401 -vn 3.139246 -3.196270 0.085838 -v -0.057000 0.125500 0.186250 -vn 3.228858 -3.135618 -0.136903 -v -0.057000 0.125500 0.201250 -vn -0.006605 -6.252311 0.439125 -v -0.063000 0.125500 0.185159 -vn 3.222150 -3.284233 0.654895 -v -0.056940 0.125500 0.185159 -vn -0.033605 -6.252628 0.435710 -v -0.064588 0.125500 0.185086 -vn 3.139246 3.196265 0.085838 -v -0.057000 0.133500 0.186250 -vn 3.054327 3.135618 0.136903 -v -0.057000 0.133500 0.201250 -vn 3.082222 -2.869783 0.177306 -v -0.057000 0.124321 0.214723 -vn 3.093899 2.869781 0.635809 -v -0.057000 0.132321 0.214723 -vn 1.680956 3.757017 -2.539482 -v -0.062374 0.133500 0.196039 -vn 2.590242 3.798386 -1.533290 -v -0.063380 0.133500 0.195029 -vn 3.034546 3.667093 -0.043479 -v -0.063749 0.133500 0.193648 -vn 2.665737 3.533909 1.489715 -v -0.063380 0.133500 0.192268 -vn 1.742716 3.310441 2.564922 -v -0.062374 0.133500 0.191258 -vn -1.742715 3.310440 2.564923 -v -0.059624 0.133500 0.191258 -vn -2.665733 3.533911 1.489719 -v -0.058617 0.133500 0.192268 -vn -3.034545 3.667092 -0.043479 -v -0.058249 0.133500 0.193648 -vn -2.590241 3.798385 -1.533291 -v -0.058617 0.133500 0.195029 -vn -1.680953 3.757013 -2.539485 -v -0.059624 0.133500 0.196039 -vn -0.817479 3.142958 3.016865 -v -0.060287 0.133500 0.190982 -vn 3.224401 3.286020 0.639042 -v -0.056940 0.133500 0.185159 -vn 0.026073 3.167491 3.124703 -v -0.060999 0.133500 0.190888 -vn -0.010520 6.252278 0.439396 -v -0.063000 0.133500 0.185159 -vn 0.791953 3.183356 3.023213 -v -0.061710 0.133500 0.190982 -vn -0.082887 6.261095 0.356603 -v -0.064588 0.133500 0.185086 -vn -0.794844 3.667070 -2.977388 -v -0.060287 0.133500 0.196315 -vn -0.000001 3.673901 -3.080299 -v -0.060999 0.133500 0.196409 -vn 0.794843 3.667071 -2.977387 -v -0.061710 0.133500 0.196315 -vn 0.000001 -3.386765 -3.342441 -v -0.011000 0.124540 0.212226 -vn 0.203534 -2.998745 2.854480 -v -0.010000 0.124059 0.217723 -vn -0.203534 -2.998745 2.854481 -v -0.012000 0.124059 0.217723 -vn -1.517277 -3.422189 -2.937443 -v -0.009625 0.124572 0.211859 -vn -2.627982 -3.519011 -1.830944 -v -0.008618 0.124660 0.210856 -vn -3.034559 -3.651244 -0.319438 -v -0.008250 0.124779 0.209487 -vn -2.627985 -3.783479 1.192058 -v -0.008618 0.124899 0.208117 -vn -1.517283 -3.880288 2.298551 -v -0.009625 0.124987 0.207114 -vn -0.000002 -3.915724 2.703562 -v -0.011000 0.125019 0.206747 -vn 1.517284 -3.880287 2.298549 -v -0.012375 0.124987 0.207114 -vn 2.590259 -2.608986 1.310884 -v -0.007402 0.124190 0.216223 -vn 1.680940 -2.737864 2.309645 -v -0.008500 0.124094 0.217322 -vn 0.794807 -2.867993 2.738076 -v -0.009224 0.124068 0.217621 -vn 2.627985 -3.783478 1.192060 -v -0.013382 0.124899 0.208117 -vn 3.034557 -3.651246 -0.319438 -v -0.013750 0.124779 0.209487 -vn 2.627980 -3.519011 -1.830946 -v -0.013382 0.124660 0.210856 -vn -2.590259 -2.608986 1.310885 -v -0.014598 0.124190 0.216223 -vn 1.517277 -3.422191 -2.937442 -v -0.012375 0.124572 0.211859 -vn -1.680942 -2.737865 2.309644 -v -0.013500 0.124094 0.217322 -vn -0.794808 -2.867992 2.738075 -v -0.012776 0.124068 0.217621 -vn -0.206500 2.998743 3.401854 -v -0.012000 0.132059 0.217723 -vn 0.206497 2.998742 3.401859 -v -0.010000 0.132059 0.217723 -vn -0.000001 3.915727 -2.703547 -v -0.011000 0.132479 0.212921 -vn 1.517267 3.880293 -2.298542 -v -0.012375 0.132511 0.212554 -vn -0.817430 2.867995 3.279082 -v -0.012776 0.132068 0.217621 -vn -2.665750 2.608986 1.723665 -v -0.014598 0.132190 0.216223 -vn -1.742734 2.737865 2.814261 -v -0.013500 0.132094 0.217322 -vn 2.627976 3.783483 -1.192063 -v -0.013382 0.132599 0.211551 -vn 3.034546 3.651246 0.319444 -v -0.013750 0.132719 0.210181 -vn 2.628009 3.519001 1.830946 -v -0.013382 0.132838 0.208812 -vn 1.517259 3.422202 2.937429 -v -0.012375 0.132926 0.207809 -vn -0.000002 3.386772 3.342432 -v -0.011000 0.132958 0.207442 -vn -1.517257 3.422203 2.937431 -v -0.009625 0.132926 0.207809 -vn -2.628010 3.519002 1.830945 -v -0.008618 0.132838 0.208812 -vn -3.034548 3.651244 0.319443 -v -0.008250 0.132719 0.210181 -vn -2.627978 3.783482 -1.192058 -v -0.008618 0.132599 0.211551 -vn 2.665750 2.608985 1.723663 -v -0.007402 0.132190 0.216223 -vn -1.517263 3.880291 -2.298542 -v -0.009625 0.132511 0.212554 -vn 1.742727 2.737864 2.814259 -v -0.008500 0.132094 0.217322 -vn 0.817435 2.867996 3.279082 -v -0.009224 0.132068 0.217621 -vn -0.000001 2.909627 -2.797796 -v -0.060999 0.125981 0.195751 -vn -1.529206 2.855056 -2.384907 -v -0.059624 0.126013 0.195384 -vn 1.529208 2.855051 -2.384905 -v -0.062374 0.126013 0.195384 -vn 2.628011 2.740273 -1.283325 -v -0.063380 0.126101 0.194381 -vn 3.034544 2.608030 0.228172 -v -0.063749 0.126221 0.193011 -vn 2.627987 2.475801 1.739669 -v -0.063380 0.126341 0.191642 -vn 1.517528 2.381587 2.846326 -v -0.062374 0.126428 0.190639 -vn -2.628010 2.740274 -1.283326 -v -0.058617 0.126101 0.194381 -vn -3.034544 2.608031 0.228171 -v -0.058249 0.126221 0.193011 -vn -2.627983 2.475797 1.739672 -v -0.058617 0.126341 0.191642 -vn -1.529995 2.398692 2.844349 -v -0.059624 0.126428 0.190639 -vn 0.012781 2.362662 3.256157 -v -0.060999 0.126460 0.190272 -vn -0.000000 6.259274 0.547625 -v -0.060999 0.126221 0.193011 -vn -1.201648 6.041221 0.567413 -v -0.063975 0.140404 0.174250 -vn -2.357323 5.691090 0.587543 -v -0.064913 0.140119 0.174250 -vn -3.422077 5.121492 0.567426 -v -0.065778 0.139657 0.174250 -vn -4.344511 4.374912 0.568681 -v -0.066536 0.139036 0.174250 -vn -5.143697 3.430759 0.470164 -v -0.067157 0.138278 0.174250 -vn -5.700220 2.344496 0.576647 -v -0.067619 0.137413 0.174250 -vn -6.041724 1.209030 0.560907 -v -0.067904 0.136475 0.174250 -vn 6.041720 1.209051 0.560914 -v -0.004096 0.136475 0.174250 -vn 5.704723 2.339183 0.568493 -v -0.004381 0.137413 0.174250 -vn 5.141847 3.437531 0.460371 -v -0.004843 0.138278 0.174250 -vn 4.345711 4.372486 0.572106 -v -0.005464 0.139036 0.174250 -vn 3.422080 5.121491 0.567429 -v -0.006222 0.139657 0.174250 -vn 2.357321 5.691088 0.587548 -v -0.007087 0.140119 0.174250 -vn 1.201641 6.041220 0.567422 -v -0.008025 0.140404 0.174250 -vn 1.201661 -6.041221 0.567420 -v -0.008025 0.118596 0.174250 -vn 2.357325 -5.691087 0.587546 -v -0.007087 0.118881 0.174250 -vn 3.422078 -5.121498 0.567412 -v -0.006222 0.119343 0.174250 -vn 4.344521 -4.374897 0.568676 -v -0.005464 0.119964 0.174250 -vn 5.143710 -3.430768 0.470135 -v -0.004843 0.120722 0.174250 -vn 5.700214 -2.344499 0.576644 -v -0.004381 0.121587 0.174250 -vn 6.041728 -1.209039 0.560905 -v -0.004096 0.122525 0.174250 -vn -6.041729 -1.209023 0.560902 -v -0.067904 0.122525 0.174250 -vn -5.704718 -2.339189 0.568485 -v -0.067619 0.121587 0.174250 -vn -5.141846 -3.437541 0.460367 -v -0.067157 0.120722 0.174250 -vn -4.345717 -4.372486 0.572091 -v -0.066536 0.119964 0.174250 -vn -3.422085 -5.121494 0.567404 -v -0.065778 0.119343 0.174250 -vn -2.357315 -5.691095 0.587540 -v -0.064913 0.118881 0.174250 -vn -1.201667 -6.041218 0.567423 -v -0.063975 0.118596 0.174250 -vn 3.459709 3.593660 3.790127 -v -0.005694 0.138519 0.175598 -vn 3.248924 3.489892 3.986729 -v -0.005859 0.138641 0.175635 -vn 2.901780 3.595871 4.247664 -v -0.005983 0.138634 0.175725 -vn 5.174271 1.249945 3.322907 -v -0.004596 0.136760 0.175476 -vn 5.214401 0.856212 3.372109 -v -0.004546 0.136364 0.175529 -vn 5.634686 1.088242 2.117198 -v -0.004238 0.136447 0.174997 -vn 5.250834 0.484479 3.380807 -v -0.004512 0.135942 0.175562 -vn 5.214334 0.114410 3.489289 -v -0.004500 0.135500 0.175573 -vn 5.593852 0.254599 2.750687 -v -0.004145 0.135500 0.174997 -vn 5.200012 2.993110 1.753590 -v -0.004904 0.138162 0.174918 -vn 5.151153 2.821734 2.171326 -v -0.004858 0.137994 0.175046 -vn 5.439534 2.127808 1.964302 -v -0.004514 0.137358 0.174997 -vn 5.091584 2.641100 2.542764 -v -0.004806 0.137791 0.175164 -vn 5.066896 2.455305 2.774293 -v -0.004787 0.137716 0.175200 -vn 5.064904 2.146903 3.017983 -v -0.004727 0.137457 0.175304 -vn 5.151550 1.754821 3.113845 -v -0.004665 0.137160 0.175392 -vn 5.183482 1.488287 3.205685 -v -0.004606 0.136822 0.175465 -vn 4.973466 3.435723 1.377190 -v -0.004920 0.138220 0.174863 -vn 4.718604 3.630272 1.916164 -v -0.004951 0.138231 0.174920 -vn 3.763269 3.593596 3.490103 -v -0.005460 0.138426 0.175460 -vn 3.940263 4.119621 2.185534 -v -0.005567 0.138933 0.174997 -vn 4.142560 3.538687 3.100242 -v -0.005267 0.138351 0.175308 -vn 4.418056 3.531085 2.713004 -v -0.005108 0.138290 0.175144 -vn 4.575567 3.550691 2.404549 -v -0.005069 0.138275 0.175097 -vn 2.541761 3.465761 4.575782 -v -0.006321 0.138766 0.175831 -vn 2.554485 3.909915 4.019227 -v -0.006532 0.139194 0.175635 -vn 2.079418 3.521540 4.767337 -v -0.006727 0.138914 0.175919 -vn 0.922031 4.383837 4.179631 -v -0.008133 0.139857 0.175635 -vn 0.218465 4.442776 4.329693 -v -0.009000 0.139942 0.175635 -vn 0.187687 3.385446 5.241193 -v -0.009000 0.139500 0.175982 -vn 1.713424 3.559895 4.881168 -v -0.006995 0.139003 0.175961 -vn 1.713112 4.212858 4.112018 -v -0.007300 0.139604 0.175635 -vn 1.164926 3.536618 5.052135 -v -0.007571 0.139162 0.176020 -vn 0.627156 3.498525 5.170523 -v -0.008249 0.139286 0.176056 -vn 0.127555 3.138525 5.436417 -v -0.009000 0.139333 0.176068 -vn 1.147959 5.550569 2.216088 -v -0.008053 0.140262 0.174997 -vn 0.287752 5.875984 1.953318 -v -0.009000 0.140355 0.174997 -vn 0.289201 5.313801 3.241627 -v -0.009000 0.140232 0.175250 -vn 3.137046 4.694908 2.243914 -v -0.006302 0.139537 0.174997 -vn 2.160831 5.216702 2.243909 -v -0.007142 0.139986 0.174997 -vn 5.987597 0.298877 1.692093 -v -0.004129 0.135500 0.174957 -vn -0.104042 2.191759 5.838999 -v -0.025000 0.139333 0.176068 -vn -0.187687 3.385462 5.241224 -v -0.063000 0.139500 0.175982 -vn -0.141656 3.139586 5.435531 -v -0.063000 0.139333 0.176068 -vn 0.104049 2.191760 5.838984 -v -0.047000 0.139333 0.176068 -vn -0.218465 4.442780 4.329698 -v -0.063000 0.139942 0.175635 -vn -0.289201 5.313800 3.241626 -v -0.063000 0.140232 0.175250 -vn -0.287745 5.875980 1.953322 -v -0.063000 0.140355 0.174997 -vn 5.215810 -0.112540 3.487363 -v -0.004500 0.123500 0.175573 -vn 5.596495 -0.247819 2.747282 -v -0.004145 0.123500 0.174997 -vn 5.987600 -0.298878 1.692093 -v -0.004129 0.123500 0.174957 -vn -0.657176 3.491671 5.168328 -v -0.063751 0.139286 0.176056 -vn -0.936581 4.364577 4.190129 -v -0.063867 0.139857 0.175635 -vn -1.691873 4.205954 4.121551 -v -0.064700 0.139604 0.175635 -vn -1.136634 3.540405 5.051465 -v -0.064429 0.139162 0.176020 -vn -2.550743 3.911811 4.019690 -v -0.065468 0.139194 0.175635 -vn -2.044221 3.533798 4.773671 -v -0.065273 0.138914 0.175919 -vn -1.702187 3.529593 4.905074 -v -0.065005 0.139003 0.175961 -vn -3.770144 3.586201 3.490457 -v -0.066540 0.138426 0.175460 -vn -3.460309 3.563390 3.825638 -v -0.066306 0.138519 0.175598 -vn -3.258641 3.486281 3.984865 -v -0.066141 0.138641 0.175635 -vn -2.933743 3.477620 4.329422 -v -0.066017 0.138634 0.175725 -vn -2.554370 3.505468 4.541595 -v -0.065679 0.138766 0.175831 -vn -5.103752 3.251003 1.288088 -v -0.067080 0.138220 0.174863 -vn -4.724774 3.582036 2.028361 -v -0.067049 0.138231 0.174920 -vn -3.934982 4.124999 2.189938 -v -0.066433 0.138933 0.174997 -vn -4.585045 3.538537 2.402376 -v -0.066931 0.138275 0.175097 -vn -4.418819 3.525027 2.718519 -v -0.066892 0.138290 0.175144 -vn -4.143038 3.532271 3.105710 -v -0.066733 0.138351 0.175308 -vn -5.254155 2.921395 1.683714 -v -0.067096 0.138162 0.174918 -vn -5.206834 2.801349 2.018810 -v -0.067142 0.137994 0.175046 -vn -5.065427 2.147008 3.017143 -v -0.067273 0.137457 0.175304 -vn -5.067536 2.454482 2.773949 -v -0.067213 0.137716 0.175200 -vn -5.431438 2.143398 1.953796 -v -0.067486 0.137358 0.174997 -vn -5.093324 2.639584 2.541227 -v -0.067194 0.137791 0.175164 -vn -5.206537 0.883016 3.382376 -v -0.067454 0.136364 0.175529 -vn -5.177416 1.253400 3.317264 -v -0.067404 0.136760 0.175476 -vn -5.638659 1.103839 2.107060 -v -0.067762 0.136447 0.174997 -vn -5.186110 1.503285 3.191607 -v -0.067394 0.136822 0.175465 -vn -5.160924 1.734524 3.105404 -v -0.067335 0.137160 0.175392 -vn -5.236203 0.454895 3.415017 -v -0.067488 0.135942 0.175562 -vn -5.596621 0.247835 2.746920 -v -0.067855 0.135500 0.174997 -vn -5.215807 0.112571 3.487364 -v -0.067500 0.135500 0.175573 -vn -5.987748 0.298879 1.691744 -v -0.067871 0.135500 0.174957 -vn -3.137041 4.694912 2.243905 -v -0.065698 0.139537 0.174997 -vn -2.160833 5.216704 2.243908 -v -0.064858 0.139986 0.174997 -vn -1.147964 5.550566 2.216097 -v -0.063947 0.140262 0.174997 -vn 0.612856 -3.447650 5.197942 -v -0.008249 0.119714 0.176056 -vn 0.109344 -2.990558 5.523173 -v -0.009000 0.119667 0.176068 -vn 0.187679 -3.385479 5.241229 -v -0.009000 0.119500 0.175982 -vn 0.936580 -4.364587 4.190124 -v -0.008133 0.119143 0.175635 -vn 1.691870 -4.205945 4.121562 -v -0.007300 0.119396 0.175635 -vn 1.136652 -3.540381 5.051483 -v -0.007571 0.119838 0.176020 -vn 2.550720 -3.911809 4.019709 -v -0.006532 0.119806 0.175635 -vn 2.044210 -3.533804 4.773675 -v -0.006727 0.120086 0.175919 -vn 1.702225 -3.529607 4.905046 -v -0.006995 0.119997 0.175961 -vn 3.770157 -3.586210 3.490426 -v -0.005460 0.120574 0.175460 -vn 3.460296 -3.563399 3.825639 -v -0.005694 0.120481 0.175598 -vn 3.258627 -3.486321 3.984838 -v -0.005859 0.120359 0.175635 -vn 2.933742 -3.477632 4.329387 -v -0.005983 0.120366 0.175725 -vn 2.554326 -3.505500 4.541589 -v -0.006321 0.120234 0.175831 -vn 5.103786 -3.250971 1.288021 -v -0.004920 0.120780 0.174863 -vn 4.724890 -3.581859 2.028329 -v -0.004951 0.120769 0.174920 -vn 3.934990 -4.125012 2.189937 -v -0.005567 0.120067 0.174997 -vn 4.584909 -3.538568 2.402551 -v -0.005069 0.120725 0.175097 -vn 4.418647 -3.525051 2.718825 -v -0.005108 0.120710 0.175144 -vn 4.143085 -3.532290 3.105632 -v -0.005267 0.120649 0.175308 -vn 5.254069 -2.921510 1.683744 -v -0.004904 0.120838 0.174918 -vn 5.206820 -2.801334 2.018833 -v -0.004858 0.121006 0.175046 -vn 5.065442 -2.146960 3.017134 -v -0.004727 0.121543 0.175304 -vn 5.067569 -2.454585 2.773771 -v -0.004787 0.121284 0.175200 -vn 5.431454 -2.143385 1.953785 -v -0.004514 0.121642 0.174997 -vn 5.093343 -2.639675 2.541123 -v -0.004806 0.121209 0.175164 -vn 5.206540 -0.883028 3.382377 -v -0.004546 0.122636 0.175529 -vn 5.177423 -1.253455 3.317220 -v -0.004596 0.122240 0.175476 -vn 5.638658 -1.103855 2.107047 -v -0.004238 0.122553 0.174997 -vn 5.186119 -1.503353 3.191570 -v -0.004606 0.122178 0.175465 -vn 5.160938 -1.734508 3.105393 -v -0.004665 0.121840 0.175392 -vn 5.236207 -0.454885 3.415007 -v -0.004512 0.123058 0.175562 -vn 0.218483 -4.442762 4.329693 -v -0.009000 0.119058 0.175635 -vn 0.289209 -5.313820 3.241601 -v -0.009000 0.118768 0.175250 -vn 3.137032 -4.694905 2.243898 -v -0.006302 0.119463 0.174997 -vn 2.160824 -5.216709 2.243908 -v -0.007142 0.119014 0.174997 -vn 1.147962 -5.550567 2.216098 -v -0.008053 0.118738 0.174997 -vn 0.287752 -5.875976 1.953346 -v -0.009000 0.118645 0.174997 -vn -5.214329 -0.114443 3.489291 -v -0.067500 0.123500 0.175573 -vn -5.593979 -0.254614 2.750324 -v -0.067855 0.123500 0.174997 -vn -5.987745 -0.298881 1.691741 -v -0.067871 0.123500 0.174957 -vn 0.116149 -2.194673 5.837478 -v -0.047000 0.119667 0.176068 -vn -0.123255 -3.138030 5.436655 -v -0.063000 0.119667 0.176068 -vn -0.187679 -3.385463 5.241197 -v -0.063000 0.119500 0.175982 -vn -0.112627 -2.193450 5.838108 -v -0.025000 0.119667 0.176068 -vn -0.218483 -4.442758 4.329688 -v -0.063000 0.119058 0.175635 -vn -0.289209 -5.313820 3.241601 -v -0.063000 0.118768 0.175250 -vn -0.287751 -5.875978 1.953348 -v -0.063000 0.118645 0.174997 -vn -3.459729 -3.593639 3.790132 -v -0.066306 0.120481 0.175598 -vn -3.248931 -3.489882 3.986727 -v -0.066141 0.120359 0.175635 -vn -2.901764 -3.595889 4.247653 -v -0.066017 0.120366 0.175725 -vn -5.174264 -1.249871 3.322954 -v -0.067404 0.122240 0.175476 -vn -5.214396 -0.856201 3.372120 -v -0.067454 0.122636 0.175529 -vn -5.634687 -1.088239 2.117189 -v -0.067762 0.122553 0.174997 -vn -5.250823 -0.484486 3.380833 -v -0.067488 0.123058 0.175562 -vn -5.200054 -2.993072 1.753561 -v -0.067096 0.120838 0.174918 -vn -5.151130 -2.821741 2.171410 -v -0.067142 0.121006 0.175046 -vn -5.439500 -2.127819 1.964333 -v -0.067486 0.121642 0.174997 -vn -5.091589 -2.641161 2.542697 -v -0.067194 0.121209 0.175164 -vn -5.066889 -2.455324 2.774284 -v -0.067213 0.121284 0.175200 -vn -5.064877 -2.146900 3.018046 -v -0.067273 0.121543 0.175304 -vn -5.151533 -1.754860 3.113863 -v -0.067335 0.121840 0.175392 -vn -5.183475 -1.488256 3.205698 -v -0.067394 0.122178 0.175465 -vn -4.973651 -3.435598 1.377019 -v -0.067080 0.120780 0.174863 -vn -4.718865 -3.629947 1.915962 -v -0.067049 0.120769 0.174920 -vn -3.763312 -3.593572 3.490072 -v -0.066540 0.120574 0.175460 -vn -3.940279 -4.119622 2.185519 -v -0.066433 0.120067 0.174997 -vn -4.142561 -3.538688 3.100250 -v -0.066733 0.120649 0.175308 -vn -4.418003 -3.531094 2.713090 -v -0.066892 0.120710 0.175144 -vn -4.575529 -3.550662 2.404660 -v -0.066931 0.120725 0.175097 -vn -2.541702 -3.465765 4.575810 -v -0.065679 0.120234 0.175831 -vn -2.554456 -3.909910 4.019254 -v -0.065468 0.119806 0.175635 -vn -2.079435 -3.521518 4.767349 -v -0.065273 0.120086 0.175919 -vn -0.922038 -4.383837 4.179630 -v -0.063867 0.119143 0.175635 -vn -1.713430 -3.559884 4.881173 -v -0.065005 0.119997 0.175961 -vn -1.713106 -4.212850 4.112024 -v -0.064700 0.119396 0.175635 -vn -1.164943 -3.536617 5.052135 -v -0.064429 0.119838 0.176020 -vn -0.627163 -3.498542 5.170506 -v -0.063751 0.119714 0.176056 -vn -1.147967 -5.550566 2.216094 -v -0.063947 0.118738 0.174997 -vn -3.137030 -4.694903 2.243898 -v -0.065698 0.119463 0.174997 -vn -2.160817 -5.216712 2.243912 -v -0.064858 0.119014 0.174997 -vn -2.765908 -3.982037 1.776689 -v -0.008413 0.123840 0.179626 -vn -2.553107 -4.646758 1.593271 -v -0.008554 0.124130 0.180099 -vn -1.063891 1.439310 3.019219 -v -0.009791 0.120865 0.176719 -vn -1.769160 1.139141 2.932073 -v -0.009372 0.121053 0.176842 -vn -2.123606 0.951185 2.914962 -v -0.009232 0.121141 0.176902 -vn -2.425369 0.781998 2.838987 -v -0.009000 0.121323 0.177029 -vn -0.357906 1.625994 2.959032 -v -0.010425 0.120751 0.176648 -vn 0.235392 1.691486 2.948572 -v -0.010500 0.120750 0.176648 -vn 0.920628 1.480397 3.019218 -v -0.011110 0.120834 0.176700 -vn 1.573285 1.044735 2.808860 -v -0.011629 0.121054 0.176843 -vn 2.123949 0.602310 2.801104 -v -0.011793 0.121159 0.176914 -vn 2.622264 -0.015374 2.711832 -v -0.012295 0.121643 0.177268 -vn 3.156030 -1.601738 2.439206 -v -0.012647 0.122326 0.177851 -vn 2.918344 -0.637401 2.563311 -v -0.012454 0.121885 0.177463 -vn 2.787767 -4.398880 1.533197 -v -0.012448 0.124126 0.180101 -vn 2.901358 -4.003752 1.806277 -v -0.012564 0.123896 0.179726 -vn 3.154777 -3.202064 2.049172 -v -0.012743 0.123174 0.178747 -vn 3.222671 -2.432881 2.184778 -v -0.012750 0.123031 0.178579 -vn 2.518941 -4.940773 1.475797 -v -0.012375 0.124243 0.180305 -vn 1.899403 -5.496696 1.238722 -v -0.011885 0.124773 0.181415 -vn 0.303468 -6.248766 0.446565 -v -0.010706 0.125241 0.182896 -vn 0.678625 -6.178273 0.685319 -v -0.010938 0.125207 0.182756 -vn 1.067959 -6.045243 0.795013 -v -0.011424 0.125051 0.182197 -vn 1.490547 -5.761066 1.045080 -v -0.011630 0.124945 0.181875 -vn -0.861884 -6.157508 0.597431 -v -0.009933 0.125177 0.182639 -vn -0.539814 -6.224493 0.539586 -v -0.010128 0.125219 0.182805 -vn 0.045359 -6.265555 0.392680 -v -0.010536 0.125250 0.182935 -vn -0.086005 -6.174994 1.091183 -v -0.010363 0.125246 0.182918 -vn -2.454819 -5.073722 1.369400 -v -0.008810 0.124486 0.180770 -vn -2.157943 -5.322432 1.208199 -v -0.009000 0.124677 0.181186 -vn -2.097933 -5.540036 1.075516 -v -0.009114 0.124772 0.181413 -vn -1.533780 -5.775531 1.091419 -v -0.009372 0.124947 0.181879 -vn -1.126441 -5.946208 1.011957 -v -0.009486 0.125009 0.182063 -vn -2.700261 0.364466 2.800042 -v -0.008957 0.121362 0.177057 -vn -2.868150 -0.314881 2.795907 -v -0.008536 0.121903 0.177466 -vn -2.843981 -1.108913 2.526830 -v -0.008476 0.122017 0.177560 -vn -3.528059 -1.828849 2.294650 -v -0.008272 0.122687 0.178180 -vn -4.216249 -2.047184 2.025438 -v -0.008256 0.122831 0.178331 -vn -4.272247 -2.593750 2.070887 -v -0.008250 0.123009 0.178528 -vn -3.195060 -3.451609 1.997537 -v -0.008319 0.123553 0.179209 -vn 1.494224 -3.006374 1.810014 -v -0.055375 0.124949 0.180786 -vn 2.399833 -3.236789 1.482274 -v -0.055964 0.125185 0.181817 -vn -3.273664 -2.853589 2.250189 -v -0.054250 0.123000 0.178544 -vn -0.882092 -1.760774 2.473019 -v -0.054376 0.123744 0.179498 -vn -0.294834 -2.010613 2.500525 -v -0.054551 0.124125 0.179694 -vn 0.654889 -2.591345 2.057256 -v -0.055090 0.124754 0.180372 -vn -1.793213 0.911748 2.942085 -v -0.055375 0.121051 0.176841 -vn -2.470182 0.249710 2.819814 -v -0.054893 0.121425 0.177103 -vn -2.888157 -0.477690 2.678545 -v -0.054551 0.121875 0.177454 -vn -3.131371 -1.295342 2.548140 -v -0.054457 0.122056 0.177608 -vn 0.918212 1.418105 2.980978 -v -0.057090 0.120829 0.176697 -vn -0.029765 1.625516 3.074106 -v -0.056500 0.120750 0.176648 -vn -0.889502 1.403700 3.011643 -v -0.055910 0.120829 0.176697 -vn 2.519294 0.255393 2.802734 -v -0.058107 0.121425 0.177103 -vn 1.774328 0.955704 2.909469 -v -0.057625 0.121051 0.176841 -vn 3.107702 -1.329878 2.489810 -v -0.058543 0.122056 0.177608 -vn 2.852063 -0.367787 2.629746 -v -0.058453 0.121883 0.177461 -vn 2.486033 -4.974174 1.522854 -v -0.058449 0.124125 0.180098 -vn 2.988755 -4.048011 1.748252 -v -0.058555 0.123916 0.179758 -vn 3.227575 -2.916071 2.247788 -v -0.058750 0.123000 0.178544 -vn 0.517589 -6.233786 0.484531 -v -0.056754 0.125236 0.182874 -vn 0.014886 -6.209230 0.784926 -v -0.056500 0.125250 0.182937 -vn 2.770275 -3.186726 1.423674 -v -0.056434 0.125249 0.182932 -vn 0.691582 -6.192451 0.552149 -v -0.056971 0.125200 0.182728 -vn 1.014168 -6.060045 0.802633 -v -0.057318 0.125096 0.182345 -vn 1.507322 -5.765307 1.147018 -v -0.057625 0.124949 0.181884 -vn -0.203535 -2.998744 2.854481 -v -0.062000 0.124059 0.217723 -vn 0.203534 -2.998744 2.854481 -v -0.060000 0.124059 0.217723 -vn -0.206502 2.998742 3.401853 -v -0.062000 0.132059 0.217723 -vn 0.206497 2.998742 3.401859 -v -0.060000 0.132059 0.217723 -vn 1.517260 3.422205 2.937428 -v -0.062375 0.132926 0.207809 -vn -0.000002 3.386772 3.342432 -v -0.061000 0.132958 0.207442 -vn -1.517257 3.422203 2.937431 -v -0.059625 0.132926 0.207809 -vn -2.665752 2.608985 1.723661 -v -0.064598 0.132190 0.216223 -vn 1.517269 3.880294 -2.298540 -v -0.062375 0.132511 0.212554 -vn -1.742731 2.737861 2.814261 -v -0.063500 0.132094 0.217322 -vn -0.000001 3.915727 -2.703548 -v -0.061000 0.132479 0.212921 -vn -0.817427 2.867998 3.279083 -v -0.062776 0.132068 0.217621 -vn 2.627978 3.783481 -1.192061 -v -0.063382 0.132599 0.211551 -vn 3.034546 3.651246 0.319444 -v -0.063750 0.132719 0.210181 -vn 2.628011 3.518999 1.830944 -v -0.063382 0.132838 0.208812 -vn -2.628010 3.519001 1.830947 -v -0.058618 0.132838 0.208812 -vn -3.034547 3.651246 0.319444 -v -0.058250 0.132719 0.210181 -vn -2.627978 3.783481 -1.192060 -v -0.058618 0.132599 0.211551 -vn 2.665750 2.608987 1.723664 -v -0.057402 0.132190 0.216223 -vn -1.517263 3.880290 -2.298542 -v -0.059625 0.132511 0.212554 -vn 1.742729 2.737864 2.814258 -v -0.058500 0.132094 0.217322 -vn 0.817436 2.867996 3.279082 -v -0.059224 0.132068 0.217621 -vn 1.517286 -3.880290 2.298547 -v -0.062375 0.124987 0.207114 -vn 0.000000 -3.915724 2.703559 -v -0.061000 0.125019 0.206747 -vn -1.517284 -3.880288 2.298549 -v -0.059625 0.124987 0.207114 -vn 0.000000 -3.386763 -3.342442 -v -0.061000 0.124540 0.212226 -vn -1.517277 -3.422189 -2.937443 -v -0.059625 0.124572 0.211859 -vn -2.627981 -3.519010 -1.830946 -v -0.058618 0.124660 0.210856 -vn -3.034558 -3.651247 -0.319438 -v -0.058250 0.124779 0.209487 -vn -2.627985 -3.783478 1.192060 -v -0.058618 0.124899 0.208117 -vn 2.627986 -3.783476 1.192058 -v -0.063382 0.124899 0.208117 -vn 3.034557 -3.651246 -0.319438 -v -0.063750 0.124779 0.209487 -vn 2.627982 -3.519011 -1.830944 -v -0.063382 0.124660 0.210856 -vn -2.590261 -2.608986 1.310881 -v -0.064598 0.124190 0.216223 -vn 1.517278 -3.422193 -2.937440 -v -0.062375 0.124572 0.211859 -vn -1.680939 -2.737861 2.309644 -v -0.063500 0.124094 0.217322 -vn -0.794806 -2.867996 2.738076 -v -0.062776 0.124068 0.217621 -vn 2.590260 -2.608988 1.310885 -v -0.057402 0.124190 0.216223 -vn 1.680941 -2.737863 2.309644 -v -0.058500 0.124094 0.217322 -vn 0.794808 -2.867994 2.738076 -v -0.059224 0.124068 0.217621 -vn 5.837563 0.037237 2.278824 -v -0.006354 0.123500 0.178652 -vn 3.765397 -2.751606 3.024914 -v -0.006425 0.123500 0.178845 -vn 3.680390 -2.455842 3.481491 -v -0.005832 0.122467 0.177406 -vn 4.645889 -3.002644 2.924791 -v -0.005029 0.121029 0.175390 -vn 4.839495 -3.317094 2.226395 -v -0.004932 0.120810 0.174941 -vn 4.882980 -3.322073 2.136866 -v -0.004931 0.120809 0.174938 -vn 4.970950 -3.303073 1.958389 -v -0.004921 0.120784 0.174874 -vn 4.706972 -3.066426 2.770333 -v -0.004995 0.120956 0.175256 -vn 4.778245 -3.090044 2.637187 -v -0.004979 0.120921 0.175187 -vn 4.815061 -3.156502 2.493199 -v -0.004972 0.120904 0.175153 -vn 4.533408 -2.895133 3.160052 -v -0.005062 0.121098 0.175510 -vn 4.608608 -2.949398 3.029094 -v -0.005051 0.121076 0.175473 -vn 4.290689 -2.674635 3.553380 -v -0.005278 0.121511 0.176136 -vn 4.381521 -2.749324 3.419892 -v -0.005145 0.121263 0.175775 -vn 4.463916 -2.776562 3.331390 -v -0.005140 0.121253 0.175759 -vn 4.467701 -2.830646 3.285836 -v -0.005137 0.121246 0.175748 -vn 4.206236 -2.608292 3.653716 -v -0.005302 0.121555 0.176197 -vn 4.158903 -2.554928 3.710751 -v -0.005461 0.121835 0.176578 -vn 4.142877 -2.536021 3.736740 -v -0.005497 0.121897 0.176659 -vn 4.103174 -2.504907 3.754537 -v -0.005500 0.121902 0.176666 -vn 4.125239 -2.340842 3.763405 -v -0.005628 0.122122 0.176954 -vn 5.313278 -0.721029 3.264320 -v -0.005651 0.122291 0.177036 -vn 3.831994 -2.283072 3.741406 -v -0.005723 0.122283 0.177165 -vn 3.589216 -2.564911 3.588070 -v -0.005731 0.122295 0.177181 -vn 3.618534 -2.477151 3.550984 -v -0.005776 0.122372 0.177281 -vn 5.246590 -0.329646 3.435016 -v -0.005632 0.122885 0.177104 -vn 5.366730 -0.138176 3.227989 -v -0.005625 0.123500 0.177127 -vn 3.639912 2.571946 3.473089 -v -0.005947 0.136340 0.177661 -vn 3.815816 2.382991 2.965205 -v -0.006425 0.135500 0.178845 -vn 5.810102 -0.080436 2.363693 -v -0.006354 0.135500 0.178652 -vn 3.868237 2.493510 3.877032 -v -0.005510 0.137081 0.176688 -vn 3.582232 2.601254 3.588011 -v -0.005776 0.136628 0.177281 -vn 5.333292 0.769435 3.221832 -v -0.005651 0.136709 0.177036 -vn 5.356894 0.407768 3.234790 -v -0.005632 0.136115 0.177104 -vn 5.385746 0.090320 3.193836 -v -0.005625 0.135500 0.177127 -vn 4.169237 2.494914 3.720662 -v -0.005470 0.137149 0.176598 -vn 4.366505 2.751255 3.432526 -v -0.005164 0.137701 0.175829 -vn 4.225664 2.660884 3.605913 -v -0.005268 0.137508 0.176109 -vn 4.166131 2.572238 3.698947 -v -0.005437 0.137206 0.176522 -vn 4.730577 3.059219 2.742021 -v -0.004992 0.138051 0.175243 -vn 4.650164 3.000452 2.920708 -v -0.005027 0.137974 0.175386 -vn 4.610404 2.951069 3.025023 -v -0.005051 0.137925 0.175471 -vn 4.543026 2.888817 3.154662 -v -0.005061 0.137903 0.175509 -vn 4.476272 2.795361 3.294617 -v -0.005138 0.137750 0.175753 -vn 4.421090 2.786220 3.358397 -v -0.005147 0.137733 0.175780 -vn 4.967113 3.296192 1.978443 -v -0.004921 0.138216 0.174874 -vn 4.866692 3.226789 2.298988 -v -0.004945 0.138158 0.175018 -vn 4.828872 3.120646 2.511406 -v -0.004970 0.138100 0.175145 -vn 4.810115 3.079512 2.590335 -v -0.004976 0.138087 0.175171 -vn 3.484249 2.777443 2.404145 -v -0.006697 0.134950 0.179745 -vn 3.793385 2.935015 1.725804 -v -0.006904 0.134418 0.180802 -vn 3.429515 -2.882403 2.243691 -v -0.006790 0.124268 0.180148 -vn 3.629409 -2.937339 1.579833 -v -0.006966 0.124813 0.181363 -vn 0.453207 -5.202851 3.450240 -v -0.006879 0.123967 0.179644 -vn 1.696216 -4.135993 4.385254 -v -0.006188 0.122316 0.177393 -vn 0.339955 -4.076661 4.725610 -v -0.008106 0.122086 0.177593 -vn 0.224769 -5.261812 3.372686 -v -0.007908 0.123930 0.179730 -vn -0.048001 -6.074242 1.509963 -v -0.009000 0.125096 0.182345 -vn 0.231495 -6.020126 1.662558 -v -0.007671 0.125100 0.182296 -vn 0.916865 -4.149572 4.572668 -v -0.007280 0.122163 0.177546 -vn 1.290600 -4.128748 4.515852 -v -0.006545 0.122261 0.177458 -vn 0.901774 4.112937 4.605710 -v -0.007280 0.136837 0.177546 -vn 0.434841 4.098763 4.678141 -v -0.008106 0.136914 0.177593 -vn 0.376071 5.240606 3.361272 -v -0.007908 0.135070 0.179730 -vn 0.678233 5.215916 3.404439 -v -0.006879 0.135033 0.179644 -vn 0.212466 5.972107 1.773071 -v -0.007671 0.133900 0.182296 -vn 1.721040 4.096907 4.424910 -v -0.006188 0.136684 0.177393 -vn 1.336315 4.073839 4.552349 -v -0.006545 0.136739 0.177458 -vn 0.007707 5.975992 1.745230 -v -0.009000 0.133904 0.182345 -vn 0.049271 5.243922 3.358970 -v -0.009000 0.135084 0.179758 -vn 0.080055 4.083985 4.703230 -v -0.009000 0.136944 0.177608 -vn -1.003191 -1.689355 5.713789 -v -0.021910 0.120896 0.176739 -vn -0.624234 -1.373370 5.981126 -v -0.022785 0.120500 0.176498 -vn -0.469929 -1.630554 6.042991 -v -0.024810 0.119737 0.176101 -vn -0.446324 -1.586853 6.056767 -v -0.024981 0.119674 0.176071 -vn -1.411202 -2.025282 5.316134 -v -0.019969 0.122056 0.177608 -vn -1.866787 -2.313530 4.819163 -v -0.019122 0.122643 0.178160 -vn -2.280100 -2.629196 4.117093 -v -0.017394 0.123916 0.179758 -vn -2.652107 -2.871516 3.362902 -v -0.016910 0.124280 0.180372 -vn -2.926507 -3.078968 2.502522 -v -0.015794 0.125096 0.182345 -vn -3.183313 -3.216299 1.516958 -v -0.015489 0.125298 0.183160 -vn -0.299536 2.000235 5.905121 -v -0.024981 0.139326 0.176071 -vn -0.524837 1.589012 5.881712 -v -0.022785 0.138500 0.176498 -vn -0.976351 1.742704 5.682867 -v -0.021910 0.138104 0.176739 -vn -3.130401 3.215508 1.537818 -v -0.015489 0.133702 0.183160 -vn -2.645634 2.870612 3.365394 -v -0.016910 0.134720 0.180372 -vn -2.925464 3.083395 2.492451 -v -0.015794 0.133904 0.182345 -vn -1.416331 2.019327 5.320574 -v -0.019969 0.136944 0.177608 -vn -1.876991 2.311814 4.820407 -v -0.019122 0.136357 0.178160 -vn -2.294865 2.616243 4.133553 -v -0.017394 0.135084 0.179758 -vn -5.837565 -0.037239 2.278824 -v -0.065646 0.135500 0.178652 -vn -3.765395 2.751598 3.024915 -v -0.065575 0.135500 0.178845 -vn -3.680348 2.455899 3.481410 -v -0.066168 0.136533 0.177406 -vn -4.645989 3.002697 2.924635 -v -0.066971 0.137971 0.175390 -vn -4.839780 3.315999 2.227584 -v -0.067068 0.138190 0.174941 -vn -4.883108 3.321310 2.137669 -v -0.067069 0.138191 0.174938 -vn -4.970903 3.303165 1.958350 -v -0.067079 0.138216 0.174874 -vn -4.706907 3.066399 2.770475 -v -0.067005 0.138044 0.175256 -vn -4.778201 3.090254 2.636956 -v -0.067021 0.138079 0.175187 -vn -4.815279 3.156817 2.492526 -v -0.067028 0.138096 0.175153 -vn -4.533333 2.895046 3.160244 -v -0.066938 0.137902 0.175510 -vn -4.608517 2.949236 3.029280 -v -0.066949 0.137924 0.175473 -vn -4.290526 2.674595 3.553529 -v -0.066722 0.137489 0.176136 -vn -4.381680 2.749527 3.419439 -v -0.066854 0.137737 0.175775 -vn -4.464649 2.776859 3.330405 -v -0.066860 0.137747 0.175759 -vn -4.467855 2.830879 3.285554 -v -0.066863 0.137754 0.175748 -vn -4.206219 2.608259 3.653771 -v -0.066698 0.137445 0.176197 -vn -4.158953 2.555007 3.710696 -v -0.066539 0.137165 0.176578 -vn -4.141952 2.534430 3.737794 -v -0.066503 0.137103 0.176659 -vn -4.102935 2.504622 3.755088 -v -0.066500 0.137098 0.176666 -vn -4.125221 2.340814 3.763413 -v -0.066372 0.136878 0.176954 -vn -5.313285 0.720969 3.264321 -v -0.066349 0.136709 0.177036 -vn -3.832055 2.283697 3.741261 -v -0.066277 0.136717 0.177165 -vn -3.588736 2.565502 3.587491 -v -0.066269 0.136705 0.177181 -vn -3.618617 2.477090 3.551000 -v -0.066224 0.136628 0.177281 -vn -5.246616 0.329659 3.434974 -v -0.066368 0.136115 0.177104 -vn -5.366732 0.138183 3.227984 -v -0.066375 0.135500 0.177127 -vn -3.639948 -2.571904 3.473077 -v -0.066053 0.122660 0.177661 -vn -3.815811 -2.382990 2.965209 -v -0.065575 0.123500 0.178845 -vn -5.810102 0.080443 2.363689 -v -0.065646 0.123500 0.178652 -vn -3.868252 -2.493518 3.876987 -v -0.066490 0.121919 0.176688 -vn -3.582260 -2.601171 3.587973 -v -0.066224 0.122372 0.177281 -vn -5.333336 -0.769323 3.221781 -v -0.066349 0.122291 0.177036 -vn -5.356901 -0.407767 3.234777 -v -0.066368 0.122885 0.177104 -vn -5.385746 -0.090338 3.193836 -v -0.066375 0.123500 0.177127 -vn -4.169406 -2.494943 3.720533 -v -0.066530 0.121851 0.176598 -vn -4.366538 -2.751278 3.432406 -v -0.066836 0.121299 0.175829 -vn -4.225698 -2.660880 3.605918 -v -0.066732 0.121492 0.176109 -vn -4.166076 -2.572350 3.698946 -v -0.066563 0.121794 0.176522 -vn -4.730607 -3.059242 2.741943 -v -0.067008 0.120949 0.175243 -vn -4.650136 -3.000398 2.920761 -v -0.066973 0.121026 0.175386 -vn -4.610418 -2.951127 3.024967 -v -0.066949 0.121075 0.175471 -vn -4.542961 -2.888826 3.154699 -v -0.066939 0.121097 0.175509 -vn -4.476274 -2.795339 3.294645 -v -0.066862 0.121250 0.175753 -vn -4.421227 -2.786387 3.358162 -v -0.066853 0.121267 0.175780 -vn -4.967465 -3.295765 1.978315 -v -0.067079 0.120784 0.174874 -vn -4.866757 -3.226627 2.299061 -v -0.067055 0.120842 0.175018 -vn -4.829225 -3.120634 2.510840 -v -0.067030 0.120900 0.175145 -vn -4.810381 -3.079541 2.589744 -v -0.067024 0.120913 0.175171 -vn -3.484347 -2.777423 2.404167 -v -0.065303 0.124050 0.179745 -vn -3.793400 -2.935006 1.725804 -v -0.065096 0.124582 0.180802 -vn -3.429493 2.882419 2.243682 -v -0.065210 0.134732 0.180148 -vn -3.629399 2.937336 1.579827 -v -0.065034 0.134187 0.181363 -vn -0.075972 5.243802 3.356306 -v -0.063000 0.135084 0.179758 -vn -0.108812 4.084237 4.701741 -v -0.063000 0.136944 0.177608 -vn -0.429974 4.120337 4.661997 -v -0.063894 0.136914 0.177593 -vn -0.453164 5.202869 3.450209 -v -0.065121 0.135033 0.179644 -vn -0.378499 5.228101 3.382391 -v -0.064092 0.135070 0.179730 -vn -1.696189 4.136007 4.385253 -v -0.065812 0.136684 0.177393 -vn -0.295859 5.996163 1.717015 -v -0.064329 0.133900 0.182296 -vn -0.035913 5.974666 1.740936 -v -0.063000 0.133904 0.182345 -vn -0.916887 4.149567 4.572666 -v -0.064720 0.136837 0.177546 -vn -1.290593 4.128743 4.515858 -v -0.065455 0.136739 0.177458 -vn -0.901764 -4.112942 4.605709 -v -0.064720 0.122163 0.177546 -vn -0.434837 -4.098768 4.678133 -v -0.063894 0.122086 0.177593 -vn -0.376058 -5.240602 3.361284 -v -0.064092 0.123930 0.179730 -vn -0.678307 -5.215893 3.404467 -v -0.065121 0.123967 0.179644 -vn -0.212469 -5.972106 1.773064 -v -0.064329 0.125100 0.182296 -vn -1.721029 -4.096887 4.424934 -v -0.065812 0.122316 0.177393 -vn -1.336316 -4.073839 4.552350 -v -0.065455 0.122261 0.177458 -vn -0.029665 -5.975186 1.738520 -v -0.063000 0.125096 0.182345 -vn -0.045469 -5.257453 3.338877 -v -0.063000 0.123916 0.179758 -vn -0.063526 -4.072931 4.715049 -v -0.063000 0.122056 0.177608 -vn 0.525421 1.597426 5.877326 -v -0.049215 0.138500 0.176498 -vn 0.306150 2.015709 5.898945 -v -0.047190 0.139263 0.176101 -vn 0.275559 1.981071 5.911514 -v -0.047019 0.139326 0.176071 -vn 2.316843 2.595231 4.156079 -v -0.054606 0.135084 0.179758 -vn 1.884509 2.312700 4.818518 -v -0.052878 0.136357 0.178160 -vn 1.446618 1.972201 5.354945 -v -0.052031 0.136944 0.177608 -vn 0.984715 1.744155 5.681723 -v -0.050090 0.138104 0.176739 -vn 3.151908 3.214977 1.524402 -v -0.056511 0.133702 0.183160 -vn 2.950077 3.062765 2.507728 -v -0.056206 0.133904 0.182345 -vn 2.655159 2.866188 3.363359 -v -0.055090 0.134720 0.180372 -vn 0.994311 -0.189330 6.073374 -v -0.047019 0.119674 0.176071 -vn 3.364696 -3.190599 1.366004 -v -0.056511 0.125298 0.183160 -vn 0.965132 -0.544580 6.175118 -v -0.049215 0.120500 0.176498 -vn 1.097978 -1.519541 5.800941 -v -0.050090 0.120896 0.176739 -vn 1.425703 -2.022433 5.317584 -v -0.052031 0.122056 0.177608 -vn 1.962442 -2.188881 4.929285 -v -0.052878 0.122643 0.178160 -# 792 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 7//7 -f 8//8 9//9 10//10 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 15//15 16//16 17//17 -f 7//7 6//6 18//18 -f 19//19 20//20 21//21 -f 17//17 16//16 11//11 -f 11//11 16//16 22//22 -f 11//11 22//22 12//12 -f 6//6 23//23 18//18 -f 18//18 23//23 24//24 -f 18//18 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 22//22 28//28 12//12 -f 12//12 28//28 29//29 -f 12//12 29//29 20//20 -f 20//20 29//29 30//30 -f 20//20 30//30 21//21 -f 10//10 9//9 31//31 -f 14//14 12//12 32//32 -f 32//32 12//12 25//25 -f 32//32 25//25 33//33 -f 10//10 34//34 8//8 -f 8//8 34//34 35//35 -f 8//8 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 38//38 -f 38//38 39//39 36//36 -f 36//36 39//39 40//40 -f 36//36 40//40 41//41 -f 42//42 43//43 44//44 -f 44//44 43//43 19//19 -f 44//44 19//19 45//45 -f 45//45 19//19 21//21 -f 5//5 7//7 46//46 -f 46//46 7//7 47//47 -f 46//46 47//47 40//40 -f 40//40 47//47 48//48 -f 40//40 48//48 41//41 -f 15//15 49//49 50//50 -f 50//50 49//49 51//51 -f 50//50 51//51 52//52 -f 52//52 51//51 31//31 -f 52//52 31//31 42//42 -f 42//42 31//31 9//9 -f 42//42 9//9 43//43 -f 15//15 17//17 49//49 -f 49//49 17//17 53//53 -f 49//49 53//53 54//54 -f 39//39 55//55 40//40 -f 40//40 55//55 56//56 -f 40//40 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 33//33 25//25 60//60 -f 60//60 25//25 27//27 -f 60//60 27//27 61//61 -f 61//61 27//27 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 59//59 -f 65//65 59//59 54//54 -f 54//54 59//59 58//58 -f 54//54 58//58 49//49 -f 66//66 67//67 68//68 -f 68//68 67//67 69//69 -f 70//70 68//68 71//71 -f 72//72 73//73 74//74 -f 73//73 75//75 74//74 -f 74//74 75//75 76//76 -f 74//74 76//76 77//77 -f 78//78 79//79 80//80 -f 69//69 81//81 68//68 -f 68//68 81//81 82//82 -f 68//68 82//82 71//71 -f 76//76 83//83 77//77 -f 77//77 83//83 84//84 -f 77//77 84//84 85//85 -f 70//70 71//71 86//86 -f 86//86 71//71 87//87 -f 86//86 87//87 79//79 -f 79//79 87//87 88//88 -f 79//79 88//88 80//80 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 66//66 -f 96//96 94//94 97//97 -f 97//97 94//94 98//98 -f 97//97 98//98 99//99 -f 96//96 100//100 94//94 -f 94//94 100//100 101//101 -f 94//94 101//101 66//66 -f 66//66 101//101 102//102 -f 66//66 102//102 67//67 -f 82//82 103//103 104//104 -f 104//104 103//103 105//105 -f 106//106 107//107 108//108 -f 108//108 107//107 85//85 -f 108//108 85//85 109//109 -f 109//109 85//85 84//84 -f 110//110 72//72 111//111 -f 111//111 72//72 74//74 -f 111//111 74//74 112//112 -f 112//112 74//74 78//78 -f 112//112 78//78 113//113 -f 113//113 78//78 80//80 -f 114//114 104//104 115//115 -f 115//115 104//104 105//105 -f 115//115 105//105 99//99 -f 99//99 105//105 116//116 -f 99//99 116//116 97//97 -f 107//107 117//117 85//85 -f 85//85 117//117 118//118 -f 85//85 118//118 89//89 -f 89//89 118//118 119//119 -f 89//89 119//119 90//90 -f 111//111 120//120 110//110 -f 110//110 120//120 121//121 -f 110//110 121//121 122//122 -f 122//122 121//121 123//123 -f 122//122 123//123 104//104 -f 104//104 123//123 124//124 -f 104//104 124//124 82//82 -f 82//82 124//124 125//125 -f 82//82 125//125 71//71 -f 114//114 115//115 108//108 -f 108//108 115//115 126//126 -f 108//108 126//126 106//106 -f 18//18 85//85 89//89 -f 18//18 89//89 7//7 -f 7//7 89//89 91//91 -f 7//7 91//91 47//47 -f 47//47 91//91 93//93 -f 47//47 93//93 48//48 -f 48//48 93//93 95//95 -f 48//48 95//95 41//41 -f 41//41 95//95 66//66 -f 41//41 66//66 36//36 -f 36//36 66//66 68//68 -f 36//36 68//68 8//8 -f 8//8 68//68 70//70 -f 8//8 70//70 9//9 -f 9//9 70//70 86//86 -f 9//9 86//86 43//43 -f 43//43 86//86 79//79 -f 43//43 79//79 19//19 -f 19//19 79//79 78//78 -f 19//19 78//78 20//20 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 131//131 132//132 133//133 -f 133//133 132//132 129//129 -f 133//133 129//129 134//134 -f 134//134 129//129 130//130 -f 134//134 130//130 135//135 -f 20//20 78//78 12//12 -f 12//12 78//78 74//74 -f 12//12 74//74 136//136 -f 74//74 137//137 136//136 -f 136//136 137//137 138//138 -f 136//136 138//138 139//139 -f 139//139 138//138 127//127 -f 139//139 127//127 140//140 -f 140//140 127//127 129//129 -f 141//141 142//142 143//143 -f 141//141 143//143 144//144 -f 145//145 144//144 146//146 -f 146//146 144//144 143//143 -f 146//146 143//143 147//147 -f 147//147 143//143 148//148 -f 147//147 148//148 149//149 -f 85//85 18//18 77//77 -f 77//77 18//18 25//25 -f 77//77 25//25 150//150 -f 25//25 151//151 150//150 -f 150//150 151//151 152//152 -f 150//150 152//152 153//153 -f 153//153 152//152 145//145 -f 153//153 145//145 154//154 -f 154//154 145//145 146//146 -f 46//46 92//92 5//5 -f 5//5 92//92 90//90 -f 5//5 90//90 6//6 -f 6//6 90//90 119//119 -f 6//6 119//119 23//23 -f 23//23 119//119 118//118 -f 23//23 118//118 24//24 -f 24//24 118//118 117//117 -f 24//24 117//117 26//26 -f 26//26 117//117 107//107 -f 26//26 107//107 27//27 -f 27//27 107//107 106//106 -f 27//27 106//106 62//62 -f 62//62 106//106 126//126 -f 62//62 126//126 64//64 -f 64//64 126//126 115//115 -f 64//64 115//115 59//59 -f 59//59 115//115 99//99 -f 59//59 99//99 57//57 -f 57//57 99//99 98//98 -f 57//57 98//98 40//40 -f 40//40 98//98 94//94 -f 40//40 94//94 46//46 -f 46//46 94//94 92//92 -f 65//65 104//104 63//63 -f 63//63 104//104 114//114 -f 63//63 114//114 61//61 -f 61//61 114//114 108//108 -f 61//61 108//108 60//60 -f 60//60 108//108 109//109 -f 60//60 109//109 33//33 -f 33//33 109//109 84//84 -f 33//33 84//84 32//32 -f 32//32 84//84 83//83 -f 32//32 83//83 14//14 -f 14//14 83//83 76//76 -f 14//14 76//76 13//13 -f 13//13 76//76 75//75 -f 13//13 75//75 11//11 -f 11//11 75//75 73//73 -f 11//11 73//73 17//17 -f 17//17 73//73 72//72 -f 17//17 72//72 53//53 -f 53//53 72//72 110//110 -f 53//53 110//110 54//54 -f 54//54 110//110 122//122 -f 54//54 122//122 65//65 -f 65//65 122//122 104//104 -f 42//42 87//87 52//52 -f 52//52 87//87 71//71 -f 52//52 71//71 50//50 -f 50//50 71//71 125//125 -f 50//50 125//125 15//15 -f 15//15 125//125 124//124 -f 15//15 124//124 16//16 -f 16//16 124//124 123//123 -f 16//16 123//123 22//22 -f 22//22 123//123 121//121 -f 22//22 121//121 28//28 -f 28//28 121//121 120//120 -f 28//28 120//120 29//29 -f 29//29 120//120 111//111 -f 29//29 111//111 30//30 -f 30//30 111//111 112//112 -f 30//30 112//112 21//21 -f 21//21 112//112 113//113 -f 21//21 113//113 45//45 -f 45//45 113//113 80//80 -f 45//45 80//80 44//44 -f 44//44 80//80 88//88 -f 44//44 88//88 42//42 -f 42//42 88//88 87//87 -f 37//37 67//67 38//38 -f 38//38 67//67 102//102 -f 38//38 102//102 39//39 -f 39//39 102//102 101//101 -f 39//39 101//101 55//55 -f 55//55 101//101 100//100 -f 55//55 100//100 56//56 -f 56//56 100//100 96//96 -f 56//56 96//96 58//58 -f 58//58 96//96 97//97 -f 58//58 97//97 49//49 -f 49//49 97//97 116//116 -f 49//49 116//116 51//51 -f 51//51 116//116 105//105 -f 51//51 105//105 31//31 -f 31//31 105//105 103//103 -f 31//31 103//103 10//10 -f 10//10 103//103 82//82 -f 10//10 82//82 34//34 -f 34//34 82//82 81//81 -f 34//34 81//81 35//35 -f 35//35 81//81 69//69 -f 35//35 69//69 37//37 -f 37//37 69//69 67//67 -f 155//155 147//147 156//156 -f 156//156 147//147 149//149 -f 155//155 157//157 147//147 -f 147//147 157//157 158//158 -f 147//147 158//158 130//130 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 165//165 163//163 166//166 -f 166//166 163//163 164//164 -f 166//166 164//164 167//167 -f 167//167 164//164 168//168 -f 167//167 168//168 149//149 -f 149//149 168//168 169//169 -f 149//149 169//169 156//156 -f 158//158 170//170 130//130 -f 130//130 170//170 171//171 -f 130//130 171//171 135//135 -f 135//135 171//171 172//172 -f 135//135 172//172 173//173 -f 173//173 172//172 160//160 -f 173//173 160//160 174//174 -f 174//174 160//160 159//159 -f 175//175 176//176 177//177 -f 177//177 176//176 178//178 -f 179//179 161//161 180//180 -f 180//180 161//161 163//163 -f 181//181 141//141 182//182 -f 182//182 141//141 132//132 -f 182//182 132//132 183//183 -f 183//183 132//132 184//184 -f 184//184 132//132 131//131 -f 184//184 131//131 185//185 -f 181//181 186//186 141//141 -f 141//141 186//186 187//187 -f 141//141 187//187 142//142 -f 142//142 187//187 188//188 -f 142//142 188//188 189//189 -f 189//189 188//188 190//190 -f 189//189 190//190 191//191 -f 191//191 190//190 192//192 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 176//176 -f 176//176 194//194 195//195 -f 176//176 195//195 178//178 -f 178//178 195//195 196//196 -f 178//178 196//196 197//197 -f 197//197 196//196 184//184 -f 197//197 184//184 198//198 -f 198//198 184//184 185//185 -f 199//199 200//200 201//201 -f 201//201 200//200 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 205//205 206//206 207//207 -f 207//207 201//201 205//205 -f 205//205 201//201 203//203 -f 205//205 203//203 208//208 -f 208//208 203//203 209//209 -f 210//210 211//211 212//212 -f 213//213 214//214 215//215 -f 215//215 214//214 207//207 -f 215//215 207//207 216//216 -f 216//216 207//207 206//206 -f 216//216 206//206 212//212 -f 212//212 206//206 217//217 -f 212//212 217//217 210//210 -f 204//204 202//202 215//215 -f 218//218 219//219 204//204 -f 218//218 204//204 220//220 -f 220//220 204//204 215//215 -f 220//220 215//215 216//216 -f 221//221 222//222 223//223 -f 224//224 225//225 226//226 -f 226//226 225//225 227//227 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 223//223 -f 223//223 229//229 230//230 -f 223//223 230//230 221//221 -f 231//231 232//232 226//226 -f 233//233 234//234 231//231 -f 233//233 231//231 235//235 -f 235//235 231//231 226//226 -f 235//235 226//226 228//228 -f 231//231 236//236 232//232 -f 232//232 236//236 237//237 -f 232//232 237//237 238//238 -f 238//238 237//237 239//239 -f 240//240 241//241 227//227 -f 227//227 241//241 242//242 -f 227//227 242//242 229//229 -f 229//229 242//242 243//243 -f 229//229 243//243 244//244 -f 245//245 246//246 236//236 -f 236//236 246//246 247//247 -f 236//236 247//247 237//237 -f 237//237 247//247 248//248 -f 237//237 248//248 249//249 -f 245//245 236//236 250//250 -f 250//250 236//236 251//251 -f 250//250 251//251 252//252 -f 252//252 251//251 253//253 -f 252//252 253//253 254//254 -f 254//254 253//253 244//244 -f 244//244 253//253 255//255 -f 244//244 255//255 229//229 -f 249//249 256//256 237//237 -f 237//237 256//256 257//257 -f 237//237 257//257 227//227 -f 227//227 257//257 258//258 -f 227//227 258//258 240//240 -f 259//259 260//260 261//261 -f 262//262 263//263 214//214 -f 214//214 263//263 264//264 -f 214//214 264//264 207//207 -f 264//264 265//265 207//207 -f 207//207 265//265 266//266 -f 207//207 266//266 201//201 -f 201//201 266//266 267//267 -f 201//201 267//267 268//268 -f 214//214 269//269 262//262 -f 262//262 269//269 270//270 -f 262//262 270//270 259//259 -f 259//259 270//270 271//271 -f 259//259 271//271 260//260 -f 268//268 272//272 201//201 -f 201//201 272//272 273//273 -f 201//201 273//273 199//199 -f 199//199 273//273 274//274 -f 199//199 274//274 275//275 -f 275//275 274//274 276//276 -f 275//275 276//276 277//277 -f 277//277 276//276 259//259 -f 277//277 259//259 278//278 -f 278//278 259//259 261//261 -f 261//261 260//260 279//279 -f 279//279 260//260 280//280 -f 280//280 281//281 279//279 -f 279//279 281//281 282//282 -f 279//279 282//282 283//283 -f 200//200 284//284 282//282 -f 282//282 284//284 285//285 -f 282//282 285//285 283//283 -f 282//282 286//286 200//200 -f 200//200 286//286 287//287 -f 200//200 287//287 202//202 -f 287//287 288//288 202//202 -f 202//202 288//288 289//289 -f 202//202 289//289 215//215 -f 215//215 289//289 290//290 -f 215//215 290//290 291//291 -f 291//291 292//292 215//215 -f 215//215 292//292 293//293 -f 215//215 293//293 213//213 -f 213//213 293//293 294//294 -f 213//213 294//294 295//295 -f 295//295 294//294 296//296 -f 295//295 296//296 297//297 -f 297//297 296//296 281//281 -f 297//297 281//281 298//298 -f 298//298 281//281 280//280 -f 290//290 267//267 291//291 -f 291//291 267//267 266//266 -f 291//291 266//266 292//292 -f 292//292 266//266 265//265 -f 292//292 265//265 293//293 -f 293//293 265//265 264//264 -f 293//293 264//264 294//294 -f 294//294 264//264 263//263 -f 294//294 263//263 296//296 -f 296//296 263//263 262//262 -f 296//296 262//262 281//281 -f 281//281 262//262 259//259 -f 281//281 259//259 282//282 -f 282//282 259//259 276//276 -f 282//282 276//276 286//286 -f 286//286 276//276 274//274 -f 286//286 274//274 287//287 -f 287//287 274//274 273//273 -f 287//287 273//273 288//288 -f 288//288 273//273 272//272 -f 288//288 272//272 289//289 -f 289//289 272//272 268//268 -f 289//289 268//268 290//290 -f 290//290 268//268 267//267 -f 299//299 257//257 256//256 -f 299//299 256//256 300//300 -f 257//257 299//299 258//258 -f 258//258 299//299 301//301 -f 258//258 301//301 240//240 -f 240//240 301//301 302//302 -f 240//240 302//302 241//241 -f 241//241 302//302 303//303 -f 241//241 303//303 242//242 -f 242//242 303//303 304//304 -f 242//242 304//304 243//243 -f 243//243 304//304 305//305 -f 243//243 305//305 244//244 -f 256//256 249//249 300//300 -f 300//300 249//249 248//248 -f 300//300 248//248 306//306 -f 306//306 248//248 247//247 -f 306//306 247//247 307//307 -f 307//307 247//247 246//246 -f 307//307 246//246 308//308 -f 308//308 246//246 245//245 -f 308//308 245//245 309//309 -f 309//309 245//245 250//250 -f 309//309 250//250 310//310 -f 310//310 250//250 252//252 -f 310//310 252//252 305//305 -f 305//305 252//252 254//254 -f 305//305 254//254 244//244 -f 308//308 309//309 311//311 -f 311//311 309//309 310//310 -f 311//311 310//310 305//305 -f 300//300 306//306 311//311 -f 311//311 306//306 307//307 -f 311//311 307//307 308//308 -f 302//302 301//301 311//311 -f 311//311 301//301 299//299 -f 311//311 299//299 300//300 -f 305//305 304//304 311//311 -f 311//311 304//304 303//303 -f 311//311 303//303 302//302 -f 147//147 130//130 146//146 -f 146//146 130//130 128//128 -f 146//146 128//128 154//154 -f 154//154 128//128 127//127 -f 154//154 127//127 153//153 -f 153//153 127//127 138//138 -f 153//153 138//138 150//150 -f 150//150 138//138 137//137 -f 150//150 137//137 77//77 -f 77//77 137//137 74//74 -f 132//132 141//141 129//129 -f 129//129 141//141 144//144 -f 129//129 144//144 140//140 -f 140//140 144//144 145//145 -f 140//140 145//145 139//139 -f 139//139 145//145 152//152 -f 139//139 152//152 136//136 -f 136//136 152//152 151//151 -f 136//136 151//151 12//12 -f 12//12 151//151 25//25 -f 134//134 135//135 312//312 -f 312//312 135//135 173//173 -f 312//312 173//173 313//313 -f 313//313 173//173 314//314 -f 314//314 173//173 174//174 -f 314//314 174//174 315//315 -f 315//315 174//174 316//316 -f 316//316 174//174 159//159 -f 316//316 159//159 317//317 -f 317//317 159//159 318//318 -f 318//318 159//159 161//161 -f 318//318 161//161 179//179 -f 177//177 178//178 319//319 -f 319//319 178//178 197//197 -f 319//319 197//197 320//320 -f 320//320 197//197 321//321 -f 321//321 197//197 198//198 -f 321//321 198//198 322//322 -f 322//322 198//198 323//323 -f 323//323 198//198 185//185 -f 323//323 185//185 324//324 -f 324//324 185//185 325//325 -f 325//325 185//185 131//131 -f 325//325 131//131 133//133 -f 143//143 142//142 326//326 -f 326//326 142//142 189//189 -f 326//326 189//189 327//327 -f 327//327 189//189 328//328 -f 328//328 189//189 191//191 -f 328//328 191//191 329//329 -f 329//329 191//191 330//330 -f 330//330 191//191 193//193 -f 330//330 193//193 331//331 -f 331//331 193//193 332//332 -f 332//332 193//193 176//176 -f 332//332 176//176 175//175 -f 180//180 163//163 333//333 -f 333//333 163//163 165//165 -f 333//333 165//165 334//334 -f 334//334 165//165 335//335 -f 335//335 165//165 166//166 -f 335//335 166//166 336//336 -f 336//336 166//166 337//337 -f 337//337 166//166 167//167 -f 337//337 167//167 338//338 -f 338//338 167//167 339//339 -f 339//339 167//167 149//149 -f 339//339 149//149 148//148 -f 340//340 341//341 342//342 -f 343//343 344//344 345//345 -f 346//346 347//347 348//348 -f 349//349 350//350 351//351 -f 351//351 350//350 352//352 -f 351//351 352//352 353//353 -f 353//353 354//354 351//351 -f 351//351 354//354 355//355 -f 351//351 355//355 345//345 -f 345//345 355//355 356//356 -f 345//345 356//356 343//343 -f 357//357 349//349 320//320 -f 320//320 321//321 357//357 -f 357//357 321//321 322//322 -f 357//357 322//322 358//358 -f 340//340 359//359 360//360 -f 360//360 359//359 361//361 -f 361//361 362//362 360//360 -f 360//360 362//362 363//363 -f 360//360 363//363 358//358 -f 342//342 341//341 364//364 -f 364//364 341//341 365//365 -f 364//364 365//365 366//366 -f 367//367 368//368 369//369 -f 366//366 365//365 370//370 -f 370//370 365//365 371//371 -f 370//370 371//371 372//372 -f 372//372 371//371 367//367 -f 372//372 367//367 373//373 -f 373//373 367//367 369//369 -f 373//373 369//369 374//374 -f 375//375 376//376 377//377 -f 340//340 360//360 341//341 -f 341//341 360//360 378//378 -f 341//341 378//378 365//365 -f 365//365 378//378 379//379 -f 365//365 379//379 371//371 -f 371//371 379//379 375//375 -f 371//371 375//375 367//367 -f 367//367 375//375 377//377 -f 367//367 377//377 368//368 -f 358//358 322//322 360//360 -f 360//360 322//322 323//323 -f 360//360 323//323 378//378 -f 378//378 323//323 324//324 -f 378//378 324//324 379//379 -f 379//379 324//324 325//325 -f 379//379 325//325 375//375 -f 375//375 325//325 133//133 -f 375//375 133//133 376//376 -f 380//380 345//345 348//348 -f 348//348 345//345 344//344 -f 348//348 344//344 346//346 -f 349//349 351//351 320//320 -f 320//320 351//351 345//345 -f 320//320 345//345 319//319 -f 319//319 345//345 380//380 -f 319//319 380//380 177//177 -f 381//381 374//374 369//369 -f 382//382 383//383 384//384 -f 2//2 1//1 384//384 -f 384//384 1//1 381//381 -f 384//384 381//381 382//382 -f 382//382 381//381 369//369 -f 382//382 369//369 385//385 -f 385//385 369//369 368//368 -f 385//385 368//368 386//386 -f 386//386 368//368 377//377 -f 386//386 377//377 387//387 -f 387//387 377//377 376//376 -f 387//387 376//376 134//134 -f 134//134 376//376 133//133 -f 347//347 388//388 348//348 -f 348//348 388//388 389//389 -f 348//348 389//389 380//380 -f 389//389 390//390 380//380 -f 380//380 390//390 175//175 -f 380//380 175//175 177//177 -f 391//391 383//383 382//382 -f 392//392 393//393 391//391 -f 391//391 393//393 394//394 -f 395//395 396//396 393//393 -f 393//393 396//396 397//397 -f 393//393 397//397 394//394 -f 398//398 399//399 400//400 -f 400//400 399//399 401//401 -f 400//400 401//401 395//395 -f 395//395 401//401 402//402 -f 395//395 402//402 396//396 -f 403//403 404//404 405//405 -f 405//405 404//404 406//406 -f 406//406 407//407 405//405 -f 405//405 407//407 408//408 -f 405//405 408//408 398//398 -f 315//315 316//316 403//403 -f 403//403 316//316 409//409 -f 409//409 316//316 317//317 -f 409//409 317//317 410//410 -f 411//411 412//412 413//413 -f 413//413 412//412 414//414 -f 413//413 414//414 410//410 -f 415//415 416//416 417//417 -f 417//417 416//416 418//418 -f 417//417 418//418 413//413 -f 413//413 418//418 419//419 -f 413//413 419//419 411//411 -f 415//415 417//417 420//420 -f 420//420 417//417 421//421 -f 420//420 421//421 422//422 -f 318//318 179//179 423//423 -f 410//410 317//317 413//413 -f 413//413 317//317 318//318 -f 413//413 318//318 417//417 -f 417//417 318//318 423//423 -f 417//417 423//423 421//421 -f 391//391 382//382 392//392 -f 392//392 382//382 385//385 -f 392//392 385//385 386//386 -f 398//398 400//400 405//405 -f 405//405 400//400 395//395 -f 405//405 395//395 424//424 -f 424//424 395//395 393//393 -f 424//424 393//393 425//425 -f 425//425 393//393 392//392 -f 425//425 392//392 426//426 -f 426//426 392//392 386//386 -f 426//426 386//386 387//387 -f 403//403 405//405 315//315 -f 315//315 405//405 424//424 -f 315//315 424//424 314//314 -f 314//314 424//424 425//425 -f 314//314 425//425 313//313 -f 313//313 425//425 426//426 -f 313//313 426//426 312//312 -f 312//312 426//426 387//387 -f 312//312 387//387 134//134 -f 427//427 428//428 429//429 -f 430//430 431//431 427//427 -f 427//427 431//431 432//432 -f 433//433 434//434 431//431 -f 431//431 434//434 435//435 -f 431//431 435//435 432//432 -f 436//436 437//437 438//438 -f 438//438 437//437 439//439 -f 438//438 439//439 433//433 -f 433//433 439//439 440//440 -f 433//433 440//440 434//434 -f 441//441 442//442 443//443 -f 443//443 442//442 444//444 -f 444//444 445//445 443//443 -f 443//443 445//445 446//446 -f 443//443 446//446 436//436 -f 329//329 330//330 441//441 -f 441//441 330//330 447//447 -f 447//447 330//330 331//331 -f 447//447 331//331 448//448 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 448//448 -f 453//453 454//454 455//455 -f 455//455 454//454 456//456 -f 455//455 456//456 451//451 -f 451//451 456//456 457//457 -f 451//451 457//457 449//449 -f 453//453 455//455 458//458 -f 458//458 455//455 389//389 -f 458//458 389//389 388//388 -f 332//332 175//175 390//390 -f 448//448 331//331 451//451 -f 451//451 331//331 332//332 -f 451//451 332//332 455//455 -f 455//455 332//332 390//390 -f 455//455 390//390 389//389 -f 427//427 429//429 430//430 -f 430//430 429//429 459//459 -f 430//430 459//459 460//460 -f 436//436 438//438 443//443 -f 443//443 438//438 433//433 -f 443//443 433//433 461//461 -f 461//461 433//433 431//431 -f 461//461 431//431 462//462 -f 462//462 431//431 430//430 -f 462//462 430//430 463//463 -f 463//463 430//430 460//460 -f 463//463 460//460 464//464 -f 441//441 443//443 329//329 -f 329//329 443//443 461//461 -f 329//329 461//461 328//328 -f 328//328 461//461 462//462 -f 328//328 462//462 327//327 -f 327//327 462//462 463//463 -f 327//327 463//463 326//326 -f 326//326 463//463 464//464 -f 326//326 464//464 143//143 -f 465//465 422//422 466//466 -f 466//466 422//422 421//421 -f 466//466 421//421 467//467 -f 421//421 423//423 467//467 -f 467//467 423//423 179//179 -f 467//467 179//179 180//180 -f 468//468 469//469 470//470 -f 429//429 428//428 471//471 -f 3//3 4//4 471//471 -f 471//471 4//4 468//468 -f 471//471 468//468 429//429 -f 429//429 468//468 470//470 -f 429//429 470//470 459//459 -f 459//459 470//470 472//472 -f 459//459 472//472 460//460 -f 460//460 472//472 473//473 -f 460//460 473//473 464//464 -f 464//464 473//473 474//474 -f 464//464 474//474 143//143 -f 143//143 474//474 148//148 -f 475//475 476//476 477//477 -f 478//478 479//479 480//480 -f 481//481 465//465 466//466 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 486//486 -f 486//486 487//487 484//484 -f 484//484 487//487 488//488 -f 484//484 488//488 480//480 -f 480//480 488//488 489//489 -f 480//480 489//489 478//478 -f 490//490 482//482 334//334 -f 334//334 335//335 490//490 -f 490//490 335//335 336//336 -f 490//490 336//336 491//491 -f 475//475 492//492 493//493 -f 493//493 492//492 494//494 -f 494//494 495//495 493//493 -f 493//493 495//495 496//496 -f 493//493 496//496 491//491 -f 477//477 476//476 497//497 -f 497//497 476//476 498//498 -f 497//497 498//498 499//499 -f 500//500 472//472 470//470 -f 499//499 498//498 501//501 -f 501//501 498//498 502//502 -f 501//501 502//502 503//503 -f 503//503 502//502 500//500 -f 503//503 500//500 504//504 -f 504//504 500//500 470//470 -f 504//504 470//470 469//469 -f 505//505 474//474 473//473 -f 475//475 493//493 476//476 -f 476//476 493//493 506//506 -f 476//476 506//506 498//498 -f 498//498 506//506 507//507 -f 498//498 507//507 502//502 -f 502//502 507//507 505//505 -f 502//502 505//505 500//500 -f 500//500 505//505 473//473 -f 500//500 473//473 472//472 -f 491//491 336//336 493//493 -f 493//493 336//336 337//337 -f 493//493 337//337 506//506 -f 506//506 337//337 338//338 -f 506//506 338//338 507//507 -f 507//507 338//338 339//339 -f 507//507 339//339 505//505 -f 505//505 339//339 148//148 -f 505//505 148//148 474//474 -f 467//467 480//480 466//466 -f 466//466 480//480 479//479 -f 466//466 479//479 481//481 -f 482//482 484//484 334//334 -f 334//334 484//484 480//480 -f 334//334 480//480 333//333 -f 333//333 480//480 467//467 -f 333//333 467//467 180//180 -f 508//508 509//509 195//195 -f 510//510 511//511 190//190 -f 190//190 511//511 192//192 -f 192//192 511//511 512//512 -f 192//192 512//512 513//513 -f 510//510 190//190 514//514 -f 514//514 190//190 188//188 -f 514//514 188//188 515//515 -f 515//515 188//188 516//516 -f 516//516 188//188 187//187 -f 516//516 187//187 517//517 -f 517//517 187//187 518//518 -f 518//518 187//187 186//186 -f 518//518 186//186 519//519 -f 181//181 520//520 186//186 -f 186//186 520//520 521//521 -f 186//186 521//521 519//519 -f 522//522 523//523 182//182 -f 182//182 523//523 524//524 -f 182//182 524//524 181//181 -f 181//181 524//524 525//525 -f 181//181 525//525 520//520 -f 522//522 182//182 526//526 -f 526//526 182//182 183//183 -f 526//526 183//183 527//527 -f 528//528 529//529 184//184 -f 184//184 529//529 530//530 -f 184//184 530//530 183//183 -f 183//183 530//530 531//531 -f 183//183 531//531 527//527 -f 184//184 532//532 533//533 -f 528//528 184//184 534//534 -f 534//534 184//184 533//533 -f 534//534 533//533 535//535 -f 195//195 509//509 196//196 -f 196//196 509//509 536//536 -f 196//196 536//536 537//537 -f 537//537 538//538 196//196 -f 196//196 538//538 539//539 -f 196//196 539//539 184//184 -f 184//184 539//539 540//540 -f 184//184 540//540 532//532 -f 513//513 541//541 192//192 -f 192//192 541//541 542//542 -f 192//192 542//542 194//194 -f 194//194 542//542 543//543 -f 194//194 543//543 544//544 -f 544//544 545//545 194//194 -f 194//194 545//545 546//546 -f 194//194 546//546 195//195 -f 195//195 546//546 547//547 -f 195//195 547//547 508//508 -f 171//171 548//548 172//172 -f 172//172 548//548 549//549 -f 170//170 158//158 550//550 -f 550//550 551//551 170//170 -f 170//170 551//551 552//552 -f 170//170 552//552 171//171 -f 171//171 552//552 553//553 -f 171//171 553//553 548//548 -f 157//157 155//155 554//554 -f 554//554 555//555 157//157 -f 157//157 555//555 556//556 -f 157//157 556//556 158//158 -f 158//158 556//556 557//557 -f 158//158 557//557 550//550 -f 169//169 558//558 156//156 -f 156//156 558//558 559//559 -f 156//156 559//559 155//155 -f 155//155 559//559 560//560 -f 155//155 560//560 554//554 -f 168//168 561//561 169//169 -f 169//169 561//561 562//562 -f 169//169 562//562 558//558 -f 164//164 563//563 168//168 -f 168//168 563//563 564//564 -f 168//168 564//564 561//561 -f 160//160 565//565 162//162 -f 162//162 565//565 566//566 -f 162//162 566//566 164//164 -f 164//164 566//566 567//567 -f 164//164 567//567 563//563 -f 568//568 172//172 569//569 -f 569//569 172//172 549//549 -f 569//569 549//549 570//570 -f 568//568 571//571 172//172 -f 172//172 571//571 572//572 -f 172//172 572//572 160//160 -f 160//160 572//572 573//573 -f 160//160 573//573 565//565 -f 574//574 575//575 576//576 -f 576//576 575//575 577//577 -f 227//227 578//578 237//237 -f 237//237 578//578 579//579 -f 237//237 579//579 580//580 -f 225//225 581//581 582//582 -f 582//582 581//581 583//583 -f 577//577 584//584 576//576 -f 576//576 584//584 582//582 -f 576//576 582//582 585//585 -f 585//585 582//582 583//583 -f 582//582 586//586 225//225 -f 225//225 586//586 587//587 -f 225//225 587//587 227//227 -f 227//227 587//587 588//588 -f 227//227 588//588 578//578 -f 580//580 589//589 237//237 -f 237//237 589//589 590//590 -f 237//237 590//590 239//239 -f 239//239 590//590 591//591 -f 239//239 591//591 592//592 -f 592//592 591//591 593//593 -f 592//592 593//593 594//594 -f 594//594 593//593 584//584 -f 594//594 584//584 595//595 -f 595//595 584//584 577//577 -f 596//596 226//226 597//597 -f 597//597 226//226 232//232 -f 597//597 232//232 598//598 -f 575//575 574//574 599//599 -f 600//600 601//601 238//238 -f 238//238 601//601 602//602 -f 238//238 602//602 232//232 -f 232//232 602//602 603//603 -f 232//232 603//603 598//598 -f 596//596 604//604 226//226 -f 226//226 604//604 605//605 -f 226//226 605//605 224//224 -f 224//224 605//605 606//606 -f 224//224 606//606 607//607 -f 607//607 606//606 608//608 -f 607//607 608//608 609//609 -f 609//609 608//608 599//599 -f 609//609 599//599 610//610 -f 610//610 599//599 574//574 -f 238//238 611//611 600//600 -f 600//600 611//611 612//612 -f 600//600 612//612 599//599 -f 599//599 612//612 613//613 -f 599//599 613//613 575//575 -f 579//579 597//597 580//580 -f 580//580 597//597 598//598 -f 580//580 598//598 589//589 -f 589//589 598//598 603//603 -f 589//589 603//603 590//590 -f 590//590 603//603 602//602 -f 590//590 602//602 591//591 -f 591//591 602//602 601//601 -f 591//591 601//601 593//593 -f 593//593 601//601 600//600 -f 593//593 600//600 584//584 -f 584//584 600//600 599//599 -f 584//584 599//599 582//582 -f 582//582 599//599 608//608 -f 582//582 608//608 586//586 -f 586//586 608//608 606//606 -f 586//586 606//606 587//587 -f 587//587 606//606 605//605 -f 587//587 605//605 588//588 -f 588//588 605//605 604//604 -f 588//588 604//604 578//578 -f 578//578 604//604 596//596 -f 578//578 596//596 579//579 -f 579//579 596//596 597//597 -f 614//614 615//615 616//616 -f 617//617 452//452 450//450 -f 618//618 447//447 448//448 -f 618//618 619//619 447//447 -f 447//447 619//619 620//620 -f 447//447 620//620 441//441 -f 617//617 621//621 452//452 -f 452//452 621//621 622//622 -f 452//452 622//622 448//448 -f 448//448 622//622 623//623 -f 448//448 623//623 618//618 -f 449//449 624//624 450//450 -f 450//450 624//624 625//625 -f 450//450 625//625 617//617 -f 626//626 627//627 457//457 -f 457//457 627//627 628//628 -f 457//457 628//628 449//449 -f 449//449 628//628 629//629 -f 449//449 629//629 624//624 -f 626//626 457//457 630//630 -f 630//630 457//457 456//456 -f 630//630 456//456 631//631 -f 631//631 456//456 454//454 -f 631//631 454//454 632//632 -f 632//632 454//454 633//633 -f 633//633 454//454 453//453 -f 633//633 453//453 634//634 -f 634//634 635//635 636//636 -f 636//636 635//635 637//637 -f 637//637 635//635 638//638 -f 638//638 635//635 639//639 -f 638//638 639//639 616//616 -f 616//616 639//639 640//640 -f 616//616 640//640 614//614 -f 634//634 453//453 635//635 -f 635//635 453//453 458//458 -f 635//635 458//458 639//639 -f 639//639 458//458 388//388 -f 639//639 388//388 640//640 -f 641//641 642//642 643//643 -f 644//644 645//645 646//646 -f 646//646 645//645 641//641 -f 646//646 641//641 647//647 -f 647//647 641//641 643//643 -f 647//647 643//643 648//648 -f 649//649 644//644 344//344 -f 650//650 651//651 355//355 -f 355//355 651//651 652//652 -f 355//355 652//652 356//356 -f 356//356 652//652 649//649 -f 356//356 649//649 343//343 -f 343//343 649//649 344//344 -f 653//653 654//654 352//352 -f 352//352 654//654 655//655 -f 352//352 655//655 353//353 -f 353//353 655//655 656//656 -f 353//353 656//656 354//354 -f 354//354 656//656 657//657 -f 354//354 657//657 355//355 -f 355//355 657//657 658//658 -f 355//355 658//658 650//650 -f 357//357 659//659 349//349 -f 349//349 659//659 660//660 -f 349//349 660//660 350//350 -f 350//350 660//660 661//661 -f 350//350 661//661 352//352 -f 352//352 661//661 662//662 -f 352//352 662//662 653//653 -f 644//644 646//646 344//344 -f 344//344 646//646 647//647 -f 344//344 647//647 346//346 -f 346//346 647//647 648//648 -f 346//346 648//648 347//347 -f 663//663 664//664 614//614 -f 663//663 614//614 642//642 -f 664//664 211//211 210//210 -f 615//615 614//614 665//665 -f 665//665 614//614 664//664 -f 665//665 664//664 666//666 -f 666//666 664//664 210//210 -f 388//388 347//347 640//640 -f 640//640 347//347 648//648 -f 640//640 648//648 614//614 -f 614//614 648//648 643//643 -f 614//614 643//643 642//642 -f 217//217 206//206 205//205 -f 628//628 627//627 436//436 -f 632//632 633//633 439//439 -f 665//665 667//667 615//615 -f 668//668 616//616 615//615 -f 636//636 637//637 668//668 -f 668//668 637//637 638//638 -f 668//668 638//638 616//616 -f 434//434 440//440 636//636 -f 439//439 633//633 440//440 -f 440//440 633//633 634//634 -f 440//440 634//634 636//636 -f 436//436 627//627 437//437 -f 627//627 626//626 437//437 -f 437//437 626//626 630//630 -f 437//437 630//630 439//439 -f 439//439 630//630 631//631 -f 439//439 631//631 632//632 -f 621//621 617//617 446//446 -f 617//617 625//625 446//446 -f 446//446 625//625 624//624 -f 446//446 624//624 436//436 -f 436//436 624//624 629//629 -f 436//436 629//629 628//628 -f 623//623 622//622 444//444 -f 444//444 622//622 621//621 -f 444//444 621//621 445//445 -f 445//445 621//621 446//446 -f 441//441 620//620 442//442 -f 442//442 620//620 619//619 -f 442//442 619//619 444//444 -f 444//444 619//619 618//618 -f 444//444 618//618 623//623 -f 513//513 428//428 541//541 -f 541//541 428//428 427//427 -f 545//545 544//544 669//669 -f 669//669 544//544 543//543 -f 669//669 543//543 542//542 -f 508//508 547//547 670//670 -f 670//670 547//547 546//546 -f 671//671 537//537 672//672 -f 672//672 537//537 536//536 -f 672//672 536//536 670//670 -f 670//670 536//536 509//509 -f 670//670 509//509 508//508 -f 667//667 665//665 670//670 -f 670//670 665//665 666//666 -f 670//670 666//666 672//672 -f 672//672 666//666 210//210 -f 672//672 210//210 217//217 -f 546//546 545//545 670//670 -f 670//670 545//545 669//669 -f 670//670 669//669 667//667 -f 667//667 669//669 673//673 -f 667//667 673//673 615//615 -f 615//615 673//673 674//674 -f 615//615 674//674 668//668 -f 636//636 668//668 434//434 -f 434//434 668//668 674//674 -f 434//434 674//674 435//435 -f 435//435 674//674 673//673 -f 435//435 673//673 432//432 -f 432//432 673//673 669//669 -f 432//432 669//669 427//427 -f 427//427 669//669 542//542 -f 427//427 542//542 541//541 -f 217//217 205//205 672//672 -f 672//672 205//205 208//208 -f 672//672 208//208 671//671 -f 675//675 676//676 677//677 -f 664//664 663//663 678//678 -f 678//678 663//663 642//642 -f 677//677 679//679 211//211 -f 220//220 216//216 679//679 -f 679//679 216//216 212//212 -f 679//679 212//212 211//211 -f 661//661 660//660 363//363 -f 363//363 660//660 358//358 -f 358//358 660//660 659//659 -f 358//358 659//659 357//357 -f 661//661 363//363 662//662 -f 662//662 363//363 362//362 -f 662//662 362//362 653//653 -f 653//653 362//362 654//654 -f 654//654 362//362 361//361 -f 654//654 361//361 655//655 -f 340//340 658//658 359//359 -f 359//359 658//658 657//657 -f 359//359 657//657 361//361 -f 361//361 657//657 656//656 -f 361//361 656//656 655//655 -f 342//342 644//644 649//649 -f 649//649 652//652 342//342 -f 342//342 652//652 651//651 -f 342//342 651//651 340//340 -f 340//340 651//651 650//650 -f 340//340 650//650 658//658 -f 342//342 364//364 644//644 -f 644//644 364//364 366//366 -f 644//644 366//366 680//680 -f 680//680 366//366 370//370 -f 680//680 370//370 681//681 -f 681//681 370//370 372//372 -f 681//681 372//372 675//675 -f 675//675 372//372 373//373 -f 675//675 373//373 676//676 -f 211//211 664//664 677//677 -f 677//677 664//664 678//678 -f 677//677 678//678 675//675 -f 675//675 678//678 642//642 -f 675//675 642//642 681//681 -f 681//681 642//642 641//641 -f 681//681 641//641 680//680 -f 680//680 641//641 645//645 -f 680//680 645//645 644//644 -f 218//218 220//220 682//682 -f 682//682 220//220 679//679 -f 682//682 679//679 683//683 -f 683//683 679//679 677//677 -f 683//683 677//677 684//684 -f 684//684 677//677 676//676 -f 684//684 676//676 374//374 -f 374//374 676//676 373//373 -f 428//428 513//513 512//512 -f 512//512 511//511 428//428 -f 428//428 511//511 510//510 -f 428//428 510//510 514//514 -f 514//514 515//515 428//428 -f 428//428 515//515 516//516 -f 428//428 516//516 471//471 -f 471//471 516//516 517//517 -f 471//471 517//517 518//518 -f 685//685 686//686 521//521 -f 521//521 686//686 687//687 -f 518//518 519//519 471//471 -f 471//471 519//519 521//521 -f 471//471 521//521 688//688 -f 688//688 521//521 687//687 -f 685//685 521//521 689//689 -f 689//689 521//521 520//520 -f 689//689 520//520 690//690 -f 690//690 520//520 525//525 -f 690//690 525//525 691//691 -f 525//525 524//524 691//691 -f 691//691 524//524 523//523 -f 691//691 523//523 692//692 -f 692//692 523//523 522//522 -f 692//692 522//522 693//693 -f 693//693 522//522 526//526 -f 693//693 526//526 527//527 -f 527//527 531//531 693//693 -f 693//693 531//531 530//530 -f 693//693 530//530 694//694 -f 694//694 530//530 209//209 -f 530//530 529//529 209//209 -f 209//209 529//529 528//528 -f 209//209 528//528 208//208 -f 208//208 528//528 534//534 -f 208//208 534//534 535//535 -f 540//540 671//671 532//532 -f 532//532 671//671 208//208 -f 532//532 208//208 533//533 -f 533//533 208//208 535//535 -f 540//540 539//539 671//671 -f 671//671 539//539 538//538 -f 671//671 538//538 537//537 -f 471//471 688//688 3//3 -f 3//3 688//688 687//687 -f 3//3 687//687 686//686 -f 374//374 381//381 695//695 -f 695//695 696//696 374//374 -f 374//374 696//696 697//697 -f 374//374 697//697 684//684 -f 219//219 218//218 698//698 -f 698//698 218//218 682//682 -f 683//683 699//699 682//682 -f 682//682 699//699 700//700 -f 682//682 700//700 698//698 -f 697//697 701//701 684//684 -f 684//684 701//701 702//702 -f 684//684 702//702 683//683 -f 683//683 702//702 703//703 -f 683//683 703//703 699//699 -f 699//699 692//692 693//693 -f 203//203 204//204 209//209 -f 209//209 204//204 219//219 -f 209//209 219//219 694//694 -f 694//694 219//219 698//698 -f 694//694 698//698 693//693 -f 693//693 698//698 700//700 -f 693//693 700//700 699//699 -f 692//692 699//699 691//691 -f 691//691 699//699 703//703 -f 691//691 703//703 702//702 -f 1//1 3//3 696//696 -f 696//696 3//3 686//686 -f 696//696 686//686 697//697 -f 697//697 686//686 685//685 -f 697//697 685//685 701//701 -f 701//701 685//685 689//689 -f 701//701 689//689 702//702 -f 702//702 689//689 690//690 -f 702//702 690//690 691//691 -f 381//381 1//1 695//695 -f 695//695 1//1 696//696 -f 704//704 705//705 706//706 -f 707//707 414//414 412//412 -f 708//708 409//409 410//410 -f 708//708 709//709 409//409 -f 409//409 709//709 710//710 -f 409//409 710//710 403//403 -f 707//707 711//711 414//414 -f 414//414 711//711 712//712 -f 414//414 712//712 410//410 -f 410//410 712//712 713//713 -f 410//410 713//713 708//708 -f 411//411 714//714 412//412 -f 412//412 714//714 715//715 -f 412//412 715//715 707//707 -f 716//716 717//717 419//419 -f 419//419 717//717 718//718 -f 419//419 718//718 411//411 -f 411//411 718//718 719//719 -f 411//411 719//719 714//714 -f 716//716 419//419 720//720 -f 720//720 419//419 418//418 -f 720//720 418//418 721//721 -f 721//721 418//418 416//416 -f 721//721 416//416 722//722 -f 722//722 416//416 723//723 -f 723//723 416//416 415//415 -f 723//723 415//415 724//724 -f 724//724 725//725 726//726 -f 726//726 725//725 727//727 -f 727//727 725//725 728//728 -f 728//728 725//725 729//729 -f 728//728 729//729 706//706 -f 706//706 729//729 730//730 -f 706//706 730//730 704//704 -f 724//724 415//415 725//725 -f 725//725 415//415 420//420 -f 725//725 420//420 729//729 -f 729//729 420//420 422//422 -f 729//729 422//422 730//730 -f 731//731 732//732 733//733 -f 734//734 735//735 736//736 -f 736//736 735//735 731//731 -f 736//736 731//731 737//737 -f 737//737 731//731 733//733 -f 737//737 733//733 738//738 -f 739//739 734//734 479//479 -f 740//740 741//741 488//488 -f 488//488 741//741 742//742 -f 488//488 742//742 489//489 -f 489//489 742//742 739//739 -f 489//489 739//739 478//478 -f 478//478 739//739 479//479 -f 743//743 744//744 485//485 -f 485//485 744//744 745//745 -f 485//485 745//745 486//486 -f 486//486 745//745 746//746 -f 486//486 746//746 487//487 -f 487//487 746//746 747//747 -f 487//487 747//747 488//488 -f 488//488 747//747 748//748 -f 488//488 748//748 740//740 -f 490//490 749//749 482//482 -f 482//482 749//749 750//750 -f 482//482 750//750 483//483 -f 483//483 750//750 751//751 -f 483//483 751//751 485//485 -f 485//485 751//751 752//752 -f 485//485 752//752 743//743 -f 734//734 736//736 479//479 -f 479//479 736//736 737//737 -f 479//479 737//737 481//481 -f 481//481 737//737 738//738 -f 481//481 738//738 465//465 -f 753//753 754//754 704//704 -f 753//753 704//704 732//732 -f 754//754 222//222 221//221 -f 705//705 704//704 755//755 -f 755//755 704//704 754//754 -f 755//755 754//754 756//756 -f 756//756 754//754 221//221 -f 422//422 465//465 730//730 -f 730//730 465//465 738//738 -f 730//730 738//738 704//704 -f 704//704 738//738 733//733 -f 704//704 733//733 732//732 -f 757//757 758//758 759//759 -f 718//718 717//717 398//398 -f 722//722 723//723 401//401 -f 755//755 760//760 705//705 -f 760//760 755//755 761//761 -f 762//762 706//706 705//705 -f 726//726 727//727 762//762 -f 762//762 727//727 728//728 -f 762//762 728//728 706//706 -f 396//396 402//402 726//726 -f 401//401 723//723 402//402 -f 402//402 723//723 724//724 -f 402//402 724//724 726//726 -f 398//398 717//717 399//399 -f 717//717 716//716 399//399 -f 399//399 716//716 720//720 -f 399//399 720//720 401//401 -f 401//401 720//720 721//721 -f 401//401 721//721 722//722 -f 711//711 707//707 408//408 -f 707//707 715//715 408//408 -f 408//408 715//715 714//714 -f 408//408 714//714 398//398 -f 398//398 714//714 719//719 -f 398//398 719//719 718//718 -f 713//713 712//712 406//406 -f 406//406 712//712 711//711 -f 406//406 711//711 407//407 -f 407//407 711//711 408//408 -f 403//403 710//710 404//404 -f 404//404 710//710 709//709 -f 404//404 709//709 406//406 -f 406//406 709//709 708//708 -f 406//406 708//708 713//713 -f 756//756 221//221 763//763 -f 763//763 221//221 230//230 -f 253//253 763//763 255//255 -f 255//255 763//763 230//230 -f 255//255 230//230 229//229 -f 253//253 764//764 763//763 -f 763//763 764//764 761//761 -f 763//763 761//761 756//756 -f 756//756 761//761 755//755 -f 764//764 757//757 761//761 -f 761//761 757//757 759//759 -f 761//761 759//759 760//760 -f 760//760 759//759 765//765 -f 760//760 765//765 705//705 -f 705//705 765//765 766//766 -f 705//705 766//766 762//762 -f 726//726 762//762 396//396 -f 396//396 762//762 766//766 -f 396//396 766//766 397//397 -f 397//397 766//766 765//765 -f 397//397 765//765 394//394 -f 394//394 765//765 759//759 -f 394//394 759//759 391//391 -f 391//391 759//759 758//758 -f 391//391 758//758 383//383 -f 767//767 768//768 769//769 -f 754//754 753//753 770//770 -f 770//770 753//753 732//732 -f 769//769 771//771 222//222 -f 235//235 228//228 771//771 -f 771//771 228//228 223//223 -f 771//771 223//223 222//222 -f 751//751 750//750 496//496 -f 496//496 750//750 491//491 -f 491//491 750//750 749//749 -f 491//491 749//749 490//490 -f 751//751 496//496 752//752 -f 752//752 496//496 495//495 -f 752//752 495//495 743//743 -f 743//743 495//495 744//744 -f 744//744 495//495 494//494 -f 744//744 494//494 745//745 -f 475//475 748//748 492//492 -f 492//492 748//748 747//747 -f 492//492 747//747 494//494 -f 494//494 747//747 746//746 -f 494//494 746//746 745//745 -f 477//477 734//734 739//739 -f 739//739 742//742 477//477 -f 477//477 742//742 741//741 -f 477//477 741//741 475//475 -f 475//475 741//741 740//740 -f 475//475 740//740 748//748 -f 477//477 497//497 734//734 -f 734//734 497//497 499//499 -f 734//734 499//499 772//772 -f 772//772 499//499 501//501 -f 772//772 501//501 773//773 -f 773//773 501//501 503//503 -f 773//773 503//503 767//767 -f 767//767 503//503 504//504 -f 767//767 504//504 768//768 -f 222//222 754//754 769//769 -f 769//769 754//754 770//770 -f 769//769 770//770 767//767 -f 767//767 770//770 732//732 -f 767//767 732//732 773//773 -f 773//773 732//732 731//731 -f 773//773 731//731 772//772 -f 772//772 731//731 735//735 -f 772//772 735//735 734//734 -f 233//233 235//235 774//774 -f 774//774 235//235 771//771 -f 774//774 771//771 775//775 -f 775//775 771//771 769//769 -f 775//775 769//769 776//776 -f 776//776 769//769 768//768 -f 776//776 768//768 469//469 -f 469//469 768//768 504//504 -f 777//777 778//778 383//383 -f 383//383 778//778 779//779 -f 383//383 779//779 384//384 -f 758//758 757//757 780//780 -f 780//780 781//781 758//758 -f 758//758 781//781 782//782 -f 758//758 782//782 383//383 -f 383//383 782//782 783//783 -f 383//383 783//783 777//777 -f 764//764 253//253 251//251 -f 251//251 784//784 764//764 -f 764//764 784//784 785//785 -f 764//764 785//785 757//757 -f 757//757 785//785 786//786 -f 757//757 786//786 780//780 -f 384//384 779//779 2//2 -f 2//2 779//779 778//778 -f 2//2 778//778 777//777 -f 573//573 572//572 774//774 -f 787//787 556//556 468//468 -f 468//468 556//556 555//555 -f 468//468 555//555 554//554 -f 554//554 560//560 468//468 -f 468//468 560//560 559//559 -f 468//468 559//559 469//469 -f 469//469 559//559 558//558 -f 469//469 558//558 562//562 -f 562//562 561//561 469//469 -f 469//469 561//561 564//564 -f 469//469 564//564 776//776 -f 774//774 572//572 233//233 -f 233//233 572//572 571//571 -f 233//233 571//571 234//234 -f 234//234 571//571 568//568 -f 234//234 568//568 788//788 -f 788//788 568//568 569//569 -f 788//788 569//569 570//570 -f 564//564 563//563 776//776 -f 776//776 563//563 567//567 -f 776//776 567//567 775//775 -f 775//775 567//567 566//566 -f 775//775 566//566 774//774 -f 774//774 566//566 565//565 -f 774//774 565//565 573//573 -f 787//787 789//789 556//556 -f 556//556 789//789 790//790 -f 556//556 790//790 557//557 -f 557//557 790//790 791//791 -f 557//557 791//791 550//550 -f 550//550 791//791 792//792 -f 550//550 792//792 551//551 -f 552//552 551//551 792//792 -f 236//236 231//231 251//251 -f 251//251 231//231 234//234 -f 251//251 234//234 784//784 -f 234//234 788//788 784//784 -f 784//784 788//788 570//570 -f 784//784 570//570 785//785 -f 785//785 570//570 549//549 -f 785//785 549//549 786//786 -f 549//549 548//548 786//786 -f 786//786 548//548 553//553 -f 786//786 553//553 780//780 -f 780//780 553//553 552//552 -f 780//780 552//552 781//781 -f 781//781 552//552 792//792 -f 781//781 792//792 782//782 -f 782//782 792//792 791//791 -f 782//782 791//791 783//783 -f 791//791 790//790 783//783 -f 783//783 790//790 789//789 -f 783//783 789//789 777//777 -f 777//777 789//789 4//4 -f 777//777 4//4 2//2 -f 468//468 4//4 787//787 -f 787//787 4//4 789//789 -f 574//574 576//576 610//610 -f 610//610 576//576 585//585 -f 610//610 585//585 609//609 -f 585//585 583//583 609//609 -f 609//609 583//583 581//581 -f 609//609 581//581 607//607 -f 607//607 581//581 225//225 -f 607//607 225//225 224//224 -f 594//594 611//611 592//592 -f 592//592 611//611 238//238 -f 592//592 238//238 239//239 -f 577//577 575//575 595//595 -f 595//595 575//575 613//613 -f 595//595 613//613 594//594 -f 594//594 613//613 612//612 -f 594//594 612//612 611//611 -f 277//277 284//284 275//275 -f 275//275 284//284 200//200 -f 275//275 200//200 199//199 -f 261//261 279//279 278//278 -f 278//278 279//279 283//283 -f 278//278 283//283 277//277 -f 277//277 283//283 285//285 -f 277//277 285//285 284//284 -f 297//297 269//269 295//295 -f 295//295 269//269 214//214 -f 295//295 214//214 213//213 -f 280//280 260//260 298//298 -f 298//298 260//260 271//271 -f 298//298 271//271 297//297 -f 297//297 271//271 270//270 -f 297//297 270//270 269//269 -# 1612 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_Dz_right.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_Dz_right.obj deleted file mode 100644 index f70cb0bc6..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_Dz_right.obj +++ /dev/null @@ -1,3212 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object hand_Dz_right.obj -# -# Vertices: 792 -# Faces: 1612 -# -#### -vn 0.343627 -0.907116 6.185071 -v -0.047000 -0.140693 0.175880 -vn -0.348265 -0.901073 6.186115 -v -0.025000 -0.140693 0.175880 -vn 0.348262 0.445449 6.235507 -v -0.047000 -0.122705 0.176540 -vn -0.343634 0.451539 6.234909 -v -0.025000 -0.122705 0.176540 -vn 2.827434 0.113736 -3.100830 -v -0.026000 -0.129097 0.105257 -vn 2.827433 1.066378 -2.913918 -v -0.026000 -0.125720 0.105920 -vn 3.665201 -1.612592 2.570601 -v -0.026000 -0.128542 0.107196 -vn 3.665202 1.419926 2.681837 -v -0.026000 -0.138080 0.114852 -vn 3.665173 2.570615 1.612591 -v -0.026000 -0.138554 0.115293 -vn 2.827430 -2.913917 -1.066380 -v -0.026000 -0.139830 0.112470 -vn 3.122248 3.305462 -0.124654 -v -0.026000 -0.120157 0.161623 -vn 3.122273 -3.287449 -0.366480 -v -0.026000 -0.142142 0.160817 -vn 3.665170 0.111230 -3.032515 -v -0.026000 -0.129839 0.125494 -vn 2.984514 -3.111148 -0.360005 -v -0.026000 -0.140493 0.115847 -vn 3.665195 1.612557 -2.570625 -v -0.026000 -0.130457 0.125304 -vn 3.665209 3.032498 0.111236 -v -0.026000 -0.130456 0.108210 -vn 3.665183 2.681841 -1.419934 -v -0.026000 -0.130311 0.108840 -vn 3.665193 -0.111237 3.032508 -v -0.026000 -0.129747 0.122995 -vn 3.665193 1.612584 -2.570611 -v -0.026000 -0.129871 0.109314 -vn 3.665187 0.111237 -3.032508 -v -0.026000 -0.129253 0.109505 -vn 3.665212 3.032497 0.111232 -v -0.026000 -0.138744 0.115911 -vn 3.665172 2.681849 -1.419929 -v -0.026000 -0.138599 0.116542 -vn 3.665201 1.612592 -2.570601 -v -0.026000 -0.138159 0.117016 -vn 3.665195 2.570625 1.612558 -v -0.026000 -0.130852 0.123580 -vn 3.665168 3.032516 0.111234 -v -0.026000 -0.131042 0.124199 -vn 3.665212 2.681839 -1.419914 -v -0.026000 -0.130898 0.124830 -vn 3.665199 -0.111220 3.032504 -v -0.026000 -0.129161 0.107006 -vn 3.665183 1.419934 2.681841 -v -0.026000 -0.129792 0.107151 -vn 3.665181 2.570605 1.612600 -v -0.026000 -0.130266 0.107591 -vn 3.665188 -0.111237 3.032508 -v -0.026000 -0.137449 0.114708 -vn 2.827436 -2.441771 -1.914638 -v -0.026000 -0.138156 0.109463 -vn 3.665194 -1.612584 2.570611 -v -0.026000 -0.136830 0.114898 -vn 2.827434 -1.730610 -2.575474 -v -0.026000 -0.135635 0.107120 -vn 2.827432 -0.850040 -2.984210 -v -0.026000 -0.132513 0.105671 -vn 3.665187 0.111237 -3.032508 -v -0.026000 -0.137540 0.117206 -vn 3.665204 -1.419926 -2.681837 -v -0.026000 -0.136910 0.117061 -vn 3.665205 1.419926 2.681837 -v -0.026000 -0.130378 0.123140 -vn 3.665174 -2.570615 -1.612591 -v -0.026000 -0.136436 0.116621 -vn 3.665208 -3.032498 -0.111236 -v -0.026000 -0.136245 0.116003 -vn 3.665182 -2.681841 1.419934 -v -0.026000 -0.136390 0.115372 -vn 2.827431 2.984210 -0.850040 -v -0.026000 -0.118921 0.113237 -vn 2.984514 3.129163 -0.131115 -v -0.026000 -0.118507 0.116653 -vn 3.665187 -3.032508 -0.111237 -v -0.026000 -0.120256 0.116589 -vn 2.827434 2.575474 -1.730610 -v -0.026000 -0.120370 0.110115 -vn 3.665172 -2.570615 -1.612591 -v -0.026000 -0.128148 0.108920 -vn 2.827435 1.914636 -2.441772 -v -0.026000 -0.122713 0.107594 -vn 3.665212 -3.032497 -0.111232 -v -0.026000 -0.127958 0.108301 -vn 3.665173 -2.681849 1.419929 -v -0.026000 -0.128102 0.107670 -vn 3.665193 -1.419899 -2.681856 -v -0.026000 -0.129208 0.125349 -vn 3.665211 -2.570607 -1.612575 -v -0.026000 -0.128734 0.124909 -vn 3.665190 1.612582 -2.570611 -v -0.026000 -0.122170 0.117602 -vn 3.665203 -2.681837 1.419926 -v -0.026000 -0.120401 0.115958 -vn 3.665184 -1.612574 2.570620 -v -0.026000 -0.120841 0.115484 -vn 3.665190 -0.111233 3.032507 -v -0.026000 -0.121460 0.115294 -vn 3.665192 1.419921 2.681844 -v -0.026000 -0.122090 0.115439 -vn 3.665203 -1.419926 -2.681837 -v -0.026000 -0.128622 0.109360 -vn 3.665193 2.570611 1.612582 -v -0.026000 -0.122564 0.115879 -vn 3.665201 0.111216 -3.032503 -v -0.026000 -0.121551 0.117792 -vn 3.665172 -1.419929 -2.681849 -v -0.026000 -0.120920 0.117648 -vn 3.665201 -2.570601 -1.612592 -v -0.026000 -0.120446 0.117207 -vn 3.665187 -3.032508 -0.111203 -v -0.026000 -0.128544 0.124290 -vn 3.665183 -2.681841 1.419934 -v -0.026000 -0.128689 0.123660 -vn 3.665191 2.681844 -1.419921 -v -0.026000 -0.122610 0.117128 -vn 3.665191 -1.612584 2.570611 -v -0.026000 -0.129129 0.123186 -vn 3.665189 3.032507 0.111233 -v -0.026000 -0.122755 0.116497 -vn -3.665168 3.032516 0.111234 -v -0.030000 -0.131042 0.124199 -vn -3.665195 2.570625 1.612558 -v -0.030000 -0.130852 0.123580 -vn -3.665179 0.111237 -3.032508 -v -0.030000 -0.129253 0.109505 -vn -3.665202 1.419926 2.681837 -v -0.030000 -0.130378 0.123140 -vn -3.665187 -0.111237 3.032508 -v -0.030000 -0.129747 0.122995 -vn -3.122254 3.305463 -0.124653 -v -0.030000 -0.120157 0.161623 -vn -3.665212 -2.570607 -1.612575 -v -0.030000 -0.128734 0.124909 -vn -3.665193 -1.419899 -2.681855 -v -0.030000 -0.129208 0.125349 -vn -2.827430 -2.913916 -1.066380 -v -0.030000 -0.139830 0.112470 -vn -2.984513 -3.111149 -0.360005 -v -0.030000 -0.140493 0.115847 -vn -3.665212 3.032497 0.111233 -v -0.030000 -0.138744 0.115911 -vn -3.665210 -3.032498 -0.111237 -v -0.030000 -0.136245 0.116003 -vn -3.665194 1.612584 -2.570611 -v -0.030000 -0.129871 0.109314 -vn -3.122265 -3.287448 -0.366480 -v -0.030000 -0.142142 0.160817 -vn -3.665173 2.570614 1.612591 -v -0.030000 -0.138554 0.115293 -vn -3.665202 1.419926 2.681837 -v -0.030000 -0.138080 0.114852 -vn -2.827437 -2.441771 -1.914638 -v -0.030000 -0.138156 0.109463 -vn -3.665188 -0.111237 3.032508 -v -0.030000 -0.137449 0.114708 -vn -2.827434 -1.730610 -2.575474 -v -0.030000 -0.135635 0.107120 -vn -3.665195 -1.612584 2.570611 -v -0.030000 -0.136830 0.114898 -vn -2.827432 -0.850040 -2.984210 -v -0.030000 -0.132513 0.105671 -vn -2.827434 0.113736 -3.100830 -v -0.030000 -0.129097 0.105257 -vn -3.665171 -2.570614 -1.612591 -v -0.030000 -0.136436 0.116621 -vn -3.665210 2.681839 -1.419913 -v -0.030000 -0.130898 0.124830 -vn -3.665170 0.111230 -3.032515 -v -0.030000 -0.129839 0.125494 -vn -3.665195 1.612557 -2.570626 -v -0.030000 -0.130457 0.125304 -vn -3.665202 -1.419926 -2.681837 -v -0.030000 -0.136910 0.117061 -vn -3.665187 0.111237 -3.032508 -v -0.030000 -0.137540 0.117206 -vn -3.665200 1.612592 -2.570601 -v -0.030000 -0.138159 0.117016 -vn -3.665172 2.681849 -1.419929 -v -0.030000 -0.138599 0.116542 -vn -3.665190 -0.111233 3.032507 -v -0.030000 -0.121460 0.115294 -vn -3.665184 -1.612575 2.570620 -v -0.030000 -0.120841 0.115484 -vn -2.827431 2.984210 -0.850040 -v -0.030000 -0.118921 0.113237 -vn -3.665202 -2.681837 1.419926 -v -0.030000 -0.120401 0.115958 -vn -2.984514 3.129162 -0.131116 -v -0.030000 -0.118507 0.116653 -vn -3.665187 -3.032508 -0.111237 -v -0.030000 -0.120256 0.116589 -vn -3.665201 -2.570601 -1.612592 -v -0.030000 -0.120446 0.117207 -vn -3.665183 2.681842 -1.419934 -v -0.030000 -0.130311 0.108840 -vn -3.665183 -2.681842 1.419934 -v -0.030000 -0.136390 0.115372 -vn -3.665210 3.032498 0.111237 -v -0.030000 -0.130456 0.108210 -vn -3.665182 2.570605 1.612600 -v -0.030000 -0.130266 0.107591 -vn -3.665183 1.419934 2.681842 -v -0.030000 -0.129792 0.107151 -vn -3.665199 -0.111220 3.032503 -v -0.030000 -0.129161 0.107006 -vn -2.827432 1.066378 -2.913917 -v -0.030000 -0.125720 0.105920 -vn -3.665173 -1.419929 -2.681849 -v -0.030000 -0.120920 0.117648 -vn -3.665201 0.111216 -3.032503 -v -0.030000 -0.121551 0.117792 -vn -3.665192 1.612583 -2.570611 -v -0.030000 -0.122170 0.117602 -vn -3.665187 -3.032508 -0.111204 -v -0.030000 -0.128544 0.124290 -vn -3.665183 -2.681842 1.419934 -v -0.030000 -0.128689 0.123660 -vn -3.665192 -1.612584 2.570611 -v -0.030000 -0.129129 0.123186 -vn -3.665192 2.681844 -1.419921 -v -0.030000 -0.122610 0.117128 -vn -3.665189 3.032507 0.111233 -v -0.030000 -0.122755 0.116497 -vn -3.665201 -1.612592 2.570601 -v -0.030000 -0.128542 0.107196 -vn -3.665173 -2.681849 1.419929 -v -0.030000 -0.128102 0.107670 -vn -2.827435 1.914636 -2.441772 -v -0.030000 -0.122713 0.107594 -vn -3.665212 -3.032497 -0.111233 -v -0.030000 -0.127958 0.108301 -vn -2.827434 2.575474 -1.730610 -v -0.030000 -0.120370 0.110115 -vn -3.665173 -2.570614 -1.612591 -v -0.030000 -0.128148 0.108920 -vn -3.665192 1.419921 2.681844 -v -0.030000 -0.122090 0.115439 -vn -3.665194 2.570611 1.612583 -v -0.030000 -0.122564 0.115879 -vn -3.665203 -1.419926 -2.681837 -v -0.030000 -0.128622 0.109360 -vn 0.245720 -3.182010 -3.241051 -v -0.016000 -0.142509 0.170810 -vn 0.275986 -3.005335 -3.097696 -v -0.009000 -0.142509 0.170810 -vn 0.303351 -6.210490 0.365051 -v -0.009000 -0.142619 0.173808 -vn -0.303357 -6.210488 0.365056 -v -0.063000 -0.142619 0.173808 -vn -0.275986 -3.005332 -3.097694 -v -0.063000 -0.142509 0.170810 -vn -0.245724 -3.182009 -3.241061 -v -0.040000 -0.142509 0.170810 -vn 0.958851 -3.345263 -3.075727 -v -0.019090 -0.142491 0.170321 -vn -2.951044 -3.418280 -1.084877 -v -0.030489 -0.142255 0.163905 -vn 2.951044 -3.418281 -1.084877 -v -0.025511 -0.142255 0.163905 -vn -0.958851 -3.345263 -3.075735 -v -0.036910 -0.142491 0.170321 -vn -1.823847 -3.361415 -2.635295 -v -0.034122 -0.142439 0.168901 -vn -2.510313 -3.386580 -1.949289 -v -0.031910 -0.142358 0.166690 -vn 1.823845 -3.361414 -2.635297 -v -0.021878 -0.142439 0.168901 -vn 2.510314 -3.386581 -1.949296 -v -0.024090 -0.142358 0.166690 -vn -0.275980 3.224193 -2.869202 -v -0.063000 -0.120523 0.171616 -vn -0.303349 6.167062 0.819035 -v -0.063000 -0.120633 0.174614 -vn -0.245730 3.410903 -2.999241 -v -0.040000 -0.120523 0.171616 -vn 0.303349 6.167064 0.819035 -v -0.009000 -0.120633 0.174614 -vn -0.958856 3.561596 -2.822418 -v -0.036910 -0.120505 0.171127 -vn 2.951044 3.488576 -0.831539 -v -0.025511 -0.120270 0.164711 -vn 0.275982 3.224201 -2.869201 -v -0.009000 -0.120523 0.171616 -vn 0.245719 3.410902 -2.999205 -v -0.016000 -0.120523 0.171616 -vn 0.958857 3.561596 -2.822394 -v -0.019090 -0.120505 0.171127 -vn 1.823845 3.545440 -2.381956 -v -0.021878 -0.120453 0.169708 -vn 2.510308 3.520282 -1.695954 -v -0.024090 -0.120372 0.167497 -vn -2.951045 3.488576 -0.831539 -v -0.030489 -0.120270 0.164711 -vn -2.510310 3.520282 -1.695951 -v -0.031910 -0.120372 0.167497 -vn -1.823847 3.545442 -2.381953 -v -0.034122 -0.120453 0.169708 -vn -3.038455 0.131942 -3.640386 -v -0.054250 -0.125020 0.171451 -vn -2.635299 -1.380347 -3.688349 -v -0.054551 -0.123896 0.171493 -vn -2.630616 1.653040 -3.583732 -v -0.054551 -0.126145 0.171410 -vn -1.519278 2.762754 -3.544739 -v -0.055375 -0.126968 0.171380 -vn -1.183322 -2.751146 -2.932151 -v -0.064913 -0.142128 0.170824 -vn 1.517279 2.760559 -3.566401 -v -0.057625 -0.126968 0.171380 -vn 0.006920 3.168255 -3.539588 -v -0.056500 -0.127269 0.171369 -vn -3.116872 0.385213 -2.973342 -v -0.068000 -0.125520 0.171433 -vn 3.034673 0.134769 -3.661009 -v -0.058750 -0.125020 0.171451 -vn -3.116878 -0.166356 -2.993571 -v -0.068000 -0.137512 0.170993 -vn 2.627947 1.650637 -3.606201 -v -0.058449 -0.126145 0.171410 -vn -2.856765 -1.078815 -2.870806 -v -0.067619 -0.139424 0.170923 -vn -2.186476 -2.081303 -2.907583 -v -0.066536 -0.141045 0.170864 -vn -1.521477 -2.498747 -3.719464 -v -0.055375 -0.123073 0.171523 -vn 0.013574 -2.902396 -3.753518 -v -0.056500 -0.122772 0.171534 -vn 1.517570 -2.491922 -3.756099 -v -0.057625 -0.123073 0.171523 -vn -1.183313 2.958580 -2.722725 -v -0.064913 -0.120904 0.171602 -vn 2.628077 -1.382180 -3.715132 -v -0.058449 -0.123896 0.171493 -vn -2.186466 2.288713 -2.747296 -v -0.066536 -0.121987 0.171563 -vn -2.856761 1.286216 -2.784060 -v -0.067619 -0.123608 0.171503 -vn 3.116876 0.385211 -2.973344 -v -0.004000 -0.125520 0.171433 -vn 6.200029 0.283021 0.570842 -v -0.004000 -0.125630 0.174431 -vn 3.116880 -0.166352 -2.993574 -v -0.004000 -0.137512 0.170993 -vn 6.200030 -0.324077 0.548574 -v -0.004000 -0.137622 0.173991 -vn -6.200029 -0.324077 0.548574 -v -0.068000 -0.137622 0.173991 -vn -6.200028 0.283021 0.570842 -v -0.068000 -0.125630 0.174431 -vn 1.517448 -2.492066 -3.755782 -v -0.011625 -0.123073 0.171523 -vn 2.628182 -1.382174 -3.714619 -v -0.012449 -0.123896 0.171493 -vn 3.034990 0.133825 -3.658477 -v -0.012750 -0.125020 0.171451 -vn 2.627671 1.651574 -3.604193 -v -0.012449 -0.126145 0.171410 -vn 1.517045 2.760656 -3.565555 -v -0.011625 -0.126968 0.171380 -vn 0.002748 3.167339 -3.546209 -v -0.010500 -0.127269 0.171369 -vn 1.183325 -2.751147 -2.932149 -v -0.007087 -0.142128 0.170824 -vn -3.038432 0.129760 -3.639242 -v -0.008250 -0.125020 0.171451 -vn 2.856760 1.286210 -2.784053 -v -0.004381 -0.123608 0.171503 -vn -2.631232 -1.383341 -3.698787 -v -0.008551 -0.123896 0.171493 -vn 0.012808 -2.902165 -3.754625 -v -0.010500 -0.122772 0.171534 -vn -1.525336 -2.494109 -3.729058 -v -0.009375 -0.123073 0.171523 -vn 1.183313 2.958570 -2.722723 -v -0.007087 -0.120904 0.171602 -vn 2.186462 2.288711 -2.747291 -v -0.005464 -0.121987 0.171563 -vn 2.186475 -2.081301 -2.907578 -v -0.005464 -0.141045 0.170864 -vn 2.856764 -1.078809 -2.870798 -v -0.004381 -0.139424 0.170923 -vn -1.514515 2.764586 -3.550441 -v -0.009375 -0.126968 0.171380 -vn -2.630748 1.653524 -3.580896 -v -0.008551 -0.126145 0.171410 -vn -3.139255 3.190970 0.202952 -v -0.015000 -0.128069 0.186350 -vn -3.139236 -3.197264 -0.031390 -v -0.015000 -0.136063 0.186056 -vn -3.228858 3.138526 -0.021878 -v -0.015000 -0.128618 0.201339 -vn -3.054328 -3.138526 0.021877 -v -0.015000 -0.136613 0.201046 -vn -3.082228 2.861353 0.282378 -v -0.015000 -0.127934 0.214847 -vn -3.093915 -2.891157 0.530187 -v -0.015000 -0.135929 0.214554 -vn 3.228858 3.138524 -0.021877 -v -0.007000 -0.128618 0.201339 -vn -0.015814 6.235506 0.646735 -v -0.009000 -0.128028 0.185259 -vn -3.211748 3.261980 0.748784 -v -0.015060 -0.128028 0.185259 -vn 0.033573 6.232452 0.664616 -v -0.007412 -0.128026 0.185186 -vn 3.306431 3.115213 0.335941 -v -0.007000 -0.128024 0.185143 -vn 3.082237 2.861359 0.282371 -v -0.007000 -0.127934 0.214847 -vn 3.093909 -2.891162 0.530180 -v -0.007000 -0.135929 0.214554 -vn 3.054327 -3.138527 0.021877 -v -0.007000 -0.136613 0.201046 -vn 3.213648 -3.139867 -0.012405 -v -0.007000 -0.136019 0.184850 -vn 3.954146 3.001080 0.431454 -v -0.007000 -0.127831 0.183507 -vn 3.770454 -3.063827 0.281662 -v -0.007000 -0.136050 0.183606 -vn 3.463285 2.950206 1.192935 -v -0.007000 -0.127511 0.182305 -vn 3.392277 -3.090753 0.923573 -v -0.007000 -0.136323 0.181981 -vn 0.098436 -6.270590 0.106524 -v -0.007412 -0.136020 0.184893 -vn 0.010508 -6.264178 0.209842 -v -0.009000 -0.136023 0.184966 -vn -3.224411 -3.307235 0.518155 -v -0.015060 -0.136023 0.184966 -vn -3.093916 -2.891161 0.530181 -v -0.065000 -0.135929 0.214554 -vn -3.082229 2.861358 0.282370 -v -0.065000 -0.127934 0.214847 -vn -3.054329 -3.138526 0.021879 -v -0.065000 -0.136613 0.201046 -vn -3.228858 3.138526 -0.021877 -v -0.065000 -0.128618 0.201339 -vn -3.306395 -3.131454 0.106809 -v -0.065000 -0.136019 0.184850 -vn -3.213692 3.132338 0.217648 -v -0.065000 -0.128024 0.185143 -vn -3.954252 -3.024597 0.210414 -v -0.065000 -0.136092 0.183204 -vn -3.770513 3.034949 0.505355 -v -0.065000 -0.127902 0.183904 -vn -3.463275 -3.029671 0.973607 -v -0.065000 -0.136323 0.181981 -vn -3.392271 3.014787 1.147520 -v -0.065000 -0.127511 0.182305 -vn -0.098492 6.245937 0.565619 -v -0.064588 -0.128026 0.185186 -vn 3.228858 3.138526 -0.021877 -v -0.057000 -0.128618 0.201339 -vn 3.139256 3.190975 0.202952 -v -0.057000 -0.128069 0.186350 -vn 0.000002 6.233339 0.660571 -v -0.063000 -0.128028 0.185259 -vn 3.214632 3.259931 0.762667 -v -0.056940 -0.128028 0.185259 -vn 3.082237 2.861358 0.282371 -v -0.057000 -0.127934 0.214847 -vn 3.093909 -2.891161 0.530180 -v -0.057000 -0.135929 0.214554 -vn 3.054329 -3.138526 0.021879 -v -0.057000 -0.136613 0.201046 -vn 3.139189 -3.197263 -0.031402 -v -0.057000 -0.136063 0.186056 -vn -3.034522 -3.663035 -0.177861 -v -0.058249 -0.136334 0.193450 -vn 2.590251 -3.739636 -1.671468 -v -0.063380 -0.136385 0.194829 -vn 3.034532 -3.663025 -0.177859 -v -0.063749 -0.136334 0.193450 -vn -0.794829 -3.555459 -3.109778 -v -0.060287 -0.136432 0.196114 -vn -1.680935 -3.661424 -2.675511 -v -0.059624 -0.136422 0.195839 -vn -2.590251 -3.739628 -1.671473 -v -0.058617 -0.136385 0.194829 -vn -2.665793 -3.586134 1.359179 -v -0.058617 -0.136284 0.192070 -vn -1.742712 -3.402227 2.441859 -v -0.059624 -0.136247 0.191061 -vn 3.200358 -3.308976 0.494662 -v -0.056940 -0.136023 0.184966 -vn -0.791937 -3.292060 2.904480 -v -0.060287 -0.136237 0.190785 -vn 0.006576 -6.265344 0.198089 -v -0.063000 -0.136023 0.184966 -vn -0.026088 -3.279869 3.006533 -v -0.060999 -0.136233 0.190691 -vn 0.817471 -3.251453 2.899607 -v -0.061710 -0.136237 0.190785 -vn -0.033510 -6.264391 0.206222 -v -0.064588 -0.136020 0.184893 -vn 1.742712 -3.402225 2.441860 -v -0.062374 -0.136247 0.191061 -vn 2.665801 -3.586143 1.359177 -v -0.063380 -0.136284 0.192070 -vn 1.680933 -3.661423 -2.675513 -v -0.062374 -0.136422 0.195839 -vn 0.794820 -3.555458 -3.109794 -v -0.061710 -0.136432 0.196114 -vn 0.000015 -3.558534 -3.212915 -v -0.060999 -0.136435 0.196208 -vn 0.000002 3.507021 -3.216047 -v -0.011000 -0.128061 0.212344 -vn -0.203572 2.892089 2.962452 -v -0.012000 -0.127782 0.217855 -vn 0.203574 2.892087 2.962454 -v -0.010000 -0.127782 0.217855 -vn 1.517293 3.527556 -2.810027 -v -0.012375 -0.128080 0.211976 -vn 2.627953 3.583754 -1.700725 -v -0.013382 -0.128131 0.210970 -vn 3.034552 3.660501 -0.185397 -v -0.013750 -0.128200 0.209597 -vn 2.627958 3.737252 1.329944 -v -0.013382 -0.128270 0.208224 -vn 1.517288 3.793418 2.439238 -v -0.012375 -0.128321 0.207219 -vn 0.000010 3.814010 2.845278 -v -0.011000 -0.128339 0.206851 -vn -1.517293 3.793423 2.439229 -v -0.009625 -0.128321 0.207219 -vn -2.590252 2.559179 1.405641 -v -0.014598 -0.127858 0.216351 -vn -1.680936 2.651371 2.408452 -v -0.013500 -0.127802 0.217452 -vn -0.794851 2.765715 2.841371 -v -0.012776 -0.127787 0.217752 -vn -2.627962 3.737248 1.329940 -v -0.008618 -0.128270 0.208224 -vn -3.034551 3.660501 -0.185397 -v -0.008250 -0.128200 0.209597 -vn -2.627958 3.583751 -1.700722 -v -0.008618 -0.128131 0.210970 -vn 2.590250 2.559171 1.405639 -v -0.007402 -0.127858 0.216351 -vn -1.517298 3.527562 -2.810024 -v -0.009625 -0.128080 0.211976 -vn 1.680935 2.651377 2.408454 -v -0.008500 -0.127802 0.217452 -vn 0.794848 2.765714 2.841372 -v -0.009224 -0.127787 0.217752 -vn 0.206516 -3.121428 3.289618 -v -0.010000 -0.135777 0.217561 -vn -0.206517 -3.121431 3.289616 -v -0.012000 -0.135777 0.217561 -vn -0.000002 -3.814009 -2.845269 -v -0.011000 -0.136020 0.212747 -vn -1.517288 -3.793424 -2.439230 -v -0.009625 -0.136039 0.212379 -vn 0.817478 -2.986231 3.171768 -v -0.009224 -0.135782 0.217459 -vn 2.665726 -2.670402 1.626870 -v -0.007402 -0.135853 0.216058 -vn 1.742734 -2.839208 2.712010 -v -0.008500 -0.135797 0.217159 -vn -2.627945 -3.583751 1.700721 -v -0.008618 -0.136229 0.208627 -vn -3.034546 -3.660501 0.185395 -v -0.008250 -0.136159 0.210000 -vn -2.627968 -3.737248 -1.329939 -v -0.008618 -0.136090 0.211373 -vn -1.517300 -3.527562 2.810024 -v -0.009625 -0.136280 0.207622 -vn 0.000002 -3.507020 3.216044 -v -0.011000 -0.136299 0.207254 -vn 1.517298 -3.527556 2.810028 -v -0.012375 -0.136280 0.207622 -vn 2.627941 -3.583754 1.700725 -v -0.013382 -0.136229 0.208627 -vn 3.034547 -3.660501 0.185396 -v -0.013750 -0.136159 0.210000 -vn 2.627964 -3.737252 -1.329945 -v -0.013382 -0.136090 0.211373 -vn -2.665728 -2.670410 1.626876 -v -0.014598 -0.135853 0.216058 -vn 1.517291 -3.793418 -2.439232 -v -0.012375 -0.136039 0.212379 -vn -1.742733 -2.839203 2.712005 -v -0.013500 -0.135797 0.217159 -vn -0.817480 -2.986232 3.171760 -v -0.012776 -0.135782 0.217459 -vn 0.000000 -2.805109 -2.902562 -v -0.060999 -0.128898 0.195827 -vn 1.529212 -2.765732 -2.487974 -v -0.062374 -0.128916 0.195459 -vn -1.529214 -2.765731 -2.487972 -v -0.059624 -0.128916 0.195459 -vn -2.628002 -2.691388 -1.382918 -v -0.058617 -0.128967 0.194453 -vn -3.034544 -2.614641 0.132417 -v -0.058249 -0.129037 0.193080 -vn -2.627990 -2.537905 1.647743 -v -0.058617 -0.129106 0.191707 -vn -1.517514 -2.484313 2.757098 -v -0.059624 -0.129157 0.190702 -vn 2.628002 -2.691381 -1.382913 -v -0.063380 -0.128967 0.194453 -vn 3.034549 -2.614652 0.132418 -v -0.063749 -0.129037 0.193080 -vn 2.627990 -2.537897 1.647739 -v -0.063380 -0.129106 0.191707 -vn 1.529982 -2.501336 2.754498 -v -0.062374 -0.129157 0.190702 -vn -0.012783 -2.480438 3.167373 -v -0.060999 -0.129176 0.190334 -vn 0.000000 -6.275144 0.317808 -v -0.060999 -0.129037 0.193080 -vn -6.041722 -1.228801 0.516219 -v -0.067904 -0.138597 0.173955 -vn -5.704718 -2.358459 0.482367 -v -0.067619 -0.139534 0.173921 -vn -5.141861 -3.452091 0.334046 -v -0.067157 -0.140398 0.173889 -vn -4.345722 -4.390504 0.411441 -v -0.066536 -0.141155 0.173862 -vn -3.422037 -5.138865 0.379324 -v -0.065778 -0.141776 0.173839 -vn -2.357337 -5.708821 0.378509 -v -0.064913 -0.142238 0.173822 -vn -1.201678 -6.057950 0.345605 -v -0.063975 -0.142523 0.173811 -vn 1.201698 -6.057944 0.345614 -v -0.008025 -0.142523 0.173811 -vn 2.357319 -5.708827 0.378507 -v -0.007087 -0.142238 0.173822 -vn 3.422052 -5.138865 0.379311 -v -0.006222 -0.141776 0.173839 -vn 4.344517 -4.392791 0.407946 -v -0.005464 -0.141155 0.173862 -vn 5.143728 -3.445688 0.344043 -v -0.004843 -0.140398 0.173889 -vn 5.700208 -2.364051 0.490338 -v -0.004381 -0.139534 0.173921 -vn 6.041733 -1.228782 0.516205 -v -0.004096 -0.138597 0.173955 -vn 6.041741 1.187647 0.604823 -v -0.004096 -0.124655 0.174467 -vn 5.704709 2.316775 0.653859 -v -0.004381 -0.123718 0.174501 -vn 5.141845 3.418374 0.586041 -v -0.004843 -0.122854 0.174533 -vn 4.345717 4.348570 0.731996 -v -0.005464 -0.122097 0.174561 -vn 3.422069 5.097254 0.754768 -v -0.006222 -0.121475 0.174583 -vn 2.357325 5.665734 0.795751 -v -0.007087 -0.121014 0.174600 -vn 1.201678 6.016358 0.788468 -v -0.008025 -0.120729 0.174611 -vn -1.201673 6.016361 0.788463 -v -0.063975 -0.120729 0.174611 -vn -2.357321 5.665740 0.795747 -v -0.064913 -0.121014 0.174600 -vn -3.422068 5.097251 0.754764 -v -0.065778 -0.121475 0.174583 -vn -4.344526 4.351113 0.728659 -v -0.066536 -0.122097 0.174561 -vn -5.143693 3.411237 0.595593 -v -0.067157 -0.122854 0.174533 -vn -5.700212 2.321786 0.662198 -v -0.067619 -0.123718 0.174501 -vn -6.041728 1.187671 0.604844 -v -0.067904 -0.124655 0.174467 -vn 5.206048 -2.872731 1.917182 -v -0.004858 -0.140144 0.174695 -vn 5.229677 -3.012917 1.582199 -v -0.004904 -0.140306 0.174561 -vn 5.066693 -2.256899 2.933934 -v -0.004727 -0.139616 0.174973 -vn 5.067396 -2.554590 2.682250 -v -0.004787 -0.139871 0.174859 -vn 5.431439 -2.213564 1.873944 -v -0.004514 -0.139506 0.174669 -vn 5.092813 -2.731780 2.442818 -v -0.004806 -0.139945 0.174821 -vn 5.206450 -1.005853 3.348075 -v -0.004546 -0.138532 0.175238 -vn 5.177265 -1.376525 3.268397 -v -0.004596 -0.138926 0.175170 -vn 5.638659 -1.180328 2.065150 -v -0.004238 -0.138596 0.174703 -vn 5.182469 -1.621222 3.138662 -v -0.004606 -0.138988 0.175157 -vn 5.157821 -1.843176 3.046582 -v -0.004665 -0.139322 0.175072 -vn 5.236206 -0.579731 3.396048 -v -0.004512 -0.138111 0.175286 -vn 5.596516 -0.348322 2.736194 -v -0.004145 -0.137649 0.174737 -vn 5.215810 -0.240297 3.480894 -v -0.004500 -0.137670 0.175313 -vn 0.657179 -3.678798 5.036834 -v -0.008249 -0.141471 0.175657 -vn 0.141602 -3.336675 5.316823 -v -0.009000 -0.141519 0.175667 -vn 0.187662 -3.575251 5.113581 -v -0.009000 -0.141683 0.175575 -vn 0.936571 -4.515274 4.027331 -v -0.008133 -0.142027 0.175216 -vn 1.691871 -4.354184 3.964643 -v -0.007300 -0.141774 0.175225 -vn 1.136680 -3.723158 4.918318 -v -0.007571 -0.141347 0.175626 -vn 2.550722 -4.056512 3.873627 -v -0.006532 -0.141364 0.175240 -vn 2.050505 -3.698705 4.644224 -v -0.006727 -0.141095 0.175534 -vn 1.702240 -3.707043 4.772354 -v -0.006995 -0.141185 0.175572 -vn 3.772246 -3.716727 3.349799 -v -0.005460 -0.140590 0.175093 -vn 3.430433 -3.636225 3.772079 -v -0.005694 -0.140688 0.175228 -vn 3.258603 -3.629786 3.854548 -v -0.005859 -0.140812 0.175260 -vn 2.951997 -3.618759 4.198044 -v -0.005983 -0.140808 0.175350 -vn 2.544663 -3.652343 4.429768 -v -0.006321 -0.140944 0.175452 -vn 5.103785 -3.296029 1.167903 -v -0.004920 -0.140363 0.174504 -vn 4.751175 -3.624656 1.880383 -v -0.004951 -0.140376 0.174561 -vn 3.934971 -4.202516 2.037297 -v -0.005567 -0.141080 0.174611 -vn 4.575339 -3.635208 2.274808 -v -0.005069 -0.140426 0.174736 -vn 4.417589 -3.621188 2.590903 -v -0.005108 -0.140442 0.174783 -vn 4.143745 -3.642854 2.974088 -v -0.005267 -0.140509 0.174944 -vn 5.987663 -0.360703 1.679853 -v -0.004129 -0.137648 0.174698 -vn 0.218496 -4.598493 4.163933 -v -0.009000 -0.142112 0.175213 -vn 0.289221 -5.429020 3.044756 -v -0.009000 -0.142387 0.174817 -vn 3.137050 -4.773999 2.070333 -v -0.006302 -0.141684 0.174589 -vn 2.160807 -5.295424 2.051171 -v -0.007142 -0.142132 0.174573 -vn 1.147964 -5.628054 2.011184 -v -0.008053 -0.142408 0.174563 -vn 0.287760 -5.943585 1.736727 -v -0.009000 -0.142501 0.174559 -vn 0.104229 -2.404420 5.754686 -v -0.047000 -0.141519 0.175667 -vn -0.127481 -3.335639 5.317750 -v -0.063000 -0.141519 0.175667 -vn -0.187662 -3.575258 5.113594 -v -0.063000 -0.141683 0.175575 -vn -0.104244 -2.404437 5.754686 -v -0.025000 -0.141519 0.175667 -vn -0.287766 -5.943590 1.736723 -v -0.063000 -0.142501 0.174559 -vn -0.289221 -5.429015 3.044754 -v -0.063000 -0.142387 0.174817 -vn -0.218496 -4.598494 4.163934 -v -0.063000 -0.142112 0.175213 -vn 5.987629 0.236674 1.701745 -v -0.004129 -0.125656 0.175138 -vn 5.214334 -0.013537 3.491135 -v -0.004500 -0.125678 0.175753 -vn 5.593905 0.153583 2.758022 -v -0.004145 -0.125657 0.175177 -vn -5.178647 -1.371895 3.268264 -v -0.067404 -0.138926 0.175170 -vn -5.215940 -0.976635 3.337139 -v -0.067454 -0.138532 0.175238 -vn -5.634684 -1.165116 2.075893 -v -0.067762 -0.138596 0.174703 -vn -5.250824 -0.608088 3.360803 -v -0.067488 -0.138111 0.175286 -vn -5.214328 -0.242278 3.482751 -v -0.067500 -0.137670 0.175313 -vn -5.593901 -0.355246 2.739361 -v -0.067855 -0.137649 0.174737 -vn -3.465891 -3.753182 3.630619 -v -0.066306 -0.140688 0.175228 -vn -3.248967 -3.633488 3.856210 -v -0.066141 -0.140812 0.175260 -vn -2.901796 -3.769934 4.095630 -v -0.066017 -0.140808 0.175350 -vn -4.973685 -3.483786 1.250033 -v -0.067080 -0.140363 0.174504 -vn -5.218909 -3.015795 1.660535 -v -0.067096 -0.140306 0.174561 -vn -4.692190 -3.730057 1.792921 -v -0.067049 -0.140376 0.174561 -vn -3.768053 -3.729037 3.341761 -v -0.066540 -0.140590 0.175093 -vn -3.940260 -4.196958 2.033086 -v -0.066433 -0.141080 0.174611 -vn -4.142700 -3.650055 2.968155 -v -0.066733 -0.140509 0.174944 -vn -4.417341 -3.628585 2.582508 -v -0.066892 -0.140442 0.174783 -vn -4.584937 -3.626646 2.267962 -v -0.066931 -0.140426 0.174736 -vn -2.570336 -3.688472 4.383917 -v -0.065679 -0.140944 0.175452 -vn -2.554469 -4.054602 3.873247 -v -0.065468 -0.141364 0.175240 -vn -2.059924 -3.716695 4.626062 -v -0.065273 -0.141095 0.175534 -vn -0.922034 -4.534115 4.016146 -v -0.063867 -0.142027 0.175216 -vn -1.713429 -3.736419 4.747398 -v -0.065005 -0.141185 0.175572 -vn -1.713081 -4.360731 3.954868 -v -0.064700 -0.141774 0.175225 -vn -1.164966 -3.719448 4.919088 -v -0.064429 -0.141347 0.175626 -vn -0.627166 -3.685748 5.038760 -v -0.063751 -0.141471 0.175657 -vn -5.144082 -2.913828 2.062169 -v -0.067142 -0.140144 0.174695 -vn -5.439498 -2.198369 1.885039 -v -0.067486 -0.139506 0.174669 -vn -5.091836 -2.731984 2.444369 -v -0.067194 -0.139945 0.174821 -vn -5.066923 -2.555500 2.682243 -v -0.067213 -0.139871 0.174859 -vn -5.064579 -2.255742 2.938027 -v -0.067273 -0.139616 0.174973 -vn -5.144423 -1.862903 3.060654 -v -0.067335 -0.139322 0.175072 -vn -5.180157 -1.612409 3.150108 -v -0.067394 -0.138988 0.175157 -vn -1.147942 -5.628058 2.011193 -v -0.063947 -0.142408 0.174563 -vn -3.137033 -4.774007 2.070317 -v -0.065698 -0.141684 0.174589 -vn -2.160827 -5.295423 2.051163 -v -0.064858 -0.142132 0.174573 -vn -5.987607 -0.360718 1.679837 -v -0.067871 -0.137648 0.174698 -vn 5.178644 1.129231 3.359780 -v -0.004596 -0.124416 0.175702 -vn 5.215940 0.729459 3.399743 -v -0.004546 -0.124813 0.175741 -vn 5.634680 1.009879 2.155656 -v -0.004238 -0.124711 0.175212 -vn 5.250830 0.360246 3.396305 -v -0.004512 -0.125237 0.175758 -vn 3.465804 3.477191 3.895814 -v -0.005694 -0.122662 0.175889 -vn 3.248895 3.341294 4.112049 -v -0.005859 -0.122542 0.175931 -vn 2.901858 3.459596 4.360913 -v -0.005983 -0.122552 0.176020 -vn 4.973627 3.382882 1.501973 -v -0.004920 -0.122934 0.175143 -vn 5.218789 2.886207 1.877032 -v -0.004904 -0.122995 0.175196 -vn 4.692207 3.588632 2.061411 -v -0.004951 -0.122925 0.175201 -vn 3.768164 3.474205 3.605836 -v -0.005460 -0.122750 0.175747 -vn 3.940280 4.036757 2.335059 -v -0.005567 -0.122226 0.175303 -vn 4.142722 3.422822 3.227567 -v -0.005267 -0.122820 0.175593 -vn 4.417472 3.429753 2.840980 -v -0.005108 -0.122875 0.175427 -vn 4.585098 3.450870 2.527192 -v -0.005069 -0.122888 0.175379 -vn 2.570343 3.357417 4.642323 -v -0.006321 -0.122424 0.176131 -vn 2.554459 3.759976 4.159857 -v -0.006532 -0.121990 0.175951 -vn 2.059898 3.367791 4.885938 -v -0.006727 -0.122279 0.176224 -vn 0.922055 4.227667 4.337530 -v -0.008133 -0.121327 0.175975 -vn 0.218498 4.281096 4.489601 -v -0.009000 -0.121241 0.175978 -vn 0.187684 3.191022 5.361789 -v -0.009000 -0.121696 0.176308 -vn 1.713394 3.378576 5.008386 -v -0.006995 -0.122192 0.176269 -vn 1.713092 4.059274 4.263704 -v -0.007300 -0.121579 0.175966 -vn 1.164940 3.349050 5.178387 -v -0.007571 -0.122035 0.176334 -vn 0.573890 3.250008 5.330425 -v -0.008249 -0.121913 0.176374 -vn 0.112455 2.781501 5.631369 -v -0.009000 -0.121866 0.176388 -vn 5.144090 2.754920 2.270121 -v -0.004858 -0.123167 0.175318 -vn 5.439500 2.054380 2.041049 -v -0.004514 -0.123801 0.175245 -vn 5.091846 2.545580 2.637903 -v -0.004806 -0.123374 0.175428 -vn 5.066900 2.352107 2.862297 -v -0.004787 -0.123450 0.175462 -vn 5.064586 2.034432 3.095389 -v -0.004727 -0.123713 0.175556 -vn 5.144420 1.633665 3.188904 -v -0.004665 -0.124013 0.175634 -vn 5.180167 1.377725 3.259623 -v -0.004606 -0.124353 0.175694 -vn 1.147972 5.465587 2.418056 -v -0.008053 -0.120898 0.175352 -vn 0.287745 5.800390 2.167475 -v -0.009000 -0.120805 0.175355 -vn 0.289208 5.191405 3.434263 -v -0.009000 -0.120938 0.175604 -vn 3.137027 4.609497 2.414502 -v -0.006302 -0.121623 0.175325 -vn 2.160847 5.130950 2.433609 -v -0.007142 -0.121175 0.175342 -vn -5.215807 -0.015298 3.489142 -v -0.067500 -0.125678 0.175753 -vn -5.596495 0.146958 2.754354 -v -0.067855 -0.125657 0.175177 -vn -5.987661 0.236689 1.701765 -v -0.067871 -0.125656 0.175138 -vn -0.112660 1.977960 5.914611 -v -0.025000 -0.121866 0.176388 -vn -0.187684 3.191016 5.361776 -v -0.063000 -0.121696 0.176308 -vn -0.131643 2.935254 5.548619 -v -0.063000 -0.121866 0.176388 -vn 0.116155 1.979173 5.914015 -v -0.047000 -0.121866 0.176388 -vn -0.287744 5.800387 2.167475 -v -0.063000 -0.120805 0.175355 -vn -0.289208 5.191410 3.434266 -v -0.063000 -0.120938 0.175604 -vn -0.218498 4.281095 4.489602 -v -0.063000 -0.121241 0.175978 -vn -0.657216 3.299867 5.292838 -v -0.063751 -0.121913 0.176374 -vn -0.936594 4.208059 4.347301 -v -0.063867 -0.121327 0.175975 -vn -1.691864 4.052035 4.272963 -v -0.064700 -0.121579 0.175966 -vn -1.136652 3.352807 5.177891 -v -0.064429 -0.122035 0.176334 -vn -2.550732 3.761852 4.160388 -v -0.065468 -0.121990 0.175951 -vn -2.050447 3.348551 4.902724 -v -0.065273 -0.122279 0.176224 -vn -1.702178 3.347449 5.031137 -v -0.065005 -0.122192 0.176269 -vn -3.772326 3.461371 3.612955 -v -0.066540 -0.122750 0.175747 -vn -3.430392 3.350394 4.028080 -v -0.066306 -0.122662 0.175889 -vn -3.258606 3.337866 4.109992 -v -0.066141 -0.122542 0.175931 -vn -2.952101 3.301566 4.451752 -v -0.066017 -0.122552 0.176020 -vn -2.544713 3.318080 4.685345 -v -0.065679 -0.122424 0.176131 -vn -5.103867 3.201607 1.406145 -v -0.067080 -0.122934 0.175143 -vn -4.751579 3.476711 2.140441 -v -0.067049 -0.122925 0.175201 -vn -3.934993 4.041959 2.339660 -v -0.066433 -0.122226 0.175303 -vn -4.575308 3.458747 2.535128 -v -0.066931 -0.122888 0.175379 -vn -4.417495 3.421635 2.849379 -v -0.066892 -0.122875 0.175427 -vn -4.143784 3.415212 3.232945 -v -0.066733 -0.122820 0.175593 -vn -5.229592 2.889077 1.798657 -v -0.067096 -0.122995 0.175196 -vn -5.206003 2.724608 2.122474 -v -0.067142 -0.123167 0.175318 -vn -5.066691 2.035854 3.091404 -v -0.067273 -0.123713 0.175556 -vn -5.067387 2.351279 2.862175 -v -0.067213 -0.123450 0.175462 -vn -5.431424 2.070315 2.031088 -v -0.067486 -0.123801 0.175245 -vn -5.092801 2.545433 2.636484 -v -0.067194 -0.123374 0.175428 -vn -5.206450 0.757809 3.412792 -v -0.067454 -0.124813 0.175741 -vn -5.177286 1.133824 3.360224 -v -0.067404 -0.124416 0.175702 -vn -5.638648 1.025864 2.146119 -v -0.067762 -0.124711 0.175212 -vn -5.182507 1.387366 3.248808 -v -0.067394 -0.124353 0.175694 -vn -5.157824 1.614937 3.173483 -v -0.067335 -0.124013 0.175634 -vn -5.236201 0.329457 3.429401 -v -0.067488 -0.125237 0.175758 -vn -3.137031 4.609484 2.414509 -v -0.065698 -0.121623 0.175325 -vn -2.160832 5.130963 2.433611 -v -0.064858 -0.121175 0.175342 -vn -1.147972 5.465583 2.418067 -v -0.063947 -0.120898 0.175352 -vn 2.622261 -0.084016 2.710598 -v -0.012295 -0.123885 0.177515 -vn 2.960335 0.609291 2.633053 -v -0.012454 -0.124134 0.177701 -vn -2.732614 4.571367 1.610885 -v -0.008554 -0.126474 0.180252 -vn -2.538499 5.023621 1.519959 -v -0.008810 -0.126854 0.180910 -vn -2.628109 5.270312 1.266733 -v -0.009000 -0.127060 0.181319 -vn -2.098033 5.496827 1.277860 -v -0.009114 -0.127164 0.181543 -vn -0.253561 6.232892 0.677312 -v -0.010363 -0.127692 0.183030 -vn -0.625692 6.193558 0.736313 -v -0.010128 -0.127662 0.182917 -vn -1.101980 6.111230 0.806659 -v -0.009933 -0.127614 0.182753 -vn -1.163874 5.966356 1.006619 -v -0.009486 -0.127424 0.182183 -vn -1.623631 5.687472 1.247310 -v -0.009372 -0.127356 0.182002 -vn 0.595403 6.154083 0.904365 -v -0.010938 -0.127648 0.182868 -vn 0.325687 6.210667 0.776300 -v -0.010706 -0.127686 0.183007 -vn 0.040906 6.241916 0.651479 -v -0.010536 -0.127697 0.183046 -vn 2.398221 4.900840 1.647541 -v -0.012375 -0.126595 0.180455 -vn 2.644904 4.392031 1.839061 -v -0.012448 -0.126471 0.180255 -vn 2.901342 3.934764 1.951870 -v -0.012564 -0.126226 0.179889 -vn 1.899389 5.447630 1.439334 -v -0.011885 -0.127165 0.181545 -vn 1.409098 5.756968 1.305545 -v -0.011630 -0.127354 0.181998 -vn 1.001151 5.971725 1.169322 -v -0.011424 -0.127472 0.182316 -vn 3.180346 1.492874 2.526856 -v -0.012647 -0.124589 0.178073 -vn 3.199864 2.444023 2.359323 -v -0.012750 -0.125320 0.178775 -vn 3.127644 3.129518 2.177500 -v -0.012743 -0.125469 0.178937 -vn 1.631451 -1.110145 2.841712 -v -0.011629 -0.123280 0.177111 -vn 2.104175 -0.717781 2.832624 -v -0.011793 -0.123388 0.177179 -vn -1.078567 -1.545800 2.939417 -v -0.009791 -0.123087 0.176995 -vn -0.337451 -1.736507 2.870568 -v -0.010425 -0.122971 0.176929 -vn 0.264454 -1.795214 2.922829 -v -0.010500 -0.122970 0.176928 -vn 0.897931 -1.594123 3.001432 -v -0.011110 -0.123056 0.176977 -vn -2.612833 -0.430574 2.773216 -v -0.008957 -0.123596 0.177314 -vn -2.270771 -0.803522 2.777904 -v -0.009000 -0.123556 0.177288 -vn -2.144281 -1.043606 2.819999 -v -0.009232 -0.123370 0.177168 -vn -1.709382 -1.283350 2.813119 -v -0.009372 -0.123280 0.177111 -vn -4.216242 1.971553 2.099090 -v -0.008256 -0.125111 0.178534 -vn -3.527999 1.743559 2.360149 -v -0.008272 -0.124962 0.178389 -vn -2.849646 1.026417 2.527827 -v -0.008476 -0.124269 0.177793 -vn -2.642402 0.328263 2.596393 -v -0.008536 -0.124152 0.177703 -vn -2.765959 3.914184 1.921444 -v -0.008413 -0.126167 0.179791 -vn -3.194786 3.379351 2.110593 -v -0.008319 -0.125864 0.179385 -vn -4.282328 2.445300 2.120229 -v -0.008250 -0.125296 0.178724 -vn -0.674138 1.356504 2.371133 -v -0.054376 -0.126066 0.179667 -vn 0.656057 2.517070 2.143690 -v -0.055090 -0.127107 0.180503 -vn -0.157418 1.889508 2.396970 -v -0.054551 -0.126454 0.179849 -vn 0.104015 6.174931 1.000040 -v -0.056500 -0.127697 0.183048 -vn 2.714579 3.138495 1.433258 -v -0.056434 -0.127696 0.183043 -vn 2.360717 3.175906 1.592480 -v -0.055964 -0.127591 0.181931 -vn 1.434760 2.916133 1.887954 -v -0.055375 -0.127317 0.180909 -vn 0.104095 6.104603 1.442649 -v -0.056754 -0.127681 0.182986 -vn 0.494550 6.157088 0.963594 -v -0.056971 -0.127640 0.182841 -vn 0.938324 5.991469 1.156496 -v -0.057318 -0.127522 0.182462 -vn 1.436755 5.750300 1.401113 -v -0.057625 -0.127357 0.182007 -vn 2.372153 4.939837 1.673902 -v -0.058449 -0.126469 0.180252 -vn 3.298433 2.892316 2.326405 -v -0.058750 -0.125288 0.178741 -vn 2.944881 3.910615 2.002723 -v -0.058555 -0.126248 0.179920 -vn 1.808672 -1.035702 2.915973 -v -0.057625 -0.123278 0.177110 -vn 2.509742 -0.366084 2.818810 -v -0.058107 -0.123661 0.177358 -vn 3.003117 0.373692 2.694474 -v -0.058453 -0.124131 0.177699 -vn 3.194638 1.137970 2.638059 -v -0.058543 -0.124310 0.177840 -vn -0.913218 -1.509122 2.917885 -v -0.055910 -0.123050 0.176974 -vn 0.030777 -1.737099 3.012479 -v -0.056500 -0.122970 0.176928 -vn 0.894493 -1.530547 2.967352 -v -0.057090 -0.123050 0.176974 -vn -2.479783 -0.344847 2.781451 -v -0.054893 -0.123661 0.177358 -vn -1.758848 -1.044907 2.863151 -v -0.055375 -0.123278 0.177110 -vn -3.270446 2.731396 2.312170 -v -0.054250 -0.125288 0.178741 -vn -3.094070 1.228339 2.545723 -v -0.054457 -0.124310 0.177840 -vn -2.822914 0.290279 2.625022 -v -0.054551 -0.124124 0.177693 -vn 0.203573 2.892087 2.962454 -v -0.060000 -0.127782 0.217855 -vn -0.203570 2.892090 2.962452 -v -0.062000 -0.127782 0.217855 -vn 0.206518 -3.121428 3.289614 -v -0.060000 -0.135777 0.217561 -vn -0.206514 -3.121432 3.289621 -v -0.062000 -0.135777 0.217561 -vn -0.817476 -2.986230 3.171772 -v -0.062776 -0.135782 0.217459 -vn -1.742764 -2.839200 2.712053 -v -0.063500 -0.135797 0.217159 -vn -2.665736 -2.670406 1.626868 -v -0.064598 -0.135853 0.216058 -vn 1.517299 -3.527559 2.810026 -v -0.062375 -0.136280 0.207622 -vn -0.000001 -3.507020 3.216044 -v -0.061000 -0.136299 0.207254 -vn -1.517300 -3.527559 2.810025 -v -0.059625 -0.136280 0.207622 -vn 2.665728 -2.670404 1.626869 -v -0.057402 -0.135853 0.216058 -vn -1.517290 -3.793421 -2.439229 -v -0.059625 -0.136039 0.212379 -vn 1.742732 -2.839207 2.712006 -v -0.058500 -0.135797 0.217159 -vn 0.000005 -3.814010 -2.845272 -v -0.061000 -0.136020 0.212747 -vn -2.627966 -3.737250 -1.329940 -v -0.058618 -0.136090 0.211373 -vn -3.034546 -3.660501 0.185395 -v -0.058250 -0.136159 0.210000 -vn -2.627943 -3.583753 1.700723 -v -0.058618 -0.136229 0.208627 -vn 0.817475 -2.986231 3.171761 -v -0.059224 -0.135782 0.217459 -vn 1.517289 -3.793422 -2.439236 -v -0.062375 -0.136039 0.212379 -vn 2.627966 -3.737249 -1.329943 -v -0.063382 -0.136090 0.211373 -vn 3.034547 -3.660501 0.185396 -v -0.063750 -0.136159 0.210000 -vn 2.627943 -3.583752 1.700723 -v -0.063382 -0.136229 0.208627 -vn -0.000001 3.507021 -3.216047 -v -0.061000 -0.128061 0.212344 -vn 1.517294 3.527559 -2.810025 -v -0.062375 -0.128080 0.211976 -vn 2.627956 3.583752 -1.700723 -v -0.063382 -0.128131 0.210970 -vn 3.034552 3.660501 -0.185397 -v -0.063750 -0.128200 0.209597 -vn 2.627960 3.737249 1.329942 -v -0.063382 -0.128270 0.208224 -vn 1.517289 3.793421 2.439236 -v -0.062375 -0.128321 0.207219 -vn 0.000007 3.814011 2.845278 -v -0.061000 -0.128339 0.206851 -vn -1.517293 3.793420 2.439230 -v -0.059625 -0.128321 0.207219 -vn -2.627960 3.737250 1.329941 -v -0.058618 -0.128270 0.208224 -vn -3.034551 3.660501 -0.185397 -v -0.058250 -0.128200 0.209597 -vn -2.627955 3.583752 -1.700724 -v -0.058618 -0.128131 0.210970 -vn 2.590252 2.559172 1.405638 -v -0.057402 -0.127858 0.216351 -vn -1.517298 3.527558 -2.810025 -v -0.059625 -0.128080 0.211976 -vn 1.680936 2.651375 2.408453 -v -0.058500 -0.127802 0.217452 -vn 0.794847 2.765714 2.841372 -v -0.059224 -0.127787 0.217752 -vn -2.590254 2.559174 1.405635 -v -0.064598 -0.127858 0.216351 -vn -1.680936 2.651371 2.408452 -v -0.063500 -0.127802 0.217452 -vn -0.794849 2.765713 2.841371 -v -0.062776 -0.127787 0.217752 -vn 4.399300 2.611875 3.509816 -v -0.005145 -0.123451 0.176036 -vn 4.303967 2.510153 3.646785 -v -0.005278 -0.123712 0.176389 -vn 4.164480 2.282046 3.827145 -v -0.005500 -0.124121 0.176903 -vn 4.279592 2.013487 3.641681 -v -0.005628 -0.124352 0.177184 -vn 5.331613 0.617348 3.257195 -v -0.005651 -0.124524 0.177260 -vn 5.385745 -0.026770 3.195007 -v -0.005625 -0.125735 0.177306 -vn 5.358095 0.294666 3.244370 -v -0.005632 -0.125120 0.177306 -vn 5.816243 -0.167580 2.336972 -v -0.006354 -0.125791 0.178830 -vn 3.633424 2.394400 3.587606 -v -0.005832 -0.124713 0.177622 -vn 3.812224 2.327751 3.058669 -v -0.006425 -0.125798 0.179023 -vn 3.831874 2.143946 3.822693 -v -0.005723 -0.124520 0.177388 -vn 3.609413 2.349620 3.658904 -v -0.005731 -0.124533 0.177404 -vn 3.629387 2.343147 3.619528 -v -0.005776 -0.124614 0.177502 -vn 4.167229 2.351782 3.813654 -v -0.005497 -0.124116 0.176897 -vn 4.156974 2.418422 3.805696 -v -0.005461 -0.124052 0.176818 -vn 4.238673 2.457470 3.727582 -v -0.005302 -0.123757 0.176448 -vn 4.609314 2.836621 3.133978 -v -0.005051 -0.123253 0.175742 -vn 4.543366 2.771237 3.258171 -v -0.005062 -0.123276 0.175779 -vn 4.481624 2.675745 3.387524 -v -0.005137 -0.123433 0.176011 -vn 4.474880 2.649485 3.415687 -v -0.005140 -0.123440 0.176021 -vn 4.828449 3.034275 2.612018 -v -0.004972 -0.123069 0.175429 -vn 4.798156 2.978459 2.726054 -v -0.004979 -0.123087 0.175462 -vn 4.719450 2.953048 2.873394 -v -0.004995 -0.123125 0.175530 -vn 4.647578 2.887845 3.035657 -v -0.005029 -0.123202 0.175661 -vn 4.885786 3.151626 2.369163 -v -0.004932 -0.122967 0.175221 -vn 4.971034 3.229087 2.077908 -v -0.004921 -0.122939 0.175154 -vn 4.941072 3.200524 2.194138 -v -0.004931 -0.122966 0.175217 -vn 5.831215 -0.051010 2.304621 -v -0.006354 -0.137783 0.178390 -vn 3.782142 -2.742552 2.920950 -v -0.006425 -0.137790 0.178583 -vn 3.771209 -2.564542 3.336388 -v -0.005947 -0.138586 0.177370 -vn 4.967262 -3.366518 1.855784 -v -0.004921 -0.140359 0.174515 -vn 4.953316 -3.157125 2.179132 -v -0.004945 -0.140307 0.174661 -vn 4.821716 -3.241505 2.370907 -v -0.004970 -0.140253 0.174790 -vn 4.789839 -3.187285 2.499272 -v -0.004976 -0.140241 0.174817 -vn 4.714632 -3.169718 2.638173 -v -0.004992 -0.140207 0.174890 -vn 4.648386 -3.111537 2.804730 -v -0.005027 -0.140136 0.175036 -vn 4.610153 -3.060218 2.915072 -v -0.005051 -0.140090 0.175122 -vn 4.533267 -3.008988 3.051773 -v -0.005061 -0.140069 0.175161 -vn 4.463623 -2.945334 3.186907 -v -0.005138 -0.139926 0.175411 -vn 4.447049 -2.888500 3.251056 -v -0.005147 -0.139910 0.175438 -vn 4.316416 -2.891835 3.363056 -v -0.005164 -0.139879 0.175488 -vn 4.229492 -2.788170 3.492793 -v -0.005268 -0.139697 0.175775 -vn 4.170874 -2.701438 3.597356 -v -0.005437 -0.139410 0.176199 -vn 4.150377 -2.677365 3.632098 -v -0.005470 -0.139356 0.176277 -vn 3.877805 -2.623356 3.795110 -v -0.005510 -0.139291 0.176370 -vn 5.327132 -0.883220 3.202658 -v -0.005651 -0.138932 0.176731 -vn 3.620385 -2.612345 3.451329 -v -0.005776 -0.138860 0.176979 -vn 5.310940 -0.480138 3.308119 -v -0.005632 -0.138341 0.176821 -vn 5.366320 -0.250188 3.222459 -v -0.005625 -0.137727 0.176866 -vn 3.357511 -2.867302 2.361174 -v -0.006697 -0.137274 0.179502 -vn 3.616287 -2.999099 1.705264 -v -0.006904 -0.136781 0.180578 -vn 4.059015 2.836674 1.515343 -v -0.006966 -0.127203 0.181491 -vn 3.436657 2.790117 2.322988 -v -0.006790 -0.126614 0.180297 -vn 0.901732 3.941375 4.753366 -v -0.007280 -0.124414 0.177773 -vn 0.315735 3.904640 4.872657 -v -0.008106 -0.124340 0.177824 -vn 0.240835 5.155719 3.528690 -v -0.007908 -0.126261 0.179892 -vn 0.445478 5.078938 3.632884 -v -0.006879 -0.126294 0.179804 -vn 0.174466 6.015444 1.637265 -v -0.009000 -0.127522 0.182462 -vn 0.181689 5.920991 1.959044 -v -0.007671 -0.127523 0.182413 -vn 1.634297 3.619162 4.864199 -v -0.006188 -0.124562 0.177615 -vn 1.334729 3.911217 4.691966 -v -0.006545 -0.124510 0.177683 -vn 0.075952 -5.363306 3.161834 -v -0.009000 -0.137408 0.179511 -vn 0.108797 -4.253832 4.548873 -v -0.009000 -0.139188 0.177294 -vn 0.429933 -4.288449 4.507839 -v -0.008106 -0.139157 0.177280 -vn 0.630037 -5.224638 3.419307 -v -0.006879 -0.137353 0.179398 -vn 0.260963 -6.055081 1.493619 -v -0.007671 -0.136318 0.182091 -vn 0.379306 -5.347225 3.191403 -v -0.007908 -0.137393 0.179484 -vn 1.765220 -4.327058 4.174985 -v -0.006188 -0.138920 0.177089 -vn 0.035923 -6.034463 1.520776 -v -0.009000 -0.136324 0.182139 -vn 0.916866 -4.314395 4.417501 -v -0.007280 -0.139079 0.177235 -vn 1.290638 -4.291496 4.361471 -v -0.006545 -0.138977 0.177152 -vn -0.446280 1.364146 6.110762 -v -0.024981 -0.121873 0.176391 -vn -0.469954 1.407567 6.098807 -v -0.024810 -0.121937 0.176418 -vn -2.921283 2.989695 2.603934 -v -0.015794 -0.127522 0.182462 -vn -2.644581 2.745202 3.468420 -v -0.016910 -0.126634 0.180520 -vn -0.624231 1.153165 6.027467 -v -0.022785 -0.122714 0.176788 -vn -1.005534 1.479387 5.771452 -v -0.021910 -0.123119 0.177014 -vn -1.432038 1.806628 5.402015 -v -0.019969 -0.124310 0.177840 -vn -1.884943 2.113992 4.919284 -v -0.019122 -0.124916 0.178370 -vn -2.277553 2.479329 4.207333 -v -0.017394 -0.126248 0.179920 -vn -3.142804 3.157149 1.650118 -v -0.015489 -0.127754 0.183269 -vn -0.299885 -2.216182 5.827337 -v -0.024981 -0.141513 0.175671 -vn -0.524828 -1.803513 5.819532 -v -0.022785 -0.140702 0.176128 -vn -2.315501 -2.747637 4.059327 -v -0.017394 -0.137408 0.179511 -vn -1.884759 -2.488520 4.730270 -v -0.019122 -0.138622 0.177867 -vn -1.446616 -2.167158 5.279050 -v -0.019969 -0.139188 0.177294 -vn -0.984722 -1.951258 5.613964 -v -0.021910 -0.140316 0.176383 -vn -3.151474 -3.270303 1.406659 -v -0.015489 -0.136152 0.182961 -vn -2.945755 -3.163895 2.400888 -v -0.015794 -0.136324 0.182139 -vn -2.656675 -2.993739 3.253155 -v -0.016910 -0.137067 0.180138 -vn -4.399245 -2.862031 3.309053 -v -0.066854 -0.139913 0.175433 -vn -4.304079 -2.770529 3.453019 -v -0.066722 -0.139678 0.175803 -vn -4.164466 -2.556001 3.649985 -v -0.066500 -0.139308 0.176346 -vn -4.279468 -2.275041 3.484523 -v -0.066372 -0.139099 0.176643 -vn -5.331539 -0.854522 3.203286 -v -0.066349 -0.138932 0.176731 -vn -5.385746 -0.207332 3.188375 -v -0.066375 -0.137727 0.176866 -vn -5.358089 -0.531557 3.214079 -v -0.066368 -0.138341 0.176821 -vn -5.816213 -0.004193 2.343076 -v -0.065646 -0.137783 0.178390 -vn -3.633478 -2.650737 3.402701 -v -0.066168 -0.138770 0.177107 -vn -3.812218 -2.545609 2.879995 -v -0.065575 -0.137790 0.178583 -vn -3.831836 -2.420424 3.655116 -v -0.066277 -0.138945 0.176859 -vn -3.608663 -2.612575 3.475828 -v -0.066269 -0.138933 0.176876 -vn -3.629452 -2.601889 3.438293 -v -0.066224 -0.138860 0.176979 -vn -4.164988 -2.625376 3.632449 -v -0.066503 -0.139312 0.176340 -vn -4.156942 -2.690649 3.618353 -v -0.066539 -0.139371 0.176256 -vn -4.238605 -2.724010 3.537547 -v -0.066698 -0.139637 0.175866 -vn -4.609287 -3.058564 2.917747 -v -0.066949 -0.140089 0.175125 -vn -4.543292 -3.002392 3.046562 -v -0.066938 -0.140068 0.175163 -vn -4.483163 -2.916807 3.180743 -v -0.066863 -0.139929 0.175405 -vn -4.475229 -2.892975 3.211481 -v -0.066860 -0.139922 0.175417 -vn -4.828397 -3.217361 2.382949 -v -0.067028 -0.140249 0.174798 -vn -4.797992 -3.170108 2.500928 -v -0.067021 -0.140234 0.174833 -vn -4.719537 -3.155591 2.649271 -v -0.067005 -0.140201 0.174903 -vn -4.647746 -3.102617 2.815571 -v -0.066971 -0.140133 0.175040 -vn -4.885075 -3.315892 2.135147 -v -0.067068 -0.140336 0.174583 -vn -4.971199 -3.372567 1.835407 -v -0.067079 -0.140359 0.174515 -vn -4.939094 -3.351757 1.959964 -v -0.067069 -0.140337 0.174580 -vn -5.831189 -0.117813 2.302273 -v -0.065646 -0.125791 0.178830 -vn -3.782077 2.521329 3.114099 -v -0.065575 -0.125798 0.179023 -vn -3.771177 2.313241 3.515291 -v -0.066053 -0.124916 0.177871 -vn -4.967698 3.220882 2.097480 -v -0.067079 -0.122939 0.175154 -vn -4.953295 2.989115 2.404564 -v -0.067055 -0.123002 0.175295 -vn -4.821837 3.059387 2.601516 -v -0.067030 -0.123065 0.175421 -vn -4.789639 2.995733 2.726209 -v -0.067024 -0.123078 0.175446 -vn -4.714565 2.968001 2.863382 -v -0.067008 -0.123117 0.175517 -vn -4.648149 2.897604 3.025452 -v -0.066973 -0.123200 0.175657 -vn -4.610235 2.838534 3.131333 -v -0.066949 -0.123251 0.175740 -vn -4.533352 2.777526 3.263733 -v -0.066939 -0.123275 0.175777 -vn -4.463067 2.703619 3.394806 -v -0.066862 -0.123436 0.176016 -vn -4.447074 2.642391 3.454114 -v -0.066853 -0.123454 0.176041 -vn -4.316453 2.637688 3.565795 -v -0.066836 -0.123489 0.176090 -vn -4.229499 2.524779 3.687664 -v -0.066732 -0.123691 0.176362 -vn -4.170563 2.430367 3.785878 -v -0.066563 -0.124008 0.176764 -vn -4.150634 2.404221 3.818358 -v -0.066530 -0.124068 0.176838 -vn -3.877836 2.338279 3.977008 -v -0.066490 -0.124139 0.176926 -vn -5.327204 0.646058 3.258663 -v -0.066349 -0.124524 0.177260 -vn -3.620300 2.352533 3.633421 -v -0.066224 -0.124614 0.177502 -vn -5.310941 0.236507 3.334404 -v -0.066368 -0.125120 0.177306 -vn -5.366317 0.013420 3.232128 -v -0.066375 -0.125735 0.177306 -vn -3.357577 2.686574 2.564960 -v -0.065303 -0.126381 0.179902 -vn -3.616326 2.866111 1.920395 -v -0.065096 -0.126951 0.180939 -vn -4.059060 -2.940055 1.303448 -v -0.065034 -0.136570 0.181148 -vn -3.436624 -2.952808 2.112335 -v -0.065210 -0.137071 0.179914 -vn -0.901774 -4.279005 4.451855 -v -0.064720 -0.139079 0.177235 -vn -0.434776 -4.267483 4.524761 -v -0.063894 -0.139157 0.177280 -vn -0.387891 -5.357317 3.171189 -v -0.064092 -0.137393 0.179484 -vn -0.445440 -5.331451 3.251000 -v -0.065121 -0.137353 0.179398 -vn -1.634234 -3.965311 4.586423 -v -0.065812 -0.138920 0.177089 -vn -0.231791 -6.030429 1.564881 -v -0.064329 -0.136318 0.182091 -vn -1.334720 -4.244399 4.392861 -v -0.065455 -0.138977 0.177152 -vn -0.007718 -6.035949 1.525009 -v -0.063000 -0.136324 0.182139 -vn -0.049256 -5.363520 3.164498 -v -0.063000 -0.137408 0.179511 -vn -0.080043 -4.253641 4.550367 -v -0.063000 -0.139188 0.177294 -vn -0.063791 5.112682 3.555228 -v -0.063000 -0.126248 0.179920 -vn -0.099084 3.906807 4.850672 -v -0.063000 -0.124310 0.177840 -vn -0.429956 3.946682 4.809889 -v -0.063894 -0.124340 0.177824 -vn -0.630103 4.959962 3.793061 -v -0.065121 -0.126294 0.179804 -vn -0.260967 5.929392 1.933192 -v -0.064329 -0.127523 0.182413 -vn -0.379299 5.099061 3.574560 -v -0.064092 -0.126261 0.179892 -vn -1.765248 4.009571 4.480750 -v -0.065812 -0.124562 0.177615 -vn -0.013481 5.910282 1.956034 -v -0.063000 -0.127522 0.182462 -vn -0.916812 3.979186 4.721700 -v -0.064720 -0.124414 0.177773 -vn -1.290715 3.960448 4.664129 -v -0.065455 -0.124510 0.177683 -vn 3.130846 -3.268096 1.417812 -v -0.056511 -0.136152 0.182961 -vn 2.643722 -2.986501 3.261268 -v -0.055090 -0.137067 0.180138 -vn 2.929780 -3.161417 2.370647 -v -0.056206 -0.136324 0.182139 -vn 1.876687 -2.485803 4.732771 -v -0.052878 -0.138622 0.177867 -vn 2.296313 -2.764545 4.033544 -v -0.054606 -0.137408 0.179511 -vn 0.306020 -2.230314 5.821263 -v -0.047190 -0.141450 0.175703 -vn 0.275778 -2.197232 5.834447 -v -0.047019 -0.141513 0.175671 -vn 0.525415 -1.811782 5.814828 -v -0.049215 -0.140702 0.176128 -vn 0.976358 -1.949849 5.615158 -v -0.050090 -0.140316 0.176383 -vn 1.416326 -2.212993 5.242975 -v -0.052031 -0.139188 0.177294 -vn 1.852459 2.110691 4.919081 -v -0.052878 -0.124916 0.178370 -vn 1.404120 1.841029 5.378354 -v -0.052031 -0.124310 0.177840 -vn 1.097094 1.305455 5.853017 -v -0.050090 -0.123119 0.177014 -vn 0.965194 0.317633 6.190941 -v -0.049215 -0.122714 0.176788 -vn 0.994419 -0.033774 6.076141 -v -0.047019 -0.121873 0.176391 -vn 3.364757 3.138393 1.482140 -v -0.056511 -0.127754 0.183269 -# 792 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 7//7 -f 8//8 9//9 10//10 -f 11//11 12//12 13//13 -f 10//10 9//9 14//14 -f 13//13 12//12 15//15 -f 16//16 17//17 18//18 -f 18//18 17//17 19//19 -f 18//18 19//19 20//20 -f 9//9 21//21 14//14 -f 14//14 21//21 22//22 -f 14//14 22//22 23//23 -f 23//23 24//24 14//14 -f 14//14 24//24 25//25 -f 14//14 25//25 12//12 -f 12//12 25//25 26//26 -f 12//12 26//26 15//15 -f 7//7 27//27 5//5 -f 5//5 27//27 28//28 -f 5//5 28//28 29//29 -f 8//8 10//10 30//30 -f 30//30 10//10 31//31 -f 30//30 31//31 32//32 -f 32//32 31//31 33//33 -f 32//32 33//33 34//34 -f 23//23 35//35 24//24 -f 24//24 35//35 36//36 -f 24//24 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 34//34 5//5 32//32 -f 32//32 5//5 29//29 -f 32//32 29//29 40//40 -f 40//40 29//29 16//16 -f 40//40 16//16 39//39 -f 39//39 16//16 18//18 -f 39//39 18//18 37//37 -f 41//41 42//42 43//43 -f 44//44 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 6//6 -f 6//6 47//47 48//48 -f 6//6 48//48 7//7 -f 13//13 49//49 11//11 -f 11//11 49//49 50//50 -f 11//11 50//50 51//51 -f 43//43 52//52 41//41 -f 41//41 52//52 53//53 -f 41//41 53//53 44//44 -f 44//44 53//53 54//54 -f 44//44 54//54 45//45 -f 45//45 54//54 55//55 -f 45//45 55//55 56//56 -f 56//56 55//55 57//57 -f 51//51 58//58 11//11 -f 11//11 58//58 59//59 -f 11//11 59//59 42//42 -f 42//42 59//59 60//60 -f 42//42 60//60 43//43 -f 50//50 61//61 51//51 -f 51//51 61//61 62//62 -f 51//51 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 18//18 -f 65//65 18//18 57//57 -f 57//57 18//18 20//20 -f 57//57 20//20 56//56 -f 66//66 67//67 68//68 -f 68//68 67//67 69//69 -f 68//68 69//69 70//70 -f 71//71 72//72 73//73 -f 74//74 75//75 76//76 -f 77//77 68//68 78//78 -f 71//71 73//73 79//79 -f 76//76 80//80 74//74 -f 74//74 80//80 81//81 -f 74//74 81//81 82//82 -f 82//82 81//81 83//83 -f 82//82 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 68//68 77//77 66//66 -f 66//66 77//77 88//88 -f 66//66 88//88 89//89 -f 73//73 90//90 79//79 -f 79//79 90//90 91//91 -f 79//79 91//91 89//89 -f 88//88 92//92 89//89 -f 89//89 92//92 93//93 -f 89//89 93//93 79//79 -f 79//79 93//93 94//94 -f 79//79 94//94 75//75 -f 75//75 94//94 95//95 -f 75//75 95//95 76//76 -f 96//96 97//97 98//98 -f 98//98 97//97 99//99 -f 98//98 99//99 100//100 -f 99//99 101//101 100//100 -f 100//100 101//101 102//102 -f 100//100 102//102 71//71 -f 103//103 85//85 78//78 -f 78//78 85//85 104//104 -f 78//78 104//104 77//77 -f 103//103 105//105 85//85 -f 85//85 105//105 106//106 -f 85//85 106//106 87//87 -f 106//106 107//107 87//87 -f 87//87 107//107 108//108 -f 87//87 108//108 109//109 -f 102//102 110//110 71//71 -f 71//71 110//110 111//111 -f 71//71 111//111 72//72 -f 72//72 111//111 112//112 -f 72//72 112//112 113//113 -f 113//113 112//112 114//114 -f 114//114 112//112 115//115 -f 115//115 112//112 116//116 -f 115//115 116//116 117//117 -f 108//108 118//118 109//109 -f 109//109 118//118 119//119 -f 109//109 119//119 120//120 -f 120//120 119//119 121//121 -f 120//120 121//121 122//122 -f 122//122 121//121 123//123 -f 98//98 122//122 96//96 -f 96//96 122//122 123//123 -f 96//96 123//123 124//124 -f 124//124 123//123 125//125 -f 123//123 126//126 125//125 -f 125//125 126//126 68//68 -f 125//125 68//68 117//117 -f 117//117 68//68 70//70 -f 117//117 70//70 115//115 -f 14//14 75//75 74//74 -f 14//14 74//74 10//10 -f 10//10 74//74 82//82 -f 10//10 82//82 31//31 -f 31//31 82//82 84//84 -f 31//31 84//84 33//33 -f 33//33 84//84 86//86 -f 33//33 86//86 34//34 -f 34//34 86//86 87//87 -f 34//34 87//87 5//5 -f 5//5 87//87 109//109 -f 5//5 109//109 6//6 -f 6//6 109//109 120//120 -f 6//6 120//120 46//46 -f 46//46 120//120 122//122 -f 46//46 122//122 44//44 -f 44//44 122//122 98//98 -f 44//44 98//98 41//41 -f 41//41 98//98 100//100 -f 41//41 100//100 42//42 -f 127//127 128//128 129//129 -f 130//130 131//131 132//132 -f 127//127 129//129 133//133 -f 75//75 14//14 79//79 -f 79//79 14//14 12//12 -f 79//79 12//12 134//134 -f 134//134 12//12 135//135 -f 130//130 132//132 129//129 -f 129//129 132//132 136//136 -f 129//129 136//136 133//133 -f 136//136 137//137 133//133 -f 133//133 137//137 138//138 -f 133//133 138//138 139//139 -f 139//139 138//138 134//134 -f 139//139 134//134 140//140 -f 140//140 134//134 135//135 -f 141//141 142//142 143//143 -f 143//143 142//142 144//144 -f 143//143 144//144 145//145 -f 42//42 100//100 11//11 -f 11//11 100//100 71//71 -f 11//11 71//71 146//146 -f 147//147 148//148 144//144 -f 144//144 148//148 149//149 -f 144//144 149//149 145//145 -f 145//145 149//149 150//150 -f 145//145 150//150 151//151 -f 71//71 152//152 146//146 -f 146//146 152//152 153//153 -f 146//146 153//153 151//151 -f 151//151 153//153 154//154 -f 151//151 154//154 145//145 -f 54//54 96//96 55//55 -f 55//55 96//96 124//124 -f 55//55 124//124 57//57 -f 57//57 124//124 125//125 -f 57//57 125//125 65//65 -f 65//65 125//125 117//117 -f 65//65 117//117 63//63 -f 63//63 117//117 116//116 -f 63//63 116//116 51//51 -f 51//51 116//116 112//112 -f 51//51 112//112 58//58 -f 58//58 112//112 111//111 -f 58//58 111//111 59//59 -f 59//59 111//111 110//110 -f 59//59 110//110 60//60 -f 60//60 110//110 102//102 -f 60//60 102//102 43//43 -f 43//43 102//102 101//101 -f 43//43 101//101 52//52 -f 52//52 101//101 99//99 -f 52//52 99//99 53//53 -f 53//53 99//99 97//97 -f 53//53 97//97 54//54 -f 54//54 97//97 96//96 -f 18//18 70//70 37//37 -f 37//37 70//70 69//69 -f 37//37 69//69 24//24 -f 24//24 69//69 67//67 -f 24//24 67//67 25//25 -f 25//25 67//67 66//66 -f 25//25 66//66 26//26 -f 26//26 66//66 89//89 -f 26//26 89//89 15//15 -f 15//15 89//89 91//91 -f 15//15 91//91 13//13 -f 13//13 91//91 90//90 -f 13//13 90//90 49//49 -f 49//49 90//90 73//73 -f 49//49 73//73 50//50 -f 50//50 73//73 72//72 -f 50//50 72//72 61//61 -f 61//61 72//72 113//113 -f 61//61 113//113 62//62 -f 62//62 113//113 114//114 -f 62//62 114//114 64//64 -f 64//64 114//114 115//115 -f 64//64 115//115 18//18 -f 18//18 115//115 70//70 -f 30//30 83//83 8//8 -f 8//8 83//83 81//81 -f 8//8 81//81 9//9 -f 9//9 81//81 80//80 -f 9//9 80//80 21//21 -f 21//21 80//80 76//76 -f 21//21 76//76 22//22 -f 22//22 76//76 95//95 -f 22//22 95//95 23//23 -f 23//23 95//95 94//94 -f 23//23 94//94 35//35 -f 35//35 94//94 93//93 -f 35//35 93//93 36//36 -f 36//36 93//93 92//92 -f 36//36 92//92 38//38 -f 38//38 92//92 88//88 -f 38//38 88//88 39//39 -f 39//39 88//88 77//77 -f 39//39 77//77 40//40 -f 40//40 77//77 104//104 -f 40//40 104//104 32//32 -f 32//32 104//104 85//85 -f 32//32 85//85 30//30 -f 30//30 85//85 83//83 -f 27//27 108//108 28//28 -f 28//28 108//108 107//107 -f 28//28 107//107 29//29 -f 29//29 107//107 106//106 -f 29//29 106//106 16//16 -f 16//16 106//106 105//105 -f 16//16 105//105 17//17 -f 17//17 105//105 103//103 -f 17//17 103//103 19//19 -f 19//19 103//103 78//78 -f 19//19 78//78 20//20 -f 20//20 78//78 68//68 -f 20//20 68//68 56//56 -f 56//56 68//68 126//126 -f 56//56 126//126 45//45 -f 45//45 126//126 123//123 -f 45//45 123//123 47//47 -f 47//47 123//123 121//121 -f 47//47 121//121 48//48 -f 48//48 121//121 119//119 -f 48//48 119//119 7//7 -f 7//7 119//119 118//118 -f 7//7 118//118 27//27 -f 27//27 118//118 108//108 -f 143//143 155//155 156//156 -f 155//155 143//143 157//157 -f 157//157 143//143 132//132 -f 157//157 132//132 158//158 -f 159//159 160//160 161//161 -f 158//158 132//132 161//161 -f 161//161 132//132 131//131 -f 161//161 131//131 159//159 -f 162//162 163//163 164//164 -f 164//164 163//163 165//165 -f 164//164 165//165 166//166 -f 166//166 165//165 160//160 -f 166//166 160//160 167//167 -f 167//167 160//160 159//159 -f 156//156 168//168 143//143 -f 143//143 168//168 169//169 -f 143//143 169//169 141//141 -f 141//141 169//169 170//170 -f 141//141 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 163//163 -f 173//173 163//163 174//174 -f 174//174 163//163 162//162 -f 175//175 176//176 177//177 -f 177//177 176//176 178//178 -f 164//164 179//179 162//162 -f 162//162 179//179 180//180 -f 181//181 182//182 148//148 -f 148//148 182//182 183//183 -f 148//148 183//183 127//127 -f 183//183 184//184 127//127 -f 127//127 184//184 185//185 -f 127//127 185//185 128//128 -f 128//128 185//185 186//186 -f 128//128 186//186 187//187 -f 175//175 188//188 189//189 -f 189//189 188//188 190//190 -f 181//181 148//148 191//191 -f 191//191 148//148 147//147 -f 191//191 147//147 192//192 -f 192//192 147//147 193//193 -f 192//192 193//193 190//190 -f 190//190 193//193 194//194 -f 190//190 194//194 189//189 -f 195//195 187//187 196//196 -f 196//196 187//187 186//186 -f 196//196 186//186 177//177 -f 177//177 186//186 197//197 -f 177//177 197//197 175//175 -f 175//175 197//197 198//198 -f 175//175 198//198 188//188 -f 199//199 200//200 201//201 -f 201//201 200//200 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 199//199 201//201 205//205 -f 206//206 207//207 199//199 -f 206//206 199//199 208//208 -f 208//208 199//199 205//205 -f 208//208 205//205 209//209 -f 210//210 211//211 205//205 -f 205//205 211//211 212//212 -f 205//205 212//212 209//209 -f 209//209 212//212 213//213 -f 209//209 213//213 214//214 -f 214//214 213//213 215//215 -f 214//214 215//215 216//216 -f 216//216 215//215 217//217 -f 218//218 213//213 212//212 -f 212//212 202//202 218//218 -f 218//218 202//202 200//200 -f 218//218 200//200 219//219 -f 219//219 200//200 220//220 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 225//225 224//224 226//226 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 229//229 -f 229//229 228//228 230//230 -f 231//231 226//226 224//224 -f 224//224 232//232 231//231 -f 231//231 232//232 233//233 -f 231//231 233//233 234//234 -f 234//234 233//233 235//235 -f 236//236 237//237 232//232 -f 232//232 237//237 238//238 -f 232//232 238//238 233//233 -f 233//233 238//238 239//239 -f 240//240 239//239 238//238 -f 241//241 223//223 242//242 -f 242//242 223//223 225//225 -f 243//243 244//244 238//238 -f 238//238 244//244 245//245 -f 238//238 245//245 240//240 -f 240//240 246//246 239//239 -f 239//239 246//246 247//247 -f 239//239 247//247 248//248 -f 248//248 247//247 249//249 -f 248//248 249//249 250//250 -f 249//249 251//251 250//250 -f 250//250 251//251 252//252 -f 250//250 252//252 253//253 -f 253//253 252//252 254//254 -f 253//253 254//254 225//225 -f 225//225 254//254 255//255 -f 225//225 255//255 242//242 -f 241//241 256//256 223//223 -f 223//223 256//256 257//257 -f 223//223 257//257 238//238 -f 238//238 257//257 258//258 -f 238//238 258//258 243//243 -f 259//259 260//260 261//261 -f 262//262 263//263 203//203 -f 203//203 263//263 264//264 -f 203//203 264//264 201//201 -f 264//264 265//265 201//201 -f 201//201 265//265 266//266 -f 201//201 266//266 205//205 -f 205//205 266//266 267//267 -f 205//205 267//267 268//268 -f 203//203 269//269 262//262 -f 262//262 269//269 270//270 -f 262//262 270//270 259//259 -f 259//259 270//270 271//271 -f 259//259 271//271 260//260 -f 268//268 272//272 205//205 -f 205//205 272//272 273//273 -f 205//205 273//273 210//210 -f 210//210 273//273 274//274 -f 210//210 274//274 275//275 -f 275//275 274//274 276//276 -f 275//275 276//276 277//277 -f 277//277 276//276 259//259 -f 277//277 259//259 278//278 -f 278//278 259//259 261//261 -f 261//261 260//260 279//279 -f 279//279 260//260 280//280 -f 280//280 281//281 279//279 -f 279//279 281//281 282//282 -f 279//279 282//282 283//283 -f 211//211 284//284 282//282 -f 282//282 284//284 285//285 -f 282//282 285//285 283//283 -f 286//286 212//212 287//287 -f 287//287 212//212 211//211 -f 287//287 211//211 288//288 -f 288//288 211//211 282//282 -f 286//286 289//289 212//212 -f 212//212 289//289 290//290 -f 212//212 290//290 202//202 -f 202//202 290//290 291//291 -f 291//291 292//292 202//202 -f 202//202 292//292 293//293 -f 202//202 293//293 204//204 -f 204//204 293//293 294//294 -f 204//204 294//294 295//295 -f 295//295 294//294 296//296 -f 295//295 296//296 297//297 -f 297//297 296//296 281//281 -f 297//297 281//281 298//298 -f 298//298 281//281 280//280 -f 290//290 267//267 291//291 -f 291//291 267//267 266//266 -f 291//291 266//266 292//292 -f 292//292 266//266 265//265 -f 292//292 265//265 293//293 -f 293//293 265//265 264//264 -f 293//293 264//264 294//294 -f 294//294 264//264 263//263 -f 294//294 263//263 296//296 -f 296//296 263//263 262//262 -f 296//296 262//262 281//281 -f 281//281 262//262 259//259 -f 281//281 259//259 282//282 -f 282//282 259//259 276//276 -f 282//282 276//276 288//288 -f 288//288 276//276 274//274 -f 288//288 274//274 287//287 -f 287//287 274//274 273//273 -f 287//287 273//273 286//286 -f 286//286 273//273 272//272 -f 286//286 272//272 289//289 -f 289//289 272//272 268//268 -f 289//289 268//268 290//290 -f 290//290 268//268 267//267 -f 299//299 258//258 257//257 -f 299//299 257//257 300//300 -f 258//258 299//299 243//243 -f 243//243 299//299 301//301 -f 243//243 301//301 244//244 -f 244//244 301//301 302//302 -f 244//244 302//302 245//245 -f 245//245 302//302 303//303 -f 245//245 303//303 240//240 -f 240//240 303//303 304//304 -f 240//240 304//304 246//246 -f 246//246 304//304 305//305 -f 246//246 305//305 247//247 -f 257//257 256//256 300//300 -f 300//300 256//256 241//241 -f 300//300 241//241 306//306 -f 306//306 241//241 242//242 -f 306//306 242//242 307//307 -f 307//307 242//242 255//255 -f 307//307 255//255 308//308 -f 308//308 255//255 254//254 -f 308//308 254//254 309//309 -f 309//309 254//254 252//252 -f 309//309 252//252 310//310 -f 310//310 252//252 251//251 -f 310//310 251//251 305//305 -f 305//305 251//251 249//249 -f 305//305 249//249 247//247 -f 308//308 309//309 311//311 -f 311//311 309//309 310//310 -f 311//311 310//310 305//305 -f 300//300 306//306 311//311 -f 311//311 306//306 307//307 -f 311//311 307//307 308//308 -f 302//302 301//301 311//311 -f 311//311 301//301 299//299 -f 311//311 299//299 300//300 -f 305//305 304//304 311//311 -f 311//311 304//304 303//303 -f 311//311 303//303 302//302 -f 71//71 79//79 152//152 -f 152//152 79//79 134//134 -f 152//152 134//134 153//153 -f 153//153 134//134 138//138 -f 153//153 138//138 154//154 -f 154//154 138//138 137//137 -f 154//154 137//137 145//145 -f 145//145 137//137 136//136 -f 145//145 136//136 143//143 -f 143//143 136//136 132//132 -f 12//12 11//11 135//135 -f 135//135 11//11 146//146 -f 135//135 146//146 140//140 -f 140//140 146//146 151//151 -f 140//140 151//151 139//139 -f 139//139 151//151 150//150 -f 139//139 150//150 133//133 -f 133//133 150//150 149//149 -f 133//133 149//149 127//127 -f 127//127 149//149 148//148 -f 179//179 164//164 312//312 -f 312//312 164//164 166//166 -f 312//312 166//166 313//313 -f 313//313 166//166 314//314 -f 314//314 166//166 167//167 -f 314//314 167//167 315//315 -f 315//315 167//167 316//316 -f 316//316 167//167 159//159 -f 316//316 159//159 317//317 -f 317//317 159//159 318//318 -f 318//318 159//159 131//131 -f 318//318 131//131 130//130 -f 129//129 128//128 319//319 -f 319//319 128//128 187//187 -f 319//319 187//187 320//320 -f 320//320 187//187 321//321 -f 321//321 187//187 195//195 -f 321//321 195//195 322//322 -f 322//322 195//195 323//323 -f 323//323 195//195 196//196 -f 323//323 196//196 324//324 -f 324//324 196//196 325//325 -f 325//325 196//196 177//177 -f 325//325 177//177 178//178 -f 176//176 175//175 326//326 -f 326//326 175//175 189//189 -f 326//326 189//189 327//327 -f 327//327 189//189 328//328 -f 328//328 189//189 194//194 -f 328//328 194//194 329//329 -f 329//329 194//194 330//330 -f 330//330 194//194 193//193 -f 330//330 193//193 331//331 -f 331//331 193//193 332//332 -f 332//332 193//193 147//147 -f 332//332 147//147 144//144 -f 142//142 141//141 333//333 -f 333//333 141//141 171//171 -f 333//333 171//171 334//334 -f 334//334 171//171 335//335 -f 335//335 171//171 173//173 -f 335//335 173//173 336//336 -f 336//336 173//173 337//337 -f 337//337 173//173 174//174 -f 337//337 174//174 338//338 -f 338//338 174//174 339//339 -f 339//339 174//174 162//162 -f 339//339 162//162 180//180 -f 340//340 341//341 324//324 -f 342//342 343//343 344//344 -f 344//344 343//343 345//345 -f 344//344 345//345 340//340 -f 346//346 347//347 348//348 -f 348//348 347//347 349//349 -f 348//348 349//349 344//344 -f 344//344 349//349 350//350 -f 344//344 350//350 342//342 -f 346//346 348//348 351//351 -f 351//351 348//348 352//352 -f 351//351 352//352 353//353 -f 354//354 355//355 356//356 -f 357//357 358//358 354//354 -f 354//354 358//358 359//359 -f 360//360 361//361 358//358 -f 358//358 361//361 362//362 -f 358//358 362//362 359//359 -f 363//363 364//364 365//365 -f 365//365 364//364 366//366 -f 365//365 366//366 360//360 -f 360//360 366//366 367//367 -f 360//360 367//367 361//361 -f 368//368 369//369 370//370 -f 370//370 369//369 371//371 -f 371//371 372//372 370//370 -f 370//370 372//372 373//373 -f 370//370 373//373 363//363 -f 324//324 341//341 323//323 -f 323//323 341//341 368//368 -f 323//323 368//368 322//322 -f 325//325 178//178 374//374 -f 340//340 324//324 344//344 -f 344//344 324//324 325//325 -f 344//344 325//325 348//348 -f 348//348 325//325 374//374 -f 348//348 374//374 352//352 -f 354//354 356//356 357//357 -f 357//357 356//356 375//375 -f 357//357 375//375 376//376 -f 363//363 365//365 370//370 -f 370//370 365//365 360//360 -f 370//370 360//360 377//377 -f 377//377 360//360 358//358 -f 377//377 358//358 378//378 -f 378//378 358//358 357//357 -f 378//378 357//357 379//379 -f 379//379 357//357 376//376 -f 379//379 376//376 380//380 -f 368//368 370//370 322//322 -f 322//322 370//370 377//377 -f 322//322 377//377 321//321 -f 321//321 377//377 378//378 -f 321//321 378//378 320//320 -f 320//320 378//378 379//379 -f 320//320 379//379 319//319 -f 319//319 379//379 380//380 -f 319//319 380//380 129//129 -f 381//381 382//382 383//383 -f 356//356 355//355 384//384 -f 130//130 129//129 385//385 -f 385//385 129//129 380//380 -f 385//385 380//380 386//386 -f 386//386 380//380 376//376 -f 386//386 376//376 387//387 -f 387//387 376//376 375//375 -f 387//387 375//375 383//383 -f 383//383 375//375 356//356 -f 383//383 356//356 381//381 -f 381//381 356//356 384//384 -f 381//381 384//384 1//1 -f 1//1 384//384 2//2 -f 178//178 176//176 388//388 -f 389//389 353//353 390//390 -f 390//390 353//353 352//352 -f 390//390 352//352 388//388 -f 388//388 352//352 374//374 -f 388//388 374//374 178//178 -f 391//391 392//392 393//393 -f 394//394 395//395 396//396 -f 397//397 398//398 399//399 -f 400//400 401//401 313//313 -f 313//313 314//314 400//400 -f 400//400 314//314 315//315 -f 400//400 315//315 402//402 -f 397//397 403//403 404//404 -f 404//404 403//403 405//405 -f 405//405 406//406 404//404 -f 404//404 406//406 407//407 -f 404//404 407//407 402//402 -f 399//399 398//398 408//408 -f 408//408 398//398 409//409 -f 408//408 409//409 410//410 -f 411//411 387//387 383//383 -f 410//410 409//409 412//412 -f 412//412 409//409 413//413 -f 412//412 413//413 414//414 -f 414//414 413//413 411//411 -f 414//414 411//411 415//415 -f 415//415 411//411 383//383 -f 415//415 383//383 382//382 -f 401//401 416//416 417//417 -f 417//417 416//416 418//418 -f 417//417 418//418 419//419 -f 419//419 420//420 417//417 -f 417//417 420//420 421//421 -f 417//417 421//421 393//393 -f 393//393 421//421 422//422 -f 393//393 422//422 391//391 -f 423//423 385//385 386//386 -f 397//397 404//404 398//398 -f 398//398 404//404 424//424 -f 398//398 424//424 409//409 -f 409//409 424//424 425//425 -f 409//409 425//425 413//413 -f 413//413 425//425 423//423 -f 413//413 423//423 411//411 -f 411//411 423//423 386//386 -f 411//411 386//386 387//387 -f 402//402 315//315 404//404 -f 404//404 315//315 316//316 -f 404//404 316//316 424//424 -f 424//424 316//316 317//317 -f 424//424 317//317 425//425 -f 425//425 317//317 318//318 -f 425//425 318//318 423//423 -f 423//423 318//318 130//130 -f 423//423 130//130 385//385 -f 426//426 393//393 396//396 -f 396//396 393//393 392//392 -f 396//396 392//392 394//394 -f 401//401 417//417 313//313 -f 313//313 417//417 393//393 -f 313//313 393//393 312//312 -f 312//312 393//393 426//426 -f 312//312 426//426 179//179 -f 427//427 428//428 429//429 -f 430//430 389//389 390//390 -f 431//431 432//432 433//433 -f 434//434 435//435 327//327 -f 327//327 328//328 434//434 -f 434//434 328//328 329//329 -f 434//434 329//329 436//436 -f 431//431 437//437 438//438 -f 438//438 437//437 439//439 -f 439//439 440//440 438//438 -f 438//438 440//440 441//441 -f 438//438 441//441 436//436 -f 433//433 432//432 442//442 -f 442//442 432//432 443//443 -f 442//442 443//443 444//444 -f 445//445 446//446 447//447 -f 444//444 443//443 448//448 -f 448//448 443//443 449//449 -f 448//448 449//449 450//450 -f 450//450 449//449 445//445 -f 450//450 445//445 451//451 -f 451//451 445//445 447//447 -f 451//451 447//447 452//452 -f 435//435 453//453 454//454 -f 454//454 453//453 455//455 -f 454//454 455//455 456//456 -f 456//456 457//457 454//454 -f 454//454 457//457 458//458 -f 454//454 458//458 429//429 -f 429//429 458//458 459//459 -f 429//429 459//459 427//427 -f 460//460 461//461 462//462 -f 431//431 438//438 432//432 -f 432//432 438//438 463//463 -f 432//432 463//463 443//443 -f 443//443 463//463 464//464 -f 443//443 464//464 449//449 -f 449//449 464//464 460//460 -f 449//449 460//460 445//445 -f 445//445 460//460 462//462 -f 445//445 462//462 446//446 -f 436//436 329//329 438//438 -f 438//438 329//329 330//330 -f 438//438 330//330 463//463 -f 463//463 330//330 331//331 -f 463//463 331//331 464//464 -f 464//464 331//331 332//332 -f 464//464 332//332 460//460 -f 460//460 332//332 144//144 -f 460//460 144//144 461//461 -f 388//388 429//429 390//390 -f 390//390 429//429 428//428 -f 390//390 428//428 430//430 -f 435//435 454//454 327//327 -f 327//327 454//454 429//429 -f 327//327 429//429 326//326 -f 326//326 429//429 388//388 -f 326//326 388//388 176//176 -f 180//180 179//179 426//426 -f 395//395 465//465 396//396 -f 396//396 465//465 466//466 -f 396//396 466//466 426//426 -f 426//426 466//466 467//467 -f 426//426 467//467 180//180 -f 468//468 452//452 447//447 -f 469//469 470//470 471//471 -f 144//144 142//142 461//461 -f 461//461 142//142 472//472 -f 461//461 472//472 462//462 -f 462//462 472//472 473//473 -f 462//462 473//473 446//446 -f 446//446 473//473 474//474 -f 446//446 474//474 447//447 -f 447//447 474//474 469//469 -f 447//447 469//469 468//468 -f 468//468 469//469 471//471 -f 468//468 471//471 4//4 -f 4//4 471//471 3//3 -f 475//475 470//470 469//469 -f 476//476 477//477 475//475 -f 475//475 477//477 478//478 -f 479//479 480//480 477//477 -f 477//477 480//480 481//481 -f 477//477 481//481 478//478 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 479//479 -f 479//479 485//485 486//486 -f 479//479 486//486 480//480 -f 487//487 488//488 489//489 -f 489//489 488//488 490//490 -f 490//490 491//491 489//489 -f 489//489 491//491 492//492 -f 489//489 492//492 482//482 -f 336//336 337//337 487//487 -f 487//487 337//337 493//493 -f 493//493 337//337 338//338 -f 493//493 338//338 494//494 -f 495//495 496//496 497//497 -f 497//497 496//496 498//498 -f 497//497 498//498 494//494 -f 499//499 500//500 501//501 -f 501//501 500//500 502//502 -f 501//501 502//502 497//497 -f 497//497 502//502 503//503 -f 497//497 503//503 495//495 -f 499//499 501//501 504//504 -f 504//504 501//501 466//466 -f 504//504 466//466 465//465 -f 339//339 180//180 467//467 -f 494//494 338//338 497//497 -f 497//497 338//338 339//339 -f 497//497 339//339 501//501 -f 501//501 339//339 467//467 -f 501//501 467//467 466//466 -f 475//475 469//469 476//476 -f 476//476 469//469 474//474 -f 476//476 474//474 473//473 -f 482//482 484//484 489//489 -f 489//489 484//484 479//479 -f 489//489 479//479 505//505 -f 505//505 479//479 477//477 -f 505//505 477//477 506//506 -f 506//506 477//477 476//476 -f 506//506 476//476 507//507 -f 507//507 476//476 473//473 -f 507//507 473//473 472//472 -f 487//487 489//489 336//336 -f 336//336 489//489 505//505 -f 336//336 505//505 335//335 -f 335//335 505//505 506//506 -f 335//335 506//506 334//334 -f 334//334 506//506 507//507 -f 334//334 507//507 333//333 -f 333//333 507//507 472//472 -f 333//333 472//472 142//142 -f 508//508 509//509 182//182 -f 510//510 198//198 511//511 -f 511//511 198//198 197//197 -f 511//511 197//197 512//512 -f 512//512 197//197 513//513 -f 514//514 515//515 186//186 -f 515//515 516//516 186//186 -f 186//186 516//516 517//517 -f 186//186 517//517 197//197 -f 197//197 517//517 518//518 -f 197//197 518//518 513//513 -f 519//519 520//520 186//186 -f 186//186 520//520 521//521 -f 186//186 521//521 514//514 -f 522//522 185//185 523//523 -f 523//523 185//185 184//184 -f 523//523 184//184 524//524 -f 522//522 525//525 185//185 -f 185//185 525//525 526//526 -f 185//185 526//526 186//186 -f 186//186 526//526 527//527 -f 186//186 527//527 519//519 -f 182//182 509//509 183//183 -f 509//509 528//528 183//183 -f 183//183 528//528 529//529 -f 183//183 529//529 184//184 -f 184//184 529//529 530//530 -f 184//184 530//530 524//524 -f 181//181 531//531 182//182 -f 182//182 531//531 532//532 -f 182//182 532//532 508//508 -f 191//191 192//192 533//533 -f 533//533 534//534 191//191 -f 191//191 534//534 535//535 -f 191//191 535//535 181//181 -f 181//181 535//535 536//536 -f 181//181 536//536 531//531 -f 537//537 538//538 190//190 -f 190//190 538//538 539//539 -f 190//190 539//539 192//192 -f 192//192 539//539 540//540 -f 192//192 540//540 533//533 -f 541//541 542//542 188//188 -f 188//188 542//542 543//543 -f 188//188 543//543 190//190 -f 190//190 543//543 544//544 -f 190//190 544//544 537//537 -f 510//510 545//545 198//198 -f 198//198 545//545 546//546 -f 198//198 546//546 188//188 -f 188//188 546//546 547//547 -f 188//188 547//547 541//541 -f 155//155 157//157 548//548 -f 158//158 549//549 157//157 -f 157//157 549//549 550//550 -f 157//157 550//550 548//548 -f 551//551 552//552 161//161 -f 161//161 552//552 553//553 -f 161//161 553//553 158//158 -f 158//158 553//553 554//554 -f 158//158 554//554 549//549 -f 555//555 551//551 556//556 -f 556//556 551//551 161//161 -f 556//556 161//161 557//557 -f 557//557 161//161 558//558 -f 161//161 160//160 558//558 -f 558//558 160//160 165//165 -f 558//558 165//165 559//559 -f 163//163 560//560 165//165 -f 165//165 560//560 561//561 -f 165//165 561//561 559//559 -f 172//172 170//170 562//562 -f 562//562 563//563 172//172 -f 172//172 563//563 564//564 -f 172//172 564//564 163//163 -f 163//163 564//564 565//565 -f 163//163 565//565 560//560 -f 168//168 566//566 169//169 -f 169//169 566//566 567//567 -f 169//169 567//567 170//170 -f 170//170 567//567 568//568 -f 170//170 568//568 562//562 -f 156//156 569//569 168//168 -f 168//168 569//569 570//570 -f 168//168 570//570 566//566 -f 548//548 571//571 155//155 -f 155//155 571//571 572//572 -f 155//155 572//572 156//156 -f 156//156 572//572 573//573 -f 156//156 573//573 569//569 -f 574//574 575//575 576//576 -f 576//576 575//575 577//577 -f 578//578 579//579 580//580 -f 581//581 223//223 582//582 -f 582//582 223//223 238//238 -f 582//582 238//238 583//583 -f 237//237 584//584 585//585 -f 585//585 584//584 586//586 -f 585//585 586//586 587//587 -f 585//585 588//588 237//237 -f 237//237 588//588 589//589 -f 237//237 589//589 238//238 -f 238//238 589//589 590//590 -f 238//238 590//590 583//583 -f 586//586 591//591 587//587 -f 587//587 591//591 576//576 -f 587//587 576//576 592//592 -f 592//592 576//576 577//577 -f 577//577 578//578 592//592 -f 592//592 578//578 580//580 -f 592//592 580//580 593//593 -f 593//593 580//580 221//221 -f 593//593 221//221 594//594 -f 594//594 221//221 223//223 -f 594//594 223//223 595//595 -f 595//595 223//223 581//581 -f 575//575 574//574 596//596 -f 597//597 598//598 222//222 -f 222//222 598//598 599//599 -f 222//222 599//599 224//224 -f 599//599 600//600 224//224 -f 224//224 600//600 601//601 -f 224//224 601//601 232//232 -f 232//232 601//601 602//602 -f 232//232 602//602 603//603 -f 603//603 604//604 232//232 -f 232//232 604//604 605//605 -f 232//232 605//605 236//236 -f 236//236 605//605 606//606 -f 236//236 606//606 607//607 -f 607//607 606//606 608//608 -f 607//607 608//608 609//609 -f 609//609 608//608 596//596 -f 609//609 596//596 610//610 -f 610//610 596//596 574//574 -f 222//222 611//611 597//597 -f 597//597 611//611 612//612 -f 597//597 612//612 596//596 -f 596//596 612//612 613//613 -f 596//596 613//613 575//575 -f 582//582 602//602 581//581 -f 581//581 602//602 601//601 -f 581//581 601//601 595//595 -f 595//595 601//601 600//600 -f 595//595 600//600 594//594 -f 594//594 600//600 599//599 -f 594//594 599//599 593//593 -f 593//593 599//599 598//598 -f 593//593 598//598 592//592 -f 592//592 598//598 597//597 -f 592//592 597//597 587//587 -f 587//587 597//597 596//596 -f 587//587 596//596 585//585 -f 585//585 596//596 608//608 -f 585//585 608//608 588//588 -f 588//588 608//608 606//606 -f 588//588 606//606 589//589 -f 589//589 606//606 605//605 -f 589//589 605//605 590//590 -f 590//590 605//605 604//604 -f 590//590 604//604 583//583 -f 583//583 604//604 603//603 -f 583//583 603//603 582//582 -f 582//582 603//603 602//602 -f 614//614 615//615 458//458 -f 616//616 617//617 618//618 -f 619//619 620//620 621//621 -f 621//621 620//620 622//622 -f 621//621 622//622 623//623 -f 617//617 624//624 618//618 -f 618//618 624//624 625//625 -f 618//618 625//625 620//620 -f 620//620 625//625 626//626 -f 620//620 626//626 622//622 -f 627//627 616//616 428//428 -f 428//428 427//427 627//627 -f 627//627 427//427 459//459 -f 627//627 459//459 628//628 -f 458//458 615//615 459//459 -f 459//459 615//615 629//629 -f 459//459 629//629 628//628 -f 455//455 630//630 456//456 -f 456//456 630//630 631//631 -f 456//456 631//631 457//457 -f 457//457 631//631 632//632 -f 457//457 632//632 458//458 -f 458//458 632//632 633//633 -f 458//458 633//633 614//614 -f 634//634 635//635 455//455 -f 635//635 636//636 455//455 -f 455//455 636//636 637//637 -f 455//455 637//637 630//630 -f 455//455 453//453 634//634 -f 634//634 453//453 435//435 -f 634//634 435//435 638//638 -f 434//434 639//639 435//435 -f 435//435 639//639 640//640 -f 435//435 640//640 638//638 -f 616//616 618//618 428//428 -f 428//428 618//618 620//620 -f 428//428 620//620 430//430 -f 430//430 620//620 619//619 -f 430//430 619//619 389//389 -f 641//641 642//642 643//643 -f 368//368 341//341 644//644 -f 644//644 341//341 645//645 -f 645//645 341//341 646//646 -f 646//646 341//341 340//340 -f 646//646 340//340 647//647 -f 647//647 340//340 345//345 -f 647//647 345//345 648//648 -f 648//648 345//345 649//649 -f 649//649 345//345 343//343 -f 649//649 343//343 650//650 -f 650//650 343//343 651//651 -f 651//651 343//343 342//342 -f 651//651 342//342 652//652 -f 652//652 342//342 653//653 -f 653//653 342//342 350//350 -f 653//653 350//350 654//654 -f 654//654 350//350 655//655 -f 655//655 350//350 349//349 -f 655//655 349//349 656//656 -f 656//656 349//349 347//347 -f 656//656 347//347 657//657 -f 658//658 659//659 660//660 -f 660//660 659//659 661//661 -f 660//660 661//661 643//643 -f 643//643 661//661 662//662 -f 643//643 662//662 641//641 -f 657//657 347//347 658//658 -f 658//658 347//347 346//346 -f 658//658 346//346 659//659 -f 659//659 346//346 351//351 -f 659//659 351//351 661//661 -f 661//661 351//351 353//353 -f 661//661 353//353 662//662 -f 663//663 642//642 641//641 -f 664//664 621//621 623//623 -f 216//216 217//217 665//665 -f 665//665 217//217 664//664 -f 665//665 664//664 666//666 -f 666//666 664//664 623//623 -f 353//353 389//389 662//662 -f 662//662 389//389 619//619 -f 662//662 619//619 641//641 -f 641//641 619//619 621//621 -f 641//641 621//621 663//663 -f 663//663 621//621 664//664 -f 667//667 668//668 669//669 -f 623//623 670//670 666//666 -f 635//635 441//441 440//440 -f 639//639 434//434 436//436 -f 544//544 543//543 668//668 -f 511//511 512//512 671//671 -f 546//546 545//545 669//669 -f 669//669 545//545 510//510 -f 669//669 510//510 672//672 -f 543//543 542//542 668//668 -f 668//668 542//542 541//541 -f 668//668 541//541 669//669 -f 669//669 541//541 547//547 -f 669//669 547//547 546//546 -f 452//452 538//538 451//451 -f 451//451 538//538 537//537 -f 635//635 634//634 441//441 -f 441//441 634//634 638//638 -f 441//441 638//638 436//436 -f 436//436 638//638 640//640 -f 436//436 640//640 639//639 -f 631//631 630//630 439//439 -f 439//439 630//630 637//637 -f 439//439 637//637 440//440 -f 440//440 637//637 636//636 -f 440//440 636//636 635//635 -f 631//631 439//439 632//632 -f 632//632 439//439 437//437 -f 632//632 437//437 633//633 -f 431//431 615//615 437//437 -f 437//437 615//615 614//614 -f 437//437 614//614 633//633 -f 616//616 627//627 433//433 -f 433//433 627//627 628//628 -f 433//433 628//628 431//431 -f 431//431 628//628 629//629 -f 431//431 629//629 615//615 -f 673//673 625//625 624//624 -f 672//672 208//208 209//209 -f 665//665 669//669 216//216 -f 216//216 669//669 672//672 -f 216//216 672//672 214//214 -f 214//214 672//672 209//209 -f 616//616 433//433 617//617 -f 617//617 433//433 442//442 -f 617//617 442//442 624//624 -f 624//624 442//442 444//444 -f 624//624 444//444 673//673 -f 673//673 444//444 448//448 -f 673//673 448//448 674//674 -f 674//674 448//448 450//450 -f 674//674 450//450 667//667 -f 667//667 450//450 451//451 -f 667//667 451//451 668//668 -f 668//668 451//451 537//537 -f 668//668 537//537 544//544 -f 665//665 666//666 669//669 -f 669//669 666//666 670//670 -f 669//669 670//670 667//667 -f 667//667 670//670 623//623 -f 667//667 623//623 674//674 -f 674//674 623//623 622//622 -f 674//674 622//622 673//673 -f 673//673 622//622 626//626 -f 673//673 626//626 625//625 -f 206//206 208//208 671//671 -f 671//671 208//208 672//672 -f 671//671 672//672 511//511 -f 511//511 672//672 510//510 -f 675//675 676//676 677//677 -f 663//663 678//678 642//642 -f 664//664 217//217 679//679 -f 679//679 217//217 215//215 -f 678//678 663//663 680//680 -f 658//658 660//660 681//681 -f 681//681 660//660 643//643 -f 681//681 643//643 642//642 -f 655//655 656//656 366//366 -f 655//655 366//366 654//654 -f 366//366 364//364 654//654 -f 654//654 364//364 363//363 -f 654//654 363//363 653//653 -f 648//648 649//649 373//373 -f 649//649 650//650 373//373 -f 373//373 650//650 651//651 -f 373//373 651//651 363//363 -f 363//363 651//651 652//652 -f 363//363 652//652 653//653 -f 373//373 372//372 648//648 -f 648//648 372//372 371//371 -f 648//648 371//371 647//647 -f 368//368 644//644 369//369 -f 369//369 644//644 645//645 -f 369//369 645//645 371//371 -f 371//371 645//645 646//646 -f 371//371 646//646 647//647 -f 219//219 679//679 218//218 -f 218//218 679//679 215//215 -f 218//218 215//215 213//213 -f 219//219 682//682 679//679 -f 679//679 682//682 680//680 -f 679//679 680//680 664//664 -f 664//664 680//680 663//663 -f 682//682 675//675 680//680 -f 680//680 675//675 677//677 -f 680//680 677//677 678//678 -f 678//678 677//677 683//683 -f 678//678 683//683 642//642 -f 642//642 683//683 684//684 -f 642//642 684//684 681//681 -f 656//656 657//657 366//366 -f 366//366 657//657 658//658 -f 366//366 658//658 367//367 -f 367//367 658//658 681//681 -f 367//367 681//681 361//361 -f 361//361 681//681 684//684 -f 361//361 684//684 362//362 -f 362//362 684//684 683//683 -f 362//362 683//683 359//359 -f 359//359 683//683 677//677 -f 359//359 677//677 354//354 -f 354//354 677//677 676//676 -f 354//354 676//676 355//355 -f 685//685 686//686 509//509 -f 685//685 509//509 468//468 -f 468//468 509//509 508//508 -f 468//468 508//508 532//532 -f 534//534 533//533 452//452 -f 532//532 531//531 468//468 -f 468//468 531//531 536//536 -f 468//468 536//536 452//452 -f 452//452 536//536 535//535 -f 452//452 535//535 534//534 -f 533//533 540//540 452//452 -f 452//452 540//540 539//539 -f 452//452 539//539 538//538 -f 687//687 525//525 522//522 -f 687//687 522//522 688//688 -f 686//686 689//689 509//509 -f 509//509 689//689 690//690 -f 509//509 690//690 528//528 -f 528//528 690//690 691//691 -f 528//528 691//691 529//529 -f 529//529 691//691 692//692 -f 529//529 692//692 530//530 -f 530//530 692//692 693//693 -f 530//530 693//693 524//524 -f 524//524 693//693 688//688 -f 524//524 688//688 523//523 -f 523//523 688//688 522//522 -f 671//671 517//517 206//206 -f 206//206 517//517 516//516 -f 206//206 516//516 515//515 -f 515//515 514//514 206//206 -f 206//206 514//514 521//521 -f 206//206 521//521 207//207 -f 521//521 520//520 207//207 -f 207//207 520//520 519//519 -f 207//207 519//519 694//694 -f 694//694 519//519 527//527 -f 694//694 527//527 687//687 -f 687//687 527//527 526//526 -f 687//687 526//526 525//525 -f 512//512 513//513 671//671 -f 671//671 513//513 518//518 -f 671//671 518//518 517//517 -f 689//689 686//686 4//4 -f 4//4 686//686 685//685 -f 4//4 685//685 468//468 -f 384//384 355//355 695//695 -f 695//695 355//355 696//696 -f 676//676 675//675 697//697 -f 697//697 698//698 676//676 -f 676//676 698//698 699//699 -f 676//676 699//699 355//355 -f 355//355 699//699 700//700 -f 355//355 700//700 696//696 -f 682//682 219//219 220//220 -f 220//220 701//701 682//682 -f 682//682 701//701 702//702 -f 682//682 702//702 675//675 -f 675//675 702//702 703//703 -f 675//675 703//703 697//697 -f 200//200 199//199 220//220 -f 220//220 199//199 207//207 -f 220//220 207//207 701//701 -f 701//701 207//207 694//694 -f 701//701 694//694 702//702 -f 702//702 694//694 687//687 -f 702//702 687//687 688//688 -f 4//4 2//2 689//689 -f 689//689 2//2 696//696 -f 689//689 696//696 690//690 -f 690//690 696//696 700//700 -f 690//690 700//700 691//691 -f 691//691 700//700 699//699 -f 691//691 699//699 692//692 -f 692//692 699//699 698//698 -f 692//692 698//698 693//693 -f 693//693 698//698 697//697 -f 693//693 697//697 688//688 -f 688//688 697//697 703//703 -f 688//688 703//703 702//702 -f 696//696 2//2 695//695 -f 695//695 2//2 384//384 -f 704//704 705//705 421//421 -f 706//706 707//707 708//708 -f 709//709 710//710 711//711 -f 711//711 710//710 712//712 -f 711//711 712//712 713//713 -f 707//707 714//714 708//708 -f 708//708 714//714 715//715 -f 708//708 715//715 710//710 -f 710//710 715//715 716//716 -f 710//710 716//716 712//712 -f 717//717 706//706 392//392 -f 392//392 391//391 717//717 -f 717//717 391//391 422//422 -f 717//717 422//422 718//718 -f 421//421 705//705 422//422 -f 422//422 705//705 719//719 -f 422//422 719//719 718//718 -f 418//418 720//720 419//419 -f 419//419 720//720 721//721 -f 419//419 721//721 420//420 -f 420//420 721//721 722//722 -f 420//420 722//722 421//421 -f 421//421 722//722 723//723 -f 421//421 723//723 704//704 -f 724//724 725//725 418//418 -f 725//725 726//726 418//418 -f 418//418 726//726 727//727 -f 418//418 727//727 720//720 -f 418//418 416//416 724//724 -f 724//724 416//416 401//401 -f 724//724 401//401 728//728 -f 400//400 729//729 401//401 -f 401//401 729//729 730//730 -f 401//401 730//730 728//728 -f 706//706 708//708 392//392 -f 392//392 708//708 710//710 -f 392//392 710//710 394//394 -f 394//394 710//710 709//709 -f 394//394 709//709 395//395 -f 731//731 732//732 733//733 -f 487//487 493//493 734//734 -f 734//734 493//493 735//735 -f 735//735 493//493 736//736 -f 736//736 493//493 494//494 -f 736//736 494//494 737//737 -f 737//737 494//494 498//498 -f 737//737 498//498 738//738 -f 738//738 498//498 739//739 -f 739//739 498//498 496//496 -f 739//739 496//496 740//740 -f 740//740 496//496 741//741 -f 741//741 496//496 495//495 -f 741//741 495//495 742//742 -f 742//742 495//495 743//743 -f 743//743 495//495 503//503 -f 743//743 503//503 744//744 -f 744//744 503//503 745//745 -f 745//745 503//503 502//502 -f 745//745 502//502 746//746 -f 746//746 502//502 500//500 -f 746//746 500//500 747//747 -f 748//748 749//749 750//750 -f 750//750 749//749 751//751 -f 750//750 751//751 733//733 -f 733//733 751//751 752//752 -f 733//733 752//752 731//731 -f 747//747 500//500 748//748 -f 748//748 500//500 499//499 -f 748//748 499//499 749//749 -f 749//749 499//499 504//504 -f 749//749 504//504 751//751 -f 751//751 504//504 465//465 -f 751//751 465//465 752//752 -f 753//753 732//732 731//731 -f 754//754 711//711 713//713 -f 229//229 230//230 755//755 -f 755//755 230//230 754//754 -f 755//755 754//754 756//756 -f 756//756 754//754 713//713 -f 754//754 753//753 711//711 -f 711//711 753//753 731//731 -f 711//711 731//731 709//709 -f 709//709 731//731 752//752 -f 709//709 752//752 395//395 -f 395//395 752//752 465//465 -f 757//757 758//758 759//759 -f 713//713 760//760 756//756 -f 725//725 407//407 406//406 -f 729//729 400//400 402//402 -f 725//725 724//724 407//407 -f 407//407 724//724 728//728 -f 407//407 728//728 402//402 -f 402//402 728//728 730//730 -f 402//402 730//730 729//729 -f 721//721 720//720 405//405 -f 405//405 720//720 727//727 -f 405//405 727//727 406//406 -f 406//406 727//727 726//726 -f 406//406 726//726 725//725 -f 721//721 405//405 722//722 -f 722//722 405//405 403//403 -f 722//722 403//403 723//723 -f 397//397 705//705 403//403 -f 403//403 705//705 704//704 -f 403//403 704//704 723//723 -f 706//706 717//717 399//399 -f 399//399 717//717 718//718 -f 399//399 718//718 397//397 -f 397//397 718//718 719//719 -f 397//397 719//719 705//705 -f 761//761 715//715 714//714 -f 762//762 253//253 225//225 -f 755//755 759//759 229//229 -f 229//229 759//759 762//762 -f 229//229 762//762 227//227 -f 227//227 762//762 225//225 -f 706//706 399//399 707//707 -f 707//707 399//399 408//408 -f 707//707 408//408 714//714 -f 714//714 408//408 410//410 -f 714//714 410//410 761//761 -f 761//761 410//410 412//412 -f 761//761 412//412 763//763 -f 763//763 412//412 414//414 -f 763//763 414//414 757//757 -f 757//757 414//414 415//415 -f 757//757 415//415 758//758 -f 755//755 756//756 759//759 -f 759//759 756//756 760//760 -f 759//759 760//760 757//757 -f 757//757 760//760 713//713 -f 757//757 713//713 763//763 -f 763//763 713//713 712//712 -f 763//763 712//712 761//761 -f 761//761 712//712 716//716 -f 761//761 716//716 715//715 -f 250//250 253//253 764//764 -f 764//764 253//253 762//762 -f 764//764 762//762 765//765 -f 765//765 762//762 759//759 -f 765//765 759//759 766//766 -f 766//766 759//759 758//758 -f 766//766 758//758 382//382 -f 382//382 758//758 415//415 -f 767//767 768//768 769//769 -f 753//753 770//770 732//732 -f 754//754 230//230 771//771 -f 771//771 230//230 228//228 -f 770//770 753//753 772//772 -f 748//748 750//750 773//773 -f 773//773 750//750 733//733 -f 773//773 733//733 732//732 -f 745//745 746//746 485//485 -f 745//745 485//485 744//744 -f 485//485 483//483 744//744 -f 744//744 483//483 482//482 -f 744//744 482//482 743//743 -f 738//738 739//739 492//492 -f 739//739 740//740 492//492 -f 492//492 740//740 741//741 -f 492//492 741//741 482//482 -f 482//482 741//741 742//742 -f 482//482 742//742 743//743 -f 492//492 491//491 738//738 -f 738//738 491//491 490//490 -f 738//738 490//490 737//737 -f 487//487 734//734 488//488 -f 488//488 734//734 735//735 -f 488//488 735//735 490//490 -f 490//490 735//735 736//736 -f 490//490 736//736 737//737 -f 234//234 771//771 231//231 -f 231//231 771//771 228//228 -f 231//231 228//228 226//226 -f 234//234 774//774 771//771 -f 771//771 774//774 772//772 -f 771//771 772//772 754//754 -f 754//754 772//772 753//753 -f 774//774 767//767 772//772 -f 772//772 767//767 769//769 -f 772//772 769//769 770//770 -f 770//770 769//769 775//775 -f 770//770 775//775 732//732 -f 732//732 775//775 776//776 -f 732//732 776//776 773//773 -f 746//746 747//747 485//485 -f 485//485 747//747 748//748 -f 485//485 748//748 486//486 -f 486//486 748//748 773//773 -f 486//486 773//773 480//480 -f 480//480 773//773 776//776 -f 480//480 776//776 481//481 -f 481//481 776//776 775//775 -f 481//481 775//775 478//478 -f 478//478 775//775 769//769 -f 478//478 769//769 475//475 -f 475//475 769//769 768//768 -f 475//475 768//768 470//470 -f 248//248 250//250 777//777 -f 777//777 250//250 764//764 -f 765//765 778//778 764//764 -f 764//764 778//778 779//779 -f 764//764 779//779 777//777 -f 766//766 780//780 765//765 -f 765//765 780//780 781//781 -f 765//765 781//781 778//778 -f 782//782 382//382 783//783 -f 783//783 382//382 381//381 -f 782//782 784//784 382//382 -f 382//382 784//784 785//785 -f 382//382 785//785 766//766 -f 766//766 785//785 786//786 -f 766//766 786//786 780//780 -f 784//784 782//782 1//1 -f 1//1 782//782 783//783 -f 1//1 783//783 381//381 -f 571//571 548//548 787//787 -f 563//563 562//562 470//470 -f 768//768 565//565 470//470 -f 470//470 565//565 564//564 -f 470//470 564//564 563//563 -f 562//562 568//568 470//470 -f 470//470 568//568 567//567 -f 470//470 567//567 471//471 -f 471//471 567//567 566//566 -f 471//471 566//566 570//570 -f 571//571 787//787 572//572 -f 572//572 787//787 788//788 -f 572//572 788//788 573//573 -f 573//573 788//788 789//789 -f 573//573 789//789 790//790 -f 570//570 569//569 471//471 -f 471//471 569//569 573//573 -f 471//471 573//573 791//791 -f 791//791 573//573 790//790 -f 557//557 558//558 774//774 -f 774//774 558//558 559//559 -f 774//774 559//559 767//767 -f 767//767 559//559 561//561 -f 767//767 561//561 768//768 -f 768//768 561//561 560//560 -f 768//768 560//560 565//565 -f 555//555 792//792 551//551 -f 551//551 792//792 552//552 -f 557//557 774//774 556//556 -f 556//556 774//774 234//234 -f 556//556 234//234 555//555 -f 555//555 234//234 235//235 -f 555//555 235//235 792//792 -f 233//233 239//239 235//235 -f 235//235 239//239 248//248 -f 235//235 248//248 792//792 -f 792//792 248//248 777//777 -f 792//792 777//777 552//552 -f 552//552 777//777 779//779 -f 552//552 779//779 553//553 -f 553//553 779//779 778//778 -f 553//553 778//778 554//554 -f 554//554 778//778 549//549 -f 787//787 548//548 780//780 -f 780//780 548//548 550//550 -f 549//549 778//778 550//550 -f 550//550 778//778 781//781 -f 550//550 781//781 780//780 -f 787//787 780//780 788//788 -f 788//788 780//780 786//786 -f 788//788 786//786 785//785 -f 1//1 3//3 784//784 -f 784//784 3//3 790//790 -f 784//784 790//790 785//785 -f 785//785 790//790 789//789 -f 785//785 789//789 788//788 -f 790//790 3//3 791//791 -f 791//791 3//3 471//471 -f 579//579 611//611 580//580 -f 580//580 611//611 222//222 -f 580//580 222//222 221//221 -f 577//577 575//575 578//578 -f 578//578 575//575 613//613 -f 578//578 613//613 579//579 -f 579//579 613//613 612//612 -f 579//579 612//612 611//611 -f 574//574 576//576 610//610 -f 610//610 576//576 591//591 -f 610//610 591//591 609//609 -f 591//591 586//586 609//609 -f 609//609 586//586 584//584 -f 609//609 584//584 607//607 -f 607//607 584//584 237//237 -f 607//607 237//237 236//236 -f 280//280 260//260 298//298 -f 298//298 260//260 271//271 -f 298//298 271//271 297//297 -f 271//271 270//270 297//297 -f 297//297 270//270 269//269 -f 297//297 269//269 295//295 -f 295//295 269//269 203//203 -f 295//295 203//203 204//204 -f 261//261 279//279 278//278 -f 278//278 279//279 283//283 -f 278//278 283//283 277//277 -f 283//283 285//285 277//277 -f 277//277 285//285 284//284 -f 277//277 284//284 275//275 -f 275//275 284//284 211//211 -f 275//275 211//211 210//210 -# 1612 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_G_left.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_G_left.obj deleted file mode 100644 index c67561d2c..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_G_left.obj +++ /dev/null @@ -1,1336 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object hand_G_left.obj -# -# Vertices: 324 -# Faces: 672 -# -#### -vn 1.508018 -1.330396 1.079942 -v 0.010000 0.121081 0.225887 -vn 0.281234 -3.242858 3.179237 -v 0.009000 0.121081 0.225887 -vn 2.827969 -2.799568 -1.401840 -v 0.009403 0.121161 0.223842 -vn 2.712342 -2.831441 -2.127716 -v 0.009000 0.121185 0.223217 -vn 2.841701 2.975100 -1.970777 -v 0.009000 0.131178 0.223609 -vn 0.306442 2.978442 3.457106 -v 0.009000 0.131073 0.226279 -vn 2.827952 2.900599 -1.178668 -v 0.009403 0.131153 0.224233 -vn 1.508019 1.241891 1.180652 -v 0.010000 0.131073 0.226279 -vn 3.226444 0.238730 3.287539 -v 0.004000 0.136167 0.223976 -vn 1.570802 1.508151 1.631046 -v 0.004000 0.137166 0.224015 -vn -3.230062 0.211521 3.256158 -v -0.001000 0.136167 0.223976 -vn -1.570801 1.508151 1.631046 -v -0.001000 0.137166 0.224015 -vn -3.227070 -0.490665 3.255411 -v -0.001000 0.116182 0.223194 -vn -1.570804 -1.631059 1.508141 -v -0.001000 0.115183 0.223155 -vn 3.231248 -0.453245 3.215994 -v 0.004000 0.116182 0.223194 -vn 1.570806 -1.631060 1.508141 -v 0.004000 0.115183 0.223155 -vn -2.984513 3.129477 -0.123391 -v -0.025000 0.140492 0.139080 -vn 2.984515 3.129477 -0.123391 -v -0.022000 0.140492 0.139080 -vn 2.827434 2.986300 -0.842669 -v -0.022000 0.140087 0.135663 -vn -2.827433 2.986300 -0.842669 -v -0.025000 0.140087 0.135663 -vn 2.827433 2.579741 -1.724244 -v -0.022000 0.138645 0.132537 -vn -2.827432 2.579740 -1.724244 -v -0.025000 0.138645 0.132537 -vn 2.827435 1.920661 -2.437036 -v -0.022000 0.136309 0.130011 -vn -2.827436 1.920661 -2.437036 -v -0.025000 0.136309 0.130011 -vn 2.827428 1.073568 -2.911275 -v -0.022000 0.133306 0.128329 -vn -2.827428 1.073568 -2.911275 -v -0.025000 0.133306 0.128329 -vn 2.827436 0.121387 -3.100540 -v -0.022000 0.129930 0.127658 -vn -2.827436 0.121387 -3.100540 -v -0.025000 0.129930 0.127658 -vn 2.827435 -0.842668 -2.986300 -v -0.022000 0.126513 0.128063 -vn -2.827434 -0.842668 -2.986300 -v -0.025000 0.126513 0.128063 -vn 2.827432 -1.724243 -2.579741 -v -0.022000 0.123387 0.129505 -vn -2.827432 -1.724243 -2.579741 -v -0.025000 0.123387 0.129505 -vn 2.827436 -2.437037 -1.920659 -v -0.022000 0.120861 0.131841 -vn -2.827435 -2.437037 -1.920659 -v -0.025000 0.120861 0.131841 -vn 2.827431 -2.911276 -1.073569 -v -0.022000 0.119179 0.134844 -vn -2.827431 -2.911276 -1.073569 -v -0.025000 0.119179 0.134844 -vn 2.984512 -3.110250 -0.367685 -v -0.022000 0.118508 0.138220 -vn -2.984514 -3.110250 -0.367685 -v -0.025000 0.118508 0.138220 -vn -3.088072 -2.893493 0.293577 -v -0.025000 0.117530 0.163201 -vn 3.111410 -2.930999 -0.421436 -v 0.004000 0.117335 0.168197 -vn 3.111409 -3.323398 -0.436797 -v -0.022000 0.117726 0.158204 -vn 2.846683 -3.485457 -1.316502 -v -0.021619 0.117651 0.160116 -vn -2.627990 -2.675347 1.413691 -v -0.024464 0.117452 0.165199 -vn 2.178751 -3.446351 -2.315356 -v -0.020536 0.117588 0.161737 -vn -1.517273 -2.718801 2.523568 -v -0.023000 0.117395 0.166662 -vn 1.179145 -3.420213 -2.982763 -v -0.018913 0.117545 0.162820 -vn -0.406552 -2.998399 2.973045 -v -0.021000 0.117374 0.167197 -vn 0.306458 -3.213670 -3.239612 -v -0.017000 0.117530 0.163201 -vn -3.122252 -3.305761 0.116490 -v -0.001000 0.116983 0.177190 -vn -2.951039 -3.490618 0.822927 -v -0.001489 0.117104 0.174102 -vn 2.846686 -2.700660 -1.285774 -v 0.003619 0.117410 0.166285 -vn -2.510314 -3.524457 1.687256 -v -0.002910 0.117213 0.171316 -vn 2.178756 -2.661552 -2.284629 -v 0.002536 0.117473 0.164664 -vn 1.179129 -2.635422 -2.952045 -v 0.000913 0.117515 0.163581 -vn -1.823849 -3.551316 2.373188 -v -0.005122 0.117299 0.169106 -vn 0.306441 -2.821266 -3.224257 -v -0.001000 0.117530 0.163201 -vn -0.958853 -3.568557 2.813595 -v -0.007910 0.117355 0.167687 -vn -0.245726 -3.418293 2.990818 -v -0.011000 0.117374 0.167197 -vn 3.111411 3.347375 -0.175630 -v -0.022000 0.139709 0.159065 -vn -3.088078 2.861683 0.518905 -v -0.025000 0.139514 0.164061 -vn 2.846668 3.577716 -1.039966 -v -0.021619 0.139634 0.160977 -vn 2.178760 3.616822 -2.038820 -v -0.020536 0.139571 0.162598 -vn -3.122242 3.286533 0.374584 -v -0.001000 0.138966 0.178050 -vn 3.111415 2.954975 -0.190986 -v 0.004000 0.139318 0.169057 -vn 2.846669 2.792919 -1.070691 -v 0.003619 0.139393 0.167145 -vn -2.510311 3.381752 1.957650 -v -0.002910 0.139196 0.172177 -vn -2.951063 3.415595 1.093308 -v -0.001489 0.139087 0.174963 -vn -2.628006 2.556631 1.618531 -v -0.024464 0.139435 0.166060 -vn -1.517271 2.513179 2.728390 -v -0.023000 0.139378 0.167523 -vn 1.179147 3.642947 -2.706249 -v -0.018913 0.139528 0.163681 -vn -0.406551 2.756779 3.198360 -v -0.021000 0.139357 0.168058 -vn 0.306454 3.457116 -2.978448 -v -0.017000 0.139514 0.164061 -vn -0.245724 3.173998 3.248906 -v -0.011000 0.139357 0.168058 -vn 0.306442 3.064714 -2.993815 -v -0.001000 0.139514 0.164061 -vn -0.958850 3.337657 3.083979 -v -0.007910 0.139338 0.168547 -vn -1.823842 3.354902 2.643578 -v -0.005122 0.139282 0.169967 -vn 1.179132 2.858155 -2.736959 -v 0.000913 0.139499 0.164442 -vn 2.178761 2.832025 -2.069557 -v 0.002536 0.139456 0.165525 -vn -3.665191 -0.118730 3.032222 -v -0.025000 0.137543 0.137714 -vn 3.665191 -0.118730 3.032222 -v -0.022000 0.137543 0.137714 -vn -3.665180 -1.618922 2.566630 -v -0.025000 0.138161 0.137906 -vn 3.665180 -1.618922 2.566629 -v -0.022000 0.138161 0.137906 -vn -3.665203 -2.685334 1.413301 -v -0.025000 0.138600 0.138381 -vn 3.665203 -2.685334 1.413301 -v -0.022000 0.138600 0.138381 -vn -3.665191 -3.032222 -0.118730 -v -0.025000 0.138743 0.139012 -vn 3.665191 -3.032222 -0.118730 -v -0.022000 0.138743 0.139012 -vn -3.665180 -2.566630 -1.618922 -v -0.025000 0.138551 0.139630 -vn 3.665180 -2.566629 -1.618922 -v -0.022000 0.138551 0.139630 -vn -3.665203 -1.413301 -2.685334 -v -0.025000 0.138076 0.140069 -vn 3.665203 -1.413301 -2.685334 -v -0.022000 0.138076 0.140069 -vn -3.665192 0.118730 -3.032222 -v -0.025000 0.137445 0.140212 -vn 3.665191 0.118730 -3.032222 -v -0.022000 0.137445 0.140212 -vn -3.665179 1.618922 -2.566630 -v -0.025000 0.136827 0.140020 -vn 3.665180 1.618922 -2.566629 -v -0.022000 0.136827 0.140020 -vn -3.665206 2.685334 -1.413301 -v -0.025000 0.136388 0.139545 -vn 3.665206 2.685334 -1.413301 -v -0.022000 0.136388 0.139545 -vn -3.665188 3.032222 0.118730 -v -0.025000 0.136245 0.138914 -vn 3.665191 3.032222 0.118730 -v -0.022000 0.136245 0.138914 -vn -3.665180 2.566630 1.618922 -v -0.025000 0.136437 0.138296 -vn 3.665180 2.566629 1.618922 -v -0.022000 0.136437 0.138296 -vn -3.665203 1.413301 2.685334 -v -0.025000 0.136912 0.137857 -vn 3.665205 1.413301 2.685334 -v -0.022000 0.136912 0.137857 -vn -3.665190 -0.118712 3.032223 -v -0.025000 0.129236 0.145395 -vn 3.665197 -0.118712 3.032224 -v -0.022000 0.129236 0.145395 -vn -3.665204 -1.618930 2.566613 -v -0.025000 0.129854 0.145587 -vn 3.665204 -1.618930 2.566613 -v -0.022000 0.129854 0.145587 -vn -3.665164 -2.685345 1.413316 -v -0.025000 0.130293 0.146062 -vn 3.665166 -2.685345 1.413315 -v -0.022000 0.130293 0.146062 -vn -3.665214 -3.032214 -0.118696 -v -0.025000 0.130436 0.146693 -vn 3.665214 -3.032215 -0.118696 -v -0.022000 0.130436 0.146693 -vn -3.665180 -2.566630 -1.618922 -v -0.025000 0.130244 0.147311 -vn 3.665180 -2.566629 -1.618922 -v -0.022000 0.130244 0.147311 -vn -3.665203 -1.413301 -2.685334 -v -0.025000 0.129769 0.147750 -vn 3.665203 -1.413301 -2.685334 -v -0.022000 0.129769 0.147750 -vn -3.665191 0.118730 -3.032222 -v -0.025000 0.129138 0.147893 -vn 3.665191 0.118730 -3.032222 -v -0.022000 0.129138 0.147893 -vn -3.665180 1.618922 -2.566630 -v -0.025000 0.128520 0.147701 -vn 3.665180 1.618922 -2.566629 -v -0.022000 0.128520 0.147701 -vn -3.665203 2.685334 -1.413301 -v -0.025000 0.128081 0.147226 -vn 3.665203 2.685334 -1.413301 -v -0.022000 0.128081 0.147226 -vn -3.665191 3.032222 0.118730 -v -0.025000 0.127938 0.146595 -vn 3.665191 3.032222 0.118730 -v -0.022000 0.127938 0.146595 -vn -3.665180 2.566630 1.618922 -v -0.025000 0.128130 0.145977 -vn 3.665179 2.566629 1.618922 -v -0.022000 0.128130 0.145977 -vn -3.665199 1.413308 2.685333 -v -0.025000 0.128605 0.145538 -vn 3.665200 1.413308 2.685332 -v -0.022000 0.128605 0.145538 -vn -3.665190 -0.118721 3.032223 -v -0.025000 0.121555 0.137088 -vn 3.665190 -0.118721 3.032223 -v -0.022000 0.121555 0.137088 -vn -3.665192 -1.618926 2.566621 -v -0.025000 0.122173 0.137280 -vn 3.665192 -1.618926 2.566621 -v -0.022000 0.122173 0.137280 -vn -3.665182 -2.685339 1.413308 -v -0.025000 0.122612 0.137755 -vn 3.665184 -2.685339 1.413308 -v -0.022000 0.122612 0.137755 -vn -3.665202 -3.032218 -0.118713 -v -0.025000 0.122755 0.138386 -vn 3.665202 -3.032218 -0.118713 -v -0.022000 0.122755 0.138386 -vn -3.665183 -2.566630 -1.618922 -v -0.025000 0.122563 0.139004 -vn 3.665180 -2.566629 -1.618922 -v -0.022000 0.122563 0.139004 -vn -3.665203 -1.413301 -2.685334 -v -0.025000 0.122088 0.139443 -vn 3.665205 -1.413301 -2.685334 -v -0.022000 0.122088 0.139443 -vn -3.665191 0.118730 -3.032222 -v -0.025000 0.121457 0.139586 -vn 3.665191 0.118730 -3.032222 -v -0.022000 0.121457 0.139586 -vn -3.665180 1.618922 -2.566630 -v -0.025000 0.120839 0.139394 -vn 3.665181 1.618922 -2.566629 -v -0.022000 0.120839 0.139394 -vn -3.665203 2.685334 -1.413301 -v -0.025000 0.120400 0.138919 -vn 3.665203 2.685334 -1.413301 -v -0.022000 0.120400 0.138919 -vn -3.665191 3.032222 0.118730 -v -0.025000 0.120257 0.138288 -vn 3.665191 3.032222 0.118730 -v -0.022000 0.120257 0.138288 -vn -3.665180 2.566630 1.618922 -v -0.025000 0.120449 0.137670 -vn 3.665180 2.566629 1.618922 -v -0.022000 0.120449 0.137670 -vn -3.665200 1.413304 2.685333 -v -0.025000 0.120924 0.137231 -vn 3.665200 1.413304 2.685333 -v -0.022000 0.120924 0.137231 -vn -3.665191 -0.118730 3.032222 -v -0.025000 0.129862 0.129407 -vn 3.665191 -0.118730 3.032222 -v -0.022000 0.129862 0.129407 -vn -3.665180 -1.618922 2.566630 -v -0.025000 0.130480 0.129599 -vn 3.665180 -1.618922 2.566629 -v -0.022000 0.130480 0.129599 -vn -3.665203 -2.685334 1.413301 -v -0.025000 0.130919 0.130074 -vn 3.665203 -2.685334 1.413301 -v -0.022000 0.130919 0.130074 -vn -3.665191 -3.032222 -0.118730 -v -0.025000 0.131062 0.130705 -vn 3.665191 -3.032222 -0.118730 -v -0.022000 0.131062 0.130705 -vn -3.665180 -2.566630 -1.618922 -v -0.025000 0.130870 0.131323 -vn 3.665180 -2.566629 -1.618922 -v -0.022000 0.130870 0.131323 -vn -3.665204 -1.413301 -2.685334 -v -0.025000 0.130395 0.131762 -vn 3.665206 -1.413301 -2.685334 -v -0.022000 0.130395 0.131762 -vn -3.665198 0.118730 -3.032222 -v -0.025000 0.129764 0.131905 -vn 3.665191 0.118730 -3.032222 -v -0.022000 0.129764 0.131905 -vn -3.665179 1.618922 -2.566630 -v -0.025000 0.129146 0.131713 -vn 3.665182 1.618922 -2.566629 -v -0.022000 0.129146 0.131713 -vn -3.665203 2.685334 -1.413301 -v -0.025000 0.128707 0.131238 -vn 3.665203 2.685334 -1.413301 -v -0.022000 0.128707 0.131238 -vn -3.665191 3.032222 0.118730 -v -0.025000 0.128564 0.130607 -vn 3.665191 3.032222 0.118730 -v -0.022000 0.128564 0.130607 -vn -3.665180 2.566630 1.618922 -v -0.025000 0.128756 0.129989 -vn 3.665180 2.566629 1.618922 -v -0.022000 0.128756 0.129989 -vn -3.665203 1.413301 2.685334 -v -0.025000 0.129231 0.129550 -vn 3.665203 1.413301 2.685334 -v -0.022000 0.129231 0.129550 -vn -6.283184 -0.000665 -0.000790 -v -0.001000 0.116574 0.213201 -vn -6.283199 0.006436 -0.002588 -v -0.001000 0.136558 0.213984 -vn 6.283184 0.000725 -0.000735 -v 0.004000 0.136526 0.214818 -vn 6.283177 -0.007493 -0.009292 -v 0.004000 0.116541 0.214036 -vn -0.272763 3.086760 -2.999270 -v -0.020670 0.131171 0.223781 -vn -0.245732 3.418298 -2.990813 -v -0.011000 0.131171 0.223781 -vn -0.272763 -2.842820 -3.231418 -v -0.020670 0.121178 0.223389 -vn -0.245732 -3.174003 -3.248912 -v -0.011000 0.121178 0.223389 -vn -1.570796 1.508142 1.631046 -v -0.025000 0.130682 0.236271 -vn -1.570796 1.631047 -1.508142 -v -0.025000 0.130877 0.231275 -vn -1.570796 -1.631046 1.508142 -v -0.025000 0.120689 0.235880 -vn -1.570796 -1.508143 -1.631046 -v -0.025000 0.120885 0.230884 -vn 1.570793 -4.647329 -1.753950 -v 0.007000 0.120885 0.230884 -vn -1.570797 -4.647330 -1.753950 -v 0.004000 0.120494 0.240876 -vn -1.570811 -4.770233 1.385235 -v 0.004000 0.120611 0.237878 -vn 1.570796 -4.770233 1.385238 -v 0.007000 0.120689 0.235880 -vn 1.570801 -4.647329 -1.753946 -v 0.007000 0.120494 0.240876 -vn 0.272764 -3.086761 2.999265 -v 0.005670 0.120396 0.243374 -vn -0.155115 -6.273299 -0.090374 -v -0.006000 0.120983 0.228385 -vn -0.884634 -3.283951 -3.117309 -v -0.007910 0.121198 0.222900 -vn -1.610764 -3.130615 -3.031495 -v -0.006000 0.121231 0.222051 -vn 1.570795 -4.647330 -1.753952 -v -0.001000 0.120494 0.240876 -vn -1.570795 -4.647329 -1.753952 -v -0.005000 0.120494 0.240876 -vn 1.570798 -4.770233 1.385237 -v -0.001000 0.120611 0.237878 -vn -1.570798 -4.770232 1.385237 -v -0.005000 0.120611 0.237878 -vn 1.058172 -2.904125 2.795832 -v 0.007380 0.120408 0.243073 -vn 1.988699 -2.883111 2.258990 -v 0.008884 0.120442 0.242205 -vn 1.203295 -0.850043 -0.594814 -v 0.010000 0.120494 0.240876 -vn 1.570796 -1.508142 -1.631046 -v 0.010000 0.120885 0.230884 -vn 1.570796 -1.631046 1.508142 -v 0.010000 0.120689 0.235880 -vn -0.272765 -3.086762 2.999265 -v -0.020670 0.120396 0.243374 -vn 1.570795 -4.647329 -1.753952 -v -0.010000 0.120494 0.240876 -vn -1.203297 -0.893945 0.526535 -v -0.025000 0.121081 0.225887 -vn -1.988697 -2.697671 -2.477479 -v -0.023884 0.121133 0.224558 -vn -1.570797 -4.770233 1.385236 -v -0.022000 0.121081 0.225887 -vn -1.058163 -2.676649 -3.014309 -v -0.022380 0.121167 0.223691 -vn -1.570795 -4.647330 -1.753952 -v -0.014000 0.120494 0.240876 -vn -1.570798 -4.770233 1.385238 -v -0.014000 0.120611 0.237878 -vn 1.570798 -4.770233 1.385237 -v -0.010000 0.120611 0.237878 -vn 1.570800 -4.770234 1.385238 -v -0.019000 0.120611 0.237878 -vn -1.570796 -4.647330 -1.753948 -v -0.022000 0.120885 0.230884 -vn 3.337940 -3.121017 0.184487 -v 0.007000 0.120983 0.228385 -vn -1.058168 -2.904124 2.795817 -v -0.022380 0.120408 0.243073 -vn -1.570799 -4.647330 -1.753946 -v -0.022000 0.120494 0.240876 -vn -1.988699 -2.883111 2.258990 -v -0.023884 0.120442 0.242205 -vn -1.203295 -0.850043 -0.594813 -v -0.025000 0.120494 0.240876 -vn -1.570788 -4.770233 1.385234 -v -0.022000 0.120689 0.235880 -vn 1.570795 -4.647329 -1.753952 -v -0.019000 0.120494 0.240876 -vn 1.570796 1.631045 -1.508142 -v 0.010000 0.130877 0.231275 -vn 1.570796 1.508142 1.631046 -v 0.010000 0.130682 0.236271 -vn -1.988682 2.883111 -2.258977 -v -0.023884 0.131125 0.224949 -vn -1.203294 0.850043 0.594813 -v -0.025000 0.131073 0.226279 -vn -1.058168 2.904125 -2.795829 -v -0.022380 0.131159 0.224082 -vn -1.570795 4.647330 1.753935 -v -0.022000 0.131073 0.226279 -vn 1.570798 4.647329 1.753947 -v -0.010000 0.130604 0.238269 -vn -1.570797 4.647330 1.753947 -v -0.005000 0.130604 0.238269 -vn -0.272763 2.842819 3.231428 -v -0.020670 0.130388 0.243765 -vn 0.272760 2.842821 3.231430 -v 0.005670 0.130388 0.243765 -vn 1.570795 4.770234 -1.385230 -v -0.010000 0.130486 0.241267 -vn -1.570795 4.770233 -1.385230 -v -0.005000 0.130486 0.241267 -vn 1.570797 4.647330 1.753947 -v -0.001000 0.130604 0.238269 -vn -1.570799 4.647329 1.753949 -v 0.004000 0.130604 0.238269 -vn -0.151771 6.262181 0.390012 -v -0.006000 0.130975 0.228777 -vn -1.771037 3.399766 -2.685784 -v -0.006000 0.131223 0.222442 -vn -0.884629 3.517619 -2.851016 -v -0.007910 0.131190 0.223291 -vn 1.570801 4.647329 1.753948 -v -0.019000 0.130604 0.238269 -vn -1.570797 4.647329 1.753949 -v -0.014000 0.130604 0.238269 -vn -1.570796 4.770234 -1.385237 -v -0.022000 0.130877 0.231275 -vn 1.570786 4.770234 -1.385244 -v 0.007000 0.130877 0.231275 -vn 3.337945 3.097039 0.427936 -v 0.007000 0.130975 0.228777 -vn 1.570795 4.770233 -1.385230 -v -0.001000 0.130486 0.241267 -vn -1.570791 4.647330 1.753947 -v -0.022000 0.130682 0.236271 -vn 1.058158 2.676650 3.014301 -v 0.007380 0.130400 0.243464 -vn 1.570797 4.770233 -1.385230 -v 0.007000 0.130486 0.241267 -vn 1.988706 2.697670 2.477494 -v 0.008884 0.130434 0.242596 -vn 1.203293 0.893945 -0.526533 -v 0.010000 0.130486 0.241267 -vn 1.570791 4.647329 1.753947 -v 0.007000 0.130682 0.236271 -vn -1.570795 4.770233 -1.385230 -v 0.004000 0.130486 0.241267 -vn 1.570796 4.770233 -1.385229 -v -0.019000 0.130486 0.241267 -vn -1.058139 2.676652 3.014244 -v -0.022380 0.130400 0.243464 -vn -1.988702 2.697671 2.477494 -v -0.023884 0.130434 0.242596 -vn -1.570800 4.770233 -1.385224 -v -0.022000 0.130486 0.241267 -vn -1.203293 0.893945 -0.526533 -v -0.025000 0.130486 0.241267 -vn -1.570795 4.770233 -1.385230 -v -0.014000 0.130486 0.241267 -vn 6.280872 0.073088 -0.072905 -v 0.004000 0.136513 0.214834 -vn 6.236260 0.491082 -0.386448 -v 0.004116 0.135395 0.216296 -vn 6.280220 -0.025933 -0.091351 -v 0.004000 0.116552 0.214052 -vn 6.243485 -0.428211 -0.360060 -v 0.004116 0.117553 0.215597 -vn 5.336203 -1.902575 -1.566633 -v 0.005300 0.119708 0.219094 -vn 5.718535 -1.498164 -1.223674 -v 0.004661 0.118884 0.217705 -vn 6.040575 1.053195 -0.857983 -v 0.004437 0.134368 0.217660 -vn 5.941192 -1.186947 -0.929798 -v 0.004474 0.118544 0.217157 -vn 6.110539 -0.852641 -0.688439 -v 0.004231 0.117957 0.216228 -vn 5.613153 1.734997 -1.205099 -v 0.004955 0.133422 0.218965 -vn 5.251211 2.038879 -1.536945 -v 0.005300 0.132972 0.219613 -vn 4.752012 -2.292428 -1.869833 -v 0.005851 0.120195 0.219979 -vn 4.755753 2.425912 -1.677524 -v 0.005852 0.132417 0.220459 -vn 4.369721 -2.497417 -2.137085 -v 0.006085 0.120361 0.220302 -vn 4.408307 2.631042 -1.902908 -v 0.006019 0.132279 0.220682 -vn 3.961887 2.836441 -2.181245 -v 0.006881 0.131726 0.221658 -vn 2.950507 3.034909 -2.361631 -v 0.008008 0.131316 0.222626 -vn 2.958457 -2.841879 -2.562739 -v 0.008008 0.121125 0.222227 -vn 3.526523 2.984350 -2.363442 -v 0.007083 0.131629 0.221854 -vn 3.329995 -2.870802 -2.478583 -v 0.007083 0.120873 0.221433 -vn 3.656978 2.912490 -2.335618 -v 0.006994 0.131670 0.221769 -vn 3.902178 -2.677768 -2.355609 -v 0.006994 0.120838 0.221345 -vn -3.958998 -2.657747 -2.371693 -v -0.003881 0.120824 0.220396 -vn -3.752781 2.966984 -2.179661 -v -0.003994 0.131703 0.220934 -vn -4.397484 -2.509388 -2.089699 -v -0.003019 0.120349 0.219379 -vn -4.727500 -2.313022 -1.880295 -v -0.002908 0.120270 0.219226 -vn -3.574775 -2.767256 -2.543889 -v -0.003994 0.120871 0.220510 -vn -2.925300 -2.968403 -2.627720 -v -0.004886 0.121134 0.221299 -vn -2.780735 3.233277 -2.486644 -v -0.004986 0.131353 0.221776 -vn -2.426924 -3.028720 -2.817678 -v -0.005121 0.121175 0.221477 -vn -2.000492 -3.054191 -2.995931 -v -0.005854 0.121232 0.221965 -vn -4.350800 2.664408 -1.919615 -v -0.003085 0.132260 0.219932 -vn -4.726948 2.447447 -1.697243 -v -0.002907 0.132403 0.219699 -vn -5.240529 -1.927821 -1.691830 -v -0.002300 0.119741 0.218260 -vn -5.331386 2.026882 -1.416749 -v -0.002300 0.133005 0.218779 -vn -5.612907 -1.636383 -1.332757 -v -0.001955 0.119344 0.217578 -vn -6.038344 -0.991962 -0.934707 -v -0.001437 0.118502 0.216203 -vn -5.712102 1.596606 -1.105857 -v -0.001661 0.133936 0.217459 -vn -5.949814 1.229627 -0.863506 -v -0.001488 0.134284 0.216983 -vn -6.236276 -0.459485 -0.421822 -v -0.001116 0.117586 0.214763 -vn -6.126577 0.840707 -0.665807 -v -0.001231 0.134975 0.216059 -vn -6.243556 0.451507 -0.340897 -v -0.001116 0.135427 0.215462 -vn -6.280872 -0.067164 -0.078388 -v -0.001000 0.116584 0.213218 -vn -6.280802 0.086986 -0.055894 -v -0.001000 0.136546 0.214000 -vn 3.955261 -4.083839 1.009390 -v 0.007000 0.120664 0.225871 -vn 3.236864 -2.941082 0.996736 -v 0.007000 0.120644 0.226371 -vn 2.160870 -5.003714 1.938194 -v 0.005464 0.119658 0.224795 -vn 3.240946 -1.485395 3.178116 -v 0.004096 0.117153 0.223328 -vn 2.975606 -3.147073 2.809260 -v 0.004381 0.118079 0.223649 -vn 0.946099 -3.107987 3.193694 -v 0.007087 0.120700 0.225873 -vn -3.240417 -1.468494 3.240502 -v -0.001096 0.117153 0.223328 -vn -2.968677 -3.156740 2.827169 -v -0.001381 0.118079 0.223649 -vn -0.945858 -6.093443 0.695940 -v -0.004087 0.120677 0.226459 -vn -2.149551 -5.023180 1.928387 -v -0.002464 0.119658 0.224795 -vn 3.347360 -3.019872 0.803666 -v 0.007000 0.120677 0.226459 -vn -2.173243 4.837698 2.293292 -v -0.002464 0.132577 0.225301 -vn -2.975201 2.915502 3.059340 -v -0.001381 0.134240 0.224282 -vn -3.238325 1.233759 3.312802 -v -0.001096 0.135189 0.224034 -vn -0.991614 6.013230 1.135320 -v -0.004087 0.131430 0.226880 -vn 3.347301 2.947828 1.037243 -v 0.007000 0.131430 0.226880 -vn 3.235782 2.854436 1.223231 -v 0.007000 0.131471 0.226795 -vn 3.240395 1.207253 3.353158 -v 0.004096 0.135189 0.224034 -vn 2.152448 4.836104 2.336268 -v 0.005464 0.132577 0.225301 -vn 2.969953 2.924090 3.063112 -v 0.004381 0.134240 0.224282 -vn 0.925834 2.852505 3.446238 -v 0.007087 0.131453 0.226294 -vn 3.956742 3.991189 1.330125 -v 0.007000 0.131490 0.226295 -# 324 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 17//17 18//18 19//19 -f 17//17 19//19 20//20 -f 20//20 19//19 21//21 -f 20//20 21//21 22//22 -f 22//22 21//21 23//23 -f 22//22 23//23 24//24 -f 24//24 23//23 25//25 -f 24//24 25//25 26//26 -f 26//26 25//25 27//27 -f 26//26 27//27 28//28 -f 28//28 27//27 29//29 -f 28//28 29//29 30//30 -f 30//30 29//29 31//31 -f 30//30 31//31 32//32 -f 32//32 31//31 33//33 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 34//34 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 38//38 -f 39//39 38//38 37//37 -f 40//40 16//16 14//14 -f 37//37 41//41 39//39 -f 39//39 41//41 42//42 -f 39//39 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 14//14 49//49 40//40 -f 40//40 49//49 50//50 -f 40//40 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 54//54 52//52 55//55 -f 54//54 55//55 56//56 -f 56//56 55//55 57//57 -f 56//56 57//57 48//48 -f 48//48 57//57 58//58 -f 48//48 58//58 47//47 -f 18//18 17//17 59//59 -f 59//59 17//17 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 12//12 10//10 63//63 -f 63//63 10//10 64//64 -f 65//65 66//66 64//64 -f 64//64 66//66 67//67 -f 64//64 67//67 63//63 -f 60//60 68//68 62//62 -f 62//62 68//68 69//69 -f 62//62 69//69 70//70 -f 70//70 69//69 71//71 -f 70//70 71//71 72//72 -f 72//72 71//71 73//73 -f 72//72 73//73 74//74 -f 73//73 75//75 74//74 -f 74//74 75//75 76//76 -f 74//74 76//76 77//77 -f 77//77 76//76 66//66 -f 77//77 66//66 78//78 -f 78//78 66//66 65//65 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 79//79 -f 79//79 102//102 80//80 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 103//103 -f 103//103 126//126 104//104 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 131//131 -f 131//131 130//130 132//132 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 141//141 -f 141//141 140//140 142//142 -f 141//141 142//142 143//143 -f 143//143 142//142 144//144 -f 143//143 144//144 145//145 -f 145//145 144//144 146//146 -f 145//145 146//146 147//147 -f 147//147 146//146 148//148 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 127//127 -f 127//127 150//150 128//128 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 158//158 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 151//151 -f 151//151 174//174 152//152 -f 29//29 27//27 152//152 -f 118//118 116//116 41//41 -f 35//35 33//33 128//128 -f 128//128 150//150 35//35 -f 35//35 150//150 148//148 -f 35//35 148//148 37//37 -f 41//41 116//116 59//59 -f 116//116 114//114 59//59 -f 59//59 114//114 112//112 -f 59//59 112//112 18//18 -f 19//19 82//82 21//21 -f 21//21 82//82 80//80 -f 21//21 80//80 23//23 -f 23//23 80//80 102//102 -f 23//23 102//102 25//25 -f 25//25 102//102 27//27 -f 126//126 33//33 31//31 -f 126//126 31//31 104//104 -f 148//148 146//146 37//37 -f 37//37 146//146 144//144 -f 37//37 144//144 142//142 -f 142//142 124//124 37//37 -f 37//37 124//124 122//122 -f 37//37 122//122 41//41 -f 41//41 122//122 120//120 -f 41//41 120//120 118//118 -f 160//160 102//102 162//162 -f 162//162 102//102 100//100 -f 162//162 100//100 98//98 -f 160//160 158//158 102//102 -f 102//102 158//158 156//156 -f 102//102 156//156 27//27 -f 27//27 156//156 154//154 -f 27//27 154//154 152//152 -f 152//152 174//174 29//29 -f 29//29 174//174 172//172 -f 29//29 172//172 31//31 -f 31//31 172//172 170//170 -f 31//31 170//170 104//104 -f 104//104 170//170 168//168 -f 104//104 168//168 166//166 -f 92//92 90//90 108//108 -f 108//108 90//90 18//18 -f 108//108 18//18 110//110 -f 110//110 18//18 112//112 -f 136//136 126//126 138//138 -f 138//138 126//126 124//124 -f 138//138 124//124 140//140 -f 140//140 124//124 142//142 -f 136//136 134//134 126//126 -f 126//126 134//134 132//132 -f 126//126 132//132 33//33 -f 33//33 132//132 130//130 -f 33//33 130//130 128//128 -f 106//106 104//104 96//96 -f 96//96 104//104 166//166 -f 96//96 166//166 98//98 -f 98//98 166//166 164//164 -f 98//98 164//164 162//162 -f 90//90 88//88 18//18 -f 18//18 88//88 86//86 -f 18//18 86//86 19//19 -f 19//19 86//86 84//84 -f 19//19 84//84 82//82 -f 106//106 96//96 108//108 -f 108//108 96//96 94//94 -f 108//108 94//94 92//92 -f 56//56 48//48 74//74 -f 74//74 48//48 72//72 -f 47//47 58//58 71//71 -f 71//71 58//58 73//73 -f 14//14 13//13 175//175 -f 11//11 12//12 176//176 -f 176//176 12//12 63//63 -f 176//176 63//63 175//175 -f 175//175 63//63 49//49 -f 175//175 49//49 14//14 -f 10//10 9//9 177//177 -f 15//15 16//16 178//178 -f 178//178 16//16 40//40 -f 178//178 40//40 177//177 -f 177//177 40//40 64//64 -f 177//177 64//64 10//10 -f 73//73 58//58 75//75 -f 75//75 58//58 57//57 -f 75//75 57//57 76//76 -f 76//76 57//57 55//55 -f 76//76 55//55 66//66 -f 66//66 55//55 52//52 -f 66//66 52//52 67//67 -f 67//67 52//52 50//50 -f 67//67 50//50 63//63 -f 63//63 50//50 49//49 -f 56//56 74//74 77//77 -f 56//56 77//77 54//54 -f 54//54 77//77 78//78 -f 54//54 78//78 53//53 -f 53//53 78//78 65//65 -f 53//53 65//65 51//51 -f 51//51 65//65 64//64 -f 51//51 64//64 40//40 -f 72//72 48//48 70//70 -f 70//70 48//48 46//46 -f 70//70 46//46 62//62 -f 62//62 46//46 44//44 -f 62//62 44//44 61//61 -f 61//61 44//44 42//42 -f 61//61 42//42 59//59 -f 59//59 42//42 41//41 -f 39//39 139//139 141//141 -f 119//119 39//39 117//117 -f 117//117 39//39 115//115 -f 39//39 141//141 38//38 -f 141//141 143//143 38//38 -f 38//38 143//143 145//145 -f 38//38 145//145 36//36 -f 30//30 32//32 169//169 -f 17//17 20//20 83//83 -f 83//83 85//85 17//17 -f 17//17 85//85 87//87 -f 17//17 87//87 60//60 -f 60//60 87//87 89//89 -f 60//60 89//89 91//91 -f 115//115 39//39 113//113 -f 113//113 39//39 60//60 -f 113//113 60//60 111//111 -f 169//169 171//171 30//30 -f 30//30 171//171 173//173 -f 30//30 173//173 28//28 -f 28//28 173//173 151//151 -f 28//28 151//151 153//153 -f 153//153 155//155 28//28 -f 28//28 155//155 101//101 -f 28//28 101//101 26//26 -f 26//26 101//101 24//24 -f 24//24 101//101 22//22 -f 22//22 101//101 79//79 -f 22//22 79//79 20//20 -f 20//20 79//79 81//81 -f 20//20 81//81 83//83 -f 145//145 147//147 36//36 -f 36//36 147//147 149//149 -f 36//36 149//149 34//34 -f 34//34 149//149 127//127 -f 34//34 127//127 32//32 -f 32//32 127//127 129//129 -f 32//32 129//129 169//169 -f 121//121 123//123 163//163 -f 163//163 123//123 125//125 -f 139//139 39//39 137//137 -f 137//137 39//39 119//119 -f 137//137 119//119 135//135 -f 135//135 119//119 121//121 -f 135//135 121//121 133//133 -f 133//133 121//121 163//163 -f 133//133 163//163 131//131 -f 131//131 163//163 165//165 -f 131//131 165//165 129//129 -f 129//129 165//165 167//167 -f 129//129 167//167 169//169 -f 155//155 157//157 101//101 -f 101//101 157//157 159//159 -f 101//101 159//159 99//99 -f 99//99 159//159 161//161 -f 99//99 161//161 97//97 -f 111//111 60//60 109//109 -f 109//109 60//60 91//91 -f 109//109 91//91 107//107 -f 107//107 91//91 93//93 -f 107//107 93//93 105//105 -f 105//105 93//93 95//95 -f 105//105 95//95 103//103 -f 103//103 95//95 97//97 -f 103//103 97//97 125//125 -f 125//125 97//97 161//161 -f 125//125 161//161 163//163 -f 60//60 39//39 43//43 -f 60//60 43//43 68//68 -f 68//68 43//43 45//45 -f 68//68 45//45 69//69 -f 69//69 45//45 47//47 -f 69//69 47//47 71//71 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 183//183 184//184 185//185 -f 185//185 184//184 186//186 -f 187//187 188//188 189//189 -f 190//190 191//191 192//192 -f 181//181 182//182 193//193 -f 193//193 182//182 194//194 -f 193//193 194//194 195//195 -f 196//196 197//197 198//198 -f 198//198 197//197 199//199 -f 200//200 192//192 201//201 -f 201//201 192//192 191//191 -f 201//201 191//191 202//202 -f 203//203 204//204 187//187 -f 187//187 204//204 190//190 -f 187//187 190//190 188//188 -f 188//188 190//190 192//192 -f 188//188 192//192 196//196 -f 196//196 192//192 205//205 -f 196//196 205//205 197//197 -f 197//197 205//205 206//206 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 181//181 -f 211//211 212//212 213//213 -f 214//214 186//186 212//212 -f 212//212 186//186 215//215 -f 212//212 215//215 213//213 -f 213//213 215//215 209//209 -f 213//213 209//209 199//199 -f 199//199 209//209 181//181 -f 199//199 181//181 198//198 -f 198//198 181//181 193//193 -f 198//198 193//193 189//189 -f 189//189 193//193 216//216 -f 189//189 216//216 187//187 -f 205//205 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 185//185 186//186 221//221 -f 221//221 186//186 214//214 -f 221//221 214//214 218//218 -f 218//218 214//214 222//222 -f 218//218 222//222 205//205 -f 205//205 222//222 211//211 -f 205//205 211//211 206//206 -f 206//206 211//211 213//213 -f 223//223 224//224 203//203 -f 203//203 224//224 204//204 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 179//179 -f 179//179 228//228 229//229 -f 179//179 229//229 230//230 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 235//235 236//236 223//223 -f 237//237 238//238 239//239 -f 240//240 241//241 242//242 -f 223//223 243//243 235//235 -f 235//235 243//243 244//244 -f 235//235 244//244 237//237 -f 239//239 180//180 237//237 -f 237//237 180//180 179//179 -f 237//237 179//179 235//235 -f 235//235 179//179 230//230 -f 235//235 230//230 245//245 -f 184//184 183//183 246//246 -f 232//232 247//247 248//248 -f 248//248 247//247 249//249 -f 248//248 249//249 250//250 -f 224//224 223//223 251//251 -f 251//251 223//223 236//236 -f 251//251 236//236 248//248 -f 248//248 236//236 252//252 -f 248//248 252//252 232//232 -f 232//232 252//252 245//245 -f 232//232 245//245 234//234 -f 234//234 245//245 230//230 -f 242//242 184//184 240//240 -f 240//240 184//184 246//246 -f 240//240 246//246 253//253 -f 254//254 231//231 255//255 -f 255//255 231//231 256//256 -f 255//255 256//256 257//257 -f 228//228 242//242 229//229 -f 229//229 242//242 241//241 -f 229//229 241//241 233//233 -f 233//233 241//241 258//258 -f 233//233 258//258 231//231 -f 231//231 258//258 253//253 -f 231//231 253//253 256//256 -f 256//256 253//253 246//246 -f 232//232 231//231 192//192 -f 192//192 231//231 205//205 -f 177//177 259//259 178//178 -f 178//178 259//259 260//260 -f 178//178 260//260 261//261 -f 261//261 260//260 262//262 -f 263//263 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 260//260 -f 260//260 266//266 267//267 -f 260//260 267//267 262//262 -f 265//265 268//268 263//263 -f 263//263 268//268 269//269 -f 263//263 269//269 270//270 -f 270//270 269//269 271//271 -f 270//270 271//271 272//272 -f 272//272 271//271 273//273 -f 272//272 273//273 274//274 -f 275//275 276//276 277//277 -f 277//277 276//276 278//278 -f 274//274 279//279 272//272 -f 272//272 279//279 277//277 -f 272//272 277//277 280//280 -f 280//280 277//277 278//278 -f 182//182 180//180 194//194 -f 194//194 180//180 239//239 -f 194//194 239//239 195//195 -f 195//195 239//239 238//238 -f 281//281 282//282 283//283 -f 283//283 282//282 284//284 -f 281//281 285//285 282//282 -f 282//282 285//285 286//286 -f 282//282 286//286 287//287 -f 287//287 286//286 288//288 -f 287//287 288//288 238//238 -f 238//238 288//288 289//289 -f 238//238 289//289 195//195 -f 282//282 290//290 284//284 -f 284//284 290//290 291//291 -f 284//284 291//291 292//292 -f 292//292 291//291 293//293 -f 292//292 293//293 294//294 -f 294//294 293//293 295//295 -f 293//293 296//296 295//295 -f 295//295 296//296 297//297 -f 295//295 297//297 298//298 -f 298//298 297//297 299//299 -f 298//298 299//299 300//300 -f 175//175 301//301 176//176 -f 176//176 301//301 298//298 -f 176//176 298//298 302//302 -f 302//302 298//298 300//300 -f 303//303 304//304 305//305 -f 15//15 178//178 306//306 -f 306//306 178//178 261//261 -f 261//261 262//262 306//306 -f 306//306 262//262 267//267 -f 306//306 267//267 307//307 -f 267//267 266//266 307//307 -f 307//307 266//266 264//264 -f 307//307 264//264 305//305 -f 305//305 264//264 263//263 -f 305//305 263//263 270//270 -f 4//4 2//2 276//276 -f 276//276 2//2 308//308 -f 276//276 308//308 278//278 -f 278//278 308//308 303//303 -f 278//278 303//303 280//280 -f 280//280 303//303 305//305 -f 280//280 305//305 272//272 -f 272//272 305//305 270//270 -f 13//13 15//15 309//309 -f 309//309 15//15 306//306 -f 309//309 306//306 310//310 -f 310//310 306//306 307//307 -f 310//310 307//307 305//305 -f 304//304 311//311 305//305 -f 305//305 311//311 312//312 -f 305//305 312//312 310//310 -f 304//304 313//313 311//311 -f 311//311 313//313 216//216 -f 311//311 216//216 193//193 -f 309//309 310//310 295//295 -f 301//301 175//175 13//13 -f 309//309 295//295 13//13 -f 13//13 295//295 298//298 -f 13//13 298//298 301//301 -f 283//283 284//284 312//312 -f 312//312 284//284 292//292 -f 312//312 292//292 310//310 -f 310//310 292//292 294//294 -f 310//310 294//294 295//295 -f 288//288 286//286 311//311 -f 311//311 286//286 285//285 -f 311//311 285//285 312//312 -f 312//312 285//285 281//281 -f 312//312 281//281 283//283 -f 193//193 195//195 311//311 -f 311//311 195//195 289//289 -f 311//311 289//289 288//288 -f 11//11 176//176 302//302 -f 293//293 314//314 296//296 -f 296//296 314//314 315//315 -f 296//296 315//315 297//297 -f 297//297 315//315 316//316 -f 297//297 316//316 299//299 -f 299//299 316//316 11//11 -f 299//299 11//11 300//300 -f 300//300 11//11 302//302 -f 293//293 291//291 314//314 -f 314//314 291//291 290//290 -f 314//314 290//290 317//317 -f 238//238 237//237 287//287 -f 287//287 237//237 317//317 -f 287//287 317//317 282//282 -f 282//282 317//317 290//290 -f 237//237 244//244 318//318 -f 237//237 318//318 317//317 -f 317//317 318//318 319//319 -f 317//317 319//319 314//314 -f 320//320 9//9 11//11 -f 319//319 321//321 314//314 -f 314//314 321//321 322//322 -f 314//314 322//322 315//315 -f 315//315 322//322 320//320 -f 315//315 320//320 316//316 -f 316//316 320//320 11//11 -f 320//320 322//322 265//265 -f 323//323 6//6 5//5 -f 277//277 279//279 321//321 -f 321//321 279//279 274//274 -f 321//321 274//274 273//273 -f 5//5 275//275 323//323 -f 323//323 275//275 277//277 -f 323//323 277//277 324//324 -f 324//324 277//277 321//321 -f 324//324 321//321 319//319 -f 273//273 271//271 321//321 -f 321//321 271//271 269//269 -f 321//321 269//269 322//322 -f 322//322 269//269 268//268 -f 322//322 268//268 265//265 -f 259//259 177//177 9//9 -f 320//320 265//265 9//9 -f 9//9 265//265 260//260 -f 9//9 260//260 259//259 -f 223//223 203//203 243//243 -f 243//243 203//203 187//187 -f 323//323 324//324 303//303 -f 2//2 1//1 8//8 -f 303//303 308//308 323//323 -f 323//323 308//308 2//2 -f 323//323 2//2 6//6 -f 6//6 2//2 8//8 -f 304//304 303//303 313//313 -f 313//313 303//303 324//324 -f 313//313 324//324 319//319 -f 244//244 243//243 187//187 -f 319//319 318//318 313//313 -f 313//313 318//318 244//244 -f 313//313 244//244 216//216 -f 216//216 244//244 187//187 -f 226//226 207//207 228//228 -f 228//228 207//207 209//209 -f 228//228 209//209 242//242 -f 242//242 209//209 215//215 -f 242//242 215//215 184//184 -f 184//184 215//215 186//186 -f 234//234 197//197 233//233 -f 233//233 197//197 206//206 -f 233//233 206//206 229//229 -f 229//229 206//206 213//213 -f 229//229 213//213 230//230 -f 230//230 213//213 199//199 -f 230//230 199//199 234//234 -f 234//234 199//199 197//197 -f 235//235 198//198 236//236 -f 236//236 198//198 189//189 -f 236//236 189//189 252//252 -f 252//252 189//189 188//188 -f 252//252 188//188 245//245 -f 245//245 188//188 196//196 -f 245//245 196//196 235//235 -f 235//235 196//196 198//198 -f 256//256 218//218 257//257 -f 257//257 218//218 220//220 -f 183//183 185//185 246//246 -f 246//246 185//185 221//221 -f 246//246 221//221 256//256 -f 256//256 221//221 218//218 -f 250//250 202//202 248//248 -f 248//248 202//202 191//191 -f 248//248 191//191 251//251 -f 251//251 191//191 190//190 -f 251//251 190//190 224//224 -f 224//224 190//190 204//204 -f 240//240 214//214 241//241 -f 241//241 214//214 212//212 -f 241//241 212//212 258//258 -f 258//258 212//212 211//211 -f 258//258 211//211 253//253 -f 253//253 211//211 222//222 -f 253//253 222//222 240//240 -f 240//240 222//222 214//214 -f 276//276 275//275 4//4 -f 4//4 275//275 5//5 -f 4//4 5//5 3//3 -f 5//5 7//7 3//3 -f 3//3 7//7 8//8 -f 3//3 8//8 1//1 -f 207//207 226//226 225//225 -f 207//207 225//225 208//208 -f 208//208 225//225 227//227 -f 208//208 227//227 210//210 -f 210//210 227//227 179//179 -f 210//210 179//179 181//181 -f 202//202 250//250 249//249 -f 202//202 249//249 201//201 -f 201//201 249//249 247//247 -f 201//201 247//247 200//200 -f 200//200 247//247 232//232 -f 200//200 232//232 192//192 -f 257//257 220//220 219//219 -f 257//257 219//219 255//255 -f 255//255 219//219 217//217 -f 255//255 217//217 254//254 -f 254//254 217//217 205//205 -f 254//254 205//205 231//231 -# 672 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_G_right.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_G_right.obj deleted file mode 100644 index bd75134af..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_G_right.obj +++ /dev/null @@ -1,1336 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object hand_G_right.obj -# -# Vertices: 324 -# Faces: 672 -# -#### -vn 1.508018 -1.327634 1.083334 -v 0.010000 -0.137697 0.225909 -vn 0.281229 -3.234732 3.187505 -v 0.009000 -0.137697 0.225909 -vn 2.827938 -2.803149 -1.394675 -v 0.009403 -0.137622 0.223863 -vn 2.712388 -2.836847 -2.120487 -v 0.009000 -0.137599 0.223238 -vn 2.841714 2.970062 -1.978356 -v 0.009000 -0.127605 0.223604 -vn 0.306450 2.987257 3.449503 -v 0.009000 -0.127703 0.226274 -vn 2.827940 2.897576 -1.186060 -v 0.009403 -0.127628 0.224229 -vn 1.508022 1.244902 1.177482 -v 0.010000 -0.127703 0.226274 -vn 3.226404 0.247129 3.286918 -v 0.004000 -0.122615 0.223959 -vn 1.570799 1.512306 1.627190 -v 0.004000 -0.121616 0.223995 -vn -3.229967 0.219840 3.255608 -v -0.001000 -0.122615 0.223959 -vn -1.570800 1.512306 1.627190 -v -0.001000 -0.121616 0.223995 -vn -3.226982 -0.482346 3.256653 -v -0.001000 -0.142602 0.223227 -vn -1.570795 -1.627187 1.512302 -v -0.001000 -0.143601 0.223191 -vn 3.231266 -0.445027 3.217140 -v 0.004000 -0.142602 0.223227 -vn 1.570795 -1.627186 1.512302 -v 0.004000 -0.143601 0.223191 -vn -2.984511 3.129151 -0.131384 -v -0.025000 -0.118507 0.139052 -vn 2.984511 3.129151 -0.131384 -v -0.022000 -0.118507 0.139052 -vn 2.827435 2.984138 -0.850295 -v -0.022000 -0.118921 0.135636 -vn -2.827436 2.984138 -0.850295 -v -0.025000 -0.118921 0.135636 -vn 2.827434 2.575330 -1.730824 -v -0.022000 -0.120370 0.132514 -vn -2.827434 2.575331 -1.730824 -v -0.025000 -0.120370 0.132514 -vn 2.827435 1.914433 -2.441931 -v -0.022000 -0.122713 0.129993 -vn -2.827435 1.914433 -2.441931 -v -0.025000 -0.122713 0.129993 -vn 2.827431 1.066134 -2.914006 -v -0.022000 -0.125721 0.128320 -vn -2.827431 1.066134 -2.914006 -v -0.025000 -0.125721 0.128320 -vn 2.827433 0.113470 -3.100838 -v -0.022000 -0.129098 0.127657 -vn -2.827433 0.113471 -3.100839 -v -0.025000 -0.129098 0.127657 -vn 2.827437 -0.850292 -2.984139 -v -0.022000 -0.132514 0.128071 -vn -2.827437 -0.850292 -2.984140 -v -0.025000 -0.132514 0.128071 -vn 2.827431 -1.730825 -2.575329 -v -0.022000 -0.135636 0.129520 -vn -2.827430 -1.730825 -2.575328 -v -0.025000 -0.135636 0.129520 -vn 2.827436 -2.441933 -1.914431 -v -0.022000 -0.138157 0.131863 -vn -2.827440 -2.441933 -1.914431 -v -0.025000 -0.138157 0.131863 -vn 2.827430 -2.914005 -1.066136 -v -0.022000 -0.139830 0.134870 -vn -2.827431 -2.914006 -1.066136 -v -0.025000 -0.139830 0.134870 -vn 2.984513 -3.111180 -0.359743 -v -0.022000 -0.140493 0.138248 -vn -2.984513 -3.111179 -0.359743 -v -0.025000 -0.140493 0.138248 -vn -3.088053 -2.892734 0.300972 -v -0.025000 -0.141407 0.163231 -vn 3.111408 -2.932066 -0.413953 -v 0.004000 -0.141590 0.168228 -vn 3.111415 -3.324503 -0.428311 -v -0.022000 -0.141224 0.158234 -vn 2.846681 -3.488805 -1.307594 -v -0.021619 -0.141294 0.160146 -vn -2.627996 -2.671733 1.420521 -v -0.024464 -0.141480 0.165230 -vn 2.178752 -3.452254 -2.306545 -v -0.020536 -0.141353 0.161768 -vn -1.517278 -2.712343 2.530499 -v -0.023000 -0.141534 0.166693 -vn 1.179134 -3.427822 -2.974028 -v -0.018913 -0.141393 0.162851 -vn -0.406555 -2.990801 2.980678 -v -0.021000 -0.141553 0.167228 -vn 0.306452 -3.221928 -3.231402 -v -0.017000 -0.141407 0.163231 -vn -3.122261 -3.305452 0.124929 -v -0.001000 -0.141919 0.177222 -vn -2.951056 -3.488506 0.831837 -v -0.001489 -0.141806 0.174134 -vn 2.846683 -2.703936 -1.278873 -v 0.003619 -0.141520 0.166316 -vn -2.510307 -3.520139 1.696255 -v -0.002910 -0.141704 0.171348 -vn 2.178757 -2.667375 -2.277826 -v 0.002536 -0.141460 0.164694 -vn 1.179126 -2.642947 -2.945309 -v 0.000913 -0.141421 0.163611 -vn -1.823842 -3.545245 2.382253 -v -0.005122 -0.141623 0.169137 -vn 0.306440 -2.829494 -3.217041 -v -0.001000 -0.141407 0.163231 -vn -0.958855 -3.561357 2.822695 -v -0.007910 -0.141571 0.167717 -vn -0.245727 -3.410650 2.999521 -v -0.011000 -0.141553 0.167228 -vn 3.111407 3.346915 -0.184170 -v -0.022000 -0.119239 0.159039 -vn -3.088061 2.862999 0.511595 -v -0.025000 -0.119422 0.164036 -vn 2.846684 3.575052 -1.049096 -v -0.021619 -0.119309 0.160951 -vn 2.178754 3.611603 -2.048054 -v -0.020536 -0.119368 0.162572 -vn -3.122257 3.287480 0.366195 -v -0.001000 -0.119934 0.178026 -vn 3.111418 2.954479 -0.198535 -v 0.004000 -0.119604 0.169032 -vn 2.846686 2.790179 -1.077818 -v 0.003619 -0.119534 0.167120 -vn -2.510309 3.386742 1.949004 -v -0.002910 -0.119719 0.172152 -vn -2.951043 3.418375 1.084591 -v -0.001489 -0.119821 0.174938 -vn -2.627999 2.560757 1.611995 -v -0.024464 -0.119495 0.166034 -vn -1.517272 2.520131 2.721972 -v -0.023000 -0.119548 0.167497 -vn 1.179136 3.636026 -2.715535 -v -0.018913 -0.119408 0.163655 -vn -0.406548 2.764939 3.191314 -v -0.021000 -0.119568 0.168033 -vn 0.306450 3.449494 -2.987262 -v -0.017000 -0.119422 0.164036 -vn -0.245730 3.182287 3.240795 -v -0.011000 -0.119568 0.168033 -vn 0.306450 3.057053 -3.001624 -v -0.001000 -0.119422 0.164036 -vn -0.958855 3.345515 3.075458 -v -0.007910 -0.119586 0.168522 -vn -1.823846 3.361640 2.635004 -v -0.005122 -0.119638 0.169941 -vn 1.179136 2.851161 -2.744254 -v 0.000913 -0.119436 0.164416 -vn 2.178758 2.826730 -2.076772 -v 0.002536 -0.119475 0.165499 -vn -3.665210 -0.110949 3.032509 -v -0.025000 -0.121460 0.137693 -vn 3.665210 -0.110949 3.032509 -v -0.022000 -0.121460 0.137693 -vn -3.665195 -1.612370 2.570743 -v -0.025000 -0.120841 0.137884 -vn 3.665195 -1.612370 2.570743 -v -0.022000 -0.120841 0.137884 -vn -3.665181 -2.681725 1.420156 -v -0.025000 -0.120401 0.138358 -vn 3.665181 -2.681725 1.420156 -v -0.022000 -0.120401 0.138358 -vn -3.665199 -3.032513 -0.110966 -v -0.025000 -0.120256 0.138988 -vn 3.665199 -3.032513 -0.110966 -v -0.022000 -0.120256 0.138988 -vn -3.665195 -2.570743 -1.612370 -v -0.025000 -0.120446 0.139607 -vn 3.665195 -2.570743 -1.612370 -v -0.022000 -0.120446 0.139607 -vn -3.665192 -1.420139 -2.681729 -v -0.025000 -0.120920 0.140047 -vn 3.665193 -1.420139 -2.681729 -v -0.022000 -0.120920 0.140047 -vn -3.665188 0.110983 -3.032517 -v -0.025000 -0.121551 0.140192 -vn 3.665187 0.110983 -3.032517 -v -0.022000 -0.121551 0.140192 -vn -3.665178 1.612353 -2.570761 -v -0.025000 -0.122170 0.140002 -vn 3.665179 1.612353 -2.570761 -v -0.022000 -0.122170 0.140002 -vn -3.665208 2.681712 -1.420157 -v -0.025000 -0.122610 0.139528 -vn 3.665207 2.681712 -1.420157 -v -0.022000 -0.122610 0.139528 -vn -3.665188 3.032517 0.110983 -v -0.025000 -0.122755 0.138897 -vn 3.665190 3.032517 0.110983 -v -0.022000 -0.122755 0.138897 -vn -3.665186 2.570752 1.612362 -v -0.025000 -0.122564 0.138278 -vn 3.665187 2.570753 1.612362 -v -0.022000 -0.122564 0.138278 -vn -3.665180 1.420183 2.681713 -v -0.025000 -0.122090 0.137838 -vn 3.665181 1.420182 2.681713 -v -0.022000 -0.122090 0.137838 -vn -3.665189 -0.110983 3.032517 -v -0.025000 -0.129747 0.145395 -vn 3.665184 -0.110983 3.032517 -v -0.022000 -0.129747 0.145395 -vn -3.665195 -1.612370 2.570743 -v -0.025000 -0.129128 0.145586 -vn 3.665195 -1.612370 2.570743 -v -0.022000 -0.129128 0.145586 -vn -3.665169 -2.681721 1.420173 -v -0.025000 -0.128688 0.146060 -vn 3.665165 -2.681721 1.420173 -v -0.022000 -0.128688 0.146060 -vn -3.665217 -3.032506 -0.110959 -v -0.025000 -0.128543 0.146690 -vn 3.665217 -3.032506 -0.110959 -v -0.022000 -0.128543 0.146690 -vn -3.665171 -2.570760 -1.612362 -v -0.025000 -0.128734 0.147309 -vn 3.665171 -2.570760 -1.612362 -v -0.022000 -0.128734 0.147309 -vn -3.665209 -1.420158 -2.681711 -v -0.025000 -0.129208 0.147749 -vn 3.665209 -1.420159 -2.681711 -v -0.022000 -0.129208 0.147749 -vn -3.665187 0.110983 -3.032517 -v -0.025000 -0.129838 0.147894 -vn 3.665187 0.110983 -3.032517 -v -0.022000 -0.129838 0.147894 -vn -3.665195 1.612370 -2.570743 -v -0.025000 -0.130457 0.147704 -vn 3.665195 1.612370 -2.570743 -v -0.022000 -0.130457 0.147704 -vn -3.665193 2.681729 -1.420139 -v -0.025000 -0.130897 0.147230 -vn 3.665192 2.681729 -1.420139 -v -0.022000 -0.130897 0.147230 -vn -3.665186 3.032517 0.110983 -v -0.025000 -0.131042 0.146599 -vn 3.665187 3.032517 0.110983 -v -0.022000 -0.131042 0.146599 -vn -3.665179 2.570761 1.612353 -v -0.025000 -0.130852 0.145980 -vn 3.665177 2.570761 1.612353 -v -0.022000 -0.130852 0.145980 -vn -3.665207 1.420157 2.681712 -v -0.025000 -0.130378 0.145540 -vn 3.665211 1.420157 2.681712 -v -0.022000 -0.130378 0.145540 -vn -3.665188 -0.110983 3.032517 -v -0.025000 -0.137449 0.137108 -vn 3.665187 -0.110983 3.032517 -v -0.022000 -0.137449 0.137108 -vn -3.665178 -1.612353 2.570761 -v -0.025000 -0.136830 0.137298 -vn 3.665179 -1.612353 2.570761 -v -0.022000 -0.136830 0.137298 -vn -3.665208 -2.681712 1.420157 -v -0.025000 -0.136390 0.137772 -vn 3.665208 -2.681712 1.420157 -v -0.022000 -0.136390 0.137772 -vn -3.665187 -3.032517 -0.110983 -v -0.025000 -0.136245 0.138403 -vn 3.665187 -3.032517 -0.110983 -v -0.022000 -0.136245 0.138403 -vn -3.665177 -2.570761 -1.612353 -v -0.025000 -0.136436 0.139022 -vn 3.665179 -2.570761 -1.612353 -v -0.022000 -0.136436 0.139022 -vn -3.665185 -1.420192 -2.681704 -v -0.025000 -0.136910 0.139462 -vn 3.665185 -1.420192 -2.681705 -v -0.022000 -0.136910 0.139462 -vn -3.665210 0.110949 -3.032509 -v -0.025000 -0.137540 0.139607 -vn 3.665210 0.110949 -3.032509 -v -0.022000 -0.137540 0.139607 -vn -3.665194 1.612370 -2.570743 -v -0.025000 -0.138159 0.139416 -vn 3.665194 1.612370 -2.570743 -v -0.022000 -0.138159 0.139416 -vn -3.665170 2.681721 -1.420173 -v -0.025000 -0.138599 0.138942 -vn 3.665170 2.681721 -1.420173 -v -0.022000 -0.138599 0.138942 -vn -3.665210 3.032509 0.110949 -v -0.025000 -0.138744 0.138312 -vn 3.665210 3.032509 0.110949 -v -0.022000 -0.138744 0.138312 -vn -3.665195 2.570743 1.612370 -v -0.025000 -0.138554 0.137693 -vn 3.665195 2.570743 1.612370 -v -0.022000 -0.138554 0.137693 -vn -3.665192 1.420139 2.681729 -v -0.025000 -0.138080 0.137253 -vn 3.665192 1.420139 2.681729 -v -0.022000 -0.138080 0.137253 -vn -3.665187 -0.110983 3.032517 -v -0.025000 -0.129162 0.129406 -vn 3.665187 -0.110983 3.032517 -v -0.022000 -0.129162 0.129406 -vn -3.665195 -1.612370 2.570743 -v -0.025000 -0.128543 0.129596 -vn 3.665195 -1.612370 2.570743 -v -0.022000 -0.128543 0.129596 -vn -3.665193 -2.681729 1.420139 -v -0.025000 -0.128103 0.130070 -vn 3.665193 -2.681729 1.420139 -v -0.022000 -0.128103 0.130070 -vn -3.665165 -3.032527 -0.110950 -v -0.025000 -0.127958 0.130701 -vn 3.665165 -3.032527 -0.110950 -v -0.022000 -0.127958 0.130701 -vn -3.665216 -2.570753 -1.612337 -v -0.025000 -0.128148 0.131320 -vn 3.665217 -2.570753 -1.612337 -v -0.022000 -0.128148 0.131320 -vn -3.665192 -1.420139 -2.681729 -v -0.025000 -0.128622 0.131760 -vn 3.665192 -1.420139 -2.681729 -v -0.022000 -0.128622 0.131760 -vn -3.665172 0.110983 -3.032517 -v -0.025000 -0.129253 0.131905 -vn 3.665187 0.110983 -3.032517 -v -0.022000 -0.129253 0.131905 -vn -3.665195 1.612370 -2.570743 -v -0.025000 -0.129872 0.131714 -vn 3.665197 1.612370 -2.570743 -v -0.022000 -0.129872 0.131714 -vn -3.665192 2.681729 -1.420139 -v -0.025000 -0.130312 0.131240 -vn 3.665192 2.681729 -1.420139 -v -0.022000 -0.130312 0.131240 -vn -3.665172 3.032524 0.110960 -v -0.025000 -0.130457 0.130610 -vn 3.665173 3.032524 0.110960 -v -0.022000 -0.130457 0.130610 -vn -3.665193 2.570770 1.612329 -v -0.025000 -0.130266 0.129991 -vn 3.665193 2.570770 1.612329 -v -0.022000 -0.130266 0.129991 -vn -3.665209 1.420158 2.681711 -v -0.025000 -0.129792 0.129551 -vn 3.665209 1.420159 2.681711 -v -0.022000 -0.129792 0.129551 -vn -6.283185 -0.000667 -0.000788 -v -0.001000 -0.142236 0.213234 -vn -6.283200 0.006432 -0.002607 -v -0.001000 -0.122249 0.213966 -vn 6.283185 0.000722 -0.000737 -v 0.004000 -0.122280 0.214800 -vn 6.283101 -0.007517 -0.009274 -v 0.004000 -0.142267 0.214068 -vn -0.272761 3.079094 -3.007143 -v -0.020670 -0.127612 0.223776 -vn -0.245735 3.410651 -2.999540 -v -0.011000 -0.127612 0.223776 -vn -0.272761 -2.851061 -3.224156 -v -0.020670 -0.137605 0.223410 -vn -0.245732 -3.182286 -3.240798 -v -0.011000 -0.137605 0.223410 -vn -1.570796 1.512301 1.627190 -v -0.025000 -0.128069 0.236268 -vn -1.570797 1.627190 -1.512301 -v -0.025000 -0.127886 0.231271 -vn -1.570799 -1.627191 1.512305 -v -0.025000 -0.138062 0.235902 -vn -1.570795 -1.512301 -1.627187 -v -0.025000 -0.137879 0.230905 -vn 1.570771 -4.651792 -1.742082 -v 0.007000 -0.137879 0.230905 -vn -1.570801 -4.651792 -1.742087 -v 0.004000 -0.138245 0.240899 -vn -1.570784 -4.766679 1.397419 -v 0.004000 -0.138135 0.237901 -vn 1.570809 -4.766682 1.397423 -v 0.007000 -0.138062 0.235902 -vn 1.570811 -4.651793 -1.742087 -v 0.007000 -0.138245 0.240899 -vn 0.272762 -3.079093 3.007130 -v 0.005670 -0.138337 0.243397 -vn -0.155117 -6.273508 -0.074358 -v -0.006000 -0.137788 0.228407 -vn -0.884627 -3.291896 -3.108913 -v -0.007910 -0.137587 0.222921 -vn -1.610791 -3.138328 -3.023514 -v -0.006000 -0.137556 0.222071 -vn 1.570799 -4.651792 -1.742085 -v -0.001000 -0.138245 0.240899 -vn -1.570799 -4.651793 -1.742085 -v -0.005000 -0.138245 0.240899 -vn 1.570795 -4.766679 1.397416 -v -0.001000 -0.138135 0.237901 -vn -1.570795 -4.766679 1.397416 -v -0.005000 -0.138135 0.237901 -vn 1.058150 -2.896982 2.803202 -v 0.007380 -0.138325 0.243096 -vn 1.988695 -2.877319 2.266316 -v 0.008884 -0.138294 0.242228 -vn 1.203306 -0.851565 -0.592654 -v 0.010000 -0.138245 0.240899 -vn 1.570793 -1.512301 -1.627186 -v 0.010000 -0.137879 0.230905 -vn 1.570799 -1.627191 1.512305 -v 0.010000 -0.138062 0.235902 -vn -0.272762 -3.079092 3.007128 -v -0.020670 -0.138337 0.243397 -vn 1.570799 -4.651793 -1.742085 -v -0.010000 -0.138245 0.240899 -vn -1.203297 -0.892600 0.528817 -v -0.025000 -0.137697 0.225909 -vn -1.988703 -2.703988 -2.470587 -v -0.023884 -0.137648 0.224579 -vn -1.570794 -4.766681 1.397401 -v -0.022000 -0.137697 0.225909 -vn -1.058167 -2.684333 -3.007470 -v -0.022380 -0.137616 0.223712 -vn -1.570799 -4.651793 -1.742085 -v -0.014000 -0.138245 0.240899 -vn -1.570795 -4.766679 1.397419 -v -0.014000 -0.138135 0.237901 -vn 1.570795 -4.766679 1.397418 -v -0.010000 -0.138135 0.237901 -vn 1.570789 -4.766679 1.397418 -v -0.019000 -0.138135 0.237901 -vn -1.570795 -4.651793 -1.742078 -v -0.022000 -0.137879 0.230905 -vn 3.337943 -3.120535 0.192457 -v 0.007000 -0.137788 0.228407 -vn -1.058153 -2.896980 2.803205 -v -0.022380 -0.138325 0.243096 -vn -1.570798 -4.651792 -1.742088 -v -0.022000 -0.138245 0.240899 -vn -1.988694 -2.877320 2.266316 -v -0.023884 -0.138294 0.242228 -vn -1.203307 -0.851566 -0.592654 -v -0.025000 -0.138245 0.240899 -vn -1.570820 -4.766683 1.397435 -v -0.022000 -0.138062 0.235902 -vn 1.570799 -4.651793 -1.742085 -v -0.019000 -0.138245 0.240899 -vn 1.570797 1.627191 -1.512301 -v 0.010000 -0.127886 0.231271 -vn 1.570796 1.512301 1.627190 -v 0.010000 -0.128069 0.236268 -vn -1.988636 2.877332 -2.266258 -v -0.023884 -0.127655 0.224945 -vn -1.203298 0.851560 0.592645 -v -0.025000 -0.127703 0.226274 -vn -1.058164 2.896976 -2.803223 -v -0.022380 -0.127623 0.224077 -vn -1.570794 4.651793 1.742069 -v -0.022000 -0.127703 0.226274 -vn 1.570793 4.651795 1.742080 -v -0.010000 -0.128142 0.238266 -vn -1.570793 4.651794 1.742080 -v -0.005000 -0.128142 0.238266 -vn -0.272761 2.851061 3.224142 -v -0.020670 -0.128343 0.243763 -vn 0.272762 2.851062 3.224141 -v 0.005670 -0.128343 0.243763 -vn 1.570798 4.766682 -1.397418 -v -0.010000 -0.128252 0.241264 -vn -1.570798 4.766682 -1.397418 -v -0.005000 -0.128252 0.241264 -vn 1.570793 4.651795 1.742083 -v -0.001000 -0.128142 0.238266 -vn -1.570789 4.651794 1.742080 -v 0.004000 -0.128142 0.238266 -vn -0.151771 6.263157 0.374021 -v -0.006000 -0.127795 0.228773 -vn -1.771031 3.392900 -2.694463 -v -0.006000 -0.127563 0.222437 -vn -0.884623 3.510326 -2.859984 -v -0.007910 -0.127594 0.223287 -vn 1.570785 4.651794 1.742083 -v -0.019000 -0.128142 0.238266 -vn -1.570793 4.651794 1.742081 -v -0.014000 -0.128142 0.238266 -vn -1.570797 4.766681 -1.397414 -v -0.022000 -0.127886 0.231271 -vn 1.570807 4.766681 -1.397407 -v 0.007000 -0.127886 0.231271 -vn 3.337935 3.098124 0.420021 -v 0.007000 -0.127795 0.228773 -vn 1.570798 4.766682 -1.397418 -v -0.001000 -0.128252 0.241264 -vn -1.570807 4.651792 1.742087 -v -0.022000 -0.128069 0.236268 -vn 1.058159 2.684336 3.007453 -v 0.007380 -0.128332 0.243461 -vn 1.570795 4.766682 -1.397422 -v 0.007000 -0.128252 0.241264 -vn 1.988693 2.703991 2.470556 -v 0.008884 -0.128300 0.242594 -vn 1.203303 0.892600 -0.528821 -v 0.010000 -0.128252 0.241264 -vn 1.570808 4.651792 1.742086 -v 0.007000 -0.128069 0.236268 -vn -1.570798 4.766682 -1.397418 -v 0.004000 -0.128252 0.241264 -vn 1.570796 4.766682 -1.397420 -v -0.019000 -0.128252 0.241264 -vn -1.058168 2.684333 3.007473 -v -0.022380 -0.128332 0.243461 -vn -1.988694 2.703991 2.470556 -v -0.023884 -0.128300 0.242594 -vn -1.570793 4.766682 -1.397425 -v -0.022000 -0.128252 0.241264 -vn -1.203304 0.892602 -0.528822 -v -0.025000 -0.128252 0.241264 -vn -1.570798 4.766682 -1.397418 -v -0.014000 -0.128252 0.241264 -vn 6.280872 0.072901 -0.073090 -v 0.004000 -0.122292 0.214816 -vn 6.236328 0.490094 -0.387702 -v 0.004116 -0.123407 0.216281 -vn 6.280220 -0.026198 -0.091276 -v 0.004000 -0.142256 0.214085 -vn 6.243485 -0.429125 -0.358966 -v 0.004116 -0.141251 0.215628 -vn 5.336207 -1.906571 -1.561771 -v 0.005300 -0.139086 0.219119 -vn 5.718532 -1.501295 -1.219837 -v 0.004661 -0.139915 0.217732 -vn 6.040574 1.050999 -0.860674 -v 0.004437 -0.124430 0.217647 -vn 5.941196 -1.189304 -0.926770 -v 0.004474 -0.140255 0.217185 -vn 6.110538 -0.854410 -0.686253 -v 0.004231 -0.140844 0.216257 -vn 5.613152 1.731929 -1.209509 -v 0.004955 -0.125373 0.218954 -vn 5.251229 2.034906 -1.542174 -v 0.005300 -0.125821 0.219604 -vn 4.752000 -2.297199 -1.863949 -v 0.005851 -0.138597 0.220003 -vn 4.755729 2.421635 -1.683693 -v 0.005852 -0.126374 0.220451 -vn 4.369791 -2.502839 -2.130688 -v 0.006085 -0.138430 0.220325 -vn 4.408333 2.626173 -1.909596 -v 0.006019 -0.126512 0.220674 -vn 3.961870 2.830837 -2.188568 -v 0.006881 -0.127062 0.221652 -vn 2.950485 3.028866 -2.369365 -v 0.008008 -0.127470 0.222621 -vn 2.958454 -2.848422 -2.555465 -v 0.008008 -0.137662 0.222248 -vn 3.526637 2.978247 -2.371068 -v 0.007083 -0.127159 0.221848 -vn 3.329778 -2.877210 -2.471199 -v 0.007083 -0.137916 0.221455 -vn 3.656878 2.906615 -2.342922 -v 0.006994 -0.127118 0.221763 -vn 3.902136 -2.683778 -2.348829 -v 0.006994 -0.137951 0.221366 -vn -3.958959 -2.663858 -2.364912 -v -0.003881 -0.137967 0.220417 -vn -3.752784 2.961417 -2.187211 -v -0.003994 -0.127087 0.220929 -vn -4.397496 -2.514652 -2.083336 -v -0.003019 -0.138445 0.219402 -vn -4.727495 -2.317824 -1.874386 -v -0.002908 -0.138524 0.219249 -vn -3.574722 -2.773652 -2.536908 -v -0.003994 -0.137920 0.220532 -vn -2.925349 -2.975063 -2.620092 -v -0.004886 -0.137654 0.221320 -vn -2.780745 3.226922 -2.494887 -v -0.004986 -0.127435 0.221771 -vn -2.426996 -3.035946 -2.809896 -v -0.005121 -0.137613 0.221498 -vn -2.000486 -3.061845 -2.988105 -v -0.005854 -0.137555 0.221986 -vn -4.350771 2.659489 -1.926433 -v -0.003085 -0.126533 0.219925 -vn -4.726933 2.443126 -1.703492 -v -0.002907 -0.126390 0.219692 -vn -5.240550 -1.932115 -1.686897 -v -0.002300 -0.139056 0.218284 -vn -5.331382 2.023263 -1.421918 -v -0.002300 -0.125791 0.218770 -vn -5.612904 -1.639793 -1.328561 -v -0.001955 -0.139455 0.217604 -vn -6.038347 -0.994336 -0.932177 -v -0.001437 -0.140300 0.216231 -vn -5.712108 1.593775 -1.109923 -v -0.001661 -0.124863 0.217447 -vn -5.949812 1.227424 -0.866641 -v -0.001488 -0.124516 0.216971 -vn -6.236280 -0.460566 -0.420647 -v -0.001116 -0.141220 0.214793 -vn -6.126577 0.839007 -0.667947 -v -0.001231 -0.123828 0.216045 -vn -6.243556 0.450630 -0.342049 -v -0.001116 -0.123377 0.215446 -vn -6.280872 -0.067364 -0.078217 -v -0.001000 -0.142225 0.213251 -vn -6.280802 0.086843 -0.056127 -v -0.001000 -0.122262 0.213981 -vn 3.955353 -4.081235 1.019722 -v 0.007000 -0.138114 0.225893 -vn 3.236861 -2.938524 1.004258 -v 0.007000 -0.138132 0.226393 -vn 2.160860 -4.998749 1.950967 -v 0.005464 -0.139122 0.224820 -vn 3.240937 -1.477284 3.181899 -v 0.004096 -0.141630 0.223359 -vn 2.975612 -3.139890 2.817280 -v 0.004381 -0.140704 0.223678 -vn 0.946144 -3.099722 3.201746 -v 0.007087 -0.138077 0.225895 -vn -3.240407 -1.460224 3.244241 -v -0.001096 -0.141630 0.223359 -vn -2.968685 -3.149513 2.835214 -v -0.001381 -0.140704 0.223678 -vn -0.945866 -6.091643 0.711499 -v -0.004087 -0.138098 0.226481 -vn -2.149546 -5.018241 1.941212 -v -0.002464 -0.139122 0.224820 -vn 3.347355 -3.017807 0.811384 -v 0.007000 -0.138098 0.226481 -vn -2.173238 4.843539 2.280936 -v -0.002464 -0.126202 0.225293 -vn -2.975210 2.923285 3.051886 -v -0.001381 -0.124541 0.224269 -vn -3.238313 1.242214 3.309644 -v -0.001096 -0.123593 0.224019 -vn -0.991598 6.016116 1.119948 -v -0.004087 -0.127344 0.226874 -vn 3.347383 2.950419 1.029809 -v 0.007000 -0.127344 0.226874 -vn 3.235700 2.857504 1.216032 -v 0.007000 -0.127304 0.226789 -vn 3.240383 1.215811 3.350066 -v 0.004096 -0.123593 0.224019 -vn 2.152447 4.842063 2.323908 -v 0.005464 -0.126202 0.225293 -vn 2.969963 2.931883 3.055634 -v 0.004381 -0.124541 0.224269 -vn 0.925506 2.861219 3.438900 -v 0.007087 -0.127323 0.226288 -vn 3.956599 3.994689 1.319952 -v 0.007000 -0.127286 0.226290 -# 324 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 17//17 18//18 19//19 -f 17//17 19//19 20//20 -f 20//20 19//19 21//21 -f 20//20 21//21 22//22 -f 22//22 21//21 23//23 -f 22//22 23//23 24//24 -f 24//24 23//23 25//25 -f 24//24 25//25 26//26 -f 26//26 25//25 27//27 -f 26//26 27//27 28//28 -f 28//28 27//27 29//29 -f 28//28 29//29 30//30 -f 30//30 29//29 31//31 -f 30//30 31//31 32//32 -f 32//32 31//31 33//33 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 34//34 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 38//38 -f 39//39 38//38 37//37 -f 40//40 16//16 14//14 -f 37//37 41//41 39//39 -f 39//39 41//41 42//42 -f 39//39 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 14//14 49//49 40//40 -f 40//40 49//49 50//50 -f 40//40 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 54//54 52//52 55//55 -f 54//54 55//55 56//56 -f 56//56 55//55 57//57 -f 56//56 57//57 48//48 -f 48//48 57//57 58//58 -f 48//48 58//58 47//47 -f 18//18 17//17 59//59 -f 59//59 17//17 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 12//12 10//10 63//63 -f 63//63 10//10 64//64 -f 65//65 66//66 64//64 -f 64//64 66//66 67//67 -f 64//64 67//67 63//63 -f 60//60 68//68 62//62 -f 62//62 68//68 69//69 -f 62//62 69//69 70//70 -f 70//70 69//69 71//71 -f 70//70 71//71 72//72 -f 72//72 71//71 73//73 -f 72//72 73//73 74//74 -f 73//73 75//75 74//74 -f 74//74 75//75 76//76 -f 74//74 76//76 77//77 -f 77//77 76//76 66//66 -f 77//77 66//66 78//78 -f 78//78 66//66 65//65 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 79//79 -f 79//79 102//102 80//80 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 103//103 -f 103//103 126//126 104//104 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 131//131 -f 131//131 130//130 132//132 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 141//141 -f 141//141 140//140 142//142 -f 141//141 142//142 143//143 -f 143//143 142//142 144//144 -f 143//143 144//144 145//145 -f 145//145 144//144 146//146 -f 145//145 146//146 147//147 -f 147//147 146//146 148//148 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 127//127 -f 127//127 150//150 128//128 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 158//158 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 151//151 -f 151//151 174//174 152//152 -f 29//29 27//27 152//152 -f 118//118 116//116 41//41 -f 35//35 33//33 128//128 -f 128//128 150//150 35//35 -f 35//35 150//150 148//148 -f 35//35 148//148 37//37 -f 41//41 116//116 59//59 -f 116//116 114//114 59//59 -f 59//59 114//114 112//112 -f 59//59 112//112 18//18 -f 19//19 82//82 21//21 -f 21//21 82//82 80//80 -f 21//21 80//80 23//23 -f 23//23 80//80 102//102 -f 23//23 102//102 25//25 -f 25//25 102//102 27//27 -f 126//126 33//33 31//31 -f 126//126 31//31 104//104 -f 148//148 146//146 37//37 -f 37//37 146//146 144//144 -f 37//37 144//144 142//142 -f 142//142 124//124 37//37 -f 37//37 124//124 122//122 -f 37//37 122//122 41//41 -f 41//41 122//122 120//120 -f 41//41 120//120 118//118 -f 160//160 102//102 162//162 -f 162//162 102//102 100//100 -f 162//162 100//100 98//98 -f 160//160 158//158 102//102 -f 102//102 158//158 156//156 -f 102//102 156//156 27//27 -f 27//27 156//156 154//154 -f 27//27 154//154 152//152 -f 152//152 174//174 29//29 -f 29//29 174//174 172//172 -f 29//29 172//172 31//31 -f 31//31 172//172 170//170 -f 31//31 170//170 104//104 -f 104//104 170//170 168//168 -f 104//104 168//168 166//166 -f 92//92 90//90 108//108 -f 108//108 90//90 18//18 -f 108//108 18//18 110//110 -f 110//110 18//18 112//112 -f 136//136 126//126 138//138 -f 138//138 126//126 124//124 -f 138//138 124//124 140//140 -f 140//140 124//124 142//142 -f 136//136 134//134 126//126 -f 126//126 134//134 132//132 -f 126//126 132//132 33//33 -f 33//33 132//132 130//130 -f 33//33 130//130 128//128 -f 106//106 104//104 96//96 -f 96//96 104//104 166//166 -f 96//96 166//166 98//98 -f 98//98 166//166 164//164 -f 98//98 164//164 162//162 -f 90//90 88//88 18//18 -f 18//18 88//88 86//86 -f 18//18 86//86 19//19 -f 19//19 86//86 84//84 -f 19//19 84//84 82//82 -f 106//106 96//96 108//108 -f 108//108 96//96 94//94 -f 108//108 94//94 92//92 -f 56//56 48//48 74//74 -f 74//74 48//48 72//72 -f 47//47 58//58 71//71 -f 71//71 58//58 73//73 -f 14//14 13//13 175//175 -f 11//11 12//12 176//176 -f 176//176 12//12 63//63 -f 176//176 63//63 175//175 -f 175//175 63//63 49//49 -f 175//175 49//49 14//14 -f 10//10 9//9 177//177 -f 15//15 16//16 178//178 -f 178//178 16//16 40//40 -f 178//178 40//40 177//177 -f 177//177 40//40 64//64 -f 177//177 64//64 10//10 -f 73//73 58//58 75//75 -f 75//75 58//58 57//57 -f 75//75 57//57 76//76 -f 76//76 57//57 55//55 -f 76//76 55//55 66//66 -f 66//66 55//55 52//52 -f 66//66 52//52 67//67 -f 67//67 52//52 50//50 -f 67//67 50//50 63//63 -f 63//63 50//50 49//49 -f 56//56 74//74 77//77 -f 56//56 77//77 54//54 -f 54//54 77//77 78//78 -f 54//54 78//78 53//53 -f 53//53 78//78 65//65 -f 53//53 65//65 51//51 -f 51//51 65//65 64//64 -f 51//51 64//64 40//40 -f 72//72 48//48 70//70 -f 70//70 48//48 46//46 -f 70//70 46//46 62//62 -f 62//62 46//46 44//44 -f 62//62 44//44 61//61 -f 61//61 44//44 42//42 -f 61//61 42//42 59//59 -f 59//59 42//42 41//41 -f 39//39 139//139 141//141 -f 119//119 39//39 117//117 -f 117//117 39//39 115//115 -f 39//39 141//141 38//38 -f 141//141 143//143 38//38 -f 38//38 143//143 145//145 -f 38//38 145//145 36//36 -f 30//30 32//32 169//169 -f 17//17 20//20 83//83 -f 83//83 85//85 17//17 -f 17//17 85//85 87//87 -f 17//17 87//87 60//60 -f 60//60 87//87 89//89 -f 60//60 89//89 91//91 -f 115//115 39//39 113//113 -f 113//113 39//39 60//60 -f 113//113 60//60 111//111 -f 169//169 171//171 30//30 -f 30//30 171//171 173//173 -f 30//30 173//173 28//28 -f 28//28 173//173 151//151 -f 28//28 151//151 153//153 -f 153//153 155//155 28//28 -f 28//28 155//155 101//101 -f 28//28 101//101 26//26 -f 26//26 101//101 24//24 -f 24//24 101//101 22//22 -f 22//22 101//101 79//79 -f 22//22 79//79 20//20 -f 20//20 79//79 81//81 -f 20//20 81//81 83//83 -f 145//145 147//147 36//36 -f 36//36 147//147 149//149 -f 36//36 149//149 34//34 -f 34//34 149//149 127//127 -f 34//34 127//127 32//32 -f 32//32 127//127 129//129 -f 32//32 129//129 169//169 -f 121//121 123//123 163//163 -f 163//163 123//123 125//125 -f 139//139 39//39 137//137 -f 137//137 39//39 119//119 -f 137//137 119//119 135//135 -f 135//135 119//119 121//121 -f 135//135 121//121 133//133 -f 133//133 121//121 163//163 -f 133//133 163//163 131//131 -f 131//131 163//163 165//165 -f 131//131 165//165 129//129 -f 129//129 165//165 167//167 -f 129//129 167//167 169//169 -f 155//155 157//157 101//101 -f 101//101 157//157 159//159 -f 101//101 159//159 99//99 -f 99//99 159//159 161//161 -f 99//99 161//161 97//97 -f 111//111 60//60 109//109 -f 109//109 60//60 91//91 -f 109//109 91//91 107//107 -f 107//107 91//91 93//93 -f 107//107 93//93 105//105 -f 105//105 93//93 95//95 -f 105//105 95//95 103//103 -f 103//103 95//95 97//97 -f 103//103 97//97 125//125 -f 125//125 97//97 161//161 -f 125//125 161//161 163//163 -f 60//60 39//39 43//43 -f 60//60 43//43 68//68 -f 68//68 43//43 45//45 -f 68//68 45//45 69//69 -f 69//69 45//45 47//47 -f 69//69 47//47 71//71 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 183//183 184//184 185//185 -f 185//185 184//184 186//186 -f 187//187 188//188 189//189 -f 190//190 191//191 192//192 -f 181//181 182//182 193//193 -f 193//193 182//182 194//194 -f 193//193 194//194 195//195 -f 196//196 197//197 198//198 -f 198//198 197//197 199//199 -f 200//200 192//192 201//201 -f 201//201 192//192 191//191 -f 201//201 191//191 202//202 -f 203//203 204//204 187//187 -f 187//187 204//204 190//190 -f 187//187 190//190 188//188 -f 188//188 190//190 192//192 -f 188//188 192//192 196//196 -f 196//196 192//192 205//205 -f 196//196 205//205 197//197 -f 197//197 205//205 206//206 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 181//181 -f 211//211 212//212 213//213 -f 214//214 186//186 212//212 -f 212//212 186//186 215//215 -f 212//212 215//215 213//213 -f 213//213 215//215 209//209 -f 213//213 209//209 199//199 -f 199//199 209//209 181//181 -f 199//199 181//181 198//198 -f 198//198 181//181 193//193 -f 198//198 193//193 189//189 -f 189//189 193//193 216//216 -f 189//189 216//216 187//187 -f 205//205 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 185//185 186//186 221//221 -f 221//221 186//186 214//214 -f 221//221 214//214 218//218 -f 218//218 214//214 222//222 -f 218//218 222//222 205//205 -f 205//205 222//222 211//211 -f 205//205 211//211 206//206 -f 206//206 211//211 213//213 -f 223//223 224//224 203//203 -f 203//203 224//224 204//204 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 179//179 -f 179//179 228//228 229//229 -f 179//179 229//229 230//230 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 235//235 236//236 223//223 -f 237//237 238//238 239//239 -f 240//240 241//241 242//242 -f 223//223 243//243 235//235 -f 235//235 243//243 244//244 -f 235//235 244//244 237//237 -f 239//239 180//180 237//237 -f 237//237 180//180 179//179 -f 237//237 179//179 235//235 -f 235//235 179//179 230//230 -f 235//235 230//230 245//245 -f 184//184 183//183 246//246 -f 232//232 247//247 248//248 -f 248//248 247//247 249//249 -f 248//248 249//249 250//250 -f 224//224 223//223 251//251 -f 251//251 223//223 236//236 -f 251//251 236//236 248//248 -f 248//248 236//236 252//252 -f 248//248 252//252 232//232 -f 232//232 252//252 245//245 -f 232//232 245//245 234//234 -f 234//234 245//245 230//230 -f 242//242 184//184 240//240 -f 240//240 184//184 246//246 -f 240//240 246//246 253//253 -f 254//254 231//231 255//255 -f 255//255 231//231 256//256 -f 255//255 256//256 257//257 -f 228//228 242//242 229//229 -f 229//229 242//242 241//241 -f 229//229 241//241 233//233 -f 233//233 241//241 258//258 -f 233//233 258//258 231//231 -f 231//231 258//258 253//253 -f 231//231 253//253 256//256 -f 256//256 253//253 246//246 -f 232//232 231//231 192//192 -f 192//192 231//231 205//205 -f 177//177 259//259 178//178 -f 178//178 259//259 260//260 -f 178//178 260//260 261//261 -f 261//261 260//260 262//262 -f 263//263 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 260//260 -f 260//260 266//266 267//267 -f 260//260 267//267 262//262 -f 265//265 268//268 263//263 -f 263//263 268//268 269//269 -f 263//263 269//269 270//270 -f 270//270 269//269 271//271 -f 270//270 271//271 272//272 -f 272//272 271//271 273//273 -f 272//272 273//273 274//274 -f 275//275 276//276 277//277 -f 277//277 276//276 278//278 -f 274//274 279//279 272//272 -f 272//272 279//279 277//277 -f 272//272 277//277 280//280 -f 280//280 277//277 278//278 -f 182//182 180//180 194//194 -f 194//194 180//180 239//239 -f 194//194 239//239 195//195 -f 195//195 239//239 238//238 -f 281//281 282//282 283//283 -f 283//283 282//282 284//284 -f 281//281 285//285 282//282 -f 282//282 285//285 286//286 -f 282//282 286//286 287//287 -f 287//287 286//286 288//288 -f 287//287 288//288 238//238 -f 238//238 288//288 289//289 -f 238//238 289//289 195//195 -f 282//282 290//290 284//284 -f 284//284 290//290 291//291 -f 284//284 291//291 292//292 -f 292//292 291//291 293//293 -f 292//292 293//293 294//294 -f 294//294 293//293 295//295 -f 293//293 296//296 295//295 -f 295//295 296//296 297//297 -f 295//295 297//297 298//298 -f 298//298 297//297 299//299 -f 298//298 299//299 300//300 -f 175//175 301//301 176//176 -f 176//176 301//301 298//298 -f 176//176 298//298 302//302 -f 302//302 298//298 300//300 -f 303//303 304//304 305//305 -f 15//15 178//178 306//306 -f 306//306 178//178 261//261 -f 261//261 262//262 306//306 -f 306//306 262//262 267//267 -f 306//306 267//267 307//307 -f 267//267 266//266 307//307 -f 307//307 266//266 264//264 -f 307//307 264//264 305//305 -f 305//305 264//264 263//263 -f 305//305 263//263 270//270 -f 4//4 2//2 276//276 -f 276//276 2//2 308//308 -f 276//276 308//308 278//278 -f 278//278 308//308 303//303 -f 278//278 303//303 280//280 -f 280//280 303//303 305//305 -f 280//280 305//305 272//272 -f 272//272 305//305 270//270 -f 13//13 15//15 309//309 -f 309//309 15//15 306//306 -f 309//309 306//306 310//310 -f 310//310 306//306 307//307 -f 310//310 307//307 305//305 -f 304//304 311//311 305//305 -f 305//305 311//311 312//312 -f 305//305 312//312 310//310 -f 304//304 313//313 311//311 -f 311//311 313//313 216//216 -f 311//311 216//216 193//193 -f 309//309 310//310 295//295 -f 301//301 175//175 13//13 -f 309//309 295//295 13//13 -f 13//13 295//295 298//298 -f 13//13 298//298 301//301 -f 283//283 284//284 312//312 -f 312//312 284//284 292//292 -f 312//312 292//292 310//310 -f 310//310 292//292 294//294 -f 310//310 294//294 295//295 -f 288//288 286//286 311//311 -f 311//311 286//286 285//285 -f 311//311 285//285 312//312 -f 312//312 285//285 281//281 -f 312//312 281//281 283//283 -f 193//193 195//195 311//311 -f 311//311 195//195 289//289 -f 311//311 289//289 288//288 -f 11//11 176//176 302//302 -f 293//293 314//314 296//296 -f 296//296 314//314 315//315 -f 296//296 315//315 297//297 -f 297//297 315//315 316//316 -f 297//297 316//316 299//299 -f 299//299 316//316 11//11 -f 299//299 11//11 300//300 -f 300//300 11//11 302//302 -f 293//293 291//291 314//314 -f 314//314 291//291 290//290 -f 314//314 290//290 317//317 -f 238//238 237//237 287//287 -f 287//287 237//237 317//317 -f 287//287 317//317 282//282 -f 282//282 317//317 290//290 -f 237//237 244//244 318//318 -f 237//237 318//318 317//317 -f 317//317 318//318 319//319 -f 317//317 319//319 314//314 -f 320//320 9//9 11//11 -f 319//319 321//321 314//314 -f 314//314 321//321 322//322 -f 314//314 322//322 315//315 -f 315//315 322//322 320//320 -f 315//315 320//320 316//316 -f 316//316 320//320 11//11 -f 320//320 322//322 265//265 -f 323//323 6//6 5//5 -f 277//277 279//279 321//321 -f 321//321 279//279 274//274 -f 321//321 274//274 273//273 -f 5//5 275//275 323//323 -f 323//323 275//275 277//277 -f 323//323 277//277 324//324 -f 324//324 277//277 321//321 -f 324//324 321//321 319//319 -f 273//273 271//271 321//321 -f 321//321 271//271 269//269 -f 321//321 269//269 322//322 -f 322//322 269//269 268//268 -f 322//322 268//268 265//265 -f 259//259 177//177 9//9 -f 320//320 265//265 9//9 -f 9//9 265//265 260//260 -f 9//9 260//260 259//259 -f 223//223 203//203 243//243 -f 243//243 203//203 187//187 -f 323//323 324//324 303//303 -f 2//2 1//1 8//8 -f 303//303 308//308 323//323 -f 323//323 308//308 2//2 -f 323//323 2//2 6//6 -f 6//6 2//2 8//8 -f 304//304 303//303 313//313 -f 313//313 303//303 324//324 -f 313//313 324//324 319//319 -f 244//244 243//243 187//187 -f 319//319 318//318 313//313 -f 313//313 318//318 244//244 -f 313//313 244//244 216//216 -f 216//216 244//244 187//187 -f 226//226 207//207 228//228 -f 228//228 207//207 209//209 -f 228//228 209//209 242//242 -f 242//242 209//209 215//215 -f 242//242 215//215 184//184 -f 184//184 215//215 186//186 -f 234//234 197//197 233//233 -f 233//233 197//197 206//206 -f 233//233 206//206 229//229 -f 229//229 206//206 213//213 -f 229//229 213//213 230//230 -f 230//230 213//213 199//199 -f 230//230 199//199 234//234 -f 234//234 199//199 197//197 -f 235//235 198//198 236//236 -f 236//236 198//198 189//189 -f 236//236 189//189 252//252 -f 252//252 189//189 188//188 -f 252//252 188//188 245//245 -f 245//245 188//188 196//196 -f 245//245 196//196 235//235 -f 235//235 196//196 198//198 -f 256//256 218//218 257//257 -f 257//257 218//218 220//220 -f 183//183 185//185 246//246 -f 246//246 185//185 221//221 -f 246//246 221//221 256//256 -f 256//256 221//221 218//218 -f 250//250 202//202 248//248 -f 248//248 202//202 191//191 -f 248//248 191//191 251//251 -f 251//251 191//191 190//190 -f 251//251 190//190 224//224 -f 224//224 190//190 204//204 -f 240//240 214//214 241//241 -f 241//241 214//214 212//212 -f 241//241 212//212 258//258 -f 258//258 212//212 211//211 -f 258//258 211//211 253//253 -f 253//253 211//211 222//222 -f 253//253 222//222 240//240 -f 240//240 222//222 214//214 -f 276//276 275//275 4//4 -f 4//4 275//275 5//5 -f 4//4 5//5 3//3 -f 5//5 7//7 3//3 -f 3//3 7//7 8//8 -f 3//3 8//8 1//1 -f 207//207 226//226 225//225 -f 207//207 225//225 208//208 -f 208//208 225//225 227//227 -f 208//208 227//227 210//210 -f 210//210 227//227 179//179 -f 210//210 179//179 181//181 -f 202//202 250//250 249//249 -f 202//202 249//249 201//201 -f 201//201 249//249 247//247 -f 201//201 247//247 200//200 -f 200//200 247//247 232//232 -f 200//200 232//232 192//192 -f 257//257 220//220 219//219 -f 257//257 219//219 255//255 -f 255//255 219//219 217//217 -f 255//255 217//217 254//254 -f 254//254 217//217 205//205 -f 254//254 205//205 231//231 -# 672 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_L_mid.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_L_mid.obj deleted file mode 100644 index 099aee44d..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_L_mid.obj +++ /dev/null @@ -1,4040 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object ruka-zadnja.obj -# -# Vertices: 995 -# Faces: 2034 -# -#### -vn -0.770260 -0.637726 -0.002465 -v -0.088763 0.030750 0.111485 -vn 0.770257 -0.637729 0.002469 -v -0.079263 0.030750 0.111516 -vn -0.769240 -0.552279 -0.321337 -v -0.088765 0.030516 0.112360 -vn 0.771282 -0.552280 -0.316403 -v -0.079265 0.030516 0.112391 -vn -0.768482 -0.318869 -0.554759 -v -0.088767 0.029875 0.113001 -vn 0.772021 -0.318870 -0.549823 -v -0.079268 0.029875 0.113031 -vn -0.768223 -0.000002 -0.640182 -v -0.088768 0.029000 0.113235 -vn 0.772309 0.000000 -0.635247 -v -0.079268 0.029000 0.113266 -vn -0.768484 0.318872 -0.554755 -v -0.088767 0.028125 0.113001 -vn 0.772025 0.318864 -0.549821 -v -0.079268 0.028125 0.113031 -vn -0.769239 0.552280 -0.321338 -v -0.088765 0.027484 0.112360 -vn 0.771282 0.552281 -0.316401 -v -0.079265 0.027484 0.112391 -vn -0.770258 0.637727 -0.002465 -v -0.088763 0.027250 0.111485 -vn 0.770253 0.637734 0.002474 -v -0.079263 0.027250 0.111516 -vn -0.771277 0.552296 0.316388 -v -0.088760 0.027484 0.110610 -vn 0.769234 0.552294 0.321326 -v -0.079260 0.027484 0.110641 -vn -0.772028 0.318856 0.549821 -v -0.088758 0.028125 0.109970 -vn 0.768491 0.318857 0.554754 -v -0.079258 0.028125 0.110000 -vn -0.772294 0.000001 0.635265 -v -0.088757 0.029000 0.109736 -vn 0.768206 0.000001 0.640202 -v -0.079257 0.029000 0.109766 -vn -0.772032 -0.318856 0.549815 -v -0.088758 0.029875 0.109970 -vn 0.768494 -0.318857 0.554750 -v -0.079258 0.029875 0.110000 -vn -0.771277 -0.552295 0.316390 -v -0.088760 0.030516 0.110610 -vn 0.769235 -0.552292 0.321328 -v -0.079260 0.030516 0.110641 -vn -0.770258 -0.637727 -0.002465 -v -0.088763 -0.027250 0.111485 -vn 0.770253 -0.637734 0.002465 -v -0.079263 -0.027250 0.111516 -vn -0.769240 -0.552280 -0.321336 -v -0.088765 -0.027484 0.112360 -vn 0.771282 -0.552282 -0.316401 -v -0.079265 -0.027484 0.112391 -vn -0.768484 -0.318866 -0.554759 -v -0.088767 -0.028125 0.113001 -vn 0.772024 -0.318870 -0.549819 -v -0.079268 -0.028125 0.113031 -vn -0.768222 -0.000002 -0.640184 -v -0.088768 -0.029000 0.113235 -vn 0.772310 0.000001 -0.635246 -v -0.079268 -0.029000 0.113266 -vn -0.768482 0.318869 -0.554760 -v -0.088767 -0.029875 0.113001 -vn 0.772025 0.318864 -0.549821 -v -0.079268 -0.029875 0.113031 -vn -0.769239 0.552281 -0.321336 -v -0.088765 -0.030516 0.112360 -vn 0.771282 0.552281 -0.316401 -v -0.079265 -0.030516 0.112391 -vn -0.770259 0.637727 -0.002466 -v -0.088763 -0.030750 0.111485 -vn 0.770257 0.637729 0.002469 -v -0.079263 -0.030750 0.111516 -vn -0.771277 0.552295 0.316390 -v -0.088760 -0.030516 0.110610 -vn 0.769235 0.552292 0.321327 -v -0.079260 -0.030516 0.110641 -vn -0.772033 0.318856 0.549815 -v -0.088758 -0.029875 0.109970 -vn 0.768493 0.318857 0.554750 -v -0.079258 -0.029875 0.110000 -vn -0.772301 0.000007 0.635256 -v -0.088757 -0.029000 0.109736 -vn 0.768207 0.000000 0.640202 -v -0.079257 -0.029000 0.109766 -vn -0.772034 -0.318858 0.549811 -v -0.088758 -0.028125 0.109970 -vn 0.768494 -0.318858 0.554750 -v -0.079258 -0.028125 0.110000 -vn -0.771277 -0.552296 0.316388 -v -0.088760 -0.027484 0.110610 -vn 0.769235 -0.552292 0.321327 -v -0.079260 -0.027484 0.110641 -vn 0.737413 -0.669355 0.090481 -v -0.084437 0.026000 0.165823 -vn -0.737977 -0.669355 0.085754 -v -0.086937 0.026000 0.165815 -vn 0.769250 -0.552262 0.321343 -v -0.084435 0.025866 0.165323 -vn -0.771290 -0.552267 0.316406 -v -0.086935 0.025866 0.165315 -vn 0.768471 -0.318860 0.554780 -v -0.084434 0.025500 0.164957 -vn -0.772016 -0.318859 0.549836 -v -0.086934 0.025500 0.164949 -vn 0.735556 -0.088130 0.671708 -v -0.084434 0.025000 0.164823 -vn -0.739837 -0.088135 0.666989 -v -0.086933 0.025000 0.164815 -vn 0.737413 -0.669355 0.090481 -v -0.084437 -0.020000 0.165823 -vn -0.737977 -0.669355 0.085754 -v -0.086937 -0.020000 0.165815 -vn 0.769250 -0.552262 0.321342 -v -0.084435 -0.020134 0.165323 -vn -0.771290 -0.552267 0.316407 -v -0.086935 -0.020134 0.165315 -vn 0.768472 -0.318859 0.554779 -v -0.084434 -0.020500 0.164957 -vn -0.772017 -0.318862 0.549834 -v -0.086934 -0.020500 0.164949 -vn 0.735556 -0.088130 0.671707 -v -0.084434 -0.021000 0.164823 -vn -0.739846 -0.088133 0.666979 -v -0.086933 -0.021000 0.164815 -vn -0.998191 0.030817 0.051628 -v -0.090515 0.031000 0.190411 -vn -0.945964 -0.282132 0.159857 -v -0.090477 0.020031 0.178405 -vn -0.934428 -0.353779 0.041037 -v -0.090483 0.020500 0.180155 -vn -0.678566 0.727972 -0.098008 -v -0.090361 -0.032000 0.142043 -vn -0.652017 0.655721 -0.380661 -v -0.090359 -0.032134 0.141543 -vn -0.651108 0.378567 -0.657834 -v -0.090358 -0.032500 0.141177 -vn -0.901831 -0.369549 0.223907 -v -0.090534 0.020500 0.196068 -vn -0.774924 0.412014 0.479309 -v -0.090534 0.027000 0.196068 -vn -0.777180 0.457960 0.431584 -v -0.090532 0.027450 0.195589 -vn -0.924351 -0.375651 0.066798 -v -0.090549 -0.026500 0.200994 -vn -0.924351 0.375651 0.066798 -v -0.090549 -0.020500 0.200994 -vn -0.939854 -0.332884 0.076567 -v -0.090535 -0.026500 0.196596 -vn -0.934428 0.353779 0.041037 -v -0.090483 -0.020500 0.180155 -vn -0.842021 -0.428188 0.328110 -v -0.090522 -0.030111 0.192497 -vn -0.804088 -0.442358 0.397192 -v -0.090527 -0.028771 0.194138 -vn -0.779069 -0.455877 0.430381 -v -0.090533 -0.027129 0.195931 -vn -0.651102 -0.378569 -0.657839 -v -0.090358 -0.034500 0.141177 -vn -0.652012 -0.655725 -0.380664 -v -0.090359 -0.034866 0.141543 -vn -0.676548 -0.095811 -0.730140 -v -0.090357 -0.034000 0.141043 -vn -0.678565 -0.727972 -0.098010 -v -0.090361 -0.035000 0.142043 -vn -0.676548 0.095810 -0.730139 -v -0.090357 -0.033000 0.141043 -vn -0.897840 0.408480 0.164402 -v -0.090518 0.030837 0.191236 -vn -0.846745 0.424037 0.321273 -v -0.090522 0.030139 0.192457 -vn -0.806767 0.440979 0.393275 -v -0.090527 0.028839 0.194060 -vn -0.771281 -0.552293 0.316383 -v -0.090461 0.025866 0.173303 -vn -0.770258 -0.637727 -0.002475 -v -0.090462 0.026000 0.173804 -vn -0.903565 -0.301509 -0.304406 -v -0.090453 0.032000 0.170804 -vn -0.726184 0.682372 0.083813 -v -0.090515 0.035000 0.190411 -vn -0.678566 0.727972 -0.098010 -v -0.090361 0.035000 0.142043 -vn -0.676548 -0.095810 -0.730140 -v -0.090357 0.033000 0.141043 -vn -0.651102 -0.378568 -0.657839 -v -0.090358 0.032500 0.141177 -vn -0.652011 -0.655727 -0.380662 -v -0.090359 0.032134 0.141543 -vn -0.652018 0.655720 -0.380663 -v -0.090359 0.034866 0.141543 -vn -0.651108 0.378568 -0.657833 -v -0.090358 0.034500 0.141177 -vn -0.676548 0.095811 -0.730139 -v -0.090357 0.034000 0.141043 -vn -0.678566 -0.727972 -0.098007 -v -0.090361 0.032000 0.142043 -vn -0.945964 0.282131 0.159857 -v -0.090477 -0.020031 0.178405 -vn -0.998062 -0.031751 0.053512 -v -0.090515 -0.031000 0.190411 -vn -0.886463 -0.422791 0.188229 -v -0.090518 -0.030826 0.191264 -vn -0.903564 0.301510 -0.304407 -v -0.090453 -0.032000 0.170804 -vn -0.726304 -0.682217 0.084045 -v -0.090515 -0.035000 0.190411 -vn -0.769235 0.552285 -0.321338 -v -0.090464 -0.025866 0.174303 -vn -0.739844 0.088132 0.666981 -v -0.090459 0.021000 0.172803 -vn -0.739844 -0.088131 0.666981 -v -0.090459 0.025000 0.172803 -vn -0.772020 -0.318876 0.549822 -v -0.090460 0.025500 0.172937 -vn -0.769232 -0.552292 -0.321334 -v -0.090464 0.025866 0.174303 -vn -0.768485 -0.318872 -0.554754 -v -0.090465 0.025500 0.174670 -vn -0.735555 -0.088135 -0.671707 -v -0.090465 0.025000 0.174803 -vn -0.735556 0.088134 -0.671707 -v -0.090465 0.021000 0.174803 -vn -0.946341 -0.162895 0.279112 -v -0.090473 0.018750 0.177124 -vn -0.768485 0.318873 -0.554753 -v -0.090465 0.020500 0.174670 -vn -0.769233 0.552290 -0.321335 -v -0.090464 0.020134 0.174303 -vn -0.935413 -0.044033 0.350805 -v -0.090471 0.017000 0.176655 -vn -0.770259 0.637727 -0.002474 -v -0.090462 0.020000 0.173804 -vn -0.935413 0.044033 0.350805 -v -0.090471 -0.017000 0.176655 -vn -0.770262 0.637723 -0.002468 -v -0.090462 -0.026000 0.173804 -vn -0.771281 0.552293 0.316383 -v -0.090461 -0.025866 0.173303 -vn -0.772020 0.318876 0.549822 -v -0.090460 -0.025500 0.172937 -vn -0.772014 0.318876 0.549829 -v -0.090460 0.020500 0.172937 -vn -0.772015 -0.318876 0.549828 -v -0.090460 -0.020500 0.172937 -vn -0.771282 0.552292 0.316381 -v -0.090461 0.020134 0.173303 -vn -0.771282 -0.552293 0.316381 -v -0.090461 -0.020134 0.173303 -vn -0.770258 -0.637727 -0.002474 -v -0.090462 -0.020000 0.173804 -vn -0.769234 -0.552289 -0.321335 -v -0.090464 -0.020134 0.174303 -vn -0.946342 0.162896 0.279111 -v -0.090473 -0.018750 0.177124 -vn -0.768485 -0.318872 -0.554754 -v -0.090465 -0.020500 0.174670 -vn -0.735555 -0.088136 -0.671707 -v -0.090465 -0.021000 0.174803 -vn -0.735556 0.088135 -0.671707 -v -0.090465 -0.025000 0.174803 -vn -0.768485 0.318872 -0.554754 -v -0.090465 -0.025500 0.174670 -vn -0.739844 -0.088132 0.666981 -v -0.090459 -0.021000 0.172803 -vn -0.739844 0.088131 0.666981 -v -0.090459 -0.025000 0.172803 -vn 0.351680 -0.741505 0.571395 -v -0.083888 -0.035000 0.189116 -vn -0.041688 -0.997001 -0.065197 -v -0.086861 -0.035000 0.142054 -vn -0.023165 -0.741503 0.670550 -v -0.076066 -0.035000 0.187047 -vn 0.171575 -0.741502 0.648642 -v -0.080130 -0.035000 0.187505 -vn 0.484325 -0.756864 0.438847 -v -0.069638 -0.035000 0.183553 -vn 0.620860 -0.756937 0.203910 -v -0.069847 -0.035000 0.183912 -vn 0.302476 -0.904534 -0.300544 -v -0.076476 -0.035000 0.178200 -vn 0.266286 -0.660627 0.701900 -v -0.087809 -0.035000 0.192289 -vn -0.091372 -0.661816 0.744077 -v -0.088760 -0.035000 0.192403 -vn -0.427589 -0.661809 0.615773 -v -0.089655 -0.035000 0.192061 -vn 0.264002 -0.756820 0.597935 -v -0.069301 -0.035000 0.183310 -vn -0.679178 -0.727973 0.093666 -v -0.088809 -0.035000 0.126048 -vn -0.699662 -0.714227 -0.018779 -v -0.088744 -0.035000 0.105637 -vn -0.042108 -0.997001 0.064932 -v -0.086809 -0.035000 0.126054 -vn 0.691668 -0.719731 -0.059853 -v -0.076251 -0.035000 0.107881 -vn 0.435302 -0.697804 0.568842 -v -0.087020 -0.035000 0.191745 -vn -0.666202 -0.660636 0.346027 -v -0.090289 -0.035000 0.191342 -vn 0.049391 -0.719702 -0.692524 -v -0.063619 -0.035000 0.178241 -vn 0.044951 -0.719703 0.692825 -v -0.063635 -0.035000 0.183241 -vn 0.068979 -0.731289 0.678571 -v -0.068894 -0.035000 0.183224 -vn 0.650041 -0.757005 -0.066257 -v -0.069892 -0.035000 0.184326 -vn 0.623884 -0.731400 -0.275361 -v -0.069765 -0.035000 0.184722 -vn -0.097060 -0.697771 0.709715 -v -0.072044 -0.035000 0.187784 -vn 0.672648 -0.682380 -0.286186 -v -0.069665 -0.035000 0.184896 -vn 0.115608 -0.660562 0.741817 -v -0.071089 -0.035000 0.187866 -vn 0.749960 -0.660869 -0.028490 -v -0.069401 -0.035000 0.185817 -vn 0.676039 -0.661874 0.323872 -v -0.069597 -0.035000 0.186755 -vn 0.447308 -0.661776 0.601638 -v -0.070206 -0.035000 0.187495 -vn 0.691927 0.719519 -0.059416 -v -0.076251 0.035000 0.107881 -vn -0.701760 0.712222 -0.016535 -v -0.088744 0.035000 0.105637 -vn -0.679178 0.727973 0.093666 -v -0.088809 0.035000 0.126048 -vn -0.042108 0.997001 0.064932 -v -0.086809 0.035000 0.126054 -vn -0.041689 0.997001 -0.065197 -v -0.086861 0.035000 0.142054 -vn 0.302475 0.904534 -0.300544 -v -0.076476 0.035000 0.178200 -vn 0.351680 0.741505 0.571395 -v -0.083888 0.035000 0.189116 -vn 0.171575 0.741502 0.648642 -v -0.080130 0.035000 0.187505 -vn 0.435286 0.697773 0.568892 -v -0.087020 0.035000 0.191745 -vn -0.665956 0.660871 0.346052 -v -0.090289 0.035000 0.191342 -vn 0.484163 0.757023 0.438751 -v -0.069638 0.035000 0.183553 -vn 0.620738 0.757036 0.203912 -v -0.069847 0.035000 0.183912 -vn 0.650006 0.757039 -0.066209 -v -0.069892 0.035000 0.184326 -vn -0.023165 0.741503 0.670550 -v -0.076066 0.035000 0.187047 -vn 0.623884 0.731400 -0.275361 -v -0.069765 0.035000 0.184722 -vn -0.097060 0.697771 0.709715 -v -0.072044 0.035000 0.187784 -vn 0.672648 0.682380 -0.286186 -v -0.069665 0.035000 0.184896 -vn 0.044951 0.719703 0.692825 -v -0.063635 0.035000 0.183241 -vn 0.049391 0.719702 -0.692524 -v -0.063619 0.035000 0.178241 -vn 0.069127 0.731415 0.678420 -v -0.068894 0.035000 0.183224 -vn 0.263870 0.757035 0.597721 -v -0.069301 0.035000 0.183310 -vn -0.427486 0.661870 0.615779 -v -0.089655 0.035000 0.192061 -vn -0.091336 0.661777 0.744116 -v -0.088760 0.035000 0.192403 -vn 0.266308 0.660557 0.701958 -v -0.087809 0.035000 0.192289 -vn 0.676039 0.661874 0.323872 -v -0.069597 0.035000 0.186755 -vn 0.749960 0.660870 -0.028490 -v -0.069401 0.035000 0.185817 -vn 0.447308 0.661776 0.601638 -v -0.070206 0.035000 0.187495 -vn 0.115608 0.660562 0.741817 -v -0.071089 0.035000 0.187866 -vn -0.755305 0.465033 0.461799 -v -0.088747 0.034415 0.106755 -vn -0.755743 0.251727 0.604554 -v -0.088749 0.033766 0.107189 -vn -0.732048 -0.067055 0.677945 -v -0.088749 -0.033000 0.107342 -vn -0.021382 -0.997721 -0.063993 -v -0.088743 -0.034995 0.105489 -vn -0.750007 -0.607442 0.261731 -v -0.088745 -0.034849 0.106105 -vn -0.755305 -0.465035 0.461798 -v -0.088747 -0.034415 0.106755 -vn -0.752012 0.606629 0.257835 -v -0.088745 0.034849 0.106105 -vn -0.026822 0.997646 -0.063110 -v -0.088743 0.034995 0.105489 -vn -0.681206 0.095830 0.725793 -v -0.088816 0.033000 0.128048 -vn -0.681206 -0.095830 0.725793 -v -0.088816 -0.033000 0.128048 -vn -0.755769 -0.251705 0.604532 -v -0.088749 -0.033766 0.107189 -vn -0.655321 0.378579 0.653630 -v -0.088815 0.034000 0.127780 -vn -0.654438 0.655722 0.376483 -v -0.088812 0.034732 0.127048 -vn -0.655323 -0.378578 0.653629 -v -0.088815 -0.034000 0.127780 -vn -0.654438 -0.655722 0.376483 -v -0.088812 -0.034732 0.127048 -vn -0.732050 0.067053 0.677943 -v -0.088749 0.033000 0.107342 -vn -0.737410 -0.669358 -0.090480 -v -0.086861 0.032000 0.142054 -vn -0.575499 -0.577350 -0.579196 -v -0.086953 0.032000 0.170815 -vn -0.737410 0.669357 -0.090480 -v -0.086861 -0.032000 0.142054 -vn -0.575498 0.577350 -0.579196 -v -0.086953 -0.032000 0.170815 -vn 0.575495 -0.577352 0.579198 -v -0.084281 0.031000 0.117175 -vn 0.735556 0.088130 0.671707 -v -0.084434 -0.025000 0.164823 -vn 0.768470 0.318860 0.554781 -v -0.084434 -0.025500 0.164957 -vn 0.575497 0.577351 0.579197 -v -0.084281 -0.031000 0.117175 -vn 0.739845 -0.088133 -0.666980 -v -0.084466 0.025000 0.174823 -vn 0.772026 -0.318878 -0.549811 -v -0.084465 0.025500 0.174689 -vn 0.579196 -0.577350 -0.575498 -v -0.084476 0.031000 0.178174 -vn 0.771275 -0.552290 -0.316403 -v -0.084464 0.025866 0.174323 -vn 0.737982 -0.669348 -0.085766 -v -0.084462 0.026000 0.173823 -vn 0.769250 0.552263 0.321342 -v -0.084435 -0.025866 0.165323 -vn 0.737413 0.669355 0.090481 -v -0.084437 -0.026000 0.165823 -vn 0.579196 0.577350 -0.575498 -v -0.084476 -0.031000 0.178174 -vn 0.737982 0.669348 -0.085766 -v -0.084462 -0.026000 0.173823 -vn 0.771274 0.552291 -0.316403 -v -0.084464 -0.025866 0.174323 -vn 0.737982 -0.669348 -0.085766 -v -0.084462 -0.020000 0.173823 -vn 0.735552 -0.088120 0.671712 -v -0.084473 0.017000 0.177174 -vn 0.771275 -0.552290 -0.316403 -v -0.084464 -0.020134 0.174323 -vn 0.735552 0.088120 0.671713 -v -0.084473 -0.017000 0.177174 -vn 0.772025 -0.318878 -0.549813 -v -0.084465 -0.020500 0.174689 -vn 0.755375 0.296997 0.584125 -v -0.084474 -0.018500 0.177576 -vn 0.739845 -0.088134 -0.666980 -v -0.084466 -0.021000 0.174823 -vn 0.539377 0.775284 0.328645 -v -0.084476 -0.019236 0.178174 -vn 0.739845 0.088133 -0.666980 -v -0.084466 -0.025000 0.174823 -vn 0.772026 0.318878 -0.549812 -v -0.084465 -0.025500 0.174689 -vn 0.735556 0.088130 0.671707 -v -0.084434 0.021000 0.164823 -vn 0.768472 0.318858 0.554780 -v -0.084434 0.020500 0.164957 -vn 0.769251 0.552263 0.321339 -v -0.084435 0.020134 0.165323 -vn 0.737413 0.669355 0.090481 -v -0.084437 0.020000 0.165823 -vn 0.739844 0.088134 -0.666981 -v -0.084466 0.021000 0.174823 -vn 0.547519 -0.768256 0.331671 -v -0.084476 0.019236 0.178174 -vn 0.772025 0.318876 -0.549814 -v -0.084465 0.020500 0.174689 -vn 0.759437 -0.300037 0.577263 -v -0.084474 0.018500 0.177576 -vn 0.771275 0.552291 -0.316402 -v -0.084464 0.020134 0.174323 -vn 0.737982 0.669348 -0.085766 -v -0.084462 0.020000 0.173823 -vn 0.304407 -0.301511 -0.903564 -v -0.076476 0.031000 0.178200 -vn 0.090484 -0.669353 -0.737414 -v -0.066878 0.022000 0.178231 -vn 0.321329 -0.552286 -0.769238 -v -0.067878 0.021732 0.178228 -vn 0.554756 -0.318862 -0.768487 -v -0.068610 0.021000 0.178225 -vn 0.671712 -0.088118 -0.735553 -v -0.068878 0.020000 0.178224 -vn 0.552575 -0.743018 -0.377605 -v -0.068878 0.019236 0.178224 -vn 0.192214 0.709236 -0.678261 -v -0.061030 0.034659 0.178250 -vn 0.576841 0.453004 -0.679736 -v -0.048184 0.023707 0.178291 -vn 0.088189 -0.726666 -0.681307 -v -0.048891 0.022000 0.178288 -vn 0.477767 0.542264 -0.691151 -v -0.056547 0.032071 0.178264 -vn 0.369299 0.635883 -0.677695 -v -0.058619 0.033660 0.178257 -vn 0.611184 -0.442526 -0.656220 -v -0.048082 0.022412 0.178291 -vn 0.343928 -0.670833 -0.657036 -v -0.048437 0.022109 0.178290 -vn 0.745741 -0.117778 -0.655743 -v -0.047903 0.022844 0.178292 -vn 0.718147 0.232656 -0.655848 -v -0.047940 0.023309 0.178291 -vn 0.745742 0.117778 -0.655742 -v -0.047903 -0.022844 0.178292 -vn 0.718150 -0.232658 -0.655843 -v -0.047940 -0.023309 0.178291 -vn 0.576841 -0.453004 -0.679736 -v -0.048184 -0.023707 0.178291 -vn 0.552575 0.743018 -0.377605 -v -0.068878 -0.019236 0.178224 -vn 0.671713 0.088120 -0.735552 -v -0.068878 -0.020000 0.178224 -vn 0.304407 0.301511 -0.903564 -v -0.076476 -0.031000 0.178200 -vn 0.090483 0.669353 -0.737414 -v -0.066878 -0.022000 0.178231 -vn 0.192214 -0.709236 -0.678261 -v -0.061030 -0.034659 0.178250 -vn 0.369299 -0.635883 -0.677696 -v -0.058619 -0.033660 0.178257 -vn 0.554757 0.318861 -0.768487 -v -0.068610 -0.021000 0.178225 -vn 0.321328 0.552286 -0.769239 -v -0.067878 -0.021732 0.178228 -vn 0.088188 0.726667 -0.681306 -v -0.048891 -0.022000 0.178288 -vn 0.343930 0.670846 -0.657022 -v -0.048437 -0.022109 0.178290 -vn 0.611197 0.442530 -0.656206 -v -0.048082 -0.022412 0.178291 -vn 0.477767 -0.542263 -0.691151 -v -0.056547 -0.032071 0.178264 -vn 0.075059 0.386496 0.919232 -v -0.068894 -0.020500 0.183224 -vn 0.335364 0.400511 0.852715 -v -0.069245 -0.020500 0.183287 -vn 0.649766 0.402265 0.644971 -v -0.069607 -0.020500 0.183520 -vn 0.860710 0.402352 0.311916 -v -0.069837 -0.020500 0.183884 -vn 0.912035 0.402436 -0.078975 -v -0.069893 -0.020500 0.184311 -vn 0.844407 0.390721 -0.366488 -v -0.069765 -0.020500 0.184722 -vn 0.544034 -0.647230 0.533967 -v -0.068894 0.020000 0.183224 -vn 0.263871 -0.757035 0.597721 -v -0.069301 0.020000 0.183310 -vn 0.484163 -0.757023 0.438750 -v -0.069638 0.020000 0.183553 -vn 0.620739 -0.757036 0.203912 -v -0.069847 0.020000 0.183912 -vn 0.650006 -0.757039 -0.066210 -v -0.069892 0.020000 0.184326 -vn 0.623869 -0.731407 -0.275376 -v -0.069765 0.020000 0.184722 -vn 0.749396 -0.596926 0.286505 -v -0.068880 0.019598 0.178724 -vn 0.643120 -0.761426 0.081410 -v -0.068884 0.020000 0.180224 -vn 0.643185 0.761216 0.082843 -v -0.068884 -0.020000 0.180224 -vn 0.749396 0.596926 0.286505 -v -0.068880 -0.019598 0.178724 -vn -0.291990 -0.943869 -0.154441 -v -0.071555 0.020000 0.203681 -vn -0.330320 -0.943869 -0.001058 -v -0.070900 0.020000 0.201057 -vn 0.398916 -0.916293 0.035686 -v -0.067050 0.020000 0.201070 -vn 0.639499 -0.706591 -0.302935 -v -0.067013 0.020000 0.189524 -vn 0.392998 -0.909355 0.136482 -v -0.067575 0.020000 0.204156 -vn 0.327278 -0.909363 0.256804 -v -0.069076 0.020000 0.206904 -vn -0.186772 -0.943868 -0.272450 -v -0.073355 0.020000 0.205699 -vn 0.226041 -0.909359 0.349244 -v -0.071388 0.020000 0.209014 -vn -0.038766 -0.943876 -0.328017 -v -0.075886 0.020000 0.206650 -vn -0.292973 -0.943870 0.152568 -v -0.071538 0.020000 0.198429 -vn -0.188529 -0.943862 0.271260 -v -0.073325 0.020000 0.196400 -vn -0.040862 -0.943874 0.327767 -v -0.075850 0.020000 0.195432 -vn -0.392430 -0.911639 0.122116 -v -0.089983 0.020000 0.180157 -vn 0.100247 -0.909354 0.403764 -v -0.074260 0.020000 0.210259 -vn -0.036439 -0.909359 0.414413 -v -0.077381 0.020000 0.210503 -vn 0.118116 -0.943873 -0.308467 -v -0.078570 0.020000 0.206316 -vn -0.169167 -0.909343 0.380101 -v -0.080412 0.020000 0.209718 -vn 0.247940 -0.943872 -0.218245 -v -0.080791 0.020000 0.204772 -vn -0.283520 -0.909357 0.304443 -v -0.083024 0.020000 0.207991 -vn 0.320975 -0.943869 -0.078019 -v -0.082040 0.020000 0.202374 -vn -0.335902 -0.916290 0.218132 -v -0.084932 0.020000 0.205509 -vn 0.320460 -0.943871 0.080078 -v -0.082031 0.020000 0.199669 -vn -0.411412 -0.905707 0.102149 -v -0.090033 0.020000 0.195944 -vn 0.246537 -0.943872 0.219829 -v -0.080767 0.020000 0.197279 -vn 0.116138 -0.943873 0.309219 -v -0.078536 0.020000 0.195750 -vn 0.282651 0.945447 -0.161981 -v -0.080454 0.027000 0.203277 -vn -0.283517 0.909357 0.304448 -v -0.083024 0.027000 0.207991 -vn 0.163788 0.945449 -0.281601 -v -0.078812 0.027000 0.204929 -vn -0.169175 0.909344 0.380098 -v -0.080412 0.027000 0.209718 -vn 0.001043 0.945449 -0.325769 -v -0.076564 0.027000 0.205539 -vn 0.325777 0.945446 0.001044 -v -0.081049 0.027000 0.201025 -vn 0.281607 0.945447 0.163790 -v -0.080439 0.027000 0.198777 -vn 0.144862 0.940536 0.307259 -v -0.085964 0.027000 0.195848 -vn -0.001047 0.945448 0.325772 -v -0.076535 0.027000 0.196539 -vn -0.163798 0.945441 0.281623 -v -0.074287 0.027000 0.197149 -vn -0.058757 0.924893 0.375660 -v -0.073331 0.027000 0.191571 -vn 0.023064 0.937566 0.347043 -v -0.088313 0.027000 0.196414 -vn -0.237779 0.802257 0.547580 -v -0.089862 0.027000 0.196265 -vn -0.335902 0.916291 0.218131 -v -0.084932 0.027000 0.205509 -vn -0.014236 0.911041 0.412069 -v -0.076204 0.027000 0.191045 -vn 0.105439 0.911040 0.398609 -v -0.079107 0.027000 0.191372 -vn 0.161995 0.945442 0.282662 -v -0.078787 0.027000 0.197135 -vn 0.216119 0.911041 0.351136 -v -0.081791 0.027000 0.192523 -vn 0.236812 0.924895 0.297471 -v -0.084028 0.027000 0.194401 -vn -0.281615 0.945444 -0.163795 -v -0.072660 0.027000 0.203302 -vn 0.392998 0.909354 0.136484 -v -0.067575 0.027000 0.204156 -vn -0.325775 0.945447 -0.001043 -v -0.072049 0.027000 0.201054 -vn 0.398916 0.916293 0.035686 -v -0.067050 0.027000 0.201070 -vn -0.282661 0.945443 0.161988 -v -0.072645 0.027000 0.198802 -vn -0.036433 0.909360 0.414412 -v -0.077381 0.027000 0.210503 -vn 0.100244 0.909354 0.403764 -v -0.074260 0.027000 0.210259 -vn -0.161984 0.945446 -0.282654 -v -0.074312 0.027000 0.204943 -vn 0.226040 0.909360 0.349243 -v -0.071388 0.027000 0.209014 -vn 0.327280 0.909363 0.256801 -v -0.069076 0.027000 0.206904 -vn 0.495571 0.792532 0.355390 -v -0.067014 0.027000 0.189985 -vn 0.154405 0.939107 0.306981 -v -0.068611 0.027000 0.191203 -vn 0.026380 0.940758 0.338050 -v -0.070933 0.027000 0.191872 -vn 0.549837 -0.318861 0.772015 -v -0.068626 0.021000 0.183225 -vn 0.316390 -0.552285 0.771284 -v -0.067894 0.021732 0.183228 -vn 0.085757 -0.669353 0.737978 -v -0.066894 0.022000 0.183231 -vn 0.572471 0.453007 0.683419 -v -0.048200 0.023707 0.183291 -vn 0.473328 0.542264 0.694198 -v -0.056563 0.032071 0.183264 -vn 0.741520 -0.117779 0.660512 -v -0.047919 0.022844 0.183292 -vn 0.713935 0.232664 0.660427 -v -0.047956 0.023309 0.183291 -vn 0.364950 0.635883 0.680047 -v -0.058635 0.033660 0.183257 -vn 0.187864 0.709235 0.679480 -v -0.061046 0.034659 0.183250 -vn 0.606961 -0.442529 0.660127 -v -0.048098 0.022412 0.183291 -vn 0.339711 -0.670836 0.659223 -v -0.048453 0.022109 0.183290 -vn 0.083823 -0.726666 0.681858 -v -0.048907 0.022000 0.183288 -vn -0.637723 0.770263 -0.002036 -v -0.083449 -0.020000 0.201017 -vn -0.637723 -0.770263 -0.002036 -v -0.083449 -0.021500 0.201017 -vn -0.551262 0.770263 -0.320631 -v -0.083599 -0.020000 0.201567 -vn -0.551262 -0.770263 -0.320631 -v -0.083599 -0.021500 0.201567 -vn -0.317076 0.770267 -0.553310 -v -0.084002 -0.020000 0.201968 -vn -0.317076 -0.770266 -0.553310 -v -0.084002 -0.021500 0.201968 -vn 0.002044 0.770251 -0.637737 -v -0.084553 -0.020000 0.202113 -vn 0.002044 -0.770251 -0.637737 -v -0.084553 -0.021500 0.202113 -vn 0.320620 0.770269 -0.551260 -v -0.085102 -0.020000 0.201964 -vn 0.320620 -0.770269 -0.551260 -v -0.085102 -0.021500 0.201964 -vn 0.553312 0.770260 -0.317089 -v -0.085504 -0.020000 0.201560 -vn 0.553312 -0.770260 -0.317089 -v -0.085504 -0.021500 0.201560 -vn 0.637724 0.770263 0.002047 -v -0.085649 -0.020000 0.201010 -vn 0.637724 -0.770263 0.002047 -v -0.085649 -0.021500 0.201010 -vn 0.551267 0.770259 0.320633 -v -0.085500 -0.020000 0.200460 -vn 0.551267 -0.770259 0.320633 -v -0.085500 -0.021500 0.200460 -vn 0.317112 0.770257 0.553303 -v -0.085096 -0.020000 0.200059 -vn 0.317112 -0.770257 0.553303 -v -0.085096 -0.021500 0.200059 -vn -0.002042 0.770273 0.637711 -v -0.084546 -0.020000 0.199913 -vn -0.002042 -0.770273 0.637711 -v -0.084546 -0.021500 0.199913 -vn -0.320646 0.770256 0.551264 -v -0.083996 -0.020000 0.200063 -vn -0.320646 -0.770256 0.551264 -v -0.083996 -0.021500 0.200063 -vn -0.553306 0.770260 0.317100 -v -0.083595 -0.020000 0.200467 -vn -0.553306 -0.770260 0.317100 -v -0.083595 -0.021500 0.200467 -vn -0.637722 0.770264 -0.002051 -v -0.075424 -0.020000 0.193043 -vn -0.637721 -0.770264 -0.002051 -v -0.075424 -0.021500 0.193043 -vn -0.551270 0.770256 -0.320635 -v -0.075573 -0.020000 0.193592 -vn -0.551270 -0.770256 -0.320635 -v -0.075573 -0.021500 0.193592 -vn -0.317109 0.770260 -0.553300 -v -0.075977 -0.020000 0.193994 -vn -0.317109 -0.770260 -0.553300 -v -0.075977 -0.021500 0.193994 -vn 0.002046 0.770271 -0.637713 -v -0.076527 -0.020000 0.194139 -vn 0.002046 -0.770271 -0.637713 -v -0.076527 -0.021500 0.194139 -vn 0.320646 0.770256 -0.551264 -v -0.077077 -0.020000 0.193990 -vn 0.320646 -0.770256 -0.551264 -v -0.077077 -0.021500 0.193990 -vn 0.553306 0.770260 -0.317100 -v -0.077478 -0.020000 0.193586 -vn 0.553306 -0.770260 -0.317100 -v -0.077478 -0.021500 0.193586 -vn 0.637723 0.770263 0.002036 -v -0.077624 -0.020000 0.193036 -vn 0.637723 -0.770263 0.002036 -v -0.077624 -0.021500 0.193036 -vn 0.551265 0.770262 0.320629 -v -0.077475 -0.020000 0.192486 -vn 0.551265 -0.770262 0.320629 -v -0.077475 -0.021500 0.192486 -vn 0.317078 0.770268 0.553308 -v -0.077071 -0.020000 0.192085 -vn 0.317078 -0.770268 0.553308 -v -0.077071 -0.021500 0.192085 -vn -0.002038 0.770249 0.637740 -v -0.076520 -0.020000 0.191939 -vn -0.002038 -0.770249 0.637740 -v -0.076520 -0.021500 0.191939 -vn -0.320615 0.770271 0.551261 -v -0.075971 -0.020000 0.192088 -vn -0.320614 -0.770271 0.551261 -v -0.075971 -0.021500 0.192088 -vn -0.553312 0.770260 0.317089 -v -0.075569 -0.020000 0.192492 -vn -0.553312 -0.770260 0.317089 -v -0.075569 -0.021500 0.192492 -vn -0.637722 0.770264 -0.002034 -v -0.067450 -0.020000 0.201068 -vn -0.637722 -0.770264 -0.002034 -v -0.067450 -0.021500 0.201068 -vn -0.551268 0.770261 -0.320627 -v -0.067599 -0.020000 0.201618 -vn -0.551268 -0.770261 -0.320627 -v -0.067599 -0.021500 0.201618 -vn -0.317080 0.770269 -0.553305 -v -0.068003 -0.020000 0.202019 -vn -0.317080 -0.770269 -0.553305 -v -0.068003 -0.021500 0.202019 -vn 0.002047 0.770253 -0.637736 -v -0.068553 -0.020000 0.202165 -vn 0.002048 -0.770253 -0.637736 -v -0.068553 -0.021500 0.202165 -vn 0.320619 0.770264 -0.551268 -v -0.069103 -0.020000 0.202016 -vn 0.320619 -0.770264 -0.551268 -v -0.069103 -0.021500 0.202016 -vn 0.553304 0.770266 -0.317087 -v -0.069504 -0.020000 0.201612 -vn 0.553304 -0.770266 -0.317087 -v -0.069504 -0.021500 0.201612 -vn 0.637726 0.770260 0.002053 -v -0.069650 -0.020000 0.201061 -vn 0.637727 -0.770260 0.002053 -v -0.069650 -0.021500 0.201061 -vn 0.551262 0.770261 0.320636 -v -0.069500 -0.020000 0.200512 -vn 0.551262 -0.770261 0.320636 -v -0.069500 -0.021500 0.200512 -vn 0.317112 0.770254 0.553308 -v -0.069096 -0.020000 0.200110 -vn 0.317112 -0.770253 0.553308 -v -0.069096 -0.021500 0.200110 -vn -0.002038 0.770275 0.637709 -v -0.068546 -0.020000 0.199965 -vn -0.002038 -0.770275 0.637709 -v -0.068546 -0.021500 0.199965 -vn -0.320650 0.770258 0.551258 -v -0.067996 -0.020000 0.200114 -vn -0.320650 -0.770258 0.551258 -v -0.067996 -0.021500 0.200114 -vn -0.553311 0.770257 0.317098 -v -0.067595 -0.020000 0.200518 -vn -0.553311 -0.770257 0.317098 -v -0.067595 -0.021500 0.200518 -vn -0.637727 0.770260 -0.002036 -v -0.075475 -0.020000 0.209043 -vn -0.637727 -0.770260 -0.002036 -v -0.075475 -0.021500 0.209043 -vn -0.551263 0.770265 -0.320627 -v -0.075624 -0.020000 0.209592 -vn -0.551263 -0.770265 -0.320627 -v -0.075624 -0.021500 0.209592 -vn -0.317076 0.770266 -0.553310 -v -0.076028 -0.020000 0.209993 -vn -0.317076 -0.770266 -0.553310 -v -0.076028 -0.021500 0.209993 -vn 0.002039 0.770249 -0.637740 -v -0.076579 -0.020000 0.210139 -vn 0.002040 -0.770249 -0.637740 -v -0.076579 -0.021500 0.210139 -vn 0.320614 0.770270 -0.551264 -v -0.077128 -0.020000 0.209990 -vn 0.320614 -0.770270 -0.551264 -v -0.077128 -0.021500 0.209990 -vn 0.553310 0.770263 -0.317086 -v -0.077529 -0.020000 0.209586 -vn 0.553310 -0.770263 -0.317086 -v -0.077529 -0.021500 0.209586 -vn 0.637725 0.770261 0.002051 -v -0.077675 -0.020000 0.209036 -vn 0.637726 -0.770261 0.002051 -v -0.077675 -0.021500 0.209036 -vn 0.551267 0.770259 0.320633 -v -0.077526 -0.020000 0.208486 -vn 0.551267 -0.770259 0.320633 -v -0.077526 -0.021500 0.208486 -vn 0.317107 0.770259 0.553303 -v -0.077122 -0.020000 0.208085 -vn 0.317107 -0.770259 0.553303 -v -0.077122 -0.021500 0.208085 -vn -0.002047 0.770272 0.637712 -v -0.076572 -0.020000 0.207939 -vn -0.002047 -0.770272 0.637712 -v -0.076572 -0.021500 0.207939 -vn -0.320646 0.770254 0.551266 -v -0.076022 -0.020000 0.208088 -vn -0.320646 -0.770254 0.551266 -v -0.076022 -0.021500 0.208088 -vn -0.553304 0.770263 0.317097 -v -0.075621 -0.020000 0.208492 -vn -0.553304 -0.770263 0.317097 -v -0.075621 -0.021500 0.208492 -vn 0.893179 -0.030816 -0.448644 -v -0.069665 -0.031000 0.184896 -vn 0.836482 0.375655 -0.398974 -v -0.064403 -0.020500 0.194078 -vn 0.836483 -0.375655 -0.398973 -v -0.064403 -0.026500 0.194078 -vn 0.854685 -0.333032 -0.398250 -v -0.066590 -0.026500 0.190262 -vn 0.889662 -0.456432 -0.013055 -v -0.067090 -0.027450 0.189388 -vn 0.861696 -0.408503 -0.301008 -v -0.069255 -0.030837 0.185611 -vn 0.894852 -0.424031 -0.139418 -v -0.068648 -0.030139 0.186671 -vn 0.895706 -0.440967 -0.057091 -v -0.067851 -0.028839 0.188062 -vn 0.909048 0.362113 -0.206167 -v -0.062872 -0.020500 0.198053 -vn 0.907585 -0.370168 -0.198156 -v -0.062872 -0.026500 0.198053 -vn 0.925524 0.368775 0.086085 -v -0.062607 -0.020500 0.202304 -vn 0.925168 -0.370162 0.083930 -v -0.062607 -0.026500 0.202304 -vn 0.857106 0.370172 0.358248 -v -0.063632 -0.020500 0.206438 -vn 0.857106 -0.370171 0.358249 -v -0.063632 -0.026500 0.206438 -vn 0.709709 0.370176 0.599402 -v -0.065854 -0.020500 0.210072 -vn 0.709710 -0.370175 0.599402 -v -0.065854 -0.026500 0.210072 -vn 0.496617 0.370176 0.785074 -v -0.069065 -0.020500 0.212871 -vn 0.496617 -0.370176 0.785074 -v -0.069065 -0.026500 0.212871 -vn 0.237558 0.370168 0.898077 -v -0.072969 -0.020500 0.214574 -vn 0.237559 -0.370168 0.898077 -v -0.072969 -0.026500 0.214574 -vn -0.032847 0.362511 0.931401 -v -0.077205 -0.020500 0.215024 -vn -0.043496 -0.370174 0.927943 -v -0.077205 -0.026500 0.215024 -vn -0.331226 0.362855 0.870991 -v -0.081380 -0.020500 0.214179 -vn -0.320522 -0.370150 0.871926 -v -0.081380 -0.026500 0.214179 -vn -0.567875 0.370159 0.735187 -v -0.085108 -0.020500 0.212119 -vn -0.567875 -0.370158 0.735188 -v -0.085108 -0.026500 0.212119 -vn -0.762663 0.370173 0.530393 -v -0.088043 -0.020500 0.209032 -vn -0.762664 -0.370172 0.530392 -v -0.088043 -0.026500 0.209032 -vn -0.886859 0.370172 0.276505 -v -0.089915 -0.020500 0.205206 -vn -0.886859 -0.370172 0.276504 -v -0.089915 -0.026500 0.205206 -vn 0.795647 -0.402892 -0.452353 -v -0.080020 -0.026500 0.203028 -vn 0.462902 0.738318 -0.490518 -v -0.079200 -0.020000 0.204035 -vn 0.457455 -0.402685 -0.792830 -v -0.078561 -0.026500 0.204497 -vn 0.284986 0.749773 -0.597180 -v -0.078561 -0.020000 0.204497 -vn 0.002926 -0.406973 -0.913436 -v -0.076562 -0.026500 0.205039 -vn 0.002043 0.770263 -0.637723 -v -0.076562 -0.020000 0.205039 -vn -0.454186 -0.406964 -0.792525 -v -0.074561 -0.026500 0.204510 -vn -0.317092 0.770260 -0.553310 -v -0.074561 -0.020000 0.204510 -vn -0.789599 -0.406956 -0.459261 -v -0.073092 -0.026500 0.203050 -vn -0.551261 0.770263 -0.320633 -v -0.073092 -0.020000 0.203050 -vn -0.913439 -0.406965 -0.002921 -v -0.072549 -0.026500 0.201052 -vn -0.637724 0.770262 -0.002040 -v -0.072549 -0.020000 0.201052 -vn -0.795749 -0.402664 0.452377 -v -0.073079 -0.026500 0.199050 -vn -0.598994 0.749772 0.281154 -v -0.073079 -0.020000 0.199050 -vn -0.493474 0.738319 0.459749 -v -0.073536 -0.020000 0.198408 -vn -0.457440 -0.402871 0.792744 -v -0.074538 -0.026500 0.197581 -vn -0.299834 0.757795 0.579523 -v -0.074538 -0.020000 0.197581 -vn -0.002921 -0.406967 0.913438 -v -0.076537 -0.026500 0.197039 -vn -0.002043 0.770256 0.637732 -v -0.076537 -0.020000 0.197039 -vn 0.452364 -0.402660 0.795759 -v -0.078538 -0.026500 0.197569 -vn 0.281142 0.749775 0.598996 -v -0.078538 -0.020000 0.197569 -vn 0.444197 0.729550 0.520045 -v -0.079180 -0.020000 0.198026 -vn 0.517215 0.729540 0.447505 -v -0.079546 -0.020000 0.198389 -vn 0.792831 -0.402677 0.457460 -v -0.080007 -0.026500 0.199028 -vn 0.597182 0.749772 0.284984 -v -0.080007 -0.020000 0.199028 -vn 0.913439 -0.406965 0.002932 -v -0.080549 -0.026500 0.201026 -vn 0.637724 0.770262 0.002046 -v -0.080549 -0.020000 0.201026 -vn 0.581432 0.757792 -0.296121 -v -0.080020 -0.020000 0.203028 -vn 0.913438 -0.406966 0.002932 -v -0.080549 0.025300 0.201026 -vn 0.913439 0.406966 0.002930 -v -0.080549 0.026500 0.201026 -vn 0.792521 -0.406969 -0.454189 -v -0.080020 0.025300 0.203028 -vn 0.792521 0.406966 -0.454192 -v -0.080020 0.026500 0.203028 -vn 0.459247 -0.406976 -0.789597 -v -0.078561 0.025300 0.204497 -vn 0.459250 0.406974 -0.789596 -v -0.078561 0.026500 0.204497 -vn 0.002926 -0.406974 -0.913435 -v -0.076562 0.025300 0.205039 -vn 0.002926 0.406974 -0.913435 -v -0.076562 0.026500 0.205039 -vn -0.454186 -0.406965 -0.792524 -v -0.074561 0.025300 0.204510 -vn -0.454185 0.406966 -0.792525 -v -0.074561 0.026500 0.204510 -vn -0.789598 -0.406957 -0.459260 -v -0.073092 0.025300 0.203050 -vn -0.789600 0.406957 -0.459258 -v -0.073092 0.026500 0.203050 -vn -0.913439 -0.406966 -0.002921 -v -0.072549 0.025300 0.201052 -vn -0.913439 0.406964 -0.002924 -v -0.072549 0.026500 0.201052 -vn -0.792527 -0.406954 0.454190 -v -0.073079 0.025300 0.199050 -vn -0.792527 0.406955 0.454189 -v -0.073079 0.026500 0.199050 -vn -0.459256 -0.406948 0.789606 -v -0.074538 0.025300 0.197581 -vn -0.459251 0.406944 0.789611 -v -0.074538 0.026500 0.197581 -vn -0.002921 -0.406968 0.913438 -v -0.076537 0.025300 0.197039 -vn -0.002932 0.406967 0.913438 -v -0.076537 0.026500 0.197039 -vn 0.454177 -0.406951 0.792537 -v -0.078538 0.025300 0.197569 -vn 0.454183 0.406952 0.792533 -v -0.078538 0.026500 0.197569 -vn 0.789598 -0.406968 0.459252 -v -0.080007 0.025300 0.199028 -vn 0.789597 0.406966 0.459255 -v -0.080007 0.026500 0.199028 -vn 0.903563 0.301512 0.304408 -v -0.076281 -0.031000 0.117200 -vn 0.903563 -0.301512 0.304407 -v -0.076281 0.031000 0.117200 -vn 0.893181 0.030812 -0.448641 -v -0.069665 0.031000 0.184896 -vn 0.893896 0.427579 -0.134632 -v -0.068648 0.030139 0.186671 -vn 0.895263 0.442690 -0.050288 -v -0.067850 0.028838 0.188062 -vn 0.888624 0.377344 -0.260689 -v -0.066672 0.026658 0.190118 -vn 0.930004 0.318462 -0.183508 -v -0.066515 0.026500 0.190392 -vn 0.930002 -0.318470 -0.183499 -v -0.066515 0.020500 0.190392 -vn 0.862463 0.422309 -0.278950 -v -0.069255 0.030837 0.185611 -vn 0.748214 0.066986 -0.660067 -v -0.076245 0.033000 0.105851 -vn 0.748215 -0.066987 -0.660066 -v -0.076245 -0.033000 0.105851 -vn -0.617669 0.077215 -0.782638 -v -0.090237 0.033000 0.103337 -vn -0.617669 -0.077215 -0.782638 -v -0.090237 -0.033000 0.103337 -vn 0.839495 -0.471729 -0.269664 -v -0.076268 0.031800 0.113142 -vn 0.840370 -0.000000 -0.542013 -v -0.076273 0.029000 0.114759 -vn 0.839495 0.471730 -0.269664 -v -0.076268 0.026200 0.113142 -vn 0.837750 0.471729 0.275039 -v -0.076258 0.026200 0.109909 -vn 0.836880 0.000000 0.547386 -v -0.076252 0.029000 0.108292 -vn 0.725026 0.273121 -0.632252 -v -0.076245 0.033765 0.106005 -vn 0.837750 -0.471729 0.275038 -v -0.076258 0.031800 0.109909 -vn 0.690445 0.675632 -0.258473 -v -0.076249 0.034848 0.107104 -vn 0.711111 0.509494 -0.484496 -v -0.076246 0.034414 0.106445 -vn 0.839496 -0.471729 -0.269664 -v -0.076268 -0.026200 0.113142 -vn 0.840370 -0.000000 -0.542013 -v -0.076273 -0.029000 0.114759 -vn 0.839495 0.471729 -0.269664 -v -0.076268 -0.031800 0.113142 -vn 0.837750 0.471729 0.275038 -v -0.076258 -0.031800 0.109909 -vn 0.836881 -0.000000 0.547386 -v -0.076252 -0.029000 0.108292 -vn 0.690056 -0.676130 -0.258207 -v -0.076249 -0.034848 0.107104 -vn 0.711112 -0.509493 -0.484496 -v -0.076246 -0.034414 0.106445 -vn 0.837750 -0.471730 0.275039 -v -0.076258 -0.026200 0.109909 -vn 0.725029 -0.273119 -0.632249 -v -0.076245 -0.033765 0.106005 -vn -0.687996 -0.071405 0.722193 -v -0.090249 -0.033000 0.107337 -vn -0.687996 0.071406 0.722193 -v -0.090249 0.033000 0.107337 -vn -0.601694 -0.302645 -0.739168 -v -0.090237 -0.033765 0.103492 -vn -0.616802 -0.551128 -0.561973 -v -0.090238 -0.034414 0.103932 -vn -0.640782 -0.702469 -0.309736 -v -0.090241 -0.034848 0.104591 -vn -0.667354 -0.528142 0.525075 -v -0.090247 -0.034415 0.106750 -vn -0.667877 -0.285859 0.687186 -v -0.090249 -0.033766 0.107185 -vn -0.668946 -0.685998 0.286214 -v -0.090245 -0.034849 0.106100 -vn -0.663655 -0.747979 -0.009434 -v -0.090243 -0.035000 0.105353 -vn -0.667881 0.285859 0.687182 -v -0.090249 0.033766 0.107185 -vn -0.667359 0.528138 0.525074 -v -0.090247 0.034415 0.106750 -vn -0.667055 0.688753 0.284001 -v -0.090245 0.034849 0.106100 -vn -0.601693 0.302646 -0.739169 -v -0.090237 0.033765 0.103492 -vn -0.616800 0.551129 -0.561973 -v -0.090238 0.034414 0.103932 -vn -0.640781 0.702469 -0.309737 -v -0.090241 0.034848 0.104591 -vn -0.662025 0.749454 -0.006432 -v -0.090243 0.035000 0.105353 -vn -0.392430 0.911639 0.122117 -v -0.089983 -0.020000 0.180157 -vn -0.092829 0.882742 0.460596 -v -0.079173 -0.020000 0.214282 -vn 0.413424 0.909481 -0.043877 -v -0.063285 -0.020000 0.198528 -vn 0.410194 0.911107 0.040306 -v -0.063105 -0.020000 0.202259 -vn 0.381532 0.910496 0.159467 -v -0.064094 -0.020000 0.206245 -vn 0.315916 0.910498 0.266815 -v -0.066236 -0.020000 0.209750 -vn 0.221060 0.910499 0.349462 -v -0.069332 -0.020000 0.212448 -vn 0.105748 0.910494 0.399772 -v -0.073097 -0.020000 0.214090 -vn -0.002229 0.913880 0.405979 -v -0.077182 -0.020000 0.214524 -vn 0.123767 0.940389 0.316782 -v -0.069418 -0.020000 0.182818 -vn 0.605421 0.751842 0.261149 -v -0.068892 -0.020000 0.182724 -vn 0.383974 0.916358 -0.113371 -v -0.063360 -0.020000 0.198159 -vn 0.360846 0.916918 -0.170445 -v -0.064837 -0.020000 0.194327 -vn 0.329960 0.932623 -0.146086 -v -0.070199 -0.020000 0.184970 -vn 0.334590 0.941919 -0.028954 -v -0.070392 -0.020000 0.184354 -vn 0.315743 0.941918 0.114439 -v -0.070307 -0.020000 0.183713 -vn 0.238327 0.941924 0.236600 -v -0.069962 -0.020000 0.183168 -vn -0.382681 0.923880 -0.001226 -v -0.090041 -0.020000 0.198446 -vn -0.397932 0.916916 0.030267 -v -0.090049 -0.020000 0.200996 -vn -0.394774 0.910497 0.123081 -v -0.089438 -0.020000 0.205057 -vn -0.339492 0.910497 0.236096 -v -0.087633 -0.020000 0.208747 -vn -0.252792 0.910489 0.327270 -v -0.084802 -0.020000 0.211723 -vn -0.155081 0.913698 0.375641 -v -0.081207 -0.020000 0.213710 -vn -0.140028 0.381444 0.913725 -v -0.072044 0.031000 0.187784 -vn -0.032067 0.370646 0.928220 -v -0.076066 0.031000 0.187047 -vn 0.237506 0.370646 0.897893 -v -0.080130 0.031000 0.187505 -vn 0.486821 0.370648 0.790965 -v -0.083888 0.031000 0.189116 -vn 0.573500 0.381449 0.724979 -v -0.087020 0.031000 0.191745 -vn 0.459528 0.392841 0.796562 -v -0.087665 0.031000 0.192228 -vn 0.269837 0.390575 0.880136 -v -0.087809 0.031000 0.192289 -vn 0.069353 0.391686 0.917482 -v -0.088448 0.031000 0.192417 -vn -0.132470 0.389258 0.911554 -v -0.088760 0.031000 0.192403 -vn -0.329362 0.395380 0.857435 -v -0.089242 0.031000 0.192281 -vn -0.512980 0.392357 0.763484 -v -0.089655 0.031000 0.192061 -vn -0.668169 0.393771 0.631264 -v -0.089918 0.031000 0.191843 -vn -0.795678 0.379028 0.472476 -v -0.090289 0.031000 0.191342 -vn -0.875303 0.393033 0.281726 -v -0.090367 0.031000 0.191174 -vn 0.908730 0.379951 -0.172765 -v -0.069417 0.031000 0.185632 -vn 0.935699 0.352798 -0.000614 -v -0.069401 0.031000 0.185817 -vn 0.893340 0.391277 0.221009 -v -0.069476 0.031000 0.186436 -vn 0.825520 0.389601 0.408324 -v -0.069597 0.031000 0.186755 -vn 0.710468 0.396403 0.581463 -v -0.069847 0.031000 0.187151 -vn 0.565900 0.392083 0.725278 -v -0.070206 0.031000 0.187495 -vn 0.389682 0.391353 0.833661 -v -0.070470 0.031000 0.187661 -vn 0.203145 0.387934 0.899022 -v -0.071089 0.031000 0.187866 -vn -0.005470 0.392850 0.919586 -v -0.071244 0.031000 0.187884 -vn -0.793633 0.333702 0.508714 -v -0.090199 0.026500 0.196696 -vn 0.573954 -0.381422 0.724634 -v -0.087020 -0.031000 0.191745 -vn 0.486822 -0.370647 0.790965 -v -0.083888 -0.031000 0.189116 -vn 0.239706 -0.368168 0.898328 -v -0.080130 -0.031000 0.187505 -vn -0.033968 -0.367283 0.929489 -v -0.076066 -0.031000 0.187047 -vn -0.140030 -0.381445 0.913724 -v -0.072044 -0.031000 0.187784 -vn 0.152980 -0.938184 0.310498 -v -0.068611 -0.027000 0.191203 -vn 0.437938 -0.852398 0.285707 -v -0.067210 -0.027000 0.190185 -vn 0.360847 -0.916918 -0.170443 -v -0.064837 -0.027000 0.194327 -vn 0.145075 -0.940659 0.306779 -v -0.085951 -0.027000 0.195842 -vn 0.237040 -0.924852 0.297423 -v -0.084028 -0.027000 0.194401 -vn -0.001047 -0.945442 0.325788 -v -0.084542 -0.027000 0.198764 -vn -0.163803 -0.945440 0.281623 -v -0.074287 -0.027000 0.197149 -vn -0.001048 -0.945441 0.325792 -v -0.068542 -0.027000 0.198815 -vn -0.282660 -0.945444 0.161988 -v -0.072645 -0.027000 0.198802 -vn 0.161985 -0.945445 0.282655 -v -0.069668 -0.027000 0.199113 -vn -0.325775 -0.945447 -0.001041 -v -0.072049 -0.027000 0.201054 -vn -0.163785 -0.945447 0.281611 -v -0.083418 -0.027000 0.199069 -vn 0.216120 -0.911042 0.351135 -v -0.081791 -0.027000 0.192523 -vn 0.118679 -0.914209 0.387476 -v -0.079107 -0.027000 0.191372 -vn -0.221634 -0.942118 -0.251580 -v -0.075047 -0.027000 0.194737 -vn -0.312352 -0.942204 -0.121192 -v -0.074431 -0.027000 0.193865 -vn 0.026003 -0.940536 0.338696 -v -0.070933 -0.027000 0.191872 -vn -0.332434 -0.942439 0.036007 -v -0.074286 -0.027000 0.192807 -vn -0.063534 -0.925610 0.373109 -v -0.073331 -0.027000 0.191571 -vn -0.280501 -0.942220 0.183141 -v -0.074645 -0.027000 0.191801 -vn -0.182977 -0.751364 0.634012 -v -0.075367 -0.027000 0.191109 -vn 0.381532 -0.910497 0.159467 -v -0.064094 -0.027000 0.206245 -vn 0.315916 -0.910498 0.266815 -v -0.066236 -0.027000 0.209750 -vn 0.001049 -0.945442 -0.325788 -v -0.068557 -0.027000 0.203315 -vn -0.161981 -0.945450 -0.282642 -v -0.067431 -0.027000 0.203017 -vn -0.281603 -0.945448 -0.163792 -v -0.066605 -0.027000 0.202196 -vn 0.411837 -0.910491 0.037361 -v -0.063105 -0.027000 0.202259 -vn -0.325775 -0.945447 -0.001043 -v -0.066300 -0.027000 0.201072 -vn 0.404003 -0.910494 -0.088211 -v -0.063360 -0.027000 0.198159 -vn -0.282658 -0.945444 0.161988 -v -0.066597 -0.027000 0.199946 -vn -0.163778 -0.945451 0.281602 -v -0.067418 -0.027000 0.199120 -vn -0.001041 -0.945448 0.325772 -v -0.076535 -0.027000 0.196539 -vn -0.085037 -0.941131 -0.327171 -v -0.075997 -0.027000 0.195227 -vn 0.228101 -0.939086 -0.257073 -v -0.078011 -0.027000 0.194728 -vn -0.282657 -0.945444 0.161988 -v -0.082597 -0.027000 0.199895 -vn 0.319670 -0.939675 -0.121745 -v -0.078622 -0.027000 0.193851 -vn 0.337217 -0.940600 0.039461 -v -0.078760 -0.027000 0.192792 -vn 0.282807 -0.940723 0.187245 -v -0.078394 -0.027000 0.191789 -vn 0.161069 -0.755026 0.635604 -v -0.077668 -0.027000 0.191102 -vn 0.083263 -0.938796 -0.334261 -v -0.077065 -0.027000 0.195223 -vn 0.161990 -0.945442 0.282663 -v -0.078787 -0.027000 0.197135 -vn 0.281608 -0.945447 0.163788 -v -0.080439 -0.027000 0.198777 -vn -0.325775 -0.945447 -0.001043 -v -0.082299 -0.027000 0.201021 -vn 0.325776 -0.945446 0.001045 -v -0.081049 -0.027000 0.201025 -vn -0.281605 -0.945447 -0.163792 -v -0.082604 -0.027000 0.202145 -vn 0.282653 -0.945447 -0.161981 -v -0.080454 -0.027000 0.203277 -vn 0.163787 -0.945449 -0.281602 -v -0.078812 -0.027000 0.204929 -vn -0.001044 -0.945453 0.325757 -v -0.076568 -0.027000 0.206789 -vn 0.001043 -0.945449 -0.325768 -v -0.076564 -0.027000 0.205539 -vn -0.163793 -0.945447 0.281605 -v -0.075444 -0.027000 0.207094 -vn -0.161984 -0.945446 -0.282652 -v -0.074312 -0.027000 0.204943 -vn -0.282651 -0.945448 0.161980 -v -0.074623 -0.027000 0.207920 -vn 0.022444 -0.938257 0.345209 -v -0.088284 -0.027000 0.196413 -vn 0.161983 -0.945448 0.282649 -v -0.085668 -0.027000 0.199061 -vn -0.238251 -0.851741 0.466662 -v -0.090034 -0.027000 0.196222 -vn 0.281611 -0.945445 0.163796 -v -0.086494 -0.027000 0.199882 -vn -0.397932 -0.916916 0.030268 -v -0.090049 -0.027000 0.200996 -vn 0.325776 -0.945446 0.001046 -v -0.086799 -0.027000 0.201006 -vn -0.394775 -0.910497 0.123080 -v -0.089438 -0.027000 0.205057 -vn 0.282647 -0.945448 -0.161983 -v -0.086502 -0.027000 0.202132 -vn -0.339492 -0.910497 0.236094 -v -0.087633 -0.027000 0.208747 -vn 0.163786 -0.945449 -0.281603 -v -0.085681 -0.027000 0.202958 -vn -0.252791 -0.910490 0.327269 -v -0.084802 -0.027000 0.211723 -vn 0.001048 -0.945440 -0.325795 -v -0.084557 -0.027000 0.203263 -vn 0.281604 -0.945448 0.163791 -v -0.078520 -0.027000 0.207908 -vn -0.161984 -0.945446 -0.282654 -v -0.083431 -0.027000 0.202966 -vn 0.161985 -0.945449 0.282644 -v -0.077694 -0.027000 0.207087 -vn 0.325767 -0.945450 0.001044 -v -0.078825 -0.027000 0.209032 -vn 0.282638 -0.945452 -0.161978 -v -0.078527 -0.027000 0.210158 -vn -0.142681 -0.910484 0.388150 -v -0.081207 -0.027000 0.213710 -vn 0.163785 -0.945451 -0.281597 -v -0.077706 -0.027000 0.210984 -vn -0.019362 -0.910498 0.413060 -v -0.077182 -0.027000 0.214524 -vn 0.001041 -0.945449 -0.325768 -v -0.076582 -0.027000 0.211289 -vn 0.105749 -0.910494 0.399772 -v -0.073097 -0.027000 0.214090 -vn -0.161977 -0.945450 -0.282646 -v -0.075456 -0.027000 0.210991 -vn 0.221060 -0.910499 0.349463 -v -0.069332 -0.027000 0.212448 -vn -0.281596 -0.945452 -0.163781 -v -0.074630 -0.027000 0.210170 -vn -0.325778 -0.945446 -0.001043 -v -0.074325 -0.027000 0.209046 -vn 0.163787 -0.945448 -0.281605 -v -0.069681 -0.027000 0.203010 -vn 0.282645 -0.945449 -0.161984 -v -0.070502 -0.027000 0.202184 -vn -0.281614 -0.945444 -0.163797 -v -0.072660 -0.027000 0.203302 -vn 0.325776 -0.945446 0.001045 -v -0.070799 -0.027000 0.201058 -vn 0.281610 -0.945445 0.163796 -v -0.070494 -0.027000 0.199933 -vn -0.873587 -0.379634 0.304506 -v -0.090358 -0.031000 0.191196 -vn -0.811103 -0.352647 0.466638 -v -0.090289 -0.031000 0.191342 -vn -0.664203 -0.391043 0.637118 -v -0.089904 -0.031000 0.191857 -vn -0.512604 -0.389372 0.765262 -v -0.089655 -0.031000 0.192061 -vn -0.327029 -0.396695 0.857721 -v -0.089229 -0.031000 0.192286 -vn -0.130305 -0.392436 0.910502 -v -0.088760 -0.031000 0.192403 -vn 0.075700 -0.391324 0.917134 -v -0.088438 -0.031000 0.192416 -vn 0.269646 -0.387848 0.881399 -v -0.087809 -0.031000 0.192289 -vn 0.460490 -0.392865 0.795994 -v -0.087661 -0.031000 0.192226 -vn -0.005469 -0.392852 0.919586 -v -0.071244 -0.031000 0.187884 -vn 0.200733 -0.390562 0.898425 -v -0.071089 -0.031000 0.187866 -vn 0.394209 -0.390876 0.831755 -v -0.070470 -0.031000 0.187661 -vn 0.565453 -0.388069 0.727781 -v -0.070206 -0.031000 0.187495 -vn 0.710237 -0.395390 0.582434 -v -0.069847 -0.031000 0.187151 -vn 0.823392 -0.392338 0.409996 -v -0.069597 -0.031000 0.186755 -vn 0.892897 -0.393766 0.218364 -v -0.069476 -0.031000 0.186436 -vn 0.925232 -0.379011 0.017230 -v -0.069401 -0.031000 0.185817 -vn 0.900129 -0.393003 -0.187928 -v -0.069417 -0.031000 0.185632 -vn 0.264191 -0.404787 0.875415 -v -0.077397 -0.026554 0.191523 -vn 0.535939 -0.353762 0.766565 -v -0.077500 -0.026500 0.191587 -vn -0.173717 -0.408278 0.896176 -v -0.076056 -0.026699 0.191353 -vn -0.092590 -0.402165 0.910874 -v -0.076211 -0.026728 0.191317 -vn 0.010020 -0.411021 0.911571 -v -0.076518 -0.026750 0.191289 -vn 0.141382 -0.414330 0.899078 -v -0.076980 -0.026699 0.191350 -vn -0.269812 -0.406071 0.873102 -v -0.075644 -0.026556 0.191526 -vn -0.545251 -0.349706 0.761844 -v -0.075538 -0.026500 0.191593 -vn 0.521513 0.430449 0.736707 -v -0.068831 -0.020498 0.183225 -vn 0.543397 0.352369 0.761943 -v -0.068626 -0.021000 0.183225 -vn 0.316390 0.552285 0.771284 -v -0.067894 -0.021732 0.183228 -vn 0.085757 0.669353 0.737978 -v -0.066894 -0.022000 0.183231 -vn 0.187864 -0.709235 0.679480 -v -0.061046 -0.034659 0.183250 -vn 0.741517 0.117775 0.660517 -v -0.047919 -0.022844 0.183292 -vn 0.606960 0.442529 0.660127 -v -0.048098 -0.022412 0.183291 -vn 0.339711 0.670836 0.659224 -v -0.048453 -0.022109 0.183290 -vn 0.364950 -0.635883 0.680047 -v -0.058635 -0.033660 0.183257 -vn 0.473328 -0.542264 0.694198 -v -0.056563 -0.032071 0.183264 -vn 0.083823 0.726666 0.681858 -v -0.048907 -0.022000 0.183288 -vn 0.572472 -0.453006 0.683419 -v -0.048200 -0.023707 0.183291 -vn 0.713928 -0.232659 0.660437 -v -0.047956 -0.023309 0.183291 -vn 0.281608 -0.945447 0.163788 -v -0.080439 0.024800 0.198777 -vn 0.562691 -0.656999 0.501729 -v -0.080393 0.024800 0.197612 -vn 0.161990 -0.945442 0.282662 -v -0.078787 0.024800 0.197135 -vn 0.265075 -0.657000 0.705752 -v -0.078360 0.024800 0.196218 -vn -0.001041 -0.945448 0.325771 -v -0.076535 0.024800 0.196539 -vn -0.093259 -0.657000 0.748100 -v -0.075912 0.024800 0.195929 -vn -0.163803 -0.945441 0.281622 -v -0.074287 0.024800 0.197149 -vn -0.430244 -0.656996 0.619069 -v -0.073610 0.024800 0.196810 -vn -0.282659 -0.945444 0.161988 -v -0.072645 0.024800 0.198802 -vn -0.668657 -0.657001 0.348206 -v -0.071982 0.024800 0.198660 -vn -0.325774 -0.945447 -0.001041 -v -0.072049 0.024800 0.201054 -vn -0.753887 -0.656999 -0.002412 -v -0.071400 0.024800 0.201056 -vn -0.281613 -0.945444 -0.163796 -v -0.072660 0.024800 0.203302 -vn -0.666413 -0.656998 -0.352488 -v -0.071997 0.024800 0.203447 -vn -0.161983 -0.945447 -0.282652 -v -0.074312 0.024800 0.204943 -vn -0.426268 -0.657000 -0.621809 -v -0.073638 0.024800 0.205287 -vn 0.001043 -0.945449 -0.325768 -v -0.076564 0.024800 0.205539 -vn -0.088473 -0.656998 -0.748683 -v -0.075945 0.024800 0.206154 -vn 0.163787 -0.945449 -0.281602 -v -0.078812 0.024800 0.204929 -vn 0.269590 -0.657000 -0.704040 -v -0.078391 0.024800 0.205849 -vn 0.282652 -0.945447 -0.161981 -v -0.080454 0.024800 0.203277 -vn 0.565893 -0.656999 -0.498114 -v -0.080415 0.024800 0.204442 -vn 0.710576 -0.668695 -0.218925 -v -0.081554 0.024800 0.202256 -vn 0.325775 -0.945447 0.001045 -v -0.081049 0.024800 0.201025 -vn 0.734545 -0.678556 0.002355 -v -0.081699 0.024800 0.201023 -vn 0.709158 -0.668696 0.223475 -v -0.081546 0.024800 0.199791 -vn 0.888565 -0.398232 0.227734 -v -0.081546 0.020500 0.199791 -vn 0.890008 -0.398225 -0.222041 -v -0.081554 0.020500 0.202256 -vn 0.686317 -0.404994 -0.604110 -v -0.080415 0.020500 0.204442 -vn 0.326960 -0.404999 -0.853858 -v -0.078391 0.020500 0.205849 -vn -0.107300 -0.405003 -0.907997 -v -0.075945 0.020500 0.206154 -vn -0.516983 -0.404981 -0.754134 -v -0.073638 0.020500 0.205287 -vn -0.808227 -0.404983 -0.427501 -v -0.071997 0.020500 0.203447 -vn -0.914320 -0.404983 -0.002926 -v -0.071400 0.020500 0.201056 -vn -0.810951 -0.404982 0.422312 -v -0.071982 0.020500 0.198660 -vn -0.521810 -0.404964 0.750812 -v -0.073610 0.020500 0.196810 -vn -0.113102 -0.405002 0.907293 -v -0.075912 0.020500 0.195929 -vn 0.321485 -0.404996 0.855935 -v -0.078360 0.020500 0.196218 -vn 0.682432 -0.404995 0.608495 -v -0.080393 0.020500 0.197612 -vn 0.380682 -0.653221 -0.654510 -v -0.077455 -0.021500 0.210552 -vn 0.656934 -0.653230 -0.376469 -v -0.078093 -0.021500 0.209909 -vn 0.757159 -0.653226 0.002425 -v -0.078325 -0.021500 0.209033 -vn 0.654502 -0.653225 0.380689 -v -0.078088 -0.021500 0.208159 -vn 0.376479 -0.653232 0.656925 -v -0.077445 -0.021500 0.207521 -vn -0.002425 -0.653221 0.757164 -v -0.076569 -0.021500 0.207289 -vn -0.380679 -0.653232 0.654500 -v -0.075695 -0.021500 0.207526 -vn -0.656928 -0.653224 0.376489 -v -0.075057 -0.021500 0.208169 -vn -0.757159 -0.653227 -0.002426 -v -0.074825 -0.021500 0.209045 -vn -0.654508 -0.653229 -0.380672 -v -0.075062 -0.021500 0.209919 -vn -0.376479 -0.653222 -0.656936 -v -0.075705 -0.021500 0.210557 -vn 0.002424 -0.653232 -0.757154 -v -0.076581 -0.021500 0.210789 -vn 0.913434 -0.406977 0.002927 -v -0.078325 -0.026500 0.209033 -vn 0.792525 -0.406980 -0.454172 -v -0.078093 -0.026500 0.209909 -vn 0.459251 -0.406981 -0.789592 -v -0.077455 -0.026500 0.210552 -vn 0.002921 -0.406975 -0.913434 -v -0.076581 -0.026500 0.210789 -vn -0.454175 -0.406979 -0.792523 -v -0.075705 -0.026500 0.210557 -vn -0.789602 -0.406980 -0.459235 -v -0.075062 -0.026500 0.209919 -vn -0.913438 -0.406966 -0.002930 -v -0.074825 -0.026500 0.209045 -vn -0.792515 -0.406973 0.454195 -v -0.075057 -0.026500 0.208169 -vn -0.459254 -0.406973 0.789594 -v -0.075695 -0.026500 0.207526 -vn -0.002927 -0.406984 0.913430 -v -0.076569 -0.026500 0.207289 -vn 0.454192 -0.406973 0.792517 -v -0.077445 -0.026500 0.207521 -vn 0.789588 -0.406970 0.459266 -v -0.078088 -0.026500 0.208159 -vn 0.380696 -0.653228 -0.654495 -v -0.069429 -0.021500 0.202577 -vn 0.656935 -0.653228 -0.376471 -v -0.070068 -0.021500 0.201935 -vn 0.757158 -0.653227 0.002426 -v -0.070299 -0.021500 0.201059 -vn 0.654504 -0.653224 0.380688 -v -0.070062 -0.021500 0.200185 -vn 0.376480 -0.653232 0.656925 -v -0.069420 -0.021500 0.199546 -vn -0.002431 -0.653219 0.757165 -v -0.068544 -0.021500 0.199315 -vn -0.380673 -0.653237 0.654500 -v -0.067670 -0.021500 0.199552 -vn -0.656926 -0.653221 0.376498 -v -0.067031 -0.021500 0.200195 -vn -0.757158 -0.653227 -0.002428 -v -0.066800 -0.021500 0.201070 -vn -0.654505 -0.653227 -0.380681 -v -0.067037 -0.021500 0.201945 -vn -0.376489 -0.653230 -0.656922 -v -0.067679 -0.021500 0.202583 -vn 0.002424 -0.653221 -0.757164 -v -0.068555 -0.021500 0.202815 -vn 0.913439 -0.406965 0.002926 -v -0.070299 -0.026500 0.201059 -vn 0.792530 -0.406968 -0.454174 -v -0.070068 -0.026500 0.201935 -vn 0.459271 -0.406963 -0.789589 -v -0.069429 -0.026500 0.202577 -vn 0.002933 -0.406959 -0.913442 -v -0.068555 -0.026500 0.202815 -vn -0.454198 -0.406978 -0.792511 -v -0.067679 -0.026500 0.202583 -vn -0.789598 -0.406971 -0.459249 -v -0.067037 -0.026500 0.201945 -vn -0.913440 -0.406964 -0.002926 -v -0.066800 -0.026500 0.201070 -vn -0.792516 -0.406965 0.454200 -v -0.067031 -0.026500 0.200195 -vn -0.459239 -0.406969 0.789605 -v -0.067670 -0.026500 0.199552 -vn -0.002941 -0.406952 0.913445 -v -0.068544 -0.026500 0.199315 -vn 0.454195 -0.406961 0.792521 -v -0.069420 -0.026500 0.199546 -vn 0.789593 -0.406961 0.459266 -v -0.070062 -0.026500 0.200185 -vn 0.218415 -0.900722 -0.375493 -v -0.077152 -0.021500 0.194120 -vn 0.376864 -0.900739 -0.215971 -v -0.077608 -0.021500 0.193661 -vn 0.434368 -0.900734 0.001388 -v -0.077774 -0.021500 0.193035 -vn 0.375485 -0.900730 0.218393 -v -0.077604 -0.021500 0.192411 -vn 0.215988 -0.900738 0.376855 -v -0.077145 -0.021500 0.191955 -vn -0.001405 -0.900727 0.434383 -v -0.076520 -0.021500 0.191789 -vn -0.218374 -0.900743 0.375465 -v -0.075895 -0.021500 0.191959 -vn -0.376873 -0.900733 0.215977 -v -0.075439 -0.021500 0.192418 -vn -0.434371 -0.900733 -0.001398 -v -0.075274 -0.021500 0.193043 -vn -0.375476 -0.900740 -0.218370 -v -0.075443 -0.021500 0.193668 -vn -0.215972 -0.900724 -0.376898 -v -0.075902 -0.021500 0.194124 -vn 0.001374 -0.900744 -0.434348 -v -0.076528 -0.021500 0.194289 -vn -0.720576 -0.390176 0.573178 -v -0.075063 -0.026500 0.192076 -vn -0.468954 -0.366206 0.803726 -v -0.075644 -0.022000 0.191526 -vn -0.807447 -0.365169 0.463338 -v -0.075006 -0.022000 0.192169 -vn -0.002979 -0.367740 0.929924 -v -0.076518 -0.022000 0.191289 -vn 0.463801 -0.366193 0.806716 -v -0.077394 -0.022000 0.191521 -vn 0.804459 -0.365167 0.468508 -v -0.078037 -0.022000 0.192159 -vn 0.718338 -0.393329 0.573832 -v -0.077979 -0.026500 0.192067 -vn 0.930461 -0.366376 0.003381 -v -0.078274 -0.022000 0.193034 -vn 0.902712 -0.393824 0.173247 -v -0.078263 -0.026500 0.192847 -vn 0.836502 -0.386883 0.388055 -v -0.078037 -0.026500 0.192159 -vn 0.807120 -0.367247 -0.462263 -v -0.078042 -0.022000 0.193909 -vn 0.874496 -0.394295 -0.282467 -v -0.078156 -0.026500 0.193671 -vn 0.921263 -0.384031 -0.061602 -v -0.078274 -0.026500 0.193034 -vn 0.467662 -0.367751 -0.803773 -v -0.077404 -0.022000 0.194552 -vn 0.630521 -0.394624 -0.668368 -v -0.077681 -0.026500 0.194352 -vn 0.779425 -0.381768 -0.496740 -v -0.078042 -0.026500 0.193909 -vn 0.002970 -0.367939 -0.929845 -v -0.076529 -0.022000 0.194789 -vn 0.231105 -0.394771 -0.889239 -v -0.076945 -0.026500 0.194738 -vn 0.446010 -0.380306 -0.810211 -v -0.077404 -0.026500 0.194552 -vn -0.462496 -0.367755 -0.806755 -v -0.075654 -0.022000 0.194557 -vn -0.239981 -0.384567 -0.891357 -v -0.076114 -0.026500 0.194740 -vn 0.002970 -0.379794 -0.925066 -v -0.076529 -0.026500 0.194789 -vn -0.804147 -0.367241 -0.467419 -v -0.075011 -0.022000 0.193919 -vn -0.636455 -0.386570 -0.667450 -v -0.075376 -0.026500 0.194360 -vn -0.429261 -0.354252 -0.830807 -v -0.075654 -0.026500 0.194557 -vn -0.930463 -0.366378 -0.002581 -v -0.074774 -0.022000 0.193045 -vn -0.877378 -0.388505 -0.281552 -v -0.074896 -0.026500 0.193681 -vn -0.774361 -0.364678 -0.517083 -v -0.075011 -0.026500 0.193919 -vn -0.842900 -0.382057 0.378884 -v -0.075006 -0.026500 0.192169 -vn -0.904418 -0.390372 0.172157 -v -0.074783 -0.026500 0.192858 -vn -0.924230 -0.373978 -0.077065 -v -0.074774 -0.026500 0.193045 -vn 0.380700 -0.653227 -0.654494 -v -0.085429 -0.021500 0.202526 -vn 0.656936 -0.653229 -0.376466 -v -0.086068 -0.021500 0.201884 -vn 0.757158 -0.653227 0.002428 -v -0.086299 -0.021500 0.201008 -vn 0.654502 -0.653225 0.380689 -v -0.086062 -0.021500 0.200134 -vn 0.376480 -0.653232 0.656925 -v -0.085420 -0.021500 0.199495 -vn -0.002421 -0.653221 0.757163 -v -0.084544 -0.021500 0.199263 -vn -0.380674 -0.653232 0.654503 -v -0.083670 -0.021500 0.199501 -vn -0.656928 -0.653223 0.376490 -v -0.083031 -0.021500 0.200143 -vn -0.757158 -0.653227 -0.002426 -v -0.082799 -0.021500 0.201019 -vn -0.654509 -0.653229 -0.380671 -v -0.083037 -0.021500 0.201893 -vn -0.376495 -0.653227 -0.656922 -v -0.083679 -0.021500 0.202532 -vn 0.002427 -0.653221 -0.757163 -v -0.084555 -0.021500 0.202764 -vn 0.913439 -0.406965 0.002928 -v -0.086299 -0.026500 0.201008 -vn 0.792533 -0.406967 -0.454170 -v -0.086068 -0.026500 0.201884 -vn 0.459275 -0.406962 -0.789588 -v -0.085429 -0.026500 0.202526 -vn 0.002936 -0.406950 -0.913446 -v -0.084555 -0.026500 0.202764 -vn -0.454203 -0.406969 -0.792512 -v -0.083679 -0.026500 0.202532 -vn -0.789605 -0.406970 -0.459238 -v -0.083037 -0.026500 0.201893 -vn -0.913440 -0.406963 -0.002924 -v -0.082799 -0.026500 0.201019 -vn -0.792521 -0.406960 0.454196 -v -0.083031 -0.026500 0.200143 -vn -0.459247 -0.406961 0.789604 -v -0.083670 -0.026500 0.199501 -vn -0.002929 -0.406958 0.913442 -v -0.084544 -0.026500 0.199263 -vn 0.454196 -0.406967 0.792518 -v -0.085420 -0.026500 0.199495 -vn 0.789592 -0.406960 0.459268 -v -0.086062 -0.026500 0.200134 -vn 0.923685 0.375026 0.078499 -v -0.066550 0.026500 0.201071 -vn 0.923685 -0.375026 0.078499 -v -0.066550 0.020500 0.201071 -vn -0.779702 -0.375022 0.501421 -v -0.085373 0.020500 0.205745 -vn -0.779703 0.375021 0.501421 -v -0.085373 0.026500 0.205745 -vn 0.877922 0.369178 0.304895 -v -0.067103 0.026500 0.204320 -vn 0.877923 -0.369177 0.304894 -v -0.067103 0.020500 0.204320 -vn 0.731141 0.369193 0.573698 -v -0.068682 0.026500 0.207212 -vn 0.731140 -0.369192 0.573700 -v -0.068682 0.020500 0.207212 -vn 0.504963 0.369186 0.780201 -v -0.071116 0.026500 0.209434 -vn 0.504963 -0.369187 0.780201 -v -0.071116 0.020500 0.209434 -vn 0.223941 0.369178 0.901974 -v -0.074140 0.026500 0.210744 -vn 0.223942 -0.369178 0.901974 -v -0.074140 0.020500 0.210744 -vn -0.081398 0.369183 0.925785 -v -0.077425 0.026500 0.211001 -vn -0.081402 -0.369185 0.925784 -v -0.077425 0.020500 0.211001 -vn -0.377902 0.369159 0.849065 -v -0.080616 0.026500 0.210175 -vn -0.377897 -0.369159 0.849068 -v -0.080616 0.020500 0.210175 -vn -0.633356 0.369181 0.680122 -v -0.083364 0.026500 0.208357 -vn -0.633359 -0.369180 0.680120 -v -0.083364 0.020500 0.208357 -vn -0.394934 0.123374 0.910388 -v -0.089973 -0.017000 0.177157 -vn -0.394934 -0.123374 0.910388 -v -0.089973 0.017000 0.177157 -vn -0.405753 0.455086 0.792629 -v -0.089974 -0.018500 0.177559 -vn -0.404532 0.793984 0.453810 -v -0.089978 -0.019598 0.178657 -vn -0.409484 -0.456721 0.789765 -v -0.089974 0.018500 0.177559 -vn -0.407748 -0.791378 0.455480 -v -0.089978 0.019598 0.178657 -vn -0.739837 0.088117 0.666990 -v -0.086816 0.033000 0.128054 -vn -0.739838 -0.088117 0.666990 -v -0.086816 -0.033000 0.128054 -vn 0.002264 0.707107 -0.707103 -v -0.086953 -0.026000 0.170815 -vn 0.002264 -0.707107 -0.707103 -v -0.086953 0.026000 0.170815 -vn 0.002264 0.707107 -0.707103 -v -0.086953 0.020000 0.170815 -vn 0.002264 -0.707107 -0.707103 -v -0.086953 -0.020000 0.170815 -vn -0.769237 0.552292 -0.321323 -v -0.086859 0.034866 0.141554 -vn -0.769237 -0.552292 -0.321323 -v -0.086859 -0.034866 0.141554 -vn -0.768499 -0.318841 -0.554752 -v -0.086858 -0.034500 0.141188 -vn -0.771277 -0.552292 0.316395 -v -0.086813 -0.034732 0.127054 -vn -0.768499 0.318841 -0.554752 -v -0.086858 0.034500 0.141188 -vn -0.771277 0.552292 0.316395 -v -0.086813 0.034732 0.127054 -vn -0.772034 0.318855 0.549814 -v -0.086815 0.034000 0.127786 -vn -0.769238 -0.552292 -0.321320 -v -0.086859 0.032134 0.141554 -vn -0.768501 0.318837 -0.554752 -v -0.086858 -0.032500 0.141188 -vn -0.769239 0.552293 -0.321317 -v -0.086859 -0.032134 0.141554 -vn -0.768499 -0.318841 -0.554752 -v -0.086858 0.032500 0.141188 -vn -0.735544 -0.088094 -0.671725 -v -0.086857 0.033000 0.141054 -vn -0.735544 0.088095 -0.671725 -v -0.086857 0.034000 0.141054 -vn -0.772034 -0.318855 0.549814 -v -0.086815 -0.034000 0.127786 -vn -0.735544 -0.088095 -0.671725 -v -0.086857 -0.034000 0.141054 -vn -0.735544 0.088094 -0.671725 -v -0.086857 -0.033000 0.141054 -vn -0.771290 0.552268 0.316405 -v -0.086935 -0.025866 0.165315 -vn -0.737977 0.669355 0.085754 -v -0.086937 -0.026000 0.165815 -vn -0.772015 0.318859 0.549837 -v -0.086934 -0.025500 0.164949 -vn -0.739837 0.088135 0.666989 -v -0.086933 -0.025000 0.164815 -vn -0.737977 0.669355 0.085754 -v -0.086937 0.020000 0.165815 -vn -0.771290 0.552268 0.316405 -v -0.086935 0.020134 0.165315 -vn -0.772019 0.318854 0.549836 -v -0.086934 0.020500 0.164949 -vn -0.739844 0.088136 0.666980 -v -0.086933 0.021000 0.164815 -vn 0.042836 -0.996895 -0.066070 -v -0.086962 -0.020000 0.173815 -vn 0.769237 -0.552292 0.321322 -v -0.086961 -0.020134 0.173315 -vn 0.768484 -0.318879 0.554750 -v -0.086960 -0.020500 0.172949 -vn 0.735557 -0.088130 0.671706 -v -0.086959 -0.021000 0.172815 -vn 0.735557 0.088130 0.671706 -v -0.086959 -0.025000 0.172815 -vn 0.768484 0.318879 0.554750 -v -0.086960 -0.025500 0.172949 -vn 0.769237 0.552292 0.321322 -v -0.086961 -0.025866 0.173315 -vn 0.042836 0.996895 -0.066070 -v -0.086962 -0.026000 0.173815 -vn 0.042836 -0.996895 -0.066070 -v -0.086962 0.026000 0.173815 -vn 0.769237 -0.552292 0.321322 -v -0.086961 0.025866 0.173315 -vn 0.768484 -0.318879 0.554750 -v -0.086960 0.025500 0.172949 -vn 0.735557 -0.088130 0.671706 -v -0.086959 0.025000 0.172815 -vn 0.735557 0.088130 0.671706 -v -0.086959 0.021000 0.172815 -vn 0.768484 0.318879 0.554750 -v -0.086960 0.020500 0.172949 -vn 0.769237 0.552292 0.321322 -v -0.086961 0.020134 0.173315 -vn 0.042836 0.996895 -0.066070 -v -0.086962 0.020000 0.173815 -vn 0.608721 -0.686245 0.398154 -v -0.079258 -0.026200 0.109899 -vn 0.607451 -0.000000 0.794357 -v -0.079252 -0.029000 0.108283 -vn 0.608721 0.686245 0.398154 -v -0.079258 -0.031800 0.109899 -vn 0.611262 -0.686244 -0.394244 -v -0.079268 -0.026200 0.113132 -vn 0.612530 -0.000000 -0.790448 -v -0.079273 -0.029000 0.114749 -vn 0.611261 0.686244 -0.394245 -v -0.079268 -0.031800 0.113132 -vn 0.608721 -0.686245 0.398154 -v -0.079258 0.031800 0.109899 -vn 0.611261 -0.686244 -0.394245 -v -0.079268 0.031800 0.113132 -vn 0.607451 0.000000 0.794357 -v -0.079252 0.029000 0.108283 -vn 0.608722 0.686245 0.398154 -v -0.079258 0.026200 0.109899 -vn 0.612530 0.000000 -0.790448 -v -0.079273 0.029000 0.114749 -vn 0.611261 0.686244 -0.394244 -v -0.079268 0.026200 0.113132 -# 995 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 1//1 -f 1//1 24//24 2//2 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 25//25 -f 25//25 48//48 26//26 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 65//65 66//66 67//67 -f 68//68 69//69 70//70 -f 71//71 72//72 67//67 -f 67//67 72//72 73//73 -f 74//74 75//75 76//76 -f 76//76 75//75 77//77 -f 78//78 79//79 77//77 -f 77//77 79//79 80//80 -f 77//77 80//80 76//76 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 86//86 65//65 87//87 -f 87//87 65//65 67//67 -f 87//87 67//67 88//88 -f 88//88 67//67 73//73 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 94//94 95//95 96//96 -f 97//97 98//98 93//93 -f 93//93 98//98 99//99 -f 93//93 99//99 91//91 -f 91//91 99//99 94//94 -f 91//91 94//94 100//100 -f 100//100 94//94 96//96 -f 101//101 102//102 77//77 -f 77//77 102//102 103//103 -f 77//77 103//103 78//78 -f 70//70 85//85 68//68 -f 68//68 85//85 84//84 -f 68//68 84//84 104//104 -f 104//104 84//84 105//105 -f 104//104 105//105 106//106 -f 107//107 108//108 91//91 -f 91//91 108//108 109//109 -f 91//91 109//109 89//89 -f 90//90 110//110 92//92 -f 92//92 110//110 111//111 -f 92//92 111//111 65//65 -f 65//65 111//111 112//112 -f 65//65 112//112 66//66 -f 66//66 112//112 113//113 -f 66//66 113//113 114//114 -f 113//113 115//115 114//114 -f 114//114 115//115 116//116 -f 114//114 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 106//106 120//120 104//104 -f 104//104 120//120 121//121 -f 104//104 121//121 122//122 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 118//118 -f 118//118 126//126 127//127 -f 118//118 127//127 119//119 -f 119//119 127//127 128//128 -f 119//119 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 101//101 -f 101//101 130//130 131//131 -f 101//101 131//131 102//102 -f 102//102 131//131 132//132 -f 102//102 132//132 105//105 -f 105//105 132//132 133//133 -f 105//105 133//133 106//106 -f 123//123 107//107 124//124 -f 124//124 107//107 91//91 -f 124//124 91//91 134//134 -f 134//134 91//91 104//104 -f 134//134 104//104 135//135 -f 135//135 104//104 122//122 -f 105//105 84//84 136//136 -f 137//137 138//138 84//84 -f 84//84 138//138 139//139 -f 84//84 139//139 136//136 -f 140//140 141//141 142//142 -f 143//143 144//144 145//145 -f 140//140 142//142 146//146 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 137//137 -f 137//137 150//150 142//142 -f 137//137 142//142 138//138 -f 138//138 142//142 141//141 -f 136//136 151//151 105//105 -f 105//105 151//151 143//143 -f 105//105 143//143 152//152 -f 152//152 143//143 145//145 -f 153//153 154//154 142//142 -f 142//142 154//154 155//155 -f 142//142 155//155 146//146 -f 141//141 156//156 138//138 -f 138//138 156//156 157//157 -f 138//138 157//157 158//158 -f 158//158 157//157 159//159 -f 158//158 159//159 160//160 -f 161//161 162//162 159//159 -f 159//159 162//162 163//163 -f 159//159 163//163 160//160 -f 164//164 165//165 166//166 -f 166//166 167//167 164//164 -f 164//164 167//167 168//168 -f 164//164 168//168 169//169 -f 169//169 170//170 171//171 -f 172//172 170//170 173//173 -f 173//173 170//170 169//169 -f 173//173 169//169 92//92 -f 92//92 169//169 168//168 -f 92//92 168//168 93//93 -f 174//174 169//169 175//175 -f 175//175 169//169 171//171 -f 175//175 171//171 176//176 -f 176//176 171//171 177//177 -f 176//176 177//177 178//178 -f 178//178 177//177 179//179 -f 178//178 179//179 180//180 -f 181//181 182//182 183//183 -f 183//183 182//182 169//169 -f 183//183 169//169 184//184 -f 184//184 169//169 174//174 -f 185//185 186//186 173//173 -f 173//173 186//186 187//187 -f 173//173 187//187 172//172 -f 188//188 189//189 190//190 -f 190//190 189//189 180//180 -f 190//190 180//180 191//191 -f 191//191 180//180 179//179 -f 23//23 192//192 21//21 -f 21//21 192//192 193//193 -f 21//21 193//193 19//19 -f 39//39 41//41 194//194 -f 194//194 41//41 43//43 -f 194//194 43//43 45//45 -f 195//195 148//148 196//196 -f 196//196 148//148 147//147 -f 196//196 147//147 197//197 -f 192//192 166//166 198//198 -f 198//198 166//166 165//165 -f 198//198 165//165 199//199 -f 200//200 7//7 201//201 -f 201//201 7//7 9//9 -f 201//201 9//9 11//11 -f 194//194 202//202 39//39 -f 39//39 202//202 197//197 -f 39//39 197//197 37//37 -f 37//37 197//197 147//147 -f 37//37 147//147 35//35 -f 200//200 203//203 7//7 -f 7//7 203//203 204//204 -f 7//7 204//204 5//5 -f 5//5 204//204 166//166 -f 5//5 166//166 3//3 -f 3//3 166//166 192//192 -f 3//3 192//192 1//1 -f 1//1 192//192 23//23 -f 205//205 201//201 206//206 -f 206//206 201//201 31//31 -f 206//206 31//31 147//147 -f 147//147 31//31 33//33 -f 147//147 33//33 35//35 -f 193//193 207//207 19//19 -f 19//19 207//207 194//194 -f 19//19 194//194 17//17 -f 17//17 194//194 45//45 -f 17//17 45//45 15//15 -f 15//15 45//45 47//47 -f 15//15 47//47 13//13 -f 13//13 47//47 25//25 -f 13//13 25//25 11//11 -f 11//11 25//25 27//27 -f 11//11 27//27 201//201 -f 201//201 27//27 29//29 -f 201//201 29//29 31//31 -f 208//208 209//209 100//100 -f 100//100 209//209 91//91 -f 68//68 104//104 210//210 -f 210//210 104//104 211//211 -f 212//212 59//59 61//61 -f 213//213 214//214 215//215 -f 216//216 217//217 218//218 -f 218//218 217//217 219//219 -f 219//219 220//220 218//218 -f 218//218 220//220 49//49 -f 218//218 49//49 212//212 -f 214//214 221//221 215//215 -f 215//215 221//221 222//222 -f 215//215 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 230//230 -f 230//230 229//229 231//231 -f 230//230 231//231 232//232 -f 232//232 231//231 233//233 -f 232//232 233//233 234//234 -f 234//234 233//233 223//223 -f 234//234 223//223 235//235 -f 235//235 223//223 225//225 -f 49//49 51//51 212//212 -f 212//212 51//51 53//53 -f 212//212 53//53 55//55 -f 212//212 61//61 215//215 -f 215//215 61//61 63//63 -f 215//215 63//63 213//213 -f 55//55 236//236 212//212 -f 212//212 236//236 237//237 -f 212//212 237//237 59//59 -f 59//59 237//237 238//238 -f 59//59 238//238 239//239 -f 216//216 218//218 240//240 -f 240//240 218//218 241//241 -f 240//240 241//241 242//242 -f 242//242 241//241 243//243 -f 242//242 243//243 244//244 -f 244//244 243//243 227//227 -f 244//244 227//227 245//245 -f 245//245 227//227 226//226 -f 245//245 226//226 239//239 -f 239//239 226//226 57//57 -f 239//239 57//57 59//59 -f 246//246 247//247 248//248 -f 246//246 248//248 218//218 -f 218//218 248//248 249//249 -f 218//218 249//249 241//241 -f 241//241 249//249 250//250 -f 241//241 250//250 251//251 -f 246//246 169//169 247//247 -f 247//247 169//169 182//182 -f 247//247 182//182 252//252 -f 253//253 254//254 255//255 -f 255//255 254//254 247//247 -f 255//255 247//247 256//256 -f 256//256 247//247 252//252 -f 257//257 258//258 259//259 -f 259//259 258//258 254//254 -f 259//259 254//254 260//260 -f 260//260 254//254 253//253 -f 261//261 262//262 263//263 -f 233//233 264//264 265//265 -f 142//142 266//266 153//153 -f 153//153 266//266 267//267 -f 153//153 267//267 268//268 -f 268//268 267//267 269//269 -f 233//233 265//265 223//223 -f 223//223 265//265 270//270 -f 223//223 270//270 266//266 -f 266//266 270//270 271//271 -f 266//266 271//271 267//267 -f 272//272 273//273 274//274 -f 274//274 261//261 272//272 -f 272//272 261//261 263//263 -f 272//272 263//263 267//267 -f 267//267 263//263 275//275 -f 267//267 275//275 269//269 -f 155//155 276//276 277//277 -f 155//155 277//277 146//146 -f 146//146 277//277 278//278 -f 146//146 278//278 140//140 -f 140//140 278//278 279//279 -f 140//140 279//279 141//141 -f 141//141 279//279 280//280 -f 141//141 280//280 156//156 -f 156//156 280//280 281//281 -f 156//156 281//281 157//157 -f 282//282 183//183 283//283 -f 283//283 183//183 184//184 -f 283//283 184//184 284//284 -f 284//284 184//184 174//174 -f 284//284 174//174 285//285 -f 285//285 174//174 175//175 -f 285//285 175//175 286//286 -f 286//286 175//175 176//176 -f 286//286 176//176 287//287 -f 287//287 176//176 178//178 -f 251//251 250//250 288//288 -f 288//288 250//250 289//289 -f 290//290 265//265 291//291 -f 291//291 265//265 264//264 -f 292//292 293//293 294//294 -f 294//294 293//293 295//295 -f 294//294 296//296 292//292 -f 292//292 296//296 297//297 -f 292//292 297//297 298//298 -f 298//298 297//297 299//299 -f 298//298 299//299 300//300 -f 284//284 289//289 283//283 -f 283//283 289//289 282//282 -f 293//293 301//301 295//295 -f 295//295 301//301 302//302 -f 295//295 302//302 287//287 -f 287//287 302//302 303//303 -f 287//287 303//303 286//286 -f 286//286 303//303 285//285 -f 284//284 285//285 289//289 -f 289//289 285//285 303//303 -f 289//289 303//303 304//304 -f 299//299 305//305 300//300 -f 300//300 305//305 306//306 -f 300//300 306//306 307//307 -f 307//307 306//306 308//308 -f 307//307 308//308 309//309 -f 309//309 308//308 310//310 -f 309//309 310//310 311//311 -f 311//311 310//310 312//312 -f 311//311 312//312 313//313 -f 313//313 312//312 314//314 -f 313//313 314//314 315//315 -f 315//315 314//314 304//304 -f 315//315 304//304 316//316 -f 316//316 304//304 303//303 -f 317//317 318//318 319//319 -f 319//319 318//318 320//320 -f 319//319 320//320 321//321 -f 322//322 323//323 324//324 -f 325//325 326//326 327//327 -f 324//324 328//328 322//322 -f 322//322 328//328 329//329 -f 322//322 329//329 317//317 -f 317//317 329//329 330//330 -f 317//317 330//330 318//318 -f 327//327 331//331 325//325 -f 325//325 331//331 332//332 -f 325//325 332//332 333//333 -f 333//333 332//332 334//334 -f 333//333 334//334 323//323 -f 323//323 334//334 335//335 -f 323//323 335//335 324//324 -f 336//336 337//337 338//338 -f 338//338 337//337 339//339 -f 338//338 339//339 340//340 -f 320//320 341//341 321//321 -f 321//321 341//341 342//342 -f 321//321 342//342 343//343 -f 343//343 342//342 344//344 -f 343//343 344//344 336//336 -f 336//336 344//344 345//345 -f 336//336 345//345 337//337 -f 339//339 346//346 340//340 -f 340//340 346//346 347//347 -f 340//340 347//347 326//326 -f 326//326 347//347 348//348 -f 326//326 348//348 327//327 -f 183//183 282//282 349//349 -f 349//349 350//350 183//183 -f 183//183 350//350 351//351 -f 183//183 351//351 181//181 -f 352//352 353//353 351//351 -f 354//354 355//355 352//352 -f 353//353 356//356 351//351 -f 351//351 356//356 357//357 -f 351//351 357//357 181//181 -f 358//358 354//354 359//359 -f 359//359 354//354 352//352 -f 359//359 352//352 360//360 -f 360//360 352//352 351//351 -f 361//361 362//362 363//363 -f 363//363 362//362 364//364 -f 363//363 364//364 365//365 -f 365//365 364//364 366//366 -f 365//365 366//366 367//367 -f 367//367 366//366 368//368 -f 367//367 368//368 369//369 -f 369//369 368//368 370//370 -f 369//369 370//370 371//371 -f 371//371 370//370 372//372 -f 371//371 372//372 373//373 -f 373//373 372//372 374//374 -f 373//373 374//374 375//375 -f 375//375 374//374 376//376 -f 375//375 376//376 377//377 -f 377//377 376//376 378//378 -f 377//377 378//378 379//379 -f 379//379 378//378 380//380 -f 379//379 380//380 381//381 -f 381//381 380//380 382//382 -f 381//381 382//382 383//383 -f 383//383 382//382 384//384 -f 383//383 384//384 361//361 -f 361//361 384//384 362//362 -f 385//385 386//386 387//387 -f 387//387 386//386 388//388 -f 387//387 388//388 389//389 -f 389//389 388//388 390//390 -f 389//389 390//390 391//391 -f 391//391 390//390 392//392 -f 391//391 392//392 393//393 -f 393//393 392//392 394//394 -f 393//393 394//394 395//395 -f 395//395 394//394 396//396 -f 395//395 396//396 397//397 -f 397//397 396//396 398//398 -f 397//397 398//398 399//399 -f 399//399 398//398 400//400 -f 399//399 400//400 401//401 -f 401//401 400//400 402//402 -f 401//401 402//402 403//403 -f 403//403 402//402 404//404 -f 403//403 404//404 405//405 -f 405//405 404//404 406//406 -f 405//405 406//406 407//407 -f 407//407 406//406 408//408 -f 407//407 408//408 385//385 -f 385//385 408//408 386//386 -f 409//409 410//410 411//411 -f 411//411 410//410 412//412 -f 411//411 412//412 413//413 -f 413//413 412//412 414//414 -f 413//413 414//414 415//415 -f 415//415 414//414 416//416 -f 415//415 416//416 417//417 -f 417//417 416//416 418//418 -f 417//417 418//418 419//419 -f 419//419 418//418 420//420 -f 419//419 420//420 421//421 -f 421//421 420//420 422//422 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 423//423 424//424 425//425 -f 425//425 424//424 426//426 -f 425//425 426//426 427//427 -f 427//427 426//426 428//428 -f 427//427 428//428 429//429 -f 429//429 428//428 430//430 -f 429//429 430//430 431//431 -f 431//431 430//430 432//432 -f 431//431 432//432 409//409 -f 409//409 432//432 410//410 -f 433//433 434//434 435//435 -f 435//435 434//434 436//436 -f 435//435 436//436 437//437 -f 437//437 436//436 438//438 -f 437//437 438//438 439//439 -f 439//439 438//438 440//440 -f 439//439 440//440 441//441 -f 441//441 440//440 442//442 -f 441//441 442//442 443//443 -f 443//443 442//442 444//444 -f 443//443 444//444 445//445 -f 445//445 444//444 446//446 -f 445//445 446//446 447//447 -f 447//447 446//446 448//448 -f 447//447 448//448 449//449 -f 449//449 448//448 450//450 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 453//453 454//454 455//455 -f 455//455 454//454 456//456 -f 455//455 456//456 433//433 -f 433//433 456//456 434//434 -f 159//159 157//157 457//457 -f 457//457 157//157 281//281 -f 458//458 459//459 281//281 -f 281//281 459//459 460//460 -f 281//281 460//460 461//461 -f 462//462 457//457 463//463 -f 463//463 457//457 281//281 -f 463//463 281//281 464//464 -f 464//464 281//281 461//461 -f 459//459 458//458 465//465 -f 459//459 465//465 466//466 -f 466//466 465//465 467//467 -f 466//466 467//467 468//468 -f 468//468 467//467 469//469 -f 468//468 469//469 470//470 -f 470//470 469//469 471//471 -f 470//470 471//471 472//472 -f 472//472 471//471 473//473 -f 472//472 473//473 474//474 -f 474//474 473//473 475//475 -f 474//474 475//475 476//476 -f 476//476 475//475 477//477 -f 476//476 477//477 478//478 -f 478//478 477//477 479//479 -f 478//478 479//479 480//480 -f 480//480 479//479 481//481 -f 480//480 481//481 482//482 -f 482//482 481//481 483//483 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 486//486 -f 486//486 485//485 75//75 -f 486//486 75//75 74//74 -f 487//487 488//488 489//489 -f 489//489 488//488 490//490 -f 489//489 490//490 491//491 -f 491//491 490//490 492//492 -f 491//491 492//492 493//493 -f 493//493 492//492 494//494 -f 493//493 494//494 495//495 -f 495//495 494//494 496//496 -f 495//495 496//496 497//497 -f 497//497 496//496 498//498 -f 497//497 498//498 499//499 -f 498//498 500//500 499//499 -f 499//499 500//500 501//501 -f 499//499 501//501 502//502 -f 502//502 501//501 503//503 -f 502//502 503//503 504//504 -f 504//504 503//503 505//505 -f 504//504 505//505 506//506 -f 506//506 505//505 507//507 -f 507//507 508//508 506//506 -f 506//506 508//508 509//509 -f 506//506 509//509 510//510 -f 510//510 509//509 511//511 -f 510//510 511//511 512//512 -f 512//512 511//511 513//513 -f 512//512 513//513 487//487 -f 487//487 513//513 514//514 -f 487//487 514//514 488//488 -f 515//515 516//516 517//517 -f 517//517 516//516 518//518 -f 517//517 518//518 519//519 -f 519//519 518//518 520//520 -f 519//519 520//520 521//521 -f 521//521 520//520 522//522 -f 521//521 522//522 523//523 -f 523//523 522//522 524//524 -f 523//523 524//524 525//525 -f 525//525 524//524 526//526 -f 525//525 526//526 527//527 -f 527//527 526//526 528//528 -f 527//527 528//528 529//529 -f 529//529 528//528 530//530 -f 529//529 530//530 531//531 -f 531//531 530//530 532//532 -f 531//531 532//532 533//533 -f 533//533 532//532 534//534 -f 533//533 534//534 535//535 -f 535//535 534//534 536//536 -f 535//535 536//536 537//537 -f 537//537 536//536 538//538 -f 537//537 538//538 515//515 -f 515//515 538//538 516//516 -f 215//215 539//539 212//212 -f 212//212 539//539 540//540 -f 178//178 180//180 541//541 -f 542//542 543//543 287//287 -f 287//287 543//543 544//544 -f 287//287 544//544 295//295 -f 295//295 544//544 545//545 -f 295//295 545//545 546//546 -f 178//178 541//541 287//287 -f 287//287 541//541 547//547 -f 287//287 547//547 542//542 -f 548//548 549//549 550//550 -f 550//550 549//549 551//551 -f 266//266 142//142 539//539 -f 539//539 142//142 150//150 -f 552//552 540//540 553//553 -f 553//553 540//540 554//554 -f 555//555 549//549 556//556 -f 556//556 549//549 548//548 -f 556//556 548//548 557//557 -f 246//246 540//540 169//169 -f 169//169 540//540 552//552 -f 169//169 552//552 164//164 -f 164//164 552//552 558//558 -f 164//164 558//558 559//559 -f 559//559 558//558 556//556 -f 559//559 556//556 560//560 -f 560//560 556//556 557//557 -f 555//555 554//554 561//561 -f 561//561 554//554 540//540 -f 561//561 540//540 562//562 -f 562//562 540//540 539//539 -f 562//562 539//539 563//563 -f 563//563 539//539 150//150 -f 563//563 150//150 564//564 -f 564//564 150//150 565//565 -f 565//565 150//150 566//566 -f 565//565 566//566 567//567 -f 561//561 568//568 555//555 -f 555//555 568//568 565//565 -f 555//555 565//565 549//549 -f 549//549 565//565 567//567 -f 549//549 567//567 569//569 -f 551//551 570//570 550//550 -f 550//550 570//570 571//571 -f 551//551 572//572 570//570 -f 570//570 572//572 573//573 -f 570//570 573//573 574//574 -f 575//575 576//576 577//577 -f 577//577 576//576 570//570 -f 577//577 570//570 578//578 -f 578//578 570//570 574//574 -f 579//579 580//580 571//571 -f 571//571 580//580 581//581 -f 582//582 550//550 583//583 -f 583//583 550//550 571//571 -f 583//583 571//571 584//584 -f 584//584 571//571 581//581 -f 584//584 581//581 585//585 -f 395//395 397//397 586//586 -f 587//587 443//443 445//445 -f 490//490 488//488 449//449 -f 427//427 429//429 588//588 -f 588//588 429//429 431//431 -f 588//588 431//431 589//589 -f 587//587 445//445 488//488 -f 488//488 445//445 447//447 -f 488//488 447//447 449//449 -f 455//455 415//415 417//417 -f 431//431 409//409 589//589 -f 589//589 409//409 411//411 -f 589//589 411//411 590//590 -f 590//590 411//411 413//413 -f 590//590 413//413 591//591 -f 591//591 413//413 415//415 -f 591//591 415//415 592//592 -f 592//592 415//415 455//455 -f 425//425 501//501 423//423 -f 423//423 501//501 500//500 -f 423//423 500//500 421//421 -f 421//421 500//500 498//498 -f 421//421 498//498 419//419 -f 419//419 498//498 496//496 -f 419//419 496//496 494//494 -f 455//455 433//433 592//592 -f 592//592 433//433 435//435 -f 592//592 435//435 593//593 -f 593//593 435//435 437//437 -f 593//593 437//437 594//594 -f 594//594 437//437 439//439 -f 594//594 439//439 587//587 -f 587//587 439//439 441//441 -f 587//587 441//441 443//443 -f 490//490 449//449 492//492 -f 492//492 449//449 451//451 -f 492//492 451//451 494//494 -f 417//417 419//419 455//455 -f 455//455 419//419 494//494 -f 455//455 494//494 453//453 -f 453//453 494//494 451//451 -f 595//595 596//596 290//290 -f 397//397 399//399 586//586 -f 586//586 399//399 401//401 -f 586//586 401//401 290//290 -f 290//290 401//401 403//403 -f 290//290 403//403 405//405 -f 387//387 389//389 501//501 -f 425//425 427//427 501//501 -f 501//501 427//427 588//588 -f 501//501 588//588 387//387 -f 387//387 588//588 597//597 -f 387//387 597//597 385//385 -f 385//385 597//597 598//598 -f 385//385 598//598 407//407 -f 407//407 598//598 599//599 -f 407//407 599//599 405//405 -f 395//395 508//508 393//393 -f 393//393 508//508 507//507 -f 393//393 507//507 391//391 -f 391//391 507//507 505//505 -f 391//391 505//505 389//389 -f 389//389 505//505 503//503 -f 389//389 503//503 501//501 -f 599//599 600//600 405//405 -f 405//405 600//600 601//601 -f 405//405 601//601 290//290 -f 290//290 601//601 602//602 -f 290//290 602//602 595//595 -f 603//603 604//604 373//373 -f 381//381 383//383 509//509 -f 373//373 604//604 371//371 -f 371//371 604//604 605//605 -f 371//371 605//605 369//369 -f 369//369 605//605 606//606 -f 369//369 606//606 367//367 -f 373//373 375//375 603//603 -f 603//603 375//375 377//377 -f 603//603 377//377 379//379 -f 395//395 586//586 508//508 -f 508//508 586//586 603//603 -f 508//508 603//603 509//509 -f 509//509 603//603 379//379 -f 509//509 379//379 381//381 -f 363//363 514//514 361//361 -f 361//361 514//514 513//513 -f 361//361 513//513 383//383 -f 383//383 513//513 511//511 -f 383//383 511//511 509//509 -f 606//606 607//607 367//367 -f 367//367 607//607 608//608 -f 367//367 608//608 365//365 -f 365//365 608//608 587//587 -f 365//365 587//587 363//363 -f 363//363 587//587 488//488 -f 363//363 488//488 514//514 -f 539//539 215//215 266//266 -f 266//266 215//215 223//223 -f 246//246 218//218 540//540 -f 540//540 218//218 212//212 -f 194//194 207//207 570//570 -f 570//570 207//207 571//571 -f 609//609 179//179 610//610 -f 610//610 179//179 177//177 -f 610//610 177//177 611//611 -f 611//611 177//177 171//171 -f 611//611 171//171 612//612 -f 612//612 171//171 170//170 -f 612//612 170//170 613//613 -f 613//613 170//170 172//172 -f 613//613 172//172 614//614 -f 614//614 172//172 187//187 -f 614//614 187//187 615//615 -f 615//615 187//187 616//616 -f 616//616 187//187 186//186 -f 616//616 186//186 617//617 -f 617//617 186//186 618//618 -f 618//618 186//186 185//185 -f 618//618 185//185 619//619 -f 619//619 185//185 620//620 -f 620//620 185//185 173//173 -f 620//620 173//173 621//621 -f 621//621 173//173 622//622 -f 622//622 173//173 92//92 -f 622//622 92//92 65//65 -f 541//541 180//180 623//623 -f 623//623 180//180 189//189 -f 623//623 189//189 624//624 -f 624//624 189//189 625//625 -f 625//625 189//189 188//188 -f 625//625 188//188 626//626 -f 626//626 188//188 627//627 -f 627//627 188//188 190//190 -f 627//627 190//190 628//628 -f 628//628 190//190 629//629 -f 629//629 190//190 191//191 -f 629//629 191//191 630//630 -f 630//630 191//191 631//631 -f 631//631 191//191 179//179 -f 631//631 179//179 609//609 -f 335//335 613//613 614//614 -f 72//72 632//632 73//73 -f 73//73 632//632 329//329 -f 335//335 614//614 324//324 -f 324//324 614//614 615//615 -f 324//324 615//615 328//328 -f 328//328 615//615 616//616 -f 328//328 616//616 329//329 -f 329//329 616//616 617//617 -f 329//329 617//617 73//73 -f 73//73 617//617 618//618 -f 73//73 618//618 88//88 -f 88//88 618//618 619//619 -f 88//88 619//619 87//87 -f 619//619 620//620 87//87 -f 87//87 620//620 621//621 -f 87//87 621//621 86//86 -f 86//86 621//621 622//622 -f 86//86 622//622 65//65 -f 327//327 609//609 331//331 -f 331//331 609//609 610//610 -f 331//331 610//610 332//332 -f 332//332 610//610 611//611 -f 332//332 611//611 334//334 -f 334//334 611//611 612//612 -f 334//334 612//612 335//335 -f 335//335 612//612 613//613 -f 541//541 623//623 547//547 -f 630//630 631//631 348//348 -f 348//348 631//631 609//609 -f 348//348 609//609 327//327 -f 547//547 623//623 542//542 -f 623//623 624//624 542//542 -f 542//542 624//624 625//625 -f 542//542 625//625 543//543 -f 543//543 625//625 626//626 -f 543//543 626//626 627//627 -f 630//630 348//348 629//629 -f 629//629 348//348 347//347 -f 629//629 347//347 628//628 -f 628//628 347//347 346//346 -f 628//628 346//346 627//627 -f 627//627 346//346 544//544 -f 627//627 544//544 543//543 -f 633//633 151//151 634//634 -f 634//634 151//151 136//136 -f 634//634 136//136 635//635 -f 635//635 136//136 139//139 -f 635//635 139//139 636//636 -f 636//636 139//139 138//138 -f 636//636 138//138 637//637 -f 637//637 138//138 158//158 -f 638//638 639//639 640//640 -f 641//641 642//642 643//643 -f 644//644 645//645 646//646 -f 646//646 645//645 647//647 -f 646//646 647//647 648//648 -f 643//643 642//642 649//649 -f 649//649 642//642 650//650 -f 649//649 650//650 651//651 -f 652//652 653//653 654//654 -f 654//654 653//653 655//655 -f 654//654 655//655 656//656 -f 656//656 655//655 657//657 -f 656//656 657//657 658//658 -f 659//659 660//660 661//661 -f 661//661 662//662 659//659 -f 659//659 662//662 663//663 -f 659//659 663//663 664//664 -f 664//664 663//663 665//665 -f 664//664 665//665 666//666 -f 666//666 665//665 667//667 -f 666//666 667//667 640//640 -f 640//640 667//667 668//668 -f 640//640 668//668 638//638 -f 638//638 668//668 645//645 -f 638//638 645//645 654//654 -f 654//654 645//645 644//644 -f 654//654 644//644 652//652 -f 652//652 644//644 669//669 -f 652//652 669//669 670//670 -f 671//671 672//672 673//673 -f 673//673 672//672 649//649 -f 673//673 649//649 674//674 -f 674//674 649//649 651//651 -f 674//674 651//651 675//675 -f 675//675 651//651 676//676 -f 670//670 669//669 677//677 -f 677//677 669//669 678//678 -f 677//677 678//678 671//671 -f 671//671 678//678 672//672 -f 672//672 678//678 679//679 -f 672//672 679//679 680//680 -f 680//680 679//679 681//681 -f 680//680 681//681 682//682 -f 682//682 681//681 683//683 -f 682//682 683//683 684//684 -f 685//685 686//686 687//687 -f 687//687 686//686 688//688 -f 687//687 688//688 689//689 -f 641//641 643//643 690//690 -f 690//690 643//643 691//691 -f 690//690 691//691 692//692 -f 692//692 691//691 693//693 -f 692//692 693//693 694//694 -f 694//694 693//693 695//695 -f 694//694 695//695 696//696 -f 696//696 695//695 697//697 -f 696//696 697//697 698//698 -f 698//698 697//697 699//699 -f 698//698 699//699 700//700 -f 700//700 699//699 701//701 -f 700//700 701//701 702//702 -f 702//702 701//701 703//703 -f 702//702 703//703 704//704 -f 704//704 703//703 682//682 -f 704//704 682//682 685//685 -f 685//685 682//682 684//684 -f 685//685 684//684 686//686 -f 702//702 705//705 700//700 -f 700//700 705//705 706//706 -f 700//700 706//706 707//707 -f 707//707 706//706 708//708 -f 707//707 708//708 709//709 -f 709//709 708//708 710//710 -f 709//709 710//710 711//711 -f 711//711 710//710 712//712 -f 711//711 712//712 713//713 -f 713//713 712//712 714//714 -f 713//713 714//714 660//660 -f 660//660 714//714 715//715 -f 660//660 715//715 661//661 -f 661//661 715//715 689//689 -f 661//661 689//689 716//716 -f 716//716 689//689 688//688 -f 716//716 688//688 717//717 -f 717//717 688//688 718//718 -f 717//717 718//718 719//719 -f 719//719 718//718 648//648 -f 719//719 648//648 720//720 -f 720//720 648//648 647//647 -f 102//102 105//105 721//721 -f 721//721 105//105 152//152 -f 721//721 152//152 722//722 -f 722//722 152//152 723//723 -f 723//723 152//152 145//145 -f 723//723 145//145 724//724 -f 724//724 145//145 725//725 -f 725//725 145//145 144//144 -f 725//725 144//144 726//726 -f 726//726 144//144 727//727 -f 727//727 144//144 143//143 -f 727//727 143//143 728//728 -f 728//728 143//143 729//729 -f 729//729 143//143 151//151 -f 729//729 151//151 633//633 -f 637//637 158//158 730//730 -f 730//730 158//158 160//160 -f 730//730 160//160 731//731 -f 731//731 160//160 732//732 -f 732//732 160//160 163//163 -f 732//732 163//163 733//733 -f 733//733 163//163 734//734 -f 734//734 163//163 162//162 -f 734//734 162//162 735//735 -f 735//735 162//162 736//736 -f 736//736 162//162 161//161 -f 736//736 161//161 737//737 -f 737//737 161//161 738//738 -f 738//738 161//161 159//159 -f 738//738 159//159 457//457 -f 102//102 721//721 103//103 -f 692//692 76//76 80//80 -f 728//728 729//729 641//641 -f 641//641 729//729 633//633 -f 641//641 633//633 642//642 -f 103//103 721//721 78//78 -f 721//721 722//722 78//78 -f 78//78 722//722 723//723 -f 78//78 723//723 79//79 -f 79//79 723//723 724//724 -f 79//79 724//724 725//725 -f 728//728 641//641 727//727 -f 727//727 641//641 690//690 -f 727//727 690//690 726//726 -f 726//726 690//690 692//692 -f 726//726 692//692 725//725 -f 725//725 692//692 80//80 -f 725//725 80//80 79//79 -f 739//739 740//740 676//676 -f 741//741 742//742 636//636 -f 636//636 742//742 743//743 -f 739//739 676//676 744//744 -f 642//642 633//633 650//650 -f 650//650 633//633 634//634 -f 650//650 634//634 651//651 -f 651//651 634//634 635//635 -f 651//651 635//635 676//676 -f 676//676 635//635 636//636 -f 676//676 636//636 744//744 -f 744//744 636//636 743//743 -f 637//637 656//656 636//636 -f 636//636 656//656 658//658 -f 741//741 636//636 745//745 -f 745//745 636//636 658//658 -f 745//745 658//658 746//746 -f 656//656 637//637 730//730 -f 461//461 460//460 639//639 -f 656//656 730//730 654//654 -f 654//654 730//730 731//731 -f 654//654 731//731 638//638 -f 638//638 731//731 732//732 -f 638//638 732//732 639//639 -f 639//639 732//732 733//733 -f 639//639 733//733 461//461 -f 461//461 733//733 734//734 -f 461//461 734//734 464//464 -f 464//464 734//734 735//735 -f 464//464 735//735 463//463 -f 735//735 736//736 463//463 -f 463//463 736//736 737//737 -f 463//463 737//737 462//462 -f 462//462 737//737 738//738 -f 462//462 738//738 457//457 -f 747//747 276//276 748//748 -f 748//748 276//276 155//155 -f 748//748 155//155 749//749 -f 749//749 155//155 750//750 -f 750//750 155//155 154//154 -f 750//750 154//154 751//751 -f 752//752 753//753 754//754 -f 751//751 755//755 750//750 -f 750//750 755//755 756//756 -f 750//750 756//756 757//757 -f 757//757 756//756 758//758 -f 757//757 758//758 754//754 -f 754//754 758//758 759//759 -f 754//754 759//759 752//752 -f 760//760 761//761 762//762 -f 762//762 761//761 763//763 -f 762//762 763//763 764//764 -f 764//764 763//763 765//765 -f 764//764 765//765 766//766 -f 766//766 765//765 767//767 -f 766//766 767//767 768//768 -f 768//768 767//767 769//769 -f 768//768 769//769 770//770 -f 770//770 769//769 771//771 -f 770//770 771//771 772//772 -f 772//772 771//771 773//773 -f 772//772 773//773 774//774 -f 774//774 773//773 775//775 -f 774//774 775//775 776//776 -f 776//776 775//775 777//777 -f 776//776 777//777 778//778 -f 778//778 777//777 779//779 -f 778//778 779//779 780//780 -f 779//779 781//781 780//780 -f 780//780 781//781 782//782 -f 780//780 782//782 783//783 -f 783//783 782//782 784//784 -f 783//783 784//784 760//760 -f 760//760 784//784 785//785 -f 760//760 785//785 761//761 -f 761//761 785//785 786//786 -f 786//786 785//785 784//784 -f 786//786 784//784 787//787 -f 787//787 784//784 782//782 -f 787//787 782//782 788//788 -f 788//788 782//782 781//781 -f 788//788 781//781 789//789 -f 789//789 781//781 779//779 -f 789//789 779//779 790//790 -f 790//790 779//779 777//777 -f 790//790 777//777 791//791 -f 791//791 777//777 775//775 -f 791//791 775//775 792//792 -f 792//792 775//775 773//773 -f 792//792 773//773 793//793 -f 793//793 773//773 771//771 -f 793//793 771//771 794//794 -f 794//794 771//771 769//769 -f 794//794 769//769 795//795 -f 795//795 769//769 767//767 -f 795//795 767//767 796//796 -f 796//796 767//767 765//765 -f 796//796 765//765 797//797 -f 797//797 765//765 763//763 -f 797//797 763//763 798//798 -f 798//798 763//763 761//761 -f 798//798 761//761 786//786 -f 353//353 352//352 255//255 -f 255//255 352//352 253//253 -f 275//275 263//263 756//756 -f 756//756 263//263 758//758 -f 442//442 799//799 444//444 -f 444//444 799//799 800//800 -f 444//444 800//800 446//446 -f 446//446 800//800 801//801 -f 446//446 801//801 448//448 -f 448//448 801//801 802//802 -f 448//448 802//802 450//450 -f 450//450 802//802 803//803 -f 450//450 803//803 452//452 -f 452//452 803//803 804//804 -f 452//452 804//804 454//454 -f 454//454 804//804 805//805 -f 454//454 805//805 456//456 -f 456//456 805//805 806//806 -f 456//456 806//806 434//434 -f 434//434 806//806 807//807 -f 434//434 807//807 436//436 -f 436//436 807//807 808//808 -f 436//436 808//808 438//438 -f 438//438 808//808 809//809 -f 438//438 809//809 440//440 -f 440//440 809//809 810//810 -f 440//440 810//810 442//442 -f 442//442 810//810 799//799 -f 811//811 801//801 812//812 -f 812//812 801//801 800//800 -f 812//812 800//800 813//813 -f 813//813 800//800 799//799 -f 813//813 799//799 814//814 -f 814//814 799//799 810//810 -f 814//814 810//810 815//815 -f 815//815 810//810 809//809 -f 815//815 809//809 816//816 -f 816//816 809//809 808//808 -f 816//816 808//808 817//817 -f 817//817 808//808 807//807 -f 817//817 807//807 818//818 -f 818//818 807//807 806//806 -f 818//818 806//806 819//819 -f 819//819 806//806 805//805 -f 819//819 805//805 820//820 -f 820//820 805//805 804//804 -f 820//820 804//804 821//821 -f 821//821 804//804 803//803 -f 821//821 803//803 822//822 -f 822//822 803//803 802//802 -f 822//822 802//802 811//811 -f 811//811 802//802 801//801 -f 418//418 823//823 420//420 -f 420//420 823//823 824//824 -f 420//420 824//824 422//422 -f 422//422 824//824 825//825 -f 422//422 825//825 424//424 -f 424//424 825//825 826//826 -f 424//424 826//826 426//426 -f 426//426 826//826 827//827 -f 426//426 827//827 428//428 -f 428//428 827//827 828//828 -f 428//428 828//828 430//430 -f 430//430 828//828 829//829 -f 430//430 829//829 432//432 -f 432//432 829//829 830//830 -f 432//432 830//830 410//410 -f 410//410 830//830 831//831 -f 410//410 831//831 412//412 -f 412//412 831//831 832//832 -f 412//412 832//832 414//414 -f 414//414 832//832 833//833 -f 414//414 833//833 416//416 -f 416//416 833//833 834//834 -f 416//416 834//834 418//418 -f 418//418 834//834 823//823 -f 835//835 825//825 836//836 -f 836//836 825//825 824//824 -f 836//836 824//824 837//837 -f 837//837 824//824 823//823 -f 837//837 823//823 838//838 -f 838//838 823//823 834//834 -f 838//838 834//834 839//839 -f 839//839 834//834 833//833 -f 839//839 833//833 840//840 -f 840//840 833//833 832//832 -f 840//840 832//832 841//841 -f 841//841 832//832 831//831 -f 841//841 831//831 842//842 -f 842//842 831//831 830//830 -f 842//842 830//830 843//843 -f 843//843 830//830 829//829 -f 843//843 829//829 844//844 -f 844//844 829//829 828//828 -f 844//844 828//828 845//845 -f 845//845 828//828 827//827 -f 845//845 827//827 846//846 -f 846//846 827//827 826//826 -f 846//846 826//826 835//835 -f 835//835 826//826 825//825 -f 394//394 847//847 396//396 -f 396//396 847//847 848//848 -f 396//396 848//848 398//398 -f 398//398 848//848 849//849 -f 398//398 849//849 400//400 -f 400//400 849//849 850//850 -f 400//400 850//850 402//402 -f 402//402 850//850 851//851 -f 402//402 851//851 404//404 -f 404//404 851//851 852//852 -f 404//404 852//852 406//406 -f 406//406 852//852 853//853 -f 406//406 853//853 408//408 -f 408//408 853//853 854//854 -f 408//408 854//854 386//386 -f 386//386 854//854 855//855 -f 386//386 855//855 388//388 -f 388//388 855//855 856//856 -f 388//388 856//856 390//390 -f 390//390 856//856 857//857 -f 390//390 857//857 392//392 -f 392//392 857//857 858//858 -f 392//392 858//858 394//394 -f 394//394 858//858 847//847 -f 746//746 859//859 860//860 -f 860//860 859//859 861//861 -f 743//743 742//742 862//862 -f 862//862 742//742 741//741 -f 862//862 741//741 860//860 -f 860//860 741//741 745//745 -f 860//860 745//745 746//746 -f 743//743 862//862 744//744 -f 744//744 862//862 863//863 -f 744//744 863//863 739//739 -f 864//864 865//865 863//863 -f 863//863 865//865 740//740 -f 863//863 740//740 739//739 -f 866//866 867//867 864//864 -f 864//864 867//867 868//868 -f 864//864 868//868 865//865 -f 869//869 870//870 866//866 -f 866//866 870//870 871//871 -f 866//866 871//871 867//867 -f 872//872 873//873 869//869 -f 869//869 873//873 874//874 -f 869//869 874//874 870//870 -f 875//875 876//876 872//872 -f 872//872 876//876 877//877 -f 872//872 877//877 873//873 -f 878//878 879//879 875//875 -f 875//875 879//879 880//880 -f 875//875 880//880 876//876 -f 881//881 882//882 878//878 -f 878//878 882//882 883//883 -f 878//878 883//883 879//879 -f 884//884 885//885 881//881 -f 881//881 885//885 886//886 -f 881//881 886//886 882//882 -f 859//859 887//887 861//861 -f 861//861 887//887 888//888 -f 861//861 888//888 884//884 -f 884//884 888//888 889//889 -f 884//884 889//889 885//885 -f 370//370 890//890 372//372 -f 372//372 890//890 891//891 -f 372//372 891//891 374//374 -f 374//374 891//891 892//892 -f 374//374 892//892 376//376 -f 376//376 892//892 893//893 -f 376//376 893//893 378//378 -f 378//378 893//893 894//894 -f 378//378 894//894 380//380 -f 380//380 894//894 895//895 -f 380//380 895//895 382//382 -f 382//382 895//895 896//896 -f 382//382 896//896 384//384 -f 384//384 896//896 897//897 -f 384//384 897//897 362//362 -f 362//362 897//897 898//898 -f 362//362 898//898 364//364 -f 364//364 898//898 899//899 -f 364//364 899//899 366//366 -f 366//366 899//899 900//900 -f 366//366 900//900 368//368 -f 368//368 900//900 901//901 -f 368//368 901//901 370//370 -f 370//370 901//901 890//890 -f 902//902 892//892 903//903 -f 903//903 892//892 891//891 -f 903//903 891//891 904//904 -f 904//904 891//891 890//890 -f 904//904 890//890 905//905 -f 905//905 890//890 901//901 -f 905//905 901//901 906//906 -f 906//906 901//901 900//900 -f 906//906 900//900 907//907 -f 907//907 900//900 899//899 -f 907//907 899//899 908//908 -f 908//908 899//899 898//898 -f 908//908 898//898 909//909 -f 909//909 898//898 897//897 -f 909//909 897//897 910//910 -f 910//910 897//897 896//896 -f 910//910 896//896 911//911 -f 911//911 896//896 895//895 -f 911//911 895//895 912//912 -f 912//912 895//895 894//894 -f 912//912 894//894 913//913 -f 913//913 894//894 893//893 -f 913//913 893//893 902//902 -f 902//902 893//893 892//892 -f 247//247 254//254 351//351 -f 351//351 254//254 360//360 -f 750//750 757//757 267//267 -f 267//267 757//757 272//272 -f 914//914 915//915 545//545 -f 545//545 915//915 546//546 -f 916//916 917//917 71//71 -f 71//71 917//917 632//632 -f 71//71 632//632 72//72 -f 915//915 914//914 918//918 -f 915//915 918//918 919//919 -f 919//919 918//918 920//920 -f 919//919 920//920 921//921 -f 921//921 920//920 922//922 -f 921//921 922//922 923//923 -f 923//923 922//922 924//924 -f 923//923 924//924 925//925 -f 925//925 924//924 926//926 -f 925//925 926//926 927//927 -f 927//927 926//926 928//928 -f 927//927 928//928 929//929 -f 929//929 928//928 930//930 -f 929//929 930//930 931//931 -f 931//931 930//930 917//917 -f 931//931 917//917 916//916 -f 932//932 229//229 933//933 -f 933//933 229//229 227//227 -f 229//229 932//932 231//231 -f 231//231 932//932 934//934 -f 231//231 934//934 233//233 -f 233//233 934//934 935//935 -f 264//264 233//233 291//291 -f 291//291 233//233 935//935 -f 291//291 935//935 290//290 -f 290//290 935//935 586//586 -f 241//241 251//251 288//288 -f 933//933 227//227 936//936 -f 936//936 227//227 243//243 -f 936//936 243//243 937//937 -f 289//289 304//304 288//288 -f 288//288 304//304 937//937 -f 288//288 937//937 241//241 -f 241//241 937//937 243//243 -f 200//200 201//201 938//938 -f 938//938 201//201 939//939 -f 940//940 211//211 104//104 -f 209//209 941//941 91//91 -f 91//91 941//941 942//942 -f 91//91 942//942 104//104 -f 104//104 942//942 943//943 -f 104//104 943//943 940//940 -f 944//944 168//168 167//167 -f 137//137 945//945 149//149 -f 149//149 945//945 946//946 -f 149//149 946//946 947//947 -f 944//944 167//167 948//948 -f 948//948 167//167 949//949 -f 948//948 949//949 950//950 -f 938//938 939//939 951//951 -f 951//951 939//939 952//952 -f 951//951 952//952 953//953 -f 951//951 954//954 938//938 -f 938//938 954//954 955//955 -f 938//938 955//955 950//950 -f 950//950 955//955 956//956 -f 950//950 956//956 948//948 -f 947//947 946//946 957//957 -f 957//957 946//946 958//958 -f 957//957 958//958 939//939 -f 939//939 958//958 959//959 -f 939//939 959//959 952//952 -f 960//960 210//210 961//961 -f 961//961 210//210 211//211 -f 961//961 211//211 940//940 -f 208//208 52//52 209//209 -f 209//209 52//52 50//50 -f 209//209 50//50 941//941 -f 960//960 962//962 210//210 -f 210//210 962//962 963//963 -f 210//210 963//963 953//953 -f 953//953 963//963 64//64 -f 953//953 64//64 951//951 -f 951//951 64//64 62//62 -f 951//951 62//62 60//60 -f 943//943 942//942 58//58 -f 58//58 942//942 964//964 -f 58//58 964//964 60//60 -f 60//60 964//964 965//965 -f 60//60 965//965 951//951 -f 951//951 965//965 966//966 -f 966//966 967//967 951//951 -f 951//951 967//967 56//56 -f 951//951 56//56 208//208 -f 208//208 56//56 54//54 -f 208//208 54//54 52//52 -f 959//959 958//958 85//85 -f 85//85 958//958 83//83 -f 94//94 99//99 955//955 -f 955//955 99//99 956//956 -f 236//236 967//967 237//237 -f 237//237 967//967 966//966 -f 237//237 966//966 238//238 -f 238//238 966//966 965//965 -f 238//238 965//965 239//239 -f 239//239 965//965 964//964 -f 56//56 967//967 55//55 -f 55//55 967//967 236//236 -f 213//213 963//963 214//214 -f 214//214 963//963 962//962 -f 214//214 962//962 221//221 -f 221//221 962//962 960//960 -f 221//221 960//960 222//222 -f 222//222 960//960 961//961 -f 64//64 963//963 63//63 -f 63//63 963//963 213//213 -f 968//968 226//226 228//228 -f 232//232 131//131 230//230 -f 230//230 131//131 130//130 -f 230//230 130//130 228//228 -f 228//228 130//130 128//128 -f 228//228 128//128 968//968 -f 968//968 128//128 127//127 -f 968//968 127//127 969//969 -f 969//969 127//127 126//126 -f 969//969 126//126 970//970 -f 970//970 126//126 124//124 -f 970//970 124//124 971//971 -f 971//971 124//124 134//134 -f 232//232 234//234 131//131 -f 131//131 234//234 132//132 -f 972//972 135//135 973//973 -f 973//973 135//135 122//122 -f 973//973 122//122 974//974 -f 974//974 122//122 121//121 -f 974//974 121//121 975//975 -f 975//975 121//121 120//120 -f 975//975 120//120 106//106 -f 224//224 975//975 225//225 -f 225//225 975//975 106//106 -f 225//225 106//106 235//235 -f 235//235 106//106 133//133 -f 235//235 133//133 234//234 -f 234//234 133//133 132//132 -f 971//971 134//134 972//972 -f 972//972 134//134 135//135 -f 976//976 220//220 219//219 -f 216//216 112//112 217//217 -f 217//217 112//112 111//111 -f 217//217 111//111 219//219 -f 219//219 111//111 110//110 -f 219//219 110//110 976//976 -f 976//976 110//110 90//90 -f 976//976 90//90 977//977 -f 977//977 90//90 89//89 -f 977//977 89//89 978//978 -f 978//978 89//89 109//109 -f 978//978 109//109 979//979 -f 979//979 109//109 108//108 -f 216//216 240//240 112//112 -f 112//112 240//240 113//113 -f 980//980 107//107 981//981 -f 981//981 107//107 123//123 -f 981//981 123//123 982//982 -f 982//982 123//123 125//125 -f 982//982 125//125 983//983 -f 983//983 125//125 118//118 -f 983//983 118//118 116//116 -f 245//245 983//983 244//244 -f 244//244 983//983 116//116 -f 244//244 116//116 242//242 -f 242//242 116//116 115//115 -f 242//242 115//115 240//240 -f 240//240 115//115 113//113 -f 979//979 108//108 980//980 -f 980//980 108//108 107//107 -f 983//983 942//942 982//982 -f 982//982 942//942 981//981 -f 941//941 976//976 977//977 -f 977//977 978//978 941//941 -f 941//941 978//978 979//979 -f 941//941 979//979 942//942 -f 942//942 979//979 980//980 -f 942//942 980//980 981//981 -f 239//239 964//964 245//245 -f 245//245 964//964 942//942 -f 245//245 942//942 983//983 -f 50//50 49//49 941//941 -f 941//941 49//49 220//220 -f 941//941 220//220 976//976 -f 974//974 975//975 940//940 -f 943//943 968//968 969//969 -f 974//974 940//940 973//973 -f 969//969 970//970 943//943 -f 943//943 970//970 971//971 -f 943//943 971//971 940//940 -f 940//940 971//971 972//972 -f 940//940 972//972 973//973 -f 58//58 57//57 943//943 -f 943//943 57//57 226//226 -f 943//943 226//226 968//968 -f 222//222 961//961 224//224 -f 224//224 961//961 940//940 -f 224//224 940//940 975//975 -f 198//198 199//199 585//585 -f 585//585 581//581 198//198 -f 198//198 581//581 580//580 -f 198//198 580//580 192//192 -f 192//192 580//580 579//579 -f 192//192 579//579 193//193 -f 193//193 579//579 571//571 -f 193//193 571//571 207//207 -f 584//584 585//585 199//199 -f 165//165 164//164 199//199 -f 199//199 164//164 559//559 -f 199//199 559//559 584//584 -f 584//584 559//559 560//560 -f 584//584 560//560 583//583 -f 583//583 560//560 557//557 -f 583//583 557//557 582//582 -f 582//582 557//557 548//548 -f 582//582 548//548 550//550 -f 577//577 578//578 195//195 -f 195//195 196//196 577//577 -f 577//577 196//196 197//197 -f 577//577 197//197 575//575 -f 575//575 197//197 202//202 -f 575//575 202//202 576//576 -f 576//576 202//202 194//194 -f 576//576 194//194 570//570 -f 195//195 578//578 574//574 -f 150//150 148//148 566//566 -f 566//566 148//148 195//195 -f 195//195 574//574 566//566 -f 566//566 574//574 573//573 -f 566//566 573//573 567//567 -f 567//567 573//573 572//572 -f 567//567 572//572 569//569 -f 569//569 572//572 551//551 -f 569//569 551//551 549//549 -f 167//167 166//166 204//204 -f 167//167 204//204 949//949 -f 949//949 204//204 203//203 -f 949//949 203//203 950//950 -f 950//950 203//203 200//200 -f 950//950 200//200 938//938 -f 147//147 149//149 947//947 -f 147//147 947//947 206//206 -f 206//206 947//947 957//957 -f 206//206 957//957 205//205 -f 205//205 957//957 939//939 -f 205//205 939//939 201//201 -f 48//48 46//46 984//984 -f 984//984 46//46 985//985 -f 46//46 44//44 985//985 -f 985//985 44//44 42//42 -f 985//985 42//42 986//986 -f 987//987 988//988 32//32 -f 32//32 30//30 987//987 -f 987//987 30//30 28//28 -f 987//987 28//28 984//984 -f 984//984 28//28 26//26 -f 984//984 26//26 48//48 -f 42//42 40//40 986//986 -f 986//986 40//40 38//38 -f 986//986 38//38 989//989 -f 989//989 38//38 36//36 -f 989//989 36//36 988//988 -f 988//988 36//36 34//34 -f 988//988 34//34 32//32 -f 988//988 987//987 562//562 -f 562//562 987//987 561//561 -f 987//987 984//984 561//561 -f 561//561 984//984 568//568 -f 984//984 985//985 568//568 -f 568//568 985//985 565//565 -f 985//985 986//986 565//565 -f 565//565 986//986 564//564 -f 986//986 989//989 564//564 -f 564//564 989//989 563//563 -f 989//989 988//988 563//563 -f 563//563 988//988 562//562 -f 990//990 991//991 2//2 -f 2//2 24//24 990//990 -f 990//990 24//24 22//22 -f 990//990 22//22 992//992 -f 992//992 22//22 20//20 -f 992//992 20//20 993//993 -f 10//10 994//994 12//12 -f 12//12 994//994 995//995 -f 10//10 8//8 994//994 -f 994//994 8//8 6//6 -f 994//994 6//6 991//991 -f 991//991 6//6 4//4 -f 991//991 4//4 2//2 -f 20//20 18//18 993//993 -f 993//993 18//18 16//16 -f 993//993 16//16 995//995 -f 995//995 16//16 14//14 -f 995//995 14//14 12//12 -f 994//994 991//991 553//553 -f 553//553 991//991 552//552 -f 991//991 990//990 552//552 -f 552//552 990//990 558//558 -f 990//990 992//992 558//558 -f 558//558 992//992 556//556 -f 992//992 993//993 556//556 -f 556//556 993//993 555//555 -f 993//993 995//995 555//555 -f 555//555 995//995 554//554 -f 995//995 994//994 554//554 -f 554//554 994//994 553//553 -f 94//94 955//955 954//954 -f 94//94 954//954 95//95 -f 95//95 954//954 951//951 -f 95//95 951//951 96//96 -f 96//96 951//951 208//208 -f 96//96 208//208 100//100 -f 956//956 99//99 98//98 -f 956//956 98//98 948//948 -f 948//948 98//98 97//97 -f 948//948 97//97 944//944 -f 944//944 97//97 93//93 -f 944//944 93//93 168//168 -f 959//959 85//85 70//70 -f 959//959 70//70 952//952 -f 952//952 70//70 69//69 -f 952//952 69//69 953//953 -f 953//953 69//69 68//68 -f 953//953 68//68 210//210 -f 83//83 958//958 946//946 -f 83//83 946//946 81//81 -f 81//81 946//946 945//945 -f 81//81 945//945 82//82 -f 82//82 945//945 137//137 -f 82//82 137//137 84//84 -f 360//360 254//254 258//258 -f 360//360 258//258 359//359 -f 359//359 258//258 257//257 -f 359//359 257//257 358//358 -f 358//358 257//257 259//259 -f 358//358 259//259 354//354 -f 354//354 259//259 260//260 -f 354//354 260//260 355//355 -f 355//355 260//260 253//253 -f 355//355 253//253 352//352 -f 272//272 757//757 754//754 -f 272//272 754//754 273//273 -f 273//273 754//754 753//753 -f 273//273 753//753 274//274 -f 274//274 753//753 752//752 -f 274//274 752//752 261//261 -f 261//261 752//752 759//759 -f 261//261 759//759 262//262 -f 262//262 759//759 758//758 -f 262//262 758//758 263//263 -f 182//182 181//181 357//357 -f 182//182 357//357 252//252 -f 252//252 357//357 356//356 -f 252//252 356//356 256//256 -f 256//256 356//356 353//353 -f 256//256 353//353 255//255 -f 154//154 153//153 268//268 -f 154//154 268//268 751//751 -f 751//751 268//268 269//269 -f 751//751 269//269 755//755 -f 755//755 269//269 275//275 -f 755//755 275//275 756//756 -f 289//289 250//250 249//249 -f 289//289 249//249 282//282 -f 247//247 351//351 248//248 -f 248//248 351//351 350//350 -f 248//248 350//350 249//249 -f 249//249 350//350 349//349 -f 249//249 349//349 282//282 -f 596//596 747//747 290//290 -f 290//290 747//747 748//748 -f 750//750 267//267 749//749 -f 749//749 267//267 271//271 -f 749//749 271//271 748//748 -f 748//748 271//271 270//270 -f 748//748 270//270 290//290 -f 290//290 270//270 265//265 -f 856//856 881//881 857//857 -f 857//857 881//881 878//878 -f 857//857 878//878 858//858 -f 858//858 878//878 875//875 -f 858//858 875//875 847//847 -f 847//847 875//875 872//872 -f 847//847 872//872 848//848 -f 848//848 872//872 869//869 -f 848//848 869//869 849//849 -f 849//849 869//869 866//866 -f 849//849 866//866 850//850 -f 850//850 866//866 864//864 -f 850//850 864//864 851//851 -f 851//851 864//864 863//863 -f 851//851 863//863 852//852 -f 852//852 863//863 862//862 -f 852//852 862//862 853//853 -f 853//853 862//862 860//860 -f 853//853 860//860 854//854 -f 854//854 860//860 861//861 -f 854//854 861//861 855//855 -f 855//855 861//861 884//884 -f 855//855 884//884 856//856 -f 856//856 884//884 881//881 -f 657//657 859//859 658//658 -f 658//658 859//859 746//746 -f 675//675 676//676 740//740 -f 740//740 865//865 675//675 -f 675//675 865//865 868//868 -f 675//675 868//868 674//674 -f 868//868 867//867 674//674 -f 674//674 867//867 871//871 -f 674//674 871//871 673//673 -f 871//871 870//870 673//673 -f 673//673 870//870 874//874 -f 673//673 874//874 671//671 -f 874//874 873//873 671//671 -f 671//671 873//873 877//877 -f 671//671 877//877 677//677 -f 877//877 876//876 677//677 -f 677//677 876//876 880//880 -f 677//677 880//880 670//670 -f 670//670 880//880 879//879 -f 670//670 879//879 652//652 -f 879//879 883//883 652//652 -f 652//652 883//883 882//882 -f 652//652 882//882 653//653 -f 882//882 886//886 653//653 -f 653//653 886//886 885//885 -f 653//653 885//885 655//655 -f 885//885 889//889 655//655 -f 655//655 889//889 888//888 -f 655//655 888//888 657//657 -f 657//657 888//888 887//887 -f 657//657 887//887 859//859 -f 840//840 663//663 839//839 -f 839//839 663//663 662//662 -f 839//839 662//662 838//838 -f 838//838 662//662 661//661 -f 838//838 661//661 837//837 -f 837//837 661//661 716//716 -f 837//837 716//716 836//836 -f 836//836 716//716 717//717 -f 836//836 717//717 835//835 -f 835//835 717//717 719//719 -f 835//835 719//719 846//846 -f 846//846 719//719 720//720 -f 846//846 720//720 845//845 -f 845//845 720//720 647//647 -f 845//845 647//647 844//844 -f 844//844 647//647 645//645 -f 844//844 645//645 843//843 -f 843//843 645//645 668//668 -f 843//843 668//668 842//842 -f 842//842 668//668 667//667 -f 842//842 667//667 841//841 -f 841//841 667//667 665//665 -f 841//841 665//665 840//840 -f 840//840 665//665 663//663 -f 816//816 714//714 815//815 -f 815//815 714//714 712//712 -f 815//815 712//712 814//814 -f 814//814 712//712 710//710 -f 814//814 710//710 813//813 -f 813//813 710//710 708//708 -f 813//813 708//708 812//812 -f 812//812 708//708 706//706 -f 812//812 706//706 811//811 -f 811//811 706//706 705//705 -f 811//811 705//705 822//822 -f 822//822 705//705 702//702 -f 822//822 702//702 821//821 -f 821//821 702//702 704//704 -f 821//821 704//704 820//820 -f 820//820 704//704 685//685 -f 820//820 685//685 819//819 -f 819//819 685//685 687//687 -f 819//819 687//687 818//818 -f 818//818 687//687 689//689 -f 818//818 689//689 817//817 -f 817//817 689//689 715//715 -f 817//817 715//715 816//816 -f 816//816 715//715 714//714 -f 907//907 682//682 906//906 -f 906//906 682//682 703//703 -f 906//906 703//703 905//905 -f 905//905 703//703 701//701 -f 905//905 701//701 904//904 -f 904//904 701//701 699//699 -f 904//904 699//699 903//903 -f 903//903 699//699 697//697 -f 903//903 697//697 902//902 -f 902//902 697//697 695//695 -f 902//902 695//695 913//913 -f 913//913 695//695 693//693 -f 913//913 693//693 912//912 -f 912//912 693//693 691//691 -f 912//912 691//691 911//911 -f 911//911 691//691 643//643 -f 911//911 643//643 910//910 -f 910//910 643//643 649//649 -f 910//910 649//649 909//909 -f 909//909 649//649 672//672 -f 909//909 672//672 908//908 -f 908//908 672//672 680//680 -f 908//908 680//680 907//907 -f 907//907 680//680 682//682 -f 495//495 718//718 493//493 -f 493//493 718//718 688//688 -f 493//493 688//688 491//491 -f 491//491 688//688 686//686 -f 491//491 686//686 489//489 -f 489//489 686//686 684//684 -f 489//489 684//684 487//487 -f 487//487 684//684 683//683 -f 487//487 683//683 512//512 -f 512//512 683//683 681//681 -f 512//512 681//681 510//510 -f 510//510 681//681 679//679 -f 510//510 679//679 506//506 -f 506//506 679//679 678//678 -f 506//506 678//678 504//504 -f 504//504 678//678 669//669 -f 504//504 669//669 502//502 -f 502//502 669//669 644//644 -f 502//502 644//644 499//499 -f 499//499 644//644 646//646 -f 499//499 646//646 497//497 -f 497//497 646//646 648//648 -f 497//497 648//648 495//495 -f 495//495 648//648 718//718 -f 459//459 640//640 460//460 -f 460//460 640//640 639//639 -f 640//640 459//459 466//466 -f 640//640 466//466 666//666 -f 666//666 466//466 468//468 -f 666//666 468//468 664//664 -f 664//664 468//468 470//470 -f 664//664 470//470 659//659 -f 659//659 470//470 472//472 -f 659//659 472//472 660//660 -f 660//660 472//472 474//474 -f 660//660 474//474 713//713 -f 713//713 474//474 476//476 -f 713//713 476//476 711//711 -f 711//711 476//476 478//478 -f 711//711 478//478 709//709 -f 709//709 478//478 480//480 -f 709//709 480//480 707//707 -f 707//707 480//480 482//482 -f 707//707 482//482 700//700 -f 700//700 482//482 484//484 -f 700//700 484//484 698//698 -f 698//698 484//484 486//486 -f 698//698 486//486 696//696 -f 696//696 486//486 74//74 -f 696//696 74//74 694//694 -f 694//694 74//74 692//692 -f 692//692 74//74 76//76 -f 599//599 281//281 600//600 -f 600//600 281//281 280//280 -f 600//600 280//280 601//601 -f 601//601 280//280 279//279 -f 601//601 279//279 602//602 -f 602//602 279//279 278//278 -f 602//602 278//278 595//595 -f 595//595 278//278 277//277 -f 595//595 277//277 596//596 -f 596//596 277//277 276//276 -f 596//596 276//276 747//747 -f 598//598 458//458 599//599 -f 599//599 458//458 281//281 -f 604//604 75//75 485//485 -f 604//604 485//485 605//605 -f 605//605 485//485 483//483 -f 605//605 483//483 606//606 -f 606//606 483//483 481//481 -f 606//606 481//481 607//607 -f 607//607 481//481 479//479 -f 607//607 479//479 608//608 -f 608//608 479//479 587//587 -f 587//587 479//479 477//477 -f 587//587 477//477 594//594 -f 594//594 477//477 475//475 -f 594//594 475//475 593//593 -f 593//593 475//475 473//473 -f 593//593 473//473 592//592 -f 592//592 473//473 471//471 -f 592//592 471//471 591//591 -f 591//591 471//471 469//469 -f 591//591 469//469 590//590 -f 590//590 469//469 467//467 -f 590//590 467//467 589//589 -f 589//589 467//467 588//588 -f 588//588 467//467 465//465 -f 588//588 465//465 597//597 -f 597//597 465//465 458//458 -f 597//597 458//458 598//598 -f 586//586 77//77 603//603 -f 603//603 77//77 75//75 -f 603//603 75//75 604//604 -f 915//915 294//294 546//546 -f 546//546 294//294 295//295 -f 932//932 119//119 934//934 -f 934//934 119//119 129//129 -f 934//934 129//129 935//935 -f 935//935 129//129 101//101 -f 935//935 101//101 586//586 -f 586//586 101//101 77//77 -f 294//294 915//915 919//919 -f 294//294 919//919 296//296 -f 296//296 919//919 921//921 -f 296//296 921//921 297//297 -f 297//297 921//921 923//923 -f 297//297 923//923 299//299 -f 299//299 923//923 925//925 -f 299//299 925//925 305//305 -f 305//305 925//925 927//927 -f 305//305 927//927 306//306 -f 306//306 927//927 929//929 -f 306//306 929//929 308//308 -f 308//308 929//929 931//931 -f 308//308 931//931 310//310 -f 310//310 931//931 916//916 -f 310//310 916//916 312//312 -f 933//933 117//117 932//932 -f 932//932 117//117 119//119 -f 71//71 314//314 916//916 -f 916//916 314//314 312//312 -f 304//304 67//67 937//937 -f 937//937 67//67 66//66 -f 937//937 66//66 936//936 -f 936//936 66//66 114//114 -f 936//936 114//114 933//933 -f 933//933 114//114 117//117 -f 67//67 304//304 71//71 -f 71//71 304//304 314//314 -f 917//917 330//330 632//632 -f 632//632 330//330 329//329 -f 330//330 917//917 930//930 -f 330//330 930//930 318//318 -f 318//318 930//930 928//928 -f 318//318 928//928 320//320 -f 320//320 928//928 926//926 -f 320//320 926//926 341//341 -f 341//341 926//926 924//924 -f 341//341 924//924 342//342 -f 342//342 924//924 922//922 -f 342//342 922//922 344//344 -f 344//344 922//922 920//920 -f 344//344 920//920 345//345 -f 345//345 920//920 918//918 -f 345//345 918//918 337//337 -f 337//337 918//918 914//914 -f 337//337 914//914 339//339 -f 914//914 545//545 339//339 -f 339//339 545//545 544//544 -f 339//339 544//544 346//346 -f 518//518 317//317 520//520 -f 520//520 317//317 319//319 -f 520//520 319//319 522//522 -f 522//522 319//319 321//321 -f 522//522 321//321 524//524 -f 524//524 321//321 343//343 -f 524//524 343//343 526//526 -f 526//526 343//343 336//336 -f 526//526 336//336 528//528 -f 528//528 336//336 338//338 -f 528//528 338//338 530//530 -f 530//530 338//338 340//340 -f 530//530 340//340 532//532 -f 532//532 340//340 326//326 -f 532//532 326//326 534//534 -f 534//534 326//326 325//325 -f 534//534 325//325 536//536 -f 536//536 325//325 333//333 -f 536//536 333//333 538//538 -f 538//538 333//333 323//323 -f 538//538 323//323 516//516 -f 516//516 323//323 322//322 -f 516//516 322//322 518//518 -f 518//518 322//322 317//317 -f 525//525 772//772 523//523 -f 523//523 772//772 774//774 -f 523//523 774//774 521//521 -f 521//521 774//774 776//776 -f 521//521 776//776 519//519 -f 519//519 776//776 778//778 -f 519//519 778//778 517//517 -f 517//517 778//778 780//780 -f 517//517 780//780 515//515 -f 515//515 780//780 783//783 -f 515//515 783//783 537//537 -f 537//537 783//783 760//760 -f 537//537 760//760 535//535 -f 535//535 760//760 762//762 -f 535//535 762//762 533//533 -f 533//533 762//762 764//764 -f 533//533 764//764 531//531 -f 531//531 764//764 766//766 -f 531//531 766//766 529//529 -f 529//529 766//766 768//768 -f 529//529 768//768 527//527 -f 527//527 768//768 770//770 -f 527//527 770//770 525//525 -f 525//525 770//770 772//772 -f 792//792 292//292 791//791 -f 791//791 292//292 298//298 -f 791//791 298//298 790//790 -f 790//790 298//298 300//300 -f 790//790 300//300 789//789 -f 789//789 300//300 307//307 -f 789//789 307//307 788//788 -f 788//788 307//307 309//309 -f 788//788 309//309 787//787 -f 787//787 309//309 311//311 -f 787//787 311//311 786//786 -f 786//786 311//311 313//313 -f 786//786 313//313 798//798 -f 798//798 313//313 315//315 -f 798//798 315//315 797//797 -f 797//797 315//315 316//316 -f 797//797 316//316 796//796 -f 796//796 316//316 303//303 -f 796//796 303//303 795//795 -f 795//795 303//303 302//302 -f 795//795 302//302 794//794 -f 794//794 302//302 301//301 -f 794//794 301//301 793//793 -f 793//793 301//301 293//293 -f 793//793 293//293 792//792 -f 792//792 293//293 292//292 -# 2034 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_S_mid.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_S_mid.obj deleted file mode 100644 index bbd251afe..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/hand_S_mid.obj +++ /dev/null @@ -1,1392 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object hand_S_mid.obj -# -# Vertices: 336 -# Faces: 704 -# -#### -vn -4.013411 -0.684889 4.573501 -v 0.077198 0.021500 0.044019 -vn -1.596641 -2.607676 2.575562 -v 0.077198 0.018500 0.044019 -vn -0.383869 -2.813968 3.075673 -v 0.080638 0.018500 0.045038 -vn -0.383869 -3.469219 3.075673 -v 0.080638 0.021500 0.045038 -vn 0.626285 -2.813969 3.035603 -v 0.084223 0.018500 0.044896 -vn 0.626285 -3.469218 3.035603 -v 0.084223 0.021500 0.044896 -vn 1.569817 -2.813965 2.672600 -v 0.087571 0.018500 0.043608 -vn 1.569817 -3.469221 2.672600 -v 0.087571 0.021500 0.043608 -vn 2.346350 -2.813968 2.025280 -v 0.090327 0.018500 0.041310 -vn 2.346350 -3.469217 2.025280 -v 0.090327 0.021500 0.041310 -vn 2.905138 -2.504320 0.679108 -v 0.092197 0.018500 0.038248 -vn 5.994989 -0.912319 0.192600 -v 0.092197 0.021500 0.038248 -vn -2.682949 -3.336426 1.605623 -v 0.079146 0.021500 0.046655 -vn 2.931146 -2.617995 0.785398 -v 0.101000 0.021500 0.067783 -vn 2.931146 -3.665192 0.785398 -v 0.077906 0.021500 0.107783 -vn 4.712389 -1.570796 -1.570796 -v 0.077906 0.021500 0.129940 -vn -4.712389 -1.570796 -1.570796 -v 0.055906 0.021500 0.129940 -vn -2.931146 -2.617994 -0.785398 -v 0.055906 0.021500 0.107783 -vn -2.770830 -3.209461 -1.476735 -v 0.079000 0.021500 0.067783 -vn 2.581446 -3.326361 -1.766846 -v 0.097227 0.021500 0.051367 -vn 2.766234 -2.579901 -1.208035 -v 0.100796 0.021500 0.055667 -vn 3.128155 -3.010694 -0.205029 -v 0.101000 0.021500 0.057220 -vn 3.042102 -3.322815 -0.736186 -v 0.092735 0.021500 0.041184 -vn 2.862110 -3.326361 -1.262512 -v 0.094510 0.021500 0.046483 -vn -2.939434 -3.365992 -1.051478 -v 0.080957 0.021500 0.063790 -vn -3.099712 -3.365992 -0.371031 -v 0.081976 0.021500 0.059462 -vn -3.104558 -3.365994 0.328023 -v 0.082007 0.021500 0.055016 -vn -2.953729 -3.365990 1.010627 -v 0.081048 0.021500 0.050674 -vn -0.000004 -3.665187 -3.034547 -v 0.082000 0.018500 0.043623 -vn -1.517272 -3.665192 -2.627994 -v 0.082750 0.018500 0.043422 -vn -1.517268 -3.665189 2.627998 -v 0.082750 0.018500 0.040824 -vn -0.000004 -3.665186 -3.034547 -v 0.082000 0.018500 0.027623 -vn -2.627993 -3.665201 1.517267 -v 0.083299 0.018500 0.041373 -vn -3.034550 -3.665180 -0.000002 -v 0.083500 0.018500 0.042123 -vn -1.517270 -3.665191 -2.627996 -v 0.082750 0.018500 0.027422 -vn 1.517276 -3.665200 2.627987 -v 0.089250 0.018500 0.032824 -vn -1.517268 -3.665192 -2.627998 -v 0.074750 0.018500 0.035422 -vn -2.138377 -3.283359 2.290730 -v 0.076398 0.018500 0.043159 -vn 0.000000 -3.665190 -3.034546 -v 0.074000 0.018500 0.035623 -vn -2.402188 -2.701069 1.904721 -v 0.072941 0.018500 0.040363 -vn 1.517268 -3.665189 -2.627998 -v 0.073250 0.018500 0.035422 -vn -2.968852 -2.835493 0.908921 -v 0.071482 0.018500 0.037343 -vn 2.627988 -3.665192 -1.517281 -v 0.072701 0.018500 0.034873 -vn 3.034543 -3.665198 0.000002 -v 0.072500 0.018500 0.034123 -vn -3.104744 -2.835494 -0.027968 -v 0.071000 0.018500 0.034024 -vn 2.627992 -3.665187 1.517279 -v 0.072701 0.018500 0.033373 -vn -2.951997 -2.835495 -0.962254 -v 0.071542 0.018500 0.030714 -vn 1.517272 -3.665192 2.627994 -v 0.073250 0.018500 0.032824 -vn 1.517272 -3.665198 -2.627991 -v 0.089250 0.018500 0.035422 -vn -2.627996 -3.665198 -1.517265 -v 0.083299 0.018500 0.042873 -vn 2.627996 -3.665186 -1.517273 -v 0.088701 0.018500 0.034873 -vn 3.034543 -3.665198 0.000002 -v 0.088500 0.018500 0.034123 -vn 2.628000 -3.665181 1.517272 -v 0.088701 0.018500 0.033373 -vn -0.000004 -3.665187 -3.034547 -v 0.090000 0.018500 0.035623 -vn -1.517276 -3.665195 -2.627990 -v 0.090750 0.018500 0.035422 -vn 3.133679 -3.277075 -0.066624 -v 0.091965 0.018500 0.035649 -vn 2.406844 -2.835492 -1.961457 -v 0.090527 0.018500 0.027174 -vn 2.923806 -2.564369 -0.722102 -v 0.092225 0.018500 0.030066 -vn -1.517280 -3.665199 2.627987 -v 0.090750 0.018500 0.032824 -vn 2.627996 -3.665185 1.517273 -v 0.080701 0.018500 0.041373 -vn 1.517272 -3.665199 2.627991 -v 0.081250 0.018500 0.040824 -vn -2.627992 -3.665201 -1.517267 -v 0.075299 0.018500 0.034873 -vn -3.034551 -3.665180 -0.000000 -v 0.083500 0.018500 0.026123 -vn -2.627995 -3.665199 1.517266 -v 0.083299 0.018500 0.025373 -vn 0.842544 -2.835494 -2.988367 -v 0.084985 0.018500 0.023535 -vn -1.517270 -3.665190 2.627995 -v 0.082750 0.018500 0.024824 -vn -0.097141 -2.835493 -3.103350 -v 0.081656 0.018500 0.023128 -vn -0.000004 -3.665188 3.034547 -v 0.082000 0.018500 0.024623 -vn -1.027794 -2.835493 -2.929822 -v 0.078359 0.018500 0.023743 -vn 3.034543 -3.665198 -0.000002 -v 0.080500 0.018500 0.042123 -vn 2.627999 -3.665181 -1.517271 -v 0.080701 0.018500 0.042873 -vn 1.517276 -3.665201 -2.627988 -v 0.081250 0.018500 0.043422 -vn -2.627996 -3.665185 -1.517273 -v 0.091299 0.018500 0.034873 -vn -3.034543 -3.665198 0.000002 -v 0.091500 0.018500 0.034123 -vn -2.627999 -3.665181 1.517271 -v 0.091299 0.018500 0.033373 -vn 1.517274 -3.665200 -2.627989 -v 0.081250 0.018500 0.027422 -vn -0.000004 -3.665188 3.034547 -v 0.082000 0.018500 0.040623 -vn 1.703897 -2.835495 -2.595564 -v 0.088037 0.018500 0.024927 -vn -2.627994 -3.665199 -1.517266 -v 0.083299 0.018500 0.026873 -vn -0.000004 -3.665188 3.034547 -v 0.090000 0.018500 0.032623 -vn -3.034550 -3.665179 0.000002 -v 0.075500 0.018500 0.034123 -vn -2.627996 -3.665198 1.517265 -v 0.075299 0.018500 0.033373 -vn 2.627998 -3.665184 -1.517272 -v 0.080701 0.018500 0.026873 -vn -1.517272 -3.665192 2.627994 -v 0.074750 0.018500 0.032824 -vn -0.000000 -3.665190 3.034546 -v 0.074000 0.018500 0.032623 -vn 1.517274 -3.665200 2.627989 -v 0.081250 0.018500 0.024824 -vn 2.627998 -3.665183 1.517272 -v 0.080701 0.018500 0.025373 -vn -1.862895 -2.835494 -2.483916 -v 0.075400 0.018500 0.025323 -vn 3.034543 -3.665198 0.000000 -v 0.080500 0.018500 0.026123 -vn -2.524809 -2.835491 -1.807084 -v 0.073055 0.018500 0.027721 -vn 2.923805 2.564369 -0.722102 -v 0.092225 0.024500 0.030066 -vn 2.406844 2.835492 -1.961457 -v 0.090527 0.024500 0.027174 -vn 1.703897 2.835495 -2.595564 -v 0.088037 0.024500 0.024927 -vn 0.842544 2.835493 -2.988367 -v 0.084985 0.024500 0.023535 -vn -0.097141 2.835493 -3.103350 -v 0.081656 0.024500 0.023128 -vn -1.027794 2.835494 -2.929822 -v 0.078359 0.024500 0.023743 -vn -1.862895 2.835494 -2.483916 -v 0.075400 0.024500 0.025323 -vn -2.524809 2.835491 -1.807084 -v 0.073055 0.024500 0.027721 -vn -2.951997 2.835495 -0.962253 -v 0.071542 0.024500 0.030714 -vn -3.104744 2.835494 -0.027968 -v 0.071000 0.024500 0.034024 -vn -2.968852 2.835493 0.908921 -v 0.071482 0.024500 0.037343 -vn -2.402188 2.701068 1.904721 -v 0.072941 0.024500 0.040363 -vn -0.000000 3.665190 -3.034546 -v 0.074000 0.024500 0.035623 -vn 1.517268 3.665189 -2.627998 -v 0.073250 0.024500 0.035422 -vn 2.627989 3.665192 -1.517281 -v 0.072701 0.024500 0.034873 -vn 3.034543 3.665198 0.000002 -v 0.072500 0.024500 0.034123 -vn 2.627992 3.665187 1.517279 -v 0.072701 0.024500 0.033373 -vn 1.517272 3.665192 2.627994 -v 0.073250 0.024500 0.032824 -vn 0.000000 3.665190 3.034546 -v 0.074000 0.024500 0.032623 -vn -1.517272 3.665191 2.627994 -v 0.074750 0.024500 0.032824 -vn -2.627996 3.665197 1.517265 -v 0.075299 0.024500 0.033373 -vn -3.034550 3.665179 0.000002 -v 0.075500 0.024500 0.034123 -vn -2.627993 3.665201 -1.517267 -v 0.075299 0.024500 0.034873 -vn -1.517268 3.665189 -2.627998 -v 0.074750 0.024500 0.035422 -vn -0.000004 3.665188 -3.034547 -v 0.082000 0.024500 0.027623 -vn 1.517274 3.665201 -2.627989 -v 0.081250 0.024500 0.027422 -vn 2.627998 3.665184 -1.517272 -v 0.080701 0.024500 0.026873 -vn 3.034543 3.665198 -0.000000 -v 0.080500 0.024500 0.026123 -vn 2.627998 3.665183 1.517272 -v 0.080701 0.024500 0.025373 -vn 1.517274 3.665200 2.627989 -v 0.081250 0.024500 0.024824 -vn -0.000004 3.665188 3.034547 -v 0.082000 0.024500 0.024623 -vn -1.517270 3.665190 2.627996 -v 0.082750 0.024500 0.024824 -vn -2.627994 3.665200 1.517266 -v 0.083299 0.024500 0.025373 -vn -3.034551 3.665179 0.000000 -v 0.083500 0.024500 0.026123 -vn -2.627995 3.665199 -1.517266 -v 0.083299 0.024500 0.026873 -vn -1.517270 3.665190 -2.627995 -v 0.082750 0.024500 0.027422 -vn -0.000004 3.665188 -3.034547 -v 0.090000 0.024500 0.035623 -vn 1.517272 3.665198 -2.627991 -v 0.089250 0.024500 0.035422 -vn 2.627996 3.665185 -1.517273 -v 0.088701 0.024500 0.034873 -vn 3.034543 3.665198 0.000002 -v 0.088500 0.024500 0.034123 -vn 2.627999 3.665180 1.517271 -v 0.088701 0.024500 0.033373 -vn 1.517276 3.665201 2.627988 -v 0.089250 0.024500 0.032824 -vn -0.000004 3.665188 3.034547 -v 0.090000 0.024500 0.032623 -vn -1.517279 3.665199 2.627986 -v 0.090750 0.024500 0.032824 -vn -2.628000 3.665181 1.517272 -v 0.091299 0.024500 0.033373 -vn -3.034543 3.665198 0.000002 -v 0.091500 0.024500 0.034123 -vn -2.627996 3.665185 -1.517273 -v 0.091299 0.024500 0.034873 -vn -1.517276 3.665195 -2.627990 -v 0.090750 0.024500 0.035422 -vn -0.000004 3.665188 -3.034547 -v 0.082000 0.024500 0.043623 -vn 1.517276 3.665201 -2.627987 -v 0.081250 0.024500 0.043422 -vn 2.628000 3.665180 -1.517272 -v 0.080701 0.024500 0.042873 -vn 3.034543 3.665198 -0.000002 -v 0.080500 0.024500 0.042123 -vn 2.627996 3.665185 1.517273 -v 0.080701 0.024500 0.041373 -vn 1.517272 3.665198 2.627991 -v 0.081250 0.024500 0.040824 -vn -0.000004 3.665188 3.034547 -v 0.082000 0.024500 0.040623 -vn -1.517268 3.665185 2.627998 -v 0.082750 0.024500 0.040824 -vn -2.627992 3.665201 1.517267 -v 0.083299 0.024500 0.041373 -vn -3.034550 3.665179 -0.000002 -v 0.083500 0.024500 0.042123 -vn -2.627996 3.665197 -1.517265 -v 0.083299 0.024500 0.042873 -vn -1.517272 3.665191 -2.627994 -v 0.082750 0.024500 0.043422 -vn 3.045341 3.326360 -0.715199 -v 0.092735 0.024500 0.041184 -vn 2.931146 2.617994 0.785398 -v 0.101000 0.024500 0.067783 -vn -1.570796 1.570796 1.570797 -v 0.055906 0.024500 0.134440 -vn 1.570796 1.570796 1.570796 -v 0.077906 0.024500 0.134440 -vn -2.931146 2.617994 -0.785398 -v 0.055906 0.024500 0.107783 -vn 2.931146 3.665191 0.785398 -v 0.077906 0.024500 0.107783 -vn -2.770830 3.209461 -1.476735 -v 0.079000 0.024500 0.067783 -vn -2.939434 3.365992 -1.051478 -v 0.080957 0.024500 0.063790 -vn -3.099712 3.365992 -0.371031 -v 0.081976 0.024500 0.059462 -vn 3.127215 3.297231 -0.124033 -v 0.091965 0.024500 0.035649 -vn -3.104558 3.365993 0.328023 -v 0.082007 0.024500 0.055016 -vn -2.953729 3.365991 1.010627 -v 0.081048 0.024500 0.050674 -vn -2.669732 3.342050 1.623105 -v 0.079146 0.024500 0.046655 -vn -2.203250 3.327277 2.215976 -v 0.076398 0.024500 0.043159 -vn 3.128154 3.010694 -0.205029 -v 0.101000 0.024500 0.057220 -vn 2.766234 2.579901 -1.208035 -v 0.100796 0.024500 0.055667 -vn 2.581446 3.326362 -1.766846 -v 0.097227 0.024500 0.051367 -vn 2.862110 3.326361 -1.262512 -v 0.094510 0.024500 0.046483 -vn -2.931146 2.617994 -0.785398 -v 0.055906 -0.022000 0.107783 -vn -2.931146 -2.617994 -0.785399 -v 0.055906 -0.026000 0.107783 -vn -4.712389 1.570796 -1.570795 -v 0.055906 -0.022000 0.129940 -vn -1.570796 -1.570796 1.570797 -v 0.055906 -0.026000 0.134440 -vn 1.570796 -1.570796 1.570794 -v 0.077906 -0.026000 0.134440 -vn -2.356195 -1.360349 4.188790 -v 0.071156 0.001704 0.134440 -vn -2.356195 1.360349 4.188790 -v 0.071156 -0.003204 0.134440 -vn -0.000001 2.720699 4.188790 -v 0.066906 -0.005657 0.134440 -vn 2.356194 1.360350 4.188790 -v 0.062656 -0.003204 0.134440 -vn 2.356194 -1.360350 4.188791 -v 0.062656 0.001704 0.134440 -vn -0.000001 -2.720699 4.188790 -v 0.066906 0.004157 0.134440 -vn 4.712388 1.570796 -1.570796 -v 0.077906 -0.022000 0.129940 -vn 2.931146 3.665191 0.785398 -v 0.077906 -0.022000 0.107783 -vn 2.931146 -3.665191 0.785398 -v 0.077906 -0.026000 0.107783 -vn -2.356195 1.360349 -4.188790 -v 0.071156 -0.003204 0.129940 -vn -2.356194 -1.360349 -4.188790 -v 0.071156 0.001704 0.129940 -vn -0.000001 -2.720699 -4.188790 -v 0.066906 0.004157 0.129940 -vn 2.356194 -1.360350 -4.188791 -v 0.062656 0.001704 0.129940 -vn 2.356194 1.360350 -4.188791 -v 0.062656 -0.003204 0.129940 -vn -0.000001 2.720699 -4.188790 -v 0.066906 -0.005657 0.129940 -vn -2.968852 2.835493 0.908921 -v 0.071482 -0.022000 0.037343 -vn 1.517268 3.665189 -2.627998 -v 0.073250 -0.022000 0.035422 -vn 2.627989 3.665192 -1.517281 -v 0.072701 -0.022000 0.034873 -vn -1.517270 3.665190 -2.627995 -v 0.082750 -0.022000 0.027422 -vn -0.000004 3.665188 3.034547 -v 0.082000 -0.022000 0.040623 -vn -2.627994 3.665199 -1.517266 -v 0.083299 -0.022000 0.026873 -vn -3.034551 3.665178 0.000000 -v 0.083500 -0.022000 0.026123 -vn -3.104744 2.835494 -0.027968 -v 0.071000 -0.022000 0.034024 -vn 3.034543 3.665198 0.000002 -v 0.072500 -0.022000 0.034123 -vn -2.951997 2.835495 -0.962253 -v 0.071542 -0.022000 0.030714 -vn 2.627992 3.665187 1.517279 -v 0.072701 -0.022000 0.033373 -vn 1.517272 3.665192 2.627994 -v 0.073250 -0.022000 0.032824 -vn -2.524809 2.835491 -1.807084 -v 0.073055 -0.022000 0.027721 -vn 0.000000 3.665190 3.034546 -v 0.074000 -0.022000 0.032623 -vn 3.034543 3.665198 -0.000002 -v 0.080500 -0.022000 0.042123 -vn -2.627995 3.665194 1.517265 -v 0.075299 -0.022000 0.033373 -vn 2.628000 3.665180 -1.517272 -v 0.080701 -0.022000 0.042873 -vn -3.034550 3.665180 0.000002 -v 0.075500 -0.022000 0.034123 -vn -2.627993 3.665201 -1.517267 -v 0.075299 -0.022000 0.034873 -vn 2.627998 3.665184 -1.517272 -v 0.080701 -0.022000 0.026873 -vn 3.034543 3.665198 -0.000000 -v 0.080500 -0.022000 0.026123 -vn -1.862895 2.835494 -2.483916 -v 0.075400 -0.022000 0.025323 -vn -1.027794 2.835494 -2.929822 -v 0.078359 -0.022000 0.023743 -vn -2.654787 3.365994 1.642555 -v 0.079146 -0.022000 0.046655 -vn -2.953729 3.365988 1.010627 -v 0.081048 -0.022000 0.050674 -vn -1.517268 3.665186 -2.627998 -v 0.074750 -0.022000 0.035422 -vn -1.517280 3.665199 2.627986 -v 0.090750 -0.022000 0.032824 -vn -2.628000 3.665181 1.517272 -v 0.091299 -0.022000 0.033373 -vn 2.923805 2.564369 -0.722102 -v 0.092225 -0.022000 0.030066 -vn -3.034543 3.665198 0.000002 -v 0.091500 -0.022000 0.034123 -vn -1.517276 3.665196 -2.627990 -v 0.090750 -0.022000 0.035422 -vn -2.627993 3.665201 1.517267 -v 0.083299 -0.022000 0.041373 -vn -3.034551 3.665180 -0.000002 -v 0.083500 -0.022000 0.042123 -vn 2.627998 3.665183 1.517272 -v 0.080701 -0.022000 0.025373 -vn 1.517274 3.665200 2.627989 -v 0.081250 -0.022000 0.024824 -vn -0.097141 2.835493 -3.103350 -v 0.081656 -0.022000 0.023128 -vn -0.000004 3.665188 3.034547 -v 0.082000 -0.022000 0.024623 -vn 0.842544 2.835494 -2.988367 -v 0.084985 -0.022000 0.023535 -vn -1.517270 3.665190 2.627996 -v 0.082750 -0.022000 0.024824 -vn 1.517274 3.665199 -2.627989 -v 0.081250 -0.022000 0.027422 -vn -1.517272 3.665190 2.627994 -v 0.074750 -0.022000 0.032824 -vn -2.627996 3.665185 -1.517273 -v 0.091299 -0.022000 0.034873 -vn 3.045341 3.326360 -0.715199 -v 0.092735 -0.022000 0.041184 -vn 3.124901 3.326362 -0.143537 -v 0.091965 -0.022000 0.035649 -vn 1.517276 3.665201 -2.627987 -v 0.081250 -0.022000 0.043422 -vn -0.000004 3.665188 -3.034547 -v 0.082000 -0.022000 0.043623 -vn -0.000000 3.665190 -3.034546 -v 0.074000 -0.022000 0.035623 -vn -2.402188 2.701068 1.904721 -v 0.072941 -0.022000 0.040363 -vn -2.222723 3.365991 2.192119 -v 0.076398 -0.022000 0.043159 -vn 2.627996 3.665185 1.517273 -v 0.080701 -0.022000 0.041373 -vn 1.517272 3.665198 2.627991 -v 0.081250 -0.022000 0.040824 -vn -0.000004 3.665188 -3.034547 -v 0.082000 -0.022000 0.027623 -vn 2.862110 3.326361 -1.262511 -v 0.094510 -0.022000 0.046483 -vn -2.627996 3.665197 -1.517265 -v 0.083299 -0.022000 0.042873 -vn 2.581446 3.326362 -1.766846 -v 0.097227 -0.022000 0.051367 -vn -1.517272 3.665191 -2.627994 -v 0.082750 -0.022000 0.043422 -vn -0.000004 3.665188 3.034547 -v 0.090000 -0.022000 0.032623 -vn 2.406844 2.835492 -1.961457 -v 0.090527 -0.022000 0.027174 -vn 1.517276 3.665200 2.627988 -v 0.089250 -0.022000 0.032824 -vn 1.703897 2.835495 -2.595564 -v 0.088037 -0.022000 0.024927 -vn -3.104558 3.365993 0.328023 -v 0.082007 -0.022000 0.055016 -vn -3.099712 3.365992 -0.371030 -v 0.081976 -0.022000 0.059462 -vn 2.931146 2.617994 0.785398 -v 0.101000 -0.022000 0.067783 -vn -0.000004 3.665188 -3.034547 -v 0.090000 -0.022000 0.035623 -vn 1.517272 3.665198 -2.627991 -v 0.089250 -0.022000 0.035422 -vn -1.517268 3.665189 2.627998 -v 0.082750 -0.022000 0.040824 -vn 2.627996 3.665185 -1.517273 -v 0.088701 -0.022000 0.034873 -vn 3.034543 3.665198 0.000002 -v 0.088500 -0.022000 0.034123 -vn 2.628000 3.665181 1.517271 -v 0.088701 -0.022000 0.033373 -vn -2.770830 3.209461 -1.476735 -v 0.079000 -0.022000 0.067783 -vn -2.939434 3.365992 -1.051478 -v 0.080957 -0.022000 0.063790 -vn -2.627994 3.665199 1.517266 -v 0.083299 -0.022000 0.025373 -vn 3.128154 3.010694 -0.205029 -v 0.101000 -0.022000 0.057220 -vn 2.766234 2.579901 -1.208035 -v 0.100796 -0.022000 0.055667 -vn 2.627996 -3.665186 1.517273 -v 0.080701 -0.026000 0.041373 -vn 0.000000 -3.665190 -3.034546 -v 0.074000 -0.026000 0.035623 -vn -1.517268 -3.665189 -2.627998 -v 0.074750 -0.026000 0.035422 -vn -2.402188 -2.701068 1.904721 -v 0.072941 -0.026000 0.040363 -vn 1.517268 -3.665189 -2.627998 -v 0.073250 -0.026000 0.035422 -vn -2.968852 -2.835493 0.908921 -v 0.071482 -0.026000 0.037343 -vn 2.627989 -3.665192 -1.517281 -v 0.072701 -0.026000 0.034873 -vn -0.000004 -3.665187 -3.034547 -v 0.082000 -0.026000 0.027623 -vn -1.517268 -3.665189 2.627998 -v 0.082750 -0.026000 0.040824 -vn 1.517274 -3.665200 -2.627989 -v 0.081250 -0.026000 0.027422 -vn -0.000004 -3.665187 3.034548 -v 0.082000 -0.026000 0.040623 -vn 1.517272 -3.665198 2.627991 -v 0.081250 -0.026000 0.040824 -vn -2.627993 -3.665202 -1.517267 -v 0.075299 -0.026000 0.034873 -vn -3.034551 -3.665180 0.000002 -v 0.075500 -0.026000 0.034123 -vn -2.627996 -3.665197 1.517265 -v 0.075299 -0.026000 0.033373 -vn 2.581446 -3.326361 -1.766846 -v 0.097227 -0.026000 0.051367 -vn 2.766233 -2.579901 -1.208035 -v 0.100796 -0.026000 0.055667 -vn 3.128155 -3.010694 -0.205029 -v 0.101000 -0.026000 0.057220 -vn -2.627994 -3.665199 1.517266 -v 0.083299 -0.026000 0.025373 -vn -1.517270 -3.665190 2.627995 -v 0.082750 -0.026000 0.024824 -vn 0.842544 -2.835494 -2.988367 -v 0.084985 -0.026000 0.023535 -vn 2.931146 -2.617994 0.785398 -v 0.101000 -0.026000 0.067783 -vn -1.517276 -3.665195 -2.627990 -v 0.090750 -0.026000 0.035422 -vn -2.627996 -3.665185 -1.517273 -v 0.091299 -0.026000 0.034873 -vn 3.124901 -3.326363 -0.143537 -v 0.091965 -0.026000 0.035649 -vn -3.034543 -3.665198 0.000002 -v 0.091500 -0.026000 0.034123 -vn 2.923806 -2.564369 -0.722102 -v 0.092225 -0.026000 0.030066 -vn -1.517270 -3.665187 -2.627996 -v 0.082750 -0.026000 0.027422 -vn -3.034550 -3.665179 -0.000002 -v 0.083500 -0.026000 0.042123 -vn -2.627993 -3.665201 1.517267 -v 0.083299 -0.026000 0.041373 -vn 3.045341 -3.326361 -0.715199 -v 0.092735 -0.026000 0.041184 -vn 2.862110 -3.326362 -1.262512 -v 0.094510 -0.026000 0.046483 -vn -3.104558 -3.365991 0.328023 -v 0.082007 -0.026000 0.055016 -vn -0.097141 -2.835493 -3.103350 -v 0.081656 -0.026000 0.023128 -vn -0.000004 -3.665188 3.034548 -v 0.082000 -0.026000 0.024623 -vn -1.027794 -2.835492 -2.929822 -v 0.078359 -0.026000 0.023743 -vn 1.517274 -3.665200 2.627989 -v 0.081250 -0.026000 0.024824 -vn 2.627998 -3.665183 1.517272 -v 0.080701 -0.026000 0.025373 -vn 3.034543 -3.665198 0.000000 -v 0.080500 -0.026000 0.026123 -vn -3.099712 -3.365992 -0.371031 -v 0.081976 -0.026000 0.059462 -vn 3.034543 -3.665198 -0.000002 -v 0.080500 -0.026000 0.042123 -vn -2.222723 -3.365991 2.192119 -v 0.076398 -0.026000 0.043159 -vn 2.628000 -3.665181 -1.517271 -v 0.080701 -0.026000 0.042873 -vn -2.654787 -3.365994 1.642555 -v 0.079146 -0.026000 0.046655 -vn 1.517276 -3.665201 -2.627988 -v 0.081250 -0.026000 0.043422 -vn -2.953729 -3.365990 1.010627 -v 0.081048 -0.026000 0.050674 -vn -0.000004 -3.665188 -3.034547 -v 0.082000 -0.026000 0.043623 -vn -1.517272 -3.665192 -2.627994 -v 0.082750 -0.026000 0.043422 -vn -2.627995 -3.665198 -1.517265 -v 0.083299 -0.026000 0.042873 -vn -3.034551 -3.665179 -0.000000 -v 0.083500 -0.026000 0.026123 -vn 1.703897 -2.835495 -2.595564 -v 0.088037 -0.026000 0.024927 -vn 2.406844 -2.835491 -1.961457 -v 0.090527 -0.026000 0.027174 -vn -2.939434 -3.365992 -1.051478 -v 0.080957 -0.026000 0.063790 -vn -2.770830 -3.209461 -1.476735 -v 0.079000 -0.026000 0.067783 -vn 1.517276 -3.665201 2.627987 -v 0.089250 -0.026000 0.032824 -vn 2.628000 -3.665181 1.517272 -v 0.088701 -0.026000 0.033373 -vn 2.627996 -3.665186 -1.517273 -v 0.088701 -0.026000 0.034873 -vn 3.034543 -3.665198 0.000002 -v 0.088500 -0.026000 0.034123 -vn -0.000004 -3.665188 -3.034547 -v 0.090000 -0.026000 0.035623 -vn 1.517272 -3.665198 -2.627991 -v 0.089250 -0.026000 0.035422 -vn 3.034543 -3.665198 0.000002 -v 0.072500 -0.026000 0.034123 -vn -3.104744 -2.835494 -0.027968 -v 0.071000 -0.026000 0.034024 -vn 2.627992 -3.665187 1.517279 -v 0.072701 -0.026000 0.033373 -vn -2.951997 -2.835495 -0.962254 -v 0.071542 -0.026000 0.030714 -vn 1.517272 -3.665192 2.627994 -v 0.073250 -0.026000 0.032824 -vn -2.524809 -2.835491 -1.807084 -v 0.073055 -0.026000 0.027721 -vn -0.000000 -3.665190 3.034546 -v 0.074000 -0.026000 0.032623 -vn -1.862895 -2.835493 -2.483916 -v 0.075400 -0.026000 0.025323 -vn -1.517272 -3.665192 2.627994 -v 0.074750 -0.026000 0.032824 -vn 2.627998 -3.665183 -1.517272 -v 0.080701 -0.026000 0.026873 -vn -2.628000 -3.665181 1.517271 -v 0.091299 -0.026000 0.033373 -vn -1.517280 -3.665199 2.627986 -v 0.090750 -0.026000 0.032824 -vn -0.000004 -3.665188 3.034548 -v 0.090000 -0.026000 0.032623 -vn -2.627994 -3.665199 -1.517266 -v 0.083299 -0.026000 0.026873 -# 336 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 1//1 3//3 4//4 -f 4//4 3//3 5//5 -f 4//4 5//5 6//6 -f 6//6 5//5 7//7 -f 6//6 7//7 8//8 -f 8//8 7//7 9//9 -f 8//8 9//9 10//10 -f 10//10 9//9 11//11 -f 10//10 11//11 12//12 -f 13//13 1//1 4//4 -f 8//8 14//14 6//6 -f 6//6 14//14 15//15 -f 16//16 17//17 15//15 -f 15//15 17//17 18//18 -f 15//15 18//18 19//19 -f 20//20 21//21 22//22 -f 12//12 23//23 10//10 -f 10//10 23//23 24//24 -f 10//10 24//24 8//8 -f 8//8 24//24 20//20 -f 8//8 20//20 14//14 -f 14//14 20//20 22//22 -f 19//19 25//25 15//15 -f 15//15 25//25 26//26 -f 15//15 26//26 6//6 -f 6//6 26//26 27//27 -f 6//6 27//27 4//4 -f 4//4 27//27 28//28 -f 4//4 28//28 13//13 -f 3//3 29//29 5//5 -f 5//5 29//29 30//30 -f 5//5 30//30 7//7 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 32//32 35//35 36//36 -f 3//3 2//2 37//37 -f 37//37 2//2 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 44//44 42//42 45//45 -f 44//44 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 48//48 -f 49//49 50//50 51//51 -f 51//51 50//50 34//34 -f 51//51 34//34 52//52 -f 52//52 34//34 32//32 -f 52//52 32//32 53//53 -f 53//53 32//32 36//36 -f 30//30 50//50 7//7 -f 7//7 50//50 49//49 -f 7//7 49//49 9//9 -f 9//9 49//49 54//54 -f 9//9 54//54 11//11 -f 11//11 54//54 55//55 -f 11//11 55//55 56//56 -f 57//57 58//58 59//59 -f 60//60 37//37 61//61 -f 61//61 37//37 62//62 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 60//60 70//70 37//37 -f 37//37 70//70 71//71 -f 37//37 71//71 3//3 -f 3//3 71//71 72//72 -f 3//3 72//72 29//29 -f 55//55 73//73 56//56 -f 56//56 73//73 74//74 -f 56//56 74//74 58//58 -f 58//58 74//74 75//75 -f 58//58 75//75 59//59 -f 62//62 76//76 61//61 -f 61//61 76//76 32//32 -f 61//61 32//32 77//77 -f 77//77 32//32 31//31 -f 65//65 78//78 63//63 -f 63//63 78//78 57//57 -f 63//63 57//57 79//79 -f 79//79 57//57 59//59 -f 79//79 59//59 35//35 -f 35//35 59//59 80//80 -f 35//35 80//80 36//36 -f 62//62 81//81 76//76 -f 76//76 81//81 82//82 -f 76//76 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 68//68 86//86 69//69 -f 69//69 86//86 87//87 -f 69//69 87//87 88//88 -f 88//88 87//87 89//89 -f 88//88 89//89 90//90 -f 90//90 89//89 83//83 -f 90//90 83//83 47//47 -f 47//47 83//83 85//85 -f 47//47 85//85 48//48 -f 91//91 58//58 57//57 -f 91//91 57//57 92//92 -f 92//92 57//57 78//78 -f 92//92 78//78 93//93 -f 93//93 78//78 65//65 -f 93//93 65//65 94//94 -f 94//94 65//65 67//67 -f 94//94 67//67 95//95 -f 95//95 67//67 69//69 -f 95//95 69//69 96//96 -f 96//96 69//69 88//88 -f 96//96 88//88 97//97 -f 97//97 88//88 90//90 -f 97//97 90//90 98//98 -f 98//98 90//90 47//47 -f 98//98 47//47 99//99 -f 99//99 47//47 45//45 -f 99//99 45//45 100//100 -f 100//100 45//45 42//42 -f 100//100 42//42 101//101 -f 101//101 42//42 40//40 -f 101//101 40//40 102//102 -f 103//103 39//39 104//104 -f 104//104 39//39 41//41 -f 104//104 41//41 105//105 -f 105//105 41//41 43//43 -f 105//105 43//43 106//106 -f 106//106 43//43 44//44 -f 106//106 44//44 107//107 -f 107//107 44//44 46//46 -f 107//107 46//46 108//108 -f 108//108 46//46 48//48 -f 108//108 48//48 109//109 -f 109//109 48//48 85//85 -f 109//109 85//85 110//110 -f 110//110 85//85 84//84 -f 110//110 84//84 111//111 -f 111//111 84//84 82//82 -f 111//111 82//82 112//112 -f 112//112 82//82 81//81 -f 112//112 81//81 113//113 -f 113//113 81//81 62//62 -f 113//113 62//62 114//114 -f 114//114 62//62 37//37 -f 114//114 37//37 103//103 -f 103//103 37//37 39//39 -f 115//115 32//32 116//116 -f 116//116 32//32 76//76 -f 116//116 76//76 117//117 -f 117//117 76//76 83//83 -f 117//117 83//83 118//118 -f 118//118 83//83 89//89 -f 118//118 89//89 119//119 -f 119//119 89//89 87//87 -f 119//119 87//87 120//120 -f 120//120 87//87 86//86 -f 120//120 86//86 121//121 -f 121//121 86//86 68//68 -f 121//121 68//68 122//122 -f 122//122 68//68 66//66 -f 122//122 66//66 123//123 -f 123//123 66//66 64//64 -f 123//123 64//64 124//124 -f 124//124 64//64 63//63 -f 124//124 63//63 125//125 -f 125//125 63//63 79//79 -f 125//125 79//79 126//126 -f 126//126 79//79 35//35 -f 126//126 35//35 115//115 -f 115//115 35//35 32//32 -f 127//127 54//54 128//128 -f 128//128 54//54 49//49 -f 128//128 49//49 129//129 -f 129//129 49//49 51//51 -f 129//129 51//51 130//130 -f 130//130 51//51 52//52 -f 130//130 52//52 131//131 -f 131//131 52//52 53//53 -f 131//131 53//53 132//132 -f 132//132 53//53 36//36 -f 132//132 36//36 133//133 -f 133//133 36//36 80//80 -f 133//133 80//80 134//134 -f 134//134 80//80 59//59 -f 134//134 59//59 135//135 -f 135//135 59//59 75//75 -f 135//135 75//75 136//136 -f 136//136 75//75 74//74 -f 136//136 74//74 137//137 -f 137//137 74//74 73//73 -f 137//137 73//73 138//138 -f 138//138 73//73 55//55 -f 138//138 55//55 127//127 -f 127//127 55//55 54//54 -f 139//139 29//29 140//140 -f 140//140 29//29 72//72 -f 140//140 72//72 141//141 -f 141//141 72//72 71//71 -f 141//141 71//71 142//142 -f 142//142 71//71 70//70 -f 142//142 70//70 143//143 -f 143//143 70//70 60//60 -f 143//143 60//60 144//144 -f 144//144 60//60 61//61 -f 144//144 61//61 145//145 -f 145//145 61//61 77//77 -f 145//145 77//77 146//146 -f 146//146 77//77 31//31 -f 146//146 31//31 147//147 -f 147//147 31//31 33//33 -f 147//147 33//33 148//148 -f 148//148 33//33 34//34 -f 148//148 34//34 149//149 -f 149//149 34//34 50//50 -f 149//149 50//50 150//150 -f 150//150 50//50 30//30 -f 150//150 30//30 139//139 -f 139//139 30//30 29//29 -f 145//145 129//129 130//130 -f 129//129 145//145 128//128 -f 128//128 145//145 146//146 -f 128//128 146//146 127//127 -f 151//151 136//136 137//137 -f 134//134 91//91 133//133 -f 133//133 91//91 92//92 -f 133//133 92//92 132//132 -f 132//132 92//92 93//93 -f 102//102 114//114 103//103 -f 99//99 108//108 98//98 -f 98//98 108//108 109//109 -f 98//98 109//109 97//97 -f 93//93 94//94 132//132 -f 132//132 94//94 123//123 -f 132//132 123//123 131//131 -f 131//131 123//123 124//124 -f 152//152 150//150 139//139 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 152//152 -f 157//157 152//152 158//158 -f 158//158 152//152 159//159 -f 125//125 145//145 124//124 -f 124//124 145//145 130//130 -f 124//124 130//130 131//131 -f 102//102 103//103 101//101 -f 134//134 135//135 91//91 -f 91//91 135//135 136//136 -f 91//91 136//136 160//160 -f 160//160 136//136 151//151 -f 127//127 146//146 138//138 -f 138//138 146//146 147//147 -f 138//138 147//147 148//148 -f 159//159 152//152 161//161 -f 161//161 152//152 139//139 -f 161//161 139//139 162//162 -f 162//162 139//139 163//163 -f 163//163 139//139 140//140 -f 163//163 140//140 164//164 -f 164//164 140//140 141//141 -f 164//164 141//141 102//102 -f 114//114 102//102 113//113 -f 113//113 102//102 116//116 -f 113//113 116//116 112//112 -f 125//125 126//126 145//145 -f 145//145 126//126 115//115 -f 145//145 115//115 144//144 -f 144//144 115//115 116//116 -f 144//144 116//116 143//143 -f 143//143 116//116 102//102 -f 143//143 102//102 142//142 -f 142//142 102//102 141//141 -f 117//117 118//118 97//97 -f 97//97 118//118 96//96 -f 165//165 166//166 167//167 -f 97//97 109//109 117//117 -f 117//117 109//109 110//110 -f 117//117 110//110 116//116 -f 116//116 110//110 111//111 -f 116//116 111//111 112//112 -f 118//118 119//119 96//96 -f 96//96 119//119 120//120 -f 96//96 120//120 95//95 -f 95//95 120//120 121//121 -f 95//95 121//121 94//94 -f 94//94 121//121 122//122 -f 94//94 122//122 123//123 -f 103//103 104//104 101//101 -f 101//101 104//104 105//105 -f 101//101 105//105 100//100 -f 100//100 105//105 106//106 -f 100//100 106//106 99//99 -f 99//99 106//106 107//107 -f 99//99 107//107 108//108 -f 152//152 165//165 150//150 -f 150//150 165//165 167//167 -f 150//150 167//167 149//149 -f 149//149 167//167 168//168 -f 149//149 168//168 148//148 -f 148//148 168//168 151//151 -f 148//148 151//151 138//138 -f 138//138 151//151 137//137 -f 155//155 157//157 18//18 -f 18//18 157//157 19//19 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 17//17 -f 17//17 172//172 153//153 -f 17//17 153//153 18//18 -f 18//18 153//153 155//155 -f 173//173 154//154 174//174 -f 174//174 175//175 173//173 -f 173//173 175//175 176//176 -f 173//173 176//176 172//172 -f 172//172 176//176 177//177 -f 172//172 177//177 153//153 -f 153//153 177//177 178//178 -f 153//153 178//178 154//154 -f 154//154 178//178 179//179 -f 154//154 179//179 174//174 -f 15//15 156//156 16//16 -f 16//16 156//156 154//154 -f 16//16 154//154 180//180 -f 180//180 154//154 173//173 -f 180//180 173//173 181//181 -f 181//181 173//173 182//182 -f 152//152 156//156 14//14 -f 14//14 156//156 15//15 -f 165//165 152//152 22//22 -f 22//22 152//152 14//14 -f 16//16 180//180 183//183 -f 183//183 184//184 16//16 -f 16//16 184//184 185//185 -f 16//16 185//185 17//17 -f 17//17 185//185 186//186 -f 17//17 186//186 171//171 -f 171//171 186//186 187//187 -f 171//171 187//187 180//180 -f 180//180 187//187 188//188 -f 180//180 188//188 183//183 -f 189//189 190//190 191//191 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 189//189 191//191 196//196 -f 196//196 191//191 197//197 -f 196//196 197//197 198//198 -f 197//197 199//199 198//198 -f 198//198 199//199 200//200 -f 198//198 200//200 201//201 -f 201//201 200//200 202//202 -f 203//203 204//204 205//205 -f 205//205 204//204 206//206 -f 205//205 206//206 207//207 -f 208//208 209//209 210//210 -f 210//210 209//209 211//211 -f 212//212 213//213 214//214 -f 215//215 216//216 217//217 -f 217//217 216//216 218//218 -f 219//219 220//220 221//221 -f 209//209 222//222 211//211 -f 211//211 222//222 223//223 -f 211//211 223//223 224//224 -f 224//224 223//223 225//225 -f 224//224 225//225 226//226 -f 226//226 225//225 227//227 -f 204//204 228//228 229//229 -f 229//229 228//228 208//208 -f 229//229 208//208 202//202 -f 202//202 208//208 210//210 -f 202//202 210//210 201//201 -f 230//230 231//231 218//218 -f 218//218 231//231 232//232 -f 218//218 232//232 217//217 -f 207//207 214//214 205//205 -f 205//205 214//214 213//213 -f 205//205 213//213 233//233 -f 233//233 213//213 234//234 -f 190//190 189//189 235//235 -f 235//235 189//189 236//236 -f 235//235 236//236 214//214 -f 214//214 236//236 237//237 -f 214//214 237//237 212//212 -f 203//203 238//238 204//204 -f 204//204 238//238 239//239 -f 204//204 239//239 228//228 -f 228//228 239//239 193//193 -f 228//228 193//193 240//240 -f 240//240 193//193 192//192 -f 230//230 219//219 231//231 -f 231//231 219//219 221//221 -f 231//231 221//221 241//241 -f 241//241 221//221 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 215//215 217//217 245//245 -f 245//245 217//217 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 226//226 -f 249//249 250//250 251//251 -f 219//219 252//252 220//220 -f 220//220 252//252 253//253 -f 220//220 253//253 254//254 -f 254//254 253//253 255//255 -f 254//254 255//255 193//193 -f 193//193 255//255 256//256 -f 193//193 256//256 195//195 -f 195//195 256//256 257//257 -f 171//171 180//180 169//169 -f 169//169 180//180 181//181 -f 169//169 181//181 258//258 -f 258//258 181//181 251//251 -f 258//258 251//251 259//259 -f 259//259 251//251 250//250 -f 257//257 247//247 195//195 -f 195//195 247//247 226//226 -f 195//195 226//226 260//260 -f 260//260 226//226 227//227 -f 213//213 249//249 234//234 -f 234//234 249//249 251//251 -f 234//234 251//251 244//244 -f 244//244 251//251 261//261 -f 244//244 261//261 243//243 -f 243//243 261//261 262//262 -f 263//263 264//264 265//265 -f 264//264 266//266 267//267 -f 267//267 266//266 268//268 -f 267//267 268//268 269//269 -f 270//270 271//271 272//272 -f 272//272 271//271 273//273 -f 263//263 265//265 274//274 -f 274//274 265//265 275//275 -f 274//274 275//275 273//273 -f 273//273 275//275 276//276 -f 273//273 276//276 277//277 -f 278//278 279//279 280//280 -f 281//281 282//282 283//283 -f 173//173 172//172 182//182 -f 182//182 172//172 170//170 -f 182//182 170//170 284//284 -f 285//285 286//286 287//287 -f 287//287 286//286 288//288 -f 287//287 288//288 289//289 -f 290//290 291//291 270//270 -f 270//270 291//291 292//292 -f 270//270 292//292 271//271 -f 293//293 294//294 295//295 -f 283//283 282//282 296//296 -f 296//296 282//282 297//297 -f 296//296 297//297 298//298 -f 297//297 299//299 298//298 -f 298//298 299//299 300//300 -f 298//298 300//300 301//301 -f 295//295 294//294 302//302 -f 264//264 263//263 266//266 -f 266//266 263//263 303//303 -f 266//266 303//303 304//304 -f 304//304 303//303 305//305 -f 304//304 305//305 306//306 -f 306//306 305//305 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 309//309 -f 308//308 309//309 295//295 -f 295//295 309//309 310//310 -f 295//295 310//310 311//311 -f 281//281 283//283 312//312 -f 312//312 283//283 313//313 -f 312//312 313//313 314//314 -f 294//294 278//278 302//302 -f 302//302 278//278 280//280 -f 302//302 280//280 315//315 -f 315//315 280//280 284//284 -f 315//315 284//284 316//316 -f 316//316 284//284 170//170 -f 317//317 318//318 290//290 -f 311//311 291//291 319//319 -f 319//319 291//291 290//290 -f 319//319 290//290 320//320 -f 320//320 290//290 318//318 -f 287//287 293//293 285//285 -f 285//285 293//293 295//295 -f 285//285 295//295 321//321 -f 321//321 295//295 311//311 -f 321//321 311//311 322//322 -f 322//322 311//311 319//319 -f 269//269 268//268 323//323 -f 323//323 268//268 324//324 -f 323//323 324//324 325//325 -f 325//325 324//324 326//326 -f 325//325 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 331//331 -f 331//331 330//330 298//298 -f 331//331 298//298 277//277 -f 277//277 298//298 301//301 -f 277//277 301//301 273//273 -f 273//273 301//301 332//332 -f 273//273 332//332 272//272 -f 288//288 333//333 289//289 -f 289//289 333//333 334//334 -f 289//289 334//334 314//314 -f 314//314 334//334 335//335 -f 314//314 335//335 312//312 -f 312//312 335//335 317//317 -f 312//312 317//317 336//336 -f 336//336 317//317 290//290 -f 266//266 236//236 189//189 -f 266//266 189//189 268//268 -f 268//268 189//189 196//196 -f 268//268 196//196 324//324 -f 324//324 196//196 198//198 -f 324//324 198//198 326//326 -f 326//326 198//198 201//201 -f 326//326 201//201 328//328 -f 328//328 201//201 210//210 -f 328//328 210//210 330//330 -f 330//330 210//210 211//211 -f 330//330 211//211 298//298 -f 298//298 211//211 224//224 -f 298//298 224//224 296//296 -f 296//296 224//224 226//226 -f 296//296 226//226 283//283 -f 283//283 226//226 248//248 -f 283//283 248//248 313//313 -f 313//313 248//248 246//246 -f 313//313 246//246 314//314 -f 314//314 246//246 217//217 -f 314//314 217//217 289//289 -f 261//261 251//251 280//280 -f 280//280 251//251 284//284 -f 182//182 284//284 181//181 -f 181//181 284//284 251//251 -f 316//316 170//170 258//258 -f 258//258 170//170 169//169 -f 297//297 225//225 299//299 -f 299//299 225//225 223//223 -f 299//299 223//223 300//300 -f 300//300 223//223 222//222 -f 300//300 222//222 301//301 -f 301//301 222//222 209//209 -f 301//301 209//209 332//332 -f 332//332 209//209 208//208 -f 332//332 208//208 272//272 -f 272//272 208//208 228//228 -f 272//272 228//228 270//270 -f 270//270 228//228 240//240 -f 270//270 240//240 290//290 -f 290//290 240//240 192//192 -f 290//290 192//192 336//336 -f 336//336 192//192 194//194 -f 336//336 194//194 312//312 -f 312//312 194//194 195//195 -f 312//312 195//195 281//281 -f 281//281 195//195 260//260 -f 281//281 260//260 282//282 -f 282//282 260//260 227//227 -f 282//282 227//227 297//297 -f 297//297 227//227 225//225 -f 335//335 245//245 317//317 -f 317//317 245//245 247//247 -f 317//317 247//247 318//318 -f 318//318 247//247 257//257 -f 318//318 257//257 320//320 -f 320//320 257//257 256//256 -f 320//320 256//256 319//319 -f 319//319 256//256 255//255 -f 319//319 255//255 322//322 -f 322//322 255//255 253//253 -f 322//322 253//253 321//321 -f 321//321 253//253 252//252 -f 321//321 252//252 285//285 -f 285//285 252//252 219//219 -f 285//285 219//219 286//286 -f 286//286 219//219 230//230 -f 286//286 230//230 288//288 -f 288//288 230//230 218//218 -f 288//288 218//218 333//333 -f 333//333 218//218 216//216 -f 333//333 216//216 334//334 -f 334//334 216//216 215//215 -f 334//334 215//215 335//335 -f 335//335 215//215 245//245 -f 273//273 193//193 274//274 -f 274//274 193//193 239//239 -f 274//274 239//239 263//263 -f 263//263 239//239 238//238 -f 263//263 238//238 303//303 -f 303//303 238//238 203//203 -f 303//303 203//203 305//305 -f 305//305 203//203 205//205 -f 305//305 205//205 307//307 -f 307//307 205//205 233//233 -f 307//307 233//233 309//309 -f 309//309 233//233 234//234 -f 309//309 234//234 310//310 -f 310//310 234//234 244//244 -f 310//310 244//244 311//311 -f 311//311 244//244 242//242 -f 311//311 242//242 291//291 -f 291//291 242//242 221//221 -f 291//291 221//221 292//292 -f 292//292 221//221 220//220 -f 292//292 220//220 271//271 -f 271//271 220//220 254//254 -f 271//271 254//254 273//273 -f 273//273 254//254 193//193 -f 329//329 202//202 327//327 -f 327//327 202//202 200//200 -f 327//327 200//200 325//325 -f 325//325 200//200 199//199 -f 325//325 199//199 323//323 -f 323//323 199//199 197//197 -f 323//323 197//197 269//269 -f 269//269 197//197 191//191 -f 269//269 191//191 267//267 -f 267//267 191//191 190//190 -f 267//267 190//190 264//264 -f 264//264 190//190 235//235 -f 264//264 235//235 265//265 -f 265//265 235//235 214//214 -f 265//265 214//214 275//275 -f 275//275 214//214 207//207 -f 275//275 207//207 276//276 -f 276//276 207//207 206//206 -f 276//276 206//206 277//277 -f 277//277 206//206 204//204 -f 277//277 204//204 331//331 -f 331//331 204//204 229//229 -f 331//331 229//229 329//329 -f 329//329 229//229 202//202 -f 262//262 261//261 279//279 -f 279//279 261//261 280//280 -f 22//22 21//21 165//165 -f 165//165 21//21 166//166 -f 12//12 11//11 56//56 -f 166//166 21//21 167//167 -f 167//167 21//21 20//20 -f 167//167 20//20 168//168 -f 168//168 20//20 24//24 -f 168//168 24//24 151//151 -f 151//151 24//24 23//23 -f 151//151 23//23 160//160 -f 23//23 12//12 160//160 -f 160//160 12//12 56//56 -f 160//160 56//56 91//91 -f 91//91 56//56 58//58 -f 262//262 279//279 243//243 -f 243//243 279//279 278//278 -f 243//243 278//278 241//241 -f 241//241 278//278 294//294 -f 241//241 294//294 231//231 -f 231//231 294//294 293//293 -f 231//231 293//293 232//232 -f 232//232 293//293 287//287 -f 232//232 287//287 217//217 -f 217//217 287//287 289//289 -f 19//19 157//157 25//25 -f 25//25 157//157 158//158 -f 25//25 158//158 26//26 -f 26//26 158//158 159//159 -f 26//26 159//159 27//27 -f 27//27 159//159 161//161 -f 27//27 161//161 28//28 -f 28//28 161//161 162//162 -f 28//28 162//162 13//13 -f 13//13 162//162 163//163 -f 13//13 163//163 1//1 -f 1//1 163//163 164//164 -f 1//1 164//164 2//2 -f 102//102 40//40 164//164 -f 164//164 40//40 38//38 -f 164//164 38//38 2//2 -f 236//236 266//266 237//237 -f 237//237 266//266 304//304 -f 237//237 304//304 212//212 -f 212//212 304//304 306//306 -f 212//212 306//306 213//213 -f 213//213 306//306 308//308 -f 213//213 308//308 249//249 -f 249//249 308//308 295//295 -f 249//249 295//295 250//250 -f 250//250 295//295 302//302 -f 250//250 302//302 259//259 -f 259//259 302//302 315//315 -f 259//259 315//315 258//258 -f 258//258 315//315 316//316 -f 179//179 185//185 174//174 -f 174//174 185//185 184//184 -f 174//174 184//184 175//175 -f 175//175 184//184 183//183 -f 175//175 183//183 176//176 -f 176//176 183//183 188//188 -f 176//176 188//188 177//177 -f 177//177 188//188 187//187 -f 177//177 187//187 178//178 -f 178//178 187//187 186//186 -f 178//178 186//186 179//179 -f 179//179 186//186 185//185 -# 704 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/kapa.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/kapa.obj deleted file mode 100644 index cde8aa72b..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/kapa.obj +++ /dev/null @@ -1,1608 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object kapa.obj -# -# Vertices: 393 -# Faces: 806 -# -#### -vn 0.577349 0.577350 -0.577351 -v 0.024500 0.050000 0.491800 -vn -0.577350 0.577350 -0.577351 -v -0.075500 0.050000 0.491800 -vn 0.577350 0.577350 0.577350 -v 0.024500 0.050000 0.496800 -vn -0.577350 0.577350 0.577350 -v -0.075500 0.050000 0.496800 -vn 0.577350 -0.577349 -0.577352 -v 0.024500 -0.050000 0.491800 -vn 0.577350 -0.577350 0.577350 -v 0.024500 -0.050000 0.496800 -vn -0.577350 -0.577351 -0.577350 -v -0.075500 -0.050000 0.491800 -vn -0.577350 -0.577350 0.577350 -v -0.075500 -0.050000 0.496800 -vn 0.000000 -0.685736 -0.727851 -v -0.025500 0.040500 0.491800 -vn -0.572297 0.377770 -0.727851 -v 0.008300 -0.022311 0.491800 -vn -0.630553 0.269511 -0.727851 -v 0.011741 -0.015918 0.491800 -vn 0.122443 -0.674716 -0.727851 -v -0.032732 0.039849 0.491800 -vn 0.240950 -0.642010 -0.727851 -v -0.039731 0.037918 0.491800 -vn 0.351713 -0.588669 -0.727851 -v -0.046272 0.034767 0.491800 -vn 0.603856 -0.324949 -0.727851 -v -0.061164 0.019192 0.491800 -vn 0.652173 -0.211904 -0.727851 -v -0.064018 0.012515 0.491800 -vn 0.451172 -0.516408 -0.727851 -v -0.052147 0.030499 0.491800 -vn 0.536130 -0.427549 -0.727851 -v -0.057164 0.025251 0.491800 -vn 0.630553 0.269511 -0.727851 -v -0.062741 -0.015918 0.491800 -vn 0.572297 0.377770 -0.727851 -v -0.059300 -0.022311 0.491800 -vn 0.495646 0.473886 -0.727851 -v -0.054773 -0.027988 0.491800 -vn 0.403065 0.554772 -0.727851 -v -0.049305 -0.032765 0.491800 -vn 0.297529 0.617826 -0.727851 -v -0.043072 -0.036489 0.491800 -vn -0.182431 0.661024 -0.727851 -v -0.014726 -0.039040 0.491800 -vn -0.297529 0.617826 -0.727851 -v -0.007928 -0.036489 0.491800 -vn 0.679530 -0.092049 -0.727851 -v -0.065633 0.005436 0.491800 -vn 0.685045 0.030765 -0.727851 -v -0.065959 -0.001817 0.491800 -vn 0.668543 0.152591 -0.727851 -v -0.064985 -0.009012 0.491800 -vn -0.403065 0.554772 -0.727851 -v -0.001695 -0.032765 0.491800 -vn -0.495646 0.473886 -0.727851 -v 0.003773 -0.027988 0.491800 -vn -0.652173 -0.211904 -0.727851 -v 0.013018 0.012515 0.491800 -vn -0.603856 -0.324949 -0.727851 -v 0.010164 0.019192 0.491800 -vn -0.668543 0.152591 -0.727851 -v 0.013985 -0.009012 0.491800 -vn -0.685045 0.030765 -0.727851 -v 0.014959 -0.001817 0.491800 -vn -0.679530 -0.092049 -0.727851 -v 0.014633 0.005436 0.491800 -vn 0.182431 0.661024 -0.727850 -v -0.036275 -0.039040 0.491800 -vn 0.061469 0.682975 -0.727851 -v -0.029130 -0.040337 0.491800 -vn -0.061469 0.682975 -0.727851 -v -0.021870 -0.040337 0.491800 -vn -0.536130 -0.427549 -0.727851 -v 0.006164 0.025251 0.491800 -vn -0.451172 -0.516408 -0.727851 -v 0.001146 0.030499 0.491800 -vn -0.351713 -0.588669 -0.727851 -v -0.004728 0.034767 0.491800 -vn -0.240950 -0.642010 -0.727851 -v -0.011269 0.037918 0.491800 -vn -0.122443 -0.674716 -0.727851 -v -0.018268 0.039849 0.491800 -vn 0.000000 -0.726207 -0.687477 -v -0.025500 0.040500 0.494300 -vn -0.129669 -0.714536 -0.687477 -v -0.018268 0.039849 0.494300 -vn -0.255171 -0.679900 -0.687476 -v -0.011269 0.037918 0.494300 -vn -0.372471 -0.623411 -0.687477 -v -0.004728 0.034767 0.494300 -vn -0.477799 -0.546886 -0.687477 -v 0.001146 0.030499 0.494300 -vn -0.567771 -0.452782 -0.687477 -v 0.006164 0.025251 0.494300 -vn -0.639494 -0.344127 -0.687477 -v 0.010164 0.019192 0.494300 -vn -0.690663 -0.224410 -0.687477 -v 0.013018 0.012515 0.494300 -vn -0.719634 -0.097481 -0.687477 -v 0.014633 0.005436 0.494300 -vn -0.725475 0.032581 -0.687477 -v 0.014959 -0.001817 0.494300 -vn -0.707999 0.161596 -0.687477 -v 0.013985 -0.009012 0.494300 -vn -0.667767 0.285417 -0.687477 -v 0.011741 -0.015918 0.494300 -vn -0.606073 0.400065 -0.687477 -v 0.008300 -0.022311 0.494300 -vn -0.524898 0.501854 -0.687477 -v 0.003773 -0.027988 0.494300 -vn -0.426854 0.587513 -0.687477 -v -0.001695 -0.032765 0.494300 -vn -0.315089 0.654290 -0.687477 -v -0.007928 -0.036489 0.494300 -vn -0.193198 0.700036 -0.687477 -v -0.014726 -0.039040 0.494300 -vn -0.065097 0.723283 -0.687477 -v -0.021870 -0.040337 0.494300 -vn 0.065097 0.723283 -0.687477 -v -0.029130 -0.040337 0.494300 -vn 0.193197 0.700036 -0.687477 -v -0.036275 -0.039040 0.494300 -vn 0.315089 0.654290 -0.687476 -v -0.043072 -0.036489 0.494300 -vn 0.426854 0.587513 -0.687477 -v -0.049305 -0.032765 0.494300 -vn 0.524898 0.501854 -0.687477 -v -0.054773 -0.027988 0.494300 -vn 0.606072 0.400065 -0.687477 -v -0.059300 -0.022311 0.494300 -vn 0.667767 0.285417 -0.687477 -v -0.062741 -0.015918 0.494300 -vn 0.707999 0.161596 -0.687477 -v -0.064985 -0.009012 0.494300 -vn 0.725475 0.032581 -0.687477 -v -0.065959 -0.001817 0.494300 -vn 0.719634 -0.097481 -0.687477 -v -0.065633 0.005436 0.494300 -vn 0.690663 -0.224410 -0.687477 -v -0.064018 0.012515 0.494300 -vn 0.639494 -0.344127 -0.687477 -v -0.061164 0.019192 0.494300 -vn 0.567771 -0.452782 -0.687477 -v -0.057164 0.025251 0.494300 -vn 0.477799 -0.546886 -0.687476 -v -0.052147 0.030499 0.494300 -vn 0.372471 -0.623411 -0.687477 -v -0.046272 0.034767 0.494300 -vn 0.255171 -0.679900 -0.687477 -v -0.039731 0.037918 0.494300 -vn 0.129669 -0.714536 -0.687477 -v -0.032732 0.039849 0.494300 -vn -0.683588 0.032563 -0.729141 -v -0.060960 0.001689 0.494300 -vn -0.665072 0.161345 -0.729141 -v -0.059999 0.008369 0.494300 -vn -0.622519 0.284295 -0.729141 -v -0.057792 0.014747 0.494300 -vn -0.557466 0.396970 -0.729141 -v -0.054417 0.020592 0.494300 -vn -0.472265 0.495297 -0.729141 -v -0.049998 0.025693 0.494300 -vn -0.369995 0.575723 -0.729141 -v -0.044693 0.029864 0.494300 -vn -0.254352 0.635341 -0.729141 -v -0.038694 0.032957 0.494300 -vn -0.129517 0.671996 -0.729141 -v -0.032218 0.034858 0.494300 -vn -0.000000 0.684363 -0.729141 -v -0.025500 0.035500 0.494300 -vn 0.129517 0.671996 -0.729141 -v -0.018782 0.034858 0.494300 -vn 0.254352 0.635341 -0.729141 -v -0.012306 0.032957 0.494300 -vn 0.369995 0.575723 -0.729141 -v -0.006307 0.029864 0.494300 -vn 0.472265 0.495297 -0.729141 -v -0.001002 0.025693 0.494300 -vn 0.557466 0.396970 -0.729141 -v 0.003417 0.020592 0.494300 -vn 0.622519 0.284295 -0.729141 -v 0.006792 0.014747 0.494300 -vn 0.665072 0.161345 -0.729141 -v 0.008999 0.008369 0.494300 -vn 0.683588 0.032563 -0.729141 -v 0.009960 0.001689 0.494300 -vn 0.677397 -0.097395 -0.729141 -v 0.009639 -0.005052 0.494300 -vn 0.646724 -0.223833 -0.729141 -v 0.008048 -0.011611 0.494300 -vn 0.592676 -0.342181 -0.729141 -v 0.005244 -0.017750 0.494300 -vn 0.517207 -0.448163 -0.729141 -v 0.001329 -0.023248 0.494300 -vn 0.423045 -0.537946 -0.729141 -v -0.003555 -0.027905 0.494300 -vn 0.313593 -0.608286 -0.729141 -v -0.009233 -0.031554 0.494300 -vn 0.192807 -0.656642 -0.729141 -v -0.015499 -0.034062 0.494300 -vn 0.065053 -0.681264 -0.729141 -v -0.022126 -0.035339 0.494300 -vn -0.065053 -0.681264 -0.729141 -v -0.028875 -0.035339 0.494300 -vn -0.192807 -0.656642 -0.729141 -v -0.035502 -0.034062 0.494300 -vn -0.313593 -0.608286 -0.729141 -v -0.041767 -0.031554 0.494300 -vn -0.423045 -0.537946 -0.729141 -v -0.047445 -0.027905 0.494300 -vn -0.517207 -0.448163 -0.729141 -v -0.052329 -0.023248 0.494300 -vn -0.592676 -0.342181 -0.729141 -v -0.056244 -0.017750 0.494300 -vn -0.646724 -0.223833 -0.729141 -v -0.059048 -0.011611 0.494300 -vn -0.677397 -0.097395 -0.729141 -v -0.060639 -0.005052 0.494300 -vn 0.000000 0.727295 -0.686325 -v -0.025500 0.035500 0.491800 -vn 0.137642 0.714152 -0.686325 -v -0.018782 0.034858 0.491800 -vn 0.270308 0.675198 -0.686325 -v -0.012306 0.032957 0.491800 -vn 0.393206 0.611840 -0.686325 -v -0.006307 0.029864 0.491800 -vn 0.501891 0.526368 -0.686325 -v -0.001002 0.025693 0.491800 -vn 0.592437 0.421873 -0.686325 -v 0.003417 0.020592 0.491800 -vn 0.661571 0.302129 -0.686325 -v 0.006792 0.014747 0.491800 -vn 0.706794 0.171466 -0.686325 -v 0.008999 0.008369 0.491800 -vn 0.726472 0.034606 -0.686325 -v 0.009960 0.001689 0.491800 -vn 0.719893 -0.103505 -0.686325 -v 0.009639 -0.005052 0.491800 -vn 0.687295 -0.237875 -0.686325 -v 0.008048 -0.011611 0.491800 -vn 0.629856 -0.363648 -0.686325 -v 0.005244 -0.017750 0.491800 -vn 0.549653 -0.476277 -0.686325 -v 0.001329 -0.023248 0.491800 -vn 0.449584 -0.571693 -0.686325 -v -0.003555 -0.027905 0.491800 -vn 0.333266 -0.646446 -0.686325 -v -0.009233 -0.031554 0.491800 -vn 0.204903 -0.697835 -0.686325 -v -0.015499 -0.034062 0.491800 -vn 0.069134 -0.724002 -0.686325 -v -0.022126 -0.035339 0.491800 -vn -0.069134 -0.724002 -0.686325 -v -0.028875 -0.035339 0.491800 -vn -0.204903 -0.697835 -0.686325 -v -0.035502 -0.034062 0.491800 -vn -0.333266 -0.646446 -0.686325 -v -0.041767 -0.031554 0.491800 -vn -0.449584 -0.571693 -0.686325 -v -0.047445 -0.027905 0.491800 -vn -0.549653 -0.476277 -0.686324 -v -0.052329 -0.023248 0.491800 -vn -0.629856 -0.363648 -0.686325 -v -0.056244 -0.017750 0.491800 -vn -0.687295 -0.237875 -0.686325 -v -0.059048 -0.011611 0.491800 -vn -0.719893 -0.103505 -0.686324 -v -0.060639 -0.005052 0.491800 -vn -0.726472 0.034606 -0.686325 -v -0.060960 0.001689 0.491800 -vn -0.706794 0.171466 -0.686325 -v -0.059999 0.008369 0.491800 -vn -0.661571 0.302129 -0.686325 -v -0.057792 0.014747 0.491800 -vn -0.592437 0.421873 -0.686325 -v -0.054417 0.020592 0.491800 -vn -0.501891 0.526368 -0.686325 -v -0.049998 0.025693 0.491800 -vn -0.393206 0.611840 -0.686325 -v -0.044693 0.029864 0.491800 -vn -0.270308 0.675198 -0.686325 -v -0.038694 0.032957 0.491800 -vn -0.137642 0.714152 -0.686325 -v -0.032218 0.034858 0.491800 -vn 0.000000 0.000000 -1.000000 -v -0.025500 -0.000000 0.491800 -vn -0.490543 -0.538605 0.685035 -v -0.052434 -0.029573 0.494300 -vn -0.489218 -0.538986 -0.685682 -v -0.052434 -0.029573 0.359300 -vn -0.372084 -0.626329 -0.685029 -v -0.045930 -0.034389 0.359300 -vn 0.698461 -0.198401 -0.687597 -v 0.012912 -0.011158 0.359300 -vn 0.660747 -0.426222 0.617858 -v 0.011325 -0.015618 0.369300 -vn 0.639905 -0.342555 -0.687879 -v 0.009880 -0.018662 0.359300 -vn 0.634568 -0.341247 0.693451 -v 0.009880 -0.018662 0.369300 -vn 0.561521 -0.462687 -0.686014 -v 0.005399 -0.025402 0.359300 -vn 0.742335 -0.288495 0.604739 -v 0.008893 -0.020423 0.369300 -vn 0.723397 -0.295068 -0.624205 -v 0.008893 -0.020423 0.374300 -vn -0.662351 -0.300045 -0.686487 -v -0.061914 -0.016555 0.359300 -vn -0.600084 -0.522391 0.605811 -v -0.060384 -0.019574 0.369300 -vn -0.599317 -0.511518 -0.615766 -v -0.060384 -0.019574 0.374300 -vn -0.372084 -0.626329 0.685029 -v -0.045930 -0.034389 0.494300 -vn -0.238388 -0.688408 -0.685029 -v -0.038589 -0.037798 0.359300 -vn -0.238389 -0.688408 0.685029 -v -0.038589 -0.037798 0.494300 -vn -0.094933 -0.722304 -0.685029 -v -0.030712 -0.039659 0.359300 -vn -0.094933 -0.722304 0.685029 -v -0.030712 -0.039659 0.494300 -vn 0.052409 -0.726628 -0.685029 -v -0.022622 -0.039896 0.359300 -vn 0.052409 -0.726628 0.685029 -v -0.022622 -0.039896 0.494300 -vn 0.197605 -0.701204 -0.685029 -v -0.014650 -0.038500 0.359300 -vn 0.197605 -0.701204 0.685029 -v -0.014650 -0.038500 0.494300 -vn 0.315986 -0.650760 -0.690409 -v -0.007122 -0.035528 0.359300 -vn 0.315986 -0.650760 0.690409 -v -0.007122 -0.035528 0.494300 -vn 0.392791 -0.601217 0.695883 -v -0.003622 -0.033487 0.494300 -vn 0.392791 -0.601218 -0.695883 -v -0.003622 -0.033487 0.359300 -vn 0.469013 -0.550783 0.690409 -v -0.000347 -0.031102 0.494300 -vn 0.659384 -0.426605 -0.619048 -v 0.011325 -0.015618 0.374300 -vn 0.699586 -0.203211 0.685043 -v 0.012912 -0.011158 0.494300 -vn 0.635803 -0.327511 -0.698922 -v 0.009880 -0.018662 0.374300 -vn 0.644317 -0.339520 0.685260 -v 0.009880 -0.018662 0.494300 -vn 0.562411 -0.462731 0.685255 -v 0.005399 -0.025402 0.494300 -vn 0.469013 -0.550783 -0.690409 -v -0.000347 -0.031102 0.359300 -vn -0.128720 0.714718 -0.687466 -v -0.032399 0.039401 0.359300 -vn 0.074059 0.788642 0.610376 -v -0.030387 0.039700 0.369300 -vn 0.024639 0.726122 -0.687124 -v -0.024327 0.039983 0.359300 -vn -0.172005 0.773375 0.610169 -v -0.025009 0.039997 0.369300 -vn -0.171034 0.772835 -0.611124 -v -0.025009 0.039997 0.374300 -vn 0.072876 0.787074 -0.612539 -v -0.030387 0.039700 0.374300 -vn -0.125756 0.717483 0.685131 -v -0.032399 0.039401 0.494300 -vn 0.021491 0.728109 0.685125 -v -0.024327 0.039983 0.494300 -vn 0.167521 0.708993 0.685029 -v -0.016302 0.038928 0.494300 -vn 0.167520 0.708993 -0.685029 -v -0.016302 0.038928 0.359300 -vn 0.306811 0.660759 0.685029 -v -0.008654 0.036280 0.494300 -vn 0.306811 0.660759 -0.685029 -v -0.008654 0.036280 0.359300 -vn 0.433540 0.585472 0.685029 -v -0.001696 0.032146 0.494300 -vn 0.433540 0.585472 -0.685029 -v -0.001696 0.032146 0.359300 -vn 0.542520 0.486217 0.685029 -v 0.004288 0.026696 0.494300 -vn 0.542520 0.486217 -0.685029 -v 0.004288 0.026696 0.359300 -vn 0.629289 0.367055 0.685029 -v 0.009052 0.020154 0.494300 -vn 0.629289 0.367055 -0.685029 -v 0.009052 0.020154 0.359300 -vn 0.690295 0.232867 0.685029 -v 0.012401 0.012786 0.494300 -vn 0.690295 0.232867 -0.685029 -v 0.012401 0.012786 0.359300 -vn 0.723041 0.089144 0.685029 -v 0.014199 0.004895 0.494300 -vn 0.723041 0.089145 -0.685029 -v 0.014199 0.004895 0.359300 -vn 0.726185 -0.058227 0.685029 -v 0.014372 -0.003197 0.494300 -vn 0.726185 -0.058227 -0.685030 -v 0.014372 -0.003197 0.359300 -vn -0.594550 -0.402305 0.696176 -v -0.057836 -0.023546 0.369300 -vn -0.588946 -0.427076 -0.686111 -v -0.057836 -0.023546 0.359300 -vn -0.675044 -0.387653 0.627727 -v -0.057438 -0.024083 0.369300 -vn -0.676522 -0.386590 -0.626791 -v -0.057438 -0.024083 0.374300 -vn -0.588142 -0.407604 -0.698533 -v -0.057836 -0.023546 0.374300 -vn -0.588475 -0.428984 0.685325 -v -0.057836 -0.023546 0.494300 -vn -0.663099 -0.301041 0.685327 -v -0.061914 -0.016555 0.494300 -vn -0.710313 -0.161836 0.685029 -v -0.064501 -0.008886 0.494300 -vn -0.710312 -0.161836 -0.685029 -v -0.064501 -0.008886 0.359300 -vn -0.728350 -0.015538 0.685029 -v -0.065491 -0.000853 0.494300 -vn -0.728350 -0.015538 -0.685029 -v -0.065491 -0.000853 0.359300 -vn -0.716568 0.131395 0.685029 -v -0.064844 0.007214 0.494300 -vn -0.716568 0.131395 -0.685029 -v -0.064844 0.007214 0.359300 -vn -0.675450 0.272950 0.685029 -v -0.062586 0.014987 0.494300 -vn -0.675450 0.272950 -0.685029 -v -0.062586 0.014987 0.359300 -vn -0.606679 0.403330 0.685029 -v -0.058810 0.022145 0.494300 -vn -0.606679 0.403330 -0.685029 -v -0.058810 0.022145 0.359300 -vn -0.513071 0.517197 0.685029 -v -0.053671 0.028397 0.494300 -vn -0.513071 0.517197 -0.685029 -v -0.053671 0.028397 0.359300 -vn -0.398457 0.609891 0.685029 -v -0.047378 0.033487 0.494300 -vn -0.398457 0.609890 -0.685030 -v -0.047378 0.033487 0.359300 -vn -0.267531 0.677615 0.685029 -v -0.040189 0.037205 0.494300 -vn -0.267531 0.677615 -0.685029 -v -0.040189 0.037205 0.359300 -vn 0.279537 -0.747990 0.601972 -v -0.029872 0.035733 0.369300 -vn 0.111350 -0.674782 -0.729568 -v -0.031229 0.035541 0.359300 -vn -0.195563 -0.774199 0.601973 -v -0.025085 0.035998 0.369300 -vn -0.036449 -0.682936 -0.729568 -v -0.023715 0.035956 0.359300 -vn -0.198377 -0.775855 -0.598912 -v -0.025085 0.035998 0.374300 -vn -0.034037 -0.681267 0.731243 -v -0.023715 0.035956 0.494300 -vn 0.108769 -0.673389 0.731243 -v -0.031229 0.035541 0.494300 -vn 0.282515 -0.749326 -0.598912 -v -0.029872 0.035733 0.374300 -vn -0.174686 -0.659186 0.731409 -v -0.016278 0.034799 0.494300 -vn -0.174686 -0.659185 -0.731409 -v -0.016278 0.034799 0.359300 -vn -0.307921 -0.608462 0.731409 -v -0.009245 0.032121 0.494300 -vn -0.307921 -0.608462 -0.731409 -v -0.009245 0.032121 0.359300 -vn -0.427699 -0.531145 0.731409 -v -0.002922 0.028039 0.494300 -vn -0.427699 -0.531145 -0.731409 -v -0.002922 0.028039 0.359300 -vn -0.528784 -0.430615 0.731409 -v 0.002415 0.022732 0.494300 -vn -0.528784 -0.430615 -0.731409 -v 0.002415 0.022732 0.359300 -vn -0.606758 -0.311264 0.731409 -v 0.006531 0.016432 0.494300 -vn -0.606758 -0.311264 -0.731409 -v 0.006531 0.016432 0.359300 -vn -0.658215 -0.178310 0.731409 -v 0.009248 0.009413 0.494300 -vn -0.658215 -0.178310 -0.731409 -v 0.009248 0.009413 0.359300 -vn -0.680904 -0.037563 0.731409 -v 0.010445 0.001983 0.494300 -vn -0.680904 -0.037563 -0.731409 -v 0.010445 0.001983 0.359300 -vn -0.673835 0.104825 0.731409 -v 0.010072 -0.005534 0.494300 -vn -0.673835 0.104825 -0.731409 -v 0.010072 -0.005534 0.359300 -vn -0.637557 0.242498 0.731243 -v 0.008144 -0.012809 0.494300 -vn -0.640054 0.240959 -0.729569 -v 0.008144 -0.012809 0.359300 -vn -0.572722 0.559727 -0.598912 -v 0.005467 -0.018358 0.374300 -vn -0.572695 0.556462 0.601973 -v 0.005467 -0.018358 0.369300 -vn -0.573215 0.373034 -0.729569 -v 0.004746 -0.019524 0.359300 -vn -0.787546 0.131908 0.601972 -v 0.007632 -0.014080 0.369300 -vn -0.790193 0.129997 -0.598912 -v 0.007632 -0.014080 0.374300 -vn -0.572976 0.370111 0.731243 -v 0.004746 -0.019524 0.494300 -vn -0.483529 0.480876 0.731409 -v 0.000026 -0.025386 0.494300 -vn -0.483529 0.480876 -0.731408 -v 0.000026 -0.025386 0.359300 -vn -0.372983 0.570899 0.731409 -v -0.005810 -0.030138 0.494300 -vn -0.372983 0.570899 -0.731409 -v -0.005810 -0.030138 0.359300 -vn -0.246136 0.635971 0.731409 -v -0.012506 -0.033573 0.494300 -vn -0.246136 0.635970 -0.731409 -v -0.012506 -0.033573 0.359300 -vn -0.108531 0.673247 0.731409 -v -0.019771 -0.035541 0.494300 -vn -0.108531 0.673247 -0.731409 -v -0.019771 -0.035541 0.359300 -vn 0.033816 0.681100 0.731409 -v -0.027285 -0.035956 0.494300 -vn 0.033816 0.681100 -0.731409 -v -0.027285 -0.035956 0.359300 -vn 0.174686 0.659186 0.731409 -v -0.034722 -0.034799 0.494300 -vn 0.174686 0.659186 -0.731409 -v -0.034722 -0.034799 0.359300 -vn 0.307921 0.608462 0.731409 -v -0.041755 -0.032121 0.494300 -vn 0.307921 0.608462 -0.731409 -v -0.041755 -0.032121 0.359300 -vn 0.427699 0.531145 0.731409 -v -0.048079 -0.028039 0.494300 -vn 0.427699 0.531145 -0.731409 -v -0.048078 -0.028039 0.359300 -vn 0.528787 0.430891 0.731243 -v -0.053415 -0.022732 0.494300 -vn 0.528703 0.433823 -0.729569 -v -0.053415 -0.022732 0.359300 -vn 0.771098 0.216129 -0.598912 -v -0.056882 -0.017639 0.374300 -vn 0.768257 0.217737 0.601973 -v -0.056882 -0.017639 0.369300 -vn 0.609665 0.309902 -0.729568 -v -0.057531 -0.016432 0.359300 -vn 0.508010 0.616081 0.601972 -v -0.054260 -0.021653 0.369300 -vn 0.507678 0.619328 -0.598912 -v -0.054260 -0.021653 0.374300 -vn 0.607013 0.311156 0.731243 -v -0.057531 -0.016432 0.494300 -vn 0.658215 0.178310 0.731409 -v -0.060248 -0.009413 0.494300 -vn 0.658215 0.178310 -0.731409 -v -0.060248 -0.009413 0.359300 -vn 0.680904 0.037563 0.731409 -v -0.061445 -0.001983 0.494300 -vn 0.680904 0.037563 -0.731409 -v -0.061445 -0.001983 0.359300 -vn 0.673835 -0.104826 0.731409 -v -0.061072 0.005534 0.494300 -vn 0.673835 -0.104826 -0.731409 -v -0.061072 0.005534 0.359300 -vn 0.637315 -0.242633 0.731409 -v -0.059144 0.012809 0.494300 -vn 0.637315 -0.242633 -0.731409 -v -0.059144 0.012809 0.359300 -vn 0.572942 -0.369836 0.731409 -v -0.055746 0.019524 0.494300 -vn 0.572942 -0.369836 -0.731409 -v -0.055746 0.019524 0.359300 -vn 0.483528 -0.480876 0.731409 -v -0.051026 0.025386 0.494300 -vn 0.483528 -0.480876 -0.731409 -v -0.051026 0.025386 0.359300 -vn 0.372983 -0.570899 0.731409 -v -0.045190 0.030138 0.494300 -vn 0.372983 -0.570899 -0.731409 -v -0.045190 0.030138 0.359300 -vn 0.246136 -0.635970 0.731409 -v -0.038494 0.033573 0.494300 -vn 0.246136 -0.635970 -0.731409 -v -0.038494 0.033573 0.359300 -vn 0.348801 -0.533886 -0.770262 -v 0.007530 -0.015819 0.359300 -vn 0.569015 -0.287958 -0.770261 -v 0.006978 -0.016436 0.359300 -vn 0.348801 -0.533886 -0.770262 -v -0.058188 -0.019444 0.359300 -vn 0.569014 -0.287958 -0.770262 -v -0.058740 -0.020061 0.359300 -vn -0.569014 0.287958 -0.770262 -v 0.009833 -0.017881 0.359300 -vn -0.636760 -0.035128 -0.770261 -v 0.010003 -0.017070 0.359300 -vn 0.287958 0.569014 -0.770262 -v -0.028316 0.036515 0.359300 -vn -0.035128 0.636760 -0.770261 -v -0.027505 0.036345 0.359300 -vn 0.636760 0.035128 -0.770261 -v -0.058910 -0.020872 0.359300 -vn 0.533885 0.348802 -0.770262 -v -0.058652 -0.021659 0.359300 -vn 0.287958 0.569015 -0.770261 -v -0.058035 -0.022211 0.359300 -vn 0.636760 0.035128 -0.770262 -v 0.006808 -0.017247 0.359300 -vn 0.533886 0.348802 -0.770262 -v 0.007066 -0.018034 0.359300 -vn 0.287959 0.569014 -0.770262 -v 0.007683 -0.018586 0.359300 -vn -0.533887 -0.348802 -0.770261 -v -0.055973 -0.019909 0.359300 -vn -0.636759 -0.035128 -0.770263 -v -0.055715 -0.020696 0.359300 -vn -0.287958 -0.569013 -0.770262 -v -0.056590 -0.019356 0.359300 -vn 0.035128 -0.636760 -0.770261 -v -0.057401 -0.019186 0.359300 -vn 0.569014 -0.287958 -0.770262 -v -0.029021 0.038665 0.359300 -vn 0.636760 0.035128 -0.770262 -v -0.029191 0.037854 0.359300 -vn 0.533887 0.348801 -0.770262 -v -0.028933 0.037067 0.359300 -vn -0.636760 -0.035128 -0.770262 -v -0.025996 0.038030 0.359300 -vn -0.533885 -0.348802 -0.770262 -v -0.026254 0.038817 0.359300 -vn -0.287959 -0.569015 -0.770261 -v -0.026871 0.039370 0.359300 -vn 0.035126 -0.636759 -0.770262 -v -0.027681 0.039540 0.359300 -vn 0.348801 -0.533886 -0.770262 -v -0.028468 0.039282 0.359300 -vn -0.035127 0.636759 -0.770262 -v -0.057224 -0.022381 0.359300 -vn -0.348802 0.533885 -0.770262 -v -0.056437 -0.022123 0.359300 -vn -0.569015 0.287959 -0.770261 -v -0.055885 -0.021506 0.359300 -vn -0.533886 -0.348801 -0.770262 -v 0.009745 -0.016283 0.359300 -vn -0.287958 -0.569015 -0.770262 -v 0.009128 -0.015731 0.359300 -vn 0.035127 -0.636760 -0.770261 -v 0.008317 -0.015561 0.359300 -vn -0.569015 0.287957 -0.770262 -v -0.026166 0.037220 0.359300 -vn -0.348801 0.533885 -0.770262 -v -0.026718 0.036603 0.359300 -vn -0.035127 0.636760 -0.770262 -v 0.008494 -0.018756 0.359300 -vn -0.348801 0.533886 -0.770262 -v 0.009281 -0.018498 0.359300 -vn 0.348801 -0.533886 0.770262 -v -0.028468 0.039282 0.369300 -vn 0.035127 -0.636760 0.770262 -v -0.027681 0.039540 0.369300 -vn -0.287959 -0.569015 0.770261 -v -0.026871 0.039370 0.369300 -vn -0.533885 -0.348802 0.770262 -v -0.026254 0.038817 0.369300 -vn -0.636760 -0.035128 0.770262 -v -0.025996 0.038030 0.369300 -vn -0.569015 0.287957 0.770262 -v -0.026166 0.037220 0.369300 -vn -0.348801 0.533886 0.770262 -v -0.026718 0.036603 0.369300 -vn -0.035128 0.636760 0.770261 -v -0.027505 0.036345 0.369300 -vn 0.287958 0.569014 0.770262 -v -0.028316 0.036515 0.369300 -vn 0.533886 0.348801 0.770262 -v -0.028933 0.037067 0.369300 -vn 0.636760 0.035128 0.770262 -v -0.029191 0.037854 0.369300 -vn 0.569014 -0.287958 0.770262 -v -0.029021 0.038665 0.369300 -vn 0.348801 -0.533886 0.770262 -v -0.058188 -0.019444 0.369300 -vn 0.035128 -0.636760 0.770261 -v -0.057401 -0.019186 0.369300 -vn -0.287958 -0.569013 0.770262 -v -0.056590 -0.019356 0.369300 -vn -0.533887 -0.348802 0.770261 -v -0.055973 -0.019909 0.369300 -vn -0.636759 -0.035128 0.770263 -v -0.055715 -0.020696 0.369300 -vn -0.569015 0.287959 0.770261 -v -0.055885 -0.021506 0.369300 -vn -0.348802 0.533885 0.770262 -v -0.056437 -0.022123 0.369300 -vn -0.035127 0.636759 0.770262 -v -0.057224 -0.022381 0.369300 -vn 0.287958 0.569015 0.770261 -v -0.058035 -0.022211 0.369300 -vn 0.533885 0.348802 0.770262 -v -0.058652 -0.021659 0.369300 -vn 0.636760 0.035128 0.770261 -v -0.058910 -0.020872 0.369300 -vn 0.569014 -0.287958 0.770262 -v -0.058740 -0.020061 0.369300 -vn 0.348801 -0.533886 0.770262 -v 0.007530 -0.015819 0.369300 -vn 0.035127 -0.636760 0.770261 -v 0.008317 -0.015561 0.369300 -vn -0.287958 -0.569015 0.770262 -v 0.009128 -0.015731 0.369300 -vn -0.533886 -0.348801 0.770262 -v 0.009745 -0.016283 0.369300 -vn -0.636760 -0.035128 0.770261 -v 0.010003 -0.017070 0.369300 -vn -0.569014 0.287957 0.770262 -v 0.009833 -0.017881 0.369300 -vn -0.348801 0.533886 0.770262 -v 0.009281 -0.018498 0.369300 -vn -0.035127 0.636760 0.770262 -v 0.008494 -0.018756 0.369300 -vn 0.287958 0.569014 0.770262 -v 0.007683 -0.018586 0.369300 -vn 0.533886 0.348802 0.770262 -v 0.007066 -0.018034 0.369300 -vn 0.636760 0.035128 0.770262 -v 0.006808 -0.017247 0.369300 -vn 0.569015 -0.287958 0.770262 -v 0.006978 -0.016436 0.369300 -vn -0.043648 0.791203 -0.609994 -v 0.008596 -0.020617 0.374300 -vn -0.043648 0.791203 0.609994 -v 0.008596 -0.020617 0.369300 -vn -0.663377 -0.433402 0.609994 -v 0.011306 -0.015264 0.369300 -vn -0.663377 -0.433402 -0.609994 -v 0.011306 -0.015264 0.374300 -vn 0.663378 0.433402 0.609994 -v 0.005506 -0.019053 0.369300 -vn 0.043648 -0.791203 0.609994 -v 0.008215 -0.013700 0.369300 -vn 0.043648 -0.791203 -0.609994 -v 0.008215 -0.013700 0.374300 -vn 0.663378 0.433402 -0.609994 -v 0.005506 -0.019053 0.374300 -vn 0.707026 -0.357801 -0.609994 -v -0.060403 -0.019220 0.374300 -vn 0.707026 -0.357800 0.609994 -v -0.060403 -0.019220 0.369300 -vn -0.043647 0.791203 0.609994 -v -0.057122 -0.024243 0.369300 -vn -0.043648 0.791203 -0.609994 -v -0.057122 -0.024243 0.374300 -vn -0.707026 0.357802 0.609994 -v -0.054222 -0.022348 0.369300 -vn 0.043647 -0.791203 0.609994 -v -0.057503 -0.017325 0.369300 -vn 0.043647 -0.791203 -0.609994 -v -0.057503 -0.017325 0.374300 -vn -0.707025 0.357801 -0.609994 -v -0.054222 -0.022348 0.374300 -vn -0.663379 -0.433398 -0.609995 -v -0.024693 0.039837 0.374300 -vn -0.663379 -0.433398 0.609995 -v -0.024693 0.039837 0.369300 -vn 0.707025 -0.357803 0.609994 -v -0.030684 0.039506 0.369300 -vn 0.707025 -0.357803 -0.609994 -v -0.030684 0.039506 0.374300 -vn -0.707026 0.357801 0.609994 -v -0.024502 0.036378 0.369300 -vn 0.663378 0.433401 0.609994 -v -0.030493 0.036048 0.369300 -vn -0.707026 0.357801 -0.609994 -v -0.024502 0.036378 0.374300 -vn 0.663378 0.433401 -0.609994 -v -0.030493 0.036048 0.374300 -# 393 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 1//1 6//6 -f 6//6 1//1 3//3 -f 7//7 5//5 8//8 -f 8//8 5//5 6//6 -f 2//2 7//7 4//4 -f 4//4 7//7 8//8 -f 2//2 1//1 9//9 -f 10//10 11//11 5//5 -f 9//9 12//12 2//2 -f 2//2 12//12 13//13 -f 2//2 13//13 14//14 -f 2//2 15//15 16//16 -f 14//14 17//17 2//2 -f 2//2 17//17 18//18 -f 2//2 18//18 15//15 -f 7//7 19//19 20//20 -f 20//20 21//21 7//7 -f 7//7 21//21 22//22 -f 7//7 22//22 23//23 -f 24//24 25//25 5//5 -f 16//16 26//26 2//2 -f 2//2 26//26 27//27 -f 2//2 27//27 7//7 -f 7//7 27//27 28//28 -f 7//7 28//28 19//19 -f 25//25 29//29 5//5 -f 5//5 29//29 30//30 -f 5//5 30//30 10//10 -f 31//31 32//32 1//1 -f 11//11 33//33 5//5 -f 5//5 33//33 34//34 -f 5//5 34//34 1//1 -f 1//1 34//34 35//35 -f 1//1 35//35 31//31 -f 23//23 36//36 7//7 -f 7//7 36//36 37//37 -f 7//7 37//37 5//5 -f 5//5 37//37 38//38 -f 5//5 38//38 24//24 -f 32//32 39//39 1//1 -f 1//1 39//39 40//40 -f 1//1 40//40 41//41 -f 41//41 42//42 1//1 -f 1//1 42//42 43//43 -f 1//1 43//43 9//9 -f 8//8 6//6 4//4 -f 4//4 6//6 3//3 -f 44//44 9//9 45//45 -f 45//45 9//9 43//43 -f 45//45 43//43 46//46 -f 46//46 43//43 42//42 -f 46//46 42//42 47//47 -f 47//47 42//42 41//41 -f 47//47 41//41 48//48 -f 48//48 41//41 40//40 -f 48//48 40//40 49//49 -f 49//49 40//40 39//39 -f 49//49 39//39 50//50 -f 50//50 39//39 32//32 -f 50//50 32//32 51//51 -f 51//51 32//32 31//31 -f 51//51 31//31 52//52 -f 52//52 31//31 35//35 -f 52//52 35//35 53//53 -f 53//53 35//35 34//34 -f 53//53 34//34 54//54 -f 54//54 34//34 33//33 -f 54//54 33//33 55//55 -f 55//55 33//33 11//11 -f 55//55 11//11 56//56 -f 56//56 11//11 10//10 -f 56//56 10//10 57//57 -f 57//57 10//10 30//30 -f 57//57 30//30 58//58 -f 58//58 30//30 29//29 -f 58//58 29//29 59//59 -f 59//59 29//29 25//25 -f 59//59 25//25 60//60 -f 60//60 25//25 24//24 -f 60//60 24//24 61//61 -f 61//61 24//24 38//38 -f 61//61 38//38 62//62 -f 62//62 38//38 37//37 -f 62//62 37//37 63//63 -f 63//63 37//37 36//36 -f 63//63 36//36 64//64 -f 64//64 36//36 23//23 -f 64//64 23//23 65//65 -f 65//65 23//23 22//22 -f 65//65 22//22 66//66 -f 66//66 22//22 21//21 -f 66//66 21//21 67//67 -f 67//67 21//21 20//20 -f 67//67 20//20 68//68 -f 68//68 20//20 19//19 -f 68//68 19//19 69//69 -f 69//69 19//19 28//28 -f 69//69 28//28 70//70 -f 70//70 28//28 27//27 -f 70//70 27//27 71//71 -f 71//71 27//27 26//26 -f 71//71 26//26 72//72 -f 72//72 26//26 16//16 -f 72//72 16//16 73//73 -f 73//73 16//16 15//15 -f 73//73 15//15 74//74 -f 74//74 15//15 18//18 -f 74//74 18//18 75//75 -f 75//75 18//18 17//17 -f 75//75 17//17 76//76 -f 76//76 17//17 14//14 -f 76//76 14//14 77//77 -f 77//77 14//14 13//13 -f 77//77 13//13 78//78 -f 78//78 13//13 12//12 -f 78//78 12//12 44//44 -f 44//44 12//12 9//9 -f 79//79 71//71 80//80 -f 80//80 71//71 72//72 -f 80//80 72//72 81//81 -f 81//81 72//72 73//73 -f 81//81 73//73 82//82 -f 82//82 73//73 74//74 -f 82//82 74//74 83//83 -f 83//83 74//74 75//75 -f 83//83 75//75 84//84 -f 84//84 75//75 76//76 -f 84//84 76//76 85//85 -f 85//85 76//76 77//77 -f 85//85 77//77 86//86 -f 86//86 77//77 78//78 -f 86//86 78//78 87//87 -f 87//87 78//78 44//44 -f 87//87 44//44 88//88 -f 88//88 44//44 45//45 -f 88//88 45//45 89//89 -f 89//89 45//45 46//46 -f 89//89 46//46 90//90 -f 90//90 46//46 47//47 -f 90//90 47//47 91//91 -f 91//91 47//47 48//48 -f 91//91 48//48 92//92 -f 92//92 48//48 49//49 -f 92//92 49//49 93//93 -f 93//93 49//49 50//50 -f 93//93 50//50 94//94 -f 94//94 50//50 51//51 -f 94//94 51//51 95//95 -f 51//51 52//52 95//95 -f 95//95 52//52 53//53 -f 95//95 53//53 96//96 -f 96//96 53//53 54//54 -f 96//96 54//54 97//97 -f 97//97 54//54 55//55 -f 97//97 55//55 98//98 -f 98//98 55//55 56//56 -f 98//98 56//56 99//99 -f 99//99 56//56 57//57 -f 99//99 57//57 100//100 -f 100//100 57//57 58//58 -f 100//100 58//58 101//101 -f 101//101 58//58 59//59 -f 101//101 59//59 102//102 -f 102//102 59//59 60//60 -f 102//102 60//60 103//103 -f 103//103 60//60 61//61 -f 103//103 61//61 104//104 -f 104//104 61//61 62//62 -f 104//104 62//62 105//105 -f 105//105 62//62 63//63 -f 105//105 63//63 106//106 -f 106//106 63//63 64//64 -f 106//106 64//64 107//107 -f 107//107 64//64 65//65 -f 107//107 65//65 108//108 -f 108//108 65//65 66//66 -f 108//108 66//66 109//109 -f 109//109 66//66 67//67 -f 109//109 67//67 110//110 -f 110//110 67//67 68//68 -f 110//110 68//68 111//111 -f 111//111 68//68 69//69 -f 111//111 69//69 79//79 -f 79//79 69//69 70//70 -f 79//79 70//70 71//71 -f 112//112 88//88 113//113 -f 113//113 88//88 89//89 -f 113//113 89//89 114//114 -f 114//114 89//89 90//90 -f 114//114 90//90 115//115 -f 115//115 90//90 91//91 -f 115//115 91//91 116//116 -f 116//116 91//91 92//92 -f 116//116 92//92 117//117 -f 117//117 92//92 93//93 -f 117//117 93//93 118//118 -f 118//118 93//93 94//94 -f 118//118 94//94 119//119 -f 119//119 94//94 95//95 -f 119//119 95//95 120//120 -f 120//120 95//95 96//96 -f 120//120 96//96 121//121 -f 121//121 96//96 97//97 -f 121//121 97//97 122//122 -f 122//122 97//97 98//98 -f 122//122 98//98 123//123 -f 123//123 98//98 99//99 -f 123//123 99//99 124//124 -f 124//124 99//99 100//100 -f 124//124 100//100 125//125 -f 125//125 100//100 101//101 -f 125//125 101//101 126//126 -f 126//126 101//101 102//102 -f 126//126 102//102 127//127 -f 127//127 102//102 103//103 -f 127//127 103//103 128//128 -f 128//128 103//103 104//104 -f 128//128 104//104 129//129 -f 129//129 104//104 105//105 -f 129//129 105//105 130//130 -f 130//130 105//105 106//106 -f 130//130 106//106 131//131 -f 131//131 106//106 107//107 -f 131//131 107//107 132//132 -f 132//132 107//107 108//108 -f 132//132 108//108 133//133 -f 133//133 108//108 109//109 -f 133//133 109//109 134//134 -f 134//134 109//109 110//110 -f 134//134 110//110 135//135 -f 135//135 110//110 111//111 -f 135//135 111//111 136//136 -f 136//136 111//111 79//79 -f 136//136 79//79 137//137 -f 137//137 79//79 80//80 -f 137//137 80//80 138//138 -f 138//138 80//80 81//81 -f 138//138 81//81 139//139 -f 139//139 81//81 82//82 -f 139//139 82//82 140//140 -f 140//140 82//82 83//83 -f 140//140 83//83 141//141 -f 141//141 83//83 84//84 -f 141//141 84//84 142//142 -f 142//142 84//84 85//85 -f 142//142 85//85 143//143 -f 143//143 85//85 86//86 -f 143//143 86//86 144//144 -f 144//144 86//86 87//87 -f 144//144 87//87 112//112 -f 112//112 87//87 88//88 -f 143//143 144//144 145//145 -f 145//145 144//144 112//112 -f 145//145 112//112 113//113 -f 140//140 141//141 145//145 -f 145//145 141//141 142//142 -f 145//145 142//142 143//143 -f 137//137 138//138 145//145 -f 145//145 138//138 139//139 -f 145//145 139//139 140//140 -f 134//134 135//135 145//145 -f 145//145 135//135 136//136 -f 145//145 136//136 137//137 -f 131//131 132//132 145//145 -f 145//145 132//132 133//133 -f 145//145 133//133 134//134 -f 128//128 129//129 145//145 -f 145//145 129//129 130//130 -f 145//145 130//130 131//131 -f 125//125 126//126 145//145 -f 145//145 126//126 127//127 -f 145//145 127//127 128//128 -f 122//122 123//123 145//145 -f 145//145 123//123 124//124 -f 145//145 124//124 125//125 -f 119//119 120//120 145//145 -f 145//145 120//120 121//121 -f 145//145 121//121 122//122 -f 116//116 117//117 145//145 -f 145//145 117//117 118//118 -f 145//145 118//118 119//119 -f 113//113 114//114 145//145 -f 145//145 114//114 115//115 -f 145//145 115//115 116//116 -f 146//146 147//147 148//148 -f 149//149 150//150 151//151 -f 151//151 150//150 152//152 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 155//155 -f 156//156 157//157 158//158 -f 146//146 148//148 159//159 -f 159//159 148//148 160//160 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 170//170 168//168 171//171 -f 170//170 171//171 172//172 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 175//175 176//176 155//155 -f 155//155 176//176 177//177 -f 155//155 177//177 153//153 -f 153//153 177//177 172//172 -f 153//153 172//172 178//178 -f 178//178 172//172 171//171 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 183//183 -f 184//184 185//185 183//183 -f 183//183 185//185 186//186 -f 183//183 186//186 181//181 -f 181//181 186//186 187//187 -f 181//181 187//187 188//188 -f 188//188 187//187 189//189 -f 188//188 189//189 190//190 -f 190//190 189//189 191//191 -f 190//190 191//191 192//192 -f 192//192 191//191 193//193 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 194//194 195//195 196//196 -f 196//196 195//195 197//197 -f 196//196 197//197 198//198 -f 198//198 197//197 199//199 -f 198//198 199//199 200//200 -f 200//200 199//199 201//201 -f 200//200 201//201 202//202 -f 202//202 201//201 174//174 -f 202//202 174//174 149//149 -f 149//149 174//174 173//173 -f 149//149 173//173 150//150 -f 157//157 156//156 203//203 -f 203//203 156//156 204//204 -f 203//203 204//204 205//205 -f 205//205 204//204 147//147 -f 205//205 147//147 206//206 -f 206//206 147//147 146//146 -f 206//206 146//146 207//207 -f 207//207 146//146 208//208 -f 207//207 208//208 158//158 -f 158//158 208//208 209//209 -f 158//158 209//209 156//156 -f 156//156 209//209 210//210 -f 156//156 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 213//213 212//212 214//214 -f 213//213 214//214 215//215 -f 215//215 214//214 216//216 -f 215//215 216//216 217//217 -f 217//217 216//216 218//218 -f 217//217 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 225//225 224//224 185//185 -f 225//225 185//185 179//179 -f 179//179 185//185 184//184 -f 179//179 184//184 180//180 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 230//230 -f 231//231 232//232 233//233 -f 233//233 230//230 231//231 -f 231//231 230//230 229//229 -f 231//231 229//229 234//234 -f 234//234 229//229 235//235 -f 234//234 235//235 236//236 -f 236//236 235//235 237//237 -f 236//236 237//237 238//238 -f 238//238 237//237 239//239 -f 238//238 239//239 240//240 -f 240//240 239//239 241//241 -f 240//240 241//241 242//242 -f 242//242 241//241 243//243 -f 242//242 243//243 244//244 -f 244//244 243//243 245//245 -f 244//244 245//245 246//246 -f 246//246 245//245 247//247 -f 246//246 247//247 248//248 -f 248//248 247//247 249//249 -f 248//248 249//249 250//250 -f 250//250 249//249 251//251 -f 252//252 253//253 254//254 -f 254//254 253//253 251//251 -f 253//253 255//255 251//251 -f 251//251 255//255 256//256 -f 251//251 256//256 250//250 -f 250//250 256//256 257//257 -f 256//256 252//252 257//257 -f 257//257 252//252 254//254 -f 257//257 254//254 258//258 -f 258//258 254//254 259//259 -f 258//258 259//259 260//260 -f 260//260 259//259 261//261 -f 260//260 261//261 262//262 -f 262//262 261//261 263//263 -f 262//262 263//263 264//264 -f 264//264 263//263 265//265 -f 264//264 265//265 266//266 -f 266//266 265//265 267//267 -f 266//266 267//267 268//268 -f 268//268 267//267 269//269 -f 268//268 269//269 270//270 -f 270//270 269//269 271//271 -f 270//270 271//271 272//272 -f 272//272 271//271 273//273 -f 272//272 273//273 274//274 -f 274//274 273//273 275//275 -f 276//276 277//277 278//278 -f 278//278 277//277 275//275 -f 277//277 279//279 275//275 -f 275//275 279//279 280//280 -f 275//275 280//280 274//274 -f 274//274 280//280 281//281 -f 280//280 276//276 281//281 -f 281//281 276//276 278//278 -f 281//281 278//278 282//282 -f 282//282 278//278 283//283 -f 282//282 283//283 284//284 -f 284//284 283//283 285//285 -f 284//284 285//285 286//286 -f 286//286 285//285 287//287 -f 286//286 287//287 288//288 -f 288//288 287//287 289//289 -f 288//288 289//289 290//290 -f 290//290 289//289 291//291 -f 290//290 291//291 292//292 -f 292//292 291//291 293//293 -f 292//292 293//293 294//294 -f 294//294 293//293 295//295 -f 294//294 295//295 296//296 -f 296//296 295//295 297//297 -f 296//296 297//297 232//232 -f 232//232 297//297 227//227 -f 232//232 227//227 233//233 -f 233//233 227//227 226//226 -f 169//169 170//170 260//260 -f 260//260 170//170 172//172 -f 260//260 172//172 258//258 -f 258//258 172//172 177//177 -f 258//258 177//177 257//257 -f 257//257 177//177 176//176 -f 257//257 176//176 250//250 -f 250//250 176//176 174//174 -f 250//250 174//174 248//248 -f 248//248 174//174 201//201 -f 248//248 201//201 246//246 -f 246//246 201//201 199//199 -f 246//246 199//199 244//244 -f 244//244 199//199 197//197 -f 244//244 197//197 242//242 -f 242//242 197//197 195//195 -f 242//242 195//195 240//240 -f 240//240 195//195 193//193 -f 240//240 193//193 238//238 -f 238//238 193//193 191//191 -f 238//238 191//191 236//236 -f 236//236 191//191 189//189 -f 236//236 189//189 234//234 -f 234//234 189//189 187//187 -f 234//234 187//187 231//231 -f 231//231 187//187 186//186 -f 231//231 186//186 232//232 -f 232//232 186//186 185//185 -f 232//232 185//185 296//296 -f 296//296 185//185 224//224 -f 296//296 224//224 294//294 -f 294//294 224//224 222//222 -f 294//294 222//222 292//292 -f 292//292 222//222 220//220 -f 292//292 220//220 290//290 -f 290//290 220//220 218//218 -f 290//290 218//218 288//288 -f 288//288 218//218 216//216 -f 288//288 216//216 286//286 -f 286//286 216//216 214//214 -f 286//286 214//214 284//284 -f 284//284 214//214 212//212 -f 284//284 212//212 282//282 -f 282//282 212//212 210//210 -f 282//282 210//210 281//281 -f 281//281 210//210 209//209 -f 281//281 209//209 274//274 -f 274//274 209//209 208//208 -f 274//274 208//208 272//272 -f 272//272 208//208 146//146 -f 272//272 146//146 270//270 -f 270//270 146//146 159//159 -f 270//270 159//159 268//268 -f 268//268 159//159 161//161 -f 268//268 161//161 266//266 -f 266//266 161//161 163//163 -f 266//266 163//163 264//264 -f 264//264 163//163 165//165 -f 264//264 165//165 262//262 -f 262//262 165//165 167//167 -f 262//262 167//167 260//260 -f 260//260 167//167 169//169 -f 251//251 298//298 299//299 -f 211//211 300//300 156//156 -f 156//156 300//300 301//301 -f 151//151 302//302 303//303 -f 223//223 304//304 305//305 -f 301//301 306//306 156//156 -f 156//156 306//306 307//307 -f 156//156 307//307 204//204 -f 204//204 307//307 308//308 -f 204//204 308//308 147//147 -f 251//251 299//299 254//254 -f 254//254 299//299 309//309 -f 254//254 309//309 259//259 -f 259//259 309//309 310//310 -f 259//259 310//310 311//311 -f 278//278 275//275 312//312 -f 312//312 275//275 313//313 -f 312//312 314//314 278//278 -f 278//278 314//314 315//315 -f 278//278 315//315 283//283 -f 179//179 316//316 225//225 -f 225//225 316//316 317//317 -f 225//225 317//317 223//223 -f 223//223 317//317 318//318 -f 223//223 318//318 304//304 -f 188//188 319//319 181//181 -f 181//181 319//319 320//320 -f 320//320 321//321 181//181 -f 181//181 321//321 322//322 -f 181//181 322//322 179//179 -f 179//179 322//322 323//323 -f 179//179 323//323 316//316 -f 315//315 300//300 283//283 -f 283//283 300//300 211//211 -f 283//283 211//211 285//285 -f 285//285 211//211 213//213 -f 285//285 213//213 287//287 -f 287//287 213//213 215//215 -f 287//287 215//215 289//289 -f 289//289 215//215 217//217 -f 289//289 217//217 291//291 -f 291//291 217//217 219//219 -f 291//291 219//219 293//293 -f 293//293 219//219 221//221 -f 293//293 221//221 295//295 -f 295//295 221//221 223//223 -f 308//308 324//324 147//147 -f 147//147 324//324 325//325 -f 147//147 325//325 326//326 -f 151//151 303//303 149//149 -f 149//149 303//303 327//327 -f 149//149 327//327 202//202 -f 202//202 327//327 328//328 -f 202//202 328//328 329//329 -f 330//330 235//235 331//331 -f 331//331 235//235 229//229 -f 331//331 229//229 305//305 -f 305//305 229//229 227//227 -f 305//305 227//227 223//223 -f 223//223 227//227 297//297 -f 223//223 297//297 295//295 -f 261//261 259//259 178//178 -f 178//178 259//259 311//311 -f 178//178 311//311 153//153 -f 153//153 311//311 332//332 -f 153//153 332//332 151//151 -f 151//151 332//332 333//333 -f 151//151 333//333 302//302 -f 178//178 171//171 261//261 -f 261//261 171//171 168//168 -f 261//261 168//168 263//263 -f 263//263 168//168 166//166 -f 263//263 166//166 265//265 -f 265//265 166//166 164//164 -f 265//265 164//164 267//267 -f 267//267 164//164 162//162 -f 267//267 162//162 269//269 -f 269//269 162//162 160//160 -f 269//269 160//160 271//271 -f 271//271 160//160 148//148 -f 271//271 148//148 273//273 -f 273//273 148//148 147//147 -f 273//273 147//147 275//275 -f 275//275 147//147 326//326 -f 275//275 326//326 313//313 -f 330//330 319//319 235//235 -f 235//235 319//319 188//188 -f 235//235 188//188 237//237 -f 237//237 188//188 190//190 -f 237//237 190//190 239//239 -f 239//239 190//190 192//192 -f 239//239 192//192 241//241 -f 241//241 192//192 194//194 -f 241//241 194//194 243//243 -f 243//243 194//194 196//196 -f 243//243 196//196 245//245 -f 245//245 196//196 198//198 -f 245//245 198//198 247//247 -f 247//247 198//198 200//200 -f 247//247 200//200 249//249 -f 249//249 200//200 202//202 -f 249//249 202//202 251//251 -f 251//251 202//202 329//329 -f 251//251 329//329 298//298 -f 334//334 323//323 335//335 -f 335//335 323//323 322//322 -f 335//335 322//322 336//336 -f 336//336 322//322 321//321 -f 336//336 321//321 337//337 -f 337//337 321//321 320//320 -f 337//337 320//320 338//338 -f 338//338 320//320 319//319 -f 338//338 319//319 339//339 -f 339//339 319//319 330//330 -f 339//339 330//330 340//340 -f 340//340 330//330 331//331 -f 340//340 331//331 341//341 -f 341//341 331//331 305//305 -f 341//341 305//305 342//342 -f 342//342 305//305 304//304 -f 342//342 304//304 343//343 -f 343//343 304//304 318//318 -f 343//343 318//318 344//344 -f 344//344 318//318 317//317 -f 344//344 317//317 345//345 -f 345//345 317//317 316//316 -f 345//345 316//316 334//334 -f 334//334 316//316 323//323 -f 346//346 300//300 347//347 -f 347//347 300//300 315//315 -f 347//347 315//315 348//348 -f 348//348 315//315 314//314 -f 348//348 314//314 349//349 -f 349//349 314//314 312//312 -f 349//349 312//312 350//350 -f 350//350 312//312 313//313 -f 350//350 313//313 351//351 -f 351//351 313//313 326//326 -f 351//351 326//326 352//352 -f 352//352 326//326 325//325 -f 352//352 325//325 353//353 -f 353//353 325//325 324//324 -f 353//353 324//324 354//354 -f 354//354 324//324 308//308 -f 354//354 308//308 355//355 -f 355//355 308//308 307//307 -f 355//355 307//307 356//356 -f 356//356 307//307 306//306 -f 356//356 306//306 357//357 -f 357//357 306//306 301//301 -f 357//357 301//301 346//346 -f 346//346 301//301 300//300 -f 358//358 298//298 359//359 -f 359//359 298//298 329//329 -f 359//359 329//329 360//360 -f 360//360 329//329 328//328 -f 360//360 328//328 361//361 -f 361//361 328//328 327//327 -f 361//361 327//327 362//362 -f 362//362 327//327 303//303 -f 362//362 303//303 363//363 -f 363//363 303//303 302//302 -f 363//363 302//302 364//364 -f 364//364 302//302 333//333 -f 364//364 333//333 365//365 -f 365//365 333//333 332//332 -f 365//365 332//332 366//366 -f 366//366 332//332 311//311 -f 366//366 311//311 367//367 -f 367//367 311//311 310//310 -f 367//367 310//310 368//368 -f 368//368 310//310 309//309 -f 368//368 309//309 369//369 -f 369//369 309//309 299//299 -f 369//369 299//299 358//358 -f 358//358 299//299 298//298 -f 370//370 155//155 371//371 -f 371//371 155//155 154//154 -f 372//372 150//150 373//373 -f 373//373 150//150 173//173 -f 150//150 372//372 361//361 -f 361//361 362//362 150//150 -f 150//150 362//362 363//363 -f 150//150 363//363 152//152 -f 152//152 363//363 364//364 -f 152//152 364//364 154//154 -f 154//154 364//364 365//365 -f 154//154 365//365 371//371 -f 371//371 365//365 374//374 -f 365//365 366//366 374//374 -f 374//374 366//366 367//367 -f 374//374 367//367 253//253 -f 367//367 368//368 253//253 -f 253//253 368//368 369//369 -f 253//253 369//369 255//255 -f 255//255 369//369 358//358 -f 255//255 358//358 375//375 -f 375//375 358//358 359//359 -f 375//375 359//359 372//372 -f 372//372 359//359 360//360 -f 372//372 360//360 361//361 -f 373//373 376//376 372//372 -f 372//372 376//376 375//375 -f 375//375 376//376 255//255 -f 255//255 376//376 256//256 -f 377//377 374//374 252//252 -f 252//252 374//374 253//253 -f 377//377 370//370 374//374 -f 374//374 370//370 371//371 -f 376//376 373//373 256//256 -f 256//256 373//373 173//173 -f 256//256 173//173 252//252 -f 370//370 377//377 155//155 -f 155//155 377//377 252//252 -f 155//155 252//252 175//175 -f 175//175 252//252 173//173 -f 378//378 158//158 379//379 -f 379//379 158//158 157//157 -f 380//380 205//205 381//381 -f 381//381 205//205 206//206 -f 382//382 352//352 380//380 -f 380//380 352//352 353//353 -f 383//383 379//379 357//357 -f 357//357 379//379 356//356 -f 356//356 379//379 157//157 -f 356//356 157//157 355//355 -f 355//355 157//157 203//203 -f 355//355 203//203 354//354 -f 357//357 346//346 383//383 -f 383//383 346//346 347//347 -f 383//383 347//347 277//277 -f 354//354 203//203 353//353 -f 353//353 203//203 205//205 -f 353//353 205//205 380//380 -f 347//347 348//348 277//277 -f 277//277 348//348 349//349 -f 277//277 349//349 279//279 -f 279//279 349//349 350//350 -f 279//279 350//350 382//382 -f 382//382 350//350 351//351 -f 382//382 351//351 352//352 -f 384//384 383//383 276//276 -f 276//276 383//383 277//277 -f 384//384 378//378 383//383 -f 383//383 378//378 379//379 -f 381//381 385//385 380//380 -f 380//380 385//385 382//382 -f 382//382 385//385 279//279 -f 279//279 385//385 280//280 -f 280//280 385//385 381//381 -f 378//378 384//384 158//158 -f 158//158 384//384 276//276 -f 158//158 276//276 207//207 -f 207//207 276//276 280//280 -f 207//207 280//280 206//206 -f 206//206 280//280 381//381 -f 386//386 183//183 387//387 -f 387//387 183//183 182//182 -f 388//388 180//180 389//389 -f 389//389 180//180 184//184 -f 180//180 388//388 345//345 -f 228//228 390//390 339//339 -f 339//339 340//340 228//228 -f 228//228 340//340 341//341 -f 228//228 341//341 226//226 -f 226//226 341//341 342//342 -f 226//226 342//342 391//391 -f 391//391 342//342 343//343 -f 391//391 343//343 388//388 -f 388//388 343//343 344//344 -f 388//388 344//344 345//345 -f 345//345 334//334 180//180 -f 180//180 334//334 335//335 -f 180//180 335//335 182//182 -f 182//182 335//335 336//336 -f 182//182 336//336 387//387 -f 387//387 336//336 337//337 -f 387//387 337//337 390//390 -f 390//390 337//337 338//338 -f 390//390 338//338 339//339 -f 392//392 390//390 230//230 -f 230//230 390//390 228//228 -f 392//392 386//386 390//390 -f 390//390 386//386 387//387 -f 389//389 393//393 388//388 -f 388//388 393//393 391//391 -f 391//391 393//393 226//226 -f 226//226 393//393 233//233 -f 393//393 389//389 233//233 -f 233//233 389//389 184//184 -f 233//233 184//184 230//230 -f 230//230 184//184 183//183 -f 230//230 183//183 392//392 -f 392//392 183//183 386//386 -# 806 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_letva.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_letva.obj deleted file mode 100644 index a1d458ddc..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_letva.obj +++ /dev/null @@ -1,1664 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object T_BOT_NOVE_SISE_I_LETVA2022 - letva m2x80-1.obj -# -# Vertices: 409 -# Faces: 830 -# -#### -vn -2.182366 5.827906 0.427294 -v 0.054425 0.007973 0.016000 -vn -4.062924 3.000890 0.100305 -v 0.053900 0.007822 0.016000 -vn -3.080221 4.235820 -1.371421 -v 0.053900 0.007822 0.016747 -vn -1.364943 3.122683 -3.068645 -v 0.051400 0.007505 0.017657 -vn -0.591769 6.204958 0.541725 -v 0.053998 0.007848 0.018402 -vn -1.259615 3.132520 3.068749 -v 0.051400 0.007505 0.020396 -vn -1.219456 3.123502 3.254155 -v 0.051843 0.007515 0.020557 -vn -1.075463 6.025340 0.884189 -v 0.054490 0.007994 0.017910 -vn -1.315046 5.696144 1.847598 -v 0.056400 0.008845 0.016000 -vn -3.100992 -4.230775 -1.391237 -v 0.053900 -0.007813 0.016747 -vn -4.039120 -3.009962 0.051740 -v 0.053900 -0.007813 0.016000 -vn -2.178971 -5.827674 0.435946 -v 0.054425 -0.007964 0.016000 -vn -1.124094 -3.141041 2.971676 -v 0.051400 -0.007495 0.020396 -vn -1.331525 -3.126680 -3.037177 -v 0.051400 -0.007495 0.017657 -vn -1.277436 -3.130356 3.081019 -v 0.051843 -0.007505 0.020557 -vn -0.859140 -6.119863 0.659567 -v 0.054490 -0.007985 0.017910 -vn -1.295394 -5.683050 1.876019 -v 0.056400 -0.008835 0.016000 -vn -2.226053 1.927630 1.357877 -v 0.053900 -0.007813 0.008740 -vn -2.221675 1.927056 -1.364435 -v 0.053900 -0.007813 0.010464 -vn -2.226052 -1.927627 1.357877 -v 0.053900 0.007822 0.008740 -vn -2.221676 -1.927054 -1.364436 -v 0.053900 0.007822 0.010464 -vn -0.217262 0.015098 -6.144427 -v 0.053900 -0.007813 0.005000 -vn -0.766623 -2.777208 -3.180781 -v 0.051648 -0.007498 0.005000 -vn -1.340479 -3.125694 3.046060 -v 0.051400 -0.007495 0.007830 -vn -1.102309 -3.141415 -2.963097 -v 0.051400 -0.007495 0.005090 -vn -1.102313 3.141415 -2.963099 -v 0.051400 0.007505 0.005090 -vn -1.340480 3.125694 3.046061 -v 0.051400 0.007505 0.007830 -vn -0.766625 2.777209 -3.180780 -v 0.051648 0.007508 0.005000 -vn -0.217262 -0.015098 -6.144425 -v 0.053900 0.007822 0.005000 -vn -2.108041 1.919863 -1.476065 -v 0.049400 0.007505 0.018385 -vn -2.108044 1.919864 1.476065 -v 0.049400 0.007505 0.019668 -vn -1.356705 3.123746 -3.063761 -v 0.051400 0.007505 0.011374 -vn -2.108041 1.919863 -1.476065 -v 0.049400 0.007505 0.012102 -vn -1.356705 3.123746 3.063762 -v 0.051400 0.007505 0.014113 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.013385 -vn -2.108041 1.919863 -1.476065 -v 0.049400 0.007505 0.005818 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.007102 -vn 1.570796 -1.570797 1.570796 -v 0.061400 -0.007495 0.110979 -vn -1.570796 -1.570796 1.570796 -v 0.053900 -0.007495 0.110979 -vn -2.108041 -4.363323 1.476066 -v 0.053900 -0.007495 0.109255 -vn -2.108041 -4.363323 1.476066 -v 0.053900 -0.007495 0.090415 -vn 3.128154 -3.272593 0.205030 -v 0.061400 -0.007495 0.025142 -vn -2.108039 -4.363324 -1.476066 -v 0.053900 -0.007495 0.092136 -vn -2.108041 -4.363322 1.476066 -v 0.053900 -0.007495 0.096695 -vn -2.108039 -1.919861 -1.476066 -v 0.049400 -0.007495 0.093773 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.095057 -vn -2.108039 -1.919861 1.476066 -v 0.049400 -0.007495 0.101337 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.100053 -vn -2.108039 -4.363325 1.476066 -v 0.053900 -0.007495 0.102975 -vn -2.108041 -4.363323 -1.476066 -v 0.053900 -0.007495 0.098416 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.107617 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.106333 -vn -2.108041 -4.363322 -1.476066 -v 0.053900 -0.007495 0.104695 -vn -2.108042 -4.363323 -1.476066 -v 0.053900 -0.007495 0.079579 -vn -2.108041 -4.363323 1.476066 -v 0.053900 -0.007495 0.077855 -vn -2.108042 -4.363323 1.476066 -v 0.053900 -0.007495 0.084138 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.082500 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.081217 -vn -2.108041 -4.363322 -1.476066 -v 0.053900 -0.007495 0.085855 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.087493 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.088777 -vn -2.108041 -4.363322 1.476066 -v 0.053900 -0.007495 0.065289 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.063651 -vn -2.108040 -1.919862 -1.476066 -v 0.049400 -0.007495 0.062367 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.076217 -vn -2.108039 -1.919861 -1.476066 -v 0.049400 -0.007495 0.074933 -vn -2.108039 -4.363324 -1.476066 -v 0.053900 -0.007495 0.073296 -vn -2.108041 -4.363323 1.476066 -v 0.053900 -0.007495 0.071572 -vn -2.108040 -4.363323 -1.476065 -v 0.053900 -0.007495 0.060729 -vn -2.108040 -4.363323 1.476066 -v 0.053900 -0.007495 0.059005 -vn -2.108039 -4.363324 -1.476066 -v 0.053900 -0.007495 0.067012 -vn -2.108039 -1.919861 -1.476066 -v 0.049400 -0.007495 0.068650 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.069934 -vn -2.108040 -4.363323 -1.476065 -v 0.053900 -0.007495 0.048163 -vn -2.108041 -4.363322 1.476066 -v 0.053900 -0.007495 0.046439 -vn -2.108041 -4.363323 1.476066 -v 0.053900 -0.007495 0.052722 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.051084 -vn -2.108040 -1.919862 -1.476066 -v 0.049400 -0.007495 0.049801 -vn -2.108040 -4.363323 -1.476065 -v 0.053900 -0.007495 0.054446 -vn -2.108040 -1.919862 -1.476066 -v 0.049400 -0.007495 0.056084 -vn -2.108040 -1.919862 1.476065 -v 0.049400 -0.007495 0.057368 -vn -2.108040 -4.363323 -1.476065 -v 0.053900 -0.007495 0.035596 -vn -2.108040 -4.363323 1.476066 -v 0.053900 -0.007495 0.033873 -vn -2.108040 -4.363323 1.476066 -v 0.053900 -0.007495 0.040156 -vn -2.108040 -1.919862 1.476065 -v 0.049400 -0.007495 0.038518 -vn -2.108040 -1.919862 -1.476066 -v 0.049400 -0.007495 0.037234 -vn -2.108041 -4.363322 -1.476066 -v 0.053900 -0.007495 0.041880 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.043517 -vn -2.108041 -1.919863 1.476066 -v 0.049400 -0.007495 0.044801 -vn -2.108040 -1.919862 1.476065 -v 0.049400 -0.007495 0.032235 -vn -2.108040 -1.919862 -1.476066 -v 0.049400 -0.007495 0.030951 -vn -2.108040 -4.363324 -1.476065 -v 0.053900 -0.007495 0.029313 -vn 3.070915 -3.281484 0.625206 -v 0.061911 -0.007495 0.021260 -vn -2.108040 -1.919862 -1.476066 -v 0.049400 -0.007495 0.024668 -vn -2.108040 -4.363326 -1.476065 -v 0.053900 -0.007495 0.023030 -vn -2.108041 -1.919862 1.476066 -v 0.049400 -0.007495 0.025952 -vn -2.108041 -4.363323 1.476066 -v 0.053900 -0.007495 0.027589 -vn 3.067879 -3.199903 1.116024 -v 0.061983 -0.007495 0.021000 -vn -2.108044 -4.363321 1.476065 -v 0.053900 -0.007495 0.021306 -vn -1.132814 -3.114130 3.358349 -v 0.053059 -0.007495 0.021000 -vn -2.108041 -1.919863 1.476065 -v 0.049400 -0.007495 0.007102 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.005818 -vn -1.356705 -3.123746 3.063761 -v 0.051400 -0.007495 0.014113 -vn -2.108041 -1.919863 1.476065 -v 0.049400 -0.007495 0.013385 -vn -1.356705 -3.123746 -3.063762 -v 0.051400 -0.007495 0.011374 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.012102 -vn -0.190650 -0.460786 6.243170 -v 0.052913 -0.012729 0.011000 -vn -3.304439 -0.208931 3.127233 -v 0.052000 -0.012531 0.011000 -vn -1.570796 -1.570796 1.570795 -v 0.052000 -0.042995 0.011000 -vn -0.242461 -0.086538 6.272601 -v 0.056250 -0.016280 0.011000 -vn -0.447565 -0.274697 6.238798 -v 0.055788 -0.015098 0.011000 -vn -0.386669 -0.363450 6.237592 -v 0.055043 -0.014071 0.011000 -vn -1.517272 -2.627994 3.665192 -v 0.088000 -0.032963 0.011000 -vn -2.627992 -1.517277 3.665189 -v 0.088732 -0.033695 0.011000 -vn 1.570796 1.570796 1.570798 -v 0.096400 -0.029995 0.011000 -vn -3.034543 0.000001 3.665198 -v 0.089000 -0.034695 0.011000 -vn 1.570796 -1.570796 1.570797 -v 0.096400 -0.042995 0.011000 -vn -2.627992 1.517278 3.665188 -v 0.088732 -0.035695 0.011000 -vn -1.517272 2.627994 3.665192 -v 0.088000 -0.036427 0.011000 -vn -1.517272 2.627994 3.665193 -v 0.068000 -0.036427 0.011000 -vn 0.000000 3.034546 3.665190 -v 0.067000 -0.036695 0.011000 -vn 1.517272 2.627994 3.665192 -v 0.066000 -0.036427 0.011000 -vn 2.627992 1.517278 3.665188 -v 0.065268 -0.035695 0.011000 -vn 3.034543 0.000001 3.665198 -v 0.065000 -0.034695 0.011000 -vn -0.000608 -0.000729 6.283182 -v 0.056400 -0.017495 0.011000 -vn -0.282711 -0.449092 6.237591 -v 0.054064 -0.013264 0.011000 -vn 2.951046 0.958856 3.455753 -v 0.069389 -0.023085 0.011000 -vn -0.000000 -3.034546 3.665188 -v 0.067000 -0.032695 0.011000 -vn 2.510310 1.823849 3.455750 -v 0.070810 -0.025873 0.011000 -vn 1.823848 2.510310 3.455752 -v 0.073022 -0.028085 0.011000 -vn 2.627992 -1.517277 3.665189 -v 0.065268 -0.033695 0.011000 -vn 1.517272 -2.627994 3.665192 -v 0.066000 -0.032963 0.011000 -vn 3.295744 -0.245694 3.122232 -v 0.068900 -0.017495 0.011000 -vn 3.122253 0.245727 3.298673 -v 0.068900 -0.019995 0.011000 -vn 0.000003 3.034545 3.665192 -v 0.087000 -0.036695 0.011000 -vn 1.517274 2.627992 3.665190 -v 0.086000 -0.036427 0.011000 -vn 2.627992 1.517278 3.665187 -v 0.085268 -0.035695 0.011000 -vn 0.000003 -3.034545 3.665192 -v 0.087000 -0.032695 0.011000 -vn 1.517275 -2.627993 3.665190 -v 0.086000 -0.032963 0.011000 -vn 2.627992 -1.517277 3.665185 -v 0.085268 -0.033695 0.011000 -vn 0.245727 3.122253 3.298672 -v 0.078900 -0.029995 0.011000 -vn 0.958854 2.951047 3.455752 -v 0.075810 -0.029506 0.011000 -vn -1.517272 -2.627994 3.665192 -v 0.068000 -0.032963 0.011000 -vn -2.627995 -1.517267 3.665197 -v 0.068732 -0.033695 0.011000 -vn 3.034543 0.000001 3.665199 -v 0.085000 -0.034695 0.011000 -vn -3.034548 0.000001 3.665183 -v 0.069000 -0.034695 0.011000 -vn -2.627995 1.517268 3.665195 -v 0.068732 -0.035695 0.011000 -vn -2.108043 -1.919864 1.476064 -v 0.049400 -0.007495 0.019668 -vn -2.108041 -1.919863 -1.476066 -v 0.049400 -0.007495 0.018385 -vn -2.108040 1.919862 1.476066 -v 0.049400 0.007505 0.025952 -vn -2.108040 1.919862 -1.476065 -v 0.049400 0.007505 0.024668 -vn -2.108040 1.919862 1.476066 -v 0.049400 0.007505 0.032235 -vn -2.108040 1.919862 -1.476065 -v 0.049400 0.007505 0.030951 -vn -2.108040 1.919862 1.476066 -v 0.049400 0.007505 0.038518 -vn -2.108040 1.919862 -1.476065 -v 0.049400 0.007505 0.037234 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.044801 -vn -2.108041 1.919863 -1.476066 -v 0.049400 0.007505 0.043517 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.051084 -vn -2.108040 1.919862 -1.476065 -v 0.049400 0.007505 0.049801 -vn -2.108040 1.919862 1.476066 -v 0.049400 0.007505 0.057368 -vn -2.108040 1.919862 -1.476065 -v 0.049400 0.007505 0.056084 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.063651 -vn -2.108040 1.919862 -1.476065 -v 0.049400 0.007505 0.062367 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.069934 -vn -2.108039 1.919861 -1.476066 -v 0.049400 0.007505 0.068650 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.076217 -vn -2.108039 1.919861 -1.476066 -v 0.049400 0.007505 0.074933 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.082500 -vn -2.108041 1.919863 -1.476066 -v 0.049400 0.007505 0.081217 -vn -1.570796 1.570796 -1.570798 -v 0.052000 0.043005 0.005000 -vn 1.517272 -2.627994 -3.665192 -v 0.066000 0.036437 0.005000 -vn 2.627992 -1.517277 -3.665188 -v 0.065268 0.035705 0.005000 -vn -1.570799 1.570796 -1.570799 -v 0.052000 -0.007813 0.005000 -vn 2.627992 -1.517277 -3.665189 -v 0.065268 -0.033695 0.005000 -vn -1.570796 -1.570796 -1.570793 -v 0.052000 -0.042995 0.005000 -vn 3.034543 0.000001 -3.665198 -v 0.065000 -0.034695 0.005000 -vn -2.627995 -1.517266 -3.665189 -v 0.068732 -0.033695 0.005000 -vn 0.000000 -3.034546 -3.665190 -v 0.067000 0.036705 0.005000 -vn 1.570796 1.570796 -1.570796 -v 0.096400 0.043005 0.005000 -vn -1.517272 -2.627994 -3.665192 -v 0.068000 0.036437 0.005000 -vn 2.627992 1.517278 -3.665188 -v 0.065268 -0.035695 0.005000 -vn 1.517272 2.627994 -3.665192 -v 0.066000 -0.036427 0.005000 -vn -0.000000 3.034546 -3.665190 -v 0.067000 -0.036695 0.005000 -vn 3.034543 0.000001 -3.665198 -v 0.065000 0.034705 0.005000 -vn -1.570799 -1.570796 -1.570796 -v 0.052000 0.007822 0.005000 -vn 2.627992 1.517278 -3.665188 -v 0.065268 0.033705 0.005000 -vn 1.517277 2.627992 -3.665189 -v 0.066000 0.032973 0.005000 -vn -0.000000 3.034543 -3.665187 -v 0.067000 0.032705 0.005000 -vn -3.034549 0.000001 -3.665185 -v 0.069000 -0.034695 0.005000 -vn -1.517272 -2.627994 -3.665192 -v 0.068000 -0.032963 0.005000 -vn 0.000000 -3.034546 -3.665190 -v 0.067000 -0.032695 0.005000 -vn 1.517272 -2.627994 -3.665192 -v 0.066000 -0.032963 0.005000 -vn 1.517274 -2.627992 -3.665191 -v 0.086000 -0.032963 0.005000 -vn 2.627992 -1.517277 -3.665189 -v 0.085268 -0.033695 0.005000 -vn -2.627995 1.517268 -3.665187 -v 0.068732 -0.035695 0.005000 -vn 3.034543 0.000001 -3.665201 -v 0.085000 -0.034695 0.005000 -vn -1.517272 2.627994 -3.665193 -v 0.068000 -0.036427 0.005000 -vn 2.627992 1.517278 -3.665184 -v 0.085268 -0.035695 0.005000 -vn 0.000003 3.034545 -3.665192 -v 0.087000 -0.036695 0.005000 -vn 1.570796 -1.570796 -1.570794 -v 0.096400 -0.042995 0.005000 -vn 1.517274 2.627993 -3.665190 -v 0.086000 -0.036427 0.005000 -vn -1.517272 2.627994 -3.665192 -v 0.088000 -0.036427 0.005000 -vn -2.627992 1.517278 -3.665188 -v 0.088732 -0.035695 0.005000 -vn 1.570796 1.570796 -1.570797 -v 0.096400 -0.029995 0.005000 -vn -3.034543 0.000001 -3.665198 -v 0.089000 -0.034695 0.005000 -vn -2.627992 -1.517277 -3.665189 -v 0.088732 -0.033695 0.005000 -vn -1.517277 2.627992 -3.665189 -v 0.068000 0.032973 0.005000 -vn -2.627995 1.517268 -3.665195 -v 0.068732 0.033705 0.005000 -vn 1.823849 -2.510310 -3.455752 -v 0.073022 0.028095 0.005000 -vn -2.627992 -1.517277 -3.665189 -v 0.088732 0.035705 0.005000 -vn -1.517272 -2.627994 -3.665192 -v 0.088000 0.036437 0.005000 -vn -1.517272 -2.627994 -3.665192 -v 0.088000 -0.032963 0.005000 -vn 0.000003 -3.034545 -3.665190 -v 0.087000 -0.032695 0.005000 -vn 0.245727 3.122254 -3.298673 -v 0.078900 -0.029995 0.005000 -vn 0.958854 2.951047 -3.455751 -v 0.075810 -0.029506 0.005000 -vn -3.034543 0.000001 -3.665198 -v 0.089000 0.034705 0.005000 -vn 1.570796 -1.570796 -1.570795 -v 0.096400 0.030005 0.005000 -vn -2.627992 1.517278 -3.665188 -v 0.088732 0.033705 0.005000 -vn 2.510310 1.823849 -3.455750 -v 0.070810 -0.025873 0.005000 -vn 1.823848 2.510310 -3.455752 -v 0.073022 -0.028085 0.005000 -vn 0.000003 -3.034545 -3.665192 -v 0.087000 0.036705 0.005000 -vn 1.517274 -2.627992 -3.665190 -v 0.086000 0.036437 0.005000 -vn 2.627992 -1.517277 -3.665188 -v 0.085268 0.035705 0.005000 -vn 2.510310 -1.823849 -3.455750 -v 0.070810 0.025883 0.005000 -vn 2.951046 -0.958856 -3.455752 -v 0.069389 0.023095 0.005000 -vn 3.122255 -0.245727 -3.298672 -v 0.068900 0.020005 0.005000 -vn 3.122255 0.245727 -3.298672 -v 0.068900 -0.019995 0.005000 -vn 2.951046 0.958856 -3.455753 -v 0.069389 -0.023085 0.005000 -vn 2.627992 1.517278 -3.665188 -v 0.085268 0.033705 0.005000 -vn 1.517280 2.627992 -3.665187 -v 0.086000 0.032973 0.005000 -vn 0.245726 -3.122254 -3.298671 -v 0.078900 0.030005 0.005000 -vn 0.000003 3.034543 -3.665199 -v 0.087000 0.032705 0.005000 -vn -1.517277 2.627992 -3.665189 -v 0.088000 0.032973 0.005000 -vn 3.034543 0.000001 -3.665198 -v 0.085000 0.034705 0.005000 -vn -3.034549 0.000001 -3.665182 -v 0.069000 0.034705 0.005000 -vn -2.627995 -1.517266 -3.665196 -v 0.068732 0.035705 0.005000 -vn 0.958853 -2.951047 -3.455753 -v 0.075810 0.029515 0.005000 -vn 3.128154 3.272491 0.205030 -v 0.061400 0.007505 0.025142 -vn 1.570796 1.570828 1.570796 -v 0.061400 0.007505 0.110979 -vn -2.108042 4.363322 1.476066 -v 0.053900 0.007505 0.109255 -vn -1.570796 1.570796 1.570796 -v 0.053900 0.007505 0.110979 -vn -2.108041 4.363322 1.476066 -v 0.053900 0.007505 0.090415 -vn -2.108039 4.363324 -1.476066 -v 0.053900 0.007505 0.092136 -vn -2.108040 4.363323 -1.476066 -v 0.053900 0.007505 0.060729 -vn 3.107111 3.195770 1.161019 -v 0.061983 0.007505 0.021000 -vn -1.132129 3.120855 3.305654 -v 0.053059 0.007505 0.021000 -vn -2.108043 4.363324 1.476064 -v 0.053900 0.007505 0.021306 -vn -2.108042 4.363322 1.476066 -v 0.053900 0.007505 0.065289 -vn -2.108039 4.363324 -1.476066 -v 0.053900 0.007505 0.067012 -vn -2.108041 4.363323 -1.476066 -v 0.053900 0.007505 0.098416 -vn -2.108041 4.363323 1.476066 -v 0.053900 0.007505 0.096695 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.095057 -vn -2.108039 1.919861 -1.476066 -v 0.049400 0.007505 0.093773 -vn -2.108040 4.363323 -1.476066 -v 0.053900 0.007505 0.023030 -vn 3.070914 3.281482 0.625206 -v 0.061911 0.007505 0.021260 -vn -2.108041 1.919863 -1.476066 -v 0.049400 0.007505 0.100053 -vn -2.108039 1.919861 1.476066 -v 0.049400 0.007505 0.101337 -vn -2.108039 4.363324 1.476066 -v 0.053900 0.007505 0.102975 -vn -2.108041 4.363323 -1.476066 -v 0.053900 0.007505 0.104695 -vn -2.108041 1.919863 -1.476066 -v 0.049400 0.007505 0.106333 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.107617 -vn -2.108040 4.363324 -1.476066 -v 0.053900 0.007505 0.029313 -vn -2.108040 4.363323 1.476065 -v 0.053900 0.007505 0.033873 -vn -2.108039 4.363324 -1.476066 -v 0.053900 0.007505 0.073296 -vn -2.108042 4.363323 1.476066 -v 0.053900 0.007505 0.071572 -vn -2.108042 4.363322 -1.476066 -v 0.053900 0.007505 0.085855 -vn -2.108041 1.919863 -1.476066 -v 0.049400 0.007505 0.087493 -vn -2.108041 1.919863 1.476066 -v 0.049400 0.007505 0.088777 -vn -2.108041 4.363322 -1.476066 -v 0.053900 0.007505 0.041880 -vn -2.108040 4.363323 1.476065 -v 0.053900 0.007505 0.040156 -vn -2.108040 4.363323 -1.476066 -v 0.053900 0.007505 0.035596 -vn -2.108040 4.363323 -1.476066 -v 0.053900 0.007505 0.048163 -vn -2.108042 4.363322 1.476066 -v 0.053900 0.007505 0.077855 -vn -2.108041 4.363323 -1.476066 -v 0.053900 0.007505 0.079579 -vn -2.108041 4.363323 1.476066 -v 0.053900 0.007505 0.027589 -vn -2.108041 4.363322 1.476066 -v 0.053900 0.007505 0.084138 -vn -2.108041 4.363323 1.476066 -v 0.053900 0.007505 0.052722 -vn -2.108040 4.363323 -1.476066 -v 0.053900 0.007505 0.054446 -vn -2.108040 4.363323 1.476065 -v 0.053900 0.007505 0.059005 -vn -2.108041 4.363323 1.476066 -v 0.053900 0.007505 0.046439 -vn -2.221676 -1.927055 1.364435 -v 0.053900 0.007822 0.015023 -vn -2.221675 1.927056 1.364436 -v 0.053900 -0.007813 0.015023 -vn -1.570796 1.570796 1.570799 -v 0.052000 0.043005 0.011000 -vn -3.288479 0.188543 3.129908 -v 0.052000 0.012541 0.011000 -vn -0.197028 0.451408 6.244163 -v 0.052913 0.012739 0.011000 -vn -0.000608 0.000729 6.283185 -v 0.056400 0.017505 0.011000 -vn -2.627995 1.517268 3.665195 -v 0.068732 0.033705 0.011000 -vn -1.517277 2.627992 3.665188 -v 0.068000 0.032973 0.011000 -vn -0.441892 0.274511 6.239583 -v 0.055788 0.015108 0.011000 -vn -0.328911 0.114654 6.263795 -v 0.056250 0.016290 0.011000 -vn -0.386669 0.363450 6.237590 -v 0.055043 0.014080 0.011000 -vn -0.282711 0.449093 6.237591 -v 0.054064 0.013273 0.011000 -vn 0.000000 3.034543 3.665197 -v 0.067000 0.032705 0.011000 -vn 1.517277 2.627992 3.665189 -v 0.066000 0.032973 0.011000 -vn 2.627992 1.517278 3.665188 -v 0.065268 0.033705 0.011000 -vn 3.034543 0.000001 3.665198 -v 0.065000 0.034705 0.011000 -vn 2.627992 -1.517277 3.665189 -v 0.065268 0.035705 0.011000 -vn 1.517280 2.627992 3.665188 -v 0.086000 0.032973 0.011000 -vn 2.627992 1.517278 3.665188 -v 0.085268 0.033705 0.011000 -vn 3.034543 0.000001 3.665198 -v 0.085000 0.034705 0.011000 -vn 0.000003 -3.034545 3.665192 -v 0.087000 0.036705 0.011000 -vn 1.570796 1.570796 1.570793 -v 0.096400 0.043005 0.011000 -vn 1.517275 -2.627993 3.665190 -v 0.086000 0.036437 0.011000 -vn 2.627992 -1.517277 3.665189 -v 0.085268 0.035705 0.011000 -vn -1.517272 -2.627994 3.665192 -v 0.088000 0.036437 0.011000 -vn -2.627992 -1.517277 3.665189 -v 0.088732 0.035705 0.011000 -vn 1.570796 -1.570796 1.570795 -v 0.096400 0.030005 0.011000 -vn -3.034543 0.000001 3.665198 -v 0.089000 0.034705 0.011000 -vn -2.627992 1.517278 3.665188 -v 0.088732 0.033705 0.011000 -vn 1.517272 -2.627994 3.665192 -v 0.066000 0.036437 0.011000 -vn -0.000000 -3.034546 3.665191 -v 0.067000 0.036705 0.011000 -vn -1.517272 -2.627994 3.665178 -v 0.068000 0.036437 0.011000 -vn 0.000003 3.034543 3.665197 -v 0.087000 0.032705 0.011000 -vn -2.627995 -1.517267 3.665195 -v 0.068732 0.035705 0.011000 -vn -3.034548 0.000001 3.665184 -v 0.069000 0.034705 0.011000 -vn -1.517277 2.627992 3.665189 -v 0.088000 0.032973 0.011000 -vn 0.245726 -3.122254 3.298672 -v 0.078900 0.030005 0.011000 -vn 0.958853 -2.951047 3.455752 -v 0.075810 0.029515 0.011000 -vn 1.823849 -2.510310 3.455752 -v 0.073022 0.028095 0.011000 -vn 3.286511 0.237847 3.123439 -v 0.068900 0.017505 0.011000 -vn 3.122253 -0.245727 3.298673 -v 0.068900 0.020005 0.011000 -vn 2.951046 -0.958856 3.455753 -v 0.069389 0.023095 0.011000 -vn 2.510310 -1.823849 3.455750 -v 0.070810 0.025883 0.011000 -vn 2.211773 2.255986 4.613851 -v 0.065793 0.009875 0.014536 -vn 2.436261 2.515978 4.078151 -v 0.065238 0.009415 0.015122 -vn 2.176172 -2.278352 4.598228 -v 0.065793 -0.009866 0.014536 -vn 2.635716 2.809045 3.485770 -v 0.064281 0.008676 0.016303 -vn 2.400125 -2.552082 4.061779 -v 0.065247 -0.009413 0.015111 -vn 3.060039 3.183646 1.823287 -v 0.062544 0.007634 0.019397 -vn 3.024426 -3.183984 1.882558 -v 0.062541 -0.007623 0.019403 -vn 2.875458 3.010805 2.753095 -v 0.063259 0.007994 0.017910 -vn 2.824586 -3.013120 2.784131 -v 0.063410 -0.008076 0.017642 -vn 2.595900 -2.788726 3.505244 -v 0.064276 -0.008663 0.016310 -vn 3.214476 -1.073075 2.917828 -v 0.068900 -0.012836 0.012152 -vn 3.203490 1.079057 2.915382 -v 0.068900 0.012846 0.012152 -vn 1.865095 1.796317 5.235184 -v 0.067718 0.011627 0.012910 -vn 1.860998 -1.790603 5.239320 -v 0.067718 -0.011617 0.012910 -vn -0.334208 -0.506341 6.247429 -v 0.057046 -0.016442 0.011056 -vn -0.102879 -0.122468 6.280222 -v 0.056577 -0.017235 0.011003 -vn -0.014400 -0.016860 6.283101 -v 0.056412 -0.017479 0.011000 -vn -1.801528 -3.785891 4.369686 -v 0.058078 -0.011304 0.013147 -vn -1.559531 -3.048978 5.085600 -v 0.058160 -0.012417 0.012385 -vn 3.390321 -0.860437 2.996845 -v 0.068900 -0.014405 0.011489 -vn -1.241877 -2.339711 5.593953 -v 0.058112 -0.013101 0.012017 -vn -1.054455 -1.743215 5.886485 -v 0.057865 -0.014374 0.011500 -vn -0.697126 -1.000164 6.139821 -v 0.057627 -0.015128 0.011284 -vn -1.646072 -4.306615 3.995102 -v 0.057933 -0.010726 0.013640 -vn -1.574406 -5.247994 2.524305 -v 0.057161 -0.009422 0.015099 -vn -1.668678 -4.779515 3.334883 -v 0.057513 -0.009855 0.014548 -vn -1.706833 5.218949 2.503281 -v 0.057137 0.009407 0.015133 -vn -1.490584 5.463925 2.262845 -v 0.056877 0.009172 0.015472 -vn -1.635202 4.829586 3.271760 -v 0.057513 0.009865 0.014548 -vn -1.651749 4.473805 3.800831 -v 0.057784 0.010352 0.014012 -vn -1.075406 2.050928 5.757975 -v 0.057992 0.013852 0.011691 -vn -1.274091 2.502367 5.506064 -v 0.058112 0.013110 0.012017 -vn 3.368898 0.862621 2.998075 -v 0.068900 0.014415 0.011489 -vn -1.811228 3.819655 4.377314 -v 0.058078 0.011314 0.013147 -vn -1.525398 3.363132 4.915481 -v 0.058151 0.011940 0.012691 -vn -0.126295 0.157892 6.278059 -v 0.056577 0.017245 0.011003 -vn -0.014400 0.016860 6.283102 -v 0.056412 0.017488 0.011000 -vn -0.407296 0.669207 6.226041 -v 0.057282 0.015977 0.011117 -vn -0.662421 1.047816 6.131742 -v 0.057627 0.015137 0.011284 -vn -1.021479 1.614920 5.910014 -v 0.057854 0.014421 0.011487 -vn -1.089712 0.224459 0.397264 -v 0.053869 -0.007813 0.015723 -vn -1.085286 0.262352 0.614562 -v 0.053693 -0.007813 0.015296 -vn -0.770881 0.275471 1.019348 -v 0.053328 -0.007813 0.014878 -vn -0.590142 0.420350 1.450860 -v 0.052701 -0.007813 0.014499 -vn -0.679483 0.224472 0.789384 -v 0.052000 -0.007813 0.014297 -vn -3.474784 -0.639368 3.051900 -v 0.052000 -0.011354 0.011139 -vn -3.564252 -1.168645 2.878382 -v 0.052000 -0.010859 0.011285 -vn -3.643472 -1.599466 2.649361 -v 0.052000 -0.009798 0.011805 -vn -3.719005 -2.034581 2.314830 -v 0.052000 -0.009378 0.012108 -vn -3.768375 -2.374002 1.949537 -v 0.052000 -0.008552 0.012952 -vn -3.793594 -2.647540 1.552222 -v 0.052000 -0.008263 0.013369 -vn -1.102325 -0.246653 0.508805 -v 0.053796 0.007822 0.015497 -vn -0.888920 -0.246134 0.819442 -v 0.053521 0.007822 0.015066 -vn -0.649848 -0.441816 1.460956 -v 0.052987 0.007822 0.014640 -vn -0.471164 -0.418887 1.491062 -v 0.052154 0.007822 0.014327 -vn -0.618495 -0.212947 0.780805 -v 0.052000 0.007822 0.014297 -vn -3.812110 2.616948 1.592819 -v 0.052000 0.008354 0.013243 -vn -3.765173 2.314240 2.021423 -v 0.052000 0.008652 0.012838 -vn -3.702455 1.971542 2.372439 -v 0.052000 0.009503 0.012019 -vn -3.630184 1.537105 2.689204 -v 0.052000 0.009917 0.011736 -vn -3.528215 1.083564 2.916471 -v 0.052000 0.010992 0.011243 -vn -3.465909 0.584418 3.065012 -v 0.052000 0.011477 0.011113 -vn -1.953545 -5.468142 1.993604 -v 0.054351 -0.008197 0.014455 -vn -1.573187 -4.722249 3.569232 -v 0.054136 -0.008874 0.013061 -vn -2.873194 -5.052399 2.028921 -v 0.056597 -0.009240 0.014455 -vn -2.579075 -4.226943 3.603756 -v 0.056219 -0.009841 0.013061 -vn -2.518515 -2.562841 5.010988 -v 0.057185 -0.012058 0.011955 -vn -1.441707 -1.355134 5.850151 -v 0.056169 -0.013013 0.011245 -vn -1.532714 -0.984192 5.926893 -v 0.057144 -0.014358 0.011245 -vn -3.384483 -3.492623 3.853017 -v 0.057991 -0.011300 0.013061 -vn -1.177691 -3.473741 4.941821 -v 0.053802 -0.009928 0.011955 -vn -0.681835 -1.875161 5.857397 -v 0.053380 -0.011257 0.011245 -vn -1.949897 -3.097458 4.931844 -v 0.055629 -0.010777 0.011955 -vn -1.054094 -1.674454 5.850150 -v 0.054887 -0.011956 0.011245 -vn -3.615430 2.910272 3.961753 -v 0.057991 0.011310 0.013061 -vn -2.579547 4.225687 3.604887 -v 0.056219 0.009850 0.013061 -vn -0.689609 1.873256 5.859104 -v 0.053380 0.011266 0.011245 -vn -1.181096 3.481058 4.936466 -v 0.053802 0.009938 0.011955 -vn -1.563411 4.728696 3.560085 -v 0.054136 0.008884 0.013061 -vn -1.935024 5.466146 2.007467 -v 0.054351 0.008207 0.014455 -vn -1.492064 0.901605 5.965670 -v 0.057144 0.014367 0.011245 -vn -1.415651 1.366475 5.857282 -v 0.056169 0.013022 0.011245 -vn -2.533770 2.558228 5.004840 -v 0.057185 0.012068 0.011955 -vn -2.870445 5.045795 2.057280 -v 0.056597 0.009249 0.014455 -vn -1.949897 3.097457 4.931845 -v 0.055629 0.010786 0.011955 -vn -1.054094 1.674453 5.850151 -v 0.054887 0.011966 0.011245 -# 409 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 3//3 5//5 1//1 -f 1//1 5//5 8//8 -f 1//1 8//8 9//9 -f 10//10 11//11 12//12 -f 13//13 14//14 15//15 -f 15//15 14//14 10//10 -f 15//15 10//10 16//16 -f 16//16 10//10 12//12 -f 16//16 12//12 17//17 -f 18//18 19//19 20//20 -f 20//20 19//19 21//21 -f 22//22 18//18 23//23 -f 23//23 18//18 24//24 -f 23//23 24//24 25//25 -f 26//26 27//27 28//28 -f 28//28 27//27 20//20 -f 28//28 20//20 29//29 -f 4//4 30//30 6//6 -f 6//6 30//30 31//31 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 26//26 36//36 27//27 -f 27//27 36//36 37//37 -f 38//38 39//39 40//40 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 51//51 52//52 40//40 -f 40//40 52//52 53//53 -f 40//40 53//53 38//38 -f 38//38 53//53 49//49 -f 38//38 49//49 42//42 -f 42//42 49//49 50//50 -f 42//42 50//50 44//44 -f 54//54 55//55 42//42 -f 56//56 57//57 58//58 -f 58//58 54//54 56//56 -f 56//56 54//54 42//42 -f 56//56 42//42 59//59 -f 59//59 42//42 41//41 -f 59//59 41//41 60//60 -f 60//60 41//41 61//61 -f 62//62 63//63 64//64 -f 65//65 66//66 55//55 -f 55//55 66//66 67//67 -f 55//55 67//67 42//42 -f 42//42 67//67 68//68 -f 69//69 70//70 42//42 -f 64//64 69//69 62//62 -f 62//62 69//69 42//42 -f 62//62 42//42 71//71 -f 71//71 42//42 68//68 -f 71//71 68//68 72//72 -f 72//72 68//68 73//73 -f 74//74 75//75 42//42 -f 76//76 77//77 78//78 -f 78//78 74//74 76//76 -f 76//76 74//74 42//42 -f 76//76 42//42 79//79 -f 79//79 42//42 70//70 -f 79//79 70//70 80//80 -f 80//80 70//70 81//81 -f 82//82 83//83 42//42 -f 84//84 85//85 86//86 -f 86//86 82//82 84//84 -f 84//84 82//82 42//42 -f 84//84 42//42 87//87 -f 87//87 42//42 75//75 -f 87//87 75//75 88//88 -f 88//88 75//75 89//89 -f 90//90 91//91 83//83 -f 83//83 91//91 92//92 -f 83//83 92//92 42//42 -f 42//42 92//92 93//93 -f 94//94 95//95 96//96 -f 96//96 95//95 97//97 -f 92//92 97//97 93//93 -f 93//93 97//97 95//95 -f 93//93 95//95 98//98 -f 98//98 95//95 99//99 -f 98//98 99//99 100//100 -f 24//24 101//101 25//25 -f 25//25 101//101 102//102 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 107//107 108//108 109//109 -f 110//110 111//111 112//112 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 117//117 120//120 121//121 -f 117//117 121//121 109//109 -f 109//109 121//121 122//122 -f 109//109 122//122 123//123 -f 123//123 124//124 109//109 -f 109//109 124//124 125//125 -f 109//109 125//125 107//107 -f 107//107 125//125 110//110 -f 107//107 110//110 126//126 -f 126//126 110//110 112//112 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 124//124 131//131 125//125 -f 125//125 131//131 132//132 -f 125//125 132//132 133//133 -f 133//133 132//132 128//128 -f 133//133 128//128 134//134 -f 134//134 128//128 127//127 -f 119//119 135//135 117//117 -f 117//117 135//135 136//136 -f 117//117 136//136 120//120 -f 120//120 136//136 137//137 -f 138//138 128//128 139//139 -f 139//139 128//128 140//140 -f 113//113 115//115 138//138 -f 138//138 115//115 141//141 -f 138//138 141//141 128//128 -f 128//128 141//141 142//142 -f 128//128 142//142 130//130 -f 128//128 143//143 140//140 -f 140//140 143//143 144//144 -f 140//140 144//144 145//145 -f 145//145 144//144 146//146 -f 145//145 146//146 137//137 -f 137//137 146//146 147//147 -f 137//137 147//147 120//120 -f 104//104 35//35 106//106 -f 106//106 35//35 33//33 -f 148//148 31//31 149//149 -f 149//149 31//31 30//30 -f 96//96 150//150 94//94 -f 94//94 150//150 151//151 -f 90//90 152//152 91//91 -f 91//91 152//152 153//153 -f 85//85 154//154 86//86 -f 86//86 154//154 155//155 -f 89//89 156//156 88//88 -f 88//88 156//156 157//157 -f 77//77 158//158 78//78 -f 78//78 158//158 159//159 -f 81//81 160//160 80//80 -f 80//80 160//160 161//161 -f 63//63 162//162 64//64 -f 64//64 162//162 163//163 -f 73//73 164//164 72//72 -f 72//72 164//164 165//165 -f 65//65 166//166 66//66 -f 66//66 166//166 167//167 -f 57//57 168//168 58//58 -f 58//58 168//168 169//169 -f 101//101 37//37 102//102 -f 102//102 37//37 36//36 -f 170//170 171//171 172//172 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 23//23 28//28 22//22 -f 22//22 28//28 29//29 -f 22//22 29//29 177//177 -f 171//171 170//170 178//178 -f 178//178 170//170 179//179 -f 178//178 179//179 180//180 -f 176//176 181//181 175//175 -f 175//175 181//181 182//182 -f 175//175 182//182 183//183 -f 184//184 29//29 172//172 -f 172//172 29//29 185//185 -f 172//172 185//185 170//170 -f 184//184 186//186 29//29 -f 29//29 186//186 187//187 -f 29//29 187//187 177//177 -f 177//177 187//187 188//188 -f 177//177 188//188 189//189 -f 177//177 190//190 22//22 -f 22//22 190//190 191//191 -f 22//22 191//191 173//173 -f 173//173 191//191 192//192 -f 173//173 192//192 174//174 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 197//197 196//196 198//198 -f 199//199 200//200 201//201 -f 201//201 200//200 175//175 -f 201//201 175//175 198//198 -f 198//198 175//175 183//183 -f 198//198 183//183 197//197 -f 199//199 202//202 200//200 -f 200//200 202//202 203//203 -f 200//200 203//203 204//204 -f 204//204 203//203 205//205 -f 204//204 205//205 206//206 -f 207//207 208//208 209//209 -f 179//179 210//210 211//211 -f 206//206 212//212 204//204 -f 204//204 212//212 213//213 -f 204//204 213//213 214//214 -f 214//214 213//213 215//215 -f 210//210 179//179 216//216 -f 216//216 179//179 217//217 -f 216//216 217//217 218//218 -f 219//219 220//220 189//189 -f 189//189 220//220 215//215 -f 189//189 215//215 195//195 -f 195//195 215//215 213//213 -f 195//195 213//213 193//193 -f 211//211 221//221 179//179 -f 179//179 221//221 222//222 -f 179//179 222//222 180//180 -f 180//180 222//222 223//223 -f 209//209 224//224 207//207 -f 207//207 224//224 225//225 -f 207//207 225//225 188//188 -f 225//225 226//226 188//188 -f 188//188 226//226 227//227 -f 188//188 227//227 189//189 -f 189//189 227//227 228//228 -f 189//189 228//228 219//219 -f 229//229 230//230 231//231 -f 231//231 230//230 232//232 -f 231//231 232//232 217//217 -f 217//217 232//232 233//233 -f 217//217 233//233 218//218 -f 234//234 235//235 223//223 -f 223//223 235//235 236//236 -f 223//223 236//236 180//180 -f 234//234 229//229 235//235 -f 235//235 229//229 231//231 -f 235//235 231//231 208//208 -f 208//208 231//231 237//237 -f 208//208 237//237 209//209 -f 238//238 239//239 42//42 -f 42//42 239//239 38//38 -f 13//13 148//148 14//14 -f 14//14 148//148 149//149 -f 240//240 241//241 239//239 -f 242//242 243//243 239//239 -f 244//244 163//163 162//162 -f 245//245 246//246 247//247 -f 248//248 249//249 239//239 -f 250//250 239//239 251//251 -f 251//251 239//239 243//243 -f 251//251 243//243 252//252 -f 252//252 243//243 253//253 -f 254//254 238//238 247//247 -f 247//247 238//238 255//255 -f 247//247 255//255 245//245 -f 256//256 257//257 250//250 -f 250//250 257//257 258//258 -f 250//250 258//258 239//239 -f 239//239 258//258 259//259 -f 239//239 259//259 240//240 -f 240//240 259//259 260//260 -f 240//240 260//260 261//261 -f 153//153 152//152 262//262 -f 262//262 152//152 263//263 -f 264//264 239//239 265//265 -f 265//265 239//239 249//249 -f 265//265 249//249 164//164 -f 164//164 249//249 165//165 -f 266//266 267//267 268//268 -f 269//269 239//239 270//270 -f 270//270 239//239 271//271 -f 270//270 271//271 154//154 -f 154//154 271//271 155//155 -f 272//272 159//159 158//158 -f 167//167 166//166 264//264 -f 264//264 166//166 273//273 -f 264//264 273//273 239//239 -f 239//239 273//273 274//274 -f 151//151 150//150 254//254 -f 254//254 150//150 275//275 -f 254//254 275//275 238//238 -f 238//238 275//275 262//262 -f 238//238 262//262 239//239 -f 239//239 262//262 263//263 -f 239//239 263//263 271//271 -f 268//268 242//242 266//266 -f 266//266 242//242 239//239 -f 266//266 239//239 276//276 -f 276//276 239//239 274//274 -f 276//276 274//274 168//168 -f 168//168 274//274 169//169 -f 277//277 278//278 239//239 -f 162//162 248//248 244//244 -f 244//244 248//248 239//239 -f 244//244 239//239 279//279 -f 279//279 239//239 278//278 -f 279//279 278//278 160//160 -f 160//160 278//278 161//161 -f 157//157 156//156 269//269 -f 269//269 156//156 280//280 -f 269//269 280//280 239//239 -f 239//239 280//280 272//272 -f 239//239 272//272 277//277 -f 277//277 272//272 158//158 -f 56//56 276//276 57//57 -f 57//57 276//276 168//168 -f 59//59 266//266 56//56 -f 56//56 266//266 276//276 -f 274//274 54//54 169//169 -f 169//169 54//54 58//58 -f 55//55 273//273 65//65 -f 65//65 273//273 166//166 -f 55//55 54//54 273//273 -f 273//273 54//54 274//274 -f 264//264 67//67 167//167 -f 167//167 67//67 66//66 -f 68//68 265//265 73//73 -f 73//73 265//265 164//164 -f 68//68 67//67 265//265 -f 265//265 67//67 264//264 -f 249//249 71//71 165//165 -f 165//165 71//71 72//72 -f 62//62 248//248 63//63 -f 63//63 248//248 162//162 -f 62//62 71//71 248//248 -f 248//248 71//71 249//249 -f 244//244 69//69 163//163 -f 163//163 69//69 64//64 -f 70//70 279//279 81//81 -f 81//81 279//279 160//160 -f 70//70 69//69 279//279 -f 279//279 69//69 244//244 -f 278//278 79//79 161//161 -f 161//161 79//79 80//80 -f 76//76 277//277 77//77 -f 77//77 277//277 158//158 -f 76//76 79//79 277//277 -f 277//277 79//79 278//278 -f 272//272 74//74 159//159 -f 159//159 74//74 78//78 -f 75//75 280//280 89//89 -f 89//89 280//280 156//156 -f 75//75 74//74 280//280 -f 280//280 74//74 272//272 -f 269//269 87//87 157//157 -f 157//157 87//87 88//88 -f 84//84 270//270 85//85 -f 85//85 270//270 154//154 -f 84//84 87//87 270//270 -f 270//270 87//87 269//269 -f 271//271 82//82 155//155 -f 155//155 82//82 86//86 -f 83//83 263//263 90//90 -f 90//90 263//263 152//152 -f 83//83 82//82 263//263 -f 263//263 82//82 271//271 -f 262//262 92//92 153//153 -f 153//153 92//92 91//91 -f 97//97 275//275 96//96 -f 96//96 275//275 150//150 -f 97//97 92//92 275//275 -f 275//275 92//92 262//262 -f 254//254 95//95 151//151 -f 151//151 95//95 94//94 -f 99//99 247//247 100//100 -f 100//100 247//247 246//246 -f 100//100 246//246 15//15 -f 15//15 246//246 7//7 -f 15//15 7//7 13//13 -f 13//13 7//7 6//6 -f 13//13 6//6 148//148 -f 148//148 6//6 31//31 -f 99//99 95//95 247//247 -f 247//247 95//95 254//254 -f 149//149 30//30 14//14 -f 14//14 30//30 4//4 -f 14//14 4//4 10//10 -f 10//10 4//4 3//3 -f 35//35 104//104 34//34 -f 34//34 104//104 103//103 -f 34//34 103//103 281//281 -f 281//281 103//103 282//282 -f 10//10 3//3 11//11 -f 11//11 3//3 2//2 -f 11//11 2//2 282//282 -f 282//282 2//2 281//281 -f 106//106 33//33 105//105 -f 105//105 33//33 32//32 -f 105//105 32//32 19//19 -f 19//19 32//32 21//21 -f 37//37 101//101 27//27 -f 27//27 101//101 24//24 -f 27//27 24//24 20//20 -f 20//20 24//24 18//18 -f 102//102 36//36 25//25 -f 25//25 36//36 26//26 -f 25//25 26//26 23//23 -f 23//23 26//26 28//28 -f 283//283 284//284 285//285 -f 286//286 287//287 288//288 -f 289//289 290//290 291//291 -f 291//291 290//290 292//292 -f 288//288 293//293 286//286 -f 286//286 293//293 294//294 -f 286//286 294//294 295//295 -f 283//283 296//296 297//297 -f 298//298 299//299 283//283 -f 283//283 299//299 300//300 -f 292//292 290//290 285//285 -f 285//285 290//290 286//286 -f 285//285 286//286 283//283 -f 283//283 286//286 295//295 -f 283//283 295//295 296//296 -f 301//301 302//302 303//303 -f 303//303 302//302 283//283 -f 303//303 283//283 304//304 -f 304//304 283//283 300//300 -f 301//301 305//305 302//302 -f 302//302 305//305 306//306 -f 302//302 306//306 307//307 -f 307//307 306//306 308//308 -f 307//307 308//308 309//309 -f 297//297 310//310 283//283 -f 283//283 310//310 311//311 -f 283//283 311//311 298//298 -f 298//298 311//311 312//312 -f 298//298 312//312 313//313 -f 313//313 312//312 314//314 -f 313//313 314//314 315//315 -f 309//309 316//316 307//307 -f 307//307 316//316 313//313 -f 307//307 313//313 317//317 -f 317//317 313//313 315//315 -f 317//317 315//315 318//318 -f 318//318 315//315 287//287 -f 318//318 287//287 319//319 -f 320//320 321//321 286//286 -f 286//286 321//321 322//322 -f 286//286 322//322 287//287 -f 287//287 322//322 323//323 -f 287//287 323//323 319//319 -f 324//324 325//325 326//326 -f 326//326 325//325 327//327 -f 326//326 327//327 328//328 -f 238//238 42//42 255//255 -f 255//255 42//42 93//93 -f 255//255 93//93 245//245 -f 245//245 93//93 98//98 -f 245//245 98//98 329//329 -f 329//329 98//98 330//330 -f 329//329 330//330 331//331 -f 331//331 330//330 332//332 -f 331//331 332//332 327//327 -f 327//327 332//332 333//333 -f 327//327 333//333 328//328 -f 334//334 335//335 336//336 -f 324//324 326//326 336//336 -f 336//336 326//326 337//337 -f 336//336 337//337 334//334 -f 282//282 103//103 19//19 -f 19//19 103//103 105//105 -f 100//100 15//15 16//16 -f 338//338 339//339 133//133 -f 133//133 339//339 340//340 -f 133//133 340//340 125//125 -f 341//341 342//342 334//334 -f 334//334 342//342 343//343 -f 342//342 344//344 343//343 -f 343//343 344//344 345//345 -f 343//343 345//345 133//133 -f 133//133 345//345 346//346 -f 133//133 346//346 338//338 -f 328//328 347//347 326//326 -f 326//326 347//347 341//341 -f 326//326 341//341 337//337 -f 337//337 341//341 334//334 -f 98//98 100//100 330//330 -f 330//330 100//100 16//16 -f 330//330 16//16 332//332 -f 332//332 16//16 17//17 -f 332//332 17//17 333//333 -f 333//333 17//17 348//348 -f 333//333 348//348 328//328 -f 328//328 348//348 349//349 -f 328//328 349//349 347//347 -f 7//7 246//246 5//5 -f 5//5 246//246 245//245 -f 5//5 245//245 8//8 -f 350//350 351//351 331//331 -f 245//245 329//329 8//8 -f 8//8 329//329 331//331 -f 8//8 331//331 9//9 -f 9//9 331//331 351//351 -f 331//331 327//327 350//350 -f 350//350 327//327 325//325 -f 350//350 325//325 352//352 -f 352//352 325//325 353//353 -f 354//354 355//355 356//356 -f 353//353 325//325 357//357 -f 357//357 325//325 324//324 -f 357//357 324//324 358//358 -f 358//358 324//324 336//336 -f 358//358 336//336 355//355 -f 355//355 336//336 335//335 -f 355//355 335//335 356//356 -f 359//359 320//320 360//360 -f 360//360 320//320 286//286 -f 359//359 361//361 320//320 -f 320//320 361//361 362//362 -f 320//320 362//362 356//356 -f 356//356 362//362 363//363 -f 356//356 363//363 354//354 -f 34//34 281//281 32//32 -f 32//32 281//281 21//21 -f 214//214 141//141 204//204 -f 204//204 141//141 115//115 -f 317//317 231//231 307//307 -f 307//307 231//231 217//217 -f 226//226 321//321 320//320 -f 134//134 227//227 133//133 -f 133//133 227//227 343//343 -f 320//320 356//356 226//226 -f 226//226 356//356 335//335 -f 226//226 335//335 227//227 -f 227//227 335//335 334//334 -f 227//227 334//334 343//343 -f 231//231 317//317 237//237 -f 237//237 317//317 318//318 -f 237//237 318//318 209//209 -f 209//209 318//318 319//319 -f 209//209 319//319 224//224 -f 224//224 319//319 323//323 -f 224//224 323//323 225//225 -f 225//225 323//323 322//322 -f 225//225 322//322 226//226 -f 226//226 322//322 321//321 -f 227//227 134//134 228//228 -f 228//228 134//134 127//127 -f 228//228 127//127 219//219 -f 219//219 127//127 129//129 -f 219//219 129//129 220//220 -f 220//220 129//129 130//130 -f 220//220 130//130 215//215 -f 215//215 130//130 142//142 -f 215//215 142//142 214//214 -f 214//214 142//142 141//141 -f 178//178 311//311 171//171 -f 171//171 311//311 310//310 -f 171//171 310//310 172//172 -f 172//172 310//310 297//297 -f 172//172 297//297 184//184 -f 184//184 297//297 296//296 -f 184//184 296//296 186//186 -f 186//186 296//296 295//295 -f 186//186 295//295 187//187 -f 187//187 295//295 294//294 -f 187//187 294//294 188//188 -f 188//188 294//294 293//293 -f 188//188 293//293 207//207 -f 207//207 293//293 288//288 -f 207//207 288//288 208//208 -f 208//208 288//288 287//287 -f 208//208 287//287 235//235 -f 235//235 287//287 315//315 -f 235//235 315//315 236//236 -f 236//236 315//315 314//314 -f 236//236 314//314 180//180 -f 180//180 314//314 312//312 -f 180//180 312//312 178//178 -f 178//178 312//312 311//311 -f 221//221 301//301 222//222 -f 222//222 301//301 303//303 -f 222//222 303//303 223//223 -f 223//223 303//303 304//304 -f 223//223 304//304 234//234 -f 234//234 304//304 300//300 -f 234//234 300//300 229//229 -f 229//229 300//300 299//299 -f 229//229 299//299 230//230 -f 230//230 299//299 298//298 -f 230//230 298//298 232//232 -f 232//232 298//298 313//313 -f 232//232 313//313 233//233 -f 233//233 313//313 316//316 -f 233//233 316//316 218//218 -f 218//218 316//316 309//309 -f 218//218 309//309 216//216 -f 216//216 309//309 308//308 -f 216//216 308//308 210//210 -f 210//210 308//308 306//306 -f 210//210 306//306 211//211 -f 211//211 306//306 305//305 -f 211//211 305//305 221//221 -f 221//221 305//305 301//301 -f 213//213 138//138 193//193 -f 193//193 138//138 139//139 -f 193//193 139//139 194//194 -f 194//194 139//139 140//140 -f 194//194 140//140 196//196 -f 196//196 140//140 145//145 -f 196//196 145//145 198//198 -f 198//198 145//145 137//137 -f 198//198 137//137 201//201 -f 201//201 137//137 136//136 -f 201//201 136//136 199//199 -f 199//199 136//136 135//135 -f 199//199 135//135 202//202 -f 202//202 135//135 119//119 -f 202//202 119//119 203//203 -f 203//203 119//119 118//118 -f 203//203 118//118 205//205 -f 205//205 118//118 116//116 -f 205//205 116//116 206//206 -f 206//206 116//116 114//114 -f 206//206 114//114 212//212 -f 212//212 114//114 113//113 -f 212//212 113//113 213//213 -f 213//213 113//113 138//138 -f 191//191 128//128 192//192 -f 192//192 128//128 132//132 -f 192//192 132//132 174//174 -f 174//174 132//132 131//131 -f 174//174 131//131 176//176 -f 176//176 131//131 124//124 -f 176//176 124//124 181//181 -f 181//181 124//124 123//123 -f 181//181 123//123 182//182 -f 182//182 123//123 122//122 -f 182//182 122//122 183//183 -f 183//183 122//122 121//121 -f 183//183 121//121 197//197 -f 197//197 121//121 120//120 -f 197//197 120//120 195//195 -f 195//195 120//120 147//147 -f 195//195 147//147 189//189 -f 189//189 147//147 146//146 -f 189//189 146//146 177//177 -f 177//177 146//146 144//144 -f 177//177 144//144 190//190 -f 190//190 144//144 143//143 -f 190//190 143//143 191//191 -f 191//191 143//143 128//128 -f 59//59 60//60 266//266 -f 266//266 60//60 267//267 -f 60//60 61//61 267//267 -f 267//267 61//61 268//268 -f 61//61 41//41 268//268 -f 268//268 41//41 242//242 -f 41//41 43//43 242//242 -f 242//242 43//43 243//243 -f 43//43 45//45 243//243 -f 243//243 45//45 253//253 -f 45//45 46//46 253//253 -f 253//253 46//46 252//252 -f 46//46 44//44 252//252 -f 252//252 44//44 251//251 -f 44//44 50//50 251//251 -f 251//251 50//50 250//250 -f 50//50 48//48 250//250 -f 250//250 48//48 256//256 -f 48//48 47//47 256//256 -f 256//256 47//47 257//257 -f 47//47 49//49 257//257 -f 257//257 49//49 258//258 -f 49//49 53//53 258//258 -f 258//258 53//53 259//259 -f 53//53 52//52 259//259 -f 259//259 52//52 260//260 -f 52//52 51//51 260//260 -f 260//260 51//51 261//261 -f 51//51 40//40 261//261 -f 261//261 40//40 240//240 -f 40//40 39//39 240//240 -f 240//240 39//39 241//241 -f 39//39 38//38 241//241 -f 241//241 38//38 239//239 -f 11//11 282//282 364//364 -f 364//364 282//282 365//365 -f 18//18 22//22 173//173 -f 18//18 173//173 19//19 -f 365//365 282//282 366//366 -f 366//366 282//282 19//19 -f 366//366 19//19 367//367 -f 367//367 19//19 173//173 -f 367//367 173//173 368//368 -f 369//369 370//370 173//173 -f 173//173 370//370 371//371 -f 173//173 371//371 372//372 -f 372//372 373//373 173//173 -f 173//173 373//373 374//374 -f 173//173 374//374 368//368 -f 175//175 109//109 173//173 -f 173//173 109//109 108//108 -f 173//173 108//108 369//369 -f 2//2 375//375 281//281 -f 281//281 375//375 376//376 -f 281//281 376//376 21//21 -f 185//185 29//29 20//20 -f 376//376 377//377 21//21 -f 21//21 377//377 378//378 -f 21//21 378//378 20//20 -f 20//20 378//378 379//379 -f 20//20 379//379 185//185 -f 379//379 380//380 185//185 -f 185//185 380//380 381//381 -f 381//381 382//382 185//185 -f 185//185 382//382 383//383 -f 185//185 383//383 384//384 -f 283//283 170//170 284//284 -f 284//284 170//170 185//185 -f 284//284 185//185 385//385 -f 385//385 185//185 384//384 -f 369//369 108//108 107//107 -f 17//17 12//12 386//386 -f 367//367 368//368 374//374 -f 365//365 386//386 364//364 -f 364//364 386//386 12//12 -f 364//364 12//12 11//11 -f 374//374 387//387 367//367 -f 367//367 387//387 386//386 -f 367//367 386//386 366//366 -f 366//366 386//386 365//365 -f 17//17 388//388 348//348 -f 348//348 388//388 349//349 -f 349//349 388//388 347//347 -f 347//347 388//388 389//389 -f 347//347 389//389 341//341 -f 390//390 391//391 392//392 -f 341//341 393//393 342//342 -f 342//342 393//393 390//390 -f 342//342 390//390 344//344 -f 344//344 390//390 392//392 -f 344//344 392//392 345//345 -f 345//345 392//392 346//346 -f 110//110 125//125 340//340 -f 340//340 339//339 110//110 -f 110//110 339//339 338//338 -f 110//110 338//338 111//111 -f 374//374 373//373 387//387 -f 387//387 373//373 372//372 -f 387//387 372//372 394//394 -f 394//394 372//372 371//371 -f 394//394 371//371 395//395 -f 395//395 371//371 370//370 -f 341//341 389//389 393//393 -f 393//393 389//389 396//396 -f 393//393 396//396 390//390 -f 390//390 396//396 397//397 -f 390//390 397//397 391//391 -f 17//17 386//386 388//388 -f 388//388 386//386 387//387 -f 388//388 387//387 389//389 -f 389//389 387//387 394//394 -f 389//389 394//394 396//396 -f 396//396 394//394 395//395 -f 396//396 395//395 397//397 -f 370//370 369//369 395//395 -f 395//395 369//369 107//107 -f 395//395 107//107 397//397 -f 397//397 107//107 126//126 -f 397//397 126//126 391//391 -f 391//391 126//126 112//112 -f 391//391 112//112 392//392 -f 392//392 112//112 111//111 -f 392//392 111//111 346//346 -f 346//346 111//111 338//338 -f 353//353 398//398 399//399 -f 360//360 286//286 290//290 -f 385//385 384//384 400//400 -f 383//383 382//382 401//401 -f 381//381 380//380 402//402 -f 378//378 377//377 403//403 -f 403//403 377//377 376//376 -f 403//403 376//376 375//375 -f 360//360 290//290 359//359 -f 359//359 290//290 361//361 -f 361//361 290//290 289//289 -f 361//361 289//289 362//362 -f 363//363 404//404 354//354 -f 354//354 404//404 405//405 -f 354//354 405//405 355//355 -f 357//357 358//358 406//406 -f 353//353 399//399 352//352 -f 407//407 351//351 350//350 -f 351//351 407//407 9//9 -f 9//9 407//407 403//403 -f 9//9 403//403 1//1 -f 1//1 403//403 375//375 -f 1//1 375//375 2//2 -f 350//350 352//352 407//407 -f 407//407 352//352 399//399 -f 407//407 399//399 403//403 -f 403//403 399//399 402//402 -f 403//403 402//402 378//378 -f 378//378 402//402 380//380 -f 378//378 380//380 379//379 -f 353//353 357//357 398//398 -f 398//398 357//357 406//406 -f 398//398 406//406 399//399 -f 399//399 406//406 408//408 -f 399//399 408//408 402//402 -f 402//402 408//408 401//401 -f 402//402 401//401 381//381 -f 381//381 401//401 382//382 -f 358//358 355//355 406//406 -f 406//406 355//355 405//405 -f 406//406 405//405 408//408 -f 408//408 405//405 409//409 -f 408//408 409//409 401//401 -f 401//401 409//409 400//400 -f 401//401 400//400 383//383 -f 383//383 400//400 384//384 -f 363//363 362//362 404//404 -f 404//404 362//362 289//289 -f 404//404 289//289 405//405 -f 405//405 289//289 291//291 -f 405//405 291//291 409//409 -f 409//409 291//291 292//292 -f 409//409 292//292 400//400 -f 400//400 292//292 285//285 -f 400//400 285//285 385//385 -f 385//385 285//285 284//284 -f 109//109 175//175 117//117 -f 117//117 175//175 200//200 -f 170//170 283//283 179//179 -f 179//179 283//283 302//302 -f 179//179 302//302 217//217 -f 217//217 302//302 307//307 -f 117//117 200//200 115//115 -f 115//115 200//200 204//204 -# 830 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_motor.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_motor.obj deleted file mode 100644 index 5ad2df5de..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_motor.obj +++ /dev/null @@ -1,105868 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object T_BOT_NOVE_SISE_I_LETVA2022 - motor sa kucistem-1 LSS-Public prirubnica-1.obj -# -# Vertices: 26495 -# Faces: 52862 -# -#### -vn 0.000002 -3.665193 -3.034545 -v 0.045700 -0.006910 0.102100 -vn 0.000003 3.665193 -3.034545 -v 0.045700 -0.006510 0.102100 -vn -1.517273 -3.665191 -2.627994 -v 0.046250 -0.006910 0.101953 -vn -1.517273 3.665192 -2.627994 -v 0.046250 -0.006510 0.101953 -vn -2.627996 -3.665198 -1.517263 -v 0.046653 -0.006910 0.101550 -vn -2.627996 3.665198 -1.517263 -v 0.046653 -0.006510 0.101550 -vn -3.034549 -3.665182 0.000005 -v 0.046800 -0.006910 0.101000 -vn -3.034549 3.665182 0.000005 -v 0.046800 -0.006510 0.101000 -vn -2.627995 -3.665195 1.517268 -v 0.046653 -0.006910 0.100450 -vn -2.627995 3.665195 1.517268 -v 0.046653 -0.006510 0.100450 -vn -1.517273 -3.665192 2.627994 -v 0.046250 -0.006910 0.100047 -vn -1.517273 3.665191 2.627994 -v 0.046250 -0.006510 0.100047 -vn 0.000003 -3.665193 3.034545 -v 0.045700 -0.006910 0.099900 -vn 0.000002 3.665193 3.034545 -v 0.045700 -0.006510 0.099900 -vn 0.000002 -3.665193 -3.034545 -v 0.045700 -0.006910 0.083200 -vn 0.000003 3.665193 -3.034545 -v 0.045700 -0.006510 0.083200 -vn -1.517273 -3.665191 -2.627994 -v 0.046250 -0.006910 0.083053 -vn -1.517273 3.665191 -2.627994 -v 0.046250 -0.006510 0.083053 -vn -2.627996 -3.665198 -1.517263 -v 0.046653 -0.006910 0.082650 -vn -2.627996 3.665198 -1.517263 -v 0.046653 -0.006510 0.082650 -vn -3.034551 -3.665179 0.000000 -v 0.046800 -0.006910 0.082100 -vn -3.034551 3.665178 -0.000000 -v 0.046800 -0.006510 0.082100 -vn -2.627986 -3.665207 1.517273 -v 0.046653 -0.006910 0.081550 -vn -2.627986 3.665207 1.517273 -v 0.046653 -0.006510 0.081550 -vn -1.517262 -3.665182 2.628004 -v 0.046250 -0.006910 0.081147 -vn -1.517262 3.665183 2.628004 -v 0.046250 -0.006510 0.081147 -vn 0.000003 -3.665193 3.034545 -v 0.045700 -0.006910 0.081000 -vn 0.000002 3.665193 3.034545 -v 0.045700 -0.006510 0.081000 -vn 0.000001 2.692787 -3.062824 -v 0.036250 -0.011260 0.094650 -vn 0.000001 3.590398 -3.062824 -v 0.036250 -0.004910 0.094650 -vn -1.328916 2.692796 -2.759509 -v 0.037595 -0.011260 0.094343 -vn -1.328916 3.590389 -2.759510 -v 0.037595 -0.004910 0.094343 -vn -2.394615 2.692794 -1.909640 -v 0.038674 -0.011260 0.093483 -vn -2.394615 3.590391 -1.909640 -v 0.038674 -0.004910 0.093483 -vn -2.986035 2.692794 -0.681543 -v 0.039272 -0.011260 0.092240 -vn -2.986035 3.590391 -0.681543 -v 0.039272 -0.004910 0.092240 -vn -2.986035 2.692794 0.681543 -v 0.039272 -0.011260 0.090860 -vn -2.986035 3.590392 0.681543 -v 0.039272 -0.004910 0.090860 -vn -2.394615 2.692794 1.909640 -v 0.038674 -0.011260 0.089617 -vn -2.394615 3.590391 1.909640 -v 0.038674 -0.004910 0.089617 -vn -1.328908 2.692791 2.759511 -v 0.037595 -0.011260 0.088757 -vn -1.328908 3.590395 2.759511 -v 0.037595 -0.004910 0.088757 -vn 0.000001 2.692798 3.062828 -v 0.036250 -0.011260 0.088450 -vn 0.000001 3.590387 3.062828 -v 0.036250 -0.004910 0.088450 -vn -0.000000 2.792532 -3.093866 -v 0.010850 -0.005410 0.096550 -vn 0.000000 3.490654 -3.093866 -v 0.010850 -0.004910 0.096550 -vn -1.058163 2.792522 -2.907280 -v 0.012560 -0.005410 0.096248 -vn -1.058163 3.490663 -2.907281 -v 0.012560 -0.004910 0.096248 -vn -1.988700 2.792530 -2.370037 -v 0.014064 -0.005410 0.095380 -vn -1.988700 3.490656 -2.370037 -v 0.014064 -0.004910 0.095380 -vn -2.679364 2.792527 -1.546934 -v 0.015180 -0.005410 0.094050 -vn -2.679364 3.490659 -1.546934 -v 0.015180 -0.004910 0.094050 -vn -3.046862 2.792526 -0.537245 -v 0.015774 -0.005410 0.092418 -vn -3.046862 3.490659 -0.537245 -v 0.015774 -0.004910 0.092418 -vn -3.046862 2.792526 0.537245 -v 0.015774 -0.005410 0.090682 -vn -3.046861 3.490659 0.537245 -v 0.015774 -0.004910 0.090682 -vn -2.679364 2.792527 1.546934 -v 0.015180 -0.005410 0.089050 -vn -2.679364 3.490659 1.546934 -v 0.015180 -0.004910 0.089050 -vn -1.988695 2.792526 2.370040 -v 0.014064 -0.005410 0.087720 -vn -1.988695 3.490659 2.370040 -v 0.014064 -0.004910 0.087720 -vn -1.058165 2.792530 2.907283 -v 0.012560 -0.005410 0.086852 -vn -1.058165 3.490655 2.907283 -v 0.012560 -0.004910 0.086852 -vn 0.000000 2.792523 3.093864 -v 0.010850 -0.005410 0.086550 -vn -0.000000 3.490662 3.093864 -v 0.010850 -0.004910 0.086550 -vn 0.000000 -3.665193 -3.034545 -v 0.019181 -0.005310 0.092650 -vn -0.000000 3.665193 -3.034545 -v 0.019181 -0.004910 0.092650 -vn -1.517266 -3.665184 -2.628001 -v 0.019731 -0.005310 0.092503 -vn -1.517266 3.665184 -2.628001 -v 0.019731 -0.004910 0.092503 -vn -2.627986 -3.665198 -1.517280 -v 0.020134 -0.005310 0.092100 -vn -2.627986 3.665199 -1.517280 -v 0.020134 -0.004910 0.092100 -vn -3.034545 -3.665191 0.000000 -v 0.020281 -0.005310 0.091550 -vn -3.034545 3.665191 0.000000 -v 0.020281 -0.004910 0.091550 -vn -2.627996 -3.665189 1.517270 -v 0.020134 -0.005310 0.091000 -vn -2.627996 3.665189 1.517270 -v 0.020134 -0.004910 0.091000 -vn -1.517277 -3.665193 2.627991 -v 0.019731 -0.005310 0.090597 -vn -1.517277 3.665193 2.627991 -v 0.019731 -0.004910 0.090597 -vn -0.000000 -3.665193 3.034545 -v 0.019181 -0.005310 0.090450 -vn 0.000000 3.665193 3.034545 -v 0.019181 -0.004910 0.090450 -vn 0.000000 -3.665193 -3.034545 -v 0.010850 -0.005310 0.084319 -vn -0.000000 3.665193 -3.034545 -v 0.010850 -0.004910 0.084319 -vn -1.517277 -3.665193 -2.627991 -v 0.011400 -0.005310 0.084171 -vn -1.517277 3.665193 -2.627991 -v 0.011400 -0.004910 0.084171 -vn -2.627996 -3.665189 -1.517270 -v 0.011803 -0.005310 0.083769 -vn -2.627996 3.665189 -1.517270 -v 0.011803 -0.004910 0.083769 -vn -3.034545 -3.665191 0.000000 -v 0.011950 -0.005310 0.083219 -vn -3.034545 3.665191 0.000000 -v 0.011950 -0.004910 0.083219 -vn -2.627996 -3.665189 1.517270 -v 0.011803 -0.005310 0.082669 -vn -2.627996 3.665189 1.517270 -v 0.011803 -0.004910 0.082669 -vn -1.517257 -3.665205 2.627996 -v 0.011400 -0.005310 0.082266 -vn -1.517257 3.665206 2.627996 -v 0.011400 -0.004910 0.082266 -vn 0.000000 -3.665168 3.034555 -v 0.010850 -0.005310 0.082119 -vn -0.000000 3.665168 3.034555 -v 0.010850 -0.004910 0.082119 -vn 0.000003 -3.665193 -3.034545 -v 0.002519 -0.005310 0.092650 -vn 0.000003 3.665193 -3.034545 -v 0.002519 -0.004910 0.092650 -vn -1.517262 -3.665182 -2.628004 -v 0.003069 -0.005310 0.092503 -vn -1.517262 3.665182 -2.628004 -v 0.003069 -0.004910 0.092503 -vn -2.627986 -3.665207 -1.517273 -v 0.003471 -0.005310 0.092100 -vn -2.627986 3.665207 -1.517273 -v 0.003471 -0.004910 0.092100 -vn -3.034551 -3.665178 0.000000 -v 0.003619 -0.005310 0.091550 -vn -3.034551 3.665179 -0.000000 -v 0.003619 -0.004910 0.091550 -vn -2.627996 -3.665198 1.517263 -v 0.003471 -0.005310 0.091000 -vn -2.627996 3.665198 1.517263 -v 0.003471 -0.004910 0.091000 -vn -1.517273 -3.665192 2.627994 -v 0.003069 -0.005310 0.090597 -vn -1.517273 3.665192 2.627994 -v 0.003069 -0.004910 0.090597 -vn 0.000003 -3.665193 3.034545 -v 0.002519 -0.005310 0.090450 -vn 0.000003 3.665193 3.034545 -v 0.002519 -0.004910 0.090450 -vn 0.000000 -3.665193 -3.034545 -v 0.010850 -0.005310 0.100981 -vn -0.000000 3.665193 -3.034545 -v 0.010850 -0.004910 0.100981 -vn -1.517277 -3.665193 -2.627991 -v 0.011400 -0.005310 0.100834 -vn -1.517277 3.665193 -2.627991 -v 0.011400 -0.004910 0.100834 -vn -2.627995 -3.665186 -1.517275 -v 0.011803 -0.005310 0.100431 -vn -2.627995 3.665186 -1.517275 -v 0.011803 -0.004910 0.100431 -vn -3.034544 -3.665195 -0.000005 -v 0.011950 -0.005310 0.099881 -vn -3.034544 3.665195 -0.000005 -v 0.011950 -0.004910 0.099881 -vn -2.627996 -3.665189 1.517270 -v 0.011803 -0.005310 0.099331 -vn -2.627996 3.665189 1.517270 -v 0.011803 -0.004910 0.099331 -vn -1.517277 -3.665193 2.627991 -v 0.011400 -0.005310 0.098929 -vn -1.517277 3.665193 2.627991 -v 0.011400 -0.004910 0.098929 -vn -0.000000 -3.665193 3.034545 -v 0.010850 -0.005310 0.098781 -vn 0.000000 3.665193 3.034545 -v 0.010850 -0.004910 0.098781 -vn -0.000000 -3.665193 -3.034545 -v 0.020300 -0.006910 0.102100 -vn 0.000000 3.665193 -3.034545 -v 0.020300 -0.006510 0.102100 -vn -1.517277 -3.665193 -2.627990 -v 0.020850 -0.006910 0.101953 -vn -1.517277 3.665193 -2.627991 -v 0.020850 -0.006510 0.101953 -vn -2.627996 -3.665189 -1.517270 -v 0.021253 -0.006910 0.101550 -vn -2.627996 3.665189 -1.517270 -v 0.021253 -0.006510 0.101550 -vn -3.034544 -3.665195 0.000005 -v 0.021400 -0.006910 0.101000 -vn -3.034544 3.665207 0.000005 -v 0.021400 -0.006510 0.101000 -vn -2.627995 -3.665186 1.517275 -v 0.021253 -0.006910 0.100450 -vn -2.627995 3.665186 1.517275 -v 0.021253 -0.006510 0.100450 -vn -1.517277 -3.665193 2.627991 -v 0.020850 -0.006910 0.100047 -vn -1.517276 3.665193 2.627990 -v 0.020850 -0.006510 0.100047 -vn 0.000000 -3.665193 3.034545 -v 0.020300 -0.006910 0.099900 -vn -0.000000 3.665193 3.034545 -v 0.020300 -0.006510 0.099900 -vn -0.000000 -3.665193 -3.034545 -v 0.026800 -0.006910 0.102100 -vn 0.000000 3.665194 -3.034545 -v 0.026800 -0.006510 0.102100 -vn -1.517277 -3.665193 -2.627990 -v 0.027350 -0.006910 0.101953 -vn -1.517277 3.665194 -2.627991 -v 0.027350 -0.006510 0.101953 -vn -2.627996 -3.665189 -1.517270 -v 0.027753 -0.006910 0.101550 -vn -2.627996 3.665189 -1.517270 -v 0.027753 -0.006510 0.101550 -vn -3.034544 -3.665195 0.000005 -v 0.027900 -0.006910 0.101000 -vn -3.034544 3.665195 0.000005 -v 0.027900 -0.006510 0.101000 -vn -2.627995 -3.665186 1.517275 -v 0.027753 -0.006910 0.100450 -vn -2.627995 3.665186 1.517275 -v 0.027753 -0.006510 0.100450 -vn -1.517277 -3.665193 2.627991 -v 0.027350 -0.006910 0.100047 -vn -1.517276 3.665193 2.627990 -v 0.027350 -0.006510 0.100047 -vn 0.000000 -3.665193 3.034545 -v 0.026800 -0.006910 0.099900 -vn -0.000000 3.665193 3.034545 -v 0.026800 -0.006510 0.099900 -vn -0.000003 -3.665193 -3.034545 -v 0.001400 -0.006910 0.102100 -vn -0.000002 3.665193 -3.034544 -v 0.001400 -0.006510 0.102100 -vn -1.517275 -3.665190 -2.627993 -v 0.001950 -0.006910 0.101953 -vn -1.517275 3.665189 -2.627993 -v 0.001950 -0.006510 0.101953 -vn -2.627994 -3.665192 -1.517273 -v 0.002353 -0.006910 0.101550 -vn -2.627994 3.665192 -1.517273 -v 0.002353 -0.006510 0.101550 -vn -3.034544 -3.665195 0.000005 -v 0.002500 -0.006910 0.101000 -vn -3.034544 3.665195 0.000005 -v 0.002500 -0.006510 0.101000 -vn -2.627992 -3.665188 1.517278 -v 0.002353 -0.006910 0.100450 -vn -2.627992 3.665188 1.517278 -v 0.002353 -0.006510 0.100450 -vn -1.517275 -3.665190 2.627993 -v 0.001950 -0.006910 0.100047 -vn -1.517275 3.665190 2.627993 -v 0.001950 -0.006510 0.100047 -vn -0.000002 -3.665193 3.034544 -v 0.001400 -0.006910 0.099900 -vn -0.000003 3.665193 3.034545 -v 0.001400 -0.006510 0.099900 -vn -0.000003 -3.665193 -3.034545 -v 0.001400 -0.006910 0.083200 -vn -0.000002 3.665193 -3.034544 -v 0.001400 -0.006510 0.083200 -vn -1.517275 -3.665190 -2.627993 -v 0.001950 -0.006910 0.083053 -vn -1.517275 3.665190 -2.627993 -v 0.001950 -0.006510 0.083053 -vn -2.627994 -3.665192 -1.517273 -v 0.002353 -0.006910 0.082650 -vn -2.627994 3.665191 -1.517273 -v 0.002353 -0.006510 0.082650 -vn -3.034546 -3.665191 0.000000 -v 0.002500 -0.006910 0.082100 -vn -3.034546 3.665191 0.000000 -v 0.002500 -0.006510 0.082100 -vn -2.627984 -3.665201 1.517283 -v 0.002353 -0.006910 0.081550 -vn -2.627983 3.665201 1.517283 -v 0.002353 -0.006510 0.081550 -vn -1.517265 -3.665181 2.628003 -v 0.001950 -0.006910 0.081147 -vn -1.517265 3.665180 2.628003 -v 0.001950 -0.006510 0.081147 -vn -0.000002 -3.665193 3.034544 -v 0.001400 -0.006910 0.081000 -vn -0.000003 3.665193 3.034545 -v 0.001400 -0.006510 0.081000 -vn -0.000000 -3.665193 -3.034545 -v 0.020300 -0.006910 0.083200 -vn 0.000000 3.665193 -3.034545 -v 0.020300 -0.006510 0.083200 -vn -1.517277 -3.665193 -2.627990 -v 0.020850 -0.006910 0.083053 -vn -1.517277 3.665193 -2.627991 -v 0.020850 -0.006510 0.083053 -vn -2.627996 -3.665189 -1.517270 -v 0.021253 -0.006910 0.082650 -vn -2.627996 3.665189 -1.517270 -v 0.021253 -0.006510 0.082650 -vn -3.034546 -3.665191 0.000000 -v 0.021400 -0.006910 0.082100 -vn -3.034546 3.665191 0.000000 -v 0.021400 -0.006510 0.082100 -vn -2.627986 -3.665199 1.517280 -v 0.021253 -0.006910 0.081550 -vn -2.627986 3.665199 1.517280 -v 0.021253 -0.006510 0.081550 -vn -1.517266 -3.665184 2.628001 -v 0.020850 -0.006910 0.081147 -vn -1.517266 3.665184 2.628001 -v 0.020850 -0.006510 0.081147 -vn 0.000000 -3.665193 3.034545 -v 0.020300 -0.006910 0.081000 -vn -0.000000 3.665193 3.034545 -v 0.020300 -0.006510 0.081000 -vn -0.000000 -3.665193 -3.034545 -v 0.026800 -0.006910 0.083200 -vn 0.000000 3.665193 -3.034545 -v 0.026800 -0.006510 0.083200 -vn -1.517277 -3.665193 -2.627990 -v 0.027350 -0.006910 0.083053 -vn -1.517277 3.665192 -2.627991 -v 0.027350 -0.006510 0.083053 -vn -2.627996 -3.665189 -1.517270 -v 0.027753 -0.006910 0.082650 -vn -2.627996 3.665189 -1.517270 -v 0.027753 -0.006510 0.082650 -vn -3.034546 -3.665191 0.000000 -v 0.027900 -0.006910 0.082100 -vn -3.034546 3.665191 0.000000 -v 0.027900 -0.006510 0.082100 -vn -2.627986 -3.665199 1.517280 -v 0.027753 -0.006910 0.081550 -vn -2.627986 3.665198 1.517280 -v 0.027753 -0.006510 0.081550 -vn -1.517266 -3.665184 2.628001 -v 0.027350 -0.006910 0.081147 -vn -1.517266 3.665184 2.628001 -v 0.027350 -0.006510 0.081147 -vn 0.000000 -3.665193 3.034545 -v 0.026800 -0.006910 0.081000 -vn -0.000000 3.665193 3.034545 -v 0.026800 -0.006510 0.081000 -vn -0.000000 2.617995 -3.034546 -v 0.045700 -0.009110 0.102750 -vn 0.000000 -2.617996 -3.034546 -v 0.045700 -0.006910 0.102750 -vn -1.517268 2.617996 -2.627997 -v 0.046575 -0.009110 0.102516 -vn -1.517268 -2.617996 -2.627997 -v 0.046575 -0.006910 0.102516 -vn -2.627989 2.617993 -1.517279 -v 0.047216 -0.009110 0.101875 -vn -2.627989 -2.617993 -1.517279 -v 0.047216 -0.006910 0.101875 -vn -3.034543 2.617987 0.000003 -v 0.047450 -0.009110 0.101000 -vn -3.034543 -2.617987 0.000003 -v 0.047450 -0.006910 0.101000 -vn -2.627995 2.618001 1.517276 -v 0.047216 -0.009110 0.100125 -vn -2.627995 -2.618001 1.517276 -v 0.047216 -0.006910 0.100125 -vn -1.517275 2.617990 2.627991 -v 0.046575 -0.009110 0.099484 -vn -1.517275 -2.617990 2.627990 -v 0.046575 -0.006910 0.099484 -vn 0.000000 2.617995 3.034546 -v 0.045700 -0.009110 0.099250 -vn -0.000000 -2.617995 3.034546 -v 0.045700 -0.006910 0.099250 -vn -0.000000 2.617995 -3.034546 -v 0.045700 -0.009110 0.083850 -vn 0.000000 -2.617996 -3.034546 -v 0.045700 -0.006910 0.083850 -vn -1.517268 2.617996 -2.627997 -v 0.046575 -0.009110 0.083616 -vn -1.517268 -2.617996 -2.627997 -v 0.046575 -0.006910 0.083616 -vn -2.627989 2.617993 -1.517279 -v 0.047216 -0.009110 0.082975 -vn -2.627989 -2.617993 -1.517279 -v 0.047216 -0.006910 0.082975 -vn -3.034543 2.617987 0.000003 -v 0.047450 -0.009110 0.082100 -vn -3.034543 -2.617987 0.000003 -v 0.047450 -0.006910 0.082100 -vn -2.627995 2.618001 1.517276 -v 0.047216 -0.009110 0.081225 -vn -2.627995 -2.618001 1.517276 -v 0.047216 -0.006910 0.081225 -vn -1.517275 2.617990 2.627991 -v 0.046575 -0.009110 0.080584 -vn -1.517275 -2.617990 2.627990 -v 0.046575 -0.006910 0.080584 -vn 0.000000 2.617995 3.034546 -v 0.045700 -0.009110 0.080350 -vn -0.000000 -2.617995 3.034546 -v 0.045700 -0.006910 0.080350 -vn 0.000000 -3.665194 -3.034544 -v 0.010850 -0.005910 0.093150 -vn -0.000000 3.665194 -3.034544 -v 0.010850 -0.005410 0.093150 -vn -1.517273 -3.665188 -2.627995 -v 0.011650 -0.005910 0.092936 -vn -1.517273 3.665189 -2.627995 -v 0.011650 -0.005410 0.092936 -vn -2.627992 -3.665193 -1.517274 -v 0.012236 -0.005910 0.092350 -vn -2.627992 3.665193 -1.517274 -v 0.012236 -0.005410 0.092350 -vn -3.034546 -3.665191 0.000000 -v 0.012450 -0.005910 0.091550 -vn -3.034546 3.665191 -0.000000 -v 0.012450 -0.005410 0.091550 -vn -2.627999 -3.665187 1.517267 -v 0.012236 -0.005910 0.090750 -vn -2.627999 3.665187 1.517267 -v 0.012236 -0.005410 0.090750 -vn -1.517280 -3.665195 2.627988 -v 0.011650 -0.005910 0.090164 -vn -1.517280 3.665195 2.627988 -v 0.011650 -0.005410 0.090164 -vn -0.000000 -3.665194 3.034544 -v 0.010850 -0.005910 0.089950 -vn 0.000000 3.665194 3.034544 -v 0.010850 -0.005410 0.089950 -vn -0.000000 2.617995 -3.034546 -v 0.019181 -0.007510 0.093300 -vn 0.000000 -2.617995 -3.034546 -v 0.019181 -0.005310 0.093300 -vn -1.517275 2.617990 -2.627990 -v 0.020056 -0.007510 0.093066 -vn -1.517275 -2.617990 -2.627991 -v 0.020056 -0.005310 0.093066 -vn -2.627997 2.617997 -1.517270 -v 0.020697 -0.007510 0.092425 -vn -2.627996 -2.617997 -1.517270 -v 0.020697 -0.005310 0.092425 -vn -3.034546 2.617995 -0.000003 -v 0.020931 -0.007510 0.091550 -vn -3.034546 -2.617995 -0.000003 -v 0.020931 -0.005310 0.091550 -vn -2.627991 2.617990 1.517273 -v 0.020697 -0.007510 0.090675 -vn -2.627991 -2.617989 1.517273 -v 0.020697 -0.005310 0.090675 -vn -1.517269 2.617996 2.627997 -v 0.020056 -0.007510 0.090034 -vn -1.517268 -2.617996 2.627997 -v 0.020056 -0.005310 0.090034 -vn 0.000000 2.617995 3.034546 -v 0.019181 -0.007510 0.089800 -vn -0.000000 -2.617995 3.034546 -v 0.019181 -0.005310 0.089800 -vn -0.000000 2.617995 -3.034546 -v 0.010850 -0.007510 0.084969 -vn 0.000000 -2.617995 -3.034546 -v 0.010850 -0.005310 0.084969 -vn -1.517268 2.617996 -2.627997 -v 0.011725 -0.007510 0.084734 -vn -1.517269 -2.617996 -2.627997 -v 0.011725 -0.005310 0.084734 -vn -2.627991 2.617989 -1.517273 -v 0.012366 -0.007510 0.084094 -vn -2.627991 -2.617990 -1.517273 -v 0.012366 -0.005310 0.084094 -vn -3.034546 2.617995 0.000003 -v 0.012600 -0.007510 0.083219 -vn -3.034546 -2.617995 0.000003 -v 0.012600 -0.005310 0.083219 -vn -2.627996 2.617997 1.517270 -v 0.012366 -0.007510 0.082344 -vn -2.627997 -2.617997 1.517270 -v 0.012366 -0.005310 0.082344 -vn -1.517275 2.617990 2.627991 -v 0.011725 -0.007510 0.081703 -vn -1.517275 -2.617990 2.627990 -v 0.011725 -0.005310 0.081703 -vn 0.000000 2.617995 3.034546 -v 0.010850 -0.007510 0.081469 -vn -0.000000 -2.617995 3.034546 -v 0.010850 -0.005310 0.081469 -vn -0.000000 2.617995 -3.034546 -v 0.002519 -0.007510 0.093300 -vn 0.000000 -2.617995 -3.034546 -v 0.002519 -0.005310 0.093300 -vn -1.517275 2.617990 -2.627990 -v 0.003394 -0.007510 0.093066 -vn -1.517275 -2.617990 -2.627991 -v 0.003394 -0.005310 0.093066 -vn -2.627995 2.618001 -1.517276 -v 0.004034 -0.007510 0.092425 -vn -2.627995 -2.618001 -1.517276 -v 0.004034 -0.005310 0.092425 -vn -3.034543 2.617987 -0.000003 -v 0.004269 -0.007510 0.091550 -vn -3.034543 -2.617987 -0.000003 -v 0.004269 -0.005310 0.091550 -vn -2.627989 2.617993 1.517279 -v 0.004034 -0.007510 0.090675 -vn -2.627990 -2.617993 1.517279 -v 0.004034 -0.005310 0.090675 -vn -1.517269 2.617996 2.627997 -v 0.003394 -0.007510 0.090034 -vn -1.517268 -2.617996 2.627997 -v 0.003394 -0.005310 0.090034 -vn 0.000000 2.617996 3.034546 -v 0.002519 -0.007510 0.089800 -vn -0.000000 -2.617995 3.034546 -v 0.002519 -0.005310 0.089800 -vn -0.000000 2.617995 -3.034546 -v 0.010850 -0.007510 0.101631 -vn 0.000000 -2.617995 -3.034546 -v 0.010850 -0.005310 0.101631 -vn -1.517275 2.617990 -2.627990 -v 0.011725 -0.007510 0.101397 -vn -1.517275 -2.617990 -2.627991 -v 0.011725 -0.005310 0.101397 -vn -2.627997 2.617997 -1.517270 -v 0.012366 -0.007510 0.100756 -vn -2.627996 -2.617997 -1.517270 -v 0.012366 -0.005310 0.100756 -vn -3.034546 2.617995 -0.000003 -v 0.012600 -0.007510 0.099881 -vn -3.034546 -2.617995 -0.000003 -v 0.012600 -0.005310 0.099881 -vn -2.627991 2.617990 1.517273 -v 0.012366 -0.007510 0.099006 -vn -2.627991 -2.617989 1.517273 -v 0.012366 -0.005310 0.099006 -vn -1.517281 2.618004 2.627994 -v 0.011725 -0.007510 0.098366 -vn -1.517280 -2.618004 2.627994 -v 0.011725 -0.005310 0.098366 -vn 0.000000 2.617979 3.034540 -v 0.010850 -0.007510 0.098131 -vn -0.000000 -2.617979 3.034540 -v 0.010850 -0.005310 0.098131 -vn -0.000000 2.617995 -3.034546 -v 0.020300 -0.009110 0.102750 -vn 0.000000 -2.617995 -3.034546 -v 0.020300 -0.006910 0.102750 -vn -1.517268 2.617996 -2.627997 -v 0.021175 -0.009110 0.102516 -vn -1.517268 -2.617996 -2.627997 -v 0.021175 -0.006910 0.102516 -vn -2.627991 2.617989 -1.517273 -v 0.021816 -0.009110 0.101875 -vn -2.627991 -2.617990 -1.517273 -v 0.021816 -0.006910 0.101875 -vn -3.034546 2.617995 0.000003 -v 0.022050 -0.009110 0.101000 -vn -3.034546 -2.617995 0.000003 -v 0.022050 -0.006910 0.101000 -vn -2.627996 2.617997 1.517270 -v 0.021816 -0.009110 0.100125 -vn -2.627996 -2.617997 1.517270 -v 0.021816 -0.006910 0.100125 -vn -1.517275 2.617990 2.627991 -v 0.021175 -0.009110 0.099484 -vn -1.517275 -2.617990 2.627990 -v 0.021175 -0.006910 0.099484 -vn 0.000000 2.617995 3.034546 -v 0.020300 -0.009110 0.099250 -vn -0.000000 -2.617995 3.034546 -v 0.020300 -0.006910 0.099250 -vn -0.000000 2.617995 -3.034546 -v 0.026800 -0.009110 0.102750 -vn 0.000000 -2.617995 -3.034546 -v 0.026800 -0.006910 0.102750 -vn -1.517270 2.617995 -2.627995 -v 0.027675 -0.009110 0.102516 -vn -1.517270 -2.617995 -2.627995 -v 0.027675 -0.006910 0.102516 -vn -2.627992 2.617992 -1.517275 -v 0.028316 -0.009110 0.101875 -vn -2.627992 -2.617993 -1.517275 -v 0.028316 -0.006910 0.101875 -vn -3.034544 2.617991 0.000003 -v 0.028550 -0.009110 0.101000 -vn -3.034544 -2.617991 0.000003 -v 0.028550 -0.006910 0.101000 -vn -2.627997 2.618001 1.517272 -v 0.028316 -0.009110 0.100125 -vn -2.627997 -2.618001 1.517272 -v 0.028316 -0.006910 0.100125 -vn -1.517277 2.617989 2.627989 -v 0.027675 -0.009110 0.099484 -vn -1.517277 -2.617989 2.627989 -v 0.027675 -0.006910 0.099484 -vn 0.000000 2.617995 3.034546 -v 0.026800 -0.009110 0.099250 -vn -0.000000 -2.617995 3.034546 -v 0.026800 -0.006910 0.099250 -vn -0.000000 2.617996 -3.034546 -v 0.001400 -0.009110 0.102750 -vn 0.000000 -2.617995 -3.034546 -v 0.001400 -0.006910 0.102750 -vn -1.517268 2.617996 -2.627997 -v 0.002275 -0.009110 0.102516 -vn -1.517268 -2.617996 -2.627997 -v 0.002275 -0.006910 0.102516 -vn -2.627991 2.617989 -1.517273 -v 0.002916 -0.009110 0.101875 -vn -2.627991 -2.617990 -1.517273 -v 0.002916 -0.006910 0.101875 -vn -3.034546 2.617995 0.000003 -v 0.003150 -0.009110 0.101000 -vn -3.034546 -2.617995 0.000003 -v 0.003150 -0.006910 0.101000 -vn -2.627996 2.617997 1.517270 -v 0.002916 -0.009110 0.100125 -vn -2.627996 -2.617997 1.517270 -v 0.002916 -0.006910 0.100125 -vn -1.517275 2.617990 2.627991 -v 0.002275 -0.009110 0.099484 -vn -1.517275 -2.617990 2.627990 -v 0.002275 -0.006910 0.099484 -vn 0.000000 2.617995 3.034546 -v 0.001400 -0.009110 0.099250 -vn -0.000000 -2.617995 3.034546 -v 0.001400 -0.006910 0.099250 -vn -0.000000 2.617996 -3.034546 -v 0.001400 -0.009110 0.083850 -vn 0.000000 -2.617995 -3.034546 -v 0.001400 -0.006910 0.083850 -vn -1.517268 2.617996 -2.627997 -v 0.002275 -0.009110 0.083616 -vn -1.517268 -2.617996 -2.627997 -v 0.002275 -0.006910 0.083616 -vn -2.627991 2.617989 -1.517273 -v 0.002916 -0.009110 0.082975 -vn -2.627991 -2.617990 -1.517273 -v 0.002916 -0.006910 0.082975 -vn -3.034546 2.617995 0.000003 -v 0.003150 -0.009110 0.082100 -vn -3.034546 -2.617995 0.000003 -v 0.003150 -0.006910 0.082100 -vn -2.627996 2.617997 1.517270 -v 0.002916 -0.009110 0.081225 -vn -2.627996 -2.617997 1.517270 -v 0.002916 -0.006910 0.081225 -vn -1.517275 2.617990 2.627991 -v 0.002275 -0.009110 0.080584 -vn -1.517275 -2.617990 2.627990 -v 0.002275 -0.006910 0.080584 -vn 0.000000 2.617995 3.034546 -v 0.001400 -0.009110 0.080350 -vn -0.000000 -2.617995 3.034546 -v 0.001400 -0.006910 0.080350 -vn -0.000000 2.617995 -3.034546 -v 0.020300 -0.009110 0.083850 -vn 0.000000 -2.617995 -3.034546 -v 0.020300 -0.006910 0.083850 -vn -1.517268 2.617996 -2.627997 -v 0.021175 -0.009110 0.083616 -vn -1.517268 -2.617996 -2.627997 -v 0.021175 -0.006910 0.083616 -vn -2.627991 2.617989 -1.517273 -v 0.021816 -0.009110 0.082975 -vn -2.627991 -2.617990 -1.517273 -v 0.021816 -0.006910 0.082975 -vn -3.034546 2.617995 0.000003 -v 0.022050 -0.009110 0.082100 -vn -3.034546 -2.617995 0.000003 -v 0.022050 -0.006910 0.082100 -vn -2.627996 2.617997 1.517270 -v 0.021816 -0.009110 0.081225 -vn -2.627996 -2.617997 1.517270 -v 0.021816 -0.006910 0.081225 -vn -1.517275 2.617990 2.627991 -v 0.021175 -0.009110 0.080584 -vn -1.517275 -2.617990 2.627990 -v 0.021175 -0.006910 0.080584 -vn 0.000000 2.617995 3.034546 -v 0.020300 -0.009110 0.080350 -vn -0.000000 -2.617995 3.034546 -v 0.020300 -0.006910 0.080350 -vn -0.000000 2.617995 -3.034546 -v 0.026800 -0.009110 0.083850 -vn 0.000000 -2.617995 -3.034546 -v 0.026800 -0.006910 0.083850 -vn -1.517270 2.617995 -2.627995 -v 0.027675 -0.009110 0.083616 -vn -1.517270 -2.617995 -2.627995 -v 0.027675 -0.006910 0.083616 -vn -2.627992 2.617992 -1.517275 -v 0.028316 -0.009110 0.082975 -vn -2.627992 -2.617993 -1.517275 -v 0.028316 -0.006910 0.082975 -vn -3.034544 2.617991 0.000003 -v 0.028550 -0.009110 0.082100 -vn -3.034544 -2.617991 0.000003 -v 0.028550 -0.006910 0.082100 -vn -2.627997 2.618001 1.517272 -v 0.028316 -0.009110 0.081225 -vn -2.627997 -2.618001 1.517272 -v 0.028316 -0.006910 0.081225 -vn -1.517277 2.617989 2.627989 -v 0.027675 -0.009110 0.080584 -vn -1.517277 -2.617989 2.627989 -v 0.027675 -0.006910 0.080584 -vn 0.000000 2.617995 3.034546 -v 0.026800 -0.009110 0.080350 -vn -0.000000 -2.617995 3.034546 -v 0.026800 -0.006910 0.080350 -vn 0.000003 2.617993 -3.034545 -v 0.045700 -0.012860 0.102100 -vn 0.000003 3.665193 -3.034545 -v 0.045700 -0.009110 0.102100 -vn -1.517273 2.617994 -2.627994 -v 0.046250 -0.012860 0.101953 -vn -1.517272 3.665192 -2.627993 -v 0.046250 -0.009110 0.101953 -vn -2.627996 2.617988 -1.517263 -v 0.046653 -0.012860 0.101550 -vn -2.627996 3.665198 -1.517263 -v 0.046653 -0.009110 0.101550 -vn -3.034549 2.618003 0.000005 -v 0.046800 -0.012860 0.101000 -vn -3.034549 3.665182 0.000005 -v 0.046800 -0.009110 0.101000 -vn -2.627995 2.617991 1.517268 -v 0.046653 -0.012860 0.100450 -vn -2.627995 3.665195 1.517268 -v 0.046653 -0.009110 0.100450 -vn -1.517272 2.617994 2.627993 -v 0.046250 -0.012860 0.100047 -vn -1.517273 3.665191 2.627994 -v 0.046250 -0.009110 0.100047 -vn 0.000003 2.617993 3.034545 -v 0.045700 -0.012860 0.099900 -vn 0.000003 3.665193 3.034545 -v 0.045700 -0.009110 0.099900 -vn 0.000003 2.617993 -3.034545 -v 0.045700 -0.012860 0.083200 -vn 0.000003 3.665193 -3.034545 -v 0.045700 -0.009110 0.083200 -vn -1.517273 2.617994 -2.627994 -v 0.046250 -0.012860 0.083053 -vn -1.517272 3.665192 -2.627993 -v 0.046250 -0.009110 0.083053 -vn -2.627996 2.617988 -1.517263 -v 0.046653 -0.012860 0.082650 -vn -2.627996 3.665198 -1.517263 -v 0.046653 -0.009110 0.082650 -vn -3.034551 2.618007 0.000000 -v 0.046800 -0.012860 0.082100 -vn -3.034551 3.665178 -0.000000 -v 0.046800 -0.009110 0.082100 -vn -2.627986 2.617978 1.517273 -v 0.046653 -0.012860 0.081550 -vn -2.627986 3.665207 1.517273 -v 0.046653 -0.009110 0.081550 -vn -1.517262 2.618003 2.628004 -v 0.046250 -0.012860 0.081147 -vn -1.517262 3.665182 2.628004 -v 0.046250 -0.009110 0.081147 -vn 0.000003 2.617993 3.034545 -v 0.045700 -0.012860 0.081000 -vn 0.000003 3.665193 3.034545 -v 0.045700 -0.009110 0.081000 -vn 0.000000 2.692796 -3.062827 -v 0.010850 -0.008910 0.094550 -vn 0.000000 -2.692796 -3.062828 -v 0.010850 -0.005910 0.094550 -vn -1.328910 2.692792 -2.759511 -v 0.012152 -0.008910 0.094253 -vn -1.328910 -2.692792 -2.759511 -v 0.012152 -0.005910 0.094253 -vn -2.394615 2.692795 -1.909641 -v 0.013195 -0.008910 0.093420 -vn -2.394615 -2.692795 -1.909641 -v 0.013195 -0.005910 0.093420 -vn -2.986035 2.692793 -0.681543 -v 0.013775 -0.008910 0.092218 -vn -2.986035 -2.692794 -0.681543 -v 0.013775 -0.005910 0.092218 -vn -2.986035 2.692794 0.681543 -v 0.013775 -0.008910 0.090882 -vn -2.986035 -2.692793 0.681543 -v 0.013775 -0.005910 0.090882 -vn -2.394615 2.692795 1.909641 -v 0.013195 -0.008910 0.089680 -vn -2.394615 -2.692795 1.909641 -v 0.013195 -0.005910 0.089680 -vn -1.328910 2.692791 2.759511 -v 0.012152 -0.008910 0.088847 -vn -1.328910 -2.692792 2.759511 -v 0.012152 -0.005910 0.088847 -vn 0.000000 2.692796 3.062828 -v 0.010850 -0.008910 0.088550 -vn 0.000000 -2.692796 3.062828 -v 0.010850 -0.005910 0.088550 -vn 0.000000 2.617993 -3.034545 -v 0.019181 -0.011260 0.092650 -vn -0.000000 3.665193 -3.034545 -v 0.019181 -0.007510 0.092650 -vn -1.517266 2.618001 -2.628001 -v 0.019731 -0.011260 0.092503 -vn -1.517267 3.665184 -2.628001 -v 0.019731 -0.007510 0.092503 -vn -2.627986 2.617987 -1.517280 -v 0.020134 -0.011260 0.092100 -vn -2.627986 3.665199 -1.517280 -v 0.020134 -0.007510 0.092100 -vn -3.034546 2.617994 0.000000 -v 0.020281 -0.011260 0.091550 -vn -3.034546 3.665191 0.000000 -v 0.020281 -0.007510 0.091550 -vn -2.627996 2.617996 1.517270 -v 0.020134 -0.011260 0.091000 -vn -2.627996 3.665189 1.517270 -v 0.020134 -0.007510 0.091000 -vn -1.517276 2.617992 2.627991 -v 0.019731 -0.011260 0.090597 -vn -1.517276 3.665193 2.627991 -v 0.019731 -0.007510 0.090597 -vn -0.000000 2.617992 3.034545 -v 0.019181 -0.011260 0.090450 -vn 0.000000 3.665193 3.034545 -v 0.019181 -0.007510 0.090450 -vn 0.000000 2.617992 -3.034545 -v 0.010850 -0.011260 0.084319 -vn -0.000000 3.665193 -3.034545 -v 0.010850 -0.007510 0.084319 -vn -1.517276 2.617992 -2.627991 -v 0.011400 -0.011260 0.084171 -vn -1.517276 3.665193 -2.627991 -v 0.011400 -0.007510 0.084171 -vn -2.627996 2.617996 -1.517270 -v 0.011803 -0.011260 0.083769 -vn -2.627996 3.665189 -1.517270 -v 0.011803 -0.007510 0.083769 -vn -3.034546 2.617994 0.000000 -v 0.011950 -0.011260 0.083219 -vn -3.034546 3.665191 0.000000 -v 0.011950 -0.007510 0.083219 -vn -2.627996 2.617997 1.517270 -v 0.011803 -0.011260 0.082669 -vn -2.627996 3.665189 1.517270 -v 0.011803 -0.007510 0.082669 -vn -1.517257 2.617980 2.627996 -v 0.011400 -0.011260 0.082266 -vn -1.517257 3.665206 2.627995 -v 0.011400 -0.007510 0.082266 -vn 0.000000 2.618018 3.034555 -v 0.010850 -0.011260 0.082119 -vn -0.000000 3.665168 3.034555 -v 0.010850 -0.007510 0.082119 -vn 0.000003 2.617992 -3.034545 -v 0.002519 -0.011260 0.092650 -vn 0.000003 3.665193 -3.034545 -v 0.002519 -0.007510 0.092650 -vn -1.517262 2.618003 -2.628004 -v 0.003069 -0.011260 0.092503 -vn -1.517262 3.665182 -2.628004 -v 0.003069 -0.007510 0.092503 -vn -2.627986 2.617978 -1.517273 -v 0.003471 -0.011260 0.092100 -vn -2.627986 3.665207 -1.517273 -v 0.003471 -0.007510 0.092100 -vn -3.034551 2.618007 -0.000000 -v 0.003619 -0.011260 0.091550 -vn -3.034551 3.665179 0.000000 -v 0.003619 -0.007510 0.091550 -vn -2.627996 2.617988 1.517263 -v 0.003471 -0.011260 0.091000 -vn -2.627996 3.665198 1.517263 -v 0.003471 -0.007510 0.091000 -vn -1.517273 2.617994 2.627994 -v 0.003069 -0.011260 0.090597 -vn -1.517273 3.665191 2.627994 -v 0.003069 -0.007510 0.090597 -vn 0.000003 2.617992 3.034545 -v 0.002519 -0.011260 0.090450 -vn 0.000003 3.665193 3.034545 -v 0.002519 -0.007510 0.090450 -vn 0.000000 2.617992 -3.034545 -v 0.010850 -0.011260 0.100981 -vn -0.000000 3.665193 -3.034545 -v 0.010850 -0.007510 0.100981 -vn -1.517276 2.617992 -2.627991 -v 0.011400 -0.011260 0.100834 -vn -1.517276 3.665193 -2.627991 -v 0.011400 -0.007510 0.100834 -vn -2.627995 2.617999 -1.517275 -v 0.011803 -0.011260 0.100431 -vn -2.627995 3.665186 -1.517275 -v 0.011803 -0.007510 0.100431 -vn -3.034544 2.617991 -0.000005 -v 0.011950 -0.011260 0.099881 -vn -3.034544 3.665195 -0.000005 -v 0.011950 -0.007510 0.099881 -vn -2.627996 2.617996 1.517270 -v 0.011803 -0.011260 0.099331 -vn -2.627996 3.665189 1.517270 -v 0.011803 -0.007510 0.099331 -vn -1.517276 2.617992 2.627991 -v 0.011400 -0.011260 0.098929 -vn -1.517276 3.665193 2.627991 -v 0.011400 -0.007510 0.098929 -vn -0.000000 2.617992 3.034545 -v 0.010850 -0.011260 0.098781 -vn 0.000000 3.665193 3.034545 -v 0.010850 -0.007510 0.098781 -vn -0.000000 2.617992 -3.034544 -v 0.020300 -0.012860 0.102100 -vn 0.000000 3.665193 -3.034544 -v 0.020300 -0.009110 0.102100 -vn -1.517276 2.617992 -2.627990 -v 0.020850 -0.012860 0.101953 -vn -1.517276 3.665193 -2.627991 -v 0.020850 -0.009110 0.101953 -vn -2.627996 2.617996 -1.517270 -v 0.021253 -0.012860 0.101550 -vn -2.627996 3.665189 -1.517270 -v 0.021253 -0.009110 0.101550 -vn -3.034544 2.617991 0.000005 -v 0.021400 -0.012860 0.101000 -vn -3.034544 3.665195 0.000005 -v 0.021400 -0.009110 0.101000 -vn -2.627995 2.618000 1.517275 -v 0.021253 -0.012860 0.100450 -vn -2.627995 3.665186 1.517275 -v 0.021253 -0.009110 0.100450 -vn -1.517276 2.617992 2.627991 -v 0.020850 -0.012860 0.100047 -vn -1.517276 3.665193 2.627990 -v 0.020850 -0.009110 0.100047 -vn 0.000000 2.617992 3.034544 -v 0.020300 -0.012860 0.099900 -vn -0.000000 3.665193 3.034544 -v 0.020300 -0.009110 0.099900 -vn -0.000000 2.617992 -3.034544 -v 0.026800 -0.012860 0.102100 -vn 0.000000 3.665193 -3.034544 -v 0.026800 -0.009110 0.102100 -vn -1.517276 2.617993 -2.627990 -v 0.027350 -0.012860 0.101953 -vn -1.517276 3.665193 -2.627991 -v 0.027350 -0.009110 0.101953 -vn -2.627996 2.617996 -1.517270 -v 0.027753 -0.012860 0.101550 -vn -2.627996 3.665189 -1.517270 -v 0.027753 -0.009110 0.101550 -vn -3.034544 2.617990 0.000005 -v 0.027900 -0.012860 0.101000 -vn -3.034544 3.665195 0.000005 -v 0.027900 -0.009110 0.101000 -vn -2.627995 2.617999 1.517275 -v 0.027753 -0.012860 0.100450 -vn -2.627995 3.665186 1.517275 -v 0.027753 -0.009110 0.100450 -vn -1.517276 2.617992 2.627991 -v 0.027350 -0.012860 0.100047 -vn -1.517276 3.665193 2.627990 -v 0.027350 -0.009110 0.100047 -vn 0.000000 2.617992 3.034544 -v 0.026800 -0.012860 0.099900 -vn -0.000000 3.665193 3.034544 -v 0.026800 -0.009110 0.099900 -vn -0.000003 2.617992 -3.034545 -v 0.001400 -0.012860 0.102100 -vn -0.000003 3.665193 -3.034545 -v 0.001400 -0.009110 0.102100 -vn -1.517275 2.617996 -2.627993 -v 0.001950 -0.012860 0.101953 -vn -1.517275 3.665190 -2.627993 -v 0.001950 -0.009110 0.101953 -vn -2.627993 2.617994 -1.517272 -v 0.002353 -0.012860 0.101550 -vn -2.627994 3.665191 -1.517273 -v 0.002353 -0.009110 0.101550 -vn -3.034544 2.617991 0.000005 -v 0.002500 -0.012860 0.101000 -vn -3.034544 3.665195 0.000005 -v 0.002500 -0.009110 0.101000 -vn -2.627992 2.617997 1.517278 -v 0.002353 -0.012860 0.100450 -vn -2.627992 3.665188 1.517277 -v 0.002353 -0.009110 0.100450 -vn -1.517275 2.617995 2.627993 -v 0.001950 -0.012860 0.100047 -vn -1.517275 3.665190 2.627993 -v 0.001950 -0.009110 0.100047 -vn -0.000003 2.617992 3.034545 -v 0.001400 -0.012860 0.099900 -vn -0.000003 3.665193 3.034545 -v 0.001400 -0.009110 0.099900 -vn -0.000003 2.617992 -3.034545 -v 0.001400 -0.012860 0.083200 -vn -0.000003 3.665193 -3.034545 -v 0.001400 -0.009110 0.083200 -vn -1.517275 2.617996 -2.627993 -v 0.001950 -0.012860 0.083053 -vn -1.517275 3.665190 -2.627993 -v 0.001950 -0.009110 0.083053 -vn -2.627993 2.617994 -1.517272 -v 0.002353 -0.012860 0.082650 -vn -2.627994 3.665191 -1.517273 -v 0.002353 -0.009110 0.082650 -vn -3.034546 2.617995 0.000000 -v 0.002500 -0.012860 0.082100 -vn -3.034546 3.665191 0.000000 -v 0.002500 -0.009110 0.082100 -vn -2.627984 2.617984 1.517283 -v 0.002353 -0.012860 0.081550 -vn -2.627983 3.665201 1.517283 -v 0.002353 -0.009110 0.081550 -vn -1.517265 2.618005 2.628003 -v 0.001950 -0.012860 0.081147 -vn -1.517265 3.665181 2.628003 -v 0.001950 -0.009110 0.081147 -vn -0.000003 2.617992 3.034545 -v 0.001400 -0.012860 0.081000 -vn -0.000003 3.665193 3.034545 -v 0.001400 -0.009110 0.081000 -vn -0.000000 2.617992 -3.034544 -v 0.020300 -0.012860 0.083200 -vn 0.000000 3.665193 -3.034544 -v 0.020300 -0.009110 0.083200 -vn -1.517276 2.617992 -2.627990 -v 0.020850 -0.012860 0.083053 -vn -1.517276 3.665193 -2.627991 -v 0.020850 -0.009110 0.083053 -vn -2.627996 2.617996 -1.517270 -v 0.021253 -0.012860 0.082650 -vn -2.627996 3.665189 -1.517270 -v 0.021253 -0.009110 0.082650 -vn -3.034546 2.617994 0.000000 -v 0.021400 -0.012860 0.082100 -vn -3.034546 3.665191 0.000000 -v 0.021400 -0.009110 0.082100 -vn -2.627986 2.617988 1.517280 -v 0.021253 -0.012860 0.081550 -vn -2.627986 3.665198 1.517280 -v 0.021253 -0.009110 0.081550 -vn -1.517266 2.618001 2.628001 -v 0.020850 -0.012860 0.081147 -vn -1.517266 3.665184 2.628000 -v 0.020850 -0.009110 0.081147 -vn 0.000000 2.617993 3.034544 -v 0.020300 -0.012860 0.081000 -vn -0.000000 3.665193 3.034544 -v 0.020300 -0.009110 0.081000 -vn -0.000000 2.617992 -3.034544 -v 0.026800 -0.012860 0.083200 -vn 0.000000 3.665193 -3.034544 -v 0.026800 -0.009110 0.083200 -vn -1.517276 2.617993 -2.627990 -v 0.027350 -0.012860 0.083053 -vn -1.517276 3.665193 -2.627991 -v 0.027350 -0.009110 0.083053 -vn -2.627996 2.617996 -1.517270 -v 0.027753 -0.012860 0.082650 -vn -2.627996 3.665189 -1.517270 -v 0.027753 -0.009110 0.082650 -vn -3.034546 2.617994 0.000000 -v 0.027900 -0.012860 0.082100 -vn -3.034546 3.665191 0.000000 -v 0.027900 -0.009110 0.082100 -vn -2.627986 2.617987 1.517280 -v 0.027753 -0.012860 0.081550 -vn -2.627986 3.665198 1.517280 -v 0.027753 -0.009110 0.081550 -vn -1.517266 2.618001 2.628001 -v 0.027350 -0.012860 0.081147 -vn -1.517266 3.665184 2.628000 -v 0.027350 -0.009110 0.081147 -vn 0.000000 2.617992 3.034544 -v 0.026800 -0.012860 0.081000 -vn -0.000000 3.665193 3.034544 -v 0.026800 -0.009110 0.081000 -vn 0.000000 2.617991 -3.034544 -v 0.010850 -0.011260 0.093150 -vn -0.000000 3.665194 -3.034544 -v 0.010850 -0.008910 0.093150 -vn -1.517273 2.617997 -2.627995 -v 0.011650 -0.011260 0.092936 -vn -1.517273 3.665188 -2.627995 -v 0.011650 -0.008910 0.092936 -vn -2.627992 2.617992 -1.517274 -v 0.012236 -0.011260 0.092350 -vn -2.627992 3.665193 -1.517274 -v 0.012236 -0.008910 0.092350 -vn -3.034545 2.617994 0.000000 -v 0.012450 -0.011260 0.091550 -vn -3.034545 3.665191 -0.000000 -v 0.012450 -0.008910 0.091550 -vn -2.627999 2.617999 1.517267 -v 0.012236 -0.011260 0.090750 -vn -2.627999 3.665187 1.517267 -v 0.012236 -0.008910 0.090750 -vn -1.517280 2.617990 2.627988 -v 0.011650 -0.011260 0.090164 -vn -1.517280 3.665195 2.627988 -v 0.011650 -0.008910 0.090164 -vn -0.000000 2.617991 3.034544 -v 0.010850 -0.011260 0.089950 -vn 0.000000 3.665194 3.034544 -v 0.010850 -0.008910 0.089950 -vn -0.000000 -2.618015 3.034554 -v 0.040450 -0.008510 0.100850 -vn 0.000237 -0.188739 -0.062828 -v 0.040450 -0.041410 0.100850 -vn -1.517267 -2.617972 2.627986 -v 0.040950 -0.008510 0.100984 -vn -1.517267 -3.665213 2.627986 -v 0.040950 -0.041410 0.100984 -vn -2.628001 -2.618011 1.517271 -v 0.041316 -0.008510 0.101350 -vn -2.628001 -3.665175 1.517271 -v 0.041316 -0.041410 0.101350 -vn -3.034541 -2.617985 0.000005 -v 0.041450 -0.008510 0.101850 -vn -3.034541 -3.665200 0.000006 -v 0.041450 -0.041410 0.101850 -vn -2.627992 -2.617997 -1.517277 -v 0.041316 -0.008510 0.102350 -vn -2.627992 -3.665189 -1.517277 -v 0.041316 -0.041410 0.102350 -vn -1.517277 -2.617997 -2.627992 -v 0.040950 -0.008510 0.102716 -vn -1.517277 -3.665189 -2.627992 -v 0.040950 -0.041410 0.102716 -vn 0.000000 -2.617988 -3.034543 -v 0.040450 -0.008510 0.102850 -vn -0.000129 -0.188541 0.062823 -v 0.040450 -0.041410 0.102850 -vn 0.000002 3.665193 3.034545 -v 0.045700 -0.041010 0.099900 -vn 0.000003 -3.665193 3.034545 -v 0.045700 -0.041410 0.099900 -vn -1.517273 3.665191 2.627994 -v 0.046250 -0.041010 0.100047 -vn -1.517273 -3.665191 2.627994 -v 0.046250 -0.041410 0.100047 -vn -2.627995 3.665195 1.517268 -v 0.046653 -0.041010 0.100450 -vn -2.627995 -3.665195 1.517268 -v 0.046653 -0.041410 0.100450 -vn -3.034549 3.665182 0.000005 -v 0.046800 -0.041010 0.101000 -vn -3.034549 -3.665182 0.000005 -v 0.046800 -0.041410 0.101000 -vn -2.627996 3.665198 -1.517263 -v 0.046653 -0.041010 0.101550 -vn -2.627996 -3.665198 -1.517263 -v 0.046653 -0.041410 0.101550 -vn -1.517273 3.665192 -2.627994 -v 0.046250 -0.041010 0.101953 -vn -1.517273 -3.665192 -2.627994 -v 0.046250 -0.041410 0.101953 -vn 0.000003 3.665193 -3.034545 -v 0.045700 -0.041010 0.102100 -vn 0.000002 -3.665193 -3.034545 -v 0.045700 -0.041410 0.102100 -vn -0.000000 -2.792523 3.093864 -v 0.010850 -0.042510 0.086550 -vn 0.000000 -3.490662 3.093864 -v 0.010850 -0.043010 0.086550 -vn -1.058165 -2.792530 2.907283 -v 0.012560 -0.042510 0.086852 -vn -1.058165 -3.490655 2.907283 -v 0.012560 -0.043010 0.086852 -vn -1.988695 -2.792526 2.370040 -v 0.014064 -0.042510 0.087720 -vn -1.988695 -3.490659 2.370040 -v 0.014064 -0.043010 0.087720 -vn -2.679364 -2.792527 1.546934 -v 0.015180 -0.042510 0.089050 -vn -2.679364 -3.490659 1.546934 -v 0.015180 -0.043010 0.089050 -vn -3.046862 -2.792526 0.537245 -v 0.015774 -0.042510 0.090682 -vn -3.046862 -3.490659 0.537245 -v 0.015774 -0.043010 0.090682 -vn -3.046862 -2.792526 -0.537245 -v 0.015774 -0.042510 0.092418 -vn -3.046861 -3.490659 -0.537245 -v 0.015774 -0.043010 0.092418 -vn -2.679364 -2.792527 -1.546934 -v 0.015180 -0.042510 0.094050 -vn -2.679364 -3.490659 -1.546934 -v 0.015180 -0.043010 0.094050 -vn -1.988700 -2.792530 -2.370037 -v 0.014064 -0.042510 0.095380 -vn -1.988700 -3.490656 -2.370037 -v 0.014064 -0.043010 0.095380 -vn -1.058163 -2.792522 -2.907281 -v 0.012560 -0.042510 0.096248 -vn -1.058163 -3.490663 -2.907281 -v 0.012560 -0.043010 0.096248 -vn 0.000000 -2.792532 -3.093866 -v 0.010850 -0.042510 0.096550 -vn -0.000000 -3.490654 -3.093866 -v 0.010850 -0.043010 0.096550 -vn 0.000001 -2.792523 3.093863 -v 0.036250 -0.042510 0.086550 -vn 0.000001 -3.490662 3.093863 -v 0.036250 -0.043010 0.086550 -vn -1.058165 -2.792529 2.907282 -v 0.037960 -0.042510 0.086852 -vn -1.058165 -3.490656 2.907282 -v 0.037960 -0.043010 0.086852 -vn -1.988695 -2.792527 2.370041 -v 0.039464 -0.042510 0.087720 -vn -1.988695 -3.490658 2.370040 -v 0.039464 -0.043010 0.087720 -vn -2.679364 -2.792525 1.546934 -v 0.040580 -0.042510 0.089050 -vn -2.679364 -3.490660 1.546934 -v 0.040580 -0.043010 0.089050 -vn -3.046862 -2.792527 0.537244 -v 0.041174 -0.042510 0.090682 -vn -3.046862 -3.490659 0.537244 -v 0.041174 -0.043010 0.090682 -vn -3.046862 -2.792527 -0.537244 -v 0.041174 -0.042510 0.092418 -vn -3.046862 -3.490659 -0.537244 -v 0.041174 -0.043010 0.092418 -vn -2.679364 -2.792525 -1.546934 -v 0.040580 -0.042510 0.094050 -vn -2.679363 -3.490660 -1.546934 -v 0.040580 -0.043010 0.094050 -vn -1.988700 -2.792531 -2.370038 -v 0.039464 -0.042510 0.095380 -vn -1.988700 -3.490654 -2.370038 -v 0.039464 -0.043010 0.095380 -vn -1.058164 -2.792521 -2.907280 -v 0.037960 -0.042510 0.096248 -vn -1.058164 -3.490664 -2.907280 -v 0.037960 -0.043010 0.096248 -vn 0.000001 -2.792531 -3.093866 -v 0.036250 -0.042510 0.096550 -vn 0.000000 -3.490654 -3.093866 -v 0.036250 -0.043010 0.096550 -vn 0.000002 3.665193 3.034545 -v 0.036250 -0.042610 0.098781 -vn 0.000003 -3.665193 3.034545 -v 0.036250 -0.043010 0.098781 -vn -1.517278 3.665196 2.627989 -v 0.036800 -0.042610 0.098929 -vn -1.517278 -3.665196 2.627988 -v 0.036800 -0.043010 0.098929 -vn -2.627999 3.665187 1.517267 -v 0.037203 -0.042610 0.099331 -vn -2.627999 -3.665187 1.517267 -v 0.037203 -0.043010 0.099331 -vn -3.034544 3.665195 -0.000005 -v 0.037350 -0.042610 0.099881 -vn -3.034544 -3.665195 -0.000005 -v 0.037350 -0.043010 0.099881 -vn -2.627997 3.665184 -1.517273 -v 0.037203 -0.042610 0.100431 -vn -2.627997 -3.665184 -1.517273 -v 0.037203 -0.043010 0.100431 -vn -1.517278 3.665196 -2.627988 -v 0.036800 -0.042610 0.100834 -vn -1.517278 -3.665196 -2.627988 -v 0.036800 -0.043010 0.100834 -vn 0.000003 3.665193 -3.034545 -v 0.036250 -0.042610 0.100981 -vn 0.000002 -3.665193 -3.034545 -v 0.036250 -0.043010 0.100981 -vn -0.000003 3.665193 3.034545 -v 0.044581 -0.042610 0.090450 -vn -0.000003 -3.665193 3.034544 -v 0.044581 -0.043010 0.090450 -vn -1.517275 3.665190 2.627993 -v 0.045131 -0.042610 0.090597 -vn -1.517275 -3.665190 2.627993 -v 0.045131 -0.043010 0.090597 -vn -2.627994 3.665192 1.517273 -v 0.045534 -0.042610 0.091000 -vn -2.627994 -3.665192 1.517273 -v 0.045534 -0.043010 0.091000 -vn -3.034546 3.665191 0.000000 -v 0.045681 -0.042610 0.091550 -vn -3.034546 -3.665191 0.000000 -v 0.045681 -0.043010 0.091550 -vn -2.627984 3.665201 -1.517283 -v 0.045534 -0.042610 0.092100 -vn -2.627983 -3.665201 -1.517283 -v 0.045534 -0.043010 0.092100 -vn -1.517265 3.665181 -2.628003 -v 0.045131 -0.042610 0.092503 -vn -1.517265 -3.665181 -2.628003 -v 0.045131 -0.043010 0.092503 -vn -0.000003 3.665193 -3.034544 -v 0.044581 -0.042610 0.092650 -vn -0.000003 -3.665193 -3.034545 -v 0.044581 -0.043010 0.092650 -vn 0.000003 3.665168 3.034555 -v 0.036250 -0.042610 0.082119 -vn 0.000003 -3.665168 3.034555 -v 0.036250 -0.043010 0.082119 -vn -1.517259 3.665209 2.627994 -v 0.036800 -0.042610 0.082266 -vn -1.517259 -3.665209 2.627994 -v 0.036800 -0.043010 0.082266 -vn -2.627999 3.665187 1.517267 -v 0.037203 -0.042610 0.082669 -vn -2.627999 -3.665187 1.517267 -v 0.037203 -0.043010 0.082669 -vn -3.034546 3.665191 0.000000 -v 0.037350 -0.042610 0.083219 -vn -3.034546 -3.665191 0.000000 -v 0.037350 -0.043010 0.083219 -vn -2.627999 3.665187 -1.517267 -v 0.037203 -0.042610 0.083769 -vn -2.627999 -3.665187 -1.517267 -v 0.037203 -0.043010 0.083769 -vn -1.517278 3.665196 -2.627988 -v 0.036800 -0.042610 0.084171 -vn -1.517278 -3.665196 -2.627988 -v 0.036800 -0.043010 0.084171 -vn 0.000003 3.665193 -3.034545 -v 0.036250 -0.042610 0.084319 -vn 0.000002 -3.665193 -3.034545 -v 0.036250 -0.043010 0.084319 -vn -0.000000 3.665193 3.034545 -v 0.027919 -0.042610 0.090450 -vn 0.000000 -3.665193 3.034545 -v 0.027919 -0.043010 0.090450 -vn -1.517277 3.665193 2.627990 -v 0.028469 -0.042610 0.090597 -vn -1.517277 -3.665193 2.627991 -v 0.028469 -0.043010 0.090597 -vn -2.627996 3.665189 1.517270 -v 0.028871 -0.042610 0.091000 -vn -2.627996 -3.665189 1.517270 -v 0.028871 -0.043010 0.091000 -vn -3.034546 3.665191 0.000000 -v 0.029019 -0.042610 0.091550 -vn -3.034546 -3.665192 0.000000 -v 0.029019 -0.043010 0.091550 -vn -2.627986 3.665199 -1.517280 -v 0.028871 -0.042610 0.092100 -vn -2.627986 -3.665198 -1.517280 -v 0.028871 -0.043010 0.092100 -vn -1.517266 3.665184 -2.628001 -v 0.028469 -0.042610 0.092503 -vn -1.517266 -3.665184 -2.628001 -v 0.028469 -0.043010 0.092503 -vn 0.000000 3.665193 -3.034545 -v 0.027919 -0.042610 0.092650 -vn -0.000000 -3.665193 -3.034545 -v 0.027919 -0.043010 0.092650 -vn -0.000000 3.665193 3.034545 -v 0.019181 -0.042610 0.090450 -vn 0.000000 -3.665193 3.034545 -v 0.019181 -0.043010 0.090450 -vn -1.517277 3.665193 2.627990 -v 0.019731 -0.042610 0.090597 -vn -1.517277 -3.665193 2.627991 -v 0.019731 -0.043010 0.090597 -vn -2.627996 3.665189 1.517270 -v 0.020134 -0.042610 0.091000 -vn -2.627996 -3.665189 1.517270 -v 0.020134 -0.043010 0.091000 -vn -3.034546 3.665191 0.000000 -v 0.020281 -0.042610 0.091550 -vn -3.034546 -3.665191 0.000000 -v 0.020281 -0.043010 0.091550 -vn -2.627986 3.665199 -1.517280 -v 0.020134 -0.042610 0.092100 -vn -2.627986 -3.665198 -1.517280 -v 0.020134 -0.043010 0.092100 -vn -1.517266 3.665184 -2.628001 -v 0.019731 -0.042610 0.092503 -vn -1.517266 -3.665184 -2.628001 -v 0.019731 -0.043010 0.092503 -vn 0.000000 3.665193 -3.034545 -v 0.019181 -0.042610 0.092650 -vn -0.000000 -3.665193 -3.034545 -v 0.019181 -0.043010 0.092650 -vn -0.000000 3.665168 3.034555 -v 0.010850 -0.042610 0.082119 -vn 0.000000 -3.665167 3.034555 -v 0.010850 -0.043010 0.082119 -vn -1.517257 3.665206 2.627996 -v 0.011400 -0.042610 0.082266 -vn -1.517257 -3.665205 2.627996 -v 0.011400 -0.043010 0.082266 -vn -2.627996 3.665189 1.517270 -v 0.011803 -0.042610 0.082669 -vn -2.627996 -3.665189 1.517270 -v 0.011803 -0.043010 0.082669 -vn -3.034546 3.665191 0.000000 -v 0.011950 -0.042610 0.083219 -vn -3.034546 -3.665191 0.000000 -v 0.011950 -0.043010 0.083219 -vn -2.627996 3.665189 -1.517270 -v 0.011803 -0.042610 0.083769 -vn -2.627996 -3.665189 -1.517270 -v 0.011803 -0.043010 0.083769 -vn -1.517277 3.665193 -2.627991 -v 0.011400 -0.042610 0.084171 -vn -1.517276 -3.665193 -2.627990 -v 0.011400 -0.043010 0.084171 -vn 0.000000 3.665193 -3.034545 -v 0.010850 -0.042610 0.084319 -vn -0.000000 -3.665193 -3.034545 -v 0.010850 -0.043010 0.084319 -vn 0.000002 3.665193 3.034545 -v 0.002519 -0.042610 0.090450 -vn 0.000003 -3.665193 3.034545 -v 0.002519 -0.043010 0.090450 -vn -1.517273 3.665191 2.627994 -v 0.003069 -0.042610 0.090597 -vn -1.517273 -3.665191 2.627994 -v 0.003069 -0.043010 0.090597 -vn -2.627996 3.665198 1.517263 -v 0.003471 -0.042610 0.091000 -vn -2.627996 -3.665198 1.517263 -v 0.003471 -0.043010 0.091000 -vn -3.034551 3.665179 0.000000 -v 0.003619 -0.042610 0.091550 -vn -3.034551 -3.665179 0.000000 -v 0.003619 -0.043010 0.091550 -vn -2.627986 3.665207 -1.517273 -v 0.003471 -0.042610 0.092100 -vn -2.627986 -3.665207 -1.517273 -v 0.003471 -0.043010 0.092100 -vn -1.517262 3.665182 -2.628004 -v 0.003069 -0.042610 0.092503 -vn -1.517262 -3.665182 -2.628004 -v 0.003069 -0.043010 0.092503 -vn 0.000003 3.665193 -3.034545 -v 0.002519 -0.042610 0.092650 -vn 0.000002 -3.665193 -3.034545 -v 0.002519 -0.043010 0.092650 -vn -0.000000 3.665193 3.034545 -v 0.010850 -0.042610 0.098781 -vn 0.000000 -3.665193 3.034545 -v 0.010850 -0.043010 0.098781 -vn -1.517277 3.665193 2.627990 -v 0.011400 -0.042610 0.098929 -vn -1.517277 -3.665193 2.627991 -v 0.011400 -0.043010 0.098929 -vn -2.627996 3.665189 1.517270 -v 0.011803 -0.042610 0.099331 -vn -2.627996 -3.665189 1.517270 -v 0.011803 -0.043010 0.099331 -vn -3.034544 3.665195 -0.000005 -v 0.011950 -0.042610 0.099881 -vn -3.034544 -3.665195 -0.000005 -v 0.011950 -0.043010 0.099881 -vn -2.627995 3.665186 -1.517275 -v 0.011803 -0.042610 0.100431 -vn -2.627995 -3.665186 -1.517275 -v 0.011803 -0.043010 0.100431 -vn -1.517277 3.665193 -2.627991 -v 0.011400 -0.042610 0.100834 -vn -1.517276 -3.665193 -2.627990 -v 0.011400 -0.043010 0.100834 -vn 0.000000 3.665193 -3.034545 -v 0.010850 -0.042610 0.100981 -vn -0.000000 -3.665193 -3.034545 -v 0.010850 -0.043010 0.100981 -vn -0.000000 -2.617989 3.034542 -v 0.040450 -0.008510 0.080250 -vn 0.000238 -0.188722 -0.062828 -v 0.040450 -0.041410 0.080250 -vn -1.517277 -2.617997 2.627992 -v 0.040950 -0.008510 0.080384 -vn -1.517277 -3.665189 2.627992 -v 0.040950 -0.041410 0.080384 -vn -2.627992 -2.617997 1.517277 -v 0.041316 -0.008510 0.080750 -vn -2.627992 -3.665189 1.517277 -v 0.041316 -0.041410 0.080750 -vn -3.034543 -2.617988 -0.000000 -v 0.041450 -0.008510 0.081250 -vn -3.034543 -3.665197 0.000000 -v 0.041450 -0.041410 0.081250 -vn -2.627992 -2.617997 -1.517277 -v 0.041316 -0.008510 0.081750 -vn -2.627992 -3.665189 -1.517277 -v 0.041316 -0.041410 0.081750 -vn -1.517277 -2.617996 -2.627992 -v 0.040950 -0.008510 0.082116 -vn -1.517277 -3.665189 -2.627992 -v 0.040950 -0.041410 0.082116 -vn 0.000000 -2.617988 -3.034543 -v 0.040450 -0.008510 0.082250 -vn -0.000129 -0.188543 0.062823 -v 0.040450 -0.041410 0.082250 -vn 0.000002 3.665193 3.034545 -v 0.045700 -0.041010 0.081000 -vn 0.000003 -3.665193 3.034545 -v 0.045700 -0.041410 0.081000 -vn -1.517262 3.665182 2.628004 -v 0.046250 -0.041010 0.081147 -vn -1.517262 -3.665183 2.628004 -v 0.046250 -0.041410 0.081147 -vn -2.627986 3.665207 1.517273 -v 0.046653 -0.041010 0.081550 -vn -2.627986 -3.665207 1.517273 -v 0.046653 -0.041410 0.081550 -vn -3.034551 3.665178 0.000000 -v 0.046800 -0.041010 0.082100 -vn -3.034551 -3.665179 0.000000 -v 0.046800 -0.041410 0.082100 -vn -2.627996 3.665198 -1.517263 -v 0.046653 -0.041010 0.082650 -vn -2.627996 -3.665198 -1.517263 -v 0.046653 -0.041410 0.082650 -vn -1.517273 3.665192 -2.627994 -v 0.046250 -0.041010 0.083053 -vn -1.517273 -3.665191 -2.627994 -v 0.046250 -0.041410 0.083053 -vn 0.000003 3.665193 -3.034545 -v 0.045700 -0.041010 0.083200 -vn 0.000002 -3.665193 -3.034545 -v 0.045700 -0.041410 0.083200 -vn -0.000002 -2.618015 3.034553 -v 0.006650 -0.008510 0.100850 -vn 0.000240 -0.188740 -0.062829 -v 0.006650 -0.041410 0.100850 -vn -1.517266 -2.617976 2.627988 -v 0.007150 -0.008510 0.100984 -vn -1.517265 -3.665209 2.627988 -v 0.007150 -0.041410 0.100984 -vn -2.628000 -2.618004 1.517268 -v 0.007516 -0.008510 0.101350 -vn -2.628000 -3.665181 1.517269 -v 0.007516 -0.041410 0.101350 -vn -3.034544 -2.617991 0.000005 -v 0.007650 -0.008510 0.101850 -vn -3.034544 -3.665194 0.000006 -v 0.007650 -0.041410 0.101850 -vn -2.627990 -2.617990 -1.517274 -v 0.007516 -0.008510 0.102350 -vn -2.627991 -3.665195 -1.517274 -v 0.007516 -0.041410 0.102350 -vn -1.517275 -2.618001 -2.627994 -v 0.007150 -0.008510 0.102716 -vn -1.517275 -3.665185 -2.627994 -v 0.007150 -0.041410 0.102716 -vn -0.000001 -2.617987 -3.034542 -v 0.006650 -0.008510 0.102850 -vn -0.000126 -0.188545 0.062824 -v 0.006650 -0.041410 0.102850 -vn -0.000003 3.665193 3.034545 -v 0.001400 -0.041010 0.099900 -vn -0.000002 -3.665193 3.034544 -v 0.001400 -0.041410 0.099900 -vn -1.517275 3.665190 2.627993 -v 0.001950 -0.041010 0.100047 -vn -1.517275 -3.665190 2.627993 -v 0.001950 -0.041410 0.100047 -vn -2.627992 3.665188 1.517278 -v 0.002353 -0.041010 0.100450 -vn -2.627992 -3.665188 1.517278 -v 0.002353 -0.041410 0.100450 -vn -3.034544 3.665195 0.000005 -v 0.002500 -0.041010 0.101000 -vn -3.034544 -3.665195 0.000005 -v 0.002500 -0.041410 0.101000 -vn -2.627994 3.665191 -1.517273 -v 0.002353 -0.041010 0.101550 -vn -2.627994 -3.665191 -1.517273 -v 0.002353 -0.041410 0.101550 -vn -1.517275 3.665190 -2.627993 -v 0.001950 -0.041010 0.101953 -vn -1.517275 -3.665190 -2.627993 -v 0.001950 -0.041410 0.101953 -vn -0.000002 3.665193 -3.034544 -v 0.001400 -0.041010 0.102100 -vn -0.000003 -3.665193 -3.034545 -v 0.001400 -0.041410 0.102100 -vn -0.000000 3.665193 3.034545 -v 0.020300 -0.041010 0.099900 -vn 0.000000 -3.665193 3.034545 -v 0.020300 -0.041410 0.099900 -vn -1.517277 3.665193 2.627990 -v 0.020850 -0.041010 0.100047 -vn -1.517277 -3.665193 2.627991 -v 0.020850 -0.041410 0.100047 -vn -2.627995 3.665186 1.517275 -v 0.021253 -0.041010 0.100450 -vn -2.627995 -3.665186 1.517275 -v 0.021253 -0.041410 0.100450 -vn -3.034544 3.665195 0.000005 -v 0.021400 -0.041010 0.101000 -vn -3.034544 -3.665195 0.000005 -v 0.021400 -0.041410 0.101000 -vn -2.627996 3.665189 -1.517270 -v 0.021253 -0.041010 0.101550 -vn -2.627996 -3.665190 -1.517270 -v 0.021253 -0.041410 0.101550 -vn -1.517277 3.665193 -2.627991 -v 0.020850 -0.041010 0.101953 -vn -1.517276 -3.665193 -2.627990 -v 0.020850 -0.041410 0.101953 -vn 0.000000 3.665193 -3.034545 -v 0.020300 -0.041010 0.102100 -vn -0.000000 -3.665193 -3.034545 -v 0.020300 -0.041410 0.102100 -vn -0.000000 3.665193 3.034545 -v 0.026800 -0.041010 0.099900 -vn 0.000000 -3.665193 3.034545 -v 0.026800 -0.041410 0.099900 -vn -1.517277 3.665193 2.627990 -v 0.027350 -0.041010 0.100047 -vn -1.517277 -3.665192 2.627991 -v 0.027350 -0.041410 0.100047 -vn -2.627995 3.665186 1.517275 -v 0.027753 -0.041010 0.100450 -vn -2.627995 -3.665186 1.517275 -v 0.027753 -0.041410 0.100450 -vn -3.034544 3.665195 0.000005 -v 0.027900 -0.041010 0.101000 -vn -3.034544 -3.665195 0.000005 -v 0.027900 -0.041410 0.101000 -vn -2.627996 3.665189 -1.517270 -v 0.027753 -0.041010 0.101550 -vn -2.627996 -3.665189 -1.517270 -v 0.027753 -0.041410 0.101550 -vn -1.517277 3.665193 -2.627991 -v 0.027350 -0.041010 0.101953 -vn -1.517276 -3.665195 -2.627990 -v 0.027350 -0.041410 0.101953 -vn 0.000000 3.665193 -3.034545 -v 0.026800 -0.041010 0.102100 -vn -0.000000 -3.665193 -3.034545 -v 0.026800 -0.041410 0.102100 -vn -0.000002 -2.617987 3.034542 -v 0.006650 -0.008510 0.080250 -vn 0.000240 -0.188726 -0.062829 -v 0.006650 -0.041410 0.080250 -vn -1.517275 -2.618001 2.627994 -v 0.007150 -0.008510 0.080384 -vn -1.517275 -3.665185 2.627994 -v 0.007150 -0.041410 0.080384 -vn -2.627991 -2.617990 1.517274 -v 0.007516 -0.008510 0.080750 -vn -2.627990 -3.665194 1.517274 -v 0.007516 -0.041410 0.080750 -vn -3.034545 -2.617996 -0.000000 -v 0.007650 -0.008510 0.081250 -vn -3.034545 -3.665190 0.000000 -v 0.007650 -0.041410 0.081250 -vn -2.627990 -2.617990 -1.517274 -v 0.007516 -0.008510 0.081750 -vn -2.627991 -3.665195 -1.517274 -v 0.007516 -0.041410 0.081750 -vn -1.517275 -2.618000 -2.627994 -v 0.007150 -0.008510 0.082116 -vn -1.517275 -3.665185 -2.627994 -v 0.007150 -0.041410 0.082116 -vn -0.000001 -2.617987 -3.034542 -v 0.006650 -0.008510 0.082250 -vn -0.000126 -0.188545 0.062824 -v 0.006650 -0.041410 0.082250 -vn -0.000003 3.665193 3.034545 -v 0.001400 -0.041010 0.081000 -vn -0.000002 -3.665193 3.034544 -v 0.001400 -0.041410 0.081000 -vn -1.517265 3.665181 2.628003 -v 0.001950 -0.041010 0.081147 -vn -1.517265 -3.665181 2.628003 -v 0.001950 -0.041410 0.081147 -vn -2.627983 3.665201 1.517283 -v 0.002353 -0.041010 0.081550 -vn -2.627983 -3.665199 1.517283 -v 0.002353 -0.041410 0.081550 -vn -3.034546 3.665191 0.000000 -v 0.002500 -0.041010 0.082100 -vn -3.034546 -3.665191 0.000000 -v 0.002500 -0.041410 0.082100 -vn -2.627994 3.665191 -1.517273 -v 0.002353 -0.041010 0.082650 -vn -2.627994 -3.665194 -1.517273 -v 0.002353 -0.041410 0.082650 -vn -1.517275 3.665190 -2.627993 -v 0.001950 -0.041010 0.083053 -vn -1.517275 -3.665190 -2.627993 -v 0.001950 -0.041410 0.083053 -vn -0.000002 3.665193 -3.034544 -v 0.001400 -0.041010 0.083200 -vn -0.000003 -3.665193 -3.034545 -v 0.001400 -0.041410 0.083200 -vn -0.000000 3.665193 3.034545 -v 0.020300 -0.041010 0.081000 -vn 0.000000 -3.665193 3.034545 -v 0.020300 -0.041410 0.081000 -vn -1.517266 3.665184 2.628001 -v 0.020850 -0.041010 0.081147 -vn -1.517266 -3.665184 2.628001 -v 0.020850 -0.041410 0.081147 -vn -2.627986 3.665198 1.517280 -v 0.021253 -0.041010 0.081550 -vn -2.627986 -3.665198 1.517280 -v 0.021253 -0.041410 0.081550 -vn -3.034546 3.665191 0.000000 -v 0.021400 -0.041010 0.082100 -vn -3.034546 -3.665191 0.000000 -v 0.021400 -0.041410 0.082100 -vn -2.627996 3.665189 -1.517270 -v 0.021253 -0.041010 0.082650 -vn -2.627996 -3.665190 -1.517270 -v 0.021253 -0.041410 0.082650 -vn -1.517277 3.665193 -2.627991 -v 0.020850 -0.041010 0.083053 -vn -1.517276 -3.665193 -2.627990 -v 0.020850 -0.041410 0.083053 -vn 0.000000 3.665193 -3.034545 -v 0.020300 -0.041010 0.083200 -vn -0.000000 -3.665193 -3.034545 -v 0.020300 -0.041410 0.083200 -vn -0.000000 3.665193 3.034545 -v 0.026800 -0.041010 0.081000 -vn 0.000000 -3.665193 3.034545 -v 0.026800 -0.041410 0.081000 -vn -1.517266 3.665184 2.628001 -v 0.027350 -0.041010 0.081147 -vn -1.517266 -3.665183 2.628001 -v 0.027350 -0.041410 0.081147 -vn -2.627986 3.665198 1.517280 -v 0.027753 -0.041010 0.081550 -vn -2.627986 -3.665198 1.517280 -v 0.027753 -0.041410 0.081550 -vn -3.034546 3.665191 0.000000 -v 0.027900 -0.041010 0.082100 -vn -3.034546 -3.665191 0.000000 -v 0.027900 -0.041410 0.082100 -vn -2.627996 3.665189 -1.517270 -v 0.027753 -0.041010 0.082650 -vn -2.627996 -3.665189 -1.517270 -v 0.027753 -0.041410 0.082650 -vn -1.517277 3.665193 -2.627991 -v 0.027350 -0.041010 0.083053 -vn -1.517276 -3.665193 -2.627990 -v 0.027350 -0.041410 0.083053 -vn 0.000000 3.665193 -3.034545 -v 0.026800 -0.041010 0.083200 -vn -0.000000 -3.665193 -3.034545 -v 0.026800 -0.041410 0.083200 -vn -0.000000 -2.617995 3.034546 -v 0.045700 -0.038810 0.099250 -vn 0.000000 2.617995 3.034546 -v 0.045700 -0.041010 0.099250 -vn -1.517275 -2.617990 2.627990 -v 0.046575 -0.038810 0.099484 -vn -1.517275 2.617990 2.627991 -v 0.046575 -0.041010 0.099484 -vn -2.627995 -2.618001 1.517276 -v 0.047216 -0.038810 0.100125 -vn -2.627995 2.618001 1.517276 -v 0.047216 -0.041010 0.100125 -vn -3.034543 -2.617987 0.000003 -v 0.047450 -0.038810 0.101000 -vn -3.034543 2.617987 0.000003 -v 0.047450 -0.041010 0.101000 -vn -2.627989 -2.617993 -1.517279 -v 0.047216 -0.038810 0.101875 -vn -2.627990 2.617993 -1.517279 -v 0.047216 -0.041010 0.101875 -vn -1.517269 -2.617996 -2.627997 -v 0.046575 -0.038810 0.102516 -vn -1.517268 2.617996 -2.627997 -v 0.046575 -0.041010 0.102516 -vn 0.000000 -2.617996 -3.034546 -v 0.045700 -0.038810 0.102750 -vn -0.000000 2.617995 -3.034546 -v 0.045700 -0.041010 0.102750 -vn 0.000000 3.665194 3.034544 -v 0.010850 -0.042010 0.089950 -vn -0.000000 -3.665194 3.034544 -v 0.010850 -0.042510 0.089950 -vn -1.517280 3.665195 2.627988 -v 0.011650 -0.042010 0.090164 -vn -1.517280 -3.665195 2.627988 -v 0.011650 -0.042510 0.090164 -vn -2.627999 3.665187 1.517267 -v 0.012236 -0.042010 0.090750 -vn -2.627999 -3.665187 1.517267 -v 0.012236 -0.042510 0.090750 -vn -3.034546 3.665191 -0.000000 -v 0.012450 -0.042010 0.091550 -vn -3.034546 -3.665191 0.000000 -v 0.012450 -0.042510 0.091550 -vn -2.627992 3.665193 -1.517274 -v 0.012236 -0.042010 0.092350 -vn -2.627992 -3.665193 -1.517274 -v 0.012236 -0.042510 0.092350 -vn -1.517273 3.665188 -2.627995 -v 0.011650 -0.042010 0.092936 -vn -1.517273 -3.665188 -2.627995 -v 0.011650 -0.042510 0.092936 -vn -0.000000 3.665194 -3.034544 -v 0.010850 -0.042010 0.093150 -vn 0.000000 -3.665194 -3.034544 -v 0.010850 -0.042510 0.093150 -vn 0.000002 3.665194 3.034545 -v 0.036250 -0.042010 0.089950 -vn 0.000002 -3.665194 3.034544 -v 0.036250 -0.042510 0.089950 -vn -1.517281 3.665197 2.627986 -v 0.037050 -0.042010 0.090164 -vn -1.517281 -3.665197 2.627986 -v 0.037050 -0.042510 0.090164 -vn -2.628000 3.665183 1.517269 -v 0.037636 -0.042010 0.090750 -vn -2.628000 -3.665183 1.517269 -v 0.037636 -0.042510 0.090750 -vn -3.034544 3.665196 -0.000000 -v 0.037850 -0.042010 0.091550 -vn -3.034544 -3.665195 0.000000 -v 0.037850 -0.042510 0.091550 -vn -2.627993 3.665190 -1.517276 -v 0.037636 -0.042010 0.092350 -vn -2.627993 -3.665190 -1.517276 -v 0.037636 -0.042510 0.092350 -vn -1.517274 3.665191 -2.627993 -v 0.037050 -0.042010 0.092936 -vn -1.517274 -3.665191 -2.627993 -v 0.037050 -0.042510 0.092936 -vn 0.000002 3.665194 -3.034544 -v 0.036250 -0.042010 0.093150 -vn 0.000002 -3.665194 -3.034545 -v 0.036250 -0.042510 0.093150 -vn -0.000000 2.617995 -3.034546 -v 0.036250 -0.042610 0.101631 -vn 0.000000 -2.617995 -3.034546 -v 0.036250 -0.040410 0.101631 -vn -1.517275 2.617990 -2.627990 -v 0.037125 -0.042610 0.101397 -vn -1.517275 -2.617990 -2.627991 -v 0.037125 -0.040410 0.101397 -vn -2.627997 2.617997 -1.517270 -v 0.037766 -0.042610 0.100756 -vn -2.627996 -2.617997 -1.517270 -v 0.037766 -0.040410 0.100756 -vn -3.034546 2.617995 -0.000003 -v 0.038000 -0.042610 0.099881 -vn -3.034546 -2.617995 -0.000003 -v 0.038000 -0.040410 0.099881 -vn -2.627991 2.617989 1.517273 -v 0.037766 -0.042610 0.099006 -vn -2.627991 -2.617989 1.517273 -v 0.037766 -0.040410 0.099006 -vn -1.517281 2.618004 2.627994 -v 0.037125 -0.042610 0.098366 -vn -1.517280 -2.618004 2.627994 -v 0.037125 -0.040410 0.098366 -vn 0.000000 2.617980 3.034540 -v 0.036250 -0.042610 0.098131 -vn -0.000000 -2.617979 3.034540 -v 0.036250 -0.040410 0.098131 -vn -0.000000 -0.358222 0.096313 -v 0.044581 -0.042610 0.093300 -vn 0.000000 0.358223 0.096313 -v 0.044581 -0.040410 0.093300 -vn -1.517275 2.617990 -2.627990 -v 0.045456 -0.042610 0.093066 -vn -1.517275 -2.617990 -2.627991 -v 0.045456 -0.040410 0.093066 -vn -2.627997 2.617997 -1.517270 -v 0.046097 -0.042610 0.092425 -vn -2.627996 -2.617997 -1.517270 -v 0.046097 -0.040410 0.092425 -vn -3.034546 2.617995 -0.000003 -v 0.046331 -0.042610 0.091550 -vn -3.034546 -2.617995 -0.000003 -v 0.046331 -0.040410 0.091550 -vn -2.627991 2.617990 1.517273 -v 0.046097 -0.042610 0.090675 -vn -2.627991 -2.617989 1.517273 -v 0.046097 -0.040410 0.090675 -vn -1.517269 2.617996 2.627997 -v 0.045456 -0.042610 0.090034 -vn -1.517268 -2.617996 2.627997 -v 0.045456 -0.040410 0.090034 -vn 0.000000 -0.358274 -0.096320 -v 0.044581 -0.042610 0.089800 -vn -0.000000 0.358274 -0.096320 -v 0.044581 -0.040410 0.089800 -vn -0.000000 2.617995 -3.034546 -v 0.036250 -0.042610 0.084969 -vn 0.000000 -2.617996 -3.034546 -v 0.036250 -0.040410 0.084969 -vn -1.517268 2.617996 -2.627997 -v 0.037125 -0.042610 0.084734 -vn -1.517269 -2.617996 -2.627997 -v 0.037125 -0.040410 0.084734 -vn -2.627991 2.617989 -1.517273 -v 0.037766 -0.042610 0.084094 -vn -2.627991 -2.617989 -1.517273 -v 0.037766 -0.040410 0.084094 -vn -3.034546 2.617995 0.000003 -v 0.038000 -0.042610 0.083219 -vn -3.034546 -2.617995 0.000003 -v 0.038000 -0.040410 0.083219 -vn -2.627996 2.617997 1.517270 -v 0.037766 -0.042610 0.082344 -vn -2.627997 -2.617997 1.517270 -v 0.037766 -0.040410 0.082344 -vn -1.517275 2.617990 2.627991 -v 0.037125 -0.042610 0.081703 -vn -1.517275 -2.617990 2.627990 -v 0.037125 -0.040410 0.081703 -vn 0.000000 2.617996 3.034546 -v 0.036250 -0.042610 0.081469 -vn -0.000000 -2.617995 3.034546 -v 0.036250 -0.040410 0.081469 -vn 0.000001 -0.358223 0.096313 -v 0.027919 -0.042610 0.093300 -vn 0.000001 0.358223 0.096313 -v 0.027919 -0.040410 0.093300 -vn -1.517275 2.617990 -2.627990 -v 0.028794 -0.042610 0.093066 -vn -1.517275 -2.617990 -2.627991 -v 0.028794 -0.040410 0.093066 -vn -2.627997 2.617997 -1.517270 -v 0.029434 -0.042610 0.092425 -vn -2.627996 -2.617997 -1.517270 -v 0.029434 -0.040410 0.092425 -vn -3.034546 2.617995 -0.000003 -v 0.029669 -0.042610 0.091550 -vn -3.034546 -2.617995 -0.000003 -v 0.029669 -0.040410 0.091550 -vn -2.627991 2.617990 1.517273 -v 0.029434 -0.042610 0.090675 -vn -2.627991 -2.617989 1.517273 -v 0.029434 -0.040410 0.090675 -vn -1.517269 2.617996 2.627997 -v 0.028794 -0.042610 0.090034 -vn -1.517268 -2.617996 2.627997 -v 0.028794 -0.040410 0.090034 -vn 0.000001 -0.358274 -0.096320 -v 0.027919 -0.042610 0.089800 -vn 0.000001 0.358275 -0.096320 -v 0.027919 -0.040410 0.089800 -vn -0.000000 -2.617995 3.034546 -v 0.019181 -0.040410 0.089800 -vn 0.000000 2.617995 3.034546 -v 0.019181 -0.042610 0.089800 -vn -1.517268 -2.617996 2.627997 -v 0.020056 -0.040410 0.090034 -vn -1.517269 2.617996 2.627997 -v 0.020056 -0.042610 0.090034 -vn -2.627991 -2.617989 1.517273 -v 0.020697 -0.040410 0.090675 -vn -2.627991 2.617990 1.517273 -v 0.020697 -0.042610 0.090675 -vn -3.034546 -2.617995 -0.000003 -v 0.020931 -0.040410 0.091550 -vn -3.034546 2.617995 -0.000003 -v 0.020931 -0.042610 0.091550 -vn -2.627996 -2.617997 -1.517270 -v 0.020697 -0.040410 0.092425 -vn -2.627997 2.617997 -1.517270 -v 0.020697 -0.042610 0.092425 -vn -1.517275 -2.617990 -2.627991 -v 0.020056 -0.040410 0.093066 -vn -1.517275 2.617990 -2.627990 -v 0.020056 -0.042610 0.093066 -vn 0.000000 -2.617995 -3.034546 -v 0.019181 -0.040410 0.093300 -vn -0.000000 2.617995 -3.034546 -v 0.019181 -0.042610 0.093300 -vn -0.000000 -2.617995 3.034546 -v 0.010850 -0.040410 0.081469 -vn 0.000000 2.617995 3.034546 -v 0.010850 -0.042610 0.081469 -vn -1.517275 -2.617990 2.627990 -v 0.011725 -0.040410 0.081703 -vn -1.517275 2.617990 2.627991 -v 0.011725 -0.042610 0.081703 -vn -2.627997 -2.617997 1.517270 -v 0.012366 -0.040410 0.082344 -vn -2.627996 2.617997 1.517270 -v 0.012366 -0.042610 0.082344 -vn -3.034546 -2.617995 0.000003 -v 0.012600 -0.040410 0.083219 -vn -3.034546 2.617995 0.000003 -v 0.012600 -0.042610 0.083219 -vn -2.627991 -2.617990 -1.517273 -v 0.012366 -0.040410 0.084094 -vn -2.627991 2.617989 -1.517273 -v 0.012366 -0.042610 0.084094 -vn -1.517269 -2.617996 -2.627997 -v 0.011725 -0.040410 0.084734 -vn -1.517268 2.617996 -2.627997 -v 0.011725 -0.042610 0.084734 -vn 0.000000 -2.617995 -3.034546 -v 0.010850 -0.040410 0.084969 -vn -0.000000 2.617995 -3.034546 -v 0.010850 -0.042610 0.084969 -vn -0.000002 0.358275 -0.096320 -v 0.002519 -0.040410 0.089800 -vn -0.000002 -0.358275 -0.096320 -v 0.002519 -0.042610 0.089800 -vn -1.517268 -2.617996 2.627997 -v 0.003394 -0.040410 0.090034 -vn -1.517269 2.617996 2.627997 -v 0.003394 -0.042610 0.090034 -vn -2.627990 -2.617993 1.517279 -v 0.004034 -0.040410 0.090675 -vn -2.627989 2.617993 1.517279 -v 0.004034 -0.042610 0.090675 -vn -3.034543 -2.617987 -0.000003 -v 0.004269 -0.040410 0.091550 -vn -3.034543 2.617987 -0.000003 -v 0.004269 -0.042610 0.091550 -vn -2.627995 -2.618001 -1.517276 -v 0.004034 -0.040410 0.092425 -vn -2.627995 2.618001 -1.517276 -v 0.004034 -0.042610 0.092425 -vn -1.517275 -2.617990 -2.627991 -v 0.003394 -0.040410 0.093066 -vn -1.517275 2.617990 -2.627990 -v 0.003394 -0.042610 0.093066 -vn -0.000002 0.358223 0.096313 -v 0.002519 -0.040410 0.093300 -vn -0.000002 -0.358224 0.096313 -v 0.002519 -0.042610 0.093300 -vn 0.000001 0.358239 -0.096319 -v 0.010850 -0.040410 0.098131 -vn 0.000001 -0.358239 -0.096319 -v 0.010850 -0.042610 0.098131 -vn -1.517280 -2.618004 2.627994 -v 0.011725 -0.040410 0.098366 -vn -1.517281 2.618004 2.627994 -v 0.011725 -0.042610 0.098366 -vn -2.627991 -2.617989 1.517273 -v 0.012366 -0.040410 0.099006 -vn -2.627991 2.617990 1.517273 -v 0.012366 -0.042610 0.099006 -vn -3.034546 -2.617995 -0.000003 -v 0.012600 -0.040410 0.099881 -vn -3.034546 2.617995 -0.000003 -v 0.012600 -0.042610 0.099881 -vn -2.627996 -2.617997 -1.517270 -v 0.012366 -0.040410 0.100756 -vn -2.627997 2.617997 -1.517270 -v 0.012366 -0.042610 0.100756 -vn -1.517275 -2.617990 -2.627991 -v 0.011725 -0.040410 0.101397 -vn -1.517275 2.617990 -2.627990 -v 0.011725 -0.042610 0.101397 -vn 0.000001 0.358223 0.096313 -v 0.010850 -0.040410 0.101631 -vn 0.000001 -0.358223 0.096313 -v 0.010850 -0.042610 0.101631 -vn -0.000000 -2.617995 3.034546 -v 0.045700 -0.038810 0.080350 -vn 0.000000 2.617995 3.034546 -v 0.045700 -0.041010 0.080350 -vn -1.517275 -2.617990 2.627990 -v 0.046575 -0.038810 0.080584 -vn -1.517275 2.617990 2.627991 -v 0.046575 -0.041010 0.080584 -vn -2.627995 -2.618001 1.517276 -v 0.047216 -0.038810 0.081225 -vn -2.627995 2.618001 1.517276 -v 0.047216 -0.041010 0.081225 -vn -3.034543 -2.617987 0.000003 -v 0.047450 -0.038810 0.082100 -vn -3.034543 2.617987 0.000003 -v 0.047450 -0.041010 0.082100 -vn -2.627989 -2.617993 -1.517279 -v 0.047216 -0.038810 0.082975 -vn -2.627990 2.617993 -1.517279 -v 0.047216 -0.041010 0.082975 -vn -1.517269 -2.617996 -2.627997 -v 0.046575 -0.038810 0.083616 -vn -1.517268 2.617996 -2.627997 -v 0.046575 -0.041010 0.083616 -vn 0.000000 -2.617996 -3.034546 -v 0.045700 -0.038810 0.083850 -vn -0.000000 2.617995 -3.034546 -v 0.045700 -0.041010 0.083850 -vn 0.000000 -2.617995 3.034546 -v 0.001400 -0.038810 0.099250 -vn 0.000000 2.617995 3.034546 -v 0.001400 -0.041010 0.099250 -vn -1.517275 -2.617990 2.627990 -v 0.002275 -0.038810 0.099484 -vn -1.517275 2.617990 2.627991 -v 0.002275 -0.041010 0.099484 -vn -2.627997 -2.617997 1.517270 -v 0.002916 -0.038810 0.100125 -vn -2.627996 2.617997 1.517270 -v 0.002916 -0.041010 0.100125 -vn -3.034546 -2.617995 0.000003 -v 0.003150 -0.038810 0.101000 -vn -3.034546 2.617995 0.000003 -v 0.003150 -0.041010 0.101000 -vn -2.627991 -2.617990 -1.517273 -v 0.002916 -0.038810 0.101875 -vn -2.627991 2.617989 -1.517273 -v 0.002916 -0.041010 0.101875 -vn -1.517269 -2.617996 -2.627997 -v 0.002275 -0.038810 0.102516 -vn -1.517268 2.617996 -2.627997 -v 0.002275 -0.041010 0.102516 -vn 0.000000 -2.617995 -3.034546 -v 0.001400 -0.038810 0.102750 -vn 0.000000 2.617996 -3.034546 -v 0.001400 -0.041010 0.102750 -vn -0.000000 0.358224 -0.096313 -v 0.020300 -0.038810 0.099250 -vn 0.000000 -0.358224 -0.096313 -v 0.020300 -0.041010 0.099250 -vn -1.517275 -2.617990 2.627990 -v 0.021175 -0.038810 0.099484 -vn -1.517275 2.617990 2.627991 -v 0.021175 -0.041010 0.099484 -vn -2.627997 -2.617997 1.517270 -v 0.021816 -0.038810 0.100125 -vn -2.627996 2.617997 1.517270 -v 0.021816 -0.041010 0.100125 -vn -3.034546 -2.617995 0.000003 -v 0.022050 -0.038810 0.101000 -vn -3.034546 2.617995 0.000003 -v 0.022050 -0.041010 0.101000 -vn -2.627991 -2.617990 -1.517273 -v 0.021816 -0.038810 0.101875 -vn -2.627991 2.617989 -1.517273 -v 0.021816 -0.041010 0.101875 -vn -1.517269 -2.617996 -2.627997 -v 0.021175 -0.038810 0.102516 -vn -1.517268 2.617996 -2.627997 -v 0.021175 -0.041010 0.102516 -vn 0.000000 0.358275 0.096320 -v 0.020300 -0.038810 0.102750 -vn -0.000000 -0.358275 0.096320 -v 0.020300 -0.041010 0.102750 -vn -0.000000 -2.617995 3.034546 -v 0.026800 -0.038810 0.099250 -vn 0.000000 2.617995 3.034546 -v 0.026800 -0.041010 0.099250 -vn -1.517276 -2.617989 2.627989 -v 0.027675 -0.038810 0.099484 -vn -1.517276 2.617989 2.627989 -v 0.027675 -0.041010 0.099484 -vn -2.627997 -2.618001 1.517271 -v 0.028316 -0.038810 0.100125 -vn -2.627997 2.618001 1.517271 -v 0.028316 -0.041010 0.100125 -vn -3.034544 -2.617991 0.000003 -v 0.028550 -0.038810 0.101000 -vn -3.034544 2.617991 0.000003 -v 0.028550 -0.041010 0.101000 -vn -2.627992 -2.617993 -1.517275 -v 0.028316 -0.038810 0.101875 -vn -2.627992 2.617992 -1.517275 -v 0.028316 -0.041010 0.101875 -vn -1.517270 -2.617995 -2.627995 -v 0.027675 -0.038810 0.102516 -vn -1.517270 2.617995 -2.627995 -v 0.027675 -0.041010 0.102516 -vn 0.000000 -2.617995 -3.034546 -v 0.026800 -0.038810 0.102750 -vn -0.000000 2.617995 -3.034546 -v 0.026800 -0.041010 0.102750 -vn 0.000000 0.358222 -0.096313 -v 0.001400 -0.038810 0.080350 -vn 0.000000 -0.358223 -0.096313 -v 0.001400 -0.041010 0.080350 -vn -1.517275 -2.617990 2.627990 -v 0.002275 -0.038810 0.080584 -vn -1.517275 2.617990 2.627991 -v 0.002275 -0.041010 0.080584 -vn -2.627997 -2.617997 1.517270 -v 0.002916 -0.038810 0.081225 -vn -2.627996 2.617997 1.517270 -v 0.002916 -0.041010 0.081225 -vn -3.034546 -2.617995 0.000003 -v 0.003150 -0.038810 0.082100 -vn -3.034546 2.617995 0.000003 -v 0.003150 -0.041010 0.082100 -vn -2.627991 -2.617990 -1.517273 -v 0.002916 -0.038810 0.082975 -vn -2.627991 2.617989 -1.517273 -v 0.002916 -0.041010 0.082975 -vn -1.517269 -2.617996 -2.627997 -v 0.002275 -0.038810 0.083616 -vn -1.517268 2.617996 -2.627997 -v 0.002275 -0.041010 0.083616 -vn 0.000000 0.358274 0.096320 -v 0.001400 -0.038810 0.083850 -vn 0.000000 -0.358274 0.096319 -v 0.001400 -0.041010 0.083850 -vn -0.000000 -2.617995 3.034546 -v 0.020300 -0.038810 0.080350 -vn 0.000000 2.617995 3.034546 -v 0.020300 -0.041010 0.080350 -vn -1.517275 -2.617990 2.627990 -v 0.021175 -0.038810 0.080584 -vn -1.517275 2.617990 2.627991 -v 0.021175 -0.041010 0.080584 -vn -2.627997 -2.617997 1.517270 -v 0.021816 -0.038810 0.081225 -vn -2.627996 2.617997 1.517270 -v 0.021816 -0.041010 0.081225 -vn -3.034546 -2.617995 0.000003 -v 0.022050 -0.038810 0.082100 -vn -3.034546 2.617995 0.000003 -v 0.022050 -0.041010 0.082100 -vn -2.627991 -2.617990 -1.517273 -v 0.021816 -0.038810 0.082975 -vn -2.627991 2.617989 -1.517273 -v 0.021816 -0.041010 0.082975 -vn -1.517269 -2.617996 -2.627997 -v 0.021175 -0.038810 0.083616 -vn -1.517268 2.617996 -2.627997 -v 0.021175 -0.041010 0.083616 -vn 0.000000 -2.617995 -3.034546 -v 0.020300 -0.038810 0.083850 -vn -0.000000 2.617995 -3.034546 -v 0.020300 -0.041010 0.083850 -vn -0.000000 -2.617995 3.034546 -v 0.026800 -0.038810 0.080350 -vn 0.000000 2.617995 3.034546 -v 0.026800 -0.041010 0.080350 -vn -1.517276 -2.617989 2.627989 -v 0.027675 -0.038810 0.080584 -vn -1.517276 2.617989 2.627989 -v 0.027675 -0.041010 0.080584 -vn -2.627997 -2.618001 1.517271 -v 0.028316 -0.038810 0.081225 -vn -2.627997 2.618001 1.517271 -v 0.028316 -0.041010 0.081225 -vn -3.034544 -2.617991 0.000003 -v 0.028550 -0.038810 0.082100 -vn -3.034544 2.617991 0.000003 -v 0.028550 -0.041010 0.082100 -vn -2.627992 -2.617993 -1.517275 -v 0.028316 -0.038810 0.082975 -vn -2.627992 2.617992 -1.517275 -v 0.028316 -0.041010 0.082975 -vn -1.517270 -2.617995 -2.627995 -v 0.027675 -0.038810 0.083616 -vn -1.517270 2.617995 -2.627995 -v 0.027675 -0.041010 0.083616 -vn 0.000000 -2.617995 -3.034546 -v 0.026800 -0.038810 0.083850 -vn -0.000000 2.617995 -3.034546 -v 0.026800 -0.041010 0.083850 -vn 0.000003 3.665196 3.034545 -v 0.045700 -0.038080 0.099900 -vn 0.000003 -3.665193 3.034545 -v 0.045700 -0.038810 0.099900 -vn -1.517272 3.665192 2.627994 -v 0.046250 -0.038080 0.100047 -vn -1.517272 -3.665192 2.627993 -v 0.046250 -0.038810 0.100047 -vn -2.627995 3.665194 1.517268 -v 0.046653 -0.038080 0.100450 -vn -2.627995 -3.665195 1.517268 -v 0.046653 -0.038810 0.100450 -vn -3.034549 3.665182 0.000005 -v 0.046800 -0.038080 0.101000 -vn -3.034549 -3.665182 0.000005 -v 0.046800 -0.038810 0.101000 -vn -2.627996 3.665198 -1.517263 -v 0.046653 -0.038080 0.101550 -vn -2.627996 -3.665198 -1.517263 -v 0.046653 -0.038810 0.101550 -vn -1.517272 3.665192 -2.627994 -v 0.046250 -0.038080 0.101953 -vn -1.517272 -3.665191 -2.627994 -v 0.046250 -0.038810 0.101953 -vn 0.000003 3.665193 -3.034545 -v 0.045700 -0.038080 0.102100 -vn 0.000003 -3.665193 -3.034545 -v 0.045700 -0.038810 0.102100 -vn 0.000000 0.283470 -0.068038 -v 0.010850 -0.039010 0.088550 -vn -0.000000 -0.283470 -0.068037 -v 0.010850 -0.042010 0.088550 -vn -1.328910 -2.692792 2.759511 -v 0.012152 -0.039010 0.088847 -vn -1.328910 2.692791 2.759511 -v 0.012152 -0.042010 0.088847 -vn -2.394615 -2.692795 1.909641 -v 0.013195 -0.039010 0.089680 -vn -2.394615 2.692795 1.909640 -v 0.013195 -0.042010 0.089680 -vn -2.986035 -2.692793 0.681543 -v 0.013775 -0.039010 0.090882 -vn -2.986035 2.692794 0.681543 -v 0.013775 -0.042010 0.090882 -vn -2.986035 -2.692794 -0.681543 -v 0.013775 -0.039010 0.092218 -vn -2.986035 2.692793 -0.681543 -v 0.013775 -0.042010 0.092218 -vn -2.394615 -2.692795 -1.909640 -v 0.013195 -0.039010 0.093420 -vn -2.394615 2.692795 -1.909641 -v 0.013195 -0.042010 0.093420 -vn -1.328910 -2.692792 -2.759511 -v 0.012152 -0.039010 0.094253 -vn -1.328910 2.692792 -2.759511 -v 0.012152 -0.042010 0.094253 -vn -0.000000 0.283440 0.068034 -v 0.010850 -0.039010 0.094550 -vn 0.000000 -0.283440 0.068034 -v 0.010850 -0.042010 0.094550 -vn 0.000001 -0.283439 0.068034 -v 0.036250 -0.042010 0.094550 -vn 0.000001 0.283440 0.068034 -v 0.036250 -0.039010 0.094550 -vn -1.328910 2.692791 -2.759510 -v 0.037552 -0.042010 0.094253 -vn -1.328910 -2.692791 -2.759510 -v 0.037552 -0.039010 0.094253 -vn -2.394615 2.692797 -1.909642 -v 0.038595 -0.042010 0.093420 -vn -2.394615 -2.692797 -1.909641 -v 0.038595 -0.039010 0.093420 -vn -2.986034 2.692792 -0.681545 -v 0.039175 -0.042010 0.092218 -vn -2.986034 -2.692792 -0.681545 -v 0.039175 -0.039010 0.092218 -vn -2.986034 2.692792 0.681545 -v 0.039175 -0.042010 0.090882 -vn -2.986034 -2.692792 0.681545 -v 0.039175 -0.039010 0.090882 -vn -2.394615 2.692797 1.909641 -v 0.038595 -0.042010 0.089680 -vn -2.394615 -2.692797 1.909642 -v 0.038595 -0.039010 0.089680 -vn -1.328910 2.692790 2.759510 -v 0.037552 -0.042010 0.088847 -vn -1.328910 -2.692791 2.759510 -v 0.037552 -0.039010 0.088847 -vn 0.000001 -0.283470 -0.068038 -v 0.036250 -0.042010 0.088550 -vn 0.000001 0.283469 -0.068038 -v 0.036250 -0.039010 0.088550 -vn 0.000003 -2.617992 3.034545 -v 0.036250 -0.036660 0.098781 -vn 0.000003 -3.665193 3.034545 -v 0.036250 -0.040410 0.098781 -vn -1.517278 -2.617989 2.627989 -v 0.036800 -0.036660 0.098929 -vn -1.517277 -3.665196 2.627988 -v 0.036800 -0.040410 0.098929 -vn -2.627999 -2.617998 1.517267 -v 0.037203 -0.036660 0.099331 -vn -2.627999 -3.665187 1.517267 -v 0.037203 -0.040410 0.099331 -vn -3.034544 -2.617991 -0.000005 -v 0.037350 -0.036660 0.099881 -vn -3.034544 -3.665195 -0.000005 -v 0.037350 -0.040410 0.099881 -vn -2.627997 -2.618002 -1.517273 -v 0.037203 -0.036660 0.100431 -vn -2.627997 -3.665184 -1.517272 -v 0.037203 -0.040410 0.100431 -vn -1.517278 -2.617989 -2.627988 -v 0.036800 -0.036660 0.100834 -vn -1.517278 -3.665196 -2.627989 -v 0.036800 -0.040410 0.100834 -vn 0.000003 -2.617992 -3.034545 -v 0.036250 -0.036660 0.100981 -vn 0.000003 -3.665193 -3.034545 -v 0.036250 -0.040410 0.100981 -vn 0.000003 -2.618018 3.034555 -v 0.036250 -0.036660 0.082119 -vn 0.000003 -3.665168 3.034555 -v 0.036250 -0.040410 0.082119 -vn -1.517258 -2.617977 2.627994 -v 0.036800 -0.036660 0.082266 -vn -1.517258 -3.665209 2.627994 -v 0.036800 -0.040410 0.082266 -vn -2.627999 -2.617999 1.517267 -v 0.037203 -0.036660 0.082669 -vn -2.627999 -3.665187 1.517267 -v 0.037203 -0.040410 0.082669 -vn -3.034546 -2.617995 0.000000 -v 0.037350 -0.036660 0.083219 -vn -3.034546 -3.665191 0.000000 -v 0.037350 -0.040410 0.083219 -vn -2.627999 -2.617998 -1.517267 -v 0.037203 -0.036660 0.083769 -vn -2.627999 -3.665187 -1.517267 -v 0.037203 -0.040410 0.083769 -vn -1.517278 -2.617989 -2.627988 -v 0.036800 -0.036660 0.084171 -vn -1.517278 -3.665196 -2.627989 -v 0.036800 -0.040410 0.084171 -vn 0.000003 -2.617992 -3.034545 -v 0.036250 -0.036660 0.084319 -vn 0.000003 -3.665193 -3.034545 -v 0.036250 -0.040410 0.084319 -vn -0.000000 -2.617992 3.034544 -v 0.027919 -0.036660 0.090450 -vn 0.000000 -3.665193 3.034544 -v 0.027919 -0.040410 0.090450 -vn -1.517276 -2.617992 2.627990 -v 0.028469 -0.036660 0.090597 -vn -1.517276 -3.665193 2.627991 -v 0.028469 -0.040410 0.090597 -vn -2.627996 -2.617996 1.517270 -v 0.028871 -0.036660 0.091000 -vn -2.627996 -3.665189 1.517270 -v 0.028871 -0.040410 0.091000 -vn -3.034546 -2.617994 0.000000 -v 0.029019 -0.036660 0.091550 -vn -3.034546 -3.665191 0.000000 -v 0.029019 -0.040410 0.091550 -vn -2.627986 -2.617987 -1.517280 -v 0.028871 -0.036660 0.092100 -vn -2.627986 -3.665198 -1.517280 -v 0.028871 -0.040410 0.092100 -vn -1.517266 -2.618001 -2.628001 -v 0.028469 -0.036660 0.092503 -vn -1.517266 -3.665184 -2.628000 -v 0.028469 -0.040410 0.092503 -vn 0.000000 -2.617992 -3.034544 -v 0.027919 -0.036660 0.092650 -vn -0.000000 -3.665193 -3.034544 -v 0.027919 -0.040410 0.092650 -vn -0.000000 -2.617992 3.034544 -v 0.019181 -0.036660 0.090450 -vn 0.000000 -3.665193 3.034544 -v 0.019181 -0.040410 0.090450 -vn -1.517276 -2.617992 2.627990 -v 0.019731 -0.036660 0.090597 -vn -1.517276 -3.665193 2.627991 -v 0.019731 -0.040410 0.090597 -vn -2.627996 -2.617996 1.517270 -v 0.020134 -0.036660 0.091000 -vn -2.627996 -3.665189 1.517270 -v 0.020134 -0.040410 0.091000 -vn -3.034546 -2.617994 0.000000 -v 0.020281 -0.036660 0.091550 -vn -3.034546 -3.665191 0.000000 -v 0.020281 -0.040410 0.091550 -vn -2.627986 -2.617987 -1.517280 -v 0.020134 -0.036660 0.092100 -vn -2.627986 -3.665198 -1.517280 -v 0.020134 -0.040410 0.092100 -vn -1.517266 -2.618001 -2.628001 -v 0.019731 -0.036660 0.092503 -vn -1.517266 -3.665184 -2.628000 -v 0.019731 -0.040410 0.092503 -vn 0.000000 -2.617993 -3.034544 -v 0.019181 -0.036660 0.092650 -vn -0.000000 -3.665193 -3.034544 -v 0.019181 -0.040410 0.092650 -vn -0.000000 -2.618018 3.034555 -v 0.010850 -0.036660 0.082119 -vn 0.000000 -3.665168 3.034555 -v 0.010850 -0.040410 0.082119 -vn -1.517257 -2.617980 2.627996 -v 0.011400 -0.036660 0.082266 -vn -1.517257 -3.665205 2.627996 -v 0.011400 -0.040410 0.082266 -vn -2.627996 -2.617996 1.517270 -v 0.011803 -0.036660 0.082669 -vn -2.627996 -3.665189 1.517270 -v 0.011803 -0.040410 0.082669 -vn -3.034546 -2.617994 0.000000 -v 0.011950 -0.036660 0.083219 -vn -3.034546 -3.665191 0.000000 -v 0.011950 -0.040410 0.083219 -vn -2.627996 -2.617997 -1.517270 -v 0.011803 -0.036660 0.083769 -vn -2.627996 -3.665189 -1.517270 -v 0.011803 -0.040410 0.083769 -vn -1.517276 -2.617992 -2.627991 -v 0.011400 -0.036660 0.084171 -vn -1.517276 -3.665193 -2.627990 -v 0.011400 -0.040410 0.084171 -vn 0.000000 -2.617992 -3.034544 -v 0.010850 -0.036660 0.084319 -vn -0.000000 -3.665193 -3.034544 -v 0.010850 -0.040410 0.084319 -vn 0.000003 -2.617992 3.034545 -v 0.002519 -0.036660 0.090450 -vn 0.000003 -3.665193 3.034545 -v 0.002519 -0.040410 0.090450 -vn -1.517273 -2.617994 2.627994 -v 0.003069 -0.036660 0.090597 -vn -1.517272 -3.665192 2.627993 -v 0.003069 -0.040410 0.090597 -vn -2.627996 -2.617988 1.517263 -v 0.003471 -0.036660 0.091000 -vn -2.627996 -3.665198 1.517263 -v 0.003471 -0.040410 0.091000 -vn -3.034551 -2.618006 -0.000000 -v 0.003619 -0.036660 0.091550 -vn -3.034551 -3.665178 0.000000 -v 0.003619 -0.040410 0.091550 -vn -2.627986 -2.617978 -1.517273 -v 0.003471 -0.036660 0.092100 -vn -2.627986 -3.665207 -1.517273 -v 0.003471 -0.040410 0.092100 -vn -1.517262 -2.618003 -2.628004 -v 0.003069 -0.036660 0.092503 -vn -1.517262 -3.665182 -2.628004 -v 0.003069 -0.040410 0.092503 -vn 0.000003 -2.617992 -3.034545 -v 0.002519 -0.036660 0.092650 -vn 0.000003 -3.665193 -3.034545 -v 0.002519 -0.040410 0.092650 -vn -0.000000 -2.617992 3.034544 -v 0.010850 -0.036660 0.098781 -vn 0.000000 -3.665193 3.034544 -v 0.010850 -0.040410 0.098781 -vn -1.517276 -2.617992 2.627990 -v 0.011400 -0.036660 0.098929 -vn -1.517276 -3.665193 2.627991 -v 0.011400 -0.040410 0.098929 -vn -2.627996 -2.617996 1.517270 -v 0.011803 -0.036660 0.099331 -vn -2.627996 -3.665189 1.517270 -v 0.011803 -0.040410 0.099331 -vn -3.034544 -2.617991 -0.000005 -v 0.011950 -0.036660 0.099881 -vn -3.034544 -3.665195 -0.000005 -v 0.011950 -0.040410 0.099881 -vn -2.627995 -2.618000 -1.517275 -v 0.011803 -0.036660 0.100431 -vn -2.627995 -3.665186 -1.517275 -v 0.011803 -0.040410 0.100431 -vn -1.517276 -2.617992 -2.627991 -v 0.011400 -0.036660 0.100834 -vn -1.517276 -3.665193 -2.627990 -v 0.011400 -0.040410 0.100834 -vn 0.000000 -2.617992 -3.034544 -v 0.010850 -0.036660 0.100981 -vn -0.000000 -3.665193 -3.034544 -v 0.010850 -0.040410 0.100981 -vn 0.000003 3.665193 3.034545 -v 0.045700 -0.038080 0.081000 -vn 0.000003 -3.665193 3.034545 -v 0.045700 -0.038810 0.081000 -vn -1.517262 3.665183 2.628004 -v 0.046250 -0.038080 0.081147 -vn -1.517262 -3.665182 2.628004 -v 0.046250 -0.038810 0.081147 -vn -2.627986 3.665207 1.517273 -v 0.046653 -0.038080 0.081550 -vn -2.627986 -3.665207 1.517273 -v 0.046653 -0.038810 0.081550 -vn -3.034551 3.665179 -0.000000 -v 0.046800 -0.038080 0.082100 -vn -3.034551 -3.665179 0.000000 -v 0.046800 -0.038810 0.082100 -vn -2.627996 3.665199 -1.517263 -v 0.046653 -0.038080 0.082650 -vn -2.627996 -3.665198 -1.517263 -v 0.046653 -0.038810 0.082650 -vn -1.517272 3.665192 -2.627994 -v 0.046250 -0.038080 0.083053 -vn -1.517272 -3.665191 -2.627994 -v 0.046250 -0.038810 0.083053 -vn 0.000003 3.665192 -3.034545 -v 0.045700 -0.038080 0.083200 -vn 0.000003 -3.665193 -3.034545 -v 0.045700 -0.038810 0.083200 -vn -0.000003 -2.617992 3.034545 -v 0.001400 -0.035060 0.099900 -vn -0.000003 -3.665193 3.034545 -v 0.001400 -0.038810 0.099900 -vn -1.517275 -2.617996 2.627993 -v 0.001950 -0.035060 0.100047 -vn -1.517275 -3.665190 2.627993 -v 0.001950 -0.038810 0.100047 -vn -2.627992 -2.617997 1.517277 -v 0.002353 -0.035060 0.100450 -vn -2.627992 -3.665188 1.517278 -v 0.002353 -0.038810 0.100450 -vn -3.034544 -2.617991 0.000005 -v 0.002500 -0.035060 0.101000 -vn -3.034544 -3.665195 0.000005 -v 0.002500 -0.038810 0.101000 -vn -2.627994 -2.617994 -1.517273 -v 0.002353 -0.035060 0.101550 -vn -2.627993 -3.665192 -1.517272 -v 0.002353 -0.038810 0.101550 -vn -1.517275 -2.617995 -2.627993 -v 0.001950 -0.035060 0.101953 -vn -1.517275 -3.665190 -2.627993 -v 0.001950 -0.038810 0.101953 -vn -0.000003 -2.617992 -3.034545 -v 0.001400 -0.035060 0.102100 -vn -0.000003 -3.665193 -3.034545 -v 0.001400 -0.038810 0.102100 -vn -0.000000 -2.617992 3.034544 -v 0.020300 -0.035060 0.099900 -vn 0.000000 -3.665193 3.034544 -v 0.020300 -0.038810 0.099900 -vn -1.517276 -2.617992 2.627990 -v 0.020850 -0.035060 0.100047 -vn -1.517276 -3.665193 2.627991 -v 0.020850 -0.038810 0.100047 -vn -2.627995 -2.618000 1.517275 -v 0.021253 -0.035060 0.100450 -vn -2.627995 -3.665186 1.517275 -v 0.021253 -0.038810 0.100450 -vn -3.034544 -2.617991 0.000005 -v 0.021400 -0.035060 0.101000 -vn -3.034544 -3.665195 0.000005 -v 0.021400 -0.038810 0.101000 -vn -2.627996 -2.617996 -1.517270 -v 0.021253 -0.035060 0.101550 -vn -2.627996 -3.665189 -1.517270 -v 0.021253 -0.038810 0.101550 -vn -1.517276 -2.617992 -2.627991 -v 0.020850 -0.035060 0.101953 -vn -1.517276 -3.665193 -2.627990 -v 0.020850 -0.038810 0.101953 -vn 0.000000 -2.617992 -3.034544 -v 0.020300 -0.035060 0.102100 -vn -0.000000 -3.665193 -3.034544 -v 0.020300 -0.038810 0.102100 -vn -0.000000 -2.617992 3.034544 -v 0.026800 -0.035060 0.099900 -vn 0.000000 -3.665193 3.034544 -v 0.026800 -0.038810 0.099900 -vn -1.517276 -2.617992 2.627990 -v 0.027350 -0.035060 0.100047 -vn -1.517276 -3.665193 2.627991 -v 0.027350 -0.038810 0.100047 -vn -2.627995 -2.618000 1.517275 -v 0.027753 -0.035060 0.100450 -vn -2.627995 -3.665186 1.517275 -v 0.027753 -0.038810 0.100450 -vn -3.034544 -2.617991 0.000005 -v 0.027900 -0.035060 0.101000 -vn -3.034544 -3.665195 0.000005 -v 0.027900 -0.038810 0.101000 -vn -2.627996 -2.617996 -1.517270 -v 0.027753 -0.035060 0.101550 -vn -2.627996 -3.665189 -1.517270 -v 0.027753 -0.038810 0.101550 -vn -1.517276 -2.617993 -2.627991 -v 0.027350 -0.035060 0.101953 -vn -1.517276 -3.665193 -2.627990 -v 0.027350 -0.038810 0.101953 -vn 0.000000 -2.617992 -3.034544 -v 0.026800 -0.035060 0.102100 -vn -0.000000 -3.665193 -3.034544 -v 0.026800 -0.038810 0.102100 -vn -0.000003 -2.617992 3.034545 -v 0.001400 -0.035060 0.081000 -vn -0.000003 -3.665193 3.034545 -v 0.001400 -0.038810 0.081000 -vn -1.517265 -2.618005 2.628003 -v 0.001950 -0.035060 0.081147 -vn -1.517265 -3.665181 2.628003 -v 0.001950 -0.038810 0.081147 -vn -2.627983 -2.617985 1.517283 -v 0.002353 -0.035060 0.081550 -vn -2.627984 -3.665201 1.517283 -v 0.002353 -0.038810 0.081550 -vn -3.034546 -2.617994 0.000000 -v 0.002500 -0.035060 0.082100 -vn -3.034546 -3.665191 0.000000 -v 0.002500 -0.038810 0.082100 -vn -2.627994 -2.617994 -1.517273 -v 0.002353 -0.035060 0.082650 -vn -2.627993 -3.665192 -1.517272 -v 0.002353 -0.038810 0.082650 -vn -1.517275 -2.617995 -2.627993 -v 0.001950 -0.035060 0.083053 -vn -1.517275 -3.665190 -2.627993 -v 0.001950 -0.038810 0.083053 -vn -0.000003 -2.617992 -3.034545 -v 0.001400 -0.035060 0.083200 -vn -0.000003 -3.665193 -3.034545 -v 0.001400 -0.038810 0.083200 -vn -0.000000 -2.617993 3.034544 -v 0.020300 -0.035060 0.081000 -vn 0.000000 -3.665193 3.034544 -v 0.020300 -0.038810 0.081000 -vn -1.517266 -2.618001 2.628000 -v 0.020850 -0.035060 0.081147 -vn -1.517266 -3.665184 2.628001 -v 0.020850 -0.038810 0.081147 -vn -2.627986 -2.617987 1.517280 -v 0.021253 -0.035060 0.081550 -vn -2.627986 -3.665199 1.517280 -v 0.021253 -0.038810 0.081550 -vn -3.034546 -2.617994 0.000000 -v 0.021400 -0.035060 0.082100 -vn -3.034546 -3.665191 0.000000 -v 0.021400 -0.038810 0.082100 -vn -2.627996 -2.617997 -1.517270 -v 0.021253 -0.035060 0.082650 -vn -2.627996 -3.665189 -1.517270 -v 0.021253 -0.038810 0.082650 -vn -1.517276 -2.617992 -2.627991 -v 0.020850 -0.035060 0.083053 -vn -1.517276 -3.665193 -2.627990 -v 0.020850 -0.038810 0.083053 -vn 0.000000 -2.617992 -3.034544 -v 0.020300 -0.035060 0.083200 -vn -0.000000 -3.665193 -3.034544 -v 0.020300 -0.038810 0.083200 -vn -0.000000 -2.617992 3.034544 -v 0.026800 -0.035060 0.081000 -vn 0.000000 -3.665193 3.034544 -v 0.026800 -0.038810 0.081000 -vn -1.517266 -2.618001 2.628000 -v 0.027350 -0.035060 0.081147 -vn -1.517266 -3.665184 2.628001 -v 0.027350 -0.038810 0.081147 -vn -2.627986 -2.617987 1.517280 -v 0.027753 -0.035060 0.081550 -vn -2.627986 -3.665199 1.517280 -v 0.027753 -0.038810 0.081550 -vn -3.034546 -2.617994 0.000000 -v 0.027900 -0.035060 0.082100 -vn -3.034546 -3.665191 0.000000 -v 0.027900 -0.038810 0.082100 -vn -2.627996 -2.617996 -1.517270 -v 0.027753 -0.035060 0.082650 -vn -2.627996 -3.665189 -1.517270 -v 0.027753 -0.038810 0.082650 -vn -1.517276 -2.617993 -2.627991 -v 0.027350 -0.035060 0.083053 -vn -1.517276 -3.665193 -2.627990 -v 0.027350 -0.038810 0.083053 -vn 0.000000 -2.617992 -3.034544 -v 0.026800 -0.035060 0.083200 -vn -0.000000 -3.665193 -3.034544 -v 0.026800 -0.038810 0.083200 -vn 0.000000 -2.617991 3.034545 -v 0.010850 -0.036660 0.089950 -vn 0.000000 -3.665194 3.034545 -v 0.010850 -0.039010 0.089950 -vn -1.517280 -2.617990 2.627988 -v 0.011650 -0.036660 0.090164 -vn -1.517280 -3.665195 2.627988 -v 0.011650 -0.039010 0.090164 -vn -2.627999 -2.617998 1.517267 -v 0.012236 -0.036660 0.090750 -vn -2.627999 -3.665187 1.517267 -v 0.012236 -0.039010 0.090750 -vn -3.034546 -2.617994 0.000000 -v 0.012450 -0.036660 0.091550 -vn -3.034546 -3.665191 -0.000000 -v 0.012450 -0.039010 0.091550 -vn -2.627992 -2.617992 -1.517274 -v 0.012236 -0.036660 0.092350 -vn -2.627992 -3.665193 -1.517274 -v 0.012236 -0.039010 0.092350 -vn -1.517273 -2.617997 -2.627995 -v 0.011650 -0.036660 0.092936 -vn -1.517273 -3.665188 -2.627995 -v 0.011650 -0.039010 0.092936 -vn 0.000000 -2.617991 -3.034545 -v 0.010850 -0.036660 0.093150 -vn 0.000000 -3.665194 -3.034545 -v 0.010850 -0.039010 0.093150 -vn 0.000002 -2.617991 3.034544 -v 0.036250 -0.036660 0.089950 -vn 0.000002 -3.665194 3.034544 -v 0.036250 -0.039010 0.089950 -vn -1.517281 -2.617988 2.627986 -v 0.037050 -0.036660 0.090164 -vn -1.517281 -3.665197 2.627986 -v 0.037050 -0.039010 0.090164 -vn -2.628000 -2.618002 1.517269 -v 0.037636 -0.036660 0.090750 -vn -2.628000 -3.665183 1.517269 -v 0.037636 -0.039010 0.090750 -vn -3.034544 -2.617990 -0.000000 -v 0.037850 -0.036660 0.091550 -vn -3.034544 -3.665196 0.000000 -v 0.037850 -0.039010 0.091550 -vn -2.627993 -2.617996 -1.517276 -v 0.037636 -0.036660 0.092350 -vn -2.627993 -3.665190 -1.517276 -v 0.037636 -0.039010 0.092350 -vn -1.517274 -2.617995 -2.627993 -v 0.037050 -0.036660 0.092936 -vn -1.517274 -3.665191 -2.627993 -v 0.037050 -0.039010 0.092936 -vn 0.000002 -2.617991 -3.034544 -v 0.036250 -0.036660 0.093150 -vn 0.000002 -3.665194 -3.034544 -v 0.036250 -0.039010 0.093150 -vn -0.000003 3.665192 3.034544 -v 0.044581 -0.038080 0.090450 -vn -0.000003 -3.665193 3.034545 -v 0.044581 -0.040410 0.090450 -vn -1.517275 3.665188 2.627993 -v 0.045131 -0.038080 0.090597 -vn -1.517275 -3.665190 2.627993 -v 0.045131 -0.040410 0.090597 -vn -2.627994 3.665191 1.517273 -v 0.045534 -0.038080 0.091000 -vn -2.627993 -3.665191 1.517272 -v 0.045534 -0.040410 0.091000 -vn -3.034545 3.665190 -0.000000 -v 0.045681 -0.038080 0.091550 -vn -3.034545 -3.665191 0.000000 -v 0.045681 -0.040410 0.091550 -vn -2.627983 3.665201 -1.517283 -v 0.045534 -0.038080 0.092100 -vn -2.627983 -3.665201 -1.517283 -v 0.045534 -0.040410 0.092100 -vn -1.517265 3.665179 -2.628003 -v 0.045131 -0.038080 0.092503 -vn -1.517265 -3.665181 -2.628004 -v 0.045131 -0.040410 0.092503 -vn -0.000003 3.665193 -3.034545 -v 0.044581 -0.038080 0.092650 -vn -0.000003 -3.665193 -3.034544 -v 0.044581 -0.040410 0.092650 -vn -4.712389 -1.570796 -1.570796 -v 0.000150 -0.033480 0.090300 -vn -1.570796 1.570796 1.570796 -v 0.000150 -0.033880 0.089775 -vn -4.712389 -1.570796 1.570796 -v 0.000150 -0.033480 0.092800 -vn -1.570796 1.570796 -1.570796 -v 0.000150 -0.033880 0.093325 -vn -4.712389 1.570796 1.570796 -v 0.000150 -0.032480 0.092800 -vn -2.681504 -1.110735 -2.356182 -v 0.000150 -0.032230 0.093325 -vn -4.712389 1.570796 -1.570796 -v 0.000150 -0.032480 0.090300 -vn -2.681503 -1.110734 2.356182 -v 0.000150 -0.032230 0.089775 -vn -1.570796 1.570796 1.570796 -v -0.001600 -0.033880 0.093825 -vn -4.712389 1.570797 1.570796 -v -0.001850 -0.033880 0.093825 -vn -3.111411 3.337941 0.306445 -v -0.001600 -0.033880 0.100825 -vn -3.113046 2.958112 0.297947 -v -0.001850 -0.033880 0.101075 -vn -2.846684 3.534292 1.179132 -v -0.001358 -0.033880 0.102040 -vn -2.849704 2.774631 1.180384 -v -0.001608 -0.033880 0.102290 -vn -2.178758 3.534293 2.178756 -v -0.000670 -0.033880 0.103070 -vn -2.181069 2.774629 2.181067 -v -0.000920 -0.033880 0.103320 -vn -1.179135 3.534292 2.846684 -v 0.000360 -0.033880 0.103758 -vn -1.180386 2.774631 2.849705 -v 0.000110 -0.033880 0.104008 -vn -0.306447 3.337942 3.111411 -v 0.001575 -0.033880 0.104000 -vn -0.297947 2.958110 3.113046 -v 0.001325 -0.033880 0.104250 -vn 4.712389 1.570794 1.570790 -v 0.022850 -0.033880 0.104000 -vn 1.570796 1.570796 1.570796 -v 0.022850 -0.033880 0.104250 -vn -3.091908 3.116712 -3.116712 -v -0.001700 -0.033880 0.093325 -vn -3.091861 3.116695 3.116759 -v -0.001700 -0.033880 0.089775 -vn 4.712389 -1.570796 1.570796 -v 0.022850 -0.033630 0.104000 -vn 1.570796 -1.570790 1.570796 -v 0.022850 -0.033630 0.104250 -vn -0.306447 -3.337936 3.111404 -v 0.001575 -0.033630 0.104000 -vn -0.306447 -2.945243 3.111410 -v 0.001325 -0.033630 0.104250 -vn -1.179134 -3.534292 2.846684 -v 0.000360 -0.033630 0.103758 -vn -1.179135 -2.748894 2.846685 -v 0.000110 -0.033630 0.104008 -vn -2.178758 -3.534293 2.178756 -v -0.000670 -0.033630 0.103070 -vn -2.178758 -2.748892 2.178756 -v -0.000920 -0.033630 0.103320 -vn -2.846684 -3.534292 1.179131 -v -0.001358 -0.033630 0.102040 -vn -2.846684 -2.748895 1.179133 -v -0.001608 -0.033630 0.102290 -vn -3.111410 -3.337941 0.306445 -v -0.001600 -0.033630 0.100825 -vn -3.111410 -2.945244 0.306447 -v -0.001850 -0.033630 0.101075 -vn -1.570797 -1.570797 1.570796 -v -0.001600 -0.033630 0.093825 -vn -4.712389 -1.570796 1.570796 -v -0.001850 -0.033630 0.093825 -vn -1.570796 -1.570796 -1.570796 -v -0.001600 -0.033630 0.089275 -vn -4.712389 -1.570797 -1.570796 -v -0.001850 -0.033630 0.089275 -vn -3.111411 -3.337943 -0.306447 -v -0.001600 -0.033630 0.082275 -vn -3.111410 -2.945243 -0.306447 -v -0.001850 -0.033630 0.082025 -vn -2.846685 -3.534291 -1.179134 -v -0.001358 -0.033630 0.081060 -vn -2.846684 -2.748894 -1.179133 -v -0.001608 -0.033630 0.080810 -vn -2.178758 -3.534293 -2.178756 -v -0.000670 -0.033630 0.080030 -vn -2.178759 -2.748893 -2.178757 -v -0.000920 -0.033630 0.079780 -vn -1.179135 -3.534292 -2.846684 -v 0.000360 -0.033630 0.079342 -vn -1.179134 -2.748894 -2.846684 -v 0.000110 -0.033630 0.079092 -vn -0.306447 -3.337942 -3.111404 -v 0.001575 -0.033630 0.079100 -vn -0.306447 -2.945241 -3.111411 -v 0.001325 -0.033630 0.078850 -vn 4.712389 -1.570794 -1.570796 -v 0.022850 -0.033630 0.079100 -vn 1.570796 -1.570796 -1.570796 -v 0.022850 -0.033630 0.078850 -vn -1.570797 1.570797 -1.570796 -v -0.001600 -0.033880 0.089275 -vn -3.111411 3.337943 -0.306447 -v -0.001600 -0.033880 0.082275 -vn 4.712389 1.570796 -1.570790 -v 0.022850 -0.033880 0.079100 -vn 1.570796 1.570790 -1.570796 -v 0.022850 -0.033880 0.078850 -vn -0.306447 3.337936 -3.111410 -v 0.001575 -0.033880 0.079100 -vn -0.297947 2.958112 -3.113046 -v 0.001325 -0.033880 0.078850 -vn -1.179134 3.534292 -2.846684 -v 0.000360 -0.033880 0.079342 -vn -1.180385 2.774632 -2.849705 -v 0.000110 -0.033880 0.079092 -vn -2.178758 3.534293 -2.178756 -v -0.000670 -0.033880 0.080030 -vn -2.181070 2.774631 -2.181068 -v -0.000920 -0.033880 0.079780 -vn -2.846684 3.534291 -1.179133 -v -0.001358 -0.033880 0.081060 -vn -2.849705 2.774632 -1.180384 -v -0.001608 -0.033880 0.080810 -vn -3.113046 2.958112 -0.297947 -v -0.001850 -0.033880 0.082025 -vn -4.712389 1.570796 -1.570796 -v -0.001850 -0.033880 0.089275 -vn 0.000000 3.141593 3.141593 -v 0.043950 -0.033880 0.104250 -vn 3.141593 0.000002 3.141594 -v 0.043950 -0.033880 0.104000 -vn -1.570796 1.570798 1.570796 -v 0.035650 -0.033880 0.104250 -vn -4.712389 1.570796 1.570796 -v 0.035650 -0.033880 0.104000 -vn -1.570796 -1.570796 1.570796 -v 0.035650 -0.033630 0.104250 -vn 0.306446 -2.945242 3.111411 -v 0.045775 -0.033630 0.104250 -vn -1.570796 -1.570796 4.712389 -v 0.035650 -0.029580 0.104250 -vn 0.306446 2.945244 3.111413 -v 0.045775 -0.013290 0.104250 -vn 1.570796 -1.570796 4.712389 -v 0.022850 -0.029580 0.104250 -vn -0.306447 2.945250 3.111411 -v 0.001325 -0.013290 0.104250 -vn -4.712389 -1.570796 -1.570798 -v 0.035650 -0.033630 0.079100 -vn -1.570796 -1.570795 -1.570796 -v 0.035650 -0.033630 0.078850 -vn 0.306446 -3.337940 -3.111410 -v 0.045525 -0.033630 0.079100 -vn 0.306446 -2.945244 -3.111412 -v 0.045775 -0.033630 0.078850 -vn 1.179135 -3.534294 -2.846682 -v 0.046740 -0.033630 0.079342 -vn 1.179135 -2.748891 -2.846682 -v 0.046990 -0.033630 0.079092 -vn 2.178758 -3.534289 -2.178757 -v 0.047770 -0.033630 0.080030 -vn 2.178757 -2.748897 -2.178758 -v 0.048020 -0.033630 0.079780 -vn 2.846682 -3.534294 -1.179136 -v 0.048458 -0.033630 0.081060 -vn 2.846682 -2.748892 -1.179137 -v 0.048708 -0.033630 0.080810 -vn 3.111411 -3.337943 -0.306447 -v 0.048700 -0.033630 0.082275 -vn 3.111411 -2.945242 -0.306447 -v 0.048950 -0.033630 0.082025 -vn 3.111409 -3.337940 0.306445 -v 0.048700 -0.033630 0.100825 -vn 3.111410 -2.945243 0.306447 -v 0.048950 -0.033630 0.101075 -vn 2.846682 -3.534295 1.179135 -v 0.048458 -0.033630 0.102040 -vn 2.846682 -2.748892 1.179136 -v 0.048708 -0.033630 0.102290 -vn 2.178757 -3.534289 2.178758 -v 0.047770 -0.033630 0.103070 -vn 2.178758 -2.748896 2.178757 -v 0.048020 -0.033630 0.103320 -vn 1.179135 -3.534294 2.846682 -v 0.046740 -0.033630 0.103758 -vn 1.179136 -2.748891 2.846684 -v 0.046990 -0.033630 0.104008 -vn 0.306446 -3.337941 3.111409 -v 0.045525 -0.033630 0.104000 -vn -4.712389 -1.570794 1.570798 -v 0.035650 -0.033630 0.104000 -vn 0.306446 -2.945244 3.111411 -v 0.045525 -0.033880 0.104000 -vn 0.300319 -0.804745 6.137357 -v 0.045775 -0.040910 0.104250 -vn 0.285576 2.974455 3.115258 -v 0.045775 -0.038080 0.104250 -vn 0.000000 -0.000008 6.283185 -v 0.043950 -0.038080 0.104250 -vn -1.570796 1.570796 4.712389 -v 0.035650 -0.034980 0.104250 -vn 0.003767 -0.000687 6.283175 -v 0.036750 -0.040910 0.104250 -vn -0.303020 -0.803067 6.137805 -v 0.001325 -0.040910 0.104250 -vn -0.103706 -0.088953 6.278874 -v 0.010350 -0.040910 0.104250 -vn 1.570796 1.570796 4.712389 -v 0.022850 -0.034980 0.104250 -vn 0.002367 -0.000424 6.283182 -v 0.015450 -0.040910 0.104250 -vn -0.162872 -0.139229 6.272572 -v 0.031650 -0.040910 0.104250 -vn -0.570415 -0.819872 6.075036 -v 0.031650 -0.042010 0.104250 -vn 0.570045 -0.826769 6.074988 -v 0.036750 -0.042010 0.104250 -vn 0.570044 -0.826769 6.074989 -v 0.015450 -0.042010 0.104250 -vn -0.561859 -0.834301 6.076398 -v 0.010350 -0.042010 0.104250 -vn -4.712389 1.570796 -1.570796 -v 0.035650 -0.033880 0.079100 -vn 3.141593 0.000002 -3.141594 -v 0.043950 -0.033880 0.079100 -vn -1.570796 1.570798 -1.570796 -v 0.035650 -0.033880 0.078850 -vn 0.000000 3.141593 -3.141592 -v 0.043950 -0.033880 0.078850 -vn 0.306446 -2.945244 -3.111410 -v 0.045525 -0.033880 0.079100 -vn 3.034546 -2.617994 0.000000 -v 0.043481 -0.036660 0.091550 -vn 2.675541 -2.661774 1.467597 -v 0.043629 -0.036660 0.091000 -vn 2.675541 -2.661773 -1.467597 -v 0.043629 -0.036660 0.092100 -vn 5.870657 -0.741618 1.061045 -v 0.043950 -0.036660 0.090649 -vn 5.870657 -0.741618 -1.061045 -v 0.043950 -0.036660 0.092451 -vn 4.686238 1.096540 3.472595 -v 0.043950 -0.038080 0.090649 -vn 1.250703 3.447148 -2.841965 -v 0.044031 -0.038080 0.092503 -vn 1.510908 -3.651506 -2.634273 -v 0.044031 -0.040410 0.092503 -vn 4.731557 1.005600 -3.446691 -v 0.043950 -0.038080 0.092451 -vn 2.634187 -3.652954 -1.511006 -v 0.043629 -0.040410 0.092100 -vn 1.517278 -3.665196 2.627988 -v 0.044031 -0.040410 0.090597 -vn 1.293557 3.517769 2.812571 -v 0.044031 -0.038080 0.090597 -vn 2.628213 -3.663108 1.517047 -v 0.043629 -0.040410 0.091000 -vn 3.034546 -3.665191 0.000000 -v 0.043481 -0.040410 0.091550 -vn 1.570796 -1.570796 -4.712389 -v 0.022850 -0.029580 0.078850 -vn -0.306447 2.945243 -3.111410 -v 0.001325 -0.013290 0.078850 -vn -1.570796 -1.570796 -4.712389 -v 0.035650 -0.029580 0.078850 -vn 0.306446 2.945251 -3.111412 -v 0.045775 -0.013290 0.078850 -vn 3.111410 2.945243 -0.306447 -v 0.048950 -0.013290 0.082025 -vn 2.846682 2.748892 -1.179136 -v 0.048708 -0.013290 0.080810 -vn 2.178758 2.748896 -2.178757 -v 0.048020 -0.013290 0.079780 -vn 1.179136 2.748891 -2.846684 -v 0.046990 -0.013290 0.079092 -vn -1.179135 2.748894 -2.846685 -v 0.000110 -0.013290 0.079092 -vn -2.178758 2.748892 -2.178756 -v -0.000920 -0.013290 0.079780 -vn -2.846684 2.748895 -1.179133 -v -0.001608 -0.013290 0.080810 -vn -3.111410 2.945242 -0.306447 -v -0.001850 -0.013290 0.082025 -vn -3.111413 2.945243 0.306447 -v -0.001850 -0.013290 0.101075 -vn -2.846684 2.748894 1.179133 -v -0.001608 -0.013290 0.102290 -vn -2.178759 2.748893 2.178757 -v -0.000920 -0.013290 0.103320 -vn -1.179134 2.748894 2.846684 -v 0.000110 -0.013290 0.104008 -vn 3.111410 2.945242 0.306447 -v 0.048950 -0.013290 0.101075 -vn 1.179135 2.748891 2.846682 -v 0.046990 -0.013290 0.104008 -vn 2.178757 2.748897 2.178758 -v 0.048020 -0.013290 0.103320 -vn 2.846682 2.748892 1.179137 -v 0.048708 -0.013290 0.102290 -vn 1.179136 -2.748891 2.846682 -v 0.046740 -0.033880 0.103758 -vn 2.178758 -2.748897 2.178757 -v 0.047770 -0.033880 0.103070 -vn 2.846682 -2.748891 1.179135 -v 0.048458 -0.033880 0.102040 -vn 3.111410 -2.945245 0.306445 -v 0.048700 -0.033880 0.100825 -vn 3.111408 -2.945243 -0.306447 -v 0.048700 -0.033880 0.082275 -vn 2.846683 -2.748892 -1.179137 -v 0.048458 -0.033880 0.081060 -vn 2.178757 -2.748897 -2.178758 -v 0.047770 -0.033880 0.080030 -vn 1.179135 -2.748891 -2.846682 -v 0.046740 -0.033880 0.079342 -vn 1.517272 -2.617999 -2.627996 -v 0.035450 -0.036660 0.092936 -vn 2.627991 -2.617988 -1.517273 -v 0.034864 -0.036660 0.092350 -vn 3.034547 -2.617998 -0.000000 -v 0.034650 -0.036660 0.091550 -vn 1.517279 -2.617993 2.627989 -v 0.035450 -0.036660 0.090164 -vn 2.627998 -2.617995 1.517266 -v 0.034864 -0.036660 0.090750 -vn 1.517273 -2.617997 -2.627995 -v 0.010050 -0.036660 0.092936 -vn 2.627991 -2.617994 -1.517277 -v 0.009464 -0.036660 0.092350 -vn 3.034544 -2.617990 0.000000 -v 0.009250 -0.036660 0.091550 -vn 1.517280 -2.617990 2.627988 -v 0.010050 -0.036660 0.090164 -vn 2.627998 -2.618001 1.517270 -v 0.009464 -0.036660 0.090750 -vn 1.517272 -3.665186 -2.627996 -v 0.035450 -0.039010 0.092936 -vn 2.627991 -3.665197 -1.517273 -v 0.034864 -0.039010 0.092350 -vn 3.034547 -3.665187 0.000000 -v 0.034650 -0.039010 0.091550 -vn 2.627998 -3.665191 1.517266 -v 0.034864 -0.039010 0.090750 -vn 1.517279 -3.665193 2.627989 -v 0.035450 -0.039010 0.090164 -vn 1.517273 -3.665188 -2.627995 -v 0.010050 -0.039010 0.092936 -vn 2.627991 -3.665191 -1.517277 -v 0.009464 -0.039010 0.092350 -vn 3.034544 -3.665196 -0.000000 -v 0.009250 -0.039010 0.091550 -vn 2.627998 -3.665185 1.517271 -v 0.009464 -0.039010 0.090750 -vn 1.517280 -3.665195 2.627988 -v 0.010050 -0.039010 0.090164 -vn 1.517274 -2.617995 -2.627993 -v 0.026250 -0.035060 0.083053 -vn 1.517264 -2.618003 2.628003 -v 0.026250 -0.035060 0.081147 -vn 3.034548 -2.618001 0.000000 -v 0.025700 -0.035060 0.082100 -vn 2.627985 -2.617981 1.517278 -v 0.025847 -0.035060 0.081550 -vn 2.627995 -2.617990 -1.517267 -v 0.025847 -0.035060 0.082650 -vn 2.627986 -2.617988 1.517280 -v 0.019347 -0.035060 0.081550 -vn 1.517266 -2.618001 2.628001 -v 0.019750 -0.035060 0.081147 -vn 3.034546 -2.617994 0.000000 -v 0.019200 -0.035060 0.082100 -vn 2.627996 -2.617996 -1.517270 -v 0.019347 -0.035060 0.082650 -vn 1.517276 -2.617992 -2.627990 -v 0.019750 -0.035060 0.083053 -vn 2.627989 -2.617989 1.517278 -v 0.000447 -0.035060 0.081550 -vn 1.517268 -2.617998 2.627999 -v 0.000850 -0.035060 0.081147 -vn 3.034546 -2.617995 0.000000 -v 0.000300 -0.035060 0.082100 -vn 1.517278 -2.617989 -2.627988 -v 0.000850 -0.035060 0.083053 -vn 2.627999 -2.617999 -1.517267 -v 0.000447 -0.035060 0.082650 -vn 1.517274 -2.617995 -2.627993 -v 0.026250 -0.035060 0.101953 -vn 3.034547 -2.617997 0.000005 -v 0.025700 -0.035060 0.101000 -vn 2.627994 -2.617994 1.517273 -v 0.025847 -0.035060 0.100450 -vn 1.517274 -2.617994 2.627993 -v 0.026250 -0.035060 0.100047 -vn 2.627995 -2.617990 -1.517267 -v 0.025847 -0.035060 0.101550 -vn 2.627996 -2.617996 -1.517270 -v 0.019347 -0.035060 0.101550 -vn 3.034544 -2.617991 0.000005 -v 0.019200 -0.035060 0.101000 -vn 2.627995 -2.618000 1.517275 -v 0.019347 -0.035060 0.100450 -vn 1.517276 -2.617992 -2.627990 -v 0.019750 -0.035060 0.101953 -vn 1.517276 -2.617992 2.627991 -v 0.019750 -0.035060 0.100047 -vn 1.517278 -2.617989 -2.627988 -v 0.000850 -0.035060 0.101953 -vn 2.627999 -2.617999 -1.517267 -v 0.000447 -0.035060 0.101550 -vn 3.034544 -2.617991 0.000005 -v 0.000300 -0.035060 0.101000 -vn 2.627997 -2.618002 1.517273 -v 0.000447 -0.035060 0.100450 -vn 1.517278 -2.617989 2.627988 -v 0.000850 -0.035060 0.100047 -vn 2.627996 -2.617996 1.517270 -v 0.009897 -0.036660 0.099331 -vn 1.517276 -2.617992 2.627991 -v 0.010300 -0.036660 0.098929 -vn 2.627995 -2.617999 -1.517275 -v 0.009897 -0.036660 0.100431 -vn 3.034544 -2.617991 -0.000005 -v 0.009750 -0.036660 0.099881 -vn 1.517276 -2.617992 -2.627990 -v 0.010300 -0.036660 0.100834 -vn 3.034546 -2.617994 0.000000 -v 0.001419 -0.036660 0.091550 -vn 2.627994 -2.617994 1.517273 -v 0.001566 -0.036660 0.091000 -vn 1.517275 -2.617996 2.627993 -v 0.001969 -0.036660 0.090597 -vn 2.627983 -2.617985 -1.517283 -v 0.001566 -0.036660 0.092100 -vn 1.517265 -2.618005 -2.628003 -v 0.001969 -0.036660 0.092503 -vn 2.627996 -2.617997 1.517270 -v 0.009897 -0.036660 0.082669 -vn 1.517257 -2.617980 2.627996 -v 0.010300 -0.036660 0.082266 -vn 1.517276 -2.617992 -2.627990 -v 0.010300 -0.036660 0.084171 -vn 2.627996 -2.617996 -1.517270 -v 0.009897 -0.036660 0.083769 -vn 3.034546 -2.617994 0.000000 -v 0.009750 -0.036660 0.083219 -vn 2.627996 -2.617996 1.517270 -v 0.018229 -0.036660 0.091000 -vn 1.517276 -2.617992 2.627991 -v 0.018631 -0.036660 0.090597 -vn 2.627986 -2.617987 -1.517280 -v 0.018229 -0.036660 0.092100 -vn 3.034546 -2.617994 0.000000 -v 0.018081 -0.036660 0.091550 -vn 1.517266 -2.618001 -2.628000 -v 0.018631 -0.036660 0.092503 -vn 1.517266 -2.618001 -2.628000 -v 0.027369 -0.036660 0.092503 -vn 2.627996 -2.617996 1.517270 -v 0.026966 -0.036660 0.091000 -vn 1.517276 -2.617993 2.627991 -v 0.027369 -0.036660 0.090597 -vn 3.034546 -2.617994 0.000000 -v 0.026819 -0.036660 0.091550 -vn 2.627986 -2.617987 -1.517280 -v 0.026966 -0.036660 0.092100 -vn 1.517256 -2.617983 2.627998 -v 0.035700 -0.036660 0.082266 -vn 3.034546 -2.617994 0.000000 -v 0.035150 -0.036660 0.083219 -vn 2.627994 -2.617994 1.517273 -v 0.035297 -0.036660 0.082669 -vn 2.627993 -2.617994 -1.517272 -v 0.035297 -0.036660 0.083769 -vn 1.517275 -2.617996 -2.627993 -v 0.035700 -0.036660 0.084171 -vn 1.517275 -2.617996 -2.627993 -v 0.035700 -0.036660 0.100834 -vn 2.627992 -2.617997 -1.517277 -v 0.035297 -0.036660 0.100431 -vn 3.034544 -2.617990 -0.000005 -v 0.035150 -0.036660 0.099881 -vn 2.627994 -2.617994 1.517273 -v 0.035297 -0.036660 0.099331 -vn 1.517275 -2.617996 2.627993 -v 0.035700 -0.036660 0.098929 -vn 2.986036 -2.692795 0.681542 -v 0.033325 -0.039010 0.090882 -vn 2.394615 -2.692793 1.909640 -v 0.033905 -0.039010 0.089680 -vn 1.328909 -2.692793 2.759511 -v 0.034948 -0.039010 0.088847 -vn 1.328909 -2.692793 -2.759511 -v 0.034948 -0.039010 0.094253 -vn 2.394615 -2.692792 -1.909640 -v 0.033905 -0.039010 0.093420 -vn 2.986036 -2.692795 -0.681542 -v 0.033325 -0.039010 0.092218 -vn 2.986035 -2.692793 0.681543 -v 0.007925 -0.039010 0.090882 -vn 2.394615 -2.692795 1.909640 -v 0.008505 -0.039010 0.089680 -vn 1.328910 -2.692791 2.759511 -v 0.009548 -0.039010 0.088847 -vn 1.328910 -2.692792 -2.759511 -v 0.009548 -0.039010 0.094253 -vn 2.394615 -2.692795 -1.909641 -v 0.008505 -0.039010 0.093420 -vn 2.986035 -2.692793 -0.681543 -v 0.007925 -0.039010 0.092218 -vn 1.517274 -3.665191 -2.627993 -v 0.026250 -0.038810 0.083053 -vn 2.627995 -3.665195 -1.517268 -v 0.025847 -0.038810 0.082650 -vn 3.034548 -3.665185 -0.000000 -v 0.025700 -0.038810 0.082100 -vn 2.627985 -3.665204 1.517278 -v 0.025847 -0.038810 0.081550 -vn 1.517264 -3.665182 2.628003 -v 0.026250 -0.038810 0.081147 -vn 1.517276 -3.665193 -2.627991 -v 0.019750 -0.038810 0.083053 -vn 2.627996 -3.665189 -1.517270 -v 0.019347 -0.038810 0.082650 -vn 3.034546 -3.665191 0.000000 -v 0.019200 -0.038810 0.082100 -vn 2.627986 -3.665198 1.517280 -v 0.019347 -0.038810 0.081550 -vn 1.517266 -3.665184 2.628000 -v 0.019750 -0.038810 0.081147 -vn 1.517278 -3.665196 -2.627988 -v 0.000850 -0.038810 0.083053 -vn 2.627999 -3.665187 -1.517267 -v 0.000447 -0.038810 0.082650 -vn 3.034546 -3.665191 0.000000 -v 0.000300 -0.038810 0.082100 -vn 2.627989 -3.665196 1.517278 -v 0.000447 -0.038810 0.081550 -vn 1.517268 -3.665187 2.627999 -v 0.000850 -0.038810 0.081147 -vn 1.517274 -3.665191 -2.627993 -v 0.026250 -0.038810 0.101953 -vn 2.627995 -3.665195 -1.517268 -v 0.025847 -0.038810 0.101550 -vn 3.034547 -3.665188 0.000005 -v 0.025700 -0.038810 0.101000 -vn 2.627993 -3.665191 1.517273 -v 0.025847 -0.038810 0.100450 -vn 1.517274 -3.665191 2.627993 -v 0.026250 -0.038810 0.100047 -vn 1.517276 -3.665193 -2.627991 -v 0.019750 -0.038810 0.101953 -vn 2.627996 -3.665189 -1.517270 -v 0.019347 -0.038810 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.019200 -0.038810 0.101000 -vn 2.627995 -3.665186 1.517275 -v 0.019347 -0.038810 0.100450 -vn 1.517276 -3.665193 2.627990 -v 0.019750 -0.038810 0.100047 -vn 1.517278 -3.665196 -2.627988 -v 0.000850 -0.038810 0.101953 -vn 2.627999 -3.665187 -1.517267 -v 0.000447 -0.038810 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.000300 -0.038810 0.101000 -vn 2.627997 -3.665184 1.517272 -v 0.000447 -0.038810 0.100450 -vn 1.517278 -3.665196 2.627988 -v 0.000850 -0.038810 0.100047 -vn 1.517275 3.665181 -2.627993 -v 0.045150 -0.038080 0.083053 -vn 1.517275 -3.665190 -2.627993 -v 0.045150 -0.038810 0.083053 -vn 2.627994 3.665192 -1.517272 -v 0.044747 -0.038080 0.082650 -vn 2.627994 -3.665192 -1.517272 -v 0.044747 -0.038810 0.082650 -vn 3.034545 3.665191 0.000000 -v 0.044600 -0.038080 0.082100 -vn 3.034545 -3.665191 0.000000 -v 0.044600 -0.038810 0.082100 -vn 2.627983 3.665201 1.517283 -v 0.044747 -0.038080 0.081550 -vn 2.627983 -3.665201 1.517283 -v 0.044747 -0.038810 0.081550 -vn 1.517265 3.665181 2.628003 -v 0.045150 -0.038080 0.081147 -vn 1.517265 -3.665181 2.628003 -v 0.045150 -0.038810 0.081147 -vn 1.517276 -3.665193 -2.627991 -v 0.010300 -0.040410 0.100834 -vn 2.627995 -3.665186 -1.517275 -v 0.009897 -0.040410 0.100431 -vn 3.034544 -3.665195 -0.000005 -v 0.009750 -0.040410 0.099881 -vn 2.627996 -3.665189 1.517270 -v 0.009897 -0.040410 0.099331 -vn 1.517276 -3.665193 2.627990 -v 0.010300 -0.040410 0.098929 -vn 1.517265 -3.665181 -2.628003 -v 0.001969 -0.040410 0.092503 -vn 2.627984 -3.665201 -1.517283 -v 0.001566 -0.040410 0.092100 -vn 3.034546 -3.665191 0.000000 -v 0.001419 -0.040410 0.091550 -vn 2.627993 -3.665192 1.517272 -v 0.001566 -0.040410 0.091000 -vn 1.517275 -3.665190 2.627993 -v 0.001969 -0.040410 0.090597 -vn 1.517276 -3.665193 -2.627991 -v 0.010300 -0.040410 0.084171 -vn 2.627996 -3.665189 -1.517270 -v 0.009897 -0.040410 0.083769 -vn 3.034546 -3.665191 0.000000 -v 0.009750 -0.040410 0.083219 -vn 2.627996 -3.665189 1.517270 -v 0.009897 -0.040410 0.082669 -vn 1.517257 -3.665206 2.627996 -v 0.010300 -0.040410 0.082266 -vn 1.517266 -3.665184 -2.628001 -v 0.018631 -0.040410 0.092503 -vn 2.627986 -3.665199 -1.517280 -v 0.018229 -0.040410 0.092100 -vn 3.034546 -3.665191 0.000000 -v 0.018081 -0.040410 0.091550 -vn 2.627996 -3.665189 1.517270 -v 0.018229 -0.040410 0.091000 -vn 1.517276 -3.665193 2.627990 -v 0.018631 -0.040410 0.090597 -vn 1.517266 -3.665184 -2.628001 -v 0.027369 -0.040410 0.092503 -vn 2.627986 -3.665199 -1.517280 -v 0.026966 -0.040410 0.092100 -vn 3.034546 -3.665191 0.000000 -v 0.026819 -0.040410 0.091550 -vn 2.627996 -3.665189 1.517270 -v 0.026966 -0.040410 0.091000 -vn 1.517276 -3.665193 2.627990 -v 0.027369 -0.040410 0.090597 -vn 1.517275 -3.665190 -2.627993 -v 0.035700 -0.040410 0.084171 -vn 2.627994 -3.665191 -1.517273 -v 0.035297 -0.040410 0.083769 -vn 3.034546 -3.665191 0.000000 -v 0.035150 -0.040410 0.083219 -vn 2.627993 -3.665192 1.517272 -v 0.035297 -0.040410 0.082669 -vn 1.517256 -3.665203 2.627998 -v 0.035700 -0.040410 0.082266 -vn 1.517275 -3.665190 -2.627993 -v 0.035700 -0.040410 0.100834 -vn 2.627992 -3.665188 -1.517278 -v 0.035297 -0.040410 0.100431 -vn 3.034544 -3.665195 -0.000005 -v 0.035150 -0.040410 0.099881 -vn 2.627993 -3.665192 1.517272 -v 0.035297 -0.040410 0.099331 -vn 1.517275 -3.665190 2.627993 -v 0.035700 -0.040410 0.098929 -vn 1.328909 2.692793 2.759511 -v 0.034948 -0.042010 0.088847 -vn 2.394615 2.692792 1.909640 -v 0.033905 -0.042010 0.089680 -vn 2.986036 2.692795 0.681542 -v 0.033325 -0.042010 0.090882 -vn 2.986036 2.692795 -0.681542 -v 0.033325 -0.042010 0.092218 -vn 2.394615 2.692793 -1.909640 -v 0.033905 -0.042010 0.093420 -vn 1.328909 2.692793 -2.759511 -v 0.034948 -0.042010 0.094253 -vn 1.328910 2.692792 -2.759511 -v 0.009548 -0.042010 0.094253 -vn 2.394615 2.692795 -1.909640 -v 0.008505 -0.042010 0.093420 -vn 2.986035 2.692794 -0.681543 -v 0.007925 -0.042010 0.092218 -vn 2.986035 2.692793 0.681543 -v 0.007925 -0.042010 0.090882 -vn 2.394615 2.692795 1.909641 -v 0.008505 -0.042010 0.089680 -vn 1.328910 2.692792 2.759511 -v 0.009548 -0.042010 0.088847 -vn 1.517275 3.665190 -2.627993 -v 0.045150 -0.038080 0.101953 -vn 1.517275 -3.665190 -2.627993 -v 0.045150 -0.038810 0.101953 -vn 2.627994 3.665192 -1.517272 -v 0.044747 -0.038080 0.101550 -vn 2.627994 -3.665192 -1.517272 -v 0.044747 -0.038810 0.101550 -vn 3.034544 3.665195 0.000005 -v 0.044600 -0.038080 0.101000 -vn 3.034544 -3.665195 0.000005 -v 0.044600 -0.038810 0.101000 -vn 2.627992 3.665188 1.517278 -v 0.044747 -0.038080 0.100450 -vn 2.627992 -3.665188 1.517278 -v 0.044747 -0.038810 0.100450 -vn 1.517275 3.665190 2.627993 -v 0.045150 -0.038080 0.100047 -vn 1.517275 -3.665190 2.627993 -v 0.045150 -0.038810 0.100047 -vn 1.517268 -2.617996 -2.627997 -v 0.025925 -0.038810 0.083616 -vn 2.627991 -2.617989 -1.517273 -v 0.025284 -0.038810 0.082975 -vn 3.034546 -2.617995 0.000003 -v 0.025050 -0.038810 0.082100 -vn 2.627996 -2.617997 1.517270 -v 0.025284 -0.038810 0.081225 -vn 1.517275 -2.617990 2.627991 -v 0.025925 -0.038810 0.080584 -vn 1.517268 -2.617996 -2.627997 -v 0.019425 -0.038810 0.083616 -vn 2.627991 -2.617989 -1.517273 -v 0.018784 -0.038810 0.082975 -vn 3.034546 -2.617995 0.000003 -v 0.018550 -0.038810 0.082100 -vn 2.627996 -2.617997 1.517270 -v 0.018784 -0.038810 0.081225 -vn 1.517275 -2.617990 2.627991 -v 0.019425 -0.038810 0.080584 -vn 1.517269 -2.617996 -2.627997 -v 0.000525 -0.038810 0.083616 -vn 2.627991 -2.617989 -1.517273 -v -0.000116 -0.038810 0.082975 -vn 3.034546 -2.617995 0.000003 -v -0.000350 -0.038810 0.082100 -vn 2.627996 -2.617997 1.517270 -v -0.000116 -0.038810 0.081225 -vn 1.517275 -2.617990 2.627991 -v 0.000525 -0.038810 0.080584 -vn 3.034546 -2.617995 0.000003 -v 0.025050 -0.038810 0.101000 -vn 2.627996 -2.617997 1.517270 -v 0.025284 -0.038810 0.100125 -vn 1.517275 -2.617990 2.627991 -v 0.025925 -0.038810 0.099484 -vn 1.517268 -2.617996 -2.627997 -v 0.025925 -0.038810 0.102516 -vn 2.627991 -2.617989 -1.517273 -v 0.025284 -0.038810 0.101875 -vn 1.517268 -2.617996 -2.627997 -v 0.019425 -0.038810 0.102516 -vn 2.627991 -2.617989 -1.517273 -v 0.018784 -0.038810 0.101875 -vn 3.034546 -2.617995 0.000003 -v 0.018550 -0.038810 0.101000 -vn 2.627996 -2.617997 1.517270 -v 0.018784 -0.038810 0.100125 -vn 1.517275 -2.617990 2.627991 -v 0.019425 -0.038810 0.099484 -vn 1.517275 -2.617990 2.627991 -v 0.000525 -0.038810 0.099484 -vn 1.517269 -2.617996 -2.627997 -v 0.000525 -0.038810 0.102516 -vn 2.627991 -2.617989 -1.517273 -v -0.000116 -0.038810 0.101875 -vn 3.034546 -2.617995 0.000003 -v -0.000350 -0.038810 0.101000 -vn 2.627996 -2.617997 1.517270 -v -0.000116 -0.038810 0.100125 -vn 1.517272 -2.617993 -2.627994 -v 0.044825 -0.038810 0.083616 -vn 2.627993 -2.617996 -1.517276 -v 0.044184 -0.038810 0.082975 -vn 3.034543 -2.617987 0.000003 -v 0.043950 -0.038810 0.082100 -vn 2.627998 -2.618004 1.517273 -v 0.044184 -0.038810 0.081225 -vn 1.517278 -2.617987 2.627987 -v 0.044825 -0.038810 0.080584 -vn 1.517275 -2.617990 -2.627990 -v 0.009975 -0.040410 0.101397 -vn 2.627997 -2.617997 -1.517270 -v 0.009334 -0.040410 0.100756 -vn 3.034546 -2.617995 -0.000003 -v 0.009100 -0.040410 0.099881 -vn 2.627991 -2.617990 1.517273 -v 0.009334 -0.040410 0.099006 -vn 1.517281 -2.618004 2.627994 -v 0.009975 -0.040410 0.098366 -vn 1.517278 -2.617987 -2.627987 -v 0.001644 -0.040410 0.093066 -vn 2.627998 -2.618004 -1.517273 -v 0.001003 -0.040410 0.092425 -vn 3.034543 -2.617987 -0.000003 -v 0.000769 -0.040410 0.091550 -vn 2.627992 -2.617996 1.517276 -v 0.001003 -0.040410 0.090675 -vn 1.517272 -2.617993 2.627994 -v 0.001644 -0.040410 0.090034 -vn 2.627996 -2.617997 1.517270 -v 0.009334 -0.040410 0.082344 -vn 1.517275 -2.617990 2.627991 -v 0.009975 -0.040410 0.081703 -vn 1.517268 -2.617996 -2.627997 -v 0.009975 -0.040410 0.084734 -vn 2.627991 -2.617989 -1.517273 -v 0.009334 -0.040410 0.084094 -vn 3.034546 -2.617995 0.000003 -v 0.009100 -0.040410 0.083219 -vn 1.517275 -2.617990 -2.627990 -v 0.018306 -0.040410 0.093066 -vn 2.627997 -2.617997 -1.517270 -v 0.017666 -0.040410 0.092425 -vn 3.034546 -2.617995 -0.000003 -v 0.017431 -0.040410 0.091550 -vn 2.627991 -2.617990 1.517273 -v 0.017666 -0.040410 0.090675 -vn 1.517269 -2.617996 2.627997 -v 0.018306 -0.040410 0.090034 -vn 1.517275 -2.617990 -2.627990 -v 0.027044 -0.040410 0.093066 -vn 2.627997 -2.617997 -1.517270 -v 0.026403 -0.040410 0.092425 -vn 3.034546 -2.617995 -0.000003 -v 0.026169 -0.040410 0.091550 -vn 2.627991 -2.617990 1.517273 -v 0.026403 -0.040410 0.090675 -vn 1.517269 -2.617996 2.627997 -v 0.027044 -0.040410 0.090034 -vn 1.517275 -2.617990 2.627991 -v 0.035375 -0.040410 0.081703 -vn 1.517268 -2.617996 -2.627997 -v 0.035375 -0.040410 0.084734 -vn 2.627991 -2.617989 -1.517273 -v 0.034734 -0.040410 0.084094 -vn 3.034546 -2.617995 0.000003 -v 0.034500 -0.040410 0.083219 -vn 2.627996 -2.617997 1.517270 -v 0.034734 -0.040410 0.082344 -vn 2.627997 -2.617997 -1.517270 -v 0.043066 -0.040410 0.092425 -vn 3.034546 -2.617995 -0.000003 -v 0.042831 -0.040410 0.091550 -vn 2.627991 -2.617989 1.517273 -v 0.043066 -0.040410 0.090675 -vn 1.517269 -2.617996 2.627997 -v 0.043706 -0.040410 0.090034 -vn 1.517275 -2.617990 -2.627990 -v 0.043706 -0.040410 0.093066 -vn 1.517275 -2.617990 -2.627990 -v 0.035375 -0.040410 0.101397 -vn 2.627997 -2.617997 -1.517270 -v 0.034734 -0.040410 0.100756 -vn 3.034546 -2.617995 -0.000003 -v 0.034500 -0.040410 0.099881 -vn 2.627991 -2.617990 1.517273 -v 0.034734 -0.040410 0.099006 -vn 1.517281 -2.618004 2.627994 -v 0.035375 -0.040410 0.098366 -vn 3.034547 3.665187 0.000000 -v 0.034650 -0.042010 0.091550 -vn 2.627991 3.665197 -1.517273 -v 0.034864 -0.042010 0.092350 -vn 1.517272 3.665186 -2.627996 -v 0.035450 -0.042010 0.092936 -vn 1.517279 3.665193 2.627989 -v 0.035450 -0.042010 0.090164 -vn 2.627998 3.665191 1.517266 -v 0.034864 -0.042010 0.090750 -vn 1.517280 3.665195 2.627988 -v 0.010050 -0.042010 0.090164 -vn 2.627998 3.665185 1.517270 -v 0.009464 -0.042010 0.090750 -vn 3.034544 3.665196 0.000000 -v 0.009250 -0.042010 0.091550 -vn 2.627991 3.665191 -1.517277 -v 0.009464 -0.042010 0.092350 -vn 1.517273 3.665188 -2.627995 -v 0.010050 -0.042010 0.092936 -vn 1.517278 -2.617987 2.627987 -v 0.044825 -0.038810 0.099484 -vn 1.517272 -2.617993 -2.627994 -v 0.044825 -0.038810 0.102516 -vn 2.627993 -2.617996 -1.517276 -v 0.044184 -0.038810 0.101875 -vn 3.034543 -2.617987 0.000003 -v 0.043950 -0.038810 0.101000 -vn 2.627998 -2.618004 1.517273 -v 0.044184 -0.038810 0.100125 -vn 1.517269 2.617996 -2.627997 -v 0.025925 -0.041010 0.083616 -vn 2.627991 2.617989 -1.517273 -v 0.025284 -0.041010 0.082975 -vn 3.034546 2.617995 0.000003 -v 0.025050 -0.041010 0.082100 -vn 2.627997 2.617997 1.517270 -v 0.025284 -0.041010 0.081225 -vn 1.517275 2.617990 2.627990 -v 0.025925 -0.041010 0.080584 -vn 1.517269 2.617996 -2.627997 -v 0.019425 -0.041010 0.083616 -vn 2.627991 2.617990 -1.517273 -v 0.018784 -0.041010 0.082975 -vn 3.034546 2.617995 0.000003 -v 0.018550 -0.041010 0.082100 -vn 2.627997 2.617997 1.517270 -v 0.018784 -0.041010 0.081225 -vn 1.517275 2.617990 2.627990 -v 0.019425 -0.041010 0.080584 -vn 1.517269 2.617996 -2.627997 -v 0.000525 -0.041010 0.083616 -vn 2.627991 2.617989 -1.517273 -v -0.000116 -0.041010 0.082975 -vn 3.034546 2.617995 0.000003 -v -0.000350 -0.041010 0.082100 -vn 2.627997 2.617997 1.517270 -v -0.000116 -0.041010 0.081225 -vn 1.517275 2.617990 2.627991 -v 0.000525 -0.041010 0.080584 -vn 1.517269 2.617996 -2.627997 -v 0.025925 -0.041010 0.102516 -vn 2.627991 2.617989 -1.517273 -v 0.025284 -0.041010 0.101875 -vn 3.034546 2.617995 0.000003 -v 0.025050 -0.041010 0.101000 -vn 2.627997 2.617997 1.517270 -v 0.025284 -0.041010 0.100125 -vn 1.517275 2.617990 2.627990 -v 0.025925 -0.041010 0.099484 -vn 1.517269 2.617996 -2.627997 -v 0.019425 -0.041010 0.102516 -vn 2.627991 2.617990 -1.517273 -v 0.018784 -0.041010 0.101875 -vn 3.034546 2.617995 0.000003 -v 0.018550 -0.041010 0.101000 -vn 2.627997 2.617997 1.517270 -v 0.018784 -0.041010 0.100125 -vn 1.517275 2.617990 2.627990 -v 0.019425 -0.041010 0.099484 -vn 1.517269 2.617996 -2.627997 -v 0.000525 -0.041010 0.102516 -vn 2.627991 2.617989 -1.517273 -v -0.000116 -0.041010 0.101875 -vn 3.034546 2.617995 0.000003 -v -0.000350 -0.041010 0.101000 -vn 2.627997 2.617997 1.517270 -v -0.000116 -0.041010 0.100125 -vn 1.517275 2.617990 2.627991 -v 0.000525 -0.041010 0.099484 -vn 1.517272 2.617993 -2.627994 -v 0.044825 -0.041010 0.083616 -vn 2.627992 2.617996 -1.517276 -v 0.044184 -0.041010 0.082975 -vn 3.034543 2.617987 0.000003 -v 0.043950 -0.041010 0.082100 -vn 2.627998 2.618004 1.517273 -v 0.044184 -0.041010 0.081225 -vn 1.517278 2.617988 2.627987 -v 0.044825 -0.041010 0.080584 -vn 1.517275 2.617990 -2.627991 -v 0.009975 -0.042610 0.101397 -vn 2.627996 2.617997 -1.517270 -v 0.009334 -0.042610 0.100756 -vn 3.034546 2.617995 -0.000003 -v 0.009100 -0.042610 0.099881 -vn 2.627991 2.617989 1.517273 -v 0.009334 -0.042610 0.099006 -vn 1.517280 2.618004 2.627994 -v 0.009975 -0.042610 0.098366 -vn 1.517278 2.617987 -2.627987 -v 0.001644 -0.042610 0.093066 -vn 2.627998 2.618004 -1.517273 -v 0.001003 -0.042610 0.092425 -vn 3.034543 2.617988 -0.000003 -v 0.000769 -0.042610 0.091550 -vn 2.627993 2.617996 1.517276 -v 0.001003 -0.042610 0.090675 -vn 1.517272 2.617993 2.627994 -v 0.001644 -0.042610 0.090034 -vn 1.517269 2.617996 -2.627997 -v 0.009975 -0.042610 0.084734 -vn 2.627991 2.617990 -1.517273 -v 0.009334 -0.042610 0.084094 -vn 3.034546 2.617995 0.000003 -v 0.009100 -0.042610 0.083219 -vn 2.627997 2.617997 1.517270 -v 0.009334 -0.042610 0.082344 -vn 1.517275 2.617990 2.627990 -v 0.009975 -0.042610 0.081703 -vn 1.517275 2.617990 -2.627991 -v 0.018306 -0.042610 0.093066 -vn 2.627996 2.617997 -1.517270 -v 0.017666 -0.042610 0.092425 -vn 3.034546 2.617995 -0.000003 -v 0.017431 -0.042610 0.091550 -vn 2.627991 2.617989 1.517273 -v 0.017666 -0.042610 0.090675 -vn 1.517268 2.617996 2.627997 -v 0.018306 -0.042610 0.090034 -vn 1.517268 2.617996 2.627997 -v 0.027044 -0.042610 0.090034 -vn 2.627991 2.617989 1.517273 -v 0.026403 -0.042610 0.090675 -vn 3.034546 2.617995 -0.000003 -v 0.026169 -0.042610 0.091550 -vn 2.627996 2.617997 -1.517270 -v 0.026403 -0.042610 0.092425 -vn 1.517275 2.617990 -2.627991 -v 0.027044 -0.042610 0.093066 -vn 1.517275 2.617990 2.627990 -v 0.035375 -0.042610 0.081703 -vn 2.627997 2.617997 1.517270 -v 0.034734 -0.042610 0.082344 -vn 3.034546 2.617995 0.000003 -v 0.034500 -0.042610 0.083219 -vn 2.627991 2.617990 -1.517273 -v 0.034734 -0.042610 0.084094 -vn 1.517269 2.617996 -2.627997 -v 0.035375 -0.042610 0.084734 -vn 1.517268 2.617996 2.627997 -v 0.043706 -0.042610 0.090034 -vn 2.627991 2.617989 1.517273 -v 0.043066 -0.042610 0.090675 -vn 3.034546 2.617995 -0.000003 -v 0.042831 -0.042610 0.091550 -vn 2.627996 2.617997 -1.517270 -v 0.043066 -0.042610 0.092425 -vn 1.517275 2.617990 -2.627991 -v 0.043706 -0.042610 0.093066 -vn 1.517280 2.618004 2.627994 -v 0.035375 -0.042610 0.098366 -vn 2.627991 2.617989 1.517273 -v 0.034734 -0.042610 0.099006 -vn 3.034546 2.617995 -0.000003 -v 0.034500 -0.042610 0.099881 -vn 2.627996 2.617997 -1.517270 -v 0.034734 -0.042610 0.100756 -vn 1.517275 2.617990 -2.627991 -v 0.035375 -0.042610 0.101397 -vn 1.517272 -3.665186 -2.627996 -v 0.035450 -0.042510 0.092936 -vn 2.627991 -3.665197 -1.517273 -v 0.034864 -0.042510 0.092350 -vn 3.034547 -3.665187 0.000000 -v 0.034650 -0.042510 0.091550 -vn 2.627998 -3.665190 1.517266 -v 0.034864 -0.042510 0.090750 -vn 1.517279 -3.665193 2.627989 -v 0.035450 -0.042510 0.090164 -vn 1.517273 -3.665188 -2.627995 -v 0.010050 -0.042510 0.092936 -vn 2.627991 -3.665191 -1.517277 -v 0.009464 -0.042510 0.092350 -vn 3.034544 -3.665195 -0.000000 -v 0.009250 -0.042510 0.091550 -vn 2.627998 -3.665184 1.517270 -v 0.009464 -0.042510 0.090750 -vn 1.517280 -3.665195 2.627988 -v 0.010050 -0.042510 0.090164 -vn 1.517272 2.617993 -2.627994 -v 0.044825 -0.041010 0.102516 -vn 2.627992 2.617996 -1.517276 -v 0.044184 -0.041010 0.101875 -vn 3.034543 2.617987 0.000003 -v 0.043950 -0.041010 0.101000 -vn 2.627998 2.618004 1.517273 -v 0.044184 -0.041010 0.100125 -vn 1.517278 2.617987 2.627987 -v 0.044825 -0.041010 0.099484 -vn 1.517264 3.665182 2.628003 -v 0.026250 -0.041010 0.081147 -vn 2.627985 3.665204 1.517278 -v 0.025847 -0.041010 0.081550 -vn 3.034548 3.665185 -0.000000 -v 0.025700 -0.041010 0.082100 -vn 2.627995 3.665195 -1.517268 -v 0.025847 -0.041010 0.082650 -vn 1.517274 3.665191 -2.627993 -v 0.026250 -0.041010 0.083053 -vn 2.627986 3.665199 1.517280 -v 0.019347 -0.041010 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.019200 -0.041010 0.082100 -vn 2.627996 3.665189 -1.517270 -v 0.019347 -0.041010 0.082650 -vn 1.517277 3.665193 -2.627990 -v 0.019750 -0.041010 0.083053 -vn 1.517266 3.665184 2.628001 -v 0.019750 -0.041010 0.081147 -vn 1.517267 3.665187 2.627999 -v 0.000850 -0.041010 0.081147 -vn 2.627989 3.665196 1.517278 -v 0.000447 -0.041010 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.000300 -0.041010 0.082100 -vn 2.627999 3.665187 -1.517267 -v 0.000447 -0.041010 0.082650 -vn 1.517278 3.665196 -2.627989 -v 0.000850 -0.041010 0.083053 -vn 2.627995 -2.617990 1.517266 -v 0.005784 -0.008510 0.080750 -vn 1.517277 -2.617997 2.627992 -v 0.006150 -0.008510 0.080384 -vn 3.034548 -2.618002 0.000000 -v 0.005650 -0.008510 0.081250 -vn 2.627995 -2.617990 -1.517266 -v 0.005784 -0.008510 0.081750 -vn 1.517277 -2.617997 -2.627992 -v 0.006150 -0.008510 0.082116 -vn 1.517274 3.665191 2.627993 -v 0.026250 -0.041010 0.100047 -vn 2.627994 3.665191 1.517273 -v 0.025847 -0.041010 0.100450 -vn 3.034547 3.665188 0.000005 -v 0.025700 -0.041010 0.101000 -vn 2.627995 3.665195 -1.517268 -v 0.025847 -0.041010 0.101550 -vn 1.517274 3.665191 -2.627993 -v 0.026250 -0.041010 0.101953 -vn 1.517277 3.665193 2.627991 -v 0.019750 -0.041010 0.100047 -vn 2.627995 3.665186 1.517275 -v 0.019347 -0.041010 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.019200 -0.041010 0.101000 -vn 2.627996 3.665189 -1.517270 -v 0.019347 -0.041010 0.101550 -vn 1.517277 3.665193 -2.627990 -v 0.019750 -0.041010 0.101953 -vn 1.517278 3.665196 -2.627989 -v 0.000850 -0.041010 0.101953 -vn 1.517278 3.665196 2.627988 -v 0.000850 -0.041010 0.100047 -vn 2.627997 3.665184 1.517273 -v 0.000447 -0.041010 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.000300 -0.041010 0.101000 -vn 2.627999 3.665187 -1.517267 -v 0.000447 -0.041010 0.101550 -vn 2.628005 -2.618003 1.517261 -v 0.005784 -0.008510 0.101350 -vn 1.517267 -2.617973 2.627986 -v 0.006150 -0.008510 0.100984 -vn 3.034547 -2.617999 0.000006 -v 0.005650 -0.008510 0.101850 -vn 2.627995 -2.617990 -1.517266 -v 0.005784 -0.008510 0.102350 -vn 1.517277 -2.617997 -2.627992 -v 0.006150 -0.008510 0.102716 -vn 1.517265 3.665181 2.628003 -v 0.045150 -0.041010 0.081147 -vn 2.627984 3.665201 1.517283 -v 0.044747 -0.041010 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.044600 -0.041010 0.082100 -vn 2.627994 3.665191 -1.517273 -v 0.044747 -0.041010 0.082650 -vn 1.517275 3.665190 -2.627993 -v 0.045150 -0.041010 0.083053 -vn 1.517277 -2.617997 -2.627992 -v 0.039950 -0.008510 0.082116 -vn 2.627995 -2.617990 1.517266 -v 0.039584 -0.008510 0.080750 -vn 1.517277 -2.617997 2.627992 -v 0.039950 -0.008510 0.080384 -vn 3.034548 -2.618002 0.000000 -v 0.039450 -0.008510 0.081250 -vn 2.627995 -2.617990 -1.517266 -v 0.039584 -0.008510 0.081750 -vn 1.517277 3.665193 -2.627990 -v 0.010300 -0.042610 0.100834 -vn 1.517277 3.665193 2.627991 -v 0.010300 -0.042610 0.098929 -vn 2.627996 3.665189 1.517270 -v 0.009897 -0.042610 0.099331 -vn 3.034544 3.665195 -0.000005 -v 0.009750 -0.042610 0.099881 -vn 2.627995 3.665186 -1.517275 -v 0.009897 -0.042610 0.100431 -vn 1.517275 3.665190 2.627993 -v 0.001969 -0.042610 0.090597 -vn 2.627994 3.665192 1.517273 -v 0.001566 -0.042610 0.091000 -vn 3.034546 3.665191 0.000000 -v 0.001419 -0.042610 0.091550 -vn 2.627983 3.665201 -1.517283 -v 0.001566 -0.042610 0.092100 -vn 1.517265 3.665181 -2.628003 -v 0.001969 -0.042610 0.092503 -vn 2.627996 3.665189 1.517270 -v 0.009897 -0.042610 0.082669 -vn 3.034546 3.665191 0.000000 -v 0.009750 -0.042610 0.083219 -vn 2.627996 3.665189 -1.517270 -v 0.009897 -0.042610 0.083769 -vn 1.517277 3.665193 -2.627990 -v 0.010300 -0.042610 0.084171 -vn 1.517257 3.665205 2.627996 -v 0.010300 -0.042610 0.082266 -vn 1.517266 3.665184 -2.628001 -v 0.018631 -0.042610 0.092503 -vn 1.517277 3.665193 2.627991 -v 0.018631 -0.042610 0.090597 -vn 2.627996 3.665189 1.517270 -v 0.018229 -0.042610 0.091000 -vn 3.034546 3.665191 0.000000 -v 0.018081 -0.042610 0.091550 -vn 2.627986 3.665198 -1.517280 -v 0.018229 -0.042610 0.092100 -vn 3.034546 3.665191 0.000000 -v 0.026819 -0.042610 0.091550 -vn 2.627986 3.665198 -1.517280 -v 0.026966 -0.042610 0.092100 -vn 1.517266 3.665184 -2.628001 -v 0.027369 -0.042610 0.092503 -vn 1.517277 3.665193 2.627991 -v 0.027369 -0.042610 0.090597 -vn 2.627996 3.665189 1.517270 -v 0.026966 -0.042610 0.091000 -vn 1.517256 3.665203 2.627998 -v 0.035700 -0.042610 0.082266 -vn 2.627994 3.665192 1.517273 -v 0.035297 -0.042610 0.082669 -vn 3.034546 3.665191 0.000000 -v 0.035150 -0.042610 0.083219 -vn 2.627994 3.665192 -1.517273 -v 0.035297 -0.042610 0.083769 -vn 1.517275 3.665190 -2.627993 -v 0.035700 -0.042610 0.084171 -vn 2.627999 3.665187 1.517267 -v 0.043629 -0.042610 0.091000 -vn 3.034546 3.665191 0.000000 -v 0.043481 -0.042610 0.091550 -vn 2.627988 3.665196 -1.517278 -v 0.043629 -0.042610 0.092100 -vn 1.517267 3.665187 -2.627999 -v 0.044031 -0.042610 0.092503 -vn 1.517278 3.665196 2.627988 -v 0.044031 -0.042610 0.090597 -vn 1.517275 3.665190 2.627993 -v 0.035700 -0.042610 0.098929 -vn 2.627994 3.665191 1.517273 -v 0.035297 -0.042610 0.099331 -vn 3.034544 3.665195 -0.000005 -v 0.035150 -0.042610 0.099881 -vn 2.627992 3.665188 -1.517278 -v 0.035297 -0.042610 0.100431 -vn 1.517275 3.665190 -2.627993 -v 0.035700 -0.042610 0.100834 -vn 1.988695 -2.792525 2.370039 -v 0.033036 -0.042510 0.087720 -vn 1.058164 -2.792531 2.907283 -v 0.034540 -0.042510 0.086852 -vn 3.046862 -2.792527 -0.537244 -v 0.031326 -0.042510 0.092418 -vn 3.046862 -2.792527 0.537244 -v 0.031326 -0.042510 0.090682 -vn 2.679366 -2.792527 1.546932 -v 0.031920 -0.042510 0.089050 -vn 1.058163 -2.792523 -2.907281 -v 0.034540 -0.042510 0.096248 -vn 1.988700 -2.792528 -2.370037 -v 0.033036 -0.042510 0.095380 -vn 2.679365 -2.792527 -1.546932 -v 0.031920 -0.042510 0.094050 -vn 3.046862 -2.792527 -0.537244 -v 0.005926 -0.042510 0.092418 -vn 3.046862 -2.792527 0.537244 -v 0.005926 -0.042510 0.090682 -vn 1.058163 -2.792522 -2.907280 -v 0.009140 -0.042510 0.096248 -vn 1.988700 -2.792531 -2.370038 -v 0.007636 -0.042510 0.095380 -vn 2.679364 -2.792525 -1.546934 -v 0.006520 -0.042510 0.094050 -vn 2.679364 -2.792525 1.546934 -v 0.006520 -0.042510 0.089050 -vn 1.988694 -2.792527 2.370041 -v 0.007636 -0.042510 0.087720 -vn 1.058165 -2.792530 2.907283 -v 0.009140 -0.042510 0.086852 -vn -0.671217 -0.789215 -6.048070 -v 0.005580 -0.042010 0.083350 -vn -0.572171 -2.915983 -5.151247 -v 0.005580 -0.042510 0.083484 -vn -2.176763 -2.797402 -4.552903 -v 0.005206 -0.042510 0.083569 -vn -0.352974 -5.141419 -3.073854 -v 0.005580 -0.042876 0.083850 -vn -1.342842 -5.026857 -2.808648 -v 0.005364 -0.042876 0.083899 -vn -2.323787 -5.077621 -2.155488 -v 0.005191 -0.042876 0.084036 -vn -0.413877 -6.119558 -0.819265 -v 0.005580 -0.043010 0.084350 -vn -1.652161 -5.872163 -1.069141 -v 0.005207 -0.042934 0.084262 -vn -3.879236 -2.808127 -3.330112 -v 0.004906 -0.042510 0.083806 -vn -3.089228 -5.253062 -1.348920 -v 0.005093 -0.042876 0.084235 -vn -3.952294 -4.369576 -1.925140 -v 0.004892 -0.042717 0.084187 -vn -4.857063 -3.247917 -2.194777 -v 0.004737 -0.042510 0.084150 -vn -5.338249 -1.950862 -2.504158 -v 0.004681 -0.042393 0.084137 -vn -2.553552 -0.765311 -5.340968 -v 0.005148 -0.042010 0.083448 -vn -4.595791 -0.721813 -3.764550 -v 0.004802 -0.042010 0.083722 -vn -5.652703 -0.599511 -2.576407 -v 0.004607 -0.042010 0.084119 -vn -5.658779 -0.794275 2.388280 -v 0.004607 -0.042010 0.098981 -vn -4.827041 -2.958256 2.037064 -v 0.004737 -0.042510 0.098950 -vn -3.927694 -2.797419 3.168685 -v 0.004906 -0.042510 0.099294 -vn -0.556913 -6.090551 0.786079 -v 0.005580 -0.043010 0.098750 -vn -0.352972 -5.141421 3.073853 -v 0.005580 -0.042876 0.099250 -vn -1.342816 -5.026866 2.808664 -v 0.005364 -0.042876 0.099201 -vn -2.422947 -5.026844 1.954762 -v 0.005191 -0.042876 0.099064 -vn -2.176754 -2.797404 4.552910 -v 0.005206 -0.042510 0.099531 -vn -0.572173 -2.915978 5.151248 -v 0.005580 -0.042510 0.099616 -vn -4.607516 -0.765326 3.717152 -v 0.004802 -0.042010 0.099378 -vn -2.553520 -0.765317 5.340993 -v 0.005148 -0.042010 0.099652 -vn -0.671219 -0.789218 6.048069 -v 0.005580 -0.042010 0.099750 -vn -2.840592 -5.185771 1.207449 -v 0.005093 -0.042876 0.098865 -vn 5.658781 -0.794254 -2.388298 -v 0.042493 -0.042010 0.084119 -vn 4.827047 -2.958255 -2.037040 -v 0.042363 -0.042510 0.084150 -vn 3.927681 -2.797383 -3.168670 -v 0.042194 -0.042510 0.083806 -vn 0.556916 -6.090549 -0.786079 -v 0.041520 -0.043010 0.084350 -vn 0.352972 -5.141421 -3.073853 -v 0.041520 -0.042876 0.083850 -vn 1.342835 -5.026865 -2.808646 -v 0.041736 -0.042876 0.083899 -vn 2.422960 -5.026884 -1.954726 -v 0.041909 -0.042876 0.084036 -vn 2.176755 -2.797399 -4.552914 -v 0.041894 -0.042510 0.083569 -vn 0.572172 -2.915980 -5.151248 -v 0.041520 -0.042510 0.083484 -vn 4.607563 -0.765305 -3.717134 -v 0.042298 -0.042010 0.083722 -vn 2.553558 -0.765321 -5.340952 -v 0.041952 -0.042010 0.083448 -vn 0.671214 -0.789218 -6.048070 -v 0.041520 -0.042010 0.083350 -vn 2.840592 -5.185760 -1.207465 -v 0.042007 -0.042876 0.084235 -vn 1.517275 3.665190 2.627993 -v 0.045150 -0.041010 0.100047 -vn 2.627992 3.665188 1.517278 -v 0.044747 -0.041010 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.044600 -0.041010 0.101000 -vn 2.627994 3.665191 -1.517273 -v 0.044747 -0.041010 0.101550 -vn 1.517275 3.665190 -2.627993 -v 0.045150 -0.041010 0.101953 -vn 0.671212 -0.789217 6.048071 -v 0.041520 -0.042010 0.099750 -vn 0.572171 -2.915983 5.151247 -v 0.041520 -0.042510 0.099616 -vn 2.176745 -2.797410 4.552920 -v 0.041894 -0.042510 0.099531 -vn 0.556913 -6.090551 0.786079 -v 0.041520 -0.043010 0.098750 -vn 2.840591 -5.185773 1.207445 -v 0.042007 -0.042876 0.098865 -vn 2.422943 -5.026857 1.954749 -v 0.041909 -0.042876 0.099064 -vn 1.342802 -5.026873 2.808665 -v 0.041736 -0.042876 0.099201 -vn 3.927692 -2.797399 3.168669 -v 0.042194 -0.042510 0.099294 -vn 4.827048 -2.958263 2.037050 -v 0.042363 -0.042510 0.098950 -vn 2.553530 -0.765321 5.340980 -v 0.041952 -0.042010 0.099652 -vn 4.607528 -0.765321 3.717148 -v 0.042298 -0.042010 0.099378 -vn 5.658780 -0.794268 2.388282 -v 0.042493 -0.042010 0.098981 -vn 0.352974 -5.141419 3.073854 -v 0.041520 -0.042876 0.099250 -vn 1.517277 -2.617997 -2.627992 -v 0.039950 -0.008510 0.102716 -vn 2.627995 -2.617990 -1.517266 -v 0.039584 -0.008510 0.102350 -vn 3.034547 -2.617999 0.000006 -v 0.039450 -0.008510 0.101850 -vn 2.628005 -2.618003 1.517261 -v 0.039584 -0.008510 0.101350 -vn 1.517267 -2.617973 2.627986 -v 0.039950 -0.008510 0.100984 -vn 6.214806 -0.615148 -0.491527 -v 0.017050 -0.042010 0.083750 -vn 3.104394 -2.956253 -0.335679 -v 0.017050 -0.041410 0.083750 -vn 5.941162 -0.843355 -1.746886 -v 0.017128 -0.042010 0.084244 -vn 2.642634 -2.786450 -1.551764 -v 0.017264 -0.041410 0.084550 -vn 2.957039 -0.787737 -5.454961 -v 0.017850 -0.042010 0.085136 -vn 3.938955 -0.928195 -4.770837 -v 0.017710 -0.042010 0.085044 -vn 1.551762 -2.786463 -2.642638 -v 0.017850 -0.041410 0.085136 -vn 4.770801 -0.928212 -3.938999 -v 0.017356 -0.042010 0.084690 -vn 5.489358 -0.718595 -2.919086 -v 0.017264 -0.042010 0.084550 -vn 1.748138 -0.927286 -5.931561 -v 0.018156 -0.042010 0.085272 -vn 0.335687 -2.956245 -3.104392 -v 0.018650 -0.041410 0.085350 -vn 0.489419 -0.818799 -6.178016 -v 0.018650 -0.042010 0.085350 -vn -0.407484 -0.818540 -6.182953 -v 0.028450 -0.042010 0.085350 -vn -0.372536 -2.941411 -3.095299 -v 0.028450 -0.041410 0.085350 -vn 1.517274 -3.665191 -2.627993 -v 0.026250 -0.041410 0.083053 -vn 2.627995 -3.665195 -1.517268 -v 0.025847 -0.041410 0.082650 -vn 3.034548 -3.665185 0.000000 -v 0.025700 -0.041410 0.082100 -vn 2.627985 -3.665207 1.517278 -v 0.025847 -0.041410 0.081550 -vn 1.517264 -3.665182 2.628003 -v 0.026250 -0.041410 0.081147 -vn 1.517277 -3.665193 -2.627991 -v 0.019750 -0.041410 0.083053 -vn 2.627996 -3.665189 -1.517270 -v 0.019347 -0.041410 0.082650 -vn 3.034546 -3.665191 0.000000 -v 0.019200 -0.041410 0.082100 -vn 2.627986 -3.665198 1.517280 -v 0.019347 -0.041410 0.081550 -vn 1.517266 -3.665184 2.628001 -v 0.019750 -0.041410 0.081147 -vn -2.617242 -2.679613 -1.550351 -v 0.029836 -0.041410 0.084550 -vn -3.088070 -2.879796 -0.406548 -v 0.030050 -0.041410 0.083750 -vn -6.162402 -0.924329 -0.517503 -v 0.030050 -0.042010 0.083750 -vn -5.962763 -1.206151 -1.441137 -v 0.029995 -0.042010 0.084164 -vn -5.280369 -0.937205 -3.188666 -v 0.029836 -0.042010 0.084550 -vn -1.491423 -2.679626 -2.651269 -v 0.029250 -0.041410 0.085136 -vn -4.443309 -1.206168 -4.229462 -v 0.029581 -0.042010 0.084881 -vn -2.978558 -0.937219 -5.401673 -v 0.029250 -0.042010 0.085136 -vn -1.733300 -1.206159 -5.884482 -v 0.028864 -0.042010 0.085295 -vn 1.517278 -3.665196 -2.627988 -v 0.000850 -0.041410 0.083053 -vn 2.627999 -3.665186 -1.517267 -v 0.000447 -0.041410 0.082650 -vn 3.034546 -3.665191 0.000000 -v 0.000300 -0.041410 0.082100 -vn 2.627988 -3.665196 1.517278 -v 0.000447 -0.041410 0.081550 -vn 1.517267 -3.665187 2.627999 -v 0.000850 -0.041410 0.081147 -vn -3.976731 -0.840897 -4.756305 -v 0.004042 -0.042010 0.085005 -vn -1.350143 -2.803327 -2.765070 -v 0.003740 -0.041410 0.085193 -vn -4.633788 -0.548488 -4.182389 -v 0.004295 -0.042010 0.084755 -vn -2.362080 -2.759151 -1.966281 -v 0.004295 -0.041410 0.084755 -vn -5.433138 -0.666570 -3.039059 -v 0.004399 -0.042010 0.084610 -vn -2.837893 -3.183399 -1.346361 -v 0.004607 -0.041410 0.084119 -vn -0.523360 -0.615045 -6.211639 -v 0.003050 -0.042010 0.085350 -vn -0.307749 -2.960412 -3.110884 -v 0.003050 -0.041410 0.085350 -vn -1.703343 -0.666540 -5.987777 -v 0.003575 -0.042010 0.085261 -vn -2.856093 -0.553479 -5.552011 -v 0.003740 -0.042010 0.085193 -vn -0.347379 -3.364585 -3.102700 -v 0.005580 -0.041410 0.083350 -vn -1.321552 -3.587569 -2.764133 -v 0.005148 -0.041410 0.083448 -vn -2.384565 -3.587562 -1.923745 -v 0.004802 -0.041410 0.083722 -vn -0.407447 -0.818540 -6.182953 -v 0.006650 -0.042010 0.083350 -vn -0.354356 -2.958396 -3.099026 -v 0.006650 -0.041410 0.083350 -vn -3.108788 -2.979061 -0.312062 -v 0.008750 -0.041410 0.081250 -vn -6.190158 -0.789733 -0.371802 -v 0.008750 -0.042010 0.081250 -vn -5.966094 -0.997452 -1.598603 -v 0.008678 -0.042010 0.081794 -vn -2.598692 -2.717261 -1.609461 -v 0.008469 -0.041410 0.082300 -vn -5.269584 -0.943543 -3.200588 -v 0.008469 -0.042010 0.082300 -vn -1.477547 -2.696588 -2.663577 -v 0.007700 -0.041410 0.083069 -vn -4.440570 -1.348736 -4.184226 -v 0.008135 -0.042010 0.082735 -vn -2.963305 -0.943522 -5.406581 -v 0.007700 -0.042010 0.083069 -vn -1.753511 -1.348741 -5.843936 -v 0.007194 -0.042010 0.083278 -vn 1.517277 -3.665189 -2.627992 -v 0.006150 -0.041410 0.082116 -vn 2.627995 -3.665195 -1.517266 -v 0.005784 -0.041410 0.081750 -vn 3.034548 -3.665183 -0.000000 -v 0.005650 -0.041410 0.081250 -vn 2.627995 -3.665195 1.517266 -v 0.005784 -0.041410 0.080750 -vn 1.517277 -3.665191 2.627992 -v 0.006150 -0.041410 0.080384 -vn -1.550353 -2.679628 2.617247 -v 0.029250 -0.041410 0.097964 -vn -0.406555 -2.879791 3.088068 -v 0.028450 -0.041410 0.097750 -vn -0.528738 -0.931790 6.160450 -v 0.028450 -0.042010 0.097750 -vn -1.441152 -1.206178 5.962749 -v 0.028864 -0.042010 0.097805 -vn -3.188694 -0.937219 5.280354 -v 0.029250 -0.042010 0.097964 -vn -2.651264 -2.679618 1.491427 -v 0.029836 -0.041410 0.098550 -vn -4.229434 -1.206165 4.443336 -v 0.029581 -0.042010 0.098219 -vn -5.401661 -0.937203 2.978586 -v 0.029836 -0.042010 0.098550 -vn -3.095300 -2.941419 0.372530 -v 0.030050 -0.041410 0.099350 -vn -5.884476 -1.206156 1.733303 -v 0.029995 -0.042010 0.098936 -vn -6.182957 -0.818529 0.407443 -v 0.030050 -0.042010 0.099350 -vn 0.489374 -0.818798 6.178019 -v 0.018650 -0.042010 0.097750 -vn 0.335677 -2.956255 3.104394 -v 0.018650 -0.041410 0.097750 -vn 1.517274 -3.665191 -2.627993 -v 0.026250 -0.041410 0.101953 -vn 2.627995 -3.665195 -1.517268 -v 0.025847 -0.041410 0.101550 -vn 3.034547 -3.665189 0.000005 -v 0.025700 -0.041410 0.101000 -vn 2.627994 -3.665191 1.517273 -v 0.025847 -0.041410 0.100450 -vn 1.517274 -3.665191 2.627993 -v 0.026250 -0.041410 0.100047 -vn 1.517277 -3.665194 -2.627991 -v 0.019750 -0.041410 0.101953 -vn 2.627996 -3.665189 -1.517270 -v 0.019347 -0.041410 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.019200 -0.041410 0.101000 -vn 2.627995 -3.665185 1.517275 -v 0.019347 -0.041410 0.100450 -vn 1.517276 -3.665193 2.627990 -v 0.019750 -0.041410 0.100047 -vn 1.790633 -0.886069 5.923739 -v 0.018156 -0.042010 0.097828 -vn 1.551767 -2.786480 2.642639 -v 0.017850 -0.041410 0.097964 -vn 5.454933 -0.787749 2.957086 -v 0.017264 -0.042010 0.098550 -vn 4.770831 -0.928195 3.938965 -v 0.017356 -0.042010 0.098410 -vn 2.642638 -2.786467 1.551762 -v 0.017264 -0.041410 0.098550 -vn 3.938936 -0.928209 4.770850 -v 0.017710 -0.042010 0.098056 -vn 2.919063 -0.718622 5.489366 -v 0.017850 -0.042010 0.097964 -vn 5.931559 -0.927287 1.748134 -v 0.017128 -0.042010 0.098856 -vn 3.104394 -2.956252 0.335681 -v 0.017050 -0.041410 0.099350 -vn 6.178017 -0.818797 0.489399 -v 0.017050 -0.042010 0.099350 -vn 1.517278 -3.665196 -2.627988 -v 0.000850 -0.041410 0.101953 -vn 2.627999 -3.665187 -1.517267 -v 0.000447 -0.041410 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.000300 -0.041410 0.101000 -vn 2.627997 -3.665184 1.517273 -v 0.000447 -0.041410 0.100450 -vn 1.517278 -3.665196 2.627988 -v 0.000850 -0.041410 0.100047 -vn -1.567953 -2.696598 2.611384 -v 0.007700 -0.041410 0.100031 -vn -0.406555 -2.879791 3.088068 -v 0.006650 -0.041410 0.099750 -vn -0.544447 -0.938123 6.157068 -v 0.006650 -0.042010 0.099750 -vn -1.403359 -1.348765 5.937748 -v 0.007194 -0.042010 0.099822 -vn -3.200590 -0.943557 5.269581 -v 0.007700 -0.042010 0.100031 -vn -2.663578 -2.696599 1.477553 -v 0.008469 -0.041410 0.100800 -vn -4.184205 -1.348775 4.440569 -v 0.008135 -0.042010 0.100365 -vn -5.406584 -0.943548 2.963298 -v 0.008469 -0.042010 0.100800 -vn -3.099024 -2.958394 0.354363 -v 0.008750 -0.041410 0.101850 -vn -5.843916 -1.348760 1.753548 -v 0.008678 -0.042010 0.101306 -vn -6.182956 -0.818529 0.407447 -v 0.008750 -0.042010 0.101850 -vn -0.347379 -3.364585 3.102700 -v 0.005580 -0.041410 0.099750 -vn -2.829677 -3.185749 1.362712 -v 0.004607 -0.041410 0.098981 -vn -2.384549 -3.587575 1.923758 -v 0.004802 -0.041410 0.099378 -vn -1.321535 -3.587557 2.764146 -v 0.005148 -0.041410 0.099652 -vn -0.347364 -2.918610 3.102703 -v 0.003050 -0.041410 0.097750 -vn -0.430978 -0.903169 6.172349 -v 0.003050 -0.042010 0.097750 -vn -1.295006 -2.808196 2.793762 -v 0.003740 -0.041410 0.097906 -vn -1.249997 -1.095367 6.035145 -v 0.003404 -0.042010 0.097790 -vn -2.671861 -0.823211 5.588490 -v 0.003740 -0.042010 0.097906 -vn -3.839723 -0.893295 4.856870 -v 0.004042 -0.042010 0.098095 -vn -2.430128 -2.764060 1.885298 -v 0.004295 -0.041410 0.098345 -vn -4.869438 -0.915681 3.805783 -v 0.004295 -0.042010 0.098345 -vn -5.482013 -1.095390 2.816543 -v 0.004487 -0.042010 0.098646 -vn 1.517277 -3.665189 -2.627992 -v 0.006150 -0.041410 0.102716 -vn 2.627995 -3.665195 -1.517266 -v 0.005784 -0.041410 0.102350 -vn 3.034547 -3.665186 0.000006 -v 0.005650 -0.041410 0.101850 -vn 2.628005 -3.665183 1.517260 -v 0.005784 -0.041410 0.101350 -vn 1.517267 -3.665213 2.627986 -v 0.006150 -0.041410 0.100984 -vn 1.517275 -3.665190 -2.627993 -v 0.045150 -0.041410 0.083053 -vn 2.627994 -3.665192 -1.517273 -v 0.044747 -0.041410 0.082650 -vn 3.034546 -3.665192 0.000000 -v 0.044600 -0.041410 0.082100 -vn 2.627983 -3.665201 1.517283 -v 0.044747 -0.041410 0.081550 -vn 1.517265 -3.665181 2.628003 -v 0.045150 -0.041410 0.081147 -vn 4.184236 -1.348724 -4.440567 -v 0.038965 -0.042010 0.082735 -vn 2.634275 -2.795855 -1.569739 -v 0.038631 -0.041410 0.082300 -vn 3.200571 -0.943517 -5.269597 -v 0.039400 -0.042010 0.083069 -vn 1.609453 -2.717255 -2.598695 -v 0.039400 -0.041410 0.083069 -vn 1.598591 -0.997438 -5.966100 -v 0.039906 -0.042010 0.083278 -vn 0.312059 -2.979062 -3.108788 -v 0.040450 -0.041410 0.083350 -vn 0.407450 -0.818537 -6.182954 -v 0.040450 -0.042010 0.083350 -vn 6.182954 -0.818540 -0.407447 -v 0.038350 -0.042010 0.081250 -vn 3.108788 -2.979062 -0.312061 -v 0.038350 -0.041410 0.081250 -vn 5.966095 -0.997451 -1.598599 -v 0.038422 -0.042010 0.081794 -vn 5.360497 -0.823955 -3.094891 -v 0.038631 -0.042010 0.082300 -vn 0.347376 -3.364583 -3.102701 -v 0.041520 -0.041410 0.083350 -vn 2.845311 -3.210039 -1.328689 -v 0.042493 -0.041410 0.084119 -vn 2.384572 -3.587557 -1.923740 -v 0.042298 -0.041410 0.083722 -vn 1.321555 -3.587577 -2.764128 -v 0.041952 -0.041410 0.083448 -vn 1.517277 -3.665189 -2.627992 -v 0.039950 -0.041410 0.082116 -vn 2.627995 -3.665196 -1.517266 -v 0.039584 -0.041410 0.081750 -vn 3.034548 -3.665183 -0.000000 -v 0.039450 -0.041410 0.081250 -vn 2.627995 -3.665196 1.517266 -v 0.039584 -0.041410 0.080750 -vn 1.517277 -3.665189 2.627992 -v 0.039950 -0.041410 0.080384 -vn 0.347380 -2.918600 -3.102700 -v 0.044050 -0.041410 0.085350 -vn 0.442237 -0.910610 -6.170398 -v 0.044050 -0.042010 0.085350 -vn 1.295010 -2.808223 -2.793768 -v 0.043360 -0.041410 0.085193 -vn 1.250034 -1.095363 -6.035136 -v 0.043696 -0.042010 0.085310 -vn 2.671872 -0.823206 -5.588489 -v 0.043360 -0.042010 0.085193 -vn 3.839689 -0.893278 -4.856900 -v 0.043058 -0.042010 0.085005 -vn 2.402182 -2.832500 -1.937968 -v 0.042805 -0.041410 0.084755 -vn 5.559116 -0.893300 -2.725597 -v 0.042613 -0.042010 0.084454 -vn 4.821061 -0.823200 -3.889405 -v 0.042805 -0.042010 0.084755 -vn 1.517277 -3.665193 -2.627991 -v 0.010300 -0.043010 0.100834 -vn 2.627995 -3.665186 -1.517275 -v 0.009897 -0.043010 0.100431 -vn 3.034544 -3.665195 -0.000005 -v 0.009750 -0.043010 0.099881 -vn 2.627996 -3.665189 1.517270 -v 0.009897 -0.043010 0.099331 -vn 1.517276 -3.665193 2.627990 -v 0.010300 -0.043010 0.098929 -vn 1.517265 -3.665181 -2.628003 -v 0.001969 -0.043010 0.092503 -vn 2.627983 -3.665201 -1.517283 -v 0.001566 -0.043010 0.092100 -vn 3.034546 -3.665191 0.000000 -v 0.001419 -0.043010 0.091550 -vn 2.627994 -3.665192 1.517273 -v 0.001566 -0.043010 0.091000 -vn 1.517275 -3.665190 2.627993 -v 0.001969 -0.043010 0.090597 -vn 1.517277 -3.665193 -2.627991 -v 0.010300 -0.043010 0.084171 -vn 2.627996 -3.665189 -1.517270 -v 0.009897 -0.043010 0.083769 -vn 3.034546 -3.665191 0.000000 -v 0.009750 -0.043010 0.083219 -vn 2.627996 -3.665189 1.517270 -v 0.009897 -0.043010 0.082669 -vn 1.517257 -3.665205 2.627996 -v 0.010300 -0.043010 0.082266 -vn 1.517266 -3.665184 -2.628001 -v 0.018631 -0.043010 0.092503 -vn 2.627986 -3.665198 -1.517280 -v 0.018229 -0.043010 0.092100 -vn 3.034546 -3.665191 0.000000 -v 0.018081 -0.043010 0.091550 -vn 2.627996 -3.665189 1.517270 -v 0.018229 -0.043010 0.091000 -vn 1.517276 -3.665193 2.627990 -v 0.018631 -0.043010 0.090597 -vn 1.517266 -3.665184 -2.628001 -v 0.027369 -0.043010 0.092503 -vn 2.627986 -3.665198 -1.517280 -v 0.026966 -0.043010 0.092100 -vn 3.034546 -3.665191 0.000000 -v 0.026819 -0.043010 0.091550 -vn 2.627996 -3.665189 1.517270 -v 0.026966 -0.043010 0.091000 -vn 1.517276 -3.665193 2.627990 -v 0.027369 -0.043010 0.090597 -vn 1.517275 -3.665190 -2.627993 -v 0.035700 -0.043010 0.084171 -vn 2.627994 -3.665192 -1.517273 -v 0.035297 -0.043010 0.083769 -vn 3.034546 -3.665191 0.000000 -v 0.035150 -0.043010 0.083219 -vn 2.627994 -3.665191 1.517273 -v 0.035297 -0.043010 0.082669 -vn 1.517256 -3.665202 2.627998 -v 0.035700 -0.043010 0.082266 -vn 1.517267 -3.665187 -2.627999 -v 0.044031 -0.043010 0.092503 -vn 2.627988 -3.665196 -1.517278 -v 0.043629 -0.043010 0.092100 -vn 3.034546 -3.665191 0.000000 -v 0.043481 -0.043010 0.091550 -vn 2.627999 -3.665187 1.517267 -v 0.043629 -0.043010 0.091000 -vn 1.517278 -3.665196 2.627988 -v 0.044031 -0.043010 0.090597 -vn 1.517275 -3.665190 -2.627993 -v 0.035700 -0.043010 0.100834 -vn 2.627992 -3.665188 -1.517278 -v 0.035297 -0.043010 0.100431 -vn 3.034544 -3.665195 -0.000005 -v 0.035150 -0.043010 0.099881 -vn 2.627994 -3.665192 1.517273 -v 0.035297 -0.043010 0.099331 -vn 1.517275 -3.665190 2.627993 -v 0.035700 -0.043010 0.098929 -vn 1.058163 -3.490663 -2.907281 -v 0.034540 -0.043010 0.096248 -vn 1.988700 -3.490658 -2.370036 -v 0.033036 -0.043010 0.095380 -vn 2.679366 -3.490658 -1.546932 -v 0.031920 -0.043010 0.094050 -vn 3.046862 -3.490659 -0.537244 -v 0.031326 -0.043010 0.092418 -vn 3.046862 -3.490659 0.537244 -v 0.031326 -0.043010 0.090682 -vn 2.679365 -3.490658 1.546932 -v 0.031920 -0.043010 0.089050 -vn 1.988695 -3.490660 2.370039 -v 0.033036 -0.043010 0.087720 -vn 1.058164 -3.490654 2.907283 -v 0.034540 -0.043010 0.086852 -vn 1.058163 -3.490663 -2.907281 -v 0.009140 -0.043010 0.096248 -vn 1.988699 -3.490655 -2.370038 -v 0.007636 -0.043010 0.095380 -vn 2.679364 -3.490660 -1.546934 -v 0.006520 -0.043010 0.094050 -vn 3.046862 -3.490659 -0.537244 -v 0.005926 -0.043010 0.092418 -vn 3.046862 -3.490660 0.537244 -v 0.005926 -0.043010 0.090682 -vn 2.679363 -3.490661 1.546934 -v 0.006520 -0.043010 0.089050 -vn 1.988694 -3.490658 2.370041 -v 0.007636 -0.043010 0.087720 -vn 1.058165 -3.490655 2.907283 -v 0.009140 -0.043010 0.086852 -vn -0.650182 -6.214002 -0.068374 -v 0.009750 -0.043010 0.080450 -vn -0.751377 -6.191322 -0.013538 -v 0.009750 -0.043010 0.081250 -vn -2.037509 -5.860775 -0.187022 -v 0.009367 -0.042934 0.080450 -vn -2.997674 -5.326804 -0.096272 -v 0.009250 -0.042876 0.081250 -vn -3.303898 -5.258896 -0.361355 -v 0.009250 -0.042876 0.080450 -vn -4.381547 -4.332810 -0.406946 -v 0.009043 -0.042717 0.080450 -vn -5.291303 -3.083422 -0.249507 -v 0.008884 -0.042510 0.081250 -vn -5.250904 -3.246561 -0.536371 -v 0.008884 -0.042510 0.080450 -vn -5.808912 -1.953600 -0.549263 -v 0.008826 -0.042393 0.080450 -vn -6.130269 -0.614986 -0.585408 -v 0.008750 -0.042010 0.080450 -vn -5.107411 -3.131279 -1.368519 -v 0.008808 -0.042510 0.081828 -vn -2.858920 -5.358583 -0.766043 -v 0.009161 -0.042876 0.081923 -vn -0.721781 -6.192101 -0.193400 -v 0.009644 -0.043010 0.082052 -vn -0.647128 -6.192102 -0.373619 -v 0.009335 -0.043010 0.082800 -vn -2.563237 -5.358582 -1.479883 -v 0.008902 -0.042876 0.082550 -vn -0.528374 -6.192103 -0.528376 -v 0.008842 -0.043010 0.083442 -vn -2.092875 -5.358581 -2.092870 -v 0.008488 -0.042876 0.083088 -vn -0.373621 -6.192102 -0.647128 -v 0.008200 -0.043010 0.083935 -vn -1.479884 -5.358597 -2.563221 -v 0.007950 -0.042876 0.083502 -vn -0.193400 -6.192101 -0.721781 -v 0.007452 -0.043010 0.084244 -vn -0.766029 -5.358605 -2.858900 -v 0.007323 -0.042876 0.083761 -vn -0.049186 -6.184118 -0.780178 -v 0.006650 -0.043010 0.084350 -vn -0.194825 -5.307285 -2.997159 -v 0.006650 -0.042876 0.083850 -vn -4.579175 -3.131285 -2.643795 -v 0.008585 -0.042510 0.082367 -vn -3.738874 -3.131284 -3.738886 -v 0.008230 -0.042510 0.082830 -vn -2.643788 -3.131284 -4.579165 -v 0.007767 -0.042510 0.083185 -vn -1.368516 -3.131293 -5.107395 -v 0.007228 -0.042510 0.083408 -vn -0.348067 -3.082922 -5.271780 -v 0.006650 -0.042510 0.083484 -vn -3.583354 -2.383600 -4.471079 -v 0.004089 -0.042393 0.085065 -vn -0.462646 -6.234116 -0.294815 -v 0.005243 -0.043010 0.085147 -vn -1.908878 -5.773362 -1.203214 -v 0.004920 -0.042934 0.084942 -vn -4.871020 -2.358214 -3.030273 -v 0.004464 -0.042393 0.084651 -vn -3.647902 -4.476587 -2.290615 -v 0.004646 -0.042717 0.084767 -vn -0.340227 -6.234115 -0.430356 -v 0.004662 -0.043010 0.085790 -vn -1.401987 -5.771911 -1.773390 -v 0.004425 -0.042934 0.085489 -vn -2.682644 -4.457129 -3.393307 -v 0.004224 -0.042717 0.085235 -vn -1.840205 -2.368657 -5.430070 -v 0.003600 -0.042393 0.085333 -vn -1.420015 -4.457139 -4.085903 -v 0.003671 -0.042717 0.085538 -vn -0.742119 -5.771914 -2.135350 -v 0.003778 -0.042934 0.085844 -vn -0.180096 -6.234115 -0.518197 -v 0.003904 -0.043010 0.086206 -vn -0.046307 -6.228469 -0.580738 -v 0.003050 -0.043010 0.086350 -vn -0.190817 -5.732644 -2.309439 -v 0.003050 -0.042934 0.085967 -vn -0.365129 -4.407306 -4.341583 -v 0.003050 -0.042717 0.085643 -vn -0.482517 -2.390353 -5.704843 -v 0.003050 -0.042393 0.085426 -vn -0.068375 -6.214003 -0.650182 -v -0.000250 -0.043010 0.086350 -vn -0.243858 -5.630284 -2.405174 -v -0.000250 -0.042934 0.085967 -vn -0.428689 -4.262744 -4.333865 -v -0.000250 -0.042717 0.085643 -vn -0.546667 -2.288655 -5.594932 -v -0.000250 -0.042393 0.085426 -vn -0.599941 -0.599946 -6.127479 -v -0.000250 -0.042010 0.085350 -vn -0.068375 -6.214003 0.650182 -v -0.000250 -0.043010 0.096750 -vn -0.031139 -6.184978 0.777637 -v 0.003050 -0.043010 0.096750 -vn -0.205321 -5.860672 2.039459 -v -0.000250 -0.042934 0.097133 -vn -0.139101 -5.305519 3.003380 -v 0.003050 -0.042876 0.097250 -vn -0.361357 -5.258888 3.303906 -v -0.000250 -0.042876 0.097250 -vn -0.431933 -4.333342 4.382070 -v -0.000250 -0.042717 0.097457 -vn -0.268705 -3.076950 5.276765 -v 0.003050 -0.042510 0.097616 -vn -0.536371 -3.246572 5.250894 -v -0.000250 -0.042510 0.097616 -vn -0.567562 -1.955560 5.808805 -v -0.000250 -0.042393 0.097674 -vn -0.585424 -0.614996 6.130260 -v -0.000250 -0.042010 0.097750 -vn -1.169218 -3.119133 5.156268 -v 0.003433 -0.042510 0.097659 -vn -0.657226 -5.344695 2.898383 -v 0.003514 -0.042876 0.097302 -vn -0.167416 -6.189916 0.738317 -v 0.003625 -0.043010 0.096814 -vn -0.326548 -6.189918 0.683004 -v 0.004171 -0.043010 0.097004 -vn -1.281929 -5.344691 2.681274 -v 0.003956 -0.042876 0.097455 -vn -0.469510 -6.189916 0.593887 -v 0.004662 -0.043010 0.097310 -vn -1.843140 -5.344690 2.331399 -v 0.004352 -0.042876 0.097703 -vn -0.589213 -6.189917 0.475351 -v 0.005074 -0.043010 0.097717 -vn -2.313082 -5.344683 1.866083 -v 0.004684 -0.042876 0.098031 -vn -0.679746 -6.189917 0.333278 -v 0.005385 -0.043010 0.098205 -vn -2.668488 -5.344686 1.308349 -v 0.004936 -0.042876 0.098426 -vn -2.280567 -3.119123 4.770037 -v 0.003798 -0.042510 0.097786 -vn -3.278974 -3.119109 4.147601 -v 0.004125 -0.042510 0.097990 -vn -4.115002 -3.119124 3.319800 -v 0.004400 -0.042510 0.098261 -vn -4.747282 -3.119113 2.327572 -v 0.004607 -0.042510 0.098587 -vn -0.049190 -6.184119 0.780175 -v 0.006650 -0.043010 0.098750 -vn -0.194836 -5.307286 2.997161 -v 0.006650 -0.042876 0.099250 -vn -0.348069 -3.082924 5.271779 -v 0.006650 -0.042510 0.099616 -vn -1.368531 -3.131280 5.107407 -v 0.007228 -0.042510 0.099692 -vn -0.766051 -5.358582 2.858920 -v 0.007323 -0.042876 0.099339 -vn -0.193403 -6.192101 0.721782 -v 0.007452 -0.043010 0.098856 -vn -0.373621 -6.192102 0.647131 -v 0.008200 -0.043010 0.099165 -vn -1.479886 -5.358580 2.563241 -v 0.007950 -0.042876 0.099598 -vn -0.528380 -6.192102 0.528380 -v 0.008842 -0.043010 0.099658 -vn -2.092873 -5.358582 2.092879 -v 0.008488 -0.042876 0.100012 -vn -0.647132 -6.192101 0.373622 -v 0.009335 -0.043010 0.100300 -vn -2.563233 -5.358588 1.479885 -v 0.008902 -0.042876 0.100550 -vn -0.721780 -6.192101 0.193401 -v 0.009644 -0.043010 0.101048 -vn -2.858918 -5.358584 0.766045 -v 0.009161 -0.042876 0.101177 -vn -0.780176 -6.184119 0.049188 -v 0.009750 -0.043010 0.101850 -vn -2.997162 -5.307285 0.194831 -v 0.009250 -0.042876 0.101850 -vn -2.643788 -3.131289 4.579177 -v 0.007767 -0.042510 0.099915 -vn -3.738879 -3.131287 3.738882 -v 0.008230 -0.042510 0.100270 -vn -4.579174 -3.131291 2.643779 -v 0.008585 -0.042510 0.100733 -vn -5.107406 -3.131283 1.368532 -v 0.008808 -0.042510 0.101272 -vn -5.271782 -3.082912 0.348061 -v 0.008884 -0.042510 0.101850 -vn -0.861577 -6.160654 0.090511 -v 0.009750 -0.043010 0.102650 -vn -3.071092 -5.157179 0.309077 -v 0.009250 -0.042876 0.102650 -vn -5.168921 -2.932350 0.505426 -v 0.008884 -0.042510 0.102650 -vn -6.070786 -0.792960 0.593304 -v 0.008750 -0.042010 0.102650 -vn 0.861579 -6.160653 0.090512 -v 0.016050 -0.043010 0.102650 -vn 0.773548 -6.185548 0.058125 -v 0.016050 -0.043010 0.099350 -vn 2.988651 -5.316312 0.233041 -v 0.016550 -0.042876 0.099350 -vn 3.071094 -5.157181 0.309070 -v 0.016550 -0.042876 0.102650 -vn 5.270853 -3.090507 0.418589 -v 0.016916 -0.042510 0.099350 -vn 5.168921 -2.932359 0.505420 -v 0.016916 -0.042510 0.102650 -vn 6.073565 -0.808020 0.578780 -v 0.017050 -0.042010 0.102650 -vn 5.046641 -3.116685 1.611285 -v 0.017001 -0.042510 0.098814 -vn 0.593798 -6.194962 0.431422 -v 0.016547 -0.043010 0.097822 -vn 0.431422 -6.194962 0.593801 -v 0.017122 -0.043010 0.097247 -vn 2.380728 -5.376637 1.729706 -v 0.016951 -0.042876 0.098116 -vn 1.729712 -5.376634 2.380732 -v 0.017416 -0.042876 0.097651 -vn 4.270345 -3.108605 3.139175 -v 0.017247 -0.042510 0.098331 -vn 3.117210 -3.125652 4.276876 -v 0.017631 -0.042510 0.097947 -vn 0.226814 -6.194961 0.698058 -v 0.017847 -0.043010 0.096877 -vn 0.058126 -6.185550 0.773545 -v 0.018650 -0.043010 0.096750 -vn 0.909353 -5.376647 2.798712 -v 0.018001 -0.042876 0.097353 -vn 0.233044 -5.316314 2.988645 -v 0.018650 -0.042876 0.097250 -vn 1.633363 -3.146427 5.027034 -v 0.018114 -0.042510 0.097701 -vn 0.418593 -3.090499 5.270859 -v 0.018650 -0.042510 0.097616 -vn 0.698059 -6.194961 0.226812 -v 0.016177 -0.043010 0.098547 -vn 2.798710 -5.376646 0.909362 -v 0.016653 -0.042876 0.098701 -vn -0.049189 -6.184120 0.780176 -v 0.028450 -0.043010 0.096750 -vn -0.194831 -5.307285 2.997163 -v 0.028450 -0.042876 0.097250 -vn -0.348058 -3.082922 5.271779 -v 0.028450 -0.042510 0.097616 -vn -1.368528 -3.131284 5.107408 -v 0.028899 -0.042510 0.097675 -vn -0.766050 -5.358585 2.858918 -v 0.028994 -0.042876 0.097322 -vn -0.193402 -6.192101 0.721782 -v 0.029123 -0.043010 0.096839 -vn -0.373622 -6.192101 0.647131 -v 0.029750 -0.043010 0.097098 -vn -1.479890 -5.358578 2.563241 -v 0.029500 -0.042876 0.097531 -vn -0.528379 -6.192101 0.528381 -v 0.030288 -0.043010 0.097512 -vn -2.092868 -5.358582 2.092885 -v 0.029935 -0.042876 0.097865 -vn -0.647131 -6.192101 0.373622 -v 0.030702 -0.043010 0.098050 -vn -2.563228 -5.358594 1.479882 -v 0.030269 -0.042876 0.098300 -vn -0.721781 -6.192101 0.193400 -v 0.030961 -0.043010 0.098677 -vn -2.858918 -5.358585 0.766041 -v 0.030478 -0.042876 0.098806 -vn -0.780177 -6.184119 0.049188 -v 0.031050 -0.043010 0.099350 -vn -2.997162 -5.307284 0.194829 -v 0.030550 -0.042876 0.099350 -vn -2.643794 -3.131287 4.579174 -v 0.029317 -0.042510 0.097848 -vn -3.738873 -3.131290 3.738886 -v 0.029676 -0.042510 0.098124 -vn -4.579171 -3.131288 2.643783 -v 0.029952 -0.042510 0.098483 -vn -5.107408 -3.131281 1.368530 -v 0.030125 -0.042510 0.098901 -vn -5.271782 -3.082912 0.348057 -v 0.030184 -0.042510 0.099350 -vn -0.861577 -6.160652 0.090511 -v 0.031050 -0.043010 0.102650 -vn -3.071092 -5.157179 0.309077 -v 0.030550 -0.042876 0.102650 -vn -5.168920 -2.932350 0.505426 -v 0.030184 -0.042510 0.102650 -vn -6.070786 -0.792960 0.593304 -v 0.030050 -0.042010 0.102650 -vn 0.861577 -6.160654 0.090511 -v 0.037350 -0.043010 0.102650 -vn 0.780176 -6.184119 0.049188 -v 0.037350 -0.043010 0.101850 -vn 2.997163 -5.307283 0.194828 -v 0.037850 -0.042876 0.101850 -vn 3.071092 -5.157180 0.309076 -v 0.037850 -0.042876 0.102650 -vn 5.271777 -3.082927 0.348065 -v 0.038216 -0.042510 0.101850 -vn 5.168919 -2.932358 0.505428 -v 0.038216 -0.042510 0.102650 -vn 6.182954 -0.818537 0.407450 -v 0.038350 -0.042010 0.101850 -vn 6.073564 -0.808022 0.578787 -v 0.038350 -0.042010 0.102650 -vn 5.107394 -3.131295 1.368533 -v 0.038292 -0.042510 0.101272 -vn 2.858912 -5.358592 0.766044 -v 0.037939 -0.042876 0.101177 -vn 0.721782 -6.192101 0.193401 -v 0.037456 -0.043010 0.101048 -vn 0.647133 -6.192101 0.373622 -v 0.037765 -0.043010 0.100300 -vn 2.563224 -5.358594 1.479887 -v 0.038198 -0.042876 0.100550 -vn 0.528379 -6.192102 0.528380 -v 0.038258 -0.043010 0.099658 -vn 2.092870 -5.358585 2.092875 -v 0.038612 -0.042876 0.100012 -vn 0.373620 -6.192102 0.647130 -v 0.038900 -0.043010 0.099165 -vn 1.479889 -5.358580 2.563239 -v 0.039150 -0.042876 0.099598 -vn 0.193403 -6.192101 0.721783 -v 0.039648 -0.043010 0.098856 -vn 0.766052 -5.358582 2.858921 -v 0.039777 -0.042876 0.099339 -vn 0.049189 -6.184119 0.780176 -v 0.040450 -0.043010 0.098750 -vn 0.194835 -5.307286 2.997160 -v 0.040450 -0.042876 0.099250 -vn 4.579168 -3.131288 2.643787 -v 0.038515 -0.042510 0.100733 -vn 3.738890 -3.131280 3.738876 -v 0.038870 -0.042510 0.100270 -vn 2.643788 -3.131290 4.579176 -v 0.039333 -0.042510 0.099915 -vn 1.368536 -3.131283 5.107404 -v 0.039872 -0.042510 0.099692 -vn 0.348067 -3.082922 5.271780 -v 0.040450 -0.042510 0.099616 -vn 5.966092 -0.997449 1.598611 -v 0.038422 -0.042010 0.101306 -vn 5.360504 -0.823954 3.094883 -v 0.038631 -0.042010 0.100800 -vn 4.367482 -0.997459 4.367481 -v 0.038965 -0.042010 0.100365 -vn 3.094886 -0.823968 5.360500 -v 0.039400 -0.042010 0.100031 -vn 1.598625 -0.997456 5.966086 -v 0.039906 -0.042010 0.099822 -vn 0.407447 -0.818540 6.182953 -v 0.040450 -0.042010 0.099750 -vn 4.747279 -3.119111 2.327586 -v 0.042493 -0.042510 0.098587 -vn 2.668478 -5.344690 1.308356 -v 0.042164 -0.042876 0.098426 -vn 0.679746 -6.189917 0.333278 -v 0.041715 -0.043010 0.098205 -vn 0.589207 -6.189919 0.475350 -v 0.042026 -0.043010 0.097717 -vn 2.313087 -5.344676 1.866087 -v 0.042416 -0.042876 0.098031 -vn 0.469513 -6.189915 0.593887 -v 0.042438 -0.043010 0.097310 -vn 1.843143 -5.344693 2.331397 -v 0.042748 -0.042876 0.097703 -vn 0.326548 -6.189917 0.683007 -v 0.042929 -0.043010 0.097004 -vn 1.281933 -5.344691 2.681273 -v 0.043144 -0.042876 0.097455 -vn 0.167419 -6.189915 0.738316 -v 0.043475 -0.043010 0.096814 -vn 0.657225 -5.344695 2.898382 -v 0.043586 -0.042876 0.097302 -vn 0.031138 -6.184977 0.777638 -v 0.044050 -0.043010 0.096750 -vn 0.139101 -5.305521 3.003376 -v 0.044050 -0.042876 0.097250 -vn 4.114992 -3.119113 3.319812 -v 0.042700 -0.042510 0.098261 -vn 3.278971 -3.119110 4.147596 -v 0.042975 -0.042510 0.097990 -vn 2.280590 -3.119118 4.770029 -v 0.043302 -0.042510 0.097786 -vn 1.169205 -3.119130 5.156273 -v 0.043667 -0.042510 0.097659 -vn 0.268710 -3.076950 5.276767 -v 0.044050 -0.042510 0.097616 -vn 5.559107 -0.893295 2.725614 -v 0.042613 -0.042010 0.098646 -vn 4.821044 -0.823209 3.889424 -v 0.042805 -0.042010 0.098345 -vn 3.839730 -0.893278 4.856868 -v 0.043058 -0.042010 0.098095 -vn 2.671868 -0.823215 5.588485 -v 0.043360 -0.042010 0.097906 -vn 1.369144 -0.893303 6.038053 -v 0.043696 -0.042010 0.097790 -vn 0.335519 -0.810721 6.187197 -v 0.044050 -0.042010 0.097750 -vn 0.090508 -6.160654 -0.861575 -v 0.047350 -0.043010 0.086350 -vn 0.042379 -6.183026 -0.785084 -v 0.044050 -0.043010 0.086350 -vn 0.166377 -5.300339 -3.003258 -v 0.044050 -0.042876 0.085850 -vn 0.309068 -5.157181 -3.071093 -v 0.047350 -0.042876 0.085850 -vn 0.296010 -3.076846 -5.271579 -v 0.044050 -0.042510 0.085484 -vn 0.505425 -2.932358 -5.168919 -v 0.047350 -0.042510 0.085484 -vn 0.578779 -0.808027 -6.073565 -v 0.047350 -0.042010 0.085350 -vn 1.169260 -3.119099 -5.156268 -v 0.043667 -0.042510 0.085441 -vn 0.657253 -5.344691 -2.898374 -v 0.043586 -0.042876 0.085798 -vn 0.167421 -6.189918 -0.738304 -v 0.043475 -0.043010 0.086286 -vn 0.326549 -6.189916 -0.683010 -v 0.042929 -0.043010 0.086096 -vn 1.281927 -5.344691 -2.681275 -v 0.043144 -0.042876 0.085645 -vn 0.469505 -6.189917 -0.593882 -v 0.042438 -0.043010 0.085790 -vn 1.843138 -5.344682 -2.331408 -v 0.042748 -0.042876 0.085397 -vn 0.589215 -6.189917 -0.475351 -v 0.042026 -0.043010 0.085383 -vn 2.313073 -5.344687 -1.866091 -v 0.042416 -0.042876 0.085069 -vn 0.679749 -6.189916 -0.333280 -v 0.041715 -0.043010 0.084895 -vn 2.668480 -5.344693 -1.308355 -v 0.042164 -0.042876 0.084674 -vn 2.280559 -3.119102 -4.770050 -v 0.043302 -0.042510 0.085314 -vn 3.278969 -3.119104 -4.147614 -v 0.042975 -0.042510 0.085110 -vn 4.114995 -3.119091 -3.319808 -v 0.042700 -0.042510 0.084839 -vn 4.747275 -3.119122 -2.327590 -v 0.042493 -0.042510 0.084513 -vn 0.049187 -6.184119 -0.780177 -v 0.040450 -0.043010 0.084350 -vn 0.194820 -5.307282 -2.997165 -v 0.040450 -0.042876 0.083850 -vn 0.348061 -3.082929 -5.271774 -v 0.040450 -0.042510 0.083484 -vn 1.368526 -3.131305 -5.107386 -v 0.039872 -0.042510 0.083408 -vn 0.766035 -5.358602 -2.858904 -v 0.039777 -0.042876 0.083761 -vn 0.193398 -6.192102 -0.721782 -v 0.039648 -0.043010 0.084244 -vn 0.373621 -6.192102 -0.647131 -v 0.038900 -0.043010 0.083935 -vn 1.479883 -5.358602 -2.563214 -v 0.039150 -0.042876 0.083502 -vn 0.528376 -6.192104 -0.528374 -v 0.038258 -0.043010 0.083442 -vn 2.092872 -5.358583 -2.092865 -v 0.038612 -0.042876 0.083088 -vn 0.647127 -6.192103 -0.373619 -v 0.037765 -0.043010 0.082800 -vn 2.563231 -5.358586 -1.479888 -v 0.038198 -0.042876 0.082550 -vn 0.721783 -6.192101 -0.193401 -v 0.037456 -0.043010 0.082052 -vn 2.858912 -5.358593 -0.766040 -v 0.037939 -0.042876 0.081923 -vn 0.780177 -6.184119 -0.049188 -v 0.037350 -0.043010 0.081250 -vn 2.997160 -5.307286 -0.194830 -v 0.037850 -0.042876 0.081250 -vn 2.643789 -3.131281 -4.579167 -v 0.039333 -0.042510 0.083185 -vn 3.738880 -3.131274 -3.738888 -v 0.038870 -0.042510 0.082830 -vn 4.579169 -3.131285 -2.643799 -v 0.038515 -0.042510 0.082367 -vn 5.107401 -3.131287 -1.368519 -v 0.038292 -0.042510 0.081828 -vn 5.271780 -3.082922 -0.348067 -v 0.038216 -0.042510 0.081250 -vn 0.861576 -6.160654 -0.090508 -v 0.037350 -0.043010 0.080450 -vn 3.071093 -5.157179 -0.309077 -v 0.037850 -0.042876 0.080450 -vn 5.168918 -2.932361 -0.505425 -v 0.038216 -0.042510 0.080450 -vn 6.070781 -0.792969 -0.593305 -v 0.038350 -0.042010 0.080450 -vn -0.650183 -6.214003 -0.068375 -v 0.031050 -0.043010 0.080450 -vn -0.772730 -6.186070 -0.037948 -v 0.031050 -0.043010 0.083750 -vn -2.039459 -5.860670 -0.205323 -v 0.030667 -0.042934 0.080450 -vn -2.997275 -5.312469 -0.167569 -v 0.030550 -0.042876 0.083750 -vn -3.303896 -5.258897 -0.361359 -v 0.030550 -0.042876 0.080450 -vn -4.382069 -4.333333 -0.431937 -v 0.030343 -0.042717 0.080450 -vn -5.276967 -3.083024 -0.320800 -v 0.030184 -0.042510 0.083750 -vn -5.250904 -3.246561 -0.536371 -v 0.030184 -0.042510 0.080450 -vn -5.808807 -1.955548 -0.567556 -v 0.030126 -0.042393 0.080450 -vn -6.130269 -0.614986 -0.585408 -v 0.030050 -0.042010 0.080450 -vn -5.107408 -3.131284 -1.368512 -v 0.030125 -0.042510 0.084199 -vn -2.858912 -5.358590 -0.766043 -v 0.030478 -0.042876 0.084294 -vn -0.721780 -6.192101 -0.193399 -v 0.030961 -0.043010 0.084423 -vn -0.647127 -6.192102 -0.373620 -v 0.030702 -0.043010 0.085050 -vn -2.563236 -5.358584 -1.479880 -v 0.030269 -0.042876 0.084800 -vn -0.528379 -6.192102 -0.528380 -v 0.030288 -0.043010 0.085588 -vn -2.092872 -5.358585 -2.092874 -v 0.029935 -0.042876 0.085235 -vn -0.373621 -6.192102 -0.647132 -v 0.029750 -0.043010 0.086002 -vn -1.479890 -5.358577 -2.563241 -v 0.029500 -0.042876 0.085569 -vn -0.193403 -6.192101 -0.721782 -v 0.029123 -0.043010 0.086261 -vn -0.766051 -5.358584 -2.858918 -v 0.028994 -0.042876 0.085778 -vn -0.049188 -6.184120 -0.780177 -v 0.028450 -0.043010 0.086350 -vn -0.194829 -5.307284 -2.997161 -v 0.028450 -0.042876 0.085850 -vn -4.579183 -3.131281 -2.643777 -v 0.029952 -0.042510 0.084617 -vn -3.738882 -3.131281 -3.738883 -v 0.029676 -0.042510 0.084976 -vn -2.643787 -3.131287 -4.579177 -v 0.029317 -0.042510 0.085252 -vn -1.368521 -3.131315 -5.107398 -v 0.028899 -0.042510 0.085425 -vn -0.348065 -3.082931 -5.271777 -v 0.028450 -0.042510 0.085484 -vn 0.058126 -6.185549 -0.773544 -v 0.018650 -0.043010 0.086350 -vn 0.233042 -5.316314 -2.988649 -v 0.018650 -0.042876 0.085850 -vn 0.418598 -3.090510 -5.270851 -v 0.018650 -0.042510 0.085484 -vn 1.611285 -3.116691 -5.046635 -v 0.018114 -0.042510 0.085399 -vn 0.678617 -6.201303 -0.188551 -v 0.016177 -0.043010 0.084553 -vn 0.582701 -6.228162 -0.043755 -v 0.016050 -0.043010 0.083750 -vn 1.969913 -5.919759 -0.129009 -v 0.016433 -0.042934 0.083750 -vn 2.828555 -5.394318 -0.795536 -v 0.016653 -0.042876 0.084399 -vn 0.431423 -6.194961 -0.593802 -v 0.017122 -0.043010 0.085853 -vn 0.593799 -6.194963 -0.431420 -v 0.016547 -0.043010 0.085278 -vn 1.729698 -5.376649 -2.380719 -v 0.017416 -0.042876 0.085449 -vn 2.380727 -5.376641 -1.729700 -v 0.016951 -0.042876 0.084984 -vn 3.139170 -3.108604 -4.270342 -v 0.017631 -0.042510 0.085153 -vn 4.276869 -3.125654 -3.117214 -v 0.017247 -0.042510 0.084769 -vn 0.226813 -6.194961 -0.698058 -v 0.017847 -0.043010 0.086223 -vn 0.909359 -5.376648 -2.798708 -v 0.018001 -0.042876 0.085747 -vn 3.282617 -5.328462 -0.258419 -v 0.016550 -0.042876 0.083750 -vn 4.397463 -4.430688 -0.300843 -v 0.016757 -0.042717 0.083750 -vn 5.078405 -3.141665 -1.506847 -v 0.017001 -0.042510 0.084286 -vn 5.299864 -3.314900 -0.418907 -v 0.016916 -0.042510 0.083750 -vn 5.905320 -2.010162 -0.425470 -v 0.016974 -0.042393 0.083750 -vn 0.650186 -6.214002 -0.068377 -v 0.016050 -0.043010 0.080450 -vn 2.007440 -5.861590 -0.280923 -v 0.016433 -0.042934 0.080450 -vn 3.308834 -5.260791 -0.329759 -v 0.016550 -0.042876 0.080450 -vn 4.367111 -4.332247 -0.494464 -v 0.016757 -0.042717 0.080450 -vn 5.255861 -3.245531 -0.517338 -v 0.016916 -0.042510 0.080450 -vn 5.802427 -1.951506 -0.601410 -v 0.016974 -0.042393 0.080450 -vn 6.127484 -0.599935 -0.599932 -v 0.017050 -0.042010 0.080450 -vn 0.068375 -6.214003 0.650182 -v 0.047350 -0.043010 0.096750 -vn 0.205321 -5.860671 2.039459 -v 0.047350 -0.042934 0.097133 -vn 0.361355 -5.258889 3.303906 -v 0.047350 -0.042876 0.097250 -vn 0.431929 -4.333342 4.382070 -v 0.047350 -0.042717 0.097457 -vn 0.599940 -0.599945 6.127480 -v 0.047350 -0.042010 0.097750 -vn 0.567556 -1.955563 5.808805 -v 0.047350 -0.042393 0.097674 -vn 0.536367 -3.246572 5.250894 -v 0.047350 -0.042510 0.097616 -vn 1.517275 -3.665190 -2.627993 -v 0.045150 -0.041410 0.101953 -vn 2.627994 -3.665192 -1.517273 -v 0.044747 -0.041410 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.044600 -0.041410 0.101000 -vn 2.627992 -3.665188 1.517278 -v 0.044747 -0.041410 0.100450 -vn 1.517275 -3.665189 2.627993 -v 0.045150 -0.041410 0.100047 -vn 2.845313 -3.210045 1.328684 -v 0.042493 -0.041410 0.098981 -vn 2.402186 -2.832510 1.937967 -v 0.042805 -0.041410 0.098345 -vn 1.331303 -2.832488 2.784567 -v 0.043360 -0.041410 0.097906 -vn 0.288835 -2.987051 3.114025 -v 0.044050 -0.041410 0.097750 -vn 0.347376 -3.364583 3.102700 -v 0.041520 -0.041410 0.099750 -vn 1.321539 -3.587563 2.764141 -v 0.041952 -0.041410 0.099652 -vn 2.384555 -3.587570 1.923753 -v 0.042298 -0.041410 0.099378 -vn 0.312064 -2.979061 3.108787 -v 0.040450 -0.041410 0.099750 -vn 3.108788 -2.979061 0.312062 -v 0.038350 -0.041410 0.101850 -vn 2.663881 -2.816531 1.537990 -v 0.038631 -0.041410 0.100800 -vn 1.537995 -2.816535 2.663879 -v 0.039400 -0.041410 0.100031 -vn 1.517277 -3.665189 -2.627992 -v 0.039950 -0.041410 0.102716 -vn 2.627995 -3.665196 -1.517266 -v 0.039584 -0.041410 0.102350 -vn 3.034547 -3.665187 0.000006 -v 0.039450 -0.041410 0.101850 -vn 2.628005 -3.665182 1.517260 -v 0.039584 -0.041410 0.101350 -vn 1.517267 -3.665213 2.627986 -v 0.039950 -0.041410 0.100984 -vn -3.117130 -3.318306 -0.276139 -v 0.008750 -0.041410 0.080450 -vn -5.083621 -2.198392 -2.142036 -v 0.008942 -0.042393 0.079867 -vn -0.576662 -0.633698 -6.131706 -v 0.010350 -0.042010 0.078850 -vn -2.142034 -2.198379 -5.083621 -v 0.009767 -0.042393 0.079042 -vn -2.326204 -0.646587 -5.570498 -v 0.009738 -0.042010 0.078972 -vn -3.886595 -2.219052 -3.886590 -v 0.009272 -0.042393 0.079372 -vn -4.245197 -0.581876 -4.284571 -v 0.009219 -0.042010 0.079319 -vn -5.572764 -0.608032 -2.320723 -v 0.008872 -0.042010 0.079838 -vn -3.971473 -4.179677 -1.721218 -v 0.009142 -0.042717 0.079950 -vn -3.047765 -4.168050 -3.047757 -v 0.009426 -0.042717 0.079526 -vn -1.721220 -4.179676 -3.971472 -v 0.009850 -0.042717 0.079242 -vn -2.213401 -5.594195 -0.985851 -v 0.009442 -0.042934 0.080074 -vn -0.568259 -1.955527 -5.808810 -v 0.010350 -0.042393 0.078926 -vn -0.536369 -3.246572 -5.250894 -v 0.010350 -0.042510 0.078984 -vn -0.432870 -4.333347 -4.382075 -v 0.010350 -0.042717 0.079143 -vn -0.361357 -5.258889 -3.303906 -v 0.010350 -0.042876 0.079350 -vn -1.733922 -5.567168 -1.733909 -v 0.009655 -0.042934 0.079755 -vn -0.985860 -5.594196 -2.213396 -v 0.009974 -0.042934 0.079542 -vn -0.206023 -5.860667 -2.039482 -v 0.010350 -0.042934 0.079467 -vn -0.635154 -6.205182 -0.263088 -v 0.009796 -0.043010 0.080220 -vn -0.486127 -6.205182 -0.486124 -v 0.009926 -0.043010 0.080026 -vn -0.263092 -6.205181 -0.635154 -v 0.010120 -0.043010 0.079896 -vn -0.068374 -6.214003 -0.650182 -v 0.010350 -0.043010 0.079850 -vn 0.097990 -6.161927 -0.856749 -v 0.015450 -0.043010 0.079850 -vn 0.326972 -5.160559 -3.071171 -v 0.015450 -0.042876 0.079350 -vn 1.189251 -5.058393 -2.871064 -v 0.015871 -0.042876 0.079434 -vn 0.523304 -2.932408 -5.172307 -v 0.015450 -0.042510 0.078984 -vn 1.944750 -2.830165 -4.695008 -v 0.016011 -0.042510 0.079096 -vn 5.497653 -0.716065 -2.346923 -v 0.016928 -0.042010 0.079838 -vn 4.690491 -2.837509 -2.071938 -v 0.016804 -0.042510 0.079889 -vn 3.593417 -2.830163 -3.593411 -v 0.016487 -0.042510 0.079413 -vn 4.260380 -0.817399 -4.182777 -v 0.016581 -0.042010 0.079319 -vn 2.270395 -0.863550 -5.529505 -v 0.016062 -0.042010 0.078972 -vn 0.577857 -0.815006 -6.076334 -v 0.015450 -0.042010 0.078850 -vn 2.197427 -5.058372 -2.197430 -v 0.016228 -0.042876 0.079672 -vn 2.830495 -5.097243 -1.336814 -v 0.016466 -0.042876 0.080029 -vn 0.348259 -6.145169 -0.840774 -v 0.015680 -0.043010 0.079896 -vn 0.643499 -6.145171 -0.643494 -v 0.015874 -0.043010 0.080026 -vn 0.762314 -6.162053 -0.391711 -v 0.016004 -0.043010 0.080220 -vn 3.114238 -3.333947 -0.291685 -v 0.017050 -0.041410 0.080450 -vn 2.462056 -3.385208 -2.717727 -v 0.016612 -0.041410 0.079350 -vn -2.370143 -3.427206 -2.847855 -v 0.030488 -0.041410 0.079350 -vn -2.891037 -3.508435 -1.085077 -v 0.030149 -0.041410 0.079896 -vn -3.117130 -3.318307 -0.276139 -v 0.030050 -0.041410 0.080450 -vn 2.880707 -3.549185 -1.089800 -v 0.016951 -0.041410 0.079896 -vn -5.083621 -2.198392 -2.142036 -v 0.030242 -0.042393 0.079867 -vn -0.576662 -0.633698 -6.131704 -v 0.031650 -0.042010 0.078850 -vn -2.142034 -2.198379 -5.083621 -v 0.031067 -0.042393 0.079042 -vn -2.326204 -0.646587 -5.570498 -v 0.031038 -0.042010 0.078972 -vn -3.886595 -2.219052 -3.886590 -v 0.030572 -0.042393 0.079372 -vn -4.245197 -0.581876 -4.284571 -v 0.030519 -0.042010 0.079319 -vn -5.572764 -0.608032 -2.320723 -v 0.030172 -0.042010 0.079838 -vn -3.971468 -4.179680 -1.721217 -v 0.030442 -0.042717 0.079950 -vn -3.047765 -4.168050 -3.047755 -v 0.030726 -0.042717 0.079526 -vn -1.721220 -4.179675 -3.971473 -v 0.031150 -0.042717 0.079242 -vn -2.213397 -5.594201 -0.985850 -v 0.030742 -0.042934 0.080074 -vn -0.568259 -1.955527 -5.808810 -v 0.031650 -0.042393 0.078926 -vn -0.536369 -3.246572 -5.250894 -v 0.031650 -0.042510 0.078984 -vn -0.432870 -4.333347 -4.382075 -v 0.031650 -0.042717 0.079143 -vn -0.361356 -5.258888 -3.303906 -v 0.031650 -0.042876 0.079350 -vn -1.733928 -5.567166 -1.733905 -v 0.030955 -0.042934 0.079755 -vn -0.985864 -5.594193 -2.213397 -v 0.031274 -0.042934 0.079542 -vn -0.206022 -5.860667 -2.039482 -v 0.031650 -0.042934 0.079467 -vn -0.635157 -6.205181 -0.263088 -v 0.031096 -0.043010 0.080220 -vn -0.486126 -6.205182 -0.486124 -v 0.031226 -0.043010 0.080026 -vn -0.263089 -6.205182 -0.635152 -v 0.031420 -0.043010 0.079896 -vn -0.068375 -6.214003 -0.650182 -v 0.031650 -0.043010 0.079850 -vn 0.097991 -6.161927 -0.856749 -v 0.036750 -0.043010 0.079850 -vn 0.326973 -5.160559 -3.071171 -v 0.036750 -0.042876 0.079350 -vn 1.189249 -5.058398 -2.871062 -v 0.037171 -0.042876 0.079434 -vn 0.523304 -2.932408 -5.172308 -v 0.036750 -0.042510 0.078984 -vn 1.944753 -2.830161 -4.695002 -v 0.037311 -0.042510 0.079096 -vn 0.569301 -0.829438 -6.077694 -v 0.036750 -0.042010 0.078850 -vn 2.277182 -0.871615 -5.527920 -v 0.037362 -0.042010 0.078972 -vn 4.260380 -0.817397 -4.182774 -v 0.037881 -0.042010 0.079319 -vn 3.593422 -2.830164 -3.593403 -v 0.037787 -0.042510 0.079413 -vn 5.497575 -0.749646 -2.305677 -v 0.038228 -0.042010 0.079838 -vn 4.695027 -2.830174 -1.944733 -v 0.038104 -0.042510 0.079889 -vn 2.197428 -5.058369 -2.197430 -v 0.037528 -0.042876 0.079672 -vn 2.871080 -5.058381 -1.189233 -v 0.037766 -0.042876 0.080029 -vn 0.348257 -6.145169 -0.840774 -v 0.036980 -0.043010 0.079896 -vn 0.643501 -6.145169 -0.643499 -v 0.037174 -0.043010 0.080026 -vn 0.840770 -6.145171 -0.348254 -v 0.037304 -0.043010 0.080220 -vn 3.114237 -3.333950 -0.291687 -v 0.038350 -0.041410 0.080450 -vn -0.276154 -3.318316 3.117127 -v -0.000250 -0.041410 0.097750 -vn -2.142041 -2.198390 5.083620 -v -0.000833 -0.042393 0.097558 -vn -6.131692 -0.633722 0.576669 -v -0.001850 -0.042010 0.096150 -vn -5.083623 -2.198390 2.142031 -v -0.001658 -0.042393 0.096733 -vn -5.570495 -0.646600 2.326218 -v -0.001728 -0.042010 0.096762 -vn -3.886588 -2.219051 3.886595 -v -0.001328 -0.042393 0.097228 -vn -4.284581 -0.581870 4.245185 -v -0.001381 -0.042010 0.097281 -vn -2.320733 -0.608024 5.572760 -v -0.000862 -0.042010 0.097628 -vn -1.721218 -4.179675 3.971478 -v -0.000750 -0.042717 0.097358 -vn -3.047761 -4.168050 3.047760 -v -0.001174 -0.042717 0.097074 -vn -3.971476 -4.179676 1.721215 -v -0.001458 -0.042717 0.096650 -vn -0.985866 -5.594192 2.213397 -v -0.000626 -0.042934 0.097058 -vn -5.808807 -1.955566 0.568765 -v -0.001774 -0.042393 0.096150 -vn -5.250896 -3.246574 0.536367 -v -0.001716 -0.042510 0.096150 -vn -4.382078 -4.333350 0.433546 -v -0.001557 -0.042717 0.096150 -vn -3.303907 -5.258889 0.361353 -v -0.001350 -0.042876 0.096150 -vn -1.733914 -5.567175 1.733909 -v -0.000945 -0.042934 0.096845 -vn -2.213399 -5.594190 0.985868 -v -0.001158 -0.042934 0.096526 -vn -2.039491 -5.860671 0.206527 -v -0.001233 -0.042934 0.096150 -vn -0.263090 -6.205182 0.635153 -v -0.000480 -0.043010 0.096704 -vn -0.486124 -6.205182 0.486124 -v -0.000674 -0.043010 0.096574 -vn -0.635153 -6.205182 0.263090 -v -0.000804 -0.043010 0.096380 -vn -0.650181 -6.214004 0.068373 -v -0.000850 -0.043010 0.096150 -vn -6.133105 -0.641256 -0.568479 -v -0.001850 -0.042010 0.086950 -vn -5.589576 -0.685766 -2.302701 -v -0.001728 -0.042010 0.086338 -vn -5.808809 -1.955567 -0.568764 -v -0.001774 -0.042393 0.086950 -vn -5.083614 -2.198379 -2.142046 -v -0.001658 -0.042393 0.086367 -vn -5.250894 -3.246572 -0.536367 -v -0.001716 -0.042510 0.086950 -vn -3.971460 -4.179676 -1.721229 -v -0.001458 -0.042717 0.086450 -vn -2.213396 -5.594199 -0.985859 -v -0.001158 -0.042934 0.086574 -vn -3.303906 -5.258891 -0.361357 -v -0.001350 -0.042876 0.086950 -vn -4.382078 -4.333350 -0.433546 -v -0.001557 -0.042717 0.086950 -vn -0.635157 -6.205181 -0.263090 -v -0.000804 -0.043010 0.086720 -vn -0.650183 -6.214003 -0.068375 -v -0.000850 -0.043010 0.086950 -vn -2.039491 -5.860668 -0.206532 -v -0.001233 -0.042934 0.086950 -vn -4.229929 -0.631583 -4.307548 -v -0.001381 -0.042010 0.085819 -vn -3.886576 -2.219088 -3.886609 -v -0.001328 -0.042393 0.085872 -vn -3.047762 -4.168047 -3.047777 -v -0.001174 -0.042717 0.086026 -vn -1.733932 -5.567155 -1.733924 -v -0.000945 -0.042934 0.086255 -vn -0.486121 -6.205182 -0.486128 -v -0.000674 -0.043010 0.086526 -vn -2.331192 -0.563825 -5.559227 -v -0.000862 -0.042010 0.085472 -vn -2.103409 -2.219063 -5.078074 -v -0.000833 -0.042393 0.085542 -vn -1.649460 -4.168036 -3.982113 -v -0.000750 -0.042717 0.085742 -vn -0.938395 -5.567150 -2.265482 -v -0.000626 -0.042934 0.086042 -vn -0.263073 -6.205186 -0.635145 -v -0.000480 -0.043010 0.086396 -vn -0.291683 -3.333947 -3.114238 -v -0.000250 -0.041410 0.085350 -vn -2.370735 -3.426959 -2.848764 -v 0.009188 -0.041410 0.079350 -vn -0.042635 -6.169054 -0.837409 -v 0.001325 -0.041410 0.079350 -vn -0.716656 -6.161917 -0.478856 -v -0.000899 -0.041410 0.080539 -vn -0.609460 -6.161920 -0.609463 -v -0.000567 -0.041410 0.080133 -vn -2.891037 -3.508435 -1.085077 -v 0.008849 -0.041410 0.079896 -vn -0.796300 -6.161920 -0.329838 -v -0.001146 -0.041410 0.081001 -vn -0.845347 -6.161920 -0.168152 -v -0.001299 -0.041410 0.081503 -vn -1.089783 -3.549220 -2.880708 -v -0.000804 -0.041410 0.085449 -vn -2.722083 -3.384106 -2.464855 -v -0.001350 -0.041410 0.085788 -vn -0.837524 -6.169024 -0.042445 -v -0.001350 -0.041410 0.082025 -vn -0.478863 -6.161915 -0.716663 -v -0.000161 -0.041410 0.079801 -vn -0.329839 -6.161917 -0.796312 -v 0.000301 -0.041410 0.079554 -vn -0.168156 -6.161914 -0.845367 -v 0.000803 -0.041410 0.079401 -vn 3.117129 -3.318310 0.276144 -v 0.038350 -0.041410 0.102650 -vn 2.871075 -5.058382 1.189235 -v 0.037766 -0.042876 0.103071 -vn 4.695027 -2.830158 1.944738 -v 0.038104 -0.042510 0.103211 -vn 5.511140 -0.793878 2.295191 -v 0.038228 -0.042010 0.103262 -vn 4.197998 -0.767699 4.237400 -v 0.037881 -0.042010 0.103781 -vn 3.593407 -2.830149 3.593413 -v 0.037787 -0.042510 0.103687 -vn 2.300696 -0.832449 5.508872 -v 0.037362 -0.042010 0.104128 -vn 1.944738 -2.830154 4.695033 -v 0.037311 -0.042510 0.104004 -vn 0.505419 -2.932359 5.168921 -v 0.036750 -0.042510 0.104116 -vn 2.197424 -5.058370 2.197424 -v 0.037528 -0.042876 0.103428 -vn 1.189221 -5.058374 2.871081 -v 0.037171 -0.042876 0.103666 -vn 0.309064 -5.157185 3.071090 -v 0.036750 -0.042876 0.103750 -vn 0.840765 -6.145173 0.348253 -v 0.037304 -0.043010 0.102880 -vn 0.643497 -6.145172 0.643492 -v 0.037174 -0.043010 0.103074 -vn 0.348252 -6.145173 0.840765 -v 0.036980 -0.043010 0.103204 -vn 0.090509 -6.160655 0.861576 -v 0.036750 -0.043010 0.103250 -vn -0.090508 -6.160658 0.861575 -v 0.031650 -0.043010 0.103250 -vn -0.309068 -5.157180 3.071093 -v 0.031650 -0.042876 0.103750 -vn -1.189222 -5.058369 2.871086 -v 0.031229 -0.042876 0.103666 -vn -0.505426 -2.932358 5.168919 -v 0.031650 -0.042510 0.104116 -vn -1.944729 -2.830157 4.695038 -v 0.031089 -0.042510 0.104004 -vn -2.270389 -0.863560 5.529525 -v 0.031038 -0.042010 0.104128 -vn -4.260364 -0.817394 4.182774 -v 0.030519 -0.042010 0.103781 -vn -3.593404 -2.830150 3.593413 -v 0.030613 -0.042510 0.103687 -vn -5.497595 -0.749651 2.305655 -v 0.030172 -0.042010 0.103262 -vn -4.695026 -2.830157 1.944739 -v 0.030296 -0.042510 0.103211 -vn -2.197420 -5.058377 2.197424 -v 0.030872 -0.042876 0.103428 -vn -2.871074 -5.058381 1.189238 -v 0.030634 -0.042876 0.103071 -vn -0.348255 -6.145173 0.840763 -v 0.031420 -0.043010 0.103204 -vn -0.643494 -6.145173 0.643491 -v 0.031226 -0.043010 0.103074 -vn -0.840766 -6.145172 0.348256 -v 0.031096 -0.043010 0.102880 -vn -3.114238 -3.333948 0.291684 -v 0.030050 -0.041410 0.102650 -vn -2.462073 -3.385161 2.717698 -v 0.030488 -0.041410 0.103750 -vn 2.370151 -3.427202 2.847826 -v 0.016612 -0.041410 0.103750 -vn -2.880704 -3.549206 1.089797 -v 0.030149 -0.041410 0.103204 -vn 3.117129 -3.318310 0.276144 -v 0.017050 -0.041410 0.102650 -vn 2.891032 -3.508439 1.085090 -v 0.016951 -0.041410 0.103204 -vn 2.871075 -5.058378 1.189234 -v 0.016466 -0.042876 0.103071 -vn 4.695024 -2.830154 1.944735 -v 0.016804 -0.042510 0.103211 -vn 5.511137 -0.793871 2.295186 -v 0.016928 -0.042010 0.103262 -vn 4.197998 -0.767699 4.237403 -v 0.016581 -0.042010 0.103781 -vn 3.593401 -2.830153 3.593420 -v 0.016487 -0.042510 0.103687 -vn 2.300696 -0.832452 5.508867 -v 0.016062 -0.042010 0.104128 -vn 1.944732 -2.830161 4.695039 -v 0.016011 -0.042510 0.104004 -vn 0.505420 -2.932358 5.168921 -v 0.015450 -0.042510 0.104116 -vn 2.197420 -5.058371 2.197428 -v 0.016228 -0.042876 0.103428 -vn 1.189228 -5.058369 2.871083 -v 0.015871 -0.042876 0.103666 -vn 0.309062 -5.157185 3.071090 -v 0.015450 -0.042876 0.103750 -vn 0.840759 -6.145174 0.348258 -v 0.016004 -0.043010 0.102880 -vn 0.643493 -6.145173 0.643489 -v 0.015874 -0.043010 0.103074 -vn 0.348257 -6.145172 0.840766 -v 0.015680 -0.043010 0.103204 -vn 0.090508 -6.160656 0.861576 -v 0.015450 -0.043010 0.103250 -vn -0.090507 -6.160654 0.861575 -v 0.010350 -0.043010 0.103250 -vn -0.309068 -5.157180 3.071093 -v 0.010350 -0.042876 0.103750 -vn -1.189221 -5.058369 2.871087 -v 0.009929 -0.042876 0.103666 -vn -0.505426 -2.932358 5.168919 -v 0.010350 -0.042510 0.104116 -vn -1.944729 -2.830157 4.695038 -v 0.009789 -0.042510 0.104004 -vn -2.277177 -0.871628 5.527934 -v 0.009738 -0.042010 0.104128 -vn -4.260364 -0.817394 4.182774 -v 0.009219 -0.042010 0.103781 -vn -3.593404 -2.830150 3.593413 -v 0.009313 -0.042510 0.103687 -vn -5.497595 -0.749651 2.305656 -v 0.008872 -0.042010 0.103262 -vn -4.695026 -2.830157 1.944739 -v 0.008996 -0.042510 0.103211 -vn -2.197421 -5.058377 2.197424 -v 0.009572 -0.042876 0.103428 -vn -2.871074 -5.058381 1.189238 -v 0.009334 -0.042876 0.103071 -vn -0.348256 -6.145172 0.840764 -v 0.010120 -0.043010 0.103204 -vn -0.643495 -6.145174 0.643488 -v 0.009926 -0.043010 0.103074 -vn -0.840766 -6.145172 0.348256 -v 0.009796 -0.043010 0.102880 -vn -3.114238 -3.333948 0.291684 -v 0.008750 -0.041410 0.102650 -vn -0.478848 -6.161921 0.716648 -v -0.000161 -0.041410 0.103299 -vn -0.609464 -6.161919 0.609463 -v -0.000567 -0.041410 0.102967 -vn -0.042448 -6.169028 0.837504 -v 0.001325 -0.041410 0.103750 -vn -0.168149 -6.161921 0.845344 -v 0.000803 -0.041410 0.103699 -vn -0.329834 -6.161922 0.796290 -v 0.000301 -0.041410 0.103546 -vn -0.837291 -6.169086 0.042815 -v -0.001350 -0.041410 0.101075 -vn -2.880704 -3.549207 1.089797 -v 0.008849 -0.041410 0.103204 -vn -2.463485 -3.384620 2.719873 -v 0.009188 -0.041410 0.103750 -vn -1.085092 -3.508418 2.891035 -v -0.000804 -0.041410 0.097651 -vn -2.848746 -3.426963 2.370744 -v -0.001350 -0.041410 0.097312 -vn -0.716655 -6.161919 0.478853 -v -0.000899 -0.041410 0.102561 -vn -0.796307 -6.161917 0.329846 -v -0.001146 -0.041410 0.102099 -vn -0.845350 -6.161919 0.168149 -v -0.001299 -0.041410 0.101597 -vn 0.837278 -6.169091 -0.042811 -v 0.048450 -0.041410 0.082025 -vn 0.609464 -6.161920 -0.609458 -v 0.047667 -0.041410 0.080133 -vn 0.276134 -3.318304 -3.117131 -v 0.047350 -0.041410 0.085350 -vn 1.085079 -3.508457 -2.891034 -v 0.047904 -0.041410 0.085449 -vn 2.848735 -3.426980 -2.370739 -v 0.048450 -0.041410 0.085788 -vn 0.716655 -6.161918 -0.478855 -v 0.047999 -0.041410 0.080539 -vn 0.796311 -6.161917 -0.329844 -v 0.048246 -0.041410 0.081001 -vn 0.845360 -6.161916 -0.168153 -v 0.048399 -0.041410 0.081503 -vn 0.329845 -6.161915 -0.796314 -v 0.046799 -0.041410 0.079554 -vn 0.478862 -6.161914 -0.716670 -v 0.047261 -0.041410 0.079801 -vn 0.042449 -6.169023 -0.837527 -v 0.045775 -0.041410 0.079350 -vn 0.168154 -6.161913 -0.845369 -v 0.046297 -0.041410 0.079401 -vn 2.880707 -3.549192 -1.089797 -v 0.038251 -0.041410 0.079896 -vn 2.463463 -3.384676 -2.719906 -v 0.037912 -0.041410 0.079350 -vn 1.189219 -5.058371 -2.871086 -v 0.047771 -0.042876 0.085934 -vn 1.944731 -2.830154 -4.695034 -v 0.047911 -0.042510 0.085596 -vn 2.295186 -0.793890 -5.511145 -v 0.047962 -0.042010 0.085472 -vn 4.237393 -0.767713 -4.198007 -v 0.048481 -0.042010 0.085819 -vn 3.593408 -2.830149 -3.593413 -v 0.048387 -0.042510 0.085913 -vn 5.508871 -0.832448 -2.300697 -v 0.048828 -0.042010 0.086338 -vn 4.695026 -2.830159 -1.944740 -v 0.048704 -0.042510 0.086389 -vn 6.075702 -0.824086 -0.574292 -v 0.048950 -0.042010 0.086950 -vn 5.170807 -2.932413 -0.515457 -v 0.048816 -0.042510 0.086950 -vn 2.197423 -5.058371 -2.197427 -v 0.048128 -0.042876 0.086172 -vn 2.871078 -5.058382 -1.189233 -v 0.048366 -0.042876 0.086529 -vn 3.071146 -5.159068 -0.319109 -v 0.048450 -0.042876 0.086950 -vn 0.348248 -6.145174 -0.840764 -v 0.047580 -0.043010 0.086396 -vn 0.643491 -6.145169 -0.643508 -v 0.047774 -0.043010 0.086526 -vn 0.840770 -6.145170 -0.348262 -v 0.047904 -0.043010 0.086720 -vn 0.858896 -6.161366 -0.094748 -v 0.047950 -0.043010 0.086950 -vn 0.000000 -6.283186 0.000000 -v 0.042366 -0.043010 0.094600 -vn 0.000000 -6.283185 0.000000 -v 0.033200 -0.043010 0.097666 -vn 0.000000 -6.283186 0.000000 -v 0.039300 -0.043010 0.097666 -vn 0.000000 -6.283185 0.000000 -v 0.039300 -0.043010 0.085434 -vn 0.000000 -6.283185 0.000000 -v 0.033200 -0.043010 0.085434 -vn 0.000000 -6.283184 0.000000 -v 0.042366 -0.043010 0.088500 -vn 0.000000 -6.283184 0.000000 -v 0.023550 -0.043010 0.094600 -vn 0.000000 -6.283185 0.000000 -v 0.023550 -0.043010 0.088500 -vn 0.000000 -6.283186 0.000000 -v 0.007800 -0.043010 0.085434 -vn 0.000000 -6.283186 0.000000 -v 0.013900 -0.043010 0.085434 -vn 0.000000 -6.283184 0.000000 -v 0.016966 -0.043010 0.088500 -vn 0.000000 -6.283185 0.000000 -v 0.016966 -0.043010 0.094600 -vn 0.000000 -6.283186 0.000000 -v 0.013900 -0.043010 0.097666 -vn 0.000000 -6.283187 0.000000 -v 0.007800 -0.043010 0.097666 -vn 0.000000 -6.283184 0.000000 -v 0.013900 -0.043010 0.080984 -vn 0.263091 -6.205182 0.635152 -v 0.047580 -0.043010 0.096704 -vn 0.486120 -6.205184 0.486123 -v 0.047774 -0.043010 0.096574 -vn 0.000000 -6.283184 0.000000 -v 0.046816 -0.043010 0.094600 -vn 0.635153 -6.205183 0.263088 -v 0.047904 -0.043010 0.096380 -vn 0.000000 -6.283186 0.000000 -v 0.046816 -0.043010 0.088500 -vn 0.000000 -6.283184 0.000000 -v 0.033200 -0.043010 0.080984 -vn 0.650182 -6.214003 0.068374 -v 0.047950 -0.043010 0.096150 -vn 5.250913 -3.246550 0.536375 -v 0.048816 -0.042510 0.096150 -vn 5.808803 -1.955591 0.568612 -v 0.048874 -0.042393 0.096150 -vn 5.083621 -2.198392 2.142036 -v 0.048758 -0.042393 0.096733 -vn 2.142050 -2.198384 5.083613 -v 0.047933 -0.042393 0.097558 -vn 2.331217 -0.563781 5.559210 -v 0.047962 -0.042010 0.097628 -vn 3.886598 -2.219051 3.886589 -v 0.048428 -0.042393 0.097228 -vn 4.229954 -0.631551 4.307549 -v 0.048481 -0.042010 0.097281 -vn 5.591146 -0.677724 2.295937 -v 0.048828 -0.042010 0.096762 -vn 6.131734 -0.626852 0.577046 -v 0.048950 -0.042010 0.096150 -vn 3.303888 -5.258904 0.361357 -v 0.048450 -0.042876 0.096150 -vn 4.382075 -4.333330 0.433353 -v 0.048657 -0.042717 0.096150 -vn 3.971478 -4.179674 1.721220 -v 0.048558 -0.042717 0.096650 -vn 3.047771 -4.168047 3.047759 -v 0.048274 -0.042717 0.097074 -vn 1.721222 -4.179674 3.971472 -v 0.047850 -0.042717 0.097358 -vn 2.039488 -5.860669 0.206371 -v 0.048333 -0.042934 0.096150 -vn 2.213402 -5.594192 0.985859 -v 0.048258 -0.042934 0.096526 -vn 1.733921 -5.567166 1.733910 -v 0.048045 -0.042934 0.096845 -vn 0.985859 -5.594196 2.213394 -v 0.047726 -0.042934 0.097058 -vn 0.291693 -3.333952 3.114236 -v 0.047350 -0.041410 0.097750 -vn 0.042633 -6.169058 0.837386 -v 0.045775 -0.041410 0.103750 -vn 0.716651 -6.161920 0.478852 -v 0.047999 -0.041410 0.102561 -vn 0.609466 -6.161919 0.609463 -v 0.047667 -0.041410 0.102967 -vn 2.370743 -3.426965 2.848735 -v 0.037912 -0.041410 0.103750 -vn 0.478851 -6.161920 0.716652 -v 0.047261 -0.041410 0.103299 -vn 0.329834 -6.161922 0.796295 -v 0.046799 -0.041410 0.103546 -vn 0.168153 -6.161920 0.845346 -v 0.046297 -0.041410 0.103699 -vn 0.845362 -6.161915 0.168153 -v 0.048399 -0.041410 0.101597 -vn 0.796318 -6.161914 0.329848 -v 0.048246 -0.041410 0.102099 -vn 1.089814 -3.549175 2.880703 -v 0.047904 -0.041410 0.097651 -vn 2.717695 -3.385191 2.462070 -v 0.048450 -0.041410 0.097312 -vn 0.836445 -6.169313 0.044119 -v 0.048450 -0.041410 0.101075 -vn 2.891031 -3.508446 1.085092 -v 0.038251 -0.041410 0.103204 -vn -0.300319 -0.804745 -6.137357 -v 0.001325 -0.040910 0.078850 -vn -0.003769 -0.000688 -6.283176 -v 0.010350 -0.040910 0.078850 -vn -0.255256 -2.987792 -5.221593 -v 0.001325 -0.041160 0.078917 -vn -0.126764 -0.045777 -6.278353 -v 0.010347 -0.040912 0.078850 -vn -0.505489 -0.747059 -6.189570 -v 0.010041 -0.041081 0.078880 -vn -1.858619 -2.855933 -4.463229 -v 0.009484 -0.041345 0.079105 -vn -0.151417 -5.209960 -3.056444 -v 0.001325 -0.041343 0.079100 -vn -0.844075 -1.594246 -5.833714 -v 0.009850 -0.041181 0.078930 -vn -1.321969 -2.096093 -5.309241 -v 0.009688 -0.041260 0.078993 -vn 1.823365 -2.770867 -4.454710 -v 0.016334 -0.041352 0.079116 -vn 1.314752 -2.076744 -5.336365 -v 0.016111 -0.041260 0.078993 -vn 0.715812 -1.066811 -6.075183 -v 0.015928 -0.041170 0.078923 -vn 0.162855 -0.139214 -6.272573 -v 0.015450 -0.040910 0.078850 -vn -0.002367 -0.000423 -6.283183 -v 0.031650 -0.040910 0.078850 -vn -0.118302 -0.062858 -6.278611 -v 0.031647 -0.040912 0.078850 -vn -0.503271 -0.751951 -6.188721 -v 0.031341 -0.041081 0.078880 -vn -0.844303 -1.593400 -5.834149 -v 0.031150 -0.041181 0.078930 -vn -1.318573 -2.097325 -5.308410 -v 0.030988 -0.041260 0.078993 -vn -1.848589 -2.867191 -4.448607 -v 0.030784 -0.041345 0.079105 -vn 0.873105 -1.514129 -5.846717 -v 0.037228 -0.041170 0.078923 -vn 1.315327 -2.075640 -5.337225 -v 0.037411 -0.041260 0.078993 -vn 1.823257 -2.771465 -4.453830 -v 0.037634 -0.041352 0.079116 -vn 0.479368 -0.722249 -6.193273 -v 0.037059 -0.041081 0.078880 -vn 0.103681 -0.088931 -6.278876 -v 0.036750 -0.040910 0.078850 -vn 0.136176 -5.494284 -2.746521 -v 0.045775 -0.041343 0.079100 -vn 0.303021 -0.803066 -6.137805 -v 0.045775 -0.040910 0.078850 -vn 0.271712 -2.692657 -5.493179 -v 0.045775 -0.041160 0.078917 -vn 0.228585 -4.374212 -4.397816 -v 0.045775 -0.041264 0.078996 -vn 6.137354 -0.804745 -0.300337 -v 0.048950 -0.040910 0.082025 -vn 5.221623 -2.987961 -0.255264 -v 0.048883 -0.041160 0.082025 -vn 5.088235 -2.940731 -1.012109 -v 0.048823 -0.041160 0.081419 -vn 3.056686 -5.209799 -0.151244 -v 0.048700 -0.041343 0.082025 -vn 3.018584 -5.164371 -0.600434 -v 0.048644 -0.041343 0.081454 -vn 2.843432 -5.164381 -1.177787 -v 0.048477 -0.041343 0.080906 -vn 2.559026 -5.164364 -1.709900 -v 0.048207 -0.041343 0.080400 -vn 2.176274 -5.164369 -2.176274 -v 0.047843 -0.041343 0.079957 -vn 1.709885 -5.164385 -2.559027 -v 0.047400 -0.041343 0.079593 -vn 1.177785 -5.164380 -2.843438 -v 0.046894 -0.041343 0.079323 -vn 0.638816 -5.186305 -2.992049 -v 0.046346 -0.041343 0.079156 -vn 4.792997 -2.940718 -1.985330 -v 0.048646 -0.041160 0.080836 -vn 4.313604 -2.940761 -2.882250 -v 0.048359 -0.041160 0.080298 -vn 3.668406 -2.940712 -3.668416 -v 0.047973 -0.041160 0.079827 -vn 2.882253 -2.940764 -4.313571 -v 0.047502 -0.041160 0.079441 -vn 1.985308 -2.940724 -4.793007 -v 0.046964 -0.041160 0.079154 -vn 1.050629 -2.922493 -5.101989 -v 0.046381 -0.041160 0.078977 -vn 5.981273 -0.787078 -1.189748 -v 0.048889 -0.040910 0.081406 -vn 5.634357 -0.796360 -2.333817 -v 0.048708 -0.040910 0.080810 -vn 5.070657 -0.787111 -3.388116 -v 0.048415 -0.040910 0.080261 -vn 4.312355 -0.796351 -4.312357 -v 0.048020 -0.040910 0.079780 -vn 3.388117 -0.787101 -5.070655 -v 0.047539 -0.040910 0.079385 -vn 2.333812 -0.796350 -5.634369 -v 0.046990 -0.040910 0.079092 -vn 1.189738 -0.787079 -5.981267 -v 0.046394 -0.040910 0.078911 -vn -1.012089 -2.940745 -5.088215 -v 0.000719 -0.041160 0.078977 -vn -0.600426 -5.164392 -3.018574 -v 0.000754 -0.041343 0.079156 -vn -1.177785 -5.164382 -2.843433 -v 0.000206 -0.041343 0.079323 -vn -1.709895 -5.164374 -2.559025 -v -0.000300 -0.041343 0.079593 -vn -2.176250 -5.164391 -2.176270 -v -0.000743 -0.041343 0.079957 -vn -2.559029 -5.164364 -1.709894 -v -0.001107 -0.041343 0.080400 -vn -2.843441 -5.164363 -1.177793 -v -0.001377 -0.041343 0.080906 -vn -2.992056 -5.186280 -0.638811 -v -0.001544 -0.041343 0.081454 -vn -2.746589 -5.494251 -0.136079 -v -0.001600 -0.041343 0.082025 -vn -4.397635 -4.374425 -0.228563 -v -0.001704 -0.041264 0.082025 -vn -1.985332 -2.940702 -4.793002 -v 0.000136 -0.041160 0.079154 -vn -2.882235 -2.940778 -4.313594 -v -0.000402 -0.041160 0.079441 -vn -3.668408 -2.940721 -3.668399 -v -0.000873 -0.041160 0.079827 -vn -4.313601 -2.940754 -2.882253 -v -0.001259 -0.041160 0.080298 -vn -4.793019 -2.940714 -1.985333 -v -0.001546 -0.041160 0.080836 -vn -5.102002 -2.922484 -1.050642 -v -0.001723 -0.041160 0.081419 -vn -5.492752 -2.694170 -0.274212 -v -0.001783 -0.041160 0.082025 -vn -1.189766 -0.794833 -5.981390 -v 0.000706 -0.040910 0.078911 -vn -2.333824 -0.796343 -5.634369 -v 0.000110 -0.040910 0.079092 -vn -3.388160 -0.794880 -5.070767 -v -0.000439 -0.040910 0.079385 -vn -4.312368 -0.796353 -4.312344 -v -0.000920 -0.040910 0.079780 -vn -5.070755 -0.794873 -3.388185 -v -0.001315 -0.040910 0.080261 -vn -5.634368 -0.796355 -2.333813 -v -0.001608 -0.040910 0.080810 -vn -5.981389 -0.794835 -1.189775 -v -0.001789 -0.040910 0.081406 -vn -6.138216 -0.801533 -0.305360 -v -0.001850 -0.040910 0.082025 -vn -6.137368 -0.804709 0.300326 -v -0.001850 -0.040910 0.101075 -vn -6.283152 -0.002274 0.007952 -v -0.001850 -0.040910 0.096150 -vn -5.221869 -2.987933 0.255262 -v -0.001783 -0.041160 0.101075 -vn -6.277438 -0.010787 0.149100 -v -0.001850 -0.040912 0.096153 -vn -6.191865 -0.733521 0.511763 -v -0.001820 -0.041081 0.096459 -vn -4.476695 -2.845471 1.867472 -v -0.001595 -0.041345 0.097016 -vn -3.056670 -5.209825 0.151237 -v -0.001600 -0.041343 0.101075 -vn -5.833173 -1.595331 0.843649 -v -0.001770 -0.041181 0.096650 -vn -5.309985 -2.094980 1.325167 -v -0.001707 -0.041260 0.096812 -vn -5.846438 -1.514684 -0.872922 -v -0.001777 -0.041170 0.086472 -vn -5.337794 -2.074925 -1.315552 -v -0.001707 -0.041260 0.086289 -vn -4.452614 -2.772353 -1.822875 -v -0.001584 -0.041352 0.086066 -vn -6.193262 -0.722295 -0.479472 -v -0.001820 -0.041081 0.086641 -vn -6.278878 -0.088942 -0.103693 -v -0.001850 -0.040910 0.086950 -vn -5.088232 -2.940718 1.012122 -v -0.001723 -0.041160 0.101681 -vn -3.018574 -5.164371 0.600433 -v -0.001544 -0.041343 0.101646 -vn -2.843443 -5.164364 1.177802 -v -0.001377 -0.041343 0.102194 -vn -2.559020 -5.164387 1.709872 -v -0.001107 -0.041343 0.102700 -vn -2.176261 -5.164390 2.176258 -v -0.000743 -0.041343 0.103143 -vn -1.709878 -5.164380 2.559015 -v -0.000300 -0.041343 0.103507 -vn -1.177783 -5.164345 2.843455 -v 0.000206 -0.041343 0.103777 -vn -0.638813 -5.186298 2.992038 -v 0.000754 -0.041343 0.103944 -vn -0.136180 -5.494219 2.746587 -v 0.001325 -0.041343 0.104000 -vn -0.228582 -4.374266 4.397818 -v 0.001325 -0.041264 0.104104 -vn -4.793016 -2.940744 1.985332 -v -0.001546 -0.041160 0.102264 -vn -4.313592 -2.940739 2.882231 -v -0.001259 -0.041160 0.102802 -vn -3.668402 -2.940714 3.668403 -v -0.000873 -0.041160 0.103273 -vn -2.882234 -2.940705 4.313613 -v -0.000402 -0.041160 0.103659 -vn -1.985345 -2.940750 4.793028 -v 0.000136 -0.041160 0.103946 -vn -1.050634 -2.922503 5.101975 -v 0.000719 -0.041160 0.104123 -vn -0.271707 -2.692765 5.493092 -v 0.001325 -0.041160 0.104183 -vn -5.981387 -0.794840 1.189774 -v -0.001789 -0.040910 0.101694 -vn -5.634350 -0.796382 2.333825 -v -0.001608 -0.040910 0.102290 -vn -5.070784 -0.794834 3.388179 -v -0.001315 -0.040910 0.102839 -vn -4.312350 -0.796345 4.312352 -v -0.000920 -0.040910 0.103320 -vn -3.388183 -0.794832 5.070783 -v -0.000439 -0.040910 0.103715 -vn -2.333837 -0.796401 5.634337 -v 0.000110 -0.040910 0.104008 -vn -1.189768 -0.794840 5.981388 -v 0.000706 -0.040910 0.104189 -vn 0.269408 -2.690905 5.493485 -v 0.045775 -0.041160 0.104183 -vn 0.126791 -0.045777 6.278351 -v 0.036753 -0.040912 0.104250 -vn 1.848565 -2.867481 4.448247 -v 0.037616 -0.041345 0.103995 -vn 0.136266 -5.494163 2.746754 -v 0.045775 -0.041343 0.104000 -vn 0.228866 -4.374492 4.397628 -v 0.045775 -0.041264 0.104104 -vn 0.505490 -0.747121 6.189553 -v 0.037059 -0.041081 0.104220 -vn 0.843864 -1.594070 5.833819 -v 0.037250 -0.041181 0.104170 -vn 1.318658 -2.097114 5.308607 -v 0.037412 -0.041260 0.104107 -vn -1.823339 -2.770844 4.454795 -v 0.030766 -0.041352 0.103984 -vn -1.314728 -2.076710 5.336374 -v 0.030989 -0.041260 0.104107 -vn -0.715846 -1.066879 6.075155 -v 0.031172 -0.041170 0.104177 -vn 0.118329 -0.062880 6.278609 -v 0.015453 -0.040912 0.104250 -vn 0.503273 -0.752006 6.188705 -v 0.015759 -0.041081 0.104220 -vn 0.844266 -1.593253 5.834242 -v 0.015950 -0.041181 0.104170 -vn 1.318561 -2.097344 5.308416 -v 0.016112 -0.041260 0.104107 -vn 1.848595 -2.867241 4.448593 -v 0.016316 -0.041345 0.103995 -vn -0.873111 -1.514128 5.846713 -v 0.009872 -0.041170 0.104177 -vn -1.315292 -2.075610 5.337239 -v 0.009689 -0.041260 0.104107 -vn -1.823230 -2.771447 4.453916 -v 0.009466 -0.041352 0.103984 -vn -0.479418 -0.722356 6.193244 -v 0.010041 -0.041081 0.104220 -vn 6.283149 -0.002279 -0.007966 -v 0.048950 -0.040910 0.086950 -vn 6.277441 -0.010980 -0.149097 -v 0.048950 -0.040912 0.086947 -vn 6.191852 -0.733574 -0.511781 -v 0.048920 -0.041081 0.086641 -vn 4.476689 -2.845473 -1.867487 -v 0.048695 -0.041345 0.086084 -vn 5.833178 -1.595314 -0.843636 -v 0.048870 -0.041181 0.086450 -vn 5.310051 -2.094968 -1.325136 -v 0.048807 -0.041260 0.086288 -vn 4.452796 -2.772310 1.822125 -v 0.048684 -0.041352 0.097034 -vn 5.337184 -2.075756 1.314992 -v 0.048807 -0.041260 0.096811 -vn 6.075269 -1.066885 0.715929 -v 0.048877 -0.041170 0.096628 -vn 6.272572 -0.139227 0.162871 -v 0.048950 -0.040910 0.096150 -vn 6.137164 -0.805457 0.299229 -v 0.048950 -0.040910 0.101075 -vn 5.493900 -2.690179 0.268249 -v 0.048883 -0.041160 0.101075 -vn 4.397564 -4.374542 0.228854 -v 0.048804 -0.041264 0.101075 -vn 2.747690 -5.493928 0.137749 -v 0.048700 -0.041343 0.101075 -vn 0.638800 -5.186306 2.992035 -v 0.046346 -0.041343 0.103944 -vn 1.050637 -2.922493 5.101982 -v 0.046381 -0.041160 0.104123 -vn 1.177800 -5.164347 2.843449 -v 0.046894 -0.041343 0.103777 -vn 1.709866 -5.164385 2.559023 -v 0.047400 -0.041343 0.103507 -vn 2.176278 -5.164370 2.176264 -v 0.047843 -0.041343 0.103143 -vn 2.559018 -5.164390 1.709876 -v 0.048207 -0.041343 0.102700 -vn 2.843435 -5.164383 1.177795 -v 0.048477 -0.041343 0.102194 -vn 2.992063 -5.186278 0.638812 -v 0.048644 -0.041343 0.101646 -vn 1.985333 -2.940767 4.793032 -v 0.046964 -0.041160 0.103946 -vn 2.882236 -2.940706 4.313594 -v 0.047502 -0.041160 0.103659 -vn 3.668419 -2.940702 3.668406 -v 0.047973 -0.041160 0.103273 -vn 4.313589 -2.940735 2.882242 -v 0.048359 -0.041160 0.102802 -vn 4.792995 -2.940752 1.985328 -v 0.048646 -0.041160 0.102264 -vn 5.102005 -2.922488 1.050633 -v 0.048823 -0.041160 0.101681 -vn 1.189751 -0.787084 5.981263 -v 0.046394 -0.040910 0.104189 -vn 2.333818 -0.796409 5.634339 -v 0.046990 -0.040910 0.104008 -vn 3.388135 -0.787043 5.070680 -v 0.047539 -0.040910 0.103715 -vn 4.312354 -0.796345 4.312348 -v 0.048020 -0.040910 0.103320 -vn 5.070674 -0.787079 3.388122 -v 0.048415 -0.040910 0.102839 -vn 5.634342 -0.796381 2.333828 -v 0.048708 -0.040910 0.102290 -vn 5.981272 -0.787081 1.189746 -v 0.048889 -0.040910 0.101694 -vn 1.182081 2.807313 2.853790 -v 0.046990 -0.038080 0.104008 -vn 2.184198 2.807317 2.184198 -v 0.048020 -0.038080 0.103320 -vn 2.853791 2.807312 1.182081 -v 0.048708 -0.038080 0.102290 -vn 3.115258 2.974453 0.285578 -v 0.048950 -0.038080 0.101075 -vn 3.115257 2.974453 -0.285578 -v 0.048950 -0.038080 0.082025 -vn -5.823096 -0.785411 1.110735 -v -0.001850 -0.032080 0.089625 -vn -5.823123 -0.785386 -1.110707 -v -0.001850 -0.032080 0.093475 -vn -6.063419 0.675498 -0.675498 -v -0.001850 -0.034030 0.093475 -vn -6.063411 0.675515 0.675507 -v -0.001850 -0.034030 0.089625 -vn 2.853791 2.807314 -1.182079 -v 0.048708 -0.038080 0.080810 -vn 2.184199 2.807323 -2.184198 -v 0.048020 -0.038080 0.079780 -vn 1.182079 2.807316 -2.853791 -v 0.046990 -0.038080 0.079092 -vn 0.285576 2.974456 -3.115258 -v 0.045775 -0.038080 0.078850 -vn -1.570796 1.570796 -4.712389 -v 0.035650 -0.034980 0.078850 -vn 1.570796 1.570796 -4.712389 -v 0.022850 -0.034980 0.078850 -vn 0.000000 0.000001 -6.283185 -v 0.043950 -0.038080 0.078850 -vn -0.306447 3.337942 3.111411 -v 0.001575 -0.013290 0.104000 -vn 0.306446 3.337948 3.111417 -v 0.045525 -0.013290 0.104000 -vn 1.179135 3.534294 2.846682 -v 0.046740 -0.013290 0.103758 -vn 2.178758 3.534289 2.178757 -v 0.047770 -0.013290 0.103070 -vn 2.846682 3.534295 1.179135 -v 0.048458 -0.013290 0.102040 -vn 3.111410 3.337941 0.306445 -v 0.048700 -0.013290 0.100825 -vn 3.111408 3.337941 -0.306447 -v 0.048700 -0.013290 0.082275 -vn 2.846682 3.534293 -1.179137 -v 0.048458 -0.013290 0.081060 -vn 2.178757 3.534289 -2.178758 -v 0.047770 -0.013290 0.080030 -vn 1.179135 3.534294 -2.846682 -v 0.046740 -0.013290 0.079342 -vn 0.306446 3.337941 -3.111410 -v 0.045525 -0.013290 0.079100 -vn -0.306447 3.337949 -3.111416 -v 0.001575 -0.013290 0.079100 -vn -1.179134 3.534292 -2.846684 -v 0.000360 -0.013290 0.079342 -vn -2.178758 3.534293 -2.178756 -v -0.000670 -0.013290 0.080030 -vn -2.846684 3.534291 -1.179133 -v -0.001358 -0.013290 0.081060 -vn -3.111411 3.337943 -0.306447 -v -0.001600 -0.013290 0.082275 -vn -3.111409 3.337940 0.306445 -v -0.001600 -0.013290 0.100825 -vn -2.846684 3.534292 1.179132 -v -0.001358 -0.013290 0.102040 -vn -2.178758 3.534293 2.178756 -v -0.000670 -0.013290 0.103070 -vn -1.179135 3.534292 2.846684 -v 0.000360 -0.013290 0.103758 -vn -0.306447 -3.337942 -3.111411 -v 0.001575 -0.013040 0.079100 -vn -0.296545 -2.960106 -3.113305 -v 0.001325 -0.013040 0.078850 -vn 0.306446 -3.337948 -3.111417 -v 0.045525 -0.013040 0.079100 -vn 0.296544 -2.960099 -3.113306 -v 0.045775 -0.013040 0.078850 -vn 1.179136 -3.534294 -2.846682 -v 0.046740 -0.013040 0.079342 -vn 1.180585 -2.778604 -2.850183 -v 0.046990 -0.013040 0.079092 -vn 2.178758 -3.534289 -2.178757 -v 0.047770 -0.013040 0.080030 -vn 2.181438 -2.778610 -2.181437 -v 0.048020 -0.013040 0.079780 -vn 2.846682 -3.534294 -1.179136 -v 0.048458 -0.013040 0.081060 -vn 2.850183 -2.778604 -1.180586 -v 0.048708 -0.013040 0.080810 -vn 3.111411 -3.337943 -0.306447 -v 0.048700 -0.013040 0.082275 -vn 3.113305 -2.960098 -0.296545 -v 0.048950 -0.013040 0.082025 -vn 3.111409 -3.337940 0.306445 -v 0.048700 -0.013040 0.100825 -vn 3.113306 -2.960098 0.296545 -v 0.048950 -0.013040 0.101075 -vn 2.846682 -3.534295 1.179135 -v 0.048458 -0.013040 0.102040 -vn 2.850183 -2.778602 1.180586 -v 0.048708 -0.013040 0.102290 -vn 2.178757 -3.534289 2.178758 -v 0.047770 -0.013040 0.103070 -vn 2.181437 -2.778607 2.181437 -v 0.048020 -0.013040 0.103320 -vn 1.179135 -3.534294 2.846682 -v 0.046740 -0.013040 0.103758 -vn 1.180586 -2.778603 2.850183 -v 0.046990 -0.013040 0.104008 -vn 0.306446 -3.337941 3.111410 -v 0.045525 -0.013040 0.104000 -vn 0.296544 -2.960107 3.113306 -v 0.045775 -0.013040 0.104250 -vn -0.306447 -3.337949 3.111416 -v 0.001575 -0.013040 0.104000 -vn -0.296545 -2.960099 3.113305 -v 0.001325 -0.013040 0.104250 -vn -1.179134 -3.534292 2.846684 -v 0.000360 -0.013040 0.103758 -vn -1.180585 -2.778605 2.850185 -v 0.000110 -0.013040 0.104008 -vn -2.178758 -3.534293 2.178756 -v -0.000670 -0.013040 0.103070 -vn -2.181437 -2.778603 2.181435 -v -0.000920 -0.013040 0.103320 -vn -2.846684 -3.534292 1.179131 -v -0.001358 -0.013040 0.102040 -vn -2.850184 -2.778606 1.180583 -v -0.001608 -0.013040 0.102290 -vn -3.111410 -3.337941 0.306445 -v -0.001600 -0.013040 0.100825 -vn -3.113305 -2.960098 0.296545 -v -0.001850 -0.013040 0.101075 -vn -3.111408 -3.337941 -0.306447 -v -0.001600 -0.013040 0.082275 -vn -3.113305 -2.960099 -0.296545 -v -0.001850 -0.013040 0.082025 -vn -2.846685 -3.534291 -1.179133 -v -0.001358 -0.013040 0.081060 -vn -2.850185 -2.778607 -1.180583 -v -0.001608 -0.013040 0.080810 -vn -2.178758 -3.534293 -2.178756 -v -0.000670 -0.013040 0.080030 -vn -2.181438 -2.778606 -2.181436 -v -0.000920 -0.013040 0.079780 -vn -1.179135 -3.534292 -2.846684 -v 0.000360 -0.013040 0.079342 -vn -1.180584 -2.778607 -2.850185 -v 0.000110 -0.013040 0.079092 -vn 1.517280 2.617990 2.627988 -v 0.010050 -0.011260 0.090164 -vn 2.627998 2.618001 1.517270 -v 0.009464 -0.011260 0.090750 -vn 3.034544 2.617990 -0.000000 -v 0.009250 -0.011260 0.091550 -vn 1.517273 2.617997 -2.627995 -v 0.010050 -0.011260 0.092936 -vn 2.627991 2.617994 -1.517278 -v 0.009464 -0.011260 0.092350 -vn 1.517280 3.665195 2.627988 -v 0.010050 -0.008910 0.090164 -vn 2.627998 3.665185 1.517270 -v 0.009464 -0.008910 0.090750 -vn 3.034544 3.665196 0.000000 -v 0.009250 -0.008910 0.091550 -vn 2.627991 3.665191 -1.517277 -v 0.009464 -0.008910 0.092350 -vn 1.517273 3.665188 -2.627995 -v 0.010050 -0.008910 0.092936 -vn 1.517264 2.618003 2.628003 -v 0.026250 -0.012860 0.081147 -vn 1.517274 2.617995 -2.627993 -v 0.026250 -0.012860 0.083053 -vn 3.034548 2.618001 -0.000000 -v 0.025700 -0.012860 0.082100 -vn 2.627995 2.617990 -1.517268 -v 0.025847 -0.012860 0.082650 -vn 2.627985 2.617981 1.517278 -v 0.025847 -0.012860 0.081550 -vn 2.627996 2.617997 -1.517270 -v 0.019347 -0.012860 0.082650 -vn 1.517276 2.617992 -2.627991 -v 0.019750 -0.012860 0.083053 -vn 3.034546 2.617994 0.000000 -v 0.019200 -0.012860 0.082100 -vn 2.627986 2.617987 1.517280 -v 0.019347 -0.012860 0.081550 -vn 1.517266 2.618001 2.628000 -v 0.019750 -0.012860 0.081147 -vn 3.034546 2.617993 0.000000 -v 0.000300 -0.012860 0.082100 -vn 2.627999 2.617998 -1.517267 -v 0.000447 -0.012860 0.082650 -vn 1.517278 2.617989 -2.627988 -v 0.000850 -0.012860 0.083053 -vn 1.517268 2.617999 2.627999 -v 0.000850 -0.012860 0.081147 -vn 2.627989 2.617989 1.517278 -v 0.000447 -0.012860 0.081550 -vn 3.034544 2.617991 0.000005 -v 0.000300 -0.012860 0.101000 -vn 2.627999 2.617999 -1.517267 -v 0.000447 -0.012860 0.101550 -vn 1.517278 2.617989 -2.627988 -v 0.000850 -0.012860 0.101953 -vn 1.517278 2.617989 2.627988 -v 0.000850 -0.012860 0.100047 -vn 2.627997 2.618002 1.517272 -v 0.000447 -0.012860 0.100450 -vn 1.517274 2.617994 2.627993 -v 0.026250 -0.012860 0.100047 -vn 2.627993 2.617994 1.517273 -v 0.025847 -0.012860 0.100450 -vn 3.034547 2.617997 0.000005 -v 0.025700 -0.012860 0.101000 -vn 1.517274 2.617995 -2.627993 -v 0.026250 -0.012860 0.101953 -vn 2.627995 2.617991 -1.517268 -v 0.025847 -0.012860 0.101550 -vn 1.517276 2.617992 -2.627991 -v 0.019750 -0.012860 0.101953 -vn 1.517276 2.617992 2.627990 -v 0.019750 -0.012860 0.100047 -vn 2.627995 2.618000 1.517275 -v 0.019347 -0.012860 0.100450 -vn 2.627996 2.617996 -1.517270 -v 0.019347 -0.012860 0.101550 -vn 3.034544 2.617991 0.000005 -v 0.019200 -0.012860 0.101000 -vn 2.627995 2.618000 -1.517275 -v 0.009897 -0.011260 0.100431 -vn 1.517276 2.617992 -2.627991 -v 0.010300 -0.011260 0.100834 -vn 1.517276 2.617992 2.627991 -v 0.010300 -0.011260 0.098929 -vn 2.627996 2.617996 1.517270 -v 0.009897 -0.011260 0.099331 -vn 3.034544 2.617991 -0.000005 -v 0.009750 -0.011260 0.099881 -vn 3.034546 2.617994 0.000000 -v 0.001419 -0.011260 0.091550 -vn 2.627984 2.617985 -1.517283 -v 0.001566 -0.011260 0.092100 -vn 1.517265 2.618005 -2.628003 -v 0.001969 -0.011260 0.092503 -vn 2.627994 2.617994 1.517273 -v 0.001566 -0.011260 0.091000 -vn 1.517275 2.617996 2.627993 -v 0.001969 -0.011260 0.090597 -vn 2.627996 2.617997 -1.517270 -v 0.009897 -0.011260 0.083769 -vn 1.517276 2.617992 -2.627991 -v 0.010300 -0.011260 0.084171 -vn 2.627996 2.617996 1.517270 -v 0.009897 -0.011260 0.082669 -vn 3.034546 2.617994 0.000000 -v 0.009750 -0.011260 0.083219 -vn 1.517257 2.617980 2.627995 -v 0.010300 -0.011260 0.082266 -vn 2.627986 2.617987 -1.517280 -v 0.018229 -0.011260 0.092100 -vn 1.517267 2.618001 -2.628001 -v 0.018631 -0.011260 0.092503 -vn 1.517276 2.617992 2.627991 -v 0.018631 -0.011260 0.090597 -vn 2.627996 2.617996 1.517270 -v 0.018229 -0.011260 0.091000 -vn 3.034546 2.617994 0.000000 -v 0.018081 -0.011260 0.091550 -vn 2.986035 2.692793 -0.681543 -v 0.007925 -0.008910 0.092218 -vn 2.394615 2.692795 -1.909641 -v 0.008505 -0.008910 0.093420 -vn 1.328910 2.692792 -2.759511 -v 0.009548 -0.008910 0.094253 -vn 1.328910 2.692792 2.759511 -v 0.009548 -0.008910 0.088847 -vn 2.394615 2.692795 1.909641 -v 0.008505 -0.008910 0.089680 -vn 2.986035 2.692793 0.681543 -v 0.007925 -0.008910 0.090882 -vn 1.517265 2.618005 2.628003 -v 0.045150 -0.012860 0.081147 -vn 1.517275 2.617995 -2.627993 -v 0.045150 -0.012860 0.083053 -vn 3.034546 2.617994 0.000000 -v 0.044600 -0.012860 0.082100 -vn 2.627994 2.617994 -1.517273 -v 0.044747 -0.012860 0.082650 -vn 2.627983 2.617985 1.517283 -v 0.044747 -0.012860 0.081550 -vn 1.517275 2.617995 -2.627993 -v 0.045150 -0.012860 0.101953 -vn 1.517275 2.617995 2.627993 -v 0.045150 -0.012860 0.100047 -vn 3.034544 2.617991 0.000005 -v 0.044600 -0.012860 0.101000 -vn 2.627994 2.617994 -1.517273 -v 0.044747 -0.012860 0.101550 -vn 2.627992 2.617997 1.517277 -v 0.044747 -0.012860 0.100450 -vn 1.517263 3.665182 2.628003 -v 0.026250 -0.009110 0.081147 -vn 2.627985 3.665204 1.517278 -v 0.025847 -0.009110 0.081550 -vn 3.034548 3.665185 0.000000 -v 0.025700 -0.009110 0.082100 -vn 2.627995 3.665195 -1.517267 -v 0.025847 -0.009110 0.082650 -vn 1.517274 3.665191 -2.627993 -v 0.026250 -0.009110 0.083053 -vn 1.517266 3.665184 2.628001 -v 0.019750 -0.009110 0.081147 -vn 2.627986 3.665199 1.517280 -v 0.019347 -0.009110 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.019200 -0.009110 0.082100 -vn 2.627996 3.665189 -1.517270 -v 0.019347 -0.009110 0.082650 -vn 1.517276 3.665193 -2.627990 -v 0.019750 -0.009110 0.083053 -vn 1.517268 3.665187 2.627999 -v 0.000850 -0.009110 0.081147 -vn 2.627989 3.665196 1.517278 -v 0.000447 -0.009110 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.000300 -0.009110 0.082100 -vn 2.627999 3.665187 -1.517267 -v 0.000447 -0.009110 0.082650 -vn 1.517278 3.665196 -2.627988 -v 0.000850 -0.009110 0.083053 -vn 1.517278 3.665196 2.627988 -v 0.000850 -0.009110 0.100047 -vn 2.627997 3.665184 1.517273 -v 0.000447 -0.009110 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.000300 -0.009110 0.101000 -vn 2.627999 3.665187 -1.517267 -v 0.000447 -0.009110 0.101550 -vn 1.517278 3.665196 -2.627988 -v 0.000850 -0.009110 0.101953 -vn 1.517274 3.665191 2.627993 -v 0.026250 -0.009110 0.100047 -vn 2.627994 3.665191 1.517273 -v 0.025847 -0.009110 0.100450 -vn 3.034547 3.665188 0.000005 -v 0.025700 -0.009110 0.101000 -vn 2.627995 3.665195 -1.517267 -v 0.025847 -0.009110 0.101550 -vn 1.517274 3.665191 -2.627993 -v 0.026250 -0.009110 0.101953 -vn 1.517276 3.665193 2.627991 -v 0.019750 -0.009110 0.100047 -vn 2.627995 3.665186 1.517275 -v 0.019347 -0.009110 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.019200 -0.009110 0.101000 -vn 2.627996 3.665189 -1.517270 -v 0.019347 -0.009110 0.101550 -vn 1.517276 3.665193 -2.627990 -v 0.019750 -0.009110 0.101953 -vn 1.517276 3.665193 2.627991 -v 0.010300 -0.007510 0.098929 -vn 2.627996 3.665189 1.517270 -v 0.009897 -0.007510 0.099331 -vn 3.034544 3.665195 -0.000005 -v 0.009750 -0.007510 0.099881 -vn 2.627995 3.665186 -1.517275 -v 0.009897 -0.007510 0.100431 -vn 1.517276 3.665193 -2.627991 -v 0.010300 -0.007510 0.100834 -vn 1.517275 3.665190 2.627993 -v 0.001969 -0.007510 0.090597 -vn 2.627994 3.665192 1.517273 -v 0.001566 -0.007510 0.091000 -vn 3.034546 3.665191 0.000000 -v 0.001419 -0.007510 0.091550 -vn 2.627983 3.665201 -1.517283 -v 0.001566 -0.007510 0.092100 -vn 1.517265 3.665181 -2.628003 -v 0.001969 -0.007510 0.092503 -vn 1.517257 3.665205 2.627996 -v 0.010300 -0.007510 0.082266 -vn 2.627996 3.665189 1.517270 -v 0.009897 -0.007510 0.082669 -vn 3.034546 3.665191 0.000000 -v 0.009750 -0.007510 0.083219 -vn 2.627996 3.665189 -1.517270 -v 0.009897 -0.007510 0.083769 -vn 1.517276 3.665193 -2.627991 -v 0.010300 -0.007510 0.084171 -vn 1.517276 3.665193 2.627991 -v 0.018631 -0.007510 0.090597 -vn 2.627996 3.665189 1.517270 -v 0.018229 -0.007510 0.091000 -vn 3.034546 3.665191 0.000000 -v 0.018081 -0.007510 0.091550 -vn 2.627986 3.665198 -1.517280 -v 0.018229 -0.007510 0.092100 -vn 1.517266 3.665184 -2.628001 -v 0.018631 -0.007510 0.092503 -vn 1.328910 -2.692791 2.759511 -v 0.009548 -0.005910 0.088847 -vn 2.394615 -2.692795 1.909641 -v 0.008505 -0.005910 0.089680 -vn 2.986035 -2.692794 0.681543 -v 0.007925 -0.005910 0.090882 -vn 2.986035 -2.692793 -0.681543 -v 0.007925 -0.005910 0.092218 -vn 2.394615 -2.692795 -1.909641 -v 0.008505 -0.005910 0.093420 -vn 1.328910 -2.692792 -2.759511 -v 0.009548 -0.005910 0.094253 -vn 1.517265 3.665181 2.628003 -v 0.045150 -0.009110 0.081147 -vn 2.627984 3.665201 1.517283 -v 0.044747 -0.009110 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.044600 -0.009110 0.082100 -vn 2.627993 3.665191 -1.517272 -v 0.044747 -0.009110 0.082650 -vn 1.517275 3.665190 -2.627993 -v 0.045150 -0.009110 0.083053 -vn 1.517275 3.665190 2.627993 -v 0.045150 -0.009110 0.100047 -vn 2.627992 3.665188 1.517278 -v 0.044747 -0.009110 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.044600 -0.009110 0.101000 -vn 2.627993 3.665191 -1.517272 -v 0.044747 -0.009110 0.101550 -vn 1.517275 3.665190 -2.627993 -v 0.045150 -0.009110 0.101953 -vn 1.517275 2.617990 2.627990 -v 0.025925 -0.009110 0.080584 -vn 2.627996 2.617997 1.517270 -v 0.025284 -0.009110 0.081225 -vn 3.034546 2.617995 0.000003 -v 0.025050 -0.009110 0.082100 -vn 2.627991 2.617989 -1.517273 -v 0.025284 -0.009110 0.082975 -vn 1.517268 2.617996 -2.627997 -v 0.025925 -0.009110 0.083616 -vn 1.517275 2.617990 2.627990 -v 0.019425 -0.009110 0.080584 -vn 2.627996 2.617997 1.517270 -v 0.018784 -0.009110 0.081225 -vn 3.034546 2.617995 0.000003 -v 0.018550 -0.009110 0.082100 -vn 2.627991 2.617990 -1.517273 -v 0.018784 -0.009110 0.082975 -vn 1.517268 2.617996 -2.627997 -v 0.019425 -0.009110 0.083616 -vn 1.517268 2.617996 -2.627997 -v 0.000525 -0.009110 0.083616 -vn 1.517275 2.617990 2.627990 -v 0.000525 -0.009110 0.080584 -vn 2.627997 2.617997 1.517270 -v -0.000116 -0.009110 0.081225 -vn 3.034546 2.617995 0.000003 -v -0.000350 -0.009110 0.082100 -vn 2.627991 2.617989 -1.517273 -v -0.000116 -0.009110 0.082975 -vn 1.517268 2.617996 -2.627997 -v 0.000525 -0.009110 0.102516 -vn 1.517275 2.617990 2.627990 -v 0.000525 -0.009110 0.099484 -vn 2.627997 2.617997 1.517270 -v -0.000116 -0.009110 0.100125 -vn 3.034546 2.617995 0.000003 -v -0.000350 -0.009110 0.101000 -vn 2.627991 2.617989 -1.517273 -v -0.000116 -0.009110 0.101875 -vn 1.517275 2.617990 2.627990 -v 0.025925 -0.009110 0.099484 -vn 2.627996 2.617997 1.517270 -v 0.025284 -0.009110 0.100125 -vn 3.034546 2.617995 0.000003 -v 0.025050 -0.009110 0.101000 -vn 2.627991 2.617989 -1.517273 -v 0.025284 -0.009110 0.101875 -vn 1.517268 2.617996 -2.627997 -v 0.025925 -0.009110 0.102516 -vn 1.517275 2.617990 2.627990 -v 0.019425 -0.009110 0.099484 -vn 2.627996 2.617997 1.517270 -v 0.018784 -0.009110 0.100125 -vn 3.034546 2.617995 0.000003 -v 0.018550 -0.009110 0.101000 -vn 2.627991 2.617990 -1.517273 -v 0.018784 -0.009110 0.101875 -vn 1.517268 2.617996 -2.627997 -v 0.019425 -0.009110 0.102516 -vn 2.627996 2.617997 -1.517270 -v 0.009334 -0.007510 0.100756 -vn 1.517275 2.617990 -2.627991 -v 0.009975 -0.007510 0.101397 -vn 1.517280 2.618004 2.627994 -v 0.009975 -0.007510 0.098366 -vn 2.627991 2.617989 1.517273 -v 0.009334 -0.007510 0.099006 -vn 3.034546 2.617995 -0.000003 -v 0.009100 -0.007510 0.099881 -vn 1.517272 2.617993 2.627994 -v 0.001644 -0.007510 0.090034 -vn 2.627993 2.617996 1.517276 -v 0.001003 -0.007510 0.090675 -vn 3.034543 2.617988 -0.000003 -v 0.000769 -0.007510 0.091550 -vn 2.627998 2.618004 -1.517273 -v 0.001003 -0.007510 0.092425 -vn 1.517278 2.617987 -2.627987 -v 0.001644 -0.007510 0.093066 -vn 1.517275 2.617990 2.627990 -v 0.009975 -0.007510 0.081703 -vn 2.627997 2.617997 1.517270 -v 0.009334 -0.007510 0.082344 -vn 3.034546 2.617995 0.000003 -v 0.009100 -0.007510 0.083219 -vn 2.627991 2.617990 -1.517273 -v 0.009334 -0.007510 0.084094 -vn 1.517269 2.617996 -2.627997 -v 0.009975 -0.007510 0.084734 -vn 2.627996 2.617997 -1.517270 -v 0.017666 -0.007510 0.092425 -vn 1.517275 2.617990 -2.627991 -v 0.018306 -0.007510 0.093066 -vn 1.517268 2.617996 2.627997 -v 0.018306 -0.007510 0.090034 -vn 2.627991 2.617989 1.517273 -v 0.017666 -0.007510 0.090675 -vn 3.034546 2.617995 -0.000003 -v 0.017431 -0.007510 0.091550 -vn 1.517273 -3.665188 -2.627995 -v 0.010050 -0.005910 0.092936 -vn 2.627991 -3.665191 -1.517277 -v 0.009464 -0.005910 0.092350 -vn 3.034544 -3.665196 -0.000000 -v 0.009250 -0.005910 0.091550 -vn 2.627998 -3.665185 1.517270 -v 0.009464 -0.005910 0.090750 -vn 1.517280 -3.665195 2.627988 -v 0.010050 -0.005910 0.090164 -vn 1.517278 2.617988 2.627987 -v 0.044825 -0.009110 0.080584 -vn 2.627998 2.618004 1.517273 -v 0.044184 -0.009110 0.081225 -vn 3.034543 2.617987 0.000003 -v 0.043950 -0.009110 0.082100 -vn 2.627993 2.617996 -1.517276 -v 0.044184 -0.009110 0.082975 -vn 1.517272 2.617993 -2.627994 -v 0.044825 -0.009110 0.083616 -vn 1.517278 2.617987 2.627987 -v 0.044825 -0.009110 0.099484 -vn 2.627998 2.618004 1.517273 -v 0.044184 -0.009110 0.100125 -vn 3.034543 2.617987 0.000003 -v 0.043950 -0.009110 0.101000 -vn 2.627993 2.617996 -1.517276 -v 0.044184 -0.009110 0.101875 -vn 1.517272 2.617993 -2.627994 -v 0.044825 -0.009110 0.102516 -vn 1.517275 -2.617990 2.627990 -v 0.025925 -0.006910 0.080584 -vn 2.627996 -2.617997 1.517270 -v 0.025284 -0.006910 0.081225 -vn 3.034546 -2.617995 0.000003 -v 0.025050 -0.006910 0.082100 -vn 2.627991 -2.617989 -1.517273 -v 0.025284 -0.006910 0.082975 -vn 1.517268 -2.617996 -2.627997 -v 0.025925 -0.006910 0.083616 -vn 1.517275 -2.617990 2.627990 -v 0.019425 -0.006910 0.080584 -vn 2.627996 -2.617997 1.517270 -v 0.018784 -0.006910 0.081225 -vn 3.034546 -2.617995 0.000003 -v 0.018550 -0.006910 0.082100 -vn 2.627991 -2.617989 -1.517273 -v 0.018784 -0.006910 0.082975 -vn 1.517268 -2.617996 -2.627997 -v 0.019425 -0.006910 0.083616 -vn 1.517275 -2.617990 2.627990 -v 0.000525 -0.006910 0.080584 -vn 2.627996 -2.617997 1.517270 -v -0.000116 -0.006910 0.081225 -vn 3.034546 -2.617995 0.000003 -v -0.000350 -0.006910 0.082100 -vn 2.627991 -2.617989 -1.517273 -v -0.000116 -0.006910 0.082975 -vn 1.517268 -2.617996 -2.627997 -v 0.000525 -0.006910 0.083616 -vn 1.517275 -2.617990 2.627990 -v 0.000525 -0.006910 0.099484 -vn 2.627996 -2.617997 1.517270 -v -0.000116 -0.006910 0.100125 -vn 3.034546 -2.617995 0.000003 -v -0.000350 -0.006910 0.101000 -vn 2.627991 -2.617989 -1.517273 -v -0.000116 -0.006910 0.101875 -vn 1.517268 -2.617996 -2.627997 -v 0.000525 -0.006910 0.102516 -vn 1.517275 -2.617990 2.627990 -v 0.025925 -0.006910 0.099484 -vn 2.627996 -2.617997 1.517270 -v 0.025284 -0.006910 0.100125 -vn 3.034546 -2.617995 0.000003 -v 0.025050 -0.006910 0.101000 -vn 2.627991 -2.617989 -1.517273 -v 0.025284 -0.006910 0.101875 -vn 1.517268 -2.617996 -2.627997 -v 0.025925 -0.006910 0.102516 -vn 1.517275 -2.617990 2.627990 -v 0.019425 -0.006910 0.099484 -vn 2.627996 -2.617997 1.517270 -v 0.018784 -0.006910 0.100125 -vn 3.034546 -2.617995 0.000003 -v 0.018550 -0.006910 0.101000 -vn 2.627991 -2.617989 -1.517273 -v 0.018784 -0.006910 0.101875 -vn 1.517268 -2.617996 -2.627997 -v 0.019425 -0.006910 0.102516 -vn 1.517281 -2.618004 2.627994 -v 0.009975 -0.005310 0.098366 -vn 2.627991 -2.617990 1.517273 -v 0.009334 -0.005310 0.099006 -vn 3.034546 -2.617995 -0.000003 -v 0.009100 -0.005310 0.099881 -vn 2.627997 -2.617997 -1.517270 -v 0.009334 -0.005310 0.100756 -vn 1.517275 -2.617990 -2.627990 -v 0.009975 -0.005310 0.101397 -vn 1.517272 -2.617993 2.627994 -v 0.001644 -0.005310 0.090034 -vn 2.627992 -2.617996 1.517276 -v 0.001003 -0.005310 0.090675 -vn 3.034543 -2.617987 -0.000003 -v 0.000769 -0.005310 0.091550 -vn 2.627998 -2.618004 -1.517273 -v 0.001003 -0.005310 0.092425 -vn 1.517278 -2.617988 -2.627987 -v 0.001644 -0.005310 0.093066 -vn 1.517275 -2.617990 2.627991 -v 0.009975 -0.005310 0.081703 -vn 2.627996 -2.617997 1.517270 -v 0.009334 -0.005310 0.082344 -vn 3.034546 -2.617995 0.000003 -v 0.009100 -0.005310 0.083219 -vn 2.627991 -2.617989 -1.517273 -v 0.009334 -0.005310 0.084094 -vn 1.517268 -2.617996 -2.627997 -v 0.009975 -0.005310 0.084734 -vn 1.517269 -2.617996 2.627997 -v 0.018306 -0.005310 0.090034 -vn 2.627991 -2.617990 1.517273 -v 0.017666 -0.005310 0.090675 -vn 3.034546 -2.617995 -0.000003 -v 0.017431 -0.005310 0.091550 -vn 2.627997 -2.617997 -1.517270 -v 0.017666 -0.005310 0.092425 -vn 1.517275 -2.617990 -2.627990 -v 0.018306 -0.005310 0.093066 -vn 1.517280 3.665195 2.627988 -v 0.010050 -0.005410 0.090164 -vn 2.627998 3.665184 1.517270 -v 0.009464 -0.005410 0.090750 -vn 3.034544 3.665195 0.000000 -v 0.009250 -0.005410 0.091550 -vn 2.627991 3.665191 -1.517277 -v 0.009464 -0.005410 0.092350 -vn 1.517273 3.665188 -2.627995 -v 0.010050 -0.005410 0.092936 -vn 1.517278 -2.617987 2.627987 -v 0.044825 -0.006910 0.080584 -vn 2.627998 -2.618004 1.517273 -v 0.044184 -0.006910 0.081225 -vn 3.034543 -2.617987 0.000003 -v 0.043950 -0.006910 0.082100 -vn 2.627993 -2.617996 -1.517276 -v 0.044184 -0.006910 0.082975 -vn 1.517272 -2.617993 -2.627994 -v 0.044825 -0.006910 0.083616 -vn 1.517278 -2.617987 2.627987 -v 0.044825 -0.006910 0.099484 -vn 2.627998 -2.618004 1.517273 -v 0.044184 -0.006910 0.100125 -vn 3.034543 -2.617987 0.000003 -v 0.043950 -0.006910 0.101000 -vn 2.627993 -2.617996 -1.517276 -v 0.044184 -0.006910 0.101875 -vn 1.517272 -2.617993 -2.627994 -v 0.044825 -0.006910 0.102516 -vn 1.517274 -3.665191 -2.627993 -v 0.026250 -0.006910 0.083053 -vn 2.627995 -3.665195 -1.517268 -v 0.025847 -0.006910 0.082650 -vn 3.034548 -3.665185 0.000000 -v 0.025700 -0.006910 0.082100 -vn 2.627985 -3.665204 1.517278 -v 0.025847 -0.006910 0.081550 -vn 1.517264 -3.665182 2.628003 -v 0.026250 -0.006910 0.081147 -vn 2.627996 -3.665189 -1.517270 -v 0.019347 -0.006910 0.082650 -vn 3.034546 -3.665191 0.000000 -v 0.019200 -0.006910 0.082100 -vn 2.627986 -3.665198 1.517280 -v 0.019347 -0.006910 0.081550 -vn 1.517266 -3.665184 2.628001 -v 0.019750 -0.006910 0.081147 -vn 1.517277 -3.665193 -2.627991 -v 0.019750 -0.006910 0.083053 -vn 1.517267 -3.665187 2.627999 -v 0.000850 -0.006910 0.081147 -vn 1.517278 -3.665196 -2.627988 -v 0.000850 -0.006910 0.083053 -vn 2.627999 -3.665187 -1.517267 -v 0.000447 -0.006910 0.082650 -vn 3.034546 -3.665191 0.000000 -v 0.000300 -0.006910 0.082100 -vn 2.627988 -3.665196 1.517278 -v 0.000447 -0.006910 0.081550 -vn 1.517278 -3.665196 -2.627988 -v 0.000850 -0.006910 0.101953 -vn 2.627999 -3.665187 -1.517267 -v 0.000447 -0.006910 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.000300 -0.006910 0.101000 -vn 2.627997 -3.665184 1.517273 -v 0.000447 -0.006910 0.100450 -vn 1.517278 -3.665196 2.627989 -v 0.000850 -0.006910 0.100047 -vn 1.517274 -3.665191 -2.627993 -v 0.026250 -0.006910 0.101953 -vn 2.627995 -3.665195 -1.517268 -v 0.025847 -0.006910 0.101550 -vn 3.034547 -3.665188 0.000005 -v 0.025700 -0.006910 0.101000 -vn 2.627994 -3.665191 1.517273 -v 0.025847 -0.006910 0.100450 -vn 1.517274 -3.665191 2.627993 -v 0.026250 -0.006910 0.100047 -vn 1.517277 -3.665193 2.627990 -v 0.019750 -0.006910 0.100047 -vn 1.517277 -3.665193 -2.627991 -v 0.019750 -0.006910 0.101953 -vn 2.627996 -3.665189 -1.517270 -v 0.019347 -0.006910 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.019200 -0.006910 0.101000 -vn 2.627995 -3.665186 1.517275 -v 0.019347 -0.006910 0.100450 -vn 2.627995 -3.665186 -1.517275 -v 0.009897 -0.005310 0.100431 -vn 3.034544 -3.665195 -0.000005 -v 0.009750 -0.005310 0.099881 -vn 2.627996 -3.665189 1.517270 -v 0.009897 -0.005310 0.099331 -vn 1.517277 -3.665193 2.627991 -v 0.010300 -0.005310 0.098929 -vn 1.517277 -3.665193 -2.627991 -v 0.010300 -0.005310 0.100834 -vn 1.517265 -3.665181 -2.628003 -v 0.001969 -0.005310 0.092503 -vn 2.627983 -3.665201 -1.517283 -v 0.001566 -0.005310 0.092100 -vn 3.034545 -3.665191 0.000000 -v 0.001419 -0.005310 0.091550 -vn 2.627994 -3.665192 1.517273 -v 0.001566 -0.005310 0.091000 -vn 1.517275 -3.665190 2.627993 -v 0.001969 -0.005310 0.090597 -vn 1.517257 -3.665206 2.627995 -v 0.010300 -0.005310 0.082266 -vn 1.517277 -3.665193 -2.627991 -v 0.010300 -0.005310 0.084171 -vn 2.627996 -3.665189 -1.517270 -v 0.009897 -0.005310 0.083769 -vn 3.034545 -3.665191 0.000000 -v 0.009750 -0.005310 0.083219 -vn 2.627996 -3.665189 1.517270 -v 0.009897 -0.005310 0.082669 -vn 2.627986 -3.665199 -1.517280 -v 0.018229 -0.005310 0.092100 -vn 3.034545 -3.665191 0.000000 -v 0.018081 -0.005310 0.091550 -vn 2.627996 -3.665189 1.517270 -v 0.018229 -0.005310 0.091000 -vn 1.517277 -3.665193 2.627991 -v 0.018631 -0.005310 0.090597 -vn 1.517266 -3.665184 -2.628001 -v 0.018631 -0.005310 0.092503 -vn 3.046862 2.792527 0.537244 -v 0.005926 -0.005410 0.090682 -vn 3.046862 2.792527 -0.537244 -v 0.005926 -0.005410 0.092418 -vn 1.058165 2.792530 2.907283 -v 0.009140 -0.005410 0.086852 -vn 1.988694 2.792527 2.370041 -v 0.007636 -0.005410 0.087720 -vn 2.679364 2.792525 1.546934 -v 0.006520 -0.005410 0.089050 -vn 2.679364 2.792525 -1.546934 -v 0.006520 -0.005410 0.094050 -vn 1.988699 2.792531 -2.370038 -v 0.007636 -0.005410 0.095380 -vn 1.058163 2.792522 -2.907281 -v 0.009140 -0.005410 0.096248 -vn 1.328907 2.692792 2.759513 -v 0.034905 -0.011260 0.088757 -vn 2.986035 2.692794 0.681543 -v 0.033228 -0.011260 0.090860 -vn 2.986035 2.692794 -0.681543 -v 0.033228 -0.011260 0.092240 -vn 2.394613 2.692792 1.909642 -v 0.033826 -0.011260 0.089617 -vn 2.394613 2.692792 -1.909642 -v 0.033826 -0.011260 0.093483 -vn 1.328914 2.692798 -2.759511 -v 0.034905 -0.011260 0.094343 -vn 1.517275 -3.665190 -2.627993 -v 0.045150 -0.006910 0.083053 -vn 2.627994 -3.665192 -1.517273 -v 0.044747 -0.006910 0.082650 -vn 3.034546 -3.665191 0.000000 -v 0.044600 -0.006910 0.082100 -vn 2.627983 -3.665201 1.517283 -v 0.044747 -0.006910 0.081550 -vn 1.517265 -3.665181 2.628003 -v 0.045150 -0.006910 0.081147 -vn 1.517275 -3.665190 -2.627993 -v 0.045150 -0.006910 0.101953 -vn 2.627994 -3.665192 -1.517273 -v 0.044747 -0.006910 0.101550 -vn 3.034544 -3.665195 0.000005 -v 0.044600 -0.006910 0.101000 -vn 2.627992 -3.665188 1.517278 -v 0.044747 -0.006910 0.100450 -vn 1.517275 -3.665190 2.627993 -v 0.045150 -0.006910 0.100047 -vn -1.550348 2.679620 -2.617249 -v 0.029250 -0.006510 0.085136 -vn -0.406555 2.879791 -3.088068 -v 0.028450 -0.006510 0.085350 -vn -0.528764 0.931788 -6.160447 -v 0.028450 -0.005910 0.085350 -vn -1.441190 1.206158 -5.962754 -v 0.028864 -0.005910 0.085295 -vn -3.188648 0.937219 -5.280378 -v 0.029250 -0.005910 0.085136 -vn -2.627597 2.767266 -1.567259 -v 0.029836 -0.006510 0.084550 -vn -4.229434 1.206165 -4.443336 -v 0.029581 -0.005910 0.084881 -vn -6.184906 0.811083 -0.396204 -v 0.030050 -0.005910 0.083750 -vn -3.105491 2.967447 -0.329039 -v 0.030050 -0.006510 0.083750 -vn -5.972664 0.932942 -1.600349 -v 0.029995 -0.005910 0.084164 -vn -5.360511 0.823955 -3.094869 -v 0.029836 -0.005910 0.084550 -vn 0.489420 0.818798 -6.178015 -v 0.018650 -0.005910 0.085350 -vn 0.335687 2.956244 -3.104392 -v 0.018650 -0.006510 0.085350 -vn 1.517264 3.665181 2.628004 -v 0.026250 -0.006510 0.081147 -vn 2.627985 3.665204 1.517278 -v 0.025847 -0.006510 0.081550 -vn 3.034548 3.665185 -0.000000 -v 0.025700 -0.006510 0.082100 -vn 2.627995 3.665195 -1.517268 -v 0.025847 -0.006510 0.082650 -vn 1.517274 3.665191 -2.627993 -v 0.026250 -0.006510 0.083053 -vn 1.517266 3.665184 2.628001 -v 0.019750 -0.006510 0.081147 -vn 2.627986 3.665198 1.517280 -v 0.019347 -0.006510 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.019200 -0.006510 0.082100 -vn 2.627996 3.665189 -1.517270 -v 0.019347 -0.006510 0.082650 -vn 1.517276 3.665193 -2.627990 -v 0.019750 -0.006510 0.083053 -vn 1.790634 0.886059 -5.923744 -v 0.018156 -0.005910 0.085272 -vn 1.551757 2.786468 -2.642643 -v 0.017850 -0.006510 0.085136 -vn 5.454913 0.787758 -2.957120 -v 0.017264 -0.005910 0.084550 -vn 4.770804 0.928184 -3.939002 -v 0.017356 -0.005910 0.084690 -vn 2.642638 2.786456 -1.551759 -v 0.017264 -0.006510 0.084550 -vn 3.938957 0.928167 -4.770842 -v 0.017710 -0.005910 0.085044 -vn 2.919003 0.718569 -5.489408 -v 0.017850 -0.005910 0.085136 -vn 5.931569 0.927285 -1.748108 -v 0.017128 -0.005910 0.084244 -vn 3.104394 2.956253 -0.335679 -v 0.017050 -0.006510 0.083750 -vn 6.211704 0.666028 -0.439311 -v 0.017050 -0.005910 0.083750 -vn 1.517267 3.665187 2.627999 -v 0.000850 -0.006510 0.081147 -vn 2.627988 3.665196 1.517278 -v 0.000447 -0.006510 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.000300 -0.006510 0.082100 -vn 2.627999 3.665186 -1.517267 -v 0.000447 -0.006510 0.082650 -vn 1.517278 3.665195 -2.627988 -v 0.000850 -0.006510 0.083053 -vn -0.329050 2.967437 -3.105489 -v 0.003050 -0.006510 0.085350 -vn -0.396237 0.811103 -6.184902 -v 0.003050 -0.005910 0.085350 -vn -1.600381 0.932968 -5.972652 -v 0.003464 -0.005910 0.085295 -vn -1.534688 2.793292 -2.658171 -v 0.003850 -0.006510 0.085136 -vn -3.094854 0.823968 -5.360516 -v 0.003850 -0.005910 0.085136 -vn -4.372281 0.932948 -4.372294 -v 0.004181 -0.005910 0.084881 -vn -2.658170 2.793294 -1.534691 -v 0.004436 -0.006510 0.084550 -vn -6.184904 0.811094 -0.396218 -v 0.004650 -0.005910 0.083750 -vn -3.105490 2.967443 -0.329044 -v 0.004650 -0.006510 0.083750 -vn -5.972660 0.932943 -1.600365 -v 0.004595 -0.005910 0.084164 -vn -5.360511 0.823968 -3.094864 -v 0.004436 -0.005910 0.084550 -vn 1.517278 3.665196 2.627988 -v 0.000850 -0.006510 0.100047 -vn 2.627997 3.665183 1.517272 -v 0.000447 -0.006510 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.000300 -0.006510 0.101000 -vn 2.627999 3.665187 -1.517267 -v 0.000447 -0.006510 0.101550 -vn 1.517278 3.665196 -2.627988 -v 0.000850 -0.006510 0.101953 -vn -3.105490 2.967443 0.329046 -v 0.004650 -0.006510 0.099350 -vn -6.184905 0.811091 0.396221 -v 0.004650 -0.005910 0.099350 -vn -5.972655 0.932946 1.600377 -v 0.004595 -0.005910 0.098936 -vn -2.658168 2.793300 1.534696 -v 0.004436 -0.006510 0.098550 -vn -5.360497 0.823968 3.094891 -v 0.004436 -0.005910 0.098550 -vn -4.372288 0.932948 4.372288 -v 0.004181 -0.005910 0.098219 -vn -1.534698 2.793303 2.658167 -v 0.003850 -0.006510 0.097964 -vn -0.396190 0.811094 6.184905 -v 0.003050 -0.005910 0.097750 -vn -0.329040 2.967448 3.105491 -v 0.003050 -0.006510 0.097750 -vn -1.600373 0.932951 5.972654 -v 0.003464 -0.005910 0.097805 -vn -3.094892 0.823967 5.360497 -v 0.003850 -0.005910 0.097964 -vn 6.178017 0.818798 0.489397 -v 0.017050 -0.005910 0.099350 -vn 3.104393 2.956251 0.335681 -v 0.017050 -0.006510 0.099350 -vn 5.923742 0.886068 1.790628 -v 0.017128 -0.005910 0.098856 -vn 2.642637 2.786466 1.551763 -v 0.017264 -0.006510 0.098550 -vn 2.957073 0.787745 5.454939 -v 0.017850 -0.005910 0.097964 -vn 3.938940 0.928207 4.770847 -v 0.017710 -0.005910 0.098056 -vn 1.551768 2.786479 2.642638 -v 0.017850 -0.006510 0.097964 -vn 4.770827 0.928193 3.938969 -v 0.017356 -0.005910 0.098410 -vn 5.489376 0.718590 2.919055 -v 0.017264 -0.005910 0.098550 -vn 1.748153 0.927258 5.931557 -v 0.018156 -0.005910 0.097828 -vn 0.335677 2.956256 3.104394 -v 0.018650 -0.006510 0.097750 -vn 0.489385 0.818788 6.178020 -v 0.018650 -0.005910 0.097750 -vn -0.407429 0.818540 6.182955 -v 0.028450 -0.005910 0.097750 -vn -0.372532 2.941420 3.095300 -v 0.028450 -0.006510 0.097750 -vn 1.517274 3.665191 2.627993 -v 0.026250 -0.006510 0.100047 -vn 2.627994 3.665192 1.517273 -v 0.025847 -0.006510 0.100450 -vn 3.034547 3.665188 0.000005 -v 0.025700 -0.006510 0.101000 -vn 2.627995 3.665195 -1.517268 -v 0.025847 -0.006510 0.101550 -vn 1.517274 3.665190 -2.627993 -v 0.026250 -0.006510 0.101953 -vn 1.517277 3.665193 2.627991 -v 0.019750 -0.006510 0.100047 -vn 2.627995 3.665185 1.517275 -v 0.019347 -0.006510 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.019200 -0.006510 0.101000 -vn 2.627996 3.665189 -1.517270 -v 0.019347 -0.006510 0.101550 -vn 1.517276 3.665194 -2.627990 -v 0.019750 -0.006510 0.101953 -vn -3.105491 2.967446 0.329041 -v 0.030050 -0.006510 0.099350 -vn -6.182957 0.818529 0.407443 -v 0.030050 -0.005910 0.099350 -vn -5.972657 0.932942 1.600369 -v 0.029995 -0.005910 0.098936 -vn -2.604322 2.705643 1.593113 -v 0.029836 -0.006510 0.098550 -vn -5.280359 0.937204 3.188685 -v 0.029836 -0.005910 0.098550 -vn -1.491423 2.679626 2.651269 -v 0.029250 -0.006510 0.097964 -vn -4.443309 1.206168 4.229462 -v 0.029581 -0.005910 0.098219 -vn -2.978580 0.937221 5.401664 -v 0.029250 -0.005910 0.097964 -vn -1.733322 1.206176 5.884462 -v 0.028864 -0.005910 0.097805 -vn 1.517277 3.665193 2.627991 -v 0.010300 -0.004910 0.098929 -vn 2.627996 3.665189 1.517270 -v 0.009897 -0.004910 0.099331 -vn 3.034544 3.665195 -0.000005 -v 0.009750 -0.004910 0.099881 -vn 2.627995 3.665186 -1.517275 -v 0.009897 -0.004910 0.100431 -vn 1.517277 3.665193 -2.627991 -v 0.010300 -0.004910 0.100834 -vn 1.517275 3.665190 2.627993 -v 0.001969 -0.004910 0.090597 -vn 2.627994 3.665192 1.517273 -v 0.001566 -0.004910 0.091000 -vn 3.034545 3.665191 0.000000 -v 0.001419 -0.004910 0.091550 -vn 2.627983 3.665201 -1.517283 -v 0.001566 -0.004910 0.092100 -vn 1.517265 3.665181 -2.628003 -v 0.001969 -0.004910 0.092503 -vn 1.517257 3.665206 2.627996 -v 0.010300 -0.004910 0.082266 -vn 2.627996 3.665189 1.517270 -v 0.009897 -0.004910 0.082669 -vn 3.034545 3.665191 0.000000 -v 0.009750 -0.004910 0.083219 -vn 2.627996 3.665189 -1.517270 -v 0.009897 -0.004910 0.083769 -vn 1.517277 3.665193 -2.627991 -v 0.010300 -0.004910 0.084171 -vn 1.517277 3.665193 2.627991 -v 0.018631 -0.004910 0.090597 -vn 2.627996 3.665189 1.517270 -v 0.018229 -0.004910 0.091000 -vn 3.034545 3.665191 0.000000 -v 0.018081 -0.004910 0.091550 -vn 2.627986 3.665199 -1.517280 -v 0.018229 -0.004910 0.092100 -vn 1.517266 3.665184 -2.628001 -v 0.018631 -0.004910 0.092503 -vn 1.058165 3.490655 2.907283 -v 0.009140 -0.004910 0.086852 -vn 1.988694 3.490658 2.370041 -v 0.007636 -0.004910 0.087720 -vn 2.679364 3.490660 1.546934 -v 0.006520 -0.004910 0.089050 -vn 3.046862 3.490659 0.537244 -v 0.005926 -0.004910 0.090682 -vn 3.046862 3.490659 -0.537244 -v 0.005926 -0.004910 0.092418 -vn 2.679363 3.490660 -1.546934 -v 0.006520 -0.004910 0.094050 -vn 1.988699 3.490654 -2.370038 -v 0.007636 -0.004910 0.095380 -vn 1.058163 3.490663 -2.907281 -v 0.009140 -0.004910 0.096248 -vn 1.328906 3.590393 2.759513 -v 0.034905 -0.004910 0.088757 -vn 2.394613 3.590392 1.909642 -v 0.033826 -0.004910 0.089617 -vn 2.986035 3.590392 0.681543 -v 0.033228 -0.004910 0.090860 -vn 2.986035 3.590391 -0.681543 -v 0.033228 -0.004910 0.092240 -vn 2.394613 3.590390 -1.909642 -v 0.033826 -0.004910 0.093483 -vn 1.328915 3.590387 -2.759511 -v 0.034905 -0.004910 0.094343 -vn 2.078371 5.865965 0.066125 -v 0.016433 -0.004986 0.083750 -vn 0.582729 6.228157 -0.043757 -v 0.016050 -0.004910 0.083750 -vn 0.694539 6.196474 -0.208778 -v 0.016177 -0.004910 0.084553 -vn 0.058126 6.185550 -0.773545 -v 0.018650 -0.004910 0.086350 -vn 0.233044 5.316315 -2.988645 -v 0.018650 -0.005044 0.085850 -vn 0.909357 5.376651 -2.798706 -v 0.018001 -0.005044 0.085747 -vn 4.462759 4.359670 -0.164899 -v 0.016757 -0.005203 0.083750 -vn 3.177420 5.383283 -0.101724 -v 0.016550 -0.005044 0.083750 -vn 2.794653 5.385265 -0.875121 -v 0.016653 -0.005044 0.084399 -vn 0.418603 3.090509 -5.270855 -v 0.018650 -0.005410 0.085484 -vn 1.633388 3.146467 -5.027010 -v 0.018114 -0.005410 0.085399 -vn 3.117202 3.125657 -4.276866 -v 0.017631 -0.005410 0.085153 -vn 5.048378 3.128208 -1.577100 -v 0.017001 -0.005410 0.084286 -vn 4.270330 3.108629 -3.139180 -v 0.017247 -0.005410 0.084769 -vn 5.923356 1.958583 -0.359533 -v 0.016974 -0.005527 0.083750 -vn 5.251084 3.393399 -0.310837 -v 0.016916 -0.005410 0.083750 -vn 1.729699 5.376646 -2.380724 -v 0.017416 -0.005044 0.085449 -vn 2.380731 5.376639 -1.729698 -v 0.016951 -0.005044 0.084984 -vn 0.226814 6.194961 -0.698058 -v 0.017847 -0.004910 0.086223 -vn 0.431422 6.194962 -0.593801 -v 0.017122 -0.004910 0.085853 -vn 0.593798 6.194963 -0.431421 -v 0.016547 -0.004910 0.085278 -vn -0.348058 3.082922 -5.271779 -v 0.028450 -0.005410 0.085484 -vn -0.194831 5.307285 -2.997163 -v 0.028450 -0.005044 0.085850 -vn -0.049189 6.184119 -0.780176 -v 0.028450 -0.004910 0.086350 -vn -0.780177 6.184118 -0.049187 -v 0.031050 -0.004910 0.083750 -vn -2.989820 5.314515 -0.179417 -v 0.030550 -0.005044 0.083750 -vn -2.858914 5.358588 -0.766042 -v 0.030478 -0.005044 0.084294 -vn -5.276967 3.083023 -0.320800 -v 0.030184 -0.005410 0.083750 -vn -5.107409 3.131285 -1.368508 -v 0.030125 -0.005410 0.084199 -vn -4.579181 3.131282 -2.643780 -v 0.029952 -0.005410 0.084617 -vn -3.738878 3.131286 -3.738884 -v 0.029676 -0.005410 0.084976 -vn -2.643782 3.131297 -4.579175 -v 0.029317 -0.005410 0.085252 -vn -1.368535 3.131311 -5.107396 -v 0.028899 -0.005410 0.085425 -vn -2.563237 5.358583 -1.479881 -v 0.030269 -0.005044 0.084800 -vn -2.092871 5.358584 -2.092875 -v 0.029935 -0.005044 0.085235 -vn -1.479890 5.358578 -2.563241 -v 0.029500 -0.005044 0.085569 -vn -0.766050 5.358585 -2.858918 -v 0.028994 -0.005044 0.085778 -vn -0.721780 6.192102 -0.193400 -v 0.030961 -0.004910 0.084423 -vn -0.647128 6.192102 -0.373619 -v 0.030702 -0.004910 0.085050 -vn -0.528379 6.192101 -0.528381 -v 0.030288 -0.004910 0.085588 -vn -0.373622 6.192101 -0.647131 -v 0.029750 -0.004910 0.086002 -vn -0.193402 6.192101 -0.721782 -v 0.029123 -0.004910 0.086261 -vn -6.127485 0.599935 -0.599932 -v 0.030050 -0.005910 0.080450 -vn -5.808807 1.955548 -0.567556 -v 0.030126 -0.005527 0.080450 -vn -5.250904 3.246562 -0.536371 -v 0.030184 -0.005410 0.080450 -vn -4.382069 4.333333 -0.431937 -v 0.030343 -0.005203 0.080450 -vn -3.164510 5.315820 -0.209140 -v 0.030550 -0.005044 0.080450 -vn -0.800019 6.179230 0.026926 -v 0.031050 -0.004910 0.080984 -vn -2.167690 5.751719 0.197662 -v 0.030667 -0.004986 0.080450 -vn -0.650212 6.213997 -0.068377 -v 0.031050 -0.004910 0.080450 -vn 6.182958 0.818521 -0.407454 -v 0.042450 -0.005910 0.083750 -vn 6.073576 0.808002 -0.578765 -v 0.042450 -0.005910 0.080450 -vn 5.168911 2.932353 -0.505420 -v 0.042316 -0.005410 0.080450 -vn 3.071088 5.157191 -0.309068 -v 0.041950 -0.005044 0.080450 -vn 0.861581 6.160653 -0.090508 -v 0.041450 -0.004910 0.080450 -vn 0.813118 6.176135 0.000000 -v 0.041450 -0.004910 0.080984 -vn 5.271776 3.082911 -0.348061 -v 0.042316 -0.005410 0.083750 -vn 2.997153 5.307296 -0.194834 -v 0.041950 -0.005044 0.083750 -vn 0.780183 6.184117 -0.049187 -v 0.041450 -0.004910 0.083750 -vn 0.049188 6.184119 -0.780176 -v 0.044050 -0.004910 0.086350 -vn 0.194829 5.307284 -2.997162 -v 0.044050 -0.005044 0.085850 -vn 0.766051 5.358584 -2.858918 -v 0.043506 -0.005044 0.085778 -vn 0.348065 3.082931 -5.271776 -v 0.044050 -0.005410 0.085484 -vn 1.368521 3.131315 -5.107398 -v 0.043601 -0.005410 0.085425 -vn 0.407484 0.818540 -6.182952 -v 0.044050 -0.005910 0.085350 -vn 1.600375 0.932967 -5.972654 -v 0.043636 -0.005910 0.085295 -vn 3.094850 0.823979 -5.360518 -v 0.043250 -0.005910 0.085136 -vn 2.643788 3.131287 -4.579177 -v 0.043183 -0.005410 0.085252 -vn 4.443309 1.206168 -4.229462 -v 0.042919 -0.005910 0.084881 -vn 3.738872 3.131283 -3.738892 -v 0.042824 -0.005410 0.084976 -vn 5.280364 0.937219 -3.188670 -v 0.042664 -0.005910 0.084550 -vn 4.579188 3.131290 -2.643775 -v 0.042548 -0.005410 0.084617 -vn 5.972662 0.932944 -1.600358 -v 0.042505 -0.005910 0.084164 -vn 5.107415 3.131276 -1.368501 -v 0.042375 -0.005410 0.084199 -vn 1.479890 5.358578 -2.563241 -v 0.043000 -0.005044 0.085569 -vn 2.092870 5.358583 -2.092877 -v 0.042565 -0.005044 0.085235 -vn 2.563243 5.358579 -1.479881 -v 0.042231 -0.005044 0.084800 -vn 2.858908 5.358590 -0.766050 -v 0.042022 -0.005044 0.084294 -vn 0.193403 6.192101 -0.721782 -v 0.043377 -0.004910 0.086261 -vn 0.373621 6.192101 -0.647132 -v 0.042750 -0.004910 0.086002 -vn 0.528378 6.192103 -0.528378 -v 0.042212 -0.004910 0.085588 -vn 0.647128 6.192102 -0.373620 -v 0.041798 -0.004910 0.085050 -vn 0.721778 6.192102 -0.193400 -v 0.041539 -0.004910 0.084423 -vn 0.780181 6.184119 0.049189 -v 0.041450 -0.004910 0.099350 -vn 2.997157 5.307293 0.194836 -v 0.041950 -0.005044 0.099350 -vn 2.858921 5.358580 0.766046 -v 0.042022 -0.005044 0.098806 -vn 5.271773 3.082917 0.348059 -v 0.042316 -0.005410 0.099350 -vn 5.107406 3.131287 1.368518 -v 0.042375 -0.005410 0.098901 -vn 6.182959 0.818519 0.407456 -v 0.042450 -0.005910 0.099350 -vn 5.884476 1.206146 1.733312 -v 0.042505 -0.005910 0.098936 -vn 5.401660 0.937214 2.978583 -v 0.042664 -0.005910 0.098550 -vn 4.579174 3.131298 2.643781 -v 0.042548 -0.005410 0.098483 -vn 4.372268 0.932951 4.372306 -v 0.042919 -0.005910 0.098219 -vn 3.738865 3.131285 3.738898 -v 0.042824 -0.005410 0.098124 -vn 3.094896 0.823967 5.360497 -v 0.043250 -0.005910 0.097964 -vn 2.643793 3.131287 4.579174 -v 0.043183 -0.005410 0.097848 -vn 1.600374 0.932954 5.972653 -v 0.043636 -0.005910 0.097805 -vn 1.368528 3.131284 5.107408 -v 0.043601 -0.005410 0.097675 -vn 0.396194 0.811090 6.184906 -v 0.044050 -0.005910 0.097750 -vn 0.320802 3.083034 5.276964 -v 0.044050 -0.005410 0.097616 -vn 2.563231 5.358588 1.479889 -v 0.042231 -0.005044 0.098300 -vn 2.092867 5.358582 2.092884 -v 0.042565 -0.005044 0.097865 -vn 1.479889 5.358578 2.563241 -v 0.043000 -0.005044 0.097531 -vn 0.766050 5.358585 2.858918 -v 0.043506 -0.005044 0.097322 -vn 0.167575 5.312469 2.997274 -v 0.044050 -0.005044 0.097250 -vn 0.721778 6.192102 0.193398 -v 0.041539 -0.004910 0.098677 -vn 0.647131 6.192101 0.373623 -v 0.041798 -0.004910 0.098050 -vn 0.528378 6.192103 0.528379 -v 0.042212 -0.004910 0.097512 -vn 0.373622 6.192101 0.647132 -v 0.042750 -0.004910 0.097098 -vn 0.193402 6.192101 0.721782 -v 0.043377 -0.004910 0.096839 -vn 0.037951 6.186070 0.772730 -v 0.044050 -0.004910 0.096750 -vn 6.070790 0.792952 0.593297 -v 0.042450 -0.005910 0.102650 -vn 5.168914 2.932347 0.505421 -v 0.042316 -0.005410 0.102650 -vn 3.071084 5.157196 0.309063 -v 0.041950 -0.005044 0.102650 -vn 0.861583 6.160652 0.090512 -v 0.041450 -0.004910 0.102650 -vn -6.073570 0.808013 0.578778 -v 0.030050 -0.005910 0.102650 -vn -5.168921 2.932349 0.505425 -v 0.030184 -0.005410 0.102650 -vn -5.271782 3.082912 0.348058 -v 0.030184 -0.005410 0.099350 -vn -3.071091 5.157180 0.309076 -v 0.030550 -0.005044 0.102650 -vn -2.997162 5.307284 0.194830 -v 0.030550 -0.005044 0.099350 -vn -0.861577 6.160654 0.090511 -v 0.031050 -0.004910 0.102650 -vn -0.780177 6.184119 0.049188 -v 0.031050 -0.004910 0.099350 -vn -0.049188 6.184120 0.780177 -v 0.028450 -0.004910 0.096750 -vn -0.194829 5.307283 2.997161 -v 0.028450 -0.005044 0.097250 -vn -0.766051 5.358584 2.858918 -v 0.028994 -0.005044 0.097322 -vn -0.348054 3.082920 5.271781 -v 0.028450 -0.005410 0.097616 -vn -1.368534 3.131287 5.107404 -v 0.028899 -0.005410 0.097675 -vn -2.643788 3.131287 4.579177 -v 0.029317 -0.005410 0.097848 -vn -3.738882 3.131281 3.738883 -v 0.029676 -0.005410 0.098124 -vn -4.579166 3.131287 2.643791 -v 0.029952 -0.005410 0.098483 -vn -5.107406 3.131285 1.368524 -v 0.030125 -0.005410 0.098901 -vn -1.479890 5.358578 2.563241 -v 0.029500 -0.005044 0.097531 -vn -2.092866 5.358585 2.092880 -v 0.029935 -0.005044 0.097865 -vn -2.563225 5.358594 1.479885 -v 0.030269 -0.005044 0.098300 -vn -2.858922 5.358582 0.766039 -v 0.030478 -0.005044 0.098806 -vn -0.193403 6.192101 0.721782 -v 0.029123 -0.004910 0.096839 -vn -0.373621 6.192102 0.647132 -v 0.029750 -0.004910 0.097098 -vn -0.528379 6.192101 0.528382 -v 0.030288 -0.004910 0.097512 -vn -0.647132 6.192101 0.373621 -v 0.030702 -0.004910 0.098050 -vn -0.721780 6.192102 0.193400 -v 0.030961 -0.004910 0.098677 -vn 0.418598 3.090510 5.270851 -v 0.018650 -0.005410 0.097616 -vn 0.233042 5.316313 2.988649 -v 0.018650 -0.005044 0.097250 -vn 0.058126 6.185549 0.773544 -v 0.018650 -0.004910 0.096750 -vn 0.773548 6.185548 0.058125 -v 0.016050 -0.004910 0.099350 -vn 2.988650 5.316312 0.233041 -v 0.016550 -0.005044 0.099350 -vn 2.798712 5.376645 0.909363 -v 0.016653 -0.005044 0.098701 -vn 5.270855 3.090505 0.418589 -v 0.016916 -0.005410 0.099350 -vn 5.027017 3.146460 1.633388 -v 0.017001 -0.005410 0.098814 -vn 4.276873 3.125648 3.117210 -v 0.017247 -0.005410 0.098331 -vn 3.139160 3.108622 4.270353 -v 0.017631 -0.005410 0.097947 -vn 1.611272 3.116672 5.046647 -v 0.018114 -0.005410 0.097701 -vn 2.380733 5.376636 1.729705 -v 0.016951 -0.005044 0.098116 -vn 1.729702 5.376638 2.380732 -v 0.017416 -0.005044 0.097651 -vn 0.909359 5.376648 2.798708 -v 0.018001 -0.005044 0.097353 -vn 0.698057 6.194961 0.226813 -v 0.016177 -0.004910 0.098547 -vn 0.593799 6.194963 0.431420 -v 0.016547 -0.004910 0.097822 -vn 0.431423 6.194961 0.593802 -v 0.017122 -0.004910 0.097247 -vn 0.226813 6.194961 0.698058 -v 0.017847 -0.004910 0.096877 -vn 6.070783 0.792968 0.593301 -v 0.017050 -0.005910 0.102650 -vn 5.168920 2.932362 0.505417 -v 0.016916 -0.005410 0.102650 -vn 3.071093 5.157181 0.309071 -v 0.016550 -0.005044 0.102650 -vn 0.861582 6.160652 0.090515 -v 0.016050 -0.004910 0.102650 -vn -6.130261 0.615001 0.585422 -v 0.004650 -0.005910 0.102650 -vn -5.808806 1.955558 0.567561 -v 0.004726 -0.005527 0.102650 -vn -5.276962 3.083040 0.320817 -v 0.004784 -0.005410 0.099350 -vn -5.250911 3.246551 0.536377 -v 0.004784 -0.005410 0.102650 -vn -4.382068 4.333323 0.431952 -v 0.004943 -0.005203 0.102650 -vn -2.997274 5.312470 0.167574 -v 0.005150 -0.005044 0.099350 -vn -0.650212 6.213997 0.068377 -v 0.005650 -0.004910 0.102650 -vn -0.772730 6.186071 0.037951 -v 0.005650 -0.004910 0.099350 -vn -2.039410 5.860708 0.205307 -v 0.005267 -0.004986 0.102650 -vn -3.303822 5.258934 0.361354 -v 0.005150 -0.005044 0.102650 -vn -0.037950 6.186069 0.772731 -v 0.003050 -0.004910 0.096750 -vn -0.167574 5.312469 2.997274 -v 0.003050 -0.005044 0.097250 -vn -0.766047 5.358583 2.858920 -v 0.003594 -0.005044 0.097322 -vn -0.320798 3.083031 5.276965 -v 0.003050 -0.005410 0.097616 -vn -1.368526 3.131286 5.107407 -v 0.003499 -0.005410 0.097675 -vn -2.643792 3.131290 4.579174 -v 0.003917 -0.005410 0.097848 -vn -3.738874 3.131288 3.738881 -v 0.004276 -0.005410 0.098124 -vn -4.579171 3.131299 2.643785 -v 0.004552 -0.005410 0.098483 -vn -5.107398 3.131289 1.368531 -v 0.004725 -0.005410 0.098901 -vn -1.479890 5.358580 2.563241 -v 0.004100 -0.005044 0.097531 -vn -2.092866 5.358589 2.092876 -v 0.004535 -0.005044 0.097865 -vn -2.563234 5.358586 1.479887 -v 0.004869 -0.005044 0.098300 -vn -2.858912 5.358591 0.766048 -v 0.005078 -0.005044 0.098806 -vn -0.193403 6.192102 0.721781 -v 0.003723 -0.004910 0.096839 -vn -0.373623 6.192101 0.647134 -v 0.004350 -0.004910 0.097098 -vn -0.528380 6.192101 0.528382 -v 0.004888 -0.004910 0.097512 -vn -0.647133 6.192101 0.373623 -v 0.005302 -0.004910 0.098050 -vn -0.721782 6.192101 0.193402 -v 0.005561 -0.004910 0.098677 -vn -0.599941 0.599946 6.127479 -v -0.000250 -0.005910 0.097750 -vn -0.567559 1.955563 5.808805 -v -0.000250 -0.005527 0.097674 -vn -0.536371 3.246572 5.250894 -v -0.000250 -0.005410 0.097616 -vn -0.431933 4.333341 4.382069 -v -0.000250 -0.005203 0.097457 -vn -0.361354 5.258920 3.303837 -v -0.000250 -0.005044 0.097250 -vn -0.205316 5.860705 2.039411 -v -0.000250 -0.004986 0.097133 -vn -0.068378 6.213996 0.650212 -v -0.000250 -0.004910 0.096750 -vn -0.585415 0.615006 -6.130262 -v -0.000250 -0.005910 0.085350 -vn -0.553378 2.284304 -5.597794 -v -0.000250 -0.005527 0.085426 -vn -0.239765 2.850597 -5.478361 -v 0.003050 -0.005410 0.085484 -vn -0.436405 4.267051 -4.330948 -v -0.000250 -0.005203 0.085643 -vn -0.069585 4.344847 -4.468538 -v 0.003050 -0.005203 0.085643 -vn -0.227976 5.632218 -2.395091 -v -0.000250 -0.004986 0.085967 -vn -0.186244 5.557330 -2.698191 -v 0.003050 -0.005044 0.085850 -vn -0.053854 6.211941 -0.660176 -v -0.000250 -0.004910 0.086350 -vn -0.049189 6.184119 -0.780176 -v 0.003050 -0.004910 0.086350 -vn -0.721924 5.371414 -2.850580 -v 0.003594 -0.005044 0.085778 -vn -0.772731 6.186069 -0.037950 -v 0.005650 -0.004910 0.083750 -vn -2.997270 5.312472 -0.167574 -v 0.005150 -0.005044 0.083750 -vn -2.858908 5.358595 -0.766045 -v 0.005078 -0.005044 0.084294 -vn -5.276966 3.083034 -0.320820 -v 0.004784 -0.005410 0.083750 -vn -5.107399 3.131293 -1.368507 -v 0.004725 -0.005410 0.084199 -vn -4.579180 3.131295 -2.643781 -v 0.004552 -0.005410 0.084617 -vn -3.738878 3.131286 -3.738880 -v 0.004276 -0.005410 0.084976 -vn -2.643783 3.131302 -4.579173 -v 0.003917 -0.005410 0.085252 -vn -1.368527 3.131310 -5.107398 -v 0.003499 -0.005410 0.085425 -vn -2.563242 5.358574 -1.479891 -v 0.004869 -0.005044 0.084800 -vn -2.092874 5.358592 -2.092864 -v 0.004535 -0.005044 0.085235 -vn -1.479887 5.358578 -2.563244 -v 0.004100 -0.005044 0.085569 -vn -0.721781 6.192101 -0.193403 -v 0.005561 -0.004910 0.084423 -vn -0.647130 6.192101 -0.373620 -v 0.005302 -0.004910 0.085050 -vn -0.528380 6.192101 -0.528382 -v 0.004888 -0.004910 0.085588 -vn -0.373622 6.192101 -0.647134 -v 0.004350 -0.004910 0.086002 -vn -0.193402 6.192102 -0.721780 -v 0.003723 -0.004910 0.086261 -vn -6.127480 0.599946 -0.599938 -v 0.004650 -0.005910 0.080450 -vn -5.808805 1.955563 -0.567556 -v 0.004726 -0.005527 0.080450 -vn -5.250913 3.246550 -0.536375 -v 0.004784 -0.005410 0.080450 -vn -4.382067 4.333323 -0.431945 -v 0.004943 -0.005203 0.080450 -vn -3.303821 5.258935 -0.361351 -v 0.005150 -0.005044 0.080450 -vn -2.039409 5.860707 -0.205307 -v 0.005267 -0.004986 0.080450 -vn -0.650212 6.213997 -0.068377 -v 0.005650 -0.004910 0.080450 -vn 6.130268 0.614984 -0.585411 -v 0.017050 -0.005910 0.080450 -vn 5.802425 1.951506 -0.601410 -v 0.016974 -0.005527 0.080450 -vn 5.255862 3.245531 -0.517338 -v 0.016916 -0.005410 0.080450 -vn 4.367111 4.332247 -0.494464 -v 0.016757 -0.005203 0.080450 -vn 3.308765 5.260823 -0.329753 -v 0.016550 -0.005044 0.080450 -vn 2.007398 5.861628 -0.280907 -v 0.016433 -0.004986 0.080450 -vn 0.650216 6.213995 -0.068380 -v 0.016050 -0.004910 0.080450 -vn 0.585424 0.614996 6.130260 -v 0.047350 -0.005910 0.097750 -vn 0.567560 1.955559 5.808805 -v 0.047350 -0.005527 0.097674 -vn 0.536367 3.246572 5.250895 -v 0.047350 -0.005410 0.097616 -vn 0.431929 4.333342 4.382070 -v 0.047350 -0.005203 0.097457 -vn 0.068379 6.213996 0.650213 -v 0.047350 -0.004910 0.096750 -vn 0.205316 5.860706 2.039411 -v 0.047350 -0.004986 0.097133 -vn 0.361352 5.258921 3.303837 -v 0.047350 -0.005044 0.097250 -vn 0.593306 0.792967 -6.070782 -v 0.047350 -0.005910 0.085350 -vn 0.505419 2.932359 -5.168921 -v 0.047350 -0.005410 0.085484 -vn 0.309064 5.157185 -3.071090 -v 0.047350 -0.005044 0.085850 -vn 0.090509 6.160654 -0.861576 -v 0.047350 -0.004910 0.086350 -vn 1.517265 3.665181 2.628003 -v 0.045150 -0.006510 0.081147 -vn 2.627983 3.665201 1.517283 -v 0.044747 -0.006510 0.081550 -vn 3.034546 3.665191 0.000000 -v 0.044600 -0.006510 0.082100 -vn 2.627994 3.665191 -1.517273 -v 0.044747 -0.006510 0.082650 -vn 1.517275 3.665190 -2.627993 -v 0.045150 -0.006510 0.083053 -vn 1.567254 2.767272 -2.627604 -v 0.043250 -0.006510 0.085136 -vn 2.604323 2.705639 -1.593110 -v 0.042664 -0.006510 0.084550 -vn 3.105490 2.967443 -0.329044 -v 0.042450 -0.006510 0.083750 -vn 0.329051 2.967436 -3.105489 -v 0.044050 -0.006510 0.085350 -vn 1.517275 3.665190 2.627993 -v 0.045150 -0.006510 0.100047 -vn 2.627992 3.665188 1.517278 -v 0.044747 -0.006510 0.100450 -vn 3.034544 3.665195 0.000005 -v 0.044600 -0.006510 0.101000 -vn 2.627994 3.665191 -1.517273 -v 0.044747 -0.006510 0.101550 -vn 1.517275 3.665190 -2.627993 -v 0.045150 -0.006510 0.101953 -vn 0.329041 2.967448 3.105491 -v 0.044050 -0.006510 0.097750 -vn 1.534695 2.793311 2.658170 -v 0.043250 -0.006510 0.097964 -vn 2.681833 2.705647 1.458863 -v 0.042664 -0.006510 0.098550 -vn 3.095299 2.941416 0.372534 -v 0.042450 -0.006510 0.099350 -vn 3.117131 3.318303 -0.276134 -v 0.042450 -0.006510 0.080450 -vn 0.574264 0.824055 -6.075718 -v 0.040850 -0.005910 0.078850 -vn 0.515458 2.932373 -5.170813 -v 0.040850 -0.005410 0.078984 -vn 1.944737 2.830158 -4.695011 -v 0.041411 -0.005410 0.079096 -vn 0.319119 5.159064 -3.071147 -v 0.040850 -0.005044 0.079350 -vn 1.189245 5.058390 -2.871069 -v 0.041271 -0.005044 0.079434 -vn 0.094747 6.161365 -0.858896 -v 0.040850 -0.004910 0.079850 -vn 0.348263 6.145169 -0.840772 -v 0.041080 -0.004910 0.079896 -vn 0.643497 6.145171 -0.643499 -v 0.041274 -0.004910 0.080026 -vn 2.197428 5.058378 -2.197427 -v 0.041628 -0.005044 0.079672 -vn 0.840771 6.145170 -0.348260 -v 0.041404 -0.004910 0.080220 -vn 2.871082 5.058372 -1.189233 -v 0.041866 -0.005044 0.080029 -vn 3.593425 2.830160 -3.593410 -v 0.041887 -0.005410 0.079413 -vn 4.695015 2.830168 -1.944744 -v 0.042204 -0.005410 0.079889 -vn 2.300677 0.832434 -5.508854 -v 0.041462 -0.005910 0.078972 -vn 4.198023 0.767735 -4.237405 -v 0.041981 -0.005910 0.079319 -vn 5.511117 0.793881 -2.295198 -v 0.042328 -0.005910 0.079838 -vn -2.213392 5.594221 -0.985852 -v 0.030742 -0.004986 0.080074 -vn -0.068379 6.213996 -0.650213 -v 0.031650 -0.004910 0.079850 -vn -0.985871 5.594209 -2.213393 -v 0.031274 -0.004986 0.079542 -vn -0.263101 6.205174 -0.635183 -v 0.031420 -0.004910 0.079896 -vn -1.733923 5.567183 -1.733908 -v 0.030955 -0.004986 0.079755 -vn -0.486151 6.205174 -0.486148 -v 0.031226 -0.004910 0.080026 -vn -0.635185 6.205173 -0.263103 -v 0.031096 -0.004910 0.080220 -vn -3.971457 4.179688 -1.721213 -v 0.030442 -0.005203 0.079950 -vn -3.047751 4.168060 -3.047747 -v 0.030726 -0.005203 0.079526 -vn -1.721218 4.179684 -3.971457 -v 0.031150 -0.005203 0.079242 -vn -5.083622 2.198393 -2.142034 -v 0.030242 -0.005527 0.079867 -vn -0.206368 5.860703 -2.039442 -v 0.031650 -0.004986 0.079467 -vn -0.361353 5.258920 -3.303837 -v 0.031650 -0.005044 0.079350 -vn -0.433339 4.333350 -4.382078 -v 0.031650 -0.005203 0.079143 -vn -0.536369 3.246572 -5.250894 -v 0.031650 -0.005410 0.078984 -vn -3.886592 2.219052 -3.886592 -v 0.030572 -0.005527 0.079372 -vn -2.142044 2.198386 -5.083618 -v 0.031067 -0.005527 0.079042 -vn -0.568602 1.955542 -5.808810 -v 0.031650 -0.005527 0.078926 -vn -5.559213 0.563796 -2.331200 -v 0.030172 -0.005910 0.079838 -vn -4.307555 0.631548 -4.229948 -v 0.030519 -0.005910 0.079319 -vn -2.295925 0.677701 -5.591145 -v 0.031038 -0.005910 0.078972 -vn -0.577015 0.626799 -6.131757 -v 0.031650 -0.005910 0.078850 -vn -3.114238 3.333946 -0.291683 -v 0.030050 -0.006510 0.080450 -vn -2.462675 3.384960 -2.718680 -v 0.030488 -0.006510 0.079350 -vn -2.880707 3.549196 -1.089793 -v 0.030149 -0.006510 0.079896 -vn 2.370736 3.426972 -2.848762 -v 0.016612 -0.006510 0.079350 -vn 2.891040 3.508423 -1.085077 -v 0.016951 -0.006510 0.079896 -vn 3.117129 3.318310 -0.276144 -v 0.017050 -0.006510 0.080450 -vn 0.574265 0.824056 -6.075718 -v 0.015450 -0.005910 0.078850 -vn 0.515459 2.932373 -5.170813 -v 0.015450 -0.005410 0.078984 -vn 1.944734 2.830159 -4.695014 -v 0.016011 -0.005410 0.079096 -vn 0.319120 5.159063 -3.071147 -v 0.015450 -0.005044 0.079350 -vn 1.189242 5.058392 -2.871069 -v 0.015871 -0.005044 0.079434 -vn 0.762326 6.162051 -0.391705 -v 0.016004 -0.004910 0.080220 -vn 2.830491 5.097244 -1.336804 -v 0.016466 -0.005044 0.080029 -vn 2.197429 5.058375 -2.197424 -v 0.016228 -0.005044 0.079672 -vn 0.643498 6.145170 -0.643497 -v 0.015874 -0.004910 0.080026 -vn 0.348263 6.145170 -0.840772 -v 0.015680 -0.004910 0.079896 -vn 0.094748 6.161365 -0.858897 -v 0.015450 -0.004910 0.079850 -vn 3.593425 2.830158 -3.593406 -v 0.016487 -0.005410 0.079413 -vn 4.690488 2.837505 -2.071943 -v 0.016804 -0.005410 0.079889 -vn 2.301572 0.823297 -5.508341 -v 0.016062 -0.005910 0.078972 -vn 4.198022 0.767734 -4.237401 -v 0.016581 -0.005910 0.079319 -vn 5.511205 0.760305 -2.336442 -v 0.016928 -0.005910 0.079838 -vn -2.213404 5.594208 -0.985852 -v 0.005342 -0.004986 0.080074 -vn -0.068378 6.213996 -0.650213 -v 0.006250 -0.004910 0.079850 -vn -0.985869 5.594211 -2.213394 -v 0.005874 -0.004986 0.079542 -vn -0.263102 6.205174 -0.635185 -v 0.006020 -0.004910 0.079896 -vn -1.733925 5.567178 -1.733917 -v 0.005555 -0.004986 0.079755 -vn -0.486152 6.205175 -0.486145 -v 0.005826 -0.004910 0.080026 -vn -0.635182 6.205176 -0.263097 -v 0.005696 -0.004910 0.080220 -vn -3.971464 4.179683 -1.721218 -v 0.005042 -0.005203 0.079950 -vn -3.047752 4.168072 -3.047740 -v 0.005326 -0.005203 0.079526 -vn -1.721216 4.179687 -3.971454 -v 0.005750 -0.005203 0.079242 -vn -5.083626 2.198400 -2.142028 -v 0.004842 -0.005527 0.079867 -vn -0.206368 5.860703 -2.039442 -v 0.006250 -0.004986 0.079467 -vn -0.361352 5.258921 -3.303837 -v 0.006250 -0.005044 0.079350 -vn -0.433337 4.333350 -4.382078 -v 0.006250 -0.005203 0.079143 -vn -0.536367 3.246572 -5.250895 -v 0.006250 -0.005410 0.078984 -vn -3.886591 2.219043 -3.886576 -v 0.005172 -0.005527 0.079372 -vn -2.142041 2.198379 -5.083620 -v 0.005667 -0.005527 0.079042 -vn -0.568601 1.955542 -5.808811 -v 0.006250 -0.005527 0.078926 -vn -5.559216 0.563792 -2.331206 -v 0.004772 -0.005910 0.079838 -vn -4.307555 0.631533 -4.229955 -v 0.005119 -0.005910 0.079319 -vn -2.302713 0.685768 -5.589557 -v 0.005638 -0.005910 0.078972 -vn -0.568457 0.641231 -6.133119 -v 0.006250 -0.005910 0.078850 -vn -3.114237 3.333949 -0.291687 -v 0.004650 -0.006510 0.080450 -vn -0.837291 6.169086 -0.042815 -v -0.001350 -0.006510 0.082025 -vn -0.609462 6.161920 -0.609459 -v -0.000567 -0.006510 0.080133 -vn -0.042449 6.169023 -0.837527 -v 0.001325 -0.006510 0.079350 -vn -2.464845 3.384128 -2.722098 -v 0.005088 -0.006510 0.079350 -vn -2.880707 3.549192 -1.089797 -v 0.004749 -0.006510 0.079896 -vn -0.168153 6.161914 -0.845367 -v 0.000803 -0.006510 0.079401 -vn -0.329842 6.161916 -0.796310 -v 0.000301 -0.006510 0.079554 -vn -0.478859 6.161915 -0.716665 -v -0.000161 -0.006510 0.079801 -vn -0.716655 6.161918 -0.478857 -v -0.000899 -0.006510 0.080539 -vn -0.796300 6.161920 -0.329837 -v -0.001146 -0.006510 0.081001 -vn -0.845350 6.161919 -0.168149 -v -0.001299 -0.006510 0.081503 -vn -2.848750 3.426978 -2.370735 -v -0.001350 -0.006510 0.085788 -vn -1.085079 3.508457 -2.891034 -v -0.000804 -0.006510 0.085449 -vn -0.276134 3.318304 -3.117131 -v -0.000250 -0.006510 0.085350 -vn -0.650212 6.213996 -0.068377 -v -0.000850 -0.004910 0.086950 -vn -0.635185 6.205173 -0.263106 -v -0.000804 -0.004910 0.086720 -vn -2.039445 5.860705 -0.206526 -v -0.001233 -0.004986 0.086950 -vn -2.213391 5.594219 -0.985858 -v -0.001158 -0.004986 0.086574 -vn -3.303836 5.258921 -0.361354 -v -0.001350 -0.005044 0.086950 -vn -3.971450 4.179682 -1.721225 -v -0.001458 -0.005203 0.086450 -vn -5.083608 2.198367 -2.142057 -v -0.001658 -0.005527 0.086367 -vn -5.250896 3.246573 -0.536367 -v -0.001716 -0.005410 0.086950 -vn -4.382078 4.333350 -0.433546 -v -0.001557 -0.005203 0.086950 -vn -5.569990 0.637454 -2.327115 -v -0.001728 -0.005910 0.086338 -vn -6.131698 0.633721 -0.576672 -v -0.001850 -0.005910 0.086950 -vn -5.808807 1.955566 -0.568765 -v -0.001774 -0.005527 0.086950 -vn -0.486146 6.205173 -0.486158 -v -0.000674 -0.004910 0.086526 -vn -1.733922 5.567175 -1.733923 -v -0.000945 -0.004986 0.086255 -vn -3.047751 4.168054 -3.047771 -v -0.001174 -0.005203 0.086026 -vn -3.886590 2.219084 -3.886595 -v -0.001328 -0.005527 0.085872 -vn -4.284563 0.581899 -4.245173 -v -0.001381 -0.005910 0.085819 -vn -0.263094 6.205177 -0.635173 -v -0.000480 -0.004910 0.086396 -vn -0.938383 5.567156 -2.265499 -v -0.000626 -0.004986 0.086042 -vn -1.649449 4.168058 -3.982086 -v -0.000750 -0.005203 0.085742 -vn -2.103408 2.219062 -5.078079 -v -0.000833 -0.005527 0.085542 -vn -2.320718 0.608053 -5.572777 -v -0.000862 -0.005910 0.085472 -vn -0.985878 5.594205 2.213394 -v -0.000626 -0.004986 0.097058 -vn -0.650212 6.213998 0.068378 -v -0.000850 -0.004910 0.096150 -vn -2.213395 5.594206 0.985871 -v -0.001158 -0.004986 0.096526 -vn -0.635183 6.205174 0.263102 -v -0.000804 -0.004910 0.096380 -vn -1.733911 5.567189 1.733917 -v -0.000945 -0.004986 0.096845 -vn -0.486147 6.205175 0.486147 -v -0.000674 -0.004910 0.096574 -vn -0.263103 6.205174 0.635182 -v -0.000480 -0.004910 0.096704 -vn -1.721216 4.179686 3.971460 -v -0.000750 -0.005203 0.097358 -vn -3.047745 4.168060 3.047747 -v -0.001174 -0.005203 0.097074 -vn -3.971463 4.179683 1.721213 -v -0.001458 -0.005203 0.096650 -vn -2.142040 2.198396 5.083620 -v -0.000833 -0.005527 0.097558 -vn -2.039443 5.860703 0.206522 -v -0.001233 -0.004986 0.096150 -vn -3.303839 5.258922 0.361351 -v -0.001350 -0.005044 0.096150 -vn -4.382078 4.333350 0.433546 -v -0.001557 -0.005203 0.096150 -vn -5.250894 3.246572 0.536367 -v -0.001716 -0.005410 0.096150 -vn -3.886592 2.219053 3.886590 -v -0.001328 -0.005527 0.097228 -vn -5.083621 2.198392 2.142036 -v -0.001658 -0.005527 0.096733 -vn -5.808809 1.955570 0.568762 -v -0.001774 -0.005527 0.096150 -vn -2.331216 0.563788 5.559208 -v -0.000862 -0.005910 0.097628 -vn -4.229957 0.631545 4.307546 -v -0.001381 -0.005910 0.097281 -vn -5.589554 0.685780 2.302717 -v -0.001728 -0.005910 0.096762 -vn -6.133108 0.641255 0.568472 -v -0.001850 -0.005910 0.096150 -vn -0.291693 3.333951 3.114236 -v -0.000250 -0.006510 0.097750 -vn -0.042814 6.169094 0.837269 -v 0.001325 -0.006510 0.103750 -vn -2.722083 3.384107 2.464855 -v -0.001350 -0.006510 0.097312 -vn -0.837524 6.169024 0.042445 -v -0.001350 -0.006510 0.101075 -vn -1.089814 3.549175 2.880704 -v -0.000804 -0.006510 0.097651 -vn -0.609464 6.161919 0.609462 -v -0.000567 -0.006510 0.102967 -vn -0.845348 6.161920 0.168153 -v -0.001299 -0.006510 0.101597 -vn -0.796308 6.161918 0.329844 -v -0.001146 -0.006510 0.102099 -vn -0.716653 6.161919 0.478853 -v -0.000899 -0.006510 0.102561 -vn -2.370743 3.426965 2.848735 -v 0.005088 -0.006510 0.103750 -vn -2.891031 3.508446 1.085092 -v 0.004749 -0.006510 0.103204 -vn -3.117129 3.318310 0.276144 -v 0.004650 -0.006510 0.102650 -vn -0.478847 6.161922 0.716647 -v -0.000161 -0.006510 0.103299 -vn -0.329832 6.161922 0.796291 -v 0.000301 -0.006510 0.103546 -vn -0.168152 6.161920 0.845344 -v 0.000803 -0.006510 0.103699 -vn -0.361360 5.258951 3.303799 -v 0.006250 -0.005044 0.103750 -vn -0.206368 5.860703 2.039442 -v 0.006250 -0.004986 0.103633 -vn -0.985866 5.594212 2.213393 -v 0.005874 -0.004986 0.103558 -vn -2.213405 5.594197 0.985871 -v 0.005342 -0.004986 0.103026 -vn -0.635177 6.205176 0.263099 -v 0.005696 -0.004910 0.102880 -vn -1.733917 5.567182 1.733919 -v 0.005555 -0.004986 0.103345 -vn -0.486152 6.205174 0.486146 -v 0.005826 -0.004910 0.103074 -vn -0.263104 6.205173 0.635184 -v 0.006020 -0.004910 0.103204 -vn -0.068377 6.213999 0.650212 -v 0.006250 -0.004910 0.103250 -vn -0.536382 3.246527 5.250931 -v 0.006250 -0.005410 0.104116 -vn -0.433369 4.333313 4.382073 -v 0.006250 -0.005203 0.103957 -vn -1.721228 4.179684 3.971454 -v 0.005750 -0.005203 0.103858 -vn -3.047748 4.168071 3.047748 -v 0.005326 -0.005203 0.103574 -vn -3.971465 4.179695 1.721217 -v 0.005042 -0.005203 0.103150 -vn -0.576679 0.633747 6.131686 -v 0.006250 -0.005910 0.104250 -vn -0.568608 1.955594 5.808803 -v 0.006250 -0.005527 0.104174 -vn -2.142044 2.198387 5.083617 -v 0.005667 -0.005527 0.104058 -vn -3.886581 2.219079 3.886585 -v 0.005172 -0.005527 0.103728 -vn -5.083609 2.198390 2.142040 -v 0.004842 -0.005527 0.103233 -vn -2.326230 0.646606 5.570504 -v 0.005638 -0.005910 0.104128 -vn -4.245163 0.581866 4.284579 -v 0.005119 -0.005910 0.103781 -vn -5.572782 0.608022 2.320718 -v 0.004772 -0.005910 0.103262 -vn 4.695023 2.830156 1.944738 -v 0.016804 -0.005410 0.103211 -vn 2.871074 5.058379 1.189231 -v 0.016466 -0.005044 0.103071 -vn 0.840763 6.145173 0.348256 -v 0.016004 -0.004910 0.102880 -vn 0.643493 6.145175 0.643487 -v 0.015874 -0.004910 0.103074 -vn 2.197421 5.058374 2.197425 -v 0.016228 -0.005044 0.103428 -vn 0.348255 6.145173 0.840763 -v 0.015680 -0.004910 0.103204 -vn 1.189221 5.058366 2.871088 -v 0.015871 -0.005044 0.103666 -vn 0.094746 6.161370 0.858895 -v 0.015450 -0.004910 0.103250 -vn 0.319099 5.159070 3.071146 -v 0.015450 -0.005044 0.103750 -vn 3.593403 2.830148 3.593422 -v 0.016487 -0.005410 0.103687 -vn 1.944728 2.830158 4.695040 -v 0.016011 -0.005410 0.104004 -vn 0.515457 2.932412 5.170809 -v 0.015450 -0.005410 0.104116 -vn 5.497588 0.749644 2.305663 -v 0.016928 -0.005910 0.103262 -vn 4.260364 0.817398 4.182775 -v 0.016581 -0.005910 0.103781 -vn 2.270391 0.863563 5.529521 -v 0.016062 -0.005910 0.104128 -vn 0.574652 0.817193 6.075749 -v 0.015450 -0.005910 0.104250 -vn 3.114238 3.333949 0.291687 -v 0.017050 -0.006510 0.102650 -vn -2.370742 3.426962 2.848738 -v 0.030488 -0.006510 0.103750 -vn 2.462695 3.384932 2.718643 -v 0.016612 -0.006510 0.103750 -vn -2.891030 3.508451 1.085090 -v 0.030149 -0.006510 0.103204 -vn -3.117130 3.318307 0.276139 -v 0.030050 -0.006510 0.102650 -vn 2.880704 3.549195 1.089803 -v 0.016951 -0.006510 0.103204 -vn -0.570046 0.826769 6.074987 -v 0.031650 -0.005910 0.104250 -vn -0.505421 2.932359 5.168921 -v 0.031650 -0.005410 0.104116 -vn -1.944735 2.830159 4.695037 -v 0.031089 -0.005410 0.104004 -vn -0.309064 5.157185 3.071090 -v 0.031650 -0.005044 0.103750 -vn -1.189227 5.058371 2.871081 -v 0.031229 -0.005044 0.103666 -vn -0.090509 6.160654 0.861576 -v 0.031650 -0.004910 0.103250 -vn -0.348255 6.145173 0.840765 -v 0.031420 -0.004910 0.103204 -vn -0.643494 6.145173 0.643492 -v 0.031226 -0.004910 0.103074 -vn -2.197418 5.058376 2.197427 -v 0.030872 -0.005044 0.103428 -vn -0.840765 6.145173 0.348256 -v 0.031096 -0.004910 0.102880 -vn -2.871073 5.058382 1.189238 -v 0.030634 -0.005044 0.103071 -vn -3.593401 2.830152 3.593413 -v 0.030613 -0.005410 0.103687 -vn -4.695027 2.830158 1.944738 -v 0.030296 -0.005410 0.103211 -vn -2.301594 0.823310 5.508353 -v 0.031038 -0.005910 0.104128 -vn -4.197998 0.767693 4.237399 -v 0.030519 -0.005910 0.103781 -vn -5.511140 0.793874 2.295187 -v 0.030172 -0.005910 0.103262 -vn 4.695019 2.830151 1.944747 -v 0.042204 -0.005410 0.103211 -vn 2.871073 5.058378 1.189236 -v 0.041866 -0.005044 0.103071 -vn 0.840768 6.145171 0.348258 -v 0.041404 -0.004910 0.102880 -vn 0.643493 6.145174 0.643489 -v 0.041274 -0.004910 0.103074 -vn 2.197421 5.058376 2.197427 -v 0.041628 -0.005044 0.103428 -vn 0.348256 6.145173 0.840764 -v 0.041080 -0.004910 0.103204 -vn 1.189224 5.058364 2.871087 -v 0.041271 -0.005044 0.103666 -vn 0.090507 6.160654 0.861574 -v 0.040850 -0.004910 0.103250 -vn 0.309066 5.157182 3.071094 -v 0.040850 -0.005044 0.103750 -vn 3.593404 2.830150 3.593425 -v 0.041887 -0.005410 0.103687 -vn 1.944731 2.830157 4.695037 -v 0.041411 -0.005410 0.104004 -vn 0.505424 2.932359 5.168919 -v 0.040850 -0.005410 0.104116 -vn 5.497587 0.749650 2.305659 -v 0.042328 -0.005910 0.103262 -vn 4.260365 0.817401 4.182781 -v 0.041981 -0.005910 0.103781 -vn 2.277182 0.871632 5.527929 -v 0.041462 -0.005910 0.104128 -vn 0.561856 0.834301 6.076398 -v 0.040850 -0.005910 0.104250 -vn 3.114239 3.333945 0.291680 -v 0.042450 -0.006510 0.102650 -vn 0.276154 3.318316 3.117127 -v 0.047350 -0.006510 0.097750 -vn 0.000000 6.283186 0.000000 -v 0.004734 -0.004910 0.093650 -vn 0.643488 6.145171 -0.643503 -v 0.047774 -0.004910 0.086526 -vn 0.348242 6.145175 -0.840764 -v 0.047580 -0.004910 0.086396 -vn 0.000000 6.283185 0.000000 -v 0.016966 -0.004910 0.089450 -vn 0.000000 6.283185 0.000000 -v 0.007800 -0.004910 0.097666 -vn 0.000000 6.283185 0.000000 -v 0.013900 -0.004910 0.097666 -vn 0.000000 6.283186 0.000000 -v 0.016966 -0.004910 0.093650 -vn 0.000000 6.283185 0.000000 -v 0.013900 -0.004910 0.085434 -vn 0.000000 6.283185 0.000000 -v 0.007800 -0.004910 0.085434 -vn 0.000000 6.283186 0.000000 -v 0.004734 -0.004910 0.089450 -vn 0.000000 6.283184 0.000000 -v 0.041950 -0.004910 0.089450 -vn 0.000000 6.283185 0.000000 -v 0.041950 -0.004910 0.093650 -vn 0.000000 6.283183 0.000000 -v 0.041950 -0.004910 0.097666 -vn 0.000000 6.283183 0.000000 -v 0.041950 -0.004910 0.085434 -vn 0.000000 6.283182 0.000000 -v 0.026716 -0.004910 0.093650 -vn 0.000000 6.283183 0.000000 -v 0.026716 -0.004910 0.089450 -vn 0.840771 6.145171 -0.348258 -v 0.047904 -0.004910 0.086720 -vn 0.000000 6.283187 0.000000 -v 0.047200 -0.004910 0.089450 -vn 0.263101 6.205175 0.635182 -v 0.047580 -0.004910 0.096704 -vn 0.486145 6.205176 0.486144 -v 0.047774 -0.004910 0.096574 -vn 0.000000 6.283185 0.000000 -v 0.047200 -0.004910 0.093650 -vn 0.000000 6.283185 0.000000 -v 0.007800 -0.004910 0.080984 -vn 0.000000 6.283186 0.000000 -v 0.013900 -0.004910 0.080984 -vn 0.582607 4.269885 -2.590072 -v 0.045050 -0.004910 0.092050 -vn 2.221450 4.712381 0.000000 -v 0.044550 -0.004910 0.091550 -vn 0.582607 4.269885 2.590071 -v 0.045050 -0.004910 0.091050 -vn -1.056237 5.597404 0.000000 -v 0.046451 -0.004910 0.091550 -vn 0.858897 6.161366 -0.094749 -v 0.047950 -0.004910 0.086950 -vn 0.650212 6.213997 0.068377 -v 0.047950 -0.004910 0.096150 -vn 0.635182 6.205174 0.263102 -v 0.047904 -0.004910 0.096380 -vn 3.303819 5.258935 0.361355 -v 0.048450 -0.005044 0.096150 -vn 2.039442 5.860703 0.206366 -v 0.048333 -0.004986 0.096150 -vn 2.213398 5.594208 0.985865 -v 0.048258 -0.004986 0.096526 -vn 0.985869 5.594210 2.213392 -v 0.047726 -0.004986 0.097058 -vn 1.733922 5.567179 1.733915 -v 0.048045 -0.004986 0.096845 -vn 5.250913 3.246550 0.536375 -v 0.048816 -0.005410 0.096150 -vn 4.382075 4.333330 0.433353 -v 0.048657 -0.005203 0.096150 -vn 3.971463 4.179684 1.721216 -v 0.048558 -0.005203 0.096650 -vn 3.047756 4.168059 3.047747 -v 0.048274 -0.005203 0.097074 -vn 1.721220 4.179684 3.971454 -v 0.047850 -0.005203 0.097358 -vn 6.131682 0.633743 0.576681 -v 0.048950 -0.005910 0.096150 -vn 5.808803 1.955594 0.568608 -v 0.048874 -0.005527 0.096150 -vn 5.083621 2.198395 2.142037 -v 0.048758 -0.005527 0.096733 -vn 3.886597 2.219053 3.886590 -v 0.048428 -0.005527 0.097228 -vn 2.142046 2.198380 5.083615 -v 0.047933 -0.005527 0.097558 -vn 5.570493 0.646604 2.326234 -v 0.048828 -0.005910 0.096762 -vn 4.284584 0.581867 4.245184 -v 0.048481 -0.005910 0.097281 -vn 2.320730 0.608015 5.572764 -v 0.047962 -0.005910 0.097628 -vn 1.944738 2.830154 -4.695033 -v 0.047911 -0.005410 0.085596 -vn 1.189221 5.058374 -2.871084 -v 0.047771 -0.005044 0.085934 -vn 2.197428 5.058369 -2.197428 -v 0.048128 -0.005044 0.086172 -vn 2.871078 5.058381 -1.189235 -v 0.048366 -0.005044 0.086529 -vn 3.071144 5.159069 -0.319108 -v 0.048450 -0.005044 0.086950 -vn 3.593407 2.830149 -3.593413 -v 0.048387 -0.005410 0.085913 -vn 4.695027 2.830158 -1.944738 -v 0.048704 -0.005410 0.086389 -vn 5.170807 2.932410 -0.515460 -v 0.048816 -0.005410 0.086950 -vn 2.305656 0.749659 -5.497599 -v 0.047962 -0.005910 0.085472 -vn 4.182766 0.817407 -4.260374 -v 0.048481 -0.005910 0.085819 -vn 5.527934 0.871637 -2.277184 -v 0.048828 -0.005910 0.086338 -vn 6.077109 0.831627 -0.566098 -v 0.048950 -0.005910 0.086950 -vn 0.291683 3.333949 -3.114238 -v 0.047350 -0.006510 0.085350 -vn 0.042815 6.169087 -0.837292 -v 0.045775 -0.006510 0.079350 -vn 0.716654 6.161919 -0.478855 -v 0.047999 -0.006510 0.080539 -vn 0.609463 6.161919 -0.609463 -v 0.047667 -0.006510 0.080133 -vn 0.845361 6.161915 -0.168151 -v 0.048399 -0.006510 0.081503 -vn 0.796310 6.161916 -0.329843 -v 0.048246 -0.006510 0.081001 -vn 1.089783 3.549219 -2.880707 -v 0.047904 -0.006510 0.085449 -vn 2.722063 3.384102 -2.464864 -v 0.048450 -0.006510 0.085788 -vn 0.837514 6.169027 -0.042445 -v 0.048450 -0.006510 0.082025 -vn 2.370734 3.426968 -2.848766 -v 0.042012 -0.006510 0.079350 -vn 2.891037 3.508441 -1.085075 -v 0.042351 -0.006510 0.079896 -vn 0.478867 6.161913 -0.716668 -v 0.047261 -0.006510 0.079801 -vn 0.329842 6.161915 -0.796316 -v 0.046799 -0.006510 0.079554 -vn 0.168157 6.161913 -0.845369 -v 0.046297 -0.006510 0.079401 -vn 0.837278 6.169091 0.042811 -v 0.048450 -0.006510 0.101075 -vn 0.478850 6.161920 0.716653 -v 0.047261 -0.006510 0.103299 -vn 0.609467 6.161919 0.609462 -v 0.047667 -0.006510 0.102967 -vn 1.085092 3.508418 2.891035 -v 0.047904 -0.006510 0.097651 -vn 2.848732 3.426965 2.370748 -v 0.048450 -0.006510 0.097312 -vn 0.716655 6.161919 0.478851 -v 0.047999 -0.006510 0.102561 -vn 0.796318 6.161914 0.329853 -v 0.048246 -0.006510 0.102099 -vn 0.845360 6.161916 0.168153 -v 0.048399 -0.006510 0.101597 -vn 0.329837 6.161922 0.796294 -v 0.046799 -0.006510 0.103546 -vn 0.168150 6.161921 0.845346 -v 0.046297 -0.006510 0.103699 -vn 2.464869 3.384074 2.722065 -v 0.042012 -0.006510 0.103750 -vn 0.042448 6.169029 0.837504 -v 0.045775 -0.006510 0.103750 -vn 2.880702 3.549214 1.089796 -v 0.042351 -0.006510 0.103204 -vn 0.300319 0.804745 -6.137357 -v 0.045775 -0.007010 0.078850 -vn 0.006871 0.001308 -6.283154 -v 0.040850 -0.007010 0.078850 -vn 0.269983 2.690609 -5.494061 -v 0.045775 -0.006760 0.078917 -vn 0.147149 0.005229 -6.277265 -v 0.040853 -0.007008 0.078850 -vn 1.848378 2.867629 -4.447989 -v 0.041716 -0.006575 0.079105 -vn 0.136237 5.494064 -2.746975 -v 0.045775 -0.006577 0.079100 -vn 0.229098 4.374749 -4.397354 -v 0.045775 -0.006656 0.078996 -vn 0.511782 0.733547 -6.191861 -v 0.041159 -0.006839 0.078880 -vn 0.843337 1.595347 -5.833169 -v 0.041350 -0.006739 0.078930 -vn 1.318753 2.096880 -5.308765 -v 0.041512 -0.006660 0.078993 -vn -1.823543 2.770873 -4.454666 -v 0.030766 -0.006568 0.079116 -vn -1.314780 2.076690 -5.336397 -v 0.030989 -0.006660 0.078993 -vn -0.715809 1.066823 -6.075180 -v 0.031172 -0.006750 0.078923 -vn -0.162857 0.139215 -6.272573 -v 0.031650 -0.007010 0.078850 -vn 1.798345 2.687850 -4.721426 -v 0.016316 -0.006575 0.079105 -vn 0.933168 1.654940 -5.802468 -v 0.015950 -0.006739 0.078930 -vn 0.503271 0.751952 -6.188721 -v 0.015759 -0.006839 0.078880 -vn 0.002367 0.000423 -6.283183 -v 0.015450 -0.007010 0.078850 -vn 0.118302 0.062858 -6.278611 -v 0.015453 -0.007008 0.078850 -vn -0.872903 1.514727 -5.846424 -v 0.005772 -0.006750 0.078923 -vn -1.315581 2.074895 -5.337824 -v 0.005589 -0.006660 0.078993 -vn -1.822899 2.772358 -4.452562 -v 0.005366 -0.006568 0.079116 -vn -0.479449 0.722240 -6.193278 -v 0.005941 -0.006839 0.078880 -vn -0.103681 0.088931 -6.278876 -v 0.006250 -0.007010 0.078850 -vn -0.136101 5.494200 -2.746647 -v 0.001325 -0.006577 0.079100 -vn -0.305361 0.801573 -6.138200 -v 0.001325 -0.007010 0.078850 -vn -0.274208 2.694146 -5.492805 -v 0.001325 -0.006760 0.078917 -vn -0.228574 4.374321 -4.397734 -v 0.001325 -0.006656 0.078996 -vn 0.638810 5.186304 -2.992052 -v 0.046346 -0.006577 0.079156 -vn 1.050622 2.922501 -5.101988 -v 0.046381 -0.006760 0.078977 -vn 1.177786 5.164381 -2.843437 -v 0.046894 -0.006577 0.079323 -vn 1.709883 5.164388 -2.559025 -v 0.047400 -0.006577 0.079593 -vn 2.176268 5.164373 -2.176272 -v 0.047843 -0.006577 0.079957 -vn 2.559032 5.164363 -1.709894 -v 0.048207 -0.006577 0.080400 -vn 2.843431 5.164380 -1.177795 -v 0.048477 -0.006577 0.080906 -vn 2.992067 5.186276 -0.638801 -v 0.048644 -0.006577 0.081454 -vn 2.746679 5.494172 -0.136095 -v 0.048700 -0.006577 0.082025 -vn 4.397697 4.374400 -0.228573 -v 0.048804 -0.006656 0.082025 -vn 1.985321 2.940720 -4.793003 -v 0.046964 -0.006760 0.079154 -vn 2.882236 2.940764 -4.313585 -v 0.047502 -0.006760 0.079441 -vn 3.668424 2.940707 -3.668404 -v 0.047973 -0.006760 0.079827 -vn 4.313596 2.940759 -2.882261 -v 0.048359 -0.006760 0.080298 -vn 4.792997 2.940725 -1.985326 -v 0.048646 -0.006760 0.080836 -vn 5.102005 2.922489 -1.050623 -v 0.048823 -0.006760 0.081419 -vn 5.492712 2.694250 -0.274220 -v 0.048883 -0.006760 0.082025 -vn 1.189762 0.794289 -5.981386 -v 0.046394 -0.007010 0.078911 -vn 2.333821 0.796353 -5.634364 -v 0.046990 -0.007010 0.079092 -vn 3.388170 0.794315 -5.070763 -v 0.047539 -0.007010 0.079385 -vn 4.312368 0.796353 -4.312344 -v 0.048020 -0.007010 0.079780 -vn 5.070745 0.794328 -3.388197 -v 0.048415 -0.007010 0.080261 -vn 5.634363 0.796354 -2.333809 -v 0.048708 -0.007010 0.080810 -vn 5.981388 0.794295 -1.189769 -v 0.048889 -0.007010 0.081406 -vn 6.138197 0.801573 -0.305378 -v 0.048950 -0.007010 0.082025 -vn -4.397287 4.374865 -0.228899 -v -0.001704 -0.006656 0.082025 -vn -2.746969 5.494070 -0.136223 -v -0.001600 -0.006577 0.082025 -vn -2.992058 5.186278 -0.638800 -v -0.001544 -0.006577 0.081454 -vn -6.137368 0.804709 -0.300326 -v -0.001850 -0.007010 0.082025 -vn -5.493839 2.690677 -0.269992 -v -0.001783 -0.006760 0.082025 -vn -5.102003 2.922484 -1.050631 -v -0.001723 -0.006760 0.081419 -vn -2.843441 5.164364 -1.177794 -v -0.001377 -0.006577 0.080906 -vn -2.559027 5.164359 -1.709904 -v -0.001107 -0.006577 0.080400 -vn -2.176262 5.164388 -2.176262 -v -0.000743 -0.006577 0.079957 -vn -1.709889 5.164375 -2.559030 -v -0.000300 -0.006577 0.079593 -vn -1.177787 5.164379 -2.843434 -v 0.000206 -0.006577 0.079323 -vn -0.638811 5.186302 -2.992051 -v 0.000754 -0.006577 0.079156 -vn -4.793017 2.940707 -1.985344 -v -0.001546 -0.006760 0.080836 -vn -4.313605 2.940760 -2.882239 -v -0.001259 -0.006760 0.080298 -vn -3.668395 2.940722 -3.668408 -v -0.000873 -0.006760 0.079827 -vn -2.882255 2.940778 -4.313582 -v -0.000402 -0.006760 0.079441 -vn -1.985312 2.940711 -4.793007 -v 0.000136 -0.006760 0.079154 -vn -1.050626 2.922495 -5.101988 -v 0.000719 -0.006760 0.078977 -vn -5.981383 0.794291 -1.189769 -v -0.001789 -0.007010 0.081406 -vn -5.634362 0.796360 -2.333819 -v -0.001608 -0.007010 0.080810 -vn -5.070762 0.794325 -3.388167 -v -0.001315 -0.007010 0.080261 -vn -4.312351 0.796354 -4.312359 -v -0.000920 -0.007010 0.079780 -vn -3.388179 0.794334 -5.070748 -v -0.000439 -0.007010 0.079385 -vn -2.333807 0.796337 -5.634378 -v 0.000110 -0.007010 0.079092 -vn -1.189767 0.794294 -5.981382 -v 0.000706 -0.007010 0.078911 -vn -4.712621 2.696031 -1.792210 -v -0.001595 -0.006575 0.086084 -vn -5.801741 1.656630 -0.930792 -v -0.001770 -0.006739 0.086450 -vn -6.191865 0.733521 -0.511759 -v -0.001820 -0.006839 0.086641 -vn -6.283149 0.002278 -0.007965 -v -0.001850 -0.007010 0.086950 -vn -6.277442 0.010969 -0.149082 -v -0.001850 -0.007008 0.086947 -vn -5.846424 1.514740 0.872884 -v -0.001777 -0.006750 0.096628 -vn -5.337823 2.074893 1.315568 -v -0.001707 -0.006660 0.096811 -vn -4.452599 2.772339 1.822901 -v -0.001584 -0.006568 0.097034 -vn -6.193263 0.722289 0.479470 -v -0.001820 -0.006839 0.096459 -vn -6.278875 0.088942 0.103693 -v -0.001850 -0.007010 0.096150 -vn -2.746645 5.494206 0.136083 -v -0.001600 -0.006577 0.101075 -vn -6.138212 0.801533 0.305360 -v -0.001850 -0.007010 0.101075 -vn -5.492722 2.694213 0.274211 -v -0.001783 -0.006760 0.101075 -vn -4.397658 4.374430 0.228564 -v -0.001704 -0.006656 0.101075 -vn -0.229095 4.374805 4.397358 -v 0.001325 -0.006656 0.104104 -vn -0.136241 5.494000 2.747040 -v 0.001325 -0.006577 0.104000 -vn -0.638794 5.186302 2.992037 -v 0.000754 -0.006577 0.103944 -vn -0.300319 0.804745 6.137357 -v 0.001325 -0.007010 0.104250 -vn -0.269979 2.690718 5.493973 -v 0.001325 -0.006760 0.104183 -vn -1.050631 2.922496 5.101980 -v 0.000719 -0.006760 0.104123 -vn -1.177799 5.164348 2.843445 -v 0.000206 -0.006577 0.103777 -vn -1.709878 5.164372 2.559023 -v -0.000300 -0.006577 0.103507 -vn -2.176260 5.164387 2.176261 -v -0.000743 -0.006577 0.103143 -vn -2.559015 5.164391 1.709876 -v -0.001107 -0.006577 0.102700 -vn -2.843445 5.164366 1.177793 -v -0.001377 -0.006577 0.102194 -vn -2.992059 5.186275 0.638811 -v -0.001544 -0.006577 0.101646 -vn -1.985344 2.940750 4.793031 -v 0.000136 -0.006760 0.103946 -vn -2.882234 2.940720 4.313604 -v -0.000402 -0.006760 0.103659 -vn -3.668402 2.940716 3.668400 -v -0.000873 -0.006760 0.103273 -vn -4.313594 2.940730 2.882234 -v -0.001259 -0.006760 0.102802 -vn -4.793017 2.940742 1.985335 -v -0.001546 -0.006760 0.102264 -vn -5.101997 2.922488 1.050641 -v -0.001723 -0.006760 0.101681 -vn -1.189777 0.794297 5.981379 -v 0.000706 -0.007010 0.104189 -vn -2.333821 0.796399 5.634344 -v 0.000110 -0.007010 0.104008 -vn -3.388188 0.794277 5.070777 -v -0.000439 -0.007010 0.103715 -vn -4.312354 0.796345 4.312348 -v -0.000920 -0.007010 0.103320 -vn -5.070779 0.794293 3.388173 -v -0.001315 -0.007010 0.102839 -vn -5.634346 0.796382 2.333832 -v -0.001608 -0.007010 0.102290 -vn -5.981383 0.794289 1.189773 -v -0.001789 -0.007010 0.101694 -vn -0.006871 0.001308 6.283154 -v 0.006250 -0.007010 0.104250 -vn -0.147174 0.005251 6.277263 -v 0.006247 -0.007008 0.104250 -vn -1.848390 2.867687 4.447975 -v 0.005384 -0.006575 0.103995 -vn -0.511779 0.733613 6.191843 -v 0.005941 -0.006839 0.104220 -vn -0.843301 1.595208 5.833261 -v 0.005750 -0.006739 0.104170 -vn -1.318743 2.096909 5.308774 -v 0.005588 -0.006660 0.104107 -vn 1.823519 2.770855 4.454750 -v 0.016334 -0.006568 0.103984 -vn 1.314741 2.076663 5.336411 -v 0.016111 -0.006660 0.104107 -vn 0.715836 1.066885 6.075154 -v 0.015928 -0.006750 0.104177 -vn 0.162873 0.139229 6.272572 -v 0.015450 -0.007010 0.104250 -vn -1.798359 2.687896 4.721407 -v 0.030784 -0.006575 0.103995 -vn -0.933135 1.654796 5.802560 -v 0.031150 -0.006739 0.104170 -vn -0.503274 0.752005 6.188704 -v 0.031341 -0.006839 0.104220 -vn -0.002367 0.000424 6.283183 -v 0.031650 -0.007010 0.104250 -vn -0.118329 0.062880 6.278609 -v 0.031647 -0.007008 0.104250 -vn 0.872900 1.514730 5.846420 -v 0.041328 -0.006750 0.104177 -vn 1.315543 2.074862 5.337839 -v 0.041511 -0.006660 0.104107 -vn 1.822870 2.772348 4.452647 -v 0.041734 -0.006568 0.103984 -vn 0.479497 0.722345 6.193249 -v 0.041159 -0.006839 0.104220 -vn 0.103706 0.088953 6.278874 -v 0.040850 -0.007010 0.104250 -vn 0.136105 5.494137 2.746713 -v 0.045775 -0.006577 0.104000 -vn 0.305359 0.801574 6.138199 -v 0.045775 -0.007010 0.104250 -vn 0.274201 2.694251 5.492713 -v 0.045775 -0.006760 0.104183 -vn 0.228570 4.374374 4.397735 -v 0.045775 -0.006656 0.104104 -vn 6.137354 0.804745 0.300337 -v 0.048950 -0.007010 0.101075 -vn 6.283152 0.002273 0.007952 -v 0.048950 -0.007010 0.096150 -vn 5.494080 2.690714 0.269996 -v 0.048883 -0.006760 0.101075 -vn 6.277436 0.010789 0.149115 -v 0.048950 -0.007008 0.096153 -vn 4.447974 2.867699 1.848386 -v 0.048695 -0.006575 0.097016 -vn 2.747006 5.494035 0.136231 -v 0.048700 -0.006577 0.101075 -vn 4.397325 4.374833 0.229096 -v 0.048804 -0.006656 0.101075 -vn 6.191851 0.733574 0.511786 -v 0.048920 -0.006839 0.096459 -vn 5.833219 1.595258 0.843303 -v 0.048870 -0.006739 0.096650 -vn 5.308847 2.096841 1.318706 -v 0.048807 -0.006660 0.096812 -vn 5.846366 1.514782 -0.872942 -v 0.048877 -0.006750 0.086472 -vn 5.337894 2.074844 -1.315521 -v 0.048807 -0.006660 0.086289 -vn 4.452609 2.772372 -1.822878 -v 0.048684 -0.006568 0.086066 -vn 6.193257 0.722314 -0.479497 -v 0.048920 -0.006839 0.086641 -vn 6.278875 0.088942 -0.103693 -v 0.048950 -0.007010 0.086950 -vn 2.992069 5.186273 0.638811 -v 0.048644 -0.006577 0.101646 -vn 5.101998 2.922493 1.050636 -v 0.048823 -0.006760 0.101681 -vn 2.843436 5.164381 1.177795 -v 0.048477 -0.006577 0.102194 -vn 2.559019 5.164392 1.709868 -v 0.048207 -0.006577 0.102700 -vn 2.176272 5.164370 2.176270 -v 0.047843 -0.006577 0.103143 -vn 1.709875 5.164390 2.559013 -v 0.047400 -0.006577 0.103507 -vn 1.177781 5.164345 2.843458 -v 0.046894 -0.006577 0.103777 -vn 0.638806 5.186295 2.992044 -v 0.046346 -0.006577 0.103944 -vn 4.792997 2.940756 1.985318 -v 0.048646 -0.006760 0.102264 -vn 4.313591 2.940739 2.882241 -v 0.048359 -0.006760 0.102802 -vn 3.668413 2.940705 3.668410 -v 0.047973 -0.006760 0.103273 -vn 2.882232 2.940691 4.313602 -v 0.047502 -0.006760 0.103659 -vn 1.985341 2.940763 4.793028 -v 0.046964 -0.006760 0.103946 -vn 1.050626 2.922507 5.101974 -v 0.046381 -0.006760 0.104123 -vn 5.981387 0.794295 1.189775 -v 0.048889 -0.007010 0.101694 -vn 5.634345 0.796381 2.333821 -v 0.048708 -0.007010 0.102290 -vn 5.070773 0.794288 3.388190 -v 0.048415 -0.007010 0.102839 -vn 4.312355 0.796341 4.312349 -v 0.048020 -0.007010 0.103320 -vn 3.388184 0.794269 5.070784 -v 0.047539 -0.007010 0.103715 -vn 2.333841 0.796414 5.634327 -v 0.046990 -0.007010 0.104008 -vn 1.189762 0.794294 5.981384 -v 0.046394 -0.007010 0.104189 -vn -1.570793 1.570796 -1.570796 -v 0.035650 -0.034980 0.086750 -vn -1.570795 -1.570796 -1.570796 -v 0.035650 -0.029580 0.086750 -vn 1.570798 -1.570796 -1.570796 -v 0.022850 -0.029580 0.086750 -vn 1.570796 1.570796 -1.570796 -v 0.022850 -0.034980 0.086750 -vn -1.570798 -1.570796 1.570796 -v 0.035650 -0.029580 0.096350 -vn -1.570796 1.570796 1.570796 -v 0.035650 -0.034980 0.096350 -vn 1.570793 1.570796 1.570796 -v 0.022850 -0.034980 0.096350 -vn 1.570795 -1.570796 1.570796 -v 0.022850 -0.029580 0.096350 -vn -1.110707 -2.681531 2.356207 -v -0.000000 -0.032080 0.089775 -vn -1.110707 -3.926979 2.681530 -v -0.001700 -0.032080 0.089775 -vn -1.110707 -2.681530 -2.356207 -v -0.000000 -0.032080 0.093325 -vn -1.110734 -3.927004 -2.681503 -v -0.001700 -0.032080 0.093325 -vn -1.570796 -1.570796 -1.570796 -v -0.001350 -0.033480 0.090300 -vn -1.570796 1.570796 -1.570796 -v -0.001350 -0.032480 0.090300 -vn -1.570796 -1.570796 1.570796 -v -0.001350 -0.033480 0.092800 -vn -1.570796 1.570796 1.570796 -v -0.001350 -0.032480 0.092800 -vn 0.582607 2.013300 2.590072 -v 0.045050 -0.005410 0.091050 -vn -1.056237 0.685781 -0.000000 -v 0.046451 -0.005410 0.091550 -vn 0.582607 2.013300 -2.590071 -v 0.045050 -0.005410 0.092050 -vn 2.221450 1.570804 0.000000 -v 0.044550 -0.005410 0.091550 -vn -0.000000 -2.692811 3.062832 -v 0.044562 -0.036280 0.090300 -vn 0.000000 -3.590375 3.062832 -v 0.044562 -0.038080 0.090300 -vn -1.328907 -2.692778 2.759507 -v 0.045104 -0.036280 0.090424 -vn -1.328907 -3.590407 2.759507 -v 0.045104 -0.038080 0.090424 -vn -2.394623 -2.692801 1.909634 -v 0.045539 -0.036280 0.090771 -vn -2.394623 -3.590384 1.909634 -v 0.045539 -0.038080 0.090771 -vn -2.986035 -2.692794 0.681543 -v 0.045781 -0.036280 0.091272 -vn -2.986035 -3.590392 0.681543 -v 0.045781 -0.038080 0.091272 -vn -2.986035 -2.692794 -0.681543 -v 0.045781 -0.036280 0.091828 -vn -2.986035 -3.590392 -0.681543 -v 0.045781 -0.038080 0.091828 -vn -2.394610 -2.692791 -1.909644 -v 0.045539 -0.036280 0.092329 -vn -2.394610 -3.590394 -1.909644 -v 0.045539 -0.038080 0.092329 -vn -1.328914 -2.692802 -2.759513 -v 0.045104 -0.036280 0.092676 -vn -1.328914 -3.590384 -2.759513 -v 0.045104 -0.038080 0.092676 -vn 0.000000 -2.692784 -3.062823 -v 0.044562 -0.036280 0.092800 -vn -0.000000 -3.590400 -3.062823 -v 0.044562 -0.038080 0.092800 -vn 0.000002 -2.692786 3.062823 -v 0.045700 -0.034080 0.099750 -vn 0.000002 -3.590400 3.062824 -v 0.045700 -0.038080 0.099750 -vn -1.328912 -2.692800 2.759514 -v 0.046242 -0.034080 0.099874 -vn -1.328911 -3.590387 2.759513 -v 0.046242 -0.038080 0.099874 -vn -2.394610 -2.692791 1.909644 -v 0.046677 -0.034080 0.100221 -vn -2.394610 -3.590395 1.909644 -v 0.046677 -0.038080 0.100221 -vn -2.986034 -2.692794 0.681543 -v 0.046919 -0.034080 0.100722 -vn -2.986035 -3.590391 0.681543 -v 0.046919 -0.038080 0.100722 -vn -2.986039 -2.692800 -0.681535 -v 0.046919 -0.034080 0.101278 -vn -2.986039 -3.590386 -0.681534 -v 0.046919 -0.038080 0.101278 -vn -2.394614 -2.692784 -1.909636 -v 0.046677 -0.034080 0.101779 -vn -2.394614 -3.590401 -1.909636 -v 0.046677 -0.038080 0.101779 -vn -1.328911 -2.692800 -2.759513 -v 0.046242 -0.034080 0.102126 -vn -1.328912 -3.590385 -2.759514 -v 0.046242 -0.038080 0.102126 -vn 0.000002 -2.692786 -3.062824 -v 0.045700 -0.034080 0.102250 -vn 0.000002 -3.590399 -3.062823 -v 0.045700 -0.038080 0.102250 -vn 0.000002 -2.692786 3.062823 -v 0.045700 -0.034080 0.080840 -vn 0.000002 -3.590400 3.062824 -v 0.045700 -0.038080 0.080840 -vn -1.328912 -2.692800 2.759514 -v 0.046242 -0.034080 0.080964 -vn -1.328911 -3.590385 2.759513 -v 0.046242 -0.038080 0.080964 -vn -2.394610 -2.692791 1.909644 -v 0.046677 -0.034080 0.081311 -vn -2.394610 -3.590395 1.909644 -v 0.046677 -0.038080 0.081311 -vn -2.986034 -2.692794 0.681543 -v 0.046919 -0.034080 0.081812 -vn -2.986035 -3.590391 0.681543 -v 0.046919 -0.038080 0.081812 -vn -2.986035 -2.692794 -0.681543 -v 0.046919 -0.034080 0.082368 -vn -2.986034 -3.590392 -0.681543 -v 0.046919 -0.038080 0.082368 -vn -2.394623 -2.692801 -1.909634 -v 0.046677 -0.034080 0.082869 -vn -2.394623 -3.590384 -1.909633 -v 0.046677 -0.038080 0.082869 -vn -1.328904 -2.692777 -2.759507 -v 0.046242 -0.034080 0.083216 -vn -1.328904 -3.590409 -2.759508 -v 0.046242 -0.038080 0.083216 -vn 0.000002 -2.692812 -3.062833 -v 0.045700 -0.034080 0.083340 -vn 0.000002 -3.590374 -3.062833 -v 0.045700 -0.038080 0.083340 -vn -0.000002 3.590399 3.062824 -v 0.041450 -0.036780 0.084300 -vn -0.000002 -3.590399 3.062824 -v 0.041450 -0.038080 0.084300 -vn -1.328914 3.590384 2.759513 -v 0.041992 -0.036780 0.084424 -vn -1.328914 -3.590384 2.759513 -v 0.041992 -0.038080 0.084424 -vn -2.394614 3.590399 1.909636 -v 0.042427 -0.036780 0.084771 -vn -2.394614 -3.590401 1.909636 -v 0.042427 -0.038080 0.084771 -vn -2.986039 3.590386 0.681535 -v 0.042669 -0.036780 0.085272 -vn -2.986039 -3.590386 0.681535 -v 0.042669 -0.038080 0.085272 -vn -2.986039 3.590386 -0.681535 -v 0.042669 -0.036780 0.085828 -vn -2.986039 -3.590386 -0.681535 -v 0.042669 -0.038080 0.085828 -vn -2.394614 3.590401 -1.909636 -v 0.042427 -0.036780 0.086329 -vn -2.394614 -3.590401 -1.909636 -v 0.042427 -0.038080 0.086329 -vn -1.328914 3.590384 -2.759513 -v 0.041992 -0.036780 0.086676 -vn -1.328914 -3.590384 -2.759513 -v 0.041992 -0.038080 0.086676 -vn -0.000002 3.590400 -3.062824 -v 0.041450 -0.036780 0.086800 -vn -0.000002 -3.590400 -3.062824 -v 0.041450 -0.038080 0.086800 -vn -0.000002 3.590400 3.062824 -v 0.041450 -0.036780 0.096300 -vn -0.000002 -3.590400 3.062824 -v 0.041450 -0.038080 0.096300 -vn -1.328914 3.590383 2.759513 -v 0.041992 -0.036780 0.096424 -vn -1.328914 -3.590385 2.759513 -v 0.041992 -0.038080 0.096424 -vn -2.394610 3.590395 1.909644 -v 0.042427 -0.036780 0.096771 -vn -2.394610 -3.590395 1.909644 -v 0.042427 -0.038080 0.096771 -vn -2.986035 3.590391 0.681543 -v 0.042669 -0.036780 0.097272 -vn -2.986035 -3.590392 0.681543 -v 0.042669 -0.038080 0.097272 -vn -2.986035 3.590392 -0.681543 -v 0.042669 -0.036780 0.097828 -vn -2.986035 -3.590391 -0.681543 -v 0.042669 -0.038080 0.097828 -vn -2.394623 3.590385 -1.909634 -v 0.042427 -0.036780 0.098329 -vn -2.394623 -3.590384 -1.909634 -v 0.042427 -0.038080 0.098329 -vn -1.328907 3.590407 -2.759507 -v 0.041992 -0.036780 0.098676 -vn -1.328907 -3.590407 -2.759507 -v 0.041992 -0.038080 0.098676 -vn -0.000002 3.590373 -3.062833 -v 0.041450 -0.036780 0.098800 -vn -0.000002 -3.590374 -3.062833 -v 0.041450 -0.038080 0.098800 -vn -0.888773 -3.339137 -2.997454 -v 0.043007 -0.038080 0.082943 -vn 0.000000 -6.283164 0.000000 -v 0.043006 -0.038080 0.088550 -vn -0.296825 -3.331700 -3.113293 -v 0.042450 -0.038080 0.083050 -vn -2.846685 -2.748892 -1.179130 -v 0.039064 -0.038080 0.083976 -vn 2.394615 -3.590390 1.909640 -v 0.040473 -0.038080 0.084771 -vn -3.111411 -2.945246 -0.306443 -v 0.038950 -0.038080 0.084550 -vn 2.986035 -3.590392 0.681543 -v 0.040231 -0.038080 0.085272 -vn -3.096232 -2.900688 0.374761 -v 0.038950 -0.038080 0.087581 -vn 2.986035 -3.590392 -0.681543 -v 0.040231 -0.038080 0.085828 -vn 2.394615 -3.590390 -1.909640 -v 0.040473 -0.038080 0.086329 -vn 1.328917 -3.590389 -2.759509 -v 0.040908 -0.038080 0.086676 -vn -1.092404 -3.342154 2.928710 -v 0.040275 -0.038080 0.088310 -vn -1.565678 -3.279763 2.715750 -v 0.040709 -0.038080 0.088524 -vn -0.306445 -2.945245 -3.111411 -v 0.040450 -0.038080 0.083050 -vn 1.328917 -3.590389 2.759509 -v 0.040908 -0.038080 0.084424 -vn -1.179132 -2.748893 -2.846684 -v 0.039876 -0.038080 0.083164 -vn -2.178757 -2.748892 -2.178757 -v 0.039389 -0.038080 0.083489 -vn -2.703521 -2.659751 1.413759 -v 0.039007 -0.038080 0.087813 -vn -1.740574 -2.659765 2.505629 -v 0.039165 -0.038080 0.087992 -vn -0.961350 -3.032104 2.985944 -v 0.039388 -0.038080 0.088077 -vn -1.179132 -2.748893 2.846684 -v 0.039876 -0.038080 0.099936 -vn -2.178757 -2.748892 2.178757 -v 0.039389 -0.038080 0.099611 -vn -2.846684 -2.748895 1.179134 -v 0.039064 -0.038080 0.099124 -vn -0.888793 -3.339119 2.997450 -v 0.043007 -0.038080 0.100157 -vn -0.296845 -3.331713 3.113289 -v 0.042450 -0.038080 0.100050 -vn 1.328910 -3.590413 -2.759503 -v 0.040908 -0.038080 0.098676 -vn -0.306445 -2.945244 3.111411 -v 0.040450 -0.038080 0.100050 -vn 2.394624 -3.590374 -1.909638 -v 0.040473 -0.038080 0.098329 -vn -2.875615 -3.404410 1.196240 -v 0.042182 -0.038080 0.090206 -vn -2.466094 -3.404403 1.902246 -v 0.041721 -0.038080 0.089412 -vn -1.887214 -3.404410 -2.477615 -v 0.041071 -0.038080 0.094334 -vn -1.178734 -3.404401 -2.882837 -v 0.040275 -0.038080 0.094790 -vn 1.328917 -3.590389 2.759509 -v 0.040908 -0.038080 0.096424 -vn -0.961393 -3.032074 -2.985928 -v 0.039388 -0.038080 0.095023 -vn 2.394611 -3.590385 1.909648 -v 0.040473 -0.038080 0.096771 -vn -1.740617 -2.659795 -2.505613 -v 0.039165 -0.038080 0.095108 -vn -1.979554 -3.335267 2.420477 -v 0.041071 -0.038080 0.088766 -vn 2.986031 -3.590398 -0.681551 -v 0.040231 -0.038080 0.097828 -vn -3.111410 -2.945243 0.306447 -v 0.038950 -0.038080 0.098550 -vn 2.986031 -3.590397 0.681551 -v 0.040231 -0.038080 0.097272 -vn -3.096232 -2.900688 -0.374761 -v 0.038950 -0.038080 0.095519 -vn -2.703521 -2.659751 -1.413759 -v 0.039007 -0.038080 0.095287 -vn -2.466098 -3.404407 -1.902240 -v 0.041721 -0.038080 0.093688 -vn -2.875618 -3.404404 -1.196237 -v 0.042182 -0.038080 0.092894 -vn -3.087657 -3.404404 -0.408088 -v 0.042420 -0.038080 0.092009 -vn -3.087657 -3.404402 0.408084 -v 0.042420 -0.038080 0.091091 -vn 2.697425 -2.879793 1.557354 -v 0.048524 -0.038080 0.102660 -vn 2.202432 -2.879788 2.202440 -v 0.048019 -0.038080 0.103319 -vn 3.128154 -3.010691 0.205033 -v 0.048950 -0.038080 0.101070 -vn 3.141593 -3.141593 0.000000 -v 0.048950 -0.038080 0.088550 -vn 1.328907 -3.590407 2.759507 -v 0.044020 -0.038080 0.090424 -vn 2.394619 -3.590379 1.909642 -v 0.043585 -0.038080 0.090771 -vn 1.557356 -2.879800 2.697426 -v 0.047360 -0.038080 0.103824 -vn 0.806148 -2.879789 3.008584 -v 0.046593 -0.038080 0.104142 -vn 0.205027 -3.010695 3.128155 -v 0.045770 -0.038080 0.104250 -vn 1.328914 -3.590384 -2.759513 -v 0.045158 -0.038080 0.102126 -vn 2.394614 -3.590401 -1.909636 -v 0.044723 -0.038080 0.101779 -vn 2.986031 -3.590397 0.681551 -v 0.043343 -0.038080 0.091272 -vn 2.986031 -3.590398 -0.681551 -v 0.043343 -0.038080 0.091828 -vn 2.394606 -3.590389 -1.909653 -v 0.043585 -0.038080 0.092329 -vn 1.328914 -3.590385 -2.759513 -v 0.044020 -0.038080 0.092676 -vn 2.986034 -3.590392 0.681543 -v 0.044481 -0.038080 0.100722 -vn -2.178757 -3.534294 2.178757 -v 0.043511 -0.038080 0.100489 -vn 2.394610 -3.590422 1.909644 -v 0.044723 -0.038080 0.100221 -vn -1.464787 -3.344147 2.760999 -v 0.043024 -0.038080 0.100164 -vn 2.986039 -3.590386 -0.681535 -v 0.044481 -0.038080 0.101278 -vn -3.111410 -3.337942 0.306447 -v 0.043950 -0.038080 0.101550 -vn -2.846684 -3.534291 1.179134 -v 0.043836 -0.038080 0.100976 -vn 3.008585 -2.879797 0.806148 -v 0.048842 -0.038080 0.101893 -vn 1.328914 -3.590384 2.759512 -v 0.045158 -0.038080 0.099874 -vn 1.328906 -3.590407 -2.759507 -v 0.045158 -0.038080 0.083216 -vn 0.205027 -3.010695 -3.128155 -v 0.045770 -0.038080 0.078850 -vn 0.806148 -2.879788 -3.008584 -v 0.046593 -0.038080 0.078958 -vn 1.557356 -2.879800 -2.697426 -v 0.047360 -0.038080 0.079276 -vn -1.464787 -3.344146 -2.760999 -v 0.043024 -0.038080 0.082936 -vn 1.328914 -3.590384 2.759512 -v 0.045158 -0.038080 0.080964 -vn 2.394610 -3.590395 1.909644 -v 0.044723 -0.038080 0.081311 -vn -3.111411 -3.337940 -0.306443 -v 0.043950 -0.038080 0.081550 -vn 2.986034 -3.590392 0.681543 -v 0.044481 -0.038080 0.081812 -vn -2.846685 -3.534294 -1.179130 -v 0.043836 -0.038080 0.082124 -vn 2.986035 -3.590392 -0.681543 -v 0.044481 -0.038080 0.082368 -vn 2.394623 -3.590384 -1.909634 -v 0.044723 -0.038080 0.082869 -vn -2.178757 -3.534294 -2.178757 -v 0.043511 -0.038080 0.082611 -vn 3.128154 -3.010691 -0.205033 -v 0.048950 -0.038080 0.082030 -vn 3.008585 -2.879797 -0.806148 -v 0.048842 -0.038080 0.081207 -vn 2.697425 -2.879792 -1.557354 -v 0.048524 -0.038080 0.080440 -vn 2.202432 -2.879788 -2.202440 -v 0.048019 -0.038080 0.079781 -vn 1.328914 -2.692802 -2.759513 -v 0.044020 -0.036280 0.092676 -vn 2.394606 -2.692796 -1.909653 -v 0.043585 -0.036280 0.092329 -vn 2.986031 -2.692788 -0.681551 -v 0.043343 -0.036280 0.091828 -vn 2.986031 -2.692787 0.681551 -v 0.043343 -0.036280 0.091272 -vn 2.394619 -2.692807 1.909642 -v 0.043585 -0.036280 0.090771 -vn 1.328907 -2.692778 2.759507 -v 0.044020 -0.036280 0.090424 -vn 1.328914 -2.692801 -2.759512 -v 0.045158 -0.034080 0.102126 -vn 2.394614 -2.692785 -1.909636 -v 0.044723 -0.034080 0.101779 -vn 2.986039 -2.692799 -0.681534 -v 0.044481 -0.034080 0.101278 -vn 2.986035 -2.692794 0.681543 -v 0.044481 -0.034080 0.100722 -vn 2.394610 -2.692791 1.909644 -v 0.044723 -0.034080 0.100221 -vn 1.328914 -2.692802 2.759513 -v 0.045158 -0.034080 0.099874 -vn 1.328907 -2.692777 -2.759507 -v 0.045158 -0.034080 0.083216 -vn 2.394623 -2.692801 -1.909633 -v 0.044723 -0.034080 0.082869 -vn 2.986034 -2.692794 -0.681543 -v 0.044481 -0.034080 0.082368 -vn 2.986035 -2.692794 0.681543 -v 0.044481 -0.034080 0.081812 -vn 2.394610 -2.692791 1.909644 -v 0.044723 -0.034080 0.081311 -vn 1.328914 -2.692802 2.759513 -v 0.045158 -0.034080 0.080964 -vn 1.328917 3.590389 -2.759509 -v 0.040908 -0.036780 0.086676 -vn 2.394615 3.590390 -1.909640 -v 0.040473 -0.036780 0.086329 -vn 2.986035 3.590392 -0.681543 -v 0.040231 -0.036780 0.085828 -vn 2.986035 3.590392 0.681543 -v 0.040231 -0.036780 0.085272 -vn 2.394615 3.590391 1.909640 -v 0.040473 -0.036780 0.084771 -vn 1.328917 3.590389 2.759509 -v 0.040908 -0.036780 0.084424 -vn 1.328910 3.590413 -2.759504 -v 0.040908 -0.036780 0.098676 -vn 2.394624 3.590374 -1.909638 -v 0.040473 -0.036780 0.098329 -vn 2.986031 3.590398 -0.681551 -v 0.040231 -0.036780 0.097828 -vn 2.986031 3.590397 0.681551 -v 0.040231 -0.036780 0.097272 -vn 2.394611 3.590384 1.909649 -v 0.040473 -0.036780 0.096771 -vn 1.328917 3.590389 2.759509 -v 0.040908 -0.036780 0.096424 -vn -3.096232 2.900689 0.374761 -v 0.038950 -0.036080 0.087581 -vn -1.404618 1.464806 -1.561982 -v 0.038950 -0.036080 0.087250 -vn -4.546211 1.676787 -1.561981 -v 0.038950 -0.036780 0.087250 -vn -3.111411 2.945245 -0.306443 -v 0.038950 -0.036780 0.084550 -vn -2.846685 2.748892 -1.179130 -v 0.039064 -0.036780 0.083976 -vn -2.178757 2.748892 -2.178757 -v 0.039389 -0.036780 0.083489 -vn -1.179132 2.748893 -2.846684 -v 0.039876 -0.036780 0.083164 -vn -0.306445 2.945245 -3.111411 -v 0.040450 -0.036780 0.083050 -vn -0.303928 3.334785 -3.111907 -v 0.042450 -0.036780 0.083050 -vn -6.253004 0.196347 -0.306443 -v 0.043950 -0.036780 0.081550 -vn -2.846685 3.534294 -1.179130 -v 0.043836 -0.036780 0.082124 -vn -2.178757 3.534294 -2.178757 -v 0.043511 -0.036780 0.082611 -vn -1.181798 3.530056 -2.846145 -v 0.043024 -0.036780 0.082936 -vn -6.253002 0.196349 0.306447 -v 0.043950 -0.036780 0.101550 -vn -4.712389 1.570796 -1.570796 -v 0.043950 -0.033880 0.079550 -vn -1.570796 1.570794 -1.570796 -v 0.043950 -0.036780 0.089448 -vn -4.712389 1.570796 -1.570796 -v 0.043950 -0.036080 0.089448 -vn -4.712389 1.570796 1.570796 -v 0.043950 -0.036080 0.093652 -vn -1.570796 1.570796 1.570796 -v 0.043950 -0.036780 0.093652 -vn -4.712389 1.570796 1.570796 -v 0.043950 -0.033880 0.103550 -vn -1.570797 1.570797 1.570796 -v 0.043950 -0.032880 0.103550 -vn -1.570796 1.570796 -1.570796 -v 0.043950 -0.032880 0.079550 -vn 0.205027 3.010695 -3.128155 -v 0.045770 -0.033880 0.078850 -vn 3.128154 3.010691 -0.205033 -v 0.048950 -0.033880 0.082030 -vn 3.008585 2.879797 -0.806148 -v 0.048842 -0.033880 0.081207 -vn 2.697425 2.879792 -1.557354 -v 0.048524 -0.033880 0.080440 -vn 2.202432 2.879788 -2.202440 -v 0.048019 -0.033880 0.079781 -vn 1.557356 2.879800 -2.697426 -v 0.047360 -0.033880 0.079276 -vn 0.806148 2.879789 -3.008584 -v 0.046593 -0.033880 0.078958 -vn 3.128154 3.010691 0.205033 -v 0.048950 -0.033880 0.101070 -vn 0.205027 3.010695 3.128155 -v 0.045770 -0.033880 0.104250 -vn 0.806148 2.879789 3.008584 -v 0.046593 -0.033880 0.104142 -vn 1.557356 2.879800 2.697426 -v 0.047360 -0.033880 0.103824 -vn 2.202432 2.879788 2.202440 -v 0.048019 -0.033880 0.103319 -vn 2.697425 2.879792 1.557354 -v 0.048524 -0.033880 0.102660 -vn 3.008585 2.879797 0.806148 -v 0.048842 -0.033880 0.101893 -vn -2.846684 3.534291 1.179134 -v 0.043836 -0.036780 0.100976 -vn -2.178757 3.534294 2.178757 -v 0.043511 -0.036780 0.100489 -vn -1.181817 3.530044 2.846141 -v 0.043024 -0.036780 0.100164 -vn -0.303947 3.334798 3.111904 -v 0.042450 -0.036780 0.100050 -vn -0.306445 2.945245 3.111411 -v 0.040450 -0.036780 0.100050 -vn -3.111410 2.945243 0.306447 -v 0.038950 -0.036780 0.098550 -vn -2.846684 2.748894 1.179134 -v 0.039064 -0.036780 0.099124 -vn -2.178757 2.748892 2.178757 -v 0.039389 -0.036780 0.099611 -vn -1.179132 2.748893 2.846684 -v 0.039876 -0.036780 0.099936 -vn -1.404618 1.464806 1.561981 -v 0.038950 -0.036080 0.095850 -vn -3.096232 2.900689 -0.374761 -v 0.038950 -0.036080 0.095519 -vn -4.546211 1.676787 1.561982 -v 0.038950 -0.036780 0.095850 -vn -1.165860 3.384341 2.890037 -v 0.040275 -0.036080 0.088310 -vn -0.961350 3.032103 2.985944 -v 0.039388 -0.036080 0.088077 -vn -1.900010 3.383992 2.470129 -v 0.041071 -0.036080 0.088766 -vn -2.466094 3.404402 1.902246 -v 0.041721 -0.036080 0.089412 -vn -2.875615 3.404410 1.196240 -v 0.042182 -0.036080 0.090206 -vn -3.087658 3.404402 0.408084 -v 0.042420 -0.036080 0.091091 -vn -3.087657 3.404404 -0.408088 -v 0.042420 -0.036080 0.092009 -vn -2.875618 3.404404 -1.196237 -v 0.042182 -0.036080 0.092894 -vn -2.466098 3.404407 -1.902240 -v 0.041721 -0.036080 0.093688 -vn -1.887214 3.404410 -2.477615 -v 0.041071 -0.036080 0.094334 -vn -1.178734 3.404401 -2.882837 -v 0.040275 -0.036080 0.094790 -vn -0.961393 3.032074 -2.985928 -v 0.039388 -0.036080 0.095023 -vn 0.657287 3.353584 -3.054031 -v 0.039855 -0.036780 0.087346 -vn 1.285159 3.353582 -2.847367 -v 0.040719 -0.036780 0.087631 -vn 1.855486 3.353578 -2.513227 -v 0.041504 -0.036780 0.088091 -vn 2.342744 3.353584 -2.066563 -v 0.042175 -0.036780 0.088705 -vn 1.281308 2.187644 -2.479450 -v 0.042701 -0.036780 0.089448 -vn 1.281303 2.187649 2.479456 -v 0.042701 -0.036780 0.093652 -vn 2.342746 3.353573 2.066563 -v 0.042175 -0.036780 0.094395 -vn 1.855493 3.353584 2.513220 -v 0.041504 -0.036780 0.095009 -vn 1.285159 3.353582 2.847367 -v 0.040719 -0.036780 0.095469 -vn 0.657287 3.353584 3.054031 -v 0.039855 -0.036780 0.095754 -vn -2.703521 2.659751 1.413759 -v 0.039007 -0.036080 0.087813 -vn -1.740574 2.659765 2.505629 -v 0.039165 -0.036080 0.087992 -vn 1.281303 4.095536 2.479456 -v 0.042701 -0.036080 0.093652 -vn 0.657287 2.929601 3.054031 -v 0.039855 -0.036080 0.095754 -vn 1.285159 2.929603 2.847367 -v 0.040719 -0.036080 0.095469 -vn 0.657287 2.929602 -3.054031 -v 0.039855 -0.036080 0.087346 -vn 1.855494 2.929601 2.513221 -v 0.041504 -0.036080 0.095009 -vn 2.342746 2.929611 2.066563 -v 0.042175 -0.036080 0.094395 -vn 1.281308 4.095541 -2.479450 -v 0.042701 -0.036080 0.089448 -vn 1.285159 2.929603 -2.847367 -v 0.040719 -0.036080 0.087631 -vn 1.855486 2.929607 -2.513227 -v 0.041504 -0.036080 0.088091 -vn 2.342744 2.929601 -2.066563 -v 0.042175 -0.036080 0.088705 -vn -2.703521 2.659751 -1.413759 -v 0.039007 -0.036080 0.095287 -vn -1.740617 2.659794 -2.505612 -v 0.039165 -0.036080 0.095108 -vn 0.245722 2.984517 -3.122254 -v 0.045770 -0.032880 0.079550 -vn 0.245736 2.984506 3.122252 -v 0.045770 -0.032880 0.103550 -vn 1.823854 2.827445 -2.510309 -v 0.047228 -0.032880 0.080024 -vn 0.958859 2.827422 -2.951042 -v 0.046536 -0.032880 0.079671 -vn 2.510309 2.827426 -1.823847 -v 0.047776 -0.032880 0.080572 -vn 2.951049 2.827439 -0.958852 -v 0.048129 -0.032880 0.081264 -vn 1.823842 2.827436 2.510315 -v 0.047228 -0.032880 0.103076 -vn 2.510309 2.827426 1.823847 -v 0.047776 -0.032880 0.102528 -vn 0.958861 2.827441 2.951046 -v 0.046536 -0.032880 0.103429 -vn 2.951049 2.827439 0.958852 -v 0.048129 -0.032880 0.101836 -vn 3.122253 2.984511 0.245730 -v 0.048250 -0.032880 0.101070 -vn 3.122253 2.984511 -0.245730 -v 0.048250 -0.032880 0.082030 -vn 0.245722 3.298669 -3.122254 -v 0.045770 -0.033880 0.079550 -vn 0.958859 3.455762 -2.951042 -v 0.046536 -0.033880 0.079671 -vn 1.823854 3.455741 -2.510309 -v 0.047228 -0.033880 0.080024 -vn 2.510309 3.455759 -1.823847 -v 0.047776 -0.033880 0.080572 -vn 2.510309 3.455759 1.823847 -v 0.047776 -0.033880 0.102528 -vn 2.951049 3.455747 0.958852 -v 0.048129 -0.033880 0.101836 -vn 3.122253 3.298675 0.245730 -v 0.048250 -0.033880 0.101070 -vn 3.122253 3.298675 -0.245730 -v 0.048250 -0.033880 0.082030 -vn 2.951049 3.455746 -0.958852 -v 0.048129 -0.033880 0.081264 -vn 0.245736 3.298678 3.122252 -v 0.045770 -0.033880 0.103550 -vn 0.958861 3.455745 2.951046 -v 0.046536 -0.033880 0.103429 -vn 1.823842 3.455750 2.510315 -v 0.047228 -0.033880 0.103076 -vn 4.520946 1.210824 -3.903148 -v 0.007976 -0.041610 0.100524 -vn 3.946144 0.252486 -4.837389 -v 0.007917 -0.041610 0.100468 -vn 3.892036 1.473907 -4.456038 -v 0.007916 -0.041581 0.100469 -vn 2.739936 1.467132 -5.245538 -v 0.007475 -0.041581 0.100169 -vn -0.489101 6.145101 -0.779670 -v 0.005880 -0.041410 0.100362 -vn -0.259308 6.187852 -0.721012 -v 0.005997 -0.041410 0.100307 -vn -1.096458 5.322638 -2.632458 -v 0.005962 -0.041431 0.100225 -vn 0.906700 6.119452 -0.422627 -v 0.008217 -0.041410 0.101257 -vn 0.753298 6.186734 -0.160928 -v 0.008270 -0.041410 0.101423 -vn 2.760837 5.322851 -0.710727 -v 0.008357 -0.041431 0.101400 -vn 2.845362 5.323622 0.088818 -v 0.008414 -0.041431 0.101899 -vn 0.796605 6.179494 -0.066909 -v 0.008325 -0.041410 0.101850 -vn 0.757567 6.189262 0.072615 -v 0.008324 -0.041410 0.101897 -vn 0.677292 6.184789 -0.381481 -v 0.008084 -0.041410 0.100984 -vn 2.445645 5.323568 -1.459204 -v 0.008161 -0.041431 0.100938 -vn 0.687581 6.154077 -0.566789 -v 0.007926 -0.041410 0.100765 -vn 1.931375 5.320551 -2.112622 -v 0.007843 -0.041431 0.100549 -vn 0.505686 6.190105 -0.564452 -v 0.007782 -0.041410 0.100615 -vn 0.498427 6.154277 -0.737790 -v 0.007557 -0.041410 0.100441 -vn 1.247596 5.321816 -2.569721 -v 0.007428 -0.041431 0.100266 -vn 0.314773 6.188356 -0.696491 -v 0.007388 -0.041410 0.100346 -vn 0.234909 6.172725 -0.790932 -v 0.007019 -0.041410 0.100216 -vn 0.467765 5.322245 -2.814887 -v 0.006950 -0.041431 0.100111 -vn 0.083033 6.188228 -0.760414 -v 0.006935 -0.041410 0.100199 -vn -0.317599 5.323427 -2.829915 -v 0.006448 -0.041431 0.100097 -vn -0.035267 6.188860 -0.761844 -v 0.006458 -0.041410 0.100186 -vn -0.177978 6.179683 -0.778575 -v 0.006415 -0.041410 0.100191 -vn -0.470520 6.185470 -0.615521 -v 0.005589 -0.041410 0.100554 -vn -1.791384 5.323670 -2.213315 -v 0.005532 -0.041431 0.100484 -vn -0.659998 6.153264 -0.602768 -v 0.005403 -0.041410 0.100732 -vn -2.365344 5.321592 -1.602572 -v 0.005193 -0.041431 0.100855 -vn -0.645291 6.187338 -0.416753 -v 0.005266 -0.041410 0.100905 -vn -0.753638 6.171174 -0.349694 -v 0.005089 -0.041410 0.101244 -vn -2.719665 5.322293 -0.863060 -v 0.004971 -0.041431 0.101306 -vn -0.741049 6.188048 -0.192160 -v 0.005057 -0.041410 0.101333 -vn -2.845317 5.323655 -0.088824 -v 0.004886 -0.041431 0.101801 -vn -0.757551 6.189266 -0.072615 -v 0.004976 -0.041410 0.101803 -vn -6.219997 0.244109 -0.559867 -v 0.004776 -0.041610 0.101798 -vn -5.908063 1.475862 -0.302120 -v 0.004778 -0.041581 0.101798 -vn -6.019441 0.250945 -1.632239 -v 0.004866 -0.041610 0.101272 -vn -5.672001 1.460407 -1.689763 -v 0.004868 -0.041581 0.101272 -vn -5.290777 1.477505 -2.455391 -v 0.004918 -0.041610 0.101132 -vn -4.897290 1.447634 -3.326671 -v 0.005103 -0.041581 0.100794 -vn -3.646094 1.451360 -4.661920 -v 0.005464 -0.041581 0.100401 -vn -4.186936 1.599020 -3.941182 -v 0.005324 -0.041610 0.100524 -vn -5.156904 0.235691 -3.497669 -v 0.005102 -0.041610 0.100793 -vn 1.042799 1.447902 -5.827669 -v 0.006968 -0.041581 0.100004 -vn 0.101574 1.668445 -5.707230 -v 0.006650 -0.041610 0.099975 -vn -0.799849 1.443377 -5.863956 -v 0.006435 -0.041581 0.099989 -vn -0.959752 0.249015 -6.155946 -v 0.006435 -0.041610 0.099987 -vn -2.304058 1.358092 -5.443226 -v 0.005920 -0.041581 0.100125 -vn -2.413866 0.271297 -5.705050 -v 0.005919 -0.041610 0.100123 -vn -3.730118 0.240770 -4.993833 -v 0.005462 -0.041610 0.100399 -vn 3.042316 0.236196 -5.447305 -v 0.007476 -0.041610 0.100167 -vn 1.966002 1.318409 -5.577275 -v 0.007368 -0.041610 0.100118 -vn 1.145283 0.230752 -6.124733 -v 0.006969 -0.041610 0.100002 -vn 5.245272 0.263601 -3.354758 -v 0.008255 -0.041610 0.100881 -vn 5.013715 1.425800 -3.143322 -v 0.008253 -0.041581 0.100882 -vn 5.234230 1.704329 -2.206378 -v 0.008382 -0.041610 0.101132 -vn 5.746018 1.447444 -1.422325 -v 0.008461 -0.041581 0.101373 -vn 6.070888 0.236384 -1.405597 -v 0.008463 -0.041610 0.101372 -vn 6.117670 0.794077 -0.449338 -v 0.008525 -0.041610 0.101850 -vn 5.908063 1.475926 0.302190 -v 0.008522 -0.041581 0.101902 -vn 6.220003 0.244115 0.560071 -v 0.008524 -0.041610 0.101902 -vn 4.875384 3.420779 0.136438 -v 0.008487 -0.041494 0.101901 -vn 4.716290 3.420847 -1.242641 -v 0.008427 -0.041494 0.101382 -vn 4.175190 3.420811 -2.521038 -v 0.008223 -0.041494 0.100900 -vn 3.295785 3.420716 -3.595241 -v 0.007892 -0.041494 0.100495 -vn 2.149373 3.420875 -4.378060 -v 0.007460 -0.041494 0.100200 -vn 0.828879 3.420786 -4.806333 -v 0.006962 -0.041494 0.100039 -vn -0.558773 3.420864 -4.845125 -v 0.006439 -0.041494 0.100024 -vn -1.901205 3.420845 -4.491426 -v 0.005934 -0.041494 0.100158 -vn -3.089609 3.420779 -3.773914 -v 0.005486 -0.041494 0.100428 -vn -4.027696 3.420819 -2.750622 -v 0.005133 -0.041494 0.100814 -vn -4.639453 3.420755 -1.504456 -v 0.004902 -0.041494 0.101283 -vn -4.875356 3.420795 -0.136453 -v 0.004813 -0.041494 0.101799 -vn -5.503509 -0.940512 2.593573 -v 0.004918 -0.042410 0.102568 -vn -5.896096 -0.776676 1.656714 -v 0.004873 -0.042410 0.102449 -vn -4.986582 -2.804529 1.638801 -v 0.004919 -0.042600 0.102434 -vn 1.176910 -6.040431 0.691876 -v 0.007963 -0.042807 0.102622 -vn 0.179304 -6.276206 0.105408 -v 0.007922 -0.042810 0.102598 -vn 0.201717 -6.276207 0.050757 -v 0.008081 -0.042810 0.102209 -vn 0.934322 -6.040428 0.995428 -v 0.007693 -0.042807 0.102961 -vn 0.142346 -6.276206 0.151655 -v 0.007659 -0.042810 0.102925 -vn 0.247823 -6.040424 1.342539 -v 0.006927 -0.042807 0.103348 -vn 0.037751 -6.276207 0.204521 -v 0.006918 -0.042810 0.103300 -vn 0.093851 -6.276206 0.185612 -v 0.007316 -0.042810 0.103166 -vn -0.021397 -6.276207 0.206891 -v 0.006498 -0.042810 0.103317 -vn -0.140443 -6.040437 1.357955 -v 0.006493 -0.042807 0.103365 -vn 0.628489 -4.912678 3.404586 -v 0.006958 -0.042742 0.103521 -vn -1.118259 -6.040429 0.783145 -v 0.005402 -0.042807 0.102724 -vn -0.170367 -6.276206 0.119310 -v 0.005442 -0.042810 0.102696 -vn -0.129856 -6.276205 0.162483 -v 0.005729 -0.042810 0.103002 -vn -1.293612 -6.040424 0.436354 -v 0.005206 -0.042807 0.102337 -vn -0.197079 -6.276207 0.066477 -v 0.005252 -0.042810 0.102321 -vn -1.369962 -6.040128 0.060523 -v 0.005128 -0.042807 0.101911 -vn -0.199917 -6.276722 0.020991 -v 0.005176 -0.042810 0.101909 -vn 1.324161 -6.040431 0.332274 -v 0.008128 -0.042807 0.102221 -vn 1.369661 -6.040112 -0.059494 -v 0.008172 -0.042807 0.101789 -vn 3.459409 -4.912632 -0.137552 -v 0.008347 -0.042742 0.101783 -vn 2.427373 -2.816443 4.654120 -v 0.007474 -0.042600 0.103481 -vn 1.562217 -4.912673 3.089634 -v 0.007417 -0.042742 0.103366 -vn 0.616034 -6.040412 1.218369 -v 0.007337 -0.042807 0.103210 -vn -1.311971 -4.912638 3.203921 -v 0.006006 -0.042742 0.103422 -vn -2.161467 -4.912638 2.704523 -v 0.005589 -0.042742 0.103177 -vn -0.852332 -6.040430 1.066471 -v 0.005699 -0.042807 0.103040 -vn -3.221534 -2.814966 4.145695 -v 0.005509 -0.042600 0.103277 -vn -1.992917 -2.746299 4.866887 -v 0.005958 -0.042600 0.103541 -vn -0.588540 -2.807169 5.216098 -v 0.006462 -0.042600 0.103667 -vn 5.244529 -2.801488 -0.253591 -v 0.008476 -0.042600 0.101777 -vn 6.101410 -0.768181 -0.602064 -v 0.008524 -0.042410 0.101776 -vn 6.112474 -0.829721 0.325854 -v 0.008525 -0.042410 0.101850 -vn 3.358037 -4.912616 0.842655 -v 0.008298 -0.042742 0.102263 -vn 5.093787 -2.764914 1.302398 -v 0.008422 -0.042600 0.102295 -vn 5.923236 -0.818676 1.410978 -v 0.008469 -0.042410 0.102306 -vn 4.510595 -2.816104 2.685478 -v 0.008225 -0.042600 0.102776 -vn 2.984608 -4.912628 1.754576 -v 0.008114 -0.042742 0.102711 -vn 0.233624 -6.274386 0.022912 -v 0.008125 -0.042810 0.101850 -vn 0.199867 -6.276726 -0.020992 -v 0.008124 -0.042810 0.101791 -vn 5.583275 -1.154750 2.182423 -v 0.008382 -0.042410 0.102568 -vn 5.187799 -0.768532 3.235273 -v 0.008266 -0.042410 0.102800 -vn 4.565997 -0.823127 4.083297 -v 0.007976 -0.042410 0.103176 -vn 2.369384 -4.912642 2.524365 -v 0.007813 -0.042742 0.103089 -vn 3.566510 -2.794338 3.854851 -v 0.007900 -0.042600 0.103182 -vn 3.919955 -0.778992 4.716831 -v 0.007933 -0.042410 0.103217 -vn 3.031512 -0.762631 5.319065 -v 0.007496 -0.042410 0.103523 -vn 2.123324 -0.868411 5.723132 -v 0.007368 -0.042410 0.103582 -vn 0.912551 -2.780891 5.176075 -v 0.006982 -0.042600 0.103647 -vn -0.356169 -4.912626 3.443758 -v 0.006475 -0.042742 0.103540 -vn -0.517350 -6.040430 1.263405 -v 0.006073 -0.042807 0.103260 -vn -0.078823 -6.276205 0.192496 -v 0.006091 -0.042810 0.103215 -vn 1.102739 -0.797312 5.994423 -v 0.006990 -0.042410 0.103694 -vn 0.208568 -1.046826 6.038547 -v 0.006650 -0.042410 0.103725 -vn -0.887094 -0.773766 6.050691 -v 0.006457 -0.042410 0.103715 -vn -2.296810 -0.787023 5.612320 -v 0.005939 -0.042410 0.103585 -vn -3.615558 -0.765364 4.929555 -v 0.005479 -0.042410 0.103315 -vn -4.387062 -0.909527 4.228877 -v 0.005324 -0.042410 0.103176 -vn -2.835858 -4.912651 1.986006 -v 0.005258 -0.042742 0.102825 -vn -4.336405 -2.795583 2.966357 -v 0.005153 -0.042600 0.102898 -vn -5.050225 -0.791262 3.424988 -v 0.005114 -0.042410 0.102926 -vn -3.280518 -4.912639 1.106601 -v 0.005040 -0.042742 0.102393 -vn -3.459321 -4.912663 0.137564 -v 0.004953 -0.042742 0.101917 -vn -5.244527 -2.801482 0.253596 -v 0.004824 -0.042600 0.101923 -vn -6.101403 -0.768179 0.601989 -v 0.004776 -0.042410 0.101924 -vn -1.747748 -2.525902 4.227680 -v 0.006186 -0.009863 0.102736 -vn -1.267479 -2.536558 4.367491 -v 0.006337 -0.009848 0.102800 -vn -2.566232 2.608404 3.711346 -v 0.006133 -0.009770 0.102706 -vn 0.081428 2.630923 -4.550735 -v 0.006650 -0.010018 0.100850 -vn -0.460276 -2.634633 -4.521331 -v 0.006650 -0.010117 0.100850 -vn -0.622930 2.588491 -4.533434 -v 0.006411 -0.009995 0.100879 -vn -1.441468 -2.620018 -4.261339 -v 0.006382 -0.010091 0.100887 -vn -1.296586 2.606288 -4.365760 -v 0.006363 -0.009990 0.100892 -vn -2.455889 -2.616044 -3.821541 -v 0.006133 -0.010065 0.100994 -vn -1.885275 2.566629 -4.119708 -v 0.006159 -0.009969 0.100979 -vn -2.963521 -2.647947 -3.485158 -v 0.006045 -0.010055 0.101054 -vn -2.596088 2.656323 -3.751820 -v 0.006033 -0.009955 0.101063 -vn -3.355365 -2.705132 -3.105383 -v 0.005943 -0.010042 0.101143 -vn -3.095207 2.663883 -3.327394 -v 0.005943 -0.009943 0.101143 -vn -3.618169 -2.625149 -2.738461 -v 0.005917 -0.010039 0.101170 -vn -3.731265 2.570671 -2.544074 -v 0.005794 -0.009920 0.101333 -vn -4.062304 -2.557628 -2.000962 -v 0.005779 -0.010017 0.101359 -vn -4.274904 2.627832 -1.432586 -v 0.005687 -0.009894 0.101581 -vn -4.271096 -2.395804 -1.531064 -v 0.005716 -0.010002 0.101493 -vn -4.504620 -2.573130 -0.690323 -v 0.005679 -0.009991 0.101611 -vn -4.487177 2.567201 -0.255276 -v 0.005650 -0.009868 0.101850 -vn -4.510019 -2.560158 0.248048 -v 0.005650 -0.009968 0.101850 -vn -4.524709 2.638773 0.615406 -v 0.005679 -0.009845 0.102089 -vn -4.398156 -2.632757 1.192130 -v 0.005680 -0.009944 0.102092 -vn -4.423710 2.687498 1.201384 -v 0.005691 -0.009841 0.102132 -vn -4.163028 -2.577273 1.899506 -v 0.005711 -0.009934 0.102194 -vn -4.104951 2.630948 1.959290 -v 0.005779 -0.009819 0.102341 -vn -3.817631 -2.627604 2.472567 -v 0.005778 -0.009918 0.102339 -vn -3.786496 2.547497 2.564152 -v 0.005860 -0.009805 0.102463 -vn -3.085638 -2.626223 3.306260 -v 0.005917 -0.009895 0.102530 -vn -3.245552 2.520294 3.171508 -v 0.005943 -0.009793 0.102557 -vn -2.364899 -2.611505 3.880968 -v 0.006128 -0.009870 0.102703 -vn -0.031552 -2.633339 4.584070 -v 0.006606 -0.009821 0.102849 -vn 0.395905 -2.702007 4.554161 -v 0.006650 -0.009816 0.102850 -vn -0.356398 2.694252 4.524610 -v 0.006650 -0.009718 0.102850 -vn -0.429129 -2.559675 4.552664 -v 0.006502 -0.009831 0.102839 -vn -1.154845 2.636143 4.429643 -v 0.006422 -0.009740 0.102824 -vn -1.646851 2.644018 4.247355 -v 0.006382 -0.009744 0.102813 -vn -4.523552 2.559063 -0.220229 -v 0.005650 -0.020668 0.101850 -vn -4.404321 2.630676 -1.155260 -v 0.005687 -0.020684 0.101582 -vn -4.501925 -2.643140 -0.698740 -v 0.005682 -0.021026 0.101606 -vn 0.219152 2.620065 -4.543344 -v 0.006650 -0.020762 0.100850 -vn -0.461277 2.665037 -4.555440 -v 0.006502 -0.020753 0.100861 -vn -1.127997 3.553610 -2.860182 -v 0.006320 -0.041410 0.100906 -vn -3.225414 2.858523 -2.235905 -v 0.005825 -0.021078 0.101284 -vn -4.892152 0.014345 -3.930521 -v 0.005864 -0.021082 0.101231 -vn -2.249700 3.633116 -2.054530 -v 0.005912 -0.041410 0.101175 -vn -4.398145 -2.620865 -1.314622 -v 0.005706 -0.021037 0.101525 -vn -4.207271 2.639972 -1.786144 -v 0.005704 -0.020688 0.101525 -vn -3.833989 2.603974 -2.423935 -v 0.005794 -0.020701 0.101333 -vn -3.573978 -2.847302 -1.861872 -v 0.005829 -0.021074 0.101280 -vn -3.432049 2.666842 -3.026841 -v 0.005890 -0.020710 0.101200 -vn -2.940103 2.615211 -3.464053 -v 0.005943 -0.020715 0.101143 -vn -2.077790 2.546925 -3.974939 -v 0.006159 -0.020731 0.100979 -vn -1.127733 2.617721 -4.399814 -v 0.006411 -0.020747 0.100879 -vn -4.388111 -2.605015 0.071655 -v 0.005652 -0.021001 0.101793 -vn -4.349364 -2.664355 1.079590 -v 0.005671 -0.020966 0.102056 -vn -4.446852 2.600680 0.796036 -v 0.005679 -0.020645 0.102089 -vn -4.256289 -2.661418 1.616829 -v 0.005680 -0.020961 0.102094 -vn -4.281603 2.637784 1.613908 -v 0.005748 -0.020626 0.102283 -vn -3.766732 -2.592264 2.419960 -v 0.005764 -0.020930 0.102312 -vn -0.683055 -2.594376 4.526266 -v 0.006376 -0.020823 0.102812 -vn 0.268748 -2.553373 4.504358 -v 0.006650 -0.020786 0.102850 -vn -0.330531 2.566854 4.502442 -v 0.006650 -0.020519 0.102850 -vn -1.271428 2.611489 4.351166 -v 0.006382 -0.020545 0.102813 -vn -1.974448 2.634006 4.124795 -v 0.006285 -0.020554 0.102781 -vn -1.313296 -2.618862 4.389474 -v 0.006319 -0.020831 0.102795 -vn -2.576453 2.604752 3.756730 -v 0.006133 -0.020570 0.102706 -vn -2.113757 -2.576954 3.960737 -v 0.006129 -0.020859 0.102705 -vn -3.161959 2.639047 3.319826 -v 0.005975 -0.020589 0.102588 -vn -3.047115 -2.547225 3.270240 -v 0.005924 -0.020894 0.102537 -vn -3.566869 2.615300 2.845198 -v 0.005943 -0.020593 0.102557 -vn -3.959299 2.587721 2.231189 -v 0.005779 -0.020619 0.102341 -vn -4.360342 2.713700 0.630526 -v 0.005673 -0.021030 0.102062 -vn -4.527091 2.671343 0.027111 -v 0.005650 -0.021041 0.101864 -vn -2.954368 3.631941 0.745115 -v 0.005680 -0.041410 0.102094 -vn -4.235602 2.787867 -0.575821 -v 0.005652 -0.021046 0.101792 -vn -2.954027 3.633077 -0.745758 -v 0.005680 -0.041410 0.101606 -vn -4.303625 2.700452 -1.158852 -v 0.005680 -0.021057 0.101606 -vn -4.132350 2.647671 -1.725540 -v 0.005704 -0.021062 0.101526 -vn -4.374750 2.646154 1.344296 -v 0.005700 -0.021023 0.102162 -vn -2.248387 3.633833 2.055828 -v 0.005912 -0.041410 0.102525 -vn -3.969545 2.613985 2.032972 -v 0.005765 -0.021014 0.102316 -vn -3.196185 2.616779 2.925341 -v 0.005923 -0.020998 0.102536 -vn -1.128744 3.555741 2.859581 -v 0.006320 -0.041410 0.102794 -vn -2.483165 2.522927 3.780934 -v 0.006133 -0.020982 0.102706 -vn -1.345562 2.529417 4.319423 -v 0.006382 -0.020965 0.102813 -vn -0.179772 2.547394 4.516856 -v 0.006650 -0.020949 0.102850 -vn 0.975383 2.547421 4.414350 -v 0.006889 -0.020935 0.102821 -vn 1.128602 3.555069 2.859712 -v 0.006980 -0.041410 0.102794 -vn 2.014457 2.573324 4.052094 -v 0.007141 -0.020919 0.102721 -vn 2.954706 3.630766 0.744576 -v 0.007620 -0.041410 0.102094 -vn 3.780986 2.556715 2.437535 -v 0.007506 -0.020888 0.102367 -vn 2.248309 3.632304 2.056268 -v 0.007388 -0.041410 0.102525 -vn 3.228125 2.628394 3.207026 -v 0.007357 -0.020902 0.102557 -vn 2.720042 2.653076 3.652633 -v 0.007294 -0.020908 0.102615 -vn 2.954718 3.630692 -0.744533 -v 0.007620 -0.041410 0.101606 -vn 4.511292 2.549615 0.181357 -v 0.007650 -0.020855 0.101850 -vn 4.304044 2.533387 1.354961 -v 0.007613 -0.020872 0.102119 -vn 1.128463 3.555318 -2.859734 -v 0.006980 -0.041410 0.100906 -vn 3.303164 2.552476 -3.058522 -v 0.007357 -0.020808 0.101143 -vn 2.248306 3.632225 -2.056303 -v 0.007388 -0.041410 0.101175 -vn 3.995760 2.537350 -2.080598 -v 0.007521 -0.020825 0.101359 -vn 4.406096 2.551463 -0.963934 -v 0.007621 -0.020841 0.101611 -vn 0.938769 2.650912 -4.474439 -v 0.006855 -0.020774 0.100871 -vn 1.587004 2.624327 -4.270700 -v 0.006918 -0.020778 0.100887 -vn 2.431208 2.556461 -3.778331 -v 0.007167 -0.020794 0.100994 -vn -4.520237 -2.600126 0.257908 -v 0.005650 -0.020168 0.101850 -vn -4.444147 2.616178 -1.046985 -v 0.005675 -0.020090 0.101628 -vn -4.511683 -2.660613 -0.590057 -v 0.005680 -0.020199 0.101607 -vn -4.229589 2.676922 -1.679620 -v 0.005687 -0.020094 0.101581 -vn -4.341753 -2.502708 -1.349357 -v 0.005704 -0.020210 0.101526 -vn -4.122469 -2.567560 -1.889634 -v 0.005784 -0.020236 0.101350 -vn -3.746357 2.604324 -2.490808 -v 0.005794 -0.020120 0.101333 -vn -3.752879 -2.581911 -2.607415 -v 0.005890 -0.020261 0.101200 -vn -3.068849 2.658828 -3.350073 -v 0.005943 -0.020143 0.101143 -vn -3.348096 -2.667005 -3.076895 -v 0.005943 -0.020271 0.101143 -vn -2.549797 2.515300 -3.784449 -v 0.006050 -0.020157 0.101050 -vn -2.481346 -2.610951 -3.790275 -v 0.006172 -0.020308 0.100972 -vn 0.104381 2.618121 -4.548691 -v 0.006650 -0.020219 0.100850 -vn -0.356775 -2.596805 -4.550654 -v 0.006650 -0.020374 0.100850 -vn -0.626935 2.668526 -4.543892 -v 0.006411 -0.020195 0.100879 -vn -0.902252 -2.475877 -4.476343 -v 0.006502 -0.020354 0.100861 -vn -1.623981 -2.650647 -4.277911 -v 0.006389 -0.020339 0.100885 -vn -1.964072 2.635388 -4.101186 -v 0.006159 -0.020169 0.100979 -vn -1.386883 2.615806 -4.338483 -v 0.006320 -0.020186 0.100906 -vn -1.010042 2.715782 -4.502939 -v 0.006389 -0.020193 0.100885 -vn -4.042477 2.630232 2.007474 -v 0.005779 -0.020019 0.102341 -vn -4.447206 2.627872 0.985916 -v 0.005679 -0.020045 0.102089 -vn -4.296808 -2.567382 1.475197 -v 0.005687 -0.020142 0.102118 -vn -4.555031 2.475336 0.392143 -v 0.005662 -0.020054 0.102003 -vn -4.528189 2.603220 -0.333171 -v 0.005650 -0.020068 0.101850 -vn -4.081580 -2.473267 2.040499 -v 0.005748 -0.020125 0.102283 -vn -3.662146 -2.578820 2.723283 -v 0.005794 -0.020116 0.102367 -vn -3.401041 2.614694 2.971993 -v 0.005943 -0.019993 0.102557 -vn -1.962189 -2.636428 4.075558 -v 0.006159 -0.020066 0.102721 -vn -2.725507 2.617803 3.661637 -v 0.006133 -0.019970 0.102706 -vn -2.743532 -2.593426 3.664395 -v 0.005975 -0.020088 0.102588 -vn -3.204562 -2.641086 3.255161 -v 0.005943 -0.020092 0.102557 -vn 0.255229 -2.638453 4.542761 -v 0.006650 -0.020017 0.102850 -vn -0.265670 2.643668 4.570675 -v 0.006650 -0.019918 0.102850 -vn -0.487608 -2.553811 4.550795 -v 0.006481 -0.020033 0.102836 -vn -0.678500 2.531188 4.509319 -v 0.006555 -0.019927 0.102846 -vn -0.985219 -2.609415 4.448603 -v 0.006411 -0.020040 0.102821 -vn -1.540785 2.560344 4.285341 -v 0.006382 -0.019944 0.102813 -vn -2.121659 2.548627 4.044875 -v 0.006195 -0.019963 0.102740 -vn -4.316489 2.462805 1.457305 -v 0.005708 -0.019435 0.102186 -vn -4.500872 2.664158 0.705039 -v 0.005679 -0.019445 0.102089 -vn -4.246064 -2.668611 1.596054 -v 0.005687 -0.019541 0.102119 -vn 0.129647 2.613082 -4.535281 -v 0.006650 -0.019618 0.100850 -vn -0.331946 -2.622375 -4.484544 -v 0.006650 -0.019717 0.100850 -vn -0.833026 2.555474 -4.417502 -v 0.006411 -0.019595 0.100879 -vn -1.456384 -2.554493 -4.249158 -v 0.006382 -0.019691 0.100887 -vn -1.800718 2.591904 -4.162891 -v 0.006159 -0.019569 0.100979 -vn -2.435369 -2.662109 -3.840077 -v 0.006133 -0.019665 0.100994 -vn -2.449433 2.687195 -3.853491 -v 0.006084 -0.019560 0.101026 -vn -2.990130 -2.637463 -3.468052 -v 0.006050 -0.019656 0.101050 -vn -2.932754 2.686726 -3.514125 -v 0.005943 -0.019543 0.101143 -vn -3.349025 -2.691495 -3.112487 -v 0.005943 -0.019642 0.101143 -vn -3.319988 2.662761 -3.168132 -v 0.005915 -0.019539 0.101172 -vn -3.611617 -2.672247 -2.782343 -v 0.005912 -0.019638 0.101175 -vn -3.741040 2.657712 -2.597315 -v 0.005794 -0.019520 0.101333 -vn -3.834367 -2.560097 -2.473628 -v 0.005825 -0.019625 0.101285 -vn -4.143830 -2.658109 -1.845982 -v 0.005779 -0.019616 0.101359 -vn -4.137245 2.470029 -1.932196 -v 0.005718 -0.019503 0.101487 -vn -4.431796 -2.581512 -0.794041 -v 0.005679 -0.019590 0.101611 -vn -4.355403 2.618145 -1.336360 -v 0.005687 -0.019494 0.101581 -vn -4.503785 2.560263 -0.253047 -v 0.005650 -0.019468 0.101850 -vn -4.524680 -2.559900 0.204394 -v 0.005650 -0.019567 0.101850 -vn -4.469168 -2.413088 0.783228 -v 0.005662 -0.019553 0.102003 -vn -4.104294 2.556806 1.969188 -v 0.005779 -0.019419 0.102341 -vn -3.746112 -2.600689 2.512470 -v 0.005794 -0.019516 0.102367 -vn -3.711419 2.551306 2.682674 -v 0.005891 -0.019400 0.102502 -vn -2.948020 -2.606843 3.428311 -v 0.005943 -0.019492 0.102557 -vn -3.260098 2.609136 3.197238 -v 0.005943 -0.019393 0.102557 -vn -2.214228 -2.652326 3.989708 -v 0.006159 -0.019467 0.102721 -vn -2.600314 2.548573 3.698282 -v 0.006133 -0.019370 0.102706 -vn -1.671078 -2.526748 4.256877 -v 0.006195 -0.019463 0.102740 -vn -1.452884 2.575692 4.265224 -v 0.006382 -0.019344 0.102813 -vn -0.845786 -2.545652 4.477232 -v 0.006411 -0.019441 0.102821 -vn -0.404422 2.670954 4.530130 -v 0.006650 -0.019318 0.102850 -vn -0.346356 -2.383419 4.546389 -v 0.006555 -0.019427 0.102845 -vn 0.396656 -2.661686 4.541669 -v 0.006650 -0.019418 0.102850 -vn -1.059022 -2.404379 -4.397242 -v 0.006408 -0.019095 0.100881 -vn -1.900172 -2.710439 -4.129655 -v 0.006320 -0.019086 0.100907 -vn -1.044479 2.617814 -4.417856 -v 0.006336 -0.018988 0.100901 -vn -0.396604 -2.641170 -4.518059 -v 0.006650 -0.019118 0.100850 -vn -0.354972 2.412995 -4.519642 -v 0.006588 -0.019012 0.100852 -vn 0.441573 2.668411 -4.548709 -v 0.006650 -0.019018 0.100850 -vn -4.234526 -2.692204 -1.562548 -v 0.005719 -0.019003 0.101487 -vn -3.829439 2.343924 -2.450958 -v 0.005752 -0.018912 0.101410 -vn -3.437287 -2.566968 -2.765507 -v 0.005915 -0.019039 0.101172 -vn -3.240160 2.514802 -3.120912 -v 0.005902 -0.018938 0.101186 -vn -2.711229 -2.587485 -3.538190 -v 0.006084 -0.019060 0.101026 -vn -2.362585 2.534815 -3.863277 -v 0.006088 -0.018962 0.101023 -vn -1.860131 2.301229 -4.131624 -v 0.006227 -0.018977 0.100944 -vn -4.491202 -2.676715 -0.789758 -v 0.005681 -0.018991 0.101606 -vn -4.513493 -2.634012 0.259308 -v 0.005650 -0.018968 0.101850 -vn -4.554785 2.578434 -0.541090 -v 0.005651 -0.018872 0.101810 -vn -4.466074 2.493442 -0.921446 -v 0.005666 -0.018886 0.101672 -vn -4.334998 2.658481 -1.433450 -v 0.005680 -0.018892 0.101606 -vn -4.144988 2.634701 -1.967497 -v 0.005733 -0.018907 0.101452 -vn -3.535380 2.624962 2.872951 -v 0.005912 -0.018798 0.102525 -vn -3.900466 2.474446 2.385742 -v 0.005815 -0.018813 0.102401 -vn -3.222510 -2.646368 3.103329 -v 0.005892 -0.018900 0.102501 -vn -4.039694 2.250431 2.045269 -v 0.005804 -0.018815 0.102383 -vn -4.081891 -2.638468 1.978783 -v 0.005709 -0.018935 0.102186 -vn -4.350912 2.641925 1.313879 -v 0.005698 -0.018838 0.102157 -vn -4.388485 -2.658358 1.206489 -v 0.005681 -0.018944 0.102094 -vn -4.495314 2.617486 0.705801 -v 0.005680 -0.018844 0.102094 -vn -4.532855 2.482491 0.230566 -v 0.005652 -0.018862 0.101915 -vn 0.183755 -2.667689 4.582179 -v 0.006650 -0.018818 0.102850 -vn -0.396381 2.669402 4.558725 -v 0.006650 -0.018719 0.102850 -vn -0.401246 -2.585411 4.550405 -v 0.006514 -0.018831 0.102840 -vn -1.168452 2.572936 4.410239 -v 0.006430 -0.018740 0.102825 -vn -1.256559 -2.668540 4.390303 -v 0.006320 -0.018850 0.102793 -vn -1.644678 2.606291 4.266170 -v 0.006352 -0.018747 0.102804 -vn -2.287421 2.601059 3.946049 -v 0.006195 -0.018763 0.102741 -vn -2.046014 -2.662480 4.042314 -v 0.006173 -0.018865 0.102728 -vn -2.910168 2.253954 3.497954 -v 0.006050 -0.018780 0.102650 -vn -3.116231 2.254562 3.306628 -v 0.005995 -0.018787 0.102606 -vn -1.929247 2.653617 -4.126967 -v 0.006159 -0.018370 0.100979 -vn -1.216436 2.640688 -4.412566 -v 0.006380 -0.018393 0.100887 -vn -1.514944 -2.619436 -4.287654 -v 0.006382 -0.018492 0.100887 -vn -0.644584 2.658609 -4.527450 -v 0.006411 -0.018396 0.100879 -vn -0.753932 -2.543547 -4.498525 -v 0.006556 -0.018509 0.100854 -vn 0.317994 2.621102 -4.508634 -v 0.006650 -0.018419 0.100850 -vn -0.097578 -2.624890 -4.545158 -v 0.006650 -0.018518 0.100850 -vn -1.990633 -2.449196 -4.084529 -v 0.006227 -0.018476 0.100944 -vn -2.667100 -2.658222 -3.704261 -v 0.006133 -0.018466 0.100994 -vn -2.590734 2.523938 -3.770761 -v 0.006040 -0.018356 0.101058 -vn -3.301209 -2.693635 -3.159318 -v 0.005943 -0.018443 0.101143 -vn -3.101982 2.656236 -3.345125 -v 0.005943 -0.018344 0.101143 -vn -3.659957 -2.595627 -2.739325 -v 0.005912 -0.018438 0.101175 -vn -3.714281 2.611321 -2.551918 -v 0.005794 -0.018320 0.101333 -vn -4.050059 -2.629489 -2.087749 -v 0.005779 -0.018417 0.101359 -vn -4.282169 -2.474964 -1.549029 -v 0.005733 -0.018407 0.101452 -vn -4.224537 2.641254 -1.406918 -v 0.005687 -0.018294 0.101582 -vn -4.471436 -2.572035 -0.718399 -v 0.005679 -0.018391 0.101611 -vn -4.454161 2.584453 -0.275398 -v 0.005650 -0.018268 0.101850 -vn -4.497743 -2.561354 0.248890 -v 0.005650 -0.018367 0.101850 -vn -4.458134 2.562876 0.744672 -v 0.005679 -0.018245 0.102089 -vn -4.269987 -2.589892 1.450934 -v 0.005687 -0.018341 0.102119 -vn -4.268370 2.493158 1.624276 -v 0.005748 -0.018226 0.102283 -vn -3.705479 -2.573414 2.592475 -v 0.005794 -0.018315 0.102367 -vn -4.002501 2.647212 2.170188 -v 0.005779 -0.018219 0.102341 -vn -3.554902 2.641932 2.862417 -v 0.005943 -0.018194 0.102557 -vn -3.132511 -2.620448 3.302619 -v 0.005943 -0.018292 0.102557 -vn -3.188857 2.671213 3.299482 -v 0.005975 -0.018189 0.102588 -vn -2.548355 -2.594316 3.806711 -v 0.006050 -0.018279 0.102650 -vn -2.541395 2.624125 3.778105 -v 0.006133 -0.018170 0.102706 -vn -1.898634 -2.570931 4.150186 -v 0.006159 -0.018266 0.102721 -vn -1.270788 -2.676276 4.399613 -v 0.006351 -0.018246 0.102804 -vn 0.053298 -2.637234 4.555876 -v 0.006650 -0.018217 0.102850 -vn -0.359081 2.627711 4.508005 -v 0.006650 -0.018119 0.102850 -vn -0.623793 -2.589201 4.522341 -v 0.006411 -0.018240 0.102821 -vn -1.306797 2.671423 4.346826 -v 0.006382 -0.018145 0.102813 -vn -2.025532 2.476326 4.091672 -v 0.006285 -0.018154 0.102781 -vn -4.496438 -2.614516 0.222659 -v 0.005650 -0.017767 0.101850 -vn -4.444256 2.624158 -1.048336 -v 0.005675 -0.017690 0.101628 -vn -4.418684 -2.629849 -0.836543 -v 0.005679 -0.017790 0.101611 -vn -4.216959 2.596947 -1.709770 -v 0.005687 -0.017694 0.101581 -vn -4.058318 -2.544626 -1.962399 -v 0.005779 -0.017816 0.101359 -vn -3.712749 2.553591 -2.539054 -v 0.005794 -0.017720 0.101333 -vn -3.479473 -2.602670 -2.933075 -v 0.005943 -0.017842 0.101143 -vn -3.106102 2.609183 -3.306018 -v 0.005943 -0.017743 0.101143 -vn -3.020046 -2.655384 -3.458250 -v 0.006040 -0.017855 0.101058 -vn -2.553413 2.667254 -3.791514 -v 0.006050 -0.017757 0.101050 -vn -2.451704 -2.632957 -3.846405 -v 0.006133 -0.017865 0.100994 -vn -1.854003 2.578785 -4.142171 -v 0.006159 -0.017769 0.100979 -vn -1.448837 -2.593250 -4.256545 -v 0.006382 -0.017891 0.100887 -vn 0.104425 2.618141 -4.548641 -v 0.006650 -0.017819 0.100850 -vn -0.316055 -2.642093 -4.461520 -v 0.006650 -0.017917 0.100850 -vn -0.597012 2.591727 -4.547088 -v 0.006411 -0.017795 0.100879 -vn -1.189659 2.664389 -4.407870 -v 0.006389 -0.017793 0.100885 -vn -4.042480 2.630333 2.007492 -v 0.005779 -0.017619 0.102341 -vn -4.447237 2.627885 0.985969 -v 0.005679 -0.017645 0.102089 -vn -4.296862 -2.567345 1.475172 -v 0.005687 -0.017742 0.102118 -vn -4.554947 2.475198 0.392218 -v 0.005662 -0.017654 0.102003 -vn -4.528221 2.603446 -0.333222 -v 0.005650 -0.017668 0.101850 -vn -4.081481 -2.473075 2.040425 -v 0.005748 -0.017725 0.102283 -vn -3.662096 -2.578856 2.723314 -v 0.005794 -0.017715 0.102367 -vn -3.401062 2.614691 2.972002 -v 0.005943 -0.017593 0.102557 -vn -1.962179 -2.636550 4.075331 -v 0.006159 -0.017666 0.102721 -vn -2.725445 2.617791 3.661659 -v 0.006133 -0.017570 0.102706 -vn -2.743389 -2.593541 3.664313 -v 0.005975 -0.017688 0.102588 -vn -3.204451 -2.641070 3.255078 -v 0.005943 -0.017692 0.102557 -vn 0.255278 -2.638696 4.542411 -v 0.006650 -0.017617 0.102850 -vn -0.265618 2.643720 4.570677 -v 0.006650 -0.017518 0.102850 -vn -0.487707 -2.553718 4.550415 -v 0.006481 -0.017633 0.102836 -vn -0.678593 2.531503 4.509355 -v 0.006555 -0.017527 0.102846 -vn -0.985240 -2.609613 4.448277 -v 0.006411 -0.017640 0.102821 -vn -1.540794 2.560303 4.285332 -v 0.006382 -0.017544 0.102813 -vn -2.121627 2.548652 4.044917 -v 0.006195 -0.017563 0.102740 -vn -4.316447 2.462845 1.457255 -v 0.005708 -0.017035 0.102186 -vn -4.500907 2.664140 0.704990 -v 0.005679 -0.017045 0.102089 -vn -4.245796 -2.668750 1.596023 -v 0.005687 -0.017141 0.102119 -vn 0.129509 2.613124 -4.535330 -v 0.006650 -0.017218 0.100850 -vn -0.332015 -2.622564 -4.484263 -v 0.006650 -0.017317 0.100850 -vn -0.833012 2.555497 -4.417453 -v 0.006411 -0.017195 0.100879 -vn -1.456322 -2.554633 -4.248878 -v 0.006382 -0.017291 0.100887 -vn -1.800812 2.591892 -4.162809 -v 0.006159 -0.017169 0.100979 -vn -2.435320 -2.662183 -3.839744 -v 0.006133 -0.017265 0.100994 -vn -2.449510 2.687274 -3.853503 -v 0.006084 -0.017160 0.101026 -vn -2.990075 -2.637613 -3.467709 -v 0.006050 -0.017256 0.101050 -vn -2.932728 2.686730 -3.514137 -v 0.005943 -0.017143 0.101143 -vn -3.348855 -2.691650 -3.112245 -v 0.005943 -0.017242 0.101143 -vn -3.319991 2.662759 -3.168135 -v 0.005915 -0.017139 0.101172 -vn -3.611429 -2.672401 -2.782054 -v 0.005912 -0.017238 0.101175 -vn -3.741031 2.657673 -2.597335 -v 0.005794 -0.017120 0.101333 -vn -3.834323 -2.560517 -2.473374 -v 0.005825 -0.017225 0.101285 -vn -4.143519 -2.658262 -1.845882 -v 0.005779 -0.017216 0.101359 -vn -4.137241 2.470032 -1.932186 -v 0.005718 -0.017103 0.101487 -vn -4.431521 -2.581653 -0.793961 -v 0.005679 -0.017190 0.101611 -vn -4.355386 2.618154 -1.336358 -v 0.005687 -0.017094 0.101581 -vn -4.503775 2.560267 -0.253051 -v 0.005650 -0.017068 0.101850 -vn -4.524388 -2.560039 0.204443 -v 0.005650 -0.017167 0.101850 -vn -4.468865 -2.413554 0.783441 -v 0.005662 -0.017153 0.102003 -vn -4.104278 2.556794 1.969242 -v 0.005779 -0.017019 0.102341 -vn -3.745873 -2.600799 2.512360 -v 0.005794 -0.017116 0.102367 -vn -3.711484 2.551387 2.682668 -v 0.005891 -0.017000 0.102502 -vn -2.947855 -2.606941 3.428115 -v 0.005943 -0.017092 0.102557 -vn -3.260139 2.609107 3.197166 -v 0.005943 -0.016993 0.102557 -vn -2.214113 -2.652465 3.989487 -v 0.006159 -0.017067 0.102721 -vn -2.600363 2.548589 3.698262 -v 0.006133 -0.016970 0.102706 -vn -1.670881 -2.526795 4.256595 -v 0.006195 -0.017063 0.102740 -vn -1.452858 2.575738 4.265215 -v 0.006382 -0.016944 0.102813 -vn -0.845649 -2.545780 4.477040 -v 0.006411 -0.017041 0.102821 -vn -0.404389 2.670966 4.530159 -v 0.006650 -0.016918 0.102850 -vn -0.346235 -2.383554 4.546144 -v 0.006555 -0.017027 0.102845 -vn 0.396750 -2.661868 4.541421 -v 0.006650 -0.017018 0.102850 -vn -1.059172 -2.404831 -4.397066 -v 0.006408 -0.016695 0.100881 -vn -1.900106 -2.710532 -4.129445 -v 0.006320 -0.016686 0.100907 -vn -1.044436 2.617780 -4.417859 -v 0.006336 -0.016588 0.100901 -vn -0.396699 -2.641314 -4.517838 -v 0.006650 -0.016718 0.100850 -vn -0.354972 2.413004 -4.519625 -v 0.006588 -0.016612 0.100852 -vn 0.448920 2.673134 -4.537486 -v 0.006650 -0.016618 0.100850 -vn -4.234434 -2.692266 -1.562345 -v 0.005719 -0.016603 0.101487 -vn -3.806921 2.351487 -2.454451 -v 0.005752 -0.016512 0.101410 -vn -3.437215 -2.566966 -2.765248 -v 0.005915 -0.016639 0.101172 -vn -3.245462 2.520028 -3.104464 -v 0.005902 -0.016538 0.101186 -vn -2.711333 -2.587728 -3.537901 -v 0.006084 -0.016660 0.101026 -vn -2.362470 2.531362 -3.870425 -v 0.006088 -0.016562 0.101023 -vn -1.860124 2.301208 -4.131645 -v 0.006227 -0.016577 0.100944 -vn -4.491021 -2.676824 -0.789666 -v 0.005681 -0.016591 0.101606 -vn -4.513314 -2.634111 0.259433 -v 0.005650 -0.016568 0.101850 -vn -4.554785 2.578374 -0.541103 -v 0.005651 -0.016472 0.101810 -vn -4.466074 2.493441 -0.921446 -v 0.005666 -0.016486 0.101672 -vn -4.334986 2.658488 -1.433464 -v 0.005680 -0.016492 0.101606 -vn -4.145102 2.634843 -1.967412 -v 0.005733 -0.016507 0.101452 -vn -3.535410 2.624931 2.872932 -v 0.005912 -0.016398 0.102525 -vn -3.900454 2.474235 2.385744 -v 0.005815 -0.016413 0.102401 -vn -3.222287 -2.646536 3.103345 -v 0.005892 -0.016500 0.102501 -vn -4.039648 2.250384 2.045344 -v 0.005804 -0.016415 0.102383 -vn -4.081637 -2.638447 1.978790 -v 0.005709 -0.016535 0.102186 -vn -4.350961 2.641970 1.313918 -v 0.005698 -0.016438 0.102157 -vn -4.388291 -2.658470 1.206485 -v 0.005681 -0.016544 0.102094 -vn -4.495243 2.617536 0.705847 -v 0.005680 -0.016444 0.102094 -vn -4.532893 2.482596 0.230512 -v 0.005652 -0.016462 0.101915 -vn 0.183678 -2.667735 4.582071 -v 0.006650 -0.016418 0.102850 -vn -0.396410 2.669384 4.558721 -v 0.006650 -0.016319 0.102850 -vn -0.401093 -2.585649 4.550274 -v 0.006514 -0.016431 0.102840 -vn -1.168416 2.572799 4.410217 -v 0.006430 -0.016340 0.102825 -vn -1.256421 -2.668610 4.390127 -v 0.006320 -0.016450 0.102793 -vn -1.644701 2.606347 4.266173 -v 0.006352 -0.016347 0.102804 -vn -2.287387 2.601034 3.946072 -v 0.006195 -0.016363 0.102741 -vn -2.045784 -2.662722 4.042281 -v 0.006173 -0.016465 0.102728 -vn -2.910067 2.253659 3.497900 -v 0.006050 -0.016380 0.102650 -vn -3.116548 2.255022 3.306521 -v 0.005995 -0.016387 0.102606 -vn -1.929244 2.653599 -4.126970 -v 0.006159 -0.015970 0.100979 -vn -1.216434 2.640683 -4.412573 -v 0.006380 -0.015993 0.100887 -vn -1.515017 -2.619500 -4.287515 -v 0.006382 -0.016092 0.100887 -vn -0.644605 2.658640 -4.527445 -v 0.006411 -0.015996 0.100879 -vn -0.753928 -2.543544 -4.498358 -v 0.006556 -0.016109 0.100854 -vn 0.318013 2.621116 -4.508634 -v 0.006650 -0.016019 0.100850 -vn -0.097523 -2.624955 -4.545064 -v 0.006650 -0.016118 0.100850 -vn -1.992054 -2.452071 -4.077339 -v 0.006227 -0.016076 0.100944 -vn -2.664041 -2.670318 -3.674025 -v 0.006133 -0.016066 0.100994 -vn -2.590724 2.523943 -3.770757 -v 0.006040 -0.015956 0.101058 -vn -3.279555 -2.700767 -3.165386 -v 0.005943 -0.016043 0.101143 -vn -3.101982 2.656235 -3.345125 -v 0.005943 -0.015944 0.101143 -vn -3.667988 -2.591656 -2.740402 -v 0.005912 -0.016038 0.101175 -vn -3.714278 2.611325 -2.551922 -v 0.005794 -0.015920 0.101333 -vn -4.049981 -2.629540 -2.087677 -v 0.005779 -0.016017 0.101359 -vn -4.282096 -2.474957 -1.548948 -v 0.005733 -0.016007 0.101452 -vn -4.224536 2.641282 -1.406901 -v 0.005687 -0.015894 0.101582 -vn -4.471352 -2.572094 -0.718345 -v 0.005679 -0.015991 0.101611 -vn -4.454155 2.584456 -0.275400 -v 0.005650 -0.015868 0.101850 -vn -4.497648 -2.561401 0.248896 -v 0.005650 -0.015967 0.101850 -vn -4.458150 2.562867 0.744652 -v 0.005679 -0.015845 0.102089 -vn -4.269893 -2.589940 1.450913 -v 0.005687 -0.015941 0.102119 -vn -4.268296 2.493201 1.624292 -v 0.005748 -0.015826 0.102283 -vn -3.705402 -2.573458 2.592427 -v 0.005794 -0.015915 0.102367 -vn -4.002503 2.647194 2.170281 -v 0.005779 -0.015819 0.102341 -vn -3.554899 2.641934 2.862415 -v 0.005943 -0.015794 0.102557 -vn -3.132443 -2.620484 3.302569 -v 0.005943 -0.015892 0.102557 -vn -3.188868 2.671191 3.299481 -v 0.005975 -0.015789 0.102588 -vn -2.548268 -2.594393 3.806659 -v 0.006050 -0.015879 0.102650 -vn -2.541341 2.624126 3.778076 -v 0.006133 -0.015770 0.102706 -vn -1.898513 -2.570921 4.150147 -v 0.006159 -0.015866 0.102721 -vn -1.270817 -2.676545 4.399564 -v 0.006351 -0.015846 0.102804 -vn 0.053261 -2.637264 4.555843 -v 0.006650 -0.015817 0.102850 -vn -0.359098 2.627727 4.508002 -v 0.006650 -0.015719 0.102850 -vn -0.623876 -2.589204 4.522213 -v 0.006411 -0.015840 0.102821 -vn -1.306843 2.671342 4.346807 -v 0.006382 -0.015745 0.102813 -vn -2.025496 2.476074 4.091676 -v 0.006285 -0.015754 0.102781 -vn -4.496438 -2.614516 0.222659 -v 0.005650 -0.015367 0.101850 -vn -4.444275 2.624149 -1.048353 -v 0.005675 -0.015290 0.101628 -vn -4.418676 -2.629853 -0.836545 -v 0.005679 -0.015390 0.101611 -vn -4.216966 2.596942 -1.709778 -v 0.005687 -0.015294 0.101581 -vn -4.058311 -2.544629 -1.962392 -v 0.005779 -0.015416 0.101359 -vn -3.712749 2.553591 -2.539054 -v 0.005794 -0.015320 0.101333 -vn -3.479505 -2.602689 -2.933044 -v 0.005943 -0.015442 0.101143 -vn -3.106113 2.609199 -3.306008 -v 0.005943 -0.015343 0.101143 -vn -3.020002 -2.655315 -3.458224 -v 0.006040 -0.015455 0.101058 -vn -2.553394 2.667308 -3.791530 -v 0.006050 -0.015357 0.101050 -vn -2.451669 -2.632972 -3.846412 -v 0.006133 -0.015465 0.100994 -vn -1.854003 2.578785 -4.142171 -v 0.006159 -0.015369 0.100979 -vn -1.448810 -2.593273 -4.256505 -v 0.006382 -0.015491 0.100887 -vn 0.104379 2.618133 -4.548667 -v 0.006650 -0.015419 0.100850 -vn -0.316061 -2.642094 -4.461520 -v 0.006650 -0.015517 0.100850 -vn -0.597011 2.591726 -4.547088 -v 0.006411 -0.015395 0.100879 -vn -1.189659 2.664389 -4.407870 -v 0.006389 -0.015393 0.100885 -vn -4.042491 2.630330 2.007484 -v 0.005779 -0.015219 0.102341 -vn -4.447237 2.627885 0.985969 -v 0.005679 -0.015245 0.102089 -vn -4.296862 -2.567345 1.475172 -v 0.005687 -0.015342 0.102118 -vn -4.554962 2.475192 0.392253 -v 0.005662 -0.015254 0.102003 -vn -4.528180 2.603467 -0.333215 -v 0.005650 -0.015268 0.101850 -vn -4.081470 -2.473079 2.040426 -v 0.005748 -0.015325 0.102283 -vn -3.662092 -2.578862 2.723304 -v 0.005794 -0.015315 0.102367 -vn -3.401034 2.614708 2.971973 -v 0.005943 -0.015193 0.102557 -vn -1.962178 -2.636549 4.075331 -v 0.006159 -0.015266 0.102721 -vn -2.725515 2.617761 3.661678 -v 0.006133 -0.015170 0.102706 -vn -2.743389 -2.593544 3.664312 -v 0.005975 -0.015288 0.102588 -vn -3.204451 -2.641070 3.255078 -v 0.005943 -0.015292 0.102557 -vn 0.255278 -2.638696 4.542411 -v 0.006650 -0.015217 0.102850 -vn -0.265581 2.643742 4.570638 -v 0.006650 -0.015118 0.102850 -vn -0.487705 -2.553723 4.550415 -v 0.006481 -0.015233 0.102836 -vn -0.678621 2.531523 4.509318 -v 0.006555 -0.015127 0.102846 -vn -0.985241 -2.609614 4.448277 -v 0.006411 -0.015240 0.102821 -vn -1.540800 2.560291 4.285358 -v 0.006382 -0.015144 0.102813 -vn -2.121647 2.548684 4.044839 -v 0.006195 -0.015163 0.102740 -vn -4.316445 2.462836 1.457257 -v 0.005708 -0.014635 0.102186 -vn -4.500907 2.664140 0.704989 -v 0.005679 -0.014645 0.102089 -vn -4.245835 -2.668728 1.596056 -v 0.005687 -0.014741 0.102119 -vn 0.129509 2.613124 -4.535330 -v 0.006650 -0.014818 0.100850 -vn -0.332015 -2.622564 -4.484263 -v 0.006650 -0.014917 0.100850 -vn -0.833012 2.555497 -4.417453 -v 0.006411 -0.014795 0.100879 -vn -1.456322 -2.554633 -4.248878 -v 0.006382 -0.014891 0.100887 -vn -1.800812 2.591892 -4.162809 -v 0.006159 -0.014769 0.100979 -vn -2.435320 -2.662183 -3.839744 -v 0.006133 -0.014865 0.100994 -vn -2.449510 2.687274 -3.853503 -v 0.006084 -0.014761 0.101026 -vn -2.990075 -2.637613 -3.467709 -v 0.006050 -0.014856 0.101050 -vn -2.932728 2.686730 -3.514137 -v 0.005943 -0.014743 0.101143 -vn -3.348855 -2.691650 -3.112245 -v 0.005943 -0.014842 0.101143 -vn -3.319991 2.662759 -3.168135 -v 0.005915 -0.014739 0.101172 -vn -3.611429 -2.672401 -2.782054 -v 0.005912 -0.014838 0.101175 -vn -3.741031 2.657673 -2.597335 -v 0.005794 -0.014720 0.101333 -vn -3.834323 -2.560517 -2.473374 -v 0.005825 -0.014825 0.101285 -vn -4.143515 -2.658264 -1.845874 -v 0.005779 -0.014816 0.101359 -vn -4.137244 2.470030 -1.932190 -v 0.005718 -0.014703 0.101487 -vn -4.431513 -2.581660 -0.793963 -v 0.005679 -0.014790 0.101611 -vn -4.355396 2.618148 -1.336363 -v 0.005687 -0.014694 0.101581 -vn -4.503785 2.560264 -0.253045 -v 0.005650 -0.014668 0.101850 -vn -4.524388 -2.560039 0.204443 -v 0.005650 -0.014767 0.101850 -vn -4.468834 -2.413561 0.783478 -v 0.005662 -0.014753 0.102003 -vn -4.104278 2.556793 1.969241 -v 0.005779 -0.014619 0.102341 -vn -3.745851 -2.600808 2.512352 -v 0.005794 -0.014716 0.102367 -vn -3.711542 2.551363 2.682645 -v 0.005891 -0.014600 0.102502 -vn -2.947878 -2.606927 3.428141 -v 0.005943 -0.014692 0.102557 -vn -3.260147 2.609131 3.197072 -v 0.005943 -0.014593 0.102557 -vn -2.214113 -2.652474 3.989467 -v 0.006159 -0.014667 0.102721 -vn -2.600336 2.548603 3.698251 -v 0.006133 -0.014570 0.102706 -vn -1.670873 -2.526809 4.256581 -v 0.006195 -0.014663 0.102740 -vn -1.452845 2.575736 4.265229 -v 0.006382 -0.014544 0.102813 -vn -0.845652 -2.545783 4.477033 -v 0.006411 -0.014641 0.102821 -vn -0.404441 2.670946 4.530189 -v 0.006650 -0.014518 0.102850 -vn -0.346235 -2.383554 4.546144 -v 0.006555 -0.014627 0.102845 -vn 0.396751 -2.661867 4.541420 -v 0.006650 -0.014618 0.102850 -vn -1.059172 -2.404831 -4.397066 -v 0.006408 -0.014295 0.100881 -vn -1.900118 -2.710532 -4.129432 -v 0.006320 -0.014286 0.100907 -vn -1.044417 2.617764 -4.417894 -v 0.006336 -0.014188 0.100901 -vn -0.396699 -2.641314 -4.517838 -v 0.006650 -0.014318 0.100850 -vn -0.354974 2.412995 -4.519641 -v 0.006588 -0.014212 0.100852 -vn 0.448925 2.673129 -4.537494 -v 0.006650 -0.014218 0.100850 -vn -4.234434 -2.692266 -1.562345 -v 0.005719 -0.014203 0.101487 -vn -3.806931 2.351485 -2.454450 -v 0.005752 -0.014112 0.101410 -vn -3.437190 -2.566975 -2.765252 -v 0.005915 -0.014239 0.101172 -vn -3.245462 2.520025 -3.104472 -v 0.005902 -0.014138 0.101186 -vn -2.711352 -2.587713 -3.537931 -v 0.006084 -0.014260 0.101026 -vn -2.362502 2.531357 -3.870421 -v 0.006088 -0.014162 0.101023 -vn -1.860075 2.301261 -4.131608 -v 0.006227 -0.014177 0.100944 -vn -4.491021 -2.676826 -0.789666 -v 0.005681 -0.014191 0.101606 -vn -4.513312 -2.634113 0.259433 -v 0.005650 -0.014168 0.101850 -vn -4.554816 2.578356 -0.541139 -v 0.005651 -0.014072 0.101810 -vn -4.466081 2.493436 -0.921452 -v 0.005666 -0.014086 0.101672 -vn -4.334986 2.658488 -1.433464 -v 0.005680 -0.014092 0.101606 -vn -4.145102 2.634843 -1.967412 -v 0.005733 -0.014107 0.101452 -vn -3.535410 2.624931 2.872932 -v 0.005912 -0.013998 0.102525 -vn -3.900454 2.474235 2.385744 -v 0.005815 -0.014013 0.102401 -vn -3.222287 -2.646536 3.103345 -v 0.005892 -0.014100 0.102501 -vn -4.039648 2.250384 2.045344 -v 0.005804 -0.014015 0.102383 -vn -4.081637 -2.638447 1.978790 -v 0.005709 -0.014135 0.102186 -vn -4.350961 2.641970 1.313918 -v 0.005698 -0.014038 0.102157 -vn -4.388291 -2.658470 1.206485 -v 0.005681 -0.014144 0.102094 -vn -4.495249 2.617532 0.705872 -v 0.005680 -0.014044 0.102094 -vn -4.532836 2.482635 0.230477 -v 0.005652 -0.014062 0.101915 -vn 0.183649 -2.667745 4.582055 -v 0.006650 -0.014018 0.102850 -vn -0.396408 2.669384 4.558722 -v 0.006650 -0.013919 0.102850 -vn -0.401116 -2.585622 4.550320 -v 0.006514 -0.014031 0.102840 -vn -1.168417 2.572796 4.410218 -v 0.006430 -0.013940 0.102825 -vn -1.256392 -2.668615 4.390120 -v 0.006320 -0.014050 0.102793 -vn -1.644701 2.606347 4.266173 -v 0.006352 -0.013947 0.102804 -vn -2.287387 2.601033 3.946076 -v 0.006195 -0.013963 0.102741 -vn -2.045784 -2.662722 4.042281 -v 0.006173 -0.014065 0.102728 -vn -2.910070 2.253659 3.497901 -v 0.006050 -0.013980 0.102650 -vn -3.116548 2.255022 3.306521 -v 0.005995 -0.013987 0.102606 -vn -1.898534 -2.570931 4.150117 -v 0.006159 -0.013466 0.102721 -vn -1.317246 -2.585412 4.378969 -v 0.006351 -0.013446 0.102804 -vn -2.649914 2.607693 3.703175 -v 0.006133 -0.013370 0.102706 -vn -1.929266 2.653596 -4.126971 -v 0.006159 -0.013570 0.100979 -vn -1.216252 2.640734 -4.412497 -v 0.006380 -0.013593 0.100887 -vn -1.515011 -2.619504 -4.287509 -v 0.006382 -0.013692 0.100887 -vn -0.644482 2.658583 -4.527558 -v 0.006411 -0.013596 0.100879 -vn -0.753927 -2.543552 -4.498341 -v 0.006556 -0.013709 0.100854 -vn 0.318012 2.621115 -4.508636 -v 0.006650 -0.013619 0.100850 -vn -0.097529 -2.624959 -4.545055 -v 0.006650 -0.013718 0.100850 -vn -1.992054 -2.452071 -4.077339 -v 0.006227 -0.013676 0.100944 -vn -2.664041 -2.670319 -3.674021 -v 0.006133 -0.013666 0.100994 -vn -2.590724 2.523943 -3.770757 -v 0.006040 -0.013556 0.101058 -vn -3.279551 -2.700770 -3.165380 -v 0.005943 -0.013643 0.101143 -vn -3.101982 2.656235 -3.345125 -v 0.005943 -0.013544 0.101143 -vn -3.667981 -2.591662 -2.740391 -v 0.005912 -0.013638 0.101175 -vn -3.714278 2.611325 -2.551922 -v 0.005794 -0.013520 0.101333 -vn -4.049973 -2.629544 -2.087677 -v 0.005779 -0.013617 0.101359 -vn -4.282096 -2.474957 -1.548948 -v 0.005733 -0.013607 0.101452 -vn -4.224536 2.641282 -1.406901 -v 0.005687 -0.013494 0.101582 -vn -4.471345 -2.572098 -0.718338 -v 0.005679 -0.013591 0.101611 -vn -4.454169 2.584448 -0.275418 -v 0.005650 -0.013468 0.101850 -vn -4.497641 -2.561407 0.248891 -v 0.005650 -0.013567 0.101850 -vn -4.533796 2.604816 0.560945 -v 0.005679 -0.013445 0.102089 -vn -4.243045 -2.517383 1.512179 -v 0.005687 -0.013541 0.102119 -vn -4.431122 2.662816 1.146410 -v 0.005680 -0.013445 0.102094 -vn -3.762223 -2.607572 2.494498 -v 0.005794 -0.013515 0.102367 -vn -4.163483 2.531396 1.831432 -v 0.005779 -0.013419 0.102341 -vn -3.706131 2.365244 2.637031 -v 0.005850 -0.013407 0.102450 -vn -3.331035 2.558162 3.080294 -v 0.005943 -0.013394 0.102557 -vn -3.080053 -2.551527 3.346763 -v 0.005943 -0.013492 0.102557 -vn -2.639396 -2.360888 3.704440 -v 0.006050 -0.013479 0.102650 -vn -0.666079 -2.664901 4.517160 -v 0.006411 -0.013440 0.102821 -vn 0.053260 -2.637263 4.555843 -v 0.006650 -0.013417 0.102850 -vn -0.251417 2.619265 4.537531 -v 0.006650 -0.013319 0.102850 -vn -0.713974 2.339525 4.475633 -v 0.006518 -0.013331 0.102841 -vn -1.577186 2.662788 4.248304 -v 0.006382 -0.013345 0.102813 -vn -2.311212 1.951321 3.809878 -v 0.006145 -0.013369 0.102713 -vn -4.045326 -2.628404 -1.994655 -v 0.005779 -0.013016 0.101359 -vn -3.652727 2.583367 -2.746654 -v 0.005794 -0.012920 0.101333 -vn -3.479549 -2.602664 -2.933067 -v 0.005943 -0.013042 0.101143 -vn -3.147918 2.608233 -3.290350 -v 0.005943 -0.012943 0.101143 -vn -2.984856 -2.607876 -3.482228 -v 0.006040 -0.013055 0.101058 -vn 0.095193 2.622656 -4.549638 -v 0.006650 -0.013019 0.100850 -vn -0.316509 -2.644078 -4.461513 -v 0.006650 -0.013117 0.100850 -vn -0.634374 2.584628 -4.530977 -v 0.006411 -0.012995 0.100879 -vn -1.429245 -2.632930 -4.264211 -v 0.006382 -0.013091 0.100887 -vn -1.330972 2.583432 -4.356468 -v 0.006351 -0.012990 0.100896 -vn -2.468764 -2.606268 -3.834562 -v 0.006133 -0.013065 0.100994 -vn -1.917299 2.572349 -4.104674 -v 0.006159 -0.012969 0.100979 -vn -2.703661 2.623671 -3.680103 -v 0.006006 -0.012952 0.101085 -vn -4.086906 2.639635 2.006198 -v 0.005779 -0.012819 0.102341 -vn -4.349166 2.520553 1.390632 -v 0.005701 -0.012838 0.102167 -vn -4.286046 -2.651749 1.460124 -v 0.005687 -0.012942 0.102118 -vn -4.515348 2.628276 0.683424 -v 0.005679 -0.012845 0.102089 -vn -4.471282 -2.592356 0.682776 -v 0.005652 -0.012961 0.101915 -vn -4.561051 2.689772 -0.131750 -v 0.005650 -0.012868 0.101850 -vn -4.522213 -2.720431 0.132738 -v 0.005650 -0.012967 0.101850 -vn -4.513928 2.553480 -0.719660 -v 0.005653 -0.012876 0.101774 -vn -4.417238 -2.605411 -0.845324 -v 0.005679 -0.012990 0.101611 -vn -4.290045 2.554291 -1.522956 -v 0.005687 -0.012894 0.101581 -vn -4.045236 2.548449 -2.125173 -v 0.005760 -0.012914 0.101395 -vn -4.072830 -2.481764 2.024000 -v 0.005748 -0.012925 0.102283 -vn -3.682933 -2.625208 2.694758 -v 0.005794 -0.012915 0.102367 -vn -3.690904 2.565036 2.699499 -v 0.005898 -0.012800 0.102509 -vn -3.165840 -2.703122 3.300245 -v 0.005943 -0.012892 0.102557 -vn -3.270630 2.703370 3.143350 -v 0.005943 -0.012793 0.102557 -vn -2.722265 -2.600720 3.660162 -v 0.005975 -0.012888 0.102588 -vn -2.711354 2.623817 3.638214 -v 0.006133 -0.012770 0.102706 -vn -1.977425 -2.645106 4.058755 -v 0.006159 -0.012866 0.102721 -vn -2.043498 2.502856 4.062668 -v 0.006212 -0.012762 0.102749 -vn -1.524840 2.577978 4.269240 -v 0.006382 -0.012744 0.102813 -vn -0.997957 -2.642785 4.440245 -v 0.006411 -0.012840 0.102821 -vn -0.455919 -2.577063 4.547029 -v 0.006481 -0.012833 0.102836 -vn -0.648058 2.642139 4.528312 -v 0.006593 -0.012724 0.102848 -vn 0.294540 -2.679900 4.533865 -v 0.006650 -0.012817 0.102850 -vn -0.178758 2.699159 4.570447 -v 0.006650 -0.012718 0.102850 -vn -4.221745 2.286446 1.619116 -v 0.005728 -0.012230 0.102237 -vn -4.467906 2.658939 0.741942 -v 0.005679 -0.012245 0.102089 -vn -4.267484 -2.642670 1.593181 -v 0.005687 -0.012341 0.102119 -vn -4.163852 -2.653174 -1.867956 -v 0.005779 -0.012416 0.101359 -vn -4.122241 2.318880 -1.868561 -v 0.005728 -0.012306 0.101463 -vn -3.693781 2.669919 -2.635539 -v 0.005794 -0.012320 0.101333 -vn 0.035975 2.618430 -4.576493 -v 0.006650 -0.012418 0.100850 -vn -0.435201 -2.624677 -4.510019 -v 0.006650 -0.012517 0.100850 -vn -0.703083 2.570857 -4.499622 -v 0.006411 -0.012395 0.100879 -vn -1.403245 -2.638738 -4.266789 -v 0.006382 -0.012491 0.100887 -vn -1.493086 2.475688 -4.314962 -v 0.006280 -0.012382 0.100921 -vn -2.485461 -2.642701 -3.813184 -v 0.006133 -0.012465 0.100994 -vn -2.059721 2.619453 -4.065480 -v 0.006159 -0.012369 0.100979 -vn -2.948995 -2.493618 -3.484234 -v 0.006050 -0.012456 0.101050 -vn -2.849454 2.687452 -3.592942 -v 0.005950 -0.012344 0.101136 -vn -3.351779 -2.701739 -3.106905 -v 0.005943 -0.012442 0.101143 -vn -3.212373 2.712719 -3.260152 -v 0.005943 -0.012343 0.101143 -vn -3.616675 -2.611238 -2.772367 -v 0.005912 -0.012438 0.101175 -vn -3.836495 -2.558156 -2.479496 -v 0.005825 -0.012425 0.101285 -vn -4.302432 2.545283 -1.418711 -v 0.005687 -0.012294 0.101581 -vn -4.445747 -2.541151 -0.823835 -v 0.005679 -0.012390 0.101611 -vn -4.491663 2.567116 -0.244827 -v 0.005650 -0.012268 0.101850 -vn -4.544888 -2.550731 0.193299 -v 0.005650 -0.012367 0.101850 -vn -4.484489 -2.403960 0.794301 -v 0.005662 -0.012353 0.102003 -vn -4.044838 2.544711 2.046928 -v 0.005779 -0.012219 0.102341 -vn -3.710876 -2.546447 2.561992 -v 0.005794 -0.012316 0.102367 -vn -3.586157 2.653354 2.845117 -v 0.005943 -0.012193 0.102557 -vn -3.001925 -2.564982 3.363464 -v 0.005943 -0.012292 0.102557 -vn -3.191302 2.625594 3.284307 -v 0.005950 -0.012192 0.102564 -vn -2.175760 -2.613218 4.007372 -v 0.006159 -0.012267 0.102721 -vn -2.664727 2.549770 3.686875 -v 0.006133 -0.012170 0.102706 -vn -1.863437 2.448948 4.147331 -v 0.006280 -0.012154 0.102779 -vn -1.749987 -2.539581 4.214959 -v 0.006195 -0.012263 0.102740 -vn -1.377188 2.576014 4.321479 -v 0.006382 -0.012144 0.102813 -vn -0.829965 -2.554431 4.461180 -v 0.006411 -0.012241 0.102821 -vn -0.487613 2.695853 4.544969 -v 0.006650 -0.012118 0.102850 -vn -0.352292 -2.392943 4.528747 -v 0.006555 -0.012227 0.102845 -vn 0.431524 -2.643484 4.519318 -v 0.006650 -0.012218 0.102850 -vn -1.075590 -2.395984 -4.408605 -v 0.006408 -0.011895 0.100881 -vn -1.892243 -2.696739 -4.156924 -v 0.006320 -0.011886 0.100907 -vn -1.048797 2.617708 -4.401235 -v 0.006336 -0.011788 0.100901 -vn -0.381760 -2.632359 -4.539330 -v 0.006650 -0.011918 0.100850 -vn -0.357672 2.421313 -4.503752 -v 0.006588 -0.011812 0.100852 -vn 0.453898 2.678673 -4.524904 -v 0.006650 -0.011818 0.100850 -vn -3.495003 -2.545477 -2.783748 -v 0.005915 -0.011839 0.101172 -vn -4.235466 -2.699580 -1.577238 -v 0.005719 -0.011803 0.101487 -vn -3.850753 2.341589 -2.384335 -v 0.005752 -0.011712 0.101410 -vn -3.481468 2.567131 -2.957222 -v 0.005897 -0.011737 0.101191 -vn -3.070146 2.666409 -3.405556 -v 0.005902 -0.011738 0.101186 -vn -2.730123 -2.558502 -3.605111 -v 0.006084 -0.011860 0.101026 -vn -2.363974 2.533869 -3.865605 -v 0.006088 -0.011762 0.101023 -vn -1.905265 2.245072 -4.092723 -v 0.006212 -0.011775 0.100951 -vn -4.476201 -2.669451 -0.734601 -v 0.005681 -0.011791 0.101606 -vn -4.466883 -2.371559 0.083682 -v 0.005650 -0.011768 0.101850 -vn -4.573819 2.629500 -0.188658 -v 0.005652 -0.011662 0.101915 -vn -4.452328 2.372806 -0.758540 -v 0.005666 -0.011686 0.101672 -vn -4.368417 2.661013 -1.383385 -v 0.005680 -0.011692 0.101606 -vn -4.257478 2.591150 -1.689866 -v 0.005701 -0.011699 0.101533 -vn -3.209621 2.376678 3.271343 -v 0.005995 -0.011587 0.102606 -vn -3.541599 2.622197 2.872763 -v 0.005912 -0.011598 0.102525 -vn -3.201059 -2.649023 3.086867 -v 0.005892 -0.011700 0.102501 -vn -3.933957 2.284535 2.250528 -v 0.005815 -0.011613 0.102401 -vn -4.058363 -2.704491 1.955515 -v 0.005709 -0.011735 0.102186 -vn -4.094398 2.233518 1.926384 -v 0.005760 -0.011623 0.102305 -vn -4.401232 2.657038 1.234165 -v 0.005698 -0.011638 0.102157 -vn -4.379321 -2.661363 1.212836 -v 0.005681 -0.011744 0.102094 -vn -4.507569 2.611281 0.726309 -v 0.005680 -0.011644 0.102094 -vn -4.561653 2.450015 0.344271 -v 0.005653 -0.011661 0.101926 -vn -2.179299 -2.495660 3.940677 -v 0.006173 -0.011665 0.102728 -vn -1.256774 -2.668581 4.390475 -v 0.006320 -0.011650 0.102793 -vn -2.399131 2.538305 3.830243 -v 0.006195 -0.011563 0.102741 -vn -2.706182 1.827105 3.477147 -v 0.006006 -0.011585 0.102615 -vn 0.192044 -2.658065 4.581387 -v 0.006650 -0.011618 0.102850 -vn -0.382678 2.668673 4.524043 -v 0.006650 -0.011519 0.102850 -vn -0.400899 -2.585632 4.550305 -v 0.006514 -0.011631 0.102840 -vn -1.142858 2.589427 4.385598 -v 0.006430 -0.011540 0.102825 -vn -1.645243 2.606477 4.265940 -v 0.006351 -0.011547 0.102804 -vn 0.394647 2.612618 -4.507634 -v 0.006650 -0.011219 0.100850 -vn -0.106640 -2.604759 -4.554484 -v 0.006650 -0.011318 0.100850 -vn -0.358786 2.612947 -4.564783 -v 0.006518 -0.011206 0.100859 -vn -0.719163 -2.621091 -4.517499 -v 0.006556 -0.011309 0.100854 -vn -0.969847 2.612851 -4.437232 -v 0.006411 -0.011196 0.100879 -vn -1.532028 -2.567248 -4.277249 -v 0.006382 -0.011292 0.100887 -vn -1.821345 2.620026 -4.177646 -v 0.006159 -0.011169 0.100979 -vn -1.990650 -2.449879 -4.080062 -v 0.006227 -0.011276 0.100944 -vn -2.292651 2.633524 -3.958286 -v 0.006145 -0.011168 0.100987 -vn -2.709686 -2.603082 -3.642056 -v 0.006133 -0.011266 0.100994 -vn -3.225481 -2.643452 -3.209258 -v 0.005943 -0.011243 0.101143 -vn -2.920109 2.620787 -3.484453 -v 0.005943 -0.011143 0.101143 -vn -3.650570 -2.659978 -2.766701 -v 0.005912 -0.011238 0.101175 -vn -3.533233 2.442972 -2.889387 -v 0.005850 -0.011130 0.101250 -vn -3.796056 2.596991 -2.524747 -v 0.005794 -0.011120 0.101333 -vn -4.050418 -2.629428 -2.087285 -v 0.005779 -0.011217 0.101359 -vn -4.281807 -2.475495 -1.548513 -v 0.005733 -0.011207 0.101452 -vn -4.271955 2.618402 -1.417075 -v 0.005687 -0.011094 0.101582 -vn -4.470929 -2.572333 -0.718533 -v 0.005679 -0.011191 0.101611 -vn -4.473666 2.577201 -0.259911 -v 0.005650 -0.011068 0.101850 -vn -4.496335 -2.561989 0.249686 -v 0.005650 -0.011167 0.101850 -vn -4.413699 2.577125 0.774067 -v 0.005679 -0.011045 0.102089 -vn -4.258208 -2.580811 1.460982 -v 0.005687 -0.011141 0.102119 -vn -4.247913 2.526898 1.622168 -v 0.005757 -0.011024 0.102300 -vn -3.705071 -2.574864 2.581281 -v 0.005794 -0.011115 0.102367 -vn -3.990334 2.661401 2.200825 -v 0.005779 -0.011019 0.102341 -vn -3.543063 2.639553 2.860455 -v 0.005943 -0.010993 0.102557 -vn -3.124477 -2.624573 3.299469 -v 0.005943 -0.011092 0.102557 -vn -3.157986 2.668736 3.321429 -v 0.005984 -0.010988 0.102596 -vn -2.546844 -2.614269 3.804881 -v 0.006050 -0.011079 0.102650 -vn -2.528144 2.630289 3.775747 -v 0.006133 -0.010970 0.102706 -vn -0.626212 -2.579852 4.493744 -v 0.006411 -0.011040 0.102821 -vn 0.038265 -2.655195 4.522710 -v 0.006650 -0.011017 0.102850 -vn -0.309474 2.623421 4.505193 -v 0.006650 -0.010918 0.102850 -vn -1.877909 -2.578920 4.140773 -v 0.006159 -0.011066 0.102721 -vn -1.251450 -2.620203 4.387150 -v 0.006351 -0.011046 0.102804 -vn -1.976067 2.507622 4.124171 -v 0.006298 -0.010952 0.102786 -vn -1.322004 2.626968 4.362105 -v 0.006382 -0.010944 0.102813 -vn -4.242552 -2.577835 1.521772 -v 0.005687 -0.010541 0.102118 -vn -4.436764 2.649449 1.017543 -v 0.005679 -0.010445 0.102089 -vn -4.546518 2.498995 0.434656 -v 0.005666 -0.010451 0.102027 -vn -4.500340 -2.618364 0.244901 -v 0.005650 -0.010567 0.101850 -vn -4.541842 2.598529 -0.266373 -v 0.005650 -0.010468 0.101850 -vn -4.462067 2.583408 -0.988256 -v 0.005670 -0.010487 0.101653 -vn -4.401807 -2.653606 -0.860578 -v 0.005679 -0.010590 0.101611 -vn -4.240458 2.586286 -1.672464 -v 0.005687 -0.010494 0.101581 -vn -4.045143 -2.553271 -1.945963 -v 0.005779 -0.010616 0.101359 -vn -3.721613 2.543937 -2.558216 -v 0.005794 -0.010520 0.101333 -vn -3.477835 -2.605491 -2.924807 -v 0.005943 -0.010642 0.101143 -vn -3.094920 2.609242 -3.310334 -v 0.005943 -0.010543 0.101143 -vn -3.025157 -2.649552 -3.452764 -v 0.006040 -0.010655 0.101058 -vn -2.511052 2.673847 -3.820206 -v 0.006063 -0.010558 0.101040 -vn -2.447145 -2.643196 -3.845580 -v 0.006133 -0.010665 0.100994 -vn -1.835043 2.582707 -4.152352 -v 0.006159 -0.010569 0.100979 -vn -1.470056 -2.561390 -4.266120 -v 0.006382 -0.010691 0.100887 -vn 0.096608 2.624314 -4.525384 -v 0.006650 -0.010618 0.100850 -vn -0.325422 -2.612966 -4.511060 -v 0.006650 -0.010717 0.100850 -vn -0.557956 2.608298 -4.526240 -v 0.006411 -0.010595 0.100879 -vn -1.136455 2.683446 -4.421724 -v 0.006402 -0.010594 0.100881 -vn -4.054951 2.547151 1.958883 -v 0.005779 -0.010419 0.102341 -vn -3.722294 -2.547068 2.547343 -v 0.005794 -0.010515 0.102367 -vn -3.475156 2.602183 2.932576 -v 0.005943 -0.010393 0.102557 -vn -3.122553 -2.604675 3.304857 -v 0.005943 -0.010492 0.102557 -vn -3.001855 2.653616 3.468803 -v 0.006042 -0.010380 0.102644 -vn -2.591434 -2.654964 3.769645 -v 0.006039 -0.010480 0.102642 -vn -2.446487 2.629811 3.839137 -v 0.006133 -0.010370 0.102706 -vn -1.888186 -2.573456 4.135211 -v 0.006159 -0.010467 0.102721 -vn -1.457138 2.616013 4.263768 -v 0.006382 -0.010344 0.102813 -vn 0.242754 -2.621769 4.465406 -v 0.006650 -0.010418 0.102850 -vn -0.437731 2.622873 4.537403 -v 0.006650 -0.010318 0.102850 -vn -0.604004 -2.596722 4.520039 -v 0.006411 -0.010441 0.102821 -vn -1.276780 -2.614398 4.382869 -v 0.006365 -0.010445 0.102809 -vn 0.473996 2.660583 4.557521 -v 0.006846 -0.020500 0.102831 -vn 1.413046 -2.537786 4.292264 -v 0.006884 -0.020756 0.102824 -vn 4.256855 -2.584538 -1.541322 -v 0.007613 -0.020545 0.101585 -vn 4.429919 2.600823 -0.987181 -v 0.007621 -0.020346 0.101611 -vn 4.560880 2.590081 -0.344681 -v 0.007641 -0.020356 0.101719 -vn 4.518169 -2.583553 -0.336309 -v 0.007649 -0.020580 0.101851 -vn 4.533663 2.593098 0.383258 -v 0.007650 -0.020369 0.101850 -vn 4.557291 -2.603044 0.527907 -v 0.007621 -0.020613 0.102094 -vn 4.269770 2.572172 1.454886 -v 0.007613 -0.020395 0.102119 -vn 4.403089 -2.609109 1.177490 -v 0.007613 -0.020617 0.102123 -vn 3.860360 2.617753 2.402879 -v 0.007506 -0.020421 0.102367 -vn 4.062744 -2.593527 1.974353 -v 0.007504 -0.020652 0.102370 -vn 3.494001 2.655581 2.953091 -v 0.007457 -0.020429 0.102441 -vn 3.701659 -2.672189 2.722182 -v 0.007388 -0.020677 0.102524 -vn 2.970982 2.624122 3.431428 -v 0.007357 -0.020444 0.102557 -vn 3.284275 -2.669919 3.133406 -v 0.007356 -0.020683 0.102557 -vn 2.435417 2.626832 3.857227 -v 0.007198 -0.020463 0.102686 -vn 2.469515 -2.544300 3.736660 -v 0.007138 -0.020720 0.102724 -vn 1.819361 2.625778 4.190885 -v 0.007141 -0.020470 0.102721 -vn 1.090721 2.639343 4.430521 -v 0.006889 -0.020496 0.102821 -vn 4.038291 2.549397 -1.999599 -v 0.007521 -0.020320 0.101359 -vn 3.738695 -2.520380 -2.521303 -v 0.007519 -0.020512 0.101354 -vn 3.512252 2.606170 -2.904948 -v 0.007357 -0.020294 0.101143 -vn 3.152414 -2.626187 -3.306525 -v 0.007357 -0.020477 0.101143 -vn 2.664402 -2.695392 -3.694505 -v 0.007336 -0.020473 0.101123 -vn 3.019462 2.612443 -3.432129 -v 0.007279 -0.020284 0.101073 -vn 1.942982 -2.642219 -4.047031 -v 0.007156 -0.020444 0.100989 -vn 1.462437 2.590366 -4.347580 -v 0.006918 -0.020244 0.100887 -vn 1.699331 2.242844 -4.185532 -v 0.006964 -0.020249 0.100901 -vn 2.488012 2.591206 -3.793084 -v 0.007167 -0.020270 0.100994 -vn 1.086657 -2.639527 -4.426396 -v 0.006910 -0.020409 0.100885 -vn 0.478783 -2.651520 -4.552025 -v 0.006855 -0.020401 0.100871 -vn 0.771630 2.626305 -4.507858 -v 0.006754 -0.020228 0.100855 -vn 0.269821 2.601112 4.575942 -v 0.006766 -0.019907 0.102843 -vn 1.044135 -2.680143 4.457776 -v 0.006846 -0.019998 0.102831 -vn 0.863598 2.680652 4.501698 -v 0.006887 -0.019896 0.102822 -vn 1.624337 -2.656481 4.269519 -v 0.006918 -0.019991 0.102813 -vn 1.564162 2.470992 4.274416 -v 0.007033 -0.019881 0.102774 -vn 2.540592 -2.559525 3.742318 -v 0.007167 -0.019965 0.102706 -vn 2.312441 2.615102 3.946464 -v 0.007224 -0.019860 0.102669 -vn 2.762312 2.273284 3.599112 -v 0.007256 -0.019856 0.102646 -vn 3.553911 2.651917 2.848493 -v 0.007448 -0.019830 0.102452 -vn 4.110206 -2.453554 1.909700 -v 0.007521 -0.019916 0.102341 -vn 4.071781 2.482831 1.949513 -v 0.007584 -0.019803 0.102207 -vn 4.444444 -2.654481 0.849803 -v 0.007621 -0.019890 0.102089 -vn 4.359847 2.656672 1.358988 -v 0.007620 -0.019792 0.102094 -vn 3.138740 2.575760 3.327282 -v 0.007388 -0.019839 0.102525 -vn 3.250651 -2.482259 3.150896 -v 0.007357 -0.019942 0.102557 -vn 3.823680 -2.645124 2.516102 -v 0.007457 -0.019928 0.102441 -vn 4.511526 2.531607 0.775308 -v 0.007644 -0.019778 0.101956 -vn 4.554979 -2.646849 -0.207195 -v 0.007650 -0.019867 0.101850 -vn 4.556264 2.662086 0.219359 -v 0.007650 -0.019769 0.101858 -vn 4.552254 2.646832 -0.393139 -v 0.007638 -0.019754 0.101695 -vn 4.501585 -2.626420 -0.824236 -v 0.007641 -0.019855 0.101719 -vn 4.496909 2.655509 -0.912058 -v 0.007620 -0.019745 0.101606 -vn 4.282256 -2.651741 -1.541969 -v 0.007613 -0.019841 0.101581 -vn 4.226109 2.550666 -1.583732 -v 0.007574 -0.019731 0.101467 -vn 3.915591 -2.461559 -2.354377 -v 0.007522 -0.019818 0.101361 -vn 3.755863 2.540548 -2.500680 -v 0.007432 -0.019704 0.101226 -vn 3.714204 -2.418459 -2.644988 -v 0.007506 -0.019815 0.101333 -vn 3.113720 -2.668139 -3.344103 -v 0.007357 -0.019792 0.101143 -vn 3.319014 2.675202 -3.103547 -v 0.007357 -0.019693 0.101143 -vn 2.613127 -2.472081 -3.752493 -v 0.007279 -0.019782 0.101073 -vn 2.405225 2.617964 -3.812179 -v 0.007136 -0.019667 0.100976 -vn 2.001761 -2.605499 -4.093111 -v 0.007141 -0.019766 0.100979 -vn 1.341698 -2.581072 -4.374585 -v 0.006964 -0.019748 0.100901 -vn 1.546571 2.673316 -4.261408 -v 0.006918 -0.019644 0.100887 -vn 0.697657 -2.664608 -4.511208 -v 0.006889 -0.019740 0.100879 -vn 0.814680 2.535376 -4.483159 -v 0.006774 -0.019630 0.100858 -vn 3.324156 -2.666477 3.163376 -v 0.007357 -0.019343 0.102557 -vn 2.994554 2.646385 3.375075 -v 0.007357 -0.019243 0.102557 -vn 2.912313 -2.492662 3.526261 -v 0.007224 -0.019359 0.102669 -vn 2.155343 2.685957 4.025165 -v 0.007141 -0.019269 0.102721 -vn 2.451938 -2.674751 3.839942 -v 0.007167 -0.019366 0.102706 -vn 1.650189 2.518039 4.256220 -v 0.007098 -0.019274 0.102744 -vn 1.456112 -2.580803 4.263752 -v 0.006918 -0.019392 0.102813 -vn 0.818517 2.558326 4.459902 -v 0.006889 -0.019295 0.102821 -vn 0.324824 2.421673 4.528448 -v 0.006737 -0.019310 0.102846 -vn 3.649895 -2.594995 2.765759 -v 0.007388 -0.019338 0.102525 -vn 3.860891 -2.589540 2.441808 -v 0.007483 -0.019324 0.102403 -vn 3.693584 2.669603 2.630206 -v 0.007506 -0.019220 0.102367 -vn 4.171256 -2.655458 1.855729 -v 0.007521 -0.019317 0.102341 -vn 4.117686 2.311958 1.861991 -v 0.007573 -0.019206 0.102234 -vn 4.304310 2.545539 1.414139 -v 0.007613 -0.019194 0.102119 -vn 4.432942 -2.547897 0.811500 -v 0.007621 -0.019291 0.102089 -vn 4.504993 2.558779 0.261586 -v 0.007650 -0.019168 0.101850 -vn 4.501644 -2.561593 -0.250268 -v 0.007650 -0.019268 0.101850 -vn 4.519696 2.579003 -0.660846 -v 0.007621 -0.019145 0.101611 -vn 4.363816 -2.660251 -1.307386 -v 0.007613 -0.019242 0.101581 -vn 4.366733 2.685659 -1.333344 -v 0.007596 -0.019137 0.101525 -vn 4.142068 -2.641004 -1.949715 -v 0.007585 -0.019233 0.101495 -vn 4.082143 2.631132 -1.985572 -v 0.007521 -0.019119 0.101359 -vn 3.736166 -2.626003 -2.590279 -v 0.007506 -0.019216 0.101333 -vn 3.723531 2.632901 -2.647689 -v 0.007417 -0.019102 0.101208 -vn 3.312629 -2.690778 -3.169185 -v 0.007390 -0.019197 0.101177 -vn 3.259173 2.620103 -3.174730 -v 0.007357 -0.019093 0.101143 -vn 2.834114 -2.631004 -3.561796 -v 0.007357 -0.019193 0.101143 -vn 2.245313 -2.675652 -3.961140 -v 0.007141 -0.019167 0.100979 -vn 2.563081 2.551962 -3.693203 -v 0.007167 -0.019070 0.100994 -vn 1.714858 -2.561565 -4.245261 -v 0.007124 -0.019165 0.100969 -vn 1.476355 2.569599 -4.234532 -v 0.006918 -0.019044 0.100887 -vn 0.870322 -2.547601 -4.457845 -v 0.006889 -0.019141 0.100879 -vn 0.444046 -2.288564 -4.513102 -v 0.006774 -0.019130 0.100858 -vn 4.469029 2.481218 0.856797 -v 0.007635 -0.018585 0.102024 -vn 4.240729 2.656949 1.623855 -v 0.007613 -0.018595 0.102119 -vn 4.482355 -2.656587 0.750407 -v 0.007621 -0.018691 0.102089 -vn 0.142365 2.675560 4.586923 -v 0.006714 -0.018713 0.102848 -vn 0.755127 -2.645774 4.518414 -v 0.006737 -0.018810 0.102846 -vn 0.831623 2.617923 4.488871 -v 0.006889 -0.018696 0.102821 -vn 1.484728 -2.626104 4.297891 -v 0.006918 -0.018792 0.102813 -vn 1.548646 2.629357 4.304781 -v 0.007060 -0.018678 0.102762 -vn 2.182375 -2.687144 4.019668 -v 0.007098 -0.018774 0.102744 -vn 2.171147 2.658132 3.994276 -v 0.007141 -0.018670 0.102721 -vn 2.752280 -2.566242 3.630873 -v 0.007167 -0.018766 0.102706 -vn 3.229163 -2.630798 3.214920 -v 0.007357 -0.018743 0.102557 -vn 2.946348 2.623590 3.366865 -v 0.007357 -0.018644 0.102557 -vn 3.658633 -2.603497 2.711223 -v 0.007388 -0.018739 0.102525 -vn 3.682699 2.598395 2.527390 -v 0.007506 -0.018621 0.102367 -vn 4.055445 -2.560603 2.026800 -v 0.007521 -0.018717 0.102341 -vn 4.237823 -2.289206 1.609658 -v 0.007573 -0.018705 0.102234 -vn 4.531674 2.581865 0.277623 -v 0.007650 -0.018569 0.101850 -vn 4.507945 -2.581979 -0.230532 -v 0.007650 -0.018668 0.101850 -vn 4.556777 2.506733 -0.461362 -v 0.007632 -0.018551 0.101662 -vn 4.374757 -2.673420 -1.329303 -v 0.007613 -0.018642 0.101581 -vn 4.461470 2.680185 -0.994126 -v 0.007621 -0.018546 0.101611 -vn 4.176558 -2.497347 -1.865754 -v 0.007596 -0.018636 0.101525 -vn 4.054258 2.603312 -1.979865 -v 0.007521 -0.018520 0.101359 -vn 3.762996 -2.597079 -2.558338 -v 0.007506 -0.018616 0.101333 -vn 3.416553 -2.495332 -3.031821 -v 0.007417 -0.018601 0.101209 -vn 3.467397 2.666081 -2.936767 -v 0.007357 -0.018494 0.101143 -vn 2.909646 -2.667872 -3.493571 -v 0.007357 -0.018593 0.101143 -vn 0.606316 -2.596678 -4.532267 -v 0.006889 -0.018541 0.100879 -vn 1.263246 2.678009 -4.390096 -v 0.006918 -0.018445 0.100887 -vn 1.157145 -2.701869 -4.424176 -v 0.006918 -0.018544 0.100887 -vn 1.841508 2.593259 -4.194785 -v 0.006959 -0.018449 0.100899 -vn 2.012438 -2.577419 -4.037547 -v 0.007141 -0.018567 0.100979 -vn 2.564019 2.551867 -3.753599 -v 0.007167 -0.018471 0.100994 -vn 2.912664 2.333423 -3.484234 -v 0.007275 -0.018483 0.101069 -vn 1.854996 2.665678 4.175655 -v 0.007141 -0.018070 0.102721 -vn 1.040331 2.657715 4.447042 -v 0.006889 -0.018096 0.102821 -vn 1.507914 -2.567919 4.305249 -v 0.006918 -0.018191 0.102813 -vn 0.511840 2.596564 4.549234 -v 0.006846 -0.018100 0.102831 -vn 0.671984 -2.611727 4.526271 -v 0.006714 -0.018211 0.102848 -vn 1.955767 -2.389626 4.111059 -v 0.007059 -0.018177 0.102762 -vn 2.663974 -2.665706 3.696599 -v 0.007167 -0.018165 0.102706 -vn 2.445771 2.599543 3.848168 -v 0.007198 -0.018063 0.102686 -vn 3.273752 -2.654548 3.202504 -v 0.007357 -0.018142 0.102557 -vn 2.960410 2.647383 3.443856 -v 0.007357 -0.018044 0.102557 -vn 3.648589 -2.661181 2.756642 -v 0.007388 -0.018138 0.102525 -vn 3.509807 2.554862 2.923785 -v 0.007457 -0.018029 0.102441 -vn 4.094323 -2.574298 1.917556 -v 0.007521 -0.018116 0.102341 -vn 3.836399 2.629802 2.448066 -v 0.007506 -0.018021 0.102367 -vn 4.255707 2.571974 1.520227 -v 0.007613 -0.017995 0.102119 -vn 4.444248 -2.644559 1.008385 -v 0.007621 -0.018090 0.102089 -vn 4.550544 -2.493267 0.436599 -v 0.007635 -0.018084 0.102025 -vn 4.537459 2.629191 0.354976 -v 0.007650 -0.017969 0.101850 -vn 4.529805 -2.637381 -0.254860 -v 0.007650 -0.018067 0.101850 -vn 4.567447 2.624619 -0.309935 -v 0.007641 -0.017956 0.101719 -vn 4.450417 -2.689549 -1.009831 -v 0.007632 -0.018049 0.101662 -vn 4.435357 2.663916 -0.983178 -v 0.007621 -0.017946 0.101611 -vn 4.224502 -2.589081 -1.672949 -v 0.007613 -0.018041 0.101581 -vn 4.060329 2.543370 -1.964728 -v 0.007521 -0.017920 0.101359 -vn 3.716534 -2.550846 -2.542579 -v 0.007506 -0.018015 0.101333 -vn 3.501992 2.612358 -2.917081 -v 0.007357 -0.017894 0.101143 -vn 3.133306 -2.618822 -3.292143 -v 0.007357 -0.017992 0.101143 -vn 3.041995 2.666360 -3.416972 -v 0.007279 -0.017884 0.101073 -vn 2.620128 -2.663107 -3.743692 -v 0.007275 -0.017982 0.101069 -vn 2.511348 2.635583 -3.783586 -v 0.007167 -0.017870 0.100994 -vn 1.936840 -2.604598 -4.110052 -v 0.007141 -0.017966 0.100979 -vn 1.844425 2.658044 -4.181840 -v 0.006964 -0.017849 0.100901 -vn 1.312426 -2.666917 -4.370798 -v 0.006959 -0.017947 0.100899 -vn 1.373189 2.693773 -4.379725 -v 0.006918 -0.017844 0.100887 -vn 0.662682 -2.665645 -4.492199 -v 0.006889 -0.017940 0.100879 -vn 0.776053 2.533031 -4.502339 -v 0.006754 -0.017828 0.100855 -vn 0.269791 2.601112 4.575945 -v 0.006766 -0.017507 0.102843 -vn 1.044349 -2.680179 4.457287 -v 0.006846 -0.017598 0.102831 -vn 0.863645 2.680717 4.501681 -v 0.006887 -0.017496 0.102822 -vn 1.630803 -2.663234 4.250999 -v 0.006918 -0.017591 0.102813 -vn 1.564150 2.470997 4.274411 -v 0.007033 -0.017481 0.102774 -vn 2.526743 -2.566233 3.736967 -v 0.007167 -0.017565 0.102706 -vn 2.312503 2.614999 3.946406 -v 0.007224 -0.017460 0.102669 -vn 2.762350 2.273288 3.599097 -v 0.007256 -0.017456 0.102646 -vn 3.553891 2.651857 2.848501 -v 0.007448 -0.017430 0.102452 -vn 4.109905 -2.453727 1.909542 -v 0.007521 -0.017516 0.102341 -vn 4.071782 2.482826 1.949525 -v 0.007584 -0.017403 0.102207 -vn 4.444139 -2.654638 0.849714 -v 0.007621 -0.017490 0.102089 -vn 4.359861 2.656666 1.358984 -v 0.007620 -0.017392 0.102094 -vn 3.138735 2.575765 3.327278 -v 0.007388 -0.017439 0.102525 -vn 3.250457 -2.482430 3.150574 -v 0.007357 -0.017542 0.102557 -vn 3.823580 -2.645367 2.515772 -v 0.007457 -0.017528 0.102441 -vn 4.511519 2.531611 0.775302 -v 0.007644 -0.017378 0.101956 -vn 4.554648 -2.647010 -0.207248 -v 0.007650 -0.017467 0.101850 -vn 4.556268 2.662087 0.219371 -v 0.007650 -0.017369 0.101858 -vn 4.552279 2.646866 -0.393098 -v 0.007638 -0.017354 0.101695 -vn 4.501211 -2.626691 -0.824395 -v 0.007641 -0.017455 0.101719 -vn 4.496931 2.655525 -0.912059 -v 0.007620 -0.017345 0.101606 -vn 4.281914 -2.651909 -1.541980 -v 0.007613 -0.017441 0.101581 -vn 4.226060 2.550609 -1.583706 -v 0.007574 -0.017331 0.101467 -vn 3.915120 -2.461678 -2.354429 -v 0.007522 -0.017418 0.101361 -vn 3.755843 2.540554 -2.500699 -v 0.007432 -0.017304 0.101226 -vn 3.686159 -2.428075 -2.647469 -v 0.007506 -0.017415 0.101333 -vn 3.110115 -2.678926 -3.320868 -v 0.007357 -0.017392 0.101143 -vn 3.319003 2.675182 -3.103542 -v 0.007357 -0.017293 0.101143 -vn 2.612838 -2.472219 -3.752351 -v 0.007279 -0.017382 0.101073 -vn 2.405175 2.617950 -3.812196 -v 0.007136 -0.017267 0.100976 -vn 2.001500 -2.605652 -4.092893 -v 0.007141 -0.017366 0.100979 -vn 1.341420 -2.581280 -4.374371 -v 0.006964 -0.017348 0.100901 -vn 1.546717 2.673319 -4.261396 -v 0.006918 -0.017244 0.100887 -vn 0.697562 -2.664838 -4.510942 -v 0.006889 -0.017340 0.100879 -vn 0.814619 2.535204 -4.483032 -v 0.006774 -0.017230 0.100858 -vn 3.324001 -2.666620 3.163181 -v 0.007357 -0.016943 0.102557 -vn 2.994566 2.646385 3.375054 -v 0.007357 -0.016843 0.102557 -vn 2.912338 -2.492762 3.526015 -v 0.007224 -0.016959 0.102669 -vn 2.155380 2.685977 4.025139 -v 0.007141 -0.016869 0.102721 -vn 2.451954 -2.674824 3.839566 -v 0.007167 -0.016966 0.102706 -vn 1.650204 2.518021 4.256191 -v 0.007098 -0.016874 0.102744 -vn 1.456055 -2.580928 4.263509 -v 0.006918 -0.016992 0.102813 -vn 0.818527 2.558324 4.459911 -v 0.006889 -0.016895 0.102821 -vn 0.324821 2.421663 4.528467 -v 0.006737 -0.016910 0.102846 -vn 3.649750 -2.595069 2.765546 -v 0.007388 -0.016938 0.102525 -vn 3.860766 -2.589744 2.441515 -v 0.007483 -0.016924 0.102403 -vn 3.693564 2.669575 2.630286 -v 0.007506 -0.016820 0.102367 -vn 4.168474 -2.657625 1.850470 -v 0.007521 -0.016917 0.102341 -vn 4.117623 2.311911 1.861934 -v 0.007573 -0.016806 0.102234 -vn 4.304347 2.545536 1.414089 -v 0.007613 -0.016794 0.102119 -vn 4.429237 -2.549724 0.813191 -v 0.007621 -0.016891 0.102089 -vn 4.504985 2.558781 0.261593 -v 0.007650 -0.016768 0.101850 -vn 4.501413 -2.561707 -0.250288 -v 0.007650 -0.016868 0.101850 -vn 4.519706 2.578997 -0.660844 -v 0.007621 -0.016745 0.101611 -vn 4.363575 -2.660370 -1.307350 -v 0.007613 -0.016842 0.101581 -vn 4.366763 2.685680 -1.333318 -v 0.007596 -0.016737 0.101525 -vn 4.141798 -2.641065 -1.949714 -v 0.007585 -0.016833 0.101495 -vn 4.082175 2.631161 -1.985571 -v 0.007521 -0.016719 0.101359 -vn 3.735952 -2.626141 -2.590222 -v 0.007506 -0.016816 0.101333 -vn 3.723388 2.632758 -2.647707 -v 0.007417 -0.016702 0.101208 -vn 3.312371 -2.690992 -3.169173 -v 0.007390 -0.016797 0.101177 -vn 3.259128 2.620108 -3.174834 -v 0.007357 -0.016693 0.101143 -vn 2.833948 -2.631117 -3.561661 -v 0.007357 -0.016793 0.101143 -vn 2.244704 -2.675489 -3.961114 -v 0.007141 -0.016767 0.100979 -vn 2.563083 2.551947 -3.693216 -v 0.007167 -0.016670 0.100994 -vn 1.714406 -2.561743 -4.245342 -v 0.007124 -0.016765 0.100969 -vn 1.468951 2.572854 -4.230883 -v 0.006918 -0.016644 0.100887 -vn 0.870208 -2.547718 -4.457632 -v 0.006889 -0.016741 0.100879 -vn 0.443932 -2.288657 -4.512939 -v 0.006774 -0.016730 0.100858 -vn 4.469008 2.481132 0.856787 -v 0.007635 -0.016185 0.102024 -vn 4.240728 2.656960 1.623895 -v 0.007613 -0.016195 0.102119 -vn 4.482224 -2.656680 0.750374 -v 0.007621 -0.016291 0.102089 -vn 0.142327 2.675614 4.586935 -v 0.006714 -0.016313 0.102848 -vn 0.755127 -2.645774 4.518200 -v 0.006737 -0.016410 0.102846 -vn 0.831623 2.617953 4.488883 -v 0.006889 -0.016296 0.102821 -vn 1.484739 -2.626187 4.297767 -v 0.006918 -0.016392 0.102813 -vn 1.548616 2.629429 4.304720 -v 0.007060 -0.016278 0.102762 -vn 2.182371 -2.687103 4.019442 -v 0.007098 -0.016373 0.102744 -vn 2.171252 2.658192 3.994248 -v 0.007141 -0.016270 0.102721 -vn 2.752299 -2.566350 3.630703 -v 0.007167 -0.016366 0.102706 -vn 3.229073 -2.630873 3.214797 -v 0.007357 -0.016343 0.102557 -vn 2.946338 2.623596 3.366856 -v 0.007357 -0.016244 0.102557 -vn 3.658515 -2.603575 2.711123 -v 0.007388 -0.016339 0.102525 -vn 3.682695 2.598401 2.527394 -v 0.007506 -0.016221 0.102367 -vn 4.055329 -2.560678 2.026679 -v 0.007521 -0.016317 0.102341 -vn 4.237781 -2.289449 1.609501 -v 0.007573 -0.016305 0.102234 -vn 4.531679 2.581865 0.277608 -v 0.007650 -0.016169 0.101850 -vn 4.507815 -2.582042 -0.230539 -v 0.007650 -0.016268 0.101850 -vn 4.556770 2.506737 -0.461361 -v 0.007632 -0.016151 0.101662 -vn 4.374629 -2.673499 -1.329267 -v 0.007613 -0.016242 0.101581 -vn 4.461472 2.680201 -0.994103 -v 0.007621 -0.016146 0.101611 -vn 4.176378 -2.497329 -1.865736 -v 0.007596 -0.016236 0.101525 -vn 4.054254 2.603356 -1.979873 -v 0.007521 -0.016120 0.101359 -vn 3.762875 -2.597181 -2.558299 -v 0.007506 -0.016216 0.101333 -vn 3.416336 -2.495290 -3.031779 -v 0.007417 -0.016201 0.101208 -vn 3.467472 2.666161 -2.936723 -v 0.007357 -0.016094 0.101143 -vn 2.909464 -2.668028 -3.493601 -v 0.007357 -0.016193 0.101143 -vn 0.603315 -2.592793 -4.539742 -v 0.006889 -0.016141 0.100879 -vn 1.263236 2.678033 -4.390099 -v 0.006918 -0.016045 0.100887 -vn 1.172863 -2.708192 -4.409695 -v 0.006918 -0.016144 0.100887 -vn 1.841524 2.593260 -4.194777 -v 0.006959 -0.016049 0.100899 -vn 1.986917 -2.586879 -4.025636 -v 0.007141 -0.016167 0.100979 -vn 2.563987 2.551867 -3.753634 -v 0.007167 -0.016071 0.100994 -vn 2.912510 2.333075 -3.484216 -v 0.007275 -0.016083 0.101069 -vn 1.854991 2.665679 4.175653 -v 0.007141 -0.015670 0.102721 -vn 1.040329 2.657717 4.447038 -v 0.006889 -0.015696 0.102821 -vn 1.507937 -2.567967 4.305145 -v 0.006918 -0.015791 0.102813 -vn 0.511855 2.596601 4.549230 -v 0.006846 -0.015700 0.102831 -vn 0.671943 -2.611721 4.526170 -v 0.006714 -0.015811 0.102848 -vn 1.955801 -2.389724 4.111025 -v 0.007059 -0.015777 0.102762 -vn 2.663928 -2.665741 3.696553 -v 0.007167 -0.015765 0.102706 -vn 2.445768 2.599545 3.848164 -v 0.007198 -0.015663 0.102686 -vn 3.273752 -2.654605 3.202319 -v 0.007357 -0.015742 0.102557 -vn 2.960406 2.647386 3.443853 -v 0.007357 -0.015644 0.102557 -vn 3.648654 -2.661165 2.756593 -v 0.007388 -0.015738 0.102525 -vn 3.509805 2.554867 2.923768 -v 0.007457 -0.015629 0.102441 -vn 4.094248 -2.574333 1.917534 -v 0.007521 -0.015716 0.102341 -vn 3.836413 2.629799 2.448059 -v 0.007506 -0.015621 0.102367 -vn 4.255708 2.571977 1.520234 -v 0.007613 -0.015595 0.102119 -vn 4.444196 -2.644592 1.008393 -v 0.007621 -0.015690 0.102089 -vn 4.550464 -2.493280 0.436589 -v 0.007635 -0.015684 0.102024 -vn 4.537460 2.629197 0.354970 -v 0.007650 -0.015569 0.101850 -vn 4.529765 -2.637406 -0.254880 -v 0.007650 -0.015667 0.101850 -vn 4.567445 2.624598 -0.309939 -v 0.007641 -0.015556 0.101719 -vn 4.450366 -2.689592 -1.009852 -v 0.007632 -0.015649 0.101662 -vn 4.435357 2.663913 -0.983175 -v 0.007621 -0.015546 0.101611 -vn 4.224473 -2.589094 -1.672945 -v 0.007613 -0.015641 0.101581 -vn 4.060330 2.543370 -1.964728 -v 0.007521 -0.015520 0.101359 -vn 3.716504 -2.550865 -2.542557 -v 0.007506 -0.015615 0.101333 -vn 3.501992 2.612358 -2.917081 -v 0.007357 -0.015494 0.101143 -vn 3.133239 -2.618844 -3.292135 -v 0.007357 -0.015592 0.101143 -vn 3.042003 2.666367 -3.416966 -v 0.007279 -0.015484 0.101073 -vn 2.620057 -2.663113 -3.743728 -v 0.007275 -0.015582 0.101069 -vn 2.511345 2.635590 -3.783589 -v 0.007167 -0.015470 0.100994 -vn 1.936793 -2.604607 -4.110052 -v 0.007141 -0.015566 0.100979 -vn 1.844522 2.657898 -4.181874 -v 0.006964 -0.015449 0.100901 -vn 1.312488 -2.667066 -4.370821 -v 0.006959 -0.015547 0.100899 -vn 1.373293 2.693753 -4.379626 -v 0.006918 -0.015444 0.100887 -vn 0.662772 -2.665669 -4.492085 -v 0.006889 -0.015540 0.100879 -vn 0.776006 2.533059 -4.502302 -v 0.006754 -0.015428 0.100855 -vn 0.269836 2.601104 4.575964 -v 0.006766 -0.015107 0.102843 -vn 1.044410 -2.680193 4.457232 -v 0.006846 -0.015198 0.102831 -vn 0.863641 2.680714 4.501689 -v 0.006887 -0.015096 0.102822 -vn 1.630873 -2.663204 4.251031 -v 0.006918 -0.015191 0.102813 -vn 1.564160 2.470983 4.274417 -v 0.007033 -0.015081 0.102774 -vn 2.526750 -2.566222 3.736982 -v 0.007167 -0.015165 0.102706 -vn 2.312505 2.614996 3.946404 -v 0.007224 -0.015060 0.102669 -vn 2.762351 2.273267 3.599101 -v 0.007256 -0.015056 0.102646 -vn 3.553890 2.651857 2.848502 -v 0.007448 -0.015030 0.102452 -vn 4.109905 -2.453727 1.909542 -v 0.007521 -0.015116 0.102341 -vn 4.071782 2.482826 1.949525 -v 0.007584 -0.015003 0.102207 -vn 4.444132 -2.654642 0.849706 -v 0.007621 -0.015090 0.102089 -vn 4.359861 2.656666 1.358984 -v 0.007620 -0.014992 0.102094 -vn 3.138747 2.575759 3.327278 -v 0.007388 -0.015039 0.102525 -vn 3.250456 -2.482410 3.150622 -v 0.007357 -0.015142 0.102557 -vn 3.823551 -2.645377 2.515785 -v 0.007457 -0.015128 0.102441 -vn 4.511519 2.531611 0.775302 -v 0.007644 -0.014978 0.101956 -vn 4.554642 -2.647014 -0.207244 -v 0.007650 -0.015067 0.101850 -vn 4.556268 2.662087 0.219371 -v 0.007650 -0.014969 0.101858 -vn 4.552279 2.646866 -0.393098 -v 0.007638 -0.014954 0.101695 -vn 4.501184 -2.626698 -0.824427 -v 0.007641 -0.015055 0.101719 -vn 4.496931 2.655525 -0.912058 -v 0.007620 -0.014945 0.101606 -vn 4.281953 -2.651887 -1.542001 -v 0.007613 -0.015041 0.101581 -vn 4.226060 2.550606 -1.583706 -v 0.007574 -0.014931 0.101467 -vn 3.915119 -2.461684 -2.354409 -v 0.007522 -0.015018 0.101361 -vn 3.755842 2.540550 -2.500700 -v 0.007432 -0.014904 0.101226 -vn 3.686141 -2.428077 -2.647479 -v 0.007506 -0.015015 0.101333 -vn 3.110177 -2.678902 -3.320888 -v 0.007357 -0.014992 0.101143 -vn 3.319017 2.675178 -3.103538 -v 0.007357 -0.014893 0.101143 -vn 2.612857 -2.472237 -3.752308 -v 0.007279 -0.014982 0.101073 -vn 2.405156 2.617968 -3.812162 -v 0.007136 -0.014867 0.100976 -vn 2.001500 -2.605653 -4.092893 -v 0.007141 -0.014966 0.100979 -vn 1.341410 -2.581286 -4.374364 -v 0.006964 -0.014948 0.100901 -vn 1.546702 2.673318 -4.261410 -v 0.006918 -0.014844 0.100887 -vn 0.697565 -2.664843 -4.510934 -v 0.006889 -0.014940 0.100879 -vn 0.814619 2.535204 -4.483032 -v 0.006774 -0.014830 0.100858 -vn 3.324033 -2.666648 3.163042 -v 0.007357 -0.014543 0.102557 -vn 2.994565 2.646386 3.375056 -v 0.007357 -0.014443 0.102557 -vn 2.912338 -2.492762 3.526015 -v 0.007224 -0.014559 0.102669 -vn 2.155380 2.685977 4.025139 -v 0.007141 -0.014469 0.102721 -vn 2.451946 -2.674829 3.839562 -v 0.007167 -0.014566 0.102706 -vn 1.650204 2.518021 4.256191 -v 0.007098 -0.014474 0.102744 -vn 1.456058 -2.580932 4.263500 -v 0.006918 -0.014592 0.102813 -vn 0.818550 2.558323 4.459911 -v 0.006889 -0.014495 0.102821 -vn 0.324782 2.421718 4.528398 -v 0.006737 -0.014510 0.102846 -vn 3.649865 -2.595023 2.765517 -v 0.007388 -0.014538 0.102525 -vn 3.860775 -2.589717 2.441610 -v 0.007483 -0.014524 0.102403 -vn 3.693565 2.669576 2.630286 -v 0.007506 -0.014420 0.102367 -vn 4.168413 -2.657650 1.850488 -v 0.007521 -0.014517 0.102341 -vn 4.117629 2.311905 1.861942 -v 0.007573 -0.014406 0.102234 -vn 4.304363 2.545527 1.414094 -v 0.007613 -0.014394 0.102119 -vn 4.429271 -2.549707 0.813201 -v 0.007621 -0.014491 0.102089 -vn 4.504994 2.558777 0.261587 -v 0.007650 -0.014368 0.101850 -vn 4.501403 -2.561714 -0.250271 -v 0.007650 -0.014468 0.101850 -vn 4.519706 2.578997 -0.660844 -v 0.007621 -0.014345 0.101611 -vn 4.363575 -2.660370 -1.307350 -v 0.007613 -0.014442 0.101581 -vn 4.366763 2.685680 -1.333318 -v 0.007596 -0.014337 0.101525 -vn 4.141798 -2.641065 -1.949714 -v 0.007585 -0.014433 0.101495 -vn 4.082175 2.631161 -1.985571 -v 0.007521 -0.014319 0.101359 -vn 3.735952 -2.626141 -2.590222 -v 0.007506 -0.014416 0.101333 -vn 3.723388 2.632758 -2.647707 -v 0.007417 -0.014302 0.101208 -vn 3.312371 -2.690992 -3.169173 -v 0.007390 -0.014397 0.101177 -vn 3.259128 2.620108 -3.174834 -v 0.007357 -0.014293 0.101143 -vn 2.833948 -2.631117 -3.561661 -v 0.007357 -0.014393 0.101143 -vn 2.244704 -2.675489 -3.961114 -v 0.007141 -0.014367 0.100979 -vn 2.563083 2.551947 -3.693216 -v 0.007167 -0.014270 0.100994 -vn 1.714406 -2.561743 -4.245342 -v 0.007124 -0.014365 0.100969 -vn 1.468951 2.572852 -4.230884 -v 0.006918 -0.014244 0.100887 -vn 0.870208 -2.547718 -4.457632 -v 0.006889 -0.014341 0.100879 -vn 0.443932 -2.288657 -4.512939 -v 0.006774 -0.014330 0.100858 -vn 4.469004 2.481134 0.856786 -v 0.007635 -0.013785 0.102024 -vn 4.240726 2.656961 1.623893 -v 0.007613 -0.013795 0.102119 -vn 4.482208 -2.656688 0.750370 -v 0.007621 -0.013891 0.102089 -vn 0.142327 2.675614 4.586935 -v 0.006714 -0.013913 0.102848 -vn 0.755133 -2.645779 4.518190 -v 0.006737 -0.014010 0.102846 -vn 0.831623 2.617953 4.488883 -v 0.006889 -0.013896 0.102821 -vn 1.484732 -2.626191 4.297760 -v 0.006918 -0.013992 0.102813 -vn 1.548616 2.629429 4.304720 -v 0.007060 -0.013878 0.102762 -vn 2.182371 -2.687103 4.019442 -v 0.007098 -0.013973 0.102744 -vn 2.171252 2.658192 3.994247 -v 0.007141 -0.013870 0.102721 -vn 2.752299 -2.566350 3.630703 -v 0.007167 -0.013966 0.102706 -vn 3.229073 -2.630873 3.214797 -v 0.007357 -0.013943 0.102557 -vn 2.946337 2.623597 3.366854 -v 0.007357 -0.013844 0.102557 -vn 3.658515 -2.603575 2.711123 -v 0.007388 -0.013939 0.102525 -vn 3.682693 2.598400 2.527393 -v 0.007506 -0.013821 0.102367 -vn 4.055329 -2.560678 2.026679 -v 0.007521 -0.013917 0.102341 -vn 4.237774 -2.289452 1.609492 -v 0.007573 -0.013905 0.102234 -vn 4.531674 2.581867 0.277608 -v 0.007650 -0.013769 0.101850 -vn 4.507799 -2.582051 -0.230540 -v 0.007650 -0.013868 0.101850 -vn 4.556766 2.506739 -0.461360 -v 0.007632 -0.013751 0.101662 -vn 4.374624 -2.673502 -1.329261 -v 0.007613 -0.013842 0.101581 -vn 4.461469 2.680202 -0.994100 -v 0.007621 -0.013746 0.101611 -vn 4.176378 -2.497329 -1.865736 -v 0.007596 -0.013836 0.101525 -vn 4.054253 2.603358 -1.979873 -v 0.007521 -0.013720 0.101359 -vn 3.762875 -2.597181 -2.558299 -v 0.007506 -0.013816 0.101333 -vn 3.416272 -2.495302 -3.031801 -v 0.007417 -0.013801 0.101208 -vn 3.467472 2.666162 -2.936720 -v 0.007357 -0.013694 0.101143 -vn 2.909477 -2.668001 -3.493661 -v 0.007357 -0.013793 0.101143 -vn 0.603318 -2.592797 -4.539732 -v 0.006889 -0.013741 0.100879 -vn 1.263237 2.678032 -4.390100 -v 0.006918 -0.013645 0.100887 -vn 1.172857 -2.708200 -4.409679 -v 0.006918 -0.013744 0.100887 -vn 1.841524 2.593260 -4.194777 -v 0.006959 -0.013649 0.100899 -vn 1.986917 -2.586888 -4.025616 -v 0.007141 -0.013767 0.100979 -vn 2.563988 2.551866 -3.753633 -v 0.007167 -0.013671 0.100994 -vn 2.912507 2.333061 -3.484216 -v 0.007275 -0.013683 0.101069 -vn 1.908561 2.660132 4.107014 -v 0.007141 -0.013270 0.102721 -vn 1.195783 2.664575 4.401530 -v 0.006912 -0.013293 0.102815 -vn 1.476640 -2.593854 4.314659 -v 0.006918 -0.013391 0.102813 -vn 0.633570 2.636601 4.539826 -v 0.006889 -0.013296 0.102821 -vn 0.694115 -2.567444 4.521451 -v 0.006714 -0.013411 0.102848 -vn 1.955828 -2.389732 4.110985 -v 0.007059 -0.013377 0.102762 -vn 2.655084 -2.654114 3.703122 -v 0.007167 -0.013365 0.102706 -vn 2.593685 2.532369 3.747614 -v 0.007265 -0.013255 0.102639 -vn 3.302803 -2.689472 3.177953 -v 0.007357 -0.013342 0.102557 -vn 3.090053 2.666807 3.335677 -v 0.007357 -0.013244 0.102557 -vn 3.670898 -2.593916 2.725491 -v 0.007388 -0.013338 0.102525 -vn 3.652352 2.622719 2.761435 -v 0.007506 -0.013221 0.102367 -vn 4.073879 -2.612221 1.955317 -v 0.007521 -0.013316 0.102341 -vn 3.983702 2.637649 2.256019 -v 0.007522 -0.013217 0.102339 -vn 4.271636 2.563239 1.577010 -v 0.007613 -0.013195 0.102119 -vn 4.447120 -2.623432 0.992439 -v 0.007621 -0.013290 0.102089 -vn 4.501536 2.553478 0.732914 -v 0.007644 -0.013179 0.101963 -vn 4.547921 -2.597023 0.488815 -v 0.007635 -0.013284 0.102024 -vn 4.539339 2.589741 0.141272 -v 0.007650 -0.013169 0.101850 -vn 4.525035 -2.590351 -0.304059 -v 0.007650 -0.013267 0.101850 -vn 4.528509 2.676668 -0.649678 -v 0.007621 -0.013146 0.101611 -vn 4.456733 -2.525362 -0.900302 -v 0.007632 -0.013249 0.101662 -vn 4.230514 -2.648717 -1.660375 -v 0.007613 -0.013241 0.101581 -vn 4.394982 2.607771 -1.269343 -v 0.007610 -0.013141 0.101569 -vn 3.752597 -2.615391 -2.493042 -v 0.007506 -0.013215 0.101333 -vn 0.757522 2.538869 -4.504742 -v 0.006745 -0.013028 0.100854 -vn 0.659641 -2.660388 -4.492553 -v 0.006889 -0.013140 0.100879 -vn 1.504111 2.667820 -4.276053 -v 0.006918 -0.013044 0.100887 -vn 1.320111 -2.610761 -4.366429 -v 0.006959 -0.013147 0.100899 -vn 2.214360 2.651232 -3.989983 -v 0.007122 -0.013066 0.100968 -vn 1.959285 -2.664361 -4.100486 -v 0.007141 -0.013166 0.100979 -vn 2.720896 2.663013 -3.672126 -v 0.007167 -0.013070 0.100994 -vn 2.621077 -2.532462 -3.735135 -v 0.007275 -0.013182 0.101069 -vn 3.333005 2.677395 -3.100068 -v 0.007357 -0.013094 0.101143 -vn 3.090354 -2.674686 -3.343582 -v 0.007357 -0.013192 0.101143 -vn 3.730701 2.534125 -2.633045 -v 0.007427 -0.013104 0.101220 -vn 4.133145 2.548277 -1.907144 -v 0.007521 -0.013120 0.101359 -vn 0.330793 2.607523 4.532009 -v 0.006766 -0.012707 0.102843 -vn 1.077632 -2.572423 4.436532 -v 0.006846 -0.012798 0.102831 -vn 1.258639 2.496428 4.372095 -v 0.006984 -0.012686 0.102792 -vn 3.341992 -2.668583 3.067763 -v 0.007357 -0.012742 0.102557 -vn 2.844765 2.584428 3.599990 -v 0.007323 -0.012648 0.102590 -vn 2.520255 -2.497876 3.744417 -v 0.007167 -0.012765 0.102706 -vn 2.514919 2.416141 3.774911 -v 0.007256 -0.012656 0.102646 -vn 1.564750 -2.560692 4.281528 -v 0.006918 -0.012791 0.102813 -vn 1.584884 2.296438 4.251198 -v 0.007033 -0.012681 0.102774 -vn 4.446294 -2.653813 0.837886 -v 0.007621 -0.012690 0.102089 -vn 4.187038 2.472861 1.858599 -v 0.007584 -0.012603 0.102207 -vn 4.079784 -2.480896 1.987930 -v 0.007521 -0.012716 0.102341 -vn 3.994601 2.543566 2.207247 -v 0.007557 -0.012610 0.102271 -vn 3.832018 -2.613998 2.486151 -v 0.007457 -0.012728 0.102441 -vn 3.558569 2.620564 2.877739 -v 0.007448 -0.012630 0.102452 -vn 3.237524 2.628865 3.248655 -v 0.007388 -0.012639 0.102525 -vn 4.538673 -2.628339 -0.219250 -v 0.007650 -0.012667 0.101850 -vn 4.502611 2.534738 0.807425 -v 0.007644 -0.012578 0.101956 -vn 4.372375 2.654733 1.341219 -v 0.007620 -0.012592 0.102094 -vn 3.702435 -2.422817 -2.645772 -v 0.007506 -0.012615 0.101333 -vn 3.097137 -2.686424 -3.336953 -v 0.007357 -0.012592 0.101143 -vn 3.778509 2.536640 -2.487095 -v 0.007432 -0.012504 0.101226 -vn 3.917538 -2.458537 -2.361110 -v 0.007522 -0.012618 0.101361 -vn 4.222570 2.552799 -1.666791 -v 0.007574 -0.012531 0.101467 -vn 4.294158 -2.661816 -1.533302 -v 0.007613 -0.012641 0.101581 -vn 4.394563 2.578874 -1.350606 -v 0.007586 -0.012534 0.101498 -vn 4.516038 2.660179 -0.879999 -v 0.007620 -0.012545 0.101606 -vn 4.493119 -2.631961 -0.816946 -v 0.007641 -0.012655 0.101719 -vn 4.544345 2.648381 -0.370641 -v 0.007638 -0.012554 0.101695 -vn 4.553971 2.658522 0.324687 -v 0.007649 -0.012572 0.101888 -vn 0.361977 -2.446882 -4.537861 -v 0.006754 -0.012527 0.100855 -vn 0.511310 2.595678 -4.537186 -v 0.006669 -0.012420 0.100850 -vn 0.707452 -2.598238 -4.524617 -v 0.006889 -0.012540 0.100879 -vn 1.369722 2.665779 -4.320185 -v 0.006918 -0.012444 0.100887 -vn 1.293103 -2.659299 -4.401603 -v 0.006964 -0.012548 0.100901 -vn 2.040581 2.607155 -4.098910 -v 0.007054 -0.012458 0.100935 -vn 2.028695 -2.633655 -4.082515 -v 0.007141 -0.012566 0.100979 -vn 2.552406 2.646870 -3.779349 -v 0.007136 -0.012467 0.100976 -vn 2.612238 -2.477666 -3.741015 -v 0.007279 -0.012582 0.101073 -vn 3.272974 2.705971 -3.191242 -v 0.007357 -0.012493 0.101143 -vn 3.570527 2.684648 -2.913403 -v 0.007377 -0.012496 0.101163 -vn 0.099228 2.611810 4.569487 -v 0.006669 -0.012116 0.102850 -vn 1.414542 -2.612673 4.269902 -v 0.006918 -0.012192 0.102813 -vn 0.731199 2.560094 4.477635 -v 0.006889 -0.012095 0.102821 -vn 1.565838 2.476322 4.280262 -v 0.007054 -0.012078 0.102765 -vn 2.463313 -2.670873 3.839617 -v 0.007167 -0.012166 0.102706 -vn 2.092613 2.655705 4.039124 -v 0.007141 -0.012069 0.102721 -vn 2.912327 -2.492826 3.525966 -v 0.007224 -0.012159 0.102669 -vn 2.884570 2.672897 3.552812 -v 0.007357 -0.012043 0.102557 -vn 3.324213 -2.666396 3.172144 -v 0.007357 -0.012143 0.102557 -vn 3.283314 2.689600 3.177825 -v 0.007377 -0.012040 0.102537 -vn 3.652637 -2.643973 2.772399 -v 0.007388 -0.012138 0.102525 -vn 3.715735 2.662852 2.592362 -v 0.007506 -0.012020 0.102367 -vn 4.444463 -2.577253 0.770477 -v 0.007621 -0.012091 0.102089 -vn 4.141190 2.480251 1.904577 -v 0.007586 -0.012002 0.102202 -vn 4.169151 -2.643260 1.856079 -v 0.007521 -0.012117 0.102341 -vn 3.862389 -2.592443 2.439683 -v 0.007483 -0.012124 0.102403 -vn 4.500010 -2.597923 -0.229983 -v 0.007650 -0.012068 0.101850 -vn 4.547144 2.640723 0.490706 -v 0.007650 -0.011968 0.101850 -vn 4.351002 2.631013 1.326577 -v 0.007613 -0.011994 0.102119 -vn 1.993634 -2.601416 -4.018798 -v 0.007141 -0.011967 0.100979 -vn 1.708026 2.117940 -4.165857 -v 0.006984 -0.011851 0.100908 -vn 2.608069 2.558727 -3.717766 -v 0.007167 -0.011870 0.100994 -vn 2.859415 -2.686643 -3.533261 -v 0.007357 -0.011993 0.101143 -vn 3.091440 2.538984 -3.364209 -v 0.007323 -0.011889 0.101110 -vn 3.439324 2.722291 -3.064666 -v 0.007357 -0.011893 0.101143 -vn 3.326459 -2.661855 -3.129818 -v 0.007390 -0.011997 0.101177 -vn 3.647716 2.664727 -2.751856 -v 0.007388 -0.011898 0.101175 -vn 3.712413 -2.599831 -2.608902 -v 0.007506 -0.012016 0.101333 -vn 4.050819 2.617601 -2.098150 -v 0.007521 -0.011919 0.101359 -vn 4.164085 -2.545704 -1.860798 -v 0.007585 -0.012033 0.101495 -vn 4.247771 2.561892 -1.647707 -v 0.007557 -0.011927 0.101429 -vn 4.340792 -2.600050 -1.351914 -v 0.007613 -0.012042 0.101581 -vn 4.461511 2.567964 -0.760931 -v 0.007621 -0.011945 0.101611 -vn 4.557389 2.573179 -0.165531 -v 0.007649 -0.011965 0.101812 -vn 1.365603 2.547745 -4.326974 -v 0.006918 -0.011844 0.100887 -vn 0.887348 -2.545095 -4.445809 -v 0.006889 -0.011941 0.100879 -vn 0.444307 -2.290196 -4.509930 -v 0.006774 -0.011930 0.100858 -vn 0.254063 2.654991 4.566298 -v 0.006745 -0.011510 0.102845 -vn 0.735071 -2.655118 4.519865 -v 0.006737 -0.011610 0.102846 -vn 0.899864 2.612404 4.445846 -v 0.006889 -0.011496 0.102821 -vn 1.520999 -2.579950 4.279962 -v 0.006918 -0.011592 0.102813 -vn 1.737375 2.669015 4.236362 -v 0.007122 -0.011472 0.102732 -vn 2.113580 -2.598874 4.046662 -v 0.007098 -0.011573 0.102744 -vn 2.238736 2.664484 3.986603 -v 0.007141 -0.011470 0.102721 -vn 2.755907 -2.571023 3.613988 -v 0.007167 -0.011566 0.102706 -vn 3.213539 -2.637640 3.213763 -v 0.007357 -0.011543 0.102557 -vn 2.894783 2.615123 3.523025 -v 0.007357 -0.011444 0.102557 -vn 3.648931 -2.674757 2.767703 -v 0.007388 -0.011539 0.102525 -vn 3.462557 2.540819 2.991410 -v 0.007427 -0.011434 0.102480 -vn 3.791203 2.573268 2.515890 -v 0.007506 -0.011421 0.102367 -vn 4.073505 -2.562140 2.019426 -v 0.007521 -0.011517 0.102341 -vn 4.240614 2.656936 1.735514 -v 0.007610 -0.011396 0.102130 -vn 4.239200 -2.358593 1.602307 -v 0.007573 -0.011505 0.102234 -vn 4.479375 -2.579640 0.696584 -v 0.007621 -0.011491 0.102089 -vn 4.467978 2.568703 -0.848777 -v 0.007621 -0.011346 0.101611 -vn 4.526994 2.320948 -0.407952 -v 0.007644 -0.011358 0.101736 -vn 4.498871 -2.606144 -0.218231 -v 0.007650 -0.011468 0.101850 -vn 4.526018 2.613584 0.411076 -v 0.007650 -0.011369 0.101850 -vn 4.401069 2.681841 1.234275 -v 0.007613 -0.011395 0.102119 -vn 4.372081 -2.648605 -1.295677 -v 0.007613 -0.011442 0.101581 -vn 4.163892 -2.504185 -1.861463 -v 0.007596 -0.011436 0.101525 -vn 4.026023 2.593757 -2.002194 -v 0.007521 -0.011320 0.101359 -vn 3.691079 -2.560976 -2.611423 -v 0.007506 -0.011416 0.101333 -vn 3.479243 2.615300 -2.899463 -v 0.007357 -0.011294 0.101143 -vn 3.123949 -2.610601 -3.297300 -v 0.007357 -0.011393 0.101143 -vn 3.014284 2.664430 -3.444673 -v 0.007265 -0.011282 0.101061 -vn 2.570438 -2.661169 -3.789264 -v 0.007256 -0.011380 0.101055 -vn 2.456725 2.636862 -3.818987 -v 0.007167 -0.011271 0.100994 -vn 1.871983 -2.574570 -4.139975 -v 0.007141 -0.011367 0.100979 -vn 1.446573 2.603829 -4.257699 -v 0.006918 -0.011245 0.100887 -vn 0.604937 -2.592035 -4.541196 -v 0.006889 -0.011341 0.100879 -vn 1.213461 -2.649245 -4.403342 -v 0.006918 -0.011344 0.100887 -vn 0.691921 -2.571240 4.516418 -v 0.006714 -0.011011 0.102848 -vn 0.731122 2.620348 4.481063 -v 0.006889 -0.010895 0.102821 -vn 1.424472 -2.647345 4.318547 -v 0.006918 -0.010991 0.102813 -vn 1.448549 2.653035 4.344174 -v 0.007024 -0.010881 0.102777 -vn 2.078559 -2.671669 4.064506 -v 0.007059 -0.010977 0.102762 -vn 2.144227 2.631592 4.010230 -v 0.007141 -0.010869 0.102721 -vn 2.711048 -2.562997 3.633923 -v 0.007167 -0.010965 0.102706 -vn 3.218191 -2.634444 3.217889 -v 0.007357 -0.010942 0.102557 -vn 2.956888 2.600998 3.413849 -v 0.007357 -0.010843 0.102557 -vn 3.668459 -2.591949 2.740242 -v 0.007388 -0.010938 0.102525 -vn 3.680009 2.608684 2.692618 -v 0.007506 -0.010820 0.102367 -vn 4.074680 -2.636460 1.977257 -v 0.007521 -0.010916 0.102341 -vn 4.092882 2.439102 2.002123 -v 0.007556 -0.010810 0.102272 -vn 4.291410 2.573753 1.506891 -v 0.007613 -0.010794 0.102119 -vn 4.455062 -2.638303 1.020240 -v 0.007621 -0.010890 0.102089 -vn 4.563502 -2.577637 0.465150 -v 0.007635 -0.010884 0.102024 -vn 4.513779 2.639022 0.670513 -v 0.007648 -0.010774 0.101913 -vn 4.541569 -2.622651 -0.331760 -v 0.007650 -0.010867 0.101850 -vn 4.555392 2.637545 0.054446 -v 0.007650 -0.010768 0.101850 -vn 4.420578 2.637591 -0.857886 -v 0.007621 -0.010745 0.101611 -vn 4.469508 -2.518374 -0.910319 -v 0.007632 -0.010849 0.101662 -vn 4.227958 -2.587950 -1.673017 -v 0.007613 -0.010841 0.101581 -vn 4.021960 2.563041 -1.956160 -v 0.007521 -0.010719 0.101359 -vn 3.720495 -2.548794 -2.544814 -v 0.007506 -0.010815 0.101333 -vn 3.402655 2.629827 -2.929952 -v 0.007357 -0.010693 0.101143 -vn 3.131327 -2.616685 -3.293846 -v 0.007357 -0.010792 0.101143 -vn 2.621244 -2.533330 -3.735765 -v 0.007275 -0.010782 0.101069 -vn 2.719753 2.666136 -3.664034 -v 0.007167 -0.010670 0.100994 -vn 1.959828 -2.665018 -4.100112 -v 0.007141 -0.010766 0.100979 -vn 2.222805 2.644794 -3.995795 -v 0.007121 -0.010665 0.100968 -vn 1.321070 -2.611428 -4.368225 -v 0.006959 -0.010747 0.100899 -vn 1.519912 2.667817 -4.287863 -v 0.006918 -0.010644 0.100887 -vn 0.700879 -2.657575 -4.522104 -v 0.006889 -0.010740 0.100879 -vn 0.806969 2.528303 -4.498781 -v 0.006767 -0.010629 0.100857 -vn 3.304663 2.696430 3.175390 -v 0.007391 -0.010238 0.102522 -vn 2.850099 2.627552 3.559311 -v 0.007357 -0.010243 0.102557 -vn 3.237932 -2.623419 3.223653 -v 0.007357 -0.010342 0.102557 -vn 2.199362 2.648685 3.985714 -v 0.007141 -0.010269 0.102721 -vn 2.605126 -2.553916 3.687646 -v 0.007167 -0.010365 0.102706 -vn 1.647518 2.511079 4.261110 -v 0.007095 -0.010274 0.102746 -vn 1.424317 -2.599040 4.244403 -v 0.006918 -0.010392 0.102813 -vn 0.825385 2.551393 4.475871 -v 0.006889 -0.010295 0.102821 -vn 0.317524 2.418256 4.547898 -v 0.006736 -0.010310 0.102846 -vn 3.609610 -2.698248 2.848733 -v 0.007388 -0.010338 0.102525 -vn 3.829401 -2.610929 2.496240 -v 0.007456 -0.010328 0.102442 -vn 3.750620 2.659923 2.579726 -v 0.007506 -0.010220 0.102367 -vn 4.132433 -2.641539 1.897490 -v 0.007521 -0.010316 0.102341 -vn 4.140629 2.469807 1.927557 -v 0.007583 -0.010203 0.102211 -vn 4.457904 -2.568903 0.783309 -v 0.007621 -0.010290 0.102089 -vn 4.354530 2.622121 1.328977 -v 0.007613 -0.010194 0.102119 -vn 4.492048 2.625371 0.315346 -v 0.007650 -0.010168 0.101850 -vn 0.188389 -2.669533 -4.571757 -v 0.006725 -0.010124 0.100853 -vn 0.728790 2.660979 -4.510762 -v 0.006733 -0.010026 0.100853 -vn 0.820785 -2.622707 -4.480859 -v 0.006889 -0.010140 0.100879 -vn 1.442651 2.629505 -4.325761 -v 0.006918 -0.010044 0.100887 -vn 1.560529 -2.650019 -4.304615 -v 0.007054 -0.010157 0.100935 -vn 2.004524 2.648761 -4.102489 -v 0.007042 -0.010056 0.100930 -vn 2.145562 -2.630322 -4.020179 -v 0.007141 -0.010166 0.100979 -vn 2.677912 2.578563 -3.659165 -v 0.007167 -0.010070 0.100994 -vn 3.005664 -2.560380 -3.361884 -v 0.007357 -0.010192 0.101143 -vn 3.354355 2.564157 -3.003942 -v 0.007357 -0.010093 0.101143 -vn 3.644915 -2.587152 -2.743552 -v 0.007506 -0.010215 0.101333 -vn 4.004679 2.668594 -2.154964 -v 0.007521 -0.010119 0.101359 -vn 4.015752 -2.685741 -2.206563 -v 0.007541 -0.010222 0.101397 -vn 4.301119 2.622404 -1.547336 -v 0.007562 -0.010128 0.101440 -vn 4.305106 -2.624361 -1.492398 -v 0.007613 -0.010241 0.101582 -vn 4.462045 2.633802 -0.772506 -v 0.007621 -0.010145 0.101611 -vn 4.511002 -2.533042 -0.769513 -v 0.007645 -0.010258 0.101753 -vn 4.568345 -2.621295 -0.086230 -v 0.007650 -0.010267 0.101850 -vn -0.101544 1.668693 5.707046 -v 0.006650 -0.041610 0.103725 -vn -1.145307 0.230708 6.124727 -v 0.006331 -0.041610 0.103698 -vn -1.966029 1.317939 5.577596 -v 0.005932 -0.041610 0.103582 -vn -3.042162 0.236114 5.447383 -v 0.005824 -0.041610 0.103533 -vn -3.946155 0.252243 4.837420 -v 0.005383 -0.041610 0.103232 -vn -4.521030 1.210573 3.903234 -v 0.005324 -0.041610 0.103176 -vn -5.245260 0.263758 3.354738 -v 0.005045 -0.041610 0.102819 -vn -5.234166 1.704424 2.206349 -v 0.004918 -0.041610 0.102568 -vn -6.070864 0.236573 1.405575 -v 0.004837 -0.041610 0.102328 -vn -6.117793 0.793760 0.449492 -v 0.004775 -0.041610 0.101850 -vn -6.112485 -0.829715 -0.325930 -v 0.004775 -0.042410 0.101850 -vn -5.923252 -0.818650 -1.410978 -v 0.004831 -0.042410 0.101394 -vn -5.583282 -1.154746 -2.182402 -v 0.004918 -0.042410 0.101132 -vn -5.187795 -0.768516 -3.235284 -v 0.005034 -0.042410 0.100900 -vn -4.566042 -0.823119 -4.083267 -v 0.005324 -0.042410 0.100524 -vn -3.920013 -0.779001 -4.716769 -v 0.005367 -0.042410 0.100483 -vn -3.031531 -0.762695 -5.319023 -v 0.005804 -0.042410 0.100177 -vn -0.208656 -1.046836 -6.038562 -v 0.006650 -0.042410 0.099975 -vn -1.102698 -0.797295 -5.994443 -v 0.006310 -0.042410 0.100006 -vn -2.123290 -0.868457 -5.723106 -v 0.005932 -0.042410 0.100118 -vn 0.214234 2.575929 4.560723 -v 0.006733 -0.009710 0.102847 -vn 1.124858 -2.431479 4.428122 -v 0.006861 -0.009796 0.102827 -vn 1.834597 1.962590 4.871474 -v 0.006997 -0.009710 0.102788 -vn 1.542975 -2.489734 4.285933 -v 0.006918 -0.009791 0.102813 -vn 2.493342 -2.409273 3.746900 -v 0.007167 -0.009765 0.102706 -vn 3.160391 1.716781 4.097045 -v 0.007219 -0.009710 0.102672 -vn 3.889823 2.175386 3.465300 -v 0.007412 -0.009710 0.102497 -vn 3.025877 -1.707446 3.119311 -v 0.007377 -0.009739 0.102536 -vn 3.814192 -2.175014 2.440599 -v 0.007447 -0.009729 0.102454 -vn 4.447005 1.457529 2.688495 -v 0.007516 -0.009710 0.102350 -vn 4.049244 -1.915117 1.876283 -v 0.007535 -0.009714 0.102316 -vn 3.379560 -0.507367 1.285717 -v 0.007554 -0.009710 0.102278 -vn -0.906679 6.119460 0.422617 -v 0.005083 -0.041410 0.102443 -vn -0.677290 6.184789 0.381482 -v 0.005216 -0.041410 0.102716 -vn -0.796578 6.179502 0.066900 -v 0.004975 -0.041410 0.101850 -vn -0.753285 6.186737 0.160924 -v 0.005030 -0.041410 0.102277 -vn 0.489089 6.145106 0.779657 -v 0.007420 -0.041410 0.103338 -vn 0.470520 6.185470 0.615521 -v 0.007711 -0.041410 0.103146 -vn 0.741065 6.188044 0.192171 -v 0.008243 -0.041410 0.102367 -vn 0.660033 6.153253 0.602787 -v 0.007897 -0.041410 0.102968 -vn 0.645327 6.187326 0.416780 -v 0.008034 -0.041410 0.102795 -vn 0.753643 6.171171 0.349707 -v 0.008211 -0.041410 0.102456 -vn 0.177978 6.179683 0.778575 -v 0.006885 -0.041410 0.103509 -vn 0.259306 6.187853 0.721008 -v 0.007303 -0.041410 0.103393 -vn -0.687582 6.154077 0.566788 -v 0.005374 -0.041410 0.102935 -vn -0.505695 6.190103 0.564460 -v 0.005518 -0.041410 0.103085 -vn -0.498426 6.154277 0.737790 -v 0.005743 -0.041410 0.103259 -vn -0.314768 6.188357 0.696485 -v 0.005912 -0.041410 0.103354 -vn -0.234910 6.172724 0.790936 -v 0.006281 -0.041410 0.103484 -vn -0.083035 6.188228 0.760415 -v 0.006365 -0.041410 0.103501 -vn 0.035267 6.188860 0.761844 -v 0.006842 -0.041410 0.103514 -vn -4.788081 0.439508 -2.300695 -v 0.005773 -0.021063 0.101399 -vn -3.493978 -0.026512 0.636544 -v 0.005702 -0.021011 0.101924 -vn -2.074988 0.153370 3.036013 -v 0.006115 -0.020929 0.102565 -vn -2.448139 0.025023 2.133664 -v 0.005922 -0.020957 0.102397 -vn -3.079652 0.009067 0.020077 -v 0.006115 -0.020418 0.101850 -vn -3.115525 0.068901 -0.680666 -v 0.006123 -0.020449 0.101671 -vn -2.675488 0.040797 -1.721730 -v 0.006201 -0.020484 0.101481 -vn -1.924755 0.026584 -2.517450 -v 0.006340 -0.020516 0.101333 -vn -1.139810 0.035750 -2.850067 -v 0.006519 -0.020548 0.101239 -vn -0.645508 0.027441 -2.986372 -v 0.006557 -0.020554 0.101227 -vn -0.083833 0.028186 -3.073745 -v 0.006722 -0.020579 0.101206 -vn 0.447233 0.023839 -3.034762 -v 0.006784 -0.020588 0.101210 -vn 1.164310 0.033322 -2.949363 -v 0.006934 -0.020610 0.101245 -vn 1.845863 0.055633 -2.587180 -v 0.007128 -0.020641 0.101351 -vn 2.322854 0.027217 -2.075642 -v 0.007220 -0.020658 0.101438 -vn 2.557927 0.020653 -1.694040 -v 0.007280 -0.020671 0.101516 -vn 2.797467 0.011172 -1.366458 -v 0.007313 -0.020680 0.101573 -vn 2.970928 0.027786 -0.846540 -v 0.007372 -0.020702 0.101727 -vn 3.064578 0.026527 -0.373610 -v 0.007391 -0.020714 0.101819 -vn 3.117765 0.021556 0.165415 -v 0.007396 -0.020732 0.101963 -vn 3.046849 0.032392 0.758786 -v 0.007378 -0.020748 0.102089 -vn 2.966425 0.054329 1.212200 -v 0.007347 -0.020761 0.102190 -vn 2.448194 0.028148 2.000391 -v 0.007225 -0.020791 0.102398 -vn 1.950344 0.056701 2.434303 -v 0.007052 -0.020819 0.102560 -vn 1.554389 0.008443 2.670506 -v 0.007044 -0.020820 0.102565 -vn 1.086487 0.021599 2.922157 -v 0.006843 -0.020846 0.102662 -vn 0.618644 0.011002 3.052683 -v 0.006785 -0.020853 0.102678 -vn 0.024642 0.026297 3.165141 -v 0.006597 -0.020874 0.102701 -vn -0.311770 0.051184 3.189162 -v 0.006481 -0.020887 0.102695 -vn -0.886588 -0.007331 3.004983 -v 0.006343 -0.020902 0.102668 -vn -1.369927 0.029280 2.840161 -v 0.006211 -0.020918 0.102619 -vn -2.911831 0.066691 1.135500 -v 0.005763 -0.020988 0.102141 -vn -2.843866 0.077312 1.404897 -v 0.005778 -0.020984 0.102174 -vn -3.470353 -0.086442 -0.222602 -v 0.005701 -0.021037 0.101662 -vn -2.907801 0.070717 -0.882082 -v 0.005730 -0.021051 0.101522 -vn -3.892006 1.473830 4.455959 -v 0.005384 -0.041581 0.103231 -vn -2.739879 1.466977 5.245568 -v 0.005825 -0.041581 0.103531 -vn 1.096457 5.322639 2.632452 -v 0.007338 -0.041431 0.103475 -vn -2.760824 5.322852 0.710726 -v 0.004943 -0.041431 0.102300 -vn -2.445663 5.323546 1.459222 -v 0.005139 -0.041431 0.102762 -vn -1.931425 5.320465 2.112703 -v 0.005457 -0.041431 0.103151 -vn -1.247600 5.321823 2.569706 -v 0.005872 -0.041431 0.103434 -vn -0.467758 5.322250 2.814884 -v 0.006350 -0.041431 0.103589 -vn 0.317588 5.323435 2.829908 -v 0.006852 -0.041431 0.103603 -vn 1.791399 5.323664 2.213309 -v 0.007768 -0.041431 0.103216 -vn 2.365278 5.321702 1.602527 -v 0.008107 -0.041431 0.102845 -vn 2.719672 5.322293 0.863065 -v 0.008329 -0.041431 0.102394 -vn 6.019464 0.250764 1.632235 -v 0.008434 -0.041610 0.102428 -vn 5.671980 1.460263 1.689744 -v 0.008432 -0.041581 0.102428 -vn 5.290800 1.477456 2.455413 -v 0.008382 -0.041610 0.102568 -vn 4.897379 1.447957 3.326635 -v 0.008197 -0.041581 0.102906 -vn 3.646086 1.451275 4.661910 -v 0.007836 -0.041581 0.103299 -vn 4.186890 1.599120 3.941126 -v 0.007976 -0.041610 0.103176 -vn 5.156838 0.236125 3.497657 -v 0.008198 -0.041610 0.102907 -vn -1.042836 1.447857 5.827657 -v 0.006332 -0.041581 0.103696 -vn 0.799876 1.443933 5.864057 -v 0.006865 -0.041581 0.103711 -vn 0.959697 0.249742 6.155855 -v 0.006865 -0.041610 0.103713 -vn 2.304066 1.357968 5.443200 -v 0.007380 -0.041581 0.103575 -vn 2.413849 0.271136 5.705083 -v 0.007381 -0.041610 0.103577 -vn 3.730095 0.240645 4.993871 -v 0.007838 -0.041610 0.103301 -vn -5.013709 1.425977 3.143325 -v 0.005047 -0.041581 0.102818 -vn -5.746059 1.447536 1.422350 -v 0.004839 -0.041581 0.102327 -vn -4.716316 3.420739 1.242668 -v 0.004873 -0.041494 0.102318 -vn -4.175206 3.420783 2.521070 -v 0.005077 -0.041494 0.102800 -vn -3.295835 3.420861 3.595232 -v 0.005408 -0.041494 0.103205 -vn -2.149377 3.420889 4.378034 -v 0.005840 -0.041494 0.103500 -vn -0.828874 3.420799 4.806326 -v 0.006338 -0.041494 0.103661 -vn 0.558809 3.420648 4.845184 -v 0.006861 -0.041494 0.103675 -vn 1.901181 3.420854 4.491432 -v 0.007366 -0.041494 0.103542 -vn 3.089598 3.420822 3.773899 -v 0.007814 -0.041494 0.103272 -vn 4.027627 3.420782 2.750596 -v 0.008167 -0.041494 0.102886 -vn 4.639440 3.420799 1.504453 -v 0.008398 -0.041494 0.102417 -vn 0.887002 -0.773833 -6.050650 -v 0.006843 -0.042410 0.099985 -vn 2.296849 -0.787011 -5.612317 -v 0.007361 -0.042410 0.100115 -vn 3.615546 -0.765368 -4.929567 -v 0.007821 -0.042410 0.100385 -vn 4.387052 -0.909532 -4.228878 -v 0.007976 -0.042410 0.100524 -vn 5.050240 -0.791252 -3.424977 -v 0.008186 -0.042410 0.100774 -vn 5.503496 -0.940527 -2.593604 -v 0.008382 -0.042410 0.101132 -vn 5.896068 -0.776706 -1.656742 -v 0.008427 -0.042410 0.101251 -vn 4.986563 -2.804574 -1.638804 -v 0.008381 -0.042600 0.101266 -vn 0.146895 -6.040182 -1.362564 -v 0.006807 -0.042807 0.100335 -vn -0.250721 -6.040010 -1.350650 -v 0.006373 -0.042807 0.100352 -vn -0.628453 -4.912699 -3.404509 -v 0.006342 -0.042742 0.100179 -vn 0.187072 -6.272533 -0.178283 -v 0.007661 -0.042810 0.100776 -vn 0.117298 -6.276627 -0.164897 -v 0.007571 -0.042810 0.100698 -vn 0.850597 -6.040170 -1.074873 -v 0.007601 -0.042807 0.100660 -vn -0.222426 -6.275253 -0.015663 -v 0.005175 -0.042810 0.101850 -vn -0.244952 -6.273483 -0.028578 -v 0.005200 -0.042810 0.101581 -vn -1.178071 -6.040565 -0.686096 -v 0.005337 -0.042807 0.101078 -vn -0.178301 -6.275846 -0.117396 -v 0.005390 -0.042810 0.101082 -vn -0.192059 -6.276690 -0.060825 -v 0.005219 -0.042810 0.101491 -vn -0.933946 -6.040969 -0.983309 -v 0.005607 -0.042807 0.100739 -vn -0.138687 -6.275078 -0.176863 -v 0.005678 -0.042810 0.100740 -vn -0.622752 -6.040120 -1.221930 -v 0.005963 -0.042807 0.100490 -vn -0.097673 -6.276609 -0.177532 -v 0.005984 -0.042810 0.100534 -vn 0.030354 -6.276570 -0.200898 -v 0.006802 -0.042810 0.100383 -vn -0.007500 -6.271969 -0.265083 -v 0.006641 -0.042810 0.100375 -vn -0.012223 -6.270945 -0.276757 -v 0.006560 -0.042810 0.100378 -vn -0.038625 -6.276795 -0.196191 -v 0.006382 -0.042810 0.100399 -vn -0.088967 -6.270997 -0.261709 -v 0.006145 -0.042810 0.100464 -vn 0.241823 -6.271523 -0.120978 -v 0.007992 -0.042810 0.101238 -vn 0.166305 -6.276527 -0.117879 -v 0.007858 -0.042810 0.101004 -vn 1.123030 -6.040132 -0.787392 -v 0.007898 -0.042807 0.100976 -vn 1.300434 -6.040185 -0.432296 -v 0.008094 -0.042807 0.101363 -vn 0.195027 -6.276600 -0.055348 -v 0.008048 -0.042810 0.101379 -vn -2.427381 -2.816529 -4.654092 -v 0.005826 -0.042600 0.100219 -vn -1.562175 -4.912713 -3.089549 -v 0.005883 -0.042742 0.100334 -vn 1.311922 -4.912676 -3.203833 -v 0.007294 -0.042742 0.100278 -vn 2.161414 -4.912669 -2.704447 -v 0.007711 -0.042742 0.100523 -vn 3.221530 -2.814974 -4.145696 -v 0.007791 -0.042600 0.100423 -vn 1.992934 -2.746301 -4.866875 -v 0.007342 -0.042600 0.100159 -vn 0.588484 -2.807293 -5.216038 -v 0.006838 -0.042600 0.100033 -vn -1.328521 -6.040122 -0.340135 -v 0.005172 -0.042807 0.101479 -vn -3.357946 -4.912673 -0.842627 -v 0.005002 -0.042742 0.101437 -vn -5.093763 -2.764905 -1.302385 -v 0.004878 -0.042600 0.101405 -vn -4.510575 -2.816111 -2.685467 -v 0.005075 -0.042600 0.100924 -vn -2.984523 -4.912684 -1.754532 -v 0.005186 -0.042742 0.100989 -vn -2.369310 -4.912687 -2.524295 -v 0.005487 -0.042742 0.100611 -vn -3.566506 -2.794343 -3.854845 -v 0.005400 -0.042600 0.100518 -vn -0.912517 -2.780905 -5.176074 -v 0.006318 -0.042600 0.100053 -vn 0.356157 -4.912723 -3.443651 -v 0.006825 -0.042742 0.100160 -vn 0.519453 -6.040491 -1.262017 -v 0.007227 -0.042807 0.100440 -vn 0.075018 -6.276101 -0.195648 -v 0.007200 -0.042810 0.100481 -vn 2.835765 -4.912710 -1.985949 -v 0.008042 -0.042742 0.100875 -vn 4.336389 -2.795594 -2.966336 -v 0.008147 -0.042600 0.100802 -vn 3.280438 -4.912682 -1.106583 -v 0.008260 -0.042742 0.101307 -vn -0.161553 0.040664 -3.209783 -v 0.006605 -0.018160 0.101317 -vn 0.622540 0.034697 -3.035372 -v 0.006804 -0.018196 0.101337 -vn 1.169223 0.004960 -2.852016 -v 0.006816 -0.018198 0.101341 -vn 1.924752 0.001461 -2.499671 -v 0.006977 -0.018231 0.101427 -vn 2.448446 0.003281 -1.879209 -v 0.007095 -0.018262 0.101553 -vn 2.767802 0.016740 -1.388607 -v 0.007112 -0.018268 0.101581 -vn 3.110595 0.022747 -0.628530 -v 0.007173 -0.018298 0.101737 -vn 3.134331 -0.009926 0.508041 -v 0.007178 -0.018334 0.101936 -vn 2.787804 -0.009539 1.344143 -v 0.007111 -0.018369 0.102122 -vn 2.485165 -0.040853 1.894423 -v 0.007104 -0.018371 0.102133 -vn 2.059753 -0.010174 2.418642 -v 0.006980 -0.018405 0.102271 -vn 1.347569 0.005880 2.749688 -v 0.006869 -0.018428 0.102338 -vn -0.834115 0.011498 2.949953 -v 0.006490 -0.018497 0.102361 -vn -0.308049 0.005421 3.071829 -v 0.006608 -0.018476 0.102383 -vn 0.226013 0.000769 3.051953 -v 0.006684 -0.018462 0.102384 -vn 0.806791 0.001830 2.933836 -v 0.006804 -0.018440 0.102363 -vn -2.579209 -0.021983 1.700837 -v 0.006198 -0.018564 0.102135 -vn -2.218123 -0.020285 2.118918 -v 0.006272 -0.018543 0.102228 -vn -1.812122 -0.001147 2.445214 -v 0.006329 -0.018530 0.102278 -vn -1.361923 0.005541 2.723436 -v 0.006415 -0.018511 0.102331 -vn -3.045233 -0.012764 0.196171 -v 0.006116 -0.018613 0.101877 -vn -3.042796 -0.026109 0.623310 -v 0.006123 -0.018601 0.101946 -vn -2.863575 -0.008271 1.208224 -v 0.006160 -0.018578 0.102066 -vn -2.974847 0.017505 -0.834635 -v 0.006143 -0.018649 0.101679 -vn -3.070131 0.006848 -0.287248 -v 0.006116 -0.018622 0.101829 -vn -2.765396 0.010072 -1.332861 -v 0.006159 -0.018657 0.101637 -vn -2.364522 -0.027184 -2.099317 -v 0.006238 -0.018684 0.101508 -vn -1.881749 -0.029272 -2.221758 -v 0.006269 -0.018691 0.101483 -vn -1.660339 0.011166 -2.592118 -v 0.006392 -0.018720 0.101381 -vn -1.141301 -0.002244 -2.856097 -v 0.006423 -0.018726 0.101365 -vn -0.418515 -0.000537 -3.130101 -v 0.006580 -0.018755 0.101319 -vn 0.666915 -0.018153 -3.084741 -v 0.006754 -0.018787 0.101326 -vn 1.077044 -0.043228 -2.717730 -v 0.006791 -0.018794 0.101340 -vn 1.671975 -0.002777 -2.719001 -v 0.006939 -0.018822 0.101399 -vn 2.247767 0.007103 -2.097557 -v 0.007060 -0.018852 0.101507 -vn 2.566904 -0.014718 -1.680336 -v 0.007080 -0.018857 0.101532 -vn 2.831425 -0.000648 -1.171268 -v 0.007156 -0.018886 0.101676 -vn 2.973022 -0.002548 -0.646446 -v 0.007167 -0.018893 0.101713 -vn 3.062314 -0.010839 -0.030957 -v 0.007185 -0.018921 0.101865 -vn 3.044630 -0.013216 0.474867 -v 0.007182 -0.018928 0.101907 -vn 2.885517 -0.005091 1.045715 -v 0.007144 -0.018956 0.102056 -vn 2.682922 -0.004932 1.576003 -v 0.007124 -0.018964 0.102099 -vn 2.403639 0.014650 1.997058 -v 0.007046 -0.018989 0.102210 -vn 1.946149 0.004476 2.392926 -v 0.007003 -0.018999 0.102252 -vn 1.480304 0.005035 2.670393 -v 0.006890 -0.019024 0.102328 -vn 1.033267 -0.010231 2.895401 -v 0.006855 -0.019031 0.102344 -vn 0.437336 -0.006237 3.046194 -v 0.006697 -0.019060 0.102383 -vn -0.016026 -0.019175 3.036814 -v 0.006659 -0.019066 0.102385 -vn -0.453464 -0.015756 3.037094 -v 0.006577 -0.019081 0.102380 -vn -0.999071 -0.002272 2.874724 -v 0.006465 -0.019102 0.102352 -vn -1.494038 0.001101 2.643914 -v 0.006395 -0.019115 0.102320 -vn -2.012146 0.019222 2.325390 -v 0.006293 -0.019138 0.102250 -vn -2.361075 0.011193 1.947359 -v 0.006244 -0.019150 0.102199 -vn -2.713589 0.017289 1.441612 -v 0.006174 -0.019173 0.102094 -vn -2.922072 0.010941 0.966081 -v 0.006146 -0.019185 0.102030 -vn -3.053184 0.008199 0.413381 -v 0.006117 -0.019209 0.101902 -vn -3.059288 0.006882 -0.101876 -v 0.006115 -0.019218 0.101850 -vn -2.953862 0.003716 -0.709076 -v 0.006134 -0.019244 0.101708 -vn -2.825254 0.030975 -1.281720 -v 0.006152 -0.019254 0.101656 -vn -2.652870 0.087945 -1.890362 -v 0.006205 -0.019274 0.101553 -vn -1.855803 0.032861 -2.670534 -v 0.006346 -0.019310 0.101410 -vn -0.768002 0.009131 -3.116162 -v 0.006528 -0.019346 0.101329 -vn 0.444461 -0.002659 -3.142541 -v 0.006725 -0.019381 0.101320 -vn 1.574367 0.002320 -2.777600 -v 0.006913 -0.019417 0.101384 -vn 2.964356 -0.016550 -0.780309 -v 0.007159 -0.019488 0.101685 -vn 2.821799 -0.022220 -1.304829 -v 0.007150 -0.019483 0.101660 -vn 2.474310 -0.009508 -2.031463 -v 0.007065 -0.019453 0.101512 -vn 3.062567 -0.003632 0.386997 -v 0.007184 -0.019524 0.101883 -vn 3.065664 -0.006147 -0.172469 -v 0.007185 -0.019519 0.101854 -vn 2.608652 -0.004563 1.691439 -v 0.007096 -0.019574 0.102146 -vn 2.928912 -0.019140 1.131795 -v 0.007144 -0.019556 0.102055 -vn 2.228488 0.013595 2.107888 -v 0.007037 -0.019591 0.102219 -vn 1.768874 0.004617 2.494872 -v 0.006958 -0.019610 0.102288 -vn -0.296290 -0.002803 3.050582 -v 0.006599 -0.019677 0.102383 -vn 0.208669 -0.002841 3.048618 -v 0.006686 -0.019662 0.102384 -vn 0.760342 0.011339 2.961914 -v 0.006777 -0.019645 0.102370 -vn 1.265852 0.018087 2.799906 -v 0.006880 -0.019626 0.102333 -vn -2.030631 -0.008418 2.376828 -v 0.006315 -0.019733 0.102267 -vn -1.431813 -0.007204 2.698802 -v 0.006407 -0.019713 0.102326 -vn -0.884664 -0.002249 2.915011 -v 0.006491 -0.019697 0.102361 -vn -2.520317 0.004799 1.733290 -v 0.006186 -0.019768 0.102118 -vn -2.789800 0.006510 1.287848 -v 0.006183 -0.019769 0.102112 -vn -2.968667 0.022845 0.781842 -v 0.006125 -0.019799 0.101954 -vn -3.060613 0.000641 0.267834 -v 0.006122 -0.019803 0.101932 -vn -3.071707 0.009011 -0.336885 -v 0.006123 -0.019835 0.101756 -vn -2.990610 0.000865 -0.933196 -v 0.006128 -0.019839 0.101731 -vn -2.797403 0.011529 -1.424729 -v 0.006192 -0.019870 0.101574 -vn -2.443221 0.001517 -1.890921 -v 0.006209 -0.019875 0.101548 -vn -1.898173 -0.004714 -2.530466 -v 0.006325 -0.019906 0.101425 -vn -0.882914 0.007791 -3.072366 -v 0.006499 -0.019941 0.101337 -vn 0.171242 0.029497 -3.148192 -v 0.006698 -0.019977 0.101317 -vn 1.847009 -0.003984 -2.427672 -v 0.006986 -0.020033 0.101434 -vn 1.417072 -0.018755 -2.742562 -v 0.006886 -0.020012 0.101370 -vn 0.911679 -0.004259 -2.948408 -v 0.006818 -0.019999 0.101342 -vn 2.620815 -0.006801 -1.592598 -v 0.007117 -0.020069 0.101588 -vn 2.228221 -0.003933 -2.077594 -v 0.007028 -0.020043 0.101472 -vn 2.887714 -0.008869 -1.118276 -v 0.007141 -0.020079 0.101637 -vn 3.010799 0.006269 -0.534432 -v 0.007180 -0.020105 0.101780 -vn 2.993399 -0.000941 0.620863 -v 0.007169 -0.020142 0.101983 -vn 3.043937 -0.001088 0.013288 -v 0.007184 -0.020114 0.101829 -vn 2.868281 -0.001264 1.162764 -v 0.007156 -0.020150 0.102026 -vn 2.564738 0.001689 1.694053 -v 0.007082 -0.020178 0.102166 -vn 2.242806 -0.018829 2.105592 -v 0.007058 -0.020185 0.102196 -vn 1.825721 -0.002907 2.486780 -v 0.006943 -0.020213 0.102297 -vn 1.336051 -0.002340 2.760510 -v 0.006903 -0.020221 0.102322 -vn 0.729111 -0.003536 2.976393 -v 0.006755 -0.020249 0.102375 -vn 0.203138 -0.015041 3.081393 -v 0.006717 -0.020256 0.102381 -vn -0.493891 -0.008610 3.078585 -v 0.006545 -0.020287 0.102375 -vn -1.144284 0.005989 2.873425 -v 0.006454 -0.020304 0.102348 -vn -2.753253 0.001430 1.333622 -v 0.006167 -0.020375 0.102082 -vn -2.485662 -0.006970 1.834115 -v 0.006216 -0.020359 0.102162 -vn -2.107538 -0.011345 2.220473 -v 0.006289 -0.020339 0.102245 -vn -1.633598 0.007707 2.585374 -v 0.006360 -0.020323 0.102300 -vn -2.979628 -0.017214 0.745495 -v 0.006131 -0.020394 0.101983 -vn -3.120916 -0.053825 0.245249 -v 0.006116 -0.020412 0.101885 -vn -0.753336 0.010216 -3.025788 -v 0.006506 -0.018142 0.101335 -vn -1.359437 -0.004719 -2.739077 -v 0.006416 -0.018125 0.101368 -vn -1.851164 -0.000269 -2.421722 -v 0.006324 -0.018105 0.101426 -vn -2.245009 0.005896 -2.050658 -v 0.006256 -0.018089 0.101488 -vn -2.683327 -0.014345 -1.576384 -v 0.006194 -0.018071 0.101571 -vn -3.070610 -0.039657 -1.048949 -v 0.006151 -0.018054 0.101655 -vn -3.196144 -0.053281 -0.215797 -v 0.006115 -0.018018 0.101850 -vn 2.720703 -4.188786 -0.000000 -v 0.005650 -0.042810 0.101850 -vn -1.360349 -4.188789 -2.356195 -v 0.007150 -0.042810 0.102716 -vn 1.360351 -4.188793 -2.356191 -v 0.006150 -0.042810 0.102716 -vn -2.720698 -4.188791 -0.000000 -v 0.007650 -0.042810 0.101850 -vn -1.360349 -4.188790 2.356195 -v 0.007150 -0.042810 0.100984 -vn 1.360352 -4.188793 2.356191 -v 0.006150 -0.042810 0.100984 -vn 2.720703 -2.094400 0.000000 -v 0.005650 -0.041810 0.101850 -vn 1.360351 -2.094393 2.356191 -v 0.006150 -0.041810 0.100984 -vn 1.360352 -2.094393 -2.356191 -v 0.006150 -0.041810 0.102716 -vn -1.360349 -2.094396 -2.356195 -v 0.007150 -0.041810 0.102716 -vn -2.720698 -2.094394 0.000000 -v 0.007650 -0.041810 0.101850 -vn -1.360349 -2.094396 2.356195 -v 0.007150 -0.041810 0.100984 -vn -0.161561 0.040648 -3.209751 -v 0.006605 -0.015760 0.101317 -vn 0.622791 0.034568 -3.035390 -v 0.006804 -0.015796 0.101337 -vn 1.169421 0.005002 -2.851733 -v 0.006816 -0.015798 0.101341 -vn 1.924700 0.001438 -2.499673 -v 0.006977 -0.015831 0.101427 -vn 2.448475 0.003257 -1.879162 -v 0.007095 -0.015862 0.101553 -vn 2.767763 0.016717 -1.388507 -v 0.007112 -0.015868 0.101581 -vn 3.110551 0.022734 -0.628524 -v 0.007173 -0.015898 0.101737 -vn 3.134284 -0.009971 0.508031 -v 0.007178 -0.015933 0.101936 -vn 2.787746 -0.009484 1.344074 -v 0.007111 -0.015969 0.102122 -vn 2.485234 -0.040991 1.894361 -v 0.007104 -0.015971 0.102133 -vn 2.059712 -0.010176 2.418596 -v 0.006980 -0.016005 0.102271 -vn 1.347479 0.005860 2.749726 -v 0.006869 -0.016028 0.102338 -vn 0.806723 0.001762 2.933722 -v 0.006804 -0.016040 0.102363 -vn 0.225924 0.000693 3.051972 -v 0.006684 -0.016062 0.102384 -vn -0.308111 0.005360 3.071644 -v 0.006608 -0.016076 0.102383 -vn -0.834104 0.011513 2.949913 -v 0.006490 -0.016097 0.102361 -vn -1.361834 0.005468 2.723361 -v 0.006415 -0.016111 0.102331 -vn -1.812040 -0.001191 2.445186 -v 0.006329 -0.016130 0.102278 -vn -2.218055 -0.020341 2.118867 -v 0.006272 -0.016143 0.102228 -vn -2.579191 -0.022053 1.700762 -v 0.006198 -0.016164 0.102135 -vn -2.863445 -0.008322 1.208169 -v 0.006161 -0.016178 0.102066 -vn -3.042730 -0.026190 0.623338 -v 0.006123 -0.016201 0.101946 -vn -3.045104 -0.012855 0.196151 -v 0.006116 -0.016213 0.101877 -vn -3.070024 0.006837 -0.287268 -v 0.006116 -0.016222 0.101829 -vn -2.974727 0.017406 -0.834577 -v 0.006143 -0.016249 0.101679 -vn -2.774570 -0.007099 -1.364422 -v 0.006159 -0.016257 0.101637 -vn -2.482436 -0.008339 -1.855723 -v 0.006238 -0.016284 0.101508 -vn -2.092577 0.009376 -2.284667 -v 0.006265 -0.016291 0.101478 -vn -1.643964 0.027072 -2.613241 -v 0.006393 -0.016320 0.101381 -vn -1.149104 0.003117 -2.861758 -v 0.006423 -0.016326 0.101365 -vn -0.407861 -0.007468 -3.139166 -v 0.006580 -0.016355 0.101319 -vn 0.421049 0.001303 -3.058338 -v 0.006754 -0.016387 0.101326 -vn 1.037037 -0.013795 -2.944713 -v 0.006793 -0.016394 0.101335 -vn 1.692018 0.009617 -2.722192 -v 0.006939 -0.016422 0.101399 -vn 2.247597 0.007085 -2.097408 -v 0.007060 -0.016452 0.101507 -vn 2.566737 -0.014826 -1.680327 -v 0.007080 -0.016457 0.101532 -vn 2.831312 -0.000803 -1.171209 -v 0.007156 -0.016486 0.101676 -vn 2.972831 -0.002612 -0.646293 -v 0.007167 -0.016493 0.101713 -vn 3.062156 -0.010966 -0.030907 -v 0.007185 -0.016521 0.101865 -vn 3.044447 -0.013249 0.474894 -v 0.007182 -0.016528 0.101907 -vn 2.885373 -0.005140 1.045619 -v 0.007144 -0.016556 0.102056 -vn 2.682806 -0.005075 1.575973 -v 0.007124 -0.016564 0.102099 -vn 2.403465 0.014503 1.996944 -v 0.007046 -0.016589 0.102210 -vn 1.946001 0.004428 2.392872 -v 0.007003 -0.016599 0.102252 -vn 1.480177 0.004928 2.670156 -v 0.006890 -0.016624 0.102328 -vn 1.033329 -0.010283 2.895177 -v 0.006855 -0.016631 0.102344 -vn 0.437460 -0.006423 3.046041 -v 0.006697 -0.016660 0.102383 -vn -0.016058 -0.019163 3.036664 -v 0.006659 -0.016666 0.102385 -vn -0.453519 -0.015901 3.036987 -v 0.006577 -0.016681 0.102380 -vn -0.999060 -0.002424 2.874444 -v 0.006465 -0.016702 0.102352 -vn -1.493904 0.001033 2.643676 -v 0.006395 -0.016715 0.102320 -vn -2.012056 0.019127 2.325286 -v 0.006293 -0.016738 0.102249 -vn -2.360983 0.011038 1.947173 -v 0.006244 -0.016750 0.102199 -vn -2.713399 0.017164 1.441454 -v 0.006174 -0.016773 0.102094 -vn -2.921875 0.010811 0.965949 -v 0.006146 -0.016785 0.102030 -vn -3.052974 0.008007 0.413304 -v 0.006117 -0.016809 0.101902 -vn -3.059037 0.006848 -0.101997 -v 0.006115 -0.016818 0.101850 -vn -2.953614 0.003642 -0.709049 -v 0.006134 -0.016844 0.101708 -vn -2.825116 0.030824 -1.281572 -v 0.006152 -0.016854 0.101656 -vn -2.652682 0.087772 -1.890181 -v 0.006205 -0.016874 0.101553 -vn -1.855683 0.032727 -2.670353 -v 0.006346 -0.016910 0.101410 -vn -0.767941 0.008999 -3.115920 -v 0.006528 -0.016946 0.101329 -vn 0.444496 -0.002808 -3.142335 -v 0.006725 -0.016981 0.101320 -vn 1.574334 0.002149 -2.777326 -v 0.006913 -0.017017 0.101384 -vn 2.964124 -0.016804 -0.780131 -v 0.007159 -0.017088 0.101685 -vn 2.821660 -0.022265 -1.304613 -v 0.007150 -0.017083 0.101660 -vn 2.474195 -0.009644 -2.031213 -v 0.007065 -0.017053 0.101512 -vn 3.062248 -0.003693 0.387184 -v 0.007184 -0.017124 0.101883 -vn 3.065437 -0.006454 -0.172352 -v 0.007185 -0.017119 0.101854 -vn 2.618620 0.000669 1.688051 -v 0.007096 -0.017174 0.102146 -vn 2.938809 -0.012070 1.149332 -v 0.007144 -0.017156 0.102055 -vn 1.768690 0.004415 2.494684 -v 0.006957 -0.017210 0.102288 -vn 2.228348 0.013495 2.107719 -v 0.007037 -0.017191 0.102219 -vn -0.296295 -0.002979 3.050333 -v 0.006599 -0.017277 0.102383 -vn 0.208635 -0.002972 3.048332 -v 0.006686 -0.017262 0.102384 -vn 0.760401 0.011172 2.961666 -v 0.006777 -0.017245 0.102369 -vn 1.265662 0.017990 2.799563 -v 0.006880 -0.017226 0.102333 -vn -2.030520 -0.008600 2.376633 -v 0.006315 -0.017333 0.102267 -vn -1.431657 -0.007346 2.698470 -v 0.006407 -0.017313 0.102326 -vn -0.884716 -0.002423 2.914711 -v 0.006491 -0.017297 0.102361 -vn -2.520128 0.004429 1.732909 -v 0.006186 -0.017368 0.102118 -vn -2.789513 0.006534 1.287471 -v 0.006183 -0.017369 0.102112 -vn -2.968221 0.022605 0.781970 -v 0.006126 -0.017399 0.101954 -vn -3.060321 0.000560 0.267982 -v 0.006122 -0.017403 0.101932 -vn -3.071496 0.008827 -0.337014 -v 0.006123 -0.017435 0.101756 -vn -2.990152 0.000646 -0.933225 -v 0.006128 -0.017439 0.101731 -vn -2.797178 0.011259 -1.424785 -v 0.006192 -0.017470 0.101574 -vn -2.442734 0.001351 -1.890883 -v 0.006209 -0.017475 0.101548 -vn -1.897887 -0.004895 -2.530216 -v 0.006325 -0.017506 0.101425 -vn -0.883828 0.006318 -3.074230 -v 0.006499 -0.017541 0.101337 -vn 0.171334 0.029303 -3.147810 -v 0.006698 -0.017577 0.101317 -vn 0.911666 -0.004424 -2.948115 -v 0.006818 -0.017599 0.101342 -vn 1.416970 -0.018977 -2.742193 -v 0.006886 -0.017612 0.101370 -vn 1.846897 -0.004108 -2.427383 -v 0.006986 -0.017633 0.101434 -vn 2.280814 0.011919 -2.075755 -v 0.007028 -0.017643 0.101472 -vn 2.628582 0.013485 -1.630476 -v 0.007117 -0.017669 0.101588 -vn 2.887379 -0.009010 -1.118258 -v 0.007141 -0.017679 0.101637 -vn 3.010418 0.006055 -0.534449 -v 0.007180 -0.017705 0.101780 -vn 3.043552 -0.001305 0.013221 -v 0.007184 -0.017714 0.101829 -vn 2.992996 -0.001047 0.620757 -v 0.007169 -0.017742 0.101983 -vn 2.867998 -0.001486 1.162568 -v 0.007156 -0.017750 0.102026 -vn 2.564442 0.001479 1.693931 -v 0.007082 -0.017778 0.102166 -vn 2.242471 -0.019063 2.105416 -v 0.007058 -0.017785 0.102196 -vn 1.825408 -0.003135 2.486590 -v 0.006943 -0.017813 0.102297 -vn -1.144151 0.005788 2.873251 -v 0.006454 -0.017904 0.102348 -vn -0.493859 -0.008840 3.078191 -v 0.006545 -0.017887 0.102375 -vn 0.202732 -0.015255 3.080950 -v 0.006717 -0.017856 0.102381 -vn 0.751414 0.009069 2.987452 -v 0.006755 -0.017849 0.102375 -vn 1.323862 0.010807 2.799841 -v 0.006903 -0.017821 0.102322 -vn -2.753391 0.001257 1.333527 -v 0.006168 -0.017975 0.102082 -vn -2.485842 -0.007132 1.834152 -v 0.006216 -0.017958 0.102162 -vn -2.107405 -0.011554 2.220436 -v 0.006289 -0.017939 0.102244 -vn -1.633531 0.007526 2.585325 -v 0.006360 -0.017923 0.102300 -vn -2.979891 -0.017424 0.745534 -v 0.006131 -0.017994 0.101983 -vn -3.121137 -0.053912 0.245283 -v 0.006116 -0.018012 0.101885 -vn -0.753216 0.010195 -3.025738 -v 0.006506 -0.015742 0.101335 -vn -1.359472 -0.004767 -2.739160 -v 0.006416 -0.015725 0.101368 -vn -1.851081 -0.000235 -2.421657 -v 0.006324 -0.015705 0.101426 -vn -2.244978 0.005894 -2.050726 -v 0.006256 -0.015689 0.101488 -vn -2.683305 -0.014377 -1.576336 -v 0.006194 -0.015671 0.101571 -vn -3.070570 -0.039653 -1.048959 -v 0.006151 -0.015654 0.101655 -vn -3.196148 -0.053281 -0.215824 -v 0.006115 -0.015618 0.101850 -vn -0.161546 0.040637 -3.209749 -v 0.006605 -0.013360 0.101317 -vn 0.622796 0.034572 -3.035391 -v 0.006804 -0.013396 0.101337 -vn 1.169423 0.005004 -2.851737 -v 0.006816 -0.013398 0.101341 -vn 1.924714 0.001438 -2.499672 -v 0.006977 -0.013431 0.101427 -vn 2.448415 0.003271 -1.879185 -v 0.007095 -0.013462 0.101553 -vn 2.767770 0.016722 -1.388584 -v 0.007112 -0.013468 0.101581 -vn 3.110541 0.022734 -0.628504 -v 0.007173 -0.013498 0.101737 -vn 3.134273 -0.009969 0.508015 -v 0.007178 -0.013533 0.101936 -vn 2.787750 -0.009493 1.344267 -v 0.007111 -0.013569 0.102122 -vn 2.485073 -0.041021 1.894446 -v 0.007104 -0.013571 0.102133 -vn 2.059714 -0.010174 2.418595 -v 0.006980 -0.013605 0.102271 -vn 1.347498 0.005868 2.749729 -v 0.006869 -0.013628 0.102338 -vn 0.806723 0.001762 2.933722 -v 0.006804 -0.013640 0.102363 -vn 0.225923 0.000699 3.051973 -v 0.006684 -0.013662 0.102384 -vn -0.308116 0.005347 3.071650 -v 0.006608 -0.013676 0.102383 -vn -0.834092 0.011523 2.949905 -v 0.006490 -0.013697 0.102361 -vn -1.361843 0.005456 2.723392 -v 0.006415 -0.013711 0.102331 -vn -1.812069 -0.001184 2.445160 -v 0.006329 -0.013730 0.102278 -vn -2.218056 -0.020336 2.118876 -v 0.006272 -0.013743 0.102228 -vn -2.579191 -0.022053 1.700762 -v 0.006198 -0.013764 0.102135 -vn -2.863445 -0.008322 1.208169 -v 0.006161 -0.013778 0.102066 -vn -3.042730 -0.026190 0.623338 -v 0.006123 -0.013801 0.101946 -vn -3.045120 -0.012803 0.196126 -v 0.006116 -0.013813 0.101877 -vn -3.070047 0.006746 -0.287234 -v 0.006116 -0.013822 0.101829 -vn -2.974725 0.017423 -0.834581 -v 0.006143 -0.013849 0.101679 -vn -2.774569 -0.007080 -1.364427 -v 0.006159 -0.013857 0.101637 -vn -2.482419 -0.008445 -1.855802 -v 0.006238 -0.013884 0.101508 -vn -2.092448 0.009420 -2.284685 -v 0.006265 -0.013891 0.101478 -vn -1.643988 0.027083 -2.613228 -v 0.006393 -0.013920 0.101381 -vn -1.149090 0.003136 -2.861753 -v 0.006423 -0.013926 0.101365 -vn -0.407874 -0.007514 -3.139163 -v 0.006580 -0.013955 0.101319 -vn 0.421087 0.001376 -3.058350 -v 0.006754 -0.013987 0.101326 -vn 1.037014 -0.013903 -2.944751 -v 0.006793 -0.013994 0.101335 -vn 1.692029 0.009636 -2.722201 -v 0.006939 -0.014022 0.101399 -vn 2.247598 0.007091 -2.097417 -v 0.007060 -0.014052 0.101507 -vn 2.566737 -0.014826 -1.680327 -v 0.007080 -0.014057 0.101532 -vn 2.831312 -0.000803 -1.171209 -v 0.007156 -0.014086 0.101676 -vn 2.972851 -0.002596 -0.646278 -v 0.007167 -0.014093 0.101713 -vn 3.062171 -0.010999 -0.030928 -v 0.007185 -0.014121 0.101865 -vn 3.044447 -0.013268 0.474891 -v 0.007182 -0.014128 0.101907 -vn 2.885368 -0.005223 1.045588 -v 0.007144 -0.014156 0.102056 -vn 2.682787 -0.005026 1.575985 -v 0.007124 -0.014164 0.102099 -vn 2.403465 0.014503 1.996944 -v 0.007046 -0.014189 0.102210 -vn 1.946001 0.004428 2.392872 -v 0.007003 -0.014199 0.102252 -vn 1.480177 0.004928 2.670156 -v 0.006890 -0.014224 0.102328 -vn 1.033280 -0.010292 2.895219 -v 0.006855 -0.014231 0.102344 -vn 0.437678 -0.006379 3.045797 -v 0.006697 -0.014260 0.102383 -vn -0.015793 -0.019123 3.036779 -v 0.006659 -0.014266 0.102385 -vn -0.453528 -0.015896 3.036997 -v 0.006577 -0.014281 0.102380 -vn -0.999049 -0.002415 2.874448 -v 0.006465 -0.014302 0.102352 -vn -1.493896 0.001043 2.643659 -v 0.006395 -0.014315 0.102320 -vn -2.012054 0.019132 2.325272 -v 0.006293 -0.014338 0.102249 -vn -2.360983 0.011038 1.947173 -v 0.006244 -0.014350 0.102199 -vn -2.713399 0.017164 1.441454 -v 0.006174 -0.014373 0.102094 -vn -2.921875 0.010811 0.965949 -v 0.006146 -0.014385 0.102030 -vn -3.052985 0.008050 0.413287 -v 0.006117 -0.014409 0.101902 -vn -3.059038 0.006761 -0.101948 -v 0.006115 -0.014418 0.101850 -vn -2.953623 0.003624 -0.709108 -v 0.006134 -0.014444 0.101708 -vn -2.825054 0.030834 -1.281624 -v 0.006152 -0.014454 0.101656 -vn -2.652682 0.087775 -1.890190 -v 0.006205 -0.014474 0.101553 -vn -1.855694 0.032734 -2.670359 -v 0.006346 -0.014510 0.101410 -vn -0.767941 0.008999 -3.115920 -v 0.006528 -0.014546 0.101329 -vn 0.444496 -0.002808 -3.142335 -v 0.006725 -0.014581 0.101320 -vn 1.574331 0.002153 -2.777322 -v 0.006913 -0.014617 0.101384 -vn 2.964124 -0.016804 -0.780131 -v 0.007159 -0.014688 0.101685 -vn 2.821660 -0.022265 -1.304613 -v 0.007150 -0.014683 0.101660 -vn 2.474195 -0.009644 -2.031213 -v 0.007065 -0.014653 0.101512 -vn 3.062256 -0.003689 0.387193 -v 0.007184 -0.014724 0.101883 -vn 3.065437 -0.006454 -0.172352 -v 0.007185 -0.014719 0.101854 -vn 2.618623 0.000694 1.688073 -v 0.007096 -0.014774 0.102146 -vn 2.938819 -0.012064 1.149329 -v 0.007144 -0.014756 0.102055 -vn 1.768659 0.004459 2.494709 -v 0.006957 -0.014810 0.102288 -vn 2.228378 0.013425 2.107691 -v 0.007037 -0.014791 0.102219 -vn -0.296302 -0.002975 3.050321 -v 0.006599 -0.014877 0.102383 -vn 0.208641 -0.002967 3.048324 -v 0.006686 -0.014862 0.102384 -vn 0.760386 0.011201 2.961660 -v 0.006777 -0.014845 0.102369 -vn 1.265703 0.017922 2.799562 -v 0.006880 -0.014826 0.102333 -vn -2.030534 -0.008573 2.376622 -v 0.006315 -0.014933 0.102267 -vn -1.431627 -0.007408 2.698488 -v 0.006407 -0.014913 0.102326 -vn -0.884744 -0.002388 2.914724 -v 0.006491 -0.014897 0.102361 -vn -2.520129 0.004433 1.732918 -v 0.006186 -0.014968 0.102118 -vn -2.789523 0.006537 1.287468 -v 0.006183 -0.014969 0.102112 -vn -2.968228 0.022611 0.781978 -v 0.006126 -0.014999 0.101954 -vn -3.060313 0.000565 0.267987 -v 0.006122 -0.015003 0.101932 -vn -3.071499 0.008931 -0.337058 -v 0.006123 -0.015035 0.101756 -vn -2.990192 0.000490 -0.933192 -v 0.006128 -0.015039 0.101731 -vn -2.797184 0.011274 -1.424785 -v 0.006192 -0.015070 0.101574 -vn -2.442734 0.001351 -1.890883 -v 0.006209 -0.015075 0.101548 -vn -1.897887 -0.004895 -2.530216 -v 0.006325 -0.015106 0.101425 -vn -0.883828 0.006318 -3.074230 -v 0.006499 -0.015141 0.101337 -vn 0.171336 0.029325 -3.147805 -v 0.006698 -0.015177 0.101317 -vn 0.911640 -0.004506 -2.948110 -v 0.006818 -0.015199 0.101342 -vn 1.416978 -0.018948 -2.742182 -v 0.006886 -0.015212 0.101370 -vn 1.846897 -0.004108 -2.427383 -v 0.006986 -0.015233 0.101434 -vn 2.280817 0.011921 -2.075758 -v 0.007028 -0.015243 0.101472 -vn 2.628582 0.013485 -1.630476 -v 0.007117 -0.015269 0.101588 -vn 2.887391 -0.009005 -1.118255 -v 0.007141 -0.015279 0.101637 -vn 3.010424 0.006060 -0.534456 -v 0.007180 -0.015305 0.101780 -vn 3.043566 -0.001292 0.013238 -v 0.007184 -0.015314 0.101829 -vn 2.993002 -0.001147 0.620705 -v 0.007169 -0.015342 0.101983 -vn 2.867973 -0.001434 1.162587 -v 0.007156 -0.015350 0.102026 -vn 2.564441 0.001480 1.693928 -v 0.007082 -0.015378 0.102166 -vn 2.242469 -0.019055 2.105425 -v 0.007058 -0.015385 0.102196 -vn 1.825414 -0.003123 2.486602 -v 0.006943 -0.015413 0.102297 -vn -1.144142 0.005795 2.873243 -v 0.006454 -0.015504 0.102348 -vn -0.493859 -0.008837 3.078187 -v 0.006545 -0.015487 0.102375 -vn 0.202731 -0.015253 3.080945 -v 0.006717 -0.015456 0.102381 -vn 0.751420 0.009079 2.987454 -v 0.006755 -0.015449 0.102375 -vn 1.323866 0.010819 2.799854 -v 0.006903 -0.015421 0.102322 -vn -2.753358 0.001194 1.333555 -v 0.006168 -0.015575 0.102082 -vn -2.485852 -0.007105 1.834144 -v 0.006216 -0.015558 0.102162 -vn -2.107402 -0.011551 2.220433 -v 0.006289 -0.015539 0.102244 -vn -1.633530 0.007534 2.585307 -v 0.006360 -0.015523 0.102300 -vn -2.979874 -0.017399 0.745505 -v 0.006131 -0.015594 0.101983 -vn -3.121133 -0.053909 0.245282 -v 0.006116 -0.015612 0.101885 -vn -0.753199 0.010205 -3.025739 -v 0.006506 -0.013342 0.101335 -vn -1.359476 -0.004760 -2.739155 -v 0.006416 -0.013325 0.101368 -vn -1.851092 -0.000227 -2.421662 -v 0.006324 -0.013305 0.101426 -vn -2.244985 0.005901 -2.050742 -v 0.006256 -0.013289 0.101488 -vn -2.683308 -0.014375 -1.576339 -v 0.006194 -0.013271 0.101571 -vn -3.070575 -0.039648 -1.048960 -v 0.006151 -0.013254 0.101655 -vn -3.246593 -0.023819 -0.093960 -v 0.006115 -0.013218 0.101850 -vn 2.973279 -0.015243 -1.151636 -v 0.007150 -0.012284 0.101662 -vn -0.938881 -0.012996 -2.950227 -v 0.006506 -0.010942 0.101335 -vn -0.402764 0.006664 -3.014315 -v 0.006579 -0.010955 0.101320 -vn -0.025619 -0.009225 -3.116610 -v 0.006617 -0.010962 0.101316 -vn 0.587018 -0.015190 -3.034324 -v 0.006790 -0.010993 0.101333 -vn 1.158018 -0.004559 -2.867001 -v 0.006816 -0.010998 0.101341 -vn 1.984725 -0.007275 -2.475405 -v 0.006979 -0.011031 0.101428 -vn 2.763864 0.002723 -1.611249 -v 0.007117 -0.011069 0.101588 -vn 2.902724 -0.004512 0.951976 -v 0.007164 -0.011145 0.102000 -vn 3.053728 -0.004068 0.387524 -v 0.007177 -0.011135 0.101943 -vn 3.058041 -0.007264 -0.177973 -v 0.007181 -0.011107 0.101789 -vn 2.984746 0.018143 -0.752191 -v 0.007176 -0.011100 0.101750 -vn 0.196403 -0.003441 3.203741 -v 0.006701 -0.011259 0.102383 -vn 1.118613 -0.001375 2.895029 -v 0.006869 -0.011228 0.102338 -vn 1.611088 0.022674 2.643500 -v 0.006903 -0.011221 0.102322 -vn 2.083270 0.015875 2.285218 -v 0.007032 -0.011192 0.102224 -vn 2.335433 0.004393 1.897714 -v 0.007066 -0.011183 0.102187 -vn 2.641758 0.002125 1.533848 -v 0.007104 -0.011171 0.102133 -vn -0.920294 0.011984 3.100614 -v 0.006490 -0.011297 0.102361 -vn -1.986404 -0.005431 2.470108 -v 0.006305 -0.011335 0.102259 -vn -2.506353 -0.000053 1.778986 -v 0.006198 -0.011364 0.102135 -vn -2.994476 0.007497 0.705103 -v 0.006123 -0.011401 0.101946 -vn -2.812319 0.007831 1.264573 -v 0.006174 -0.011373 0.102094 -vn -2.974002 0.020437 -0.825514 -v 0.006143 -0.011449 0.101681 -vn -3.101950 -0.000210 -0.251456 -v 0.006116 -0.011422 0.101829 -vn -3.023772 -0.006101 0.182842 -v 0.006116 -0.011411 0.101891 -vn -2.758026 0.011927 -1.349789 -v 0.006159 -0.011457 0.101637 -vn -2.403590 0.004116 -1.892988 -v 0.006247 -0.011487 0.101498 -vn -2.058185 0.002335 -2.316994 -v 0.006265 -0.011491 0.101478 -vn -1.372296 0.003631 -2.879100 -v 0.006415 -0.011525 0.101369 -vn -0.231340 -0.025212 -3.182664 -v 0.006619 -0.011563 0.101316 -vn 0.621546 -0.010385 -3.023252 -v 0.006793 -0.011594 0.101335 -vn 1.186396 0.003301 -2.830508 -v 0.006829 -0.011601 0.101346 -vn 1.727330 0.007344 -2.542671 -v 0.006974 -0.011630 0.101424 -vn 2.073610 -0.005394 -2.194202 -v 0.007010 -0.011638 0.101454 -vn 2.429051 0.000401 -1.907016 -v 0.007060 -0.011652 0.101507 -vn 2.758047 0.006890 -1.388029 -v 0.007135 -0.011676 0.101625 -vn 2.968070 -0.010712 -0.907624 -v 0.007156 -0.011686 0.101676 -vn 3.072505 -0.004951 -0.280278 -v 0.007185 -0.011714 0.101830 -vn 3.074471 0.004745 0.290999 -v 0.007185 -0.011721 0.101865 -vn 2.937970 0.012658 0.885538 -v 0.007151 -0.011752 0.102038 -vn 2.753563 -0.009090 1.381091 -v 0.007144 -0.011756 0.102056 -vn 2.298698 0.003163 2.214748 -v 0.007039 -0.011790 0.102218 -vn 1.324945 0.014602 2.868834 -v 0.006866 -0.011828 0.102339 -vn -1.032439 -0.001694 2.858782 -v 0.006452 -0.011904 0.102347 -vn -0.470787 -0.017223 3.042875 -v 0.006577 -0.011881 0.102380 -vn -0.023517 -0.013248 3.022763 -v 0.006660 -0.011866 0.102385 -vn 0.462791 0.002397 3.038330 -v 0.006697 -0.011860 0.102383 -vn -2.967546 0.038979 1.229778 -v 0.006157 -0.011980 0.102057 -vn -2.520914 0.021920 1.882240 -v 0.006244 -0.011950 0.102199 -vn -2.080628 0.008114 2.272150 -v 0.006275 -0.011942 0.102232 -vn -1.540081 -0.000850 2.623213 -v 0.006395 -0.011915 0.102320 -vn -3.201953 0.002411 0.000351 -v 0.006115 -0.012018 0.101850 -vn -2.950696 0.026925 -1.259717 -v 0.006157 -0.012056 0.101643 -vn -2.471700 0.033247 -1.909023 -v 0.006257 -0.012089 0.101487 -vn 1.117363 0.010556 -2.869486 -v 0.006866 -0.012208 0.101361 -vn 0.514812 -0.015518 -3.045549 -v 0.006716 -0.012180 0.101319 -vn -0.041327 -0.007960 -3.058704 -v 0.006660 -0.012170 0.101315 -vn -0.665321 0.001344 -2.976625 -v 0.006521 -0.012145 0.101331 -vn -1.169144 0.007638 -2.806857 -v 0.006452 -0.012132 0.101353 -vn -1.684151 0.001740 -2.533116 -v 0.006347 -0.012111 0.101409 -vn -2.047969 -0.002464 -2.195244 -v 0.006275 -0.012094 0.101468 -vn 2.482358 -0.020558 -1.875966 -v 0.007046 -0.012248 0.101490 -vn 2.070677 0.030620 -2.281098 -v 0.007039 -0.012246 0.101482 -vn 1.637515 0.024398 -2.639186 -v 0.006903 -0.012215 0.101379 -vn 3.163069 0.007318 0.008313 -v 0.007185 -0.012322 0.101870 -vn 3.026724 0.011541 0.684974 -v 0.007171 -0.012340 0.101972 -vn 2.783777 0.004914 1.262644 -v 0.007135 -0.012360 0.102075 -vn 2.514095 0.011666 1.763096 -v 0.007096 -0.012374 0.102146 -vn 2.141237 0.003778 2.189389 -v 0.007010 -0.012398 0.102246 -vn 1.675118 -0.006231 2.567687 -v 0.006957 -0.012410 0.102288 -vn 1.108078 -0.001459 2.870441 -v 0.006829 -0.012435 0.102354 -vn 0.592380 0.000675 3.064408 -v 0.006777 -0.012445 0.102369 -vn 0.037187 0.013977 3.091726 -v 0.006620 -0.012473 0.102384 -vn -0.508218 -0.004780 3.048143 -v 0.006599 -0.012477 0.102383 -vn -1.427239 -0.022191 2.841806 -v 0.006416 -0.012511 0.102331 -vn -2.284202 0.003738 2.195070 -v 0.006247 -0.012549 0.102202 -vn -3.040286 -0.003077 -0.154878 -v 0.006116 -0.012625 0.101809 -vn -3.033792 -0.007939 0.440157 -v 0.006122 -0.012603 0.101932 -vn -2.898916 -0.000981 0.955484 -v 0.006143 -0.012587 0.102019 -vn -2.665059 0.014771 1.529115 -v 0.006183 -0.012569 0.102112 -vn -0.900841 0.006761 -3.067018 -v 0.006490 -0.012739 0.101339 -vn -1.706167 -0.009507 -2.584089 -v 0.006329 -0.012707 0.101422 -vn -2.098035 0.011868 -2.246849 -v 0.006305 -0.012701 0.101441 -vn -2.481415 0.003219 -1.835701 -v 0.006209 -0.012675 0.101548 -vn -2.750397 0.002998 -1.338496 -v 0.006174 -0.012663 0.101606 -vn -2.960105 0.000407 -0.747057 -v 0.006128 -0.012639 0.101731 -vn 0.289512 0.013634 -3.175348 -v 0.006701 -0.012777 0.101317 -vn 1.354425 -0.011352 -2.832915 -v 0.006903 -0.012815 0.101378 -vn 1.957227 -0.009314 -2.392889 -v 0.006986 -0.012833 0.101434 -vn 2.378691 0.012558 -1.971915 -v 0.007066 -0.012853 0.101513 -vn 2.689243 0.010942 -1.488373 -v 0.007117 -0.012869 0.101588 -vn 2.933109 -0.006145 -0.884537 -v 0.007164 -0.012891 0.101700 -vn 3.072323 -0.008168 -0.333734 -v 0.007180 -0.012905 0.101780 -vn 3.077992 0.015816 0.269331 -v 0.007181 -0.012929 0.101911 -vn 2.960712 0.011604 0.818890 -v 0.007169 -0.012942 0.101983 -vn 2.709544 -0.003770 1.433106 -v 0.007117 -0.012967 0.102112 -vn 2.419466 -0.007462 1.921566 -v 0.007082 -0.012978 0.102166 -vn 2.001904 0.009093 2.365098 -v 0.006979 -0.013005 0.102272 -vn 1.588510 -0.011238 2.680660 -v 0.006943 -0.013013 0.102297 -vn 0.992740 -0.013643 2.933658 -v 0.006790 -0.013043 0.102367 -vn 0.405519 -0.003647 3.060768 -v 0.006755 -0.013049 0.102375 -vn -0.461153 -0.006749 3.135157 -v 0.006579 -0.013081 0.102380 -vn -1.535083 -0.009220 2.805931 -v 0.006380 -0.013119 0.102312 -vn -2.054206 0.008749 2.340396 -v 0.006289 -0.013139 0.102244 -vn -2.458961 0.006769 1.825650 -v 0.006222 -0.013157 0.102171 -vn -2.796301 0.013799 1.334480 -v 0.006168 -0.013175 0.102082 -vn -3.083020 0.008299 0.688133 -v 0.006131 -0.013194 0.101981 -vn -1.461012 -0.024375 -2.713682 -v 0.006380 -0.010917 0.101388 -vn -1.975094 0.002625 -2.354582 -v 0.006324 -0.010905 0.101426 -vn -2.359991 0.000015 -1.950962 -v 0.006222 -0.010879 0.101529 -vn -2.704659 0.024703 -1.466200 -v 0.006194 -0.010871 0.101571 -vn -3.108576 0.022995 -0.787852 -v 0.006131 -0.010842 0.101719 -vn -3.171767 -0.028636 -0.075031 -v 0.006115 -0.010818 0.101850 -vn -0.238518 0.001086 3.083169 -v 0.006590 -0.009478 0.102382 -vn -0.800952 0.005094 2.996038 -v 0.006528 -0.009490 0.102371 -vn -1.274147 -0.008507 2.785345 -v 0.006402 -0.009514 0.102324 -vn -1.701635 0.002874 2.537068 -v 0.006376 -0.009519 0.102310 -vn -2.163928 0.005656 2.150583 -v 0.006252 -0.009548 0.102207 -vn -2.476026 -0.006375 1.757213 -v 0.006227 -0.009555 0.102178 -vn -2.907012 -0.015423 1.153321 -v 0.006157 -0.009580 0.102058 -vn -3.136172 -0.010610 0.228828 -v 0.006115 -0.009614 0.101871 -vn -3.068895 0.008036 -0.457318 -v 0.006122 -0.009634 0.101761 -vn -2.916048 0.009116 -0.943250 -v 0.006138 -0.009646 0.101696 -vn -2.668454 0.001158 -1.518048 -v 0.006192 -0.009670 0.101574 -vn -2.396359 -0.010606 -1.933618 -v 0.006224 -0.009680 0.101526 -vn -1.985346 -0.005421 -2.333229 -v 0.006320 -0.009704 0.101429 -vn -1.570626 -0.015742 -2.669753 -v 0.006354 -0.009712 0.101405 -vn -1.057955 0.009187 -2.920973 -v 0.006496 -0.009740 0.101338 -vn 0.303052 0.011326 -3.127113 -v 0.006706 -0.009778 0.101318 -vn -0.532068 0.007179 -3.030270 -v 0.006529 -0.009746 0.101329 -vn 2.833332 0.037744 -1.374919 -v 0.007139 -0.009878 0.101633 -vn 2.362581 0.002621 -1.980641 -v 0.007032 -0.009844 0.101475 -vn 1.951347 -0.006647 -2.366631 -v 0.007016 -0.009840 0.101459 -vn 1.506032 -0.013560 -2.696076 -v 0.006889 -0.009812 0.101371 -vn 0.980303 0.008610 -2.913009 -v 0.006841 -0.009803 0.101350 -vn 3.005327 0.024994 -0.783567 -v 0.007168 -0.009894 0.101715 -vn 3.111000 -0.044540 -0.299828 -v 0.007183 -0.009910 0.101805 -vn 3.096533 -0.022773 -0.025081 -v 0.007185 -0.009917 0.101846 -vn 3.059000 0.009346 0.415947 -v 0.007180 -0.009930 0.101920 -vn 2.941421 0.027135 0.775648 -v 0.007165 -0.009944 0.101995 -vn 2.806620 0.005935 1.196460 -v 0.007149 -0.009953 0.102043 -vn 2.581160 -0.004653 1.648483 -v 0.007090 -0.009976 0.102155 -vn 2.393276 -0.004925 1.820795 -v 0.007077 -0.009980 0.102173 -vn 2.179299 -0.014018 2.128829 -v 0.007046 -0.009988 0.102209 -vn 1.816279 -0.006871 2.499648 -v 0.006954 -0.010010 0.102290 -vn 1.340467 0.001003 2.731659 -v 0.006888 -0.010024 0.102329 -vn 0.883670 0.003451 2.880859 -v 0.006794 -0.010042 0.102365 -vn 0.597760 -0.000160 2.937953 -v 0.006763 -0.010047 0.102373 -vn 0.207465 0.006700 3.046164 -v 0.006696 -0.010060 0.102383 -vn -0.260820 0.008569 3.068074 -v 0.006604 -0.010076 0.102383 -vn -0.827685 -0.008038 2.947110 -v 0.006502 -0.010094 0.102364 -vn -1.167473 -0.000484 2.804099 -v 0.006433 -0.010108 0.102339 -vn -1.461417 0.014637 2.637257 -v 0.006402 -0.010114 0.102324 -vn -1.858840 0.022563 2.433093 -v 0.006325 -0.010130 0.102275 -vn -2.555445 0.003836 1.619685 -v 0.006195 -0.010165 0.102131 -vn -2.297859 -0.001338 1.967916 -v 0.006249 -0.010149 0.102204 -vn -2.102874 0.022139 2.197984 -v 0.006275 -0.010142 0.102232 -vn -2.761880 -0.011334 1.325289 -v 0.006171 -0.010174 0.102088 -vn -2.886940 -0.007236 1.054914 -v 0.006148 -0.010184 0.102034 -vn -2.956417 -0.013400 0.600474 -v 0.006123 -0.010201 0.101944 -vn -3.007950 -0.000211 0.282731 -v 0.006118 -0.010208 0.101905 -vn -3.035244 0.008397 -0.057122 -v 0.006115 -0.010218 0.101847 -vn -2.973110 0.002660 -0.505364 -v 0.006126 -0.010237 0.101745 -vn -2.914973 -0.005068 -0.747706 -v 0.006129 -0.010240 0.101728 -vn -2.851460 -0.001675 -1.158744 -v 0.006150 -0.010253 0.101659 -vn -2.558242 0.011523 -1.807032 -v 0.006205 -0.010274 0.101553 -vn -1.900021 -0.003464 -2.523905 -v 0.006326 -0.010306 0.101424 -vn -1.107280 -0.000724 -2.880174 -v 0.006496 -0.010340 0.101338 -vn -0.542059 -0.011552 -3.065613 -v 0.006517 -0.010344 0.101332 -vn -0.083170 0.009541 -3.118240 -v 0.006672 -0.010372 0.101315 -vn 0.507550 0.001767 -3.019273 -v 0.006713 -0.010379 0.101319 -vn 1.059858 0.003603 -2.877817 -v 0.006858 -0.010406 0.101357 -vn 1.542566 -0.013463 -2.636067 -v 0.006902 -0.010415 0.101378 -vn 2.001941 -0.009992 -2.355133 -v 0.007008 -0.010438 0.101452 -vn 2.469343 -0.036341 -1.948563 -v 0.007057 -0.010450 0.101503 -vn 2.756328 -0.034032 -1.531344 -v 0.007124 -0.010472 0.101603 -vn 2.928225 -0.019413 -0.971976 -v 0.007159 -0.010488 0.101686 -vn 3.019837 -0.020098 -0.506669 -v 0.007179 -0.010504 0.101771 -vn 3.037457 -0.012674 -0.255515 -v 0.007183 -0.010509 0.101798 -vn 3.042154 -0.019563 0.194505 -v 0.007184 -0.010524 0.101884 -vn 2.978080 -0.007044 0.559491 -v 0.007173 -0.010538 0.101962 -vn 2.878957 0.002565 0.856797 -v 0.007166 -0.010543 0.101992 -vn 2.759118 0.009163 1.256994 -v 0.007135 -0.010559 0.102076 -vn 2.592225 0.005737 1.576451 -v 0.007108 -0.010570 0.102127 -vn 2.439926 0.006689 1.849786 -v 0.007081 -0.010578 0.102167 -vn 2.135324 -0.007289 2.165564 -v 0.007019 -0.010595 0.102238 -vn 1.882744 0.001768 2.387437 -v 0.006982 -0.010604 0.102270 -vn 1.600688 0.019069 2.577407 -v 0.006940 -0.010613 0.102299 -vn 1.197198 0.010197 2.794863 -v 0.006850 -0.010631 0.102346 -vn 0.838486 0.022604 3.018491 -v 0.006827 -0.010636 0.102355 -vn 0.405423 0.044822 3.103974 -v 0.006683 -0.010662 0.102384 -vn 0.046108 0.006502 2.975229 -v 0.006658 -0.010666 0.102385 -vn -0.246173 0.008951 3.056399 -v 0.006638 -0.010670 0.102385 -vn -0.717410 0.020314 2.969127 -v 0.006498 -0.010695 0.102363 -vn -1.227794 0.001673 2.808075 -v 0.006464 -0.010702 0.102352 -vn -1.719962 0.006689 2.526243 -v 0.006323 -0.010731 0.102274 -vn -2.143864 -0.016143 2.188305 -v 0.006300 -0.010736 0.102254 -vn -2.495861 -0.006690 1.792051 -v 0.006195 -0.010765 0.102132 -vn -2.570557 0.000677 1.468168 -v 0.006187 -0.010768 0.102118 -vn -2.868664 -0.023824 1.193777 -v 0.006172 -0.010773 0.102091 -vn -3.104458 -0.042657 0.641688 -v 0.006122 -0.010802 0.101938 -vn 0.335306 0.015379 3.088921 -v 0.006726 -0.009454 0.102379 -vn 0.594763 4.006982 4.279759 -v 0.006769 -0.009702 0.102835 -vn 0.922395 0.018272 2.940783 -v 0.006788 -0.009443 0.102367 -vn 1.058697 4.899951 3.582290 -v 0.006993 -0.009650 0.102725 -vn 1.772818 0.503058 3.242755 -v 0.006915 -0.009418 0.102315 -vn 1.593798 4.884598 3.421782 -v 0.007100 -0.009620 0.102641 -vn 0.597256 5.846856 1.469185 -v 0.006955 -0.009410 0.102290 -vn 2.231967 4.845255 3.039304 -v 0.007183 -0.009593 0.102554 -vn 0.828910 5.842716 1.370543 -v 0.007101 -0.009410 0.102221 -vn 2.730793 4.903707 2.549194 -v 0.007314 -0.009533 0.102335 -vn 1.031254 5.846476 1.214503 -v 0.007131 -0.009410 0.102200 -vn 3.052141 4.950683 2.070227 -v 0.007343 -0.009511 0.102250 -vn 1.384435 5.815094 0.874846 -v 0.007274 -0.009410 0.102044 -vn 3.425072 4.905870 1.432425 -v 0.007369 -0.009473 0.102104 -vn 2.275294 5.278052 0.304076 -v 0.007350 -0.009410 0.101875 -vn 0.772529 0.357372 1.233405 -v 0.006807 -0.009410 0.102425 -vn 3.438967 -0.474457 0.761421 -v 0.007594 -0.009702 0.102159 -vn 3.533398 -0.481880 0.132021 -v 0.007626 -0.009686 0.101914 -vn 3.570827 -0.494693 -0.386022 -v 0.007623 -0.009682 0.101850 -vn 3.337297 -0.440836 -0.979905 -v 0.007594 -0.009670 0.101673 -vn 3.169407 -0.469522 -1.568363 -v 0.007507 -0.009655 0.101453 -vn 2.904695 -0.502586 -2.081766 -v 0.007464 -0.009650 0.101380 -vn 2.510033 -0.457047 -2.426599 -v 0.007353 -0.009638 0.101242 -vn 2.168380 -0.417140 -2.745646 -v 0.007280 -0.009631 0.101176 -vn 1.667088 -0.467369 -3.111052 -v 0.007151 -0.009621 0.101089 -vn 1.081399 -0.460167 -3.397651 -v 0.006971 -0.009607 0.101013 -vn 0.580847 -0.416820 -3.444578 -v 0.006907 -0.009603 0.100996 -vn -0.109413 -0.475781 -3.534076 -v 0.006650 -0.009585 0.100975 -vn -0.668656 -0.488755 -3.532552 -v 0.006550 -0.009578 0.100987 -vn -1.021768 -0.483726 -3.398559 -v 0.006492 -0.009573 0.101000 -vn -1.635830 -0.468598 -3.108359 -v 0.006318 -0.009560 0.101067 -vn -2.154054 -0.498852 -2.861037 -v 0.006197 -0.009549 0.101144 -vn -2.588256 -0.462472 -2.429394 -v 0.006113 -0.009541 0.101217 -vn -3.056992 -0.472910 -1.694489 -v 0.005975 -0.009524 0.101395 -vn -3.375887 -0.444743 -0.707907 -v 0.005889 -0.009506 0.101614 -vn -3.459776 -0.443780 0.375267 -v 0.005875 -0.009486 0.101861 -vn -3.233028 -0.434365 1.286655 -v 0.005924 -0.009469 0.102072 -vn -2.798387 -0.191778 1.539908 -v 0.005973 -0.009459 0.102173 -vn -2.697370 -0.445504 2.274494 -v 0.006039 -0.009450 0.102269 -vn -2.152046 -0.263095 2.546010 -v 0.006123 -0.009440 0.102356 -vn -1.835522 -0.496220 3.081248 -v 0.006214 -0.009430 0.102423 -vn -0.931354 0.084726 2.605895 -v 0.006354 -0.009416 0.102491 -vn -0.087476 0.358333 1.437474 -v 0.006428 -0.009410 0.102514 -vn 0.349597 0.344075 1.378315 -v 0.006643 -0.009410 0.102495 -vn -1.376547 5.234383 1.883180 -v 0.006228 -0.009410 0.102408 -vn -1.887503 5.303436 1.256542 -v 0.006072 -0.009410 0.102245 -vn -2.265462 5.207354 0.628116 -v 0.005976 -0.009410 0.102040 -vn -2.360055 5.196601 -0.132306 -v 0.005951 -0.009410 0.101814 -vn -2.203853 5.233540 -0.767291 -v 0.005990 -0.009410 0.101618 -vn -2.054678 5.241586 -1.103688 -v 0.006044 -0.009410 0.101500 -vn -1.769077 5.251349 -1.502312 -v 0.006098 -0.009410 0.101419 -vn -1.278730 5.242810 -1.935910 -v 0.006264 -0.009410 0.101266 -vn -0.619097 5.253607 -2.228953 -v 0.006471 -0.009410 0.101173 -vn 0.123538 5.218516 -2.331569 -v 0.006650 -0.009410 0.101150 -vn 1.170448 5.190411 -2.027138 -v 0.007000 -0.009410 0.101244 -vn 2.041872 5.180048 -1.158935 -v 0.007256 -0.009410 0.101500 -vn 2.293391 5.261362 -0.238226 -v 0.007350 -0.009410 0.101850 -vn 4.520947 1.210840 -3.903131 -v 0.041776 -0.041610 0.100524 -vn 3.946141 0.252483 -4.837392 -v 0.041717 -0.041610 0.100468 -vn 3.892035 1.473944 -4.456016 -v 0.041716 -0.041581 0.100469 -vn 2.739941 1.467037 -5.245535 -v 0.041275 -0.041581 0.100169 -vn -0.489078 6.145112 -0.779643 -v 0.039680 -0.041410 0.100362 -vn -0.259303 6.187855 -0.721004 -v 0.039797 -0.041410 0.100307 -vn -1.096455 5.322640 -2.632449 -v 0.039762 -0.041431 0.100225 -vn 0.906679 6.119461 -0.422617 -v 0.042017 -0.041410 0.101257 -vn 0.753285 6.186737 -0.160924 -v 0.042070 -0.041410 0.101423 -vn 2.760824 5.322852 -0.710726 -v 0.042157 -0.041431 0.101400 -vn 2.845344 5.323648 0.088825 -v 0.042214 -0.041431 0.101899 -vn 0.796623 6.179489 -0.066914 -v 0.042125 -0.041410 0.101850 -vn 0.757581 6.189259 0.072617 -v 0.042124 -0.041410 0.101897 -vn 0.677290 6.184789 -0.381482 -v 0.041884 -0.041410 0.100984 -vn 2.445663 5.323546 -1.459222 -v 0.041961 -0.041431 0.100938 -vn 0.687582 6.154077 -0.566788 -v 0.041726 -0.041410 0.100765 -vn 1.931383 5.320548 -2.112626 -v 0.041643 -0.041431 0.100549 -vn 0.505695 6.190102 -0.564460 -v 0.041582 -0.041410 0.100615 -vn 0.498426 6.154277 -0.737790 -v 0.041357 -0.041410 0.100441 -vn 1.247588 5.321830 -2.569705 -v 0.041228 -0.041431 0.100266 -vn 0.314768 6.188357 -0.696485 -v 0.041188 -0.041410 0.100346 -vn 0.234908 6.172726 -0.790927 -v 0.040819 -0.041410 0.100216 -vn 0.467770 5.322240 -2.814888 -v 0.040750 -0.041431 0.100111 -vn 0.083032 6.188228 -0.760412 -v 0.040735 -0.041410 0.100199 -vn -0.317587 5.323435 -2.829908 -v 0.040248 -0.041431 0.100097 -vn -0.035267 6.188860 -0.761844 -v 0.040258 -0.041410 0.100186 -vn -0.177978 6.179683 -0.778575 -v 0.040215 -0.041410 0.100191 -vn -0.470519 6.185470 -0.615521 -v 0.039389 -0.041410 0.100554 -vn -1.791384 5.323670 -2.213315 -v 0.039332 -0.041431 0.100484 -vn -0.659998 6.153264 -0.602768 -v 0.039203 -0.041410 0.100732 -vn -2.365344 5.321592 -1.602572 -v 0.038993 -0.041431 0.100855 -vn -0.645291 6.187338 -0.416753 -v 0.039066 -0.041410 0.100905 -vn -0.753638 6.171175 -0.349694 -v 0.038889 -0.041410 0.101244 -vn -2.719665 5.322293 -0.863060 -v 0.038771 -0.041431 0.101306 -vn -0.741049 6.188049 -0.192160 -v 0.038857 -0.041410 0.101333 -vn -2.845378 5.323596 -0.088809 -v 0.038686 -0.041431 0.101801 -vn -0.757551 6.189266 -0.072615 -v 0.038776 -0.041410 0.101803 -vn -6.220052 0.243724 -0.560074 -v 0.038576 -0.041610 0.101798 -vn -5.908018 1.475636 -0.302182 -v 0.038578 -0.041581 0.101798 -vn -6.019442 0.250939 -1.632229 -v 0.038666 -0.041610 0.101272 -vn -5.672001 1.460413 -1.689754 -v 0.038668 -0.041581 0.101272 -vn -5.290777 1.477505 -2.455391 -v 0.038718 -0.041610 0.101132 -vn -4.897290 1.447634 -3.326671 -v 0.038903 -0.041581 0.100794 -vn -3.646090 1.451356 -4.661923 -v 0.039264 -0.041581 0.100401 -vn -4.186936 1.599020 -3.941182 -v 0.039124 -0.041610 0.100524 -vn -5.156904 0.235691 -3.497669 -v 0.038902 -0.041610 0.100793 -vn 1.042815 1.447875 -5.827662 -v 0.040768 -0.041581 0.100004 -vn 0.101572 1.668442 -5.707230 -v 0.040450 -0.041610 0.099975 -vn -0.799875 1.443316 -5.863953 -v 0.040235 -0.041581 0.099989 -vn -0.959731 0.248955 -6.155958 -v 0.040235 -0.041610 0.099987 -vn -2.304087 1.357938 -5.443210 -v 0.039720 -0.041581 0.100125 -vn -2.413841 0.271155 -5.705089 -v 0.039719 -0.041610 0.100123 -vn -3.730109 0.240772 -4.993837 -v 0.039262 -0.041610 0.100399 -vn 3.042310 0.236100 -5.447323 -v 0.041276 -0.041610 0.100167 -vn 1.966009 1.318366 -5.577297 -v 0.041168 -0.041610 0.100118 -vn 1.145272 0.230716 -6.124740 -v 0.040769 -0.041610 0.100002 -vn 5.245266 0.263763 -3.354731 -v 0.042055 -0.041610 0.100881 -vn 5.013717 1.425965 -3.143328 -v 0.042053 -0.041581 0.100882 -vn 5.234227 1.704327 -2.206396 -v 0.042182 -0.041610 0.101132 -vn 5.746013 1.447259 -1.422337 -v 0.042261 -0.041581 0.101373 -vn 6.070911 0.236196 -1.405614 -v 0.042263 -0.041610 0.101372 -vn 6.117670 0.794070 -0.449346 -v 0.042325 -0.041610 0.101850 -vn 5.908062 1.475922 0.302195 -v 0.042322 -0.041581 0.101902 -vn 6.220000 0.244112 0.560084 -v 0.042324 -0.041610 0.101902 -vn 4.875354 3.420801 0.136444 -v 0.042287 -0.041494 0.101901 -vn 4.716286 3.420842 -1.242654 -v 0.042227 -0.041494 0.101382 -vn 4.175207 3.420798 -2.521063 -v 0.042023 -0.041494 0.100900 -vn 3.295783 3.420752 -3.595225 -v 0.041692 -0.041494 0.100495 -vn 2.149371 3.420884 -4.378046 -v 0.041260 -0.041494 0.100200 -vn 0.828870 3.420791 -4.806336 -v 0.040762 -0.041494 0.100039 -vn -0.558777 3.420869 -4.845119 -v 0.040239 -0.041494 0.100024 -vn -1.901205 3.420845 -4.491426 -v 0.039734 -0.041494 0.100158 -vn -3.089609 3.420779 -3.773914 -v 0.039286 -0.041494 0.100428 -vn -4.027696 3.420819 -2.750622 -v 0.038933 -0.041494 0.100814 -vn -4.639457 3.420748 -1.504445 -v 0.038702 -0.041494 0.101283 -vn -4.875380 3.420864 -0.136441 -v 0.038613 -0.041494 0.101799 -vn -5.503509 -0.940512 2.593573 -v 0.038718 -0.042410 0.102568 -vn -5.896096 -0.776676 1.656714 -v 0.038673 -0.042410 0.102449 -vn -4.986582 -2.804529 1.638801 -v 0.038719 -0.042600 0.102434 -vn 1.176910 -6.040431 0.691876 -v 0.041763 -0.042807 0.102622 -vn 0.179304 -6.276206 0.105408 -v 0.041722 -0.042810 0.102598 -vn 0.201717 -6.276206 0.050758 -v 0.041881 -0.042810 0.102209 -vn 0.934325 -6.040427 0.995429 -v 0.041493 -0.042807 0.102961 -vn 0.142351 -6.276206 0.151658 -v 0.041459 -0.042810 0.102925 -vn 0.247824 -6.040423 1.342538 -v 0.040727 -0.042807 0.103348 -vn 0.037750 -6.276207 0.204520 -v 0.040718 -0.042810 0.103300 -vn 0.093846 -6.276207 0.185606 -v 0.041116 -0.042810 0.103166 -vn -0.021397 -6.276207 0.206891 -v 0.040298 -0.042810 0.103317 -vn -0.140443 -6.040439 1.357955 -v 0.040293 -0.042807 0.103365 -vn 0.628492 -4.912676 3.404586 -v 0.040758 -0.042742 0.103521 -vn -1.118279 -6.040421 0.783147 -v 0.039202 -0.042807 0.102724 -vn -0.170368 -6.276206 0.119310 -v 0.039242 -0.042810 0.102696 -vn -0.129856 -6.276205 0.162483 -v 0.039529 -0.042810 0.103002 -vn -1.293602 -6.040433 0.436361 -v 0.039006 -0.042807 0.102337 -vn -0.197092 -6.276205 0.066482 -v 0.039052 -0.042810 0.102321 -vn -1.369955 -6.040127 0.060520 -v 0.038928 -0.042807 0.101911 -vn -0.199897 -6.276723 0.020994 -v 0.038976 -0.042810 0.101909 -vn 1.324162 -6.040431 0.332275 -v 0.041928 -0.042807 0.102221 -vn 1.369673 -6.040108 -0.059492 -v 0.041972 -0.042807 0.101789 -vn 3.459392 -4.912662 -0.137552 -v 0.042147 -0.042742 0.101783 -vn 2.427368 -2.816458 4.654130 -v 0.041274 -0.042600 0.103481 -vn 1.562221 -4.912667 3.089643 -v 0.041217 -0.042742 0.103366 -vn 0.616035 -6.040411 1.218368 -v 0.041137 -0.042807 0.103210 -vn -1.311970 -4.912637 3.203922 -v 0.039806 -0.042742 0.103422 -vn -2.161491 -4.912613 2.704528 -v 0.039389 -0.042742 0.103177 -vn -0.852332 -6.040430 1.066471 -v 0.039499 -0.042807 0.103040 -vn -3.221540 -2.814984 4.145705 -v 0.039309 -0.042600 0.103277 -vn -1.992921 -2.746296 4.866884 -v 0.039758 -0.042600 0.103541 -vn -0.588528 -2.807175 5.216101 -v 0.040262 -0.042600 0.103667 -vn 5.244499 -2.801514 -0.253592 -v 0.042276 -0.042600 0.101777 -vn 6.101421 -0.768168 -0.602133 -v 0.042324 -0.042410 0.101776 -vn 6.112462 -0.829717 0.325803 -v 0.042325 -0.042410 0.101850 -vn 3.358033 -4.912621 0.842661 -v 0.042098 -0.042742 0.102263 -vn 5.093791 -2.764891 1.302415 -v 0.042222 -0.042600 0.102295 -vn 5.923247 -0.818661 1.410993 -v 0.042269 -0.042410 0.102306 -vn 4.510599 -2.816107 2.685472 -v 0.042025 -0.042600 0.102776 -vn 2.984608 -4.912628 1.754576 -v 0.041914 -0.042742 0.102711 -vn 0.233626 -6.274386 0.022913 -v 0.041925 -0.042810 0.101850 -vn 0.199867 -6.276725 -0.020993 -v 0.041924 -0.042810 0.101791 -vn 5.583273 -1.154766 2.182398 -v 0.042182 -0.042410 0.102568 -vn 5.187806 -0.768535 3.235265 -v 0.042066 -0.042410 0.102800 -vn 4.565955 -0.823120 4.083330 -v 0.041776 -0.042410 0.103176 -vn 2.369380 -4.912652 2.524358 -v 0.041613 -0.042742 0.103089 -vn 3.566499 -2.794333 3.854847 -v 0.041700 -0.042600 0.103182 -vn 3.919911 -0.778982 4.716887 -v 0.041733 -0.042410 0.103217 -vn 3.031500 -0.762658 5.319057 -v 0.041296 -0.042410 0.103523 -vn 2.123316 -0.868421 5.723136 -v 0.041168 -0.042410 0.103582 -vn 0.912557 -2.780888 5.176075 -v 0.040782 -0.042600 0.103647 -vn -0.356174 -4.912622 3.443760 -v 0.040275 -0.042742 0.103540 -vn -0.517350 -6.040430 1.263405 -v 0.039873 -0.042807 0.103260 -vn -0.078823 -6.276205 0.192496 -v 0.039891 -0.042810 0.103215 -vn 1.102737 -0.797309 5.994425 -v 0.040790 -0.042410 0.103694 -vn 0.208566 -1.046822 6.038548 -v 0.040450 -0.042410 0.103725 -vn -0.887095 -0.773772 6.050689 -v 0.040257 -0.042410 0.103715 -vn -2.296813 -0.787026 5.612317 -v 0.039739 -0.042410 0.103585 -vn -3.615554 -0.765396 4.929545 -v 0.039279 -0.042410 0.103315 -vn -4.387050 -0.909549 4.228878 -v 0.039124 -0.042410 0.103176 -vn -2.835844 -4.912678 1.986011 -v 0.039058 -0.042742 0.102825 -vn -4.336378 -2.795606 2.966352 -v 0.038953 -0.042600 0.102898 -vn -5.050225 -0.791262 3.424988 -v 0.038914 -0.042410 0.102926 -vn -3.280499 -4.912644 1.106602 -v 0.038840 -0.042742 0.102393 -vn -3.459318 -4.912663 0.137561 -v 0.038753 -0.042742 0.101917 -vn -5.244527 -2.801482 0.253596 -v 0.038624 -0.042600 0.101923 -vn -6.101403 -0.768179 0.601989 -v 0.038576 -0.042410 0.101924 -vn -1.747748 -2.525902 4.227680 -v 0.039986 -0.009863 0.102736 -vn -1.267479 -2.536558 4.367491 -v 0.040137 -0.009848 0.102800 -vn -2.566238 2.608405 3.711335 -v 0.039933 -0.009770 0.102706 -vn 0.081427 2.630923 -4.550736 -v 0.040450 -0.010018 0.100850 -vn -0.460276 -2.634633 -4.521329 -v 0.040450 -0.010117 0.100850 -vn -0.622961 2.588481 -4.533423 -v 0.040211 -0.009995 0.100879 -vn -1.441479 -2.619995 -4.261330 -v 0.040182 -0.010091 0.100887 -vn -1.296604 2.606342 -4.365765 -v 0.040163 -0.009990 0.100892 -vn -2.455880 -2.616043 -3.821538 -v 0.039933 -0.010065 0.100994 -vn -1.885263 2.566619 -4.119711 -v 0.039959 -0.009969 0.100979 -vn -2.963517 -2.647951 -3.485152 -v 0.039845 -0.010055 0.101054 -vn -2.596103 2.656325 -3.751799 -v 0.039833 -0.009955 0.101063 -vn -3.355370 -2.705074 -3.105366 -v 0.039743 -0.010042 0.101143 -vn -3.095225 2.663988 -3.327402 -v 0.039743 -0.009943 0.101143 -vn -3.618147 -2.625082 -2.738470 -v 0.039717 -0.010039 0.101170 -vn -3.731251 2.570672 -2.544082 -v 0.039594 -0.009920 0.101333 -vn -4.062299 -2.557630 -2.000962 -v 0.039579 -0.010017 0.101359 -vn -4.274904 2.627832 -1.432586 -v 0.039487 -0.009894 0.101581 -vn -4.271096 -2.395804 -1.531064 -v 0.039516 -0.010002 0.101493 -vn -4.504620 -2.573130 -0.690323 -v 0.039479 -0.009991 0.101611 -vn -4.487177 2.567201 -0.255276 -v 0.039450 -0.009868 0.101850 -vn -4.510019 -2.560158 0.248048 -v 0.039450 -0.009968 0.101850 -vn -4.524709 2.638773 0.615406 -v 0.039479 -0.009845 0.102089 -vn -4.398156 -2.632757 1.192130 -v 0.039480 -0.009944 0.102092 -vn -4.423710 2.687498 1.201384 -v 0.039491 -0.009841 0.102132 -vn -4.163028 -2.577273 1.899506 -v 0.039511 -0.009934 0.102194 -vn -4.104917 2.630931 1.959330 -v 0.039579 -0.009819 0.102341 -vn -3.817621 -2.627587 2.472581 -v 0.039578 -0.009918 0.102339 -vn -3.786504 2.547587 2.564185 -v 0.039660 -0.009805 0.102463 -vn -3.085650 -2.626142 3.306242 -v 0.039717 -0.009895 0.102530 -vn -3.245586 2.520381 3.171503 -v 0.039743 -0.009793 0.102557 -vn -2.364899 -2.611505 3.880968 -v 0.039928 -0.009870 0.102703 -vn -0.031534 -2.633360 4.584064 -v 0.040406 -0.009821 0.102849 -vn 0.395909 -2.702001 4.554169 -v 0.040450 -0.009816 0.102850 -vn -0.356399 2.694250 4.524610 -v 0.040450 -0.009718 0.102850 -vn -0.429129 -2.559674 4.552665 -v 0.040302 -0.009831 0.102839 -vn -1.154846 2.636143 4.429641 -v 0.040222 -0.009740 0.102824 -vn -1.646849 2.644020 4.247354 -v 0.040182 -0.009744 0.102813 -vn -4.523552 2.559050 -0.220229 -v 0.039450 -0.020668 0.101850 -vn -4.404321 2.630676 -1.155260 -v 0.039487 -0.020684 0.101582 -vn -4.501927 -2.643133 -0.698719 -v 0.039482 -0.021026 0.101606 -vn 0.219152 2.620065 -4.543344 -v 0.040450 -0.020762 0.100850 -vn -0.461277 2.665037 -4.555441 -v 0.040302 -0.020753 0.100861 -vn -1.127994 3.553604 -2.860185 -v 0.040120 -0.041410 0.100906 -vn -3.225414 2.858523 -2.235905 -v 0.039625 -0.021078 0.101284 -vn -4.892152 0.014345 -3.930521 -v 0.039664 -0.021082 0.101231 -vn -2.249694 3.633121 -2.054533 -v 0.039712 -0.041410 0.101175 -vn -4.398141 -2.620855 -1.314631 -v 0.039506 -0.021037 0.101525 -vn -4.207251 2.639959 -1.786173 -v 0.039504 -0.020688 0.101525 -vn -3.834012 2.604013 -2.423941 -v 0.039594 -0.020701 0.101333 -vn -3.573981 -2.847288 -1.861866 -v 0.039629 -0.021074 0.101280 -vn -3.432066 2.666835 -3.026807 -v 0.039690 -0.020710 0.101200 -vn -2.940103 2.615211 -3.464053 -v 0.039743 -0.020715 0.101143 -vn -2.077790 2.546924 -3.974939 -v 0.039959 -0.020731 0.100979 -vn -1.127733 2.617721 -4.399814 -v 0.040211 -0.020747 0.100879 -vn -4.388203 -2.605052 0.071676 -v 0.039452 -0.021001 0.101793 -vn -4.349366 -2.664351 1.079572 -v 0.039471 -0.020966 0.102056 -vn -4.446852 2.600682 0.796036 -v 0.039479 -0.020645 0.102089 -vn -4.256289 -2.661418 1.616829 -v 0.039480 -0.020961 0.102094 -vn -4.281603 2.637784 1.613908 -v 0.039548 -0.020626 0.102283 -vn -3.766726 -2.592261 2.419968 -v 0.039564 -0.020930 0.102312 -vn -0.683055 -2.594376 4.526266 -v 0.040176 -0.020823 0.102812 -vn 0.268743 -2.553372 4.504362 -v 0.040450 -0.020786 0.102850 -vn -0.330531 2.566854 4.502441 -v 0.040450 -0.020519 0.102850 -vn -1.271428 2.611489 4.351166 -v 0.040182 -0.020545 0.102813 -vn -1.974448 2.634006 4.124795 -v 0.040084 -0.020554 0.102781 -vn -1.313296 -2.618862 4.389474 -v 0.040119 -0.020831 0.102795 -vn -2.576453 2.604754 3.756726 -v 0.039933 -0.020570 0.102706 -vn -2.113767 -2.576954 3.960727 -v 0.039929 -0.020859 0.102705 -vn -3.161961 2.639033 3.319821 -v 0.039775 -0.020589 0.102588 -vn -3.047121 -2.547262 3.270274 -v 0.039724 -0.020894 0.102537 -vn -3.566864 2.615278 2.845203 -v 0.039743 -0.020593 0.102557 -vn -3.959299 2.587721 2.231189 -v 0.039579 -0.020619 0.102341 -vn -4.360342 2.713700 0.630526 -v 0.039473 -0.021030 0.102062 -vn -4.527091 2.671343 0.027111 -v 0.039450 -0.021041 0.101864 -vn -2.954368 3.631941 0.745115 -v 0.039480 -0.041410 0.102094 -vn -4.235602 2.787867 -0.575821 -v 0.039452 -0.021046 0.101792 -vn -2.954027 3.633078 -0.745758 -v 0.039480 -0.041410 0.101606 -vn -4.303625 2.700452 -1.158852 -v 0.039480 -0.021057 0.101606 -vn -4.132350 2.647671 -1.725540 -v 0.039504 -0.021062 0.101526 -vn -4.374750 2.646154 1.344296 -v 0.039500 -0.021023 0.102162 -vn -2.248382 3.633837 2.055832 -v 0.039712 -0.041410 0.102525 -vn -3.969545 2.613985 2.032972 -v 0.039565 -0.021014 0.102316 -vn -3.196185 2.616779 2.925341 -v 0.039723 -0.020998 0.102536 -vn -1.128742 3.555734 2.859584 -v 0.040120 -0.041410 0.102794 -vn -2.483165 2.522927 3.780934 -v 0.039933 -0.020982 0.102706 -vn -1.345562 2.529417 4.319423 -v 0.040182 -0.020965 0.102813 -vn -0.179773 2.547395 4.516856 -v 0.040450 -0.020949 0.102850 -vn 0.975387 2.547418 4.414348 -v 0.040689 -0.020935 0.102821 -vn 1.128600 3.555070 2.859712 -v 0.040780 -0.041410 0.102794 -vn 2.014461 2.573325 4.052095 -v 0.040941 -0.020919 0.102721 -vn 2.954708 3.630764 0.744572 -v 0.041420 -0.041410 0.102094 -vn 3.780984 2.556713 2.437519 -v 0.041306 -0.020888 0.102367 -vn 2.248311 3.632308 2.056263 -v 0.041188 -0.041410 0.102525 -vn 3.228094 2.628386 3.207038 -v 0.041157 -0.020902 0.102557 -vn 2.720023 2.653088 3.652658 -v 0.041094 -0.020908 0.102615 -vn 2.954721 3.630688 -0.744528 -v 0.041420 -0.041410 0.101606 -vn 4.511283 2.549612 0.181370 -v 0.041450 -0.020855 0.101850 -vn 4.304050 2.533399 1.354964 -v 0.041413 -0.020872 0.102119 -vn 1.128462 3.555319 -2.859735 -v 0.040780 -0.041410 0.100906 -vn 3.303150 2.552474 -3.058526 -v 0.041157 -0.020808 0.101143 -vn 2.248308 3.632227 -2.056298 -v 0.041188 -0.041410 0.101175 -vn 3.995758 2.537352 -2.080594 -v 0.041321 -0.020825 0.101359 -vn 4.406089 2.551466 -0.963932 -v 0.041421 -0.020841 0.101611 -vn 0.938769 2.650912 -4.474439 -v 0.040655 -0.020774 0.100871 -vn 1.587004 2.624327 -4.270700 -v 0.040718 -0.020778 0.100887 -vn 2.431201 2.556465 -3.778337 -v 0.040967 -0.020794 0.100994 -vn -4.520237 -2.600126 0.257908 -v 0.039450 -0.020168 0.101850 -vn -4.444147 2.616178 -1.046985 -v 0.039475 -0.020090 0.101628 -vn -4.511683 -2.660613 -0.590057 -v 0.039480 -0.020199 0.101607 -vn -4.229589 2.676922 -1.679620 -v 0.039487 -0.020094 0.101581 -vn -4.341753 -2.502708 -1.349357 -v 0.039504 -0.020210 0.101526 -vn -4.122469 -2.567560 -1.889634 -v 0.039584 -0.020236 0.101350 -vn -3.746346 2.604323 -2.490817 -v 0.039594 -0.020120 0.101333 -vn -3.752863 -2.581864 -2.607430 -v 0.039690 -0.020261 0.101200 -vn -3.068866 2.658908 -3.350085 -v 0.039743 -0.020143 0.101143 -vn -3.348093 -2.666958 -3.076891 -v 0.039743 -0.020271 0.101143 -vn -2.549802 2.515275 -3.784435 -v 0.039850 -0.020157 0.101050 -vn -2.481342 -2.610978 -3.790296 -v 0.039972 -0.020308 0.100972 -vn 0.104373 2.618122 -4.548695 -v 0.040450 -0.020219 0.100850 -vn -0.356778 -2.596808 -4.550654 -v 0.040450 -0.020374 0.100850 -vn -0.627007 2.668498 -4.543869 -v 0.040211 -0.020195 0.100879 -vn -0.902252 -2.475877 -4.476343 -v 0.040302 -0.020354 0.100861 -vn -1.623999 -2.650632 -4.277900 -v 0.040189 -0.020339 0.100885 -vn -1.964064 2.635339 -4.101185 -v 0.039959 -0.020169 0.100979 -vn -1.386879 2.615823 -4.338490 -v 0.040120 -0.020186 0.100906 -vn -1.010106 2.715843 -4.502931 -v 0.040189 -0.020193 0.100885 -vn -4.042461 2.630227 2.007491 -v 0.039579 -0.020019 0.102341 -vn -4.447206 2.627872 0.985916 -v 0.039479 -0.020045 0.102089 -vn -4.296803 -2.567384 1.475199 -v 0.039487 -0.020142 0.102118 -vn -4.555026 2.475336 0.392140 -v 0.039462 -0.020054 0.102003 -vn -4.528184 2.603223 -0.333169 -v 0.039450 -0.020068 0.101850 -vn -4.081578 -2.473269 2.040495 -v 0.039548 -0.020125 0.102283 -vn -3.662137 -2.578804 2.723294 -v 0.039594 -0.020116 0.102367 -vn -3.401063 2.614776 2.972005 -v 0.039743 -0.019993 0.102557 -vn -1.962183 -2.636409 4.075561 -v 0.039959 -0.020066 0.102721 -vn -2.725458 2.617796 3.661645 -v 0.039933 -0.019970 0.102706 -vn -2.743547 -2.593368 3.664378 -v 0.039775 -0.020088 0.102588 -vn -3.204567 -2.640998 3.255150 -v 0.039743 -0.020092 0.102557 -vn 0.255226 -2.638452 4.542764 -v 0.040450 -0.020017 0.102850 -vn -0.265670 2.643669 4.570674 -v 0.040450 -0.019918 0.102850 -vn -0.487608 -2.553811 4.550795 -v 0.040281 -0.020033 0.102836 -vn -0.678500 2.531188 4.509319 -v 0.040355 -0.019927 0.102846 -vn -0.985219 -2.609415 4.448603 -v 0.040211 -0.020040 0.102821 -vn -1.540793 2.560345 4.285334 -v 0.040182 -0.019944 0.102813 -vn -2.121644 2.548688 4.044916 -v 0.039995 -0.019963 0.102740 -vn -4.316489 2.462805 1.457305 -v 0.039508 -0.019435 0.102186 -vn -4.500868 2.664160 0.705035 -v 0.039479 -0.019445 0.102089 -vn -4.246064 -2.668611 1.596054 -v 0.039487 -0.019541 0.102119 -vn 0.129647 2.613082 -4.535281 -v 0.040450 -0.019618 0.100850 -vn -0.331946 -2.622375 -4.484544 -v 0.040450 -0.019717 0.100850 -vn -0.833026 2.555474 -4.417502 -v 0.040211 -0.019595 0.100879 -vn -1.456384 -2.554493 -4.249158 -v 0.040182 -0.019691 0.100887 -vn -1.800718 2.591904 -4.162891 -v 0.039959 -0.019569 0.100979 -vn -2.435369 -2.662109 -3.840077 -v 0.039933 -0.019665 0.100994 -vn -2.449449 2.687191 -3.853474 -v 0.039884 -0.019560 0.101026 -vn -2.990155 -2.637442 -3.468019 -v 0.039850 -0.019656 0.101050 -vn -2.932685 2.686794 -3.514234 -v 0.039743 -0.019543 0.101143 -vn -3.348991 -2.691560 -3.112579 -v 0.039743 -0.019642 0.101143 -vn -3.319867 2.662705 -3.168213 -v 0.039715 -0.019539 0.101172 -vn -3.611487 -2.672214 -2.782431 -v 0.039712 -0.019638 0.101175 -vn -3.741040 2.657712 -2.597315 -v 0.039594 -0.019520 0.101333 -vn -3.834367 -2.560097 -2.473628 -v 0.039625 -0.019625 0.101285 -vn -4.143830 -2.658109 -1.845982 -v 0.039579 -0.019616 0.101359 -vn -4.137245 2.470029 -1.932196 -v 0.039518 -0.019503 0.101487 -vn -4.431796 -2.581512 -0.794041 -v 0.039479 -0.019590 0.101611 -vn -4.355403 2.618145 -1.336360 -v 0.039487 -0.019494 0.101581 -vn -4.503781 2.560266 -0.253044 -v 0.039450 -0.019468 0.101850 -vn -4.524675 -2.559902 0.204397 -v 0.039450 -0.019567 0.101850 -vn -4.469165 -2.413092 0.783225 -v 0.039462 -0.019553 0.102003 -vn -4.104272 2.556801 1.969212 -v 0.039579 -0.019419 0.102341 -vn -3.746090 -2.600668 2.512493 -v 0.039594 -0.019516 0.102367 -vn -3.711409 2.551330 2.682715 -v 0.039691 -0.019400 0.102502 -vn -2.948028 -2.606850 3.428322 -v 0.039743 -0.019492 0.102557 -vn -3.260122 2.609138 3.197233 -v 0.039743 -0.019393 0.102557 -vn -2.214241 -2.652322 3.989697 -v 0.039959 -0.019467 0.102721 -vn -2.600327 2.548561 3.698261 -v 0.039933 -0.019370 0.102706 -vn -1.671078 -2.526748 4.256877 -v 0.039995 -0.019463 0.102740 -vn -1.452884 2.575693 4.265221 -v 0.040182 -0.019344 0.102813 -vn -0.845785 -2.545652 4.477232 -v 0.040211 -0.019441 0.102821 -vn -0.404424 2.670952 4.530129 -v 0.040450 -0.019318 0.102850 -vn -0.346338 -2.383454 4.546392 -v 0.040355 -0.019427 0.102845 -vn 0.396654 -2.661683 4.541672 -v 0.040450 -0.019418 0.102850 -vn -1.059022 -2.404379 -4.397242 -v 0.040208 -0.019095 0.100881 -vn -1.900185 -2.710428 -4.129648 -v 0.040120 -0.019086 0.100907 -vn -1.044499 2.617807 -4.417845 -v 0.040136 -0.018988 0.100901 -vn -0.396604 -2.641170 -4.518059 -v 0.040450 -0.019118 0.100850 -vn -0.354972 2.412994 -4.519642 -v 0.040388 -0.019012 0.100852 -vn 0.441572 2.668411 -4.548711 -v 0.040450 -0.019018 0.100850 -vn -4.234514 -2.692183 -1.562572 -v 0.039519 -0.019003 0.101487 -vn -3.829426 2.344018 -2.451091 -v 0.039552 -0.018912 0.101410 -vn -3.437253 -2.566873 -2.765519 -v 0.039715 -0.019039 0.101172 -vn -3.240167 2.514882 -3.120936 -v 0.039702 -0.018938 0.101186 -vn -2.711250 -2.587542 -3.538198 -v 0.039884 -0.019060 0.101026 -vn -2.362605 2.534747 -3.863252 -v 0.039888 -0.018962 0.101023 -vn -1.860114 2.301324 -4.131661 -v 0.040027 -0.018977 0.100944 -vn -4.491202 -2.676715 -0.789758 -v 0.039481 -0.018991 0.101606 -vn -4.513488 -2.634013 0.259310 -v 0.039450 -0.018968 0.101850 -vn -4.554785 2.578434 -0.541090 -v 0.039451 -0.018872 0.101810 -vn -4.466074 2.493442 -0.921446 -v 0.039466 -0.018886 0.101672 -vn -4.334998 2.658481 -1.433450 -v 0.039480 -0.018892 0.101606 -vn -4.144886 2.634588 -1.967643 -v 0.039533 -0.018907 0.101452 -vn -3.535380 2.624962 2.872951 -v 0.039712 -0.018798 0.102525 -vn -3.900466 2.474446 2.385742 -v 0.039615 -0.018813 0.102401 -vn -3.222510 -2.646368 3.103329 -v 0.039692 -0.018900 0.102501 -vn -4.039694 2.250431 2.045269 -v 0.039604 -0.018815 0.102383 -vn -4.081891 -2.638468 1.978783 -v 0.039509 -0.018935 0.102186 -vn -4.350912 2.641925 1.313879 -v 0.039498 -0.018838 0.102157 -vn -4.388482 -2.658360 1.206486 -v 0.039481 -0.018944 0.102094 -vn -4.495314 2.617486 0.705801 -v 0.039480 -0.018844 0.102094 -vn -4.532855 2.482491 0.230566 -v 0.039452 -0.018862 0.101915 -vn 0.183755 -2.667689 4.582179 -v 0.040450 -0.018818 0.102850 -vn -0.396381 2.669403 4.558724 -v 0.040450 -0.018719 0.102850 -vn -0.401246 -2.585411 4.550405 -v 0.040314 -0.018831 0.102840 -vn -1.168471 2.572936 4.410227 -v 0.040230 -0.018740 0.102825 -vn -1.256571 -2.668504 4.390297 -v 0.040120 -0.018850 0.102793 -vn -1.644719 2.606338 4.266173 -v 0.040152 -0.018747 0.102804 -vn -2.287407 2.601113 3.946074 -v 0.039995 -0.018763 0.102741 -vn -2.046008 -2.662439 4.042316 -v 0.039973 -0.018865 0.102728 -vn -2.910153 2.253956 3.497959 -v 0.039850 -0.018780 0.102650 -vn -3.116231 2.254562 3.306628 -v 0.039795 -0.018787 0.102606 -vn -1.929223 2.653680 -4.126995 -v 0.039959 -0.018370 0.100979 -vn -1.216448 2.640682 -4.412561 -v 0.040180 -0.018393 0.100887 -vn -1.514948 -2.619432 -4.287651 -v 0.040182 -0.018492 0.100887 -vn -0.644584 2.658609 -4.527450 -v 0.040211 -0.018396 0.100879 -vn -0.753932 -2.543549 -4.498522 -v 0.040356 -0.018509 0.100854 -vn 0.317994 2.621102 -4.508634 -v 0.040450 -0.018419 0.100850 -vn -0.097579 -2.624891 -4.545157 -v 0.040450 -0.018518 0.100850 -vn -1.990631 -2.449154 -4.084526 -v 0.040027 -0.018476 0.100944 -vn -2.667094 -2.658178 -3.704255 -v 0.039933 -0.018466 0.100994 -vn -2.590732 2.523901 -3.770752 -v 0.039840 -0.018356 0.101058 -vn -3.301157 -2.693762 -3.159431 -v 0.039743 -0.018443 0.101143 -vn -3.101967 2.656187 -3.345138 -v 0.039743 -0.018344 0.101143 -vn -3.659851 -2.595621 -2.739396 -v 0.039712 -0.018438 0.101175 -vn -3.714281 2.611321 -2.551918 -v 0.039594 -0.018320 0.101333 -vn -4.050059 -2.629489 -2.087749 -v 0.039579 -0.018417 0.101359 -vn -4.282169 -2.474964 -1.549029 -v 0.039533 -0.018407 0.101452 -vn -4.224533 2.641256 -1.406914 -v 0.039487 -0.018294 0.101582 -vn -4.471436 -2.572035 -0.718399 -v 0.039479 -0.018391 0.101611 -vn -4.454157 2.584454 -0.275401 -v 0.039450 -0.018268 0.101850 -vn -4.497743 -2.561354 0.248890 -v 0.039450 -0.018367 0.101850 -vn -4.458132 2.562877 0.744671 -v 0.039479 -0.018245 0.102089 -vn -4.269987 -2.589892 1.450934 -v 0.039487 -0.018341 0.102119 -vn -4.268370 2.493158 1.624276 -v 0.039548 -0.018226 0.102283 -vn -3.705469 -2.573414 2.592482 -v 0.039594 -0.018315 0.102367 -vn -4.002496 2.647213 2.170188 -v 0.039579 -0.018219 0.102341 -vn -3.554888 2.641858 2.862424 -v 0.039743 -0.018194 0.102557 -vn -3.132519 -2.620549 3.302644 -v 0.039743 -0.018292 0.102557 -vn -3.188869 2.671165 3.299469 -v 0.039775 -0.018189 0.102588 -vn -2.548370 -2.594316 3.806693 -v 0.039850 -0.018279 0.102650 -vn -2.541395 2.624125 3.778105 -v 0.039933 -0.018170 0.102706 -vn -1.898634 -2.570931 4.150186 -v 0.039959 -0.018266 0.102721 -vn -1.270788 -2.676276 4.399613 -v 0.040151 -0.018246 0.102804 -vn 0.053286 -2.637234 4.555882 -v 0.040450 -0.018217 0.102850 -vn -0.359084 2.627714 4.508005 -v 0.040450 -0.018119 0.102850 -vn -0.623793 -2.589201 4.522341 -v 0.040211 -0.018240 0.102821 -vn -1.306797 2.671423 4.346826 -v 0.040182 -0.018145 0.102813 -vn -2.025532 2.476326 4.091672 -v 0.040085 -0.018154 0.102781 -vn -4.496434 -2.614519 0.222662 -v 0.039450 -0.017767 0.101850 -vn -4.444256 2.624158 -1.048336 -v 0.039475 -0.017690 0.101628 -vn -4.418679 -2.629852 -0.836544 -v 0.039479 -0.017790 0.101611 -vn -4.216959 2.596947 -1.709770 -v 0.039487 -0.017694 0.101581 -vn -4.058316 -2.544628 -1.962395 -v 0.039579 -0.017816 0.101359 -vn -3.712739 2.553592 -2.539062 -v 0.039594 -0.017720 0.101333 -vn -3.479460 -2.602596 -2.933083 -v 0.039743 -0.017842 0.101143 -vn -3.106103 2.609278 -3.306048 -v 0.039743 -0.017743 0.101143 -vn -3.020057 -2.655367 -3.458239 -v 0.039840 -0.017855 0.101058 -vn -2.553437 2.667244 -3.791487 -v 0.039850 -0.017757 0.101050 -vn -2.451704 -2.632957 -3.846405 -v 0.039933 -0.017865 0.100994 -vn -1.854003 2.578785 -4.142171 -v 0.039959 -0.017769 0.100979 -vn -1.448837 -2.593250 -4.256545 -v 0.040182 -0.017891 0.100887 -vn 0.104425 2.618141 -4.548641 -v 0.040450 -0.017819 0.100850 -vn -0.316055 -2.642093 -4.461520 -v 0.040450 -0.017917 0.100850 -vn -0.597012 2.591727 -4.547088 -v 0.040211 -0.017795 0.100879 -vn -1.189659 2.664389 -4.407870 -v 0.040189 -0.017793 0.100885 -vn -4.042472 2.630295 2.007493 -v 0.039579 -0.017619 0.102341 -vn -4.447237 2.627885 0.985969 -v 0.039479 -0.017645 0.102089 -vn -4.296840 -2.567350 1.475187 -v 0.039487 -0.017742 0.102118 -vn -4.554947 2.475198 0.392218 -v 0.039462 -0.017654 0.102003 -vn -4.528221 2.603446 -0.333222 -v 0.039450 -0.017668 0.101850 -vn -4.081516 -2.473234 2.040457 -v 0.039548 -0.017725 0.102283 -vn -3.662107 -2.578829 2.723260 -v 0.039594 -0.017715 0.102367 -vn -3.401084 2.614773 2.972014 -v 0.039743 -0.017593 0.102557 -vn -1.962160 -2.636611 4.075353 -v 0.039959 -0.017666 0.102721 -vn -2.725439 2.617740 3.661654 -v 0.039933 -0.017570 0.102706 -vn -2.743394 -2.593482 3.664299 -v 0.039775 -0.017688 0.102588 -vn -3.204455 -2.640984 3.255064 -v 0.039743 -0.017692 0.102557 -vn 0.255274 -2.638694 4.542412 -v 0.040450 -0.017617 0.102850 -vn -0.265620 2.643718 4.570675 -v 0.040450 -0.017518 0.102850 -vn -0.487674 -2.553770 4.550425 -v 0.040281 -0.017633 0.102836 -vn -0.678593 2.531499 4.509351 -v 0.040355 -0.017527 0.102846 -vn -0.985241 -2.609609 4.448275 -v 0.040211 -0.017640 0.102821 -vn -1.540799 2.560297 4.285325 -v 0.040182 -0.017544 0.102813 -vn -2.121623 2.548608 4.044913 -v 0.039995 -0.017563 0.102740 -vn -4.316447 2.462845 1.457255 -v 0.039508 -0.017035 0.102186 -vn -4.500907 2.664140 0.704990 -v 0.039479 -0.017045 0.102089 -vn -4.245796 -2.668750 1.596023 -v 0.039487 -0.017141 0.102119 -vn 0.129509 2.613124 -4.535330 -v 0.040450 -0.017218 0.100850 -vn -0.332015 -2.622564 -4.484263 -v 0.040450 -0.017317 0.100850 -vn -0.833012 2.555497 -4.417453 -v 0.040211 -0.017195 0.100879 -vn -1.456322 -2.554633 -4.248878 -v 0.040182 -0.017291 0.100887 -vn -1.800812 2.591892 -4.162809 -v 0.039959 -0.017169 0.100979 -vn -2.435320 -2.662183 -3.839744 -v 0.039933 -0.017265 0.100994 -vn -2.449527 2.687270 -3.853485 -v 0.039884 -0.017160 0.101026 -vn -2.990100 -2.637592 -3.467676 -v 0.039850 -0.017256 0.101050 -vn -2.932659 2.686798 -3.514246 -v 0.039743 -0.017143 0.101143 -vn -3.348822 -2.691715 -3.112337 -v 0.039743 -0.017242 0.101143 -vn -3.319870 2.662703 -3.168216 -v 0.039715 -0.017139 0.101172 -vn -3.611300 -2.672369 -2.782142 -v 0.039712 -0.017238 0.101175 -vn -3.741031 2.657673 -2.597335 -v 0.039594 -0.017120 0.101333 -vn -3.834323 -2.560517 -2.473374 -v 0.039625 -0.017225 0.101285 -vn -4.143519 -2.658262 -1.845882 -v 0.039579 -0.017216 0.101359 -vn -4.137241 2.470032 -1.932186 -v 0.039518 -0.017103 0.101487 -vn -4.431521 -2.581653 -0.793961 -v 0.039479 -0.017190 0.101611 -vn -4.355386 2.618154 -1.336358 -v 0.039487 -0.017094 0.101581 -vn -4.503775 2.560267 -0.253051 -v 0.039450 -0.017068 0.101850 -vn -4.524388 -2.560039 0.204443 -v 0.039450 -0.017167 0.101850 -vn -4.468865 -2.413554 0.783441 -v 0.039462 -0.017153 0.102003 -vn -4.104278 2.556794 1.969242 -v 0.039579 -0.017019 0.102341 -vn -3.745862 -2.600798 2.512369 -v 0.039594 -0.017116 0.102367 -vn -3.711414 2.551327 2.682722 -v 0.039691 -0.017000 0.102502 -vn -2.947843 -2.606976 3.428149 -v 0.039743 -0.017092 0.102557 -vn -3.260119 2.609138 3.197236 -v 0.039743 -0.016993 0.102557 -vn -2.214126 -2.652461 3.989476 -v 0.039959 -0.017067 0.102721 -vn -2.600378 2.548577 3.698243 -v 0.039933 -0.016970 0.102706 -vn -1.670881 -2.526795 4.256595 -v 0.039995 -0.017063 0.102740 -vn -1.452858 2.575738 4.265215 -v 0.040182 -0.016944 0.102813 -vn -0.845648 -2.545780 4.477040 -v 0.040211 -0.017041 0.102821 -vn -0.404391 2.670967 4.530156 -v 0.040450 -0.016918 0.102850 -vn -0.346218 -2.383588 4.546148 -v 0.040355 -0.017027 0.102845 -vn 0.396748 -2.661867 4.541423 -v 0.040450 -0.017018 0.102850 -vn -1.059172 -2.404831 -4.397066 -v 0.040208 -0.016695 0.100881 -vn -1.900111 -2.710532 -4.129440 -v 0.040120 -0.016686 0.100907 -vn -1.044436 2.617780 -4.417859 -v 0.040136 -0.016588 0.100901 -vn -0.396700 -2.641316 -4.517836 -v 0.040450 -0.016718 0.100850 -vn -0.354972 2.413004 -4.519625 -v 0.040388 -0.016612 0.100852 -vn 0.448919 2.673136 -4.537486 -v 0.040450 -0.016618 0.100850 -vn -4.234413 -2.692245 -1.562380 -v 0.039519 -0.016603 0.101487 -vn -3.806899 2.351558 -2.454594 -v 0.039552 -0.016512 0.101410 -vn -3.437218 -2.566963 -2.765261 -v 0.039715 -0.016639 0.101172 -vn -3.245472 2.520027 -3.104464 -v 0.039702 -0.016538 0.101186 -vn -2.711360 -2.587784 -3.537900 -v 0.039884 -0.016660 0.101026 -vn -2.362499 2.531297 -3.870392 -v 0.039888 -0.016562 0.101023 -vn -1.860124 2.301208 -4.131645 -v 0.040027 -0.016577 0.100944 -vn -4.491021 -2.676824 -0.789666 -v 0.039481 -0.016591 0.101606 -vn -4.513314 -2.634111 0.259433 -v 0.039450 -0.016568 0.101850 -vn -4.554785 2.578374 -0.541103 -v 0.039451 -0.016472 0.101810 -vn -4.466074 2.493441 -0.921446 -v 0.039466 -0.016486 0.101672 -vn -4.334986 2.658488 -1.433464 -v 0.039480 -0.016492 0.101606 -vn -4.145000 2.634730 -1.967558 -v 0.039533 -0.016507 0.101452 -vn -3.535409 2.624933 2.872927 -v 0.039712 -0.016398 0.102525 -vn -3.900447 2.474239 2.385739 -v 0.039615 -0.016413 0.102401 -vn -3.222279 -2.646534 3.103351 -v 0.039692 -0.016500 0.102501 -vn -4.039642 2.250386 2.045344 -v 0.039604 -0.016415 0.102383 -vn -4.081637 -2.638447 1.978790 -v 0.039509 -0.016535 0.102186 -vn -4.350961 2.641970 1.313918 -v 0.039498 -0.016438 0.102157 -vn -4.388291 -2.658470 1.206485 -v 0.039481 -0.016544 0.102094 -vn -4.495243 2.617536 0.705847 -v 0.039480 -0.016444 0.102094 -vn -4.532893 2.482596 0.230512 -v 0.039452 -0.016462 0.101915 -vn 0.183677 -2.667736 4.582071 -v 0.040450 -0.016418 0.102850 -vn -0.396408 2.669388 4.558718 -v 0.040450 -0.016319 0.102850 -vn -0.401093 -2.585649 4.550274 -v 0.040314 -0.016431 0.102840 -vn -1.168416 2.572799 4.410217 -v 0.040230 -0.016340 0.102825 -vn -1.256441 -2.668597 4.390116 -v 0.040120 -0.016450 0.102793 -vn -1.644716 2.606344 4.266161 -v 0.040152 -0.016347 0.102804 -vn -2.287414 2.601043 3.946070 -v 0.039995 -0.016363 0.102741 -vn -2.045795 -2.662725 4.042285 -v 0.039973 -0.016465 0.102728 -vn -2.910042 2.253681 3.497957 -v 0.039850 -0.016380 0.102650 -vn -3.116427 2.254881 3.306569 -v 0.039795 -0.016387 0.102606 -vn -1.929213 2.653646 -4.126997 -v 0.039959 -0.015970 0.100979 -vn -1.216445 2.640679 -4.412566 -v 0.040180 -0.015993 0.100887 -vn -1.515031 -2.619495 -4.287507 -v 0.040182 -0.016092 0.100887 -vn -0.644605 2.658639 -4.527445 -v 0.040211 -0.015996 0.100879 -vn -0.753928 -2.543544 -4.498358 -v 0.040356 -0.016109 0.100854 -vn 0.318012 2.621115 -4.508636 -v 0.040450 -0.016019 0.100850 -vn -0.097523 -2.624955 -4.545064 -v 0.040450 -0.016118 0.100850 -vn -1.992061 -2.452088 -4.077361 -v 0.040027 -0.016076 0.100944 -vn -2.663998 -2.670270 -3.674030 -v 0.039933 -0.016066 0.100994 -vn -2.590719 2.523907 -3.770747 -v 0.039840 -0.015956 0.101058 -vn -3.279501 -2.700895 -3.165498 -v 0.039743 -0.016043 0.101143 -vn -3.101967 2.656186 -3.345138 -v 0.039743 -0.015944 0.101143 -vn -3.667881 -2.591651 -2.740473 -v 0.039712 -0.016038 0.101175 -vn -3.714278 2.611325 -2.551922 -v 0.039594 -0.015920 0.101333 -vn -4.049981 -2.629540 -2.087677 -v 0.039579 -0.016017 0.101359 -vn -4.282096 -2.474957 -1.548948 -v 0.039533 -0.016007 0.101452 -vn -4.224536 2.641282 -1.406901 -v 0.039487 -0.015894 0.101582 -vn -4.471352 -2.572094 -0.718345 -v 0.039479 -0.015991 0.101611 -vn -4.454155 2.584456 -0.275400 -v 0.039450 -0.015868 0.101850 -vn -4.497648 -2.561401 0.248896 -v 0.039450 -0.015967 0.101850 -vn -4.458148 2.562868 0.744651 -v 0.039479 -0.015845 0.102089 -vn -4.269893 -2.589940 1.450913 -v 0.039487 -0.015941 0.102119 -vn -4.268296 2.493201 1.624292 -v 0.039548 -0.015826 0.102283 -vn -3.705387 -2.573459 2.592434 -v 0.039594 -0.015915 0.102367 -vn -4.002499 2.647197 2.170281 -v 0.039579 -0.015819 0.102341 -vn -3.554885 2.641860 2.862421 -v 0.039743 -0.015794 0.102557 -vn -3.132450 -2.620586 3.302592 -v 0.039743 -0.015892 0.102557 -vn -3.188880 2.671143 3.299468 -v 0.039775 -0.015789 0.102588 -vn -2.548283 -2.594393 3.806641 -v 0.039850 -0.015879 0.102650 -vn -2.541341 2.624126 3.778076 -v 0.039933 -0.015770 0.102706 -vn -1.898513 -2.570921 4.150147 -v 0.039959 -0.015866 0.102721 -vn -1.270817 -2.676545 4.399564 -v 0.040151 -0.015846 0.102804 -vn 0.053261 -2.637264 4.555843 -v 0.040450 -0.015817 0.102850 -vn -0.359098 2.627727 4.508002 -v 0.040450 -0.015719 0.102850 -vn -0.623876 -2.589204 4.522213 -v 0.040211 -0.015840 0.102821 -vn -1.306843 2.671342 4.346807 -v 0.040182 -0.015745 0.102813 -vn -2.025496 2.476074 4.091676 -v 0.040085 -0.015754 0.102781 -vn -4.496434 -2.614519 0.222662 -v 0.039450 -0.015367 0.101850 -vn -4.444275 2.624149 -1.048353 -v 0.039475 -0.015290 0.101628 -vn -4.418676 -2.629853 -0.836545 -v 0.039479 -0.015390 0.101611 -vn -4.216966 2.596942 -1.709778 -v 0.039487 -0.015294 0.101581 -vn -4.058311 -2.544629 -1.962392 -v 0.039579 -0.015416 0.101359 -vn -3.712739 2.553592 -2.539062 -v 0.039594 -0.015320 0.101333 -vn -3.479446 -2.602602 -2.933078 -v 0.039743 -0.015442 0.101143 -vn -3.106103 2.609278 -3.306048 -v 0.039743 -0.015343 0.101143 -vn -3.020042 -2.655380 -3.458220 -v 0.039840 -0.015455 0.101058 -vn -2.553437 2.667244 -3.791487 -v 0.039850 -0.015357 0.101050 -vn -2.451689 -2.632973 -3.846380 -v 0.039933 -0.015465 0.100994 -vn -1.854003 2.578785 -4.142171 -v 0.039959 -0.015369 0.100979 -vn -1.448810 -2.593273 -4.256505 -v 0.040182 -0.015491 0.100887 -vn 0.104379 2.618133 -4.548667 -v 0.040450 -0.015419 0.100850 -vn -0.316061 -2.642095 -4.461520 -v 0.040450 -0.015517 0.100850 -vn -0.597011 2.591726 -4.547088 -v 0.040211 -0.015395 0.100879 -vn -1.189659 2.664389 -4.407870 -v 0.040189 -0.015393 0.100885 -vn -4.042484 2.630291 2.007485 -v 0.039579 -0.015219 0.102341 -vn -4.447237 2.627885 0.985969 -v 0.039479 -0.015245 0.102089 -vn -4.296840 -2.567350 1.475187 -v 0.039487 -0.015342 0.102118 -vn -4.554962 2.475192 0.392253 -v 0.039462 -0.015254 0.102003 -vn -4.528180 2.603467 -0.333215 -v 0.039450 -0.015268 0.101850 -vn -4.081504 -2.473239 2.040458 -v 0.039548 -0.015325 0.102283 -vn -3.662103 -2.578835 2.723251 -v 0.039594 -0.015315 0.102367 -vn -3.401057 2.614789 2.971986 -v 0.039743 -0.015193 0.102557 -vn -1.962160 -2.636610 4.075353 -v 0.039959 -0.015266 0.102721 -vn -2.725509 2.617709 3.661674 -v 0.039933 -0.015170 0.102706 -vn -2.743394 -2.593485 3.664299 -v 0.039775 -0.015288 0.102588 -vn -3.204455 -2.640984 3.255064 -v 0.039743 -0.015292 0.102557 -vn 0.255274 -2.638694 4.542412 -v 0.040450 -0.015217 0.102850 -vn -0.265583 2.643741 4.570637 -v 0.040450 -0.015118 0.102850 -vn -0.487671 -2.553775 4.550425 -v 0.040281 -0.015233 0.102836 -vn -0.678621 2.531519 4.509315 -v 0.040355 -0.015127 0.102846 -vn -0.985242 -2.609610 4.448275 -v 0.040211 -0.015240 0.102821 -vn -1.540805 2.560285 4.285351 -v 0.040182 -0.015144 0.102813 -vn -2.121643 2.548639 4.044835 -v 0.039995 -0.015163 0.102740 -vn -4.316445 2.462836 1.457257 -v 0.039508 -0.014635 0.102186 -vn -4.500904 2.664142 0.704985 -v 0.039479 -0.014645 0.102089 -vn -4.245835 -2.668728 1.596056 -v 0.039487 -0.014741 0.102119 -vn 0.129509 2.613124 -4.535330 -v 0.040450 -0.014818 0.100850 -vn -0.332015 -2.622564 -4.484263 -v 0.040450 -0.014917 0.100850 -vn -0.833012 2.555497 -4.417453 -v 0.040211 -0.014795 0.100879 -vn -1.456322 -2.554633 -4.248878 -v 0.040182 -0.014891 0.100887 -vn -1.800812 2.591892 -4.162809 -v 0.039959 -0.014769 0.100979 -vn -2.435320 -2.662183 -3.839744 -v 0.039933 -0.014865 0.100994 -vn -2.449527 2.687270 -3.853485 -v 0.039884 -0.014761 0.101026 -vn -2.990100 -2.637592 -3.467676 -v 0.039850 -0.014856 0.101050 -vn -2.932659 2.686798 -3.514246 -v 0.039743 -0.014743 0.101143 -vn -3.348822 -2.691715 -3.112337 -v 0.039743 -0.014842 0.101143 -vn -3.319870 2.662703 -3.168216 -v 0.039715 -0.014739 0.101172 -vn -3.611300 -2.672369 -2.782142 -v 0.039712 -0.014838 0.101175 -vn -3.741031 2.657673 -2.597335 -v 0.039594 -0.014720 0.101333 -vn -3.834323 -2.560517 -2.473374 -v 0.039625 -0.014825 0.101285 -vn -4.143515 -2.658264 -1.845874 -v 0.039579 -0.014816 0.101359 -vn -4.137244 2.470030 -1.932190 -v 0.039518 -0.014703 0.101487 -vn -4.431513 -2.581660 -0.793963 -v 0.039479 -0.014790 0.101611 -vn -4.355396 2.618148 -1.336363 -v 0.039487 -0.014694 0.101581 -vn -4.503781 2.560267 -0.253043 -v 0.039450 -0.014668 0.101850 -vn -4.524388 -2.560039 0.204443 -v 0.039450 -0.014767 0.101850 -vn -4.468834 -2.413561 0.783478 -v 0.039462 -0.014753 0.102003 -vn -4.104278 2.556793 1.969241 -v 0.039579 -0.014619 0.102341 -vn -3.745839 -2.600808 2.512361 -v 0.039594 -0.014716 0.102367 -vn -3.711472 2.551303 2.682698 -v 0.039691 -0.014600 0.102502 -vn -2.947866 -2.606962 3.428173 -v 0.039743 -0.014692 0.102557 -vn -3.260128 2.609163 3.197141 -v 0.039743 -0.014593 0.102557 -vn -2.214125 -2.652470 3.989455 -v 0.039959 -0.014667 0.102721 -vn -2.600352 2.548591 3.698231 -v 0.039933 -0.014570 0.102706 -vn -1.670873 -2.526809 4.256581 -v 0.039995 -0.014663 0.102740 -vn -1.452845 2.575736 4.265229 -v 0.040182 -0.014544 0.102813 -vn -0.845651 -2.545783 4.477034 -v 0.040211 -0.014641 0.102821 -vn -0.404443 2.670947 4.530187 -v 0.040450 -0.014518 0.102850 -vn -0.346218 -2.383588 4.546148 -v 0.040355 -0.014627 0.102845 -vn 0.396749 -2.661866 4.541423 -v 0.040450 -0.014618 0.102850 -vn -1.059172 -2.404831 -4.397066 -v 0.040208 -0.014295 0.100881 -vn -1.900123 -2.710533 -4.129427 -v 0.040120 -0.014286 0.100907 -vn -1.044417 2.617764 -4.417894 -v 0.040136 -0.014188 0.100901 -vn -0.396700 -2.641316 -4.517836 -v 0.040450 -0.014318 0.100850 -vn -0.354974 2.412995 -4.519641 -v 0.040388 -0.014212 0.100852 -vn 0.448924 2.673131 -4.537495 -v 0.040450 -0.014218 0.100850 -vn -4.234413 -2.692245 -1.562380 -v 0.039519 -0.014203 0.101487 -vn -3.806904 2.351556 -2.454593 -v 0.039552 -0.014112 0.101410 -vn -3.437192 -2.566972 -2.765265 -v 0.039715 -0.014239 0.101172 -vn -3.245474 2.520023 -3.104468 -v 0.039702 -0.014138 0.101186 -vn -2.711380 -2.587770 -3.537929 -v 0.039884 -0.014260 0.101026 -vn -2.362532 2.531291 -3.870390 -v 0.039888 -0.014162 0.101023 -vn -1.860075 2.301261 -4.131608 -v 0.040027 -0.014177 0.100944 -vn -4.491021 -2.676826 -0.789666 -v 0.039481 -0.014191 0.101606 -vn -4.513308 -2.634113 0.259436 -v 0.039450 -0.014168 0.101850 -vn -4.554816 2.578356 -0.541139 -v 0.039451 -0.014072 0.101810 -vn -4.466081 2.493436 -0.921452 -v 0.039466 -0.014086 0.101672 -vn -4.334986 2.658488 -1.433464 -v 0.039480 -0.014092 0.101606 -vn -4.145000 2.634730 -1.967558 -v 0.039533 -0.014107 0.101452 -vn -3.535409 2.624933 2.872927 -v 0.039712 -0.013998 0.102525 -vn -3.900447 2.474239 2.385739 -v 0.039615 -0.014013 0.102401 -vn -3.222279 -2.646534 3.103351 -v 0.039692 -0.014100 0.102501 -vn -4.039642 2.250386 2.045344 -v 0.039604 -0.014015 0.102383 -vn -4.081637 -2.638447 1.978790 -v 0.039509 -0.014135 0.102186 -vn -4.350961 2.641970 1.313918 -v 0.039498 -0.014038 0.102157 -vn -4.388288 -2.658472 1.206482 -v 0.039481 -0.014144 0.102094 -vn -4.495249 2.617532 0.705872 -v 0.039480 -0.014044 0.102094 -vn -4.532836 2.482635 0.230477 -v 0.039452 -0.014062 0.101915 -vn 0.183647 -2.667746 4.582055 -v 0.040450 -0.014018 0.102850 -vn -0.396407 2.669388 4.558718 -v 0.040450 -0.013919 0.102850 -vn -0.401116 -2.585622 4.550320 -v 0.040314 -0.014031 0.102840 -vn -1.168416 2.572797 4.410217 -v 0.040230 -0.013940 0.102825 -vn -1.256412 -2.668602 4.390110 -v 0.040120 -0.014050 0.102793 -vn -1.644716 2.606344 4.266161 -v 0.040152 -0.013947 0.102804 -vn -2.287414 2.601043 3.946070 -v 0.039995 -0.013963 0.102741 -vn -2.045795 -2.662725 4.042285 -v 0.039973 -0.014065 0.102728 -vn -2.910042 2.253681 3.497957 -v 0.039850 -0.013980 0.102650 -vn -3.116427 2.254881 3.306569 -v 0.039795 -0.013987 0.102606 -vn -1.898532 -2.570932 4.150117 -v 0.039959 -0.013466 0.102721 -vn -1.317253 -2.585403 4.378964 -v 0.040151 -0.013446 0.102804 -vn -2.649733 2.607736 3.703202 -v 0.039933 -0.013370 0.102706 -vn -1.929235 2.653643 -4.126999 -v 0.039959 -0.013570 0.100979 -vn -1.216264 2.640729 -4.412489 -v 0.040180 -0.013593 0.100887 -vn -1.515025 -2.619499 -4.287500 -v 0.040182 -0.013692 0.100887 -vn -0.644482 2.658583 -4.527558 -v 0.040211 -0.013596 0.100879 -vn -0.753927 -2.543552 -4.498341 -v 0.040356 -0.013709 0.100854 -vn 0.318012 2.621115 -4.508636 -v 0.040450 -0.013619 0.100850 -vn -0.097529 -2.624959 -4.545055 -v 0.040450 -0.013718 0.100850 -vn -1.992061 -2.452088 -4.077361 -v 0.040027 -0.013676 0.100944 -vn -2.663998 -2.670270 -3.674030 -v 0.039933 -0.013666 0.100994 -vn -2.590719 2.523907 -3.770747 -v 0.039840 -0.013556 0.101058 -vn -3.279501 -2.700895 -3.165498 -v 0.039743 -0.013643 0.101143 -vn -3.101967 2.656186 -3.345138 -v 0.039743 -0.013544 0.101143 -vn -3.667876 -2.591655 -2.740458 -v 0.039712 -0.013638 0.101175 -vn -3.714278 2.611325 -2.551922 -v 0.039594 -0.013520 0.101333 -vn -4.049968 -2.629547 -2.087677 -v 0.039579 -0.013617 0.101359 -vn -4.282096 -2.474957 -1.548948 -v 0.039533 -0.013607 0.101452 -vn -4.224536 2.641282 -1.406901 -v 0.039487 -0.013494 0.101582 -vn -4.471345 -2.572098 -0.718338 -v 0.039479 -0.013591 0.101611 -vn -4.454169 2.584448 -0.275418 -v 0.039450 -0.013468 0.101850 -vn -4.497641 -2.561407 0.248891 -v 0.039450 -0.013567 0.101850 -vn -4.533796 2.604816 0.560945 -v 0.039479 -0.013445 0.102089 -vn -4.243045 -2.517383 1.512179 -v 0.039487 -0.013541 0.102119 -vn -4.431122 2.662816 1.146410 -v 0.039480 -0.013445 0.102094 -vn -3.762208 -2.607574 2.494505 -v 0.039594 -0.013515 0.102367 -vn -4.163483 2.531396 1.831432 -v 0.039579 -0.013419 0.102341 -vn -3.706131 2.365244 2.637031 -v 0.039650 -0.013407 0.102450 -vn -3.331022 2.558091 3.080300 -v 0.039743 -0.013394 0.102557 -vn -3.080052 -2.551619 3.346795 -v 0.039743 -0.013492 0.102557 -vn -2.639431 -2.360832 3.704395 -v 0.039850 -0.013479 0.102650 -vn -0.666079 -2.664901 4.517160 -v 0.040211 -0.013440 0.102821 -vn 0.053261 -2.637264 4.555843 -v 0.040450 -0.013417 0.102850 -vn -0.251417 2.619265 4.537531 -v 0.040450 -0.013319 0.102850 -vn -0.713974 2.339525 4.475633 -v 0.040318 -0.013331 0.102841 -vn -1.577195 2.662785 4.248298 -v 0.040182 -0.013345 0.102813 -vn -2.311046 1.952185 3.810359 -v 0.039945 -0.013369 0.102713 -vn -4.045326 -2.628404 -1.994655 -v 0.039579 -0.013016 0.101359 -vn -3.652717 2.583368 -2.746661 -v 0.039594 -0.012920 0.101333 -vn -3.479493 -2.602579 -2.933102 -v 0.039743 -0.013042 0.101143 -vn -3.147918 2.608315 -3.290382 -v 0.039743 -0.012943 0.101143 -vn -2.984879 -2.607933 -3.482237 -v 0.039840 -0.013055 0.101058 -vn 0.095193 2.622656 -4.549638 -v 0.040450 -0.013019 0.100850 -vn -0.316509 -2.644078 -4.461513 -v 0.040450 -0.013117 0.100850 -vn -0.634374 2.584628 -4.530977 -v 0.040211 -0.012995 0.100879 -vn -1.429245 -2.632930 -4.264211 -v 0.040182 -0.013091 0.100887 -vn -1.330972 2.583432 -4.356468 -v 0.040151 -0.012990 0.100896 -vn -2.468798 -2.606247 -3.834520 -v 0.039933 -0.013065 0.100994 -vn -1.917311 2.572339 -4.104666 -v 0.039959 -0.012969 0.100979 -vn -2.703720 2.623545 -3.680027 -v 0.039806 -0.012952 0.101085 -vn -4.086914 2.639600 2.006182 -v 0.039579 -0.012819 0.102341 -vn -4.349166 2.520553 1.390632 -v 0.039501 -0.012838 0.102167 -vn -4.286034 -2.651749 1.460140 -v 0.039487 -0.012942 0.102118 -vn -4.515348 2.628276 0.683424 -v 0.039479 -0.012845 0.102089 -vn -4.471282 -2.592356 0.682776 -v 0.039452 -0.012961 0.101915 -vn -4.561025 2.689733 -0.131856 -v 0.039450 -0.012868 0.101850 -vn -4.522211 -2.720394 0.132701 -v 0.039450 -0.012967 0.101850 -vn -4.513960 2.553596 -0.719734 -v 0.039453 -0.012876 0.101774 -vn -4.417241 -2.605385 -0.845303 -v 0.039479 -0.012990 0.101611 -vn -4.290045 2.554286 -1.522915 -v 0.039487 -0.012894 0.101581 -vn -4.045236 2.548449 -2.125173 -v 0.039560 -0.012914 0.101395 -vn -4.072867 -2.481921 2.024038 -v 0.039548 -0.012925 0.102283 -vn -3.682957 -2.625195 2.694694 -v 0.039594 -0.012915 0.102367 -vn -3.690839 2.565036 2.699543 -v 0.039698 -0.012800 0.102509 -vn -3.165827 -2.703066 3.300258 -v 0.039743 -0.012892 0.102557 -vn -3.270608 2.703483 3.143425 -v 0.039743 -0.012793 0.102557 -vn -2.722271 -2.600661 3.660149 -v 0.039775 -0.012888 0.102588 -vn -2.711347 2.623766 3.638210 -v 0.039933 -0.012770 0.102706 -vn -1.977407 -2.645167 4.058778 -v 0.039959 -0.012866 0.102721 -vn -2.043496 2.502812 4.062665 -v 0.040012 -0.012762 0.102749 -vn -1.524840 2.577967 4.269238 -v 0.040182 -0.012744 0.102813 -vn -0.997947 -2.642767 4.440245 -v 0.040211 -0.012840 0.102821 -vn -0.455905 -2.577084 4.547032 -v 0.040281 -0.012833 0.102836 -vn -0.648061 2.642135 4.528312 -v 0.040393 -0.012724 0.102848 -vn 0.294537 -2.679899 4.533866 -v 0.040450 -0.012817 0.102850 -vn -0.178758 2.699159 4.570447 -v 0.040450 -0.012718 0.102850 -vn -4.221843 2.286650 1.619073 -v 0.039528 -0.012230 0.102237 -vn -4.467885 2.658931 0.741985 -v 0.039479 -0.012245 0.102089 -vn -4.267478 -2.642643 1.593196 -v 0.039487 -0.012341 0.102119 -vn -4.163852 -2.653174 -1.867956 -v 0.039579 -0.012416 0.101359 -vn -4.122241 2.318880 -1.868561 -v 0.039528 -0.012306 0.101463 -vn -3.693772 2.669919 -2.635547 -v 0.039594 -0.012320 0.101333 -vn 0.035947 2.618424 -4.576509 -v 0.040450 -0.012418 0.100850 -vn -0.435201 -2.624677 -4.510019 -v 0.040450 -0.012517 0.100850 -vn -0.703083 2.570857 -4.499622 -v 0.040211 -0.012395 0.100879 -vn -1.403245 -2.638738 -4.266789 -v 0.040182 -0.012491 0.100887 -vn -1.493086 2.475688 -4.314962 -v 0.040080 -0.012382 0.100921 -vn -2.485461 -2.642701 -3.813184 -v 0.039933 -0.012465 0.100994 -vn -2.059721 2.619453 -4.065480 -v 0.039959 -0.012369 0.100979 -vn -2.949008 -2.493619 -3.484207 -v 0.039850 -0.012456 0.101050 -vn -2.849847 2.687214 -3.592439 -v 0.039750 -0.012344 0.101136 -vn -3.351764 -2.701838 -3.106978 -v 0.039743 -0.012442 0.101143 -vn -3.212821 2.712987 -3.259880 -v 0.039743 -0.012343 0.101143 -vn -3.616547 -2.611164 -2.772451 -v 0.039712 -0.012438 0.101175 -vn -3.836495 -2.558156 -2.479496 -v 0.039625 -0.012425 0.101285 -vn -4.302432 2.545283 -1.418711 -v 0.039487 -0.012294 0.101581 -vn -4.445747 -2.541151 -0.823835 -v 0.039479 -0.012390 0.101611 -vn -4.491663 2.567116 -0.244827 -v 0.039450 -0.012268 0.101850 -vn -4.544882 -2.550733 0.193302 -v 0.039450 -0.012367 0.101850 -vn -4.484487 -2.403962 0.794298 -v 0.039462 -0.012353 0.102003 -vn -4.044827 2.544709 2.046911 -v 0.039579 -0.012219 0.102341 -vn -3.710858 -2.546431 2.562010 -v 0.039594 -0.012316 0.102367 -vn -3.586739 2.653545 2.844734 -v 0.039743 -0.012193 0.102557 -vn -3.001944 -2.565027 3.363472 -v 0.039743 -0.012292 0.102557 -vn -3.191636 2.625346 3.283769 -v 0.039750 -0.012192 0.102564 -vn -2.175764 -2.613219 4.007366 -v 0.039959 -0.012267 0.102721 -vn -2.664727 2.549772 3.686870 -v 0.039933 -0.012170 0.102706 -vn -1.863437 2.448948 4.147331 -v 0.040080 -0.012154 0.102779 -vn -1.749987 -2.539581 4.214959 -v 0.039995 -0.012263 0.102740 -vn -1.377188 2.576014 4.321479 -v 0.040182 -0.012144 0.102813 -vn -0.829965 -2.554431 4.461180 -v 0.040211 -0.012241 0.102821 -vn -0.487613 2.695853 4.544969 -v 0.040450 -0.012118 0.102850 -vn -0.352292 -2.392943 4.528747 -v 0.040355 -0.012227 0.102845 -vn 0.431524 -2.643484 4.519318 -v 0.040450 -0.012218 0.102850 -vn -1.075590 -2.395984 -4.408605 -v 0.040208 -0.011895 0.100881 -vn -1.892243 -2.696739 -4.156924 -v 0.040120 -0.011886 0.100907 -vn -1.048797 2.617709 -4.401235 -v 0.040136 -0.011788 0.100901 -vn -0.381760 -2.632359 -4.539330 -v 0.040450 -0.011918 0.100850 -vn -0.357673 2.421312 -4.503753 -v 0.040388 -0.011812 0.100852 -vn 0.453898 2.678672 -4.524906 -v 0.040450 -0.011818 0.100850 -vn -3.494988 -2.545419 -2.783757 -v 0.039715 -0.011839 0.101172 -vn -4.235451 -2.699533 -1.577268 -v 0.039519 -0.011803 0.101487 -vn -3.850766 2.341687 -2.384384 -v 0.039552 -0.011712 0.101410 -vn -3.480927 2.566917 -2.957613 -v 0.039697 -0.011737 0.101191 -vn -3.069604 2.666912 -3.406370 -v 0.039702 -0.011738 0.101186 -vn -2.730130 -2.558492 -3.605104 -v 0.039884 -0.011860 0.101026 -vn -2.363987 2.533862 -3.865589 -v 0.039888 -0.011762 0.101023 -vn -1.905264 2.245074 -4.092721 -v 0.040012 -0.011775 0.100951 -vn -4.476201 -2.669451 -0.734601 -v 0.039481 -0.011791 0.101606 -vn -4.466883 -2.371559 0.083682 -v 0.039450 -0.011768 0.101850 -vn -4.573819 2.629500 -0.188658 -v 0.039452 -0.011662 0.101915 -vn -4.452323 2.372808 -0.758543 -v 0.039466 -0.011686 0.101672 -vn -4.368409 2.661017 -1.383384 -v 0.039480 -0.011692 0.101606 -vn -4.257445 2.591146 -1.689900 -v 0.039501 -0.011699 0.101533 -vn -3.209621 2.376678 3.271343 -v 0.039795 -0.011587 0.102606 -vn -3.541599 2.622197 2.872763 -v 0.039712 -0.011598 0.102525 -vn -3.201056 -2.649022 3.086868 -v 0.039692 -0.011700 0.102501 -vn -3.933957 2.284535 2.250528 -v 0.039615 -0.011613 0.102401 -vn -4.058363 -2.704491 1.955515 -v 0.039509 -0.011735 0.102186 -vn -4.094398 2.233518 1.926384 -v 0.039560 -0.011623 0.102305 -vn -4.401232 2.657038 1.234165 -v 0.039498 -0.011638 0.102157 -vn -4.379321 -2.661363 1.212836 -v 0.039481 -0.011744 0.102094 -vn -4.507569 2.611281 0.726309 -v 0.039480 -0.011644 0.102094 -vn -4.561653 2.450015 0.344271 -v 0.039453 -0.011661 0.101926 -vn -2.179306 -2.495595 3.940664 -v 0.039973 -0.011665 0.102728 -vn -1.256786 -2.668568 4.390470 -v 0.040120 -0.011650 0.102793 -vn -2.399139 2.538355 3.830259 -v 0.039995 -0.011563 0.102741 -vn -2.706145 1.827069 3.477151 -v 0.039806 -0.011585 0.102615 -vn 0.192044 -2.658065 4.581387 -v 0.040450 -0.011618 0.102850 -vn -0.382678 2.668673 4.524043 -v 0.040450 -0.011519 0.102850 -vn -0.400899 -2.585632 4.550305 -v 0.040314 -0.011631 0.102840 -vn -1.142858 2.589427 4.385598 -v 0.040230 -0.011540 0.102825 -vn -1.645258 2.606473 4.265929 -v 0.040151 -0.011547 0.102804 -vn 0.394646 2.612618 -4.507635 -v 0.040450 -0.011219 0.100850 -vn -0.106641 -2.604759 -4.554482 -v 0.040450 -0.011318 0.100850 -vn -0.358800 2.612936 -4.564781 -v 0.040318 -0.011206 0.100859 -vn -0.719166 -2.621090 -4.517496 -v 0.040356 -0.011309 0.100854 -vn -0.969834 2.612883 -4.437241 -v 0.040211 -0.011196 0.100879 -vn -1.532024 -2.567222 -4.277244 -v 0.040182 -0.011292 0.100887 -vn -1.821341 2.620026 -4.177646 -v 0.039959 -0.011169 0.100979 -vn -1.990649 -2.449882 -4.080057 -v 0.040027 -0.011276 0.100944 -vn -2.292660 2.633517 -3.958279 -v 0.039945 -0.011168 0.100987 -vn -2.709697 -2.603073 -3.642038 -v 0.039933 -0.011266 0.100994 -vn -3.225429 -2.643572 -3.209379 -v 0.039743 -0.011243 0.101143 -vn -2.920094 2.620741 -3.484464 -v 0.039743 -0.011143 0.101143 -vn -3.650471 -2.659965 -2.766766 -v 0.039712 -0.011238 0.101175 -vn -3.533272 2.442877 -2.889289 -v 0.039650 -0.011130 0.101250 -vn -3.796091 2.597070 -2.524734 -v 0.039594 -0.011120 0.101333 -vn -4.050433 -2.629281 -2.087214 -v 0.039579 -0.011217 0.101359 -vn -4.281839 -2.475538 -1.548525 -v 0.039533 -0.011207 0.101452 -vn -4.271936 2.618374 -1.417108 -v 0.039487 -0.011094 0.101582 -vn -4.470904 -2.572328 -0.718574 -v 0.039479 -0.011191 0.101611 -vn -4.473656 2.577189 -0.259874 -v 0.039450 -0.011068 0.101850 -vn -4.496333 -2.561975 0.249701 -v 0.039450 -0.011167 0.101850 -vn -4.413737 2.577240 0.774049 -v 0.039479 -0.011045 0.102089 -vn -4.258211 -2.580721 1.460950 -v 0.039487 -0.011141 0.102119 -vn -4.247915 2.526900 1.622151 -v 0.039557 -0.011024 0.102300 -vn -3.705060 -2.574865 2.581288 -v 0.039594 -0.011115 0.102367 -vn -3.990334 2.661401 2.200825 -v 0.039579 -0.011019 0.102341 -vn -3.542954 2.639445 2.860530 -v 0.039743 -0.010993 0.102557 -vn -3.124446 -2.624643 3.299521 -v 0.039743 -0.011092 0.102557 -vn -3.157964 2.668742 3.321500 -v 0.039784 -0.010988 0.102596 -vn -2.546878 -2.614300 3.804870 -v 0.039850 -0.011079 0.102650 -vn -2.528165 2.630269 3.775722 -v 0.039933 -0.010970 0.102706 -vn -0.626212 -2.579852 4.493744 -v 0.040211 -0.011040 0.102821 -vn 0.038254 -2.655195 4.522714 -v 0.040450 -0.011017 0.102850 -vn -0.309478 2.623424 4.505193 -v 0.040450 -0.010918 0.102850 -vn -1.877931 -2.578913 4.140755 -v 0.039959 -0.011066 0.102721 -vn -1.251450 -2.620203 4.387150 -v 0.040151 -0.011046 0.102804 -vn -1.976068 2.507624 4.124167 -v 0.040098 -0.010952 0.102786 -vn -1.322004 2.626968 4.362105 -v 0.040182 -0.010944 0.102813 -vn -4.242554 -2.577814 1.521743 -v 0.039487 -0.010541 0.102118 -vn -4.436769 2.649371 1.017405 -v 0.039479 -0.010445 0.102089 -vn -4.546584 2.499100 0.434590 -v 0.039466 -0.010451 0.102027 -vn -4.500338 -2.618346 0.244920 -v 0.039450 -0.010567 0.101850 -vn -4.541831 2.598513 -0.266323 -v 0.039450 -0.010468 0.101850 -vn -4.462067 2.583408 -0.988256 -v 0.039470 -0.010487 0.101653 -vn -4.401807 -2.653606 -0.860578 -v 0.039479 -0.010590 0.101611 -vn -4.240458 2.586286 -1.672464 -v 0.039487 -0.010494 0.101581 -vn -4.045142 -2.553272 -1.945963 -v 0.039579 -0.010616 0.101359 -vn -3.721599 2.543939 -2.558223 -v 0.039594 -0.010520 0.101333 -vn -3.477821 -2.605418 -2.924816 -v 0.039743 -0.010642 0.101143 -vn -3.094900 2.609338 -3.310371 -v 0.039743 -0.010543 0.101143 -vn -3.025152 -2.649479 -3.452764 -v 0.039840 -0.010655 0.101058 -vn -2.511069 2.673920 -3.820206 -v 0.039863 -0.010558 0.101040 -vn -2.447158 -2.643174 -3.845571 -v 0.039933 -0.010665 0.100994 -vn -1.835068 2.582701 -4.152328 -v 0.039959 -0.010569 0.100979 -vn -1.470055 -2.561391 -4.266119 -v 0.040182 -0.010691 0.100887 -vn 0.096607 2.624313 -4.525385 -v 0.040450 -0.010618 0.100850 -vn -0.325423 -2.612966 -4.511058 -v 0.040450 -0.010717 0.100850 -vn -0.557956 2.608297 -4.526241 -v 0.040211 -0.010595 0.100879 -vn -1.136455 2.683445 -4.421722 -v 0.040202 -0.010594 0.100881 -vn -4.054935 2.547147 1.958900 -v 0.039579 -0.010419 0.102341 -vn -3.722284 -2.547055 2.547351 -v 0.039594 -0.010515 0.102367 -vn -3.475202 2.602277 2.932570 -v 0.039743 -0.010393 0.102557 -vn -3.122569 -2.604605 3.304835 -v 0.039743 -0.010492 0.102557 -vn -3.001870 2.653616 3.468778 -v 0.039842 -0.010380 0.102644 -vn -2.591434 -2.654964 3.769645 -v 0.039839 -0.010480 0.102642 -vn -2.446487 2.629811 3.839137 -v 0.039933 -0.010370 0.102706 -vn -1.888180 -2.573456 4.135211 -v 0.039959 -0.010467 0.102721 -vn -1.457144 2.615996 4.263766 -v 0.040182 -0.010344 0.102813 -vn 0.242754 -2.621769 4.465407 -v 0.040450 -0.010418 0.102850 -vn -0.437731 2.622873 4.537403 -v 0.040450 -0.010318 0.102850 -vn -0.604037 -2.596712 4.520028 -v 0.040211 -0.010441 0.102821 -vn -1.276791 -2.614459 4.382876 -v 0.040165 -0.010445 0.102809 -vn 0.473995 2.660584 4.557520 -v 0.040646 -0.020500 0.102831 -vn 1.413044 -2.537781 4.292265 -v 0.040684 -0.020756 0.102824 -vn 4.256851 -2.584518 -1.541302 -v 0.041413 -0.020545 0.101585 -vn 4.429929 2.600854 -0.987167 -v 0.041421 -0.020346 0.101611 -vn 4.560887 2.590099 -0.344695 -v 0.041441 -0.020356 0.101719 -vn 4.518181 -2.583579 -0.336324 -v 0.041449 -0.020580 0.101851 -vn 4.533648 2.593068 0.383226 -v 0.041450 -0.020369 0.101850 -vn 4.557227 -2.602993 0.528034 -v 0.041421 -0.020613 0.102094 -vn 4.269766 2.572189 1.454911 -v 0.041413 -0.020395 0.102119 -vn 4.403088 -2.609156 1.177626 -v 0.041413 -0.020617 0.102123 -vn 3.860384 2.617769 2.402851 -v 0.041306 -0.020421 0.102367 -vn 4.062757 -2.593538 1.974336 -v 0.041304 -0.020652 0.102370 -vn 3.494016 2.655565 2.953051 -v 0.041257 -0.020429 0.102441 -vn 3.701601 -2.672179 2.722205 -v 0.041188 -0.020677 0.102524 -vn 2.970978 2.624114 3.431429 -v 0.041157 -0.020444 0.102557 -vn 3.284247 -2.669960 3.133461 -v 0.041156 -0.020683 0.102557 -vn 2.435421 2.626827 3.857224 -v 0.040998 -0.020463 0.102686 -vn 2.469519 -2.544299 3.736651 -v 0.040938 -0.020720 0.102724 -vn 1.819357 2.625777 4.190885 -v 0.040941 -0.020470 0.102721 -vn 1.090716 2.639352 4.430524 -v 0.040689 -0.020496 0.102821 -vn 4.038289 2.549398 -1.999588 -v 0.041321 -0.020320 0.101359 -vn 3.738693 -2.520382 -2.521300 -v 0.041319 -0.020512 0.101354 -vn 3.512203 2.606161 -2.904975 -v 0.041157 -0.020294 0.101143 -vn 3.152412 -2.626188 -3.306524 -v 0.041157 -0.020477 0.101143 -vn 2.664388 -2.695375 -3.694512 -v 0.041136 -0.020473 0.101123 -vn 3.019449 2.612481 -3.432170 -v 0.041079 -0.020284 0.101073 -vn 1.942984 -2.642214 -4.047032 -v 0.040956 -0.020444 0.100989 -vn 1.462448 2.590373 -4.347581 -v 0.040718 -0.020244 0.100887 -vn 1.699332 2.242842 -4.185534 -v 0.040764 -0.020249 0.100901 -vn 2.488027 2.591198 -3.793072 -v 0.040967 -0.020270 0.100994 -vn 1.086665 -2.639514 -4.426392 -v 0.040710 -0.020409 0.100885 -vn 0.478788 -2.651517 -4.552026 -v 0.040655 -0.020401 0.100871 -vn 0.771631 2.626302 -4.507848 -v 0.040554 -0.020228 0.100855 -vn 0.269816 2.601117 4.575943 -v 0.040566 -0.019907 0.102843 -vn 1.044143 -2.680139 4.457771 -v 0.040646 -0.019998 0.102831 -vn 0.863601 2.680642 4.501697 -v 0.040687 -0.019896 0.102822 -vn 1.624353 -2.656497 4.269524 -v 0.040718 -0.019991 0.102813 -vn 1.564164 2.470968 4.274412 -v 0.040833 -0.019881 0.102774 -vn 2.540595 -2.559549 3.742326 -v 0.040967 -0.019965 0.102706 -vn 2.312506 2.615002 3.946401 -v 0.041024 -0.019860 0.102669 -vn 2.762334 2.273310 3.599119 -v 0.041056 -0.019856 0.102646 -vn 3.553927 2.651934 2.848495 -v 0.041248 -0.019830 0.102452 -vn 4.110180 -2.453531 1.909710 -v 0.041321 -0.019916 0.102341 -vn 4.071780 2.482802 1.949482 -v 0.041384 -0.019803 0.102207 -vn 4.444454 -2.654491 0.849795 -v 0.041421 -0.019890 0.102089 -vn 4.359862 2.656686 1.358959 -v 0.041420 -0.019792 0.102094 -vn 3.138754 2.575732 3.327251 -v 0.041188 -0.019839 0.102525 -vn 3.250647 -2.482247 3.150883 -v 0.041157 -0.019942 0.102557 -vn 3.823685 -2.645144 2.516117 -v 0.041257 -0.019928 0.102441 -vn 4.511527 2.531640 0.775324 -v 0.041444 -0.019778 0.101956 -vn 4.554971 -2.646791 -0.207181 -v 0.041450 -0.019867 0.101850 -vn 4.556267 2.662145 0.219365 -v 0.041450 -0.019769 0.101858 -vn 4.552277 2.646914 -0.393082 -v 0.041438 -0.019754 0.101695 -vn 4.501572 -2.626373 -0.824236 -v 0.041441 -0.019855 0.101719 -vn 4.496888 2.655462 -0.912067 -v 0.041420 -0.019745 0.101606 -vn 4.282251 -2.651788 -1.542014 -v 0.041413 -0.019841 0.101581 -vn 4.226117 2.550663 -1.583745 -v 0.041374 -0.019731 0.101467 -vn 3.915600 -2.461580 -2.354372 -v 0.041322 -0.019818 0.101361 -vn 3.755869 2.540527 -2.500665 -v 0.041232 -0.019704 0.101226 -vn 3.714216 -2.418508 -2.644993 -v 0.041306 -0.019815 0.101333 -vn 3.113702 -2.668129 -3.344109 -v 0.041157 -0.019792 0.101143 -vn 3.319006 2.675192 -3.103554 -v 0.041157 -0.019693 0.101143 -vn 2.613123 -2.472116 -3.752509 -v 0.041079 -0.019782 0.101073 -vn 2.405225 2.617955 -3.812178 -v 0.040936 -0.019667 0.100976 -vn 2.001765 -2.605490 -4.093102 -v 0.040941 -0.019766 0.100979 -vn 1.341693 -2.581092 -4.374590 -v 0.040764 -0.019748 0.100901 -vn 1.546565 2.673300 -4.261406 -v 0.040718 -0.019644 0.100887 -vn 0.697652 -2.664618 -4.511210 -v 0.040689 -0.019740 0.100879 -vn 0.814675 2.535375 -4.483162 -v 0.040574 -0.019630 0.100858 -vn 3.324142 -2.666471 3.163385 -v 0.041157 -0.019343 0.102557 -vn 2.994555 2.646377 3.375065 -v 0.041157 -0.019243 0.102557 -vn 2.912313 -2.492694 3.526274 -v 0.041024 -0.019359 0.102669 -vn 2.155310 2.685903 4.025173 -v 0.040941 -0.019269 0.102721 -vn 2.451933 -2.674774 3.839948 -v 0.040967 -0.019366 0.102706 -vn 1.650169 2.518040 4.256237 -v 0.040898 -0.019274 0.102744 -vn 1.456112 -2.580802 4.263753 -v 0.040718 -0.019392 0.102813 -vn 0.818517 2.558326 4.459902 -v 0.040689 -0.019295 0.102821 -vn 0.324824 2.421673 4.528448 -v 0.040537 -0.019310 0.102846 -vn 3.649907 -2.594978 2.765738 -v 0.041188 -0.019338 0.102525 -vn 3.860898 -2.589554 2.441836 -v 0.041283 -0.019324 0.102403 -vn 3.693575 2.669640 2.630235 -v 0.041306 -0.019220 0.102367 -vn 4.171218 -2.655413 1.855766 -v 0.041321 -0.019317 0.102341 -vn 4.117675 2.311908 1.861951 -v 0.041373 -0.019206 0.102234 -vn 4.304324 2.545550 1.414135 -v 0.041413 -0.019194 0.102119 -vn 4.432951 -2.547909 0.811505 -v 0.041421 -0.019291 0.102089 -vn 4.504984 2.558767 0.261581 -v 0.041450 -0.019168 0.101850 -vn 4.501631 -2.561583 -0.250265 -v 0.041450 -0.019268 0.101850 -vn 4.519715 2.579019 -0.660825 -v 0.041421 -0.019145 0.101611 -vn 4.363839 -2.660281 -1.307357 -v 0.041413 -0.019242 0.101581 -vn 4.366734 2.685635 -1.333294 -v 0.041396 -0.019137 0.101525 -vn 4.142066 -2.640997 -1.949685 -v 0.041385 -0.019233 0.101495 -vn 4.082134 2.631095 -1.985581 -v 0.041321 -0.019119 0.101359 -vn 3.736162 -2.626055 -2.590304 -v 0.041306 -0.019216 0.101333 -vn 3.723527 2.632855 -2.647690 -v 0.041217 -0.019102 0.101208 -vn 3.312670 -2.690830 -3.169165 -v 0.041190 -0.019197 0.101177 -vn 3.259174 2.620090 -3.174724 -v 0.041157 -0.019093 0.101143 -vn 2.834154 -2.630981 -3.561743 -v 0.041157 -0.019193 0.101143 -vn 2.245220 -2.675559 -3.961174 -v 0.040941 -0.019167 0.100979 -vn 2.563067 2.551994 -3.693218 -v 0.040967 -0.019070 0.100994 -vn 1.714797 -2.561574 -4.245308 -v 0.040924 -0.019165 0.100969 -vn 1.476355 2.569599 -4.234533 -v 0.040718 -0.019044 0.100887 -vn 0.870322 -2.547601 -4.457845 -v 0.040689 -0.019141 0.100879 -vn 0.444046 -2.288564 -4.513102 -v 0.040574 -0.019130 0.100858 -vn 4.469010 2.481155 0.856819 -v 0.041435 -0.018585 0.102024 -vn 4.240732 2.656970 1.623885 -v 0.041413 -0.018595 0.102119 -vn 4.482367 -2.656612 0.750410 -v 0.041421 -0.018691 0.102089 -vn 0.142365 2.675560 4.586922 -v 0.040514 -0.018713 0.102848 -vn 0.755127 -2.645774 4.518414 -v 0.040537 -0.018810 0.102846 -vn 0.831623 2.617923 4.488872 -v 0.040689 -0.018696 0.102821 -vn 1.484724 -2.626105 4.297894 -v 0.040718 -0.018792 0.102813 -vn 1.548626 2.629376 4.304795 -v 0.040860 -0.018678 0.102762 -vn 2.182376 -2.687130 4.019654 -v 0.040898 -0.018774 0.102744 -vn 2.171140 2.658113 3.994274 -v 0.040941 -0.018670 0.102721 -vn 2.752299 -2.566285 3.630875 -v 0.040967 -0.018766 0.102706 -vn 3.229155 -2.630801 3.214920 -v 0.041157 -0.018743 0.102557 -vn 2.946352 2.623590 3.366853 -v 0.041157 -0.018644 0.102557 -vn 3.658634 -2.603488 2.711211 -v 0.041188 -0.018739 0.102525 -vn 3.682703 2.598448 2.527395 -v 0.041306 -0.018621 0.102367 -vn 4.055432 -2.560555 2.026795 -v 0.041321 -0.018717 0.102341 -vn 4.237808 -2.289158 1.609640 -v 0.041373 -0.018705 0.102234 -vn 4.531671 2.581859 0.277629 -v 0.041450 -0.018569 0.101850 -vn 4.507937 -2.581973 -0.230522 -v 0.041450 -0.018668 0.101850 -vn 4.556741 2.506698 -0.461429 -v 0.041432 -0.018551 0.101662 -vn 4.374755 -2.673432 -1.329331 -v 0.041413 -0.018642 0.101581 -vn 4.461472 2.680233 -0.994202 -v 0.041421 -0.018546 0.101611 -vn 4.176563 -2.497365 -1.865745 -v 0.041396 -0.018636 0.101525 -vn 4.054257 2.603266 -1.979847 -v 0.041321 -0.018520 0.101359 -vn 3.763013 -2.597142 -2.558329 -v 0.041306 -0.018616 0.101333 -vn 3.416557 -2.495334 -3.031810 -v 0.041217 -0.018601 0.101209 -vn 3.467393 2.666083 -2.936766 -v 0.041157 -0.018494 0.101143 -vn 2.909642 -2.667872 -3.493572 -v 0.041157 -0.018593 0.101143 -vn 0.606292 -2.596684 -4.532274 -v 0.040689 -0.018541 0.100879 -vn 1.263242 2.678018 -4.390098 -v 0.040718 -0.018445 0.100887 -vn 1.157123 -2.701836 -4.424178 -v 0.040718 -0.018544 0.100887 -vn 1.841510 2.593284 -4.194789 -v 0.040759 -0.018449 0.100899 -vn 2.012442 -2.577391 -4.037541 -v 0.040941 -0.018567 0.100979 -vn 2.564016 2.551898 -3.753608 -v 0.040967 -0.018471 0.100994 -vn 2.912632 2.333400 -3.484238 -v 0.041075 -0.018483 0.101069 -vn 1.854998 2.665651 4.175651 -v 0.040941 -0.018070 0.102721 -vn 1.040326 2.657716 4.447044 -v 0.040689 -0.018096 0.102821 -vn 1.507919 -2.567920 4.305253 -v 0.040718 -0.018191 0.102813 -vn 0.511844 2.596570 4.549233 -v 0.040646 -0.018100 0.102831 -vn 0.671981 -2.611719 4.526262 -v 0.040514 -0.018211 0.102848 -vn 1.955769 -2.389644 4.111064 -v 0.040859 -0.018177 0.102762 -vn 2.663971 -2.665739 3.696608 -v 0.040967 -0.018165 0.102706 -vn 2.445765 2.599518 3.848165 -v 0.040998 -0.018063 0.102686 -vn 3.273745 -2.654552 3.202504 -v 0.041157 -0.018142 0.102557 -vn 2.960416 2.647382 3.443839 -v 0.041157 -0.018044 0.102557 -vn 3.648592 -2.661169 2.756628 -v 0.041188 -0.018138 0.102525 -vn 3.509816 2.554912 2.923782 -v 0.041257 -0.018029 0.102441 -vn 4.094311 -2.574246 1.917547 -v 0.041321 -0.018116 0.102341 -vn 3.836396 2.629854 2.448073 -v 0.041306 -0.018021 0.102367 -vn 4.255709 2.571994 1.520246 -v 0.041413 -0.017995 0.102119 -vn 4.444253 -2.644599 1.008442 -v 0.041421 -0.018090 0.102089 -vn 4.550519 -2.493233 0.436654 -v 0.041435 -0.018084 0.102025 -vn 4.537448 2.629183 0.354949 -v 0.041450 -0.017969 0.101850 -vn 4.529798 -2.637369 -0.254884 -v 0.041450 -0.018067 0.101850 -vn 4.567451 2.624638 -0.309966 -v 0.041441 -0.017956 0.101719 -vn 4.450418 -2.689550 -1.009849 -v 0.041432 -0.018049 0.101662 -vn 4.435365 2.663917 -0.983166 -v 0.041421 -0.017946 0.101611 -vn 4.224505 -2.589090 -1.672942 -v 0.041413 -0.018041 0.101581 -vn 4.060325 2.543319 -1.964721 -v 0.041321 -0.017920 0.101359 -vn 3.716541 -2.550894 -2.542584 -v 0.041306 -0.018015 0.101333 -vn 3.501996 2.612352 -2.917076 -v 0.041157 -0.017894 0.101143 -vn 3.133311 -2.618818 -3.292131 -v 0.041157 -0.017992 0.101143 -vn 3.041977 2.666356 -3.416981 -v 0.041079 -0.017884 0.101073 -vn 2.620120 -2.663102 -3.743693 -v 0.041075 -0.017982 0.101069 -vn 2.511351 2.635612 -3.783597 -v 0.040967 -0.017870 0.100994 -vn 1.936845 -2.604576 -4.110045 -v 0.040941 -0.017966 0.100979 -vn 1.844393 2.658021 -4.181841 -v 0.040764 -0.017849 0.100901 -vn 1.312411 -2.666936 -4.370807 -v 0.040759 -0.017947 0.100899 -vn 1.373167 2.693775 -4.379740 -v 0.040718 -0.017844 0.100887 -vn 0.662682 -2.665645 -4.492199 -v 0.040689 -0.017940 0.100879 -vn 0.776053 2.533031 -4.502339 -v 0.040554 -0.017828 0.100855 -vn 0.269788 2.601116 4.575945 -v 0.040566 -0.017507 0.102843 -vn 1.044360 -2.680167 4.457277 -v 0.040646 -0.017598 0.102831 -vn 0.863642 2.680723 4.501683 -v 0.040687 -0.017496 0.102822 -vn 1.630813 -2.663240 4.251002 -v 0.040718 -0.017591 0.102813 -vn 1.564152 2.470973 4.274405 -v 0.040833 -0.017481 0.102774 -vn 2.526746 -2.566244 3.736969 -v 0.040967 -0.017565 0.102706 -vn 2.312508 2.615000 3.946404 -v 0.041024 -0.017460 0.102669 -vn 2.762337 2.273311 3.599117 -v 0.041056 -0.017456 0.102646 -vn 3.553905 2.651876 2.848501 -v 0.041248 -0.017430 0.102452 -vn 4.109877 -2.453705 1.909555 -v 0.041321 -0.017516 0.102341 -vn 4.071779 2.482798 1.949494 -v 0.041384 -0.017403 0.102207 -vn 4.444150 -2.654649 0.849703 -v 0.041421 -0.017490 0.102089 -vn 4.359878 2.656679 1.358955 -v 0.041420 -0.017392 0.102094 -vn 3.138749 2.575736 3.327244 -v 0.041188 -0.017439 0.102525 -vn 3.250450 -2.482419 3.150560 -v 0.041157 -0.017542 0.102557 -vn 3.823584 -2.645387 2.515785 -v 0.041257 -0.017528 0.102441 -vn 4.511520 2.531643 0.775319 -v 0.041444 -0.017378 0.101956 -vn 4.554641 -2.646952 -0.207231 -v 0.041450 -0.017467 0.101850 -vn 4.556270 2.662146 0.219377 -v 0.041450 -0.017369 0.101858 -vn 4.552299 2.646948 -0.393042 -v 0.041438 -0.017354 0.101695 -vn 4.501200 -2.626643 -0.824396 -v 0.041441 -0.017455 0.101719 -vn 4.496905 2.655480 -0.912067 -v 0.041420 -0.017345 0.101606 -vn 4.281917 -2.651956 -1.542016 -v 0.041413 -0.017441 0.101581 -vn 4.226073 2.550637 -1.583705 -v 0.041374 -0.017331 0.101467 -vn 3.915077 -2.461649 -2.354446 -v 0.041322 -0.017418 0.101361 -vn 3.755847 2.540535 -2.500686 -v 0.041232 -0.017304 0.101226 -vn 3.686114 -2.428320 -2.647640 -v 0.041306 -0.017415 0.101333 -vn 3.110098 -2.678916 -3.320874 -v 0.041157 -0.017392 0.101143 -vn 3.318994 2.675173 -3.103549 -v 0.041157 -0.017293 0.101143 -vn 2.612836 -2.472255 -3.752370 -v 0.041079 -0.017382 0.101073 -vn 2.405179 2.617947 -3.812191 -v 0.040936 -0.017267 0.100976 -vn 2.001511 -2.605647 -4.092884 -v 0.040941 -0.017366 0.100979 -vn 1.341411 -2.581277 -4.374372 -v 0.040764 -0.017348 0.100901 -vn 1.546706 2.673312 -4.261395 -v 0.040718 -0.017244 0.100887 -vn 0.697547 -2.664851 -4.510948 -v 0.040689 -0.017340 0.100879 -vn 0.814614 2.535204 -4.483035 -v 0.040574 -0.017230 0.100858 -vn 3.323999 -2.666621 3.163181 -v 0.041157 -0.016943 0.102557 -vn 2.994573 2.646382 3.375043 -v 0.041157 -0.016843 0.102557 -vn 2.912311 -2.492767 3.526020 -v 0.041024 -0.016959 0.102669 -vn 2.155376 2.685953 4.025141 -v 0.040941 -0.016869 0.102721 -vn 2.451929 -2.674874 3.839594 -v 0.040967 -0.016966 0.102706 -vn 1.650204 2.517997 4.256188 -v 0.040898 -0.016874 0.102744 -vn 1.456051 -2.580932 4.263512 -v 0.040718 -0.016992 0.102813 -vn 0.818524 2.558325 4.459913 -v 0.040689 -0.016895 0.102821 -vn 0.324839 2.421632 4.528465 -v 0.040537 -0.016910 0.102846 -vn 3.649761 -2.595054 2.765522 -v 0.041188 -0.016938 0.102525 -vn 3.860770 -2.589760 2.441541 -v 0.041283 -0.016924 0.102403 -vn 3.693565 2.669605 2.630298 -v 0.041306 -0.016820 0.102367 -vn 4.168437 -2.657568 1.850501 -v 0.041321 -0.016917 0.102341 -vn 4.117633 2.311963 1.861944 -v 0.041373 -0.016806 0.102234 -vn 4.304353 2.545546 1.414094 -v 0.041413 -0.016794 0.102119 -vn 4.429246 -2.549735 0.813195 -v 0.041421 -0.016891 0.102089 -vn 4.504973 2.558769 0.261590 -v 0.041450 -0.016768 0.101850 -vn 4.501400 -2.561697 -0.250285 -v 0.041450 -0.016868 0.101850 -vn 4.519725 2.579013 -0.660823 -v 0.041421 -0.016745 0.101611 -vn 4.363578 -2.660395 -1.307350 -v 0.041413 -0.016842 0.101581 -vn 4.366757 2.685622 -1.333284 -v 0.041396 -0.016737 0.101525 -vn 4.141798 -2.641119 -1.949721 -v 0.041385 -0.016833 0.101495 -vn 4.082156 2.631109 -1.985584 -v 0.041321 -0.016719 0.101359 -vn 3.735954 -2.626179 -2.590230 -v 0.041306 -0.016816 0.101333 -vn 3.723420 2.632794 -2.647690 -v 0.041217 -0.016702 0.101208 -vn 3.312388 -2.690965 -3.169148 -v 0.041190 -0.016797 0.101177 -vn 3.259137 2.620104 -3.174808 -v 0.041157 -0.016693 0.101143 -vn 2.833947 -2.631117 -3.561661 -v 0.041157 -0.016793 0.101143 -vn 2.244519 -2.675333 -3.961182 -v 0.040941 -0.016767 0.100979 -vn 2.563063 2.551970 -3.693237 -v 0.040967 -0.016670 0.100994 -vn 1.714283 -2.561787 -4.245440 -v 0.040924 -0.016765 0.100969 -vn 1.468953 2.572849 -4.230882 -v 0.040718 -0.016644 0.100887 -vn 0.870215 -2.547717 -4.457630 -v 0.040689 -0.016741 0.100879 -vn 0.443954 -2.288610 -4.512930 -v 0.040574 -0.016730 0.100858 -vn 4.469012 2.481155 0.856820 -v 0.041435 -0.016185 0.102024 -vn 4.240732 2.656975 1.623884 -v 0.041413 -0.016195 0.102119 -vn 4.482237 -2.656686 0.750365 -v 0.041421 -0.016291 0.102089 -vn 0.142342 2.675600 4.586937 -v 0.040514 -0.016313 0.102848 -vn 0.755128 -2.645783 4.518200 -v 0.040537 -0.016410 0.102846 -vn 0.831619 2.617955 4.488885 -v 0.040689 -0.016296 0.102821 -vn 1.484735 -2.626191 4.297770 -v 0.040718 -0.016392 0.102813 -vn 1.548615 2.629407 4.304717 -v 0.040860 -0.016278 0.102762 -vn 2.182373 -2.687126 4.019444 -v 0.040898 -0.016373 0.102744 -vn 2.171252 2.658165 3.994246 -v 0.040941 -0.016270 0.102721 -vn 2.752295 -2.566389 3.630716 -v 0.040967 -0.016366 0.102706 -vn 3.229068 -2.630874 3.214799 -v 0.041157 -0.016343 0.102557 -vn 2.946342 2.623596 3.366844 -v 0.041157 -0.016244 0.102557 -vn 3.658519 -2.603565 2.711117 -v 0.041188 -0.016339 0.102525 -vn 3.682698 2.598450 2.527397 -v 0.041306 -0.016221 0.102367 -vn 4.055323 -2.560626 2.026679 -v 0.041321 -0.016317 0.102341 -vn 4.237772 -2.289398 1.609485 -v 0.041373 -0.016305 0.102234 -vn 4.531667 2.581861 0.277625 -v 0.041450 -0.016169 0.101850 -vn 4.507804 -2.582036 -0.230528 -v 0.041450 -0.016268 0.101850 -vn 4.556730 2.506703 -0.461426 -v 0.041432 -0.016151 0.101662 -vn 4.374627 -2.673512 -1.329294 -v 0.041413 -0.016242 0.101581 -vn 4.461473 2.680249 -0.994176 -v 0.041421 -0.016146 0.101611 -vn 4.176383 -2.497348 -1.865728 -v 0.041396 -0.016236 0.101525 -vn 4.054251 2.603312 -1.979859 -v 0.041321 -0.016120 0.101359 -vn 3.762890 -2.597245 -2.558290 -v 0.041306 -0.016216 0.101333 -vn 3.416337 -2.495291 -3.031766 -v 0.041217 -0.016201 0.101208 -vn 3.467469 2.666164 -2.936717 -v 0.041157 -0.016094 0.101143 -vn 2.909461 -2.668027 -3.493601 -v 0.041157 -0.016193 0.101143 -vn 0.603315 -2.592793 -4.539742 -v 0.040689 -0.016141 0.100879 -vn 1.263237 2.678032 -4.390100 -v 0.040718 -0.016045 0.100887 -vn 1.172859 -2.708193 -4.409697 -v 0.040718 -0.016144 0.100887 -vn 1.841521 2.593266 -4.194780 -v 0.040759 -0.016049 0.100899 -vn 1.986918 -2.586851 -4.025631 -v 0.040941 -0.016167 0.100979 -vn 2.563984 2.551897 -3.753644 -v 0.040967 -0.016071 0.100994 -vn 2.912481 2.333050 -3.484223 -v 0.041075 -0.016083 0.101069 -vn 1.854993 2.665652 4.175648 -v 0.040941 -0.015670 0.102721 -vn 1.040325 2.657718 4.447041 -v 0.040689 -0.015696 0.102821 -vn 1.507934 -2.567970 4.305147 -v 0.040718 -0.015791 0.102813 -vn 0.511855 2.596601 4.549230 -v 0.040646 -0.015700 0.102831 -vn 0.671943 -2.611721 4.526170 -v 0.040514 -0.015811 0.102848 -vn 1.955803 -2.389743 4.111028 -v 0.040859 -0.015777 0.102762 -vn 2.663923 -2.665774 3.696561 -v 0.040967 -0.015765 0.102706 -vn 2.445762 2.599520 3.848162 -v 0.040998 -0.015663 0.102686 -vn 3.273744 -2.654608 3.202319 -v 0.041157 -0.015742 0.102557 -vn 2.960413 2.647385 3.443837 -v 0.041157 -0.015644 0.102557 -vn 3.648658 -2.661153 2.756580 -v 0.041188 -0.015738 0.102525 -vn 3.509814 2.554916 2.923765 -v 0.041257 -0.015629 0.102441 -vn 4.094240 -2.574289 1.917526 -v 0.041321 -0.015716 0.102341 -vn 3.836409 2.629852 2.448066 -v 0.041306 -0.015621 0.102367 -vn 4.255713 2.571985 1.520237 -v 0.041413 -0.015595 0.102119 -vn 4.444202 -2.644595 1.008382 -v 0.041421 -0.015690 0.102089 -vn 4.550467 -2.493300 0.436613 -v 0.041435 -0.015684 0.102024 -vn 4.537448 2.629179 0.354953 -v 0.041450 -0.015569 0.101850 -vn 4.529753 -2.637390 -0.254868 -v 0.041450 -0.015667 0.101850 -vn 4.567453 2.624657 -0.309953 -v 0.041441 -0.015556 0.101719 -vn 4.450340 -2.689531 -1.009878 -v 0.041432 -0.015649 0.101662 -vn 4.435363 2.663938 -0.983177 -v 0.041421 -0.015546 0.101611 -vn 4.224473 -2.589111 -1.672980 -v 0.041413 -0.015641 0.101581 -vn 4.060325 2.543318 -1.964721 -v 0.041321 -0.015520 0.101359 -vn 3.716508 -2.550914 -2.542563 -v 0.041306 -0.015615 0.101333 -vn 3.501996 2.612352 -2.917076 -v 0.041157 -0.015494 0.101143 -vn 3.133231 -2.618839 -3.292127 -v 0.041157 -0.015592 0.101143 -vn 3.041976 2.666335 -3.416980 -v 0.041079 -0.015484 0.101073 -vn 2.620040 -2.663151 -3.743752 -v 0.041075 -0.015582 0.101069 -vn 2.511353 2.635612 -3.783595 -v 0.040967 -0.015470 0.100994 -vn 1.936807 -2.604581 -4.110038 -v 0.040941 -0.015566 0.100979 -vn 1.844490 2.657876 -4.181874 -v 0.040764 -0.015449 0.100901 -vn 1.312473 -2.667085 -4.370830 -v 0.040759 -0.015547 0.100899 -vn 1.373271 2.693756 -4.379642 -v 0.040718 -0.015444 0.100887 -vn 0.662772 -2.665670 -4.492085 -v 0.040689 -0.015540 0.100879 -vn 0.776006 2.533059 -4.502302 -v 0.040554 -0.015428 0.100855 -vn 0.269833 2.601108 4.575965 -v 0.040566 -0.015107 0.102843 -vn 1.044420 -2.680182 4.457222 -v 0.040646 -0.015198 0.102831 -vn 0.863638 2.680720 4.501691 -v 0.040687 -0.015096 0.102822 -vn 1.630884 -2.663210 4.251034 -v 0.040718 -0.015191 0.102813 -vn 1.564161 2.470960 4.274411 -v 0.040833 -0.015081 0.102774 -vn 2.526753 -2.566234 3.736985 -v 0.040967 -0.015165 0.102706 -vn 2.312510 2.614997 3.946403 -v 0.041024 -0.015060 0.102669 -vn 2.762338 2.273290 3.599122 -v 0.041056 -0.015056 0.102646 -vn 3.553904 2.651875 2.848501 -v 0.041248 -0.015030 0.102452 -vn 4.109877 -2.453705 1.909555 -v 0.041321 -0.015116 0.102341 -vn 4.071779 2.482798 1.949494 -v 0.041384 -0.015003 0.102207 -vn 4.444143 -2.654653 0.849695 -v 0.041421 -0.015090 0.102089 -vn 4.359878 2.656679 1.358955 -v 0.041420 -0.014992 0.102094 -vn 3.138761 2.575731 3.327245 -v 0.041188 -0.015039 0.102525 -vn 3.250449 -2.482400 3.150609 -v 0.041157 -0.015142 0.102557 -vn 3.823555 -2.645397 2.515797 -v 0.041257 -0.015128 0.102441 -vn 4.511520 2.531643 0.775319 -v 0.041444 -0.014978 0.101956 -vn 4.554635 -2.646955 -0.207227 -v 0.041450 -0.015067 0.101850 -vn 4.556270 2.662146 0.219377 -v 0.041450 -0.014969 0.101858 -vn 4.552299 2.646948 -0.393042 -v 0.041438 -0.014954 0.101695 -vn 4.501173 -2.626650 -0.824428 -v 0.041441 -0.015055 0.101719 -vn 4.496905 2.655480 -0.912066 -v 0.041420 -0.014945 0.101606 -vn 4.281955 -2.651936 -1.542037 -v 0.041413 -0.015041 0.101581 -vn 4.226073 2.550633 -1.583704 -v 0.041374 -0.014931 0.101467 -vn 3.915076 -2.461656 -2.354427 -v 0.041322 -0.015018 0.101361 -vn 3.755846 2.540531 -2.500687 -v 0.041232 -0.014904 0.101226 -vn 3.686097 -2.428322 -2.647650 -v 0.041306 -0.015015 0.101333 -vn 3.110161 -2.678892 -3.320894 -v 0.041157 -0.014992 0.101143 -vn 3.319008 2.675169 -3.103545 -v 0.041157 -0.014893 0.101143 -vn 2.612854 -2.472273 -3.752327 -v 0.041079 -0.014982 0.101073 -vn 2.405160 2.617964 -3.812155 -v 0.040936 -0.014867 0.100976 -vn 2.001511 -2.605647 -4.092884 -v 0.040941 -0.014966 0.100979 -vn 1.341401 -2.581283 -4.374365 -v 0.040764 -0.014948 0.100901 -vn 1.546691 2.673310 -4.261409 -v 0.040718 -0.014844 0.100887 -vn 0.697550 -2.664856 -4.510939 -v 0.040689 -0.014940 0.100879 -vn 0.814614 2.535204 -4.483035 -v 0.040574 -0.014830 0.100858 -vn 3.324032 -2.666650 3.163042 -v 0.041157 -0.014543 0.102557 -vn 2.994573 2.646383 3.375044 -v 0.041157 -0.014443 0.102557 -vn 2.912311 -2.492767 3.526020 -v 0.041024 -0.014559 0.102669 -vn 2.155376 2.685953 4.025141 -v 0.040941 -0.014469 0.102721 -vn 2.451921 -2.674878 3.839590 -v 0.040967 -0.014566 0.102706 -vn 1.650204 2.517997 4.256188 -v 0.040898 -0.014474 0.102744 -vn 1.456055 -2.580935 4.263503 -v 0.040718 -0.014592 0.102813 -vn 0.818546 2.558324 4.459914 -v 0.040689 -0.014495 0.102821 -vn 0.324800 2.421684 4.528395 -v 0.040537 -0.014510 0.102846 -vn 3.649876 -2.595007 2.765494 -v 0.041188 -0.014538 0.102525 -vn 3.860779 -2.589733 2.441636 -v 0.041283 -0.014524 0.102403 -vn 3.693565 2.669607 2.630297 -v 0.041306 -0.014420 0.102367 -vn 4.168376 -2.657592 1.850520 -v 0.041321 -0.014517 0.102341 -vn 4.117639 2.311957 1.861952 -v 0.041373 -0.014406 0.102234 -vn 4.304368 2.545538 1.414099 -v 0.041413 -0.014394 0.102119 -vn 4.429279 -2.549718 0.813205 -v 0.041421 -0.014491 0.102089 -vn 4.504983 2.558766 0.261584 -v 0.041450 -0.014368 0.101850 -vn 4.501390 -2.561704 -0.250268 -v 0.041450 -0.014468 0.101850 -vn 4.519725 2.579013 -0.660823 -v 0.041421 -0.014345 0.101611 -vn 4.363578 -2.660395 -1.307350 -v 0.041413 -0.014442 0.101581 -vn 4.366757 2.685622 -1.333284 -v 0.041396 -0.014337 0.101525 -vn 4.141798 -2.641119 -1.949721 -v 0.041385 -0.014433 0.101495 -vn 4.082156 2.631109 -1.985584 -v 0.041321 -0.014319 0.101359 -vn 3.735954 -2.626179 -2.590230 -v 0.041306 -0.014416 0.101333 -vn 3.723420 2.632794 -2.647690 -v 0.041217 -0.014302 0.101208 -vn 3.312388 -2.690965 -3.169148 -v 0.041190 -0.014397 0.101177 -vn 3.259137 2.620104 -3.174808 -v 0.041157 -0.014293 0.101143 -vn 2.833947 -2.631117 -3.561661 -v 0.041157 -0.014393 0.101143 -vn 2.244519 -2.675333 -3.961182 -v 0.040941 -0.014367 0.100979 -vn 2.563063 2.551970 -3.693237 -v 0.040967 -0.014270 0.100994 -vn 1.714283 -2.561787 -4.245440 -v 0.040924 -0.014365 0.100969 -vn 1.468953 2.572846 -4.230883 -v 0.040718 -0.014244 0.100887 -vn 0.870215 -2.547717 -4.457630 -v 0.040689 -0.014341 0.100879 -vn 0.443954 -2.288610 -4.512930 -v 0.040574 -0.014330 0.100858 -vn 4.469012 2.481155 0.856820 -v 0.041435 -0.013785 0.102024 -vn 4.240732 2.656975 1.623884 -v 0.041413 -0.013795 0.102119 -vn 4.482222 -2.656694 0.750361 -v 0.041421 -0.013891 0.102089 -vn 0.142342 2.675600 4.586937 -v 0.040514 -0.013913 0.102848 -vn 0.755133 -2.645788 4.518190 -v 0.040537 -0.014010 0.102846 -vn 0.831619 2.617955 4.488885 -v 0.040689 -0.013896 0.102821 -vn 1.484728 -2.626195 4.297764 -v 0.040718 -0.013992 0.102813 -vn 1.548615 2.629407 4.304717 -v 0.040860 -0.013878 0.102762 -vn 2.182373 -2.687126 4.019444 -v 0.040898 -0.013973 0.102744 -vn 2.171252 2.658165 3.994246 -v 0.040941 -0.013870 0.102721 -vn 2.752295 -2.566389 3.630716 -v 0.040967 -0.013966 0.102706 -vn 3.229068 -2.630874 3.214799 -v 0.041157 -0.013943 0.102557 -vn 2.946342 2.623596 3.366844 -v 0.041157 -0.013844 0.102557 -vn 3.658519 -2.603565 2.711117 -v 0.041188 -0.013939 0.102525 -vn 3.682698 2.598450 2.527397 -v 0.041306 -0.013821 0.102367 -vn 4.055323 -2.560626 2.026679 -v 0.041321 -0.013917 0.102341 -vn 4.237764 -2.289401 1.609475 -v 0.041373 -0.013905 0.102234 -vn 4.531667 2.581861 0.277625 -v 0.041450 -0.013769 0.101850 -vn 4.507790 -2.582047 -0.230528 -v 0.041450 -0.013868 0.101850 -vn 4.556730 2.506703 -0.461426 -v 0.041432 -0.013751 0.101662 -vn 4.374622 -2.673515 -1.329288 -v 0.041413 -0.013842 0.101581 -vn 4.461473 2.680249 -0.994176 -v 0.041421 -0.013746 0.101611 -vn 4.176383 -2.497348 -1.865728 -v 0.041396 -0.013836 0.101525 -vn 4.054251 2.603312 -1.979859 -v 0.041321 -0.013720 0.101359 -vn 3.762890 -2.597245 -2.558290 -v 0.041306 -0.013816 0.101333 -vn 3.416273 -2.495303 -3.031787 -v 0.041217 -0.013801 0.101208 -vn 3.467469 2.666164 -2.936717 -v 0.041157 -0.013694 0.101143 -vn 2.909475 -2.668001 -3.493660 -v 0.041157 -0.013793 0.101143 -vn 0.603318 -2.592798 -4.539732 -v 0.040689 -0.013741 0.100879 -vn 1.263237 2.678032 -4.390100 -v 0.040718 -0.013645 0.100887 -vn 1.172853 -2.708201 -4.409681 -v 0.040718 -0.013744 0.100887 -vn 1.841521 2.593266 -4.194780 -v 0.040759 -0.013649 0.100899 -vn 1.986918 -2.586860 -4.025611 -v 0.040941 -0.013767 0.100979 -vn 2.563985 2.551896 -3.753644 -v 0.040967 -0.013671 0.100994 -vn 2.912477 2.333036 -3.484224 -v 0.041075 -0.013683 0.101069 -vn 1.908563 2.660104 4.107010 -v 0.040941 -0.013270 0.102721 -vn 1.195778 2.664577 4.401534 -v 0.040712 -0.013293 0.102815 -vn 1.476636 -2.593856 4.314662 -v 0.040718 -0.013391 0.102813 -vn 0.633570 2.636600 4.539826 -v 0.040689 -0.013296 0.102821 -vn 0.694115 -2.567444 4.521451 -v 0.040514 -0.013411 0.102848 -vn 1.955831 -2.389752 4.110987 -v 0.040859 -0.013377 0.102762 -vn 2.655081 -2.654145 3.703131 -v 0.040967 -0.013365 0.102706 -vn 2.593680 2.532352 3.747616 -v 0.041065 -0.013255 0.102639 -vn 3.302796 -2.689472 3.177957 -v 0.041157 -0.013342 0.102557 -vn 3.090057 2.666806 3.335668 -v 0.041157 -0.013244 0.102557 -vn 3.670903 -2.593907 2.725482 -v 0.041188 -0.013338 0.102525 -vn 3.652358 2.622766 2.761438 -v 0.041306 -0.013221 0.102367 -vn 4.073874 -2.612176 1.955308 -v 0.041321 -0.013316 0.102341 -vn 3.983703 2.637702 2.256024 -v 0.041322 -0.013217 0.102339 -vn 4.271638 2.563248 1.577005 -v 0.041413 -0.013195 0.102119 -vn 4.447128 -2.623433 0.992430 -v 0.041421 -0.013290 0.102089 -vn 4.501546 2.553510 0.732966 -v 0.041444 -0.013179 0.101963 -vn 4.547928 -2.597025 0.488837 -v 0.041435 -0.013284 0.102024 -vn 4.539328 2.589725 0.141283 -v 0.041450 -0.013169 0.101850 -vn 4.525027 -2.590337 -0.304043 -v 0.041450 -0.013267 0.101850 -vn 4.528548 2.676704 -0.649621 -v 0.041421 -0.013146 0.101611 -vn 4.456708 -2.525299 -0.900329 -v 0.041432 -0.013249 0.101662 -vn 4.230517 -2.648752 -1.660406 -v 0.041413 -0.013241 0.101581 -vn 4.394980 2.607689 -1.269254 -v 0.041410 -0.013141 0.101569 -vn 3.752604 -2.615443 -2.493047 -v 0.041306 -0.013215 0.101333 -vn 0.757522 2.538869 -4.504742 -v 0.040545 -0.013028 0.100854 -vn 0.659641 -2.660388 -4.492553 -v 0.040689 -0.013140 0.100879 -vn 1.504106 2.667822 -4.276056 -v 0.040718 -0.013044 0.100887 -vn 1.320102 -2.610765 -4.366434 -v 0.040759 -0.013147 0.100899 -vn 2.214378 2.651221 -3.989954 -v 0.040922 -0.013066 0.100968 -vn 1.959299 -2.664341 -4.100472 -v 0.040941 -0.013166 0.100979 -vn 2.720938 2.663040 -3.672114 -v 0.040967 -0.013070 0.100994 -vn 2.621067 -2.532482 -3.735153 -v 0.041075 -0.013182 0.101069 -vn 3.332989 2.677387 -3.100078 -v 0.041157 -0.013094 0.101143 -vn 3.090338 -2.674678 -3.343585 -v 0.041157 -0.013192 0.101143 -vn 3.730706 2.534105 -2.633037 -v 0.041227 -0.013104 0.101220 -vn 4.133140 2.548225 -1.907146 -v 0.041321 -0.013120 0.101359 -vn 0.330787 2.607528 4.532010 -v 0.040566 -0.012707 0.102843 -vn 1.077636 -2.572418 4.436522 -v 0.040646 -0.012798 0.102831 -vn 1.258643 2.496408 4.372091 -v 0.040784 -0.012686 0.102792 -vn 3.341992 -2.668578 3.067750 -v 0.041157 -0.012742 0.102557 -vn 2.844744 2.584421 3.599997 -v 0.041123 -0.012648 0.102590 -vn 2.520257 -2.497889 3.744421 -v 0.040967 -0.012765 0.102706 -vn 2.514894 2.416188 3.774945 -v 0.041056 -0.012656 0.102646 -vn 1.564771 -2.560719 4.281530 -v 0.040718 -0.012791 0.102813 -vn 1.584887 2.296417 4.251190 -v 0.040833 -0.012681 0.102774 -vn 4.446307 -2.653824 0.837876 -v 0.041421 -0.012690 0.102089 -vn 4.187040 2.472833 1.858564 -v 0.041384 -0.012603 0.102207 -vn 4.079756 -2.480863 1.987953 -v 0.041321 -0.012716 0.102341 -vn 3.994589 2.543565 2.207255 -v 0.041357 -0.012610 0.102271 -vn 3.832030 -2.614008 2.486164 -v 0.041257 -0.012728 0.102441 -vn 3.558587 2.620577 2.877736 -v 0.041248 -0.012630 0.102452 -vn 3.237546 2.628839 3.248619 -v 0.041188 -0.012639 0.102525 -vn 4.538668 -2.628314 -0.219236 -v 0.041450 -0.012667 0.101850 -vn 4.502621 2.534766 0.807482 -v 0.041444 -0.012578 0.101956 -vn 4.372395 2.654745 1.341191 -v 0.041420 -0.012592 0.102094 -vn 3.702393 -2.423061 -2.645945 -v 0.041306 -0.012615 0.101333 -vn 3.097123 -2.686403 -3.336956 -v 0.041157 -0.012592 0.101143 -vn 3.778491 2.536623 -2.487100 -v 0.041232 -0.012504 0.101226 -vn 3.917497 -2.458509 -2.361126 -v 0.041322 -0.012618 0.101361 -vn 4.222582 2.552825 -1.666853 -v 0.041374 -0.012531 0.101467 -vn 4.294161 -2.661874 -1.533336 -v 0.041413 -0.012641 0.101581 -vn 4.394464 2.578672 -1.350763 -v 0.041386 -0.012534 0.101498 -vn 4.516028 2.660137 -0.879984 -v 0.041420 -0.012545 0.101606 -vn 4.493110 -2.631912 -0.816946 -v 0.041441 -0.012655 0.101719 -vn 4.544372 2.648462 -0.370598 -v 0.041438 -0.012554 0.101695 -vn 4.553950 2.658478 0.324733 -v 0.041449 -0.012572 0.101888 -vn 0.361972 -2.446900 -4.537865 -v 0.040554 -0.012527 0.100855 -vn 0.511287 2.595681 -4.537168 -v 0.040469 -0.012420 0.100850 -vn 0.707450 -2.598251 -4.524618 -v 0.040689 -0.012540 0.100879 -vn 1.369734 2.665764 -4.320178 -v 0.040718 -0.012444 0.100887 -vn 1.293102 -2.659311 -4.401605 -v 0.040764 -0.012548 0.100901 -vn 2.040574 2.607165 -4.098927 -v 0.040854 -0.012458 0.100935 -vn 2.028697 -2.633644 -4.082508 -v 0.040941 -0.012566 0.100979 -vn 2.552388 2.646861 -3.779352 -v 0.040936 -0.012467 0.100976 -vn 2.612234 -2.477701 -3.741032 -v 0.041079 -0.012582 0.101073 -vn 3.273021 2.705925 -3.191154 -v 0.041157 -0.012493 0.101143 -vn 3.570599 2.684729 -2.913381 -v 0.041177 -0.012496 0.101163 -vn 0.099228 2.611810 4.569487 -v 0.040469 -0.012116 0.102850 -vn 1.414539 -2.612679 4.269903 -v 0.040718 -0.012192 0.102813 -vn 0.731193 2.560096 4.477637 -v 0.040689 -0.012095 0.102821 -vn 1.565836 2.476299 4.280258 -v 0.040854 -0.012078 0.102765 -vn 2.463313 -2.670903 3.839616 -v 0.040967 -0.012166 0.102706 -vn 2.092616 2.655678 4.039119 -v 0.040941 -0.012069 0.102721 -vn 2.912325 -2.492860 3.525975 -v 0.041024 -0.012159 0.102669 -vn 2.884629 2.672856 3.552727 -v 0.041157 -0.012043 0.102557 -vn 3.324204 -2.666378 3.172142 -v 0.041157 -0.012143 0.102557 -vn 3.283381 2.689667 3.177782 -v 0.041177 -0.012040 0.102537 -vn 3.652631 -2.643929 2.772401 -v 0.041188 -0.012138 0.102525 -vn 3.715727 2.662906 2.592386 -v 0.041306 -0.012020 0.102367 -vn 4.444474 -2.577271 0.770476 -v 0.041421 -0.012091 0.102089 -vn 4.141185 2.480228 1.904542 -v 0.041386 -0.012002 0.102202 -vn 4.169142 -2.643222 1.856080 -v 0.041321 -0.012117 0.102341 -vn 3.862384 -2.592396 2.439684 -v 0.041283 -0.012124 0.102403 -vn 4.500000 -2.597897 -0.229988 -v 0.041450 -0.012068 0.101850 -vn 4.547121 2.640681 0.490601 -v 0.041450 -0.011968 0.101850 -vn 4.351024 2.631043 1.326551 -v 0.041413 -0.011994 0.102119 -vn 1.993637 -2.601388 -4.018794 -v 0.040941 -0.011967 0.100979 -vn 1.708029 2.117954 -4.165863 -v 0.040784 -0.011851 0.100908 -vn 2.608067 2.558757 -3.717777 -v 0.040967 -0.011870 0.100994 -vn 2.859411 -2.686642 -3.533262 -v 0.041157 -0.011993 0.101143 -vn 3.091425 2.538974 -3.364217 -v 0.041123 -0.011889 0.101110 -vn 3.439324 2.722291 -3.064664 -v 0.041157 -0.011893 0.101143 -vn 3.326466 -2.661849 -3.129802 -v 0.041190 -0.011997 0.101177 -vn 3.647717 2.664722 -2.751848 -v 0.041188 -0.011898 0.101175 -vn 3.712421 -2.599880 -2.608907 -v 0.041306 -0.012016 0.101333 -vn 4.050816 2.617552 -2.098120 -v 0.041321 -0.011919 0.101359 -vn 4.164092 -2.545706 -1.860794 -v 0.041385 -0.012033 0.101495 -vn 4.247812 2.561941 -1.647652 -v 0.041357 -0.011927 0.101429 -vn 4.340796 -2.600052 -1.351928 -v 0.041413 -0.012042 0.101581 -vn 4.461511 2.567972 -0.760942 -v 0.041421 -0.011945 0.101611 -vn 4.557417 2.573255 -0.165617 -v 0.041449 -0.011965 0.101812 -vn 1.365600 2.547747 -4.326977 -v 0.040718 -0.011844 0.100887 -vn 0.887344 -2.545096 -4.445811 -v 0.040689 -0.011941 0.100879 -vn 0.444307 -2.290196 -4.509930 -v 0.040574 -0.011930 0.100858 -vn 0.254063 2.654991 4.566298 -v 0.040545 -0.011510 0.102845 -vn 0.735071 -2.655118 4.519865 -v 0.040537 -0.011610 0.102846 -vn 0.899864 2.612404 4.445846 -v 0.040689 -0.011496 0.102821 -vn 1.520995 -2.579950 4.279964 -v 0.040718 -0.011592 0.102813 -vn 1.737282 2.669094 4.236426 -v 0.040922 -0.011472 0.102732 -vn 2.113579 -2.598852 4.046646 -v 0.040898 -0.011573 0.102744 -vn 2.238682 2.664452 3.986617 -v 0.040941 -0.011470 0.102721 -vn 2.755926 -2.571066 3.613989 -v 0.040967 -0.011566 0.102706 -vn 3.213531 -2.637643 3.213761 -v 0.041157 -0.011543 0.102557 -vn 2.894797 2.615122 3.523004 -v 0.041157 -0.011444 0.102557 -vn 3.648935 -2.674740 2.767691 -v 0.041188 -0.011539 0.102525 -vn 3.462573 2.540870 2.991403 -v 0.041227 -0.011434 0.102480 -vn 3.791201 2.573318 2.515898 -v 0.041306 -0.011421 0.102367 -vn 4.073497 -2.562091 2.019424 -v 0.041321 -0.011517 0.102341 -vn 4.240618 2.656954 1.735502 -v 0.041410 -0.011396 0.102130 -vn 4.239186 -2.358539 1.602289 -v 0.041373 -0.011505 0.102234 -vn 4.479388 -2.579651 0.696582 -v 0.041421 -0.011491 0.102089 -vn 4.467982 2.568713 -0.848763 -v 0.041421 -0.011346 0.101611 -vn 4.527052 2.321108 -0.407947 -v 0.041444 -0.011358 0.101736 -vn 4.498862 -2.606116 -0.218239 -v 0.041450 -0.011468 0.101850 -vn 4.526000 2.613552 0.411013 -v 0.041450 -0.011369 0.101850 -vn 4.401069 2.681841 1.234290 -v 0.041413 -0.011395 0.102119 -vn 4.372082 -2.648607 -1.295692 -v 0.041413 -0.011442 0.101581 -vn 4.163897 -2.504203 -1.861454 -v 0.041396 -0.011436 0.101525 -vn 4.026015 2.593708 -2.002184 -v 0.041321 -0.011320 0.101359 -vn 3.691083 -2.561025 -2.611428 -v 0.041306 -0.011416 0.101333 -vn 3.479226 2.615288 -2.899469 -v 0.041157 -0.011294 0.101143 -vn 3.123950 -2.610589 -3.297291 -v 0.041157 -0.011393 0.101143 -vn 3.014280 2.664465 -3.444690 -v 0.041065 -0.011282 0.101061 -vn 2.570441 -2.661133 -3.789260 -v 0.041056 -0.011380 0.101055 -vn 2.456725 2.636890 -3.818991 -v 0.040967 -0.011271 0.100994 -vn 1.871987 -2.574543 -4.139971 -v 0.040941 -0.011367 0.100979 -vn 1.446567 2.603840 -4.257701 -v 0.040718 -0.011245 0.100887 -vn 0.604912 -2.592042 -4.541204 -v 0.040689 -0.011341 0.100879 -vn 1.213439 -2.649211 -4.403344 -v 0.040718 -0.011344 0.100887 -vn 0.691917 -2.571232 4.516407 -v 0.040514 -0.011011 0.102848 -vn 0.731119 2.620355 4.481066 -v 0.040689 -0.010895 0.102821 -vn 1.424470 -2.647351 4.318554 -v 0.040718 -0.010991 0.102813 -vn 1.448542 2.653028 4.344174 -v 0.040824 -0.010881 0.102777 -vn 2.078558 -2.671668 4.064498 -v 0.040859 -0.010977 0.102762 -vn 2.144232 2.631575 4.010225 -v 0.040941 -0.010869 0.102721 -vn 2.711059 -2.563037 3.633931 -v 0.040967 -0.010965 0.102706 -vn 3.218186 -2.634445 3.217891 -v 0.041157 -0.010942 0.102557 -vn 2.956893 2.600998 3.413840 -v 0.041157 -0.010843 0.102557 -vn 3.668463 -2.591940 2.740234 -v 0.041188 -0.010938 0.102525 -vn 3.680015 2.608730 2.692622 -v 0.041306 -0.010820 0.102367 -vn 4.074672 -2.636414 1.977245 -v 0.041321 -0.010916 0.102341 -vn 4.092887 2.439155 2.002130 -v 0.041356 -0.010810 0.102272 -vn 4.291414 2.573762 1.506896 -v 0.041413 -0.010794 0.102119 -vn 4.455065 -2.638307 1.020229 -v 0.041421 -0.010890 0.102089 -vn 4.563507 -2.577662 0.465179 -v 0.041435 -0.010884 0.102024 -vn 4.513767 2.639001 0.670536 -v 0.041448 -0.010774 0.101913 -vn 4.541564 -2.622643 -0.331750 -v 0.041450 -0.010867 0.101850 -vn 4.555382 2.637543 0.054427 -v 0.041450 -0.010768 0.101850 -vn 4.420582 2.637619 -0.857896 -v 0.041421 -0.010745 0.101611 -vn 4.469487 -2.518310 -0.910347 -v 0.041432 -0.010849 0.101662 -vn 4.227960 -2.587965 -1.673056 -v 0.041413 -0.010841 0.101581 -vn 4.021953 2.562991 -1.956151 -v 0.041321 -0.010719 0.101359 -vn 3.720501 -2.548842 -2.544819 -v 0.041306 -0.010815 0.101333 -vn 3.402644 2.629813 -2.929956 -v 0.041157 -0.010693 0.101143 -vn 3.131317 -2.616670 -3.293845 -v 0.041157 -0.010792 0.101143 -vn 2.621237 -2.533349 -3.735785 -v 0.041075 -0.010782 0.101069 -vn 2.719794 2.666163 -3.664025 -v 0.040967 -0.010670 0.100994 -vn 1.959847 -2.665000 -4.100098 -v 0.040941 -0.010766 0.100979 -vn 2.222830 2.644789 -3.995766 -v 0.040921 -0.010665 0.100968 -vn 1.321059 -2.611410 -4.368226 -v 0.040759 -0.010747 0.100899 -vn 1.519901 2.667826 -4.287870 -v 0.040718 -0.010644 0.100887 -vn 0.700868 -2.657579 -4.522108 -v 0.040689 -0.010740 0.100879 -vn 0.806969 2.528303 -4.498782 -v 0.040567 -0.010629 0.100857 -vn 3.304661 2.696418 3.175387 -v 0.041191 -0.010238 0.102522 -vn 2.850102 2.627513 3.559305 -v 0.041157 -0.010243 0.102557 -vn 3.237907 -2.623465 3.223708 -v 0.041157 -0.010342 0.102557 -vn 2.199332 2.648631 3.985722 -v 0.040941 -0.010269 0.102721 -vn 2.605121 -2.553943 3.687652 -v 0.040967 -0.010365 0.102706 -vn 1.647500 2.511079 4.261125 -v 0.040895 -0.010274 0.102746 -vn 1.424318 -2.599042 4.244404 -v 0.040718 -0.010392 0.102813 -vn 0.825385 2.551392 4.475870 -v 0.040689 -0.010295 0.102821 -vn 0.317524 2.418256 4.547897 -v 0.040536 -0.010310 0.102846 -vn 3.609549 -2.698225 2.848780 -v 0.041188 -0.010338 0.102525 -vn 3.829406 -2.610907 2.496229 -v 0.041256 -0.010328 0.102442 -vn 3.750620 2.659977 2.579744 -v 0.041306 -0.010220 0.102367 -vn 4.132423 -2.641500 1.897493 -v 0.041321 -0.010316 0.102341 -vn 4.140624 2.469779 1.927524 -v 0.041383 -0.010203 0.102211 -vn 4.457913 -2.568919 0.783297 -v 0.041421 -0.010290 0.102089 -vn 4.354550 2.622149 1.328952 -v 0.041413 -0.010194 0.102119 -vn 4.492037 2.625329 0.315355 -v 0.041450 -0.010168 0.101850 -vn 0.188389 -2.669533 -4.571756 -v 0.040525 -0.010124 0.100853 -vn 0.728790 2.660978 -4.510765 -v 0.040533 -0.010026 0.100853 -vn 0.820779 -2.622709 -4.480862 -v 0.040689 -0.010140 0.100879 -vn 1.442642 2.629509 -4.325768 -v 0.040718 -0.010044 0.100887 -vn 1.560523 -2.650016 -4.304616 -v 0.040854 -0.010157 0.100935 -vn 2.004517 2.648758 -4.102482 -v 0.040842 -0.010056 0.100930 -vn 2.145576 -2.630299 -4.020166 -v 0.040941 -0.010166 0.100979 -vn 2.677927 2.578591 -3.659166 -v 0.040967 -0.010070 0.100994 -vn 3.005656 -2.560422 -3.361907 -v 0.041157 -0.010192 0.101143 -vn 3.354337 2.564117 -3.003950 -v 0.041157 -0.010093 0.101143 -vn 3.644910 -2.587153 -2.743554 -v 0.041306 -0.010215 0.101333 -vn 4.004679 2.668594 -2.154964 -v 0.041321 -0.010119 0.101359 -vn 4.015752 -2.685741 -2.206546 -v 0.041341 -0.010222 0.101397 -vn 4.301123 2.622388 -1.547313 -v 0.041362 -0.010128 0.101440 -vn 4.305115 -2.624378 -1.492401 -v 0.041413 -0.010241 0.101582 -vn 4.462057 2.633819 -0.772509 -v 0.041421 -0.010145 0.101611 -vn 4.510983 -2.533019 -0.769507 -v 0.041445 -0.010258 0.101753 -vn 4.568359 -2.621370 -0.086194 -v 0.041450 -0.010267 0.101850 -vn -0.101545 1.668696 5.707045 -v 0.040450 -0.041610 0.103725 -vn -1.145329 0.230779 6.124712 -v 0.040131 -0.041610 0.103698 -vn -1.966015 1.318025 5.577553 -v 0.039732 -0.041610 0.103582 -vn -3.042166 0.236305 5.447352 -v 0.039624 -0.041610 0.103533 -vn -3.946147 0.252490 4.837386 -v 0.039183 -0.041610 0.103232 -vn -4.520945 1.210807 3.903165 -v 0.039124 -0.041610 0.103176 -vn -5.245255 0.263763 3.354744 -v 0.038845 -0.041610 0.102819 -vn -5.234166 1.704424 2.206349 -v 0.038718 -0.041610 0.102568 -vn -6.070864 0.236573 1.405575 -v 0.038637 -0.041610 0.102328 -vn -6.117791 0.793695 0.449345 -v 0.038575 -0.041610 0.101850 -vn -6.112485 -0.829708 -0.325935 -v 0.038575 -0.042410 0.101850 -vn -5.923253 -0.818644 -1.410974 -v 0.038631 -0.042410 0.101394 -vn -5.583282 -1.154746 -2.182402 -v 0.038718 -0.042410 0.101132 -vn -5.187795 -0.768516 -3.235284 -v 0.038834 -0.042410 0.100900 -vn -4.566042 -0.823119 -4.083267 -v 0.039124 -0.042410 0.100524 -vn -3.920013 -0.779001 -4.716769 -v 0.039167 -0.042410 0.100483 -vn -3.031529 -0.762691 -5.319023 -v 0.039604 -0.042410 0.100177 -vn -0.208657 -1.046837 -6.038561 -v 0.040450 -0.042410 0.099975 -vn -1.102699 -0.797293 -5.994443 -v 0.040110 -0.042410 0.100006 -vn -2.123290 -0.868452 -5.723106 -v 0.039732 -0.042410 0.100118 -vn 0.214232 2.575932 4.560724 -v 0.040533 -0.009710 0.102847 -vn 1.124866 -2.431466 4.428113 -v 0.040661 -0.009796 0.102827 -vn 1.834594 1.962588 4.871478 -v 0.040797 -0.009710 0.102788 -vn 1.543007 -2.489758 4.285933 -v 0.040718 -0.009791 0.102813 -vn 2.493333 -2.409309 3.746914 -v 0.040967 -0.009765 0.102706 -vn 3.160378 1.716719 4.097030 -v 0.041019 -0.009710 0.102672 -vn 3.889843 2.175296 3.465270 -v 0.041212 -0.009710 0.102497 -vn 3.025865 -1.707425 3.119297 -v 0.041177 -0.009739 0.102536 -vn 3.814247 -2.175244 2.440614 -v 0.041247 -0.009729 0.102454 -vn 4.446896 1.456948 2.688333 -v 0.041316 -0.009710 0.102350 -vn 4.049428 -1.915722 1.876312 -v 0.041335 -0.009714 0.102316 -vn 3.379579 -0.507371 1.285703 -v 0.041354 -0.009710 0.102278 -vn 0.753639 6.171173 0.349707 -v 0.042011 -0.041410 0.102456 -vn 0.741081 6.188040 0.192183 -v 0.042043 -0.041410 0.102367 -vn -0.753311 6.186730 0.160932 -v 0.038830 -0.041410 0.102277 -vn -0.796578 6.179502 0.066900 -v 0.038775 -0.041410 0.101850 -vn -0.906721 6.119445 0.422638 -v 0.038883 -0.041410 0.102443 -vn -0.677293 6.184788 0.381480 -v 0.039016 -0.041410 0.102716 -vn 0.645316 6.187330 0.416774 -v 0.041834 -0.041410 0.102795 -vn 0.660026 6.153255 0.602783 -v 0.041697 -0.041410 0.102968 -vn 0.470520 6.185470 0.615521 -v 0.041511 -0.041410 0.103146 -vn 0.489101 6.145101 0.779670 -v 0.041220 -0.041410 0.103338 -vn -0.687581 6.154077 0.566789 -v 0.039174 -0.041410 0.102935 -vn -0.505677 6.190108 0.564444 -v 0.039318 -0.041410 0.103085 -vn -0.498427 6.154277 0.737790 -v 0.039543 -0.041410 0.103259 -vn -0.314768 6.188357 0.696485 -v 0.039712 -0.041410 0.103354 -vn 0.177978 6.179683 0.778575 -v 0.040685 -0.041410 0.103509 -vn 0.259308 6.187852 0.721012 -v 0.041103 -0.041410 0.103393 -vn -0.234910 6.172724 0.790936 -v 0.040081 -0.041410 0.103484 -vn -0.083035 6.188228 0.760415 -v 0.040165 -0.041410 0.103501 -vn 0.035267 6.188860 0.761844 -v 0.040642 -0.041410 0.103514 -vn -4.788081 0.439508 -2.300695 -v 0.039573 -0.021063 0.101399 -vn -3.494033 -0.026479 0.636525 -v 0.039502 -0.021011 0.101924 -vn -2.075002 0.153389 3.036032 -v 0.039915 -0.020929 0.102565 -vn -2.448152 0.025036 2.133682 -v 0.039722 -0.020957 0.102397 -vn -3.079652 0.009067 0.020077 -v 0.039915 -0.020418 0.101850 -vn -3.115527 0.068899 -0.680669 -v 0.039923 -0.020449 0.101671 -vn -2.675493 0.040795 -1.721728 -v 0.040001 -0.020484 0.101481 -vn -1.924756 0.026587 -2.517457 -v 0.040140 -0.020516 0.101333 -vn -1.139813 0.035752 -2.850069 -v 0.040319 -0.020548 0.101239 -vn -0.645508 0.027441 -2.986372 -v 0.040357 -0.020554 0.101227 -vn -0.083833 0.028186 -3.073745 -v 0.040522 -0.020579 0.101206 -vn 0.447233 0.023839 -3.034763 -v 0.040584 -0.020588 0.101210 -vn 1.164310 0.033321 -2.949363 -v 0.040734 -0.020610 0.101245 -vn 1.845842 0.055635 -2.587182 -v 0.040928 -0.020641 0.101351 -vn 2.322865 0.027215 -2.075645 -v 0.041020 -0.020658 0.101438 -vn 2.557919 0.020653 -1.694007 -v 0.041080 -0.020671 0.101516 -vn 2.797453 0.011173 -1.366451 -v 0.041113 -0.020680 0.101573 -vn 2.970892 0.027784 -0.846560 -v 0.041172 -0.020702 0.101727 -vn 3.064604 0.026525 -0.373621 -v 0.041191 -0.020714 0.101819 -vn 3.117750 0.021554 0.165429 -v 0.041196 -0.020732 0.101963 -vn 3.046844 0.032392 0.758786 -v 0.041178 -0.020748 0.102089 -vn 2.966416 0.054334 1.212198 -v 0.041147 -0.020761 0.102190 -vn 2.448188 0.028149 2.000381 -v 0.041025 -0.020791 0.102398 -vn 1.950277 0.056700 2.434451 -v 0.040852 -0.020819 0.102560 -vn 1.554210 0.008406 2.670506 -v 0.040844 -0.020820 0.102565 -vn 1.086501 0.021598 2.922147 -v 0.040643 -0.020846 0.102662 -vn 0.618653 0.011009 3.052692 -v 0.040585 -0.020853 0.102678 -vn 0.024639 0.026295 3.165140 -v 0.040397 -0.020874 0.102701 -vn -0.311770 0.051184 3.189162 -v 0.040281 -0.020887 0.102695 -vn -0.886588 -0.007331 3.004983 -v 0.040143 -0.020902 0.102668 -vn -1.369931 0.029280 2.840161 -v 0.040011 -0.020918 0.102619 -vn -2.911831 0.066691 1.135500 -v 0.039563 -0.020988 0.102141 -vn -2.843866 0.077312 1.404897 -v 0.039578 -0.020984 0.102174 -vn -3.470399 -0.086413 -0.222587 -v 0.039501 -0.021037 0.101662 -vn -2.907801 0.070717 -0.882082 -v 0.039530 -0.021051 0.101522 -vn -3.891999 1.474013 4.456006 -v 0.039184 -0.041581 0.103231 -vn -2.739863 1.467170 5.245575 -v 0.039625 -0.041581 0.103531 -vn 1.096459 5.322639 2.632457 -v 0.041138 -0.041431 0.103475 -vn -2.760850 5.322849 0.710727 -v 0.038743 -0.041431 0.102300 -vn -2.445669 5.323544 1.459214 -v 0.038939 -0.041431 0.102762 -vn -1.931416 5.320469 2.112693 -v 0.039257 -0.041431 0.103151 -vn -1.247614 5.321799 2.569727 -v 0.039672 -0.041431 0.103434 -vn -0.467760 5.322249 2.814884 -v 0.040150 -0.041431 0.103589 -vn 0.317590 5.323435 2.829909 -v 0.040652 -0.041431 0.103603 -vn 1.791396 5.323665 2.213310 -v 0.041568 -0.041431 0.103216 -vn 2.365271 5.321702 1.602522 -v 0.041907 -0.041431 0.102845 -vn 2.719680 5.322292 0.863066 -v 0.042129 -0.041431 0.102394 -vn 6.019488 0.250574 1.632247 -v 0.042234 -0.041610 0.102428 -vn 5.671961 1.460116 1.689737 -v 0.042232 -0.041581 0.102428 -vn 5.290864 1.477345 2.455439 -v 0.042182 -0.041610 0.102568 -vn 4.897383 1.447955 3.326626 -v 0.041997 -0.041581 0.102906 -vn 3.646081 1.451194 4.661897 -v 0.041636 -0.041581 0.103299 -vn 4.186880 1.599112 3.941135 -v 0.041776 -0.041610 0.103176 -vn 5.156845 0.236122 3.497644 -v 0.041998 -0.041610 0.102907 -vn -1.042804 1.447913 5.827671 -v 0.040132 -0.041581 0.103696 -vn 0.799858 1.443961 5.864061 -v 0.040665 -0.041581 0.103711 -vn 0.959706 0.249771 6.155849 -v 0.040665 -0.041610 0.103713 -vn 2.304065 1.357988 5.443191 -v 0.041180 -0.041581 0.103575 -vn 2.413851 0.271133 5.705083 -v 0.041181 -0.041610 0.103577 -vn 3.730088 0.240528 4.993899 -v 0.041638 -0.041610 0.103301 -vn -5.013703 1.425972 3.143332 -v 0.038847 -0.041581 0.102818 -vn -5.746018 1.447627 1.422329 -v 0.038639 -0.041581 0.102327 -vn -4.716289 3.420852 1.242648 -v 0.038673 -0.041494 0.102318 -vn -4.175206 3.420785 2.521061 -v 0.038877 -0.041494 0.102800 -vn -3.295846 3.420786 3.595253 -v 0.039208 -0.041494 0.103205 -vn -2.149384 3.420870 4.378062 -v 0.039640 -0.041494 0.103500 -vn -0.828887 3.420780 4.806328 -v 0.040138 -0.041494 0.103661 -vn 0.558817 3.420641 4.845184 -v 0.040661 -0.041494 0.103675 -vn 1.901174 3.420875 4.491428 -v 0.041166 -0.041494 0.103542 -vn 3.089584 3.420859 3.773898 -v 0.041614 -0.041494 0.103272 -vn 4.027627 3.420781 2.750590 -v 0.041967 -0.041494 0.102886 -vn 4.639424 3.420855 1.504452 -v 0.042198 -0.041494 0.102417 -vn 0.887002 -0.773830 -6.050651 -v 0.040643 -0.042410 0.099985 -vn 2.296847 -0.787009 -5.612319 -v 0.041161 -0.042410 0.100115 -vn 3.615534 -0.765354 -4.929585 -v 0.041621 -0.042410 0.100385 -vn 4.387049 -0.909531 -4.228875 -v 0.041776 -0.042410 0.100524 -vn 5.050248 -0.791250 -3.424971 -v 0.041986 -0.042410 0.100774 -vn 5.503492 -0.940513 -2.593641 -v 0.042182 -0.042410 0.101132 -vn 5.896051 -0.776700 -1.656771 -v 0.042227 -0.042410 0.101251 -vn 4.986547 -2.804580 -1.638808 -v 0.042181 -0.042600 0.101266 -vn 0.146896 -6.040181 -1.362563 -v 0.040607 -0.042807 0.100335 -vn -0.250721 -6.040010 -1.350650 -v 0.040173 -0.042807 0.100352 -vn -0.628453 -4.912698 -3.404509 -v 0.040142 -0.042742 0.100179 -vn 0.187075 -6.272533 -0.178285 -v 0.041461 -0.042810 0.100776 -vn 0.117294 -6.276627 -0.164894 -v 0.041371 -0.042810 0.100698 -vn 0.850597 -6.040170 -1.074870 -v 0.041401 -0.042807 0.100660 -vn -0.222426 -6.275253 -0.015660 -v 0.038975 -0.042810 0.101850 -vn -0.244970 -6.273482 -0.028582 -v 0.039000 -0.042810 0.101581 -vn -1.178072 -6.040565 -0.686095 -v 0.039137 -0.042807 0.101078 -vn -0.178301 -6.275846 -0.117396 -v 0.039190 -0.042810 0.101082 -vn -0.192073 -6.276689 -0.060828 -v 0.039019 -0.042810 0.101491 -vn -0.933946 -6.040969 -0.983309 -v 0.039407 -0.042807 0.100739 -vn -0.138687 -6.275078 -0.176863 -v 0.039478 -0.042810 0.100740 -vn -0.622752 -6.040120 -1.221930 -v 0.039763 -0.042807 0.100490 -vn -0.097673 -6.276609 -0.177532 -v 0.039784 -0.042810 0.100534 -vn 0.030353 -6.276570 -0.200897 -v 0.040602 -0.042810 0.100383 -vn -0.007500 -6.271969 -0.265083 -v 0.040441 -0.042810 0.100375 -vn -0.012223 -6.270945 -0.276758 -v 0.040360 -0.042810 0.100378 -vn -0.038625 -6.276795 -0.196191 -v 0.040182 -0.042810 0.100399 -vn -0.088967 -6.270997 -0.261709 -v 0.039945 -0.042810 0.100464 -vn 0.241827 -6.271522 -0.120980 -v 0.041792 -0.042810 0.101238 -vn 0.166311 -6.276526 -0.117883 -v 0.041658 -0.042810 0.101004 -vn 1.123033 -6.040133 -0.787394 -v 0.041698 -0.042807 0.100976 -vn 1.300438 -6.040181 -0.432297 -v 0.041894 -0.042807 0.101363 -vn 0.195019 -6.276601 -0.055345 -v 0.041848 -0.042810 0.101379 -vn -2.427381 -2.816529 -4.654092 -v 0.039626 -0.042600 0.100219 -vn -1.562175 -4.912713 -3.089549 -v 0.039683 -0.042742 0.100334 -vn 1.311926 -4.912671 -3.203834 -v 0.041094 -0.042742 0.100278 -vn 2.161417 -4.912666 -2.704446 -v 0.041511 -0.042742 0.100523 -vn 3.221529 -2.814964 -4.145696 -v 0.041591 -0.042600 0.100423 -vn 1.992933 -2.746297 -4.866882 -v 0.041142 -0.042600 0.100159 -vn 0.588489 -2.807289 -5.216039 -v 0.040638 -0.042600 0.100033 -vn -1.328512 -6.040132 -0.340130 -v 0.038972 -0.042807 0.101479 -vn -3.357932 -4.912678 -0.842620 -v 0.038802 -0.042742 0.101437 -vn -5.093763 -2.764905 -1.302385 -v 0.038678 -0.042600 0.101405 -vn -4.510575 -2.816111 -2.685467 -v 0.038875 -0.042600 0.100924 -vn -2.984523 -4.912684 -1.754532 -v 0.038986 -0.042742 0.100989 -vn -2.369310 -4.912687 -2.524295 -v 0.039287 -0.042742 0.100611 -vn -3.566506 -2.794343 -3.854845 -v 0.039200 -0.042600 0.100518 -vn -0.912516 -2.780905 -5.176074 -v 0.040118 -0.042600 0.100053 -vn 0.356158 -4.912723 -3.443650 -v 0.040625 -0.042742 0.100160 -vn 0.519448 -6.040493 -1.262014 -v 0.041027 -0.042807 0.100440 -vn 0.075018 -6.276102 -0.195648 -v 0.041000 -0.042810 0.100481 -vn 2.835769 -4.912711 -1.985947 -v 0.041842 -0.042742 0.100875 -vn 4.336392 -2.795600 -2.966335 -v 0.041947 -0.042600 0.100802 -vn 3.280434 -4.912695 -1.106586 -v 0.042060 -0.042742 0.101307 -vn -0.161553 0.040664 -3.209783 -v 0.040405 -0.018160 0.101317 -vn 0.622477 0.034724 -3.035360 -v 0.040604 -0.018196 0.101337 -vn 1.169178 0.004944 -2.852082 -v 0.040616 -0.018198 0.101341 -vn 1.924731 0.001469 -2.499660 -v 0.040777 -0.018231 0.101427 -vn 2.448503 0.003271 -1.879194 -v 0.040895 -0.018262 0.101553 -vn 2.767803 0.016737 -1.388521 -v 0.040912 -0.018268 0.101581 -vn 3.110585 0.022750 -0.628544 -v 0.040973 -0.018298 0.101737 -vn 3.134343 -0.009924 0.508048 -v 0.040978 -0.018334 0.101936 -vn 2.787791 -0.009554 1.344349 -v 0.040911 -0.018369 0.102122 -vn 2.485003 -0.040884 1.894493 -v 0.040904 -0.018371 0.102133 -vn 2.059764 -0.010171 2.418626 -v 0.040780 -0.018405 0.102271 -vn 1.347581 0.005883 2.749690 -v 0.040669 -0.018428 0.102338 -vn -0.834118 0.011495 2.949955 -v 0.040290 -0.018497 0.102361 -vn -0.308046 0.005415 3.071831 -v 0.040408 -0.018476 0.102383 -vn 0.226014 0.000781 3.051955 -v 0.040484 -0.018462 0.102384 -vn 0.806797 0.001830 2.933834 -v 0.040604 -0.018440 0.102363 -vn -2.579209 -0.021981 1.700840 -v 0.039998 -0.018564 0.102135 -vn -2.218127 -0.020284 2.118919 -v 0.040072 -0.018543 0.102228 -vn -1.812122 -0.001147 2.445214 -v 0.040129 -0.018530 0.102278 -vn -1.361923 0.005539 2.723441 -v 0.040215 -0.018511 0.102331 -vn -3.045233 -0.012764 0.196171 -v 0.039916 -0.018613 0.101877 -vn -3.042796 -0.026109 0.623310 -v 0.039923 -0.018601 0.101946 -vn -2.863575 -0.008271 1.208224 -v 0.039960 -0.018578 0.102066 -vn -2.974847 0.017505 -0.834635 -v 0.039943 -0.018649 0.101679 -vn -3.070131 0.006848 -0.287248 -v 0.039916 -0.018622 0.101829 -vn -2.765398 0.010070 -1.332865 -v 0.039959 -0.018657 0.101637 -vn -2.364538 -0.027138 -2.099293 -v 0.040038 -0.018684 0.101508 -vn -1.881800 -0.029310 -2.221755 -v 0.040069 -0.018691 0.101483 -vn -1.660326 0.011176 -2.592128 -v 0.040192 -0.018720 0.101381 -vn -1.141297 -0.002242 -2.856106 -v 0.040223 -0.018726 0.101365 -vn -0.418506 -0.000545 -3.130096 -v 0.040380 -0.018755 0.101319 -vn 0.666944 -0.018160 -3.084740 -v 0.040554 -0.018787 0.101326 -vn 1.077054 -0.043220 -2.717702 -v 0.040591 -0.018794 0.101340 -vn 1.671959 -0.002775 -2.719006 -v 0.040739 -0.018822 0.101399 -vn 2.247763 0.007103 -2.097569 -v 0.040860 -0.018852 0.101507 -vn 2.566919 -0.014720 -1.680327 -v 0.040880 -0.018857 0.101532 -vn 2.831423 -0.000650 -1.171251 -v 0.040956 -0.018886 0.101676 -vn 2.973009 -0.002546 -0.646462 -v 0.040967 -0.018893 0.101713 -vn 3.062321 -0.010838 -0.030974 -v 0.040985 -0.018921 0.101865 -vn 3.044637 -0.013218 0.474887 -v 0.040982 -0.018928 0.101907 -vn 2.885509 -0.005099 1.045784 -v 0.040944 -0.018956 0.102056 -vn 2.682871 -0.004941 1.576013 -v 0.040924 -0.018964 0.102099 -vn 2.403651 0.014653 1.997046 -v 0.040846 -0.018989 0.102210 -vn 1.946145 0.004476 2.392925 -v 0.040803 -0.018999 0.102252 -vn 1.480304 0.005034 2.670390 -v 0.040690 -0.019024 0.102328 -vn 1.033266 -0.010232 2.895400 -v 0.040655 -0.019031 0.102344 -vn 0.437336 -0.006237 3.046194 -v 0.040497 -0.019060 0.102383 -vn -0.016026 -0.019175 3.036814 -v 0.040459 -0.019066 0.102385 -vn -0.453473 -0.015761 3.037095 -v 0.040377 -0.019081 0.102380 -vn -0.999055 -0.002260 2.874707 -v 0.040265 -0.019102 0.102352 -vn -1.494021 0.001095 2.643947 -v 0.040195 -0.019115 0.102320 -vn -2.012151 0.019217 2.325396 -v 0.040093 -0.019138 0.102250 -vn -2.361077 0.011190 1.947366 -v 0.040044 -0.019150 0.102199 -vn -2.713589 0.017289 1.441612 -v 0.039974 -0.019173 0.102094 -vn -2.922099 0.010935 0.966049 -v 0.039946 -0.019185 0.102030 -vn -3.053106 0.008207 0.413429 -v 0.039917 -0.019209 0.101902 -vn -3.059345 0.006897 -0.101769 -v 0.039915 -0.019218 0.101850 -vn -2.953862 0.003716 -0.709076 -v 0.039934 -0.019244 0.101708 -vn -2.825254 0.030975 -1.281720 -v 0.039952 -0.019254 0.101656 -vn -2.652870 0.087945 -1.890368 -v 0.040005 -0.019274 0.101553 -vn -1.855811 0.032864 -2.670536 -v 0.040146 -0.019310 0.101410 -vn -0.768002 0.009131 -3.116162 -v 0.040328 -0.019346 0.101329 -vn 0.444456 -0.002655 -3.142540 -v 0.040525 -0.019381 0.101320 -vn 1.574364 0.002321 -2.777603 -v 0.040713 -0.019417 0.101384 -vn 2.964373 -0.016553 -0.780297 -v 0.040959 -0.019488 0.101685 -vn 2.821803 -0.022220 -1.304830 -v 0.040950 -0.019483 0.101660 -vn 2.474313 -0.009506 -2.031463 -v 0.040865 -0.019453 0.101512 -vn 3.062562 -0.003633 0.386985 -v 0.040984 -0.019524 0.101883 -vn 3.065657 -0.006150 -0.172457 -v 0.040985 -0.019519 0.101854 -vn 2.608655 -0.004562 1.691439 -v 0.040896 -0.019574 0.102146 -vn 2.928929 -0.019136 1.131785 -v 0.040944 -0.019556 0.102055 -vn 2.228488 0.013595 2.107889 -v 0.040837 -0.019591 0.102219 -vn 1.768875 0.004619 2.494874 -v 0.040758 -0.019610 0.102288 -vn -0.296287 -0.002809 3.050583 -v 0.040399 -0.019677 0.102383 -vn 0.208673 -0.002828 3.048620 -v 0.040486 -0.019662 0.102384 -vn 0.760344 0.011331 2.961902 -v 0.040577 -0.019645 0.102370 -vn 1.265848 0.018090 2.799915 -v 0.040680 -0.019626 0.102333 -vn -2.030636 -0.008417 2.376830 -v 0.040115 -0.019733 0.102267 -vn -1.431812 -0.007206 2.698807 -v 0.040207 -0.019713 0.102326 -vn -0.884667 -0.002251 2.915012 -v 0.040291 -0.019697 0.102361 -vn -2.520318 0.004800 1.733293 -v 0.039986 -0.019768 0.102118 -vn -2.789800 0.006510 1.287848 -v 0.039983 -0.019769 0.102112 -vn -2.968821 0.022811 0.781646 -v 0.039925 -0.019799 0.101954 -vn -3.060488 0.000615 0.267606 -v 0.039922 -0.019803 0.101932 -vn -3.071720 0.009015 -0.336859 -v 0.039923 -0.019835 0.101756 -vn -2.990610 0.000865 -0.933196 -v 0.039928 -0.019839 0.101731 -vn -2.797403 0.011529 -1.424729 -v 0.039992 -0.019870 0.101574 -vn -2.443222 0.001516 -1.890929 -v 0.040009 -0.019875 0.101548 -vn -1.898180 -0.004712 -2.530467 -v 0.040125 -0.019906 0.101425 -vn -0.882914 0.007790 -3.072366 -v 0.040299 -0.019941 0.101337 -vn 0.171238 0.029498 -3.148190 -v 0.040498 -0.019977 0.101317 -vn 1.847014 -0.003984 -2.427660 -v 0.040786 -0.020033 0.101434 -vn 1.417086 -0.018760 -2.742565 -v 0.040686 -0.020012 0.101370 -vn 0.911676 -0.004263 -2.948414 -v 0.040618 -0.019999 0.101342 -vn 2.620860 -0.006811 -1.592587 -v 0.040917 -0.020069 0.101588 -vn 2.228204 -0.003931 -2.077596 -v 0.040828 -0.020043 0.101472 -vn 2.887712 -0.008871 -1.118227 -v 0.040941 -0.020079 0.101637 -vn 3.010794 0.006268 -0.534434 -v 0.040980 -0.020105 0.101780 -vn 2.993448 -0.000952 0.620981 -v 0.040969 -0.020142 0.101983 -vn 3.043922 -0.001088 0.013274 -v 0.040984 -0.020114 0.101829 -vn 2.868192 -0.001280 1.162827 -v 0.040956 -0.020150 0.102026 -vn 2.564747 0.001690 1.694044 -v 0.040882 -0.020178 0.102166 -vn 2.242808 -0.018828 2.105576 -v 0.040858 -0.020185 0.102196 -vn 1.825696 -0.002902 2.486838 -v 0.040743 -0.020213 0.102297 -vn 1.336002 -0.002361 2.760487 -v 0.040703 -0.020221 0.102322 -vn 0.729125 -0.003531 2.976396 -v 0.040555 -0.020249 0.102375 -vn 0.203138 -0.015036 3.081393 -v 0.040517 -0.020256 0.102381 -vn -0.493890 -0.008612 3.078586 -v 0.040345 -0.020287 0.102375 -vn -1.144304 0.005983 2.873425 -v 0.040254 -0.020304 0.102348 -vn -2.753289 0.001426 1.333589 -v 0.039967 -0.020375 0.102082 -vn -2.485662 -0.006970 1.834115 -v 0.040016 -0.020359 0.102162 -vn -2.107522 -0.011347 2.220513 -v 0.040089 -0.020339 0.102245 -vn -1.633572 0.007717 2.585348 -v 0.040160 -0.020323 0.102300 -vn -2.979558 -0.017205 0.745488 -v 0.039931 -0.020394 0.101983 -vn -3.120929 -0.053820 0.245296 -v 0.039916 -0.020412 0.101885 -vn -0.753336 0.010216 -3.025788 -v 0.040306 -0.018142 0.101335 -vn -1.359439 -0.004720 -2.739078 -v 0.040216 -0.018125 0.101368 -vn -1.851164 -0.000269 -2.421724 -v 0.040124 -0.018105 0.101426 -vn -2.245009 0.005896 -2.050658 -v 0.040056 -0.018089 0.101488 -vn -2.683367 -0.014333 -1.576353 -v 0.039994 -0.018071 0.101571 -vn -3.070575 -0.039651 -1.048902 -v 0.039951 -0.018054 0.101655 -vn -3.196215 -0.053257 -0.215684 -v 0.039915 -0.018018 0.101850 -vn 2.720703 -4.188786 -0.000000 -v 0.039450 -0.042810 0.101850 -vn -1.360349 -4.188790 -2.356195 -v 0.040950 -0.042810 0.102716 -vn 1.360351 -4.188793 -2.356191 -v 0.039950 -0.042810 0.102716 -vn -2.720698 -4.188792 -0.000000 -v 0.041450 -0.042810 0.101850 -vn -1.360349 -4.188790 2.356196 -v 0.040950 -0.042810 0.100984 -vn 1.360352 -4.188793 2.356191 -v 0.039950 -0.042810 0.100984 -vn 2.720703 -2.094400 0.000000 -v 0.039450 -0.041810 0.101850 -vn 1.360351 -2.094393 2.356191 -v 0.039950 -0.041810 0.100984 -vn 1.360352 -2.094393 -2.356191 -v 0.039950 -0.041810 0.102716 -vn -1.360349 -2.094396 -2.356195 -v 0.040950 -0.041810 0.102716 -vn -2.720698 -2.094393 0.000000 -v 0.041450 -0.041810 0.101850 -vn -1.360349 -2.094396 2.356195 -v 0.040950 -0.041810 0.100984 -vn -0.161547 0.040634 -3.209745 -v 0.040405 -0.015760 0.101317 -vn 0.622732 0.034599 -3.035374 -v 0.040604 -0.015796 0.101337 -vn 1.169370 0.004987 -2.851799 -v 0.040616 -0.015798 0.101341 -vn 1.924711 0.001436 -2.499661 -v 0.040777 -0.015831 0.101427 -vn 2.448346 0.003282 -1.879214 -v 0.040895 -0.015862 0.101553 -vn 2.767781 0.016724 -1.388656 -v 0.040912 -0.015868 0.101581 -vn 3.110523 0.022733 -0.628500 -v 0.040973 -0.015898 0.101737 -vn 3.134285 -0.009970 0.508022 -v 0.040978 -0.015933 0.101936 -vn 2.787741 -0.009497 1.344272 -v 0.040911 -0.015969 0.102122 -vn 2.485073 -0.041022 1.894431 -v 0.040904 -0.015971 0.102133 -vn 2.059719 -0.010175 2.418591 -v 0.040780 -0.016005 0.102271 -vn 1.347489 0.005859 2.749712 -v 0.040669 -0.016028 0.102338 -vn 0.806731 0.001769 2.933730 -v 0.040604 -0.016040 0.102363 -vn 0.225923 0.000691 3.051973 -v 0.040484 -0.016062 0.102384 -vn -0.308111 0.005360 3.071644 -v 0.040408 -0.016076 0.102383 -vn -0.834107 0.011511 2.949914 -v 0.040290 -0.016097 0.102361 -vn -1.361837 0.005464 2.723367 -v 0.040215 -0.016111 0.102331 -vn -1.812040 -0.001193 2.445192 -v 0.040129 -0.016130 0.102278 -vn -2.218097 -0.020347 2.118853 -v 0.040072 -0.016143 0.102228 -vn -2.579125 -0.022040 1.700761 -v 0.039998 -0.016164 0.102135 -vn -2.863442 -0.008317 1.208229 -v 0.039961 -0.016178 0.102066 -vn -3.042730 -0.026190 0.623338 -v 0.039923 -0.016201 0.101946 -vn -3.045104 -0.012855 0.196151 -v 0.039916 -0.016213 0.101877 -vn -3.070024 0.006837 -0.287268 -v 0.039916 -0.016222 0.101829 -vn -2.974727 0.017406 -0.834577 -v 0.039943 -0.016249 0.101679 -vn -2.774572 -0.007101 -1.364425 -v 0.039959 -0.016257 0.101637 -vn -2.482416 -0.008349 -1.855836 -v 0.040038 -0.016284 0.101508 -vn -2.092480 0.009352 -2.284679 -v 0.040065 -0.016291 0.101478 -vn -1.643986 0.027079 -2.613242 -v 0.040193 -0.016320 0.101381 -vn -1.149108 0.003119 -2.861760 -v 0.040223 -0.016326 0.101365 -vn -0.407861 -0.007468 -3.139166 -v 0.040380 -0.016355 0.101319 -vn 0.421062 0.001296 -3.058341 -v 0.040554 -0.016387 0.101326 -vn 1.037035 -0.013782 -2.944693 -v 0.040593 -0.016394 0.101335 -vn 1.692018 0.009615 -2.722201 -v 0.040739 -0.016422 0.101399 -vn 2.247598 0.007085 -2.097391 -v 0.040860 -0.016452 0.101507 -vn 2.566734 -0.014826 -1.680326 -v 0.040880 -0.016457 0.101532 -vn 2.831311 -0.000801 -1.171206 -v 0.040956 -0.016486 0.101676 -vn 2.972818 -0.002610 -0.646309 -v 0.040967 -0.016493 0.101713 -vn 3.062202 -0.010974 -0.030853 -v 0.040985 -0.016521 0.101865 -vn 3.044406 -0.013255 0.474936 -v 0.040982 -0.016528 0.101907 -vn 2.885390 -0.005139 1.045607 -v 0.040944 -0.016556 0.102056 -vn 2.682810 -0.005077 1.575974 -v 0.040924 -0.016564 0.102099 -vn 2.403467 0.014502 1.996944 -v 0.040846 -0.016589 0.102210 -vn 1.946001 0.004429 2.392875 -v 0.040803 -0.016599 0.102252 -vn 1.480179 0.004929 2.670160 -v 0.040690 -0.016624 0.102328 -vn 1.033326 -0.010281 2.895183 -v 0.040655 -0.016631 0.102344 -vn 0.437457 -0.006426 3.046041 -v 0.040497 -0.016660 0.102383 -vn -0.016057 -0.019162 3.036666 -v 0.040459 -0.016666 0.102385 -vn -0.453519 -0.015901 3.036987 -v 0.040377 -0.016681 0.102380 -vn -0.999060 -0.002424 2.874444 -v 0.040265 -0.016702 0.102352 -vn -1.493909 0.001032 2.643677 -v 0.040195 -0.016715 0.102320 -vn -2.012057 0.019125 2.325294 -v 0.040093 -0.016738 0.102249 -vn -2.360983 0.011038 1.947173 -v 0.040044 -0.016750 0.102199 -vn -2.713399 0.017164 1.441454 -v 0.039974 -0.016773 0.102094 -vn -2.921875 0.010811 0.965949 -v 0.039946 -0.016785 0.102030 -vn -3.052974 0.008007 0.413304 -v 0.039917 -0.016809 0.101902 -vn -3.059037 0.006848 -0.101997 -v 0.039915 -0.016818 0.101850 -vn -2.953614 0.003642 -0.709049 -v 0.039934 -0.016844 0.101708 -vn -2.825117 0.030825 -1.281577 -v 0.039952 -0.016854 0.101656 -vn -2.652690 0.087778 -1.890189 -v 0.040005 -0.016874 0.101553 -vn -1.855692 0.032730 -2.670357 -v 0.040146 -0.016910 0.101410 -vn -0.767941 0.008999 -3.115920 -v 0.040328 -0.016946 0.101329 -vn 0.444495 -0.002807 -3.142334 -v 0.040525 -0.016981 0.101320 -vn 1.574323 0.002155 -2.777323 -v 0.040713 -0.017017 0.101384 -vn 2.964123 -0.016804 -0.780131 -v 0.040959 -0.017088 0.101685 -vn 2.821661 -0.022266 -1.304599 -v 0.040950 -0.017083 0.101660 -vn 2.474207 -0.009646 -2.031214 -v 0.040865 -0.017053 0.101512 -vn 3.062243 -0.003693 0.387171 -v 0.040984 -0.017124 0.101883 -vn 3.065434 -0.006455 -0.172354 -v 0.040985 -0.017119 0.101854 -vn 2.618600 0.000663 1.688039 -v 0.040896 -0.017174 0.102146 -vn 2.938824 -0.012071 1.149345 -v 0.040944 -0.017156 0.102055 -vn 1.768682 0.004409 2.494673 -v 0.040757 -0.017210 0.102288 -vn 2.228366 0.013500 2.107729 -v 0.040837 -0.017191 0.102219 -vn -0.296296 -0.002972 3.050329 -v 0.040399 -0.017277 0.102383 -vn 0.208637 -0.002978 3.048332 -v 0.040486 -0.017262 0.102384 -vn 0.760393 0.011169 2.961665 -v 0.040577 -0.017245 0.102369 -vn 1.265672 0.017996 2.799571 -v 0.040680 -0.017226 0.102333 -vn -2.030525 -0.008600 2.376635 -v 0.040115 -0.017333 0.102267 -vn -1.431640 -0.007349 2.698493 -v 0.040207 -0.017313 0.102326 -vn -0.884694 -0.002414 2.914705 -v 0.040291 -0.017297 0.102361 -vn -2.520128 0.004430 1.732912 -v 0.039986 -0.017368 0.102118 -vn -2.789513 0.006534 1.287471 -v 0.039983 -0.017369 0.102112 -vn -2.968221 0.022605 0.781970 -v 0.039926 -0.017399 0.101954 -vn -3.060321 0.000560 0.267982 -v 0.039922 -0.017403 0.101932 -vn -3.071496 0.008827 -0.337014 -v 0.039923 -0.017435 0.101756 -vn -2.990152 0.000646 -0.933225 -v 0.039928 -0.017439 0.101731 -vn -2.797178 0.011259 -1.424785 -v 0.039992 -0.017470 0.101574 -vn -2.442736 0.001350 -1.890891 -v 0.040009 -0.017475 0.101548 -vn -1.897895 -0.004893 -2.530217 -v 0.040125 -0.017506 0.101425 -vn -0.883828 0.006318 -3.074230 -v 0.040299 -0.017541 0.101337 -vn 0.171331 0.029305 -3.147809 -v 0.040498 -0.017577 0.101317 -vn 0.911661 -0.004426 -2.948120 -v 0.040618 -0.017599 0.101342 -vn 1.416972 -0.018978 -2.742194 -v 0.040686 -0.017612 0.101370 -vn 1.846898 -0.004108 -2.427386 -v 0.040786 -0.017633 0.101434 -vn 2.280826 0.011918 -2.075750 -v 0.040828 -0.017643 0.101472 -vn 2.628533 0.013496 -1.630482 -v 0.040917 -0.017669 0.101588 -vn 2.887396 -0.009009 -1.118289 -v 0.040941 -0.017679 0.101637 -vn 3.010377 0.006058 -0.534482 -v 0.040980 -0.017705 0.101780 -vn 3.043587 -0.001303 0.013182 -v 0.040984 -0.017714 0.101829 -vn 2.992983 -0.001048 0.620773 -v 0.040969 -0.017742 0.101983 -vn 2.867996 -0.001488 1.162580 -v 0.040956 -0.017750 0.102026 -vn 2.564429 0.001478 1.693869 -v 0.040882 -0.017778 0.102166 -vn 2.242517 -0.019052 2.105401 -v 0.040858 -0.017785 0.102196 -vn 1.825425 -0.003140 2.486528 -v 0.040743 -0.017813 0.102297 -vn -1.144152 0.005788 2.873252 -v 0.040254 -0.017904 0.102348 -vn -0.493859 -0.008840 3.078191 -v 0.040345 -0.017887 0.102375 -vn 0.202731 -0.015256 3.080949 -v 0.040517 -0.017856 0.102381 -vn 0.751409 0.009066 2.987449 -v 0.040555 -0.017849 0.102375 -vn 1.323920 0.010825 2.799845 -v 0.040703 -0.017821 0.102322 -vn -2.753431 0.001259 1.333547 -v 0.039968 -0.017975 0.102082 -vn -2.485796 -0.007125 1.834136 -v 0.040016 -0.017958 0.102162 -vn -2.107443 -0.011562 2.220425 -v 0.040089 -0.017939 0.102244 -vn -1.633533 0.007528 2.585326 -v 0.040160 -0.017923 0.102300 -vn -2.979867 -0.017423 0.745480 -v 0.039931 -0.017994 0.101983 -vn -3.120999 -0.053861 0.245449 -v 0.039916 -0.018012 0.101885 -vn -0.753223 0.010201 -3.025742 -v 0.040306 -0.015742 0.101335 -vn -1.359489 -0.004774 -2.739129 -v 0.040216 -0.015725 0.101368 -vn -1.851035 -0.000243 -2.421666 -v 0.040124 -0.015705 0.101426 -vn -2.244964 0.005894 -2.050767 -v 0.040056 -0.015689 0.101488 -vn -2.683305 -0.014377 -1.576336 -v 0.039994 -0.015671 0.101571 -vn -3.070570 -0.039653 -1.048959 -v 0.039951 -0.015654 0.101655 -vn -3.196210 -0.053251 -0.215684 -v 0.039915 -0.015618 0.101850 -vn -0.161546 0.040637 -3.209749 -v 0.040405 -0.013360 0.101317 -vn 0.622733 0.034601 -3.035378 -v 0.040604 -0.013396 0.101337 -vn 1.169372 0.004990 -2.851802 -v 0.040616 -0.013398 0.101341 -vn 1.924713 0.001438 -2.499665 -v 0.040777 -0.013431 0.101427 -vn 2.448349 0.003285 -1.879216 -v 0.040895 -0.013462 0.101553 -vn 2.767782 0.016726 -1.388658 -v 0.040912 -0.013468 0.101581 -vn 3.110526 0.022735 -0.628500 -v 0.040973 -0.013498 0.101737 -vn 3.134285 -0.009970 0.508022 -v 0.040978 -0.013533 0.101936 -vn 2.787741 -0.009497 1.344272 -v 0.040911 -0.013569 0.102122 -vn 2.485073 -0.041022 1.894431 -v 0.040904 -0.013571 0.102133 -vn 2.059718 -0.010171 2.418604 -v 0.040780 -0.013605 0.102271 -vn 1.347498 0.005863 2.749716 -v 0.040669 -0.013628 0.102338 -vn 0.806731 0.001769 2.933730 -v 0.040604 -0.013640 0.102363 -vn 0.225923 0.000691 3.051973 -v 0.040484 -0.013662 0.102384 -vn -0.308111 0.005360 3.071644 -v 0.040408 -0.013676 0.102383 -vn -0.834107 0.011511 2.949914 -v 0.040290 -0.013697 0.102361 -vn -1.361837 0.005464 2.723367 -v 0.040215 -0.013711 0.102331 -vn -1.812053 -0.001188 2.445196 -v 0.040129 -0.013730 0.102278 -vn -2.218098 -0.020342 2.118862 -v 0.040072 -0.013743 0.102228 -vn -2.579125 -0.022040 1.700761 -v 0.039998 -0.013764 0.102135 -vn -2.863442 -0.008317 1.208229 -v 0.039961 -0.013778 0.102066 -vn -3.042730 -0.026190 0.623338 -v 0.039923 -0.013801 0.101946 -vn -3.045120 -0.012803 0.196126 -v 0.039916 -0.013813 0.101877 -vn -3.070047 0.006746 -0.287234 -v 0.039916 -0.013822 0.101829 -vn -2.974725 0.017423 -0.834581 -v 0.039943 -0.013849 0.101679 -vn -2.774569 -0.007086 -1.364465 -v 0.039959 -0.013857 0.101637 -vn -2.482416 -0.008449 -1.855701 -v 0.040038 -0.013884 0.101508 -vn -2.092554 0.009442 -2.284652 -v 0.040065 -0.013891 0.101478 -vn -1.643987 0.027085 -2.613232 -v 0.040193 -0.013920 0.101381 -vn -1.149094 0.003138 -2.861756 -v 0.040223 -0.013926 0.101365 -vn -0.407874 -0.007514 -3.139163 -v 0.040380 -0.013955 0.101319 -vn 0.421100 0.001369 -3.058352 -v 0.040554 -0.013987 0.101326 -vn 1.037012 -0.013892 -2.944732 -v 0.040593 -0.013994 0.101335 -vn 1.692029 0.009633 -2.722210 -v 0.040739 -0.014022 0.101399 -vn 2.247600 0.007090 -2.097401 -v 0.040860 -0.014052 0.101507 -vn 2.566734 -0.014826 -1.680326 -v 0.040880 -0.014057 0.101532 -vn 2.831311 -0.000801 -1.171206 -v 0.040956 -0.014086 0.101676 -vn 2.972838 -0.002595 -0.646294 -v 0.040967 -0.014093 0.101713 -vn 3.062216 -0.011007 -0.030875 -v 0.040985 -0.014121 0.101865 -vn 3.044407 -0.013275 0.474932 -v 0.040982 -0.014128 0.101907 -vn 2.885386 -0.005222 1.045575 -v 0.040944 -0.014156 0.102056 -vn 2.682790 -0.005028 1.575987 -v 0.040924 -0.014164 0.102099 -vn 2.403467 0.014502 1.996944 -v 0.040846 -0.014189 0.102210 -vn 1.946001 0.004429 2.392875 -v 0.040803 -0.014199 0.102252 -vn 1.480179 0.004929 2.670160 -v 0.040690 -0.014224 0.102328 -vn 1.033277 -0.010290 2.895225 -v 0.040655 -0.014231 0.102344 -vn 0.437674 -0.006382 3.045797 -v 0.040497 -0.014260 0.102383 -vn -0.015792 -0.019124 3.036780 -v 0.040459 -0.014266 0.102385 -vn -0.453528 -0.015896 3.036997 -v 0.040377 -0.014281 0.102380 -vn -0.999049 -0.002415 2.874448 -v 0.040265 -0.014302 0.102352 -vn -1.493901 0.001042 2.643660 -v 0.040195 -0.014315 0.102320 -vn -2.012055 0.019131 2.325280 -v 0.040093 -0.014338 0.102249 -vn -2.360983 0.011038 1.947173 -v 0.040044 -0.014350 0.102199 -vn -2.713399 0.017164 1.441454 -v 0.039974 -0.014373 0.102094 -vn -2.921903 0.010805 0.965918 -v 0.039946 -0.014385 0.102030 -vn -3.052907 0.008060 0.413336 -v 0.039917 -0.014409 0.101902 -vn -3.059095 0.006775 -0.101840 -v 0.039915 -0.014418 0.101850 -vn -2.953623 0.003624 -0.709108 -v 0.039934 -0.014444 0.101708 -vn -2.825055 0.030835 -1.281629 -v 0.039952 -0.014454 0.101656 -vn -2.652690 0.087780 -1.890198 -v 0.040005 -0.014474 0.101553 -vn -1.855703 0.032737 -2.670362 -v 0.040146 -0.014510 0.101410 -vn -0.767941 0.008999 -3.115920 -v 0.040328 -0.014546 0.101329 -vn 0.444495 -0.002807 -3.142334 -v 0.040525 -0.014581 0.101320 -vn 1.574321 0.002158 -2.777318 -v 0.040713 -0.014617 0.101384 -vn 2.964123 -0.016804 -0.780131 -v 0.040959 -0.014688 0.101685 -vn 2.821661 -0.022266 -1.304599 -v 0.040950 -0.014683 0.101660 -vn 2.474207 -0.009646 -2.031214 -v 0.040865 -0.014653 0.101512 -vn 3.062250 -0.003689 0.387180 -v 0.040984 -0.014724 0.101883 -vn 3.065434 -0.006455 -0.172354 -v 0.040985 -0.014719 0.101854 -vn 2.618603 0.000689 1.688061 -v 0.040896 -0.014774 0.102146 -vn 2.938834 -0.012065 1.149342 -v 0.040944 -0.014756 0.102055 -vn 1.768650 0.004453 2.494698 -v 0.040757 -0.014810 0.102288 -vn 2.228396 0.013430 2.107701 -v 0.040837 -0.014791 0.102219 -vn -0.296303 -0.002966 3.050318 -v 0.040399 -0.014877 0.102383 -vn 0.208642 -0.002972 3.048324 -v 0.040486 -0.014862 0.102384 -vn 0.760377 0.011197 2.961659 -v 0.040577 -0.014845 0.102369 -vn 1.265713 0.017927 2.799571 -v 0.040680 -0.014826 0.102333 -vn -2.030539 -0.008573 2.376624 -v 0.040115 -0.014933 0.102267 -vn -1.431610 -0.007411 2.698511 -v 0.040207 -0.014913 0.102326 -vn -0.884722 -0.002380 2.914717 -v 0.040291 -0.014897 0.102361 -vn -2.520130 0.004434 1.732920 -v 0.039986 -0.014968 0.102118 -vn -2.789523 0.006537 1.287468 -v 0.039983 -0.014969 0.102112 -vn -2.968228 0.022611 0.781978 -v 0.039926 -0.014999 0.101954 -vn -3.060313 0.000565 0.267987 -v 0.039922 -0.015003 0.101932 -vn -3.071499 0.008931 -0.337058 -v 0.039923 -0.015035 0.101756 -vn -2.990192 0.000490 -0.933192 -v 0.039928 -0.015039 0.101731 -vn -2.797184 0.011274 -1.424785 -v 0.039992 -0.015070 0.101574 -vn -2.442736 0.001350 -1.890891 -v 0.040009 -0.015075 0.101548 -vn -1.897895 -0.004893 -2.530217 -v 0.040125 -0.015106 0.101425 -vn -0.883828 0.006318 -3.074230 -v 0.040299 -0.015141 0.101337 -vn 0.171333 0.029327 -3.147805 -v 0.040498 -0.015177 0.101317 -vn 0.911635 -0.004508 -2.948115 -v 0.040618 -0.015199 0.101342 -vn 1.416980 -0.018950 -2.742183 -v 0.040686 -0.015212 0.101370 -vn 1.846898 -0.004108 -2.427386 -v 0.040786 -0.015233 0.101434 -vn 2.280829 0.011919 -2.075752 -v 0.040828 -0.015243 0.101472 -vn 2.628533 0.013496 -1.630482 -v 0.040917 -0.015269 0.101588 -vn 2.887408 -0.009005 -1.118285 -v 0.040941 -0.015279 0.101637 -vn 3.010383 0.006063 -0.534489 -v 0.040980 -0.015305 0.101780 -vn 3.043601 -0.001290 0.013199 -v 0.040984 -0.015314 0.101829 -vn 2.992989 -0.001148 0.620721 -v 0.040969 -0.015342 0.101983 -vn 2.867971 -0.001436 1.162598 -v 0.040956 -0.015350 0.102026 -vn 2.564428 0.001480 1.693866 -v 0.040882 -0.015378 0.102166 -vn 2.242516 -0.019045 2.105410 -v 0.040858 -0.015385 0.102196 -vn 1.825432 -0.003126 2.486542 -v 0.040743 -0.015413 0.102297 -vn -1.144143 0.005795 2.873244 -v 0.040254 -0.015504 0.102348 -vn -0.493859 -0.008837 3.078187 -v 0.040345 -0.015487 0.102375 -vn 0.202730 -0.015253 3.080945 -v 0.040517 -0.015456 0.102381 -vn 0.751415 0.009076 2.987451 -v 0.040555 -0.015449 0.102375 -vn 1.323923 0.010837 2.799858 -v 0.040703 -0.015421 0.102322 -vn -2.753397 0.001196 1.333575 -v 0.039968 -0.015575 0.102082 -vn -2.485807 -0.007097 1.834127 -v 0.040016 -0.015558 0.102162 -vn -2.107440 -0.011559 2.220422 -v 0.040089 -0.015539 0.102244 -vn -1.633532 0.007535 2.585309 -v 0.040160 -0.015523 0.102300 -vn -2.979849 -0.017398 0.745451 -v 0.039931 -0.015594 0.101983 -vn -3.120995 -0.053858 0.245447 -v 0.039916 -0.015612 0.101885 -vn -0.753214 0.010209 -3.025739 -v 0.040306 -0.013342 0.101335 -vn -1.359493 -0.004766 -2.739124 -v 0.040216 -0.013325 0.101368 -vn -1.851046 -0.000235 -2.421671 -v 0.040124 -0.013305 0.101426 -vn -2.244971 0.005901 -2.050784 -v 0.040056 -0.013289 0.101488 -vn -2.683308 -0.014375 -1.576339 -v 0.039994 -0.013271 0.101571 -vn -3.070575 -0.039648 -1.048960 -v 0.039951 -0.013254 0.101655 -vn -3.246593 -0.023819 -0.093960 -v 0.039915 -0.013218 0.101850 -vn 2.973285 -0.015243 -1.151636 -v 0.040950 -0.012284 0.101662 -vn -0.938866 -0.012990 -2.950242 -v 0.040306 -0.010942 0.101335 -vn -0.402767 0.006644 -3.014305 -v 0.040379 -0.010955 0.101320 -vn -0.025633 -0.009205 -3.116618 -v 0.040417 -0.010962 0.101316 -vn 0.587045 -0.015206 -3.034333 -v 0.040590 -0.010993 0.101333 -vn 1.158037 -0.004554 -2.866976 -v 0.040616 -0.010998 0.101341 -vn 1.984731 -0.007278 -2.475410 -v 0.040779 -0.011031 0.101428 -vn 2.763856 0.002725 -1.611245 -v 0.040917 -0.011069 0.101588 -vn 2.902694 -0.004517 0.952031 -v 0.040964 -0.011145 0.102000 -vn 3.053746 -0.004072 0.387576 -v 0.040977 -0.011135 0.101943 -vn 3.058046 -0.007268 -0.177978 -v 0.040981 -0.011107 0.101789 -vn 2.984758 0.018142 -0.752211 -v 0.040976 -0.011100 0.101750 -vn 0.196400 -0.003443 3.203740 -v 0.040501 -0.011259 0.102383 -vn 1.118610 -0.001374 2.895033 -v 0.040669 -0.011228 0.102338 -vn 1.611090 0.022676 2.643502 -v 0.040703 -0.011221 0.102322 -vn 2.083312 0.015885 2.285207 -v 0.040832 -0.011192 0.102224 -vn 2.335470 0.004396 1.897653 -v 0.040866 -0.011183 0.102187 -vn 2.641739 0.002121 1.533810 -v 0.040904 -0.011171 0.102133 -vn -0.920297 0.011982 3.100615 -v 0.040290 -0.011297 0.102361 -vn -1.986407 -0.005430 2.470114 -v 0.040105 -0.011335 0.102259 -vn -2.506353 -0.000051 1.778989 -v 0.039998 -0.011364 0.102135 -vn -2.994476 0.007497 0.705103 -v 0.039923 -0.011401 0.101946 -vn -2.812319 0.007831 1.264573 -v 0.039974 -0.011373 0.102094 -vn -2.973957 0.020438 -0.825439 -v 0.039943 -0.011449 0.101681 -vn -3.101958 -0.000214 -0.251489 -v 0.039916 -0.011422 0.101829 -vn -3.023772 -0.006101 0.182842 -v 0.039916 -0.011411 0.101891 -vn -2.758141 0.011947 -1.349709 -v 0.039959 -0.011457 0.101637 -vn -2.403589 0.004111 -1.892988 -v 0.040047 -0.011487 0.101498 -vn -2.058181 0.002334 -2.317008 -v 0.040065 -0.011491 0.101478 -vn -1.372273 0.003622 -2.879096 -v 0.040215 -0.011525 0.101369 -vn -0.231337 -0.025217 -3.182663 -v 0.040419 -0.011563 0.101316 -vn 0.621548 -0.010385 -3.023252 -v 0.040593 -0.011594 0.101335 -vn 1.186397 0.003299 -2.830511 -v 0.040629 -0.011601 0.101346 -vn 1.727330 0.007343 -2.542674 -v 0.040774 -0.011630 0.101424 -vn 2.073637 -0.005401 -2.194194 -v 0.040810 -0.011638 0.101454 -vn 2.429055 0.000400 -1.906984 -v 0.040860 -0.011652 0.101507 -vn 2.758046 0.006891 -1.388026 -v 0.040935 -0.011676 0.101625 -vn 2.968058 -0.010710 -0.907638 -v 0.040956 -0.011686 0.101676 -vn 3.072513 -0.004949 -0.280297 -v 0.040985 -0.011714 0.101830 -vn 3.074478 0.004743 0.291016 -v 0.040985 -0.011721 0.101865 -vn 2.937957 0.012656 0.885546 -v 0.040951 -0.011752 0.102038 -vn 2.753556 -0.009091 1.381089 -v 0.040944 -0.011756 0.102056 -vn 2.298695 0.003161 2.214745 -v 0.040839 -0.011790 0.102218 -vn 1.324944 0.014602 2.868833 -v 0.040666 -0.011828 0.102339 -vn -1.032471 -0.001702 2.858783 -v 0.040252 -0.011904 0.102347 -vn -0.470787 -0.017223 3.042875 -v 0.040377 -0.011881 0.102380 -vn -0.023517 -0.013248 3.022763 -v 0.040460 -0.011866 0.102385 -vn 0.462791 0.002397 3.038330 -v 0.040497 -0.011860 0.102383 -vn -2.967547 0.038978 1.229779 -v 0.039957 -0.011980 0.102057 -vn -2.520916 0.021918 1.882246 -v 0.040044 -0.011950 0.102199 -vn -2.080621 0.008105 2.272173 -v 0.040075 -0.011942 0.102232 -vn -1.540083 -0.000841 2.623168 -v 0.040195 -0.011915 0.102320 -vn -3.201953 0.002411 0.000351 -v 0.039915 -0.012018 0.101850 -vn -2.950696 0.026925 -1.259717 -v 0.039957 -0.012056 0.101643 -vn -2.471701 0.033248 -1.909025 -v 0.040057 -0.012089 0.101487 -vn 1.117386 0.010546 -2.869489 -v 0.040666 -0.012208 0.101361 -vn 0.514808 -0.015514 -3.045546 -v 0.040516 -0.012180 0.101319 -vn -0.041328 -0.007962 -3.058700 -v 0.040460 -0.012170 0.101315 -vn -0.665321 0.001344 -2.976625 -v 0.040321 -0.012145 0.101331 -vn -1.169144 0.007638 -2.806857 -v 0.040252 -0.012132 0.101353 -vn -1.684151 0.001740 -2.533116 -v 0.040147 -0.012111 0.101409 -vn -2.047969 -0.002464 -2.195244 -v 0.040075 -0.012094 0.101468 -vn 2.482308 -0.020547 -1.876189 -v 0.040846 -0.012248 0.101490 -vn 2.070474 0.030666 -2.281159 -v 0.040839 -0.012246 0.101482 -vn 1.637532 0.024401 -2.639151 -v 0.040703 -0.012215 0.101379 -vn 3.163076 0.007317 0.008313 -v 0.040985 -0.012322 0.101870 -vn 3.026737 0.011541 0.685000 -v 0.040971 -0.012340 0.101972 -vn 2.783758 0.004911 1.262627 -v 0.040935 -0.012360 0.102075 -vn 2.514123 0.011668 1.763094 -v 0.040896 -0.012374 0.102146 -vn 2.141217 0.003773 2.189392 -v 0.040810 -0.012398 0.102246 -vn 1.675111 -0.006231 2.567694 -v 0.040757 -0.012410 0.102288 -vn 1.108081 -0.001464 2.870427 -v 0.040629 -0.012435 0.102354 -vn 0.592394 0.000681 3.064411 -v 0.040577 -0.012445 0.102369 -vn 0.037187 0.013977 3.091726 -v 0.040420 -0.012473 0.102384 -vn -0.508218 -0.004780 3.048143 -v 0.040399 -0.012477 0.102383 -vn -1.427239 -0.022191 2.841806 -v 0.040216 -0.012511 0.102331 -vn -2.284204 0.003738 2.195072 -v 0.040047 -0.012549 0.102202 -vn -3.040222 -0.003079 -0.154846 -v 0.039916 -0.012625 0.101809 -vn -3.033818 -0.007943 0.440116 -v 0.039922 -0.012603 0.101932 -vn -2.898916 -0.000981 0.955484 -v 0.039943 -0.012587 0.102019 -vn -2.665059 0.014771 1.529115 -v 0.039983 -0.012569 0.102112 -vn -0.900841 0.006761 -3.067018 -v 0.040290 -0.012739 0.101339 -vn -1.706286 -0.009476 -2.584068 -v 0.040129 -0.012707 0.101422 -vn -2.098055 0.011866 -2.246734 -v 0.040105 -0.012701 0.101441 -vn -2.481408 0.003219 -1.835734 -v 0.040009 -0.012675 0.101548 -vn -2.750397 0.002998 -1.338496 -v 0.039974 -0.012663 0.101606 -vn -2.960149 0.000410 -0.747001 -v 0.039928 -0.012639 0.101731 -vn 0.289512 0.013634 -3.175348 -v 0.040501 -0.012777 0.101317 -vn 1.354424 -0.011352 -2.832913 -v 0.040703 -0.012815 0.101378 -vn 1.957207 -0.009310 -2.392892 -v 0.040786 -0.012833 0.101434 -vn 2.378687 0.012560 -1.971933 -v 0.040866 -0.012853 0.101513 -vn 2.689260 0.010941 -1.488362 -v 0.040917 -0.012869 0.101588 -vn 2.933079 -0.006141 -0.884538 -v 0.040964 -0.012891 0.101700 -vn 3.072335 -0.008165 -0.333769 -v 0.040980 -0.012905 0.101780 -vn 3.078016 0.015810 0.269402 -v 0.040981 -0.012929 0.101911 -vn 2.960639 0.011593 0.818914 -v 0.040969 -0.012942 0.101983 -vn 2.709575 -0.003772 1.433083 -v 0.040917 -0.012967 0.102112 -vn 2.419465 -0.007463 1.921579 -v 0.040882 -0.012978 0.102166 -vn 2.001905 0.009091 2.365066 -v 0.040779 -0.013005 0.102272 -vn 1.588552 -0.011224 2.680659 -v 0.040743 -0.013013 0.102297 -vn 0.992725 -0.013636 2.933678 -v 0.040590 -0.013043 0.102367 -vn 0.405505 -0.003654 3.060765 -v 0.040555 -0.013049 0.102375 -vn -0.461153 -0.006748 3.135157 -v 0.040379 -0.013081 0.102380 -vn -1.535083 -0.009222 2.805932 -v 0.040180 -0.013119 0.102312 -vn -2.054206 0.008749 2.340396 -v 0.040089 -0.013139 0.102244 -vn -2.458961 0.006769 1.825650 -v 0.040022 -0.013157 0.102171 -vn -2.796302 0.013800 1.334480 -v 0.039968 -0.013175 0.102082 -vn -3.083020 0.008299 0.688133 -v 0.039931 -0.013194 0.101981 -vn -1.461012 -0.024375 -2.713682 -v 0.040180 -0.010917 0.101388 -vn -1.975094 0.002625 -2.354582 -v 0.040124 -0.010905 0.101426 -vn -2.360070 0.000027 -1.950920 -v 0.040022 -0.010879 0.101529 -vn -2.704626 0.024694 -1.466108 -v 0.039994 -0.010871 0.101571 -vn -3.108577 0.022990 -0.787881 -v 0.039931 -0.010842 0.101719 -vn -3.171772 -0.028637 -0.075026 -v 0.039915 -0.010818 0.101850 -vn -0.238524 0.001076 3.083166 -v 0.040390 -0.009478 0.102382 -vn -0.800953 0.005109 2.996016 -v 0.040328 -0.009490 0.102371 -vn -1.274141 -0.008506 2.785357 -v 0.040202 -0.009514 0.102324 -vn -1.701639 0.002874 2.537072 -v 0.040176 -0.009519 0.102310 -vn -2.163934 0.005651 2.150590 -v 0.040052 -0.009548 0.102207 -vn -2.476029 -0.006378 1.757220 -v 0.040027 -0.009555 0.102178 -vn -2.907012 -0.015423 1.153321 -v 0.039957 -0.009580 0.102058 -vn -3.136186 -0.010603 0.228821 -v 0.039915 -0.009614 0.101871 -vn -3.068904 0.008041 -0.457314 -v 0.039922 -0.009634 0.101761 -vn -2.916048 0.009116 -0.943250 -v 0.039938 -0.009646 0.101696 -vn -2.668447 0.001150 -1.518134 -v 0.039992 -0.009670 0.101574 -vn -2.396284 -0.010629 -1.933607 -v 0.040024 -0.009680 0.101526 -vn -1.985368 -0.005420 -2.333220 -v 0.040120 -0.009704 0.101429 -vn -1.570624 -0.015740 -2.669759 -v 0.040154 -0.009712 0.101405 -vn -1.057960 0.009190 -2.920976 -v 0.040296 -0.009740 0.101338 -vn 0.303062 0.011316 -3.127116 -v 0.040506 -0.009778 0.101318 -vn -0.532065 0.007180 -3.030272 -v 0.040329 -0.009746 0.101329 -vn 2.833355 0.037740 -1.374900 -v 0.040939 -0.009878 0.101633 -vn 2.362584 0.002622 -1.980642 -v 0.040832 -0.009844 0.101475 -vn 1.951344 -0.006646 -2.366643 -v 0.040816 -0.009840 0.101459 -vn 1.506023 -0.013556 -2.696075 -v 0.040689 -0.009812 0.101371 -vn 0.980310 0.008613 -2.913000 -v 0.040641 -0.009803 0.101350 -vn 3.005297 0.024995 -0.783555 -v 0.040968 -0.009894 0.101715 -vn 3.111021 -0.044536 -0.299854 -v 0.040983 -0.009910 0.101805 -vn 3.096560 -0.022776 -0.025048 -v 0.040985 -0.009917 0.101846 -vn 3.058979 0.009342 0.415981 -v 0.040980 -0.009930 0.101920 -vn 2.941410 0.027139 0.775593 -v 0.040965 -0.009944 0.101995 -vn 2.806666 0.005943 1.196446 -v 0.040949 -0.009953 0.102043 -vn 2.581144 -0.004656 1.648494 -v 0.040890 -0.009976 0.102155 -vn 2.393285 -0.004923 1.820743 -v 0.040877 -0.009980 0.102173 -vn 2.179344 -0.014009 2.128812 -v 0.040846 -0.009988 0.102209 -vn 1.816269 -0.006871 2.499668 -v 0.040754 -0.010010 0.102290 -vn 1.340449 0.000999 2.731660 -v 0.040688 -0.010024 0.102329 -vn 0.883708 0.003440 2.880820 -v 0.040594 -0.010042 0.102365 -vn 0.597783 -0.000133 2.937976 -v 0.040563 -0.010047 0.102373 -vn 0.207459 0.006691 3.046161 -v 0.040496 -0.010060 0.102383 -vn -0.260821 0.008568 3.068073 -v 0.040404 -0.010076 0.102383 -vn -0.827685 -0.008038 2.947110 -v 0.040302 -0.010094 0.102364 -vn -1.167473 -0.000484 2.804099 -v 0.040233 -0.010108 0.102339 -vn -1.461417 0.014637 2.637257 -v 0.040202 -0.010114 0.102324 -vn -1.858845 0.022561 2.433094 -v 0.040125 -0.010130 0.102275 -vn -2.555445 0.003836 1.619685 -v 0.039995 -0.010165 0.102131 -vn -2.297861 -0.001340 1.967923 -v 0.040049 -0.010149 0.102204 -vn -2.102879 0.022134 2.197991 -v 0.040075 -0.010142 0.102232 -vn -2.761880 -0.011334 1.325289 -v 0.039971 -0.010174 0.102088 -vn -2.886940 -0.007236 1.054914 -v 0.039948 -0.010184 0.102034 -vn -2.956422 -0.013403 0.600471 -v 0.039923 -0.010201 0.101944 -vn -3.007955 -0.000214 0.282735 -v 0.039918 -0.010208 0.101905 -vn -3.035244 0.008397 -0.057122 -v 0.039915 -0.010218 0.101847 -vn -2.973110 0.002660 -0.505364 -v 0.039926 -0.010237 0.101745 -vn -2.914973 -0.005068 -0.747706 -v 0.039929 -0.010240 0.101728 -vn -2.851459 -0.001678 -1.158783 -v 0.039950 -0.010253 0.101659 -vn -2.558193 0.011513 -1.807051 -v 0.040005 -0.010274 0.101553 -vn -1.900016 -0.003469 -2.523898 -v 0.040126 -0.010306 0.101424 -vn -1.107336 -0.000740 -2.880108 -v 0.040296 -0.010340 0.101338 -vn -0.542118 -0.011519 -3.065628 -v 0.040317 -0.010344 0.101332 -vn -0.083160 0.009523 -3.118237 -v 0.040472 -0.010372 0.101315 -vn 0.507562 0.001780 -3.019260 -v 0.040513 -0.010379 0.101319 -vn 1.059877 0.003594 -2.877823 -v 0.040658 -0.010406 0.101357 -vn 1.542569 -0.013457 -2.636041 -v 0.040702 -0.010415 0.101378 -vn 2.001937 -0.009992 -2.355145 -v 0.040808 -0.010438 0.101452 -vn 2.469364 -0.036347 -1.948555 -v 0.040857 -0.010450 0.101503 -vn 2.756324 -0.034033 -1.531323 -v 0.040924 -0.010472 0.101603 -vn 2.928222 -0.019413 -0.971972 -v 0.040959 -0.010488 0.101686 -vn 3.019909 -0.020123 -0.506576 -v 0.040979 -0.010504 0.101771 -vn 3.037388 -0.012688 -0.255449 -v 0.040983 -0.010509 0.101798 -vn 3.042162 -0.019558 0.194478 -v 0.040984 -0.010524 0.101884 -vn 2.978077 -0.007044 0.559492 -v 0.040973 -0.010538 0.101962 -vn 2.878952 0.002566 0.856766 -v 0.040966 -0.010543 0.101992 -vn 2.759144 0.009162 1.257018 -v 0.040935 -0.010559 0.102076 -vn 2.592186 0.005731 1.576421 -v 0.040908 -0.010570 0.102127 -vn 2.439973 0.006699 1.849762 -v 0.040881 -0.010578 0.102167 -vn 2.135310 -0.007289 2.165612 -v 0.040819 -0.010595 0.102238 -vn 1.882710 0.001763 2.387445 -v 0.040782 -0.010604 0.102270 -vn 1.600687 0.019070 2.577406 -v 0.040740 -0.010613 0.102299 -vn 1.197226 0.010195 2.794832 -v 0.040650 -0.010631 0.102346 -vn 0.838528 0.022624 3.018504 -v 0.040627 -0.010636 0.102355 -vn 0.405419 0.044820 3.103972 -v 0.040483 -0.010662 0.102384 -vn 0.046108 0.006502 2.975229 -v 0.040458 -0.010666 0.102385 -vn -0.246173 0.008951 3.056399 -v 0.040438 -0.010670 0.102385 -vn -0.717453 0.020298 2.969132 -v 0.040298 -0.010695 0.102363 -vn -1.227816 0.001687 2.808023 -v 0.040264 -0.010702 0.102352 -vn -1.719957 0.006686 2.526260 -v 0.040123 -0.010731 0.102274 -vn -2.143865 -0.016145 2.188311 -v 0.040100 -0.010736 0.102254 -vn -2.495861 -0.006690 1.792051 -v 0.039995 -0.010765 0.102132 -vn -2.570698 0.000654 1.468079 -v 0.039987 -0.010768 0.102118 -vn -2.868618 -0.023823 1.193623 -v 0.039972 -0.010773 0.102091 -vn -3.104467 -0.042657 0.641715 -v 0.039922 -0.010802 0.101938 -vn 0.335304 0.015377 3.088922 -v 0.040526 -0.009454 0.102379 -vn 0.594763 4.006982 4.279760 -v 0.040569 -0.009702 0.102835 -vn 0.922401 0.018291 2.940815 -v 0.040588 -0.009443 0.102367 -vn 1.058684 4.899955 3.582292 -v 0.040793 -0.009650 0.102725 -vn 1.772819 0.503058 3.242753 -v 0.040715 -0.009418 0.102315 -vn 1.593800 4.884593 3.421780 -v 0.040900 -0.009620 0.102641 -vn 0.597252 5.846858 1.469184 -v 0.040755 -0.009410 0.102290 -vn 2.231949 4.845278 3.039300 -v 0.040983 -0.009593 0.102554 -vn 0.828926 5.842710 1.370543 -v 0.040901 -0.009410 0.102221 -vn 2.730801 4.903708 2.549171 -v 0.041114 -0.009533 0.102335 -vn 1.031264 5.846489 1.214467 -v 0.040931 -0.009410 0.102200 -vn 3.052147 4.950696 2.070200 -v 0.041143 -0.009511 0.102250 -vn 1.384427 5.815099 0.874851 -v 0.041074 -0.009410 0.102044 -vn 3.425067 4.905872 1.432441 -v 0.041169 -0.009473 0.102104 -vn 2.275301 5.278043 0.304083 -v 0.041150 -0.009410 0.101875 -vn 0.772530 0.357378 1.233418 -v 0.040607 -0.009410 0.102425 -vn 3.438972 -0.474458 0.761423 -v 0.041394 -0.009702 0.102159 -vn 3.533388 -0.481878 0.131977 -v 0.041426 -0.009686 0.101914 -vn 3.570887 -0.494712 -0.386066 -v 0.041423 -0.009682 0.101850 -vn 3.337301 -0.440838 -0.979893 -v 0.041394 -0.009670 0.101673 -vn 3.169410 -0.469519 -1.568365 -v 0.041307 -0.009655 0.101453 -vn 2.904698 -0.502584 -2.081768 -v 0.041264 -0.009650 0.101380 -vn 2.510036 -0.457045 -2.426601 -v 0.041153 -0.009638 0.101242 -vn 2.168368 -0.417135 -2.745649 -v 0.041080 -0.009631 0.101176 -vn 1.667088 -0.467372 -3.111067 -v 0.040951 -0.009621 0.101089 -vn 1.081403 -0.460162 -3.397644 -v 0.040771 -0.009607 0.101013 -vn 0.580847 -0.416819 -3.444575 -v 0.040707 -0.009603 0.100996 -vn -0.109414 -0.475781 -3.534073 -v 0.040450 -0.009585 0.100975 -vn -0.668656 -0.488754 -3.532549 -v 0.040350 -0.009578 0.100987 -vn -1.021776 -0.483721 -3.398547 -v 0.040292 -0.009573 0.101000 -vn -1.635831 -0.468599 -3.108387 -v 0.040118 -0.009560 0.101067 -vn -2.154024 -0.498851 -2.861040 -v 0.039997 -0.009549 0.101144 -vn -2.588256 -0.462472 -2.429394 -v 0.039913 -0.009541 0.101217 -vn -3.056983 -0.472898 -1.694470 -v 0.039775 -0.009524 0.101395 -vn -3.375851 -0.444715 -0.707897 -v 0.039689 -0.009506 0.101614 -vn -3.459864 -0.443818 0.375282 -v 0.039675 -0.009486 0.101861 -vn -3.233025 -0.434362 1.286628 -v 0.039724 -0.009469 0.102072 -vn -2.798387 -0.191778 1.539908 -v 0.039773 -0.009459 0.102173 -vn -2.697370 -0.445504 2.274494 -v 0.039839 -0.009450 0.102269 -vn -2.152046 -0.263095 2.546010 -v 0.039923 -0.009440 0.102356 -vn -1.835507 -0.496215 3.081249 -v 0.040014 -0.009430 0.102423 -vn -0.931415 0.084671 2.606022 -v 0.040154 -0.009416 0.102491 -vn -0.087482 0.358332 1.437472 -v 0.040228 -0.009410 0.102514 -vn 0.349598 0.344076 1.378316 -v 0.040443 -0.009410 0.102495 -vn -1.376538 5.234375 1.883195 -v 0.040028 -0.009410 0.102408 -vn -1.887503 5.303436 1.256542 -v 0.039872 -0.009410 0.102245 -vn -2.265476 5.207341 0.628102 -v 0.039776 -0.009410 0.102040 -vn -2.360094 5.196556 -0.132297 -v 0.039751 -0.009410 0.101814 -vn -2.203805 5.233590 -0.767299 -v 0.039790 -0.009410 0.101618 -vn -2.054657 5.241632 -1.103645 -v 0.039844 -0.009410 0.101500 -vn -1.769102 5.251340 -1.502294 -v 0.039898 -0.009410 0.101419 -vn -1.278724 5.242805 -1.935918 -v 0.040064 -0.009410 0.101266 -vn -0.619094 5.253615 -2.228950 -v 0.040271 -0.009410 0.101173 -vn 0.123536 5.218515 -2.331570 -v 0.040450 -0.009410 0.101150 -vn 1.170444 5.190416 -2.027137 -v 0.040800 -0.009410 0.101244 -vn 2.041869 5.180048 -1.158940 -v 0.041056 -0.009410 0.101500 -vn 2.293401 5.261351 -0.238231 -v 0.041150 -0.009410 0.101850 -vn 4.520943 1.210847 -3.903136 -v 0.041776 -0.041610 0.079924 -vn 3.946141 0.252483 -4.837392 -v 0.041717 -0.041610 0.079868 -vn 3.892035 1.473944 -4.456016 -v 0.041716 -0.041581 0.079869 -vn 2.739941 1.467037 -5.245535 -v 0.041275 -0.041581 0.079569 -vn -0.489147 6.145079 -0.779725 -v 0.039680 -0.041410 0.079762 -vn -0.259321 6.187840 -0.721058 -v 0.039797 -0.041410 0.079707 -vn -1.096459 5.322635 -2.632495 -v 0.039762 -0.041431 0.079625 -vn 0.906637 6.119476 -0.422598 -v 0.042017 -0.041410 0.080657 -vn 0.753287 6.186736 -0.160929 -v 0.042070 -0.041410 0.080823 -vn 2.760845 5.322822 -0.710761 -v 0.042157 -0.041431 0.080800 -vn 2.845345 5.323647 0.088843 -v 0.042214 -0.041431 0.081299 -vn 0.796622 6.179489 -0.066912 -v 0.042125 -0.041410 0.081250 -vn 0.757581 6.189259 0.072617 -v 0.042124 -0.041410 0.081297 -vn 0.677288 6.184790 -0.381483 -v 0.041884 -0.041410 0.080384 -vn 2.445662 5.323546 -1.459225 -v 0.041961 -0.041431 0.080338 -vn 0.687582 6.154078 -0.566788 -v 0.041726 -0.041410 0.080165 -vn 1.931398 5.320553 -2.112612 -v 0.041643 -0.041431 0.079949 -vn 0.505698 6.190104 -0.564451 -v 0.041582 -0.041410 0.080015 -vn 0.498448 6.154268 -0.737810 -v 0.041357 -0.041410 0.079841 -vn 1.247593 5.321725 -2.569782 -v 0.041228 -0.041431 0.079666 -vn 0.314732 6.188373 -0.696433 -v 0.041188 -0.041410 0.079746 -vn 0.234896 6.172729 -0.790917 -v 0.040819 -0.041410 0.079616 -vn 0.467766 5.322240 -2.814890 -v 0.040750 -0.041431 0.079511 -vn 0.083032 6.188228 -0.760412 -v 0.040735 -0.041410 0.079599 -vn -0.317574 5.323431 -2.829930 -v 0.040248 -0.041431 0.079497 -vn -0.035201 6.188869 -0.761813 -v 0.040258 -0.041410 0.079586 -vn -0.177952 6.179662 -0.778660 -v 0.040215 -0.041410 0.079591 -vn -0.470491 6.185482 -0.615486 -v 0.039389 -0.041410 0.079954 -vn -1.791356 5.323670 -2.213291 -v 0.039332 -0.041431 0.079884 -vn -0.659984 6.153273 -0.602744 -v 0.039203 -0.041410 0.080132 -vn -2.365347 5.321597 -1.602560 -v 0.038993 -0.041431 0.080255 -vn -0.645291 6.187338 -0.416753 -v 0.039066 -0.041410 0.080305 -vn -0.753638 6.171175 -0.349694 -v 0.038889 -0.041410 0.080644 -vn -2.719665 5.322293 -0.863060 -v 0.038771 -0.041431 0.080706 -vn -0.741049 6.188048 -0.192160 -v 0.038857 -0.041410 0.080733 -vn -2.845378 5.323596 -0.088809 -v 0.038686 -0.041431 0.081201 -vn -0.757551 6.189266 -0.072615 -v 0.038776 -0.041410 0.081203 -vn -6.220053 0.243722 -0.560068 -v 0.038576 -0.041610 0.081198 -vn -5.908017 1.475640 -0.302175 -v 0.038578 -0.041581 0.081198 -vn -6.019386 0.251137 -1.632310 -v 0.038666 -0.041610 0.080672 -vn -5.672003 1.460601 -1.689732 -v 0.038668 -0.041581 0.080672 -vn -5.290768 1.477528 -2.455416 -v 0.038718 -0.041610 0.080532 -vn -4.897302 1.447626 -3.326662 -v 0.038903 -0.041581 0.080194 -vn -3.646060 1.450734 -4.661939 -v 0.039264 -0.041581 0.079801 -vn -4.187052 1.598816 -3.941257 -v 0.039124 -0.041610 0.079924 -vn -5.156902 0.235700 -3.497673 -v 0.038902 -0.041610 0.080193 -vn 1.042815 1.447875 -5.827662 -v 0.040768 -0.041581 0.079404 -vn 0.101572 1.668442 -5.707230 -v 0.040450 -0.041610 0.079375 -vn -0.799875 1.443316 -5.863953 -v 0.040235 -0.041581 0.079389 -vn -0.959731 0.248955 -6.155958 -v 0.040235 -0.041610 0.079387 -vn -2.304058 1.357940 -5.443232 -v 0.039720 -0.041581 0.079525 -vn -2.413825 0.271143 -5.705098 -v 0.039719 -0.041610 0.079523 -vn -3.730182 0.240146 -4.993888 -v 0.039262 -0.041610 0.079799 -vn 3.042310 0.236100 -5.447323 -v 0.041276 -0.041610 0.079567 -vn 1.966009 1.318366 -5.577297 -v 0.041168 -0.041610 0.079518 -vn 1.145272 0.230716 -6.124740 -v 0.040769 -0.041610 0.079402 -vn 5.245270 0.263772 -3.354726 -v 0.042055 -0.041610 0.080281 -vn 5.013717 1.425965 -3.143328 -v 0.042053 -0.041581 0.080282 -vn 5.234227 1.704327 -2.206396 -v 0.042182 -0.041610 0.080532 -vn 5.746013 1.447259 -1.422337 -v 0.042261 -0.041581 0.080773 -vn 6.070911 0.236198 -1.405615 -v 0.042263 -0.041610 0.080772 -vn 6.117671 0.794072 -0.449345 -v 0.042325 -0.041610 0.081250 -vn 5.908059 1.475929 0.302212 -v 0.042322 -0.041581 0.081302 -vn 6.220000 0.244112 0.560084 -v 0.042324 -0.041610 0.081302 -vn 4.875359 3.420802 0.136405 -v 0.042287 -0.041494 0.081301 -vn 4.716314 3.420821 -1.242655 -v 0.042227 -0.041494 0.080782 -vn 4.175207 3.420798 -2.521063 -v 0.042023 -0.041494 0.080300 -vn 3.295795 3.420747 -3.595224 -v 0.041692 -0.041494 0.079895 -vn 2.149409 3.420809 -4.378136 -v 0.041260 -0.041494 0.079600 -vn 0.828870 3.420791 -4.806336 -v 0.040762 -0.041494 0.079439 -vn -0.558777 3.420869 -4.845119 -v 0.040239 -0.041494 0.079425 -vn -1.901179 3.420852 -4.491442 -v 0.039734 -0.041494 0.079558 -vn -3.089599 3.420767 -3.773911 -v 0.039286 -0.041494 0.079828 -vn -4.027712 3.420825 -2.750605 -v 0.038933 -0.041494 0.080214 -vn -4.639457 3.420748 -1.504445 -v 0.038702 -0.041494 0.080683 -vn -4.875380 3.420862 -0.136439 -v 0.038613 -0.041494 0.081199 -vn -5.503525 -0.940498 2.593523 -v 0.038718 -0.042410 0.081968 -vn -5.896132 -0.776649 1.656659 -v 0.038673 -0.042410 0.081849 -vn -4.986579 -2.804518 1.638806 -v 0.038719 -0.042600 0.081834 -vn 1.176913 -6.040430 0.691875 -v 0.041763 -0.042807 0.082022 -vn 0.179304 -6.276206 0.105408 -v 0.041722 -0.042810 0.081998 -vn 0.201717 -6.276206 0.050758 -v 0.041881 -0.042810 0.081609 -vn 0.934320 -6.040426 0.995439 -v 0.041493 -0.042807 0.082361 -vn 0.142350 -6.276205 0.151659 -v 0.041459 -0.042810 0.082325 -vn 0.247828 -6.040424 1.342536 -v 0.040727 -0.042807 0.082748 -vn 0.037752 -6.276207 0.204520 -v 0.040718 -0.042810 0.082700 -vn 0.093845 -6.276207 0.185605 -v 0.041116 -0.042810 0.082566 -vn -0.021397 -6.276206 0.206891 -v 0.040298 -0.042810 0.082717 -vn -0.140454 -6.040423 1.357993 -v 0.040293 -0.042807 0.082765 -vn 0.628480 -4.912592 3.404653 -v 0.040758 -0.042742 0.082921 -vn -1.118279 -6.040421 0.783147 -v 0.039202 -0.042807 0.082124 -vn -0.170368 -6.276206 0.119310 -v 0.039242 -0.042810 0.082096 -vn -0.129855 -6.276205 0.162484 -v 0.039529 -0.042810 0.082402 -vn -1.293603 -6.040432 0.436359 -v 0.039006 -0.042807 0.081737 -vn -0.197093 -6.276206 0.066481 -v 0.039052 -0.042810 0.081721 -vn -1.369957 -6.040127 0.060516 -v 0.038928 -0.042807 0.081311 -vn -0.199900 -6.276723 0.020996 -v 0.038976 -0.042810 0.081309 -vn 1.324170 -6.040427 0.332283 -v 0.041928 -0.042807 0.081621 -vn 1.369676 -6.040107 -0.059491 -v 0.041972 -0.042807 0.081189 -vn 3.459393 -4.912661 -0.137550 -v 0.042147 -0.042742 0.081183 -vn 2.427380 -2.816501 4.654172 -v 0.041274 -0.042600 0.082881 -vn 1.562218 -4.912617 3.089665 -v 0.041217 -0.042742 0.082766 -vn 0.616026 -6.040430 1.218325 -v 0.041137 -0.042807 0.082610 -vn -1.311958 -4.912638 3.203922 -v 0.039806 -0.042742 0.082822 -vn -2.161491 -4.912613 2.704528 -v 0.039389 -0.042742 0.082577 -vn -0.852330 -6.040431 1.066471 -v 0.039499 -0.042807 0.082440 -vn -3.221552 -2.814889 4.145715 -v 0.039309 -0.042600 0.082677 -vn -1.992938 -2.746201 4.866894 -v 0.039758 -0.042600 0.082941 -vn -0.588461 -2.807204 5.216050 -v 0.040262 -0.042600 0.083067 -vn 5.244498 -2.801523 -0.253587 -v 0.042276 -0.042600 0.081177 -vn 6.101415 -0.768178 -0.602140 -v 0.042324 -0.042410 0.081175 -vn 6.112463 -0.829718 0.325808 -v 0.042325 -0.042410 0.081250 -vn 3.358031 -4.912639 0.842641 -v 0.042098 -0.042742 0.081663 -vn 5.093778 -2.764903 1.302415 -v 0.042222 -0.042600 0.081695 -vn 5.923247 -0.818661 1.410993 -v 0.042269 -0.042410 0.081706 -vn 4.510594 -2.816098 2.685483 -v 0.042025 -0.042600 0.082176 -vn 2.984608 -4.912628 1.754571 -v 0.041914 -0.042742 0.082111 -vn 0.233626 -6.274386 0.022914 -v 0.041925 -0.042810 0.081250 -vn 0.199870 -6.276725 -0.020994 -v 0.041924 -0.042810 0.081191 -vn 5.583273 -1.154766 2.182398 -v 0.042182 -0.042410 0.081968 -vn 5.187787 -0.768536 3.235286 -v 0.042066 -0.042410 0.082200 -vn 4.566154 -0.823098 4.083191 -v 0.041776 -0.042410 0.082576 -vn 2.369373 -4.912654 2.524358 -v 0.041613 -0.042742 0.082489 -vn 3.566504 -2.794291 3.854849 -v 0.041700 -0.042600 0.082582 -vn 3.920078 -0.778973 4.716687 -v 0.041733 -0.042410 0.082617 -vn 3.031482 -0.762727 5.319033 -v 0.041296 -0.042410 0.082923 -vn 2.123267 -0.868476 5.723113 -v 0.041168 -0.042410 0.082982 -vn 0.912562 -2.780867 5.176124 -v 0.040782 -0.042600 0.083047 -vn -0.356148 -4.912684 3.443748 -v 0.040275 -0.042742 0.082940 -vn -0.517337 -6.040430 1.263391 -v 0.039873 -0.042807 0.082660 -vn -0.078814 -6.276207 0.192466 -v 0.039891 -0.042810 0.082615 -vn 1.102710 -0.797288 5.994444 -v 0.040790 -0.042410 0.083094 -vn 0.208660 -1.046754 6.038594 -v 0.040450 -0.042410 0.083125 -vn -0.886999 -0.773758 6.050681 -v 0.040257 -0.042410 0.083115 -vn -2.296866 -0.786949 5.612344 -v 0.039739 -0.042410 0.082985 -vn -3.615580 -0.765318 4.929561 -v 0.039279 -0.042410 0.082715 -vn -4.387053 -0.909519 4.228899 -v 0.039124 -0.042410 0.082576 -vn -2.835869 -4.912641 1.986026 -v 0.039058 -0.042742 0.082225 -vn -4.336405 -2.795625 2.966369 -v 0.038953 -0.042600 0.082298 -vn -5.050172 -0.791314 3.425022 -v 0.038914 -0.042410 0.082326 -vn -3.280501 -4.912640 1.106604 -v 0.038840 -0.042742 0.081793 -vn -3.459293 -4.912696 0.137552 -v 0.038753 -0.042742 0.081317 -vn -5.244494 -2.801496 0.253606 -v 0.038624 -0.042600 0.081323 -vn -6.101405 -0.768164 0.601998 -v 0.038576 -0.042410 0.081324 -vn -1.747885 -2.525898 4.227557 -v 0.039986 -0.009863 0.082136 -vn -1.267479 -2.536558 4.367491 -v 0.040137 -0.009848 0.082200 -vn -2.566285 2.608288 3.711278 -v 0.039933 -0.009770 0.082106 -vn 0.081466 2.630648 -4.550663 -v 0.040450 -0.010018 0.080250 -vn -0.460336 -2.634834 -4.521346 -v 0.040450 -0.010117 0.080250 -vn -0.622996 2.588480 -4.533431 -v 0.040211 -0.009995 0.080279 -vn -1.441439 -2.620011 -4.261356 -v 0.040182 -0.010091 0.080287 -vn -1.296567 2.606376 -4.365781 -v 0.040163 -0.009990 0.080292 -vn -2.455918 -2.615766 -3.821454 -v 0.039933 -0.010065 0.080394 -vn -1.885255 2.566787 -4.119761 -v 0.039959 -0.009969 0.080379 -vn -2.963525 -2.648105 -3.485219 -v 0.039845 -0.010055 0.080454 -vn -2.596031 2.656174 -3.751782 -v 0.039833 -0.009955 0.080463 -vn -3.355500 -2.704823 -3.105153 -v 0.039743 -0.010042 0.080543 -vn -3.095328 2.664131 -3.327362 -v 0.039743 -0.009943 0.080543 -vn -3.618350 -2.625148 -2.738349 -v 0.039717 -0.010039 0.080570 -vn -3.731221 2.570644 -2.544086 -v 0.039594 -0.009920 0.080733 -vn -4.062278 -2.557609 -2.000956 -v 0.039579 -0.010017 0.080759 -vn -4.274920 2.627834 -1.432570 -v 0.039487 -0.009894 0.080981 -vn -4.271136 -2.395870 -1.531009 -v 0.039516 -0.010002 0.080893 -vn -4.504620 -2.573132 -0.690323 -v 0.039479 -0.009991 0.081011 -vn -4.487179 2.567191 -0.255255 -v 0.039450 -0.009868 0.081250 -vn -4.510026 -2.560148 0.248020 -v 0.039450 -0.009968 0.081250 -vn -4.524740 2.638854 0.615308 -v 0.039479 -0.009845 0.081489 -vn -4.398128 -2.632728 1.192149 -v 0.039480 -0.009944 0.081492 -vn -4.423705 2.687443 1.201353 -v 0.039491 -0.009841 0.081532 -vn -4.163058 -2.577355 1.899534 -v 0.039511 -0.009934 0.081594 -vn -4.104878 2.630893 1.959363 -v 0.039579 -0.009819 0.081741 -vn -3.817599 -2.627550 2.472567 -v 0.039578 -0.009918 0.081739 -vn -3.786487 2.547639 2.564239 -v 0.039660 -0.009805 0.081863 -vn -3.085653 -2.626149 3.306266 -v 0.039717 -0.009895 0.081930 -vn -3.245643 2.520417 3.171475 -v 0.039743 -0.009793 0.081957 -vn -2.365106 -2.611766 3.880921 -v 0.039928 -0.009870 0.082103 -vn -0.031534 -2.633360 4.584064 -v 0.040406 -0.009821 0.082249 -vn 0.395959 -2.701994 4.554152 -v 0.040450 -0.009816 0.082250 -vn -0.356400 2.694259 4.524592 -v 0.040450 -0.009718 0.082250 -vn -0.429129 -2.559674 4.552665 -v 0.040302 -0.009831 0.082239 -vn -1.154840 2.636148 4.429635 -v 0.040222 -0.009740 0.082224 -vn -1.646849 2.644020 4.247354 -v 0.040182 -0.009744 0.082213 -vn -4.523555 2.559048 -0.220223 -v 0.039450 -0.020668 0.081250 -vn -4.404371 2.630700 -1.155188 -v 0.039487 -0.020684 0.080982 -vn -4.501910 -2.643097 -0.698767 -v 0.039482 -0.021026 0.081006 -vn 0.219218 2.620039 -4.543316 -v 0.040450 -0.020762 0.080250 -vn -0.461450 2.664988 -4.555357 -v 0.040302 -0.020753 0.080261 -vn -1.128012 3.553568 -2.860190 -v 0.040120 -0.041410 0.080306 -vn -3.225414 2.858523 -2.235905 -v 0.039625 -0.021078 0.080684 -vn -4.892174 0.014240 -3.930512 -v 0.039664 -0.021082 0.080631 -vn -2.249685 3.633134 -2.054551 -v 0.039712 -0.041410 0.080575 -vn -4.398144 -2.620884 -1.314653 -v 0.039506 -0.021037 0.080925 -vn -4.207239 2.639899 -1.786103 -v 0.039504 -0.020688 0.080925 -vn -3.834052 2.604050 -2.423925 -v 0.039594 -0.020701 0.080733 -vn -3.573793 -2.847267 -1.861857 -v 0.039629 -0.021074 0.080680 -vn -3.432071 2.666807 -3.026754 -v 0.039690 -0.020710 0.080600 -vn -2.940061 2.615181 -3.464055 -v 0.039743 -0.020715 0.080543 -vn -2.077753 2.546941 -3.974977 -v 0.039959 -0.020731 0.080379 -vn -1.127909 2.617787 -4.399810 -v 0.040211 -0.020747 0.080279 -vn -4.388221 -2.605039 0.071663 -v 0.039452 -0.021001 0.081193 -vn -4.349449 -2.664372 1.079503 -v 0.039471 -0.020966 0.081456 -vn -4.446853 2.600677 0.796034 -v 0.039479 -0.020645 0.081489 -vn -4.256223 -2.661433 1.616665 -v 0.039480 -0.020961 0.081494 -vn -4.281597 2.637762 1.613919 -v 0.039548 -0.020626 0.081683 -vn -3.766783 -2.592274 2.420021 -v 0.039564 -0.020930 0.081712 -vn -0.683066 -2.594394 4.526231 -v 0.040176 -0.020823 0.082212 -vn 0.268743 -2.553372 4.504362 -v 0.040450 -0.020786 0.082250 -vn -0.330537 2.566858 4.502433 -v 0.040450 -0.020519 0.082250 -vn -1.271425 2.611497 4.351150 -v 0.040182 -0.020545 0.082213 -vn -1.974443 2.634014 4.124780 -v 0.040084 -0.020554 0.082181 -vn -1.313269 -2.618897 4.389411 -v 0.040119 -0.020831 0.082195 -vn -2.576447 2.604758 3.756723 -v 0.039933 -0.020570 0.082106 -vn -2.113750 -2.576987 3.960640 -v 0.039929 -0.020859 0.082105 -vn -3.161969 2.639001 3.319803 -v 0.039775 -0.020589 0.081988 -vn -3.047164 -2.547307 3.270298 -v 0.039724 -0.020894 0.081937 -vn -3.566849 2.615229 2.845206 -v 0.039743 -0.020593 0.081957 -vn -3.959293 2.587679 2.231194 -v 0.039579 -0.020619 0.081741 -vn -4.360341 2.713704 0.630529 -v 0.039473 -0.021030 0.081462 -vn -4.527111 2.671333 0.027137 -v 0.039450 -0.021041 0.081264 -vn -2.954368 3.631941 0.745115 -v 0.039480 -0.041410 0.081494 -vn -4.235570 2.787877 -0.575812 -v 0.039452 -0.021046 0.081192 -vn -2.954027 3.633078 -0.745758 -v 0.039480 -0.041410 0.081006 -vn -4.303549 2.700453 -1.158908 -v 0.039480 -0.021057 0.081006 -vn -4.132346 2.647690 -1.725604 -v 0.039504 -0.021062 0.080926 -vn -4.374792 2.646156 1.344269 -v 0.039500 -0.021023 0.081562 -vn -2.248382 3.633838 2.055832 -v 0.039712 -0.041410 0.081925 -vn -3.969556 2.613967 2.032945 -v 0.039565 -0.021014 0.081716 -vn -3.196134 2.616767 2.925359 -v 0.039723 -0.020998 0.081936 -vn -1.128742 3.555734 2.859584 -v 0.040120 -0.041410 0.082194 -vn -2.483182 2.522973 3.780942 -v 0.039933 -0.020982 0.082106 -vn -1.345616 2.529407 4.319367 -v 0.040182 -0.020965 0.082213 -vn -0.179773 2.547395 4.516856 -v 0.040450 -0.020949 0.082250 -vn 0.975440 2.547409 4.414297 -v 0.040689 -0.020935 0.082221 -vn 1.128600 3.555071 2.859712 -v 0.040780 -0.041410 0.082194 -vn 2.014458 2.573372 4.052139 -v 0.040941 -0.020919 0.082121 -vn 2.954708 3.630764 0.744572 -v 0.041420 -0.041410 0.081494 -vn 3.780958 2.556697 2.437541 -v 0.041306 -0.020888 0.081767 -vn 2.248311 3.632308 2.056263 -v 0.041188 -0.041410 0.081925 -vn 3.228225 2.628433 3.207022 -v 0.041157 -0.020902 0.081957 -vn 2.720048 2.653010 3.652575 -v 0.041094 -0.020908 0.082015 -vn 2.954721 3.630689 -0.744528 -v 0.041420 -0.041410 0.081006 -vn 4.511282 2.549611 0.181370 -v 0.041450 -0.020855 0.081250 -vn 4.304039 2.533403 1.354967 -v 0.041413 -0.020872 0.081519 -vn 1.128479 3.555284 -2.859740 -v 0.040780 -0.041410 0.080306 -vn 3.303149 2.552475 -3.058524 -v 0.041157 -0.020808 0.080543 -vn 2.248291 3.632242 -2.056310 -v 0.041188 -0.041410 0.080575 -vn 3.995758 2.537352 -2.080594 -v 0.041321 -0.020825 0.080759 -vn 4.406090 2.551466 -0.963932 -v 0.041421 -0.020841 0.081011 -vn 0.938855 2.650930 -4.474463 -v 0.040655 -0.020774 0.080271 -vn 1.587015 2.624321 -4.270710 -v 0.040718 -0.020778 0.080287 -vn 2.431201 2.556465 -3.778337 -v 0.040967 -0.020794 0.080394 -vn -4.520233 -2.600131 0.257920 -v 0.039450 -0.020168 0.081250 -vn -4.444092 2.616127 -1.047066 -v 0.039475 -0.020090 0.081028 -vn -4.511681 -2.660630 -0.590062 -v 0.039480 -0.020199 0.081007 -vn -4.229607 2.676931 -1.679704 -v 0.039487 -0.020094 0.080981 -vn -4.341778 -2.502740 -1.349319 -v 0.039504 -0.020210 0.080926 -vn -4.122442 -2.567534 -1.889649 -v 0.039584 -0.020236 0.080750 -vn -3.746307 2.604295 -2.490826 -v 0.039594 -0.020120 0.080733 -vn -3.752842 -2.581906 -2.607472 -v 0.039690 -0.020261 0.080600 -vn -3.068848 2.658910 -3.350115 -v 0.039743 -0.020143 0.080543 -vn -3.348093 -2.666958 -3.076891 -v 0.039743 -0.020271 0.080543 -vn -2.549802 2.515275 -3.784435 -v 0.039850 -0.020157 0.080450 -vn -2.481377 -2.610977 -3.790286 -v 0.039972 -0.020308 0.080372 -vn 0.104451 2.618035 -4.548646 -v 0.040450 -0.020219 0.080250 -vn -0.356758 -2.596729 -4.550603 -v 0.040450 -0.020374 0.080250 -vn -0.627020 2.668604 -4.543905 -v 0.040211 -0.020195 0.080279 -vn -0.902319 -2.476000 -4.476402 -v 0.040302 -0.020354 0.080261 -vn -1.623873 -2.650443 -4.277866 -v 0.040189 -0.020339 0.080285 -vn -1.964073 2.635335 -4.101190 -v 0.039959 -0.020169 0.080379 -vn -1.386917 2.615910 -4.338500 -v 0.040120 -0.020186 0.080306 -vn -1.010099 2.715988 -4.502954 -v 0.040189 -0.020193 0.080285 -vn -4.042418 2.630135 2.007538 -v 0.039579 -0.020019 0.081741 -vn -4.447210 2.627901 0.985928 -v 0.039479 -0.020045 0.081489 -vn -4.296832 -2.567398 1.475188 -v 0.039487 -0.020142 0.081518 -vn -4.555019 2.475315 0.392164 -v 0.039462 -0.020054 0.081403 -vn -4.528191 2.603225 -0.333156 -v 0.039450 -0.020068 0.081250 -vn -4.081536 -2.473231 2.040499 -v 0.039548 -0.020125 0.081683 -vn -3.662114 -2.578916 2.723404 -v 0.039594 -0.020116 0.081767 -vn -3.401103 2.614777 2.972005 -v 0.039743 -0.019993 0.081957 -vn -1.962186 -2.636407 4.075514 -v 0.039959 -0.020066 0.082121 -vn -2.725490 2.617763 3.661602 -v 0.039933 -0.019970 0.082106 -vn -2.743608 -2.593408 3.664350 -v 0.039775 -0.020088 0.081988 -vn -3.204569 -2.640995 3.255157 -v 0.039743 -0.020092 0.081957 -vn 0.255221 -2.638457 4.542756 -v 0.040450 -0.020017 0.082250 -vn -0.265670 2.643669 4.570674 -v 0.040450 -0.019918 0.082250 -vn -0.487914 -2.553573 4.550657 -v 0.040281 -0.020033 0.082236 -vn -0.678529 2.531170 4.509315 -v 0.040355 -0.019927 0.082246 -vn -0.985298 -2.609654 4.448660 -v 0.040211 -0.020040 0.082221 -vn -1.540734 2.560158 4.285339 -v 0.040182 -0.019944 0.082213 -vn -2.121645 2.548693 4.044906 -v 0.039995 -0.019963 0.082140 -vn -4.316517 2.462850 1.457260 -v 0.039508 -0.019435 0.081586 -vn -4.500866 2.664173 0.705042 -v 0.039479 -0.019445 0.081489 -vn -4.246085 -2.668614 1.596072 -v 0.039487 -0.019541 0.081519 -vn 0.129571 2.613061 -4.535257 -v 0.040450 -0.019618 0.080250 -vn -0.331961 -2.622350 -4.484517 -v 0.040450 -0.019717 0.080250 -vn -0.833095 2.555511 -4.417506 -v 0.040211 -0.019595 0.080279 -vn -1.456424 -2.554494 -4.249193 -v 0.040182 -0.019691 0.080287 -vn -1.800681 2.592078 -4.162922 -v 0.039959 -0.019569 0.080379 -vn -2.435365 -2.661877 -3.840020 -v 0.039933 -0.019665 0.080394 -vn -2.449491 2.687276 -3.853447 -v 0.039884 -0.019560 0.080426 -vn -2.990263 -2.637457 -3.467969 -v 0.039850 -0.019656 0.080450 -vn -2.932685 2.686794 -3.514234 -v 0.039743 -0.019543 0.080543 -vn -3.348886 -2.691614 -3.112730 -v 0.039743 -0.019642 0.080543 -vn -3.319810 2.662812 -3.168300 -v 0.039715 -0.019539 0.080572 -vn -3.611250 -2.672012 -2.782586 -v 0.039712 -0.019638 0.080575 -vn -3.741008 2.657667 -2.597307 -v 0.039594 -0.019520 0.080733 -vn -3.834432 -2.560319 -2.473619 -v 0.039625 -0.019625 0.080685 -vn -4.143785 -2.658064 -1.846023 -v 0.039579 -0.019616 0.080759 -vn -4.137284 2.470066 -1.932158 -v 0.039518 -0.019503 0.080887 -vn -4.431804 -2.581514 -0.794030 -v 0.039479 -0.019590 0.081011 -vn -4.355403 2.618145 -1.336360 -v 0.039487 -0.019494 0.080981 -vn -4.503781 2.560261 -0.253039 -v 0.039450 -0.019468 0.081250 -vn -4.524673 -2.559900 0.204400 -v 0.039450 -0.019567 0.081250 -vn -4.469148 -2.413073 0.783254 -v 0.039462 -0.019553 0.081403 -vn -4.104278 2.556786 1.969181 -v 0.039579 -0.019419 0.081741 -vn -3.746072 -2.600666 2.512483 -v 0.039594 -0.019516 0.081767 -vn -3.711295 2.551226 2.682809 -v 0.039691 -0.019400 0.081902 -vn -2.947992 -2.606891 3.428396 -v 0.039743 -0.019492 0.081957 -vn -3.260068 2.609189 3.197348 -v 0.039743 -0.019393 0.081957 -vn -2.214634 -2.652721 3.989583 -v 0.039959 -0.019467 0.082121 -vn -2.600390 2.548388 3.698184 -v 0.039933 -0.019370 0.082106 -vn -1.671291 -2.526761 4.256669 -v 0.039995 -0.019463 0.082140 -vn -1.452884 2.575693 4.265221 -v 0.040182 -0.019344 0.082213 -vn -0.845788 -2.545656 4.477224 -v 0.040211 -0.019441 0.082221 -vn -0.404424 2.670952 4.530129 -v 0.040450 -0.019318 0.082250 -vn -0.346338 -2.383454 4.546392 -v 0.040355 -0.019427 0.082245 -vn 0.396654 -2.661683 4.541672 -v 0.040450 -0.019418 0.082250 -vn -1.059119 -2.404453 -4.397248 -v 0.040208 -0.019095 0.080281 -vn -1.900171 -2.710435 -4.129655 -v 0.040120 -0.019086 0.080307 -vn -1.044515 2.617816 -4.417843 -v 0.040136 -0.018988 0.080301 -vn -0.396551 -2.641057 -4.518009 -v 0.040450 -0.019118 0.080250 -vn -0.355164 2.413248 -4.519724 -v 0.040388 -0.019012 0.080252 -vn 0.441359 2.668283 -4.548628 -v 0.040450 -0.019018 0.080250 -vn -4.234519 -2.692118 -1.562543 -v 0.039519 -0.019003 0.080887 -vn -3.829420 2.344034 -2.450972 -v 0.039552 -0.018912 0.080810 -vn -3.437153 -2.566697 -2.765575 -v 0.039715 -0.019039 0.080572 -vn -3.240168 2.515029 -3.120984 -v 0.039702 -0.018938 0.080586 -vn -2.711288 -2.587714 -3.538195 -v 0.039884 -0.019060 0.080426 -vn -2.362581 2.534547 -3.863191 -v 0.039888 -0.018962 0.080423 -vn -1.860012 2.301447 -4.131759 -v 0.040027 -0.018977 0.080344 -vn -4.491216 -2.676741 -0.789728 -v 0.039481 -0.018991 0.081006 -vn -4.513489 -2.634003 0.259297 -v 0.039450 -0.018968 0.081250 -vn -4.554799 2.578442 -0.541082 -v 0.039451 -0.018872 0.081210 -vn -4.466038 2.493403 -0.921469 -v 0.039466 -0.018886 0.081072 -vn -4.335005 2.658506 -1.433508 -v 0.039480 -0.018892 0.081006 -vn -4.145005 2.634778 -1.967497 -v 0.039533 -0.018907 0.080852 -vn -3.535364 2.624974 2.872998 -v 0.039712 -0.018798 0.081925 -vn -3.900420 2.474320 2.385770 -v 0.039615 -0.018813 0.081801 -vn -3.222502 -2.646410 3.103367 -v 0.039692 -0.018900 0.081901 -vn -4.039668 2.250361 2.045285 -v 0.039604 -0.018815 0.081783 -vn -4.081875 -2.638469 1.978732 -v 0.039509 -0.018935 0.081586 -vn -4.350919 2.641890 1.313828 -v 0.039498 -0.018838 0.081557 -vn -4.388512 -2.658385 1.206429 -v 0.039481 -0.018944 0.081494 -vn -4.495337 2.617513 0.705741 -v 0.039480 -0.018844 0.081494 -vn -4.532850 2.482493 0.230558 -v 0.039452 -0.018862 0.081315 -vn 0.183627 -2.667647 4.582154 -v 0.040450 -0.018818 0.082250 -vn -0.396430 2.669362 4.558712 -v 0.040450 -0.018719 0.082250 -vn -0.401253 -2.585636 4.550478 -v 0.040314 -0.018831 0.082240 -vn -1.168394 2.572809 4.410226 -v 0.040230 -0.018740 0.082225 -vn -1.256566 -2.668511 4.390252 -v 0.040120 -0.018850 0.082193 -vn -1.644719 2.606338 4.266173 -v 0.040152 -0.018747 0.082204 -vn -2.287435 2.600966 3.946043 -v 0.039995 -0.018763 0.082141 -vn -2.046084 -2.662661 4.042320 -v 0.039973 -0.018865 0.082128 -vn -2.910161 2.253784 3.497865 -v 0.039850 -0.018780 0.082050 -vn -3.116526 2.254926 3.306520 -v 0.039795 -0.018787 0.082006 -vn -1.929178 2.653806 -4.127036 -v 0.039959 -0.018370 0.080379 -vn -1.216445 2.640678 -4.412569 -v 0.040180 -0.018393 0.080287 -vn -1.514948 -2.619432 -4.287651 -v 0.040182 -0.018492 0.080287 -vn -0.644622 2.658611 -4.527454 -v 0.040211 -0.018396 0.080279 -vn -0.754124 -2.543684 -4.498550 -v 0.040356 -0.018509 0.080254 -vn 0.317939 2.621022 -4.508579 -v 0.040450 -0.018419 0.080250 -vn -0.097670 -2.624806 -4.545090 -v 0.040450 -0.018518 0.080250 -vn -1.990559 -2.449166 -4.084590 -v 0.040027 -0.018476 0.080344 -vn -2.666965 -2.657960 -3.704267 -v 0.039933 -0.018466 0.080394 -vn -2.590764 2.523997 -3.770736 -v 0.039840 -0.018356 0.080458 -vn -3.301051 -2.693861 -3.159609 -v 0.039743 -0.018443 0.080543 -vn -3.101933 2.656246 -3.345176 -v 0.039743 -0.018344 0.080543 -vn -3.659655 -2.595447 -2.739526 -v 0.039712 -0.018438 0.080575 -vn -3.714298 2.611433 -2.551903 -v 0.039594 -0.018320 0.080733 -vn -4.050061 -2.629329 -2.087698 -v 0.039579 -0.018417 0.080759 -vn -4.282192 -2.474962 -1.549001 -v 0.039533 -0.018407 0.080852 -vn -4.224535 2.641256 -1.406926 -v 0.039487 -0.018294 0.080982 -vn -4.471436 -2.572040 -0.718404 -v 0.039479 -0.018391 0.081011 -vn -4.454153 2.584461 -0.275432 -v 0.039450 -0.018268 0.081250 -vn -4.497736 -2.561363 0.248914 -v 0.039450 -0.018367 0.081250 -vn -4.458115 2.562826 0.744713 -v 0.039479 -0.018245 0.081489 -vn -4.269999 -2.589939 1.450939 -v 0.039487 -0.018341 0.081519 -vn -4.268390 2.493218 1.624265 -v 0.039548 -0.018226 0.081683 -vn -3.705454 -2.573313 2.592450 -v 0.039594 -0.018315 0.081767 -vn -4.002535 2.647340 2.170153 -v 0.039579 -0.018219 0.081741 -vn -3.554631 2.641622 2.862602 -v 0.039743 -0.018194 0.081957 -vn -3.132475 -2.620655 3.302733 -v 0.039743 -0.018292 0.081957 -vn -3.188797 2.671205 3.299631 -v 0.039775 -0.018189 0.081988 -vn -2.548416 -2.594398 3.806685 -v 0.039850 -0.018279 0.082050 -vn -2.541393 2.623918 3.778077 -v 0.039933 -0.018170 0.082106 -vn -1.898627 -2.571137 4.150214 -v 0.039959 -0.018266 0.082121 -vn -1.271013 -2.676547 4.399623 -v 0.040151 -0.018246 0.082204 -vn 0.053526 -2.637138 4.555821 -v 0.040450 -0.018217 0.082250 -vn -0.359006 2.627634 4.508000 -v 0.040450 -0.018119 0.082250 -vn -0.624011 -2.589167 4.522228 -v 0.040211 -0.018240 0.082221 -vn -1.306853 2.671317 4.346807 -v 0.040182 -0.018145 0.082213 -vn -2.025502 2.476114 4.091662 -v 0.040085 -0.018154 0.082181 -vn -4.496432 -2.614516 0.222667 -v 0.039450 -0.017767 0.081250 -vn -4.444263 2.624193 -1.048328 -v 0.039475 -0.017690 0.081028 -vn -4.418662 -2.629788 -0.836579 -v 0.039479 -0.017790 0.081011 -vn -4.216968 2.597009 -1.709771 -v 0.039487 -0.017694 0.080981 -vn -4.058340 -2.544723 -1.962371 -v 0.039579 -0.017816 0.080759 -vn -3.712702 2.553469 -2.539042 -v 0.039594 -0.017720 0.080733 -vn -3.479448 -2.602613 -2.933098 -v 0.039743 -0.017842 0.080543 -vn -3.106088 2.609289 -3.306091 -v 0.039743 -0.017743 0.080543 -vn -3.020166 -2.655398 -3.458186 -v 0.039840 -0.017855 0.080458 -vn -2.553484 2.667287 -3.791475 -v 0.039850 -0.017757 0.080450 -vn -2.451675 -2.632740 -3.846359 -v 0.039933 -0.017865 0.080394 -vn -1.853977 2.578950 -4.142217 -v 0.039959 -0.017769 0.080379 -vn -1.448872 -2.593259 -4.256564 -v 0.040182 -0.017891 0.080287 -vn 0.104503 2.618054 -4.548593 -v 0.040450 -0.017819 0.080250 -vn -0.315999 -2.642016 -4.461469 -v 0.040450 -0.017917 0.080250 -vn -0.597087 2.591754 -4.547111 -v 0.040211 -0.017795 0.080279 -vn -1.189666 2.664380 -4.407887 -v 0.040189 -0.017793 0.080285 -vn -4.042429 2.630175 2.007535 -v 0.039579 -0.017619 0.081741 -vn -4.447253 2.627949 0.985936 -v 0.039479 -0.017645 0.081489 -vn -4.296815 -2.567297 1.475200 -v 0.039487 -0.017742 0.081518 -vn -4.554949 2.475233 0.392211 -v 0.039462 -0.017654 0.081403 -vn -4.528227 2.603439 -0.333217 -v 0.039450 -0.017668 0.081250 -vn -4.081522 -2.473348 2.040510 -v 0.039548 -0.017725 0.081683 -vn -3.662102 -2.578934 2.723290 -v 0.039594 -0.017715 0.081767 -vn -3.401165 2.614850 2.971966 -v 0.039743 -0.017593 0.081957 -vn -1.962132 -2.636611 4.075356 -v 0.039959 -0.017666 0.082121 -vn -2.725455 2.617742 3.661627 -v 0.039933 -0.017570 0.082106 -vn -2.743569 -2.593327 3.664051 -v 0.039775 -0.017688 0.081988 -vn -3.204704 -2.641080 3.254917 -v 0.039743 -0.017692 0.081957 -vn 0.255322 -2.638690 4.542396 -v 0.040450 -0.017617 0.082250 -vn -0.265626 2.643722 4.570666 -v 0.040450 -0.017518 0.082250 -vn -0.487983 -2.553523 4.550305 -v 0.040281 -0.017633 0.082236 -vn -0.678620 2.531489 4.509329 -v 0.040355 -0.017527 0.082246 -vn -0.985325 -2.609839 4.448349 -v 0.040211 -0.017640 0.082221 -vn -1.540733 2.560115 4.285325 -v 0.040182 -0.017544 0.082213 -vn -2.121623 2.548608 4.044913 -v 0.039995 -0.017563 0.082140 -vn -4.316436 2.462745 1.457240 -v 0.039508 -0.017035 0.081586 -vn -4.500919 2.664151 0.704957 -v 0.039479 -0.017045 0.081489 -vn -4.245819 -2.668777 1.595990 -v 0.039487 -0.017141 0.081519 -vn 0.129559 2.613046 -4.535288 -v 0.040450 -0.017218 0.080250 -vn -0.331968 -2.622486 -4.484232 -v 0.040450 -0.017317 0.080250 -vn -0.833087 2.555526 -4.417474 -v 0.040211 -0.017195 0.080279 -vn -1.456362 -2.554634 -4.248912 -v 0.040182 -0.017291 0.080287 -vn -1.800667 2.592086 -4.162945 -v 0.039959 -0.017169 0.080379 -vn -2.435274 -2.662026 -3.839723 -v 0.039933 -0.017265 0.080394 -vn -2.449481 2.687147 -3.853423 -v 0.039884 -0.017160 0.080426 -vn -2.990265 -2.637735 -3.467605 -v 0.039850 -0.017256 0.080450 -vn -2.932698 2.686796 -3.514235 -v 0.039743 -0.017143 0.080543 -vn -3.348724 -2.691766 -3.112490 -v 0.039743 -0.017242 0.080543 -vn -3.319824 2.662803 -3.168312 -v 0.039715 -0.017139 0.080572 -vn -3.611063 -2.672166 -2.782296 -v 0.039712 -0.017238 0.080575 -vn -3.741005 2.657628 -2.597322 -v 0.039594 -0.017120 0.080733 -vn -3.834387 -2.560741 -2.473362 -v 0.039625 -0.017225 0.080685 -vn -4.143470 -2.658219 -1.845922 -v 0.039579 -0.017216 0.080759 -vn -4.137276 2.470070 -1.932153 -v 0.039518 -0.017103 0.080887 -vn -4.431527 -2.581654 -0.793951 -v 0.039479 -0.017190 0.081011 -vn -4.355392 2.618152 -1.336357 -v 0.039487 -0.017094 0.080981 -vn -4.503775 2.560264 -0.253045 -v 0.039450 -0.017068 0.081250 -vn -4.524380 -2.560039 0.204456 -v 0.039450 -0.017167 0.081250 -vn -4.468870 -2.413560 0.783458 -v 0.039462 -0.017153 0.081403 -vn -4.104283 2.556777 1.969229 -v 0.039579 -0.017019 0.081741 -vn -3.745844 -2.600796 2.512360 -v 0.039594 -0.017116 0.081767 -vn -3.711300 2.551223 2.682815 -v 0.039691 -0.017000 0.081902 -vn -2.947797 -2.607021 3.428219 -v 0.039743 -0.017092 0.081957 -vn -3.260072 2.609186 3.197351 -v 0.039743 -0.016993 0.081957 -vn -2.214530 -2.652860 3.989359 -v 0.039959 -0.017067 0.082121 -vn -2.600441 2.548400 3.698173 -v 0.039933 -0.016970 0.082106 -vn -1.671101 -2.526799 4.256402 -v 0.039995 -0.017063 0.082140 -vn -1.452851 2.575743 4.265209 -v 0.040182 -0.016944 0.082213 -vn -0.845585 -2.545784 4.477027 -v 0.040211 -0.017041 0.082221 -vn -0.404423 2.670929 4.530136 -v 0.040450 -0.016918 0.082250 -vn -0.346160 -2.383969 4.546274 -v 0.040355 -0.017027 0.082245 -vn 0.396555 -2.661813 4.541381 -v 0.040450 -0.017018 0.082250 -vn -1.059272 -2.404896 -4.397089 -v 0.040208 -0.016695 0.080281 -vn -1.900088 -2.710535 -4.129467 -v 0.040120 -0.016686 0.080307 -vn -1.044450 2.617783 -4.417866 -v 0.040136 -0.016588 0.080301 -vn -0.396641 -2.641201 -4.517794 -v 0.040450 -0.016718 0.080250 -vn -0.355164 2.413257 -4.519706 -v 0.040388 -0.016612 0.080252 -vn 0.448696 2.673001 -4.537418 -v 0.040450 -0.016618 0.080250 -vn -4.234406 -2.692223 -1.562358 -v 0.039519 -0.016603 0.080887 -vn -3.806862 2.351536 -2.454613 -v 0.039552 -0.016512 0.080810 -vn -3.437269 -2.566998 -2.765246 -v 0.039715 -0.016639 0.080572 -vn -3.245497 2.520058 -3.104478 -v 0.039702 -0.016538 0.080586 -vn -2.711330 -2.587748 -3.537883 -v 0.039884 -0.016660 0.080426 -vn -2.362453 2.531266 -3.870359 -v 0.039888 -0.016562 0.080423 -vn -1.860032 2.301327 -4.131750 -v 0.040027 -0.016577 0.080344 -vn -4.491034 -2.676851 -0.789635 -v 0.039481 -0.016591 0.081006 -vn -4.513310 -2.634106 0.259447 -v 0.039450 -0.016568 0.081250 -vn -4.554797 2.578369 -0.541096 -v 0.039451 -0.016472 0.081210 -vn -4.466038 2.493402 -0.921469 -v 0.039466 -0.016486 0.081072 -vn -4.335008 2.658514 -1.433501 -v 0.039480 -0.016492 0.081006 -vn -4.144995 2.634733 -1.967521 -v 0.039533 -0.016507 0.080852 -vn -3.535413 2.625106 2.872963 -v 0.039712 -0.016398 0.081925 -vn -3.900420 2.474242 2.385762 -v 0.039615 -0.016413 0.081801 -vn -3.222253 -2.646425 3.103374 -v 0.039692 -0.016500 0.081901 -vn -4.039642 2.250386 2.045344 -v 0.039604 -0.016415 0.081783 -vn -4.081642 -2.638443 1.978731 -v 0.039509 -0.016535 0.081586 -vn -4.350970 2.641933 1.313865 -v 0.039498 -0.016438 0.081557 -vn -4.388330 -2.658493 1.206442 -v 0.039481 -0.016544 0.081494 -vn -4.495264 2.617568 0.705791 -v 0.039480 -0.016444 0.081494 -vn -4.532891 2.482631 0.230493 -v 0.039452 -0.016462 0.081315 -vn 0.183678 -2.667745 4.582053 -v 0.040450 -0.016418 0.082250 -vn -0.396408 2.669388 4.558718 -v 0.040450 -0.016319 0.082250 -vn -0.401085 -2.585654 4.550264 -v 0.040314 -0.016431 0.082240 -vn -1.168416 2.572799 4.410217 -v 0.040230 -0.016340 0.082225 -vn -1.256441 -2.668597 4.390116 -v 0.040120 -0.016450 0.082193 -vn -1.644716 2.606344 4.266161 -v 0.040152 -0.016347 0.082204 -vn -2.287464 2.601022 3.946023 -v 0.039995 -0.016363 0.082141 -vn -2.045838 -2.662674 4.042257 -v 0.039973 -0.016465 0.082128 -vn -2.910123 2.253852 3.497956 -v 0.039850 -0.016380 0.082050 -vn -3.116460 2.255055 3.306587 -v 0.039795 -0.016387 0.082006 -vn -1.929156 2.653773 -4.127043 -v 0.039959 -0.015970 0.080379 -vn -1.216455 2.640674 -4.412575 -v 0.040180 -0.015993 0.080287 -vn -1.515028 -2.619491 -4.287516 -v 0.040182 -0.016092 0.080287 -vn -0.644648 2.658632 -4.527467 -v 0.040211 -0.015996 0.080279 -vn -0.754119 -2.543678 -4.498386 -v 0.040356 -0.016109 0.080254 -vn 0.317957 2.621027 -4.508598 -v 0.040450 -0.016019 0.080250 -vn -0.097620 -2.624865 -4.545005 -v 0.040450 -0.016118 0.080250 -vn -1.991997 -2.452096 -4.077427 -v 0.040027 -0.016076 0.080344 -vn -2.663867 -2.670051 -3.674047 -v 0.039933 -0.016066 0.080394 -vn -2.590762 2.523998 -3.770736 -v 0.039840 -0.015956 0.080458 -vn -3.279399 -2.700991 -3.165677 -v 0.039743 -0.016043 0.080543 -vn -3.101933 2.656245 -3.345177 -v 0.039743 -0.015944 0.080543 -vn -3.667685 -2.591478 -2.740603 -v 0.039712 -0.016038 0.080575 -vn -3.714295 2.611436 -2.551906 -v 0.039594 -0.015920 0.080733 -vn -4.049983 -2.629380 -2.087626 -v 0.039579 -0.016017 0.080759 -vn -4.282118 -2.474955 -1.548920 -v 0.039533 -0.016007 0.080852 -vn -4.224538 2.641282 -1.406912 -v 0.039487 -0.015894 0.080982 -vn -4.471352 -2.572100 -0.718350 -v 0.039479 -0.015991 0.081011 -vn -4.454151 2.584463 -0.275431 -v 0.039450 -0.015868 0.081250 -vn -4.497644 -2.561407 0.248917 -v 0.039450 -0.015967 0.081250 -vn -4.458132 2.562819 0.744693 -v 0.039479 -0.015845 0.081489 -vn -4.269912 -2.589984 1.450917 -v 0.039487 -0.015941 0.081519 -vn -4.268315 2.493262 1.624280 -v 0.039548 -0.015826 0.081683 -vn -3.705376 -2.573356 2.592408 -v 0.039594 -0.015915 0.081767 -vn -4.002538 2.647324 2.170246 -v 0.039579 -0.015819 0.081741 -vn -3.554628 2.641624 2.862599 -v 0.039743 -0.015794 0.081957 -vn -3.132406 -2.620693 3.302682 -v 0.039743 -0.015892 0.081957 -vn -3.188809 2.671183 3.299629 -v 0.039775 -0.015789 0.081988 -vn -2.548318 -2.594481 3.806629 -v 0.039850 -0.015879 0.082050 -vn -2.541369 2.623936 3.778034 -v 0.039933 -0.015770 0.082106 -vn -1.898594 -2.571172 4.150154 -v 0.039959 -0.015866 0.082121 -vn -1.270845 -2.676551 4.399541 -v 0.040151 -0.015846 0.082204 -vn 0.053506 -2.637163 4.555791 -v 0.040450 -0.015817 0.082250 -vn -0.359020 2.627647 4.507998 -v 0.040450 -0.015719 0.082250 -vn -0.623876 -2.589204 4.522213 -v 0.040211 -0.015840 0.082221 -vn -1.306843 2.671342 4.346807 -v 0.040182 -0.015745 0.082213 -vn -2.025496 2.476074 4.091676 -v 0.040085 -0.015754 0.082181 -vn -4.496432 -2.614516 0.222667 -v 0.039450 -0.015367 0.081250 -vn -4.444281 2.624183 -1.048345 -v 0.039475 -0.015290 0.081028 -vn -4.418659 -2.629789 -0.836580 -v 0.039479 -0.015390 0.081011 -vn -4.216975 2.597004 -1.709779 -v 0.039487 -0.015294 0.080981 -vn -4.058334 -2.544724 -1.962368 -v 0.039579 -0.015416 0.080759 -vn -3.712702 2.553469 -2.539042 -v 0.039594 -0.015320 0.080733 -vn -3.479441 -2.602617 -2.933095 -v 0.039743 -0.015442 0.080543 -vn -3.106088 2.609289 -3.306091 -v 0.039743 -0.015343 0.080543 -vn -3.020146 -2.655410 -3.458172 -v 0.039840 -0.015455 0.080458 -vn -2.553484 2.667287 -3.791475 -v 0.039850 -0.015357 0.080450 -vn -2.451666 -2.632756 -3.846326 -v 0.039933 -0.015465 0.080394 -vn -1.853977 2.578950 -4.142217 -v 0.039959 -0.015369 0.080379 -vn -1.448849 -2.593274 -4.256538 -v 0.040182 -0.015491 0.080287 -vn 0.104457 2.618046 -4.548619 -v 0.040450 -0.015419 0.080250 -vn -0.316004 -2.642009 -4.461485 -v 0.040450 -0.015517 0.080250 -vn -0.597086 2.591754 -4.547111 -v 0.040211 -0.015395 0.080279 -vn -1.189666 2.664380 -4.407887 -v 0.040189 -0.015393 0.080285 -vn -4.042440 2.630171 2.007527 -v 0.039579 -0.015219 0.081741 -vn -4.447253 2.627949 0.985936 -v 0.039479 -0.015245 0.081489 -vn -4.296815 -2.567297 1.475200 -v 0.039487 -0.015342 0.081518 -vn -4.554964 2.475226 0.392246 -v 0.039462 -0.015254 0.081403 -vn -4.528185 2.603459 -0.333210 -v 0.039450 -0.015268 0.081250 -vn -4.081511 -2.473353 2.040511 -v 0.039548 -0.015325 0.081683 -vn -3.662098 -2.578939 2.723280 -v 0.039594 -0.015315 0.081767 -vn -3.401138 2.614866 2.971937 -v 0.039743 -0.015193 0.081957 -vn -1.962132 -2.636611 4.075356 -v 0.039959 -0.015266 0.082121 -vn -2.725525 2.617711 3.661646 -v 0.039933 -0.015170 0.082106 -vn -2.743569 -2.593330 3.664051 -v 0.039775 -0.015288 0.081988 -vn -3.204704 -2.641080 3.254917 -v 0.039743 -0.015292 0.081957 -vn 0.255322 -2.638690 4.542396 -v 0.040450 -0.015217 0.082250 -vn -0.265589 2.643745 4.570628 -v 0.040450 -0.015118 0.082250 -vn -0.487981 -2.553528 4.550305 -v 0.040281 -0.015233 0.082236 -vn -0.678648 2.531509 4.509293 -v 0.040355 -0.015127 0.082246 -vn -0.985326 -2.609840 4.448349 -v 0.040211 -0.015240 0.082221 -vn -1.540740 2.560103 4.285351 -v 0.040182 -0.015144 0.082213 -vn -2.121643 2.548639 4.044835 -v 0.039995 -0.015163 0.082140 -vn -4.316434 2.462737 1.457242 -v 0.039508 -0.014635 0.081586 -vn -4.500916 2.664153 0.704953 -v 0.039479 -0.014645 0.081489 -vn -4.245857 -2.668756 1.596022 -v 0.039487 -0.014741 0.081519 -vn 0.129559 2.613046 -4.535288 -v 0.040450 -0.014818 0.080250 -vn -0.331968 -2.622486 -4.484232 -v 0.040450 -0.014917 0.080250 -vn -0.833087 2.555526 -4.417474 -v 0.040211 -0.014795 0.080279 -vn -1.456362 -2.554634 -4.248912 -v 0.040182 -0.014891 0.080287 -vn -1.800667 2.592086 -4.162945 -v 0.039959 -0.014769 0.080379 -vn -2.435274 -2.662026 -3.839723 -v 0.039933 -0.014865 0.080394 -vn -2.449481 2.687147 -3.853423 -v 0.039884 -0.014761 0.080426 -vn -2.990265 -2.637735 -3.467605 -v 0.039850 -0.014856 0.080450 -vn -2.932698 2.686796 -3.514235 -v 0.039743 -0.014743 0.080543 -vn -3.348724 -2.691766 -3.112490 -v 0.039743 -0.014842 0.080543 -vn -3.319824 2.662803 -3.168312 -v 0.039715 -0.014739 0.080572 -vn -3.611063 -2.672166 -2.782296 -v 0.039712 -0.014838 0.080575 -vn -3.741005 2.657628 -2.597322 -v 0.039594 -0.014720 0.080733 -vn -3.834387 -2.560741 -2.473362 -v 0.039625 -0.014825 0.080685 -vn -4.143466 -2.658222 -1.845914 -v 0.039579 -0.014816 0.080759 -vn -4.137276 2.470070 -1.932153 -v 0.039518 -0.014703 0.080887 -vn -4.431519 -2.581659 -0.793954 -v 0.039479 -0.014790 0.081011 -vn -4.355396 2.618148 -1.336363 -v 0.039487 -0.014694 0.080981 -vn -4.503781 2.560263 -0.253037 -v 0.039450 -0.014668 0.081250 -vn -4.524380 -2.560039 0.204456 -v 0.039450 -0.014767 0.081250 -vn -4.468839 -2.413568 0.783495 -v 0.039462 -0.014753 0.081403 -vn -4.104283 2.556777 1.969228 -v 0.039579 -0.014619 0.081741 -vn -3.745821 -2.600805 2.512351 -v 0.039594 -0.014716 0.081767 -vn -3.711357 2.551199 2.682791 -v 0.039691 -0.014600 0.081902 -vn -2.947820 -2.607007 3.428244 -v 0.039743 -0.014692 0.081957 -vn -3.260080 2.609210 3.197257 -v 0.039743 -0.014593 0.081957 -vn -2.214529 -2.652869 3.989339 -v 0.039959 -0.014667 0.082121 -vn -2.600414 2.548414 3.698162 -v 0.039933 -0.014570 0.082106 -vn -1.671093 -2.526813 4.256388 -v 0.039995 -0.014663 0.082140 -vn -1.452838 2.575740 4.265224 -v 0.040182 -0.014544 0.082213 -vn -0.845588 -2.545788 4.477020 -v 0.040211 -0.014641 0.082221 -vn -0.404475 2.670908 4.530167 -v 0.040450 -0.014518 0.082250 -vn -0.346160 -2.383969 4.546274 -v 0.040355 -0.014627 0.082245 -vn 0.396556 -2.661812 4.541381 -v 0.040450 -0.014618 0.082250 -vn -1.059272 -2.404896 -4.397089 -v 0.040208 -0.014295 0.080281 -vn -1.900100 -2.710536 -4.129454 -v 0.040120 -0.014286 0.080307 -vn -1.044430 2.617767 -4.417902 -v 0.040136 -0.014188 0.080301 -vn -0.396641 -2.641201 -4.517794 -v 0.040450 -0.014318 0.080250 -vn -0.355166 2.413249 -4.519722 -v 0.040388 -0.014212 0.080252 -vn 0.448702 2.672997 -4.537426 -v 0.040450 -0.014218 0.080250 -vn -4.234406 -2.692223 -1.562358 -v 0.039519 -0.014203 0.080887 -vn -3.806868 2.351534 -2.454612 -v 0.039552 -0.014112 0.080810 -vn -3.437243 -2.567008 -2.765250 -v 0.039715 -0.014239 0.080572 -vn -3.245498 2.520055 -3.104483 -v 0.039702 -0.014138 0.080586 -vn -2.711349 -2.587733 -3.537912 -v 0.039884 -0.014260 0.080426 -vn -2.362486 2.531260 -3.870359 -v 0.039888 -0.014162 0.080423 -vn -1.859982 2.301379 -4.131712 -v 0.040027 -0.014177 0.080344 -vn -4.491034 -2.676851 -0.789635 -v 0.039481 -0.014191 0.081006 -vn -4.513303 -2.634108 0.259450 -v 0.039450 -0.014168 0.081250 -vn -4.554827 2.578351 -0.541133 -v 0.039451 -0.014072 0.081210 -vn -4.466045 2.493398 -0.921475 -v 0.039466 -0.014086 0.081072 -vn -4.335008 2.658514 -1.433501 -v 0.039480 -0.014092 0.081006 -vn -4.144995 2.634733 -1.967521 -v 0.039533 -0.014107 0.080852 -vn -3.535413 2.625106 2.872963 -v 0.039712 -0.013998 0.081925 -vn -3.900420 2.474242 2.385762 -v 0.039615 -0.014013 0.081801 -vn -3.222253 -2.646425 3.103374 -v 0.039692 -0.014100 0.081901 -vn -4.039642 2.250386 2.045344 -v 0.039604 -0.014015 0.081783 -vn -4.081642 -2.638443 1.978731 -v 0.039509 -0.014135 0.081586 -vn -4.350970 2.641933 1.313865 -v 0.039498 -0.014038 0.081557 -vn -4.388326 -2.658495 1.206438 -v 0.039481 -0.014144 0.081494 -vn -4.495271 2.617564 0.705816 -v 0.039480 -0.014044 0.081494 -vn -4.532834 2.482671 0.230457 -v 0.039452 -0.014062 0.081315 -vn 0.183649 -2.667756 4.582036 -v 0.040450 -0.014018 0.082250 -vn -0.396407 2.669388 4.558718 -v 0.040450 -0.013919 0.082250 -vn -0.401108 -2.585628 4.550311 -v 0.040314 -0.014031 0.082240 -vn -1.168416 2.572797 4.410217 -v 0.040230 -0.013940 0.082225 -vn -1.256412 -2.668602 4.390110 -v 0.040120 -0.014050 0.082193 -vn -1.644716 2.606344 4.266161 -v 0.040152 -0.013947 0.082204 -vn -2.287464 2.601022 3.946023 -v 0.039995 -0.013963 0.082141 -vn -2.045838 -2.662674 4.042257 -v 0.039973 -0.014065 0.082128 -vn -2.910123 2.253852 3.497956 -v 0.039850 -0.013980 0.082050 -vn -3.116460 2.255055 3.306587 -v 0.039795 -0.013987 0.082006 -vn -1.898613 -2.571183 4.150124 -v 0.039959 -0.013466 0.082121 -vn -1.317309 -2.585369 4.378925 -v 0.040151 -0.013446 0.082204 -vn -2.649246 2.607656 3.703288 -v 0.039933 -0.013370 0.082106 -vn -1.929178 2.653769 -4.127044 -v 0.039959 -0.013570 0.080379 -vn -1.216273 2.640724 -4.412498 -v 0.040180 -0.013593 0.080287 -vn -1.515021 -2.619496 -4.287509 -v 0.040182 -0.013692 0.080287 -vn -0.644525 2.658575 -4.527580 -v 0.040211 -0.013596 0.080279 -vn -0.754118 -2.543687 -4.498369 -v 0.040356 -0.013709 0.080254 -vn 0.317957 2.621027 -4.508598 -v 0.040450 -0.013619 0.080250 -vn -0.097626 -2.624869 -4.544995 -v 0.040450 -0.013718 0.080250 -vn -1.991997 -2.452096 -4.077427 -v 0.040027 -0.013676 0.080344 -vn -2.663867 -2.670051 -3.674047 -v 0.039933 -0.013666 0.080394 -vn -2.590762 2.523998 -3.770736 -v 0.039840 -0.013556 0.080458 -vn -3.279399 -2.700991 -3.165677 -v 0.039743 -0.013643 0.080543 -vn -3.101933 2.656245 -3.345177 -v 0.039743 -0.013544 0.080543 -vn -3.667682 -2.591486 -2.740589 -v 0.039712 -0.013638 0.080575 -vn -3.714295 2.611436 -2.551906 -v 0.039594 -0.013520 0.080733 -vn -4.049969 -2.629386 -2.087627 -v 0.039579 -0.013617 0.080759 -vn -4.282118 -2.474955 -1.548920 -v 0.039533 -0.013607 0.080852 -vn -4.224538 2.641282 -1.406912 -v 0.039487 -0.013494 0.080982 -vn -4.471345 -2.572103 -0.718342 -v 0.039479 -0.013591 0.081011 -vn -4.454165 2.584455 -0.275450 -v 0.039450 -0.013468 0.081250 -vn -4.497637 -2.561413 0.248912 -v 0.039450 -0.013567 0.081250 -vn -4.533792 2.604780 0.560961 -v 0.039479 -0.013445 0.081489 -vn -4.243077 -2.517465 1.512157 -v 0.039487 -0.013541 0.081519 -vn -4.431114 2.662754 1.146421 -v 0.039480 -0.013445 0.081494 -vn -3.762194 -2.607509 2.494490 -v 0.039594 -0.013515 0.081767 -vn -4.163537 2.531523 1.831393 -v 0.039579 -0.013419 0.081741 -vn -3.706140 2.365242 2.636992 -v 0.039650 -0.013407 0.081850 -vn -3.330973 2.557946 3.080319 -v 0.039743 -0.013394 0.081957 -vn -3.080045 -2.551791 3.346856 -v 0.039743 -0.013492 0.081957 -vn -2.639436 -2.361003 3.704431 -v 0.039850 -0.013479 0.082050 -vn -0.666079 -2.664901 4.517160 -v 0.040211 -0.013440 0.082221 -vn 0.053506 -2.637163 4.555791 -v 0.040450 -0.013417 0.082250 -vn -0.251339 2.619185 4.537526 -v 0.040450 -0.013319 0.082250 -vn -0.713974 2.339525 4.475633 -v 0.040318 -0.013331 0.082241 -vn -1.577234 2.662770 4.248276 -v 0.040182 -0.013345 0.082213 -vn -2.310551 1.955309 3.811892 -v 0.039945 -0.013369 0.082113 -vn -4.045353 -2.628478 -1.994621 -v 0.039579 -0.013016 0.080759 -vn -3.652718 2.583230 -2.746549 -v 0.039594 -0.012920 0.080733 -vn -3.479486 -2.602592 -2.933118 -v 0.039743 -0.013042 0.080543 -vn -3.147990 2.608329 -3.290383 -v 0.039743 -0.012943 0.080543 -vn -2.984941 -2.608033 -3.482224 -v 0.039840 -0.013055 0.080458 -vn 0.095287 2.622571 -4.549570 -v 0.040450 -0.013019 0.080250 -vn -0.316449 -2.643988 -4.461478 -v 0.040450 -0.013117 0.080250 -vn -0.634445 2.584665 -4.530982 -v 0.040211 -0.012995 0.080279 -vn -1.429267 -2.632944 -4.264252 -v 0.040182 -0.013091 0.080287 -vn -1.330934 2.583473 -4.356487 -v 0.040151 -0.012990 0.080296 -vn -2.468838 -2.605976 -3.834425 -v 0.039933 -0.013065 0.080394 -vn -1.917311 2.572516 -4.104695 -v 0.039959 -0.012969 0.080379 -vn -2.703779 2.623256 -3.679879 -v 0.039806 -0.012952 0.080485 -vn -4.086895 2.639490 2.006192 -v 0.039579 -0.012819 0.081741 -vn -4.349200 2.520674 1.390582 -v 0.039501 -0.012838 0.081567 -vn -4.286019 -2.651693 1.460155 -v 0.039487 -0.012942 0.081518 -vn -4.515352 2.628325 0.683412 -v 0.039479 -0.012845 0.081489 -vn -4.471280 -2.592348 0.682781 -v 0.039452 -0.012961 0.081315 -vn -4.561024 2.689731 -0.131853 -v 0.039450 -0.012868 0.081250 -vn -4.522210 -2.720396 0.132703 -v 0.039450 -0.012967 0.081250 -vn -4.513962 2.553605 -0.719728 -v 0.039453 -0.012876 0.081174 -vn -4.417223 -2.605324 -0.845337 -v 0.039479 -0.012990 0.081011 -vn -4.290046 2.554343 -1.522922 -v 0.039487 -0.012894 0.080981 -vn -4.045311 2.548466 -2.125095 -v 0.039560 -0.012914 0.080795 -vn -4.072877 -2.482031 2.024097 -v 0.039548 -0.012925 0.081683 -vn -3.682972 -2.625317 2.694707 -v 0.039594 -0.012915 0.081767 -vn -3.690717 2.564882 2.699626 -v 0.039698 -0.012800 0.081909 -vn -3.166034 -2.703213 3.300153 -v 0.039743 -0.012892 0.081957 -vn -3.270617 2.703622 3.143495 -v 0.039743 -0.012793 0.081957 -vn -2.722444 -2.600511 3.659891 -v 0.039775 -0.012888 0.081988 -vn -2.711363 2.623765 3.638193 -v 0.039933 -0.012770 0.082106 -vn -1.977376 -2.645168 4.058780 -v 0.039959 -0.012866 0.082121 -vn -2.043496 2.502812 4.062665 -v 0.040012 -0.012762 0.082149 -vn -1.524792 2.577825 4.269231 -v 0.040182 -0.012744 0.082213 -vn -0.998134 -2.643138 4.440289 -v 0.040211 -0.012840 0.082221 -vn -0.456004 -2.576989 4.546961 -v 0.040281 -0.012833 0.082236 -vn -0.648276 2.642382 4.528391 -v 0.040393 -0.012724 0.082248 -vn 0.294504 -2.679810 4.533848 -v 0.040450 -0.012817 0.082250 -vn -0.179034 2.699056 4.570370 -v 0.040450 -0.012718 0.082250 -vn -4.221821 2.286549 1.619063 -v 0.039528 -0.012230 0.081637 -vn -4.467894 2.658939 0.741962 -v 0.039479 -0.012245 0.081489 -vn -4.267498 -2.642662 1.593170 -v 0.039487 -0.012341 0.081519 -vn -4.163802 -2.653130 -1.867996 -v 0.039579 -0.012416 0.080759 -vn -4.122289 2.318950 -1.868542 -v 0.039528 -0.012306 0.080863 -vn -3.693757 2.669869 -2.635527 -v 0.039594 -0.012320 0.080733 -vn 0.036490 2.618316 -4.576309 -v 0.040450 -0.012418 0.080250 -vn -0.435084 -2.624602 -4.509958 -v 0.040450 -0.012517 0.080250 -vn -0.703056 2.570913 -4.499674 -v 0.040211 -0.012395 0.080279 -vn -1.403228 -2.638816 -4.266827 -v 0.040182 -0.012491 0.080287 -vn -1.493006 2.475571 -4.314922 -v 0.040080 -0.012382 0.080321 -vn -2.485543 -2.642447 -3.813068 -v 0.039933 -0.012465 0.080394 -vn -2.059886 2.619690 -4.065450 -v 0.039959 -0.012369 0.080379 -vn -2.949086 -2.493610 -3.484186 -v 0.039850 -0.012456 0.080450 -vn -2.849849 2.687210 -3.592448 -v 0.039750 -0.012344 0.080536 -vn -3.351640 -2.701940 -3.107157 -v 0.039743 -0.012442 0.080543 -vn -3.212780 2.713042 -3.259962 -v 0.039743 -0.012343 0.080543 -vn -3.616342 -2.611029 -2.772569 -v 0.039712 -0.012438 0.080575 -vn -3.836559 -2.558379 -2.479486 -v 0.039625 -0.012425 0.080685 -vn -4.302443 2.545295 -1.418698 -v 0.039487 -0.012294 0.080981 -vn -4.445755 -2.541156 -0.823819 -v 0.039479 -0.012390 0.081011 -vn -4.491663 2.567112 -0.244821 -v 0.039450 -0.012268 0.081250 -vn -4.544875 -2.550732 0.193316 -v 0.039450 -0.012367 0.081250 -vn -4.484496 -2.403966 0.794313 -v 0.039462 -0.012353 0.081403 -vn -4.044809 2.544687 2.046917 -v 0.039579 -0.012219 0.081741 -vn -3.710829 -2.546406 2.562010 -v 0.039594 -0.012316 0.081767 -vn -3.587762 2.653987 2.843982 -v 0.039743 -0.012193 0.081957 -vn -3.001970 -2.565115 3.363492 -v 0.039743 -0.012292 0.081957 -vn -3.192234 2.624768 3.282869 -v 0.039750 -0.012192 0.081964 -vn -2.175997 -2.613417 4.007353 -v 0.039959 -0.012267 0.082121 -vn -2.664697 2.549577 3.686872 -v 0.039933 -0.012170 0.082106 -vn -1.863460 2.448933 4.147320 -v 0.040080 -0.012154 0.082179 -vn -1.750421 -2.539119 4.214609 -v 0.039995 -0.012263 0.082140 -vn -1.377188 2.576014 4.321479 -v 0.040182 -0.012144 0.082213 -vn -0.829910 -2.554433 4.461173 -v 0.040211 -0.012241 0.082221 -vn -0.487646 2.695806 4.544966 -v 0.040450 -0.012118 0.082250 -vn -0.352229 -2.393321 4.528878 -v 0.040355 -0.012227 0.082245 -vn 0.431330 -2.643431 4.519273 -v 0.040450 -0.012218 0.082250 -vn -1.075690 -2.396054 -4.408614 -v 0.040208 -0.011895 0.080281 -vn -1.892212 -2.696744 -4.156948 -v 0.040120 -0.011886 0.080307 -vn -1.048822 2.617714 -4.401238 -v 0.040136 -0.011788 0.080301 -vn -0.381704 -2.632245 -4.539282 -v 0.040450 -0.011918 0.080250 -vn -0.357862 2.421560 -4.503845 -v 0.040388 -0.011812 0.080252 -vn 0.453683 2.678538 -4.524834 -v 0.040450 -0.011818 0.080250 -vn -3.495037 -2.545454 -2.783735 -v 0.039715 -0.011839 0.080572 -vn -4.235470 -2.699612 -1.577242 -v 0.039519 -0.011803 0.080887 -vn -3.850736 2.341575 -2.384384 -v 0.039552 -0.011712 0.080810 -vn -3.480919 2.566931 -2.957659 -v 0.039697 -0.011737 0.080591 -vn -3.069649 2.666922 -3.406353 -v 0.039702 -0.011738 0.080586 -vn -2.730103 -2.558455 -3.605084 -v 0.039884 -0.011860 0.080426 -vn -2.363938 2.533832 -3.865560 -v 0.039888 -0.011762 0.080423 -vn -1.905150 2.245228 -4.092840 -v 0.040012 -0.011775 0.080351 -vn -4.476201 -2.669460 -0.734606 -v 0.039481 -0.011791 0.081006 -vn -4.466883 -2.371581 0.083705 -v 0.039450 -0.011768 0.081250 -vn -4.573816 2.629510 -0.188670 -v 0.039452 -0.011662 0.081315 -vn -4.452295 2.372790 -0.758592 -v 0.039466 -0.011686 0.081072 -vn -4.368449 2.661024 -1.383415 -v 0.039480 -0.011692 0.081006 -vn -4.257449 2.591032 -1.689803 -v 0.039501 -0.011699 0.080933 -vn -3.211021 2.378698 3.270673 -v 0.039795 -0.011587 0.082006 -vn -3.541596 2.622375 2.872794 -v 0.039712 -0.011598 0.081925 -vn -3.201037 -2.648926 3.086863 -v 0.039692 -0.011700 0.081901 -vn -3.933926 2.284501 2.250529 -v 0.039615 -0.011613 0.081801 -vn -4.058380 -2.704574 1.955505 -v 0.039509 -0.011735 0.081586 -vn -4.094371 2.233405 1.926387 -v 0.039560 -0.011623 0.081705 -vn -4.401230 2.656952 1.234141 -v 0.039498 -0.011638 0.081557 -vn -4.379328 -2.661384 1.212834 -v 0.039481 -0.011744 0.081494 -vn -4.507592 2.611312 0.726252 -v 0.039480 -0.011644 0.081494 -vn -4.561656 2.450052 0.344263 -v 0.039453 -0.011661 0.081326 -vn -2.179307 -2.495599 3.940656 -v 0.039973 -0.011665 0.082128 -vn -1.256786 -2.668568 4.390470 -v 0.040120 -0.011650 0.082193 -vn -2.399141 2.538358 3.830251 -v 0.039995 -0.011563 0.082141 -vn -2.706400 1.827072 3.476711 -v 0.039806 -0.011585 0.082015 -vn 0.192044 -2.658065 4.581387 -v 0.040450 -0.011618 0.082250 -vn -0.382678 2.668673 4.524043 -v 0.040450 -0.011519 0.082250 -vn -0.400899 -2.585632 4.550305 -v 0.040314 -0.011631 0.082240 -vn -1.142858 2.589427 4.385598 -v 0.040230 -0.011540 0.082225 -vn -1.645258 2.606473 4.265929 -v 0.040151 -0.011547 0.082204 -vn 0.394568 2.612556 -4.507577 -v 0.040450 -0.011219 0.080250 -vn -0.106712 -2.604689 -4.554422 -v 0.040450 -0.011318 0.080250 -vn -0.358908 2.612965 -4.564801 -v 0.040318 -0.011206 0.080259 -vn -0.719393 -2.621202 -4.517533 -v 0.040356 -0.011309 0.080254 -vn -0.969840 2.612874 -4.437258 -v 0.040211 -0.011196 0.080279 -vn -1.532031 -2.567217 -4.277250 -v 0.040182 -0.011292 0.080287 -vn -1.821349 2.620017 -4.177662 -v 0.039959 -0.011169 0.080379 -vn -1.990582 -2.449891 -4.080118 -v 0.040027 -0.011276 0.080344 -vn -2.292647 2.633629 -3.958312 -v 0.039945 -0.011168 0.080387 -vn -2.709570 -2.602820 -3.642046 -v 0.039933 -0.011266 0.080394 -vn -3.225320 -2.643667 -3.209564 -v 0.039743 -0.011243 0.080543 -vn -2.920068 2.620799 -3.484506 -v 0.039743 -0.011143 0.080543 -vn -3.650280 -2.659786 -2.766904 -v 0.039712 -0.011238 0.080575 -vn -3.533279 2.443008 -2.889304 -v 0.039650 -0.011130 0.080650 -vn -3.796097 2.597197 -2.524740 -v 0.039594 -0.011120 0.080733 -vn -4.050417 -2.629164 -2.087229 -v 0.039579 -0.011217 0.080759 -vn -4.281827 -2.475443 -1.548520 -v 0.039533 -0.011207 0.080852 -vn -4.271943 2.618394 -1.417104 -v 0.039487 -0.011094 0.080982 -vn -4.470914 -2.572339 -0.718556 -v 0.039479 -0.011191 0.081011 -vn -4.473650 2.577193 -0.259900 -v 0.039450 -0.011068 0.081250 -vn -4.496330 -2.561977 0.249726 -v 0.039450 -0.011167 0.081250 -vn -4.413737 2.577245 0.774053 -v 0.039479 -0.011045 0.081489 -vn -4.258229 -2.580717 1.460950 -v 0.039487 -0.011141 0.081519 -vn -4.248002 2.526971 1.622041 -v 0.039557 -0.011024 0.081700 -vn -3.705034 -2.574823 2.581273 -v 0.039594 -0.011115 0.081767 -vn -3.990367 2.661288 2.200696 -v 0.039579 -0.011019 0.081741 -vn -3.543122 2.639534 2.860432 -v 0.039743 -0.010993 0.081957 -vn -3.124453 -2.624712 3.299532 -v 0.039743 -0.011092 0.081957 -vn -3.158024 2.668541 3.321379 -v 0.039784 -0.010988 0.081996 -vn -2.546872 -2.614488 3.804887 -v 0.039850 -0.011079 0.082050 -vn -2.528161 2.630091 3.775701 -v 0.039933 -0.010970 0.082106 -vn -0.626212 -2.579852 4.493744 -v 0.040211 -0.011040 0.082221 -vn 0.038497 -2.655093 4.522664 -v 0.040450 -0.011017 0.082250 -vn -0.309400 2.623344 4.505188 -v 0.040450 -0.010918 0.082250 -vn -1.878008 -2.579165 4.140759 -v 0.039959 -0.011066 0.082121 -vn -1.251478 -2.620211 4.387125 -v 0.040151 -0.011046 0.082204 -vn -1.976070 2.507629 4.124158 -v 0.040098 -0.010952 0.082186 -vn -1.322004 2.626968 4.362105 -v 0.040182 -0.010944 0.082213 -vn -4.242575 -2.577831 1.521739 -v 0.039487 -0.010541 0.081518 -vn -4.436771 2.649410 1.017431 -v 0.039479 -0.010445 0.081489 -vn -4.546574 2.499073 0.434625 -v 0.039466 -0.010451 0.081427 -vn -4.500334 -2.618351 0.244933 -v 0.039450 -0.010567 0.081250 -vn -4.541836 2.598515 -0.266311 -v 0.039450 -0.010468 0.081250 -vn -4.462030 2.583399 -0.988291 -v 0.039470 -0.010487 0.081053 -vn -4.401789 -2.653559 -0.860621 -v 0.039479 -0.010590 0.081011 -vn -4.240468 2.586349 -1.672525 -v 0.039487 -0.010494 0.080981 -vn -4.045166 -2.553367 -1.945939 -v 0.039579 -0.010616 0.080759 -vn -3.721563 2.543817 -2.558205 -v 0.039594 -0.010520 0.080733 -vn -3.477897 -2.605467 -2.924774 -v 0.039743 -0.010642 0.080543 -vn -3.094957 2.609386 -3.310369 -v 0.039743 -0.010543 0.080543 -vn -3.025210 -2.649429 -3.452693 -v 0.039840 -0.010655 0.080458 -vn -2.511029 2.673901 -3.820172 -v 0.039863 -0.010558 0.080440 -vn -2.447047 -2.643026 -3.845617 -v 0.039933 -0.010665 0.080394 -vn -1.834942 2.582888 -4.152447 -v 0.039959 -0.010569 0.080379 -vn -1.470087 -2.561397 -4.266147 -v 0.040182 -0.010691 0.080287 -vn 0.096667 2.624236 -4.525334 -v 0.040450 -0.010618 0.080250 -vn -0.325378 -2.612893 -4.511010 -v 0.040450 -0.010717 0.080250 -vn -0.558028 2.608334 -4.526247 -v 0.040211 -0.010595 0.080279 -vn -1.136455 2.683445 -4.421722 -v 0.040202 -0.010594 0.080281 -vn -4.054921 2.547124 1.958903 -v 0.039579 -0.010419 0.081741 -vn -3.722276 -2.547028 2.547343 -v 0.039594 -0.010515 0.081767 -vn -3.475302 2.602471 2.932522 -v 0.039743 -0.010393 0.081957 -vn -3.122532 -2.604477 3.304829 -v 0.039743 -0.010492 0.081957 -vn -3.001852 2.653463 3.468755 -v 0.039842 -0.010380 0.082044 -vn -2.591422 -2.655181 3.769732 -v 0.039839 -0.010480 0.082042 -vn -2.446521 2.629755 3.839113 -v 0.039933 -0.010370 0.082106 -vn -1.888206 -2.573450 4.135139 -v 0.039959 -0.010467 0.082121 -vn -1.457173 2.615905 4.263754 -v 0.040182 -0.010344 0.082213 -vn 0.242759 -2.621772 4.465400 -v 0.040450 -0.010418 0.082250 -vn -0.437731 2.622873 4.537403 -v 0.040450 -0.010318 0.082250 -vn -0.604336 -2.596663 4.519889 -v 0.040211 -0.010441 0.082221 -vn -1.277039 -2.614799 4.382926 -v 0.040165 -0.010445 0.082209 -vn 0.473995 2.660584 4.557520 -v 0.040646 -0.020500 0.082231 -vn 1.413067 -2.537775 4.292229 -v 0.040684 -0.020756 0.082224 -vn 4.256858 -2.584526 -1.541296 -v 0.041413 -0.020545 0.080985 -vn 4.429938 2.600861 -0.987148 -v 0.041421 -0.020346 0.081011 -vn 4.560887 2.590099 -0.344695 -v 0.041441 -0.020356 0.081119 -vn 4.518181 -2.583579 -0.336324 -v 0.041449 -0.020580 0.081251 -vn 4.533640 2.593069 0.383236 -v 0.041450 -0.020369 0.081250 -vn 4.557224 -2.602976 0.528043 -v 0.041421 -0.020613 0.081494 -vn 4.269784 2.572227 1.454895 -v 0.041413 -0.020395 0.081519 -vn 4.403085 -2.609133 1.177624 -v 0.041413 -0.020617 0.081523 -vn 3.860308 2.617735 2.402906 -v 0.041306 -0.020421 0.081767 -vn 4.062744 -2.593513 1.974352 -v 0.041304 -0.020652 0.081770 -vn 3.493988 2.655627 2.953161 -v 0.041257 -0.020429 0.081841 -vn 3.701592 -2.672115 2.722212 -v 0.041188 -0.020677 0.081924 -vn 2.971032 2.624205 3.431412 -v 0.041157 -0.020444 0.081957 -vn 3.284256 -2.669911 3.133451 -v 0.041156 -0.020683 0.081957 -vn 2.435255 2.626792 3.857234 -v 0.040998 -0.020463 0.082086 -vn 2.469468 -2.544258 3.736647 -v 0.040938 -0.020720 0.082124 -vn 1.819205 2.625935 4.191040 -v 0.040941 -0.020470 0.082121 -vn 1.090773 2.639335 4.430489 -v 0.040689 -0.020496 0.082221 -vn 4.038252 2.549326 -1.999615 -v 0.041321 -0.020320 0.080759 -vn 3.738690 -2.520427 -2.521312 -v 0.041319 -0.020512 0.080754 -vn 3.512195 2.606162 -2.904994 -v 0.041157 -0.020294 0.080543 -vn 3.152412 -2.626188 -3.306524 -v 0.041157 -0.020477 0.080543 -vn 2.664388 -2.695375 -3.694512 -v 0.041136 -0.020473 0.080523 -vn 3.019512 2.612480 -3.432142 -v 0.041079 -0.020284 0.080473 -vn 1.942986 -2.642273 -4.047032 -v 0.040956 -0.020444 0.080389 -vn 1.462455 2.590369 -4.347587 -v 0.040718 -0.020244 0.080287 -vn 1.699301 2.242845 -4.185557 -v 0.040764 -0.020249 0.080301 -vn 2.488004 2.591023 -3.793019 -v 0.040967 -0.020270 0.080394 -vn 1.086678 -2.639507 -4.426404 -v 0.040710 -0.020409 0.080285 -vn 0.478853 -2.651514 -4.552058 -v 0.040655 -0.020401 0.080271 -vn 0.771808 2.626372 -4.507882 -v 0.040554 -0.020228 0.080255 -vn 0.269816 2.601117 4.575943 -v 0.040566 -0.019907 0.082243 -vn 1.044143 -2.680139 4.457771 -v 0.040646 -0.019998 0.082231 -vn 0.863605 2.680646 4.501689 -v 0.040687 -0.019896 0.082222 -vn 1.624353 -2.656497 4.269524 -v 0.040718 -0.019991 0.082213 -vn 1.564154 2.470974 4.274405 -v 0.040833 -0.019881 0.082174 -vn 2.540617 -2.559550 3.742290 -v 0.040967 -0.019965 0.082106 -vn 2.312506 2.615002 3.946401 -v 0.041024 -0.019860 0.082069 -vn 2.762393 2.273212 3.599029 -v 0.041056 -0.019856 0.082046 -vn 3.553834 2.651911 2.848531 -v 0.041248 -0.019830 0.081852 -vn 4.110184 -2.453479 1.909682 -v 0.041321 -0.019916 0.081741 -vn 4.071801 2.482842 1.949455 -v 0.041384 -0.019803 0.081607 -vn 4.444458 -2.654500 0.849793 -v 0.041421 -0.019890 0.081489 -vn 4.359865 2.656688 1.358989 -v 0.041420 -0.019792 0.081494 -vn 3.138733 2.575818 3.327362 -v 0.041188 -0.019839 0.081925 -vn 3.250675 -2.482307 3.150905 -v 0.041157 -0.019942 0.081957 -vn 3.823636 -2.645124 2.516163 -v 0.041257 -0.019928 0.081841 -vn 4.511508 2.531632 0.775334 -v 0.041444 -0.019778 0.081356 -vn 4.554974 -2.646792 -0.207175 -v 0.041450 -0.019867 0.081250 -vn 4.556281 2.662143 0.219333 -v 0.041450 -0.019769 0.081258 -vn 4.552284 2.646938 -0.393046 -v 0.041438 -0.019754 0.081095 -vn 4.501575 -2.626379 -0.824229 -v 0.041441 -0.019855 0.081119 -vn 4.496871 2.655394 -0.912094 -v 0.041420 -0.019745 0.081006 -vn 4.282254 -2.651831 -1.542026 -v 0.041413 -0.019841 0.080981 -vn 4.226115 2.550666 -1.583761 -v 0.041374 -0.019731 0.080867 -vn 3.915744 -2.461568 -2.354261 -v 0.041322 -0.019818 0.080761 -vn 3.755869 2.540583 -2.500679 -v 0.041232 -0.019704 0.080626 -vn 3.714293 -2.417968 -2.644571 -v 0.041306 -0.019815 0.080733 -vn 3.113689 -2.668128 -3.344134 -v 0.041157 -0.019792 0.080543 -vn 3.319008 2.675189 -3.103560 -v 0.041157 -0.019693 0.080543 -vn 2.613123 -2.472116 -3.752509 -v 0.041079 -0.019782 0.080473 -vn 2.405225 2.617955 -3.812178 -v 0.040936 -0.019667 0.080376 -vn 2.001765 -2.605490 -4.093102 -v 0.040941 -0.019766 0.080379 -vn 1.341693 -2.581092 -4.374590 -v 0.040764 -0.019748 0.080301 -vn 1.546673 2.673314 -4.261406 -v 0.040718 -0.019644 0.080287 -vn 0.697750 -2.664684 -4.511213 -v 0.040689 -0.019740 0.080279 -vn 0.814779 2.535256 -4.483116 -v 0.040574 -0.019630 0.080258 -vn 3.324019 -2.666565 3.163585 -v 0.041157 -0.019343 0.081957 -vn 2.994524 2.646425 3.375137 -v 0.041157 -0.019243 0.081957 -vn 2.912449 -2.492682 3.526236 -v 0.041024 -0.019359 0.082069 -vn 2.155658 2.686248 4.025067 -v 0.040941 -0.019269 0.082121 -vn 2.452113 -2.674495 3.839782 -v 0.040967 -0.019366 0.082106 -vn 1.650338 2.518058 4.256064 -v 0.040898 -0.019274 0.082144 -vn 1.456115 -2.580805 4.263745 -v 0.040718 -0.019392 0.082213 -vn 0.818520 2.558330 4.459892 -v 0.040689 -0.019295 0.082221 -vn 0.324824 2.421673 4.528448 -v 0.040537 -0.019310 0.082246 -vn 3.649719 -2.594801 2.765880 -v 0.041188 -0.019338 0.081925 -vn 3.860883 -2.589516 2.441864 -v 0.041283 -0.019324 0.081803 -vn 3.693548 2.669632 2.630258 -v 0.041306 -0.019220 0.081767 -vn 4.171223 -2.655410 1.855750 -v 0.041321 -0.019317 0.081741 -vn 4.117675 2.311845 1.861869 -v 0.041373 -0.019206 0.081634 -vn 4.304348 2.545563 1.414111 -v 0.041413 -0.019194 0.081519 -vn 4.432957 -2.547919 0.811494 -v 0.041421 -0.019291 0.081489 -vn 4.504978 2.558767 0.261594 -v 0.041450 -0.019168 0.081250 -vn 4.501631 -2.561579 -0.250259 -v 0.041450 -0.019268 0.081250 -vn 4.519715 2.579019 -0.660825 -v 0.041421 -0.019145 0.081011 -vn 4.363839 -2.660281 -1.307357 -v 0.041413 -0.019242 0.080981 -vn 4.366749 2.685642 -1.333267 -v 0.041396 -0.019137 0.080925 -vn 4.142096 -2.641020 -1.949647 -v 0.041385 -0.019233 0.080895 -vn 4.082140 2.631071 -1.985546 -v 0.041321 -0.019119 0.080759 -vn 3.736171 -2.626052 -2.590260 -v 0.041306 -0.019216 0.080733 -vn 3.723438 2.632845 -2.647751 -v 0.041217 -0.019102 0.080608 -vn 3.312453 -2.690727 -3.169306 -v 0.041190 -0.019197 0.080577 -vn 3.259124 2.620159 -3.174822 -v 0.041157 -0.019093 0.080543 -vn 2.833997 -2.631054 -3.561978 -v 0.041157 -0.019193 0.080543 -vn 2.245234 -2.675744 -3.961172 -v 0.040941 -0.019167 0.080379 -vn 2.563028 2.551760 -3.693190 -v 0.040967 -0.019070 0.080394 -vn 1.714754 -2.561739 -4.245341 -v 0.040924 -0.019165 0.080369 -vn 1.476386 2.569609 -4.234550 -v 0.040718 -0.019044 0.080287 -vn 0.870365 -2.547635 -4.457850 -v 0.040689 -0.019141 0.080279 -vn 0.444120 -2.288780 -4.513178 -v 0.040574 -0.019130 0.080258 -vn 4.468980 2.481133 0.856858 -v 0.041435 -0.018585 0.081424 -vn 4.240746 2.656995 1.623901 -v 0.041413 -0.018595 0.081519 -vn 4.482374 -2.656635 0.750393 -v 0.041421 -0.018691 0.081489 -vn 0.142365 2.675560 4.586922 -v 0.040514 -0.018713 0.082248 -vn 0.755127 -2.645774 4.518414 -v 0.040537 -0.018810 0.082246 -vn 0.831696 2.617909 4.488836 -v 0.040689 -0.018696 0.082221 -vn 1.484766 -2.626055 4.297869 -v 0.040718 -0.018792 0.082213 -vn 1.548676 2.629584 4.304827 -v 0.040860 -0.018678 0.082162 -vn 2.182345 -2.686924 4.019644 -v 0.040898 -0.018774 0.082144 -vn 2.171165 2.658291 3.994286 -v 0.040941 -0.018670 0.082121 -vn 2.752301 -2.566062 3.630835 -v 0.040967 -0.018766 0.082106 -vn 3.229053 -2.630891 3.215109 -v 0.041157 -0.018743 0.081957 -vn 2.946311 2.623645 3.366937 -v 0.041157 -0.018644 0.081957 -vn 3.658431 -2.603346 2.711368 -v 0.041188 -0.018739 0.081925 -vn 3.682688 2.598448 2.527378 -v 0.041306 -0.018621 0.081767 -vn 4.055438 -2.560539 2.026782 -v 0.041321 -0.018717 0.081741 -vn 4.237789 -2.289055 1.609629 -v 0.041373 -0.018705 0.081634 -vn 4.531668 2.581857 0.277634 -v 0.041450 -0.018569 0.081250 -vn 4.507941 -2.581969 -0.230515 -v 0.041450 -0.018668 0.081250 -vn 4.556741 2.506698 -0.461429 -v 0.041432 -0.018551 0.081062 -vn 4.374813 -2.673479 -1.329239 -v 0.041413 -0.018642 0.080981 -vn 4.461484 2.680250 -0.994170 -v 0.041421 -0.018546 0.081011 -vn 4.176559 -2.497324 -1.865649 -v 0.041396 -0.018636 0.080925 -vn 4.054241 2.603271 -1.979848 -v 0.041321 -0.018520 0.080759 -vn 3.763002 -2.597147 -2.558323 -v 0.041306 -0.018616 0.080733 -vn 3.416439 -2.495242 -3.031866 -v 0.041217 -0.018601 0.080609 -vn 3.467461 2.666162 -2.936743 -v 0.041157 -0.018494 0.080543 -vn 2.909600 -2.667948 -3.493669 -v 0.041157 -0.018593 0.080543 -vn 0.606361 -2.596722 -4.532278 -v 0.040689 -0.018541 0.080279 -vn 1.263291 2.678025 -4.390106 -v 0.040718 -0.018445 0.080287 -vn 1.157120 -2.701833 -4.424186 -v 0.040718 -0.018544 0.080287 -vn 1.841492 2.593280 -4.194819 -v 0.040759 -0.018449 0.080299 -vn 2.012415 -2.577547 -4.037587 -v 0.040941 -0.018567 0.080379 -vn 2.563924 2.551692 -3.753625 -v 0.040967 -0.018471 0.080394 -vn 2.912637 2.333206 -3.484170 -v 0.041075 -0.018483 0.080469 -vn 1.855017 2.665854 4.175673 -v 0.040941 -0.018070 0.082121 -vn 1.040366 2.657715 4.447003 -v 0.040689 -0.018096 0.082221 -vn 1.507892 -2.567881 4.305242 -v 0.040718 -0.018191 0.082213 -vn 0.511801 2.596491 4.549227 -v 0.040646 -0.018100 0.082231 -vn 0.672171 -2.611952 4.526348 -v 0.040514 -0.018211 0.082248 -vn 1.955738 -2.389426 4.111047 -v 0.040859 -0.018177 0.082162 -vn 2.663973 -2.665526 3.696585 -v 0.040967 -0.018165 0.082106 -vn 2.445803 2.599658 3.848168 -v 0.040998 -0.018063 0.082086 -vn 3.273646 -2.654636 3.202706 -v 0.041157 -0.018142 0.081957 -vn 2.960358 2.647441 3.443946 -v 0.041157 -0.018044 0.081957 -vn 3.648394 -2.661036 2.756788 -v 0.041188 -0.018138 0.081925 -vn 3.509774 2.554909 2.923810 -v 0.041257 -0.018029 0.081841 -vn 4.094313 -2.574235 1.917524 -v 0.041321 -0.018116 0.081741 -vn 3.836403 2.629851 2.448049 -v 0.041306 -0.018021 0.081767 -vn 4.255731 2.572011 1.520240 -v 0.041413 -0.017995 0.081519 -vn 4.444254 -2.644640 1.008467 -v 0.041421 -0.018090 0.081489 -vn 4.550509 -2.493206 0.436688 -v 0.041435 -0.018084 0.081425 -vn 4.537442 2.629189 0.354960 -v 0.041450 -0.017969 0.081250 -vn 4.529799 -2.637371 -0.254881 -v 0.041450 -0.018067 0.081250 -vn 4.567449 2.624605 -0.309993 -v 0.041441 -0.017956 0.081119 -vn 4.450418 -2.689569 -1.009858 -v 0.041432 -0.018049 0.081062 -vn 4.435370 2.663927 -0.983163 -v 0.041421 -0.017946 0.081011 -vn 4.224519 -2.589105 -1.672919 -v 0.041413 -0.018041 0.080981 -vn 4.060309 2.543297 -1.964722 -v 0.041321 -0.017920 0.080759 -vn 3.716501 -2.550874 -2.542584 -v 0.041306 -0.018015 0.080733 -vn 3.502079 2.612409 -2.917041 -v 0.041157 -0.017894 0.080543 -vn 3.133323 -2.618869 -3.292149 -v 0.041157 -0.017992 0.080543 -vn 3.041986 2.666171 -3.416920 -v 0.041079 -0.017884 0.080473 -vn 2.620126 -2.663280 -3.743718 -v 0.041075 -0.017982 0.080469 -vn 2.511259 2.635405 -3.783608 -v 0.040967 -0.017870 0.080394 -vn 1.936805 -2.604737 -4.110087 -v 0.040941 -0.017966 0.080379 -vn 1.844368 2.658022 -4.181861 -v 0.040764 -0.017849 0.080301 -vn 1.312420 -2.666928 -4.370812 -v 0.040759 -0.017947 0.080299 -vn 1.373174 2.693771 -4.379746 -v 0.040718 -0.017844 0.080287 -vn 0.662714 -2.665642 -4.492213 -v 0.040689 -0.017940 0.080279 -vn 0.776229 2.533148 -4.502379 -v 0.040554 -0.017828 0.080255 -vn 0.269862 2.600983 4.575921 -v 0.040566 -0.017507 0.082243 -vn 1.044290 -2.680433 4.457370 -v 0.040646 -0.017598 0.082231 -vn 0.863573 2.680625 4.501686 -v 0.040687 -0.017496 0.082222 -vn 1.630609 -2.663217 4.251004 -v 0.040718 -0.017591 0.082213 -vn 1.564181 2.470977 4.274380 -v 0.040833 -0.017481 0.082174 -vn 2.526761 -2.566134 3.736932 -v 0.040967 -0.017565 0.082106 -vn 2.312205 2.615533 3.946782 -v 0.041024 -0.017460 0.082069 -vn 2.762163 2.273206 3.599100 -v 0.041056 -0.017456 0.082046 -vn 3.553808 2.651854 2.848539 -v 0.041248 -0.017430 0.081852 -vn 4.109882 -2.453652 1.909529 -v 0.041321 -0.017516 0.081741 -vn 4.071805 2.482835 1.949470 -v 0.041384 -0.017403 0.081607 -vn 4.444154 -2.654656 0.849700 -v 0.041421 -0.017490 0.081489 -vn 4.359883 2.656682 1.358981 -v 0.041420 -0.017392 0.081494 -vn 3.138717 2.575828 3.327349 -v 0.041188 -0.017439 0.081925 -vn 3.250483 -2.482476 3.150582 -v 0.041157 -0.017542 0.081957 -vn 3.823535 -2.645369 2.515830 -v 0.041257 -0.017528 0.081841 -vn 4.511497 2.531639 0.775328 -v 0.041444 -0.017378 0.081356 -vn 4.554647 -2.646952 -0.207215 -v 0.041450 -0.017467 0.081250 -vn 4.556279 2.662143 0.219346 -v 0.041450 -0.017369 0.081258 -vn 4.552309 2.647008 -0.392991 -v 0.041438 -0.017354 0.081095 -vn 4.501178 -2.626626 -0.824398 -v 0.041441 -0.017455 0.081119 -vn 4.496886 2.655425 -0.912104 -v 0.041420 -0.017345 0.081006 -vn 4.281914 -2.652004 -1.542058 -v 0.041413 -0.017441 0.080981 -vn 4.226071 2.550639 -1.583720 -v 0.041374 -0.017331 0.080867 -vn 3.915220 -2.461641 -2.354332 -v 0.041322 -0.017418 0.080761 -vn 3.755847 2.540592 -2.500700 -v 0.041232 -0.017304 0.080626 -vn 3.686204 -2.427775 -2.647216 -v 0.041306 -0.017415 0.080733 -vn 3.110097 -2.678906 -3.320911 -v 0.041157 -0.017392 0.080543 -vn 3.318995 2.675171 -3.103556 -v 0.041157 -0.017293 0.080543 -vn 2.612836 -2.472251 -3.752378 -v 0.041079 -0.017382 0.080473 -vn 2.405179 2.617947 -3.812191 -v 0.040936 -0.017267 0.080376 -vn 2.001511 -2.605647 -4.092884 -v 0.040941 -0.017366 0.080379 -vn 1.341411 -2.581277 -4.374372 -v 0.040764 -0.017348 0.080301 -vn 1.546713 2.673307 -4.261401 -v 0.040718 -0.017244 0.080287 -vn 0.697596 -2.664850 -4.510960 -v 0.040689 -0.017340 0.080279 -vn 0.814765 2.535302 -4.483070 -v 0.040574 -0.017230 0.080258 -vn 3.323936 -2.666745 3.163332 -v 0.041157 -0.016943 0.081957 -vn 2.994556 2.646461 3.375093 -v 0.041157 -0.016843 0.081957 -vn 2.912306 -2.492580 3.525986 -v 0.041024 -0.016959 0.082069 -vn 2.155694 2.686335 4.025061 -v 0.040941 -0.016869 0.082121 -vn 2.451959 -2.674720 3.839572 -v 0.040967 -0.016966 0.082106 -vn 1.650382 2.518004 4.256032 -v 0.040898 -0.016874 0.082144 -vn 1.456051 -2.580934 4.263511 -v 0.040718 -0.016992 0.082213 -vn 0.818515 2.558329 4.459905 -v 0.040689 -0.016895 0.082221 -vn 0.324836 2.421641 4.528447 -v 0.040537 -0.016910 0.082246 -vn 3.649566 -2.594883 2.765653 -v 0.041188 -0.016938 0.081925 -vn 3.860742 -2.589729 2.441562 -v 0.041283 -0.016924 0.081803 -vn 3.693536 2.669600 2.630316 -v 0.041306 -0.016820 0.081767 -vn 4.168436 -2.657567 1.850489 -v 0.041321 -0.016917 0.081741 -vn 4.117627 2.311902 1.861864 -v 0.041373 -0.016806 0.081634 -vn 4.304379 2.545558 1.414073 -v 0.041413 -0.016794 0.081519 -vn 4.429254 -2.549744 0.813184 -v 0.041421 -0.016891 0.081489 -vn 4.504969 2.558766 0.261600 -v 0.041450 -0.016768 0.081250 -vn 4.501403 -2.561691 -0.250277 -v 0.041450 -0.016868 0.081250 -vn 4.519739 2.579024 -0.660786 -v 0.041421 -0.016745 0.081011 -vn 4.363585 -2.660421 -1.307334 -v 0.041413 -0.016842 0.080981 -vn 4.366750 2.685535 -1.333269 -v 0.041396 -0.016737 0.080925 -vn 4.141823 -2.641207 -1.949702 -v 0.041385 -0.016833 0.080895 -vn 4.082134 2.631076 -1.985597 -v 0.041321 -0.016719 0.080759 -vn 3.735948 -2.626144 -2.590207 -v 0.041306 -0.016816 0.080733 -vn 3.723436 2.632938 -2.647708 -v 0.041217 -0.016702 0.080608 -vn 3.312202 -2.690781 -3.169250 -v 0.041190 -0.016797 0.080577 -vn 3.259131 2.620152 -3.174836 -v 0.041157 -0.016693 0.080543 -vn 2.833790 -2.631190 -3.561895 -v 0.041157 -0.016793 0.080543 -vn 2.244533 -2.675519 -3.961179 -v 0.040941 -0.016767 0.080379 -vn 2.563017 2.551743 -3.693198 -v 0.040967 -0.016670 0.080394 -vn 1.714241 -2.561952 -4.245472 -v 0.040924 -0.016765 0.080369 -vn 1.468996 2.572855 -4.230901 -v 0.040718 -0.016644 0.080287 -vn 0.870258 -2.547751 -4.457635 -v 0.040689 -0.016741 0.080279 -vn 0.444028 -2.288825 -4.513007 -v 0.040574 -0.016730 0.080258 -vn 4.469020 2.481157 0.856836 -v 0.041435 -0.016185 0.081424 -vn 4.240757 2.656993 1.623858 -v 0.041413 -0.016195 0.081519 -vn 4.482245 -2.656695 0.750343 -v 0.041421 -0.016291 0.081489 -vn 0.142342 2.675600 4.586937 -v 0.040514 -0.016313 0.082248 -vn 0.755127 -2.645793 4.518183 -v 0.040537 -0.016410 0.082246 -vn 0.831692 2.617941 4.488850 -v 0.040689 -0.016296 0.082221 -vn 1.484803 -2.626140 4.297723 -v 0.040718 -0.016392 0.082213 -vn 1.548719 2.629457 4.304717 -v 0.040860 -0.016278 0.082162 -vn 2.182339 -2.687155 4.019536 -v 0.040898 -0.016373 0.082144 -vn 2.171229 2.658256 3.994283 -v 0.040941 -0.016270 0.082121 -vn 2.752148 -2.566133 3.630732 -v 0.040967 -0.016366 0.082106 -vn 3.228960 -2.630969 3.214987 -v 0.041157 -0.016343 0.081957 -vn 2.946302 2.623651 3.366929 -v 0.041157 -0.016244 0.081957 -vn 3.658315 -2.603424 2.711269 -v 0.041188 -0.016339 0.081925 -vn 3.682687 2.598447 2.527385 -v 0.041306 -0.016221 0.081767 -vn 4.055323 -2.560613 2.026663 -v 0.041321 -0.016317 0.081741 -vn 4.237750 -2.289296 1.609474 -v 0.041373 -0.016305 0.081634 -vn 4.531663 2.581859 0.277637 -v 0.041450 -0.016169 0.081250 -vn 4.507808 -2.582032 -0.230520 -v 0.041450 -0.016268 0.081250 -vn 4.556730 2.506703 -0.461426 -v 0.041432 -0.016151 0.081062 -vn 4.374628 -2.673510 -1.329296 -v 0.041413 -0.016242 0.080981 -vn 4.461478 2.680250 -0.994165 -v 0.041421 -0.016146 0.081011 -vn 4.176408 -2.497375 -1.865697 -v 0.041396 -0.016236 0.080925 -vn 4.054227 2.603281 -1.979865 -v 0.041321 -0.016120 0.080759 -vn 3.762845 -2.597204 -2.558303 -v 0.041306 -0.016216 0.080733 -vn 3.416319 -2.495327 -3.031841 -v 0.041217 -0.016201 0.080608 -vn 3.467465 2.666164 -2.936737 -v 0.041157 -0.016094 0.080543 -vn 2.909475 -2.668030 -3.493602 -v 0.041157 -0.016193 0.080543 -vn 0.603392 -2.592826 -4.539753 -v 0.040689 -0.016141 0.080279 -vn 1.263293 2.678035 -4.390113 -v 0.040718 -0.016045 0.080287 -vn 1.172859 -2.708193 -4.409697 -v 0.040718 -0.016144 0.080287 -vn 1.841500 2.593256 -4.194818 -v 0.040759 -0.016049 0.080299 -vn 1.986882 -2.587015 -4.025663 -v 0.040941 -0.016167 0.080379 -vn 2.563928 2.551689 -3.753627 -v 0.040967 -0.016071 0.080394 -vn 2.912639 2.333204 -3.484174 -v 0.041075 -0.016083 0.080469 -vn 1.855013 2.665854 4.175671 -v 0.040941 -0.015670 0.082121 -vn 1.040365 2.657717 4.447000 -v 0.040689 -0.015696 0.082221 -vn 1.507907 -2.567930 4.305136 -v 0.040718 -0.015791 0.082213 -vn 0.511812 2.596520 4.549223 -v 0.040646 -0.015700 0.082231 -vn 0.672133 -2.611954 4.526256 -v 0.040514 -0.015811 0.082248 -vn 1.955772 -2.389525 4.111010 -v 0.040859 -0.015777 0.082162 -vn 2.663925 -2.665562 3.696539 -v 0.040967 -0.015765 0.082106 -vn 2.445800 2.599660 3.848165 -v 0.040998 -0.015663 0.082086 -vn 3.273645 -2.654693 3.202521 -v 0.041157 -0.015742 0.081957 -vn 2.960354 2.647444 3.443944 -v 0.041157 -0.015644 0.081957 -vn 3.648460 -2.661018 2.756744 -v 0.041188 -0.015738 0.081925 -vn 3.509772 2.554914 2.923793 -v 0.041257 -0.015629 0.081841 -vn 4.094246 -2.574273 1.917505 -v 0.041321 -0.015716 0.081741 -vn 3.836416 2.629848 2.448042 -v 0.041306 -0.015621 0.081767 -vn 4.255734 2.572002 1.520232 -v 0.041413 -0.015595 0.081519 -vn 4.444204 -2.644634 1.008406 -v 0.041421 -0.015690 0.081489 -vn 4.550457 -2.493274 0.436646 -v 0.041435 -0.015684 0.081424 -vn 4.537442 2.629185 0.354964 -v 0.041450 -0.015569 0.081250 -vn 4.529753 -2.637393 -0.254864 -v 0.041450 -0.015667 0.081250 -vn 4.567451 2.624624 -0.309980 -v 0.041441 -0.015556 0.081119 -vn 4.450339 -2.689549 -1.009887 -v 0.041432 -0.015649 0.081062 -vn 4.435369 2.663948 -0.983174 -v 0.041421 -0.015546 0.081011 -vn 4.224487 -2.589125 -1.672957 -v 0.041413 -0.015641 0.080981 -vn 4.060310 2.543297 -1.964722 -v 0.041321 -0.015520 0.080759 -vn 3.716468 -2.550893 -2.542562 -v 0.041306 -0.015615 0.080733 -vn 3.502079 2.612409 -2.917041 -v 0.041157 -0.015494 0.080543 -vn 3.133244 -2.618890 -3.292144 -v 0.041157 -0.015592 0.080543 -vn 3.041986 2.666150 -3.416919 -v 0.041079 -0.015484 0.080473 -vn 2.620046 -2.663329 -3.743777 -v 0.041075 -0.015582 0.080469 -vn 2.511261 2.635404 -3.783606 -v 0.040967 -0.015470 0.080394 -vn 1.936776 -2.604739 -4.110085 -v 0.040941 -0.015566 0.080379 -vn 1.844465 2.657876 -4.181895 -v 0.040764 -0.015449 0.080301 -vn 1.312480 -2.667080 -4.370849 -v 0.040759 -0.015547 0.080299 -vn 1.373277 2.693752 -4.379647 -v 0.040718 -0.015444 0.080287 -vn 0.662811 -2.665664 -4.492105 -v 0.040689 -0.015540 0.080279 -vn 0.776181 2.533177 -4.502342 -v 0.040554 -0.015428 0.080255 -vn 0.269907 2.600975 4.575941 -v 0.040566 -0.015107 0.082243 -vn 1.044351 -2.680448 4.457315 -v 0.040646 -0.015198 0.082231 -vn 0.863569 2.680622 4.501694 -v 0.040687 -0.015096 0.082222 -vn 1.630679 -2.663186 4.251035 -v 0.040718 -0.015191 0.082213 -vn 1.564190 2.470964 4.274387 -v 0.040833 -0.015081 0.082174 -vn 2.526768 -2.566123 3.736948 -v 0.040967 -0.015165 0.082106 -vn 2.312207 2.615530 3.946780 -v 0.041024 -0.015060 0.082069 -vn 2.762164 2.273186 3.599104 -v 0.041056 -0.015056 0.082046 -vn 3.553808 2.651854 2.848540 -v 0.041248 -0.015030 0.081852 -vn 4.109882 -2.453652 1.909529 -v 0.041321 -0.015116 0.081741 -vn 4.071805 2.482835 1.949470 -v 0.041384 -0.015003 0.081607 -vn 4.444147 -2.654661 0.849692 -v 0.041421 -0.015090 0.081489 -vn 4.359883 2.656682 1.358981 -v 0.041420 -0.014992 0.081494 -vn 3.138729 2.575823 3.327349 -v 0.041188 -0.015039 0.081925 -vn 3.250483 -2.482457 3.150631 -v 0.041157 -0.015142 0.081957 -vn 3.823506 -2.645379 2.515843 -v 0.041257 -0.015128 0.081841 -vn 4.511497 2.531639 0.775328 -v 0.041444 -0.014978 0.081356 -vn 4.554641 -2.646955 -0.207210 -v 0.041450 -0.015067 0.081250 -vn 4.556279 2.662143 0.219346 -v 0.041450 -0.014969 0.081258 -vn 4.552309 2.647008 -0.392991 -v 0.041438 -0.014954 0.081095 -vn 4.501152 -2.626633 -0.824430 -v 0.041441 -0.015055 0.081119 -vn 4.496887 2.655425 -0.912103 -v 0.041420 -0.014945 0.081006 -vn 4.281952 -2.651983 -1.542079 -v 0.041413 -0.015041 0.080981 -vn 4.226071 2.550636 -1.583720 -v 0.041374 -0.014931 0.080867 -vn 3.915219 -2.461647 -2.354312 -v 0.041322 -0.015018 0.080761 -vn 3.755846 2.540588 -2.500701 -v 0.041232 -0.014904 0.080626 -vn 3.686188 -2.427777 -2.647226 -v 0.041306 -0.015015 0.080733 -vn 3.110159 -2.678882 -3.320931 -v 0.041157 -0.014992 0.080543 -vn 3.319009 2.675167 -3.103551 -v 0.041157 -0.014893 0.080543 -vn 2.612854 -2.472270 -3.752335 -v 0.041079 -0.014982 0.080473 -vn 2.405160 2.617964 -3.812155 -v 0.040936 -0.014867 0.080376 -vn 2.001511 -2.605647 -4.092884 -v 0.040941 -0.014966 0.080379 -vn 1.341401 -2.581283 -4.374365 -v 0.040764 -0.014948 0.080301 -vn 1.546698 2.673305 -4.261415 -v 0.040718 -0.014844 0.080287 -vn 0.697599 -2.664856 -4.510950 -v 0.040689 -0.014940 0.080279 -vn 0.814765 2.535302 -4.483070 -v 0.040574 -0.014830 0.080258 -vn 3.323969 -2.666773 3.163192 -v 0.041157 -0.014543 0.081957 -vn 2.994554 2.646463 3.375094 -v 0.041157 -0.014443 0.081957 -vn 2.912306 -2.492580 3.525986 -v 0.041024 -0.014559 0.082069 -vn 2.155694 2.686335 4.025061 -v 0.040941 -0.014469 0.082121 -vn 2.451951 -2.674724 3.839568 -v 0.040967 -0.014566 0.082106 -vn 1.650382 2.518004 4.256032 -v 0.040898 -0.014474 0.082144 -vn 1.456055 -2.580938 4.263502 -v 0.040718 -0.014592 0.082213 -vn 0.818546 2.558324 4.459914 -v 0.040689 -0.014495 0.082221 -vn 0.324793 2.421689 4.528386 -v 0.040537 -0.014510 0.082246 -vn 3.649681 -2.594836 2.765625 -v 0.041188 -0.014538 0.081925 -vn 3.860750 -2.589702 2.441657 -v 0.041283 -0.014524 0.081803 -vn 3.693536 2.669602 2.630315 -v 0.041306 -0.014420 0.081767 -vn 4.168376 -2.657591 1.850507 -v 0.041321 -0.014517 0.081741 -vn 4.117633 2.311898 1.861872 -v 0.041373 -0.014406 0.081634 -vn 4.304395 2.545549 1.414078 -v 0.041413 -0.014394 0.081519 -vn 4.429287 -2.549728 0.813193 -v 0.041421 -0.014491 0.081489 -vn 4.504979 2.558763 0.261595 -v 0.041450 -0.014368 0.081250 -vn 4.501392 -2.561697 -0.250261 -v 0.041450 -0.014468 0.081250 -vn 4.519739 2.579024 -0.660786 -v 0.041421 -0.014345 0.081011 -vn 4.363585 -2.660421 -1.307334 -v 0.041413 -0.014442 0.080981 -vn 4.366750 2.685535 -1.333269 -v 0.041396 -0.014337 0.080925 -vn 4.141823 -2.641207 -1.949702 -v 0.041385 -0.014433 0.080895 -vn 4.082134 2.631076 -1.985597 -v 0.041321 -0.014319 0.080759 -vn 3.735948 -2.626144 -2.590207 -v 0.041306 -0.014416 0.080733 -vn 3.723436 2.632938 -2.647708 -v 0.041217 -0.014302 0.080608 -vn 3.312202 -2.690781 -3.169250 -v 0.041190 -0.014397 0.080577 -vn 3.259131 2.620152 -3.174836 -v 0.041157 -0.014293 0.080543 -vn 2.833790 -2.631190 -3.561895 -v 0.041157 -0.014393 0.080543 -vn 2.244533 -2.675519 -3.961179 -v 0.040941 -0.014367 0.080379 -vn 2.563017 2.551743 -3.693198 -v 0.040967 -0.014270 0.080394 -vn 1.714241 -2.561952 -4.245472 -v 0.040924 -0.014365 0.080369 -vn 1.468997 2.572855 -4.230903 -v 0.040718 -0.014244 0.080287 -vn 0.870258 -2.547751 -4.457635 -v 0.040689 -0.014341 0.080279 -vn 0.444028 -2.288825 -4.513007 -v 0.040574 -0.014330 0.080258 -vn 4.469020 2.481157 0.856836 -v 0.041435 -0.013785 0.081424 -vn 4.240757 2.656993 1.623858 -v 0.041413 -0.013795 0.081519 -vn 4.482230 -2.656703 0.750339 -v 0.041421 -0.013891 0.081489 -vn 0.142342 2.675600 4.586937 -v 0.040514 -0.013913 0.082248 -vn 0.755127 -2.645793 4.518183 -v 0.040537 -0.014010 0.082246 -vn 0.831692 2.617941 4.488850 -v 0.040689 -0.013896 0.082221 -vn 1.484803 -2.626140 4.297723 -v 0.040718 -0.013992 0.082213 -vn 1.548719 2.629457 4.304717 -v 0.040860 -0.013878 0.082162 -vn 2.182339 -2.687155 4.019536 -v 0.040898 -0.013973 0.082144 -vn 2.171229 2.658256 3.994283 -v 0.040941 -0.013870 0.082121 -vn 2.752148 -2.566133 3.630732 -v 0.040967 -0.013966 0.082106 -vn 3.228960 -2.630969 3.214987 -v 0.041157 -0.013943 0.081957 -vn 2.946302 2.623651 3.366929 -v 0.041157 -0.013844 0.081957 -vn 3.658315 -2.603424 2.711269 -v 0.041188 -0.013939 0.081925 -vn 3.682687 2.598447 2.527385 -v 0.041306 -0.013821 0.081767 -vn 4.055323 -2.560613 2.026663 -v 0.041321 -0.013917 0.081741 -vn 4.237743 -2.289300 1.609465 -v 0.041373 -0.013905 0.081634 -vn 4.531663 2.581859 0.277637 -v 0.041450 -0.013769 0.081250 -vn 4.507792 -2.582040 -0.230521 -v 0.041450 -0.013868 0.081250 -vn 4.556730 2.506703 -0.461426 -v 0.041432 -0.013751 0.081062 -vn 4.374623 -2.673514 -1.329291 -v 0.041413 -0.013842 0.080981 -vn 4.461478 2.680250 -0.994165 -v 0.041421 -0.013746 0.081011 -vn 4.176408 -2.497375 -1.865697 -v 0.041396 -0.013836 0.080925 -vn 4.054227 2.603281 -1.979865 -v 0.041321 -0.013720 0.080759 -vn 3.762845 -2.597204 -2.558303 -v 0.041306 -0.013816 0.080733 -vn 3.416255 -2.495339 -3.031863 -v 0.041217 -0.013801 0.080608 -vn 3.467459 2.666167 -2.936736 -v 0.041157 -0.013694 0.080543 -vn 2.909488 -2.668003 -3.493661 -v 0.041157 -0.013793 0.080543 -vn 0.603396 -2.592832 -4.539745 -v 0.040689 -0.013741 0.080279 -vn 1.263293 2.678035 -4.390113 -v 0.040718 -0.013645 0.080287 -vn 1.172853 -2.708201 -4.409681 -v 0.040718 -0.013744 0.080287 -vn 1.841500 2.593256 -4.194818 -v 0.040759 -0.013649 0.080299 -vn 1.986882 -2.587023 -4.025644 -v 0.040941 -0.013767 0.080379 -vn 2.563928 2.551691 -3.753618 -v 0.040967 -0.013671 0.080394 -vn 2.912628 2.333196 -3.484165 -v 0.041075 -0.013683 0.080469 -vn 1.908518 2.660319 4.107093 -v 0.040941 -0.013270 0.082121 -vn 1.195829 2.664567 4.401483 -v 0.040712 -0.013293 0.082215 -vn 1.476594 -2.593814 4.314654 -v 0.040718 -0.013391 0.082213 -vn 0.633533 2.636556 4.539822 -v 0.040689 -0.013296 0.082221 -vn 0.694310 -2.567674 4.521539 -v 0.040514 -0.013411 0.082248 -vn 1.955800 -2.389534 4.110970 -v 0.040859 -0.013377 0.082162 -vn 2.655042 -2.653996 3.703137 -v 0.040967 -0.013365 0.082106 -vn 2.593694 2.532265 3.747538 -v 0.041065 -0.013255 0.082039 -vn 3.302738 -2.689600 3.178124 -v 0.041157 -0.013342 0.081957 -vn 3.090101 2.666901 3.335698 -v 0.041157 -0.013244 0.081957 -vn 3.670709 -2.593760 2.725639 -v 0.041188 -0.013338 0.081925 -vn 3.652334 2.622771 2.761446 -v 0.041306 -0.013221 0.081767 -vn 4.073880 -2.612166 1.955289 -v 0.041321 -0.013316 0.081741 -vn 3.983703 2.637696 2.255994 -v 0.041322 -0.013217 0.081739 -vn 4.271664 2.563257 1.576981 -v 0.041413 -0.013195 0.081519 -vn 4.447134 -2.623441 0.992430 -v 0.041421 -0.013290 0.081489 -vn 4.501556 2.553525 0.732985 -v 0.041444 -0.013179 0.081363 -vn 4.547907 -2.596927 0.488908 -v 0.041435 -0.013284 0.081424 -vn 4.539321 2.589727 0.141294 -v 0.041450 -0.013169 0.081250 -vn 4.525027 -2.590337 -0.304043 -v 0.041450 -0.013267 0.081250 -vn 4.528547 2.676704 -0.649620 -v 0.041421 -0.013146 0.081011 -vn 4.456708 -2.525299 -0.900329 -v 0.041432 -0.013249 0.081062 -vn 4.230530 -2.648760 -1.660386 -v 0.041413 -0.013241 0.080981 -vn 4.394992 2.607701 -1.269231 -v 0.041410 -0.013141 0.080969 -vn 3.752560 -2.615410 -2.493056 -v 0.041306 -0.013215 0.080733 -vn 0.757711 2.539005 -4.504768 -v 0.040545 -0.013028 0.080254 -vn 0.659680 -2.660382 -4.492573 -v 0.040689 -0.013140 0.080279 -vn 1.504103 2.667819 -4.276065 -v 0.040718 -0.013044 0.080287 -vn 1.320110 -2.610763 -4.366454 -v 0.040759 -0.013147 0.080299 -vn 2.214203 2.651284 -3.990126 -v 0.040922 -0.013066 0.080368 -vn 1.959248 -2.664437 -4.100515 -v 0.040941 -0.013166 0.080379 -vn 2.720695 2.662796 -3.672182 -v 0.040967 -0.013070 0.080394 -vn 2.621099 -2.532566 -3.735136 -v 0.041075 -0.013182 0.080469 -vn 3.333017 2.677386 -3.100062 -v 0.041157 -0.013094 0.080543 -vn 3.090324 -2.674676 -3.343612 -v 0.041157 -0.013192 0.080543 -vn 3.730683 2.534169 -2.633088 -v 0.041227 -0.013104 0.080620 -vn 4.133111 2.548198 -1.907154 -v 0.041321 -0.013120 0.080759 -vn 0.330848 2.607395 4.531985 -v 0.040566 -0.012707 0.082243 -vn 1.077612 -2.572640 4.436625 -v 0.040646 -0.012798 0.082231 -vn 1.258614 2.496388 4.372098 -v 0.040784 -0.012686 0.082192 -vn 3.342053 -2.668690 3.067742 -v 0.041157 -0.012742 0.081957 -vn 2.844837 2.584278 3.599864 -v 0.041123 -0.012648 0.081990 -vn 2.520266 -2.497892 3.744399 -v 0.040967 -0.012765 0.082106 -vn 2.514894 2.416188 3.774945 -v 0.041056 -0.012656 0.082046 -vn 1.564465 -2.560492 4.281548 -v 0.040718 -0.012791 0.082213 -vn 1.584887 2.296417 4.251190 -v 0.040833 -0.012681 0.082174 -vn 4.446310 -2.653833 0.837874 -v 0.041421 -0.012690 0.081489 -vn 4.187052 2.472869 1.858556 -v 0.041384 -0.012603 0.081607 -vn 4.079736 -2.480739 1.987951 -v 0.041321 -0.012716 0.081741 -vn 3.994616 2.543660 2.207244 -v 0.041357 -0.012610 0.081671 -vn 3.831990 -2.613969 2.486192 -v 0.041257 -0.012728 0.081841 -vn 3.558502 2.620543 2.877754 -v 0.041248 -0.012630 0.081852 -vn 3.237566 2.628941 3.248692 -v 0.041188 -0.012639 0.081925 -vn 4.538676 -2.628311 -0.219222 -v 0.041450 -0.012667 0.081250 -vn 4.502610 2.534754 0.807506 -v 0.041444 -0.012578 0.081356 -vn 4.372404 2.654745 1.341221 -v 0.041420 -0.012592 0.081494 -vn 3.702474 -2.422519 -2.645523 -v 0.041306 -0.012615 0.080733 -vn 3.097110 -2.686400 -3.336983 -v 0.041157 -0.012592 0.080543 -vn 3.778492 2.536680 -2.487114 -v 0.041232 -0.012504 0.080626 -vn 3.917640 -2.458501 -2.361011 -v 0.041322 -0.012618 0.080761 -vn 4.222569 2.552835 -1.666941 -v 0.041374 -0.012531 0.080867 -vn 4.294162 -2.661931 -1.533375 -v 0.041413 -0.012641 0.080981 -vn 4.394329 2.578341 -1.350996 -v 0.041386 -0.012534 0.080898 -vn 4.516022 2.660092 -0.879993 -v 0.041420 -0.012545 0.081006 -vn 4.493093 -2.631892 -0.816947 -v 0.041441 -0.012655 0.081119 -vn 4.544383 2.648520 -0.370550 -v 0.041438 -0.012554 0.081095 -vn 4.553950 2.658478 0.324733 -v 0.041449 -0.012572 0.081288 -vn 0.362112 -2.446930 -4.537888 -v 0.040554 -0.012527 0.080255 -vn 0.512584 2.596734 -4.537378 -v 0.040469 -0.012420 0.080250 -vn 0.707447 -2.598246 -4.524627 -v 0.040689 -0.012540 0.080279 -vn 1.369740 2.665759 -4.320184 -v 0.040718 -0.012444 0.080287 -vn 1.293108 -2.659302 -4.401621 -v 0.040764 -0.012548 0.080301 -vn 2.040574 2.607165 -4.098927 -v 0.040854 -0.012458 0.080335 -vn 2.028707 -2.633639 -4.082514 -v 0.040941 -0.012566 0.080379 -vn 2.552388 2.646861 -3.779352 -v 0.040936 -0.012467 0.080376 -vn 2.612234 -2.477701 -3.741032 -v 0.041079 -0.012582 0.080473 -vn 3.273021 2.705925 -3.191154 -v 0.041157 -0.012493 0.080543 -vn 3.570600 2.684725 -2.913387 -v 0.041177 -0.012496 0.080563 -vn 0.099228 2.611810 4.569487 -v 0.040469 -0.012116 0.082250 -vn 1.414539 -2.612679 4.269903 -v 0.040718 -0.012192 0.082213 -vn 0.731193 2.560096 4.477637 -v 0.040689 -0.012095 0.082221 -vn 1.565912 2.476311 4.280190 -v 0.040854 -0.012078 0.082165 -vn 2.463333 -2.670734 3.839600 -v 0.040967 -0.012166 0.082106 -vn 2.092777 2.655969 4.039100 -v 0.040941 -0.012069 0.082121 -vn 2.912320 -2.492673 3.525941 -v 0.041024 -0.012159 0.082069 -vn 2.884395 2.673001 3.553107 -v 0.041157 -0.012043 0.081957 -vn 3.324132 -2.666519 3.172318 -v 0.041157 -0.012143 0.081957 -vn 3.283023 2.689514 3.178016 -v 0.041177 -0.012040 0.081937 -vn 3.652442 -2.643868 2.772549 -v 0.041188 -0.012138 0.081925 -vn 3.715724 2.662909 2.592380 -v 0.041306 -0.012020 0.081767 -vn 4.444483 -2.577290 0.770452 -v 0.041421 -0.012091 0.081489 -vn 4.141180 2.480195 1.904470 -v 0.041386 -0.012002 0.081602 -vn 4.169139 -2.643224 1.856070 -v 0.041321 -0.012117 0.081741 -vn 3.862378 -2.592400 2.439680 -v 0.041283 -0.012124 0.081803 -vn 4.500000 -2.597893 -0.229982 -v 0.041450 -0.012068 0.081250 -vn 4.547114 2.640680 0.490614 -v 0.041450 -0.011968 0.081250 -vn 4.351061 2.631079 1.326498 -v 0.041413 -0.011994 0.081519 -vn 1.993598 -2.601546 -4.018827 -v 0.040941 -0.011967 0.080379 -vn 1.707997 2.117951 -4.165900 -v 0.040784 -0.011851 0.080308 -vn 2.607995 2.558551 -3.717767 -v 0.040967 -0.011870 0.080394 -vn 2.859269 -2.686729 -3.533481 -v 0.041157 -0.011993 0.080543 -vn 3.091502 2.539026 -3.364181 -v 0.041123 -0.011889 0.080510 -vn 3.439201 2.722386 -3.064849 -v 0.041157 -0.011893 0.080543 -vn 3.326248 -2.661767 -3.129943 -v 0.041190 -0.011997 0.080577 -vn 3.647496 2.664634 -2.752012 -v 0.041188 -0.011898 0.080575 -vn 3.712418 -2.599883 -2.608901 -v 0.041306 -0.012016 0.080733 -vn 4.050821 2.617551 -2.098074 -v 0.041321 -0.011919 0.080759 -vn 4.164093 -2.545588 -1.860686 -v 0.041385 -0.012033 0.080895 -vn 4.247902 2.562145 -1.647525 -v 0.041357 -0.011927 0.080829 -vn 4.340822 -2.600050 -1.351894 -v 0.041413 -0.012042 0.080981 -vn 4.461511 2.567972 -0.760942 -v 0.041421 -0.011945 0.081011 -vn 4.557417 2.573255 -0.165617 -v 0.041449 -0.011965 0.081212 -vn 1.365656 2.547757 -4.326978 -v 0.040718 -0.011844 0.080287 -vn 0.887386 -2.545131 -4.445816 -v 0.040689 -0.011941 0.080279 -vn 0.444380 -2.290413 -4.510006 -v 0.040574 -0.011930 0.080258 -vn 0.254063 2.654991 4.566298 -v 0.040545 -0.011510 0.082245 -vn 0.735071 -2.655118 4.519865 -v 0.040537 -0.011610 0.082246 -vn 0.899864 2.612404 4.445846 -v 0.040689 -0.011496 0.082221 -vn 1.521025 -2.579950 4.279942 -v 0.040718 -0.011592 0.082213 -vn 1.737998 2.668537 4.235883 -v 0.040922 -0.011472 0.082132 -vn 2.113642 -2.599081 4.046712 -v 0.040898 -0.011573 0.082144 -vn 2.239204 2.664639 3.986506 -v 0.040941 -0.011470 0.082121 -vn 2.755780 -2.570807 3.614015 -v 0.040967 -0.011566 0.082106 -vn 3.213430 -2.637732 3.213953 -v 0.041157 -0.011543 0.081957 -vn 2.894709 2.615187 3.523135 -v 0.041157 -0.011444 0.081957 -vn 3.648727 -2.674624 2.767858 -v 0.041188 -0.011539 0.081925 -vn 3.462496 2.540864 2.991446 -v 0.041227 -0.011434 0.081880 -vn 3.791192 2.573322 2.515897 -v 0.041306 -0.011421 0.081767 -vn 4.073495 -2.562092 2.019421 -v 0.041321 -0.011517 0.081741 -vn 4.240633 2.656905 1.735072 -v 0.041410 -0.011396 0.081530 -vn 4.239186 -2.358540 1.602273 -v 0.041373 -0.011505 0.081634 -vn 4.479403 -2.579685 0.696542 -v 0.041421 -0.011491 0.081489 -vn 4.467995 2.568730 -0.848731 -v 0.041421 -0.011346 0.081011 -vn 4.527052 2.321107 -0.407947 -v 0.041444 -0.011358 0.081136 -vn 4.498864 -2.606113 -0.218234 -v 0.041450 -0.011468 0.081250 -vn 4.525996 2.613549 0.411023 -v 0.041450 -0.011369 0.081250 -vn 4.401320 2.682048 1.233876 -v 0.041413 -0.011395 0.081519 -vn 4.372135 -2.648656 -1.295600 -v 0.041413 -0.011442 0.080981 -vn 4.163891 -2.504163 -1.861355 -v 0.041396 -0.011436 0.080925 -vn 4.025990 2.593704 -2.002196 -v 0.041321 -0.011320 0.080759 -vn 3.691039 -2.561007 -2.611452 -v 0.041306 -0.011416 0.080733 -vn 3.479293 2.615343 -2.899437 -v 0.041157 -0.011294 0.080543 -vn 3.123961 -2.610635 -3.297312 -v 0.041157 -0.011393 0.080543 -vn 3.014282 2.664283 -3.444640 -v 0.041065 -0.011282 0.080461 -vn 2.570436 -2.661315 -3.789281 -v 0.041056 -0.011380 0.080455 -vn 2.456644 2.636683 -3.818998 -v 0.040967 -0.011271 0.080394 -vn 1.871960 -2.574713 -4.140007 -v 0.040941 -0.011367 0.080379 -vn 1.446603 2.603849 -4.257720 -v 0.040718 -0.011245 0.080287 -vn 0.604983 -2.592079 -4.541209 -v 0.040689 -0.011341 0.080279 -vn 1.213436 -2.649207 -4.403353 -v 0.040718 -0.011344 0.080287 -vn 0.692114 -2.571461 4.516496 -v 0.040514 -0.011011 0.082248 -vn 0.731176 2.620293 4.481014 -v 0.040689 -0.010895 0.082221 -vn 1.424444 -2.647272 4.318542 -v 0.040718 -0.010991 0.082213 -vn 1.448603 2.653251 4.344188 -v 0.040824 -0.010881 0.082177 -vn 2.078533 -2.671453 4.064501 -v 0.040859 -0.010977 0.082162 -vn 2.144248 2.631763 4.010225 -v 0.040941 -0.010869 0.082121 -vn 2.711067 -2.562811 3.633889 -v 0.040967 -0.010965 0.082106 -vn 3.218077 -2.634540 3.218077 -v 0.041157 -0.010942 0.081957 -vn 2.956842 2.601058 3.413920 -v 0.041157 -0.010843 0.081957 -vn 3.668256 -2.591799 2.740390 -v 0.041188 -0.010938 0.081925 -vn 3.680017 2.608721 2.692566 -v 0.041306 -0.010820 0.081767 -vn 4.074680 -2.636379 1.977215 -v 0.041321 -0.010916 0.081741 -vn 4.092947 2.439239 2.002091 -v 0.041356 -0.010810 0.081672 -vn 4.291421 2.573784 1.506913 -v 0.041413 -0.010794 0.081519 -vn 4.455067 -2.638346 1.020255 -v 0.041421 -0.010890 0.081489 -vn 4.563498 -2.577636 0.465214 -v 0.041435 -0.010884 0.081424 -vn 4.513762 2.639000 0.670547 -v 0.041448 -0.010774 0.081313 -vn 4.541564 -2.622643 -0.331750 -v 0.041450 -0.010867 0.081250 -vn 4.555382 2.637543 0.054427 -v 0.041450 -0.010768 0.081250 -vn 4.420590 2.637624 -0.857880 -v 0.041421 -0.010745 0.081011 -vn 4.469492 -2.518308 -0.910345 -v 0.041432 -0.010849 0.081062 -vn 4.227977 -2.587977 -1.673037 -v 0.041413 -0.010841 0.080981 -vn 4.021936 2.562969 -1.956153 -v 0.041321 -0.010719 0.080759 -vn 3.720459 -2.548823 -2.544819 -v 0.041306 -0.010815 0.080733 -vn 3.402663 2.629826 -2.929974 -v 0.041157 -0.010693 0.080543 -vn 3.131292 -2.616685 -3.293885 -v 0.041157 -0.010792 0.080543 -vn 2.621268 -2.533432 -3.735768 -v 0.041075 -0.010782 0.080469 -vn 2.719549 2.665923 -3.664095 -v 0.040967 -0.010670 0.080394 -vn 1.959787 -2.665101 -4.100136 -v 0.040941 -0.010766 0.080379 -vn 2.222661 2.644853 -3.995924 -v 0.040921 -0.010665 0.080368 -vn 1.321059 -2.611410 -4.368226 -v 0.040759 -0.010747 0.080299 -vn 1.519898 2.667822 -4.287879 -v 0.040718 -0.010644 0.080287 -vn 0.700912 -2.657581 -4.522116 -v 0.040689 -0.010740 0.080279 -vn 0.807132 2.528414 -4.498806 -v 0.040567 -0.010629 0.080257 -vn 3.304651 2.696469 3.175436 -v 0.041191 -0.010238 0.081922 -vn 2.850104 2.627508 3.559314 -v 0.041157 -0.010243 0.081957 -vn 3.237828 -2.623500 3.223864 -v 0.041157 -0.010342 0.081957 -vn 2.199652 2.648984 3.985632 -v 0.040941 -0.010269 0.082121 -vn 2.605181 -2.553764 3.687578 -v 0.040967 -0.010365 0.082106 -vn 1.647663 2.511088 4.260980 -v 0.040895 -0.010274 0.082146 -vn 1.424311 -2.599047 4.244398 -v 0.040718 -0.010392 0.082213 -vn 0.825385 2.551392 4.475870 -v 0.040689 -0.010295 0.082221 -vn 0.317524 2.418256 4.547897 -v 0.040536 -0.010310 0.082246 -vn 3.609363 -2.697935 2.848892 -v 0.041188 -0.010338 0.081925 -vn 3.829447 -2.610971 2.496219 -v 0.041256 -0.010328 0.081842 -vn 3.750585 2.659855 2.579759 -v 0.041306 -0.010220 0.081767 -vn 4.132441 -2.641611 1.897490 -v 0.041321 -0.010316 0.081741 -vn 4.140607 2.469752 1.927494 -v 0.041383 -0.010203 0.081611 -vn 4.457907 -2.568891 0.783311 -v 0.041421 -0.010290 0.081489 -vn 4.354594 2.622238 1.328900 -v 0.041413 -0.010194 0.081519 -vn 4.492033 2.625329 0.315361 -v 0.041450 -0.010168 0.081250 -vn 0.188452 -2.669598 -4.571763 -v 0.040525 -0.010124 0.080253 -vn 0.729004 2.661024 -4.510807 -v 0.040533 -0.010026 0.080253 -vn 0.820776 -2.622704 -4.480871 -v 0.040689 -0.010140 0.080279 -vn 1.442646 2.629501 -4.325784 -v 0.040718 -0.010044 0.080287 -vn 1.560533 -2.650013 -4.304624 -v 0.040854 -0.010157 0.080335 -vn 2.004476 2.648757 -4.102529 -v 0.040842 -0.010056 0.080330 -vn 2.145528 -2.630436 -4.020210 -v 0.040941 -0.010166 0.080379 -vn 2.677815 2.578382 -3.659178 -v 0.040967 -0.010070 0.080394 -vn 3.005685 -2.560440 -3.361893 -v 0.041157 -0.010192 0.080543 -vn 3.354386 2.564134 -3.003937 -v 0.041157 -0.010093 0.080543 -vn 3.644904 -2.587259 -2.743585 -v 0.041306 -0.010215 0.080733 -vn 4.004655 2.668451 -2.154948 -v 0.041321 -0.010119 0.080759 -vn 4.015769 -2.685794 -2.206549 -v 0.041341 -0.010222 0.080797 -vn 4.301153 2.622421 -1.547277 -v 0.041362 -0.010128 0.080840 -vn 4.305088 -2.624316 -1.492400 -v 0.041413 -0.010241 0.080982 -vn 4.462064 2.633863 -0.772487 -v 0.041421 -0.010145 0.081011 -vn 4.510991 -2.533018 -0.769493 -v 0.041445 -0.010258 0.081153 -vn 4.568359 -2.621370 -0.086194 -v 0.041450 -0.010267 0.081250 -vn -0.101512 1.668285 5.707357 -v 0.040450 -0.041610 0.083125 -vn -1.145268 0.230773 6.124715 -v 0.040131 -0.041610 0.083098 -vn -1.965979 1.318408 5.577337 -v 0.039732 -0.041610 0.082982 -vn -3.042128 0.236967 5.447268 -v 0.039624 -0.041610 0.082933 -vn -3.946214 0.251902 4.837428 -v 0.039183 -0.041610 0.082632 -vn -4.521080 1.210387 3.903322 -v 0.039124 -0.041610 0.082576 -vn -5.245246 0.263755 3.354756 -v 0.038845 -0.041610 0.082219 -vn -5.234118 1.704500 2.206296 -v 0.038718 -0.041610 0.081968 -vn -6.070872 0.236572 1.405555 -v 0.038637 -0.041610 0.081728 -vn -6.117786 0.793701 0.449351 -v 0.038575 -0.041610 0.081250 -vn -6.112488 -0.829696 -0.325937 -v 0.038575 -0.042410 0.081250 -vn -5.923254 -0.818649 -1.410971 -v 0.038631 -0.042410 0.080794 -vn -5.583294 -1.154761 -2.182380 -v 0.038718 -0.042410 0.080532 -vn -5.187769 -0.768563 -3.235268 -v 0.038834 -0.042410 0.080300 -vn -4.566033 -0.823123 -4.083279 -v 0.039124 -0.042410 0.079924 -vn -3.920013 -0.779001 -4.716769 -v 0.039167 -0.042410 0.079883 -vn -3.031529 -0.762691 -5.319023 -v 0.039604 -0.042410 0.079577 -vn -0.208657 -1.046837 -6.038561 -v 0.040450 -0.042410 0.079375 -vn -1.102699 -0.797293 -5.994443 -v 0.040110 -0.042410 0.079406 -vn -2.123290 -0.868452 -5.723106 -v 0.039732 -0.042410 0.079518 -vn 0.214284 2.575838 4.560703 -v 0.040533 -0.009710 0.082247 -vn 1.124800 -2.431708 4.428245 -v 0.040661 -0.009796 0.082227 -vn 1.834549 1.962575 4.871368 -v 0.040797 -0.009710 0.082188 -vn 1.542601 -2.489321 4.285937 -v 0.040718 -0.009791 0.082213 -vn 2.493390 -2.409666 3.746963 -v 0.040967 -0.009765 0.082106 -vn 3.160333 1.716415 4.096991 -v 0.041019 -0.009710 0.082072 -vn 3.889836 2.175294 3.465275 -v 0.041212 -0.009710 0.081897 -vn 3.025766 -1.707307 3.119305 -v 0.041177 -0.009739 0.081936 -vn 3.814247 -2.175244 2.440614 -v 0.041247 -0.009729 0.081854 -vn 4.446896 1.456948 2.688333 -v 0.041316 -0.009710 0.081750 -vn 4.049427 -1.915723 1.876309 -v 0.041335 -0.009714 0.081716 -vn 3.379571 -0.507368 1.285694 -v 0.041354 -0.009710 0.081678 -vn 0.753662 6.171165 0.349715 -v 0.042011 -0.041410 0.081856 -vn 0.741093 6.188035 0.192191 -v 0.042043 -0.041410 0.081767 -vn -0.906743 6.119434 0.422659 -v 0.038883 -0.041410 0.081843 -vn -0.677291 6.184789 0.381482 -v 0.039016 -0.041410 0.082116 -vn -0.796578 6.179502 0.066900 -v 0.038775 -0.041410 0.081250 -vn -0.753311 6.186730 0.160932 -v 0.038830 -0.041410 0.081677 -vn 0.645287 6.187339 0.416755 -v 0.041834 -0.041410 0.082195 -vn 0.659984 6.153273 0.602744 -v 0.041697 -0.041410 0.082368 -vn 0.470493 6.185483 0.615480 -v 0.041511 -0.041410 0.082546 -vn 0.489130 6.145092 0.779688 -v 0.041220 -0.041410 0.082738 -vn 0.177936 6.179679 0.778598 -v 0.040685 -0.041410 0.082909 -vn 0.259308 6.187852 0.721012 -v 0.041103 -0.041410 0.082793 -vn -0.687581 6.154077 0.566789 -v 0.039174 -0.041410 0.082335 -vn -0.505680 6.190110 0.564435 -v 0.039318 -0.041410 0.082485 -vn -0.498452 6.154268 0.737808 -v 0.039543 -0.041410 0.082659 -vn -0.314768 6.188357 0.696485 -v 0.039712 -0.041410 0.082754 -vn -0.234910 6.172724 0.790936 -v 0.040081 -0.041410 0.082884 -vn -0.083034 6.188228 0.760415 -v 0.040165 -0.041410 0.082901 -vn 0.035205 6.188886 0.761749 -v 0.040642 -0.041410 0.082914 -vn -4.787906 0.439053 -2.300510 -v 0.039573 -0.021063 0.080799 -vn -3.494092 -0.026438 0.636531 -v 0.039502 -0.021011 0.081324 -vn -2.074962 0.153409 3.036030 -v 0.039915 -0.020929 0.081965 -vn -2.448210 0.025089 2.133746 -v 0.039722 -0.020957 0.081797 -vn -3.079637 0.009035 0.020061 -v 0.039915 -0.020418 0.081250 -vn -3.115533 0.068889 -0.680689 -v 0.039923 -0.020449 0.081071 -vn -2.675469 0.040801 -1.721732 -v 0.040001 -0.020484 0.080881 -vn -1.924743 0.026591 -2.517455 -v 0.040140 -0.020516 0.080733 -vn -1.139821 0.035750 -2.850041 -v 0.040319 -0.020548 0.080639 -vn -0.645546 0.027451 -2.986305 -v 0.040357 -0.020554 0.080627 -vn -0.083890 0.028186 -3.073781 -v 0.040522 -0.020579 0.080606 -vn 0.447315 0.023829 -3.034819 -v 0.040584 -0.020588 0.080610 -vn 1.164359 0.033314 -2.949326 -v 0.040734 -0.020610 0.080645 -vn 1.845842 0.055635 -2.587182 -v 0.040928 -0.020641 0.080751 -vn 2.322865 0.027215 -2.075645 -v 0.041020 -0.020658 0.080838 -vn 2.557919 0.020653 -1.694007 -v 0.041080 -0.020671 0.080916 -vn 2.797439 0.011173 -1.366466 -v 0.041113 -0.020680 0.080973 -vn 2.970939 0.027808 -0.846564 -v 0.041172 -0.020702 0.081127 -vn 3.064604 0.026520 -0.373608 -v 0.041191 -0.020714 0.081219 -vn 3.117751 0.021550 0.165437 -v 0.041196 -0.020732 0.081363 -vn 3.046816 0.032409 0.758772 -v 0.041178 -0.020748 0.081489 -vn 2.966469 0.054325 1.212166 -v 0.041147 -0.020761 0.081590 -vn 2.448188 0.028139 2.000407 -v 0.041025 -0.020791 0.081798 -vn 1.950208 0.056681 2.434430 -v 0.040852 -0.020819 0.081960 -vn 1.554201 0.008393 2.670457 -v 0.040844 -0.020820 0.081965 -vn 1.086610 0.021622 2.921911 -v 0.040643 -0.020846 0.082062 -vn 0.618807 0.011021 3.052712 -v 0.040585 -0.020853 0.082078 -vn 0.024639 0.026295 3.165140 -v 0.040397 -0.020874 0.082101 -vn -0.311826 0.051179 3.189170 -v 0.040281 -0.020887 0.082095 -vn -0.886621 -0.007353 3.004838 -v 0.040143 -0.020902 0.082068 -vn -1.369908 0.029239 2.840095 -v 0.040011 -0.020918 0.082019 -vn -2.911878 0.066696 1.135532 -v 0.039563 -0.020988 0.081541 -vn -2.843958 0.077343 1.404929 -v 0.039578 -0.020984 0.081574 -vn -3.470413 -0.086423 -0.222589 -v 0.039501 -0.021037 0.081062 -vn -2.907792 0.070717 -0.882094 -v 0.039530 -0.021051 0.080922 -vn -3.891951 1.473393 4.456052 -v 0.039184 -0.041581 0.082631 -vn -2.739902 1.467832 5.245555 -v 0.039625 -0.041581 0.082931 -vn 1.096498 5.322530 2.632561 -v 0.041138 -0.041431 0.082875 -vn -2.760874 5.322817 0.710760 -v 0.038743 -0.041431 0.081700 -vn -2.445627 5.323601 1.459169 -v 0.038939 -0.041431 0.082162 -vn -1.931379 5.320561 2.112605 -v 0.039257 -0.041431 0.082551 -vn -1.247644 5.321699 2.569827 -v 0.039672 -0.041431 0.082834 -vn -0.467775 5.322242 2.814888 -v 0.040150 -0.041431 0.082989 -vn 0.317602 5.323331 2.829991 -v 0.040652 -0.041431 0.083003 -vn 1.791362 5.323669 2.213291 -v 0.041568 -0.041431 0.082616 -vn 2.365252 5.321705 1.602506 -v 0.041907 -0.041431 0.082245 -vn 2.719665 5.322326 0.863041 -v 0.042129 -0.041431 0.081794 -vn 6.019488 0.250574 1.632247 -v 0.042234 -0.041610 0.081828 -vn 5.671961 1.460118 1.689734 -v 0.042232 -0.041581 0.081828 -vn 5.290864 1.477345 2.455439 -v 0.042182 -0.041610 0.081968 -vn 4.897370 1.447941 3.326642 -v 0.041997 -0.041581 0.082306 -vn 3.646044 1.450565 4.661926 -v 0.041636 -0.041581 0.082699 -vn 4.187023 1.598824 3.941287 -v 0.041776 -0.041610 0.082576 -vn 5.156817 0.236121 3.497676 -v 0.041998 -0.041610 0.082307 -vn -1.042770 1.447912 5.827662 -v 0.040132 -0.041581 0.083096 -vn 0.799861 1.443359 5.863968 -v 0.040665 -0.041581 0.083111 -vn 0.959750 0.249013 6.155947 -v 0.040665 -0.041610 0.083113 -vn 2.304056 1.357980 5.443213 -v 0.041180 -0.041581 0.082975 -vn 2.413828 0.271138 5.705096 -v 0.041181 -0.041610 0.082977 -vn 3.730162 0.239924 4.993951 -v 0.041638 -0.041610 0.082701 -vn -5.013705 1.425976 3.143324 -v 0.038847 -0.041581 0.082218 -vn -5.746026 1.447633 1.422314 -v 0.038639 -0.041581 0.081727 -vn -4.716317 3.420837 1.242642 -v 0.038673 -0.041494 0.081718 -vn -4.175155 3.420829 2.521027 -v 0.038877 -0.041494 0.082200 -vn -3.295780 3.420836 3.595207 -v 0.039208 -0.041494 0.082605 -vn -2.149431 3.420809 4.378159 -v 0.039640 -0.041494 0.082900 -vn -0.828896 3.420760 4.806324 -v 0.040138 -0.041494 0.083061 -vn 0.558842 3.420773 4.845237 -v 0.040661 -0.041494 0.083075 -vn 1.901217 3.420816 4.491522 -v 0.041166 -0.041494 0.082942 -vn 3.089558 3.420853 3.773913 -v 0.041614 -0.041494 0.082672 -vn 4.027627 3.420783 2.750584 -v 0.041967 -0.041494 0.082286 -vn 4.639388 3.420879 1.504450 -v 0.042198 -0.041494 0.081817 -vn 0.887002 -0.773830 -6.050651 -v 0.040643 -0.042410 0.079385 -vn 2.296836 -0.786999 -5.612328 -v 0.041161 -0.042410 0.079515 -vn 3.615554 -0.765266 -4.929605 -v 0.041621 -0.042410 0.079785 -vn 4.387053 -0.909501 -4.228897 -v 0.041776 -0.042410 0.079924 -vn 5.050206 -0.791292 -3.424981 -v 0.041986 -0.042410 0.080174 -vn 5.503511 -0.940500 -2.593620 -v 0.042182 -0.042410 0.080532 -vn 5.896050 -0.776702 -1.656775 -v 0.042227 -0.042410 0.080651 -vn 4.986548 -2.804583 -1.638803 -v 0.042181 -0.042600 0.080666 -vn 0.146885 -6.040196 -1.362525 -v 0.040607 -0.042807 0.079735 -vn -0.250721 -6.040010 -1.350650 -v 0.040173 -0.042807 0.079752 -vn -0.628474 -4.912708 -3.404500 -v 0.040142 -0.042742 0.079579 -vn 0.187048 -6.272535 -0.178260 -v 0.041461 -0.042810 0.080176 -vn 0.117280 -6.276628 -0.164873 -v 0.041371 -0.042810 0.080098 -vn 0.850600 -6.040156 -1.074883 -v 0.041401 -0.042807 0.080060 -vn -0.222423 -6.275253 -0.015659 -v 0.038975 -0.042810 0.081250 -vn -0.244969 -6.273481 -0.028581 -v 0.039000 -0.042810 0.080981 -vn -1.178083 -6.040565 -0.686099 -v 0.039137 -0.042807 0.080478 -vn -0.178316 -6.275844 -0.117409 -v 0.039190 -0.042810 0.080482 -vn -0.192083 -6.276689 -0.060831 -v 0.039019 -0.042810 0.080891 -vn -0.933947 -6.040969 -0.983311 -v 0.039407 -0.042807 0.080139 -vn -0.138687 -6.275078 -0.176863 -v 0.039478 -0.042810 0.080140 -vn -0.622752 -6.040120 -1.221930 -v 0.039763 -0.042807 0.079890 -vn -0.097673 -6.276609 -0.177532 -v 0.039784 -0.042810 0.079934 -vn 0.030353 -6.276570 -0.200897 -v 0.040602 -0.042810 0.079783 -vn -0.007500 -6.271969 -0.265083 -v 0.040441 -0.042810 0.079775 -vn -0.012223 -6.270945 -0.276758 -v 0.040360 -0.042810 0.079778 -vn -0.038625 -6.276795 -0.196191 -v 0.040182 -0.042810 0.079799 -vn -0.088967 -6.270997 -0.261709 -v 0.039945 -0.042810 0.079864 -vn 0.241819 -6.271523 -0.120975 -v 0.041792 -0.042810 0.080638 -vn 0.166297 -6.276527 -0.117871 -v 0.041658 -0.042810 0.080404 -vn 1.123042 -6.040122 -0.787401 -v 0.041698 -0.042807 0.080376 -vn 1.300445 -6.040180 -0.432298 -v 0.041894 -0.042807 0.080763 -vn 0.195027 -6.276601 -0.055352 -v 0.041848 -0.042810 0.080779 -vn -2.427381 -2.816529 -4.654092 -v 0.039626 -0.042600 0.079619 -vn -1.562175 -4.912713 -3.089549 -v 0.039683 -0.042742 0.079734 -vn 1.311935 -4.912668 -3.203841 -v 0.041094 -0.042742 0.079678 -vn 2.161407 -4.912708 -2.704440 -v 0.041511 -0.042742 0.079923 -vn 3.221490 -2.814920 -4.145676 -v 0.041591 -0.042600 0.079823 -vn 1.992912 -2.746309 -4.866891 -v 0.041142 -0.042600 0.079559 -vn 0.588506 -2.807237 -5.216090 -v 0.040638 -0.042600 0.079433 -vn -1.328519 -6.040133 -0.340130 -v 0.038972 -0.042807 0.080879 -vn -3.357928 -4.912682 -0.842627 -v 0.038802 -0.042742 0.080837 -vn -5.093764 -2.764902 -1.302393 -v 0.038678 -0.042600 0.080805 -vn -4.510571 -2.816153 -2.685457 -v 0.038875 -0.042600 0.080324 -vn -2.984523 -4.912684 -1.754532 -v 0.038986 -0.042742 0.080389 -vn -2.369310 -4.912687 -2.524295 -v 0.039287 -0.042742 0.080011 -vn -3.566506 -2.794343 -3.854845 -v 0.039200 -0.042600 0.079918 -vn -0.912529 -2.780898 -5.176080 -v 0.040118 -0.042600 0.079453 -vn 0.356169 -4.912652 -3.443670 -v 0.040625 -0.042742 0.079560 -vn 0.519442 -6.040497 -1.262007 -v 0.041027 -0.042807 0.079840 -vn 0.075017 -6.276102 -0.195648 -v 0.041000 -0.042810 0.079881 -vn 2.835790 -4.912711 -1.985943 -v 0.041842 -0.042742 0.080275 -vn 4.336393 -2.795647 -2.966327 -v 0.041947 -0.042600 0.080202 -vn 3.280434 -4.912695 -1.106586 -v 0.042060 -0.042742 0.080707 -vn -0.161587 0.040663 -3.209755 -v 0.040405 -0.018160 0.080717 -vn 0.623367 0.034648 -3.035633 -v 0.040604 -0.018196 0.080737 -vn 1.169786 0.004807 -2.851368 -v 0.040616 -0.018198 0.080741 -vn 1.924761 0.001484 -2.499703 -v 0.040777 -0.018231 0.080827 -vn 2.448500 0.003261 -1.879157 -v 0.040895 -0.018262 0.080953 -vn 2.767795 0.016734 -1.388509 -v 0.040912 -0.018268 0.080981 -vn 3.110584 0.022747 -0.628546 -v 0.040973 -0.018298 0.081137 -vn 3.134341 -0.009916 0.508049 -v 0.040978 -0.018334 0.081336 -vn 2.787785 -0.009550 1.344338 -v 0.040911 -0.018369 0.081522 -vn 2.484993 -0.040863 1.894434 -v 0.040904 -0.018371 0.081533 -vn 2.059799 -0.010176 2.418628 -v 0.040780 -0.018405 0.081671 -vn 1.347594 0.005879 2.749698 -v 0.040669 -0.018428 0.081738 -vn -0.834189 0.011512 2.950044 -v 0.040290 -0.018497 0.081761 -vn -0.308091 0.005407 3.071701 -v 0.040408 -0.018476 0.081783 -vn 0.225879 0.000763 3.052030 -v 0.040484 -0.018462 0.081784 -vn 0.806797 0.001830 2.933834 -v 0.040604 -0.018440 0.081763 -vn -2.579283 -0.021976 1.700810 -v 0.039998 -0.018564 0.081535 -vn -2.218145 -0.020279 2.118938 -v 0.040072 -0.018543 0.081628 -vn -1.812092 -0.001127 2.445312 -v 0.040129 -0.018530 0.081678 -vn -1.361907 0.005538 2.723332 -v 0.040215 -0.018511 0.081731 -vn -3.045222 -0.012795 0.196171 -v 0.039916 -0.018613 0.081277 -vn -3.042831 -0.026075 0.623312 -v 0.039923 -0.018601 0.081346 -vn -2.863554 -0.008294 1.208175 -v 0.039960 -0.018578 0.081466 -vn -2.974842 0.017508 -0.834638 -v 0.039943 -0.018649 0.081079 -vn -3.070120 0.006871 -0.287254 -v 0.039916 -0.018622 0.081229 -vn -2.765395 0.010071 -1.332861 -v 0.039959 -0.018657 0.081037 -vn -2.364533 -0.027142 -2.099284 -v 0.040038 -0.018684 0.080908 -vn -1.881795 -0.029307 -2.221745 -v 0.040069 -0.018691 0.080883 -vn -1.660313 0.011181 -2.592123 -v 0.040192 -0.018720 0.080781 -vn -1.141295 -0.002244 -2.856104 -v 0.040223 -0.018726 0.080765 -vn -0.418515 -0.000547 -3.130084 -v 0.040380 -0.018755 0.080719 -vn 0.666949 -0.018166 -3.084732 -v 0.040554 -0.018787 0.080726 -vn 1.076977 -0.043212 -2.717688 -v 0.040591 -0.018794 0.080740 -vn 1.671979 -0.002765 -2.719053 -v 0.040739 -0.018822 0.080799 -vn 2.247764 0.007090 -2.097517 -v 0.040860 -0.018852 0.080907 -vn 2.566901 -0.014724 -1.680314 -v 0.040880 -0.018857 0.080932 -vn 2.831411 -0.000656 -1.171245 -v 0.040956 -0.018886 0.081076 -vn 2.972994 -0.002554 -0.646470 -v 0.040967 -0.018893 0.081113 -vn 3.062319 -0.010825 -0.030976 -v 0.040985 -0.018921 0.081265 -vn 3.044635 -0.013214 0.474889 -v 0.040982 -0.018928 0.081307 -vn 2.885493 -0.005060 1.045674 -v 0.040944 -0.018956 0.081456 -vn 2.682953 -0.004945 1.575949 -v 0.040924 -0.018964 0.081499 -vn 2.403656 0.014649 1.997063 -v 0.040846 -0.018989 0.081610 -vn 1.946133 0.004459 2.392989 -v 0.040803 -0.018999 0.081652 -vn 1.480225 0.005029 2.670372 -v 0.040690 -0.019024 0.081728 -vn 1.033303 -0.010221 2.895324 -v 0.040655 -0.019031 0.081744 -vn 0.437398 -0.006230 3.046207 -v 0.040497 -0.019060 0.081783 -vn -0.016026 -0.019175 3.036814 -v 0.040459 -0.019066 0.081785 -vn -0.453483 -0.015755 3.037107 -v 0.040377 -0.019081 0.081780 -vn -0.999191 -0.002257 2.874729 -v 0.040265 -0.019102 0.081752 -vn -1.494026 0.001083 2.643822 -v 0.040195 -0.019115 0.081720 -vn -2.012134 0.019229 2.325485 -v 0.040093 -0.019138 0.081650 -vn -2.361143 0.011203 1.947352 -v 0.040044 -0.019150 0.081599 -vn -2.713584 0.017279 1.441570 -v 0.039974 -0.019173 0.081494 -vn -2.922095 0.010930 0.966043 -v 0.039946 -0.019185 0.081430 -vn -3.053098 0.008192 0.413443 -v 0.039917 -0.019209 0.081302 -vn -3.059351 0.006922 -0.101765 -v 0.039915 -0.019218 0.081250 -vn -2.953856 0.003738 -0.709021 -v 0.039934 -0.019244 0.081108 -vn -2.825321 0.030950 -1.281703 -v 0.039952 -0.019254 0.081056 -vn -2.652804 0.087943 -1.890396 -v 0.040005 -0.019274 0.080953 -vn -1.855811 0.032864 -2.670536 -v 0.040146 -0.019310 0.080810 -vn -0.768057 0.009138 -3.116123 -v 0.040328 -0.019346 0.080729 -vn 0.444478 -0.002653 -3.142590 -v 0.040525 -0.019381 0.080720 -vn 1.574362 0.002317 -2.777585 -v 0.040713 -0.019417 0.080784 -vn 2.964372 -0.016553 -0.780297 -v 0.040959 -0.019488 0.081085 -vn 2.821803 -0.022232 -1.304797 -v 0.040950 -0.019483 0.081060 -vn 2.474332 -0.009497 -2.031502 -v 0.040865 -0.019453 0.080912 -vn 3.062570 -0.003642 0.386996 -v 0.040984 -0.019524 0.081283 -vn 3.065660 -0.006151 -0.172455 -v 0.040985 -0.019519 0.081254 -vn 2.608664 -0.004563 1.691449 -v 0.040896 -0.019574 0.081546 -vn 2.928918 -0.019124 1.131789 -v 0.040944 -0.019556 0.081455 -vn 2.228495 0.013588 2.107901 -v 0.040837 -0.019591 0.081619 -vn 1.768827 0.004611 2.494956 -v 0.040758 -0.019610 0.081688 -vn -0.296287 -0.002809 3.050583 -v 0.040399 -0.019677 0.081783 -vn 0.208673 -0.002828 3.048620 -v 0.040486 -0.019662 0.081784 -vn 0.760455 0.011341 2.961925 -v 0.040577 -0.019645 0.081770 -vn 1.265767 0.018102 2.799821 -v 0.040680 -0.019626 0.081733 -vn -2.030611 -0.008396 2.376911 -v 0.040115 -0.019733 0.081667 -vn -1.431782 -0.007207 2.698706 -v 0.040207 -0.019713 0.081726 -vn -0.884794 -0.002251 2.915032 -v 0.040291 -0.019697 0.081761 -vn -2.520319 0.004804 1.733300 -v 0.039986 -0.019768 0.081518 -vn -2.789807 0.006512 1.287846 -v 0.039983 -0.019769 0.081512 -vn -2.968826 0.022815 0.781651 -v 0.039925 -0.019799 0.081354 -vn -3.060489 0.000620 0.267605 -v 0.039922 -0.019803 0.081332 -vn -3.071722 0.009007 -0.336854 -v 0.039923 -0.019835 0.081156 -vn -2.990614 0.000860 -0.933203 -v 0.039928 -0.019839 0.081131 -vn -2.797399 0.011470 -1.424933 -v 0.039992 -0.019870 0.080974 -vn -2.443020 0.001517 -1.891032 -v 0.040009 -0.019875 0.080948 -vn -1.898211 -0.004707 -2.530416 -v 0.040125 -0.019906 0.080825 -vn -0.882972 0.007792 -3.072381 -v 0.040299 -0.019941 0.080737 -vn 0.171334 0.029487 -3.148228 -v 0.040498 -0.019977 0.080717 -vn 1.847014 -0.003982 -2.427652 -v 0.040786 -0.020033 0.080834 -vn 1.417079 -0.018756 -2.742561 -v 0.040686 -0.020012 0.080770 -vn 0.911748 -0.004276 -2.948351 -v 0.040618 -0.019999 0.080742 -vn 2.620759 -0.006816 -1.592642 -v 0.040917 -0.020069 0.080988 -vn 2.228200 -0.003929 -2.077596 -v 0.040828 -0.020043 0.080872 -vn 2.887738 -0.008837 -1.118298 -v 0.040941 -0.020079 0.081037 -vn 3.010767 0.006244 -0.534447 -v 0.040980 -0.020105 0.081180 -vn 2.993450 -0.000951 0.620980 -v 0.040969 -0.020142 0.081383 -vn 3.043921 -0.001062 0.013270 -v 0.040984 -0.020114 0.081229 -vn 2.868189 -0.001270 1.162792 -v 0.040956 -0.020150 0.081426 -vn 2.564782 0.001684 1.694033 -v 0.040882 -0.020178 0.081566 -vn 2.242804 -0.018848 2.105646 -v 0.040858 -0.020185 0.081596 -vn 1.825647 -0.002908 2.486841 -v 0.040743 -0.020213 0.081697 -vn 1.336046 -0.002362 2.760410 -v 0.040703 -0.020221 0.081722 -vn 0.729189 -0.003531 2.976405 -v 0.040555 -0.020249 0.081775 -vn 0.203079 -0.015044 3.081422 -v 0.040517 -0.020256 0.081781 -vn -0.493946 -0.008616 3.078532 -v 0.040345 -0.020287 0.081775 -vn -1.144201 0.005994 2.873405 -v 0.040254 -0.020304 0.081748 -vn -2.753293 0.001430 1.333596 -v 0.039967 -0.020375 0.081482 -vn -2.485658 -0.006949 1.834180 -v 0.040016 -0.020359 0.081562 -vn -2.107481 -0.011353 2.220439 -v 0.040089 -0.020339 0.081645 -vn -1.633632 0.007736 2.585420 -v 0.040160 -0.020323 0.081700 -vn -2.979565 -0.017202 0.745486 -v 0.039931 -0.020394 0.081383 -vn -3.120925 -0.053781 0.245290 -v 0.039916 -0.020412 0.081285 -vn -0.753227 0.010208 -3.025760 -v 0.040306 -0.018142 0.080735 -vn -1.359469 -0.004732 -2.739183 -v 0.040216 -0.018125 0.080768 -vn -1.851207 -0.000258 -2.421647 -v 0.040124 -0.018105 0.080826 -vn -2.245009 0.005896 -2.050658 -v 0.040056 -0.018089 0.080888 -vn -2.683367 -0.014333 -1.576353 -v 0.039994 -0.018071 0.080971 -vn -3.070569 -0.039647 -1.048911 -v 0.039951 -0.018054 0.081055 -vn -3.196205 -0.053294 -0.215711 -v 0.039915 -0.018018 0.081250 -vn 2.720703 -4.188785 -0.000000 -v 0.039450 -0.042810 0.081250 -vn 1.360351 -4.188793 -2.356191 -v 0.039950 -0.042810 0.082116 -vn -1.360349 -4.188789 -2.356195 -v 0.040950 -0.042810 0.082116 -vn -2.720698 -4.188791 -0.000000 -v 0.041450 -0.042810 0.081250 -vn -1.360349 -4.188790 2.356196 -v 0.040950 -0.042810 0.080384 -vn 1.360352 -4.188793 2.356191 -v 0.039950 -0.042810 0.080384 -vn 2.720703 -2.094400 0.000000 -v 0.039450 -0.041810 0.081250 -vn 1.360351 -2.094393 2.356191 -v 0.039950 -0.041810 0.080384 -vn 1.360352 -2.094393 -2.356191 -v 0.039950 -0.041810 0.082116 -vn -1.360349 -2.094396 -2.356195 -v 0.040950 -0.041810 0.082116 -vn -2.720698 -2.094393 0.000000 -v 0.041450 -0.041810 0.081250 -vn -1.360349 -2.094396 2.356195 -v 0.040950 -0.041810 0.080384 -vn -0.161543 0.040629 -3.209765 -v 0.040405 -0.015760 0.080717 -vn 0.622739 0.034599 -3.035410 -v 0.040604 -0.015796 0.080737 -vn 1.169377 0.004993 -2.851828 -v 0.040616 -0.015798 0.080741 -vn 1.924772 0.001442 -2.499662 -v 0.040777 -0.015831 0.080827 -vn 2.448344 0.003272 -1.879177 -v 0.040895 -0.015862 0.080953 -vn 2.767774 0.016720 -1.388644 -v 0.040912 -0.015868 0.080981 -vn 3.110523 0.022733 -0.628500 -v 0.040973 -0.015898 0.081137 -vn 3.134290 -0.009973 0.508027 -v 0.040978 -0.015933 0.081336 -vn 2.787749 -0.009498 1.344270 -v 0.040911 -0.015969 0.081522 -vn 2.485073 -0.041022 1.894431 -v 0.040904 -0.015971 0.081533 -vn 2.059723 -0.010181 2.418606 -v 0.040780 -0.016005 0.081671 -vn 1.347502 0.005853 2.749720 -v 0.040669 -0.016028 0.081738 -vn 0.806731 0.001769 2.933730 -v 0.040604 -0.016040 0.081763 -vn 0.225923 0.000693 3.051976 -v 0.040484 -0.016062 0.081784 -vn -0.308111 0.005360 3.071644 -v 0.040408 -0.016076 0.081783 -vn -0.834107 0.011511 2.949914 -v 0.040290 -0.016097 0.081761 -vn -1.361950 0.005463 2.723370 -v 0.040215 -0.016111 0.081731 -vn -1.811961 -0.001202 2.445133 -v 0.040129 -0.016130 0.081678 -vn -2.218076 -0.020325 2.118967 -v 0.040072 -0.016143 0.081628 -vn -2.579128 -0.022038 1.700772 -v 0.039998 -0.016164 0.081535 -vn -2.863469 -0.008312 1.208206 -v 0.039961 -0.016178 0.081466 -vn -3.042701 -0.026218 0.623340 -v 0.039923 -0.016201 0.081346 -vn -3.045107 -0.012842 0.196162 -v 0.039916 -0.016213 0.081277 -vn -3.070021 0.006839 -0.287264 -v 0.039916 -0.016222 0.081229 -vn -2.974719 0.017413 -0.834574 -v 0.039943 -0.016249 0.081079 -vn -2.774559 -0.007094 -1.364417 -v 0.039959 -0.016257 0.081037 -vn -2.482402 -0.008349 -1.855832 -v 0.040038 -0.016284 0.080908 -vn -2.092475 0.009353 -2.284662 -v 0.040065 -0.016291 0.080878 -vn -1.644132 0.027126 -2.613003 -v 0.040193 -0.016320 0.080781 -vn -1.149404 0.003132 -2.861856 -v 0.040223 -0.016326 0.080765 -vn -0.407870 -0.007466 -3.139112 -v 0.040380 -0.016355 0.080719 -vn 0.421300 0.001278 -3.058457 -v 0.040554 -0.016387 0.080726 -vn 1.037250 -0.013821 -2.944490 -v 0.040593 -0.016394 0.080735 -vn 1.691972 0.009620 -2.722210 -v 0.040739 -0.016422 0.080799 -vn 2.247599 0.007100 -2.097459 -v 0.040860 -0.016452 0.080907 -vn 2.566769 -0.014822 -1.680320 -v 0.040880 -0.016457 0.080932 -vn 2.831308 -0.000810 -1.171171 -v 0.040956 -0.016486 0.081076 -vn 2.972806 -0.002615 -0.646321 -v 0.040967 -0.016493 0.081113 -vn 3.062196 -0.010931 -0.030865 -v 0.040985 -0.016521 0.081265 -vn 3.044426 -0.013281 0.474930 -v 0.040982 -0.016528 0.081307 -vn 2.885370 -0.005132 1.045614 -v 0.040944 -0.016556 0.081456 -vn 2.682800 -0.005058 1.575918 -v 0.040924 -0.016564 0.081499 -vn 2.403473 0.014473 1.997069 -v 0.040846 -0.016589 0.081610 -vn 1.945895 0.004429 2.392856 -v 0.040803 -0.016599 0.081652 -vn 1.480266 0.004934 2.670171 -v 0.040690 -0.016624 0.081728 -vn 1.033284 -0.010285 2.895230 -v 0.040655 -0.016631 0.081744 -vn 0.437390 -0.006431 3.045991 -v 0.040497 -0.016660 0.081783 -vn -0.016057 -0.019162 3.036628 -v 0.040459 -0.016666 0.081785 -vn -0.453415 -0.015897 3.036921 -v 0.040377 -0.016681 0.081780 -vn -0.998995 -0.002415 2.874500 -v 0.040265 -0.016702 0.081752 -vn -1.493914 0.001029 2.643678 -v 0.040195 -0.016715 0.081720 -vn -2.012058 0.019122 2.325304 -v 0.040093 -0.016738 0.081649 -vn -2.360983 0.011038 1.947173 -v 0.040044 -0.016750 0.081599 -vn -2.713399 0.017164 1.441454 -v 0.039974 -0.016773 0.081494 -vn -2.921881 0.010813 0.965947 -v 0.039946 -0.016785 0.081430 -vn -3.052976 0.008011 0.413307 -v 0.039917 -0.016809 0.081302 -vn -3.059039 0.006854 -0.101994 -v 0.039915 -0.016818 0.081250 -vn -2.953644 0.003608 -0.709092 -v 0.039934 -0.016844 0.081108 -vn -2.825054 0.030848 -1.281585 -v 0.039952 -0.016854 0.081056 -vn -2.652736 0.087773 -1.890201 -v 0.040005 -0.016874 0.080953 -vn -1.855674 0.032732 -2.670326 -v 0.040146 -0.016910 0.080810 -vn -0.768007 0.009007 -3.115939 -v 0.040328 -0.016946 0.080729 -vn 0.444569 -0.002813 -3.142363 -v 0.040525 -0.016981 0.080720 -vn 1.574322 0.002151 -2.777304 -v 0.040713 -0.017017 0.080784 -vn 2.964112 -0.016808 -0.780142 -v 0.040959 -0.017088 0.081085 -vn 2.821661 -0.022278 -1.304565 -v 0.040950 -0.017083 0.081060 -vn 2.474227 -0.009637 -2.031254 -v 0.040865 -0.017053 0.080912 -vn 3.062241 -0.003685 0.387159 -v 0.040984 -0.017124 0.081283 -vn 3.065440 -0.006446 -0.172358 -v 0.040985 -0.017119 0.081254 -vn 2.618556 0.000661 1.688061 -v 0.040896 -0.017174 0.081546 -vn 2.938849 -0.012101 1.149395 -v 0.040944 -0.017156 0.081455 -vn 1.768771 0.004412 2.494659 -v 0.040757 -0.017210 0.081688 -vn 2.228390 0.013514 2.107648 -v 0.040837 -0.017191 0.081619 -vn -0.296317 -0.002979 3.050210 -v 0.040399 -0.017277 0.081783 -vn 0.208629 -0.002988 3.048431 -v 0.040486 -0.017262 0.081784 -vn 0.760374 0.011171 2.961523 -v 0.040577 -0.017245 0.081769 -vn 1.265611 0.017984 2.799628 -v 0.040680 -0.017226 0.081733 -vn -2.030530 -0.008608 2.376573 -v 0.040115 -0.017333 0.081667 -vn -1.431748 -0.007350 2.698492 -v 0.040207 -0.017313 0.081726 -vn -0.884615 -0.002402 2.914773 -v 0.040291 -0.017297 0.081761 -vn -2.520122 0.004439 1.732952 -v 0.039986 -0.017368 0.081518 -vn -2.789536 0.006537 1.287454 -v 0.039983 -0.017369 0.081512 -vn -2.968218 0.022596 0.781949 -v 0.039926 -0.017399 0.081354 -vn -3.060320 0.000557 0.267983 -v 0.039922 -0.017403 0.081332 -vn -3.071521 0.008774 -0.337090 -v 0.039923 -0.017435 0.081156 -vn -2.990073 0.000676 -0.933311 -v 0.039928 -0.017439 0.081131 -vn -2.797172 0.011264 -1.424777 -v 0.039992 -0.017470 0.080974 -vn -2.442736 0.001362 -1.890853 -v 0.040009 -0.017475 0.080948 -vn -1.897957 -0.004900 -2.530218 -v 0.040125 -0.017506 0.080825 -vn -0.883842 0.006316 -3.074247 -v 0.040299 -0.017541 0.080737 -vn 0.171427 0.029296 -3.147847 -v 0.040498 -0.017577 0.080717 -vn 0.911733 -0.004439 -2.948057 -v 0.040618 -0.017599 0.080742 -vn 1.416965 -0.018973 -2.742190 -v 0.040686 -0.017612 0.080770 -vn 1.846736 -0.004103 -2.427411 -v 0.040786 -0.017633 0.080834 -vn 2.280815 0.011944 -2.075887 -v 0.040828 -0.017643 0.080872 -vn 2.628533 0.013479 -1.630419 -v 0.040917 -0.017669 0.080988 -vn 2.887395 -0.009008 -1.118287 -v 0.040941 -0.017679 0.081037 -vn 3.010372 0.006055 -0.534485 -v 0.040980 -0.017705 0.081180 -vn 3.043586 -0.001307 0.013187 -v 0.040984 -0.017714 0.081229 -vn 2.992991 -0.001054 0.620775 -v 0.040969 -0.017742 0.081383 -vn 2.868005 -0.001492 1.162578 -v 0.040956 -0.017750 0.081426 -vn 2.564429 0.001478 1.693869 -v 0.040882 -0.017778 0.081566 -vn 2.242520 -0.019056 2.105417 -v 0.040858 -0.017785 0.081596 -vn 1.825337 -0.003180 2.486720 -v 0.040743 -0.017813 0.081697 -vn -1.144149 0.005794 2.873263 -v 0.040254 -0.017904 0.081748 -vn -0.493870 -0.008836 3.078200 -v 0.040345 -0.017887 0.081775 -vn 0.203010 -0.015220 3.081047 -v 0.040517 -0.017856 0.081781 -vn 0.751644 0.009117 2.987220 -v 0.040555 -0.017849 0.081775 -vn 1.323696 0.010808 2.799828 -v 0.040703 -0.017821 0.081722 -vn -2.753478 0.001287 1.333585 -v 0.039968 -0.017975 0.081482 -vn -2.485756 -0.007136 1.834108 -v 0.040016 -0.017958 0.081562 -vn -2.107529 -0.011564 2.220410 -v 0.040089 -0.017939 0.081644 -vn -1.633539 0.007524 2.585328 -v 0.040160 -0.017923 0.081700 -vn -2.979841 -0.017446 0.745473 -v 0.039931 -0.017994 0.081383 -vn -3.120995 -0.053816 0.245450 -v 0.039916 -0.018012 0.081285 -vn -0.753340 0.010194 -3.025781 -v 0.040306 -0.015742 0.080735 -vn -1.359475 -0.004775 -2.739030 -v 0.040216 -0.015725 0.080768 -vn -1.851109 -0.000257 -2.421744 -v 0.040124 -0.015705 0.080826 -vn -2.244994 0.005907 -2.050690 -v 0.040056 -0.015689 0.080888 -vn -2.683305 -0.014377 -1.576336 -v 0.039994 -0.015671 0.080971 -vn -3.070564 -0.039650 -1.048967 -v 0.039951 -0.015654 0.081055 -vn -3.196199 -0.053288 -0.215711 -v 0.039915 -0.015618 0.081250 -vn -0.161542 0.040632 -3.209770 -v 0.040405 -0.013360 0.080717 -vn 0.622740 0.034601 -3.035414 -v 0.040604 -0.013396 0.080737 -vn 1.169428 0.004992 -2.851830 -v 0.040616 -0.013398 0.080741 -vn 1.924744 0.001432 -2.499612 -v 0.040777 -0.013431 0.080827 -vn 2.448335 0.003282 -1.879215 -v 0.040895 -0.013462 0.080953 -vn 2.767776 0.016722 -1.388647 -v 0.040912 -0.013468 0.080981 -vn 3.110526 0.022735 -0.628500 -v 0.040973 -0.013498 0.081137 -vn 3.134290 -0.009973 0.508027 -v 0.040978 -0.013533 0.081336 -vn 2.787749 -0.009498 1.344270 -v 0.040911 -0.013569 0.081522 -vn 2.485073 -0.041022 1.894431 -v 0.040904 -0.013571 0.081533 -vn 2.059723 -0.010177 2.418619 -v 0.040780 -0.013605 0.081671 -vn 1.347511 0.005858 2.749724 -v 0.040669 -0.013628 0.081738 -vn 0.806731 0.001769 2.933730 -v 0.040604 -0.013640 0.081763 -vn 0.225923 0.000693 3.051976 -v 0.040484 -0.013662 0.081784 -vn -0.308111 0.005360 3.071644 -v 0.040408 -0.013676 0.081783 -vn -0.834107 0.011511 2.949914 -v 0.040290 -0.013697 0.081761 -vn -1.361950 0.005463 2.723370 -v 0.040215 -0.013711 0.081731 -vn -1.811974 -0.001197 2.445137 -v 0.040129 -0.013730 0.081678 -vn -2.218076 -0.020320 2.118976 -v 0.040072 -0.013743 0.081628 -vn -2.579128 -0.022038 1.700772 -v 0.039998 -0.013764 0.081535 -vn -2.863469 -0.008312 1.208206 -v 0.039961 -0.013778 0.081466 -vn -3.042701 -0.026218 0.623340 -v 0.039923 -0.013801 0.081346 -vn -3.045123 -0.012791 0.196137 -v 0.039916 -0.013813 0.081277 -vn -3.070044 0.006748 -0.287231 -v 0.039916 -0.013822 0.081229 -vn -2.974716 0.017429 -0.834578 -v 0.039943 -0.013849 0.081079 -vn -2.774556 -0.007079 -1.364456 -v 0.039959 -0.013857 0.081037 -vn -2.482402 -0.008450 -1.855696 -v 0.040038 -0.013884 0.080908 -vn -2.092550 0.009443 -2.284635 -v 0.040065 -0.013891 0.080878 -vn -1.644133 0.027132 -2.612993 -v 0.040193 -0.013920 0.080781 -vn -1.149389 0.003151 -2.861852 -v 0.040223 -0.013926 0.080765 -vn -0.407884 -0.007514 -3.139107 -v 0.040380 -0.013955 0.080719 -vn 0.421337 0.001351 -3.058468 -v 0.040554 -0.013987 0.080726 -vn 1.037227 -0.013931 -2.944530 -v 0.040593 -0.013994 0.080735 -vn 1.691983 0.009638 -2.722220 -v 0.040739 -0.014022 0.080799 -vn 2.247601 0.007106 -2.097468 -v 0.040860 -0.014052 0.080907 -vn 2.566769 -0.014822 -1.680320 -v 0.040880 -0.014057 0.080932 -vn 2.831308 -0.000810 -1.171171 -v 0.040956 -0.014086 0.081076 -vn 2.972826 -0.002600 -0.646306 -v 0.040967 -0.014093 0.081113 -vn 3.062210 -0.010964 -0.030887 -v 0.040985 -0.014121 0.081265 -vn 3.044427 -0.013301 0.474927 -v 0.040982 -0.014128 0.081307 -vn 2.885366 -0.005215 1.045582 -v 0.040944 -0.014156 0.081456 -vn 2.682780 -0.005008 1.575931 -v 0.040924 -0.014164 0.081499 -vn 2.403473 0.014473 1.997069 -v 0.040846 -0.014189 0.081610 -vn 1.945895 0.004429 2.392856 -v 0.040803 -0.014199 0.081652 -vn 1.480266 0.004934 2.670171 -v 0.040690 -0.014224 0.081728 -vn 1.033284 -0.010285 2.895230 -v 0.040655 -0.014231 0.081744 -vn 0.437395 -0.006425 3.045981 -v 0.040497 -0.014260 0.081783 -vn -0.016064 -0.019158 3.036618 -v 0.040459 -0.014266 0.081785 -vn -0.453425 -0.015891 3.036931 -v 0.040377 -0.014281 0.081780 -vn -0.998984 -0.002406 2.874503 -v 0.040265 -0.014302 0.081752 -vn -1.493907 0.001039 2.643661 -v 0.040195 -0.014315 0.081720 -vn -2.012056 0.019127 2.325289 -v 0.040093 -0.014338 0.081649 -vn -2.360983 0.011038 1.947173 -v 0.040044 -0.014350 0.081599 -vn -2.713399 0.017164 1.441454 -v 0.039974 -0.014373 0.081494 -vn -2.921908 0.010807 0.965915 -v 0.039946 -0.014385 0.081430 -vn -3.052910 0.008062 0.413339 -v 0.039917 -0.014409 0.081302 -vn -3.059095 0.006775 -0.101840 -v 0.039915 -0.014418 0.081250 -vn -2.953623 0.003624 -0.709108 -v 0.039934 -0.014444 0.081108 -vn -2.825054 0.030848 -1.281585 -v 0.039952 -0.014454 0.081056 -vn -2.652735 0.087775 -1.890209 -v 0.040005 -0.014474 0.080953 -vn -1.855685 0.032740 -2.670331 -v 0.040146 -0.014510 0.080810 -vn -0.768007 0.009007 -3.115939 -v 0.040328 -0.014546 0.080729 -vn 0.444569 -0.002813 -3.142363 -v 0.040525 -0.014581 0.080720 -vn 1.574319 0.002154 -2.777300 -v 0.040713 -0.014617 0.080784 -vn 2.964112 -0.016808 -0.780142 -v 0.040959 -0.014688 0.081085 -vn 2.821661 -0.022278 -1.304565 -v 0.040950 -0.014683 0.081060 -vn 2.474227 -0.009637 -2.031254 -v 0.040865 -0.014653 0.080912 -vn 3.062249 -0.003681 0.387167 -v 0.040984 -0.014724 0.081283 -vn 3.065440 -0.006446 -0.172358 -v 0.040985 -0.014719 0.081254 -vn 2.618559 0.000687 1.688084 -v 0.040896 -0.014774 0.081546 -vn 2.938859 -0.012095 1.149392 -v 0.040944 -0.014756 0.081455 -vn 1.768740 0.004456 2.494684 -v 0.040757 -0.014810 0.081688 -vn 2.228420 0.013444 2.107620 -v 0.040837 -0.014791 0.081619 -vn -0.296324 -0.002973 3.050198 -v 0.040399 -0.014877 0.081783 -vn 0.208634 -0.002982 3.048423 -v 0.040486 -0.014862 0.081784 -vn 0.760358 0.011199 2.961518 -v 0.040577 -0.014845 0.081769 -vn 1.265652 0.017916 2.799628 -v 0.040680 -0.014826 0.081733 -vn -2.030544 -0.008581 2.376562 -v 0.040115 -0.014933 0.081667 -vn -1.431718 -0.007412 2.698511 -v 0.040207 -0.014913 0.081726 -vn -0.884643 -0.002368 2.914786 -v 0.040291 -0.014897 0.081761 -vn -2.520124 0.004443 1.732961 -v 0.039986 -0.014968 0.081518 -vn -2.789546 0.006541 1.287451 -v 0.039983 -0.014969 0.081512 -vn -2.968224 0.022602 0.781956 -v 0.039926 -0.014999 0.081354 -vn -3.060312 0.000562 0.267988 -v 0.039922 -0.015003 0.081332 -vn -3.071524 0.008878 -0.337134 -v 0.039923 -0.015035 0.081156 -vn -2.990113 0.000519 -0.933278 -v 0.039928 -0.015039 0.081131 -vn -2.797178 0.011279 -1.424777 -v 0.039992 -0.015070 0.080974 -vn -2.442736 0.001362 -1.890853 -v 0.040009 -0.015075 0.080948 -vn -1.897957 -0.004900 -2.530218 -v 0.040125 -0.015106 0.080825 -vn -0.883842 0.006316 -3.074247 -v 0.040299 -0.015141 0.080737 -vn 0.171429 0.029318 -3.147842 -v 0.040498 -0.015177 0.080717 -vn 0.911707 -0.004521 -2.948053 -v 0.040618 -0.015199 0.080742 -vn 1.416973 -0.018945 -2.742179 -v 0.040686 -0.015212 0.080770 -vn 1.846736 -0.004103 -2.427411 -v 0.040786 -0.015233 0.080834 -vn 2.280818 0.011946 -2.075889 -v 0.040828 -0.015243 0.080872 -vn 2.628533 0.013479 -1.630419 -v 0.040917 -0.015269 0.080988 -vn 2.887407 -0.009004 -1.118284 -v 0.040941 -0.015279 0.081037 -vn 3.010377 0.006060 -0.534492 -v 0.040980 -0.015305 0.081180 -vn 3.043600 -0.001294 0.013205 -v 0.040984 -0.015314 0.081229 -vn 2.992998 -0.001154 0.620723 -v 0.040969 -0.015342 0.081383 -vn 2.867980 -0.001439 1.162596 -v 0.040956 -0.015350 0.081426 -vn 2.564428 0.001480 1.693866 -v 0.040882 -0.015378 0.081566 -vn 2.242519 -0.019049 2.105427 -v 0.040858 -0.015385 0.081596 -vn 1.825344 -0.003168 2.486732 -v 0.040743 -0.015413 0.081697 -vn -1.144140 0.005801 2.873255 -v 0.040254 -0.015504 0.081748 -vn -0.493870 -0.008833 3.078196 -v 0.040345 -0.015487 0.081775 -vn 0.203009 -0.015217 3.081043 -v 0.040517 -0.015456 0.081781 -vn 0.751650 0.009125 2.987222 -v 0.040555 -0.015449 0.081775 -vn 1.323699 0.010820 2.799840 -v 0.040703 -0.015421 0.081722 -vn -2.753446 0.001223 1.333613 -v 0.039968 -0.015575 0.081482 -vn -2.485767 -0.007108 1.834099 -v 0.040016 -0.015558 0.081562 -vn -2.107527 -0.011560 2.220407 -v 0.040089 -0.015539 0.081644 -vn -1.633538 0.007533 2.585310 -v 0.040160 -0.015523 0.081700 -vn -2.979824 -0.017420 0.745444 -v 0.039931 -0.015594 0.081383 -vn -3.120990 -0.053814 0.245448 -v 0.039916 -0.015612 0.081285 -vn -0.753331 0.010202 -3.025778 -v 0.040306 -0.013342 0.080735 -vn -1.359479 -0.004768 -2.739026 -v 0.040216 -0.013325 0.080768 -vn -1.851120 -0.000250 -2.421750 -v 0.040124 -0.013305 0.080826 -vn -2.245000 0.005914 -2.050707 -v 0.040056 -0.013289 0.080888 -vn -2.683308 -0.014375 -1.576339 -v 0.039994 -0.013271 0.080971 -vn -3.070569 -0.039644 -1.048969 -v 0.039951 -0.013254 0.081055 -vn -3.246589 -0.023840 -0.093984 -v 0.039915 -0.013218 0.081250 -vn 2.973284 -0.015255 -1.151604 -v 0.040950 -0.012284 0.081062 -vn -0.938756 -0.013010 -2.950370 -v 0.040306 -0.010942 0.080735 -vn -0.402627 0.006631 -3.014247 -v 0.040379 -0.010955 0.080720 -vn -0.025642 -0.009209 -3.116590 -v 0.040417 -0.010962 0.080716 -vn 0.587056 -0.015207 -3.034316 -v 0.040590 -0.010993 0.080733 -vn 1.158031 -0.004550 -2.866973 -v 0.040616 -0.010998 0.080741 -vn 1.984731 -0.007273 -2.475400 -v 0.040779 -0.011031 0.080828 -vn 2.763837 0.002723 -1.611257 -v 0.040917 -0.011069 0.080988 -vn 2.902701 -0.004525 0.952053 -v 0.040964 -0.011145 0.081400 -vn 3.053750 -0.004075 0.387580 -v 0.040977 -0.011135 0.081343 -vn 3.058041 -0.007295 -0.177952 -v 0.040981 -0.011107 0.081189 -vn 2.984810 0.018177 -0.752190 -v 0.040976 -0.011100 0.081150 -vn 0.196400 -0.003441 3.203743 -v 0.040501 -0.011259 0.081783 -vn 1.118610 -0.001374 2.895033 -v 0.040669 -0.011228 0.081738 -vn 1.611169 0.022677 2.643501 -v 0.040703 -0.011221 0.081722 -vn 2.083163 0.015885 2.285214 -v 0.040832 -0.011192 0.081624 -vn 2.335536 0.004360 1.897751 -v 0.040866 -0.011183 0.081587 -vn 2.641706 0.002150 1.533726 -v 0.040904 -0.011171 0.081533 -vn -0.920352 0.011981 3.100619 -v 0.040290 -0.011297 0.081761 -vn -1.986431 -0.005437 2.470069 -v 0.040105 -0.011335 0.081659 -vn -2.506225 -0.000058 1.779055 -v 0.039998 -0.011364 0.081535 -vn -2.994484 0.007504 0.705107 -v 0.039923 -0.011401 0.081346 -vn -2.812322 0.007863 1.264683 -v 0.039974 -0.011373 0.081494 -vn -2.973966 0.020434 -0.825428 -v 0.039943 -0.011449 0.081081 -vn -3.101949 -0.000204 -0.251477 -v 0.039916 -0.011422 0.081229 -vn -3.023771 -0.006094 0.182845 -v 0.039916 -0.011411 0.081291 -vn -2.758143 0.011943 -1.349715 -v 0.039959 -0.011457 0.081037 -vn -2.403529 0.004025 -1.893294 -v 0.040047 -0.011487 0.080898 -vn -2.057876 0.002322 -2.317091 -v 0.040065 -0.011491 0.080878 -vn -1.372292 0.003630 -2.879056 -v 0.040215 -0.011525 0.080769 -vn -0.231332 -0.025221 -3.182718 -v 0.040419 -0.011563 0.080716 -vn 0.621299 -0.010371 -3.023146 -v 0.040593 -0.011594 0.080735 -vn 1.186251 0.003338 -2.830756 -v 0.040629 -0.011601 0.080746 -vn 1.727161 0.007342 -2.542652 -v 0.040774 -0.011630 0.080824 -vn 2.073700 -0.005369 -2.194351 -v 0.040810 -0.011638 0.080854 -vn 2.429069 0.000378 -1.906886 -v 0.040860 -0.011652 0.080907 -vn 2.758032 0.006884 -1.388017 -v 0.040935 -0.011676 0.081025 -vn 2.968054 -0.010715 -0.907632 -v 0.040956 -0.011686 0.081076 -vn 3.072506 -0.004976 -0.280307 -v 0.040985 -0.011714 0.081230 -vn 3.074470 0.004774 0.291027 -v 0.040985 -0.011721 0.081265 -vn 2.937951 0.012659 0.885540 -v 0.040951 -0.011752 0.081438 -vn 2.753544 -0.009078 1.381052 -v 0.040944 -0.011756 0.081456 -vn 2.298722 0.003157 2.214743 -v 0.040839 -0.011790 0.081618 -vn 1.324957 0.014599 2.868840 -v 0.040666 -0.011828 0.081739 -vn -1.032471 -0.001702 2.858783 -v 0.040252 -0.011904 0.081747 -vn -0.470787 -0.017223 3.042875 -v 0.040377 -0.011881 0.081780 -vn -0.023517 -0.013248 3.022763 -v 0.040460 -0.011866 0.081785 -vn 0.462791 0.002397 3.038330 -v 0.040497 -0.011860 0.081783 -vn -2.967536 0.038961 1.229744 -v 0.039957 -0.011980 0.081457 -vn -2.520905 0.021959 1.882404 -v 0.040044 -0.011950 0.081599 -vn -2.080462 0.008103 2.272161 -v 0.040075 -0.011942 0.081632 -vn -1.540148 -0.000839 2.623162 -v 0.040195 -0.011915 0.081720 -vn -3.201956 0.002421 0.000368 -v 0.039915 -0.012018 0.081250 -vn -2.950714 0.026920 -1.259709 -v 0.039957 -0.012056 0.081043 -vn -2.471628 0.033184 -1.909329 -v 0.040057 -0.012089 0.080887 -vn 1.117434 0.010538 -2.869447 -v 0.040666 -0.012208 0.080761 -vn 0.514887 -0.015526 -3.045589 -v 0.040516 -0.012180 0.080719 -vn -0.041400 -0.007958 -3.058745 -v 0.040460 -0.012170 0.080715 -vn -0.665390 0.001352 -2.976572 -v 0.040321 -0.012145 0.080731 -vn -1.169038 0.007639 -2.806843 -v 0.040252 -0.012132 0.080753 -vn -1.684237 0.001723 -2.533178 -v 0.040147 -0.012111 0.080809 -vn -2.047680 -0.002464 -2.195258 -v 0.040075 -0.012094 0.080868 -vn 2.482153 -0.020375 -1.876946 -v 0.040846 -0.012248 0.080890 -vn 2.069659 0.030694 -2.281411 -v 0.040839 -0.012246 0.080882 -vn 1.637532 0.024401 -2.639151 -v 0.040703 -0.012215 0.080779 -vn 3.163075 0.007316 0.008311 -v 0.040985 -0.012322 0.081270 -vn 3.026743 0.011525 0.685034 -v 0.040971 -0.012340 0.081372 -vn 2.783726 0.004918 1.262644 -v 0.040935 -0.012360 0.081475 -vn 2.514121 0.011678 1.763041 -v 0.040896 -0.012374 0.081546 -vn 2.141284 0.003775 2.189379 -v 0.040810 -0.012398 0.081646 -vn 1.675116 -0.006228 2.567695 -v 0.040757 -0.012410 0.081688 -vn 1.108081 -0.001464 2.870427 -v 0.040629 -0.012435 0.081754 -vn 0.592339 0.000670 3.064444 -v 0.040577 -0.012445 0.081769 -vn 0.037646 0.014041 3.091426 -v 0.040420 -0.012473 0.081784 -vn -0.507708 -0.004693 3.048495 -v 0.040399 -0.012477 0.081783 -vn -1.427252 -0.022188 2.841811 -v 0.040216 -0.012511 0.081731 -vn -2.284254 0.003742 2.195058 -v 0.040047 -0.012549 0.081602 -vn -3.040224 -0.003078 -0.154844 -v 0.039916 -0.012625 0.081209 -vn -3.033829 -0.007925 0.440139 -v 0.039922 -0.012603 0.081332 -vn -2.898888 -0.000990 0.955504 -v 0.039943 -0.012587 0.081419 -vn -2.665050 0.014748 1.529042 -v 0.039983 -0.012569 0.081512 -vn -0.900845 0.006758 -3.066999 -v 0.040290 -0.012739 0.080739 -vn -1.705963 -0.009499 -2.584109 -v 0.040129 -0.012707 0.080822 -vn -2.098012 0.011805 -2.247006 -v 0.040105 -0.012701 0.080841 -vn -2.481407 0.003231 -1.835691 -v 0.040009 -0.012675 0.080948 -vn -2.750392 0.003001 -1.338486 -v 0.039974 -0.012663 0.081006 -vn -2.960149 0.000410 -0.747001 -v 0.039928 -0.012639 0.081131 -vn 0.289478 0.013637 -3.175321 -v 0.040501 -0.012777 0.080717 -vn 1.354504 -0.011345 -2.832964 -v 0.040703 -0.012815 0.080778 -vn 1.957249 -0.009321 -2.392813 -v 0.040786 -0.012833 0.080834 -vn 2.378674 0.012557 -1.971933 -v 0.040866 -0.012853 0.080913 -vn 2.689254 0.010937 -1.488350 -v 0.040917 -0.012869 0.080988 -vn 2.933052 -0.006150 -0.884565 -v 0.040964 -0.012891 0.081100 -vn 3.072344 -0.008140 -0.333788 -v 0.040980 -0.012905 0.081180 -vn 3.078019 0.015798 0.269403 -v 0.040981 -0.012929 0.081311 -vn 2.960646 0.011582 0.818935 -v 0.040969 -0.012942 0.081383 -vn 2.709536 -0.003733 1.432999 -v 0.040917 -0.012967 0.081512 -vn 2.419552 -0.007466 1.921545 -v 0.040882 -0.012978 0.081566 -vn 2.001922 0.009091 2.365069 -v 0.040779 -0.013005 0.081672 -vn 1.588513 -0.011241 2.680726 -v 0.040743 -0.013013 0.081697 -vn 0.992917 -0.013598 2.933423 -v 0.040590 -0.013043 0.081767 -vn 0.405806 -0.003625 3.060849 -v 0.040555 -0.013049 0.081775 -vn -0.461164 -0.006744 3.135165 -v 0.040379 -0.013081 0.081780 -vn -1.535160 -0.009227 2.805931 -v 0.040180 -0.013119 0.081712 -vn -2.054157 0.008728 2.340327 -v 0.040089 -0.013139 0.081644 -vn -2.458959 0.006789 1.825729 -v 0.040022 -0.013157 0.081571 -vn -2.796309 0.013804 1.334491 -v 0.039968 -0.013175 0.081482 -vn -3.083023 0.008304 0.688125 -v 0.039931 -0.013194 0.081381 -vn -1.461022 -0.024391 -2.713697 -v 0.040180 -0.010917 0.080788 -vn -1.975163 0.002620 -2.354578 -v 0.040124 -0.010905 0.080826 -vn -2.360086 0.000037 -1.950872 -v 0.040022 -0.010879 0.080929 -vn -2.704626 0.024694 -1.466108 -v 0.039994 -0.010871 0.080971 -vn -3.108574 0.022992 -0.787882 -v 0.039931 -0.010842 0.081119 -vn -3.171769 -0.028632 -0.075024 -v 0.039915 -0.010818 0.081250 -vn -0.238351 0.001014 3.082918 -v 0.040390 -0.009478 0.081782 -vn -0.800870 0.005128 2.996134 -v 0.040328 -0.009490 0.081771 -vn -1.274530 -0.008498 2.785401 -v 0.040202 -0.009514 0.081724 -vn -1.701766 0.002835 2.536794 -v 0.040176 -0.009519 0.081710 -vn -2.164138 0.005667 2.150584 -v 0.040052 -0.009548 0.081607 -vn -2.476036 -0.006423 1.757038 -v 0.040027 -0.009555 0.081578 -vn -2.906978 -0.015438 1.153318 -v 0.039957 -0.009580 0.081458 -vn -3.136193 -0.010585 0.228825 -v 0.039915 -0.009614 0.081271 -vn -3.068924 0.008016 -0.457337 -v 0.039922 -0.009634 0.081161 -vn -2.916011 0.009136 -0.943254 -v 0.039938 -0.009646 0.081096 -vn -2.668487 0.001149 -1.518116 -v 0.039992 -0.009670 0.080974 -vn -2.396279 -0.010635 -1.933687 -v 0.040024 -0.009680 0.080926 -vn -1.985414 -0.005370 -2.332997 -v 0.040120 -0.009704 0.080829 -vn -1.570806 -0.015740 -2.669803 -v 0.040154 -0.009712 0.080805 -vn -1.057906 0.009177 -2.920961 -v 0.040296 -0.009740 0.080738 -vn 0.303020 0.011325 -3.127167 -v 0.040506 -0.009778 0.080718 -vn -0.532110 0.007183 -3.030225 -v 0.040329 -0.009746 0.080729 -vn 2.833349 0.037736 -1.374888 -v 0.040939 -0.009878 0.081033 -vn 2.362674 0.002553 -1.980305 -v 0.040832 -0.009844 0.080875 -vn 1.951722 -0.006638 -2.366607 -v 0.040816 -0.009840 0.080859 -vn 1.506077 -0.013573 -2.695932 -v 0.040689 -0.009812 0.080771 -vn 0.980544 0.008603 -2.913065 -v 0.040641 -0.009803 0.080750 -vn 3.005297 0.024995 -0.783555 -v 0.040968 -0.009894 0.081115 -vn 3.111021 -0.044536 -0.299854 -v 0.040983 -0.009910 0.081205 -vn 3.096558 -0.022778 -0.025050 -v 0.040985 -0.009917 0.081246 -vn 3.058985 0.009325 0.416009 -v 0.040980 -0.009930 0.081320 -vn 2.941380 0.027154 0.775617 -v 0.040965 -0.009944 0.081395 -vn 2.806654 0.005959 1.196404 -v 0.040949 -0.009953 0.081443 -vn 2.581183 -0.004658 1.648469 -v 0.040890 -0.009976 0.081555 -vn 2.393287 -0.004928 1.820752 -v 0.040877 -0.009980 0.081573 -vn 2.179334 -0.014035 2.128894 -v 0.040846 -0.009988 0.081609 -vn 1.816269 -0.006857 2.499579 -v 0.040754 -0.010010 0.081690 -vn 1.340598 0.001012 2.731675 -v 0.040688 -0.010024 0.081729 -vn 0.883714 0.003444 2.880824 -v 0.040594 -0.010042 0.081765 -vn 0.597778 -0.000128 2.937987 -v 0.040563 -0.010047 0.081773 -vn 0.207466 0.006697 3.046168 -v 0.040496 -0.010060 0.081783 -vn -0.260821 0.008568 3.068073 -v 0.040404 -0.010076 0.081783 -vn -0.827685 -0.008038 2.947110 -v 0.040302 -0.010094 0.081764 -vn -1.167473 -0.000484 2.804099 -v 0.040233 -0.010108 0.081739 -vn -1.461532 0.014638 2.637252 -v 0.040202 -0.010114 0.081724 -vn -1.858781 0.022558 2.433024 -v 0.040125 -0.010130 0.081675 -vn -2.555447 0.003841 1.619692 -v 0.039995 -0.010165 0.081531 -vn -2.297876 -0.001334 1.967939 -v 0.040049 -0.010149 0.081604 -vn -2.102854 0.022174 2.198154 -v 0.040075 -0.010142 0.081632 -vn -2.761888 -0.011331 1.325287 -v 0.039971 -0.010174 0.081488 -vn -2.886951 -0.007230 1.054918 -v 0.039948 -0.010184 0.081434 -vn -2.956424 -0.013400 0.600474 -v 0.039923 -0.010201 0.081345 -vn -3.007959 -0.000212 0.282732 -v 0.039918 -0.010208 0.081305 -vn -3.035249 0.008411 -0.057117 -v 0.039915 -0.010218 0.081247 -vn -2.973164 0.002573 -0.505476 -v 0.039926 -0.010237 0.081145 -vn -2.914853 -0.005027 -0.747839 -v 0.039929 -0.010240 0.081128 -vn -2.851454 -0.001675 -1.158775 -v 0.039950 -0.010253 0.081059 -vn -2.558191 0.011522 -1.807011 -v 0.040005 -0.010274 0.080953 -vn -1.900040 -0.003483 -2.523939 -v 0.040126 -0.010306 0.080824 -vn -1.107285 -0.000747 -2.880107 -v 0.040296 -0.010340 0.080738 -vn -0.542179 -0.011502 -3.065587 -v 0.040317 -0.010344 0.080732 -vn -0.082966 0.009511 -3.118409 -v 0.040472 -0.010372 0.080715 -vn 0.507738 0.001753 -3.019078 -v 0.040513 -0.010379 0.080719 -vn 1.060060 0.003593 -2.877915 -v 0.040658 -0.010406 0.080757 -vn 1.542606 -0.013478 -2.635868 -v 0.040702 -0.010415 0.080778 -vn 2.002039 -0.009981 -2.355176 -v 0.040808 -0.010438 0.080852 -vn 2.469343 -0.036364 -1.948479 -v 0.040857 -0.010450 0.080903 -vn 2.756380 -0.034007 -1.531347 -v 0.040924 -0.010472 0.081003 -vn 2.928213 -0.019428 -0.971933 -v 0.040959 -0.010488 0.081086 -vn 3.019906 -0.020126 -0.506572 -v 0.040979 -0.010504 0.081171 -vn 3.037388 -0.012688 -0.255449 -v 0.040983 -0.010509 0.081198 -vn 3.042162 -0.019558 0.194478 -v 0.040984 -0.010524 0.081284 -vn 2.978097 -0.007085 0.559569 -v 0.040973 -0.010538 0.081362 -vn 2.878869 0.002600 0.856811 -v 0.040966 -0.010543 0.081392 -vn 2.759198 0.009153 1.256986 -v 0.040935 -0.010559 0.081476 -vn 2.592190 0.005734 1.576424 -v 0.040908 -0.010570 0.081527 -vn 2.439960 0.006682 1.849839 -v 0.040881 -0.010578 0.081567 -vn 2.135221 -0.007294 2.165640 -v 0.040819 -0.010595 0.081638 -vn 1.882710 0.001760 2.387437 -v 0.040782 -0.010604 0.081670 -vn 1.600735 0.019073 2.577318 -v 0.040740 -0.010613 0.081699 -vn 1.197057 0.010105 2.795176 -v 0.040650 -0.010631 0.081746 -vn 0.838111 0.022570 3.018356 -v 0.040627 -0.010636 0.081755 -vn 0.405498 0.044838 3.103999 -v 0.040483 -0.010662 0.081784 -vn 0.046108 0.006502 2.975229 -v 0.040458 -0.010666 0.081785 -vn -0.246173 0.008951 3.056399 -v 0.040438 -0.010670 0.081785 -vn -0.717781 0.020280 2.969203 -v 0.040298 -0.010695 0.081763 -vn -1.228012 0.001653 2.807770 -v 0.040264 -0.010702 0.081752 -vn -1.719640 0.006696 2.526291 -v 0.040123 -0.010731 0.081674 -vn -2.143761 -0.016092 2.188597 -v 0.040100 -0.010736 0.081654 -vn -2.495862 -0.006691 1.792056 -v 0.039995 -0.010765 0.081532 -vn -2.570699 0.000653 1.468079 -v 0.039987 -0.010768 0.081518 -vn -2.868627 -0.023820 1.193622 -v 0.039972 -0.010773 0.081491 -vn -3.104475 -0.042649 0.641719 -v 0.039922 -0.010802 0.081338 -vn 0.335287 0.015400 3.089005 -v 0.040526 -0.009454 0.081779 -vn 0.594779 4.006989 4.279747 -v 0.040569 -0.009702 0.082235 -vn 0.922434 0.018356 2.940951 -v 0.040588 -0.009443 0.081767 -vn 1.058515 4.900138 3.582218 -v 0.040793 -0.009650 0.082125 -vn 1.772884 0.503224 3.242930 -v 0.040715 -0.009418 0.081715 -vn 1.593735 4.884595 3.421793 -v 0.040900 -0.009620 0.082041 -vn 0.597248 5.846858 1.469187 -v 0.040755 -0.009410 0.081690 -vn 2.231949 4.845278 3.039300 -v 0.040983 -0.009593 0.081954 -vn 0.828926 5.842711 1.370543 -v 0.040901 -0.009410 0.081621 -vn 2.730801 4.903708 2.549171 -v 0.041114 -0.009533 0.081735 -vn 1.031264 5.846489 1.214467 -v 0.040931 -0.009410 0.081600 -vn 3.052165 4.950692 2.070169 -v 0.041143 -0.009511 0.081650 -vn 1.384455 5.815083 0.874854 -v 0.041074 -0.009410 0.081444 -vn 3.425133 4.905866 1.432409 -v 0.041169 -0.009473 0.081504 -vn 2.275302 5.278039 0.304089 -v 0.041150 -0.009410 0.081275 -vn 0.772597 0.357443 1.233528 -v 0.040607 -0.009410 0.081825 -vn 3.438959 -0.474449 0.761423 -v 0.041394 -0.009702 0.081559 -vn 3.533389 -0.481888 0.131958 -v 0.041426 -0.009686 0.081314 -vn 3.570893 -0.494706 -0.386076 -v 0.041423 -0.009682 0.081250 -vn 3.337311 -0.440839 -0.979882 -v 0.041394 -0.009670 0.081073 -vn 3.169386 -0.469512 -1.568332 -v 0.041307 -0.009655 0.080853 -vn 2.904633 -0.502566 -2.081773 -v 0.041264 -0.009650 0.080780 -vn 2.510024 -0.457042 -2.426646 -v 0.041153 -0.009638 0.080642 -vn 2.168380 -0.417130 -2.745652 -v 0.041080 -0.009631 0.080576 -vn 1.667087 -0.467366 -3.111079 -v 0.040951 -0.009621 0.080489 -vn 1.081415 -0.460156 -3.397653 -v 0.040771 -0.009607 0.080413 -vn 0.580885 -0.416808 -3.444605 -v 0.040707 -0.009603 0.080396 -vn -0.109483 -0.475712 -3.533921 -v 0.040450 -0.009585 0.080375 -vn -0.668617 -0.488792 -3.532705 -v 0.040350 -0.009578 0.080387 -vn -1.021529 -0.483677 -3.398394 -v 0.040292 -0.009573 0.080400 -vn -1.635919 -0.468620 -3.108414 -v 0.040118 -0.009560 0.080467 -vn -2.154035 -0.498841 -2.861056 -v 0.039997 -0.009549 0.080544 -vn -2.588266 -0.462467 -2.429396 -v 0.039913 -0.009541 0.080617 -vn -3.056986 -0.472895 -1.694474 -v 0.039775 -0.009524 0.080795 -vn -3.375853 -0.444715 -0.707894 -v 0.039689 -0.009506 0.081014 -vn -3.459881 -0.443817 0.375258 -v 0.039675 -0.009486 0.081261 -vn -3.233010 -0.434367 1.286618 -v 0.039724 -0.009469 0.081472 -vn -2.798364 -0.191791 1.539898 -v 0.039773 -0.009459 0.081573 -vn -2.697344 -0.445520 2.274478 -v 0.039839 -0.009450 0.081669 -vn -2.151987 -0.263113 2.546004 -v 0.039923 -0.009440 0.081756 -vn -1.835694 -0.496552 3.081645 -v 0.040014 -0.009430 0.081823 -vn -0.931181 0.084786 2.605678 -v 0.040154 -0.009416 0.081891 -vn -0.087454 0.358376 1.437563 -v 0.040228 -0.009410 0.081914 -vn 0.349586 0.344056 1.378278 -v 0.040443 -0.009410 0.081895 -vn -1.376655 5.234040 1.883484 -v 0.040028 -0.009410 0.081808 -vn -1.887503 5.303436 1.256542 -v 0.039872 -0.009410 0.081645 -vn -2.265481 5.207337 0.628098 -v 0.039776 -0.009410 0.081440 -vn -2.360090 5.196560 -0.132291 -v 0.039751 -0.009410 0.081214 -vn -2.203805 5.233590 -0.767299 -v 0.039790 -0.009410 0.081018 -vn -2.054657 5.241632 -1.103645 -v 0.039844 -0.009410 0.080900 -vn -1.769102 5.251340 -1.502294 -v 0.039898 -0.009410 0.080819 -vn -1.278741 5.242811 -1.935904 -v 0.040064 -0.009410 0.080666 -vn -0.619099 5.253560 -2.228994 -v 0.040271 -0.009410 0.080573 -vn 0.123569 5.218545 -2.331544 -v 0.040450 -0.009410 0.080550 -vn 1.170444 5.190416 -2.027137 -v 0.040800 -0.009410 0.080644 -vn 2.041862 5.180056 -1.158937 -v 0.041056 -0.009410 0.080900 -vn 2.293401 5.261351 -0.238231 -v 0.041150 -0.009410 0.081250 -vn 4.520942 1.210830 -3.903153 -v 0.007976 -0.041610 0.079924 -vn 3.946144 0.252486 -4.837389 -v 0.007917 -0.041610 0.079868 -vn 3.892036 1.473907 -4.456038 -v 0.007916 -0.041581 0.079869 -vn 2.739936 1.467132 -5.245538 -v 0.007475 -0.041581 0.079569 -vn -0.489171 6.145068 -0.779751 -v 0.005880 -0.041410 0.079762 -vn -0.259326 6.187839 -0.721066 -v 0.005997 -0.041410 0.079707 -vn -1.096462 5.322632 -2.632505 -v 0.005962 -0.041431 0.079625 -vn 0.906658 6.119468 -0.422608 -v 0.008217 -0.041410 0.080657 -vn 0.753300 6.186733 -0.160933 -v 0.008270 -0.041410 0.080823 -vn 2.760858 5.322820 -0.710761 -v 0.008357 -0.041431 0.080800 -vn 2.845362 5.323619 0.088835 -v 0.008414 -0.041431 0.081299 -vn 0.796603 6.179495 -0.066908 -v 0.008325 -0.041410 0.081250 -vn 0.757567 6.189262 0.072615 -v 0.008324 -0.041410 0.081297 -vn 0.677289 6.184789 -0.381482 -v 0.008084 -0.041410 0.080384 -vn 2.445645 5.323568 -1.459207 -v 0.008161 -0.041431 0.080338 -vn 0.687581 6.154078 -0.566789 -v 0.007926 -0.041410 0.080165 -vn 1.931390 5.320557 -2.112608 -v 0.007843 -0.041431 0.079949 -vn 0.505689 6.190107 -0.564443 -v 0.007782 -0.041410 0.080015 -vn 0.498449 6.154268 -0.737810 -v 0.007557 -0.041410 0.079841 -vn 1.247601 5.321712 -2.569798 -v 0.007428 -0.041431 0.079666 -vn 0.314737 6.188372 -0.696440 -v 0.007388 -0.041410 0.079746 -vn 0.234897 6.172728 -0.790921 -v 0.007019 -0.041410 0.079616 -vn 0.467761 5.322245 -2.814889 -v 0.006950 -0.041431 0.079511 -vn 0.083033 6.188228 -0.760414 -v 0.006935 -0.041410 0.079599 -vn -0.317586 5.323423 -2.829936 -v 0.006448 -0.041431 0.079497 -vn -0.035201 6.188869 -0.761813 -v 0.006458 -0.041410 0.079586 -vn -0.177952 6.179662 -0.778660 -v 0.006415 -0.041410 0.079591 -vn -0.470491 6.185482 -0.615486 -v 0.005589 -0.041410 0.079954 -vn -1.791356 5.323670 -2.213291 -v 0.005532 -0.041431 0.079884 -vn -0.659984 6.153273 -0.602744 -v 0.005403 -0.041410 0.080132 -vn -2.365347 5.321597 -1.602560 -v 0.005193 -0.041431 0.080255 -vn -0.645291 6.187338 -0.416753 -v 0.005266 -0.041410 0.080305 -vn -0.753638 6.171175 -0.349694 -v 0.005089 -0.041410 0.080644 -vn -2.719665 5.322293 -0.863060 -v 0.004971 -0.041431 0.080706 -vn -0.741049 6.188048 -0.192160 -v 0.005057 -0.041410 0.080733 -vn -2.845317 5.323655 -0.088824 -v 0.004886 -0.041431 0.081201 -vn -0.757551 6.189266 -0.072615 -v 0.004976 -0.041410 0.081203 -vn -6.219998 0.244108 -0.559861 -v 0.004776 -0.041610 0.081198 -vn -5.908062 1.475865 -0.302113 -v 0.004778 -0.041581 0.081198 -vn -6.019384 0.251142 -1.632320 -v 0.004866 -0.041610 0.080672 -vn -5.672003 1.460596 -1.689741 -v 0.004868 -0.041581 0.080672 -vn -5.290768 1.477528 -2.455416 -v 0.004918 -0.041610 0.080532 -vn -4.897302 1.447626 -3.326662 -v 0.005103 -0.041581 0.080194 -vn -3.646064 1.450738 -4.661934 -v 0.005464 -0.041581 0.079801 -vn -4.187052 1.598816 -3.941257 -v 0.005324 -0.041610 0.079924 -vn -5.156902 0.235700 -3.497673 -v 0.005102 -0.041610 0.080193 -vn 1.042799 1.447902 -5.827669 -v 0.006968 -0.041581 0.079404 -vn 0.101574 1.668445 -5.707230 -v 0.006650 -0.041610 0.079375 -vn -0.799849 1.443377 -5.863956 -v 0.006435 -0.041581 0.079389 -vn -0.959752 0.249015 -6.155946 -v 0.006435 -0.041610 0.079387 -vn -2.304028 1.358095 -5.443247 -v 0.005920 -0.041581 0.079525 -vn -2.413850 0.271286 -5.705059 -v 0.005919 -0.041610 0.079523 -vn -3.730191 0.240144 -4.993884 -v 0.005462 -0.041610 0.079799 -vn 3.042316 0.236196 -5.447305 -v 0.007476 -0.041610 0.079567 -vn 1.966002 1.318409 -5.577275 -v 0.007368 -0.041610 0.079518 -vn 1.145283 0.230752 -6.124733 -v 0.006969 -0.041610 0.079402 -vn 5.245275 0.263611 -3.354753 -v 0.008255 -0.041610 0.080281 -vn 5.013715 1.425800 -3.143322 -v 0.008253 -0.041581 0.080282 -vn 5.234230 1.704329 -2.206378 -v 0.008382 -0.041610 0.080532 -vn 5.746018 1.447444 -1.422325 -v 0.008461 -0.041581 0.080773 -vn 6.070887 0.236385 -1.405598 -v 0.008463 -0.041610 0.080772 -vn 6.117671 0.794079 -0.449337 -v 0.008525 -0.041610 0.081250 -vn 5.908059 1.475933 0.302207 -v 0.008522 -0.041581 0.081302 -vn 6.220003 0.244115 0.560071 -v 0.008524 -0.041610 0.081302 -vn 4.875389 3.420780 0.136400 -v 0.008487 -0.041494 0.081301 -vn 4.716318 3.420825 -1.242642 -v 0.008427 -0.041494 0.080782 -vn 4.175190 3.420811 -2.521038 -v 0.008223 -0.041494 0.080300 -vn 3.295796 3.420712 -3.595240 -v 0.007892 -0.041494 0.079895 -vn 2.149411 3.420800 -4.378150 -v 0.007460 -0.041494 0.079600 -vn 0.828879 3.420786 -4.806333 -v 0.006962 -0.041494 0.079439 -vn -0.558773 3.420864 -4.845125 -v 0.006439 -0.041494 0.079425 -vn -1.901179 3.420852 -4.491442 -v 0.005934 -0.041494 0.079558 -vn -3.089599 3.420767 -3.773911 -v 0.005486 -0.041494 0.079828 -vn -4.027712 3.420825 -2.750605 -v 0.005133 -0.041494 0.080214 -vn -4.639453 3.420755 -1.504456 -v 0.004902 -0.041494 0.080683 -vn -4.875356 3.420794 -0.136451 -v 0.004813 -0.041494 0.081199 -vn -5.503525 -0.940498 2.593523 -v 0.004918 -0.042410 0.081968 -vn -5.896132 -0.776651 1.656656 -v 0.004873 -0.042410 0.081849 -vn -4.986580 -2.804516 1.638802 -v 0.004919 -0.042600 0.081834 -vn 1.176913 -6.040430 0.691875 -v 0.007963 -0.042807 0.082022 -vn 0.179304 -6.276206 0.105408 -v 0.007922 -0.042810 0.081998 -vn 0.201717 -6.276207 0.050757 -v 0.008081 -0.042810 0.081609 -vn 0.934316 -6.040426 0.995437 -v 0.007693 -0.042807 0.082361 -vn 0.142345 -6.276206 0.151656 -v 0.007659 -0.042810 0.082325 -vn 0.247827 -6.040424 1.342537 -v 0.006927 -0.042807 0.082748 -vn 0.037753 -6.276207 0.204522 -v 0.006918 -0.042810 0.082700 -vn 0.093851 -6.276206 0.185610 -v 0.007316 -0.042810 0.082566 -vn -0.021397 -6.276206 0.206891 -v 0.006498 -0.042810 0.082717 -vn -0.140454 -6.040422 1.357993 -v 0.006493 -0.042807 0.082765 -vn 0.628477 -4.912593 3.404653 -v 0.006958 -0.042742 0.082921 -vn -1.118259 -6.040429 0.783145 -v 0.005402 -0.042807 0.082124 -vn -0.170367 -6.276206 0.119310 -v 0.005442 -0.042810 0.082096 -vn -0.129855 -6.276205 0.162484 -v 0.005729 -0.042810 0.082402 -vn -1.293614 -6.040424 0.436352 -v 0.005206 -0.042807 0.081737 -vn -0.197079 -6.276206 0.066476 -v 0.005252 -0.042810 0.081721 -vn -1.369964 -6.040128 0.060518 -v 0.005128 -0.042807 0.081311 -vn -0.199920 -6.276722 0.020993 -v 0.005176 -0.042810 0.081309 -vn 1.324170 -6.040427 0.332282 -v 0.008128 -0.042807 0.081621 -vn 1.369664 -6.040112 -0.059493 -v 0.008172 -0.042807 0.081189 -vn 3.459385 -4.912661 -0.137555 -v 0.008347 -0.042742 0.081183 -vn 2.427384 -2.816486 4.654162 -v 0.007474 -0.042600 0.082881 -vn 1.562215 -4.912622 3.089656 -v 0.007417 -0.042742 0.082766 -vn 0.616025 -6.040431 1.218327 -v 0.007337 -0.042807 0.082610 -vn -1.311959 -4.912639 3.203920 -v 0.006006 -0.042742 0.082822 -vn -2.161467 -4.912638 2.704523 -v 0.005589 -0.042742 0.082577 -vn -0.852330 -6.040431 1.066471 -v 0.005699 -0.042807 0.082440 -vn -3.221546 -2.814872 4.145705 -v 0.005509 -0.042600 0.082677 -vn -1.992935 -2.746204 4.866897 -v 0.005958 -0.042600 0.082941 -vn -0.588473 -2.807198 5.216047 -v 0.006462 -0.042600 0.083067 -vn 5.244498 -2.801511 -0.253587 -v 0.008476 -0.042600 0.081177 -vn 6.101408 -0.768177 -0.602072 -v 0.008524 -0.042410 0.081175 -vn 6.112478 -0.829710 0.325862 -v 0.008525 -0.042410 0.081250 -vn 3.358031 -4.912639 0.842641 -v 0.008298 -0.042742 0.081663 -vn 5.093776 -2.764923 1.302405 -v 0.008422 -0.042600 0.081695 -vn 5.923236 -0.818676 1.410978 -v 0.008469 -0.042410 0.081706 -vn 4.510591 -2.816095 2.685488 -v 0.008225 -0.042600 0.082176 -vn 2.984608 -4.912628 1.754571 -v 0.008114 -0.042742 0.082111 -vn 0.233624 -6.274386 0.022912 -v 0.008125 -0.042810 0.081250 -vn 0.199870 -6.276725 -0.020994 -v 0.008124 -0.042810 0.081191 -vn 5.583275 -1.154750 2.182423 -v 0.008382 -0.042410 0.081968 -vn 5.187780 -0.768533 3.235294 -v 0.008266 -0.042410 0.082200 -vn 4.566195 -0.823105 4.083158 -v 0.007976 -0.042410 0.082576 -vn 2.369377 -4.912642 2.524365 -v 0.007813 -0.042742 0.082489 -vn 3.566515 -2.794296 3.854853 -v 0.007900 -0.042600 0.082582 -vn 3.920121 -0.778984 4.716632 -v 0.007933 -0.042410 0.082617 -vn 3.031493 -0.762700 5.319040 -v 0.007496 -0.042410 0.082923 -vn 2.123276 -0.868466 5.723110 -v 0.007368 -0.042410 0.082982 -vn 0.912556 -2.780871 5.176126 -v 0.006982 -0.042600 0.083047 -vn -0.356143 -4.912688 3.443745 -v 0.006475 -0.042742 0.082940 -vn -0.517337 -6.040430 1.263391 -v 0.006073 -0.042807 0.082660 -vn -0.078814 -6.276207 0.192466 -v 0.006091 -0.042810 0.082615 -vn 1.102712 -0.797291 5.994443 -v 0.006990 -0.042410 0.083094 -vn 0.208661 -1.046757 6.038594 -v 0.006650 -0.042410 0.083125 -vn -0.886998 -0.773751 6.050683 -v 0.006457 -0.042410 0.083115 -vn -2.296863 -0.786945 5.612347 -v 0.005939 -0.042410 0.082985 -vn -3.615584 -0.765286 4.929571 -v 0.005479 -0.042410 0.082715 -vn -4.387065 -0.909497 4.228899 -v 0.005324 -0.042410 0.082576 -vn -2.835884 -4.912613 1.986021 -v 0.005258 -0.042742 0.082225 -vn -4.336432 -2.795602 2.966374 -v 0.005153 -0.042600 0.082298 -vn -5.050172 -0.791314 3.425022 -v 0.005114 -0.042410 0.082326 -vn -3.280520 -4.912633 1.106603 -v 0.005040 -0.042742 0.081793 -vn -3.459320 -4.912665 0.137550 -v 0.004953 -0.042742 0.081317 -vn -5.244524 -2.801483 0.253605 -v 0.004824 -0.042600 0.081323 -vn -6.101401 -0.768178 0.601997 -v 0.004776 -0.042410 0.081324 -vn -1.747885 -2.525898 4.227557 -v 0.006186 -0.009863 0.082136 -vn -1.267479 -2.536558 4.367491 -v 0.006337 -0.009848 0.082200 -vn -2.566278 2.608287 3.711290 -v 0.006133 -0.009770 0.082106 -vn 0.081467 2.630648 -4.550662 -v 0.006650 -0.010018 0.080250 -vn -0.460336 -2.634834 -4.521347 -v 0.006650 -0.010117 0.080250 -vn -0.622965 2.588489 -4.533442 -v 0.006411 -0.009995 0.080279 -vn -1.441427 -2.620034 -4.261365 -v 0.006382 -0.010091 0.080287 -vn -1.296550 2.606323 -4.365777 -v 0.006363 -0.009990 0.080292 -vn -2.455927 -2.615767 -3.821456 -v 0.006133 -0.010065 0.080394 -vn -1.885267 2.566797 -4.119758 -v 0.006159 -0.009969 0.080379 -vn -2.963529 -2.648102 -3.485225 -v 0.006045 -0.010055 0.080454 -vn -2.596015 2.656173 -3.751804 -v 0.006033 -0.009955 0.080463 -vn -3.355494 -2.704881 -3.105170 -v 0.005943 -0.010042 0.080543 -vn -3.095310 2.664026 -3.327352 -v 0.005943 -0.009943 0.080543 -vn -3.618371 -2.625215 -2.738340 -v 0.005917 -0.010039 0.080570 -vn -3.731235 2.570643 -2.544078 -v 0.005794 -0.009920 0.080733 -vn -4.062283 -2.557606 -2.000956 -v 0.005779 -0.010017 0.080759 -vn -4.274920 2.627834 -1.432570 -v 0.005687 -0.009894 0.080981 -vn -4.271136 -2.395870 -1.531009 -v 0.005716 -0.010002 0.080893 -vn -4.504620 -2.573132 -0.690323 -v 0.005679 -0.009991 0.081011 -vn -4.487179 2.567191 -0.255255 -v 0.005650 -0.009868 0.081250 -vn -4.510026 -2.560148 0.248020 -v 0.005650 -0.009968 0.081250 -vn -4.524740 2.638854 0.615308 -v 0.005679 -0.009845 0.081489 -vn -4.398128 -2.632728 1.192149 -v 0.005680 -0.009944 0.081492 -vn -4.423705 2.687443 1.201353 -v 0.005691 -0.009841 0.081532 -vn -4.163058 -2.577355 1.899534 -v 0.005711 -0.009934 0.081594 -vn -4.104913 2.630910 1.959323 -v 0.005779 -0.009819 0.081741 -vn -3.817609 -2.627567 2.472553 -v 0.005778 -0.009918 0.081739 -vn -3.786479 2.547549 2.564205 -v 0.005860 -0.009805 0.081863 -vn -3.085642 -2.626230 3.306284 -v 0.005917 -0.009895 0.081930 -vn -3.245609 2.520330 3.171480 -v 0.005943 -0.009793 0.081957 -vn -2.365106 -2.611766 3.880921 -v 0.006128 -0.009870 0.082103 -vn -0.031552 -2.633339 4.584070 -v 0.006606 -0.009821 0.082249 -vn 0.395955 -2.702000 4.554145 -v 0.006650 -0.009816 0.082250 -vn -0.356399 2.694261 4.524592 -v 0.006650 -0.009718 0.082250 -vn -0.429129 -2.559675 4.552664 -v 0.006502 -0.009831 0.082239 -vn -1.154839 2.636147 4.429637 -v 0.006422 -0.009740 0.082224 -vn -1.646851 2.644018 4.247355 -v 0.006382 -0.009744 0.082213 -vn -4.523555 2.559062 -0.220222 -v 0.005650 -0.020668 0.081250 -vn -4.404371 2.630700 -1.155188 -v 0.005687 -0.020684 0.080982 -vn -4.501908 -2.643104 -0.698789 -v 0.005682 -0.021026 0.081006 -vn 0.219218 2.620039 -4.543316 -v 0.006650 -0.020762 0.080250 -vn -0.461450 2.664988 -4.555357 -v 0.006502 -0.020753 0.080261 -vn -1.128015 3.553574 -2.860187 -v 0.006320 -0.041410 0.080306 -vn -3.225414 2.858523 -2.235905 -v 0.005825 -0.021078 0.080684 -vn -4.892174 0.014240 -3.930512 -v 0.005864 -0.021082 0.080631 -vn -2.249691 3.633129 -2.054548 -v 0.005912 -0.041410 0.080575 -vn -4.398149 -2.620894 -1.314643 -v 0.005706 -0.021037 0.080925 -vn -4.207259 2.639912 -1.786074 -v 0.005704 -0.020688 0.080925 -vn -3.834029 2.604011 -2.423919 -v 0.005794 -0.020701 0.080733 -vn -3.573789 -2.847280 -1.861863 -v 0.005829 -0.021074 0.080680 -vn -3.432054 2.666815 -3.026788 -v 0.005890 -0.020710 0.080600 -vn -2.940061 2.615181 -3.464055 -v 0.005943 -0.020715 0.080543 -vn -2.077753 2.546941 -3.974977 -v 0.006159 -0.020731 0.080379 -vn -1.127909 2.617787 -4.399810 -v 0.006411 -0.020747 0.080279 -vn -4.388129 -2.605002 0.071641 -v 0.005652 -0.021001 0.081193 -vn -4.349447 -2.664376 1.079522 -v 0.005671 -0.020966 0.081456 -vn -4.446853 2.600675 0.796035 -v 0.005679 -0.020645 0.081489 -vn -4.256223 -2.661433 1.616665 -v 0.005680 -0.020961 0.081494 -vn -4.281597 2.637762 1.613919 -v 0.005748 -0.020626 0.081683 -vn -3.766789 -2.592276 2.420013 -v 0.005764 -0.020930 0.081712 -vn -0.683066 -2.594394 4.526231 -v 0.006376 -0.020823 0.082212 -vn 0.268748 -2.553373 4.504358 -v 0.006650 -0.020786 0.082250 -vn -0.330537 2.566858 4.502433 -v 0.006650 -0.020519 0.082250 -vn -1.271425 2.611497 4.351150 -v 0.006382 -0.020545 0.082213 -vn -1.974443 2.634014 4.124780 -v 0.006285 -0.020554 0.082181 -vn -1.313269 -2.618897 4.389411 -v 0.006319 -0.020831 0.082195 -vn -2.576447 2.604756 3.756727 -v 0.006133 -0.020570 0.082106 -vn -2.113741 -2.576988 3.960651 -v 0.006129 -0.020859 0.082105 -vn -3.161968 2.639014 3.319809 -v 0.005975 -0.020589 0.081988 -vn -3.047158 -2.547270 3.270265 -v 0.005924 -0.020894 0.081937 -vn -3.566855 2.615251 2.845201 -v 0.005943 -0.020593 0.081957 -vn -3.959293 2.587679 2.231194 -v 0.005779 -0.020619 0.081741 -vn -4.360341 2.713704 0.630529 -v 0.005673 -0.021030 0.081462 -vn -4.527111 2.671333 0.027137 -v 0.005650 -0.021041 0.081264 -vn -2.954368 3.631941 0.745115 -v 0.005680 -0.041410 0.081494 -vn -4.235570 2.787877 -0.575812 -v 0.005652 -0.021046 0.081192 -vn -2.954027 3.633078 -0.745758 -v 0.005680 -0.041410 0.081006 -vn -4.303549 2.700453 -1.158908 -v 0.005680 -0.021057 0.081006 -vn -4.132346 2.647690 -1.725604 -v 0.005704 -0.021062 0.080926 -vn -4.374792 2.646156 1.344269 -v 0.005700 -0.021023 0.081562 -vn -2.248387 3.633833 2.055828 -v 0.005912 -0.041410 0.081925 -vn -3.969556 2.613967 2.032945 -v 0.005765 -0.021014 0.081716 -vn -3.196134 2.616767 2.925359 -v 0.005923 -0.020998 0.081936 -vn -1.128744 3.555741 2.859581 -v 0.006320 -0.041410 0.082194 -vn -2.483182 2.522973 3.780942 -v 0.006133 -0.020982 0.082106 -vn -1.345616 2.529407 4.319367 -v 0.006382 -0.020965 0.082213 -vn -0.179772 2.547394 4.516856 -v 0.006650 -0.020949 0.082250 -vn 0.975436 2.547412 4.414299 -v 0.006889 -0.020935 0.082221 -vn 1.128602 3.555070 2.859711 -v 0.006980 -0.041410 0.082194 -vn 2.014453 2.573372 4.052137 -v 0.007141 -0.020919 0.082121 -vn 2.954706 3.630766 0.744576 -v 0.007620 -0.041410 0.081494 -vn 3.780960 2.556699 2.437557 -v 0.007506 -0.020888 0.081767 -vn 2.248309 3.632305 2.056268 -v 0.007388 -0.041410 0.081925 -vn 3.228258 2.628441 3.207010 -v 0.007357 -0.020902 0.081957 -vn 2.720067 2.652997 3.652550 -v 0.007294 -0.020908 0.082015 -vn 2.954718 3.630692 -0.744533 -v 0.007620 -0.041410 0.081006 -vn 4.511292 2.549615 0.181357 -v 0.007650 -0.020855 0.081250 -vn 4.304033 2.533392 1.354964 -v 0.007613 -0.020872 0.081519 -vn 1.128481 3.555283 -2.859740 -v 0.006980 -0.041410 0.080306 -vn 3.303162 2.552477 -3.058520 -v 0.007357 -0.020808 0.080543 -vn 2.248289 3.632238 -2.056314 -v 0.007388 -0.041410 0.080575 -vn 3.995760 2.537351 -2.080598 -v 0.007521 -0.020825 0.080759 -vn 4.406097 2.551462 -0.963934 -v 0.007621 -0.020841 0.081011 -vn 0.938855 2.650930 -4.474463 -v 0.006855 -0.020774 0.080271 -vn 1.587015 2.624321 -4.270710 -v 0.006918 -0.020778 0.080287 -vn 2.431208 2.556461 -3.778331 -v 0.007167 -0.020794 0.080394 -vn -4.520233 -2.600131 0.257920 -v 0.005650 -0.020168 0.081250 -vn -4.444092 2.616127 -1.047066 -v 0.005675 -0.020090 0.081028 -vn -4.511681 -2.660630 -0.590062 -v 0.005680 -0.020199 0.081007 -vn -4.229607 2.676931 -1.679704 -v 0.005687 -0.020094 0.080981 -vn -4.341778 -2.502740 -1.349319 -v 0.005704 -0.020210 0.080926 -vn -4.122442 -2.567534 -1.889649 -v 0.005784 -0.020236 0.080750 -vn -3.746319 2.604296 -2.490817 -v 0.005794 -0.020120 0.080733 -vn -3.752858 -2.581953 -2.607457 -v 0.005890 -0.020261 0.080600 -vn -3.068832 2.658829 -3.350104 -v 0.005943 -0.020143 0.080543 -vn -3.348096 -2.667005 -3.076895 -v 0.005943 -0.020271 0.080543 -vn -2.549797 2.515300 -3.784449 -v 0.006050 -0.020157 0.080450 -vn -2.481381 -2.610950 -3.790265 -v 0.006172 -0.020308 0.080372 -vn 0.104459 2.618034 -4.548643 -v 0.006650 -0.020219 0.080250 -vn -0.356756 -2.596727 -4.550603 -v 0.006650 -0.020374 0.080250 -vn -0.626948 2.668632 -4.543929 -v 0.006411 -0.020195 0.080279 -vn -0.902319 -2.476000 -4.476402 -v 0.006502 -0.020354 0.080261 -vn -1.623855 -2.650457 -4.277878 -v 0.006389 -0.020339 0.080285 -vn -1.964081 2.635385 -4.101191 -v 0.006159 -0.020169 0.080379 -vn -1.386920 2.615893 -4.338493 -v 0.006320 -0.020186 0.080306 -vn -1.010034 2.715927 -4.502963 -v 0.006389 -0.020193 0.080285 -vn -4.042433 2.630139 2.007522 -v 0.005779 -0.020019 0.081741 -vn -4.447210 2.627901 0.985928 -v 0.005679 -0.020045 0.081489 -vn -4.296837 -2.567396 1.475186 -v 0.005687 -0.020142 0.081518 -vn -4.555024 2.475315 0.392167 -v 0.005662 -0.020054 0.081403 -vn -4.528195 2.603222 -0.333159 -v 0.005650 -0.020068 0.081250 -vn -4.081538 -2.473229 2.040502 -v 0.005748 -0.020125 0.081683 -vn -3.662122 -2.578932 2.723393 -v 0.005794 -0.020116 0.081767 -vn -3.401080 2.614695 2.971992 -v 0.005943 -0.019993 0.081957 -vn -1.962193 -2.636425 4.075511 -v 0.006159 -0.020066 0.082121 -vn -2.725539 2.617769 3.661594 -v 0.006133 -0.019970 0.082106 -vn -2.743593 -2.593467 3.664366 -v 0.005975 -0.020088 0.081988 -vn -3.204564 -2.641083 3.255168 -v 0.005943 -0.020092 0.081957 -vn 0.255224 -2.638458 4.542753 -v 0.006650 -0.020017 0.082250 -vn -0.265670 2.643668 4.570675 -v 0.006650 -0.019918 0.082250 -vn -0.487914 -2.553573 4.550657 -v 0.006481 -0.020033 0.082236 -vn -0.678529 2.531170 4.509315 -v 0.006555 -0.019927 0.082246 -vn -0.985298 -2.609654 4.448660 -v 0.006411 -0.020040 0.082221 -vn -1.540726 2.560157 4.285346 -v 0.006382 -0.019944 0.082213 -vn -2.121660 2.548631 4.044865 -v 0.006195 -0.019963 0.082140 -vn -4.316517 2.462850 1.457260 -v 0.005708 -0.019435 0.081586 -vn -4.500870 2.664171 0.705046 -v 0.005679 -0.019445 0.081489 -vn -4.246085 -2.668614 1.596072 -v 0.005687 -0.019541 0.081519 -vn 0.129571 2.613061 -4.535257 -v 0.006650 -0.019618 0.080250 -vn -0.331961 -2.622350 -4.484517 -v 0.006650 -0.019717 0.080250 -vn -0.833095 2.555511 -4.417506 -v 0.006411 -0.019595 0.080279 -vn -1.456424 -2.554494 -4.249193 -v 0.006382 -0.019691 0.080287 -vn -1.800681 2.592078 -4.162922 -v 0.006159 -0.019569 0.080379 -vn -2.435365 -2.661877 -3.840020 -v 0.006133 -0.019665 0.080394 -vn -2.449475 2.687280 -3.853465 -v 0.006084 -0.019560 0.080426 -vn -2.990239 -2.637478 -3.468003 -v 0.006050 -0.019656 0.080450 -vn -2.932754 2.686726 -3.514125 -v 0.005943 -0.019543 0.080543 -vn -3.348920 -2.691549 -3.112638 -v 0.005943 -0.019642 0.080543 -vn -3.319931 2.662868 -3.168220 -v 0.005915 -0.019539 0.080572 -vn -3.611379 -2.672045 -2.782497 -v 0.005912 -0.019638 0.080575 -vn -3.741008 2.657667 -2.597307 -v 0.005794 -0.019520 0.080733 -vn -3.834432 -2.560319 -2.473619 -v 0.005825 -0.019625 0.080685 -vn -4.143785 -2.658064 -1.846023 -v 0.005779 -0.019616 0.080759 -vn -4.137284 2.470066 -1.932158 -v 0.005718 -0.019503 0.080887 -vn -4.431804 -2.581514 -0.794030 -v 0.005679 -0.019590 0.081011 -vn -4.355403 2.618145 -1.336360 -v 0.005687 -0.019494 0.080981 -vn -4.503786 2.560259 -0.253042 -v 0.005650 -0.019468 0.081250 -vn -4.524678 -2.559897 0.204397 -v 0.005650 -0.019567 0.081250 -vn -4.469151 -2.413069 0.783257 -v 0.005662 -0.019553 0.081403 -vn -4.104300 2.556792 1.969157 -v 0.005779 -0.019419 0.081741 -vn -3.746094 -2.600687 2.512461 -v 0.005794 -0.019516 0.081767 -vn -3.711305 2.551201 2.682767 -v 0.005891 -0.019400 0.081902 -vn -2.947985 -2.606885 3.428384 -v 0.005943 -0.019492 0.081957 -vn -3.260046 2.609186 3.197353 -v 0.005943 -0.019393 0.081957 -vn -2.214622 -2.652726 3.989594 -v 0.006159 -0.019467 0.082121 -vn -2.600377 2.548400 3.698204 -v 0.006133 -0.019370 0.082106 -vn -1.671291 -2.526761 4.256669 -v 0.006195 -0.019463 0.082140 -vn -1.452884 2.575692 4.265224 -v 0.006382 -0.019344 0.082213 -vn -0.845790 -2.545656 4.477224 -v 0.006411 -0.019441 0.082221 -vn -0.404422 2.670954 4.530130 -v 0.006650 -0.019318 0.082250 -vn -0.346356 -2.383419 4.546389 -v 0.006555 -0.019427 0.082245 -vn 0.396656 -2.661686 4.541669 -v 0.006650 -0.019418 0.082250 -vn -1.059119 -2.404453 -4.397248 -v 0.006408 -0.019095 0.080281 -vn -1.900159 -2.710446 -4.129663 -v 0.006320 -0.019086 0.080307 -vn -1.044496 2.617823 -4.417853 -v 0.006336 -0.018988 0.080301 -vn -0.396551 -2.641057 -4.518009 -v 0.006650 -0.019118 0.080250 -vn -0.355164 2.413248 -4.519723 -v 0.006588 -0.019012 0.080252 -vn 0.441360 2.668283 -4.548625 -v 0.006650 -0.019018 0.080250 -vn -4.234531 -2.692139 -1.562518 -v 0.005719 -0.019003 0.080887 -vn -3.829433 2.343940 -2.450838 -v 0.005752 -0.018912 0.080810 -vn -3.437187 -2.566792 -2.765563 -v 0.005915 -0.019039 0.080572 -vn -3.240162 2.514949 -3.120960 -v 0.005902 -0.018938 0.080586 -vn -2.711266 -2.587657 -3.538187 -v 0.006084 -0.019060 0.080426 -vn -2.362562 2.534616 -3.863216 -v 0.006088 -0.018962 0.080423 -vn -1.860028 2.301353 -4.131722 -v 0.006227 -0.018977 0.080344 -vn -4.491216 -2.676741 -0.789728 -v 0.005681 -0.018991 0.081006 -vn -4.513494 -2.634002 0.259295 -v 0.005650 -0.018968 0.081250 -vn -4.554799 2.578442 -0.541082 -v 0.005651 -0.018872 0.081210 -vn -4.466038 2.493403 -0.921469 -v 0.005666 -0.018886 0.081072 -vn -4.335005 2.658506 -1.433508 -v 0.005680 -0.018892 0.081006 -vn -4.145107 2.634892 -1.967350 -v 0.005733 -0.018907 0.080852 -vn -3.535364 2.624974 2.872998 -v 0.005912 -0.018798 0.081925 -vn -3.900420 2.474320 2.385770 -v 0.005815 -0.018813 0.081801 -vn -3.222502 -2.646410 3.103367 -v 0.005892 -0.018900 0.081901 -vn -4.039668 2.250361 2.045285 -v 0.005804 -0.018815 0.081783 -vn -4.081875 -2.638469 1.978732 -v 0.005709 -0.018935 0.081586 -vn -4.350919 2.641890 1.313828 -v 0.005698 -0.018838 0.081557 -vn -4.388515 -2.658382 1.206433 -v 0.005681 -0.018944 0.081494 -vn -4.495337 2.617513 0.705741 -v 0.005680 -0.018844 0.081494 -vn -4.532850 2.482493 0.230558 -v 0.005652 -0.018862 0.081315 -vn 0.183627 -2.667647 4.582154 -v 0.006650 -0.018818 0.082250 -vn -0.396431 2.669362 4.558712 -v 0.006650 -0.018719 0.082250 -vn -0.401253 -2.585636 4.550479 -v 0.006514 -0.018831 0.082240 -vn -1.168375 2.572809 4.410239 -v 0.006430 -0.018740 0.082225 -vn -1.256554 -2.668548 4.390258 -v 0.006320 -0.018850 0.082193 -vn -1.644678 2.606291 4.266170 -v 0.006352 -0.018747 0.082204 -vn -2.287449 2.600912 3.946018 -v 0.006195 -0.018763 0.082141 -vn -2.046090 -2.662702 4.042318 -v 0.006173 -0.018865 0.082128 -vn -2.910177 2.253782 3.497860 -v 0.006050 -0.018780 0.082050 -vn -3.116526 2.254926 3.306520 -v 0.005995 -0.018787 0.082006 -vn -1.929201 2.653744 -4.127010 -v 0.006159 -0.018370 0.080379 -vn -1.216433 2.640684 -4.412575 -v 0.006380 -0.018393 0.080287 -vn -1.514944 -2.619436 -4.287654 -v 0.006382 -0.018492 0.080287 -vn -0.644622 2.658611 -4.527454 -v 0.006411 -0.018396 0.080279 -vn -0.754124 -2.543682 -4.498553 -v 0.006556 -0.018509 0.080254 -vn 0.317939 2.621022 -4.508579 -v 0.006650 -0.018419 0.080250 -vn -0.097670 -2.624805 -4.545091 -v 0.006650 -0.018518 0.080250 -vn -1.990562 -2.449208 -4.084594 -v 0.006227 -0.018476 0.080344 -vn -2.666971 -2.658003 -3.704272 -v 0.006133 -0.018466 0.080394 -vn -2.590766 2.524034 -3.770746 -v 0.006040 -0.018356 0.080458 -vn -3.301103 -2.693733 -3.159496 -v 0.005943 -0.018443 0.080543 -vn -3.101948 2.656295 -3.345164 -v 0.005943 -0.018344 0.080543 -vn -3.659762 -2.595456 -2.739455 -v 0.005912 -0.018438 0.080575 -vn -3.714298 2.611433 -2.551903 -v 0.005794 -0.018320 0.080733 -vn -4.050061 -2.629329 -2.087698 -v 0.005779 -0.018417 0.080759 -vn -4.282192 -2.474962 -1.549001 -v 0.005733 -0.018407 0.080852 -vn -4.224539 2.641254 -1.406929 -v 0.005687 -0.018294 0.080982 -vn -4.471436 -2.572040 -0.718404 -v 0.005679 -0.018391 0.081011 -vn -4.454156 2.584460 -0.275430 -v 0.005650 -0.018268 0.081250 -vn -4.497736 -2.561363 0.248914 -v 0.005650 -0.018367 0.081250 -vn -4.458117 2.562826 0.744713 -v 0.005679 -0.018245 0.081489 -vn -4.269999 -2.589939 1.450939 -v 0.005687 -0.018341 0.081519 -vn -4.268390 2.493218 1.624265 -v 0.005748 -0.018226 0.081683 -vn -3.705465 -2.573313 2.592443 -v 0.005794 -0.018315 0.081767 -vn -4.002540 2.647338 2.170153 -v 0.005779 -0.018219 0.081741 -vn -3.554646 2.641697 2.862596 -v 0.005943 -0.018194 0.081957 -vn -3.132467 -2.620554 3.302708 -v 0.005943 -0.018292 0.081957 -vn -3.188785 2.671254 3.299644 -v 0.005975 -0.018189 0.081988 -vn -2.548401 -2.594398 3.806704 -v 0.006050 -0.018279 0.082050 -vn -2.541393 2.623918 3.778077 -v 0.006133 -0.018170 0.082106 -vn -1.898627 -2.571137 4.150214 -v 0.006159 -0.018266 0.082121 -vn -1.271013 -2.676547 4.399623 -v 0.006351 -0.018246 0.082204 -vn 0.053538 -2.637138 4.555815 -v 0.006650 -0.018217 0.082250 -vn -0.359003 2.627631 4.508000 -v 0.006650 -0.018119 0.082250 -vn -0.624011 -2.589167 4.522228 -v 0.006411 -0.018240 0.082221 -vn -1.306853 2.671317 4.346807 -v 0.006382 -0.018145 0.082213 -vn -2.025502 2.476114 4.091662 -v 0.006285 -0.018154 0.082181 -vn -4.496436 -2.614513 0.222664 -v 0.005650 -0.017767 0.081250 -vn -4.444263 2.624193 -1.048328 -v 0.005675 -0.017690 0.081028 -vn -4.418667 -2.629785 -0.836578 -v 0.005679 -0.017790 0.081011 -vn -4.216968 2.597009 -1.709771 -v 0.005687 -0.017694 0.080981 -vn -4.058342 -2.544721 -1.962376 -v 0.005779 -0.017816 0.080759 -vn -3.712712 2.553469 -2.539035 -v 0.005794 -0.017720 0.080733 -vn -3.479462 -2.602687 -2.933090 -v 0.005943 -0.017842 0.080543 -vn -3.106087 2.609193 -3.306060 -v 0.005943 -0.017743 0.080543 -vn -3.020155 -2.655415 -3.458196 -v 0.006040 -0.017855 0.080458 -vn -2.553459 2.667298 -3.791502 -v 0.006050 -0.017757 0.080450 -vn -2.451675 -2.632740 -3.846359 -v 0.006133 -0.017865 0.080394 -vn -1.853977 2.578950 -4.142217 -v 0.006159 -0.017769 0.080379 -vn -1.448872 -2.593259 -4.256564 -v 0.006382 -0.017891 0.080287 -vn 0.104503 2.618054 -4.548593 -v 0.006650 -0.017819 0.080250 -vn -0.315999 -2.642016 -4.461469 -v 0.006650 -0.017917 0.080250 -vn -0.597087 2.591754 -4.547111 -v 0.006411 -0.017795 0.080279 -vn -1.189666 2.664380 -4.407887 -v 0.006389 -0.017793 0.080285 -vn -4.042436 2.630213 2.007534 -v 0.005779 -0.017619 0.081741 -vn -4.447253 2.627949 0.985936 -v 0.005679 -0.017645 0.081489 -vn -4.296838 -2.567292 1.475185 -v 0.005687 -0.017742 0.081518 -vn -4.554949 2.475233 0.392211 -v 0.005662 -0.017654 0.081403 -vn -4.528227 2.603439 -0.333217 -v 0.005650 -0.017668 0.081250 -vn -4.081487 -2.473188 2.040478 -v 0.005748 -0.017725 0.081683 -vn -3.662090 -2.578961 2.723343 -v 0.005794 -0.017715 0.081767 -vn -3.401143 2.614768 2.971953 -v 0.005943 -0.017593 0.081957 -vn -1.962151 -2.636551 4.075333 -v 0.006159 -0.017666 0.082121 -vn -2.725461 2.617793 3.661631 -v 0.006133 -0.017570 0.082106 -vn -2.743564 -2.593386 3.664064 -v 0.005975 -0.017688 0.081988 -vn -3.204700 -2.641166 3.254931 -v 0.005943 -0.017692 0.081957 -vn 0.255326 -2.638692 4.542395 -v 0.006650 -0.017617 0.082250 -vn -0.265624 2.643723 4.570668 -v 0.006650 -0.017518 0.082250 -vn -0.488017 -2.553472 4.550295 -v 0.006481 -0.017633 0.082236 -vn -0.678620 2.531494 4.509333 -v 0.006555 -0.017527 0.082246 -vn -0.985324 -2.609843 4.448352 -v 0.006411 -0.017640 0.082221 -vn -1.540728 2.560119 4.285331 -v 0.006382 -0.017544 0.082213 -vn -2.121627 2.548652 4.044917 -v 0.006195 -0.017563 0.082140 -vn -4.316436 2.462745 1.457240 -v 0.005708 -0.017035 0.081586 -vn -4.500919 2.664151 0.704957 -v 0.005679 -0.017045 0.081489 -vn -4.245819 -2.668777 1.595990 -v 0.005687 -0.017141 0.081519 -vn 0.129559 2.613046 -4.535288 -v 0.006650 -0.017218 0.080250 -vn -0.331968 -2.622486 -4.484232 -v 0.006650 -0.017317 0.080250 -vn -0.833087 2.555526 -4.417474 -v 0.006411 -0.017195 0.080279 -vn -1.456362 -2.554634 -4.248912 -v 0.006382 -0.017291 0.080287 -vn -1.800667 2.592086 -4.162945 -v 0.006159 -0.017169 0.080379 -vn -2.435274 -2.662026 -3.839723 -v 0.006133 -0.017265 0.080394 -vn -2.449466 2.687151 -3.853440 -v 0.006084 -0.017160 0.080426 -vn -2.990240 -2.637756 -3.467638 -v 0.006050 -0.017256 0.080450 -vn -2.932767 2.686728 -3.514127 -v 0.005943 -0.017143 0.080543 -vn -3.348758 -2.691701 -3.112398 -v 0.005943 -0.017242 0.080543 -vn -3.319945 2.662859 -3.168231 -v 0.005915 -0.017139 0.080572 -vn -3.611192 -2.672199 -2.782208 -v 0.005912 -0.017238 0.080575 -vn -3.741005 2.657628 -2.597322 -v 0.005794 -0.017120 0.080733 -vn -3.834387 -2.560741 -2.473362 -v 0.005825 -0.017225 0.080685 -vn -4.143470 -2.658219 -1.845922 -v 0.005779 -0.017216 0.080759 -vn -4.137276 2.470070 -1.932153 -v 0.005718 -0.017103 0.080887 -vn -4.431527 -2.581654 -0.793951 -v 0.005679 -0.017190 0.081011 -vn -4.355392 2.618152 -1.336357 -v 0.005687 -0.017094 0.080981 -vn -4.503775 2.560264 -0.253045 -v 0.005650 -0.017068 0.081250 -vn -4.524380 -2.560039 0.204456 -v 0.005650 -0.017167 0.081250 -vn -4.468870 -2.413560 0.783458 -v 0.005662 -0.017153 0.081403 -vn -4.104283 2.556777 1.969229 -v 0.005779 -0.017019 0.081741 -vn -3.745855 -2.600796 2.512351 -v 0.005794 -0.017116 0.081767 -vn -3.711370 2.551283 2.682761 -v 0.005891 -0.017000 0.081902 -vn -2.947808 -2.606987 3.428186 -v 0.005943 -0.017092 0.081957 -vn -3.260091 2.609155 3.197282 -v 0.005943 -0.016993 0.081957 -vn -2.214518 -2.652864 3.989370 -v 0.006159 -0.017067 0.082121 -vn -2.600425 2.548413 3.698192 -v 0.006133 -0.016970 0.082106 -vn -1.671101 -2.526799 4.256402 -v 0.006195 -0.017063 0.082140 -vn -1.452851 2.575743 4.265209 -v 0.006382 -0.016944 0.082213 -vn -0.845587 -2.545784 4.477027 -v 0.006411 -0.017041 0.082221 -vn -0.404422 2.670928 4.530138 -v 0.006650 -0.016918 0.082250 -vn -0.346178 -2.383934 4.546270 -v 0.006555 -0.017027 0.082245 -vn 0.396557 -2.661814 4.541380 -v 0.006650 -0.017018 0.082250 -vn -1.059272 -2.404896 -4.397089 -v 0.006408 -0.016695 0.080281 -vn -1.900082 -2.710534 -4.129472 -v 0.006320 -0.016686 0.080307 -vn -1.044450 2.617783 -4.417866 -v 0.006336 -0.016588 0.080301 -vn -0.396639 -2.641198 -4.517795 -v 0.006650 -0.016718 0.080250 -vn -0.355164 2.413257 -4.519706 -v 0.006588 -0.016612 0.080252 -vn 0.448698 2.673000 -4.537417 -v 0.006650 -0.016618 0.080250 -vn -4.234427 -2.692243 -1.562322 -v 0.005719 -0.016603 0.080887 -vn -3.806884 2.351466 -2.454470 -v 0.005752 -0.016512 0.080810 -vn -3.437266 -2.567002 -2.765233 -v 0.005915 -0.016639 0.080572 -vn -3.245486 2.520060 -3.104478 -v 0.005902 -0.016538 0.080586 -vn -2.711302 -2.587691 -3.537884 -v 0.006084 -0.016660 0.080426 -vn -2.362424 2.531332 -3.870393 -v 0.006088 -0.016562 0.080423 -vn -1.860032 2.301327 -4.131750 -v 0.006227 -0.016577 0.080344 -vn -4.491034 -2.676851 -0.789635 -v 0.005681 -0.016591 0.081006 -vn -4.513310 -2.634106 0.259447 -v 0.005650 -0.016568 0.081250 -vn -4.554797 2.578369 -0.541096 -v 0.005651 -0.016472 0.081210 -vn -4.466038 2.493402 -0.921469 -v 0.005666 -0.016486 0.081072 -vn -4.335008 2.658514 -1.433501 -v 0.005680 -0.016492 0.081006 -vn -4.145098 2.634846 -1.967376 -v 0.005733 -0.016507 0.080852 -vn -3.535414 2.625105 2.872968 -v 0.005912 -0.016398 0.081925 -vn -3.900426 2.474237 2.385767 -v 0.005815 -0.016413 0.081801 -vn -3.222261 -2.646427 3.103368 -v 0.005892 -0.016500 0.081901 -vn -4.039648 2.250384 2.045344 -v 0.005804 -0.016415 0.081783 -vn -4.081642 -2.638443 1.978731 -v 0.005709 -0.016535 0.081586 -vn -4.350970 2.641933 1.313865 -v 0.005698 -0.016438 0.081557 -vn -4.388330 -2.658493 1.206442 -v 0.005681 -0.016544 0.081494 -vn -4.495264 2.617568 0.705791 -v 0.005680 -0.016444 0.081494 -vn -4.532891 2.482631 0.230493 -v 0.005652 -0.016462 0.081315 -vn 0.183679 -2.667744 4.582053 -v 0.006650 -0.016418 0.082250 -vn -0.396410 2.669384 4.558721 -v 0.006650 -0.016319 0.082250 -vn -0.401085 -2.585654 4.550264 -v 0.006514 -0.016431 0.082240 -vn -1.168416 2.572799 4.410217 -v 0.006430 -0.016340 0.082225 -vn -1.256421 -2.668610 4.390127 -v 0.006320 -0.016450 0.082193 -vn -1.644701 2.606347 4.266173 -v 0.006352 -0.016347 0.082204 -vn -2.287438 2.601014 3.946025 -v 0.006195 -0.016363 0.082141 -vn -2.045826 -2.662671 4.042253 -v 0.006173 -0.016465 0.082128 -vn -2.910148 2.253831 3.497899 -v 0.006050 -0.016380 0.082050 -vn -3.116582 2.255196 3.306539 -v 0.005995 -0.016387 0.082006 -vn -1.929187 2.653725 -4.127016 -v 0.006159 -0.015970 0.080379 -vn -1.216443 2.640678 -4.412581 -v 0.006380 -0.015993 0.080287 -vn -1.515014 -2.619496 -4.287524 -v 0.006382 -0.016092 0.080287 -vn -0.644647 2.658632 -4.527466 -v 0.006411 -0.015996 0.080279 -vn -0.754119 -2.543678 -4.498386 -v 0.006556 -0.016109 0.080254 -vn 0.317958 2.621027 -4.508596 -v 0.006650 -0.016019 0.080250 -vn -0.097620 -2.624865 -4.545005 -v 0.006650 -0.016118 0.080250 -vn -1.991991 -2.452080 -4.077405 -v 0.006227 -0.016076 0.080344 -vn -2.663910 -2.670098 -3.674042 -v 0.006133 -0.016066 0.080394 -vn -2.590766 2.524034 -3.770746 -v 0.006040 -0.015956 0.080458 -vn -3.279453 -2.700863 -3.165565 -v 0.005943 -0.016043 0.080543 -vn -3.101948 2.656294 -3.345164 -v 0.005943 -0.015944 0.080543 -vn -3.667793 -2.591484 -2.740532 -v 0.005912 -0.016038 0.080575 -vn -3.714295 2.611436 -2.551906 -v 0.005794 -0.015920 0.080733 -vn -4.049983 -2.629380 -2.087626 -v 0.005779 -0.016017 0.080759 -vn -4.282118 -2.474955 -1.548920 -v 0.005733 -0.016007 0.080852 -vn -4.224538 2.641282 -1.406912 -v 0.005687 -0.015894 0.080982 -vn -4.471352 -2.572100 -0.718350 -v 0.005679 -0.015991 0.081011 -vn -4.454151 2.584463 -0.275431 -v 0.005650 -0.015868 0.081250 -vn -4.497644 -2.561407 0.248917 -v 0.005650 -0.015967 0.081250 -vn -4.458134 2.562817 0.744693 -v 0.005679 -0.015845 0.081489 -vn -4.269912 -2.589984 1.450917 -v 0.005687 -0.015941 0.081519 -vn -4.268315 2.493262 1.624280 -v 0.005748 -0.015826 0.081683 -vn -3.705390 -2.573355 2.592401 -v 0.005794 -0.015915 0.081767 -vn -4.002542 2.647322 2.170245 -v 0.005779 -0.015819 0.081741 -vn -3.554643 2.641699 2.862593 -v 0.005943 -0.015794 0.081957 -vn -3.132399 -2.620591 3.302659 -v 0.005943 -0.015892 0.081957 -vn -3.188797 2.671232 3.299642 -v 0.005975 -0.015789 0.081988 -vn -2.548303 -2.594481 3.806647 -v 0.006050 -0.015879 0.082050 -vn -2.541369 2.623936 3.778034 -v 0.006133 -0.015770 0.082106 -vn -1.898594 -2.571172 4.150154 -v 0.006159 -0.015866 0.082121 -vn -1.270845 -2.676551 4.399541 -v 0.006351 -0.015846 0.082204 -vn 0.053506 -2.637163 4.555791 -v 0.006650 -0.015817 0.082250 -vn -0.359020 2.627647 4.507998 -v 0.006650 -0.015719 0.082250 -vn -0.623876 -2.589204 4.522213 -v 0.006411 -0.015840 0.082221 -vn -1.306843 2.671342 4.346807 -v 0.006382 -0.015745 0.082213 -vn -2.025496 2.476074 4.091676 -v 0.006285 -0.015754 0.082181 -vn -4.496436 -2.614513 0.222664 -v 0.005650 -0.015367 0.081250 -vn -4.444281 2.624183 -1.048345 -v 0.005675 -0.015290 0.081028 -vn -4.418659 -2.629789 -0.836580 -v 0.005679 -0.015390 0.081011 -vn -4.216975 2.597004 -1.709779 -v 0.005687 -0.015294 0.080981 -vn -4.058334 -2.544724 -1.962368 -v 0.005779 -0.015416 0.080759 -vn -3.712712 2.553469 -2.539035 -v 0.005794 -0.015320 0.080733 -vn -3.479498 -2.602703 -2.933060 -v 0.005943 -0.015442 0.080543 -vn -3.106098 2.609209 -3.306051 -v 0.005943 -0.015343 0.080543 -vn -3.020106 -2.655345 -3.458177 -v 0.006040 -0.015455 0.080458 -vn -2.553441 2.667352 -3.791519 -v 0.006050 -0.015357 0.080450 -vn -2.451646 -2.632756 -3.846359 -v 0.006133 -0.015465 0.080394 -vn -1.853977 2.578950 -4.142217 -v 0.006159 -0.015369 0.080379 -vn -1.448849 -2.593274 -4.256538 -v 0.006382 -0.015491 0.080287 -vn 0.104457 2.618046 -4.548619 -v 0.006650 -0.015419 0.080250 -vn -0.316004 -2.642009 -4.461486 -v 0.006650 -0.015517 0.080250 -vn -0.597086 2.591754 -4.547111 -v 0.006411 -0.015395 0.080279 -vn -1.189666 2.664380 -4.407887 -v 0.006389 -0.015393 0.080285 -vn -4.042448 2.630210 2.007526 -v 0.005779 -0.015219 0.081741 -vn -4.447253 2.627949 0.985936 -v 0.005679 -0.015245 0.081489 -vn -4.296838 -2.567292 1.475185 -v 0.005687 -0.015342 0.081518 -vn -4.554964 2.475226 0.392246 -v 0.005662 -0.015254 0.081403 -vn -4.528185 2.603459 -0.333210 -v 0.005650 -0.015268 0.081250 -vn -4.081476 -2.473193 2.040478 -v 0.005748 -0.015325 0.081683 -vn -3.662086 -2.578967 2.723334 -v 0.005794 -0.015315 0.081767 -vn -3.401115 2.614784 2.971925 -v 0.005943 -0.015193 0.081957 -vn -1.962150 -2.636550 4.075333 -v 0.006159 -0.015266 0.082121 -vn -2.725531 2.617763 3.661650 -v 0.006133 -0.015170 0.082106 -vn -2.743564 -2.593389 3.664064 -v 0.005975 -0.015288 0.081988 -vn -3.204700 -2.641166 3.254931 -v 0.005943 -0.015292 0.081957 -vn 0.255326 -2.638692 4.542395 -v 0.006650 -0.015217 0.082250 -vn -0.265587 2.643746 4.570629 -v 0.006650 -0.015118 0.082250 -vn -0.488014 -2.553476 4.550296 -v 0.006481 -0.015233 0.082236 -vn -0.678648 2.531514 4.509295 -v 0.006555 -0.015127 0.082246 -vn -0.985325 -2.609844 4.448351 -v 0.006411 -0.015240 0.082221 -vn -1.540735 2.560107 4.285357 -v 0.006382 -0.015144 0.082213 -vn -2.121647 2.548684 4.044839 -v 0.006195 -0.015163 0.082140 -vn -4.316434 2.462737 1.457242 -v 0.005708 -0.014635 0.081586 -vn -4.500919 2.664151 0.704957 -v 0.005679 -0.014645 0.081489 -vn -4.245857 -2.668756 1.596022 -v 0.005687 -0.014741 0.081519 -vn 0.129559 2.613046 -4.535288 -v 0.006650 -0.014818 0.080250 -vn -0.331968 -2.622486 -4.484232 -v 0.006650 -0.014917 0.080250 -vn -0.833087 2.555526 -4.417474 -v 0.006411 -0.014795 0.080279 -vn -1.456362 -2.554634 -4.248912 -v 0.006382 -0.014891 0.080287 -vn -1.800667 2.592086 -4.162945 -v 0.006159 -0.014769 0.080379 -vn -2.435274 -2.662026 -3.839723 -v 0.006133 -0.014865 0.080394 -vn -2.449466 2.687151 -3.853440 -v 0.006084 -0.014761 0.080426 -vn -2.990240 -2.637756 -3.467638 -v 0.006050 -0.014856 0.080450 -vn -2.932767 2.686728 -3.514127 -v 0.005943 -0.014743 0.080543 -vn -3.348758 -2.691701 -3.112398 -v 0.005943 -0.014842 0.080543 -vn -3.319945 2.662859 -3.168231 -v 0.005915 -0.014739 0.080572 -vn -3.611192 -2.672199 -2.782208 -v 0.005912 -0.014838 0.080575 -vn -3.741005 2.657628 -2.597322 -v 0.005794 -0.014720 0.080733 -vn -3.834387 -2.560741 -2.473362 -v 0.005825 -0.014825 0.080685 -vn -4.143466 -2.658222 -1.845914 -v 0.005779 -0.014816 0.080759 -vn -4.137276 2.470070 -1.932153 -v 0.005718 -0.014703 0.080887 -vn -4.431519 -2.581659 -0.793954 -v 0.005679 -0.014790 0.081011 -vn -4.355396 2.618148 -1.336363 -v 0.005687 -0.014694 0.080981 -vn -4.503785 2.560260 -0.253040 -v 0.005650 -0.014668 0.081250 -vn -4.524380 -2.560039 0.204456 -v 0.005650 -0.014767 0.081250 -vn -4.468839 -2.413568 0.783495 -v 0.005662 -0.014753 0.081403 -vn -4.104283 2.556777 1.969228 -v 0.005779 -0.014619 0.081741 -vn -3.745832 -2.600806 2.512343 -v 0.005794 -0.014716 0.081767 -vn -3.711428 2.551259 2.682738 -v 0.005891 -0.014600 0.081902 -vn -2.947832 -2.606973 3.428211 -v 0.005943 -0.014692 0.081957 -vn -3.260099 2.609179 3.197188 -v 0.005943 -0.014593 0.081957 -vn -2.214516 -2.652873 3.989350 -v 0.006159 -0.014667 0.082121 -vn -2.600398 2.548427 3.698181 -v 0.006133 -0.014570 0.082106 -vn -1.671093 -2.526813 4.256388 -v 0.006195 -0.014663 0.082140 -vn -1.452838 2.575740 4.265224 -v 0.006382 -0.014544 0.082213 -vn -0.845590 -2.545788 4.477020 -v 0.006411 -0.014641 0.082221 -vn -0.404473 2.670907 4.530169 -v 0.006650 -0.014518 0.082250 -vn -0.346178 -2.383934 4.546270 -v 0.006555 -0.014627 0.082245 -vn 0.396558 -2.661813 4.541379 -v 0.006650 -0.014618 0.082250 -vn -1.059272 -2.404896 -4.397089 -v 0.006408 -0.014295 0.080281 -vn -1.900095 -2.710535 -4.129459 -v 0.006320 -0.014286 0.080307 -vn -1.044430 2.617767 -4.417902 -v 0.006336 -0.014188 0.080301 -vn -0.396639 -2.641198 -4.517795 -v 0.006650 -0.014318 0.080250 -vn -0.355166 2.413249 -4.519722 -v 0.006588 -0.014212 0.080252 -vn 0.448703 2.672995 -4.537426 -v 0.006650 -0.014218 0.080250 -vn -4.234427 -2.692243 -1.562322 -v 0.005719 -0.014203 0.080887 -vn -3.806894 2.351462 -2.454468 -v 0.005752 -0.014112 0.080810 -vn -3.437241 -2.567012 -2.765237 -v 0.005915 -0.014239 0.080572 -vn -3.245487 2.520057 -3.104486 -v 0.005902 -0.014138 0.080586 -vn -2.711321 -2.587676 -3.537914 -v 0.006084 -0.014260 0.080426 -vn -2.362457 2.531327 -3.870389 -v 0.006088 -0.014162 0.080423 -vn -1.859982 2.301379 -4.131712 -v 0.006227 -0.014177 0.080344 -vn -4.491034 -2.676851 -0.789635 -v 0.005681 -0.014191 0.081006 -vn -4.513308 -2.634107 0.259447 -v 0.005650 -0.014168 0.081250 -vn -4.554827 2.578351 -0.541133 -v 0.005651 -0.014072 0.081210 -vn -4.466045 2.493398 -0.921475 -v 0.005666 -0.014086 0.081072 -vn -4.335008 2.658514 -1.433501 -v 0.005680 -0.014092 0.081006 -vn -4.145098 2.634846 -1.967376 -v 0.005733 -0.014107 0.080852 -vn -3.535414 2.625105 2.872968 -v 0.005912 -0.013998 0.081925 -vn -3.900426 2.474237 2.385767 -v 0.005815 -0.014013 0.081801 -vn -3.222261 -2.646427 3.103368 -v 0.005892 -0.014100 0.081901 -vn -4.039648 2.250384 2.045344 -v 0.005804 -0.014015 0.081783 -vn -4.081642 -2.638443 1.978731 -v 0.005709 -0.014135 0.081586 -vn -4.350970 2.641933 1.313865 -v 0.005698 -0.014038 0.081557 -vn -4.388330 -2.658493 1.206442 -v 0.005681 -0.014144 0.081494 -vn -4.495271 2.617564 0.705816 -v 0.005680 -0.014044 0.081494 -vn -4.532834 2.482671 0.230457 -v 0.005652 -0.014062 0.081315 -vn 0.183650 -2.667754 4.582036 -v 0.006650 -0.014018 0.082250 -vn -0.396408 2.669384 4.558722 -v 0.006650 -0.013919 0.082250 -vn -0.401108 -2.585628 4.550311 -v 0.006514 -0.014031 0.082240 -vn -1.168417 2.572796 4.410218 -v 0.006430 -0.013940 0.082225 -vn -1.256392 -2.668615 4.390120 -v 0.006320 -0.014050 0.082193 -vn -1.644701 2.606347 4.266173 -v 0.006352 -0.013947 0.082204 -vn -2.287438 2.601013 3.946029 -v 0.006195 -0.013963 0.082141 -vn -2.045826 -2.662671 4.042253 -v 0.006173 -0.014065 0.082128 -vn -2.910151 2.253830 3.497900 -v 0.006050 -0.013980 0.082050 -vn -3.116582 2.255196 3.306539 -v 0.005995 -0.013987 0.082006 -vn -1.898615 -2.571182 4.150125 -v 0.006159 -0.013466 0.082121 -vn -1.317302 -2.585377 4.378930 -v 0.006351 -0.013446 0.082204 -vn -2.649427 2.607614 3.703261 -v 0.006133 -0.013370 0.082106 -vn -1.929209 2.653722 -4.127017 -v 0.006159 -0.013570 0.080379 -vn -1.216262 2.640728 -4.412505 -v 0.006380 -0.013593 0.080287 -vn -1.515008 -2.619501 -4.287519 -v 0.006382 -0.013692 0.080287 -vn -0.644525 2.658575 -4.527580 -v 0.006411 -0.013596 0.080279 -vn -0.754118 -2.543687 -4.498369 -v 0.006556 -0.013709 0.080254 -vn 0.317957 2.621027 -4.508598 -v 0.006650 -0.013619 0.080250 -vn -0.097626 -2.624869 -4.544995 -v 0.006650 -0.013718 0.080250 -vn -1.991991 -2.452080 -4.077405 -v 0.006227 -0.013676 0.080344 -vn -2.663910 -2.670099 -3.674038 -v 0.006133 -0.013666 0.080394 -vn -2.590766 2.524034 -3.770746 -v 0.006040 -0.013556 0.080458 -vn -3.279449 -2.700867 -3.165560 -v 0.005943 -0.013643 0.080543 -vn -3.101948 2.656294 -3.345164 -v 0.005943 -0.013544 0.080543 -vn -3.667786 -2.591491 -2.740522 -v 0.005912 -0.013638 0.080575 -vn -3.714295 2.611436 -2.551906 -v 0.005794 -0.013520 0.080733 -vn -4.049974 -2.629385 -2.087627 -v 0.005779 -0.013617 0.080759 -vn -4.282118 -2.474955 -1.548920 -v 0.005733 -0.013607 0.080852 -vn -4.224538 2.641282 -1.406912 -v 0.005687 -0.013494 0.080982 -vn -4.471345 -2.572103 -0.718342 -v 0.005679 -0.013591 0.081011 -vn -4.454165 2.584455 -0.275450 -v 0.005650 -0.013468 0.081250 -vn -4.497637 -2.561413 0.248912 -v 0.005650 -0.013567 0.081250 -vn -4.533792 2.604780 0.560961 -v 0.005679 -0.013445 0.081489 -vn -4.243077 -2.517465 1.512157 -v 0.005687 -0.013541 0.081519 -vn -4.431114 2.662754 1.146421 -v 0.005680 -0.013445 0.081494 -vn -3.762209 -2.607508 2.494483 -v 0.005794 -0.013515 0.081767 -vn -4.163537 2.531523 1.831393 -v 0.005779 -0.013419 0.081741 -vn -3.706140 2.365242 2.636992 -v 0.005850 -0.013407 0.081850 -vn -3.330986 2.558018 3.080313 -v 0.005943 -0.013394 0.081957 -vn -3.080046 -2.551699 3.346824 -v 0.005943 -0.013492 0.081957 -vn -2.639401 -2.361058 3.704475 -v 0.006050 -0.013479 0.082050 -vn -0.666079 -2.664901 4.517160 -v 0.006411 -0.013440 0.082221 -vn 0.053506 -2.637163 4.555790 -v 0.006650 -0.013417 0.082250 -vn -0.251339 2.619185 4.537526 -v 0.006650 -0.013319 0.082250 -vn -0.713974 2.339525 4.475633 -v 0.006518 -0.013331 0.082241 -vn -1.577224 2.662773 4.248282 -v 0.006382 -0.013345 0.082213 -vn -2.310717 1.954445 3.811412 -v 0.006145 -0.013369 0.082113 -vn -4.045353 -2.628478 -1.994621 -v 0.005779 -0.013016 0.080759 -vn -3.652728 2.583230 -2.746542 -v 0.005794 -0.012920 0.080733 -vn -3.479544 -2.602679 -2.933084 -v 0.005943 -0.013042 0.080543 -vn -3.147989 2.608247 -3.290351 -v 0.005943 -0.012943 0.080543 -vn -2.984917 -2.607976 -3.482214 -v 0.006040 -0.013055 0.080458 -vn 0.095287 2.622571 -4.549570 -v 0.006650 -0.013019 0.080250 -vn -0.316449 -2.643988 -4.461478 -v 0.006650 -0.013117 0.080250 -vn -0.634445 2.584665 -4.530982 -v 0.006411 -0.012995 0.080279 -vn -1.429267 -2.632944 -4.264252 -v 0.006382 -0.013091 0.080287 -vn -1.330934 2.583473 -4.356487 -v 0.006351 -0.012990 0.080296 -vn -2.468804 -2.605999 -3.834467 -v 0.006133 -0.013065 0.080394 -vn -1.917299 2.572525 -4.104703 -v 0.006159 -0.012969 0.080379 -vn -2.703720 2.623383 -3.679955 -v 0.006006 -0.012952 0.080485 -vn -4.086888 2.639524 2.006207 -v 0.005779 -0.012819 0.081741 -vn -4.349200 2.520674 1.390582 -v 0.005701 -0.012838 0.081567 -vn -4.286031 -2.651693 1.460139 -v 0.005687 -0.012942 0.081518 -vn -4.515352 2.628325 0.683412 -v 0.005679 -0.012845 0.081489 -vn -4.471280 -2.592348 0.682781 -v 0.005652 -0.012961 0.081315 -vn -4.561051 2.689771 -0.131747 -v 0.005650 -0.012868 0.081250 -vn -4.522212 -2.720433 0.132740 -v 0.005650 -0.012967 0.081250 -vn -4.513929 2.553489 -0.719654 -v 0.005653 -0.012876 0.081174 -vn -4.417220 -2.605350 -0.845358 -v 0.005679 -0.012990 0.081011 -vn -4.290046 2.554348 -1.522962 -v 0.005687 -0.012894 0.080981 -vn -4.045311 2.548466 -2.125095 -v 0.005760 -0.012914 0.080795 -vn -4.072839 -2.481874 2.024059 -v 0.005748 -0.012925 0.081683 -vn -3.682948 -2.625329 2.694772 -v 0.005794 -0.012915 0.081767 -vn -3.690783 2.564881 2.699582 -v 0.005898 -0.012800 0.081909 -vn -3.166047 -2.703269 3.300141 -v 0.005943 -0.012892 0.081957 -vn -3.270640 2.703508 3.143420 -v 0.005943 -0.012793 0.081957 -vn -2.722438 -2.600570 3.659904 -v 0.005975 -0.012888 0.081988 -vn -2.711369 2.623816 3.638197 -v 0.006133 -0.012770 0.082106 -vn -1.977394 -2.645108 4.058756 -v 0.006159 -0.012866 0.082121 -vn -2.043498 2.502856 4.062668 -v 0.006212 -0.012762 0.082149 -vn -1.524791 2.577836 4.269233 -v 0.006382 -0.012744 0.082213 -vn -0.998145 -2.643156 4.440290 -v 0.006411 -0.012840 0.082221 -vn -0.456018 -2.576968 4.546957 -v 0.006481 -0.012833 0.082236 -vn -0.648273 2.642386 4.528391 -v 0.006593 -0.012724 0.082248 -vn 0.294507 -2.679811 4.533846 -v 0.006650 -0.012817 0.082250 -vn -0.179034 2.699056 4.570370 -v 0.006650 -0.012718 0.082250 -vn -4.221724 2.286345 1.619105 -v 0.005728 -0.012230 0.081637 -vn -4.467914 2.658947 0.741920 -v 0.005679 -0.012245 0.081489 -vn -4.267504 -2.642688 1.593156 -v 0.005687 -0.012341 0.081519 -vn -4.163802 -2.653130 -1.867996 -v 0.005779 -0.012416 0.080759 -vn -4.122289 2.318950 -1.868542 -v 0.005728 -0.012306 0.080863 -vn -3.693767 2.669869 -2.635520 -v 0.005794 -0.012320 0.080733 -vn 0.036518 2.618322 -4.576294 -v 0.006650 -0.012418 0.080250 -vn -0.435084 -2.624602 -4.509958 -v 0.006650 -0.012517 0.080250 -vn -0.703056 2.570913 -4.499674 -v 0.006411 -0.012395 0.080279 -vn -1.403228 -2.638816 -4.266827 -v 0.006382 -0.012491 0.080287 -vn -1.493006 2.475571 -4.314922 -v 0.006280 -0.012382 0.080321 -vn -2.485543 -2.642447 -3.813068 -v 0.006133 -0.012465 0.080394 -vn -2.059886 2.619690 -4.065450 -v 0.006159 -0.012369 0.080379 -vn -2.949072 -2.493608 -3.484213 -v 0.006050 -0.012456 0.080450 -vn -2.849455 2.687448 -3.592950 -v 0.005950 -0.012344 0.080536 -vn -3.351655 -2.701840 -3.107085 -v 0.005943 -0.012442 0.080543 -vn -3.212332 2.712774 -3.260235 -v 0.005943 -0.012343 0.080543 -vn -3.616470 -2.611103 -2.772484 -v 0.005912 -0.012438 0.080575 -vn -3.836559 -2.558379 -2.479486 -v 0.005825 -0.012425 0.080685 -vn -4.302443 2.545295 -1.418698 -v 0.005687 -0.012294 0.080981 -vn -4.445755 -2.541156 -0.823819 -v 0.005679 -0.012390 0.081011 -vn -4.491663 2.567112 -0.244821 -v 0.005650 -0.012268 0.081250 -vn -4.544880 -2.550730 0.193313 -v 0.005650 -0.012367 0.081250 -vn -4.484499 -2.403964 0.794316 -v 0.005662 -0.012353 0.081403 -vn -4.044821 2.544690 2.046934 -v 0.005779 -0.012219 0.081741 -vn -3.710847 -2.546422 2.561992 -v 0.005794 -0.012316 0.081767 -vn -3.587181 2.653797 2.844365 -v 0.005943 -0.012193 0.081957 -vn -3.001952 -2.565071 3.363483 -v 0.005943 -0.012292 0.081957 -vn -3.191900 2.625016 3.283407 -v 0.005950 -0.012192 0.081964 -vn -2.175993 -2.613416 4.007358 -v 0.006159 -0.012267 0.082121 -vn -2.664697 2.549576 3.686876 -v 0.006133 -0.012170 0.082106 -vn -1.863460 2.448933 4.147320 -v 0.006280 -0.012154 0.082179 -vn -1.750421 -2.539119 4.214609 -v 0.006195 -0.012263 0.082140 -vn -1.377188 2.576014 4.321479 -v 0.006382 -0.012144 0.082213 -vn -0.829910 -2.554433 4.461173 -v 0.006411 -0.012241 0.082221 -vn -0.487646 2.695806 4.544966 -v 0.006650 -0.012118 0.082250 -vn -0.352229 -2.393321 4.528878 -v 0.006555 -0.012227 0.082245 -vn 0.431330 -2.643431 4.519273 -v 0.006650 -0.012218 0.082250 -vn -1.075690 -2.396054 -4.408614 -v 0.006408 -0.011895 0.080281 -vn -1.892212 -2.696744 -4.156948 -v 0.006320 -0.011886 0.080307 -vn -1.048822 2.617713 -4.401239 -v 0.006336 -0.011788 0.080301 -vn -0.381704 -2.632245 -4.539282 -v 0.006650 -0.011918 0.080250 -vn -0.357862 2.421561 -4.503844 -v 0.006588 -0.011812 0.080252 -vn 0.453683 2.678539 -4.524832 -v 0.006650 -0.011818 0.080250 -vn -3.495053 -2.545512 -2.783726 -v 0.005915 -0.011839 0.080572 -vn -4.235485 -2.699658 -1.577212 -v 0.005719 -0.011803 0.080887 -vn -3.850723 2.341477 -2.384336 -v 0.005752 -0.011712 0.080810 -vn -3.481461 2.567145 -2.957268 -v 0.005897 -0.011737 0.080591 -vn -3.070191 2.666419 -3.405539 -v 0.005902 -0.011738 0.080586 -vn -2.730096 -2.558464 -3.605091 -v 0.006084 -0.011860 0.080426 -vn -2.363925 2.533839 -3.865576 -v 0.006088 -0.011762 0.080423 -vn -1.905151 2.245227 -4.092843 -v 0.006212 -0.011775 0.080351 -vn -4.476201 -2.669460 -0.734606 -v 0.005681 -0.011791 0.081006 -vn -4.466883 -2.371581 0.083705 -v 0.005650 -0.011768 0.081250 -vn -4.573816 2.629510 -0.188670 -v 0.005652 -0.011662 0.081315 -vn -4.452300 2.372787 -0.758589 -v 0.005666 -0.011686 0.081072 -vn -4.368457 2.661020 -1.383416 -v 0.005680 -0.011692 0.081006 -vn -4.257483 2.591036 -1.689769 -v 0.005701 -0.011699 0.080933 -vn -3.211021 2.378698 3.270673 -v 0.005995 -0.011587 0.082006 -vn -3.541596 2.622375 2.872794 -v 0.005912 -0.011598 0.081925 -vn -3.201039 -2.648927 3.086862 -v 0.005892 -0.011700 0.081901 -vn -3.933926 2.284501 2.250529 -v 0.005815 -0.011613 0.081801 -vn -4.058380 -2.704574 1.955505 -v 0.005709 -0.011735 0.081586 -vn -4.094371 2.233405 1.926387 -v 0.005760 -0.011623 0.081705 -vn -4.401230 2.656952 1.234141 -v 0.005698 -0.011638 0.081557 -vn -4.379328 -2.661384 1.212834 -v 0.005681 -0.011744 0.081494 -vn -4.507592 2.611312 0.726252 -v 0.005680 -0.011644 0.081494 -vn -4.561656 2.450052 0.344263 -v 0.005653 -0.011661 0.081326 -vn -2.179300 -2.495663 3.940670 -v 0.006173 -0.011665 0.082128 -vn -1.256774 -2.668581 4.390475 -v 0.006320 -0.011650 0.082193 -vn -2.399132 2.538308 3.830235 -v 0.006195 -0.011563 0.082141 -vn -2.706436 1.827108 3.476707 -v 0.006006 -0.011585 0.082015 -vn 0.192044 -2.658065 4.581387 -v 0.006650 -0.011618 0.082250 -vn -0.382678 2.668673 4.524043 -v 0.006650 -0.011519 0.082250 -vn -0.400899 -2.585632 4.550305 -v 0.006514 -0.011631 0.082240 -vn -1.142858 2.589427 4.385598 -v 0.006430 -0.011540 0.082225 -vn -1.645243 2.606477 4.265940 -v 0.006351 -0.011547 0.082204 -vn 0.394568 2.612556 -4.507576 -v 0.006650 -0.011219 0.080250 -vn -0.106711 -2.604688 -4.554424 -v 0.006650 -0.011318 0.080250 -vn -0.358894 2.612974 -4.564803 -v 0.006518 -0.011206 0.080259 -vn -0.719390 -2.621203 -4.517537 -v 0.006556 -0.011309 0.080254 -vn -0.969853 2.612842 -4.437249 -v 0.006411 -0.011196 0.080279 -vn -1.532035 -2.567244 -4.277255 -v 0.006382 -0.011292 0.080287 -vn -1.821353 2.620017 -4.177662 -v 0.006159 -0.011169 0.080379 -vn -1.990583 -2.449888 -4.080123 -v 0.006227 -0.011276 0.080344 -vn -2.292638 2.633636 -3.958319 -v 0.006145 -0.011168 0.080387 -vn -2.709559 -2.602829 -3.642063 -v 0.006133 -0.011266 0.080394 -vn -3.225373 -2.643547 -3.209442 -v 0.005943 -0.011243 0.080543 -vn -2.920082 2.620845 -3.484495 -v 0.005943 -0.011143 0.080543 -vn -3.650378 -2.659799 -2.766839 -v 0.005912 -0.011238 0.080575 -vn -3.533239 2.443102 -2.889402 -v 0.005850 -0.011130 0.080650 -vn -3.796062 2.597117 -2.524752 -v 0.005794 -0.011120 0.080733 -vn -4.050403 -2.629311 -2.087300 -v 0.005779 -0.011217 0.080759 -vn -4.281796 -2.475400 -1.548507 -v 0.005733 -0.011207 0.080852 -vn -4.271961 2.618423 -1.417070 -v 0.005687 -0.011094 0.080982 -vn -4.470939 -2.572344 -0.718515 -v 0.005679 -0.011191 0.081011 -vn -4.473659 2.577204 -0.259937 -v 0.005650 -0.011068 0.081250 -vn -4.496331 -2.561991 0.249711 -v 0.005650 -0.011167 0.081250 -vn -4.413699 2.577130 0.774071 -v 0.005679 -0.011045 0.081489 -vn -4.258226 -2.580807 1.460981 -v 0.005687 -0.011141 0.081519 -vn -4.248001 2.526972 1.622058 -v 0.005757 -0.011024 0.081700 -vn -3.705044 -2.574823 2.581265 -v 0.005794 -0.011115 0.081767 -vn -3.990367 2.661288 2.200696 -v 0.005779 -0.011019 0.081741 -vn -3.543231 2.639641 2.860356 -v 0.005943 -0.010993 0.081957 -vn -3.124484 -2.624642 3.299480 -v 0.005943 -0.011092 0.081957 -vn -3.158045 2.668532 3.321306 -v 0.005984 -0.010988 0.081996 -vn -2.546838 -2.614457 3.804897 -v 0.006050 -0.011079 0.082050 -vn -2.528138 2.630111 3.775725 -v 0.006133 -0.010970 0.082106 -vn -0.626212 -2.579852 4.493744 -v 0.006411 -0.011040 0.082221 -vn 0.038508 -2.655093 4.522659 -v 0.006650 -0.011017 0.082250 -vn -0.309396 2.623341 4.505188 -v 0.006650 -0.010918 0.082250 -vn -1.877985 -2.579171 4.140778 -v 0.006159 -0.011066 0.082121 -vn -1.251478 -2.620211 4.387125 -v 0.006351 -0.011046 0.082204 -vn -1.976069 2.507627 4.124162 -v 0.006298 -0.010952 0.082186 -vn -1.322004 2.626968 4.362105 -v 0.006382 -0.010944 0.082213 -vn -4.242573 -2.577853 1.521768 -v 0.005687 -0.010541 0.081518 -vn -4.436767 2.649489 1.017569 -v 0.005679 -0.010445 0.081489 -vn -4.546507 2.498968 0.434690 -v 0.005666 -0.010451 0.081427 -vn -4.500336 -2.618369 0.244914 -v 0.005650 -0.010567 0.081250 -vn -4.541847 2.598531 -0.266360 -v 0.005650 -0.010468 0.081250 -vn -4.462030 2.583399 -0.988291 -v 0.005670 -0.010487 0.081053 -vn -4.401789 -2.653559 -0.860621 -v 0.005679 -0.010590 0.081011 -vn -4.240468 2.586349 -1.672525 -v 0.005687 -0.010494 0.080981 -vn -4.045167 -2.553365 -1.945940 -v 0.005779 -0.010616 0.080759 -vn -3.721577 2.543815 -2.558197 -v 0.005794 -0.010520 0.080733 -vn -3.477911 -2.605541 -2.924766 -v 0.005943 -0.010642 0.080543 -vn -3.094977 2.609290 -3.310333 -v 0.005943 -0.010543 0.080543 -vn -3.025215 -2.649502 -3.452693 -v 0.006040 -0.010655 0.080458 -vn -2.511013 2.673828 -3.820172 -v 0.006063 -0.010558 0.080440 -vn -2.447034 -2.643048 -3.845625 -v 0.006133 -0.010665 0.080394 -vn -1.834917 2.582895 -4.152470 -v 0.006159 -0.010569 0.080379 -vn -1.470088 -2.561397 -4.266148 -v 0.006382 -0.010691 0.080287 -vn 0.096667 2.624237 -4.525332 -v 0.006650 -0.010618 0.080250 -vn -0.325377 -2.612892 -4.511012 -v 0.006650 -0.010717 0.080250 -vn -0.558027 2.608334 -4.526247 -v 0.006411 -0.010595 0.080279 -vn -1.136455 2.683446 -4.421724 -v 0.006402 -0.010594 0.080281 -vn -4.054936 2.547128 1.958886 -v 0.005779 -0.010419 0.081741 -vn -3.722287 -2.547040 2.547335 -v 0.005794 -0.010515 0.081767 -vn -3.475256 2.602378 2.932529 -v 0.005943 -0.010393 0.081957 -vn -3.122516 -2.604548 3.304852 -v 0.005943 -0.010492 0.081957 -vn -3.001836 2.653463 3.468780 -v 0.006042 -0.010380 0.082044 -vn -2.591422 -2.655181 3.769732 -v 0.006039 -0.010480 0.082042 -vn -2.446521 2.629755 3.839113 -v 0.006133 -0.010370 0.082106 -vn -1.888212 -2.573450 4.135139 -v 0.006159 -0.010467 0.082121 -vn -1.457167 2.615921 4.263757 -v 0.006382 -0.010344 0.082213 -vn 0.242760 -2.621772 4.465400 -v 0.006650 -0.010418 0.082250 -vn -0.437731 2.622873 4.537403 -v 0.006650 -0.010318 0.082250 -vn -0.604303 -2.596673 4.519901 -v 0.006411 -0.010441 0.082221 -vn -1.277028 -2.614737 4.382920 -v 0.006365 -0.010445 0.082209 -vn 0.473996 2.660583 4.557521 -v 0.006846 -0.020500 0.082231 -vn 1.413068 -2.537780 4.292228 -v 0.006884 -0.020756 0.082224 -vn 4.256862 -2.584546 -1.541315 -v 0.007613 -0.020545 0.080985 -vn 4.429929 2.600829 -0.987163 -v 0.007621 -0.020346 0.081011 -vn 4.560880 2.590081 -0.344681 -v 0.007641 -0.020356 0.081119 -vn 4.518169 -2.583553 -0.336309 -v 0.007649 -0.020580 0.081251 -vn 4.533656 2.593100 0.383268 -v 0.007650 -0.020369 0.081250 -vn 4.557289 -2.603027 0.527916 -v 0.007621 -0.020613 0.081494 -vn 4.269789 2.572211 1.454870 -v 0.007613 -0.020395 0.081519 -vn 4.403085 -2.609087 1.177488 -v 0.007613 -0.020617 0.081523 -vn 3.860284 2.617719 2.402934 -v 0.007506 -0.020421 0.081767 -vn 4.062731 -2.593502 1.974369 -v 0.007504 -0.020652 0.081770 -vn 3.493972 2.655642 2.953201 -v 0.007457 -0.020429 0.081841 -vn 3.701651 -2.672124 2.722189 -v 0.007388 -0.020677 0.081924 -vn 2.971035 2.624212 3.431411 -v 0.007357 -0.020444 0.081957 -vn 3.284283 -2.669870 3.133396 -v 0.007356 -0.020683 0.081957 -vn 2.435251 2.626798 3.857236 -v 0.007198 -0.020463 0.082086 -vn 2.469464 -2.544258 3.736655 -v 0.007138 -0.020720 0.082124 -vn 1.819209 2.625935 4.191040 -v 0.007141 -0.020470 0.082121 -vn 1.090779 2.639325 4.430486 -v 0.006889 -0.020496 0.082221 -vn 4.038254 2.549324 -1.999626 -v 0.007521 -0.020320 0.080759 -vn 3.738692 -2.520425 -2.521315 -v 0.007519 -0.020512 0.080754 -vn 3.512244 2.606171 -2.904966 -v 0.007357 -0.020294 0.080543 -vn 3.152414 -2.626187 -3.306525 -v 0.007357 -0.020477 0.080543 -vn 2.664402 -2.695392 -3.694505 -v 0.007336 -0.020473 0.080523 -vn 3.019526 2.612443 -3.432101 -v 0.007279 -0.020284 0.080473 -vn 1.942983 -2.642278 -4.047031 -v 0.007156 -0.020444 0.080389 -vn 1.462444 2.590361 -4.347585 -v 0.006918 -0.020244 0.080287 -vn 1.699301 2.242847 -4.185555 -v 0.006964 -0.020249 0.080301 -vn 2.487990 2.591032 -3.793031 -v 0.007167 -0.020270 0.080394 -vn 1.086670 -2.639521 -4.426408 -v 0.006910 -0.020409 0.080285 -vn 0.478848 -2.651517 -4.552058 -v 0.006855 -0.020401 0.080271 -vn 0.771807 2.626375 -4.507893 -v 0.006754 -0.020228 0.080255 -vn 0.269821 2.601112 4.575942 -v 0.006766 -0.019907 0.082243 -vn 1.044135 -2.680143 4.457776 -v 0.006846 -0.019998 0.082231 -vn 0.863601 2.680657 4.501690 -v 0.006887 -0.019896 0.082222 -vn 1.624337 -2.656481 4.269519 -v 0.006918 -0.019991 0.082213 -vn 1.564152 2.470997 4.274408 -v 0.007033 -0.019881 0.082174 -vn 2.540613 -2.559523 3.742281 -v 0.007167 -0.019965 0.082106 -vn 2.312441 2.615102 3.946464 -v 0.007224 -0.019860 0.082069 -vn 2.762371 2.273186 3.599022 -v 0.007256 -0.019856 0.082046 -vn 3.553818 2.651894 2.848530 -v 0.007448 -0.019830 0.081852 -vn 4.110210 -2.453501 1.909671 -v 0.007521 -0.019916 0.081741 -vn 4.071802 2.482871 1.949486 -v 0.007584 -0.019803 0.081607 -vn 4.444448 -2.654490 0.849801 -v 0.007621 -0.019890 0.081489 -vn 4.359849 2.656675 1.359018 -v 0.007620 -0.019792 0.081494 -vn 3.138719 2.575847 3.327393 -v 0.007388 -0.019839 0.081925 -vn 3.250678 -2.482319 3.150917 -v 0.007357 -0.019942 0.081957 -vn 3.823632 -2.645106 2.516148 -v 0.007457 -0.019928 0.081841 -vn 4.511508 2.531599 0.775317 -v 0.007644 -0.019778 0.081356 -vn 4.554982 -2.646849 -0.207189 -v 0.007650 -0.019867 0.081250 -vn 4.556279 2.662085 0.219328 -v 0.007650 -0.019769 0.081258 -vn 4.552260 2.646856 -0.393103 -v 0.007638 -0.019754 0.081095 -vn 4.501588 -2.626427 -0.824229 -v 0.007641 -0.019855 0.081119 -vn 4.496892 2.655441 -0.912085 -v 0.007620 -0.019745 0.081006 -vn 4.282259 -2.651783 -1.541981 -v 0.007613 -0.019841 0.080981 -vn 4.226106 2.550668 -1.583748 -v 0.007574 -0.019731 0.080867 -vn 3.915735 -2.461548 -2.354267 -v 0.007522 -0.019818 0.080761 -vn 3.755863 2.540605 -2.500694 -v 0.007432 -0.019704 0.080626 -vn 3.714282 -2.417920 -2.644566 -v 0.007506 -0.019815 0.080733 -vn 3.113707 -2.668137 -3.344128 -v 0.007357 -0.019792 0.080543 -vn 3.319016 2.675200 -3.103553 -v 0.007357 -0.019693 0.080543 -vn 2.613127 -2.472081 -3.752493 -v 0.007279 -0.019782 0.080473 -vn 2.405225 2.617964 -3.812179 -v 0.007136 -0.019667 0.080376 -vn 2.001761 -2.605499 -4.093111 -v 0.007141 -0.019766 0.080379 -vn 1.341698 -2.581072 -4.374585 -v 0.006964 -0.019748 0.080301 -vn 1.546679 2.673330 -4.261407 -v 0.006918 -0.019644 0.080287 -vn 0.697755 -2.664674 -4.511211 -v 0.006889 -0.019740 0.080279 -vn 0.814784 2.535256 -4.483113 -v 0.006774 -0.019630 0.080258 -vn 3.324033 -2.666571 3.163576 -v 0.007357 -0.019343 0.081957 -vn 2.994523 2.646432 3.375146 -v 0.007357 -0.019243 0.081957 -vn 2.912449 -2.492649 3.526224 -v 0.007224 -0.019359 0.082069 -vn 2.155691 2.686302 4.025058 -v 0.007141 -0.019269 0.082121 -vn 2.452117 -2.674472 3.839775 -v 0.007167 -0.019366 0.082106 -vn 1.650358 2.518057 4.256049 -v 0.007098 -0.019274 0.082144 -vn 1.456115 -2.580806 4.263743 -v 0.006918 -0.019392 0.082213 -vn 0.818520 2.558330 4.459892 -v 0.006889 -0.019295 0.082221 -vn 0.324824 2.421673 4.528448 -v 0.006737 -0.019310 0.082246 -vn 3.649708 -2.594817 2.765901 -v 0.007388 -0.019338 0.081925 -vn 3.860876 -2.589501 2.441835 -v 0.007483 -0.019324 0.081803 -vn 3.693558 2.669595 2.630229 -v 0.007506 -0.019220 0.081767 -vn 4.171260 -2.655455 1.855713 -v 0.007521 -0.019317 0.081741 -vn 4.117687 2.311895 1.861910 -v 0.007573 -0.019206 0.081634 -vn 4.304335 2.545552 1.414115 -v 0.007613 -0.019194 0.081519 -vn 4.432949 -2.547908 0.811489 -v 0.007621 -0.019291 0.081489 -vn 4.504987 2.558779 0.261598 -v 0.007650 -0.019168 0.081250 -vn 4.501644 -2.561589 -0.250263 -v 0.007650 -0.019268 0.081250 -vn 4.519696 2.579003 -0.660846 -v 0.007621 -0.019145 0.081011 -vn 4.363816 -2.660251 -1.307386 -v 0.007613 -0.019242 0.080981 -vn 4.366747 2.685667 -1.333318 -v 0.007596 -0.019137 0.080925 -vn 4.142097 -2.641027 -1.949677 -v 0.007585 -0.019233 0.080895 -vn 4.082150 2.631109 -1.985537 -v 0.007521 -0.019119 0.080759 -vn 3.736176 -2.626000 -2.590234 -v 0.007506 -0.019216 0.080733 -vn 3.723442 2.632891 -2.647750 -v 0.007417 -0.019102 0.080608 -vn 3.312413 -2.690675 -3.169325 -v 0.007390 -0.019197 0.080577 -vn 3.259123 2.620171 -3.174828 -v 0.007357 -0.019093 0.080543 -vn 2.833958 -2.631076 -3.562030 -v 0.007357 -0.019193 0.080543 -vn 2.245327 -2.675837 -3.961137 -v 0.007141 -0.019167 0.080379 -vn 2.563042 2.551729 -3.693175 -v 0.007167 -0.019070 0.080394 -vn 1.714815 -2.561730 -4.245293 -v 0.007124 -0.019165 0.080369 -vn 1.476385 2.569610 -4.234550 -v 0.006918 -0.019044 0.080287 -vn 0.870365 -2.547636 -4.457850 -v 0.006889 -0.019141 0.080279 -vn 0.444120 -2.288780 -4.513178 -v 0.006774 -0.019130 0.080258 -vn 4.468999 2.481195 0.856836 -v 0.007635 -0.018585 0.081424 -vn 4.240743 2.656974 1.623872 -v 0.007613 -0.018595 0.081519 -vn 4.482362 -2.656610 0.750390 -v 0.007621 -0.018691 0.081489 -vn 0.142365 2.675560 4.586923 -v 0.006714 -0.018713 0.082248 -vn 0.755127 -2.645774 4.518414 -v 0.006737 -0.018810 0.082246 -vn 0.831696 2.617908 4.488835 -v 0.006889 -0.018696 0.082221 -vn 1.484770 -2.626055 4.297865 -v 0.006918 -0.018792 0.082213 -vn 1.548696 2.629565 4.304812 -v 0.007060 -0.018678 0.082162 -vn 2.182344 -2.686939 4.019659 -v 0.007098 -0.018774 0.082144 -vn 2.171171 2.658310 3.994288 -v 0.007141 -0.018670 0.082121 -vn 2.752281 -2.566019 3.630833 -v 0.007167 -0.018766 0.082106 -vn 3.229060 -2.630888 3.215110 -v 0.007357 -0.018743 0.081957 -vn 2.946307 2.623645 3.366949 -v 0.007357 -0.018644 0.081957 -vn 3.658429 -2.603354 2.711380 -v 0.007388 -0.018739 0.081925 -vn 3.682685 2.598397 2.527374 -v 0.007506 -0.018621 0.081767 -vn 4.055449 -2.560587 2.026786 -v 0.007521 -0.018717 0.081741 -vn 4.237804 -2.289104 1.609648 -v 0.007573 -0.018705 0.081634 -vn 4.531671 2.581863 0.277628 -v 0.007650 -0.018569 0.081250 -vn 4.507949 -2.581974 -0.230525 -v 0.007650 -0.018668 0.081250 -vn 4.556777 2.506733 -0.461362 -v 0.007632 -0.018551 0.081062 -vn 4.374815 -2.673467 -1.329212 -v 0.007613 -0.018642 0.080981 -vn 4.461482 2.680202 -0.994094 -v 0.007621 -0.018546 0.081011 -vn 4.176554 -2.497305 -1.865657 -v 0.007596 -0.018636 0.080925 -vn 4.054241 2.603316 -1.979865 -v 0.007521 -0.018520 0.080759 -vn 3.762985 -2.597085 -2.558332 -v 0.007506 -0.018616 0.080733 -vn 3.416435 -2.495240 -3.031877 -v 0.007417 -0.018601 0.080609 -vn 3.467466 2.666160 -2.936744 -v 0.007357 -0.018494 0.080543 -vn 2.909602 -2.667949 -3.493667 -v 0.007357 -0.018593 0.080543 -vn 0.606386 -2.596716 -4.532270 -v 0.006889 -0.018541 0.080279 -vn 1.263296 2.678015 -4.390105 -v 0.006918 -0.018445 0.080287 -vn 1.157142 -2.701865 -4.424184 -v 0.006918 -0.018544 0.080287 -vn 1.841491 2.593256 -4.194815 -v 0.006959 -0.018449 0.080299 -vn 2.012412 -2.577574 -4.037593 -v 0.007141 -0.018567 0.080379 -vn 2.563927 2.551661 -3.753616 -v 0.007167 -0.018471 0.080394 -vn 2.912669 2.333230 -3.484166 -v 0.007275 -0.018483 0.080469 -vn 1.855016 2.665882 4.175678 -v 0.007141 -0.018070 0.082121 -vn 1.040371 2.657714 4.447001 -v 0.006889 -0.018096 0.082221 -vn 1.507888 -2.567879 4.305238 -v 0.006918 -0.018191 0.082213 -vn 0.511798 2.596484 4.549227 -v 0.006846 -0.018100 0.082231 -vn 0.672174 -2.611960 4.526356 -v 0.006714 -0.018211 0.082248 -vn 1.955736 -2.389407 4.111043 -v 0.007059 -0.018177 0.082162 -vn 2.663976 -2.665493 3.696577 -v 0.007167 -0.018165 0.082106 -vn 2.445808 2.599683 3.848171 -v 0.007198 -0.018063 0.082086 -vn 3.273654 -2.654634 3.202707 -v 0.007357 -0.018142 0.081957 -vn 2.960352 2.647442 3.443961 -v 0.007357 -0.018044 0.081957 -vn 3.648391 -2.661048 2.756801 -v 0.007388 -0.018138 0.081925 -vn 3.509765 2.554860 2.923813 -v 0.007457 -0.018029 0.081841 -vn 4.094321 -2.574281 1.917533 -v 0.007521 -0.018116 0.081741 -vn 3.836406 2.629798 2.448042 -v 0.007506 -0.018021 0.081767 -vn 4.255730 2.571991 1.520222 -v 0.007613 -0.017995 0.081519 -vn 4.444249 -2.644600 1.008410 -v 0.007621 -0.018090 0.081489 -vn 4.550534 -2.493241 0.436633 -v 0.007635 -0.018084 0.081425 -vn 4.537453 2.629197 0.354986 -v 0.007650 -0.017969 0.081250 -vn 4.529806 -2.637383 -0.254857 -v 0.007650 -0.018067 0.081250 -vn 4.567444 2.624585 -0.309961 -v 0.007641 -0.017956 0.081119 -vn 4.450416 -2.689568 -1.009840 -v 0.007632 -0.018049 0.081062 -vn 4.435362 2.663926 -0.983175 -v 0.007621 -0.017946 0.081011 -vn 4.224516 -2.589095 -1.672927 -v 0.007613 -0.018041 0.080981 -vn 4.060315 2.543348 -1.964729 -v 0.007521 -0.017920 0.080759 -vn 3.716495 -2.550826 -2.542580 -v 0.007506 -0.018015 0.080733 -vn 3.502075 2.612414 -2.917046 -v 0.007357 -0.017894 0.080543 -vn 3.133319 -2.618872 -3.292161 -v 0.007357 -0.017992 0.080543 -vn 3.042004 2.666175 -3.416911 -v 0.007279 -0.017884 0.080473 -vn 2.620134 -2.663285 -3.743718 -v 0.007275 -0.017982 0.080469 -vn 2.511257 2.635375 -3.783597 -v 0.007167 -0.017870 0.080394 -vn 1.936800 -2.604759 -4.110094 -v 0.007141 -0.017966 0.080379 -vn 1.844400 2.658044 -4.181861 -v 0.006964 -0.017849 0.080301 -vn 1.312435 -2.666910 -4.370803 -v 0.006959 -0.017947 0.080299 -vn 1.373196 2.693769 -4.379731 -v 0.006918 -0.017844 0.080287 -vn 0.662714 -2.665642 -4.492213 -v 0.006889 -0.017940 0.080279 -vn 0.776229 2.533148 -4.502379 -v 0.006754 -0.017828 0.080255 -vn 0.269865 2.600979 4.575920 -v 0.006766 -0.017507 0.082243 -vn 1.044279 -2.680444 4.457380 -v 0.006846 -0.017598 0.082231 -vn 0.863576 2.680619 4.501684 -v 0.006887 -0.017496 0.082222 -vn 1.630598 -2.663211 4.251001 -v 0.006918 -0.017591 0.082213 -vn 1.564179 2.471001 4.274387 -v 0.007033 -0.017481 0.082174 -vn 2.526758 -2.566123 3.736929 -v 0.007167 -0.017565 0.082106 -vn 2.312200 2.615531 3.946784 -v 0.007224 -0.017460 0.082069 -vn 2.762177 2.273184 3.599079 -v 0.007256 -0.017456 0.082046 -vn 3.553794 2.651835 2.848540 -v 0.007448 -0.017430 0.081852 -vn 4.109910 -2.453674 1.909516 -v 0.007521 -0.017516 0.081741 -vn 4.071808 2.482863 1.949501 -v 0.007584 -0.017403 0.081607 -vn 4.444143 -2.654645 0.849711 -v 0.007621 -0.017490 0.081489 -vn 4.359867 2.656669 1.359010 -v 0.007620 -0.017392 0.081494 -vn 3.138703 2.575857 3.327382 -v 0.007388 -0.017439 0.081925 -vn 3.250489 -2.482487 3.150595 -v 0.007357 -0.017542 0.081957 -vn 3.823531 -2.645349 2.515817 -v 0.007457 -0.017528 0.081841 -vn 4.511496 2.531606 0.775312 -v 0.007644 -0.017378 0.081356 -vn 4.554655 -2.647010 -0.207232 -v 0.007650 -0.017467 0.081250 -vn 4.556277 2.662085 0.219340 -v 0.007650 -0.017369 0.081258 -vn 4.552288 2.646925 -0.393047 -v 0.007638 -0.017354 0.081095 -vn 4.501189 -2.626675 -0.824397 -v 0.007641 -0.017455 0.081119 -vn 4.496912 2.655470 -0.912096 -v 0.007620 -0.017345 0.081006 -vn 4.281912 -2.651956 -1.542022 -v 0.007613 -0.017441 0.080981 -vn 4.226058 2.550611 -1.583722 -v 0.007574 -0.017331 0.080867 -vn 3.915262 -2.461669 -2.354314 -v 0.007522 -0.017418 0.080761 -vn 3.755844 2.540610 -2.500713 -v 0.007432 -0.017304 0.080626 -vn 3.686248 -2.427530 -2.647045 -v 0.007506 -0.017415 0.080733 -vn 3.110114 -2.678916 -3.320905 -v 0.007357 -0.017392 0.080543 -vn 3.319004 2.675180 -3.103549 -v 0.007357 -0.017293 0.080543 -vn 2.612839 -2.472215 -3.752359 -v 0.007279 -0.017382 0.080473 -vn 2.405175 2.617950 -3.812196 -v 0.007136 -0.017267 0.080376 -vn 2.001500 -2.605652 -4.092893 -v 0.007141 -0.017366 0.080379 -vn 1.341420 -2.581280 -4.374371 -v 0.006964 -0.017348 0.080301 -vn 1.546724 2.673315 -4.261403 -v 0.006918 -0.017244 0.080287 -vn 0.697611 -2.664837 -4.510953 -v 0.006889 -0.017340 0.080279 -vn 0.814770 2.535302 -4.483068 -v 0.006774 -0.017230 0.080258 -vn 3.323938 -2.666744 3.163332 -v 0.007357 -0.016943 0.081957 -vn 2.994548 2.646464 3.375105 -v 0.007357 -0.016843 0.081957 -vn 2.912333 -2.492575 3.525981 -v 0.007224 -0.016959 0.082069 -vn 2.155698 2.686358 4.025059 -v 0.007141 -0.016869 0.082121 -vn 2.451984 -2.674670 3.839544 -v 0.007167 -0.016966 0.082106 -vn 1.650382 2.518028 4.256035 -v 0.007098 -0.016874 0.082144 -vn 1.456055 -2.580931 4.263508 -v 0.006918 -0.016992 0.082213 -vn 0.818519 2.558328 4.459903 -v 0.006889 -0.016895 0.082221 -vn 0.324818 2.421674 4.528450 -v 0.006737 -0.016910 0.082246 -vn 3.649555 -2.594898 2.765676 -v 0.007388 -0.016938 0.081925 -vn 3.860738 -2.589713 2.441536 -v 0.007483 -0.016924 0.081803 -vn 3.693535 2.669571 2.630304 -v 0.007506 -0.016820 0.081767 -vn 4.168473 -2.657624 1.850457 -v 0.007521 -0.016917 0.081741 -vn 4.117618 2.311851 1.861855 -v 0.007573 -0.016806 0.081634 -vn 4.304374 2.545547 1.414068 -v 0.007613 -0.016794 0.081519 -vn 4.429245 -2.549733 0.813179 -v 0.007621 -0.016891 0.081489 -vn 4.504981 2.558778 0.261603 -v 0.007650 -0.016768 0.081250 -vn 4.501416 -2.561700 -0.250280 -v 0.007650 -0.016868 0.081250 -vn 4.519720 2.579009 -0.660807 -v 0.007621 -0.016745 0.081011 -vn 4.363582 -2.660396 -1.307335 -v 0.007613 -0.016842 0.080981 -vn 4.366756 2.685594 -1.333303 -v 0.007596 -0.016737 0.080925 -vn 4.141823 -2.641152 -1.949695 -v 0.007585 -0.016833 0.080895 -vn 4.082154 2.631128 -1.985584 -v 0.007521 -0.016719 0.080759 -vn 3.735946 -2.626106 -2.590199 -v 0.007506 -0.016816 0.080733 -vn 3.723404 2.632902 -2.647725 -v 0.007417 -0.016702 0.080608 -vn 3.312185 -2.690807 -3.169275 -v 0.007390 -0.016797 0.080577 -vn 3.259122 2.620155 -3.174861 -v 0.007357 -0.016693 0.080543 -vn 2.833791 -2.631189 -3.561895 -v 0.007357 -0.016793 0.080543 -vn 2.244718 -2.675674 -3.961112 -v 0.007141 -0.016767 0.080379 -vn 2.563037 2.551720 -3.693177 -v 0.007167 -0.016670 0.080394 -vn 1.714363 -2.561908 -4.245375 -v 0.007124 -0.016765 0.080369 -vn 1.468994 2.572861 -4.230902 -v 0.006918 -0.016644 0.080287 -vn 0.870251 -2.547751 -4.457637 -v 0.006889 -0.016741 0.080279 -vn 0.444006 -2.288873 -4.513016 -v 0.006774 -0.016730 0.080258 -vn 4.469018 2.481134 0.856802 -v 0.007635 -0.016185 0.081424 -vn 4.240752 2.656978 1.623869 -v 0.007613 -0.016195 0.081519 -vn 4.482232 -2.656689 0.750352 -v 0.007621 -0.016291 0.081489 -vn 0.142327 2.675614 4.586935 -v 0.006714 -0.016313 0.082248 -vn 0.755127 -2.645784 4.518183 -v 0.006737 -0.016410 0.082246 -vn 0.831696 2.617939 4.488848 -v 0.006889 -0.016296 0.082221 -vn 1.484807 -2.626136 4.297720 -v 0.006918 -0.016392 0.082213 -vn 1.548719 2.629479 4.304720 -v 0.007060 -0.016278 0.082162 -vn 2.182337 -2.687131 4.019533 -v 0.007098 -0.016373 0.082144 -vn 2.171229 2.658282 3.994285 -v 0.007141 -0.016270 0.082121 -vn 2.752152 -2.566095 3.630719 -v 0.007167 -0.016366 0.082106 -vn 3.228965 -2.630968 3.214985 -v 0.007357 -0.016343 0.081957 -vn 2.946298 2.623651 3.366940 -v 0.007357 -0.016244 0.081957 -vn 3.658310 -2.603434 2.711276 -v 0.007388 -0.016339 0.081925 -vn 3.682684 2.598398 2.527382 -v 0.007506 -0.016221 0.081767 -vn 4.055328 -2.560664 2.026662 -v 0.007521 -0.016317 0.081741 -vn 4.237758 -2.289347 1.609491 -v 0.007573 -0.016305 0.081634 -vn 4.531674 2.581862 0.277620 -v 0.007650 -0.016169 0.081250 -vn 4.507818 -2.582037 -0.230532 -v 0.007650 -0.016268 0.081250 -vn 4.556770 2.506737 -0.461361 -v 0.007632 -0.016151 0.081062 -vn 4.374630 -2.673498 -1.329269 -v 0.007613 -0.016242 0.080981 -vn 4.461477 2.680202 -0.994092 -v 0.007621 -0.016146 0.081011 -vn 4.176403 -2.497357 -1.865706 -v 0.007596 -0.016236 0.080925 -vn 4.054230 2.603326 -1.979879 -v 0.007521 -0.016120 0.080759 -vn 3.762830 -2.597140 -2.558312 -v 0.007506 -0.016216 0.080733 -vn 3.416317 -2.495326 -3.031854 -v 0.007417 -0.016201 0.080608 -vn 3.467469 2.666162 -2.936742 -v 0.007357 -0.016094 0.080543 -vn 2.909477 -2.668030 -3.493602 -v 0.007357 -0.016193 0.080543 -vn 0.603392 -2.592826 -4.539754 -v 0.006889 -0.016141 0.080279 -vn 1.263292 2.678036 -4.390113 -v 0.006918 -0.016045 0.080287 -vn 1.172863 -2.708192 -4.409695 -v 0.006918 -0.016144 0.080287 -vn 1.841505 2.593255 -4.194817 -v 0.006959 -0.016049 0.080299 -vn 1.986881 -2.587043 -4.025669 -v 0.007141 -0.016167 0.080379 -vn 2.563931 2.551658 -3.753616 -v 0.007167 -0.016071 0.080394 -vn 2.912669 2.333229 -3.484167 -v 0.007275 -0.016083 0.080469 -vn 1.855011 2.665882 4.175675 -v 0.007141 -0.015670 0.082121 -vn 1.040369 2.657716 4.446997 -v 0.006889 -0.015696 0.082221 -vn 1.507911 -2.567927 4.305133 -v 0.006918 -0.015791 0.082213 -vn 0.511812 2.596520 4.549223 -v 0.006846 -0.015700 0.082231 -vn 0.672133 -2.611954 4.526256 -v 0.006714 -0.015811 0.082248 -vn 1.955770 -2.389506 4.111008 -v 0.007059 -0.015777 0.082162 -vn 2.663929 -2.665528 3.696531 -v 0.007167 -0.015765 0.082106 -vn 2.445805 2.599686 3.848167 -v 0.007198 -0.015663 0.082086 -vn 3.273653 -2.654690 3.202522 -v 0.007357 -0.015742 0.081957 -vn 2.960348 2.647445 3.443959 -v 0.007357 -0.015644 0.081957 -vn 3.648457 -2.661030 2.756757 -v 0.007388 -0.015738 0.081925 -vn 3.509763 2.554864 2.923796 -v 0.007457 -0.015629 0.081841 -vn 4.094253 -2.574317 1.917513 -v 0.007521 -0.015716 0.081741 -vn 3.836419 2.629796 2.448035 -v 0.007506 -0.015621 0.081767 -vn 4.255730 2.571994 1.520229 -v 0.007613 -0.015595 0.081519 -vn 4.444199 -2.644632 1.008417 -v 0.007621 -0.015690 0.081489 -vn 4.550454 -2.493254 0.436622 -v 0.007635 -0.015684 0.081424 -vn 4.537454 2.629203 0.354981 -v 0.007650 -0.015569 0.081250 -vn 4.529766 -2.637410 -0.254876 -v 0.007650 -0.015667 0.081250 -vn 4.567443 2.624565 -0.309965 -v 0.007641 -0.015556 0.081119 -vn 4.450366 -2.689610 -1.009861 -v 0.007632 -0.015649 0.081062 -vn 4.435363 2.663923 -0.983171 -v 0.007621 -0.015546 0.081011 -vn 4.224487 -2.589108 -1.672922 -v 0.007613 -0.015641 0.080981 -vn 4.060314 2.543348 -1.964728 -v 0.007521 -0.015520 0.080759 -vn 3.716464 -2.550844 -2.542557 -v 0.007506 -0.015615 0.080733 -vn 3.502075 2.612414 -2.917046 -v 0.007357 -0.015494 0.080543 -vn 3.133251 -2.618895 -3.292152 -v 0.007357 -0.015592 0.080543 -vn 3.042013 2.666182 -3.416905 -v 0.007279 -0.015484 0.080473 -vn 2.620064 -2.663291 -3.743753 -v 0.007275 -0.015582 0.080469 -vn 2.511253 2.635382 -3.783599 -v 0.007167 -0.015470 0.080394 -vn 1.936762 -2.604764 -4.110099 -v 0.007141 -0.015566 0.080379 -vn 1.844497 2.657898 -4.181894 -v 0.006964 -0.015449 0.080301 -vn 1.312495 -2.667064 -4.370842 -v 0.006959 -0.015547 0.080299 -vn 1.373300 2.693749 -4.379632 -v 0.006918 -0.015444 0.080287 -vn 0.662812 -2.665664 -4.492105 -v 0.006889 -0.015540 0.080279 -vn 0.776181 2.533177 -4.502342 -v 0.006754 -0.015428 0.080255 -vn 0.269909 2.600971 4.575940 -v 0.006766 -0.015107 0.082243 -vn 1.044340 -2.680459 4.457325 -v 0.006846 -0.015198 0.082231 -vn 0.863572 2.680615 4.501691 -v 0.006887 -0.015096 0.082222 -vn 1.630669 -2.663180 4.251033 -v 0.006918 -0.015191 0.082213 -vn 1.564189 2.470987 4.274393 -v 0.007033 -0.015081 0.082174 -vn 2.526765 -2.566112 3.736944 -v 0.007167 -0.015165 0.082106 -vn 2.312202 2.615529 3.946782 -v 0.007224 -0.015060 0.082069 -vn 2.762177 2.273163 3.599083 -v 0.007256 -0.015056 0.082046 -vn 3.553794 2.651835 2.848540 -v 0.007448 -0.015030 0.081852 -vn 4.109910 -2.453674 1.909516 -v 0.007521 -0.015116 0.081741 -vn 4.071808 2.482863 1.949501 -v 0.007584 -0.015003 0.081607 -vn 4.444137 -2.654650 0.849703 -v 0.007621 -0.015090 0.081489 -vn 4.359867 2.656669 1.359010 -v 0.007620 -0.014992 0.081494 -vn 3.138715 2.575851 3.327382 -v 0.007388 -0.015039 0.081925 -vn 3.250489 -2.482467 3.150644 -v 0.007357 -0.015142 0.081957 -vn 3.823502 -2.645359 2.515830 -v 0.007457 -0.015128 0.081841 -vn 4.511496 2.531606 0.775312 -v 0.007644 -0.014978 0.081356 -vn 4.554649 -2.647014 -0.207228 -v 0.007650 -0.015067 0.081250 -vn 4.556277 2.662085 0.219340 -v 0.007650 -0.014969 0.081258 -vn 4.552288 2.646925 -0.393047 -v 0.007638 -0.014954 0.081095 -vn 4.501163 -2.626682 -0.824429 -v 0.007641 -0.015055 0.081119 -vn 4.496912 2.655470 -0.912095 -v 0.007620 -0.014945 0.081006 -vn 4.281950 -2.651935 -1.542043 -v 0.007613 -0.015041 0.080981 -vn 4.226058 2.550608 -1.583721 -v 0.007574 -0.014931 0.080867 -vn 3.915262 -2.461675 -2.354294 -v 0.007522 -0.015018 0.080761 -vn 3.755843 2.540606 -2.500714 -v 0.007432 -0.014904 0.080626 -vn 3.686231 -2.427532 -2.647055 -v 0.007506 -0.015015 0.080733 -vn 3.110176 -2.678892 -3.320925 -v 0.007357 -0.014992 0.080543 -vn 3.319019 2.675176 -3.103545 -v 0.007357 -0.014893 0.080543 -vn 2.612857 -2.472233 -3.752316 -v 0.007279 -0.014982 0.080473 -vn 2.405156 2.617968 -3.812162 -v 0.007136 -0.014867 0.080376 -vn 2.001500 -2.605653 -4.092893 -v 0.007141 -0.014966 0.080379 -vn 1.341410 -2.581286 -4.374364 -v 0.006964 -0.014948 0.080301 -vn 1.546709 2.673313 -4.261416 -v 0.006918 -0.014844 0.080287 -vn 0.697614 -2.664843 -4.510944 -v 0.006889 -0.014940 0.080279 -vn 0.814770 2.535302 -4.483068 -v 0.006774 -0.014830 0.080258 -vn 3.323971 -2.666773 3.163192 -v 0.007357 -0.014543 0.081957 -vn 2.994547 2.646466 3.375106 -v 0.007357 -0.014443 0.081957 -vn 2.912333 -2.492575 3.525981 -v 0.007224 -0.014559 0.082069 -vn 2.155698 2.686358 4.025059 -v 0.007141 -0.014469 0.082121 -vn 2.451976 -2.674675 3.839540 -v 0.007167 -0.014566 0.082106 -vn 1.650382 2.518028 4.256035 -v 0.007098 -0.014474 0.082144 -vn 1.456058 -2.580934 4.263498 -v 0.006918 -0.014592 0.082213 -vn 0.818550 2.558323 4.459911 -v 0.006889 -0.014495 0.082221 -vn 0.324775 2.421722 4.528390 -v 0.006737 -0.014510 0.082246 -vn 3.649671 -2.594852 2.765648 -v 0.007388 -0.014538 0.081925 -vn 3.860746 -2.589686 2.441631 -v 0.007483 -0.014524 0.081803 -vn 3.693536 2.669572 2.630303 -v 0.007506 -0.014420 0.081767 -vn 4.168413 -2.657649 1.850476 -v 0.007521 -0.014517 0.081741 -vn 4.117623 2.311846 1.861863 -v 0.007573 -0.014406 0.081634 -vn 4.304389 2.545538 1.414073 -v 0.007613 -0.014394 0.081519 -vn 4.429279 -2.549717 0.813189 -v 0.007621 -0.014491 0.081489 -vn 4.504991 2.558774 0.261598 -v 0.007650 -0.014368 0.081250 -vn 4.501406 -2.561706 -0.250264 -v 0.007650 -0.014468 0.081250 -vn 4.519720 2.579009 -0.660807 -v 0.007621 -0.014345 0.081011 -vn 4.363582 -2.660396 -1.307335 -v 0.007613 -0.014442 0.080981 -vn 4.366756 2.685594 -1.333303 -v 0.007596 -0.014337 0.080925 -vn 4.141823 -2.641152 -1.949695 -v 0.007585 -0.014433 0.080895 -vn 4.082154 2.631128 -1.985584 -v 0.007521 -0.014319 0.080759 -vn 3.735946 -2.626106 -2.590199 -v 0.007506 -0.014416 0.080733 -vn 3.723404 2.632902 -2.647725 -v 0.007417 -0.014302 0.080608 -vn 3.312185 -2.690807 -3.169275 -v 0.007390 -0.014397 0.080577 -vn 3.259122 2.620155 -3.174861 -v 0.007357 -0.014293 0.080543 -vn 2.833791 -2.631189 -3.561895 -v 0.007357 -0.014393 0.080543 -vn 2.244718 -2.675674 -3.961112 -v 0.007141 -0.014367 0.080379 -vn 2.563037 2.551720 -3.693177 -v 0.007167 -0.014270 0.080394 -vn 1.714363 -2.561908 -4.245375 -v 0.007124 -0.014365 0.080369 -vn 1.468994 2.572860 -4.230904 -v 0.006918 -0.014244 0.080287 -vn 0.870251 -2.547751 -4.457637 -v 0.006889 -0.014341 0.080279 -vn 0.444006 -2.288873 -4.513016 -v 0.006774 -0.014330 0.080258 -vn 4.469013 2.481136 0.856802 -v 0.007635 -0.013785 0.081424 -vn 4.240751 2.656979 1.623867 -v 0.007613 -0.013795 0.081519 -vn 4.482216 -2.656697 0.750347 -v 0.007621 -0.013891 0.081489 -vn 0.142327 2.675614 4.586935 -v 0.006714 -0.013913 0.082248 -vn 0.755127 -2.645784 4.518183 -v 0.006737 -0.014010 0.082246 -vn 0.831696 2.617939 4.488848 -v 0.006889 -0.013896 0.082221 -vn 1.484807 -2.626136 4.297720 -v 0.006918 -0.013992 0.082213 -vn 1.548719 2.629479 4.304720 -v 0.007060 -0.013878 0.082162 -vn 2.182337 -2.687131 4.019533 -v 0.007098 -0.013973 0.082144 -vn 2.171230 2.658283 3.994284 -v 0.007141 -0.013870 0.082121 -vn 2.752152 -2.566095 3.630719 -v 0.007167 -0.013966 0.082106 -vn 3.228965 -2.630968 3.214985 -v 0.007357 -0.013943 0.081957 -vn 2.946296 2.623652 3.366939 -v 0.007357 -0.013844 0.081957 -vn 3.658310 -2.603434 2.711276 -v 0.007388 -0.013939 0.081925 -vn 3.682682 2.598396 2.527381 -v 0.007506 -0.013821 0.081767 -vn 4.055328 -2.560664 2.026662 -v 0.007521 -0.013917 0.081741 -vn 4.237751 -2.289351 1.609482 -v 0.007573 -0.013905 0.081634 -vn 4.531670 2.581864 0.277620 -v 0.007650 -0.013769 0.081250 -vn 4.507802 -2.582045 -0.230532 -v 0.007650 -0.013868 0.081250 -vn 4.556766 2.506739 -0.461360 -v 0.007632 -0.013751 0.081062 -vn 4.374626 -2.673501 -1.329263 -v 0.007613 -0.013842 0.080981 -vn 4.461474 2.680203 -0.994090 -v 0.007621 -0.013746 0.081011 -vn 4.176403 -2.497357 -1.865706 -v 0.007596 -0.013836 0.080925 -vn 4.054227 2.603326 -1.979879 -v 0.007521 -0.013720 0.080759 -vn 3.762830 -2.597140 -2.558312 -v 0.007506 -0.013816 0.080733 -vn 3.416254 -2.495338 -3.031876 -v 0.007417 -0.013801 0.080608 -vn 3.467462 2.666166 -2.936738 -v 0.007357 -0.013694 0.080543 -vn 2.909491 -2.668003 -3.493661 -v 0.007357 -0.013793 0.080543 -vn 0.603395 -2.592832 -4.539744 -v 0.006889 -0.013741 0.080279 -vn 1.263293 2.678035 -4.390113 -v 0.006918 -0.013645 0.080287 -vn 1.172857 -2.708200 -4.409679 -v 0.006918 -0.013744 0.080287 -vn 1.841505 2.593255 -4.194817 -v 0.006959 -0.013649 0.080299 -vn 1.986881 -2.587052 -4.025649 -v 0.007141 -0.013767 0.080379 -vn 2.563932 2.551661 -3.753606 -v 0.007167 -0.013671 0.080394 -vn 2.912658 2.333221 -3.484158 -v 0.007275 -0.013683 0.080469 -vn 1.908515 2.660348 4.107096 -v 0.007141 -0.013270 0.082121 -vn 1.195834 2.664566 4.401480 -v 0.006912 -0.013293 0.082215 -vn 1.476597 -2.593812 4.314652 -v 0.006918 -0.013391 0.082213 -vn 0.633533 2.636557 4.539822 -v 0.006889 -0.013296 0.082221 -vn 0.694310 -2.567674 4.521539 -v 0.006714 -0.013411 0.082248 -vn 1.955797 -2.389514 4.110968 -v 0.007059 -0.013377 0.082162 -vn 2.655046 -2.653965 3.703129 -v 0.007167 -0.013365 0.082106 -vn 2.593700 2.532282 3.747537 -v 0.007265 -0.013255 0.082039 -vn 3.302745 -2.689599 3.178121 -v 0.007357 -0.013342 0.081957 -vn 3.090097 2.666902 3.335707 -v 0.007357 -0.013244 0.081957 -vn 3.670704 -2.593769 2.725648 -v 0.007388 -0.013338 0.081925 -vn 3.652328 2.622723 2.761443 -v 0.007506 -0.013221 0.081767 -vn 4.073884 -2.612211 1.955298 -v 0.007521 -0.013316 0.081741 -vn 3.983702 2.637642 2.255989 -v 0.007522 -0.013217 0.081739 -vn 4.271663 2.563247 1.576986 -v 0.007613 -0.013195 0.081519 -vn 4.447126 -2.623439 0.992439 -v 0.007621 -0.013290 0.081489 -vn 4.501547 2.553493 0.732934 -v 0.007644 -0.013179 0.081363 -vn 4.547900 -2.596925 0.488886 -v 0.007635 -0.013284 0.081424 -vn 4.539332 2.589742 0.141284 -v 0.007650 -0.013169 0.081250 -vn 4.525035 -2.590351 -0.304059 -v 0.007650 -0.013267 0.081250 -vn 4.528509 2.676668 -0.649677 -v 0.007621 -0.013146 0.081011 -vn 4.456733 -2.525362 -0.900302 -v 0.007632 -0.013249 0.081062 -vn 4.230526 -2.648725 -1.660356 -v 0.007613 -0.013241 0.080981 -vn 4.394994 2.607783 -1.269320 -v 0.007610 -0.013141 0.080969 -vn 3.752554 -2.615360 -2.493051 -v 0.007506 -0.013215 0.080733 -vn 0.757711 2.539005 -4.504768 -v 0.006745 -0.013028 0.080254 -vn 0.659680 -2.660382 -4.492573 -v 0.006889 -0.013140 0.080279 -vn 1.504108 2.667817 -4.276062 -v 0.006918 -0.013044 0.080287 -vn 1.320118 -2.610754 -4.366447 -v 0.006959 -0.013147 0.080299 -vn 2.214185 2.651296 -3.990154 -v 0.007122 -0.013066 0.080368 -vn 1.959235 -2.664458 -4.100529 -v 0.007141 -0.013166 0.080379 -vn 2.720653 2.662769 -3.672194 -v 0.007167 -0.013070 0.080394 -vn 2.621109 -2.532546 -3.735118 -v 0.007275 -0.013182 0.080469 -vn 3.333034 2.677394 -3.100053 -v 0.007357 -0.013094 0.080543 -vn 3.090341 -2.674685 -3.343608 -v 0.007357 -0.013192 0.080543 -vn 3.730679 2.534189 -2.633096 -v 0.007427 -0.013104 0.080620 -vn 4.133117 2.548250 -1.907153 -v 0.007521 -0.013120 0.080759 -vn 0.330854 2.607390 4.531984 -v 0.006766 -0.012707 0.082243 -vn 1.077607 -2.572646 4.436634 -v 0.006846 -0.012798 0.082231 -vn 1.258611 2.496408 4.372103 -v 0.006984 -0.012686 0.082192 -vn 3.342053 -2.668695 3.067755 -v 0.007357 -0.012742 0.081957 -vn 2.844858 2.584285 3.599856 -v 0.007323 -0.012648 0.081990 -vn 2.520264 -2.497879 3.744394 -v 0.007167 -0.012765 0.082106 -vn 2.514919 2.416141 3.774911 -v 0.007256 -0.012656 0.082046 -vn 1.564444 -2.560465 4.281546 -v 0.006918 -0.012791 0.082213 -vn 1.584884 2.296438 4.251198 -v 0.007033 -0.012681 0.082174 -vn 4.446296 -2.653821 0.837884 -v 0.007621 -0.012690 0.081489 -vn 4.187051 2.472897 1.858590 -v 0.007584 -0.012603 0.081607 -vn 4.079764 -2.480772 1.987928 -v 0.007521 -0.012716 0.081741 -vn 3.994628 2.543661 2.207235 -v 0.007557 -0.012610 0.081671 -vn 3.831978 -2.613959 2.486179 -v 0.007457 -0.012728 0.081841 -vn 3.558484 2.620529 2.877757 -v 0.007448 -0.012630 0.081852 -vn 3.237544 2.628966 3.248728 -v 0.007388 -0.012639 0.081925 -vn 4.538682 -2.628335 -0.219235 -v 0.007650 -0.012667 0.081250 -vn 4.502599 2.534726 0.807449 -v 0.007644 -0.012578 0.081356 -vn 4.372384 2.654733 1.341249 -v 0.007620 -0.012592 0.081494 -vn 3.702516 -2.422276 -2.645350 -v 0.007506 -0.012615 0.080733 -vn 3.097123 -2.686421 -3.336980 -v 0.007357 -0.012592 0.080543 -vn 3.778510 2.536696 -2.487110 -v 0.007432 -0.012504 0.080626 -vn 3.917681 -2.458529 -2.360995 -v 0.007522 -0.012618 0.080761 -vn 4.222556 2.552809 -1.666878 -v 0.007574 -0.012531 0.080867 -vn 4.294159 -2.661873 -1.533341 -v 0.007613 -0.012641 0.080981 -vn 4.394428 2.578542 -1.350838 -v 0.007586 -0.012534 0.080898 -vn 4.516032 2.660134 -0.880008 -v 0.007620 -0.012545 0.081006 -vn 4.493102 -2.631943 -0.816947 -v 0.007641 -0.012655 0.081119 -vn 4.544357 2.648439 -0.370593 -v 0.007638 -0.012554 0.081095 -vn 4.553971 2.658522 0.324687 -v 0.007649 -0.012572 0.081288 -vn 0.362117 -2.446911 -4.537885 -v 0.006754 -0.012527 0.080255 -vn 0.512607 2.596730 -4.537396 -v 0.006669 -0.012420 0.080250 -vn 0.707448 -2.598233 -4.524626 -v 0.006889 -0.012540 0.080279 -vn 1.369729 2.665774 -4.320190 -v 0.006918 -0.012444 0.080287 -vn 1.293109 -2.659290 -4.401619 -v 0.006964 -0.012548 0.080301 -vn 2.040581 2.607155 -4.098910 -v 0.007054 -0.012458 0.080335 -vn 2.028706 -2.633650 -4.082520 -v 0.007141 -0.012566 0.080379 -vn 2.552406 2.646870 -3.779349 -v 0.007136 -0.012467 0.080376 -vn 2.612238 -2.477666 -3.741015 -v 0.007279 -0.012582 0.080473 -vn 3.272974 2.705971 -3.191242 -v 0.007357 -0.012493 0.080543 -vn 3.570529 2.684647 -2.913409 -v 0.007377 -0.012496 0.080563 -vn 0.099228 2.611810 4.569487 -v 0.006669 -0.012116 0.082250 -vn 1.414542 -2.612673 4.269902 -v 0.006918 -0.012192 0.082213 -vn 0.731199 2.560094 4.477635 -v 0.006889 -0.012095 0.082221 -vn 1.565913 2.476334 4.280194 -v 0.007054 -0.012078 0.082165 -vn 2.463333 -2.670704 3.839599 -v 0.007167 -0.012166 0.082106 -vn 2.092774 2.655997 4.039104 -v 0.007141 -0.012069 0.082121 -vn 2.912321 -2.492639 3.525931 -v 0.007224 -0.012159 0.082069 -vn 2.884336 2.673042 3.553192 -v 0.007357 -0.012043 0.081957 -vn 3.324141 -2.666538 3.172320 -v 0.007357 -0.012143 0.081957 -vn 3.282956 2.689446 3.178059 -v 0.007377 -0.012040 0.081937 -vn 3.652447 -2.643912 2.772548 -v 0.007388 -0.012138 0.081925 -vn 3.715732 2.662856 2.592356 -v 0.007506 -0.012020 0.081767 -vn 4.444472 -2.577274 0.770454 -v 0.007621 -0.012091 0.081489 -vn 4.141185 2.480218 1.904505 -v 0.007586 -0.012002 0.081602 -vn 4.169148 -2.643263 1.856069 -v 0.007521 -0.012117 0.081741 -vn 3.862382 -2.592447 2.439679 -v 0.007483 -0.012124 0.081803 -vn 4.500010 -2.597919 -0.229978 -v 0.007650 -0.012068 0.081250 -vn 4.547138 2.640723 0.490719 -v 0.007650 -0.011968 0.081250 -vn 4.351039 2.631049 1.326524 -v 0.007613 -0.011994 0.081519 -vn 1.993596 -2.601573 -4.018831 -v 0.007141 -0.011967 0.080379 -vn 1.707994 2.117936 -4.165895 -v 0.006984 -0.011851 0.080308 -vn 2.607995 2.558521 -3.717756 -v 0.007167 -0.011870 0.080394 -vn 2.859272 -2.686730 -3.533480 -v 0.007357 -0.011993 0.080543 -vn 3.091518 2.539035 -3.364173 -v 0.007323 -0.011889 0.080510 -vn 3.439202 2.722386 -3.064852 -v 0.007357 -0.011893 0.080543 -vn 3.326240 -2.661773 -3.129958 -v 0.007390 -0.011997 0.080577 -vn 3.647495 2.664639 -2.752020 -v 0.007388 -0.011898 0.080575 -vn 3.712410 -2.599834 -2.608896 -v 0.007506 -0.012016 0.080733 -vn 4.050824 2.617601 -2.098104 -v 0.007521 -0.011919 0.080759 -vn 4.164086 -2.545585 -1.860691 -v 0.007585 -0.012033 0.080895 -vn 4.247861 2.562096 -1.647580 -v 0.007557 -0.011927 0.080829 -vn 4.340818 -2.600049 -1.351880 -v 0.007613 -0.012042 0.080981 -vn 4.461511 2.567964 -0.760931 -v 0.007621 -0.011945 0.081011 -vn 4.557389 2.573179 -0.165531 -v 0.007649 -0.011965 0.081212 -vn 1.365659 2.547755 -4.326974 -v 0.006918 -0.011844 0.080287 -vn 0.887390 -2.545130 -4.445813 -v 0.006889 -0.011941 0.080279 -vn 0.444380 -2.290413 -4.510006 -v 0.006774 -0.011930 0.080258 -vn 0.254063 2.654991 4.566298 -v 0.006745 -0.011510 0.082245 -vn 0.735071 -2.655118 4.519865 -v 0.006737 -0.011610 0.082246 -vn 0.899864 2.612404 4.445846 -v 0.006889 -0.011496 0.082221 -vn 1.521029 -2.579950 4.279939 -v 0.006918 -0.011592 0.082213 -vn 1.738090 2.668458 4.235817 -v 0.007122 -0.011472 0.082132 -vn 2.113643 -2.599102 4.046728 -v 0.007098 -0.011573 0.082144 -vn 2.239258 2.664671 3.986491 -v 0.007141 -0.011470 0.082121 -vn 2.755761 -2.570763 3.614013 -v 0.007167 -0.011566 0.082106 -vn 3.213438 -2.637729 3.213955 -v 0.007357 -0.011543 0.081957 -vn 2.894695 2.615190 3.523156 -v 0.007357 -0.011444 0.081957 -vn 3.648723 -2.674641 2.767870 -v 0.007388 -0.011539 0.081925 -vn 3.462479 2.540812 2.991453 -v 0.007427 -0.011434 0.081880 -vn 3.791195 2.573272 2.515890 -v 0.007506 -0.011421 0.081767 -vn 4.073504 -2.562141 2.019423 -v 0.007521 -0.011517 0.081741 -vn 4.240628 2.656887 1.735083 -v 0.007610 -0.011396 0.081530 -vn 4.239196 -2.358588 1.602291 -v 0.007573 -0.011505 0.081634 -vn 4.479390 -2.579673 0.696544 -v 0.007621 -0.011491 0.081489 -vn 4.467990 2.568720 -0.848745 -v 0.007621 -0.011346 0.081011 -vn 4.526994 2.320949 -0.407952 -v 0.007644 -0.011358 0.081136 -vn 4.498873 -2.606142 -0.218226 -v 0.007650 -0.011468 0.081250 -vn 4.526014 2.613581 0.411087 -v 0.007650 -0.011369 0.081250 -vn 4.401320 2.682047 1.233861 -v 0.007613 -0.011395 0.081519 -vn 4.372134 -2.648654 -1.295585 -v 0.007613 -0.011442 0.080981 -vn 4.163886 -2.504144 -1.861364 -v 0.007596 -0.011436 0.080925 -vn 4.025997 2.593752 -2.002206 -v 0.007521 -0.011320 0.080759 -vn 3.691034 -2.560959 -2.611448 -v 0.007506 -0.011416 0.080733 -vn 3.479311 2.615355 -2.899430 -v 0.007357 -0.011294 0.080543 -vn 3.123960 -2.610647 -3.297321 -v 0.007357 -0.011393 0.080543 -vn 3.014287 2.664248 -3.444623 -v 0.007265 -0.011282 0.080461 -vn 2.570432 -2.661351 -3.789285 -v 0.007256 -0.011380 0.080455 -vn 2.456643 2.636654 -3.818995 -v 0.007167 -0.011271 0.080394 -vn 1.871957 -2.574739 -4.140011 -v 0.007141 -0.011367 0.080379 -vn 1.446608 2.603838 -4.257717 -v 0.006918 -0.011245 0.080287 -vn 0.605007 -2.592072 -4.541201 -v 0.006889 -0.011341 0.080279 -vn 1.213458 -2.649241 -4.403351 -v 0.006918 -0.011344 0.080287 -vn 0.692117 -2.571468 4.516506 -v 0.006714 -0.011011 0.082248 -vn 0.731179 2.620287 4.481011 -v 0.006889 -0.010895 0.082221 -vn 1.424447 -2.647266 4.318535 -v 0.006918 -0.010991 0.082213 -vn 1.448611 2.653256 4.344186 -v 0.007024 -0.010881 0.082177 -vn 2.078534 -2.671454 4.064508 -v 0.007059 -0.010977 0.082162 -vn 2.144243 2.631779 4.010230 -v 0.007141 -0.010869 0.082121 -vn 2.711056 -2.562771 3.633881 -v 0.007167 -0.010965 0.082106 -vn 3.218083 -2.634539 3.218075 -v 0.007357 -0.010942 0.081957 -vn 2.956837 2.601058 3.413929 -v 0.007357 -0.010843 0.081957 -vn 3.668252 -2.591809 2.740399 -v 0.007388 -0.010938 0.081925 -vn 3.680011 2.608675 2.692562 -v 0.007506 -0.010820 0.081767 -vn 4.074688 -2.636425 1.977226 -v 0.007521 -0.010916 0.081741 -vn 4.092940 2.439185 2.002084 -v 0.007556 -0.010810 0.081672 -vn 4.291418 2.573775 1.506907 -v 0.007613 -0.010794 0.081519 -vn 4.455063 -2.638343 1.020266 -v 0.007621 -0.010890 0.081489 -vn 4.563493 -2.577611 0.465185 -v 0.007635 -0.010884 0.081424 -vn 4.513773 2.639022 0.670524 -v 0.007648 -0.010774 0.081313 -vn 4.541569 -2.622651 -0.331760 -v 0.007650 -0.010867 0.081250 -vn 4.555392 2.637545 0.054446 -v 0.007650 -0.010768 0.081250 -vn 4.420586 2.637596 -0.857871 -v 0.007621 -0.010745 0.081011 -vn 4.469513 -2.518373 -0.910317 -v 0.007632 -0.010849 0.081062 -vn 4.227976 -2.587962 -1.672998 -v 0.007613 -0.010841 0.080981 -vn 4.021943 2.563019 -1.956161 -v 0.007521 -0.010719 0.080759 -vn 3.720455 -2.548774 -2.544815 -v 0.007506 -0.010815 0.080733 -vn 3.402674 2.629840 -2.929970 -v 0.007357 -0.010693 0.080543 -vn 3.131303 -2.616700 -3.293885 -v 0.007357 -0.010792 0.080543 -vn 2.621276 -2.533413 -3.735748 -v 0.007275 -0.010782 0.080469 -vn 2.719507 2.665896 -3.664104 -v 0.007167 -0.010670 0.080394 -vn 1.959769 -2.665119 -4.100151 -v 0.007141 -0.010766 0.080379 -vn 2.222636 2.644859 -3.995953 -v 0.007121 -0.010665 0.080368 -vn 1.321070 -2.611428 -4.368225 -v 0.006959 -0.010747 0.080299 -vn 1.519909 2.667814 -4.287873 -v 0.006918 -0.010644 0.080287 -vn 0.700923 -2.657576 -4.522111 -v 0.006889 -0.010740 0.080279 -vn 0.807131 2.528414 -4.498806 -v 0.006767 -0.010629 0.080257 -vn 3.304654 2.696483 3.175439 -v 0.007391 -0.010238 0.081922 -vn 2.850101 2.627548 3.559320 -v 0.007357 -0.010243 0.081957 -vn 3.237854 -2.623454 3.223808 -v 0.007357 -0.010342 0.081957 -vn 2.199682 2.649039 3.985625 -v 0.007141 -0.010269 0.082121 -vn 2.605186 -2.553737 3.687573 -v 0.007167 -0.010365 0.082106 -vn 1.647682 2.511088 4.260965 -v 0.007095 -0.010274 0.082146 -vn 1.424310 -2.599045 4.244396 -v 0.006918 -0.010392 0.082213 -vn 0.825385 2.551393 4.475871 -v 0.006889 -0.010295 0.082221 -vn 0.317524 2.418256 4.547898 -v 0.006736 -0.010310 0.082246 -vn 3.609425 -2.697958 2.848844 -v 0.007388 -0.010338 0.081925 -vn 3.829443 -2.610994 2.496230 -v 0.007456 -0.010328 0.081842 -vn 3.750584 2.659801 2.579740 -v 0.007506 -0.010220 0.081767 -vn 4.132450 -2.641648 1.897487 -v 0.007521 -0.010316 0.081741 -vn 4.140612 2.469779 1.927526 -v 0.007583 -0.010203 0.081611 -vn 4.457897 -2.568874 0.783322 -v 0.007621 -0.010290 0.081489 -vn 4.354574 2.622211 1.328925 -v 0.007613 -0.010194 0.081519 -vn 4.492045 2.625371 0.315353 -v 0.007650 -0.010168 0.081250 -vn 0.188452 -2.669597 -4.571764 -v 0.006725 -0.010124 0.080253 -vn 0.729004 2.661026 -4.510804 -v 0.006733 -0.010026 0.080253 -vn 0.820782 -2.622703 -4.480868 -v 0.006889 -0.010140 0.080279 -vn 1.442655 2.629497 -4.325777 -v 0.006918 -0.010044 0.080287 -vn 1.560539 -2.650015 -4.304623 -v 0.007054 -0.010157 0.080335 -vn 2.004483 2.648761 -4.102537 -v 0.007042 -0.010056 0.080330 -vn 2.145514 -2.630460 -4.020222 -v 0.007141 -0.010166 0.080379 -vn 2.677799 2.578354 -3.659178 -v 0.007167 -0.010070 0.080394 -vn 3.005694 -2.560398 -3.361871 -v 0.007357 -0.010192 0.080543 -vn 3.354403 2.564173 -3.003928 -v 0.007357 -0.010093 0.080543 -vn 3.644910 -2.587257 -2.743583 -v 0.007506 -0.010215 0.080733 -vn 4.004655 2.668451 -2.154948 -v 0.007521 -0.010119 0.080759 -vn 4.015768 -2.685794 -2.206566 -v 0.007541 -0.010222 0.080797 -vn 4.301150 2.622437 -1.547301 -v 0.007562 -0.010128 0.080840 -vn 4.305079 -2.624298 -1.492397 -v 0.007613 -0.010241 0.080982 -vn 4.462052 2.633846 -0.772484 -v 0.007621 -0.010145 0.081011 -vn 4.511010 -2.533042 -0.769499 -v 0.007645 -0.010258 0.081153 -vn 4.568345 -2.621295 -0.086230 -v 0.007650 -0.010267 0.081250 -vn -0.101510 1.668282 5.707357 -v 0.006650 -0.041610 0.083125 -vn -1.145246 0.230702 6.124729 -v 0.006331 -0.041610 0.083098 -vn -1.965992 1.318322 5.577381 -v 0.005932 -0.041610 0.082982 -vn -3.042124 0.236777 5.447298 -v 0.005824 -0.041610 0.082933 -vn -3.946221 0.251655 4.837462 -v 0.005383 -0.041610 0.082632 -vn -4.521166 1.210154 3.903391 -v 0.005324 -0.041610 0.082576 -vn -5.245251 0.263750 3.354750 -v 0.005045 -0.041610 0.082219 -vn -5.234118 1.704500 2.206296 -v 0.004918 -0.041610 0.081968 -vn -6.070872 0.236572 1.405555 -v 0.004837 -0.041610 0.081728 -vn -6.117789 0.793766 0.449499 -v 0.004775 -0.041610 0.081250 -vn -6.112485 -0.829715 -0.325930 -v 0.004775 -0.042410 0.081250 -vn -5.923253 -0.818655 -1.410975 -v 0.004831 -0.042410 0.080794 -vn -5.583294 -1.154761 -2.182380 -v 0.004918 -0.042410 0.080532 -vn -5.187769 -0.768563 -3.235268 -v 0.005034 -0.042410 0.080300 -vn -4.566033 -0.823123 -4.083279 -v 0.005324 -0.042410 0.079924 -vn -3.920013 -0.779001 -4.716769 -v 0.005367 -0.042410 0.079883 -vn -3.031531 -0.762695 -5.319023 -v 0.005804 -0.042410 0.079577 -vn -0.208656 -1.046836 -6.038562 -v 0.006650 -0.042410 0.079375 -vn -1.102698 -0.797295 -5.994443 -v 0.006310 -0.042410 0.079406 -vn -2.123290 -0.868457 -5.723106 -v 0.005932 -0.042410 0.079518 -vn 0.214287 2.575835 4.560702 -v 0.006733 -0.009710 0.082247 -vn 1.124791 -2.431721 4.428256 -v 0.006861 -0.009796 0.082227 -vn 1.834552 1.962577 4.871365 -v 0.006997 -0.009710 0.082188 -vn 1.542569 -2.489297 4.285936 -v 0.006918 -0.009791 0.082213 -vn 2.493399 -2.409629 3.746948 -v 0.007167 -0.009765 0.082106 -vn 3.160345 1.716477 4.097005 -v 0.007219 -0.009710 0.082072 -vn 3.889817 2.175384 3.465306 -v 0.007412 -0.009710 0.081897 -vn 3.025778 -1.707327 3.119319 -v 0.007377 -0.009739 0.081936 -vn 3.814192 -2.175014 2.440599 -v 0.007447 -0.009729 0.081854 -vn 4.447005 1.457529 2.688495 -v 0.007516 -0.009710 0.081750 -vn 4.049243 -1.915118 1.876280 -v 0.007535 -0.009714 0.081716 -vn 3.379552 -0.507363 1.285708 -v 0.007554 -0.009710 0.081678 -vn 0.753666 6.171165 0.349716 -v 0.008211 -0.041410 0.081856 -vn 0.741077 6.188040 0.192179 -v 0.008243 -0.041410 0.081767 -vn -0.906700 6.119451 0.422638 -v 0.005083 -0.041410 0.081843 -vn -0.677288 6.184790 0.381484 -v 0.005216 -0.041410 0.082116 -vn -0.796578 6.179502 0.066900 -v 0.004975 -0.041410 0.081250 -vn -0.753285 6.186737 0.160924 -v 0.005030 -0.041410 0.081677 -vn 0.645298 6.187335 0.416762 -v 0.008034 -0.041410 0.082195 -vn 0.659991 6.153270 0.602748 -v 0.007897 -0.041410 0.082368 -vn 0.470493 6.185483 0.615480 -v 0.007711 -0.041410 0.082546 -vn 0.489118 6.145097 0.779675 -v 0.007420 -0.041410 0.082738 -vn 0.177936 6.179678 0.778598 -v 0.006885 -0.041410 0.082909 -vn 0.259306 6.187853 0.721008 -v 0.007303 -0.041410 0.082793 -vn -0.687582 6.154077 0.566788 -v 0.005374 -0.041410 0.082335 -vn -0.505698 6.190104 0.564451 -v 0.005518 -0.041410 0.082485 -vn -0.498451 6.154268 0.737808 -v 0.005743 -0.041410 0.082659 -vn -0.314768 6.188357 0.696485 -v 0.005912 -0.041410 0.082754 -vn -0.234910 6.172724 0.790936 -v 0.006281 -0.041410 0.082884 -vn -0.083034 6.188228 0.760415 -v 0.006365 -0.041410 0.082901 -vn 0.035205 6.188886 0.761749 -v 0.006842 -0.041410 0.082914 -vn -4.787906 0.439053 -2.300510 -v 0.005773 -0.021063 0.080799 -vn -3.494036 -0.026470 0.636549 -v 0.005702 -0.021011 0.081324 -vn -2.074947 0.153390 3.036011 -v 0.006115 -0.020929 0.081965 -vn -2.448198 0.025076 2.133728 -v 0.005922 -0.020957 0.081797 -vn -3.079637 0.009035 0.020061 -v 0.006115 -0.020418 0.081250 -vn -3.115531 0.068891 -0.680686 -v 0.006123 -0.020449 0.081071 -vn -2.675463 0.040803 -1.721733 -v 0.006201 -0.020484 0.080881 -vn -1.924743 0.026589 -2.517448 -v 0.006340 -0.020516 0.080733 -vn -1.139817 0.035748 -2.850040 -v 0.006519 -0.020548 0.080639 -vn -0.645546 0.027451 -2.986305 -v 0.006557 -0.020554 0.080627 -vn -0.083890 0.028186 -3.073781 -v 0.006722 -0.020579 0.080606 -vn 0.447315 0.023829 -3.034819 -v 0.006784 -0.020588 0.080610 -vn 1.164360 0.033315 -2.949326 -v 0.006934 -0.020610 0.080645 -vn 1.845863 0.055633 -2.587180 -v 0.007128 -0.020641 0.080751 -vn 2.322854 0.027217 -2.075642 -v 0.007220 -0.020658 0.080838 -vn 2.557927 0.020653 -1.694040 -v 0.007280 -0.020671 0.080916 -vn 2.797453 0.011172 -1.366472 -v 0.007313 -0.020680 0.080973 -vn 2.970976 0.027810 -0.846545 -v 0.007372 -0.020702 0.081127 -vn 3.064578 0.026521 -0.373598 -v 0.007391 -0.020714 0.081219 -vn 3.117766 0.021552 0.165423 -v 0.007396 -0.020732 0.081363 -vn 3.046822 0.032409 0.758773 -v 0.007378 -0.020748 0.081489 -vn 2.966477 0.054320 1.212169 -v 0.007347 -0.020761 0.081590 -vn 2.448194 0.028137 2.000416 -v 0.007225 -0.020791 0.081798 -vn 1.950275 0.056681 2.434282 -v 0.007052 -0.020819 0.081960 -vn 1.554381 0.008430 2.670458 -v 0.007044 -0.020820 0.081965 -vn 1.086596 0.021623 2.921921 -v 0.006843 -0.020846 0.082062 -vn 0.618798 0.011015 3.052703 -v 0.006785 -0.020853 0.082078 -vn 0.024642 0.026297 3.165141 -v 0.006597 -0.020874 0.082101 -vn -0.311826 0.051179 3.189170 -v 0.006481 -0.020887 0.082095 -vn -0.886621 -0.007353 3.004838 -v 0.006343 -0.020902 0.082068 -vn -1.369904 0.029238 2.840096 -v 0.006211 -0.020918 0.082019 -vn -2.911878 0.066696 1.135532 -v 0.005763 -0.020988 0.081541 -vn -2.843958 0.077343 1.404929 -v 0.005778 -0.020984 0.081574 -vn -3.470366 -0.086452 -0.222603 -v 0.005701 -0.021037 0.081062 -vn -2.907792 0.070717 -0.882094 -v 0.005730 -0.021051 0.080922 -vn -3.891958 1.473210 4.456006 -v 0.005384 -0.041581 0.082631 -vn -2.739917 1.467640 5.245546 -v 0.005825 -0.041581 0.082931 -vn 1.096495 5.322531 2.632557 -v 0.007338 -0.041431 0.082875 -vn -2.760849 5.322821 0.710760 -v 0.004943 -0.041431 0.081700 -vn -2.445621 5.323605 1.459176 -v 0.005139 -0.041431 0.082162 -vn -1.931388 5.320558 2.112615 -v 0.005457 -0.041431 0.082551 -vn -1.247630 5.321723 2.569806 -v 0.005872 -0.041431 0.082834 -vn -0.467773 5.322244 2.814887 -v 0.006350 -0.041431 0.082989 -vn 0.317601 5.323331 2.829990 -v 0.006852 -0.041431 0.083003 -vn 1.791365 5.323668 2.213289 -v 0.007768 -0.041431 0.082616 -vn 2.365258 5.321704 1.602511 -v 0.008107 -0.041431 0.082245 -vn 2.719656 5.322327 0.863040 -v 0.008329 -0.041431 0.081794 -vn 6.019464 0.250764 1.632235 -v 0.008434 -0.041610 0.081828 -vn 5.671980 1.460265 1.689741 -v 0.008432 -0.041581 0.081828 -vn 5.290800 1.477456 2.455413 -v 0.008382 -0.041610 0.081968 -vn 4.897367 1.447943 3.326651 -v 0.008197 -0.041581 0.082306 -vn 3.646049 1.450646 4.661938 -v 0.007836 -0.041581 0.082699 -vn 4.187033 1.598832 3.941278 -v 0.007976 -0.041610 0.082576 -vn 5.156811 0.236124 3.497689 -v 0.008198 -0.041610 0.082307 -vn -1.042802 1.447856 5.827647 -v 0.006332 -0.041581 0.083096 -vn 0.799879 1.443331 5.863963 -v 0.006865 -0.041581 0.083111 -vn 0.959740 0.248984 6.155952 -v 0.006865 -0.041610 0.083113 -vn 2.304057 1.357960 5.443223 -v 0.007380 -0.041581 0.082975 -vn 2.413827 0.271141 5.705096 -v 0.007381 -0.041610 0.082977 -vn 3.730170 0.240042 4.993922 -v 0.007838 -0.041610 0.082701 -vn -5.013711 1.425981 3.143317 -v 0.005047 -0.041581 0.082218 -vn -5.746067 1.447542 1.422335 -v 0.004839 -0.041581 0.081727 -vn -4.716344 3.420724 1.242663 -v 0.004873 -0.041494 0.081718 -vn -4.175155 3.420826 2.521035 -v 0.005077 -0.041494 0.082200 -vn -3.295768 3.420912 3.595186 -v 0.005408 -0.041494 0.082605 -vn -2.149423 3.420828 4.378130 -v 0.005840 -0.041494 0.082900 -vn -0.828882 3.420778 4.806321 -v 0.006338 -0.041494 0.083061 -vn 0.558834 3.420780 4.845236 -v 0.006861 -0.041494 0.083075 -vn 1.901225 3.420795 4.491527 -v 0.007366 -0.041494 0.082942 -vn 3.089573 3.420815 3.773914 -v 0.007814 -0.041494 0.082672 -vn 4.027627 3.420784 2.750590 -v 0.008167 -0.041494 0.082286 -vn 4.639405 3.420824 1.504451 -v 0.008398 -0.041494 0.081817 -vn 0.887002 -0.773833 -6.050650 -v 0.006843 -0.042410 0.079385 -vn 2.296838 -0.787000 -5.612327 -v 0.007361 -0.042410 0.079515 -vn 3.615565 -0.765280 -4.929587 -v 0.007821 -0.042410 0.079785 -vn 4.387055 -0.909501 -4.228900 -v 0.007976 -0.042410 0.079924 -vn 5.050197 -0.791294 -3.424987 -v 0.008186 -0.042410 0.080174 -vn 5.503515 -0.940514 -2.593582 -v 0.008382 -0.042410 0.080532 -vn 5.896067 -0.776706 -1.656749 -v 0.008427 -0.042410 0.080651 -vn 4.986563 -2.804579 -1.638803 -v 0.008381 -0.042600 0.080666 -vn 0.146884 -6.040197 -1.362526 -v 0.006807 -0.042807 0.079735 -vn -0.250721 -6.040010 -1.350650 -v 0.006373 -0.042807 0.079752 -vn -0.628474 -4.912708 -3.404500 -v 0.006342 -0.042742 0.079579 -vn 0.187046 -6.272535 -0.178258 -v 0.007661 -0.042810 0.080176 -vn 0.117284 -6.276628 -0.164876 -v 0.007571 -0.042810 0.080098 -vn 0.850601 -6.040156 -1.074886 -v 0.007601 -0.042807 0.080060 -vn -0.222422 -6.275253 -0.015662 -v 0.005175 -0.042810 0.081250 -vn -0.244951 -6.273483 -0.028578 -v 0.005200 -0.042810 0.080981 -vn -1.178082 -6.040565 -0.686100 -v 0.005337 -0.042807 0.080478 -vn -0.178316 -6.275844 -0.117409 -v 0.005390 -0.042810 0.080482 -vn -0.192069 -6.276689 -0.060828 -v 0.005219 -0.042810 0.080891 -vn -0.933947 -6.040969 -0.983311 -v 0.005607 -0.042807 0.080139 -vn -0.138687 -6.275078 -0.176863 -v 0.005678 -0.042810 0.080140 -vn -0.622752 -6.040120 -1.221930 -v 0.005963 -0.042807 0.079890 -vn -0.097673 -6.276609 -0.177532 -v 0.005984 -0.042810 0.079934 -vn 0.030354 -6.276570 -0.200898 -v 0.006802 -0.042810 0.079783 -vn -0.007500 -6.271969 -0.265083 -v 0.006641 -0.042810 0.079775 -vn -0.012223 -6.270945 -0.276757 -v 0.006560 -0.042810 0.079778 -vn -0.038625 -6.276795 -0.196191 -v 0.006382 -0.042810 0.079799 -vn -0.088967 -6.270997 -0.261709 -v 0.006145 -0.042810 0.079864 -vn 0.241815 -6.271523 -0.120972 -v 0.007992 -0.042810 0.080638 -vn 0.166291 -6.276528 -0.117868 -v 0.007858 -0.042810 0.080404 -vn 1.123039 -6.040121 -0.787398 -v 0.007898 -0.042807 0.080376 -vn 1.300440 -6.040184 -0.432297 -v 0.008094 -0.042807 0.080763 -vn 0.195035 -6.276600 -0.055355 -v 0.008048 -0.042810 0.080779 -vn -2.427381 -2.816529 -4.654092 -v 0.005826 -0.042600 0.079619 -vn -1.562175 -4.912713 -3.089549 -v 0.005883 -0.042742 0.079734 -vn 1.311931 -4.912673 -3.203840 -v 0.007294 -0.042742 0.079678 -vn 2.161403 -4.912710 -2.704441 -v 0.007711 -0.042742 0.079923 -vn 3.221491 -2.814931 -4.145676 -v 0.007791 -0.042600 0.079823 -vn 1.992913 -2.746313 -4.866883 -v 0.007342 -0.042600 0.079559 -vn 0.588502 -2.807241 -5.216089 -v 0.006838 -0.042600 0.079433 -vn -1.328528 -6.040123 -0.340136 -v 0.005172 -0.042807 0.080879 -vn -3.357946 -4.912672 -0.842628 -v 0.005002 -0.042742 0.080837 -vn -5.093763 -2.764905 -1.302385 -v 0.004878 -0.042600 0.080805 -vn -4.510571 -2.816153 -2.685457 -v 0.005075 -0.042600 0.080324 -vn -2.984523 -4.912684 -1.754532 -v 0.005186 -0.042742 0.080389 -vn -2.369310 -4.912687 -2.524295 -v 0.005487 -0.042742 0.080011 -vn -3.566506 -2.794343 -3.854845 -v 0.005400 -0.042600 0.079918 -vn -0.912530 -2.780899 -5.176080 -v 0.006318 -0.042600 0.079453 -vn 0.356169 -4.912652 -3.443671 -v 0.006825 -0.042742 0.079560 -vn 0.519446 -6.040495 -1.262010 -v 0.007227 -0.042807 0.079840 -vn 0.075017 -6.276102 -0.195648 -v 0.007200 -0.042810 0.079881 -vn 2.835787 -4.912709 -1.985945 -v 0.008042 -0.042742 0.080275 -vn 4.336390 -2.795641 -2.966328 -v 0.008147 -0.042600 0.080202 -vn 3.280438 -4.912682 -1.106583 -v 0.008260 -0.042742 0.080707 -vn -0.161587 0.040663 -3.209755 -v 0.006605 -0.018160 0.080717 -vn 0.623431 0.034621 -3.035645 -v 0.006804 -0.018196 0.080737 -vn 1.169831 0.004823 -2.851302 -v 0.006816 -0.018198 0.080741 -vn 1.924782 0.001477 -2.499714 -v 0.006977 -0.018231 0.080827 -vn 2.448443 0.003271 -1.879172 -v 0.007095 -0.018262 0.080953 -vn 2.767795 0.016737 -1.388596 -v 0.007112 -0.018268 0.080981 -vn 3.110594 0.022744 -0.628532 -v 0.007173 -0.018298 0.081137 -vn 3.134329 -0.009917 0.508042 -v 0.007178 -0.018334 0.081336 -vn 2.787797 -0.009535 1.344132 -v 0.007111 -0.018369 0.081522 -vn 2.485155 -0.040832 1.894363 -v 0.007104 -0.018371 0.081533 -vn 2.059787 -0.010176 2.418643 -v 0.006980 -0.018405 0.081671 -vn 1.347582 0.005874 2.749696 -v 0.006869 -0.018428 0.081738 -vn -0.834186 0.011514 2.950042 -v 0.006490 -0.018497 0.081761 -vn -0.308094 0.005412 3.071699 -v 0.006608 -0.018476 0.081783 -vn 0.225878 0.000751 3.052028 -v 0.006684 -0.018462 0.081784 -vn 0.806791 0.001830 2.933836 -v 0.006804 -0.018440 0.081763 -vn -2.579282 -0.021978 1.700807 -v 0.006198 -0.018564 0.081535 -vn -2.218141 -0.020280 2.118937 -v 0.006272 -0.018543 0.081628 -vn -1.812092 -0.001127 2.445312 -v 0.006329 -0.018530 0.081678 -vn -1.361908 0.005540 2.723327 -v 0.006415 -0.018511 0.081731 -vn -3.045222 -0.012795 0.196171 -v 0.006116 -0.018613 0.081277 -vn -3.042831 -0.026075 0.623312 -v 0.006123 -0.018601 0.081346 -vn -2.863554 -0.008294 1.208175 -v 0.006160 -0.018578 0.081466 -vn -2.974842 0.017508 -0.834638 -v 0.006143 -0.018649 0.081079 -vn -3.070120 0.006871 -0.287254 -v 0.006116 -0.018622 0.081229 -vn -2.765393 0.010072 -1.332857 -v 0.006159 -0.018657 0.081037 -vn -2.364518 -0.027188 -2.099309 -v 0.006238 -0.018684 0.080908 -vn -1.881744 -0.029270 -2.221748 -v 0.006269 -0.018691 0.080883 -vn -1.660327 0.011171 -2.592114 -v 0.006392 -0.018720 0.080781 -vn -1.141299 -0.002246 -2.856096 -v 0.006423 -0.018726 0.080765 -vn -0.418524 -0.000539 -3.130088 -v 0.006580 -0.018755 0.080719 -vn 0.666920 -0.018159 -3.084732 -v 0.006754 -0.018787 0.080726 -vn 1.076967 -0.043221 -2.717716 -v 0.006791 -0.018794 0.080740 -vn 1.671996 -0.002767 -2.719047 -v 0.006939 -0.018822 0.080799 -vn 2.247768 0.007090 -2.097505 -v 0.007060 -0.018852 0.080907 -vn 2.566886 -0.014723 -1.680323 -v 0.007080 -0.018857 0.080932 -vn 2.831413 -0.000655 -1.171262 -v 0.007156 -0.018886 0.081076 -vn 2.973006 -0.002556 -0.646454 -v 0.007167 -0.018893 0.081113 -vn 3.062312 -0.010827 -0.030959 -v 0.007185 -0.018921 0.081265 -vn 3.044627 -0.013212 0.474868 -v 0.007182 -0.018928 0.081307 -vn 2.885502 -0.005052 1.045605 -v 0.007144 -0.018956 0.081456 -vn 2.683005 -0.004936 1.575939 -v 0.007124 -0.018964 0.081499 -vn 2.403643 0.014646 1.997075 -v 0.007046 -0.018989 0.081610 -vn 1.946137 0.004460 2.392991 -v 0.007003 -0.018999 0.081652 -vn 1.480226 0.005030 2.670374 -v 0.006890 -0.019024 0.081728 -vn 1.033304 -0.010220 2.895325 -v 0.006855 -0.019031 0.081744 -vn 0.437398 -0.006230 3.046207 -v 0.006697 -0.019060 0.081783 -vn -0.016026 -0.019175 3.036814 -v 0.006659 -0.019066 0.081785 -vn -0.453474 -0.015750 3.037105 -v 0.006577 -0.019081 0.081780 -vn -0.999208 -0.002269 2.874745 -v 0.006465 -0.019102 0.081752 -vn -1.494044 0.001088 2.643789 -v 0.006395 -0.019115 0.081720 -vn -2.012128 0.019234 2.325478 -v 0.006293 -0.019138 0.081650 -vn -2.361141 0.011205 1.947345 -v 0.006244 -0.019150 0.081599 -vn -2.713584 0.017279 1.441570 -v 0.006174 -0.019173 0.081494 -vn -2.922067 0.010936 0.966075 -v 0.006146 -0.019185 0.081430 -vn -3.053177 0.008183 0.413395 -v 0.006117 -0.019209 0.081302 -vn -3.059294 0.006908 -0.101872 -v 0.006115 -0.019218 0.081250 -vn -2.953856 0.003738 -0.709021 -v 0.006134 -0.019244 0.081108 -vn -2.825321 0.030950 -1.281703 -v 0.006152 -0.019254 0.081056 -vn -2.652804 0.087943 -1.890390 -v 0.006205 -0.019274 0.080953 -vn -1.855803 0.032861 -2.670534 -v 0.006346 -0.019310 0.080810 -vn -0.768057 0.009138 -3.116123 -v 0.006528 -0.019346 0.080729 -vn 0.444483 -0.002655 -3.142592 -v 0.006725 -0.019381 0.080720 -vn 1.574365 0.002317 -2.777582 -v 0.006913 -0.019417 0.080784 -vn 2.964355 -0.016551 -0.780309 -v 0.007159 -0.019488 0.081085 -vn 2.821799 -0.022231 -1.304796 -v 0.007150 -0.019483 0.081060 -vn 2.474329 -0.009498 -2.031502 -v 0.007065 -0.019453 0.080912 -vn 3.062576 -0.003642 0.387009 -v 0.007184 -0.019524 0.081283 -vn 3.065667 -0.006148 -0.172467 -v 0.007185 -0.019519 0.081254 -vn 2.608660 -0.004563 1.691449 -v 0.007096 -0.019574 0.081546 -vn 2.928902 -0.019128 1.131799 -v 0.007144 -0.019556 0.081455 -vn 2.228495 0.013588 2.107900 -v 0.007037 -0.019591 0.081619 -vn 1.768826 0.004609 2.494954 -v 0.006958 -0.019610 0.081688 -vn -0.296290 -0.002803 3.050582 -v 0.006599 -0.019677 0.081783 -vn 0.208669 -0.002841 3.048618 -v 0.006686 -0.019662 0.081784 -vn 0.760453 0.011349 2.961938 -v 0.006777 -0.019645 0.081770 -vn 1.265772 0.018100 2.799812 -v 0.006880 -0.019626 0.081733 -vn -2.030605 -0.008396 2.376909 -v 0.006315 -0.019733 0.081667 -vn -1.431783 -0.007205 2.698701 -v 0.006407 -0.019713 0.081726 -vn -0.884791 -0.002249 2.915032 -v 0.006491 -0.019697 0.081761 -vn -2.520319 0.004803 1.733298 -v 0.006186 -0.019768 0.081518 -vn -2.789807 0.006512 1.287846 -v 0.006183 -0.019769 0.081512 -vn -2.968672 0.022848 0.781847 -v 0.006125 -0.019799 0.081354 -vn -3.060614 0.000645 0.267833 -v 0.006122 -0.019803 0.081332 -vn -3.071709 0.009004 -0.336881 -v 0.006123 -0.019835 0.081156 -vn -2.990614 0.000860 -0.933203 -v 0.006128 -0.019839 0.081131 -vn -2.797399 0.011470 -1.424933 -v 0.006192 -0.019870 0.080974 -vn -2.443019 0.001517 -1.891023 -v 0.006209 -0.019875 0.080948 -vn -1.898203 -0.004709 -2.530415 -v 0.006325 -0.019906 0.080825 -vn -0.882972 0.007794 -3.072382 -v 0.006499 -0.019941 0.080737 -vn 0.171338 0.029486 -3.148229 -v 0.006698 -0.019977 0.080717 -vn 1.847010 -0.003982 -2.427664 -v 0.006986 -0.020033 0.080834 -vn 1.417065 -0.018750 -2.742558 -v 0.006886 -0.020012 0.080770 -vn 0.911752 -0.004272 -2.948345 -v 0.006818 -0.019999 0.080742 -vn 2.620714 -0.006805 -1.592653 -v 0.007117 -0.020069 0.080988 -vn 2.228218 -0.003932 -2.077594 -v 0.007028 -0.020043 0.080872 -vn 2.887739 -0.008835 -1.118347 -v 0.007141 -0.020079 0.081037 -vn 3.010772 0.006244 -0.534444 -v 0.007180 -0.020105 0.081180 -vn 2.993400 -0.000940 0.620862 -v 0.007169 -0.020142 0.081383 -vn 3.043936 -0.001061 0.013285 -v 0.007184 -0.020114 0.081229 -vn 2.868279 -0.001254 1.162728 -v 0.007156 -0.020150 0.081426 -vn 2.564772 0.001682 1.694042 -v 0.007082 -0.020178 0.081566 -vn 2.242802 -0.018848 2.105663 -v 0.007058 -0.020185 0.081596 -vn 1.825672 -0.002913 2.486782 -v 0.006943 -0.020213 0.081697 -vn 1.336094 -0.002340 2.760433 -v 0.006903 -0.020221 0.081722 -vn 0.729175 -0.003536 2.976402 -v 0.006755 -0.020249 0.081775 -vn 0.203079 -0.015050 3.081422 -v 0.006717 -0.020256 0.081781 -vn -0.493948 -0.008614 3.078531 -v 0.006545 -0.020287 0.081775 -vn -1.144181 0.006000 2.873406 -v 0.006454 -0.020304 0.081748 -vn -2.753256 0.001433 1.333629 -v 0.006167 -0.020375 0.081482 -vn -2.485658 -0.006949 1.834180 -v 0.006216 -0.020359 0.081562 -vn -2.107497 -0.011352 2.220400 -v 0.006289 -0.020339 0.081645 -vn -1.633659 0.007726 2.585446 -v 0.006360 -0.020323 0.081700 -vn -2.979635 -0.017211 0.745493 -v 0.006131 -0.020394 0.081383 -vn -3.120913 -0.053786 0.245243 -v 0.006116 -0.020412 0.081285 -vn -0.753227 0.010208 -3.025760 -v 0.006506 -0.018142 0.080735 -vn -1.359468 -0.004731 -2.739182 -v 0.006416 -0.018125 0.080768 -vn -1.851207 -0.000257 -2.421646 -v 0.006324 -0.018105 0.080826 -vn -2.245009 0.005896 -2.050658 -v 0.006256 -0.018089 0.080888 -vn -2.683327 -0.014345 -1.576384 -v 0.006194 -0.018071 0.080971 -vn -3.070604 -0.039653 -1.048958 -v 0.006151 -0.018054 0.081055 -vn -3.196134 -0.053318 -0.215823 -v 0.006115 -0.018018 0.081250 -vn 2.720703 -4.188785 -0.000000 -v 0.005650 -0.042810 0.081250 -vn -1.360349 -4.188789 -2.356195 -v 0.007150 -0.042810 0.082116 -vn 1.360351 -4.188793 -2.356191 -v 0.006150 -0.042810 0.082116 -vn -2.720698 -4.188791 -0.000000 -v 0.007650 -0.042810 0.081250 -vn -1.360349 -4.188790 2.356195 -v 0.007150 -0.042810 0.080384 -vn 1.360352 -4.188793 2.356191 -v 0.006150 -0.042810 0.080384 -vn 2.720703 -2.094400 0.000000 -v 0.005650 -0.041810 0.081250 -vn 1.360351 -2.094393 2.356191 -v 0.006150 -0.041810 0.080384 -vn 1.360352 -2.094393 -2.356191 -v 0.006150 -0.041810 0.082116 -vn -1.360349 -2.094396 -2.356195 -v 0.007150 -0.041810 0.082116 -vn -2.720698 -2.094394 0.000000 -v 0.007650 -0.041810 0.081250 -vn -1.360349 -2.094396 2.356195 -v 0.007150 -0.041810 0.080384 -vn -0.161557 0.040642 -3.209772 -v 0.006605 -0.015760 0.080717 -vn 0.622798 0.034569 -3.035426 -v 0.006804 -0.015796 0.080737 -vn 1.169428 0.005008 -2.851763 -v 0.006816 -0.015798 0.080741 -vn 1.924761 0.001444 -2.499674 -v 0.006977 -0.015831 0.080827 -vn 2.448472 0.003246 -1.879125 -v 0.007095 -0.015862 0.080953 -vn 2.767756 0.016713 -1.388496 -v 0.007112 -0.015868 0.080981 -vn 3.110551 0.022734 -0.628524 -v 0.007173 -0.015898 0.081137 -vn 3.134289 -0.009975 0.508036 -v 0.007178 -0.015933 0.081336 -vn 2.787754 -0.009485 1.344072 -v 0.007111 -0.015969 0.081522 -vn 2.485234 -0.040991 1.894361 -v 0.007104 -0.015971 0.081533 -vn 2.059718 -0.010185 2.418612 -v 0.006980 -0.016005 0.081671 -vn 1.347492 0.005854 2.749734 -v 0.006869 -0.016028 0.081738 -vn 0.806723 0.001762 2.933722 -v 0.006804 -0.016040 0.081763 -vn 0.225925 0.000695 3.051975 -v 0.006684 -0.016062 0.081784 -vn -0.308111 0.005360 3.071644 -v 0.006608 -0.016076 0.081783 -vn -0.834104 0.011513 2.949913 -v 0.006490 -0.016097 0.081761 -vn -1.361947 0.005466 2.723363 -v 0.006415 -0.016111 0.081731 -vn -1.811961 -0.001200 2.445127 -v 0.006329 -0.016130 0.081678 -vn -2.218034 -0.020318 2.118981 -v 0.006272 -0.016143 0.081628 -vn -2.579194 -0.022051 1.700774 -v 0.006198 -0.016164 0.081535 -vn -2.863472 -0.008317 1.208147 -v 0.006161 -0.016178 0.081466 -vn -3.042701 -0.026218 0.623340 -v 0.006123 -0.016201 0.081346 -vn -3.045107 -0.012842 0.196162 -v 0.006116 -0.016213 0.081277 -vn -3.070021 0.006839 -0.287264 -v 0.006116 -0.016222 0.081229 -vn -2.974719 0.017413 -0.834574 -v 0.006143 -0.016249 0.081079 -vn -2.774557 -0.007092 -1.364413 -v 0.006159 -0.016257 0.081037 -vn -2.482422 -0.008340 -1.855719 -v 0.006238 -0.016284 0.080908 -vn -2.092572 0.009377 -2.284650 -v 0.006265 -0.016291 0.080878 -vn -1.644111 0.027118 -2.613001 -v 0.006393 -0.016320 0.080781 -vn -1.149400 0.003130 -2.861853 -v 0.006423 -0.016326 0.080765 -vn -0.407870 -0.007466 -3.139112 -v 0.006580 -0.016355 0.080719 -vn 0.421287 0.001285 -3.058454 -v 0.006754 -0.016387 0.080726 -vn 1.037253 -0.013834 -2.944511 -v 0.006793 -0.016394 0.080735 -vn 1.691972 0.009623 -2.722202 -v 0.006939 -0.016422 0.080799 -vn 2.247598 0.007101 -2.097476 -v 0.007060 -0.016452 0.080907 -vn 2.566773 -0.014823 -1.680321 -v 0.007080 -0.016457 0.080932 -vn 2.831310 -0.000812 -1.171174 -v 0.007156 -0.016486 0.081076 -vn 2.972819 -0.002617 -0.646305 -v 0.007167 -0.016493 0.081113 -vn 3.062151 -0.010923 -0.030919 -v 0.007185 -0.016521 0.081265 -vn 3.044467 -0.013275 0.474888 -v 0.007182 -0.016528 0.081307 -vn 2.885353 -0.005133 1.045627 -v 0.007144 -0.016556 0.081456 -vn 2.682796 -0.005056 1.575917 -v 0.007124 -0.016564 0.081499 -vn 2.403471 0.014473 1.997069 -v 0.007046 -0.016589 0.081610 -vn 1.945895 0.004429 2.392854 -v 0.007003 -0.016599 0.081652 -vn 1.480264 0.004932 2.670167 -v 0.006890 -0.016624 0.081728 -vn 1.033287 -0.010287 2.895224 -v 0.006855 -0.016631 0.081744 -vn 0.437394 -0.006428 3.045990 -v 0.006697 -0.016660 0.081783 -vn -0.016058 -0.019162 3.036626 -v 0.006659 -0.016666 0.081785 -vn -0.453415 -0.015897 3.036921 -v 0.006577 -0.016681 0.081780 -vn -0.998995 -0.002415 2.874500 -v 0.006465 -0.016702 0.081752 -vn -1.493909 0.001030 2.643677 -v 0.006395 -0.016715 0.081720 -vn -2.012057 0.019123 2.325295 -v 0.006293 -0.016738 0.081649 -vn -2.360983 0.011038 1.947173 -v 0.006244 -0.016750 0.081599 -vn -2.713399 0.017164 1.441454 -v 0.006174 -0.016773 0.081494 -vn -2.921881 0.010813 0.965947 -v 0.006146 -0.016785 0.081430 -vn -3.052976 0.008011 0.413307 -v 0.006117 -0.016809 0.081302 -vn -3.059039 0.006854 -0.101994 -v 0.006115 -0.016818 0.081250 -vn -2.953644 0.003608 -0.709092 -v 0.006134 -0.016844 0.081108 -vn -2.825052 0.030846 -1.281580 -v 0.006152 -0.016854 0.081056 -vn -2.652728 0.087766 -1.890193 -v 0.006205 -0.016874 0.080953 -vn -1.855665 0.032730 -2.670323 -v 0.006346 -0.016910 0.080810 -vn -0.768007 0.009007 -3.115939 -v 0.006528 -0.016946 0.080729 -vn 0.444570 -0.002814 -3.142364 -v 0.006725 -0.016981 0.080720 -vn 1.574332 0.002146 -2.777307 -v 0.006913 -0.017017 0.080784 -vn 2.964112 -0.016809 -0.780142 -v 0.007159 -0.017088 0.081085 -vn 2.821660 -0.022277 -1.304579 -v 0.007150 -0.017083 0.081060 -vn 2.474215 -0.009634 -2.031252 -v 0.007065 -0.017053 0.080912 -vn 3.062247 -0.003685 0.387171 -v 0.007184 -0.017124 0.081283 -vn 3.065443 -0.006445 -0.172356 -v 0.007185 -0.017119 0.081254 -vn 2.618576 0.000665 1.688073 -v 0.007096 -0.017174 0.081546 -vn 2.938834 -0.012100 1.149381 -v 0.007144 -0.017156 0.081455 -vn 1.768780 0.004417 2.494671 -v 0.006957 -0.017210 0.081688 -vn 2.228372 0.013510 2.107639 -v 0.007037 -0.017191 0.081619 -vn -0.296316 -0.002987 3.050214 -v 0.006599 -0.017277 0.081783 -vn 0.208627 -0.002982 3.048432 -v 0.006686 -0.017262 0.081784 -vn 0.760382 0.011174 2.961525 -v 0.006777 -0.017245 0.081769 -vn 1.265601 0.017979 2.799620 -v 0.006880 -0.017226 0.081733 -vn -2.030525 -0.008608 2.376571 -v 0.006315 -0.017333 0.081667 -vn -1.431765 -0.007347 2.698469 -v 0.006407 -0.017313 0.081726 -vn -0.884637 -0.002411 2.914780 -v 0.006491 -0.017297 0.081761 -vn -2.520122 0.004438 1.732950 -v 0.006186 -0.017368 0.081518 -vn -2.789536 0.006537 1.287454 -v 0.006183 -0.017369 0.081512 -vn -2.968218 0.022596 0.781949 -v 0.006126 -0.017399 0.081354 -vn -3.060320 0.000557 0.267983 -v 0.006122 -0.017403 0.081332 -vn -3.071521 0.008774 -0.337090 -v 0.006123 -0.017435 0.081156 -vn -2.990073 0.000676 -0.933311 -v 0.006128 -0.017439 0.081131 -vn -2.797172 0.011264 -1.424777 -v 0.006192 -0.017470 0.080974 -vn -2.442735 0.001362 -1.890845 -v 0.006209 -0.017475 0.080948 -vn -1.897949 -0.004902 -2.530217 -v 0.006325 -0.017506 0.080825 -vn -0.883842 0.006316 -3.074247 -v 0.006499 -0.017541 0.080737 -vn 0.171430 0.029294 -3.147847 -v 0.006698 -0.017577 0.080717 -vn 0.911738 -0.004436 -2.948052 -v 0.006818 -0.017599 0.080742 -vn 1.416964 -0.018972 -2.742189 -v 0.006886 -0.017612 0.080770 -vn 1.846735 -0.004102 -2.427408 -v 0.006986 -0.017633 0.080834 -vn 2.280803 0.011945 -2.075891 -v 0.007028 -0.017643 0.080872 -vn 2.628581 0.013469 -1.630412 -v 0.007117 -0.017669 0.080988 -vn 2.887378 -0.009009 -1.118256 -v 0.007141 -0.017679 0.081037 -vn 3.010412 0.006052 -0.534452 -v 0.007180 -0.017705 0.081180 -vn 3.043551 -0.001309 0.013226 -v 0.007184 -0.017714 0.081229 -vn 2.993005 -0.001053 0.620759 -v 0.007169 -0.017742 0.081383 -vn 2.868007 -0.001489 1.162567 -v 0.007156 -0.017750 0.081426 -vn 2.564442 0.001479 1.693931 -v 0.007082 -0.017778 0.081566 -vn 2.242474 -0.019066 2.105433 -v 0.007058 -0.017785 0.081596 -vn 1.825320 -0.003176 2.486781 -v 0.006943 -0.017813 0.081697 -vn -1.144148 0.005794 2.873263 -v 0.006454 -0.017904 0.081748 -vn -0.493870 -0.008836 3.078200 -v 0.006545 -0.017887 0.081775 -vn 0.203011 -0.015219 3.081048 -v 0.006717 -0.017856 0.081781 -vn 0.751649 0.009119 2.987223 -v 0.006755 -0.017849 0.081775 -vn 1.323639 0.010790 2.799823 -v 0.006903 -0.017821 0.081722 -vn -2.753438 0.001285 1.333564 -v 0.006168 -0.017975 0.081482 -vn -2.485801 -0.007144 1.834124 -v 0.006216 -0.017958 0.081562 -vn -2.107491 -0.011556 2.220421 -v 0.006289 -0.017939 0.081644 -vn -1.633537 0.007523 2.585326 -v 0.006360 -0.017923 0.081700 -vn -2.979866 -0.017448 0.745527 -v 0.006131 -0.017994 0.081383 -vn -3.121133 -0.053867 0.245284 -v 0.006116 -0.018012 0.081285 -vn -0.753333 0.010187 -3.025778 -v 0.006506 -0.015742 0.080735 -vn -1.359458 -0.004769 -2.739061 -v 0.006416 -0.015725 0.080768 -vn -1.851155 -0.000249 -2.421736 -v 0.006324 -0.015705 0.080826 -vn -2.245008 0.005907 -2.050648 -v 0.006256 -0.015689 0.080888 -vn -2.683305 -0.014377 -1.576336 -v 0.006194 -0.015671 0.080971 -vn -3.070564 -0.039650 -1.048967 -v 0.006151 -0.015654 0.081055 -vn -3.196137 -0.053318 -0.215850 -v 0.006115 -0.015618 0.081250 -vn -0.161542 0.040632 -3.209770 -v 0.006605 -0.013360 0.080717 -vn 0.622804 0.034573 -3.035427 -v 0.006804 -0.013396 0.080737 -vn 1.169478 0.005007 -2.851764 -v 0.006816 -0.013398 0.080741 -vn 1.924744 0.001432 -2.499620 -v 0.006977 -0.013431 0.080827 -vn 2.448400 0.003268 -1.879184 -v 0.007095 -0.013462 0.080953 -vn 2.767764 0.016718 -1.388573 -v 0.007112 -0.013468 0.080981 -vn 3.110541 0.022734 -0.628504 -v 0.007173 -0.013498 0.081137 -vn 3.134277 -0.009973 0.508021 -v 0.007178 -0.013533 0.081336 -vn 2.787758 -0.009495 1.344265 -v 0.007111 -0.013569 0.081522 -vn 2.485073 -0.041021 1.894446 -v 0.007104 -0.013571 0.081533 -vn 2.059719 -0.010180 2.418610 -v 0.006980 -0.013605 0.081671 -vn 1.347511 0.005862 2.749737 -v 0.006869 -0.013628 0.081738 -vn 0.806723 0.001762 2.933722 -v 0.006804 -0.013640 0.081763 -vn 0.225923 0.000701 3.051976 -v 0.006684 -0.013662 0.081784 -vn -0.308116 0.005347 3.071650 -v 0.006608 -0.013676 0.081783 -vn -0.834092 0.011523 2.949905 -v 0.006490 -0.013697 0.081761 -vn -1.361957 0.005455 2.723394 -v 0.006415 -0.013711 0.081731 -vn -1.811989 -0.001194 2.445101 -v 0.006329 -0.013730 0.081678 -vn -2.218035 -0.020314 2.118990 -v 0.006272 -0.013743 0.081628 -vn -2.579194 -0.022051 1.700774 -v 0.006198 -0.013764 0.081535 -vn -2.863472 -0.008317 1.208147 -v 0.006161 -0.013778 0.081466 -vn -3.042701 -0.026218 0.623340 -v 0.006123 -0.013801 0.081346 -vn -3.045123 -0.012791 0.196137 -v 0.006116 -0.013813 0.081277 -vn -3.070044 0.006748 -0.287231 -v 0.006116 -0.013822 0.081229 -vn -2.974716 0.017429 -0.834578 -v 0.006143 -0.013849 0.081079 -vn -2.774556 -0.007073 -1.364419 -v 0.006159 -0.013857 0.081037 -vn -2.482405 -0.008446 -1.855797 -v 0.006238 -0.013884 0.080908 -vn -2.092444 0.009421 -2.284668 -v 0.006265 -0.013891 0.080878 -vn -1.644134 0.027130 -2.612989 -v 0.006393 -0.013920 0.080781 -vn -1.149386 0.003149 -2.861850 -v 0.006423 -0.013926 0.080765 -vn -0.407884 -0.007514 -3.139107 -v 0.006580 -0.013955 0.080719 -vn 0.421324 0.001358 -3.058465 -v 0.006754 -0.013987 0.080726 -vn 1.037230 -0.013942 -2.944549 -v 0.006793 -0.013994 0.080735 -vn 1.691983 0.009641 -2.722211 -v 0.006939 -0.014022 0.080799 -vn 2.247599 0.007107 -2.097485 -v 0.007060 -0.014052 0.080907 -vn 2.566773 -0.014823 -1.680321 -v 0.007080 -0.014057 0.080932 -vn 2.831310 -0.000812 -1.171174 -v 0.007156 -0.014086 0.081076 -vn 2.972839 -0.002602 -0.646290 -v 0.007167 -0.014093 0.081113 -vn 3.062164 -0.010956 -0.030940 -v 0.007185 -0.014121 0.081265 -vn 3.044467 -0.013295 0.474885 -v 0.007182 -0.014128 0.081307 -vn 2.885349 -0.005216 1.045595 -v 0.007144 -0.014156 0.081456 -vn 2.682777 -0.005007 1.575929 -v 0.007124 -0.014164 0.081499 -vn 2.403471 0.014473 1.997069 -v 0.007046 -0.014189 0.081610 -vn 1.945895 0.004429 2.392854 -v 0.007003 -0.014199 0.081652 -vn 1.480264 0.004932 2.670167 -v 0.006890 -0.014224 0.081728 -vn 1.033287 -0.010287 2.895224 -v 0.006855 -0.014231 0.081744 -vn 0.437399 -0.006422 3.045980 -v 0.006697 -0.014260 0.081783 -vn -0.016065 -0.019158 3.036617 -v 0.006659 -0.014266 0.081785 -vn -0.453425 -0.015891 3.036931 -v 0.006577 -0.014281 0.081780 -vn -0.998984 -0.002406 2.874503 -v 0.006465 -0.014302 0.081752 -vn -1.493902 0.001040 2.643660 -v 0.006395 -0.014315 0.081720 -vn -2.012055 0.019129 2.325281 -v 0.006293 -0.014338 0.081649 -vn -2.360983 0.011038 1.947173 -v 0.006244 -0.014350 0.081599 -vn -2.713399 0.017164 1.441454 -v 0.006174 -0.014373 0.081494 -vn -2.921881 0.010813 0.965947 -v 0.006146 -0.014385 0.081430 -vn -3.052988 0.008053 0.413290 -v 0.006117 -0.014409 0.081302 -vn -3.059038 0.006761 -0.101948 -v 0.006115 -0.014418 0.081250 -vn -2.953623 0.003624 -0.709108 -v 0.006134 -0.014444 0.081108 -vn -2.825052 0.030846 -1.281580 -v 0.006152 -0.014454 0.081056 -vn -2.652727 0.087769 -1.890201 -v 0.006205 -0.014474 0.080953 -vn -1.855676 0.032737 -2.670328 -v 0.006346 -0.014510 0.080810 -vn -0.768007 0.009007 -3.115939 -v 0.006528 -0.014546 0.080729 -vn 0.444570 -0.002814 -3.142364 -v 0.006725 -0.014581 0.080720 -vn 1.574329 0.002149 -2.777303 -v 0.006913 -0.014617 0.080784 -vn 2.964112 -0.016809 -0.780142 -v 0.007159 -0.014688 0.081085 -vn 2.821660 -0.022277 -1.304579 -v 0.007150 -0.014683 0.081060 -vn 2.474215 -0.009634 -2.031252 -v 0.007065 -0.014653 0.080912 -vn 3.062255 -0.003681 0.387180 -v 0.007184 -0.014724 0.081283 -vn 3.065443 -0.006445 -0.172356 -v 0.007185 -0.014719 0.081254 -vn 2.618578 0.000692 1.688095 -v 0.007096 -0.014774 0.081546 -vn 2.938844 -0.012094 1.149378 -v 0.007144 -0.014756 0.081455 -vn 1.768749 0.004462 2.494694 -v 0.006957 -0.014810 0.081688 -vn 2.228402 0.013440 2.107610 -v 0.007037 -0.014791 0.081619 -vn -0.296323 -0.002982 3.050202 -v 0.006599 -0.014877 0.081783 -vn 0.208633 -0.002977 3.048424 -v 0.006686 -0.014862 0.081784 -vn 0.760367 0.011203 2.961519 -v 0.006777 -0.014845 0.081769 -vn 1.265642 0.017910 2.799620 -v 0.006880 -0.014826 0.081733 -vn -2.030539 -0.008581 2.376560 -v 0.006315 -0.014933 0.081667 -vn -1.431735 -0.007409 2.698488 -v 0.006407 -0.014913 0.081726 -vn -0.884665 -0.002376 2.914793 -v 0.006491 -0.014897 0.081761 -vn -2.520123 0.004442 1.732958 -v 0.006186 -0.014968 0.081518 -vn -2.789546 0.006541 1.287451 -v 0.006183 -0.014969 0.081512 -vn -2.968224 0.022602 0.781956 -v 0.006126 -0.014999 0.081354 -vn -3.060312 0.000562 0.267988 -v 0.006122 -0.015003 0.081332 -vn -3.071524 0.008878 -0.337134 -v 0.006123 -0.015035 0.081156 -vn -2.990113 0.000519 -0.933278 -v 0.006128 -0.015039 0.081131 -vn -2.797178 0.011279 -1.424777 -v 0.006192 -0.015070 0.080974 -vn -2.442735 0.001362 -1.890845 -v 0.006209 -0.015075 0.080948 -vn -1.897949 -0.004902 -2.530217 -v 0.006325 -0.015106 0.080825 -vn -0.883842 0.006316 -3.074247 -v 0.006499 -0.015141 0.080737 -vn 0.171433 0.029316 -3.147843 -v 0.006698 -0.015177 0.080717 -vn 0.911712 -0.004519 -2.948047 -v 0.006818 -0.015199 0.080742 -vn 1.416972 -0.018944 -2.742178 -v 0.006886 -0.015212 0.080770 -vn 1.846735 -0.004102 -2.427408 -v 0.006986 -0.015233 0.080834 -vn 2.280806 0.011947 -2.075894 -v 0.007028 -0.015243 0.080872 -vn 2.628581 0.013469 -1.630412 -v 0.007117 -0.015269 0.080988 -vn 2.887390 -0.009004 -1.118253 -v 0.007141 -0.015279 0.081037 -vn 3.010418 0.006057 -0.534459 -v 0.007180 -0.015305 0.081180 -vn 3.043565 -0.001296 0.013243 -v 0.007184 -0.015314 0.081229 -vn 2.993011 -0.001153 0.620707 -v 0.007169 -0.015342 0.081383 -vn 2.867982 -0.001437 1.162585 -v 0.007156 -0.015350 0.081426 -vn 2.564441 0.001480 1.693928 -v 0.007082 -0.015378 0.081566 -vn 2.242472 -0.019058 2.105442 -v 0.007058 -0.015385 0.081596 -vn 1.825326 -0.003163 2.486794 -v 0.006943 -0.015413 0.081697 -vn -1.144139 0.005801 2.873254 -v 0.006454 -0.015504 0.081748 -vn -0.493870 -0.008833 3.078196 -v 0.006545 -0.015487 0.081775 -vn 0.203010 -0.015216 3.081043 -v 0.006717 -0.015456 0.081781 -vn 0.751655 0.009128 2.987224 -v 0.006755 -0.015449 0.081775 -vn 1.323642 0.010802 2.799836 -v 0.006903 -0.015421 0.081722 -vn -2.753406 0.001221 1.333593 -v 0.006168 -0.015575 0.081482 -vn -2.485811 -0.007116 1.834116 -v 0.006216 -0.015558 0.081562 -vn -2.107488 -0.011553 2.220418 -v 0.006289 -0.015539 0.081644 -vn -1.633535 0.007531 2.585309 -v 0.006360 -0.015523 0.081700 -vn -2.979848 -0.017422 0.745498 -v 0.006131 -0.015594 0.081383 -vn -3.121129 -0.053864 0.245283 -v 0.006116 -0.015612 0.081285 -vn -0.753317 0.010197 -3.025778 -v 0.006506 -0.013342 0.080735 -vn -1.359462 -0.004762 -2.739057 -v 0.006416 -0.013325 0.080768 -vn -1.851167 -0.000242 -2.421741 -v 0.006324 -0.013305 0.080826 -vn -2.245014 0.005914 -2.050665 -v 0.006256 -0.013289 0.080888 -vn -2.683308 -0.014375 -1.576339 -v 0.006194 -0.013271 0.080971 -vn -3.070569 -0.039644 -1.048969 -v 0.006151 -0.013254 0.081055 -vn -3.246589 -0.023840 -0.093984 -v 0.006115 -0.013218 0.081250 -vn 2.973278 -0.015254 -1.151604 -v 0.007150 -0.012284 0.081062 -vn -0.938771 -0.013015 -2.950355 -v 0.006506 -0.010942 0.080735 -vn -0.402624 0.006651 -3.014257 -v 0.006579 -0.010955 0.080720 -vn -0.025628 -0.009228 -3.116582 -v 0.006617 -0.010962 0.080716 -vn 0.587029 -0.015191 -3.034307 -v 0.006790 -0.010993 0.080733 -vn 1.158012 -0.004555 -2.866998 -v 0.006816 -0.010998 0.080741 -vn 1.984725 -0.007271 -2.475394 -v 0.006979 -0.011031 0.080828 -vn 2.763845 0.002721 -1.611260 -v 0.007117 -0.011069 0.080988 -vn 2.902731 -0.004520 0.951998 -v 0.007164 -0.011145 0.081400 -vn 3.053731 -0.004072 0.387528 -v 0.007177 -0.011135 0.081343 -vn 3.058036 -0.007292 -0.177947 -v 0.007181 -0.011107 0.081189 -vn 2.984798 0.018178 -0.752171 -v 0.007176 -0.011100 0.081150 -vn 0.196403 -0.003439 3.203744 -v 0.006701 -0.011259 0.081783 -vn 1.118613 -0.001375 2.895029 -v 0.006869 -0.011228 0.081738 -vn 1.611166 0.022672 2.643498 -v 0.006903 -0.011221 0.081722 -vn 2.083122 0.015876 2.285226 -v 0.007032 -0.011192 0.081624 -vn 2.335500 0.004356 1.897812 -v 0.007066 -0.011183 0.081587 -vn 2.641724 0.002154 1.533763 -v 0.007104 -0.011171 0.081533 -vn -0.920349 0.011983 3.100617 -v 0.006490 -0.011297 0.081761 -vn -1.986428 -0.005437 2.470064 -v 0.006305 -0.011335 0.081659 -vn -2.506224 -0.000060 1.779052 -v 0.006198 -0.011364 0.081535 -vn -2.994484 0.007504 0.705107 -v 0.006123 -0.011401 0.081346 -vn -2.812322 0.007863 1.264683 -v 0.006174 -0.011373 0.081494 -vn -2.974011 0.020433 -0.825502 -v 0.006143 -0.011449 0.081081 -vn -3.101940 -0.000199 -0.251444 -v 0.006116 -0.011422 0.081229 -vn -3.023771 -0.006094 0.182845 -v 0.006116 -0.011411 0.081291 -vn -2.758028 0.011924 -1.349796 -v 0.006159 -0.011457 0.081037 -vn -2.403530 0.004030 -1.893294 -v 0.006247 -0.011487 0.080898 -vn -2.057880 0.002324 -2.317077 -v 0.006265 -0.011491 0.080878 -vn -1.372315 0.003639 -2.879060 -v 0.006415 -0.011525 0.080769 -vn -0.231335 -0.025216 -3.182719 -v 0.006619 -0.011563 0.080716 -vn 0.621297 -0.010371 -3.023146 -v 0.006793 -0.011594 0.080735 -vn 1.186250 0.003339 -2.830753 -v 0.006829 -0.011601 0.080746 -vn 1.727161 0.007342 -2.542650 -v 0.006974 -0.011630 0.080824 -vn 2.073673 -0.005363 -2.194360 -v 0.007010 -0.011638 0.080854 -vn 2.429065 0.000378 -1.906918 -v 0.007060 -0.011652 0.080907 -vn 2.758034 0.006884 -1.388020 -v 0.007135 -0.011676 0.081025 -vn 2.968066 -0.010718 -0.907618 -v 0.007156 -0.011686 0.081076 -vn 3.072498 -0.004978 -0.280289 -v 0.007185 -0.011714 0.081230 -vn 3.074463 0.004776 0.291010 -v 0.007185 -0.011721 0.081265 -vn 2.937965 0.012662 0.885531 -v 0.007151 -0.011752 0.081438 -vn 2.753551 -0.009076 1.381053 -v 0.007144 -0.011756 0.081456 -vn 2.298725 0.003159 2.214744 -v 0.007039 -0.011790 0.081618 -vn 1.324959 0.014598 2.868841 -v 0.006866 -0.011828 0.081739 -vn -1.032439 -0.001694 2.858782 -v 0.006452 -0.011904 0.081747 -vn -0.470787 -0.017223 3.042875 -v 0.006577 -0.011881 0.081780 -vn -0.023517 -0.013248 3.022763 -v 0.006660 -0.011866 0.081785 -vn 0.462791 0.002397 3.038330 -v 0.006697 -0.011860 0.081783 -vn -2.967535 0.038962 1.229743 -v 0.006157 -0.011980 0.081457 -vn -2.520904 0.021961 1.882397 -v 0.006244 -0.011950 0.081599 -vn -2.080470 0.008115 2.272139 -v 0.006275 -0.011942 0.081632 -vn -1.540146 -0.000849 2.623207 -v 0.006395 -0.011915 0.081720 -vn -3.201956 0.002421 0.000368 -v 0.006115 -0.012018 0.081250 -vn -2.950714 0.026920 -1.259709 -v 0.006157 -0.012056 0.081043 -vn -2.471627 0.033183 -1.909327 -v 0.006257 -0.012089 0.080887 -vn 1.117411 0.010547 -2.869443 -v 0.006866 -0.012208 0.080761 -vn 0.514891 -0.015529 -3.045592 -v 0.006716 -0.012180 0.080719 -vn -0.041399 -0.007959 -3.058747 -v 0.006660 -0.012170 0.080715 -vn -0.665390 0.001352 -2.976572 -v 0.006521 -0.012145 0.080731 -vn -1.169038 0.007639 -2.806843 -v 0.006452 -0.012132 0.080753 -vn -1.684237 0.001723 -2.533178 -v 0.006347 -0.012111 0.080809 -vn -2.047680 -0.002464 -2.195258 -v 0.006275 -0.012094 0.080868 -vn 2.482203 -0.020386 -1.876724 -v 0.007046 -0.012248 0.080890 -vn 2.069862 0.030648 -2.281350 -v 0.007039 -0.012246 0.080882 -vn 1.637515 0.024398 -2.639186 -v 0.006903 -0.012215 0.080779 -vn 3.163068 0.007318 0.008311 -v 0.007185 -0.012322 0.081270 -vn 3.026730 0.011525 0.685008 -v 0.007171 -0.012340 0.081372 -vn 2.783745 0.004920 1.262660 -v 0.007135 -0.012360 0.081475 -vn 2.514093 0.011676 1.763043 -v 0.007096 -0.012374 0.081546 -vn 2.141304 0.003780 2.189377 -v 0.007010 -0.012398 0.081646 -vn 1.675123 -0.006228 2.567688 -v 0.006957 -0.012410 0.081688 -vn 1.108078 -0.001459 2.870441 -v 0.006829 -0.012435 0.081754 -vn 0.592325 0.000664 3.064441 -v 0.006777 -0.012445 0.081769 -vn 0.037646 0.014041 3.091426 -v 0.006620 -0.012473 0.081784 -vn -0.507708 -0.004693 3.048495 -v 0.006599 -0.012477 0.081783 -vn -1.427252 -0.022188 2.841811 -v 0.006416 -0.012511 0.081731 -vn -2.284252 0.003742 2.195056 -v 0.006247 -0.012549 0.081602 -vn -3.040288 -0.003076 -0.154876 -v 0.006116 -0.012625 0.081209 -vn -3.033804 -0.007921 0.440180 -v 0.006122 -0.012603 0.081332 -vn -2.898888 -0.000990 0.955504 -v 0.006143 -0.012587 0.081419 -vn -2.665050 0.014748 1.529042 -v 0.006183 -0.012569 0.081512 -vn -0.900845 0.006758 -3.066999 -v 0.006490 -0.012739 0.080739 -vn -1.705844 -0.009530 -2.584129 -v 0.006329 -0.012707 0.080822 -vn -2.097991 0.011808 -2.247122 -v 0.006305 -0.012701 0.080841 -vn -2.481414 0.003232 -1.835658 -v 0.006209 -0.012675 0.080948 -vn -2.750392 0.003001 -1.338486 -v 0.006174 -0.012663 0.081006 -vn -2.960105 0.000407 -0.747057 -v 0.006128 -0.012639 0.081131 -vn 0.289478 0.013637 -3.175321 -v 0.006701 -0.012777 0.080717 -vn 1.354505 -0.011345 -2.832965 -v 0.006903 -0.012815 0.080778 -vn 1.957269 -0.009324 -2.392809 -v 0.006986 -0.012833 0.080834 -vn 2.378677 0.012556 -1.971916 -v 0.007066 -0.012853 0.080913 -vn 2.689237 0.010939 -1.488362 -v 0.007117 -0.012869 0.080988 -vn 2.933083 -0.006154 -0.884565 -v 0.007164 -0.012891 0.081100 -vn 3.072332 -0.008143 -0.333753 -v 0.007180 -0.012905 0.081180 -vn 3.077996 0.015805 0.269331 -v 0.007181 -0.012929 0.081311 -vn 2.960719 0.011594 0.818911 -v 0.007169 -0.012942 0.081383 -vn 2.709503 -0.003736 1.433021 -v 0.007117 -0.012967 0.081512 -vn 2.419553 -0.007465 1.921532 -v 0.007082 -0.012978 0.081566 -vn 2.001920 0.009092 2.365102 -v 0.006979 -0.013005 0.081672 -vn 1.588470 -0.011255 2.680727 -v 0.006943 -0.013013 0.081697 -vn 0.992933 -0.013604 2.933404 -v 0.006790 -0.013043 0.081767 -vn 0.405820 -0.003616 3.060852 -v 0.006755 -0.013049 0.081775 -vn -0.461164 -0.006745 3.135165 -v 0.006579 -0.013081 0.081780 -vn -1.535160 -0.009225 2.805930 -v 0.006380 -0.013119 0.081712 -vn -2.054157 0.008728 2.340327 -v 0.006289 -0.013139 0.081644 -vn -2.458959 0.006789 1.825729 -v 0.006222 -0.013157 0.081571 -vn -2.796308 0.013803 1.334491 -v 0.006168 -0.013175 0.081482 -vn -3.083023 0.008304 0.688125 -v 0.006131 -0.013194 0.081381 -vn -1.461022 -0.024391 -2.713697 -v 0.006380 -0.010917 0.080788 -vn -1.975163 0.002620 -2.354578 -v 0.006324 -0.010905 0.080826 -vn -2.360007 0.000025 -1.950914 -v 0.006222 -0.010879 0.080929 -vn -2.704659 0.024703 -1.466200 -v 0.006194 -0.010871 0.080971 -vn -3.108573 0.022997 -0.787854 -v 0.006131 -0.010842 0.081119 -vn -3.171765 -0.028630 -0.075028 -v 0.006115 -0.010818 0.081250 -vn -0.238344 0.001025 3.082921 -v 0.006590 -0.009478 0.081782 -vn -0.800869 0.005112 2.996157 -v 0.006528 -0.009490 0.081771 -vn -1.274536 -0.008499 2.785388 -v 0.006402 -0.009514 0.081724 -vn -1.701762 0.002835 2.536790 -v 0.006376 -0.009519 0.081710 -vn -2.164132 0.005672 2.150578 -v 0.006252 -0.009548 0.081607 -vn -2.476034 -0.006420 1.757031 -v 0.006227 -0.009555 0.081578 -vn -2.906978 -0.015438 1.153318 -v 0.006157 -0.009580 0.081458 -vn -3.136179 -0.010591 0.228832 -v 0.006115 -0.009614 0.081271 -vn -3.068915 0.008010 -0.457341 -v 0.006122 -0.009634 0.081161 -vn -2.916011 0.009136 -0.943254 -v 0.006138 -0.009646 0.081096 -vn -2.668495 0.001157 -1.518031 -v 0.006192 -0.009670 0.080974 -vn -2.396355 -0.010612 -1.933698 -v 0.006224 -0.009680 0.080926 -vn -1.985392 -0.005371 -2.333004 -v 0.006320 -0.009704 0.080829 -vn -1.570807 -0.015742 -2.669797 -v 0.006354 -0.009712 0.080805 -vn -1.057902 0.009173 -2.920957 -v 0.006496 -0.009740 0.080738 -vn 0.303011 0.011336 -3.127163 -v 0.006706 -0.009778 0.080718 -vn -0.532112 0.007181 -3.030222 -v 0.006529 -0.009746 0.080729 -vn 2.833325 0.037739 -1.374906 -v 0.007139 -0.009878 0.081033 -vn 2.362672 0.002550 -1.980304 -v 0.007032 -0.009844 0.080875 -vn 1.951725 -0.006640 -2.366594 -v 0.007016 -0.009840 0.080859 -vn 1.506085 -0.013577 -2.695932 -v 0.006889 -0.009812 0.080771 -vn 0.980538 0.008601 -2.913074 -v 0.006841 -0.009803 0.080750 -vn 3.005327 0.024994 -0.783567 -v 0.007168 -0.009894 0.081115 -vn 3.111000 -0.044540 -0.299828 -v 0.007183 -0.009910 0.081205 -vn 3.096530 -0.022775 -0.025084 -v 0.007185 -0.009917 0.081246 -vn 3.059007 0.009330 0.415976 -v 0.007180 -0.009930 0.081320 -vn 2.941390 0.027149 0.775672 -v 0.007165 -0.009944 0.081395 -vn 2.806608 0.005951 1.196418 -v 0.007149 -0.009953 0.081443 -vn 2.581199 -0.004655 1.648458 -v 0.007090 -0.009976 0.081555 -vn 2.393279 -0.004930 1.820804 -v 0.007077 -0.009980 0.081573 -vn 2.179289 -0.014044 2.128911 -v 0.007046 -0.009988 0.081609 -vn 1.816279 -0.006858 2.499559 -v 0.006954 -0.010010 0.081690 -vn 1.340616 0.001016 2.731674 -v 0.006888 -0.010024 0.081729 -vn 0.883676 0.003454 2.880862 -v 0.006794 -0.010042 0.081765 -vn 0.597755 -0.000155 2.937965 -v 0.006763 -0.010047 0.081773 -vn 0.207472 0.006705 3.046171 -v 0.006696 -0.010060 0.081783 -vn -0.260820 0.008569 3.068074 -v 0.006604 -0.010076 0.081783 -vn -0.827685 -0.008038 2.947110 -v 0.006502 -0.010094 0.081764 -vn -1.167473 -0.000484 2.804099 -v 0.006433 -0.010108 0.081739 -vn -1.461532 0.014638 2.637252 -v 0.006402 -0.010114 0.081724 -vn -1.858778 0.022560 2.433023 -v 0.006325 -0.010130 0.081675 -vn -2.555447 0.003841 1.619692 -v 0.006195 -0.010165 0.081531 -vn -2.297875 -0.001331 1.967932 -v 0.006249 -0.010149 0.081604 -vn -2.102849 0.022179 2.198148 -v 0.006275 -0.010142 0.081632 -vn -2.761888 -0.011331 1.325287 -v 0.006171 -0.010174 0.081488 -vn -2.886951 -0.007230 1.054918 -v 0.006148 -0.010184 0.081434 -vn -2.956419 -0.013397 0.600477 -v 0.006123 -0.010201 0.081345 -vn -3.007954 -0.000209 0.282728 -v 0.006118 -0.010208 0.081305 -vn -3.035249 0.008411 -0.057117 -v 0.006115 -0.010218 0.081247 -vn -2.973164 0.002573 -0.505476 -v 0.006126 -0.010237 0.081145 -vn -2.914853 -0.005027 -0.747839 -v 0.006129 -0.010240 0.081128 -vn -2.851456 -0.001672 -1.158736 -v 0.006150 -0.010253 0.081059 -vn -2.558239 0.011534 -1.806992 -v 0.006205 -0.010274 0.080953 -vn -1.900045 -0.003479 -2.523946 -v 0.006326 -0.010306 0.080824 -vn -1.107229 -0.000731 -2.880173 -v 0.006496 -0.010340 0.080738 -vn -0.542120 -0.011535 -3.065572 -v 0.006517 -0.010344 0.080732 -vn -0.082976 0.009531 -3.118411 -v 0.006672 -0.010372 0.080715 -vn 0.507727 0.001740 -3.019091 -v 0.006713 -0.010379 0.080719 -vn 1.060042 0.003602 -2.877909 -v 0.006858 -0.010406 0.080757 -vn 1.542603 -0.013484 -2.635894 -v 0.006902 -0.010415 0.080778 -vn 2.002043 -0.009980 -2.355164 -v 0.007008 -0.010438 0.080852 -vn 2.469322 -0.036357 -1.948487 -v 0.007057 -0.010450 0.080903 -vn 2.756385 -0.034005 -1.531367 -v 0.007124 -0.010472 0.081003 -vn 2.928216 -0.019428 -0.971938 -v 0.007159 -0.010488 0.081086 -vn 3.019834 -0.020101 -0.506665 -v 0.007179 -0.010504 0.081171 -vn 3.037457 -0.012674 -0.255515 -v 0.007183 -0.010509 0.081198 -vn 3.042154 -0.019563 0.194505 -v 0.007184 -0.010524 0.081284 -vn 2.978100 -0.007086 0.559567 -v 0.007173 -0.010538 0.081362 -vn 2.878875 0.002599 0.856843 -v 0.007166 -0.010543 0.081392 -vn 2.759171 0.009154 1.256961 -v 0.007135 -0.010559 0.081476 -vn 2.592228 0.005739 1.576454 -v 0.007108 -0.010570 0.081527 -vn 2.439913 0.006672 1.849862 -v 0.007081 -0.010578 0.081567 -vn 2.135235 -0.007294 2.165592 -v 0.007019 -0.010595 0.081638 -vn 1.882744 0.001765 2.387429 -v 0.006982 -0.010604 0.081670 -vn 1.600736 0.019072 2.577319 -v 0.006940 -0.010613 0.081699 -vn 1.197030 0.010107 2.795206 -v 0.006850 -0.010631 0.081746 -vn 0.838069 0.022549 3.018344 -v 0.006827 -0.010636 0.081755 -vn 0.405503 0.044841 3.104002 -v 0.006683 -0.010662 0.081784 -vn 0.046108 0.006502 2.975229 -v 0.006658 -0.010666 0.081785 -vn -0.246173 0.008951 3.056399 -v 0.006638 -0.010670 0.081785 -vn -0.717738 0.020298 2.969196 -v 0.006498 -0.010695 0.081763 -vn -1.227990 0.001638 2.807823 -v 0.006464 -0.010702 0.081752 -vn -1.719645 0.006699 2.526274 -v 0.006323 -0.010731 0.081674 -vn -2.143760 -0.016091 2.188591 -v 0.006300 -0.010736 0.081654 -vn -2.495862 -0.006691 1.792056 -v 0.006195 -0.010765 0.081532 -vn -2.570559 0.000676 1.468168 -v 0.006187 -0.010768 0.081518 -vn -2.868672 -0.023822 1.193777 -v 0.006172 -0.010773 0.081491 -vn -3.104465 -0.042650 0.641692 -v 0.006122 -0.010802 0.081338 -vn 0.335289 0.015402 3.089005 -v 0.006726 -0.009454 0.081779 -vn 0.594779 4.006989 4.279747 -v 0.006769 -0.009702 0.082235 -vn 0.922428 0.018337 2.940919 -v 0.006788 -0.009443 0.081767 -vn 1.058529 4.900134 3.582216 -v 0.006993 -0.009650 0.082125 -vn 1.772883 0.503223 3.242932 -v 0.006915 -0.009418 0.081715 -vn 1.593733 4.884600 3.421795 -v 0.007100 -0.009620 0.082041 -vn 0.597252 5.846856 1.469188 -v 0.006955 -0.009410 0.081690 -vn 2.231967 4.845255 3.039304 -v 0.007183 -0.009593 0.081954 -vn 0.828910 5.842717 1.370543 -v 0.007101 -0.009410 0.081621 -vn 2.730793 4.903707 2.549194 -v 0.007314 -0.009533 0.081735 -vn 1.031254 5.846476 1.214503 -v 0.007131 -0.009410 0.081600 -vn 3.052159 4.950679 2.070196 -v 0.007343 -0.009511 0.081650 -vn 1.384463 5.815079 0.874849 -v 0.007274 -0.009410 0.081444 -vn 3.425139 4.905864 1.432394 -v 0.007369 -0.009473 0.081504 -vn 2.275295 5.278049 0.304082 -v 0.007350 -0.009410 0.081275 -vn 0.772596 0.357436 1.233515 -v 0.006807 -0.009410 0.081825 -vn 3.438954 -0.474448 0.761421 -v 0.007594 -0.009702 0.081559 -vn 3.533400 -0.481890 0.132002 -v 0.007626 -0.009686 0.081314 -vn 3.570832 -0.494686 -0.386032 -v 0.007623 -0.009682 0.081250 -vn 3.337306 -0.440837 -0.979894 -v 0.007594 -0.009670 0.081073 -vn 3.169382 -0.469514 -1.568330 -v 0.007507 -0.009655 0.080853 -vn 2.904630 -0.502568 -2.081770 -v 0.007464 -0.009650 0.080780 -vn 2.510021 -0.457044 -2.426644 -v 0.007353 -0.009638 0.080642 -vn 2.168391 -0.417136 -2.745649 -v 0.007280 -0.009631 0.080576 -vn 1.667088 -0.467364 -3.111063 -v 0.007151 -0.009621 0.080489 -vn 1.081411 -0.460160 -3.397661 -v 0.006971 -0.009607 0.080413 -vn 0.580885 -0.416809 -3.444608 -v 0.006907 -0.009603 0.080396 -vn -0.109483 -0.475711 -3.533923 -v 0.006650 -0.009585 0.080375 -vn -0.668617 -0.488793 -3.532708 -v 0.006550 -0.009578 0.080387 -vn -1.021521 -0.483682 -3.398407 -v 0.006492 -0.009573 0.080400 -vn -1.635918 -0.468619 -3.108386 -v 0.006318 -0.009560 0.080467 -vn -2.154066 -0.498842 -2.861053 -v 0.006197 -0.009549 0.080544 -vn -2.588266 -0.462467 -2.429396 -v 0.006113 -0.009541 0.080617 -vn -3.056995 -0.472908 -1.694494 -v 0.005975 -0.009524 0.080795 -vn -3.375889 -0.444742 -0.707905 -v 0.005889 -0.009506 0.081014 -vn -3.459794 -0.443778 0.375243 -v 0.005875 -0.009486 0.081261 -vn -3.233012 -0.434370 1.286645 -v 0.005924 -0.009469 0.081472 -vn -2.798364 -0.191791 1.539898 -v 0.005973 -0.009459 0.081573 -vn -2.697344 -0.445520 2.274478 -v 0.006039 -0.009450 0.081669 -vn -2.151987 -0.263113 2.546004 -v 0.006123 -0.009440 0.081756 -vn -1.835710 -0.496557 3.081643 -v 0.006214 -0.009430 0.081823 -vn -0.931120 0.084840 2.605550 -v 0.006354 -0.009416 0.081891 -vn -0.087449 0.358377 1.437566 -v 0.006428 -0.009410 0.081914 -vn 0.349585 0.344056 1.378278 -v 0.006643 -0.009410 0.081895 -vn -1.376664 5.234048 1.883469 -v 0.006228 -0.009410 0.081808 -vn -1.887503 5.303436 1.256542 -v 0.006072 -0.009410 0.081645 -vn -2.265466 5.207350 0.628112 -v 0.005976 -0.009410 0.081440 -vn -2.360051 5.196605 -0.132300 -v 0.005951 -0.009410 0.081214 -vn -2.203853 5.233540 -0.767291 -v 0.005990 -0.009410 0.081018 -vn -2.054678 5.241586 -1.103688 -v 0.006044 -0.009410 0.080900 -vn -1.769077 5.251349 -1.502312 -v 0.006098 -0.009410 0.080819 -vn -1.278747 5.242815 -1.935896 -v 0.006264 -0.009410 0.080666 -vn -0.619101 5.253554 -2.228997 -v 0.006471 -0.009410 0.080573 -vn 0.123571 5.218546 -2.331544 -v 0.006650 -0.009410 0.080550 -vn 1.170448 5.190411 -2.027138 -v 0.007000 -0.009410 0.080644 -vn 2.041865 5.180056 -1.158932 -v 0.007256 -0.009410 0.080900 -vn 2.293391 5.261362 -0.238225 -v 0.007350 -0.009410 0.081250 -vn 1.707466 -3.365983 -2.613513 -v 0.035703 -0.042610 0.084056 -vn 1.707466 3.365983 -2.613513 -v 0.035703 -0.040410 0.084056 -vn 1.083110 -3.365991 -2.927927 -v 0.035903 -0.042610 0.084157 -vn 1.083110 3.365991 -2.927926 -v 0.035903 -0.040410 0.084157 -vn 0.404411 -3.366005 -3.095531 -v 0.036120 -0.042610 0.084210 -vn 0.404411 3.366005 -3.095532 -v 0.036120 -0.040410 0.084210 -vn -0.294558 -3.365985 -3.107913 -v 0.036344 -0.042610 0.084214 -vn -0.294558 3.365985 -3.107913 -v 0.036344 -0.040410 0.084214 -vn -0.978741 -3.365994 -2.964446 -v 0.036564 -0.042610 0.084168 -vn -0.978741 3.365994 -2.964446 -v 0.036564 -0.040410 0.084168 -vn -1.613858 -3.365993 -2.672328 -v 0.036767 -0.042610 0.084075 -vn -1.613858 3.365993 -2.672329 -v 0.036767 -0.040410 0.084075 -vn -2.168024 -3.365971 -2.246236 -v 0.036944 -0.042610 0.083938 -vn -2.168024 3.365971 -2.246236 -v 0.036944 -0.040410 0.083938 -vn -2.613495 -3.366014 -1.707484 -v 0.037087 -0.042610 0.083766 -vn -2.613495 3.366014 -1.707483 -v 0.037087 -0.040410 0.083766 -vn -2.927932 -3.365983 -1.083099 -v 0.037188 -0.042610 0.083566 -vn -2.927931 3.365983 -1.083099 -v 0.037188 -0.040410 0.083566 -vn -3.095531 -3.366004 -0.404412 -v 0.037242 -0.042610 0.083348 -vn -3.095531 3.366004 -0.404412 -v 0.037242 -0.040410 0.083348 -vn -3.107913 -3.365982 0.294552 -v 0.037246 -0.042610 0.083124 -vn -3.107914 3.365982 0.294553 -v 0.037246 -0.040410 0.083124 -vn -2.964453 -3.365990 0.978724 -v 0.037200 -0.042610 0.082905 -vn -2.964453 3.365990 0.978724 -v 0.037200 -0.040410 0.082905 -vn -2.672354 -3.365981 1.613821 -v 0.037106 -0.042610 0.082702 -vn -2.672354 3.365980 1.613821 -v 0.037106 -0.040410 0.082702 -vn -2.246215 -3.366025 2.168032 -v 0.036970 -0.042610 0.082524 -vn -2.246214 3.366025 2.168032 -v 0.036970 -0.040410 0.082524 -vn -1.707452 -3.365972 2.613523 -v 0.036797 -0.042610 0.082382 -vn -1.707453 3.365972 2.613524 -v 0.036797 -0.040410 0.082382 -vn 1.712404 2.976236 -2.621062 -v 0.037207 -0.042010 0.081754 -vn 1.712403 -2.976236 -2.621062 -v 0.037207 -0.042610 0.081754 -vn 1.257643 -2.976260 -2.867167 -v 0.036953 -0.042610 0.081616 -vn 1.257644 2.976259 -2.867167 -v 0.036953 -0.042010 0.081616 -vn 0.768584 -2.976241 -3.035058 -v 0.036680 -0.042610 0.081522 -vn 0.768584 2.976241 -3.035058 -v 0.036680 -0.042010 0.081522 -vn 0.258543 -2.976247 -3.120170 -v 0.036395 -0.042610 0.081475 -vn 0.258543 2.976247 -3.120169 -v 0.036395 -0.042010 0.081475 -vn -0.258582 -2.976221 -3.120163 -v 0.036105 -0.042610 0.081475 -vn -0.258582 2.976222 -3.120163 -v 0.036105 -0.042010 0.081475 -vn -0.768624 -2.976266 -3.035051 -v 0.035820 -0.042610 0.081522 -vn -0.768624 2.976267 -3.035051 -v 0.035820 -0.042010 0.081522 -vn -1.257652 -2.976254 -2.867162 -v 0.035547 -0.042610 0.081616 -vn -1.257652 2.976253 -2.867162 -v 0.035547 -0.042010 0.081616 -vn -1.712412 -2.976242 -2.621058 -v 0.035293 -0.042610 0.081754 -vn -1.712412 2.976242 -2.621058 -v 0.035293 -0.042010 0.081754 -vn -2.120491 -2.976228 -2.303433 -v 0.035065 -0.042610 0.081931 -vn -2.120491 2.976228 -2.303433 -v 0.035065 -0.042010 0.081931 -vn -2.470710 -2.976259 -1.922994 -v 0.034869 -0.042610 0.082144 -vn -2.470710 2.976259 -1.922993 -v 0.034869 -0.042010 0.082144 -vn -2.753517 -2.976243 -1.490115 -v 0.034711 -0.042610 0.082386 -vn -2.753517 2.976243 -1.490115 -v 0.034711 -0.042010 0.082386 -vn -2.961228 -2.976247 -1.016577 -v 0.034595 -0.042610 0.082651 -vn -2.961228 2.976247 -1.016577 -v 0.034595 -0.042010 0.082651 -vn -3.088163 -2.976250 -0.515320 -v 0.034524 -0.042610 0.082931 -vn -3.088163 2.976250 -0.515320 -v 0.034524 -0.042010 0.082931 -vn -3.130861 -2.976231 0.000020 -v 0.034500 -0.042610 0.083219 -vn -3.130861 2.976231 0.000020 -v 0.034500 -0.042010 0.083219 -vn -3.088161 -2.976263 0.515340 -v 0.034524 -0.042610 0.083507 -vn -3.088161 2.976263 0.515340 -v 0.034524 -0.042010 0.083507 -vn -2.961221 -2.976236 1.016594 -v 0.034595 -0.042610 0.083787 -vn -2.961221 2.976235 1.016594 -v 0.034595 -0.042010 0.083787 -vn -2.753510 -2.976255 1.490132 -v 0.034711 -0.042610 0.084052 -vn -2.753510 2.976255 1.490132 -v 0.034711 -0.042010 0.084052 -vn -2.470671 -2.976223 1.923036 -v 0.034869 -0.042610 0.084294 -vn -2.470671 2.976223 1.923035 -v 0.034869 -0.042010 0.084294 -vn -2.120452 -2.976265 2.303475 -v 0.035065 -0.042610 0.084506 -vn -2.120452 2.976265 2.303475 -v 0.035065 -0.042010 0.084506 -vn -1.712412 -2.976242 2.621058 -v 0.035293 -0.042610 0.084684 -vn -1.712412 2.976242 2.621058 -v 0.035293 -0.042010 0.084684 -vn 1.712404 2.976236 -2.621062 -v 0.037207 -0.040410 0.081754 -vn 1.712404 -2.976236 -2.621062 -v 0.037207 -0.041010 0.081754 -vn 1.257643 -2.976260 -2.867167 -v 0.036953 -0.041010 0.081616 -vn 1.257643 2.976260 -2.867167 -v 0.036953 -0.040410 0.081616 -vn 0.768584 -2.976241 -3.035058 -v 0.036680 -0.041010 0.081522 -vn 0.768584 2.976241 -3.035058 -v 0.036680 -0.040410 0.081522 -vn 0.258543 -2.976247 -3.120170 -v 0.036395 -0.041010 0.081475 -vn 0.258543 2.976247 -3.120169 -v 0.036395 -0.040410 0.081475 -vn -0.258582 -2.976222 -3.120163 -v 0.036105 -0.041010 0.081475 -vn -0.258582 2.976222 -3.120162 -v 0.036105 -0.040410 0.081475 -vn -0.768624 -2.976267 -3.035051 -v 0.035820 -0.041010 0.081522 -vn -0.768624 2.976266 -3.035051 -v 0.035820 -0.040410 0.081522 -vn -1.257652 -2.976254 -2.867162 -v 0.035547 -0.041010 0.081616 -vn -1.257652 2.976254 -2.867162 -v 0.035547 -0.040410 0.081616 -vn -1.712412 -2.976242 -2.621058 -v 0.035293 -0.041010 0.081754 -vn -1.712412 2.976242 -2.621058 -v 0.035293 -0.040410 0.081754 -vn -2.120491 -2.976228 -2.303433 -v 0.035065 -0.041010 0.081931 -vn -2.120491 2.976229 -2.303433 -v 0.035065 -0.040410 0.081931 -vn -2.470710 -2.976259 -1.922994 -v 0.034869 -0.041010 0.082144 -vn -2.470710 2.976259 -1.922993 -v 0.034869 -0.040410 0.082144 -vn -2.753517 -2.976243 -1.490115 -v 0.034711 -0.041010 0.082386 -vn -2.753517 2.976243 -1.490115 -v 0.034711 -0.040410 0.082386 -vn -2.961228 -2.976247 -1.016577 -v 0.034595 -0.041010 0.082651 -vn -2.961228 2.976248 -1.016577 -v 0.034595 -0.040410 0.082651 -vn -3.088163 -2.976250 -0.515320 -v 0.034524 -0.041010 0.082931 -vn -3.088162 2.976250 -0.515320 -v 0.034524 -0.040410 0.082931 -vn -3.130860 -2.976231 0.000020 -v 0.034500 -0.041010 0.083219 -vn -3.130861 2.976231 0.000020 -v 0.034500 -0.040410 0.083219 -vn -3.088161 -2.976263 0.515340 -v 0.034524 -0.041010 0.083507 -vn -3.088161 2.976263 0.515340 -v 0.034524 -0.040410 0.083507 -vn -2.961221 -2.976235 1.016594 -v 0.034595 -0.041010 0.083787 -vn -2.961221 2.976235 1.016594 -v 0.034595 -0.040410 0.083787 -vn -2.753510 -2.976255 1.490132 -v 0.034711 -0.041010 0.084052 -vn -2.753510 2.976255 1.490132 -v 0.034711 -0.040410 0.084052 -vn -2.470671 -2.976222 1.923036 -v 0.034869 -0.041010 0.084294 -vn -2.470671 2.976223 1.923036 -v 0.034869 -0.040410 0.084294 -vn -2.120452 -2.976265 2.303475 -v 0.035065 -0.041010 0.084506 -vn -2.120452 2.976265 2.303475 -v 0.035065 -0.040410 0.084506 -vn -1.712412 -2.976242 2.621058 -v 0.035293 -0.041010 0.084684 -vn -1.712412 2.976242 2.621058 -v 0.035293 -0.040410 0.084684 -vn 1.710948 -3.326382 -2.618825 -v 0.037070 -0.041010 0.081963 -vn 1.710948 3.326382 -2.618825 -v 0.037070 -0.042010 0.081963 -vn 1.200624 3.326391 -2.888613 -v 0.036826 -0.042010 0.081834 -vn 1.200624 -3.326392 -2.888613 -v 0.036826 -0.041010 0.081834 -vn 0.649381 3.326405 -3.060044 -v 0.036561 -0.042010 0.081751 -vn 0.649381 -3.326405 -3.060045 -v 0.036561 -0.041010 0.081751 -vn 0.076019 3.326394 -3.127267 -v 0.036286 -0.042010 0.081719 -vn 0.076019 -3.326395 -3.127267 -v 0.036286 -0.041010 0.081719 -vn -0.499879 3.326370 -3.087996 -v 0.036010 -0.042010 0.081738 -vn -0.499879 -3.326370 -3.087996 -v 0.036010 -0.041010 0.081738 -vn -1.058777 3.326411 -2.943562 -v 0.035742 -0.042010 0.081807 -vn -1.058777 -3.326410 -2.943562 -v 0.035742 -0.041010 0.081807 -vn -1.581653 3.326392 -2.698880 -v 0.035492 -0.042010 0.081925 -vn -1.581653 -3.326392 -2.698880 -v 0.035492 -0.041010 0.081925 -vn -2.050636 3.326389 -2.362303 -v 0.035267 -0.042010 0.082086 -vn -2.050636 -3.326389 -2.362303 -v 0.035267 -0.041010 0.082086 -vn -2.449786 3.326389 -1.945285 -v 0.035075 -0.042010 0.082286 -vn -2.449786 -3.326389 -1.945285 -v 0.035075 -0.041010 0.082286 -vn -2.765520 3.326397 -1.462011 -v 0.034924 -0.042010 0.082518 -vn -2.765520 -3.326398 -1.462011 -v 0.034924 -0.041010 0.082518 -vn -2.987075 3.326382 -0.928962 -v 0.034818 -0.042010 0.082773 -vn -2.987075 -3.326382 -0.928962 -v 0.034818 -0.041010 0.082773 -vn -3.106908 3.326403 -0.364270 -v 0.034760 -0.042010 0.083044 -vn -3.106908 -3.326403 -0.364270 -v 0.034760 -0.041010 0.083044 -vn -3.120942 3.326394 0.212844 -v 0.034753 -0.042010 0.083321 -vn -3.120941 -3.326394 0.212844 -v 0.034753 -0.041010 0.083321 -vn -3.028695 3.326386 0.782684 -v 0.034798 -0.042010 0.083594 -vn -3.028695 -3.326386 0.782684 -v 0.034798 -0.041010 0.083594 -vn -2.833304 3.326401 1.325882 -v 0.034891 -0.042010 0.083855 -vn -2.833304 -3.326401 1.325882 -v 0.034891 -0.041010 0.083855 -vn -2.541440 3.326377 1.823918 -v 0.035031 -0.042010 0.084093 -vn -2.541440 -3.326377 1.823918 -v 0.035031 -0.041010 0.084093 -vn -2.163013 3.326413 2.259853 -v 0.035213 -0.042010 0.084302 -vn -2.163013 -3.326413 2.259853 -v 0.035213 -0.041010 0.084302 -vn -1.710947 3.326367 2.618829 -v 0.035430 -0.042010 0.084475 -vn -1.710947 -3.326367 2.618829 -v 0.035430 -0.041010 0.084475 -vn -1.083116 -3.365987 2.927925 -v 0.036597 -0.042610 0.082281 -vn -1.083116 3.365987 2.927925 -v 0.036597 -0.040410 0.082281 -vn -0.404417 -3.366009 3.095531 -v 0.036380 -0.042610 0.082227 -vn -0.404417 3.366009 3.095530 -v 0.036380 -0.040410 0.082227 -vn 0.294558 -3.365985 3.107913 -v 0.036156 -0.042610 0.082223 -vn 0.294558 3.365985 3.107913 -v 0.036156 -0.040410 0.082223 -vn 0.978741 -3.365994 2.964446 -v 0.035936 -0.042610 0.082269 -vn 0.978741 3.365994 2.964446 -v 0.035936 -0.040410 0.082269 -vn 1.613845 -3.365983 2.672338 -v 0.035733 -0.042610 0.082363 -vn 1.613845 3.365983 2.672339 -v 0.035733 -0.040410 0.082363 -vn 2.168011 -3.365981 2.246246 -v 0.035556 -0.042610 0.082499 -vn 2.168011 3.365981 2.246246 -v 0.035556 -0.040410 0.082499 -vn 2.613495 -3.366014 1.707484 -v 0.035413 -0.042610 0.082672 -vn 2.613495 3.366014 1.707483 -v 0.035413 -0.040410 0.082672 -vn 2.927938 -3.365999 1.083075 -v 0.035312 -0.042610 0.082872 -vn 2.927938 3.365999 1.083075 -v 0.035312 -0.040410 0.082872 -vn 3.095537 -3.365972 0.404413 -v 0.035258 -0.042610 0.083089 -vn 3.095537 3.365972 0.404413 -v 0.035258 -0.040410 0.083089 -vn 3.107913 -3.365999 -0.294526 -v 0.035254 -0.042610 0.083313 -vn 3.107913 3.365999 -0.294526 -v 0.035254 -0.040410 0.083313 -vn 2.964443 -3.366004 -0.978746 -v 0.035300 -0.042610 0.083532 -vn 2.964442 3.366004 -0.978745 -v 0.035300 -0.040410 0.083532 -vn 2.672343 -3.365965 -1.613842 -v 0.035394 -0.042610 0.083736 -vn 2.672344 3.365965 -1.613842 -v 0.035394 -0.040410 0.083736 -vn 2.246227 -3.366014 -2.168022 -v 0.035530 -0.042610 0.083913 -vn 2.246227 3.366014 -2.168022 -v 0.035530 -0.040410 0.083913 -vn 1.257646 -2.976250 2.867164 -v 0.036953 -0.042610 0.084821 -vn 0.768617 -2.976271 3.035053 -v 0.036680 -0.042610 0.084915 -vn 0.258582 -2.976221 3.120163 -v 0.036395 -0.042610 0.084963 -vn -0.258543 -2.976247 3.120170 -v 0.036105 -0.042610 0.084963 -vn -0.768578 -2.976245 3.035059 -v 0.035820 -0.042610 0.084915 -vn -1.257646 -2.976249 2.867164 -v 0.035547 -0.042610 0.084821 -vn 2.470700 -2.976250 1.923005 -v 0.037631 -0.042610 0.084294 -vn 2.120491 -2.976246 2.303436 -v 0.037435 -0.042610 0.084506 -vn 1.712422 -2.976234 2.621050 -v 0.037207 -0.042610 0.084684 -vn 2.120462 -2.976256 -2.303464 -v 0.037435 -0.042610 0.081931 -vn 2.470672 -2.976243 -1.923039 -v 0.037631 -0.042610 0.082144 -vn 2.753500 -2.976244 -1.490146 -v 0.037789 -0.042610 0.082386 -vn 2.961221 -2.976236 -1.016594 -v 0.037905 -0.042610 0.082651 -vn 3.088163 -2.976250 -0.515320 -v 0.037976 -0.042610 0.082931 -vn 3.130864 -2.976256 -0.000020 -v 0.038000 -0.042610 0.083219 -vn 3.088165 -2.976237 0.515300 -v 0.037976 -0.042610 0.083507 -vn 2.961228 -2.976247 1.016577 -v 0.037905 -0.042610 0.083787 -vn 2.753517 -2.976243 1.490115 -v 0.037789 -0.042610 0.084052 -vn -0.768578 2.976245 3.035060 -v 0.035820 -0.040410 0.084915 -vn -0.258543 2.976247 3.120169 -v 0.036105 -0.040410 0.084963 -vn 0.258582 2.976221 3.120162 -v 0.036395 -0.040410 0.084963 -vn 2.470672 2.976243 -1.923039 -v 0.037631 -0.040410 0.082144 -vn 2.120462 2.976256 -2.303464 -v 0.037435 -0.040410 0.081931 -vn 3.130864 2.976256 -0.000020 -v 0.038000 -0.040410 0.083219 -vn 3.088163 2.976250 -0.515320 -v 0.037976 -0.040410 0.082931 -vn 2.961221 2.976235 -1.016594 -v 0.037905 -0.040410 0.082651 -vn 2.753500 2.976244 -1.490146 -v 0.037789 -0.040410 0.082386 -vn 2.470700 2.976250 1.923004 -v 0.037631 -0.040410 0.084294 -vn 2.753517 2.976243 1.490115 -v 0.037789 -0.040410 0.084052 -vn 2.961228 2.976247 1.016577 -v 0.037905 -0.040410 0.083787 -vn 3.088164 2.976237 0.515300 -v 0.037976 -0.040410 0.083507 -vn 0.768618 2.976271 3.035053 -v 0.036680 -0.040410 0.084915 -vn 1.257646 2.976250 2.867164 -v 0.036953 -0.040410 0.084821 -vn 1.712422 2.976234 2.621050 -v 0.037207 -0.040410 0.084684 -vn 2.120491 2.976246 2.303436 -v 0.037435 -0.040410 0.084506 -vn -1.257646 2.976249 2.867164 -v 0.035547 -0.040410 0.084821 -vn -1.257646 2.976249 2.867164 -v 0.035547 -0.042010 0.084821 -vn -0.768578 2.976245 3.035060 -v 0.035820 -0.042010 0.084915 -vn -0.258543 2.976247 3.120169 -v 0.036105 -0.042010 0.084963 -vn 0.258582 2.976222 3.120163 -v 0.036395 -0.042010 0.084963 -vn 0.768617 2.976271 3.035053 -v 0.036680 -0.042010 0.084915 -vn 1.257646 2.976249 2.867164 -v 0.036953 -0.042010 0.084821 -vn 1.712422 2.976234 2.621050 -v 0.037207 -0.042010 0.084684 -vn 2.120491 2.976246 2.303437 -v 0.037435 -0.042010 0.084506 -vn 2.470700 2.976250 1.923004 -v 0.037631 -0.042010 0.084294 -vn 2.753517 2.976243 1.490115 -v 0.037789 -0.042010 0.084052 -vn 2.961228 2.976247 1.016577 -v 0.037905 -0.042010 0.083787 -vn 3.088165 2.976237 0.515300 -v 0.037976 -0.042010 0.083507 -vn 3.130864 2.976256 -0.000020 -v 0.038000 -0.042010 0.083219 -vn 3.088163 2.976250 -0.515320 -v 0.037976 -0.042010 0.082931 -vn 2.961221 2.976235 -1.016594 -v 0.037905 -0.042010 0.082651 -vn 2.753500 2.976245 -1.490146 -v 0.037789 -0.042010 0.082386 -vn 2.470672 2.976243 -1.923039 -v 0.037631 -0.042010 0.082144 -vn 2.120462 2.976256 -2.303464 -v 0.037435 -0.042010 0.081931 -vn -1.257646 -2.976249 2.867164 -v 0.035547 -0.041010 0.084821 -vn -0.768578 -2.976245 3.035060 -v 0.035820 -0.041010 0.084915 -vn -0.258543 -2.976247 3.120170 -v 0.036105 -0.041010 0.084963 -vn 0.258582 -2.976222 3.120162 -v 0.036395 -0.041010 0.084963 -vn 0.768618 -2.976271 3.035053 -v 0.036680 -0.041010 0.084915 -vn 1.257646 -2.976249 2.867164 -v 0.036953 -0.041010 0.084821 -vn 1.712422 -2.976234 2.621050 -v 0.037207 -0.041010 0.084684 -vn 2.120491 -2.976246 2.303436 -v 0.037435 -0.041010 0.084506 -vn 2.470700 -2.976249 1.923005 -v 0.037631 -0.041010 0.084294 -vn 2.753517 -2.976243 1.490115 -v 0.037789 -0.041010 0.084052 -vn 2.961228 -2.976247 1.016577 -v 0.037905 -0.041010 0.083787 -vn 3.088164 -2.976237 0.515299 -v 0.037976 -0.041010 0.083507 -vn 3.130864 -2.976257 -0.000020 -v 0.038000 -0.041010 0.083219 -vn 3.088162 -2.976250 -0.515320 -v 0.037976 -0.041010 0.082931 -vn 2.961221 -2.976235 -1.016594 -v 0.037905 -0.041010 0.082651 -vn 2.753500 -2.976245 -1.490146 -v 0.037789 -0.041010 0.082386 -vn 2.470672 -2.976243 -1.923039 -v 0.037631 -0.041010 0.082144 -vn 2.120462 -2.976256 -2.303464 -v 0.037435 -0.041010 0.081931 -vn 3.028699 3.326404 -0.782657 -v 0.037702 -0.042010 0.082843 -vn 2.833304 3.326401 -1.325882 -v 0.037609 -0.042010 0.082583 -vn 2.541430 3.326387 -1.823930 -v 0.037469 -0.042010 0.082344 -vn 2.163013 3.326394 -2.259857 -v 0.037287 -0.042010 0.082135 -vn -1.200626 3.326402 2.888610 -v 0.035674 -0.042010 0.084604 -vn -0.649377 3.326399 3.060046 -v 0.035939 -0.042010 0.084686 -vn -0.076022 3.326396 3.127266 -v 0.036214 -0.042010 0.084718 -vn 0.499879 3.326370 3.087996 -v 0.036490 -0.042010 0.084700 -vn 1.058777 3.326410 2.943562 -v 0.036758 -0.042010 0.084630 -vn 1.581653 3.326392 2.698880 -v 0.037008 -0.042010 0.084513 -vn 2.050625 3.326379 2.362314 -v 0.037233 -0.042010 0.084352 -vn 2.449785 3.326410 1.945281 -v 0.037425 -0.042010 0.084152 -vn 2.765523 3.326376 1.462011 -v 0.037576 -0.042010 0.083920 -vn 2.987071 3.326398 0.928969 -v 0.037682 -0.042010 0.083664 -vn 3.106910 3.326397 0.364263 -v 0.037740 -0.042010 0.083393 -vn 3.120946 3.326376 -0.212815 -v 0.037747 -0.042010 0.083117 -vn 0.499879 -3.326370 3.087996 -v 0.036490 -0.041010 0.084700 -vn -0.076022 -3.326396 3.127267 -v 0.036214 -0.041010 0.084718 -vn -0.649377 -3.326399 3.060046 -v 0.035939 -0.041010 0.084686 -vn -1.200626 -3.326402 2.888610 -v 0.035674 -0.041010 0.084604 -vn 2.163013 -3.326394 -2.259856 -v 0.037287 -0.041010 0.082135 -vn 2.541430 -3.326388 -1.823930 -v 0.037469 -0.041010 0.082344 -vn 2.833304 -3.326401 -1.325882 -v 0.037609 -0.041010 0.082583 -vn 3.028699 -3.326404 -0.782657 -v 0.037702 -0.041010 0.082843 -vn 3.120946 -3.326376 -0.212815 -v 0.037747 -0.041010 0.083117 -vn 3.106910 -3.326396 0.364263 -v 0.037740 -0.041010 0.083393 -vn 2.987071 -3.326398 0.928969 -v 0.037682 -0.041010 0.083664 -vn 2.765523 -3.326376 1.462012 -v 0.037576 -0.041010 0.083920 -vn 2.449785 -3.326410 1.945281 -v 0.037425 -0.041010 0.084152 -vn 2.050625 -3.326379 2.362314 -v 0.037233 -0.041010 0.084352 -vn 1.581653 -3.326392 2.698880 -v 0.037008 -0.041010 0.084513 -vn 1.058777 -3.326410 2.943562 -v 0.036758 -0.041010 0.084630 -vn 1.707466 -3.365983 -2.613513 -v 0.045153 -0.041010 0.082937 -vn 1.707466 3.365983 -2.613513 -v 0.045153 -0.038810 0.082937 -vn 1.083110 -3.365991 -2.927927 -v 0.045353 -0.041010 0.083038 -vn 1.083110 3.365991 -2.927926 -v 0.045353 -0.038810 0.083038 -vn 0.404411 -3.366005 -3.095531 -v 0.045570 -0.041010 0.083092 -vn 0.404411 3.366005 -3.095532 -v 0.045570 -0.038810 0.083092 -vn -0.294558 -3.365985 -3.107913 -v 0.045794 -0.041010 0.083096 -vn -0.294558 3.365985 -3.107913 -v 0.045794 -0.038810 0.083096 -vn -0.978741 -3.365994 -2.964446 -v 0.046014 -0.041010 0.083050 -vn -0.978741 3.365994 -2.964446 -v 0.046014 -0.038810 0.083050 -vn -1.613845 -3.365983 -2.672338 -v 0.046217 -0.041010 0.082956 -vn -1.613845 3.365983 -2.672339 -v 0.046217 -0.038810 0.082956 -vn -2.168024 -3.365993 -2.246231 -v 0.046394 -0.041010 0.082820 -vn -2.168024 3.365993 -2.246231 -v 0.046394 -0.038810 0.082820 -vn -2.613508 -3.366001 -1.707468 -v 0.046537 -0.041010 0.082647 -vn -2.613508 3.366001 -1.707468 -v 0.046537 -0.038810 0.082647 -vn -2.927928 -3.365975 -1.083112 -v 0.046638 -0.041010 0.082447 -vn -2.927929 3.365975 -1.083112 -v 0.046638 -0.038810 0.082447 -vn -3.095529 -3.366013 -0.404423 -v 0.046692 -0.041010 0.082230 -vn -3.095529 3.366013 -0.404423 -v 0.046692 -0.038810 0.082230 -vn -3.107920 -3.365965 0.294528 -v 0.046696 -0.041010 0.082006 -vn -3.107919 3.365965 0.294528 -v 0.046696 -0.038810 0.082006 -vn -2.964448 -3.366021 0.978721 -v 0.046650 -0.041010 0.081786 -vn -2.964448 3.366021 0.978720 -v 0.046650 -0.038810 0.081786 -vn -2.672324 -3.365986 1.613867 -v 0.046556 -0.041010 0.081583 -vn -2.672325 3.365986 1.613868 -v 0.046556 -0.038810 0.081583 -vn -2.246239 -3.365969 2.168021 -v 0.046420 -0.041010 0.081406 -vn -2.246239 3.365969 2.168021 -v 0.046420 -0.038810 0.081406 -vn -1.707486 -3.366016 2.613492 -v 0.046247 -0.041010 0.081263 -vn -1.707486 3.366016 2.613492 -v 0.046247 -0.038810 0.081263 -vn 1.712412 2.976242 -2.621058 -v 0.046657 -0.040410 0.080635 -vn 1.712412 -2.976243 -2.621058 -v 0.046657 -0.041010 0.080635 -vn 1.257646 -2.976249 -2.867164 -v 0.046403 -0.041010 0.080497 -vn 1.257646 2.976249 -2.867164 -v 0.046403 -0.040410 0.080497 -vn 0.768578 -2.976245 -3.035060 -v 0.046130 -0.041010 0.080404 -vn 0.768578 2.976245 -3.035060 -v 0.046130 -0.040410 0.080404 -vn 0.258502 -2.976221 -3.120170 -v 0.045845 -0.041010 0.080356 -vn 0.258502 2.976221 -3.120169 -v 0.045845 -0.040410 0.080356 -vn -0.258583 -2.976273 -3.120169 -v 0.045555 -0.041010 0.080356 -vn -0.258583 2.976273 -3.120170 -v 0.045555 -0.040410 0.080356 -vn -0.768584 -2.976241 -3.035058 -v 0.045270 -0.041010 0.080404 -vn -0.768584 2.976241 -3.035058 -v 0.045270 -0.040410 0.080404 -vn -1.257652 -2.976254 -2.867162 -v 0.044997 -0.041010 0.080497 -vn -1.257652 2.976253 -2.867162 -v 0.044997 -0.040410 0.080497 -vn -1.712422 -2.976234 -2.621050 -v 0.044743 -0.041010 0.080635 -vn -1.712422 2.976234 -2.621050 -v 0.044743 -0.040410 0.080635 -vn -2.120491 -2.976246 -2.303436 -v 0.044515 -0.041010 0.080812 -vn -2.120491 2.976246 -2.303436 -v 0.044515 -0.040410 0.080812 -vn -2.470700 -2.976249 -1.923005 -v 0.044319 -0.041010 0.081025 -vn -2.470700 2.976249 -1.923004 -v 0.044319 -0.040410 0.081025 -vn -2.753523 -2.976233 -1.490100 -v 0.044161 -0.041010 0.081267 -vn -2.753523 2.976233 -1.490100 -v 0.044161 -0.040410 0.081267 -vn -2.961232 -2.976264 -1.016572 -v 0.044045 -0.041010 0.081532 -vn -2.961232 2.976264 -1.016572 -v 0.044045 -0.040410 0.081532 -vn -3.088161 -2.976243 -0.515329 -v 0.043974 -0.041010 0.081812 -vn -3.088160 2.976244 -0.515329 -v 0.043974 -0.040410 0.081812 -vn -3.130860 -2.976231 0.000020 -v 0.043950 -0.041010 0.082100 -vn -3.130861 2.976231 0.000020 -v 0.043950 -0.040410 0.082100 -vn -3.088161 -2.976263 0.515340 -v 0.043974 -0.041010 0.082388 -vn -3.088161 2.976263 0.515340 -v 0.043974 -0.040410 0.082388 -vn -2.961221 -2.976236 1.016594 -v 0.044045 -0.041010 0.082668 -vn -2.961221 2.976235 1.016594 -v 0.044045 -0.040410 0.082668 -vn -2.753500 -2.976244 1.490146 -v 0.044161 -0.041010 0.082933 -vn -2.753500 2.976245 1.490146 -v 0.044161 -0.040410 0.082933 -vn -2.470691 -2.976260 1.923019 -v 0.044319 -0.041010 0.083175 -vn -2.470691 2.976260 1.923019 -v 0.044319 -0.040410 0.083175 -vn -2.120456 -2.976218 2.303464 -v 0.044515 -0.041010 0.083388 -vn -2.120456 2.976218 2.303463 -v 0.044515 -0.040410 0.083388 -vn -1.712387 -2.976263 2.621077 -v 0.044743 -0.041010 0.083565 -vn -1.712387 2.976263 2.621077 -v 0.044743 -0.040410 0.083565 -vn 1.712412 2.976242 -2.621058 -v 0.046657 -0.038810 0.080635 -vn 1.712412 -2.976242 -2.621058 -v 0.046657 -0.039410 0.080635 -vn 1.257646 -2.976249 -2.867164 -v 0.046403 -0.039410 0.080497 -vn 1.257646 2.976249 -2.867164 -v 0.046403 -0.038810 0.080497 -vn 0.768578 -2.976245 -3.035060 -v 0.046130 -0.039410 0.080404 -vn 0.768578 2.976245 -3.035060 -v 0.046130 -0.038810 0.080404 -vn 0.258502 -2.976221 -3.120170 -v 0.045845 -0.039410 0.080356 -vn 0.258502 2.976221 -3.120169 -v 0.045845 -0.038810 0.080356 -vn -0.258583 -2.976273 -3.120169 -v 0.045555 -0.039410 0.080356 -vn -0.258583 2.976273 -3.120170 -v 0.045555 -0.038810 0.080356 -vn -0.768584 -2.976241 -3.035058 -v 0.045270 -0.039410 0.080404 -vn -0.768584 2.976241 -3.035058 -v 0.045270 -0.038810 0.080404 -vn -1.257652 -2.976254 -2.867162 -v 0.044997 -0.039410 0.080497 -vn -1.257652 2.976254 -2.867162 -v 0.044997 -0.038810 0.080497 -vn -1.712422 -2.976234 -2.621050 -v 0.044743 -0.039410 0.080635 -vn -1.712422 2.976234 -2.621050 -v 0.044743 -0.038810 0.080635 -vn -2.120491 -2.976246 -2.303436 -v 0.044515 -0.039410 0.080812 -vn -2.120491 2.976246 -2.303436 -v 0.044515 -0.038810 0.080812 -vn -2.470700 -2.976250 -1.923005 -v 0.044319 -0.039410 0.081025 -vn -2.470700 2.976249 -1.923004 -v 0.044319 -0.038810 0.081025 -vn -2.753523 -2.976233 -1.490100 -v 0.044161 -0.039410 0.081267 -vn -2.753523 2.976233 -1.490100 -v 0.044161 -0.038810 0.081267 -vn -2.961232 -2.976264 -1.016572 -v 0.044045 -0.039410 0.081532 -vn -2.961232 2.976264 -1.016572 -v 0.044045 -0.038810 0.081532 -vn -3.088161 -2.976244 -0.515329 -v 0.043974 -0.039410 0.081812 -vn -3.088160 2.976244 -0.515329 -v 0.043974 -0.038810 0.081812 -vn -3.130860 -2.976231 0.000020 -v 0.043950 -0.039410 0.082100 -vn -3.130861 2.976231 0.000020 -v 0.043950 -0.038810 0.082100 -vn -3.088161 -2.976263 0.515340 -v 0.043974 -0.039410 0.082388 -vn -3.088161 2.976263 0.515340 -v 0.043974 -0.038810 0.082388 -vn -2.961221 -2.976235 1.016594 -v 0.044045 -0.039410 0.082668 -vn -2.961221 2.976235 1.016594 -v 0.044045 -0.038810 0.082668 -vn -2.753500 -2.976245 1.490146 -v 0.044161 -0.039410 0.082933 -vn -2.753500 2.976244 1.490146 -v 0.044161 -0.038810 0.082933 -vn -2.470691 -2.976260 1.923019 -v 0.044319 -0.039410 0.083175 -vn -2.470691 2.976260 1.923019 -v 0.044319 -0.038810 0.083175 -vn -2.120456 -2.976218 2.303464 -v 0.044515 -0.039410 0.083388 -vn -2.120456 2.976218 2.303463 -v 0.044515 -0.038810 0.083388 -vn -1.712387 -2.976263 2.621077 -v 0.044743 -0.039410 0.083565 -vn -1.712387 2.976263 2.621077 -v 0.044743 -0.038810 0.083565 -vn 1.710957 -3.326375 -2.618821 -v 0.046520 -0.039410 0.080844 -vn 1.710957 3.326375 -2.618821 -v 0.046520 -0.040410 0.080844 -vn 1.200627 3.326402 -2.888610 -v 0.046276 -0.040410 0.080715 -vn 1.200626 -3.326402 -2.888610 -v 0.046276 -0.039410 0.080715 -vn 0.649375 3.326401 -3.060046 -v 0.046011 -0.040410 0.080633 -vn 0.649375 -3.326401 -3.060047 -v 0.046011 -0.039410 0.080633 -vn 0.076019 3.326394 -3.127267 -v 0.045736 -0.040410 0.080600 -vn 0.076019 -3.326395 -3.127267 -v 0.045736 -0.039410 0.080600 -vn -0.499879 3.326370 -3.087996 -v 0.045460 -0.040410 0.080619 -vn -0.499879 -3.326370 -3.087996 -v 0.045460 -0.039410 0.080619 -vn -1.058777 3.326411 -2.943562 -v 0.045192 -0.040410 0.080689 -vn -1.058777 -3.326410 -2.943562 -v 0.045192 -0.039410 0.080689 -vn -1.581653 3.326392 -2.698880 -v 0.044942 -0.040410 0.080806 -vn -1.581653 -3.326392 -2.698880 -v 0.044942 -0.039410 0.080806 -vn -2.050636 3.326389 -2.362303 -v 0.044717 -0.040410 0.080967 -vn -2.050636 -3.326389 -2.362303 -v 0.044717 -0.039410 0.080967 -vn -2.449786 3.326389 -1.945285 -v 0.044525 -0.040410 0.081167 -vn -2.449786 -3.326389 -1.945284 -v 0.044525 -0.039410 0.081167 -vn -2.765520 3.326397 -1.462011 -v 0.044374 -0.040410 0.081399 -vn -2.765520 -3.326398 -1.462011 -v 0.044374 -0.039410 0.081399 -vn -2.987077 3.326388 -0.928954 -v 0.044268 -0.040410 0.081655 -vn -2.987077 -3.326388 -0.928954 -v 0.044268 -0.039410 0.081655 -vn -3.106910 3.326396 -0.364263 -v 0.044210 -0.040410 0.081925 -vn -3.106910 -3.326396 -0.364263 -v 0.044210 -0.039410 0.081925 -vn -3.120942 3.326394 0.212843 -v 0.044203 -0.040410 0.082202 -vn -3.120942 -3.326394 0.212843 -v 0.044203 -0.039410 0.082202 -vn -3.028695 3.326386 0.782684 -v 0.044248 -0.040410 0.082475 -vn -3.028695 -3.326386 0.782684 -v 0.044248 -0.039410 0.082475 -vn -2.833304 3.326401 1.325882 -v 0.044341 -0.040410 0.082736 -vn -2.833304 -3.326401 1.325882 -v 0.044341 -0.039410 0.082736 -vn -2.541440 3.326377 1.823918 -v 0.044481 -0.040410 0.082975 -vn -2.541440 -3.326377 1.823918 -v 0.044481 -0.039410 0.082975 -vn -2.163039 3.326392 2.259832 -v 0.044663 -0.040410 0.083184 -vn -2.163039 -3.326392 2.259832 -v 0.044663 -0.039410 0.083184 -vn -1.710940 3.326412 2.618826 -v 0.044880 -0.040410 0.083356 -vn -1.710939 -3.326412 2.618825 -v 0.044880 -0.039410 0.083356 -vn -1.083056 -3.366011 2.927942 -v 0.046047 -0.041010 0.081162 -vn -1.083056 3.366011 2.927943 -v 0.046047 -0.038810 0.081162 -vn -0.404420 -3.365943 3.095541 -v 0.045830 -0.041010 0.081108 -vn -0.404420 3.365943 3.095541 -v 0.045830 -0.038810 0.081108 -vn 0.294506 -3.366019 3.107912 -v 0.045606 -0.041010 0.081104 -vn 0.294506 3.366019 3.107912 -v 0.045606 -0.038810 0.081104 -vn 0.978741 -3.365994 2.964446 -v 0.045386 -0.041010 0.081150 -vn 0.978741 3.365994 2.964446 -v 0.045386 -0.038810 0.081150 -vn 1.613845 -3.365983 2.672338 -v 0.045183 -0.041010 0.081244 -vn 1.613845 3.365983 2.672339 -v 0.045183 -0.038810 0.081244 -vn 2.168045 -3.366015 2.246205 -v 0.045006 -0.041010 0.081380 -vn 2.168044 3.366015 2.246204 -v 0.045006 -0.038810 0.081380 -vn 2.613518 -3.365965 1.707463 -v 0.044863 -0.041010 0.081553 -vn 2.613518 3.365965 1.707463 -v 0.044863 -0.038810 0.081553 -vn 2.927921 -3.365998 1.083120 -v 0.044762 -0.041010 0.081753 -vn 2.927921 3.365998 1.083120 -v 0.044762 -0.038810 0.081753 -vn 3.095531 -3.365988 0.404438 -v 0.044708 -0.041010 0.081970 -vn 3.095531 3.365988 0.404438 -v 0.044708 -0.038810 0.081970 -vn 3.107913 -3.365999 -0.294526 -v 0.044704 -0.041010 0.082194 -vn 3.107913 3.365999 -0.294526 -v 0.044704 -0.038810 0.082194 -vn 2.964452 -3.365991 -0.978726 -v 0.044750 -0.041010 0.082414 -vn 2.964452 3.365991 -0.978726 -v 0.044750 -0.038810 0.082414 -vn 2.672334 -3.366000 -1.613848 -v 0.044844 -0.041010 0.082617 -vn 2.672333 3.366000 -1.613848 -v 0.044844 -0.038810 0.082617 -vn 2.246208 -3.365994 -2.168047 -v 0.044980 -0.041010 0.082794 -vn 2.246208 3.365994 -2.168047 -v 0.044980 -0.038810 0.082794 -vn -0.768578 -2.976245 3.035060 -v 0.045270 -0.041010 0.083796 -vn -1.257646 -2.976249 2.867164 -v 0.044997 -0.041010 0.083703 -vn 1.257677 -2.976227 2.867147 -v 0.046403 -0.041010 0.083703 -vn 0.768578 -2.976245 3.035060 -v 0.046130 -0.041010 0.083796 -vn 0.258543 -2.976247 3.120169 -v 0.045845 -0.041010 0.083844 -vn -0.258543 -2.976247 3.120170 -v 0.045555 -0.041010 0.083844 -vn 2.470700 -2.976249 1.923005 -v 0.047081 -0.041010 0.083175 -vn 2.120491 -2.976246 2.303436 -v 0.046885 -0.041010 0.083388 -vn 1.712453 -2.976257 2.621033 -v 0.046657 -0.041010 0.083565 -vn 3.130860 -2.976231 -0.000020 -v 0.047450 -0.041010 0.082100 -vn 3.088163 -2.976250 0.515320 -v 0.047426 -0.041010 0.082388 -vn 2.961228 -2.976247 1.016577 -v 0.047355 -0.041010 0.082668 -vn 2.753517 -2.976243 1.490115 -v 0.047239 -0.041010 0.082933 -vn 2.120462 -2.976256 -2.303464 -v 0.046885 -0.041010 0.080812 -vn 2.470672 -2.976243 -1.923039 -v 0.047081 -0.041010 0.081025 -vn 2.753500 -2.976244 -1.490146 -v 0.047239 -0.041010 0.081267 -vn 2.961221 -2.976235 -1.016594 -v 0.047355 -0.041010 0.081532 -vn 3.088161 -2.976263 -0.515340 -v 0.047426 -0.041010 0.081812 -vn 1.257677 2.976227 2.867147 -v 0.046403 -0.038810 0.083703 -vn 1.712453 2.976257 2.621033 -v 0.046657 -0.038810 0.083565 -vn -1.257646 2.976249 2.867164 -v 0.044997 -0.038810 0.083703 -vn -0.768578 2.976245 3.035060 -v 0.045270 -0.038810 0.083796 -vn -0.258543 2.976247 3.120169 -v 0.045555 -0.038810 0.083844 -vn 0.258543 2.976247 3.120170 -v 0.045845 -0.038810 0.083844 -vn 0.768578 2.976245 3.035060 -v 0.046130 -0.038810 0.083796 -vn 2.120491 2.976246 2.303436 -v 0.046885 -0.038810 0.083388 -vn 2.470700 2.976249 1.923004 -v 0.047081 -0.038810 0.083175 -vn 2.753517 2.976243 1.490115 -v 0.047239 -0.038810 0.082933 -vn 2.961228 2.976247 1.016577 -v 0.047355 -0.038810 0.082668 -vn 2.470672 2.976243 -1.923039 -v 0.047081 -0.038810 0.081025 -vn 2.120462 2.976255 -2.303464 -v 0.046885 -0.038810 0.080812 -vn 3.088162 2.976250 0.515320 -v 0.047426 -0.038810 0.082388 -vn 3.130861 2.976231 -0.000020 -v 0.047450 -0.038810 0.082100 -vn 3.088161 2.976263 -0.515340 -v 0.047426 -0.038810 0.081812 -vn 2.961221 2.976235 -1.016594 -v 0.047355 -0.038810 0.081532 -vn 2.753500 2.976244 -1.490146 -v 0.047239 -0.038810 0.081267 -vn -1.257646 2.976249 2.867164 -v 0.044997 -0.040410 0.083703 -vn -0.768578 2.976245 3.035060 -v 0.045270 -0.040410 0.083796 -vn -0.258543 2.976247 3.120169 -v 0.045555 -0.040410 0.083844 -vn 0.258543 2.976247 3.120170 -v 0.045845 -0.040410 0.083844 -vn 0.768578 2.976245 3.035060 -v 0.046130 -0.040410 0.083796 -vn 1.257677 2.976227 2.867147 -v 0.046403 -0.040410 0.083703 -vn 1.712453 2.976257 2.621033 -v 0.046657 -0.040410 0.083565 -vn 2.120491 2.976246 2.303436 -v 0.046885 -0.040410 0.083388 -vn 2.470700 2.976250 1.923004 -v 0.047081 -0.040410 0.083175 -vn 2.753517 2.976243 1.490115 -v 0.047239 -0.040410 0.082933 -vn 2.961228 2.976247 1.016577 -v 0.047355 -0.040410 0.082668 -vn 3.088162 2.976250 0.515320 -v 0.047426 -0.040410 0.082388 -vn 3.130861 2.976231 -0.000020 -v 0.047450 -0.040410 0.082100 -vn 3.088161 2.976263 -0.515340 -v 0.047426 -0.040410 0.081812 -vn 2.961221 2.976235 -1.016594 -v 0.047355 -0.040410 0.081532 -vn 2.753500 2.976245 -1.490146 -v 0.047239 -0.040410 0.081267 -vn 2.470672 2.976243 -1.923039 -v 0.047081 -0.040410 0.081025 -vn 2.120462 2.976256 -2.303464 -v 0.046885 -0.040410 0.080812 -vn -1.257646 -2.976249 2.867164 -v 0.044997 -0.039410 0.083703 -vn -0.768578 -2.976245 3.035060 -v 0.045270 -0.039410 0.083796 -vn -0.258543 -2.976247 3.120170 -v 0.045555 -0.039410 0.083844 -vn 0.258543 -2.976247 3.120169 -v 0.045845 -0.039410 0.083844 -vn 0.768578 -2.976245 3.035060 -v 0.046130 -0.039410 0.083796 -vn 1.257677 -2.976226 2.867147 -v 0.046403 -0.039410 0.083703 -vn 1.712453 -2.976257 2.621033 -v 0.046657 -0.039410 0.083565 -vn 2.120491 -2.976246 2.303436 -v 0.046885 -0.039410 0.083388 -vn 2.470700 -2.976250 1.923005 -v 0.047081 -0.039410 0.083175 -vn 2.753517 -2.976243 1.490115 -v 0.047239 -0.039410 0.082933 -vn 2.961228 -2.976247 1.016577 -v 0.047355 -0.039410 0.082668 -vn 3.088163 -2.976250 0.515320 -v 0.047426 -0.039410 0.082388 -vn 3.130860 -2.976231 -0.000020 -v 0.047450 -0.039410 0.082100 -vn 3.088161 -2.976263 -0.515340 -v 0.047426 -0.039410 0.081812 -vn 2.961221 -2.976235 -1.016594 -v 0.047355 -0.039410 0.081532 -vn 2.753500 -2.976245 -1.490146 -v 0.047239 -0.039410 0.081267 -vn 2.470672 -2.976243 -1.923039 -v 0.047081 -0.039410 0.081025 -vn 2.120462 -2.976256 -2.303464 -v 0.046885 -0.039410 0.080812 -vn 3.028691 3.326400 -0.782691 -v 0.047152 -0.040410 0.081725 -vn 2.833310 3.326378 -1.325876 -v 0.047059 -0.040410 0.081464 -vn 2.541440 3.326401 -1.823912 -v 0.046919 -0.040410 0.081225 -vn 2.163013 3.326394 -2.259857 -v 0.046737 -0.040410 0.081016 -vn 0.499875 3.326424 3.087989 -v 0.045940 -0.040410 0.083581 -vn 1.058817 3.326384 2.943552 -v 0.046208 -0.040410 0.083511 -vn 1.581653 3.326392 2.698880 -v 0.046458 -0.040410 0.083394 -vn 2.050636 3.326389 2.362303 -v 0.046683 -0.040410 0.083233 -vn 2.449783 3.326386 1.945289 -v 0.046875 -0.040410 0.083033 -vn 2.765509 3.326389 1.462034 -v 0.047026 -0.040410 0.082801 -vn 2.987073 3.326413 0.928952 -v 0.047132 -0.040410 0.082545 -vn 3.106914 3.326370 0.364264 -v 0.047190 -0.040410 0.082275 -vn 3.120942 3.326403 -0.212815 -v 0.047197 -0.040410 0.081998 -vn -1.200593 3.326378 2.888627 -v 0.045124 -0.040410 0.083485 -vn -0.649377 3.326399 3.060046 -v 0.045389 -0.040410 0.083567 -vn -0.076065 3.326368 3.127270 -v 0.045664 -0.040410 0.083600 -vn 0.499875 -3.326424 3.087989 -v 0.045940 -0.039410 0.083581 -vn -0.076065 -3.326368 3.127270 -v 0.045664 -0.039410 0.083600 -vn -0.649378 -3.326399 3.060046 -v 0.045389 -0.039410 0.083567 -vn -1.200593 -3.326378 2.888628 -v 0.045124 -0.039410 0.083485 -vn 3.028691 -3.326400 -0.782691 -v 0.047152 -0.039410 0.081725 -vn 3.120942 -3.326404 -0.212815 -v 0.047197 -0.039410 0.081998 -vn 3.106914 -3.326370 0.364264 -v 0.047190 -0.039410 0.082275 -vn 2.987074 -3.326414 0.928952 -v 0.047132 -0.039410 0.082545 -vn 2.765509 -3.326389 1.462034 -v 0.047026 -0.039410 0.082801 -vn 2.449783 -3.326385 1.945289 -v 0.046875 -0.039410 0.083033 -vn 2.050636 -3.326389 2.362303 -v 0.046683 -0.039410 0.083233 -vn 1.581653 -3.326392 2.698880 -v 0.046458 -0.039410 0.083394 -vn 1.058817 -3.326384 2.943551 -v 0.046208 -0.039410 0.083511 -vn 2.163013 -3.326394 -2.259857 -v 0.046737 -0.039410 0.081016 -vn 2.541440 -3.326401 -1.823912 -v 0.046919 -0.039410 0.081225 -vn 2.833310 -3.326378 -1.325876 -v 0.047059 -0.039410 0.081464 -vn -0.000003 3.365984 3.121840 -v 0.044581 -0.040410 0.090550 -vn -0.000003 -3.365984 3.121840 -v 0.044581 -0.042610 0.090550 -vn -0.694682 3.366003 3.043564 -v 0.044804 -0.040410 0.090575 -vn -0.694682 -3.366004 3.043564 -v 0.044804 -0.042610 0.090575 -vn -1.354514 3.365974 2.812683 -v 0.045015 -0.040410 0.090649 -vn -1.354514 -3.365974 2.812683 -v 0.045015 -0.042610 0.090649 -vn -1.946422 3.366002 2.440760 -v 0.045205 -0.040410 0.090768 -vn -1.946422 -3.366002 2.440761 -v 0.045205 -0.042610 0.090768 -vn -2.440756 3.365997 1.946429 -v 0.045363 -0.040410 0.090927 -vn -2.440756 -3.365997 1.946429 -v 0.045363 -0.042610 0.090927 -vn -2.812688 3.365995 1.354498 -v 0.045482 -0.040410 0.091116 -vn -2.812687 -3.365995 1.354498 -v 0.045482 -0.042610 0.091116 -vn -3.043572 3.365987 0.694659 -v 0.045556 -0.040410 0.091327 -vn -3.043572 -3.365987 0.694659 -v 0.045556 -0.042610 0.091327 -vn -3.121840 3.365986 0.000000 -v 0.045581 -0.040410 0.091550 -vn -3.121840 -3.365986 0.000000 -v 0.045581 -0.042610 0.091550 -vn -3.043572 3.365988 -0.694659 -v 0.045556 -0.040410 0.091773 -vn -3.043572 -3.365988 -0.694659 -v 0.045556 -0.042610 0.091773 -vn -2.812673 3.366013 -1.354521 -v 0.045482 -0.040410 0.091984 -vn -2.812673 -3.366013 -1.354521 -v 0.045482 -0.042610 0.091984 -vn -2.440741 3.365979 -1.946452 -v 0.045363 -0.040410 0.092173 -vn -2.440741 -3.365979 -1.946452 -v 0.045363 -0.042610 0.092173 -vn -1.946459 3.365974 -2.440737 -v 0.045205 -0.040410 0.092332 -vn -1.946459 -3.365974 -2.440736 -v 0.045205 -0.042610 0.092332 -vn -1.354505 3.366034 -2.812676 -v 0.045015 -0.040410 0.092451 -vn -1.354505 -3.366034 -2.812676 -v 0.045015 -0.042610 0.092451 -vn -0.694635 3.365972 -3.043580 -v 0.044804 -0.040410 0.092525 -vn -0.694635 -3.365972 -3.043581 -v 0.044804 -0.042610 0.092525 -vn -0.000003 3.365984 -3.121840 -v 0.044581 -0.040410 0.092550 -vn -0.000003 -3.365984 -3.121840 -v 0.044581 -0.042610 0.092550 -vn 0.000000 -2.976218 3.130859 -v 0.044581 -0.041010 0.093300 -vn -0.515340 2.976263 3.088161 -v 0.044293 -0.040410 0.093276 -vn -0.515340 -2.976263 3.088161 -v 0.044293 -0.041010 0.093276 -vn -1.016594 2.976235 2.961221 -v 0.044013 -0.040410 0.093205 -vn -1.016594 -2.976236 2.961221 -v 0.044013 -0.041010 0.093205 -vn -1.490118 2.976266 2.753519 -v 0.043748 -0.040410 0.093089 -vn -1.490118 -2.976266 2.753519 -v 0.043748 -0.041010 0.093089 -vn -1.923011 2.976220 2.470690 -v 0.043506 -0.040410 0.092931 -vn -1.923011 -2.976220 2.470690 -v 0.043506 -0.041010 0.092931 -vn -2.303450 2.976272 2.120481 -v 0.043294 -0.040410 0.092735 -vn -2.303450 -2.976272 2.120481 -v 0.043294 -0.041010 0.092735 -vn -2.621043 2.976225 1.712430 -v 0.043116 -0.040410 0.092507 -vn -2.621043 -2.976225 1.712430 -v 0.043116 -0.041010 0.092507 -vn -2.867160 2.976259 1.257657 -v 0.042979 -0.040410 0.092253 -vn -2.867161 -2.976259 1.257657 -v 0.042979 -0.041010 0.092253 -vn -3.035056 2.976235 0.768587 -v 0.042885 -0.040410 0.091980 -vn -3.035056 -2.976235 0.768587 -v 0.042885 -0.041010 0.091980 -vn -3.120170 2.976249 0.258539 -v 0.042837 -0.040410 0.091695 -vn -3.120170 -2.976249 0.258539 -v 0.042837 -0.041010 0.091695 -vn -3.120169 2.976244 -0.258546 -v 0.042837 -0.040410 0.091405 -vn -3.120169 -2.976245 -0.258546 -v 0.042837 -0.041010 0.091405 -vn -3.035059 2.976247 -0.768581 -v 0.042885 -0.040410 0.091120 -vn -3.035059 -2.976248 -0.768581 -v 0.042885 -0.041010 0.091120 -vn -2.867156 2.976238 -1.257661 -v 0.042979 -0.040410 0.090847 -vn -2.867156 -2.976238 -1.257661 -v 0.042979 -0.041010 0.090847 -vn -2.621049 2.976254 -1.712427 -v 0.043116 -0.040410 0.090593 -vn -2.621049 -2.976254 -1.712428 -v 0.043116 -0.041010 0.090593 -vn -2.303443 2.976237 -2.120482 -v 0.043294 -0.040410 0.090365 -vn -2.303443 -2.976237 -2.120482 -v 0.043294 -0.041010 0.090365 -vn -1.923018 2.976261 -2.470692 -v 0.043506 -0.040410 0.090169 -vn -1.923018 -2.976261 -2.470691 -v 0.043506 -0.041010 0.090169 -vn -1.490146 2.976244 -2.753500 -v 0.043748 -0.040410 0.090011 -vn -1.490146 -2.976244 -2.753500 -v 0.043748 -0.041010 0.090011 -vn -1.016594 2.976236 -2.961221 -v 0.044013 -0.040410 0.089895 -vn -1.016594 -2.976235 -2.961221 -v 0.044013 -0.041010 0.089895 -vn -0.515299 2.976237 -3.088164 -v 0.044293 -0.040410 0.089824 -vn -0.515300 -2.976237 -3.088164 -v 0.044293 -0.041010 0.089824 -vn 0.000000 -2.976269 -3.130866 -v 0.044581 -0.041010 0.089800 -vn -0.000000 2.976218 3.130859 -v 0.044581 -0.042010 0.093300 -vn -0.515340 2.976263 3.088161 -v 0.044293 -0.042010 0.093276 -vn -0.515340 -2.976263 3.088161 -v 0.044293 -0.042610 0.093276 -vn -1.016594 2.976235 2.961221 -v 0.044013 -0.042010 0.093205 -vn -1.016594 -2.976235 2.961221 -v 0.044013 -0.042610 0.093205 -vn -1.490118 2.976266 2.753519 -v 0.043748 -0.042010 0.093089 -vn -1.490118 -2.976266 2.753519 -v 0.043748 -0.042610 0.093089 -vn -1.923011 2.976220 2.470690 -v 0.043506 -0.042010 0.092931 -vn -1.923011 -2.976220 2.470690 -v 0.043506 -0.042610 0.092931 -vn -2.303450 2.976272 2.120481 -v 0.043294 -0.042010 0.092735 -vn -2.303450 -2.976272 2.120481 -v 0.043294 -0.042610 0.092735 -vn -2.621043 2.976225 1.712430 -v 0.043116 -0.042010 0.092507 -vn -2.621043 -2.976225 1.712430 -v 0.043116 -0.042610 0.092507 -vn -2.867161 2.976258 1.257657 -v 0.042979 -0.042010 0.092253 -vn -2.867160 -2.976259 1.257657 -v 0.042979 -0.042610 0.092253 -vn -3.035056 2.976235 0.768587 -v 0.042885 -0.042010 0.091980 -vn -3.035056 -2.976235 0.768587 -v 0.042885 -0.042610 0.091980 -vn -3.120170 2.976249 0.258539 -v 0.042837 -0.042010 0.091695 -vn -3.120170 -2.976249 0.258539 -v 0.042837 -0.042610 0.091695 -vn -3.120169 2.976245 -0.258546 -v 0.042837 -0.042010 0.091405 -vn -3.120169 -2.976244 -0.258546 -v 0.042837 -0.042610 0.091405 -vn -3.035059 2.976247 -0.768581 -v 0.042885 -0.042010 0.091120 -vn -3.035059 -2.976247 -0.768581 -v 0.042885 -0.042610 0.091120 -vn -2.867156 2.976238 -1.257661 -v 0.042979 -0.042010 0.090847 -vn -2.867156 -2.976238 -1.257661 -v 0.042979 -0.042610 0.090847 -vn -2.621049 2.976254 -1.712428 -v 0.043116 -0.042010 0.090593 -vn -2.621049 -2.976254 -1.712428 -v 0.043116 -0.042610 0.090593 -vn -2.303443 2.976238 -2.120482 -v 0.043294 -0.042010 0.090365 -vn -2.303443 -2.976237 -2.120482 -v 0.043294 -0.042610 0.090365 -vn -1.923018 2.976261 -2.470691 -v 0.043506 -0.042010 0.090169 -vn -1.923018 -2.976261 -2.470692 -v 0.043506 -0.042610 0.090169 -vn -1.490146 2.976244 -2.753500 -v 0.043748 -0.042010 0.090011 -vn -1.490146 -2.976244 -2.753500 -v 0.043748 -0.042610 0.090011 -vn -1.016594 2.976236 -2.961221 -v 0.044013 -0.042010 0.089895 -vn -1.016594 -2.976236 -2.961221 -v 0.044013 -0.042610 0.089895 -vn -0.515300 2.976237 -3.088165 -v 0.044293 -0.042010 0.089824 -vn -0.515300 -2.976237 -3.088165 -v 0.044293 -0.042610 0.089824 -vn 0.000000 2.976269 -3.130866 -v 0.044581 -0.042010 0.089800 -vn 0.000002 3.326394 3.128191 -v 0.044581 -0.042010 0.093050 -vn 0.000002 -3.326394 3.128191 -v 0.044581 -0.041010 0.093050 -vn -0.574801 -3.326391 3.074928 -v 0.044306 -0.041010 0.093024 -vn -0.574801 3.326391 3.074928 -v 0.044306 -0.042010 0.093024 -vn -1.130022 -3.326387 2.916956 -v 0.044039 -0.041010 0.092949 -vn -1.130022 3.326387 2.916956 -v 0.044039 -0.042010 0.092949 -vn -1.646768 -3.326396 2.659649 -v 0.043792 -0.041010 0.092825 -vn -1.646768 3.326396 2.659649 -v 0.043792 -0.042010 0.092825 -vn -2.107455 -3.326404 2.311753 -v 0.043571 -0.041010 0.092659 -vn -2.107455 3.326404 2.311753 -v 0.043571 -0.042010 0.092659 -vn -2.496347 -3.326368 1.885166 -v 0.043384 -0.041010 0.092454 -vn -2.496347 3.326368 1.885166 -v 0.043384 -0.042010 0.092454 -vn -2.800239 -3.326424 1.394351 -v 0.043238 -0.041010 0.092219 -vn -2.800239 3.326424 1.394351 -v 0.043238 -0.042010 0.092219 -vn -3.008780 -3.326365 0.856063 -v 0.043138 -0.041010 0.091960 -vn -3.008781 3.326365 0.856063 -v 0.043138 -0.042010 0.091960 -vn -3.114844 -3.326403 0.288650 -v 0.043088 -0.041010 0.091688 -vn -3.114844 3.326403 0.288650 -v 0.043088 -0.042010 0.091688 -vn -3.114846 -3.326398 -0.288642 -v 0.043088 -0.041010 0.091412 -vn -3.114845 3.326398 -0.288642 -v 0.043088 -0.042010 0.091412 -vn -3.008777 -3.326379 -0.856070 -v 0.043138 -0.041010 0.091140 -vn -3.008777 3.326379 -0.856070 -v 0.043138 -0.042010 0.091140 -vn -2.800245 -3.326400 -1.394346 -v 0.043238 -0.041010 0.090881 -vn -2.800245 3.326400 -1.394346 -v 0.043238 -0.042010 0.090881 -vn -2.496340 -3.326400 -1.885168 -v 0.043384 -0.041010 0.090646 -vn -2.496340 3.326400 -1.885168 -v 0.043384 -0.042010 0.090646 -vn -2.107462 -3.326364 -2.311754 -v 0.043571 -0.041010 0.090441 -vn -2.107462 3.326364 -2.311754 -v 0.043571 -0.042010 0.090441 -vn -1.646795 -3.326417 -2.659629 -v 0.043792 -0.041010 0.090275 -vn -1.646795 3.326417 -2.659628 -v 0.043792 -0.042010 0.090275 -vn -1.130022 -3.326387 -2.916956 -v 0.044039 -0.041010 0.090151 -vn -1.130022 3.326387 -2.916956 -v 0.044039 -0.042010 0.090151 -vn -0.574801 -3.326391 -3.074928 -v 0.044306 -0.041010 0.090076 -vn -0.574801 3.326391 -3.074928 -v 0.044306 -0.042010 0.090076 -vn 0.000002 -3.326394 -3.128191 -v 0.044581 -0.041010 0.090050 -vn 0.000002 3.326394 -3.128191 -v 0.044581 -0.042010 0.090050 -vn 0.694641 3.365979 -3.043578 -v 0.044359 -0.040410 0.092525 -vn 0.694641 -3.365979 -3.043578 -v 0.044359 -0.042610 0.092525 -vn 1.354513 3.366028 -2.812674 -v 0.044147 -0.040410 0.092451 -vn 1.354513 -3.366028 -2.812674 -v 0.044147 -0.042610 0.092451 -vn 1.946459 3.365974 -2.440736 -v 0.043958 -0.040410 0.092332 -vn 1.946459 -3.365974 -2.440737 -v 0.043958 -0.042610 0.092332 -vn 2.440741 3.365979 -1.946452 -v 0.043799 -0.040410 0.092173 -vn 2.440741 -3.365979 -1.946452 -v 0.043799 -0.042610 0.092173 -vn 2.812673 3.366013 -1.354521 -v 0.043680 -0.040410 0.091984 -vn 2.812673 -3.366013 -1.354521 -v 0.043680 -0.042610 0.091984 -vn 3.043569 3.365971 -0.694684 -v 0.043606 -0.040410 0.091773 -vn 3.043569 -3.365971 -0.694684 -v 0.043606 -0.042610 0.091773 -vn 3.121834 3.366019 0.000000 -v 0.043581 -0.040410 0.091550 -vn 3.121834 -3.366019 -0.000000 -v 0.043581 -0.042610 0.091550 -vn 3.043569 3.365971 0.694684 -v 0.043606 -0.040410 0.091327 -vn 3.043569 -3.365971 0.694684 -v 0.043606 -0.042610 0.091327 -vn 2.812687 3.365995 1.354498 -v 0.043680 -0.040410 0.091116 -vn 2.812688 -3.365995 1.354498 -v 0.043680 -0.042610 0.091116 -vn 2.440756 3.365997 1.946429 -v 0.043799 -0.040410 0.090927 -vn 2.440756 -3.365997 1.946429 -v 0.043799 -0.042610 0.090927 -vn 1.946422 3.366002 2.440761 -v 0.043958 -0.040410 0.090768 -vn 1.946422 -3.366002 2.440760 -v 0.043958 -0.042610 0.090768 -vn 1.354522 3.365969 2.812681 -v 0.044147 -0.040410 0.090649 -vn 1.354522 -3.365969 2.812681 -v 0.044147 -0.042610 0.090649 -vn 0.694687 3.366010 3.043561 -v 0.044359 -0.040410 0.090575 -vn 0.694687 -3.366011 3.043562 -v 0.044359 -0.042610 0.090575 -vn 1.016592 2.976244 -2.961223 -v 0.045149 -0.040410 0.089895 -vn 0.515304 2.976234 -3.088163 -v 0.044869 -0.040410 0.089824 -vn 2.621058 2.976242 -1.712412 -v 0.046046 -0.040410 0.090593 -vn 2.303443 2.976237 -2.120482 -v 0.045869 -0.040410 0.090365 -vn 1.923018 2.976261 -2.470691 -v 0.045656 -0.040410 0.090169 -vn 1.490139 2.976239 -2.753504 -v 0.045414 -0.040410 0.090011 -vn 3.120170 2.976249 0.258539 -v 0.046325 -0.040410 0.091695 -vn 3.120169 2.976244 -0.258546 -v 0.046325 -0.040410 0.091405 -vn 3.035059 2.976247 -0.768581 -v 0.046278 -0.040410 0.091120 -vn 2.867164 2.976249 -1.257646 -v 0.046184 -0.040410 0.090847 -vn 0.515345 2.976260 3.088160 -v 0.044869 -0.040410 0.093276 -vn 1.016592 2.976244 2.961223 -v 0.045149 -0.040410 0.093205 -vn 1.490111 2.976261 2.753522 -v 0.045414 -0.040410 0.093089 -vn 1.923011 2.976220 2.470690 -v 0.045656 -0.040410 0.092931 -vn 2.303450 2.976272 2.120482 -v 0.045869 -0.040410 0.092735 -vn 2.621051 2.976214 1.712415 -v 0.046046 -0.040410 0.092507 -vn 2.867169 2.976270 1.257641 -v 0.046184 -0.040410 0.092253 -vn 3.035056 2.976235 0.768587 -v 0.046278 -0.040410 0.091980 -vn 1.016592 -2.976244 2.961223 -v 0.045149 -0.042610 0.093205 -vn 0.515345 -2.976260 3.088160 -v 0.044869 -0.042610 0.093276 -vn 2.621052 -2.976214 1.712415 -v 0.046046 -0.042610 0.092507 -vn 2.303450 -2.976272 2.120481 -v 0.045869 -0.042610 0.092735 -vn 1.923011 -2.976220 2.470690 -v 0.045656 -0.042610 0.092931 -vn 1.490110 -2.976261 2.753522 -v 0.045414 -0.042610 0.093089 -vn 3.120169 -2.976244 -0.258546 -v 0.046325 -0.042610 0.091405 -vn 3.120170 -2.976249 0.258539 -v 0.046325 -0.042610 0.091695 -vn 3.035056 -2.976235 0.768587 -v 0.046278 -0.042610 0.091980 -vn 2.867169 -2.976270 1.257641 -v 0.046184 -0.042610 0.092253 -vn 2.621058 -2.976242 -1.712412 -v 0.046046 -0.042610 0.090593 -vn 2.867164 -2.976249 -1.257646 -v 0.046184 -0.042610 0.090847 -vn 3.035059 -2.976247 -0.768581 -v 0.046278 -0.042610 0.091120 -vn 0.515304 -2.976234 -3.088163 -v 0.044869 -0.042610 0.089824 -vn 1.016592 -2.976244 -2.961223 -v 0.045149 -0.042610 0.089895 -vn 1.490139 -2.976239 -2.753504 -v 0.045414 -0.042610 0.090011 -vn 1.923018 -2.976261 -2.470691 -v 0.045656 -0.042610 0.090169 -vn 2.303443 -2.976237 -2.120482 -v 0.045869 -0.042610 0.090365 -vn 0.515304 -2.976234 -3.088163 -v 0.044869 -0.041010 0.089824 -vn 1.016592 -2.976244 -2.961223 -v 0.045149 -0.041010 0.089895 -vn 1.490139 -2.976239 -2.753504 -v 0.045414 -0.041010 0.090011 -vn 1.923018 -2.976261 -2.470692 -v 0.045656 -0.041010 0.090169 -vn 2.303443 -2.976238 -2.120482 -v 0.045869 -0.041010 0.090365 -vn 2.621058 -2.976242 -1.712412 -v 0.046046 -0.041010 0.090593 -vn 2.867164 -2.976249 -1.257646 -v 0.046184 -0.041010 0.090847 -vn 3.035059 -2.976247 -0.768581 -v 0.046278 -0.041010 0.091120 -vn 3.120169 -2.976245 -0.258546 -v 0.046325 -0.041010 0.091405 -vn 3.120170 -2.976249 0.258539 -v 0.046325 -0.041010 0.091695 -vn 3.035056 -2.976235 0.768587 -v 0.046278 -0.041010 0.091980 -vn 2.867169 -2.976270 1.257641 -v 0.046184 -0.041010 0.092253 -vn 2.621052 -2.976214 1.712415 -v 0.046046 -0.041010 0.092507 -vn 2.303450 -2.976272 2.120481 -v 0.045869 -0.041010 0.092735 -vn 1.923011 -2.976220 2.470690 -v 0.045656 -0.041010 0.092931 -vn 1.490110 -2.976261 2.753522 -v 0.045414 -0.041010 0.093089 -vn 1.016592 -2.976244 2.961223 -v 0.045149 -0.041010 0.093205 -vn 0.515345 -2.976260 3.088160 -v 0.044869 -0.041010 0.093276 -vn 0.515304 2.976234 -3.088163 -v 0.044869 -0.042010 0.089824 -vn 1.016592 2.976244 -2.961223 -v 0.045149 -0.042010 0.089895 -vn 1.490139 2.976239 -2.753503 -v 0.045414 -0.042010 0.090011 -vn 1.923018 2.976261 -2.470692 -v 0.045656 -0.042010 0.090169 -vn 2.303443 2.976237 -2.120482 -v 0.045869 -0.042010 0.090365 -vn 2.621058 2.976242 -1.712412 -v 0.046046 -0.042010 0.090593 -vn 2.867164 2.976249 -1.257646 -v 0.046184 -0.042010 0.090847 -vn 3.035059 2.976247 -0.768581 -v 0.046278 -0.042010 0.091120 -vn 3.120169 2.976245 -0.258546 -v 0.046325 -0.042010 0.091405 -vn 3.120170 2.976249 0.258539 -v 0.046325 -0.042010 0.091695 -vn 3.035056 2.976235 0.768587 -v 0.046278 -0.042010 0.091980 -vn 2.867169 2.976270 1.257641 -v 0.046184 -0.042010 0.092253 -vn 2.621052 2.976214 1.712415 -v 0.046046 -0.042010 0.092507 -vn 2.303450 2.976272 2.120481 -v 0.045869 -0.042010 0.092735 -vn 1.923011 2.976220 2.470690 -v 0.045656 -0.042010 0.092931 -vn 1.490110 2.976261 2.753522 -v 0.045414 -0.042010 0.093089 -vn 1.016592 2.976244 2.961223 -v 0.045149 -0.042010 0.093205 -vn 0.515345 2.976260 3.088160 -v 0.044869 -0.042010 0.093276 -vn 2.107444 -3.326394 2.311765 -v 0.045592 -0.041010 0.092659 -vn 1.646776 -3.326390 2.659645 -v 0.045371 -0.041010 0.092825 -vn 1.130025 -3.326397 2.916954 -v 0.045123 -0.041010 0.092949 -vn 0.574798 -3.326385 3.074930 -v 0.044857 -0.041010 0.093024 -vn 0.574798 -3.326386 -3.074930 -v 0.044857 -0.041010 0.090076 -vn 1.130025 -3.326397 -2.916954 -v 0.045123 -0.041010 0.090151 -vn 1.646803 -3.326411 -2.659625 -v 0.045371 -0.041010 0.090275 -vn 2.107452 -3.326355 -2.311766 -v 0.045592 -0.041010 0.090441 -vn 2.496339 -3.326422 -1.885164 -v 0.045778 -0.041010 0.090646 -vn 2.800247 -3.326376 -1.394349 -v 0.045924 -0.041010 0.090881 -vn 3.008774 -3.326405 -0.856068 -v 0.046024 -0.041010 0.091140 -vn 3.114849 -3.326385 -0.288622 -v 0.046075 -0.041010 0.091412 -vn 3.114848 -3.326390 0.288630 -v 0.046075 -0.041010 0.091688 -vn 3.008777 -3.326391 0.856061 -v 0.046024 -0.041010 0.091960 -vn 2.800241 -3.326400 1.394354 -v 0.045924 -0.041010 0.092219 -vn 2.496346 -3.326390 1.885162 -v 0.045778 -0.041010 0.092454 -vn 2.107452 3.326354 -2.311765 -v 0.045592 -0.042010 0.090441 -vn 1.646803 3.326411 -2.659625 -v 0.045371 -0.042010 0.090275 -vn 1.130025 3.326397 -2.916954 -v 0.045123 -0.042010 0.090151 -vn 0.574798 3.326385 -3.074930 -v 0.044857 -0.042010 0.090076 -vn 2.107444 3.326394 2.311765 -v 0.045592 -0.042010 0.092659 -vn 2.496346 3.326390 1.885162 -v 0.045778 -0.042010 0.092454 -vn 2.800241 3.326400 1.394354 -v 0.045924 -0.042010 0.092219 -vn 3.008777 3.326391 0.856061 -v 0.046024 -0.042010 0.091960 -vn 3.114847 3.326390 0.288630 -v 0.046075 -0.042010 0.091688 -vn 3.114849 3.326385 -0.288622 -v 0.046075 -0.042010 0.091412 -vn 3.008773 3.326405 -0.856068 -v 0.046024 -0.042010 0.091140 -vn 2.800248 3.326376 -1.394349 -v 0.045924 -0.042010 0.090881 -vn 2.496339 3.326422 -1.885164 -v 0.045778 -0.042010 0.090646 -vn 0.574798 3.326386 3.074930 -v 0.044857 -0.042010 0.093024 -vn 1.130025 3.326397 2.916954 -v 0.045123 -0.042010 0.092949 -vn 1.646776 3.326390 2.659645 -v 0.045371 -0.042010 0.092825 -vn 1.707466 -3.365983 -2.613513 -v 0.035703 -0.042610 0.100718 -vn 1.707466 3.365983 -2.613513 -v 0.035703 -0.040410 0.100718 -vn 1.083110 -3.365991 -2.927927 -v 0.035903 -0.042610 0.100819 -vn 1.083110 3.365991 -2.927926 -v 0.035903 -0.040410 0.100819 -vn 0.404463 -3.365972 -3.095530 -v 0.036120 -0.042610 0.100873 -vn 0.404464 3.365972 -3.095531 -v 0.036120 -0.040410 0.100873 -vn -0.294506 -3.366019 -3.107912 -v 0.036344 -0.042610 0.100877 -vn -0.294506 3.366018 -3.107912 -v 0.036344 -0.040410 0.100877 -vn -0.978741 -3.365994 -2.964446 -v 0.036564 -0.042610 0.100831 -vn -0.978741 3.365994 -2.964446 -v 0.036564 -0.040410 0.100831 -vn -1.613858 -3.365993 -2.672328 -v 0.036767 -0.042610 0.100737 -vn -1.613858 3.365993 -2.672329 -v 0.036767 -0.040410 0.100737 -vn -2.168045 -3.365992 -2.246211 -v 0.036944 -0.042610 0.100601 -vn -2.168045 3.365992 -2.246211 -v 0.036944 -0.040410 0.100601 -vn -2.613517 -3.365993 -1.707458 -v 0.037087 -0.042610 0.100428 -vn -2.613516 3.365993 -1.707458 -v 0.037087 -0.040410 0.100428 -vn -2.927928 -3.365975 -1.083112 -v 0.037188 -0.042610 0.100228 -vn -2.927929 3.365975 -1.083112 -v 0.037188 -0.040410 0.100228 -vn -3.095529 -3.366013 -0.404423 -v 0.037242 -0.042610 0.100011 -vn -3.095529 3.366013 -0.404423 -v 0.037242 -0.040410 0.100011 -vn -3.107912 -3.365988 0.294564 -v 0.037246 -0.042610 0.099787 -vn -3.107911 3.365988 0.294564 -v 0.037246 -0.040410 0.099787 -vn -2.964459 -3.365969 0.978715 -v 0.037200 -0.042610 0.099568 -vn -2.964460 3.365969 0.978715 -v 0.037200 -0.040410 0.099568 -vn -2.672344 -3.366015 1.613826 -v 0.037106 -0.042610 0.099364 -vn -2.672343 3.366015 1.613826 -v 0.037106 -0.040410 0.099364 -vn -2.246195 -3.366005 2.168057 -v 0.036970 -0.042610 0.099187 -vn -2.246195 3.366005 2.168057 -v 0.036970 -0.040410 0.099187 -vn -1.707452 -3.365972 2.613523 -v 0.036797 -0.042610 0.099044 -vn -1.707453 3.365972 2.613524 -v 0.036797 -0.040410 0.099044 -vn 1.712404 2.976236 -2.621062 -v 0.037207 -0.042010 0.098416 -vn 1.712403 -2.976236 -2.621062 -v 0.037207 -0.042610 0.098416 -vn 1.257607 -2.976235 -2.867179 -v 0.036953 -0.042610 0.098279 -vn 1.257607 2.976235 -2.867179 -v 0.036953 -0.042010 0.098279 -vn 0.768548 -2.976265 -3.035070 -v 0.036680 -0.042610 0.098185 -vn 0.768548 2.976266 -3.035070 -v 0.036680 -0.042010 0.098185 -vn 0.258543 -2.976247 -3.120170 -v 0.036395 -0.042610 0.098137 -vn 0.258543 2.976247 -3.120169 -v 0.036395 -0.042010 0.098137 -vn -0.258543 -2.976247 -3.120169 -v 0.036105 -0.042610 0.098137 -vn -0.258543 2.976247 -3.120170 -v 0.036105 -0.042010 0.098137 -vn -0.768584 -2.976241 -3.035058 -v 0.035820 -0.042610 0.098185 -vn -0.768584 2.976241 -3.035058 -v 0.035820 -0.042010 0.098185 -vn -1.257683 -2.976231 -2.867145 -v 0.035547 -0.042610 0.098279 -vn -1.257683 2.976231 -2.867145 -v 0.035547 -0.042010 0.098279 -vn -1.712443 -2.976265 -2.621041 -v 0.035293 -0.042610 0.098416 -vn -1.712443 2.976265 -2.621041 -v 0.035293 -0.042010 0.098416 -vn -2.120472 -2.976246 -2.303453 -v 0.035065 -0.042610 0.098594 -vn -2.120472 2.976246 -2.303453 -v 0.035065 -0.042010 0.098594 -vn -2.470691 -2.976241 -1.923014 -v 0.034869 -0.042610 0.098806 -vn -2.470691 2.976241 -1.923013 -v 0.034869 -0.042010 0.098806 -vn -2.753523 -2.976233 -1.490100 -v 0.034711 -0.042610 0.099048 -vn -2.753524 2.976233 -1.490100 -v 0.034711 -0.042010 0.099048 -vn -2.961232 -2.976264 -1.016572 -v 0.034595 -0.042610 0.099313 -vn -2.961232 2.976264 -1.016572 -v 0.034595 -0.042010 0.099313 -vn -3.088161 -2.976242 -0.515326 -v 0.034524 -0.042610 0.099593 -vn -3.088161 2.976242 -0.515326 -v 0.034524 -0.042010 0.099593 -vn -3.130861 -2.976233 0.000023 -v 0.034500 -0.042610 0.099881 -vn -3.130861 2.976233 0.000023 -v 0.034500 -0.042010 0.099881 -vn -3.088159 -2.976256 0.515349 -v 0.034524 -0.042610 0.100169 -vn -3.088158 2.976256 0.515349 -v 0.034524 -0.042010 0.100169 -vn -2.961225 -2.976252 1.016589 -v 0.034595 -0.042610 0.100449 -vn -2.961225 2.976252 1.016589 -v 0.034595 -0.042010 0.100449 -vn -2.753504 -2.976231 1.490136 -v 0.034711 -0.042610 0.100714 -vn -2.753504 2.976231 1.490136 -v 0.034711 -0.042010 0.100714 -vn -2.470678 -2.976254 1.923034 -v 0.034869 -0.042610 0.100956 -vn -2.470678 2.976254 1.923034 -v 0.034869 -0.042010 0.100956 -vn -2.120471 -2.976248 2.303455 -v 0.035065 -0.042610 0.101169 -vn -2.120471 2.976248 2.303455 -v 0.035065 -0.042010 0.101169 -vn -1.712412 -2.976242 2.621058 -v 0.035293 -0.042610 0.101346 -vn -1.712412 2.976242 2.621058 -v 0.035293 -0.042010 0.101346 -vn 1.712404 2.976236 -2.621062 -v 0.037207 -0.040410 0.098416 -vn 1.712404 -2.976236 -2.621062 -v 0.037207 -0.041010 0.098416 -vn 1.257607 -2.976235 -2.867179 -v 0.036953 -0.041010 0.098279 -vn 1.257607 2.976235 -2.867179 -v 0.036953 -0.040410 0.098279 -vn 0.768548 -2.976265 -3.035070 -v 0.036680 -0.041010 0.098185 -vn 0.768548 2.976265 -3.035070 -v 0.036680 -0.040410 0.098185 -vn 0.258543 -2.976247 -3.120170 -v 0.036395 -0.041010 0.098137 -vn 0.258543 2.976247 -3.120169 -v 0.036395 -0.040410 0.098137 -vn -0.258543 -2.976247 -3.120169 -v 0.036105 -0.041010 0.098137 -vn -0.258543 2.976247 -3.120170 -v 0.036105 -0.040410 0.098137 -vn -0.768584 -2.976241 -3.035058 -v 0.035820 -0.041010 0.098185 -vn -0.768584 2.976241 -3.035058 -v 0.035820 -0.040410 0.098185 -vn -1.257683 -2.976231 -2.867145 -v 0.035547 -0.041010 0.098279 -vn -1.257683 2.976231 -2.867145 -v 0.035547 -0.040410 0.098279 -vn -1.712443 -2.976265 -2.621041 -v 0.035293 -0.041010 0.098416 -vn -1.712443 2.976265 -2.621041 -v 0.035293 -0.040410 0.098416 -vn -2.120472 -2.976246 -2.303453 -v 0.035065 -0.041010 0.098594 -vn -2.120472 2.976246 -2.303453 -v 0.035065 -0.040410 0.098594 -vn -2.470691 -2.976242 -1.923014 -v 0.034869 -0.041010 0.098806 -vn -2.470691 2.976241 -1.923014 -v 0.034869 -0.040410 0.098806 -vn -2.753523 -2.976233 -1.490100 -v 0.034711 -0.041010 0.099048 -vn -2.753523 2.976233 -1.490100 -v 0.034711 -0.040410 0.099048 -vn -2.961232 -2.976264 -1.016572 -v 0.034595 -0.041010 0.099313 -vn -2.961232 2.976264 -1.016572 -v 0.034595 -0.040410 0.099313 -vn -3.088161 -2.976242 -0.515326 -v 0.034524 -0.041010 0.099593 -vn -3.088161 2.976242 -0.515326 -v 0.034524 -0.040410 0.099593 -vn -3.130861 -2.976233 0.000023 -v 0.034500 -0.041010 0.099881 -vn -3.130861 2.976233 0.000023 -v 0.034500 -0.040410 0.099881 -vn -3.088159 -2.976257 0.515349 -v 0.034524 -0.041010 0.100169 -vn -3.088159 2.976256 0.515349 -v 0.034524 -0.040410 0.100169 -vn -2.961225 -2.976252 1.016589 -v 0.034595 -0.041010 0.100449 -vn -2.961225 2.976252 1.016589 -v 0.034595 -0.040410 0.100449 -vn -2.753504 -2.976231 1.490136 -v 0.034711 -0.041010 0.100714 -vn -2.753504 2.976231 1.490136 -v 0.034711 -0.040410 0.100714 -vn -2.470677 -2.976254 1.923034 -v 0.034869 -0.041010 0.100956 -vn -2.470678 2.976254 1.923034 -v 0.034869 -0.040410 0.100956 -vn -2.120471 -2.976248 2.303455 -v 0.035065 -0.041010 0.101169 -vn -2.120471 2.976248 2.303455 -v 0.035065 -0.040410 0.101169 -vn -1.712412 -2.976242 2.621058 -v 0.035293 -0.041010 0.101346 -vn -1.712412 2.976243 2.621058 -v 0.035293 -0.040410 0.101346 -vn 1.710948 -3.326382 -2.618825 -v 0.037070 -0.041010 0.098625 -vn 1.710948 3.326382 -2.618825 -v 0.037070 -0.042010 0.098625 -vn 1.200585 3.326417 -2.888625 -v 0.036826 -0.042010 0.098496 -vn 1.200585 -3.326417 -2.888624 -v 0.036826 -0.041010 0.098496 -vn 0.649384 3.326352 -3.060051 -v 0.036561 -0.042010 0.098414 -vn 0.649384 -3.326352 -3.060052 -v 0.036561 -0.041010 0.098414 -vn 0.076061 3.326421 -3.127262 -v 0.036286 -0.042010 0.098382 -vn 0.076061 -3.326421 -3.127262 -v 0.036286 -0.041010 0.098382 -vn -0.499918 3.326396 -3.087986 -v 0.036010 -0.042010 0.098400 -vn -0.499919 -3.326396 -3.087986 -v 0.036010 -0.041010 0.098400 -vn -1.058782 3.326360 -2.943568 -v 0.035742 -0.042010 0.098470 -vn -1.058782 -3.326360 -2.943568 -v 0.035742 -0.041010 0.098470 -vn -1.581618 3.326416 -2.698896 -v 0.035492 -0.042010 0.098587 -vn -1.581618 -3.326416 -2.698896 -v 0.035492 -0.041010 0.098587 -vn -2.050656 3.326407 -2.362282 -v 0.035267 -0.042010 0.098748 -vn -2.050656 -3.326408 -2.362282 -v 0.035267 -0.041010 0.098748 -vn -2.449794 3.326356 -1.945283 -v 0.035075 -0.042010 0.098948 -vn -2.449793 -3.326355 -1.945283 -v 0.035075 -0.041010 0.098948 -vn -2.765507 3.326412 -1.462031 -v 0.034924 -0.042010 0.099180 -vn -2.765507 -3.326412 -1.462031 -v 0.034924 -0.041010 0.099180 -vn -2.987077 3.326388 -0.928954 -v 0.034818 -0.042010 0.099436 -vn -2.987077 -3.326388 -0.928954 -v 0.034818 -0.041010 0.099436 -vn -3.106910 3.326396 -0.364263 -v 0.034760 -0.042010 0.099707 -vn -3.106910 -3.326396 -0.364263 -v 0.034760 -0.041010 0.099707 -vn -3.120943 3.326390 0.212836 -v 0.034753 -0.042010 0.099983 -vn -3.120943 -3.326390 0.212836 -v 0.034753 -0.041010 0.099983 -vn -3.028691 3.326400 0.782691 -v 0.034798 -0.042010 0.100257 -vn -3.028691 -3.326400 0.782691 -v 0.034798 -0.041010 0.100257 -vn -2.833310 3.326378 1.325877 -v 0.034891 -0.042010 0.100517 -vn -2.833310 -3.326378 1.325876 -v 0.034891 -0.041010 0.100517 -vn -2.541451 3.326391 1.823900 -v 0.035031 -0.042010 0.100756 -vn -2.541451 -3.326391 1.823900 -v 0.035031 -0.041010 0.100756 -vn -2.163013 3.326413 2.259853 -v 0.035213 -0.042010 0.100965 -vn -2.163013 -3.326413 2.259853 -v 0.035213 -0.041010 0.100965 -vn -1.710947 3.326367 2.618829 -v 0.035430 -0.042010 0.101137 -vn -1.710947 -3.326367 2.618829 -v 0.035430 -0.041010 0.101137 -vn -1.083116 -3.365987 2.927925 -v 0.036597 -0.042610 0.098943 -vn -1.083116 3.365986 2.927925 -v 0.036597 -0.040410 0.098943 -vn -0.404470 -3.365975 3.095529 -v 0.036380 -0.042610 0.098890 -vn -0.404470 3.365976 3.095529 -v 0.036380 -0.040410 0.098890 -vn 0.294506 -3.366019 3.107912 -v 0.036156 -0.042610 0.098886 -vn 0.294506 3.366019 3.107912 -v 0.036156 -0.040410 0.098886 -vn 0.978741 -3.365994 2.964446 -v 0.035936 -0.042610 0.098932 -vn 0.978741 3.365994 2.964446 -v 0.035936 -0.040410 0.098932 -vn 1.613845 -3.365983 2.672338 -v 0.035733 -0.042610 0.099025 -vn 1.613845 3.365983 2.672339 -v 0.035733 -0.040410 0.099025 -vn 2.168032 -3.366002 2.246221 -v 0.035556 -0.042610 0.099162 -vn 2.168032 3.366002 2.246221 -v 0.035556 -0.040410 0.099162 -vn 2.613517 -3.365993 1.707458 -v 0.035413 -0.042610 0.099334 -vn 2.613516 3.365993 1.707458 -v 0.035413 -0.040410 0.099334 -vn 2.927935 -3.365992 1.083087 -v 0.035312 -0.042610 0.099534 -vn 2.927935 3.365992 1.083087 -v 0.035312 -0.040410 0.099534 -vn 3.095534 -3.365980 0.404425 -v 0.035258 -0.042610 0.099752 -vn 3.095535 3.365980 0.404425 -v 0.035258 -0.040410 0.099752 -vn 3.107912 -3.366005 -0.294538 -v 0.035254 -0.042610 0.099976 -vn 3.107911 3.366005 -0.294538 -v 0.035254 -0.040410 0.099976 -vn 2.964449 -3.365984 -0.978736 -v 0.035300 -0.042610 0.100195 -vn 2.964450 3.365984 -0.978737 -v 0.035300 -0.040410 0.100195 -vn 2.672334 -3.366000 -1.613848 -v 0.035394 -0.042610 0.100398 -vn 2.672333 3.365999 -1.613848 -v 0.035394 -0.040410 0.100398 -vn 2.246208 -3.365994 -2.168047 -v 0.035530 -0.042610 0.100576 -vn 2.246208 3.365994 -2.168047 -v 0.035530 -0.040410 0.100576 -vn 1.257646 -2.976250 2.867164 -v 0.036953 -0.042610 0.101484 -vn 0.768578 -2.976246 3.035060 -v 0.036680 -0.042610 0.101578 -vn 0.258583 -2.976273 3.120169 -v 0.036395 -0.042610 0.101625 -vn -0.258502 -2.976221 3.120170 -v 0.036105 -0.042610 0.101625 -vn -0.768578 -2.976245 3.035059 -v 0.035820 -0.042610 0.101578 -vn -1.257646 -2.976249 2.867164 -v 0.035547 -0.042610 0.101484 -vn 2.753523 -2.976233 1.490100 -v 0.037789 -0.042610 0.100714 -vn 2.470681 -2.976232 1.923025 -v 0.037631 -0.042610 0.100956 -vn 2.120497 -2.976284 2.303437 -v 0.037435 -0.042610 0.101169 -vn 1.712447 -2.976214 2.621030 -v 0.037207 -0.042610 0.101346 -vn 2.120481 -2.976238 -2.303444 -v 0.037435 -0.042610 0.098594 -vn 2.470691 -2.976260 -1.923019 -v 0.037631 -0.042610 0.098806 -vn 2.753500 -2.976244 -1.490146 -v 0.037789 -0.042610 0.099048 -vn 2.961218 -2.976242 -1.016604 -v 0.037905 -0.042610 0.099313 -vn 3.088161 -2.976244 -0.515329 -v 0.037976 -0.042610 0.099593 -vn 3.130864 -2.976258 -0.000023 -v 0.038000 -0.042610 0.099881 -vn 3.088162 -2.976229 0.515306 -v 0.037976 -0.042610 0.100169 -vn 2.961232 -2.976264 1.016572 -v 0.037905 -0.042610 0.100449 -vn -0.768578 2.976245 3.035060 -v 0.035820 -0.040410 0.101578 -vn -0.258502 2.976221 3.120169 -v 0.036105 -0.040410 0.101625 -vn 0.258583 2.976273 3.120170 -v 0.036395 -0.040410 0.101625 -vn 0.768578 2.976245 3.035060 -v 0.036680 -0.040410 0.101578 -vn 1.257646 2.976250 2.867164 -v 0.036953 -0.040410 0.101484 -vn 1.712447 2.976214 2.621030 -v 0.037207 -0.040410 0.101346 -vn 2.120497 2.976284 2.303437 -v 0.037435 -0.040410 0.101169 -vn 2.470691 2.976260 -1.923019 -v 0.037631 -0.040410 0.098806 -vn 2.120481 2.976238 -2.303444 -v 0.037435 -0.040410 0.098594 -vn -1.257646 2.976249 2.867164 -v 0.035547 -0.040410 0.101484 -vn 3.130864 2.976258 -0.000023 -v 0.038000 -0.040410 0.099881 -vn 3.088161 2.976243 -0.515329 -v 0.037976 -0.040410 0.099593 -vn 2.961218 2.976242 -1.016604 -v 0.037905 -0.040410 0.099313 -vn 2.753500 2.976244 -1.490146 -v 0.037789 -0.040410 0.099048 -vn 2.470681 2.976232 1.923025 -v 0.037631 -0.040410 0.100956 -vn 2.753523 2.976233 1.490100 -v 0.037789 -0.040410 0.100714 -vn 2.961232 2.976264 1.016572 -v 0.037905 -0.040410 0.100449 -vn 3.088162 2.976229 0.515306 -v 0.037976 -0.040410 0.100169 -vn -1.257646 2.976249 2.867164 -v 0.035547 -0.042010 0.101484 -vn -0.768578 2.976245 3.035060 -v 0.035820 -0.042010 0.101578 -vn -0.258502 2.976221 3.120169 -v 0.036105 -0.042010 0.101625 -vn 0.258583 2.976273 3.120170 -v 0.036395 -0.042010 0.101625 -vn 0.768578 2.976245 3.035060 -v 0.036680 -0.042010 0.101578 -vn 1.257646 2.976249 2.867164 -v 0.036953 -0.042010 0.101484 -vn 1.712447 2.976214 2.621030 -v 0.037207 -0.042010 0.101346 -vn 2.120497 2.976284 2.303437 -v 0.037435 -0.042010 0.101169 -vn 2.470681 2.976232 1.923025 -v 0.037631 -0.042010 0.100956 -vn 2.753524 2.976233 1.490100 -v 0.037789 -0.042010 0.100714 -vn 2.961232 2.976264 1.016572 -v 0.037905 -0.042010 0.100449 -vn 3.088162 2.976229 0.515306 -v 0.037976 -0.042010 0.100169 -vn 3.130864 2.976259 -0.000023 -v 0.038000 -0.042010 0.099881 -vn 3.088160 2.976244 -0.515329 -v 0.037976 -0.042010 0.099593 -vn 2.961218 2.976242 -1.016604 -v 0.037905 -0.042010 0.099313 -vn 2.753500 2.976244 -1.490146 -v 0.037789 -0.042010 0.099048 -vn 2.470691 2.976260 -1.923019 -v 0.037631 -0.042010 0.098806 -vn 2.120481 2.976238 -2.303444 -v 0.037435 -0.042010 0.098594 -vn -1.257646 -2.976249 2.867164 -v 0.035547 -0.041010 0.101484 -vn -0.768578 -2.976245 3.035060 -v 0.035820 -0.041010 0.101578 -vn -0.258502 -2.976221 3.120170 -v 0.036105 -0.041010 0.101625 -vn 0.258583 -2.976273 3.120169 -v 0.036395 -0.041010 0.101625 -vn 0.768578 -2.976245 3.035060 -v 0.036680 -0.041010 0.101578 -vn 1.257646 -2.976249 2.867164 -v 0.036953 -0.041010 0.101484 -vn 1.712447 -2.976214 2.621030 -v 0.037207 -0.041010 0.101346 -vn 2.120497 -2.976284 2.303437 -v 0.037435 -0.041010 0.101169 -vn 2.470681 -2.976232 1.923025 -v 0.037631 -0.041010 0.100956 -vn 2.753523 -2.976233 1.490100 -v 0.037789 -0.041010 0.100714 -vn 2.961232 -2.976264 1.016572 -v 0.037905 -0.041010 0.100449 -vn 3.088162 -2.976229 0.515306 -v 0.037976 -0.041010 0.100169 -vn 3.130864 -2.976259 -0.000023 -v 0.038000 -0.041010 0.099881 -vn 3.088160 -2.976243 -0.515329 -v 0.037976 -0.041010 0.099593 -vn 2.961218 -2.976242 -1.016604 -v 0.037905 -0.041010 0.099313 -vn 2.753500 -2.976245 -1.490146 -v 0.037789 -0.041010 0.099048 -vn 2.470691 -2.976260 -1.923019 -v 0.037631 -0.041010 0.098806 -vn 2.120481 -2.976238 -2.303444 -v 0.037435 -0.041010 0.098594 -vn 3.028694 3.326413 -0.782670 -v 0.037702 -0.042010 0.099506 -vn 2.833310 3.326378 -1.325877 -v 0.037609 -0.042010 0.099245 -vn 2.541440 3.326401 -1.823912 -v 0.037469 -0.042010 0.099007 -vn 2.163013 3.326394 -2.259857 -v 0.037287 -0.042010 0.098798 -vn -1.200626 3.326402 2.888610 -v 0.035674 -0.042010 0.101266 -vn -0.649377 3.326399 3.060046 -v 0.035939 -0.042010 0.101349 -vn -0.076022 3.326396 3.127266 -v 0.036214 -0.042010 0.101381 -vn 0.499879 3.326370 3.087996 -v 0.036490 -0.042010 0.101362 -vn 1.058777 3.326410 2.943562 -v 0.036758 -0.042010 0.101293 -vn 1.581653 3.326392 2.698880 -v 0.037008 -0.042010 0.101175 -vn 2.050646 3.326398 2.362293 -v 0.037233 -0.042010 0.101014 -vn 2.449792 3.326377 1.945279 -v 0.037425 -0.042010 0.100814 -vn 2.765517 3.326401 1.462016 -v 0.037576 -0.042010 0.100582 -vn 2.987077 3.326388 0.928954 -v 0.037682 -0.042010 0.100327 -vn 3.106910 3.326397 0.364263 -v 0.037740 -0.042010 0.100056 -vn 3.120946 3.326376 -0.212815 -v 0.037747 -0.042010 0.099779 -vn 0.499879 -3.326370 3.087996 -v 0.036490 -0.041010 0.101362 -vn -0.076022 -3.326396 3.127267 -v 0.036214 -0.041010 0.101381 -vn -0.649377 -3.326399 3.060046 -v 0.035939 -0.041010 0.101349 -vn -1.200626 -3.326402 2.888610 -v 0.035674 -0.041010 0.101266 -vn 2.163013 -3.326394 -2.259856 -v 0.037287 -0.041010 0.098798 -vn 2.541440 -3.326401 -1.823912 -v 0.037469 -0.041010 0.099007 -vn 2.833310 -3.326378 -1.325876 -v 0.037609 -0.041010 0.099245 -vn 3.028694 -3.326413 -0.782670 -v 0.037702 -0.041010 0.099506 -vn 3.120946 -3.326376 -0.212815 -v 0.037747 -0.041010 0.099779 -vn 3.106910 -3.326397 0.364263 -v 0.037740 -0.041010 0.100056 -vn 2.987077 -3.326388 0.928954 -v 0.037682 -0.041010 0.100327 -vn 2.765517 -3.326401 1.462016 -v 0.037576 -0.041010 0.100582 -vn 2.449793 -3.326377 1.945279 -v 0.037425 -0.041010 0.100814 -vn 2.050646 -3.326398 2.362293 -v 0.037233 -0.041010 0.101014 -vn 1.581653 -3.326392 2.698880 -v 0.037008 -0.041010 0.101175 -vn 1.058777 -3.326410 2.943562 -v 0.036758 -0.041010 0.101293 -vn -0.000000 3.365984 3.121840 -v 0.027919 -0.040410 0.090550 -vn 0.000000 -3.365984 3.121840 -v 0.027919 -0.042610 0.090550 -vn -0.694689 3.366010 3.043561 -v 0.028141 -0.040410 0.090575 -vn -0.694688 -3.366009 3.043561 -v 0.028141 -0.042610 0.090575 -vn -1.354522 3.365969 2.812681 -v 0.028353 -0.040410 0.090649 -vn -1.354522 -3.365969 2.812681 -v 0.028353 -0.042610 0.090649 -vn -1.946415 3.365996 2.440767 -v 0.028542 -0.040410 0.090768 -vn -1.946415 -3.365996 2.440767 -v 0.028542 -0.042610 0.090768 -vn -2.440749 3.366003 1.946435 -v 0.028701 -0.040410 0.090927 -vn -2.440750 -3.366003 1.946435 -v 0.028701 -0.042610 0.090927 -vn -2.812688 3.365995 1.354498 -v 0.028820 -0.040410 0.091116 -vn -2.812687 -3.365995 1.354498 -v 0.028820 -0.042610 0.091116 -vn -3.043571 3.365979 0.694671 -v 0.028894 -0.040410 0.091327 -vn -3.043571 -3.365979 0.694671 -v 0.028894 -0.042610 0.091327 -vn -3.121837 3.366003 -0.000000 -v 0.028919 -0.040410 0.091550 -vn -3.121837 -3.366003 0.000000 -v 0.028919 -0.042610 0.091550 -vn -3.043571 3.365979 -0.694671 -v 0.028894 -0.040410 0.091773 -vn -3.043571 -3.365979 -0.694671 -v 0.028894 -0.042610 0.091773 -vn -2.812673 3.366013 -1.354521 -v 0.028820 -0.040410 0.091984 -vn -2.812673 -3.366013 -1.354521 -v 0.028820 -0.042610 0.091984 -vn -2.440735 3.365985 -1.946459 -v 0.028701 -0.040410 0.092173 -vn -2.440734 -3.365985 -1.946459 -v 0.028701 -0.042610 0.092173 -vn -1.946452 3.365968 -2.440743 -v 0.028542 -0.040410 0.092332 -vn -1.946452 -3.365968 -2.440743 -v 0.028542 -0.042610 0.092332 -vn -1.354513 3.366028 -2.812674 -v 0.028353 -0.040410 0.092451 -vn -1.354513 -3.366028 -2.812674 -v 0.028353 -0.042610 0.092451 -vn -0.694642 3.365978 -3.043578 -v 0.028141 -0.040410 0.092525 -vn -0.694642 -3.365978 -3.043578 -v 0.028141 -0.042610 0.092525 -vn 0.000000 3.365984 -3.121840 -v 0.027919 -0.040410 0.092550 -vn -0.000000 -3.365984 -3.121840 -v 0.027919 -0.042610 0.092550 -vn 0.000001 -2.976218 3.130859 -v 0.027919 -0.041010 0.093300 -vn -0.515344 2.976259 3.088160 -v 0.027631 -0.040410 0.093276 -vn -0.515344 -2.976259 3.088160 -v 0.027631 -0.041010 0.093276 -vn -1.016595 2.976241 2.961221 -v 0.027351 -0.040410 0.093205 -vn -1.016595 -2.976241 2.961221 -v 0.027351 -0.041010 0.093205 -vn -1.490114 2.976264 2.753520 -v 0.027086 -0.040410 0.093089 -vn -1.490114 -2.976264 2.753520 -v 0.027086 -0.041010 0.093089 -vn -1.923011 2.976220 2.470690 -v 0.026844 -0.040410 0.092931 -vn -1.923011 -2.976220 2.470690 -v 0.026844 -0.041010 0.092931 -vn -2.303450 2.976272 2.120481 -v 0.026631 -0.040410 0.092735 -vn -2.303450 -2.976272 2.120481 -v 0.026631 -0.041010 0.092735 -vn -2.621047 2.976220 1.712423 -v 0.026454 -0.040410 0.092507 -vn -2.621047 -2.976220 1.712422 -v 0.026454 -0.041010 0.092507 -vn -2.867165 2.976264 1.257649 -v 0.026316 -0.040410 0.092253 -vn -2.867165 -2.976264 1.257649 -v 0.026316 -0.041010 0.092253 -vn -3.035056 2.976235 0.768587 -v 0.026222 -0.040410 0.091980 -vn -3.035056 -2.976235 0.768587 -v 0.026222 -0.041010 0.091980 -vn -3.120170 2.976249 0.258539 -v 0.026175 -0.040410 0.091695 -vn -3.120170 -2.976249 0.258539 -v 0.026175 -0.041010 0.091695 -vn -3.120169 2.976244 -0.258546 -v 0.026175 -0.040410 0.091405 -vn -3.120169 -2.976245 -0.258546 -v 0.026175 -0.041010 0.091405 -vn -3.035059 2.976247 -0.768581 -v 0.026222 -0.040410 0.091120 -vn -3.035059 -2.976248 -0.768581 -v 0.026222 -0.041010 0.091120 -vn -2.867160 2.976243 -1.257653 -v 0.026316 -0.040410 0.090847 -vn -2.867160 -2.976243 -1.257653 -v 0.026316 -0.041010 0.090847 -vn -2.621053 2.976248 -1.712420 -v 0.026454 -0.040410 0.090593 -vn -2.621053 -2.976248 -1.712420 -v 0.026454 -0.041010 0.090593 -vn -2.303443 2.976237 -2.120482 -v 0.026631 -0.040410 0.090365 -vn -2.303443 -2.976237 -2.120482 -v 0.026631 -0.041010 0.090365 -vn -1.923018 2.976261 -2.470692 -v 0.026844 -0.040410 0.090169 -vn -1.923018 -2.976261 -2.470691 -v 0.026844 -0.041010 0.090169 -vn -1.490143 2.976242 -2.753502 -v 0.027086 -0.040410 0.090011 -vn -1.490143 -2.976242 -2.753502 -v 0.027086 -0.041010 0.090011 -vn -1.016595 2.976241 -2.961221 -v 0.027351 -0.040410 0.089895 -vn -1.016595 -2.976241 -2.961221 -v 0.027351 -0.041010 0.089895 -vn -0.515303 2.976233 -3.088163 -v 0.027631 -0.040410 0.089824 -vn -0.515304 -2.976233 -3.088163 -v 0.027631 -0.041010 0.089824 -vn 0.000001 -2.976270 -3.130866 -v 0.027919 -0.041010 0.089800 -vn 0.000001 2.976218 3.130859 -v 0.027919 -0.042010 0.093300 -vn -0.515344 2.976259 3.088160 -v 0.027631 -0.042010 0.093276 -vn -0.515344 -2.976259 3.088160 -v 0.027631 -0.042610 0.093276 -vn -1.016595 2.976241 2.961221 -v 0.027351 -0.042010 0.093205 -vn -1.016595 -2.976241 2.961221 -v 0.027351 -0.042610 0.093205 -vn -1.490114 2.976263 2.753520 -v 0.027086 -0.042010 0.093089 -vn -1.490114 -2.976264 2.753520 -v 0.027086 -0.042610 0.093089 -vn -1.923011 2.976221 2.470690 -v 0.026844 -0.042010 0.092931 -vn -1.923011 -2.976220 2.470690 -v 0.026844 -0.042610 0.092931 -vn -2.303450 2.976272 2.120481 -v 0.026631 -0.042010 0.092735 -vn -2.303450 -2.976272 2.120481 -v 0.026631 -0.042610 0.092735 -vn -2.621047 2.976220 1.712422 -v 0.026454 -0.042010 0.092507 -vn -2.621047 -2.976220 1.712423 -v 0.026454 -0.042610 0.092507 -vn -2.867165 2.976264 1.257649 -v 0.026316 -0.042010 0.092253 -vn -2.867165 -2.976264 1.257649 -v 0.026316 -0.042610 0.092253 -vn -3.035056 2.976235 0.768587 -v 0.026222 -0.042010 0.091980 -vn -3.035056 -2.976235 0.768587 -v 0.026222 -0.042610 0.091980 -vn -3.120170 2.976249 0.258539 -v 0.026175 -0.042010 0.091695 -vn -3.120170 -2.976249 0.258539 -v 0.026175 -0.042610 0.091695 -vn -3.120169 2.976245 -0.258546 -v 0.026175 -0.042010 0.091405 -vn -3.120169 -2.976244 -0.258546 -v 0.026175 -0.042610 0.091405 -vn -3.035059 2.976247 -0.768581 -v 0.026222 -0.042010 0.091120 -vn -3.035059 -2.976248 -0.768581 -v 0.026222 -0.042610 0.091120 -vn -2.867160 2.976244 -1.257653 -v 0.026316 -0.042010 0.090847 -vn -2.867160 -2.976243 -1.257653 -v 0.026316 -0.042610 0.090847 -vn -2.621053 2.976248 -1.712420 -v 0.026454 -0.042010 0.090593 -vn -2.621053 -2.976248 -1.712420 -v 0.026454 -0.042610 0.090593 -vn -2.303443 2.976237 -2.120482 -v 0.026631 -0.042010 0.090365 -vn -2.303443 -2.976237 -2.120482 -v 0.026631 -0.042610 0.090365 -vn -1.923018 2.976261 -2.470691 -v 0.026844 -0.042010 0.090169 -vn -1.923018 -2.976261 -2.470692 -v 0.026844 -0.042610 0.090169 -vn -1.490143 2.976242 -2.753502 -v 0.027086 -0.042010 0.090011 -vn -1.490143 -2.976242 -2.753502 -v 0.027086 -0.042610 0.090011 -vn -1.016595 2.976241 -2.961221 -v 0.027351 -0.042010 0.089895 -vn -1.016595 -2.976241 -2.961221 -v 0.027351 -0.042610 0.089895 -vn -0.515303 2.976233 -3.088163 -v 0.027631 -0.042010 0.089824 -vn -0.515304 -2.976234 -3.088164 -v 0.027631 -0.042610 0.089824 -vn 0.000001 2.976270 -3.130866 -v 0.027919 -0.042010 0.089800 -vn 0.000000 3.326394 3.128191 -v 0.027919 -0.042010 0.093050 -vn 0.000000 -3.326394 3.128191 -v 0.027919 -0.041010 0.093050 -vn -0.574800 -3.326388 3.074929 -v 0.027643 -0.041010 0.093024 -vn -0.574800 3.326388 3.074929 -v 0.027643 -0.042010 0.093024 -vn -1.130023 -3.326392 2.916955 -v 0.027377 -0.041010 0.092949 -vn -1.130023 3.326392 2.916955 -v 0.027377 -0.042010 0.092949 -vn -1.646767 -3.326389 2.659651 -v 0.027129 -0.041010 0.092825 -vn -1.646767 3.326389 2.659651 -v 0.027129 -0.042010 0.092825 -vn -2.107444 -3.326403 2.311763 -v 0.026908 -0.041010 0.092659 -vn -2.107445 3.326403 2.311763 -v 0.026908 -0.042010 0.092659 -vn -2.496352 -3.326385 1.885156 -v 0.026722 -0.041010 0.092454 -vn -2.496352 3.326385 1.885157 -v 0.026722 -0.042010 0.092454 -vn -2.800245 -3.326406 1.394345 -v 0.026576 -0.041010 0.092219 -vn -2.800245 3.326406 1.394345 -v 0.026576 -0.042010 0.092219 -vn -3.008779 -3.326377 0.856062 -v 0.026476 -0.041010 0.091960 -vn -3.008779 3.326378 0.856062 -v 0.026476 -0.042010 0.091960 -vn -3.114846 -3.326396 0.288640 -v 0.026425 -0.041010 0.091688 -vn -3.114846 3.326396 0.288640 -v 0.026425 -0.042010 0.091688 -vn -3.114847 -3.326392 -0.288632 -v 0.026425 -0.041010 0.091412 -vn -3.114847 3.326392 -0.288632 -v 0.026425 -0.042010 0.091412 -vn -3.008775 -3.326392 -0.856069 -v 0.026476 -0.041010 0.091140 -vn -3.008775 3.326392 -0.856069 -v 0.026476 -0.042010 0.091140 -vn -2.800251 -3.326382 -1.394340 -v 0.026576 -0.041010 0.090881 -vn -2.800251 3.326382 -1.394340 -v 0.026576 -0.042010 0.090881 -vn -2.496344 -3.326416 -1.885159 -v 0.026722 -0.041010 0.090646 -vn -2.496344 3.326417 -1.885158 -v 0.026722 -0.042010 0.090646 -vn -2.107452 -3.326363 -2.311763 -v 0.026908 -0.041010 0.090441 -vn -2.107452 3.326364 -2.311764 -v 0.026908 -0.042010 0.090441 -vn -1.646794 -3.326410 -2.659630 -v 0.027129 -0.041010 0.090275 -vn -1.646794 3.326410 -2.659630 -v 0.027129 -0.042010 0.090275 -vn -1.130023 -3.326392 -2.916955 -v 0.027377 -0.041010 0.090151 -vn -1.130023 3.326392 -2.916955 -v 0.027377 -0.042010 0.090151 -vn -0.574800 -3.326388 -3.074929 -v 0.027643 -0.041010 0.090076 -vn -0.574800 3.326388 -3.074929 -v 0.027643 -0.042010 0.090076 -vn 0.000000 -3.326394 -3.128191 -v 0.027919 -0.041010 0.090050 -vn 0.000000 3.326394 -3.128191 -v 0.027919 -0.042010 0.090050 -vn 0.694638 3.365975 -3.043579 -v 0.027696 -0.040410 0.092525 -vn 0.694638 -3.365975 -3.043579 -v 0.027696 -0.042610 0.092525 -vn 1.354509 3.366031 -2.812675 -v 0.027485 -0.040410 0.092451 -vn 1.354509 -3.366031 -2.812675 -v 0.027485 -0.042610 0.092451 -vn 1.946452 3.365968 -2.440743 -v 0.027295 -0.040410 0.092332 -vn 1.946452 -3.365968 -2.440743 -v 0.027295 -0.042610 0.092332 -vn 2.440740 3.365992 -1.946449 -v 0.027137 -0.040410 0.092173 -vn 2.440740 -3.365992 -1.946449 -v 0.027137 -0.042610 0.092173 -vn 2.812674 3.365998 -1.354523 -v 0.027018 -0.040410 0.091984 -vn 2.812674 -3.365998 -1.354523 -v 0.027018 -0.042610 0.091984 -vn 3.043568 3.365995 -0.694670 -v 0.026944 -0.040410 0.091773 -vn 3.043569 -3.365995 -0.694670 -v 0.026944 -0.042610 0.091773 -vn 3.121840 3.365986 0.000000 -v 0.026919 -0.040410 0.091550 -vn 3.121840 -3.365986 0.000000 -v 0.026919 -0.042610 0.091550 -vn 3.043569 3.365995 0.694670 -v 0.026944 -0.040410 0.091327 -vn 3.043568 -3.365995 0.694670 -v 0.026944 -0.042610 0.091327 -vn 2.812689 3.365980 1.354500 -v 0.027018 -0.040410 0.091116 -vn 2.812689 -3.365980 1.354500 -v 0.027018 -0.042610 0.091116 -vn 2.440755 3.366010 1.946426 -v 0.027137 -0.040410 0.090927 -vn 2.440755 -3.366010 1.946426 -v 0.027137 -0.042610 0.090927 -vn 1.946415 3.365996 2.440767 -v 0.027295 -0.040410 0.090768 -vn 1.946415 -3.365996 2.440767 -v 0.027295 -0.042610 0.090768 -vn 1.354518 3.365972 2.812682 -v 0.027485 -0.040410 0.090649 -vn 1.354518 -3.365972 2.812681 -v 0.027485 -0.042610 0.090649 -vn 0.694684 3.366007 3.043562 -v 0.027696 -0.040410 0.090575 -vn 0.694685 -3.366007 3.043563 -v 0.027696 -0.042610 0.090575 -vn 1.016593 2.976240 -2.961222 -v 0.028487 -0.040410 0.089895 -vn 0.515302 2.976235 -3.088164 -v 0.028207 -0.040410 0.089824 -vn 2.621053 2.976248 -1.712420 -v 0.029384 -0.040410 0.090593 -vn 2.303438 2.976233 -2.120486 -v 0.029206 -0.040410 0.090365 -vn 1.923018 2.976269 -2.470693 -v 0.028994 -0.040410 0.090169 -vn 1.490147 2.976238 -2.753499 -v 0.028752 -0.040410 0.090011 -vn 2.621047 2.976220 1.712422 -v 0.029384 -0.040410 0.092507 -vn 2.867165 2.976264 1.257649 -v 0.029521 -0.040410 0.092253 -vn 3.035056 2.976235 0.768587 -v 0.029615 -0.040410 0.091980 -vn 3.120170 2.976249 0.258539 -v 0.029663 -0.040410 0.091695 -vn 3.120169 2.976244 -0.258546 -v 0.029663 -0.040410 0.091405 -vn 3.035059 2.976247 -0.768581 -v 0.029615 -0.040410 0.091120 -vn 2.867160 2.976243 -1.257653 -v 0.029521 -0.040410 0.090847 -vn 0.515342 2.976261 3.088161 -v 0.028207 -0.040410 0.093276 -vn 1.016593 2.976240 2.961222 -v 0.028487 -0.040410 0.093205 -vn 1.490119 2.976260 2.753517 -v 0.028752 -0.040410 0.093089 -vn 1.923011 2.976228 2.470691 -v 0.028994 -0.040410 0.092931 -vn 2.303445 2.976268 2.120486 -v 0.029206 -0.040410 0.092735 -vn 2.621053 -2.976248 -1.712420 -v 0.029384 -0.042610 0.090593 -vn 2.867160 -2.976243 -1.257653 -v 0.029521 -0.042610 0.090847 -vn 1.016593 -2.976240 2.961222 -v 0.028487 -0.042610 0.093205 -vn 0.515342 -2.976261 3.088161 -v 0.028207 -0.042610 0.093276 -vn 2.621047 -2.976220 1.712422 -v 0.029384 -0.042610 0.092507 -vn 2.303445 -2.976268 2.120486 -v 0.029206 -0.042610 0.092735 -vn 1.923011 -2.976228 2.470691 -v 0.028994 -0.042610 0.092931 -vn 1.490119 -2.976260 2.753518 -v 0.028752 -0.042610 0.093089 -vn 3.035059 -2.976247 -0.768581 -v 0.029615 -0.042610 0.091120 -vn 3.120169 -2.976244 -0.258546 -v 0.029663 -0.042610 0.091405 -vn 3.120170 -2.976249 0.258539 -v 0.029663 -0.042610 0.091695 -vn 3.035056 -2.976235 0.768587 -v 0.029615 -0.042610 0.091980 -vn 2.867165 -2.976264 1.257649 -v 0.029521 -0.042610 0.092253 -vn 1.016593 -2.976240 -2.961222 -v 0.028487 -0.042610 0.089895 -vn 1.490147 -2.976238 -2.753499 -v 0.028752 -0.042610 0.090011 -vn 1.923017 -2.976269 -2.470693 -v 0.028994 -0.042610 0.090169 -vn 2.303438 -2.976233 -2.120486 -v 0.029206 -0.042610 0.090365 -vn 0.515302 -2.976236 -3.088164 -v 0.028207 -0.042610 0.089824 -vn 0.515302 -2.976236 -3.088164 -v 0.028207 -0.041010 0.089824 -vn 1.016593 -2.976240 -2.961222 -v 0.028487 -0.041010 0.089895 -vn 1.490147 -2.976238 -2.753499 -v 0.028752 -0.041010 0.090011 -vn 1.923018 -2.976269 -2.470693 -v 0.028994 -0.041010 0.090169 -vn 2.303438 -2.976233 -2.120486 -v 0.029206 -0.041010 0.090365 -vn 2.621053 -2.976248 -1.712420 -v 0.029384 -0.041010 0.090593 -vn 2.867160 -2.976244 -1.257654 -v 0.029521 -0.041010 0.090847 -vn 3.035059 -2.976247 -0.768581 -v 0.029615 -0.041010 0.091120 -vn 3.120169 -2.976245 -0.258546 -v 0.029663 -0.041010 0.091405 -vn 3.120170 -2.976249 0.258539 -v 0.029663 -0.041010 0.091695 -vn 3.035056 -2.976235 0.768587 -v 0.029615 -0.041010 0.091980 -vn 2.867165 -2.976264 1.257649 -v 0.029521 -0.041010 0.092253 -vn 2.621047 -2.976220 1.712423 -v 0.029384 -0.041010 0.092507 -vn 2.303445 -2.976268 2.120486 -v 0.029206 -0.041010 0.092735 -vn 1.923011 -2.976228 2.470691 -v 0.028994 -0.041010 0.092931 -vn 1.490119 -2.976260 2.753517 -v 0.028752 -0.041010 0.093089 -vn 1.016593 -2.976240 2.961222 -v 0.028487 -0.041010 0.093205 -vn 0.515342 -2.976262 3.088161 -v 0.028207 -0.041010 0.093276 -vn 0.515302 2.976236 -3.088164 -v 0.028207 -0.042010 0.089824 -vn 1.016593 2.976240 -2.961222 -v 0.028487 -0.042010 0.089895 -vn 1.490147 2.976238 -2.753499 -v 0.028752 -0.042010 0.090011 -vn 1.923017 2.976269 -2.470693 -v 0.028994 -0.042010 0.090169 -vn 2.303438 2.976233 -2.120486 -v 0.029206 -0.042010 0.090365 -vn 2.621053 2.976248 -1.712420 -v 0.029384 -0.042010 0.090593 -vn 2.867160 2.976243 -1.257653 -v 0.029521 -0.042010 0.090847 -vn 3.035059 2.976248 -0.768581 -v 0.029615 -0.042010 0.091120 -vn 3.120169 2.976245 -0.258546 -v 0.029663 -0.042010 0.091405 -vn 3.120170 2.976249 0.258539 -v 0.029663 -0.042010 0.091695 -vn 3.035056 2.976235 0.768587 -v 0.029615 -0.042010 0.091980 -vn 2.867165 2.976264 1.257649 -v 0.029521 -0.042010 0.092253 -vn 2.621047 2.976220 1.712422 -v 0.029384 -0.042010 0.092507 -vn 2.303445 2.976268 2.120486 -v 0.029206 -0.042010 0.092735 -vn 1.923011 2.976228 2.470691 -v 0.028994 -0.042010 0.092931 -vn 1.490119 2.976260 2.753517 -v 0.028752 -0.042010 0.093089 -vn 1.016593 2.976240 2.961222 -v 0.028487 -0.042010 0.093205 -vn 0.515342 2.976261 3.088160 -v 0.028207 -0.042010 0.093276 -vn 2.107457 -3.326359 -2.311760 -v 0.028929 -0.041010 0.090441 -vn 2.496339 -3.326411 -1.885166 -v 0.029116 -0.041010 0.090646 -vn 2.800246 -3.326388 -1.394348 -v 0.029262 -0.041010 0.090881 -vn 3.008775 -3.326392 -0.856069 -v 0.029362 -0.041010 0.091140 -vn 3.114847 -3.326392 -0.288632 -v 0.029412 -0.041010 0.091412 -vn 3.114846 -3.326396 0.288640 -v 0.029412 -0.041010 0.091688 -vn 3.008779 -3.326378 0.856062 -v 0.029362 -0.041010 0.091960 -vn 2.800240 -3.326412 1.394352 -v 0.029262 -0.041010 0.092219 -vn 2.496347 -3.326379 1.885164 -v 0.029116 -0.041010 0.092454 -vn 2.107450 -3.326399 2.311759 -v 0.028929 -0.041010 0.092659 -vn 0.574800 -3.326388 -3.074929 -v 0.028194 -0.041010 0.090076 -vn 1.130023 -3.326392 -2.916955 -v 0.028461 -0.041010 0.090151 -vn 1.646799 -3.326415 -2.659626 -v 0.028708 -0.041010 0.090275 -vn 1.646772 -3.326393 2.659647 -v 0.028708 -0.041010 0.092825 -vn 1.130023 -3.326392 2.916955 -v 0.028461 -0.041010 0.092949 -vn 0.574800 -3.326388 3.074929 -v 0.028194 -0.041010 0.093024 -vn 0.574800 3.326388 3.074929 -v 0.028194 -0.042010 0.093024 -vn 1.130023 3.326392 2.916955 -v 0.028461 -0.042010 0.092949 -vn 1.646772 3.326393 2.659647 -v 0.028708 -0.042010 0.092825 -vn 2.107449 3.326399 2.311759 -v 0.028929 -0.042010 0.092659 -vn 2.107457 3.326359 -2.311760 -v 0.028929 -0.042010 0.090441 -vn 1.646799 3.326415 -2.659626 -v 0.028708 -0.042010 0.090275 -vn 1.130023 3.326392 -2.916955 -v 0.028461 -0.042010 0.090151 -vn 0.574800 3.326388 -3.074929 -v 0.028194 -0.042010 0.090076 -vn 2.496347 3.326379 1.885164 -v 0.029116 -0.042010 0.092454 -vn 2.800240 3.326412 1.394352 -v 0.029262 -0.042010 0.092219 -vn 3.008779 3.326377 0.856062 -v 0.029362 -0.042010 0.091960 -vn 3.114846 3.326396 0.288640 -v 0.029412 -0.042010 0.091688 -vn 3.114847 3.326392 -0.288632 -v 0.029412 -0.042010 0.091412 -vn 3.008775 3.326392 -0.856069 -v 0.029362 -0.042010 0.091140 -vn 2.800246 3.326388 -1.394348 -v 0.029262 -0.042010 0.090881 -vn 2.496340 3.326411 -1.885166 -v 0.029116 -0.042010 0.090646 -vn 1.707460 -3.365987 -2.613516 -v 0.026253 -0.041010 0.082937 -vn 1.707460 3.365987 -2.613515 -v 0.026253 -0.038810 0.082937 -vn 1.083110 -3.365983 -2.927927 -v 0.026453 -0.041010 0.083038 -vn 1.083111 3.365983 -2.927927 -v 0.026453 -0.038810 0.083038 -vn 0.404417 -3.366009 -3.095531 -v 0.026670 -0.041010 0.083092 -vn 0.404417 3.366009 -3.095530 -v 0.026670 -0.038810 0.083092 -vn -0.294556 -3.365983 -3.107913 -v 0.026894 -0.041010 0.083096 -vn -0.294556 3.365983 -3.107914 -v 0.026894 -0.038810 0.083096 -vn -0.978739 -3.365996 -2.964447 -v 0.027114 -0.041010 0.083050 -vn -0.978738 3.365996 -2.964447 -v 0.027114 -0.038810 0.083050 -vn -1.613851 -3.365988 -2.672333 -v 0.027317 -0.041010 0.082956 -vn -1.613851 3.365988 -2.672334 -v 0.027317 -0.038810 0.082956 -vn -2.168024 -3.365982 -2.246233 -v 0.027494 -0.041010 0.082820 -vn -2.168023 3.365982 -2.246233 -v 0.027494 -0.038810 0.082820 -vn -2.613501 -3.366007 -1.707476 -v 0.027637 -0.041010 0.082647 -vn -2.613501 3.366007 -1.707476 -v 0.027637 -0.038810 0.082647 -vn -2.927928 -3.365975 -1.083112 -v 0.027738 -0.041010 0.082447 -vn -2.927929 3.365975 -1.083112 -v 0.027738 -0.038810 0.082447 -vn -3.095529 -3.366005 -0.404436 -v 0.027792 -0.041010 0.082230 -vn -3.095529 3.366005 -0.404436 -v 0.027792 -0.038810 0.082230 -vn -3.107914 -3.365990 0.294540 -v 0.027796 -0.041010 0.082006 -vn -3.107914 3.365990 0.294540 -v 0.027796 -0.038810 0.082006 -vn -2.964448 -3.365997 0.978735 -v 0.027750 -0.041010 0.081786 -vn -2.964447 3.365997 0.978735 -v 0.027750 -0.038810 0.081786 -vn -2.672323 -3.366000 1.613865 -v 0.027656 -0.041010 0.081583 -vn -2.672323 3.366000 1.613865 -v 0.027656 -0.038810 0.081583 -vn -2.246233 -3.365962 2.168030 -v 0.027520 -0.041010 0.081406 -vn -2.246233 3.365962 2.168029 -v 0.027520 -0.038810 0.081406 -vn -1.707497 -3.366009 2.613487 -v 0.027347 -0.041010 0.081263 -vn -1.707497 3.366008 2.613488 -v 0.027347 -0.038810 0.081263 -vn 1.712408 2.976239 -2.621060 -v 0.027757 -0.040410 0.080635 -vn 1.712408 -2.976239 -2.621060 -v 0.027757 -0.041010 0.080635 -vn 1.257644 -2.976255 -2.867165 -v 0.027503 -0.041010 0.080497 -vn 1.257645 2.976254 -2.867165 -v 0.027503 -0.040410 0.080497 -vn 0.768580 -2.976242 -3.035059 -v 0.027230 -0.041010 0.080404 -vn 0.768580 2.976242 -3.035059 -v 0.027230 -0.040410 0.080404 -vn 0.258500 -2.976222 -3.120170 -v 0.026945 -0.041010 0.080356 -vn 0.258501 2.976222 -3.120170 -v 0.026945 -0.040410 0.080356 -vn -0.258583 -2.976273 -3.120169 -v 0.026655 -0.041010 0.080356 -vn -0.258583 2.976273 -3.120170 -v 0.026655 -0.040410 0.080356 -vn -0.768581 -2.976243 -3.035059 -v 0.026370 -0.041010 0.080404 -vn -0.768581 2.976243 -3.035059 -v 0.026370 -0.040410 0.080404 -vn -1.257649 -2.976252 -2.867163 -v 0.026097 -0.041010 0.080497 -vn -1.257649 2.976251 -2.867163 -v 0.026097 -0.040410 0.080497 -vn -1.712417 -2.976238 -2.621054 -v 0.025843 -0.041010 0.080635 -vn -1.712417 2.976238 -2.621054 -v 0.025843 -0.040410 0.080635 -vn -2.120486 -2.976242 -2.303441 -v 0.025615 -0.041010 0.080812 -vn -2.120486 2.976242 -2.303440 -v 0.025615 -0.040410 0.080812 -vn -2.470704 -2.976243 -1.922997 -v 0.025419 -0.041010 0.081025 -vn -2.470705 2.976244 -1.922997 -v 0.025419 -0.040410 0.081025 -vn -2.753525 -2.976245 -1.490102 -v 0.025261 -0.041010 0.081267 -vn -2.753524 2.976244 -1.490102 -v 0.025261 -0.040410 0.081267 -vn -2.961231 -2.976252 -1.016571 -v 0.025145 -0.041010 0.081532 -vn -2.961231 2.976252 -1.016571 -v 0.025145 -0.040410 0.081532 -vn -3.088163 -2.976243 -0.515310 -v 0.025074 -0.041010 0.081812 -vn -3.088163 2.976243 -0.515310 -v 0.025074 -0.040410 0.081812 -vn -3.130863 -2.976250 0.000010 -v 0.025050 -0.041010 0.082100 -vn -3.130863 2.976250 0.000010 -v 0.025050 -0.040410 0.082100 -vn -3.088160 -2.976244 0.515329 -v 0.025074 -0.041010 0.082388 -vn -3.088160 2.976244 0.515329 -v 0.025074 -0.040410 0.082388 -vn -2.961218 -2.976242 1.016604 -v 0.025145 -0.041010 0.082668 -vn -2.961218 2.976242 1.016604 -v 0.025145 -0.040410 0.082668 -vn -2.753505 -2.976250 1.490139 -v 0.025261 -0.041010 0.082933 -vn -2.753505 2.976250 1.490139 -v 0.025261 -0.040410 0.082933 -vn -2.470690 -2.976250 1.923017 -v 0.025419 -0.041010 0.083175 -vn -2.470690 2.976250 1.923017 -v 0.025419 -0.040410 0.083175 -vn -2.120456 -2.976226 2.303465 -v 0.025615 -0.041010 0.083388 -vn -2.120456 2.976227 2.303465 -v 0.025615 -0.040410 0.083388 -vn -1.712388 -2.976256 2.621076 -v 0.025843 -0.041010 0.083565 -vn -1.712387 2.976256 2.621076 -v 0.025843 -0.040410 0.083565 -vn 1.712408 2.976239 -2.621060 -v 0.027757 -0.038810 0.080635 -vn 1.712408 -2.976239 -2.621060 -v 0.027757 -0.039410 0.080635 -vn 1.257644 -2.976254 -2.867165 -v 0.027503 -0.039410 0.080497 -vn 1.257645 2.976254 -2.867165 -v 0.027503 -0.038810 0.080497 -vn 0.768580 -2.976242 -3.035059 -v 0.027230 -0.039410 0.080404 -vn 0.768580 2.976242 -3.035059 -v 0.027230 -0.038810 0.080404 -vn 0.258500 -2.976222 -3.120170 -v 0.026945 -0.039410 0.080356 -vn 0.258501 2.976222 -3.120170 -v 0.026945 -0.038810 0.080356 -vn -0.258583 -2.976273 -3.120169 -v 0.026655 -0.039410 0.080356 -vn -0.258583 2.976273 -3.120170 -v 0.026655 -0.038810 0.080356 -vn -0.768581 -2.976243 -3.035059 -v 0.026370 -0.039410 0.080404 -vn -0.768581 2.976243 -3.035059 -v 0.026370 -0.038810 0.080404 -vn -1.257649 -2.976251 -2.867163 -v 0.026097 -0.039410 0.080497 -vn -1.257649 2.976252 -2.867163 -v 0.026097 -0.038810 0.080497 -vn -1.712417 -2.976238 -2.621054 -v 0.025843 -0.039410 0.080635 -vn -1.712417 2.976238 -2.621054 -v 0.025843 -0.038810 0.080635 -vn -2.120486 -2.976242 -2.303441 -v 0.025615 -0.039410 0.080812 -vn -2.120486 2.976242 -2.303440 -v 0.025615 -0.038810 0.080812 -vn -2.470704 -2.976244 -1.922997 -v 0.025419 -0.039410 0.081025 -vn -2.470705 2.976244 -1.922997 -v 0.025419 -0.038810 0.081025 -vn -2.753525 -2.976244 -1.490102 -v 0.025261 -0.039410 0.081267 -vn -2.753524 2.976245 -1.490102 -v 0.025261 -0.038810 0.081267 -vn -2.961231 -2.976252 -1.016571 -v 0.025145 -0.039410 0.081532 -vn -2.961231 2.976252 -1.016571 -v 0.025145 -0.038810 0.081532 -vn -3.088163 -2.976244 -0.515310 -v 0.025074 -0.039410 0.081812 -vn -3.088163 2.976243 -0.515310 -v 0.025074 -0.038810 0.081812 -vn -3.130863 -2.976250 0.000010 -v 0.025050 -0.039410 0.082100 -vn -3.130863 2.976250 0.000010 -v 0.025050 -0.038810 0.082100 -vn -3.088160 -2.976243 0.515329 -v 0.025074 -0.039410 0.082388 -vn -3.088160 2.976244 0.515329 -v 0.025074 -0.038810 0.082388 -vn -2.961218 -2.976242 1.016604 -v 0.025145 -0.039410 0.082668 -vn -2.961218 2.976242 1.016604 -v 0.025145 -0.038810 0.082668 -vn -2.753505 -2.976250 1.490139 -v 0.025261 -0.039410 0.082933 -vn -2.753505 2.976250 1.490139 -v 0.025261 -0.038810 0.082933 -vn -2.470690 -2.976250 1.923017 -v 0.025419 -0.039410 0.083175 -vn -2.470690 2.976250 1.923017 -v 0.025419 -0.038810 0.083175 -vn -2.120456 -2.976226 2.303465 -v 0.025615 -0.039410 0.083388 -vn -2.120456 2.976227 2.303465 -v 0.025615 -0.038810 0.083388 -vn -1.712388 -2.976256 2.621076 -v 0.025843 -0.039410 0.083565 -vn -1.712387 2.976255 2.621076 -v 0.025843 -0.038810 0.083565 -vn 1.710953 -3.326379 -2.618823 -v 0.027620 -0.039410 0.080844 -vn 1.710953 3.326378 -2.618823 -v 0.027620 -0.040410 0.080844 -vn 1.200625 3.326397 -2.888611 -v 0.027376 -0.040410 0.080715 -vn 1.200625 -3.326396 -2.888611 -v 0.027376 -0.039410 0.080715 -vn 0.649378 3.326403 -3.060046 -v 0.027111 -0.040410 0.080633 -vn 0.649378 -3.326403 -3.060046 -v 0.027111 -0.039410 0.080633 -vn 0.076019 3.326394 -3.127267 -v 0.026836 -0.040410 0.080600 -vn 0.076019 -3.326394 -3.127267 -v 0.026836 -0.039410 0.080600 -vn -0.499879 3.326370 -3.087996 -v 0.026560 -0.040410 0.080619 -vn -0.499879 -3.326370 -3.087996 -v 0.026560 -0.039410 0.080619 -vn -1.058777 3.326411 -2.943562 -v 0.026292 -0.040410 0.080689 -vn -1.058777 -3.326410 -2.943562 -v 0.026292 -0.039410 0.080689 -vn -1.581653 3.326392 -2.698880 -v 0.026042 -0.040410 0.080806 -vn -1.581653 -3.326392 -2.698880 -v 0.026042 -0.039410 0.080806 -vn -2.050631 3.326384 -2.362309 -v 0.025817 -0.040410 0.080967 -vn -2.050631 -3.326384 -2.362308 -v 0.025817 -0.039410 0.080967 -vn -2.449790 3.326405 -1.945275 -v 0.025625 -0.040410 0.081167 -vn -2.449791 -3.326406 -1.945275 -v 0.025625 -0.039410 0.081167 -vn -2.765526 3.326380 -1.462006 -v 0.025474 -0.040410 0.081399 -vn -2.765526 -3.326380 -1.462006 -v 0.025474 -0.039410 0.081399 -vn -2.987076 3.326400 -0.928953 -v 0.025368 -0.040410 0.081655 -vn -2.987076 -3.326401 -0.928953 -v 0.025368 -0.039410 0.081655 -vn -3.106912 3.326383 -0.364263 -v 0.025310 -0.040410 0.081925 -vn -3.106912 -3.326383 -0.364263 -v 0.025310 -0.039410 0.081925 -vn -3.120941 3.326401 0.212832 -v 0.025303 -0.040410 0.082202 -vn -3.120942 -3.326401 0.212832 -v 0.025303 -0.039410 0.082202 -vn -3.028698 3.326380 0.782675 -v 0.025348 -0.040410 0.082475 -vn -3.028698 -3.326380 0.782675 -v 0.025348 -0.039410 0.082475 -vn -2.833307 3.326407 1.325872 -v 0.025441 -0.040410 0.082736 -vn -2.833308 -3.326407 1.325872 -v 0.025441 -0.039410 0.082736 -vn -2.541430 3.326387 1.823930 -v 0.025581 -0.040410 0.082975 -vn -2.541430 -3.326387 1.823930 -v 0.025581 -0.039410 0.082975 -vn -2.163039 3.326373 2.259836 -v 0.025763 -0.040410 0.083184 -vn -2.163039 -3.326373 2.259836 -v 0.025763 -0.039410 0.083184 -vn -1.710941 3.326427 2.618822 -v 0.025980 -0.040410 0.083356 -vn -1.710941 -3.326427 2.618822 -v 0.025980 -0.039410 0.083356 -vn -1.083064 -3.366021 2.927938 -v 0.027147 -0.041010 0.081162 -vn -1.083064 3.366021 2.927938 -v 0.027147 -0.038810 0.081162 -vn -0.404417 -3.365941 3.095542 -v 0.026930 -0.041010 0.081108 -vn -0.404417 3.365941 3.095541 -v 0.026930 -0.038810 0.081108 -vn 0.294506 -3.366018 3.107912 -v 0.026706 -0.041010 0.081104 -vn 0.294506 3.366019 3.107912 -v 0.026706 -0.038810 0.081104 -vn 0.978741 -3.365994 2.964446 -v 0.026486 -0.041010 0.081150 -vn 0.978741 3.365994 2.964446 -v 0.026486 -0.038810 0.081150 -vn 1.613845 -3.365983 2.672338 -v 0.026283 -0.041010 0.081244 -vn 1.613845 3.365983 2.672339 -v 0.026283 -0.038810 0.081244 -vn 2.168039 -3.366008 2.246213 -v 0.026106 -0.041010 0.081380 -vn 2.168038 3.366008 2.246212 -v 0.026106 -0.038810 0.081380 -vn 2.613512 -3.365971 1.707471 -v 0.025963 -0.041010 0.081553 -vn 2.613512 3.365971 1.707471 -v 0.025963 -0.038810 0.081553 -vn 2.927924 -3.366006 1.083108 -v 0.025862 -0.041010 0.081753 -vn 2.927924 3.366006 1.083108 -v 0.025862 -0.038810 0.081753 -vn 3.095534 -3.365988 0.404412 -v 0.025808 -0.041010 0.081970 -vn 3.095534 3.365988 0.404412 -v 0.025808 -0.038810 0.081970 -vn 3.107916 -3.365982 -0.294527 -v 0.025804 -0.041010 0.082194 -vn 3.107917 3.365982 -0.294527 -v 0.025804 -0.038810 0.082194 -vn 2.964455 -3.365999 -0.978714 -v 0.025850 -0.041010 0.082414 -vn 2.964455 3.365999 -0.978714 -v 0.025850 -0.038810 0.082414 -vn 2.672334 -3.366000 -1.613848 -v 0.025944 -0.041010 0.082617 -vn 2.672333 3.366000 -1.613848 -v 0.025944 -0.038810 0.082617 -vn 2.246208 -3.365994 -2.168047 -v 0.026080 -0.041010 0.082794 -vn 2.246208 3.365994 -2.168047 -v 0.026080 -0.038810 0.082794 -vn -0.768578 -2.976245 3.035060 -v 0.026370 -0.041010 0.083796 -vn -1.257641 -2.976253 2.867167 -v 0.026097 -0.041010 0.083703 -vn 1.257683 -2.976231 2.867145 -v 0.027503 -0.041010 0.083703 -vn 0.768583 -2.976240 3.035058 -v 0.027230 -0.041010 0.083796 -vn 0.258541 -2.976248 3.120170 -v 0.026945 -0.041010 0.083844 -vn -0.258543 -2.976247 3.120170 -v 0.026655 -0.041010 0.083844 -vn 2.753517 -2.976243 1.490115 -v 0.028339 -0.041010 0.082933 -vn 2.470700 -2.976249 1.923005 -v 0.028181 -0.041010 0.083175 -vn 2.120486 -2.976242 2.303441 -v 0.027985 -0.041010 0.083388 -vn 1.712448 -2.976261 2.621037 -v 0.027757 -0.041010 0.083565 -vn 3.130862 -2.976244 -0.000020 -v 0.028550 -0.041010 0.082100 -vn 3.088163 -2.976244 0.515310 -v 0.028526 -0.041010 0.082388 -vn 2.961228 -2.976247 1.016577 -v 0.028455 -0.041010 0.082668 -vn 2.120462 -2.976256 -2.303464 -v 0.027985 -0.041010 0.080812 -vn 2.470676 -2.976237 -1.923032 -v 0.028181 -0.041010 0.081025 -vn 2.753505 -2.976249 -1.490139 -v 0.028339 -0.041010 0.081267 -vn 2.961218 -2.976242 -1.016604 -v 0.028455 -0.041010 0.081532 -vn 3.088160 -2.976250 -0.515339 -v 0.028526 -0.041010 0.081812 -vn 2.753517 2.976243 1.490115 -v 0.028339 -0.038810 0.082933 -vn 2.961228 2.976247 1.016577 -v 0.028455 -0.038810 0.082668 -vn 1.257683 2.976231 2.867145 -v 0.027503 -0.038810 0.083703 -vn 1.712448 2.976261 2.621037 -v 0.027757 -0.038810 0.083565 -vn 2.120486 2.976242 2.303440 -v 0.027985 -0.038810 0.083388 -vn 2.470700 2.976249 1.923004 -v 0.028181 -0.038810 0.083175 -vn -0.768578 2.976245 3.035060 -v 0.026370 -0.038810 0.083796 -vn -0.258543 2.976247 3.120169 -v 0.026655 -0.038810 0.083844 -vn 0.258541 2.976248 3.120170 -v 0.026945 -0.038810 0.083844 -vn 0.768583 2.976240 3.035058 -v 0.027230 -0.038810 0.083796 -vn 2.470676 2.976237 -1.923032 -v 0.028181 -0.038810 0.081025 -vn 2.120462 2.976255 -2.303464 -v 0.027985 -0.038810 0.080812 -vn 3.088163 2.976243 0.515310 -v 0.028526 -0.038810 0.082388 -vn 3.130862 2.976244 -0.000020 -v 0.028550 -0.038810 0.082100 -vn 3.088159 2.976250 -0.515339 -v 0.028526 -0.038810 0.081812 -vn 2.961218 2.976242 -1.016604 -v 0.028455 -0.038810 0.081532 -vn 2.753505 2.976250 -1.490139 -v 0.028339 -0.038810 0.081267 -vn -1.257641 2.976252 2.867167 -v 0.026097 -0.038810 0.083703 -vn -1.257641 2.976252 2.867167 -v 0.026097 -0.040410 0.083703 -vn -0.768578 2.976245 3.035060 -v 0.026370 -0.040410 0.083796 -vn -0.258543 2.976247 3.120169 -v 0.026655 -0.040410 0.083844 -vn 0.258541 2.976248 3.120170 -v 0.026945 -0.040410 0.083844 -vn 0.768583 2.976240 3.035058 -v 0.027230 -0.040410 0.083796 -vn 1.257683 2.976231 2.867145 -v 0.027503 -0.040410 0.083703 -vn 1.712448 2.976261 2.621037 -v 0.027757 -0.040410 0.083565 -vn 2.120486 2.976242 2.303440 -v 0.027985 -0.040410 0.083388 -vn 2.470700 2.976249 1.923004 -v 0.028181 -0.040410 0.083175 -vn 2.753517 2.976243 1.490115 -v 0.028339 -0.040410 0.082933 -vn 2.961228 2.976247 1.016577 -v 0.028455 -0.040410 0.082668 -vn 3.088163 2.976244 0.515310 -v 0.028526 -0.040410 0.082388 -vn 3.130862 2.976244 -0.000020 -v 0.028550 -0.040410 0.082100 -vn 3.088159 2.976250 -0.515339 -v 0.028526 -0.040410 0.081812 -vn 2.961218 2.976242 -1.016604 -v 0.028455 -0.040410 0.081532 -vn 2.753505 2.976250 -1.490139 -v 0.028339 -0.040410 0.081267 -vn 2.470676 2.976237 -1.923032 -v 0.028181 -0.040410 0.081025 -vn 2.120462 2.976256 -2.303464 -v 0.027985 -0.040410 0.080812 -vn -1.257641 -2.976253 2.867167 -v 0.026097 -0.039410 0.083703 -vn -0.768578 -2.976245 3.035060 -v 0.026370 -0.039410 0.083796 -vn -0.258543 -2.976247 3.120170 -v 0.026655 -0.039410 0.083844 -vn 0.258541 -2.976248 3.120170 -v 0.026945 -0.039410 0.083844 -vn 0.768583 -2.976240 3.035058 -v 0.027230 -0.039410 0.083796 -vn 1.257683 -2.976231 2.867145 -v 0.027503 -0.039410 0.083703 -vn 1.712448 -2.976261 2.621037 -v 0.027757 -0.039410 0.083565 -vn 2.120486 -2.976242 2.303441 -v 0.027985 -0.039410 0.083388 -vn 2.470700 -2.976249 1.923005 -v 0.028181 -0.039410 0.083175 -vn 2.753517 -2.976243 1.490115 -v 0.028339 -0.039410 0.082933 -vn 2.961228 -2.976247 1.016577 -v 0.028455 -0.039410 0.082668 -vn 3.088163 -2.976244 0.515310 -v 0.028526 -0.039410 0.082388 -vn 3.130862 -2.976243 -0.000020 -v 0.028550 -0.039410 0.082100 -vn 3.088160 -2.976250 -0.515339 -v 0.028526 -0.039410 0.081812 -vn 2.961218 -2.976242 -1.016604 -v 0.028455 -0.039410 0.081532 -vn 2.753505 -2.976250 -1.490139 -v 0.028339 -0.039410 0.081267 -vn 2.470676 -2.976237 -1.923032 -v 0.028181 -0.039410 0.081025 -vn 2.120462 -2.976256 -2.303464 -v 0.027985 -0.039410 0.080812 -vn 3.028694 3.326394 -0.782682 -v 0.028252 -0.040410 0.081725 -vn 2.833313 3.326385 -1.325867 -v 0.028159 -0.040410 0.081464 -vn 2.541440 3.326401 -1.823912 -v 0.028019 -0.040410 0.081225 -vn 2.163013 3.326394 -2.259857 -v 0.027837 -0.040410 0.081016 -vn 0.499876 3.326423 3.087989 -v 0.027040 -0.040410 0.083581 -vn 1.058817 3.326384 2.943552 -v 0.027308 -0.040410 0.083511 -vn 1.581653 3.326392 2.698880 -v 0.027558 -0.040410 0.083394 -vn 2.050631 3.326384 2.362309 -v 0.027783 -0.040410 0.083233 -vn 2.449773 3.326385 1.945302 -v 0.027975 -0.040410 0.083033 -vn 2.765512 3.326407 1.462023 -v 0.028126 -0.040410 0.082801 -vn 2.987077 3.326388 0.928954 -v 0.028232 -0.040410 0.082545 -vn 3.106910 3.326397 0.364263 -v 0.028290 -0.040410 0.082275 -vn 3.120943 3.326390 -0.212836 -v 0.028297 -0.040410 0.081998 -vn -1.200591 3.326368 2.888630 -v 0.026224 -0.040410 0.083485 -vn -0.649381 3.326405 3.060045 -v 0.026489 -0.040410 0.083567 -vn -0.076061 3.326368 3.127270 -v 0.026764 -0.040410 0.083600 -vn 3.028694 -3.326393 -0.782681 -v 0.028252 -0.039410 0.081725 -vn 3.120943 -3.326390 -0.212836 -v 0.028297 -0.039410 0.081998 -vn 3.106910 -3.326396 0.364263 -v 0.028290 -0.039410 0.082275 -vn 2.987077 -3.326388 0.928954 -v 0.028232 -0.039410 0.082545 -vn 2.765512 -3.326407 1.462024 -v 0.028126 -0.039410 0.082801 -vn 2.449773 -3.326385 1.945302 -v 0.027975 -0.039410 0.083033 -vn 2.050631 -3.326384 2.362308 -v 0.027783 -0.039410 0.083233 -vn 1.581653 -3.326392 2.698880 -v 0.027558 -0.039410 0.083394 -vn 1.058817 -3.326384 2.943551 -v 0.027308 -0.039410 0.083511 -vn 0.499876 -3.326423 3.087989 -v 0.027040 -0.039410 0.083581 -vn 2.163013 -3.326394 -2.259857 -v 0.027837 -0.039410 0.081016 -vn 2.541440 -3.326401 -1.823912 -v 0.028019 -0.039410 0.081225 -vn 2.833313 -3.326385 -1.325867 -v 0.028159 -0.039410 0.081464 -vn -0.076061 -3.326368 3.127270 -v 0.026764 -0.039410 0.083600 -vn -0.649381 -3.326405 3.060045 -v 0.026489 -0.039410 0.083567 -vn -1.200591 -3.326368 2.888630 -v 0.026224 -0.039410 0.083485 -vn 1.707459 -3.365978 -2.613518 -v 0.019753 -0.041010 0.082937 -vn 1.707459 3.365977 -2.613518 -v 0.019753 -0.038810 0.082937 -vn 1.083113 -3.365989 -2.927926 -v 0.019953 -0.041010 0.083038 -vn 1.083113 3.365989 -2.927926 -v 0.019953 -0.038810 0.083038 -vn 0.404414 -3.366007 -3.095531 -v 0.020170 -0.041010 0.083092 -vn 0.404414 3.366007 -3.095531 -v 0.020170 -0.038810 0.083092 -vn -0.294558 -3.365985 -3.107913 -v 0.020394 -0.041010 0.083096 -vn -0.294558 3.365985 -3.107913 -v 0.020394 -0.038810 0.083096 -vn -0.978741 -3.365994 -2.964446 -v 0.020614 -0.041010 0.083050 -vn -0.978741 3.365995 -2.964446 -v 0.020614 -0.038810 0.083050 -vn -1.613851 -3.365988 -2.672333 -v 0.020817 -0.041010 0.082956 -vn -1.613851 3.365988 -2.672334 -v 0.020817 -0.038810 0.082956 -vn -2.168017 -3.365976 -2.246241 -v 0.020994 -0.041010 0.082820 -vn -2.168017 3.365976 -2.246241 -v 0.020994 -0.038810 0.082820 -vn -2.613495 -3.366014 -1.707484 -v 0.021137 -0.041010 0.082647 -vn -2.613495 3.366014 -1.707483 -v 0.021137 -0.038810 0.082647 -vn -2.927932 -3.365983 -1.083099 -v 0.021238 -0.041010 0.082447 -vn -2.927932 3.365983 -1.083099 -v 0.021238 -0.038810 0.082447 -vn -3.095531 -3.365997 -0.404424 -v 0.021292 -0.041010 0.082230 -vn -3.095532 3.365997 -0.404424 -v 0.021292 -0.038810 0.082230 -vn -3.107914 -3.365989 0.294540 -v 0.021296 -0.041010 0.082006 -vn -3.107914 3.365990 0.294540 -v 0.021296 -0.038810 0.082006 -vn -2.964448 -3.365997 0.978735 -v 0.021250 -0.041010 0.081786 -vn -2.964447 3.365997 0.978735 -v 0.021250 -0.038810 0.081786 -vn -2.672329 -3.365993 1.613857 -v 0.021156 -0.041010 0.081583 -vn -2.672329 3.365993 1.613857 -v 0.021156 -0.038810 0.081583 -vn -2.246233 -3.365974 2.168027 -v 0.021020 -0.041010 0.081406 -vn -2.246233 3.365974 2.168027 -v 0.021020 -0.038810 0.081406 -vn -1.707490 -3.366003 2.613493 -v 0.020847 -0.041010 0.081263 -vn -1.707490 3.366003 2.613493 -v 0.020847 -0.038810 0.081263 -vn 1.712408 2.976239 -2.621060 -v 0.021257 -0.040410 0.080635 -vn 1.712408 -2.976239 -2.621060 -v 0.021257 -0.041010 0.080635 -vn 1.257644 -2.976255 -2.867165 -v 0.021003 -0.041010 0.080497 -vn 1.257645 2.976254 -2.867165 -v 0.021003 -0.040410 0.080497 -vn 0.768581 -2.976243 -3.035059 -v 0.020730 -0.041010 0.080404 -vn 0.768581 2.976243 -3.035059 -v 0.020730 -0.040410 0.080404 -vn 0.258502 -2.976221 -3.120170 -v 0.020445 -0.041010 0.080356 -vn 0.258502 2.976221 -3.120169 -v 0.020445 -0.040410 0.080356 -vn -0.258583 -2.976273 -3.120169 -v 0.020155 -0.041010 0.080356 -vn -0.258583 2.976273 -3.120170 -v 0.020155 -0.040410 0.080356 -vn -0.768581 -2.976243 -3.035059 -v 0.019870 -0.041010 0.080404 -vn -0.768581 2.976243 -3.035059 -v 0.019870 -0.040410 0.080404 -vn -1.257649 -2.976252 -2.867163 -v 0.019597 -0.041010 0.080497 -vn -1.257649 2.976251 -2.867163 -v 0.019597 -0.040410 0.080497 -vn -1.712417 -2.976238 -2.621054 -v 0.019343 -0.041010 0.080635 -vn -1.712417 2.976238 -2.621054 -v 0.019343 -0.040410 0.080635 -vn -2.120491 -2.976237 -2.303435 -v 0.019115 -0.041010 0.080812 -vn -2.120491 2.976237 -2.303435 -v 0.019115 -0.040410 0.080812 -vn -2.470705 -2.976254 -1.922999 -v 0.018919 -0.041010 0.081025 -vn -2.470705 2.976254 -1.922999 -v 0.018919 -0.040410 0.081025 -vn -2.753520 -2.976239 -1.490109 -v 0.018761 -0.041010 0.081267 -vn -2.753520 2.976239 -1.490109 -v 0.018761 -0.040410 0.081267 -vn -2.961231 -2.976252 -1.016571 -v 0.018645 -0.041010 0.081532 -vn -2.961231 2.976252 -1.016571 -v 0.018645 -0.040410 0.081532 -vn -3.088163 -2.976243 -0.515310 -v 0.018574 -0.041010 0.081812 -vn -3.088163 2.976243 -0.515310 -v 0.018574 -0.040410 0.081812 -vn -3.130862 -2.976243 0.000020 -v 0.018550 -0.041010 0.082100 -vn -3.130862 2.976244 0.000020 -v 0.018550 -0.040410 0.082100 -vn -3.088162 -2.976256 0.515330 -v 0.018574 -0.041010 0.082388 -vn -3.088162 2.976256 0.515330 -v 0.018574 -0.040410 0.082388 -vn -2.961221 -2.976236 1.016594 -v 0.018645 -0.041010 0.082668 -vn -2.961221 2.976235 1.016594 -v 0.018645 -0.040410 0.082668 -vn -2.753505 -2.976250 1.490139 -v 0.018761 -0.041010 0.082933 -vn -2.753505 2.976250 1.490139 -v 0.018761 -0.040410 0.082933 -vn -2.470690 -2.976250 1.923017 -v 0.018919 -0.041010 0.083175 -vn -2.470690 2.976250 1.923017 -v 0.018919 -0.040410 0.083175 -vn -2.120451 -2.976223 2.303469 -v 0.019115 -0.041010 0.083388 -vn -2.120451 2.976223 2.303469 -v 0.019115 -0.040410 0.083388 -vn -1.712383 -2.976259 2.621079 -v 0.019343 -0.041010 0.083565 -vn -1.712383 2.976259 2.621079 -v 0.019343 -0.040410 0.083565 -vn 1.712408 2.976239 -2.621060 -v 0.021257 -0.038810 0.080635 -vn 1.712408 -2.976239 -2.621060 -v 0.021257 -0.039410 0.080635 -vn 1.257644 -2.976255 -2.867165 -v 0.021003 -0.039410 0.080497 -vn 1.257645 2.976254 -2.867165 -v 0.021003 -0.038810 0.080497 -vn 0.768581 -2.976243 -3.035059 -v 0.020730 -0.039410 0.080404 -vn 0.768581 2.976243 -3.035059 -v 0.020730 -0.038810 0.080404 -vn 0.258502 -2.976221 -3.120170 -v 0.020445 -0.039410 0.080356 -vn 0.258502 2.976221 -3.120169 -v 0.020445 -0.038810 0.080356 -vn -0.258583 -2.976273 -3.120169 -v 0.020155 -0.039410 0.080356 -vn -0.258583 2.976273 -3.120170 -v 0.020155 -0.038810 0.080356 -vn -0.768581 -2.976243 -3.035059 -v 0.019870 -0.039410 0.080404 -vn -0.768581 2.976243 -3.035059 -v 0.019870 -0.038810 0.080404 -vn -1.257649 -2.976251 -2.867163 -v 0.019597 -0.039410 0.080497 -vn -1.257649 2.976252 -2.867163 -v 0.019597 -0.038810 0.080497 -vn -1.712417 -2.976238 -2.621054 -v 0.019343 -0.039410 0.080635 -vn -1.712417 2.976238 -2.621054 -v 0.019343 -0.038810 0.080635 -vn -2.120491 -2.976237 -2.303435 -v 0.019115 -0.039410 0.080812 -vn -2.120491 2.976237 -2.303435 -v 0.019115 -0.038810 0.080812 -vn -2.470705 -2.976254 -1.922999 -v 0.018919 -0.039410 0.081025 -vn -2.470705 2.976254 -1.922999 -v 0.018919 -0.038810 0.081025 -vn -2.753520 -2.976239 -1.490109 -v 0.018761 -0.039410 0.081267 -vn -2.753520 2.976239 -1.490109 -v 0.018761 -0.038810 0.081267 -vn -2.961231 -2.976252 -1.016571 -v 0.018645 -0.039410 0.081532 -vn -2.961231 2.976252 -1.016571 -v 0.018645 -0.038810 0.081532 -vn -3.088163 -2.976243 -0.515310 -v 0.018574 -0.039410 0.081812 -vn -3.088163 2.976243 -0.515310 -v 0.018574 -0.038810 0.081812 -vn -3.130862 -2.976244 0.000020 -v 0.018550 -0.039410 0.082100 -vn -3.130862 2.976243 0.000020 -v 0.018550 -0.038810 0.082100 -vn -3.088162 -2.976257 0.515330 -v 0.018574 -0.039410 0.082388 -vn -3.088162 2.976256 0.515330 -v 0.018574 -0.038810 0.082388 -vn -2.961221 -2.976235 1.016594 -v 0.018645 -0.039410 0.082668 -vn -2.961221 2.976236 1.016594 -v 0.018645 -0.038810 0.082668 -vn -2.753505 -2.976250 1.490139 -v 0.018761 -0.039410 0.082933 -vn -2.753505 2.976250 1.490139 -v 0.018761 -0.038810 0.082933 -vn -2.470690 -2.976250 1.923017 -v 0.018919 -0.039410 0.083175 -vn -2.470690 2.976250 1.923017 -v 0.018919 -0.038810 0.083175 -vn -2.120451 -2.976222 2.303469 -v 0.019115 -0.039410 0.083388 -vn -2.120451 2.976223 2.303469 -v 0.019115 -0.038810 0.083388 -vn -1.712383 -2.976260 2.621079 -v 0.019343 -0.039410 0.083565 -vn -1.712383 2.976259 2.621079 -v 0.019343 -0.038810 0.083565 -vn 1.710948 -3.326382 -2.618825 -v 0.021120 -0.039410 0.080844 -vn 1.710948 3.326382 -2.618825 -v 0.021120 -0.040410 0.080844 -vn 1.200621 3.326394 -2.888614 -v 0.020876 -0.040410 0.080715 -vn 1.200621 -3.326394 -2.888614 -v 0.020876 -0.039410 0.080715 -vn 0.649379 3.326402 -3.060045 -v 0.020611 -0.040410 0.080633 -vn 0.649379 -3.326402 -3.060045 -v 0.020611 -0.039410 0.080633 -vn 0.076020 3.326395 -3.127267 -v 0.020336 -0.040410 0.080600 -vn 0.076020 -3.326396 -3.127267 -v 0.020336 -0.039410 0.080600 -vn -0.499879 3.326370 -3.087996 -v 0.020060 -0.040410 0.080619 -vn -0.499879 -3.326370 -3.087996 -v 0.020060 -0.039410 0.080619 -vn -1.058777 3.326410 -2.943562 -v 0.019792 -0.040410 0.080689 -vn -1.058777 -3.326410 -2.943562 -v 0.019792 -0.039410 0.080689 -vn -1.581653 3.326392 -2.698880 -v 0.019542 -0.040410 0.080806 -vn -1.581653 -3.326392 -2.698880 -v 0.019542 -0.039410 0.080806 -vn -2.050631 3.326384 -2.362309 -v 0.019317 -0.040410 0.080967 -vn -2.050631 -3.326384 -2.362308 -v 0.019317 -0.039410 0.080967 -vn -2.449786 3.326400 -1.945282 -v 0.019125 -0.040410 0.081167 -vn -2.449785 -3.326400 -1.945282 -v 0.019125 -0.039410 0.081167 -vn -2.765524 3.326392 -1.462004 -v 0.018974 -0.040410 0.081399 -vn -2.765525 -3.326392 -1.462004 -v 0.018974 -0.039410 0.081399 -vn -2.987077 3.326388 -0.928954 -v 0.018868 -0.040410 0.081655 -vn -2.987077 -3.326388 -0.928954 -v 0.018868 -0.039410 0.081655 -vn -3.106910 3.326397 -0.364263 -v 0.018810 -0.040410 0.081925 -vn -3.106910 -3.326396 -0.364263 -v 0.018810 -0.039410 0.081925 -vn -3.120943 3.326387 0.212832 -v 0.018803 -0.040410 0.082202 -vn -3.120944 -3.326388 0.212832 -v 0.018803 -0.039410 0.082202 -vn -3.028697 3.326393 0.782674 -v 0.018848 -0.040410 0.082475 -vn -3.028697 -3.326393 0.782674 -v 0.018848 -0.039410 0.082475 -vn -2.833309 3.326395 1.325874 -v 0.018941 -0.040410 0.082736 -vn -2.833309 -3.326395 1.325874 -v 0.018941 -0.039410 0.082736 -vn -2.541434 3.326393 1.823922 -v 0.019081 -0.040410 0.082975 -vn -2.541434 -3.326393 1.823922 -v 0.019081 -0.039410 0.082975 -vn -2.163039 3.326373 2.259836 -v 0.019263 -0.040410 0.083184 -vn -2.163039 -3.326373 2.259836 -v 0.019263 -0.039410 0.083184 -vn -1.710941 3.326427 2.618822 -v 0.019480 -0.040410 0.083356 -vn -1.710941 -3.326427 2.618822 -v 0.019480 -0.039410 0.083356 -vn -1.083064 -3.366021 2.927938 -v 0.020647 -0.041010 0.081162 -vn -1.083064 3.366021 2.927938 -v 0.020647 -0.038810 0.081162 -vn -0.404417 -3.365941 3.095542 -v 0.020430 -0.041010 0.081108 -vn -0.404417 3.365941 3.095541 -v 0.020430 -0.038810 0.081108 -vn 0.294506 -3.366018 3.107912 -v 0.020206 -0.041010 0.081104 -vn 0.294506 3.366018 3.107912 -v 0.020206 -0.038810 0.081104 -vn 0.978741 -3.365994 2.964446 -v 0.019986 -0.041010 0.081150 -vn 0.978741 3.365994 2.964446 -v 0.019986 -0.038810 0.081150 -vn 1.613851 -3.365988 2.672333 -v 0.019783 -0.041010 0.081244 -vn 1.613851 3.365988 2.672334 -v 0.019783 -0.038810 0.081244 -vn 2.168038 -3.365997 2.246215 -v 0.019606 -0.041010 0.081380 -vn 2.168039 3.365997 2.246216 -v 0.019606 -0.038810 0.081380 -vn 2.613506 -3.365978 1.707479 -v 0.019463 -0.041010 0.081553 -vn 2.613505 3.365977 1.707479 -v 0.019463 -0.038810 0.081553 -vn 2.927924 -3.366006 1.083108 -v 0.019362 -0.041010 0.081753 -vn 2.927924 3.366006 1.083108 -v 0.019362 -0.038810 0.081753 -vn 3.095534 -3.365988 0.404412 -v 0.019308 -0.041010 0.081970 -vn 3.095534 3.365988 0.404412 -v 0.019308 -0.038810 0.081970 -vn 3.107913 -3.365990 -0.294539 -v 0.019304 -0.041010 0.082194 -vn 3.107914 3.365990 -0.294539 -v 0.019304 -0.038810 0.082194 -vn 2.964458 -3.365983 -0.978715 -v 0.019350 -0.041010 0.082414 -vn 2.964457 3.365983 -0.978715 -v 0.019350 -0.038810 0.082414 -vn 2.672338 -3.366007 -1.613837 -v 0.019444 -0.041010 0.082617 -vn 2.672338 3.366007 -1.613837 -v 0.019444 -0.038810 0.082617 -vn 2.246202 -3.365999 -2.168052 -v 0.019580 -0.041010 0.082794 -vn 2.246201 3.365999 -2.168052 -v 0.019580 -0.038810 0.082794 -vn 1.257680 -2.976229 2.867146 -v 0.021003 -0.041010 0.083703 -vn 0.768581 -2.976243 3.035059 -v 0.020730 -0.041010 0.083796 -vn 0.258543 -2.976246 3.120169 -v 0.020445 -0.041010 0.083844 -vn 2.470705 -2.976254 1.922999 -v 0.021681 -0.041010 0.083175 -vn 2.120491 -2.976237 2.303435 -v 0.021485 -0.041010 0.083388 -vn 1.712448 -2.976261 2.621037 -v 0.021257 -0.041010 0.083565 -vn 3.130862 -2.976244 -0.000020 -v 0.022050 -0.041010 0.082100 -vn 3.088166 -2.976250 0.515300 -v 0.022026 -0.041010 0.082388 -vn 2.961227 -2.976235 1.016576 -v 0.021955 -0.041010 0.082668 -vn 2.753513 -2.976249 1.490124 -v 0.021839 -0.041010 0.082933 -vn -0.258543 -2.976247 3.120170 -v 0.020155 -0.041010 0.083844 -vn -0.768581 -2.976243 3.035059 -v 0.019870 -0.041010 0.083796 -vn -1.257644 -2.976255 2.867165 -v 0.019597 -0.041010 0.083703 -vn 2.120457 -2.976260 -2.303470 -v 0.021485 -0.041010 0.080812 -vn 2.470671 -2.976233 -1.923037 -v 0.021681 -0.041010 0.081025 -vn 2.753505 -2.976250 -1.490139 -v 0.021839 -0.041010 0.081267 -vn 2.961221 -2.976236 -1.016594 -v 0.021955 -0.041010 0.081532 -vn 3.088162 -2.976256 -0.515330 -v 0.022026 -0.041010 0.081812 -vn 1.257680 2.976229 2.867146 -v 0.021003 -0.038810 0.083703 -vn 1.712448 2.976261 2.621037 -v 0.021257 -0.038810 0.083565 -vn -0.768581 2.976243 3.035059 -v 0.019870 -0.038810 0.083796 -vn -0.258543 2.976247 3.120169 -v 0.020155 -0.038810 0.083844 -vn 0.258543 2.976247 3.120170 -v 0.020445 -0.038810 0.083844 -vn 0.768581 2.976243 3.035059 -v 0.020730 -0.038810 0.083796 -vn -1.257645 2.976254 2.867165 -v 0.019597 -0.038810 0.083703 -vn 2.470671 2.976233 -1.923037 -v 0.021681 -0.038810 0.081025 -vn 2.120457 2.976260 -2.303470 -v 0.021485 -0.038810 0.080812 -vn 3.130862 2.976244 -0.000020 -v 0.022050 -0.038810 0.082100 -vn 3.088162 2.976256 -0.515330 -v 0.022026 -0.038810 0.081812 -vn 2.961221 2.976235 -1.016594 -v 0.021955 -0.038810 0.081532 -vn 2.753505 2.976250 -1.490139 -v 0.021839 -0.038810 0.081267 -vn 2.120491 2.976237 2.303435 -v 0.021485 -0.038810 0.083388 -vn 2.470705 2.976254 1.922999 -v 0.021681 -0.038810 0.083175 -vn 2.753513 2.976250 1.490124 -v 0.021839 -0.038810 0.082933 -vn 2.961227 2.976235 1.016576 -v 0.021955 -0.038810 0.082668 -vn 3.088166 2.976250 0.515300 -v 0.022026 -0.038810 0.082388 -vn -1.257645 2.976254 2.867165 -v 0.019597 -0.040410 0.083703 -vn -0.768581 2.976243 3.035059 -v 0.019870 -0.040410 0.083796 -vn -0.258543 2.976247 3.120169 -v 0.020155 -0.040410 0.083844 -vn 0.258543 2.976247 3.120170 -v 0.020445 -0.040410 0.083844 -vn 0.768581 2.976243 3.035059 -v 0.020730 -0.040410 0.083796 -vn 1.257680 2.976229 2.867146 -v 0.021003 -0.040410 0.083703 -vn 1.712448 2.976261 2.621037 -v 0.021257 -0.040410 0.083565 -vn 2.120491 2.976237 2.303435 -v 0.021485 -0.040410 0.083388 -vn 2.470705 2.976254 1.922999 -v 0.021681 -0.040410 0.083175 -vn 2.753513 2.976249 1.490124 -v 0.021839 -0.040410 0.082933 -vn 2.961227 2.976235 1.016576 -v 0.021955 -0.040410 0.082668 -vn 3.088166 2.976250 0.515300 -v 0.022026 -0.040410 0.082388 -vn 3.130862 2.976243 -0.000020 -v 0.022050 -0.040410 0.082100 -vn 3.088162 2.976256 -0.515330 -v 0.022026 -0.040410 0.081812 -vn 2.961221 2.976235 -1.016594 -v 0.021955 -0.040410 0.081532 -vn 2.753505 2.976250 -1.490139 -v 0.021839 -0.040410 0.081267 -vn 2.470671 2.976232 -1.923037 -v 0.021681 -0.040410 0.081025 -vn 2.120457 2.976260 -2.303470 -v 0.021485 -0.040410 0.080812 -vn -1.257644 -2.976254 2.867165 -v 0.019597 -0.039410 0.083703 -vn -0.768581 -2.976243 3.035059 -v 0.019870 -0.039410 0.083796 -vn -0.258543 -2.976247 3.120170 -v 0.020155 -0.039410 0.083844 -vn 0.258543 -2.976247 3.120169 -v 0.020445 -0.039410 0.083844 -vn 0.768581 -2.976243 3.035059 -v 0.020730 -0.039410 0.083796 -vn 1.257680 -2.976229 2.867146 -v 0.021003 -0.039410 0.083703 -vn 1.712448 -2.976261 2.621037 -v 0.021257 -0.039410 0.083565 -vn 2.120491 -2.976237 2.303435 -v 0.021485 -0.039410 0.083388 -vn 2.470705 -2.976254 1.922999 -v 0.021681 -0.039410 0.083175 -vn 2.753513 -2.976249 1.490124 -v 0.021839 -0.039410 0.082933 -vn 2.961227 -2.976235 1.016576 -v 0.021955 -0.039410 0.082668 -vn 3.088166 -2.976250 0.515300 -v 0.022026 -0.039410 0.082388 -vn 3.130862 -2.976243 -0.000020 -v 0.022050 -0.039410 0.082100 -vn 3.088162 -2.976256 -0.515330 -v 0.022026 -0.039410 0.081812 -vn 2.961221 -2.976235 -1.016594 -v 0.021955 -0.039410 0.081532 -vn 2.753505 -2.976250 -1.490139 -v 0.021839 -0.039410 0.081267 -vn 2.470671 -2.976232 -1.923037 -v 0.021681 -0.039410 0.081025 -vn 2.120457 -2.976260 -2.303470 -v 0.021485 -0.039410 0.080812 -vn 3.028692 3.326407 -0.782681 -v 0.021752 -0.040410 0.081725 -vn 2.833314 3.326372 -1.325869 -v 0.021659 -0.040410 0.081464 -vn 2.541445 3.326407 -1.823904 -v 0.021519 -0.040410 0.081225 -vn 2.163013 3.326394 -2.259857 -v 0.021337 -0.040410 0.081016 -vn -1.200588 3.326370 2.888631 -v 0.019724 -0.040410 0.083485 -vn -0.649379 3.326402 3.060045 -v 0.019989 -0.040410 0.083567 -vn -0.076062 3.326369 3.127270 -v 0.020264 -0.040410 0.083600 -vn 0.499876 3.326423 3.087989 -v 0.020540 -0.040410 0.083581 -vn 1.058817 3.326384 2.943552 -v 0.020808 -0.040410 0.083511 -vn 1.581653 3.326392 2.698880 -v 0.021058 -0.040410 0.083394 -vn 2.050631 3.326384 2.362309 -v 0.021283 -0.040410 0.083233 -vn 2.449773 3.326385 1.945302 -v 0.021475 -0.040410 0.083033 -vn 2.765512 3.326407 1.462023 -v 0.021626 -0.040410 0.082801 -vn 2.987077 3.326388 0.928954 -v 0.021732 -0.040410 0.082545 -vn 3.106910 3.326397 0.364263 -v 0.021790 -0.040410 0.082275 -vn 3.120944 3.326383 -0.212826 -v 0.021797 -0.040410 0.081998 -vn 0.499876 -3.326423 3.087989 -v 0.020540 -0.039410 0.083581 -vn -0.076062 -3.326368 3.127270 -v 0.020264 -0.039410 0.083600 -vn -0.649379 -3.326402 3.060045 -v 0.019989 -0.039410 0.083567 -vn -1.200588 -3.326370 2.888631 -v 0.019724 -0.039410 0.083485 -vn 3.028693 -3.326406 -0.782681 -v 0.021752 -0.039410 0.081725 -vn 3.120944 -3.326383 -0.212826 -v 0.021797 -0.039410 0.081998 -vn 3.106910 -3.326396 0.364263 -v 0.021790 -0.039410 0.082275 -vn 2.987077 -3.326388 0.928954 -v 0.021732 -0.039410 0.082545 -vn 2.765512 -3.326407 1.462024 -v 0.021626 -0.039410 0.082801 -vn 2.449773 -3.326385 1.945302 -v 0.021475 -0.039410 0.083033 -vn 2.050631 -3.326384 2.362308 -v 0.021283 -0.039410 0.083233 -vn 1.581653 -3.326392 2.698880 -v 0.021058 -0.039410 0.083394 -vn 1.058817 -3.326384 2.943551 -v 0.020808 -0.039410 0.083511 -vn 2.163013 -3.326394 -2.259857 -v 0.021337 -0.039410 0.081016 -vn 2.541445 -3.326407 -1.823904 -v 0.021519 -0.039410 0.081225 -vn 2.833314 -3.326372 -1.325869 -v 0.021659 -0.039410 0.081464 -vn 1.707491 -3.366012 -2.613490 -v 0.018634 -0.042610 0.092387 -vn 1.707491 3.366012 -2.613489 -v 0.018634 -0.040410 0.092387 -vn 1.083107 -3.365985 -2.927928 -v 0.018834 -0.042610 0.092488 -vn 1.083108 3.365984 -2.927929 -v 0.018834 -0.040410 0.092488 -vn 0.404414 -3.366007 -3.095531 -v 0.019052 -0.042610 0.092542 -vn 0.404414 3.366007 -3.095531 -v 0.019052 -0.040410 0.092542 -vn -0.294558 -3.365985 -3.107913 -v 0.019276 -0.042610 0.092546 -vn -0.294558 3.365985 -3.107913 -v 0.019276 -0.040410 0.092546 -vn -0.978741 -3.365994 -2.964446 -v 0.019495 -0.042610 0.092500 -vn -0.978741 3.365994 -2.964446 -v 0.019495 -0.040410 0.092500 -vn -1.613851 -3.365988 -2.672333 -v 0.019698 -0.042610 0.092406 -vn -1.613851 3.365988 -2.672334 -v 0.019698 -0.040410 0.092406 -vn -2.168038 -3.365997 -2.246215 -v 0.019876 -0.042610 0.092270 -vn -2.168039 3.365997 -2.246216 -v 0.019876 -0.040410 0.092270 -vn -2.613506 -3.365977 -1.707479 -v 0.020018 -0.042610 0.092097 -vn -2.613505 3.365977 -1.707479 -v 0.020018 -0.040410 0.092097 -vn -2.927924 -3.366006 -1.083108 -v 0.020119 -0.042610 0.091897 -vn -2.927924 3.366006 -1.083108 -v 0.020119 -0.040410 0.091897 -vn -3.095534 -3.365988 -0.404412 -v 0.020173 -0.042610 0.091680 -vn -3.095534 3.365988 -0.404412 -v 0.020173 -0.040410 0.091680 -vn -3.107913 -3.365991 0.294539 -v 0.020177 -0.042610 0.091456 -vn -3.107914 3.365990 0.294539 -v 0.020177 -0.040410 0.091456 -vn -2.964458 -3.365983 0.978715 -v 0.020131 -0.042610 0.091236 -vn -2.964457 3.365983 0.978715 -v 0.020131 -0.040410 0.091236 -vn -2.672338 -3.366007 1.613837 -v 0.020037 -0.042610 0.091033 -vn -2.672338 3.366008 1.613837 -v 0.020037 -0.040410 0.091033 -vn -2.246202 -3.365999 2.168052 -v 0.019901 -0.042610 0.090856 -vn -2.246201 3.365999 2.168052 -v 0.019901 -0.040410 0.090856 -vn -1.707459 -3.365978 2.613518 -v 0.019728 -0.042610 0.090713 -vn -1.707459 3.365977 2.613518 -v 0.019728 -0.040410 0.090713 -vn 1.712383 2.976260 -2.621079 -v 0.020138 -0.042010 0.090085 -vn 1.712383 -2.976259 -2.621079 -v 0.020138 -0.042610 0.090085 -vn 1.257645 -2.976255 -2.867166 -v 0.019884 -0.042610 0.089947 -vn 1.257645 2.976254 -2.867165 -v 0.019884 -0.042010 0.089947 -vn 0.768581 -2.976243 -3.035058 -v 0.019611 -0.042610 0.089854 -vn 0.768581 2.976243 -3.035059 -v 0.019611 -0.042010 0.089854 -vn 0.258543 -2.976247 -3.120170 -v 0.019326 -0.042610 0.089806 -vn 0.258543 2.976247 -3.120170 -v 0.019326 -0.042010 0.089806 -vn -0.258543 -2.976246 -3.120170 -v 0.019037 -0.042610 0.089806 -vn -0.258543 2.976247 -3.120170 -v 0.019037 -0.042010 0.089806 -vn -0.768581 -2.976243 -3.035059 -v 0.018752 -0.042610 0.089854 -vn -0.768581 2.976243 -3.035058 -v 0.018752 -0.042010 0.089854 -vn -1.257680 -2.976229 -2.867146 -v 0.018478 -0.042610 0.089947 -vn -1.257680 2.976228 -2.867146 -v 0.018478 -0.042010 0.089947 -vn -1.712448 -2.976261 -2.621037 -v 0.018224 -0.042610 0.090085 -vn -1.712448 2.976261 -2.621037 -v 0.018224 -0.042010 0.090085 -vn -2.120491 -2.976237 -2.303435 -v 0.017996 -0.042610 0.090262 -vn -2.120491 2.976237 -2.303435 -v 0.017996 -0.042010 0.090262 -vn -2.470705 -2.976254 -1.922999 -v 0.017800 -0.042610 0.090475 -vn -2.470705 2.976254 -1.922999 -v 0.017800 -0.042010 0.090475 -vn -2.753513 -2.976249 -1.490124 -v 0.017642 -0.042610 0.090717 -vn -2.753513 2.976249 -1.490124 -v 0.017642 -0.042010 0.090717 -vn -2.961227 -2.976235 -1.016576 -v 0.017526 -0.042610 0.090982 -vn -2.961227 2.976235 -1.016576 -v 0.017526 -0.042010 0.090982 -vn -3.088166 -2.976250 -0.515300 -v 0.017455 -0.042610 0.091262 -vn -3.088166 2.976250 -0.515300 -v 0.017455 -0.042010 0.091262 -vn -3.130863 -2.976250 0.000010 -v 0.017431 -0.042610 0.091550 -vn -3.130863 2.976250 0.000010 -v 0.017431 -0.042010 0.091550 -vn -3.088161 -2.976244 0.515329 -v 0.017455 -0.042610 0.091838 -vn -3.088160 2.976244 0.515329 -v 0.017455 -0.042010 0.091838 -vn -2.961218 -2.976242 1.016604 -v 0.017526 -0.042610 0.092118 -vn -2.961218 2.976242 1.016604 -v 0.017526 -0.042010 0.092118 -vn -2.753505 -2.976250 1.490139 -v 0.017642 -0.042610 0.092383 -vn -2.753505 2.976250 1.490139 -v 0.017642 -0.042010 0.092383 -vn -2.470672 -2.976233 1.923037 -v 0.017800 -0.042610 0.092625 -vn -2.470671 2.976232 1.923037 -v 0.017800 -0.042010 0.092625 -vn -2.120457 -2.976260 2.303470 -v 0.017996 -0.042610 0.092838 -vn -2.120457 2.976260 2.303470 -v 0.017996 -0.042010 0.092838 -vn -1.712412 -2.976243 2.621058 -v 0.018224 -0.042610 0.093015 -vn -1.712412 2.976243 2.621058 -v 0.018224 -0.042010 0.093015 -vn 1.712383 2.976259 -2.621079 -v 0.020138 -0.040410 0.090085 -vn 1.712382 -2.976260 -2.621080 -v 0.020138 -0.041010 0.090085 -vn 1.257644 -2.976254 -2.867165 -v 0.019884 -0.041010 0.089947 -vn 1.257645 2.976254 -2.867165 -v 0.019884 -0.040410 0.089947 -vn 0.768581 -2.976243 -3.035059 -v 0.019611 -0.041010 0.089854 -vn 0.768581 2.976243 -3.035059 -v 0.019611 -0.040410 0.089854 -vn 0.258543 -2.976247 -3.120170 -v 0.019326 -0.041010 0.089806 -vn 0.258543 2.976247 -3.120169 -v 0.019326 -0.040410 0.089806 -vn -0.258543 -2.976247 -3.120169 -v 0.019037 -0.041010 0.089806 -vn -0.258543 2.976247 -3.120170 -v 0.019037 -0.040410 0.089806 -vn -0.768581 -2.976243 -3.035059 -v 0.018752 -0.041010 0.089854 -vn -0.768581 2.976243 -3.035059 -v 0.018752 -0.040410 0.089854 -vn -1.257680 -2.976228 -2.867146 -v 0.018478 -0.041010 0.089947 -vn -1.257680 2.976229 -2.867146 -v 0.018478 -0.040410 0.089947 -vn -1.712448 -2.976261 -2.621037 -v 0.018224 -0.041010 0.090085 -vn -1.712448 2.976261 -2.621037 -v 0.018224 -0.040410 0.090085 -vn -2.120491 -2.976238 -2.303435 -v 0.017996 -0.041010 0.090262 -vn -2.120491 2.976237 -2.303435 -v 0.017996 -0.040410 0.090262 -vn -2.470705 -2.976254 -1.922999 -v 0.017800 -0.041010 0.090475 -vn -2.470705 2.976254 -1.922999 -v 0.017800 -0.040410 0.090475 -vn -2.753513 -2.976249 -1.490124 -v 0.017642 -0.041010 0.090717 -vn -2.753513 2.976250 -1.490124 -v 0.017642 -0.040410 0.090717 -vn -2.961227 -2.976235 -1.016576 -v 0.017526 -0.041010 0.090982 -vn -2.961227 2.976235 -1.016576 -v 0.017526 -0.040410 0.090982 -vn -3.088166 -2.976250 -0.515300 -v 0.017455 -0.041010 0.091262 -vn -3.088166 2.976250 -0.515300 -v 0.017455 -0.040410 0.091262 -vn -3.130863 -2.976250 0.000010 -v 0.017431 -0.041010 0.091550 -vn -3.130863 2.976250 0.000010 -v 0.017431 -0.040410 0.091550 -vn -3.088160 -2.976243 0.515329 -v 0.017455 -0.041010 0.091838 -vn -3.088160 2.976244 0.515329 -v 0.017455 -0.040410 0.091838 -vn -2.961218 -2.976242 1.016604 -v 0.017526 -0.041010 0.092118 -vn -2.961218 2.976242 1.016604 -v 0.017526 -0.040410 0.092118 -vn -2.753505 -2.976250 1.490139 -v 0.017642 -0.041010 0.092383 -vn -2.753505 2.976250 1.490139 -v 0.017642 -0.040410 0.092383 -vn -2.470671 -2.976233 1.923037 -v 0.017800 -0.041010 0.092625 -vn -2.470671 2.976233 1.923037 -v 0.017800 -0.040410 0.092625 -vn -2.120457 -2.976260 2.303470 -v 0.017996 -0.041010 0.092838 -vn -2.120457 2.976260 2.303470 -v 0.017996 -0.040410 0.092838 -vn -1.712412 -2.976243 2.621058 -v 0.018224 -0.041010 0.093015 -vn -1.712412 2.976242 2.621058 -v 0.018224 -0.040410 0.093015 -vn 1.710940 -3.326419 -2.618824 -v 0.020002 -0.041010 0.090294 -vn 1.710940 3.326420 -2.618824 -v 0.020002 -0.042010 0.090294 -vn 1.200592 3.326373 -2.888628 -v 0.019757 -0.042010 0.090165 -vn 1.200592 -3.326373 -2.888628 -v 0.019757 -0.041010 0.090165 -vn 0.649379 3.326402 -3.060045 -v 0.019493 -0.042010 0.090083 -vn 0.649379 -3.326402 -3.060045 -v 0.019493 -0.041010 0.090083 -vn 0.076063 3.326368 -3.127270 -v 0.019218 -0.042010 0.090050 -vn 0.076063 -3.326368 -3.127270 -v 0.019218 -0.041010 0.090050 -vn -0.499876 3.326424 -3.087989 -v 0.018941 -0.042010 0.090069 -vn -0.499876 -3.326424 -3.087989 -v 0.018941 -0.041010 0.090069 -vn -1.058821 3.326387 -2.943550 -v 0.018673 -0.042010 0.090139 -vn -1.058821 -3.326387 -2.943550 -v 0.018673 -0.041010 0.090139 -vn -1.581652 3.326385 -2.698882 -v 0.018423 -0.042010 0.090256 -vn -1.581652 -3.326385 -2.698882 -v 0.018423 -0.041010 0.090256 -vn -2.050625 3.326388 -2.362311 -v 0.018198 -0.042010 0.090417 -vn -2.050626 -3.326388 -2.362312 -v 0.018198 -0.041010 0.090417 -vn -2.449778 3.326391 -1.945294 -v 0.018007 -0.042010 0.090617 -vn -2.449778 -3.326391 -1.945294 -v 0.018007 -0.041010 0.090617 -vn -2.765517 3.326401 -1.462016 -v 0.017855 -0.042010 0.090849 -vn -2.765517 -3.326401 -1.462016 -v 0.017855 -0.041010 0.090849 -vn -2.987077 3.326388 -0.928954 -v 0.017749 -0.042010 0.091105 -vn -2.987077 -3.326388 -0.928954 -v 0.017749 -0.041010 0.091105 -vn -3.106910 3.326390 -0.364273 -v 0.017691 -0.042010 0.091375 -vn -3.106910 -3.326390 -0.364273 -v 0.017691 -0.041010 0.091375 -vn -3.120942 3.326396 0.212825 -v 0.017685 -0.042010 0.091652 -vn -3.120942 -3.326396 0.212825 -v 0.017685 -0.041010 0.091652 -vn -3.028694 3.326394 0.782682 -v 0.017729 -0.042010 0.091925 -vn -3.028694 -3.326393 0.782681 -v 0.017729 -0.041010 0.091925 -vn -2.833313 3.326385 1.325867 -v 0.017823 -0.042010 0.092186 -vn -2.833313 -3.326385 1.325867 -v 0.017823 -0.041010 0.092186 -vn -2.541440 3.326401 1.823912 -v 0.017963 -0.042010 0.092425 -vn -2.541440 -3.326401 1.823912 -v 0.017963 -0.041010 0.092425 -vn -2.163013 3.326394 2.259857 -v 0.018144 -0.042010 0.092634 -vn -2.163013 -3.326394 2.259856 -v 0.018144 -0.041010 0.092634 -vn -1.710948 3.326382 2.618825 -v 0.018361 -0.042010 0.092806 -vn -1.710948 -3.326382 2.618825 -v 0.018361 -0.041010 0.092806 -vn -1.083113 -3.365989 2.927926 -v 0.019528 -0.042610 0.090612 -vn -1.083113 3.365989 2.927926 -v 0.019528 -0.040410 0.090612 -vn -0.404414 -3.366007 3.095531 -v 0.019311 -0.042610 0.090558 -vn -0.404414 3.366007 3.095531 -v 0.019311 -0.040410 0.090558 -vn 0.294558 -3.365985 3.107913 -v 0.019087 -0.042610 0.090554 -vn 0.294558 3.365985 3.107913 -v 0.019087 -0.040410 0.090554 -vn 0.978741 -3.365994 2.964446 -v 0.018868 -0.042610 0.090600 -vn 0.978741 3.365995 2.964446 -v 0.018868 -0.040410 0.090600 -vn 1.613845 -3.365983 2.672338 -v 0.018664 -0.042610 0.090694 -vn 1.613845 3.365983 2.672339 -v 0.018664 -0.040410 0.090694 -vn 2.168017 -3.365987 2.246238 -v 0.018487 -0.042610 0.090830 -vn 2.168017 3.365987 2.246238 -v 0.018487 -0.040410 0.090830 -vn 2.613501 -3.366007 1.707476 -v 0.018344 -0.042610 0.091003 -vn 2.613501 3.366007 1.707476 -v 0.018344 -0.040410 0.091003 -vn 2.927932 -3.365983 1.083099 -v 0.018243 -0.042610 0.091203 -vn 2.927932 3.365983 1.083099 -v 0.018243 -0.040410 0.091203 -vn 3.095531 -3.365997 0.404424 -v 0.018190 -0.042610 0.091420 -vn 3.095532 3.365997 0.404424 -v 0.018190 -0.040410 0.091420 -vn 3.107917 -3.365982 -0.294528 -v 0.018186 -0.042610 0.091644 -vn 3.107917 3.365982 -0.294528 -v 0.018186 -0.040410 0.091644 -vn 2.964447 -3.366013 -0.978733 -v 0.018232 -0.042610 0.091864 -vn 2.964445 3.366013 -0.978733 -v 0.018232 -0.040410 0.091864 -vn 2.672324 -3.365986 -1.613867 -v 0.018325 -0.042610 0.092067 -vn 2.672325 3.365985 -1.613868 -v 0.018325 -0.040410 0.092067 -vn 2.246239 -3.365968 -2.168021 -v 0.018462 -0.042610 0.092244 -vn 2.246239 3.365968 -2.168021 -v 0.018462 -0.040410 0.092244 -vn 1.257648 -2.976256 2.867164 -v 0.019884 -0.042610 0.093153 -vn 0.768584 -2.976241 3.035058 -v 0.019611 -0.042610 0.093246 -vn 0.258583 -2.976273 3.120170 -v 0.019326 -0.042610 0.093294 -vn 2.470700 -2.976249 1.923005 -v 0.020562 -0.042610 0.092625 -vn 2.120491 -2.976245 2.303436 -v 0.020366 -0.042610 0.092838 -vn 1.712418 -2.976231 2.621052 -v 0.020138 -0.042610 0.093015 -vn 3.130862 -2.976243 -0.000020 -v 0.020931 -0.042610 0.091550 -vn 3.088161 -2.976237 0.515319 -v 0.020907 -0.042610 0.091838 -vn 2.961232 -2.976264 1.016572 -v 0.020836 -0.042610 0.092118 -vn 2.753523 -2.976233 1.490100 -v 0.020720 -0.042610 0.092383 -vn -0.258502 -2.976221 3.120170 -v 0.019037 -0.042610 0.093294 -vn -0.768578 -2.976245 3.035059 -v 0.018752 -0.042610 0.093246 -vn -1.257646 -2.976249 2.867164 -v 0.018478 -0.042610 0.093153 -vn 2.120451 -2.976223 -2.303469 -v 0.020366 -0.042610 0.090262 -vn 2.470695 -2.976245 -1.923010 -v 0.020562 -0.042610 0.090475 -vn 2.753510 -2.976255 -1.490132 -v 0.020720 -0.042610 0.090717 -vn 2.961218 -2.976242 -1.016604 -v 0.020836 -0.042610 0.090982 -vn 3.088160 -2.976250 -0.515339 -v 0.020907 -0.042610 0.091262 -vn 1.257648 2.976256 2.867164 -v 0.019884 -0.040410 0.093153 -vn 1.712418 2.976231 2.621052 -v 0.020138 -0.040410 0.093015 -vn -0.768578 2.976245 3.035060 -v 0.018752 -0.040410 0.093246 -vn -0.258502 2.976221 3.120169 -v 0.019037 -0.040410 0.093294 -vn 0.258583 2.976273 3.120170 -v 0.019326 -0.040410 0.093294 -vn 0.768584 2.976241 3.035058 -v 0.019611 -0.040410 0.093246 -vn -1.257646 2.976249 2.867164 -v 0.018478 -0.040410 0.093153 -vn 2.470695 2.976245 -1.923010 -v 0.020562 -0.040410 0.090475 -vn 2.120451 2.976223 -2.303469 -v 0.020366 -0.040410 0.090262 -vn 3.130862 2.976243 -0.000020 -v 0.020931 -0.040410 0.091550 -vn 3.088159 2.976250 -0.515339 -v 0.020907 -0.040410 0.091262 -vn 2.961218 2.976242 -1.016604 -v 0.020836 -0.040410 0.090982 -vn 2.753510 2.976255 -1.490132 -v 0.020720 -0.040410 0.090717 -vn 2.120491 2.976246 2.303436 -v 0.020366 -0.040410 0.092838 -vn 2.470700 2.976249 1.923004 -v 0.020562 -0.040410 0.092625 -vn 2.753523 2.976233 1.490100 -v 0.020720 -0.040410 0.092383 -vn 2.961232 2.976264 1.016572 -v 0.020836 -0.040410 0.092118 -vn 3.088161 2.976237 0.515319 -v 0.020907 -0.040410 0.091838 -vn -1.257646 2.976249 2.867164 -v 0.018478 -0.042010 0.093153 -vn -0.768578 2.976245 3.035060 -v 0.018752 -0.042010 0.093246 -vn -0.258502 2.976221 3.120170 -v 0.019037 -0.042010 0.093294 -vn 0.258583 2.976273 3.120170 -v 0.019326 -0.042010 0.093294 -vn 0.768584 2.976241 3.035058 -v 0.019611 -0.042010 0.093246 -vn 1.257648 2.976256 2.867164 -v 0.019884 -0.042010 0.093153 -vn 1.712418 2.976231 2.621052 -v 0.020138 -0.042010 0.093015 -vn 2.120491 2.976246 2.303437 -v 0.020366 -0.042010 0.092838 -vn 2.470700 2.976249 1.923004 -v 0.020562 -0.042010 0.092625 -vn 2.753524 2.976233 1.490100 -v 0.020720 -0.042010 0.092383 -vn 2.961232 2.976264 1.016572 -v 0.020836 -0.042010 0.092118 -vn 3.088161 2.976237 0.515319 -v 0.020907 -0.042010 0.091838 -vn 3.130862 2.976244 -0.000020 -v 0.020931 -0.042010 0.091550 -vn 3.088159 2.976250 -0.515339 -v 0.020907 -0.042010 0.091262 -vn 2.961218 2.976242 -1.016604 -v 0.020836 -0.042010 0.090982 -vn 2.753510 2.976255 -1.490132 -v 0.020720 -0.042010 0.090717 -vn 2.470695 2.976245 -1.923010 -v 0.020562 -0.042010 0.090475 -vn 2.120451 2.976223 -2.303469 -v 0.020366 -0.042010 0.090262 -vn -1.257646 -2.976249 2.867164 -v 0.018478 -0.041010 0.093153 -vn -0.768578 -2.976245 3.035060 -v 0.018752 -0.041010 0.093246 -vn -0.258502 -2.976221 3.120170 -v 0.019037 -0.041010 0.093294 -vn 0.258583 -2.976273 3.120169 -v 0.019326 -0.041010 0.093294 -vn 0.768584 -2.976241 3.035058 -v 0.019611 -0.041010 0.093246 -vn 1.257648 -2.976257 2.867164 -v 0.019884 -0.041010 0.093153 -vn 1.712417 -2.976232 2.621052 -v 0.020138 -0.041010 0.093015 -vn 2.120491 -2.976246 2.303436 -v 0.020366 -0.041010 0.092838 -vn 2.470700 -2.976249 1.923005 -v 0.020562 -0.041010 0.092625 -vn 2.753523 -2.976233 1.490100 -v 0.020720 -0.041010 0.092383 -vn 2.961232 -2.976264 1.016572 -v 0.020836 -0.041010 0.092118 -vn 3.088161 -2.976237 0.515319 -v 0.020907 -0.041010 0.091838 -vn 3.130862 -2.976244 -0.000020 -v 0.020931 -0.041010 0.091550 -vn 3.088160 -2.976250 -0.515339 -v 0.020907 -0.041010 0.091262 -vn 2.961218 -2.976242 -1.016604 -v 0.020836 -0.041010 0.090982 -vn 2.753510 -2.976255 -1.490132 -v 0.020720 -0.041010 0.090717 -vn 2.470695 -2.976244 -1.923010 -v 0.020562 -0.041010 0.090475 -vn 2.120451 -2.976223 -2.303469 -v 0.020366 -0.041010 0.090262 -vn 3.028698 3.326380 -0.782675 -v 0.020633 -0.042010 0.091175 -vn 2.833307 3.326407 -1.325872 -v 0.020540 -0.042010 0.090914 -vn 2.541435 3.326383 -1.823924 -v 0.020400 -0.042010 0.090675 -vn 2.163039 3.326382 -2.259834 -v 0.020218 -0.042010 0.090466 -vn -1.200624 3.326392 2.888613 -v 0.018605 -0.042010 0.092935 -vn -0.649381 3.326405 3.060044 -v 0.018870 -0.042010 0.093017 -vn -0.076019 3.326394 3.127267 -v 0.019145 -0.042010 0.093050 -vn 0.499879 3.326370 3.087996 -v 0.019421 -0.042010 0.093031 -vn 1.058777 3.326411 2.943562 -v 0.019689 -0.042010 0.092961 -vn 1.581653 3.326392 2.698880 -v 0.019940 -0.042010 0.092844 -vn 2.050631 3.326384 2.362308 -v 0.020164 -0.042010 0.092683 -vn 2.449786 3.326400 1.945282 -v 0.020356 -0.042010 0.092483 -vn 2.765524 3.326392 1.462004 -v 0.020507 -0.042010 0.092251 -vn 2.987077 3.326388 0.928954 -v 0.020614 -0.042010 0.091995 -vn 3.106910 3.326397 0.364263 -v 0.020671 -0.042010 0.091725 -vn 3.120942 3.326394 -0.212843 -v 0.020678 -0.042010 0.091448 -vn 0.499879 -3.326370 3.087996 -v 0.019421 -0.041010 0.093031 -vn -0.076019 -3.326395 3.127267 -v 0.019145 -0.041010 0.093050 -vn -0.649381 -3.326405 3.060045 -v 0.018870 -0.041010 0.093017 -vn -1.200624 -3.326391 2.888613 -v 0.018605 -0.041010 0.092935 -vn 3.028698 -3.326380 -0.782675 -v 0.020633 -0.041010 0.091175 -vn 3.120941 -3.326394 -0.212842 -v 0.020678 -0.041010 0.091448 -vn 3.106910 -3.326396 0.364263 -v 0.020671 -0.041010 0.091725 -vn 2.987077 -3.326388 0.928954 -v 0.020614 -0.041010 0.091995 -vn 2.765524 -3.326392 1.462004 -v 0.020507 -0.041010 0.092251 -vn 2.449785 -3.326400 1.945282 -v 0.020356 -0.041010 0.092483 -vn 2.050631 -3.326384 2.362308 -v 0.020164 -0.041010 0.092683 -vn 1.581653 -3.326392 2.698880 -v 0.019940 -0.041010 0.092844 -vn 1.058777 -3.326410 2.943562 -v 0.019689 -0.041010 0.092961 -vn 2.163039 -3.326382 -2.259834 -v 0.020218 -0.041010 0.090466 -vn 2.541435 -3.326382 -1.823924 -v 0.020400 -0.041010 0.090675 -vn 2.833307 -3.326407 -1.325872 -v 0.020540 -0.041010 0.090914 -vn -0.000000 3.365984 3.121840 -v 0.020300 -0.038810 0.100000 -vn 0.000000 -3.365984 3.121840 -v 0.020300 -0.041010 0.100000 -vn -0.694638 3.365975 3.043579 -v 0.020523 -0.038810 0.100025 -vn -0.694638 -3.365975 3.043579 -v 0.020523 -0.041010 0.100025 -vn -1.354509 3.366031 2.812675 -v 0.020734 -0.038810 0.100099 -vn -1.354509 -3.366031 2.812675 -v 0.020734 -0.041010 0.100099 -vn -1.946452 3.365968 2.440743 -v 0.020923 -0.038810 0.100218 -vn -1.946452 -3.365968 2.440743 -v 0.020923 -0.041010 0.100218 -vn -2.440740 3.365992 1.946449 -v 0.021082 -0.038810 0.100377 -vn -2.440740 -3.365992 1.946449 -v 0.021082 -0.041010 0.100377 -vn -2.812678 3.366006 1.354511 -v 0.021201 -0.038810 0.100566 -vn -2.812678 -3.366006 1.354512 -v 0.021201 -0.041010 0.100566 -vn -3.043571 3.365979 0.694671 -v 0.021275 -0.038810 0.100777 -vn -3.043571 -3.365979 0.694671 -v 0.021275 -0.041010 0.100777 -vn -3.121838 3.365999 0.000006 -v 0.021300 -0.038810 0.101000 -vn -3.121837 -3.365999 0.000006 -v 0.021300 -0.041010 0.101000 -vn -3.043566 3.365994 -0.694682 -v 0.021275 -0.038810 0.101223 -vn -3.043566 -3.365994 -0.694682 -v 0.021275 -0.041010 0.101223 -vn -2.812688 3.365977 -1.354505 -v 0.021201 -0.038810 0.101434 -vn -2.812688 -3.365977 -1.354504 -v 0.021201 -0.041010 0.101434 -vn -2.440755 3.366010 -1.946426 -v 0.021082 -0.038810 0.101623 -vn -2.440755 -3.366010 -1.946426 -v 0.021082 -0.041010 0.101623 -vn -1.946415 3.365996 -2.440767 -v 0.020923 -0.038810 0.101782 -vn -1.946415 -3.365996 -2.440767 -v 0.020923 -0.041010 0.101782 -vn -1.354518 3.365972 -2.812682 -v 0.020734 -0.038810 0.101901 -vn -1.354518 -3.365971 -2.812681 -v 0.020734 -0.041010 0.101901 -vn -0.694684 3.366007 -3.043562 -v 0.020523 -0.038810 0.101975 -vn -0.694685 -3.366007 -3.043563 -v 0.020523 -0.041010 0.101975 -vn 0.000000 3.365984 -3.121840 -v 0.020300 -0.038810 0.102000 -vn -0.000000 -3.365984 -3.121840 -v 0.020300 -0.041010 0.102000 -vn 0.000000 -2.976270 3.130866 -v 0.020300 -0.039410 0.102750 -vn -0.515304 2.976234 3.088163 -v 0.020012 -0.038810 0.102726 -vn -0.515303 -2.976233 3.088163 -v 0.020012 -0.039410 0.102726 -vn -1.016595 2.976241 2.961221 -v 0.019732 -0.038810 0.102655 -vn -1.016595 -2.976241 2.961221 -v 0.019732 -0.039410 0.102655 -vn -1.490114 2.976264 2.753520 -v 0.019467 -0.038810 0.102539 -vn -1.490114 -2.976264 2.753520 -v 0.019467 -0.039410 0.102539 -vn -1.923011 2.976220 2.470690 -v 0.019225 -0.038810 0.102381 -vn -1.923011 -2.976220 2.470690 -v 0.019225 -0.039410 0.102381 -vn -2.303465 2.976256 2.120461 -v 0.019012 -0.038810 0.102185 -vn -2.303465 -2.976256 2.120462 -v 0.019012 -0.039410 0.102185 -vn -2.621053 2.976248 1.712420 -v 0.018835 -0.038810 0.101957 -vn -2.621053 -2.976248 1.712420 -v 0.018835 -0.039410 0.101957 -vn -2.867160 2.976243 1.257653 -v 0.018697 -0.038810 0.101703 -vn -2.867160 -2.976244 1.257654 -v 0.018697 -0.039410 0.101703 -vn -3.035059 2.976248 0.768581 -v 0.018604 -0.038810 0.101430 -vn -3.035059 -2.976247 0.768581 -v 0.018604 -0.039410 0.101430 -vn -3.120169 2.976245 0.258546 -v 0.018556 -0.038810 0.101145 -vn -3.120169 -2.976245 0.258546 -v 0.018556 -0.039410 0.101145 -vn -3.120170 2.976249 -0.258539 -v 0.018556 -0.038810 0.100855 -vn -3.120170 -2.976249 -0.258539 -v 0.018556 -0.039410 0.100855 -vn -3.035056 2.976235 -0.768587 -v 0.018604 -0.038810 0.100570 -vn -3.035056 -2.976235 -0.768587 -v 0.018604 -0.039410 0.100570 -vn -2.867156 2.976252 -1.257666 -v 0.018697 -0.038810 0.100297 -vn -2.867156 -2.976252 -1.257666 -v 0.018697 -0.039410 0.100297 -vn -2.621053 2.976248 -1.712420 -v 0.018835 -0.038810 0.100043 -vn -2.621053 -2.976248 -1.712420 -v 0.018835 -0.039410 0.100043 -vn -2.303465 2.976256 -2.120462 -v 0.019012 -0.038810 0.099815 -vn -2.303465 -2.976256 -2.120462 -v 0.019012 -0.039410 0.099815 -vn -1.923011 2.976220 -2.470690 -v 0.019225 -0.038810 0.099619 -vn -1.923011 -2.976221 -2.470690 -v 0.019225 -0.039410 0.099619 -vn -1.490114 2.976264 -2.753520 -v 0.019467 -0.038810 0.099461 -vn -1.490114 -2.976263 -2.753520 -v 0.019467 -0.039410 0.099461 -vn -1.016595 2.976241 -2.961221 -v 0.019732 -0.038810 0.099345 -vn -1.016595 -2.976241 -2.961221 -v 0.019732 -0.039410 0.099345 -vn -0.515344 2.976259 -3.088160 -v 0.020012 -0.038810 0.099274 -vn -0.515344 -2.976259 -3.088160 -v 0.020012 -0.039410 0.099274 -vn 0.000000 -2.976219 -3.130859 -v 0.020300 -0.039410 0.099250 -vn 0.000000 2.976270 3.130866 -v 0.020300 -0.040410 0.102750 -vn -0.515304 2.976233 3.088163 -v 0.020012 -0.040410 0.102726 -vn -0.515303 -2.976233 3.088163 -v 0.020012 -0.041010 0.102726 -vn -1.016595 2.976241 2.961221 -v 0.019732 -0.040410 0.102655 -vn -1.016595 -2.976241 2.961221 -v 0.019732 -0.041010 0.102655 -vn -1.490114 2.976263 2.753520 -v 0.019467 -0.040410 0.102539 -vn -1.490114 -2.976264 2.753520 -v 0.019467 -0.041010 0.102539 -vn -1.923011 2.976221 2.470690 -v 0.019225 -0.040410 0.102381 -vn -1.923011 -2.976220 2.470690 -v 0.019225 -0.041010 0.102381 -vn -2.303465 2.976256 2.120461 -v 0.019012 -0.040410 0.102185 -vn -2.303465 -2.976256 2.120462 -v 0.019012 -0.041010 0.102185 -vn -2.621053 2.976248 1.712420 -v 0.018835 -0.040410 0.101957 -vn -2.621053 -2.976248 1.712420 -v 0.018835 -0.041010 0.101957 -vn -2.867160 2.976243 1.257653 -v 0.018697 -0.040410 0.101703 -vn -2.867160 -2.976243 1.257654 -v 0.018697 -0.041010 0.101703 -vn -3.035059 2.976248 0.768581 -v 0.018604 -0.040410 0.101430 -vn -3.035059 -2.976247 0.768581 -v 0.018604 -0.041010 0.101430 -vn -3.120169 2.976245 0.258546 -v 0.018556 -0.040410 0.101145 -vn -3.120169 -2.976245 0.258546 -v 0.018556 -0.041010 0.101145 -vn -3.120170 2.976249 -0.258539 -v 0.018556 -0.040410 0.100855 -vn -3.120170 -2.976249 -0.258539 -v 0.018556 -0.041010 0.100855 -vn -3.035056 2.976235 -0.768587 -v 0.018604 -0.040410 0.100570 -vn -3.035056 -2.976235 -0.768587 -v 0.018604 -0.041010 0.100570 -vn -2.867156 2.976252 -1.257666 -v 0.018697 -0.040410 0.100297 -vn -2.867156 -2.976252 -1.257666 -v 0.018697 -0.041010 0.100297 -vn -2.621053 2.976248 -1.712420 -v 0.018835 -0.040410 0.100043 -vn -2.621053 -2.976248 -1.712420 -v 0.018835 -0.041010 0.100043 -vn -2.303465 2.976256 -2.120462 -v 0.019012 -0.040410 0.099815 -vn -2.303465 -2.976256 -2.120462 -v 0.019012 -0.041010 0.099815 -vn -1.923011 2.976220 -2.470690 -v 0.019225 -0.040410 0.099619 -vn -1.923011 -2.976220 -2.470690 -v 0.019225 -0.041010 0.099619 -vn -1.490114 2.976264 -2.753520 -v 0.019467 -0.040410 0.099461 -vn -1.490114 -2.976264 -2.753520 -v 0.019467 -0.041010 0.099461 -vn -1.016595 2.976241 -2.961221 -v 0.019732 -0.040410 0.099345 -vn -1.016595 -2.976241 -2.961221 -v 0.019732 -0.041010 0.099345 -vn -0.515344 2.976259 -3.088160 -v 0.020012 -0.040410 0.099274 -vn -0.515344 -2.976259 -3.088160 -v 0.020012 -0.041010 0.099274 -vn 0.000000 2.976219 -3.130859 -v 0.020300 -0.040410 0.099250 -vn -0.000000 3.326394 3.128191 -v 0.020300 -0.040410 0.102500 -vn 0.000000 -3.326394 3.128191 -v 0.020300 -0.039410 0.102500 -vn -0.574800 -3.326388 3.074929 -v 0.020024 -0.039410 0.102474 -vn -0.574800 3.326388 3.074929 -v 0.020024 -0.040410 0.102474 -vn -1.130023 -3.326392 2.916955 -v 0.019758 -0.039410 0.102399 -vn -1.130023 3.326392 2.916955 -v 0.019758 -0.040410 0.102399 -vn -1.646772 -3.326393 2.659647 -v 0.019510 -0.039410 0.102275 -vn -1.646772 3.326393 2.659647 -v 0.019510 -0.040410 0.102275 -vn -2.107449 -3.326399 2.311759 -v 0.019289 -0.039410 0.102109 -vn -2.107450 3.326399 2.311759 -v 0.019289 -0.040410 0.102109 -vn -2.496359 -3.326393 1.885145 -v 0.019103 -0.039410 0.101904 -vn -2.496359 3.326393 1.885145 -v 0.019103 -0.040410 0.101904 -vn -2.800246 -3.326388 1.394348 -v 0.018957 -0.039410 0.101669 -vn -2.800246 3.326388 1.394348 -v 0.018957 -0.040410 0.101669 -vn -3.008775 -3.326392 0.856069 -v 0.018857 -0.039410 0.101410 -vn -3.008775 3.326392 0.856069 -v 0.018857 -0.040410 0.101410 -vn -3.114847 -3.326392 0.288632 -v 0.018806 -0.039410 0.101138 -vn -3.114847 3.326392 0.288632 -v 0.018806 -0.040410 0.101138 -vn -3.114846 -3.326396 -0.288640 -v 0.018806 -0.039410 0.100862 -vn -3.114846 3.326396 -0.288640 -v 0.018806 -0.040410 0.100862 -vn -3.008779 -3.326378 -0.856062 -v 0.018857 -0.039410 0.100590 -vn -3.008779 3.326377 -0.856062 -v 0.018857 -0.040410 0.100590 -vn -2.800240 -3.326412 -1.394352 -v 0.018957 -0.039410 0.100331 -vn -2.800240 3.326412 -1.394352 -v 0.018957 -0.040410 0.100331 -vn -2.496347 -3.326379 -1.885164 -v 0.019103 -0.039410 0.100096 -vn -2.496347 3.326379 -1.885164 -v 0.019103 -0.040410 0.100096 -vn -2.107450 -3.326399 -2.311759 -v 0.019289 -0.039410 0.099891 -vn -2.107449 3.326399 -2.311759 -v 0.019289 -0.040410 0.099891 -vn -1.646772 -3.326393 -2.659647 -v 0.019510 -0.039410 0.099725 -vn -1.646772 3.326393 -2.659647 -v 0.019510 -0.040410 0.099725 -vn -1.130023 -3.326392 -2.916955 -v 0.019758 -0.039410 0.099601 -vn -1.130023 3.326392 -2.916955 -v 0.019758 -0.040410 0.099601 -vn -0.574800 -3.326388 -3.074929 -v 0.020024 -0.039410 0.099526 -vn -0.574800 3.326388 -3.074929 -v 0.020024 -0.040410 0.099526 -vn -0.000000 -3.326394 -3.128191 -v 0.020300 -0.039410 0.099500 -vn 0.000000 3.326394 -3.128191 -v 0.020300 -0.040410 0.099500 -vn 0.694685 3.366007 -3.043563 -v 0.020077 -0.038810 0.101975 -vn 0.694684 -3.366007 -3.043562 -v 0.020077 -0.041010 0.101975 -vn 1.354518 3.365971 -2.812681 -v 0.019866 -0.038810 0.101901 -vn 1.354518 -3.365972 -2.812682 -v 0.019866 -0.041010 0.101901 -vn 1.946415 3.365996 -2.440767 -v 0.019677 -0.038810 0.101782 -vn 1.946415 -3.365996 -2.440767 -v 0.019677 -0.041010 0.101782 -vn 2.440755 3.366010 -1.946426 -v 0.019518 -0.038810 0.101623 -vn 2.440755 -3.366010 -1.946426 -v 0.019518 -0.041010 0.101623 -vn 2.812688 3.365977 -1.354504 -v 0.019399 -0.038810 0.101434 -vn 2.812688 -3.365977 -1.354505 -v 0.019399 -0.041010 0.101434 -vn 3.043566 3.365994 -0.694682 -v 0.019325 -0.038810 0.101223 -vn 3.043566 -3.365994 -0.694682 -v 0.019325 -0.041010 0.101223 -vn 3.121837 3.365999 0.000006 -v 0.019300 -0.038810 0.101000 -vn 3.121838 -3.365999 0.000006 -v 0.019300 -0.041010 0.101000 -vn 3.043571 3.365979 0.694671 -v 0.019325 -0.038810 0.100777 -vn 3.043571 -3.365979 0.694671 -v 0.019325 -0.041010 0.100777 -vn 2.812678 3.366006 1.354512 -v 0.019399 -0.038810 0.100566 -vn 2.812678 -3.366006 1.354511 -v 0.019399 -0.041010 0.100566 -vn 2.440740 3.365992 1.946449 -v 0.019518 -0.038810 0.100377 -vn 2.440740 -3.365992 1.946449 -v 0.019518 -0.041010 0.100377 -vn 1.946452 3.365968 2.440743 -v 0.019677 -0.038810 0.100218 -vn 1.946452 -3.365968 2.440743 -v 0.019677 -0.041010 0.100218 -vn 1.354509 3.366031 2.812675 -v 0.019866 -0.038810 0.100099 -vn 1.354509 -3.366031 2.812675 -v 0.019866 -0.041010 0.100099 -vn 0.694638 3.365975 3.043579 -v 0.020077 -0.038810 0.100025 -vn 0.694638 -3.365975 3.043579 -v 0.020077 -0.041010 0.100025 -vn 1.016595 2.976241 -2.961221 -v 0.020868 -0.038810 0.099345 -vn 0.515344 2.976259 -3.088160 -v 0.020588 -0.038810 0.099274 -vn 2.621053 2.976248 -1.712420 -v 0.021765 -0.038810 0.100043 -vn 2.303465 2.976256 -2.120461 -v 0.021588 -0.038810 0.099815 -vn 1.923011 2.976220 -2.470690 -v 0.021375 -0.038810 0.099619 -vn 1.490114 2.976264 -2.753520 -v 0.021133 -0.038810 0.099461 -vn 3.120169 2.976245 0.258546 -v 0.022044 -0.038810 0.101145 -vn 3.120170 2.976249 -0.258539 -v 0.022044 -0.038810 0.100855 -vn 3.035056 2.976235 -0.768587 -v 0.021996 -0.038810 0.100570 -vn 2.867156 2.976252 -1.257666 -v 0.021903 -0.038810 0.100297 -vn 2.621053 2.976248 1.712420 -v 0.021765 -0.038810 0.101957 -vn 2.867160 2.976243 1.257653 -v 0.021903 -0.038810 0.101703 -vn 3.035059 2.976247 0.768581 -v 0.021996 -0.038810 0.101430 -vn 0.515303 2.976233 3.088163 -v 0.020588 -0.038810 0.102726 -vn 1.016595 2.976241 2.961221 -v 0.020868 -0.038810 0.102655 -vn 1.490114 2.976264 2.753520 -v 0.021133 -0.038810 0.102539 -vn 1.923011 2.976220 2.470690 -v 0.021375 -0.038810 0.102381 -vn 2.303465 2.976256 2.120462 -v 0.021588 -0.038810 0.102185 -vn 1.016595 -2.976241 2.961221 -v 0.020868 -0.041010 0.102655 -vn 0.515304 -2.976234 3.088163 -v 0.020588 -0.041010 0.102726 -vn 2.621053 -2.976248 -1.712420 -v 0.021765 -0.041010 0.100043 -vn 2.867156 -2.976252 -1.257666 -v 0.021903 -0.041010 0.100297 -vn 3.035056 -2.976235 -0.768587 -v 0.021996 -0.041010 0.100570 -vn 2.621053 -2.976248 1.712420 -v 0.021765 -0.041010 0.101957 -vn 2.303465 -2.976256 2.120462 -v 0.021588 -0.041010 0.102185 -vn 1.923011 -2.976220 2.470690 -v 0.021375 -0.041010 0.102381 -vn 1.490114 -2.976264 2.753520 -v 0.021133 -0.041010 0.102539 -vn 3.120170 -2.976249 -0.258539 -v 0.022044 -0.041010 0.100855 -vn 3.120169 -2.976245 0.258546 -v 0.022044 -0.041010 0.101145 -vn 3.035059 -2.976248 0.768581 -v 0.021996 -0.041010 0.101430 -vn 2.867160 -2.976243 1.257653 -v 0.021903 -0.041010 0.101703 -vn 1.016595 -2.976241 -2.961221 -v 0.020868 -0.041010 0.099345 -vn 1.490114 -2.976264 -2.753520 -v 0.021133 -0.041010 0.099461 -vn 1.923011 -2.976220 -2.470690 -v 0.021375 -0.041010 0.099619 -vn 2.303465 -2.976256 -2.120462 -v 0.021588 -0.041010 0.099815 -vn 0.515344 -2.976259 -3.088160 -v 0.020588 -0.041010 0.099274 -vn 0.515344 -2.976259 -3.088160 -v 0.020588 -0.039410 0.099274 -vn 1.016595 -2.976241 -2.961221 -v 0.020868 -0.039410 0.099345 -vn 1.490114 -2.976264 -2.753520 -v 0.021133 -0.039410 0.099461 -vn 1.923011 -2.976220 -2.470690 -v 0.021375 -0.039410 0.099619 -vn 2.303465 -2.976256 -2.120462 -v 0.021588 -0.039410 0.099815 -vn 2.621053 -2.976248 -1.712420 -v 0.021765 -0.039410 0.100043 -vn 2.867156 -2.976252 -1.257666 -v 0.021903 -0.039410 0.100297 -vn 3.035056 -2.976235 -0.768587 -v 0.021996 -0.039410 0.100570 -vn 3.120170 -2.976249 -0.258539 -v 0.022044 -0.039410 0.100855 -vn 3.120169 -2.976245 0.258546 -v 0.022044 -0.039410 0.101145 -vn 3.035059 -2.976248 0.768581 -v 0.021996 -0.039410 0.101430 -vn 2.867160 -2.976243 1.257653 -v 0.021903 -0.039410 0.101703 -vn 2.621053 -2.976248 1.712420 -v 0.021765 -0.039410 0.101957 -vn 2.303465 -2.976256 2.120462 -v 0.021588 -0.039410 0.102185 -vn 1.923011 -2.976221 2.470690 -v 0.021375 -0.039410 0.102381 -vn 1.490114 -2.976263 2.753520 -v 0.021133 -0.039410 0.102539 -vn 1.016595 -2.976241 2.961221 -v 0.020868 -0.039410 0.102655 -vn 0.515304 -2.976233 3.088163 -v 0.020588 -0.039410 0.102726 -vn 0.515344 2.976259 -3.088160 -v 0.020588 -0.040410 0.099274 -vn 1.016595 2.976241 -2.961221 -v 0.020868 -0.040410 0.099345 -vn 1.490114 2.976263 -2.753520 -v 0.021133 -0.040410 0.099461 -vn 1.923011 2.976221 -2.470690 -v 0.021375 -0.040410 0.099619 -vn 2.303465 2.976256 -2.120461 -v 0.021588 -0.040410 0.099815 -vn 2.621053 2.976248 -1.712420 -v 0.021765 -0.040410 0.100043 -vn 2.867156 2.976252 -1.257666 -v 0.021903 -0.040410 0.100297 -vn 3.035056 2.976235 -0.768587 -v 0.021996 -0.040410 0.100570 -vn 3.120170 2.976249 -0.258539 -v 0.022044 -0.040410 0.100855 -vn 3.120169 2.976245 0.258546 -v 0.022044 -0.040410 0.101145 -vn 3.035059 2.976247 0.768581 -v 0.021996 -0.040410 0.101430 -vn 2.867160 2.976244 1.257653 -v 0.021903 -0.040410 0.101703 -vn 2.621053 2.976248 1.712420 -v 0.021765 -0.040410 0.101957 -vn 2.303465 2.976256 2.120462 -v 0.021588 -0.040410 0.102185 -vn 1.923011 2.976220 2.470690 -v 0.021375 -0.040410 0.102381 -vn 1.490114 2.976264 2.753520 -v 0.021133 -0.040410 0.102539 -vn 1.016595 2.976241 2.961221 -v 0.020868 -0.040410 0.102655 -vn 0.515303 2.976233 3.088163 -v 0.020588 -0.040410 0.102726 -vn 0.574800 -3.326388 -3.074929 -v 0.020576 -0.039410 0.099526 -vn 1.130023 -3.326392 -2.916955 -v 0.020842 -0.039410 0.099601 -vn 1.646772 -3.326393 -2.659647 -v 0.021090 -0.039410 0.099725 -vn 2.107449 -3.326399 -2.311759 -v 0.021311 -0.039410 0.099891 -vn 2.107450 -3.326399 2.311759 -v 0.021311 -0.039410 0.102109 -vn 1.646772 -3.326393 2.659647 -v 0.021090 -0.039410 0.102275 -vn 1.130023 -3.326392 2.916955 -v 0.020842 -0.039410 0.102399 -vn 0.574800 -3.326388 3.074929 -v 0.020576 -0.039410 0.102474 -vn 2.496347 -3.326379 -1.885164 -v 0.021497 -0.039410 0.100096 -vn 2.800240 -3.326412 -1.394352 -v 0.021643 -0.039410 0.100331 -vn 3.008779 -3.326377 -0.856062 -v 0.021743 -0.039410 0.100590 -vn 3.114846 -3.326396 -0.288640 -v 0.021794 -0.039410 0.100862 -vn 3.114847 -3.326392 0.288632 -v 0.021794 -0.039410 0.101138 -vn 3.008775 -3.326392 0.856069 -v 0.021743 -0.039410 0.101410 -vn 2.800246 -3.326388 1.394348 -v 0.021643 -0.039410 0.101669 -vn 2.496359 -3.326393 1.885145 -v 0.021497 -0.039410 0.101904 -vn 2.107450 3.326399 -2.311759 -v 0.021311 -0.040410 0.099891 -vn 1.646772 3.326393 -2.659647 -v 0.021090 -0.040410 0.099725 -vn 1.130023 3.326392 -2.916955 -v 0.020842 -0.040410 0.099601 -vn 0.574800 3.326388 -3.074929 -v 0.020576 -0.040410 0.099526 -vn 0.574800 3.326388 3.074929 -v 0.020576 -0.040410 0.102474 -vn 1.130023 3.326392 2.916955 -v 0.020842 -0.040410 0.102399 -vn 1.646772 3.326393 2.659647 -v 0.021090 -0.040410 0.102275 -vn 2.107449 3.326399 2.311759 -v 0.021311 -0.040410 0.102109 -vn 2.496359 3.326393 1.885145 -v 0.021497 -0.040410 0.101904 -vn 2.800246 3.326388 1.394348 -v 0.021643 -0.040410 0.101669 -vn 3.008775 3.326392 0.856069 -v 0.021743 -0.040410 0.101410 -vn 3.114847 3.326392 0.288632 -v 0.021794 -0.040410 0.101138 -vn 3.114846 3.326396 -0.288640 -v 0.021794 -0.040410 0.100862 -vn 3.008779 3.326378 -0.856062 -v 0.021743 -0.040410 0.100590 -vn 2.800240 3.326412 -1.394352 -v 0.021643 -0.040410 0.100331 -vn 2.496347 3.326379 -1.885164 -v 0.021497 -0.040410 0.100096 -vn 1.707460 -3.365986 -2.613516 -v 0.026253 -0.041010 0.101837 -vn 1.707460 3.365987 -2.613515 -v 0.026253 -0.038810 0.101837 -vn 1.083110 -3.365983 -2.927927 -v 0.026453 -0.041010 0.101938 -vn 1.083111 3.365983 -2.927927 -v 0.026453 -0.038810 0.101938 -vn 0.404417 -3.366009 -3.095531 -v 0.026670 -0.041010 0.101992 -vn 0.404417 3.366009 -3.095530 -v 0.026670 -0.038810 0.101992 -vn -0.294505 -3.365951 -3.107924 -v 0.026894 -0.041010 0.101996 -vn -0.294505 3.365951 -3.107924 -v 0.026894 -0.038810 0.101996 -vn -0.978688 -3.366029 -2.964457 -v 0.027114 -0.041010 0.101950 -vn -0.978688 3.366029 -2.964457 -v 0.027114 -0.038810 0.101950 -vn -1.613851 -3.365987 -2.672333 -v 0.027317 -0.041010 0.101856 -vn -1.613851 3.365988 -2.672334 -v 0.027317 -0.038810 0.101856 -vn -2.168045 -3.366003 -2.246207 -v 0.027494 -0.041010 0.101720 -vn -2.168045 3.366003 -2.246207 -v 0.027494 -0.038810 0.101720 -vn -2.613523 -3.365986 -1.707450 -v 0.027637 -0.041010 0.101547 -vn -2.613523 3.365986 -1.707450 -v 0.027637 -0.038810 0.101547 -vn -2.927928 -3.365975 -1.083112 -v 0.027738 -0.041010 0.101347 -vn -2.927929 3.365975 -1.083112 -v 0.027738 -0.038810 0.101347 -vn -3.095529 -3.366005 -0.404436 -v 0.027792 -0.041010 0.101130 -vn -3.095529 3.366005 -0.404436 -v 0.027792 -0.038810 0.101130 -vn -3.107912 -3.365997 0.294551 -v 0.027796 -0.041010 0.100906 -vn -3.107911 3.365996 0.294551 -v 0.027796 -0.038810 0.100906 -vn -2.964454 -3.365976 0.978726 -v 0.027750 -0.041010 0.100686 -vn -2.964454 3.365976 0.978725 -v 0.027750 -0.038810 0.100686 -vn -2.672332 -3.366014 1.613845 -v 0.027656 -0.041010 0.100483 -vn -2.672332 3.366014 1.613845 -v 0.027656 -0.038810 0.100483 -vn -2.246233 -3.365962 2.168030 -v 0.027520 -0.041010 0.100306 -vn -2.246233 3.365962 2.168029 -v 0.027520 -0.038810 0.100306 -vn -1.707497 -3.366009 2.613487 -v 0.027347 -0.041010 0.100163 -vn -1.707497 3.366008 2.613488 -v 0.027347 -0.038810 0.100163 -vn 1.712408 2.976239 -2.621060 -v 0.027757 -0.040410 0.099535 -vn 1.712408 -2.976239 -2.621060 -v 0.027757 -0.041010 0.099535 -vn 1.257644 -2.976255 -2.867165 -v 0.027503 -0.041010 0.099397 -vn 1.257645 2.976254 -2.867165 -v 0.027503 -0.040410 0.099397 -vn 0.768580 -2.976242 -3.035059 -v 0.027230 -0.041010 0.099304 -vn 0.768580 2.976242 -3.035059 -v 0.027230 -0.040410 0.099304 -vn 0.258500 -2.976222 -3.120170 -v 0.026945 -0.041010 0.099256 -vn 0.258501 2.976222 -3.120170 -v 0.026945 -0.040410 0.099256 -vn -0.258583 -2.976273 -3.120169 -v 0.026655 -0.041010 0.099256 -vn -0.258583 2.976273 -3.120170 -v 0.026655 -0.040410 0.099256 -vn -0.768581 -2.976243 -3.035059 -v 0.026370 -0.041010 0.099304 -vn -0.768581 2.976243 -3.035059 -v 0.026370 -0.040410 0.099304 -vn -1.257649 -2.976252 -2.867163 -v 0.026097 -0.041010 0.099397 -vn -1.257649 2.976251 -2.867163 -v 0.026097 -0.040410 0.099397 -vn -1.712417 -2.976238 -2.621054 -v 0.025843 -0.041010 0.099535 -vn -1.712417 2.976238 -2.621054 -v 0.025843 -0.040410 0.099535 -vn -2.120486 -2.976242 -2.303441 -v 0.025615 -0.041010 0.099712 -vn -2.120486 2.976242 -2.303440 -v 0.025615 -0.040410 0.099712 -vn -2.470704 -2.976243 -1.922997 -v 0.025419 -0.041010 0.099925 -vn -2.470705 2.976244 -1.922997 -v 0.025419 -0.040410 0.099925 -vn -2.753525 -2.976245 -1.490102 -v 0.025261 -0.041010 0.100167 -vn -2.753524 2.976244 -1.490102 -v 0.025261 -0.040410 0.100167 -vn -2.961231 -2.976252 -1.016571 -v 0.025145 -0.041010 0.100432 -vn -2.961231 2.976252 -1.016571 -v 0.025145 -0.040410 0.100432 -vn -3.088163 -2.976243 -0.515310 -v 0.025074 -0.041010 0.100712 -vn -3.088163 2.976243 -0.515310 -v 0.025074 -0.040410 0.100712 -vn -3.130863 -2.976252 0.000007 -v 0.025050 -0.041010 0.101000 -vn -3.130863 2.976252 0.000007 -v 0.025050 -0.040410 0.101000 -vn -3.088158 -2.976235 0.515335 -v 0.025074 -0.041010 0.101288 -vn -3.088158 2.976235 0.515335 -v 0.025074 -0.040410 0.101288 -vn -2.961216 -2.976248 1.016613 -v 0.025145 -0.041010 0.101568 -vn -2.961216 2.976248 1.016613 -v 0.025145 -0.040410 0.101568 -vn -2.753505 -2.976250 1.490139 -v 0.025261 -0.041010 0.101833 -vn -2.753505 2.976250 1.490139 -v 0.025261 -0.040410 0.101833 -vn -2.470690 -2.976250 1.923017 -v 0.025419 -0.041010 0.102075 -vn -2.470690 2.976250 1.923017 -v 0.025419 -0.040410 0.102075 -vn -2.120481 -2.976247 2.303446 -v 0.025615 -0.041010 0.102288 -vn -2.120481 2.976247 2.303446 -v 0.025615 -0.040410 0.102288 -vn -1.712413 -2.976235 2.621056 -v 0.025843 -0.041010 0.102465 -vn -1.712413 2.976235 2.621056 -v 0.025843 -0.040410 0.102465 -vn 1.712408 2.976239 -2.621060 -v 0.027757 -0.038810 0.099535 -vn 1.712408 -2.976239 -2.621060 -v 0.027757 -0.039410 0.099535 -vn 1.257644 -2.976254 -2.867165 -v 0.027503 -0.039410 0.099397 -vn 1.257645 2.976254 -2.867165 -v 0.027503 -0.038810 0.099397 -vn 0.768580 -2.976242 -3.035059 -v 0.027230 -0.039410 0.099304 -vn 0.768580 2.976242 -3.035059 -v 0.027230 -0.038810 0.099304 -vn 0.258500 -2.976222 -3.120170 -v 0.026945 -0.039410 0.099256 -vn 0.258501 2.976222 -3.120170 -v 0.026945 -0.038810 0.099256 -vn -0.258583 -2.976273 -3.120169 -v 0.026655 -0.039410 0.099256 -vn -0.258583 2.976273 -3.120170 -v 0.026655 -0.038810 0.099256 -vn -0.768581 -2.976243 -3.035059 -v 0.026370 -0.039410 0.099304 -vn -0.768581 2.976243 -3.035059 -v 0.026370 -0.038810 0.099304 -vn -1.257649 -2.976251 -2.867163 -v 0.026097 -0.039410 0.099397 -vn -1.257649 2.976252 -2.867163 -v 0.026097 -0.038810 0.099397 -vn -1.712417 -2.976238 -2.621054 -v 0.025843 -0.039410 0.099535 -vn -1.712417 2.976238 -2.621054 -v 0.025843 -0.038810 0.099535 -vn -2.120486 -2.976242 -2.303441 -v 0.025615 -0.039410 0.099712 -vn -2.120486 2.976242 -2.303440 -v 0.025615 -0.038810 0.099712 -vn -2.470704 -2.976244 -1.922997 -v 0.025419 -0.039410 0.099925 -vn -2.470705 2.976244 -1.922997 -v 0.025419 -0.038810 0.099925 -vn -2.753525 -2.976244 -1.490102 -v 0.025261 -0.039410 0.100167 -vn -2.753524 2.976245 -1.490102 -v 0.025261 -0.038810 0.100167 -vn -2.961231 -2.976252 -1.016571 -v 0.025145 -0.039410 0.100432 -vn -2.961231 2.976252 -1.016571 -v 0.025145 -0.038810 0.100432 -vn -3.088163 -2.976244 -0.515310 -v 0.025074 -0.039410 0.100712 -vn -3.088163 2.976243 -0.515310 -v 0.025074 -0.038810 0.100712 -vn -3.130863 -2.976252 0.000007 -v 0.025050 -0.039410 0.101000 -vn -3.130863 2.976252 0.000007 -v 0.025050 -0.038810 0.101000 -vn -3.088158 -2.976235 0.515335 -v 0.025074 -0.039410 0.101288 -vn -3.088158 2.976235 0.515335 -v 0.025074 -0.038810 0.101288 -vn -2.961216 -2.976248 1.016613 -v 0.025145 -0.039410 0.101568 -vn -2.961216 2.976248 1.016613 -v 0.025145 -0.038810 0.101568 -vn -2.753505 -2.976250 1.490139 -v 0.025261 -0.039410 0.101833 -vn -2.753505 2.976250 1.490139 -v 0.025261 -0.038810 0.101833 -vn -2.470690 -2.976250 1.923017 -v 0.025419 -0.039410 0.102075 -vn -2.470690 2.976250 1.923017 -v 0.025419 -0.038810 0.102075 -vn -2.120481 -2.976247 2.303446 -v 0.025615 -0.039410 0.102288 -vn -2.120481 2.976247 2.303446 -v 0.025615 -0.038810 0.102288 -vn -1.712413 -2.976235 2.621056 -v 0.025843 -0.039410 0.102465 -vn -1.712413 2.976235 2.621056 -v 0.025843 -0.038810 0.102465 -vn 1.710953 -3.326379 -2.618823 -v 0.027620 -0.039410 0.099744 -vn 1.710953 3.326378 -2.618823 -v 0.027620 -0.040410 0.099744 -vn 1.200625 3.326397 -2.888611 -v 0.027376 -0.040410 0.099615 -vn 1.200625 -3.326396 -2.888611 -v 0.027376 -0.039410 0.099615 -vn 0.649378 3.326403 -3.060046 -v 0.027111 -0.040410 0.099533 -vn 0.649378 -3.326403 -3.060046 -v 0.027111 -0.039410 0.099533 -vn 0.076019 3.326394 -3.127267 -v 0.026836 -0.040410 0.099500 -vn 0.076019 -3.326394 -3.127267 -v 0.026836 -0.039410 0.099500 -vn -0.499879 3.326370 -3.087996 -v 0.026560 -0.040410 0.099519 -vn -0.499879 -3.326370 -3.087996 -v 0.026560 -0.039410 0.099519 -vn -1.058777 3.326411 -2.943562 -v 0.026292 -0.040410 0.099589 -vn -1.058777 -3.326410 -2.943562 -v 0.026292 -0.039410 0.099589 -vn -1.581653 3.326392 -2.698880 -v 0.026042 -0.040410 0.099706 -vn -1.581653 -3.326392 -2.698880 -v 0.026042 -0.039410 0.099706 -vn -2.050631 3.326384 -2.362309 -v 0.025817 -0.040410 0.099867 -vn -2.050631 -3.326384 -2.362308 -v 0.025817 -0.039410 0.099867 -vn -2.449790 3.326405 -1.945275 -v 0.025625 -0.040410 0.100067 -vn -2.449791 -3.326406 -1.945275 -v 0.025625 -0.039410 0.100067 -vn -2.765526 3.326380 -1.462006 -v 0.025474 -0.040410 0.100299 -vn -2.765526 -3.326380 -1.462006 -v 0.025474 -0.039410 0.100299 -vn -2.987076 3.326400 -0.928953 -v 0.025368 -0.040410 0.100555 -vn -2.987076 -3.326401 -0.928953 -v 0.025368 -0.039410 0.100555 -vn -3.106912 3.326383 -0.364263 -v 0.025310 -0.040410 0.100825 -vn -3.106912 -3.326383 -0.364263 -v 0.025310 -0.039410 0.100825 -vn -3.120942 3.326396 0.212825 -v 0.025303 -0.040410 0.101102 -vn -3.120942 -3.326396 0.212825 -v 0.025303 -0.039410 0.101102 -vn -3.028694 3.326393 0.782682 -v 0.025348 -0.040410 0.101375 -vn -3.028694 -3.326394 0.782681 -v 0.025348 -0.039410 0.101375 -vn -2.833302 3.326398 1.325886 -v 0.025441 -0.040410 0.101636 -vn -2.833302 -3.326398 1.325886 -v 0.025441 -0.039410 0.101636 -vn -2.541448 3.326370 1.823909 -v 0.025581 -0.040410 0.101875 -vn -2.541448 -3.326370 1.823909 -v 0.025581 -0.039410 0.101875 -vn -2.163031 3.326412 2.259836 -v 0.025763 -0.040410 0.102084 -vn -2.163031 -3.326412 2.259836 -v 0.025763 -0.039410 0.102084 -vn -1.710948 3.326382 2.618825 -v 0.025980 -0.040410 0.102256 -vn -1.710948 -3.326382 2.618825 -v 0.025980 -0.039410 0.102256 -vn -1.083064 -3.366021 2.927938 -v 0.027147 -0.041010 0.100062 -vn -1.083064 3.366021 2.927938 -v 0.027147 -0.038810 0.100062 -vn -0.404417 -3.365941 3.095542 -v 0.026930 -0.041010 0.100008 -vn -0.404417 3.365941 3.095541 -v 0.026930 -0.038810 0.100008 -vn 0.294506 -3.366018 3.107912 -v 0.026706 -0.041010 0.100004 -vn 0.294506 3.366019 3.107912 -v 0.026706 -0.038810 0.100004 -vn 0.978741 -3.365994 2.964446 -v 0.026486 -0.041010 0.100050 -vn 0.978741 3.365994 2.964446 -v 0.026486 -0.038810 0.100050 -vn 1.613845 -3.365983 2.672338 -v 0.026283 -0.041010 0.100144 -vn 1.613845 3.365983 2.672339 -v 0.026283 -0.038810 0.100144 -vn 2.168039 -3.366008 2.246213 -v 0.026106 -0.041010 0.100280 -vn 2.168038 3.366008 2.246212 -v 0.026106 -0.038810 0.100280 -vn 2.613512 -3.365971 1.707471 -v 0.025963 -0.041010 0.100453 -vn 2.613512 3.365971 1.707471 -v 0.025963 -0.038810 0.100453 -vn 2.927924 -3.366006 1.083108 -v 0.025862 -0.041010 0.100653 -vn 2.927924 3.366006 1.083108 -v 0.025862 -0.038810 0.100653 -vn 3.095534 -3.365989 0.404412 -v 0.025808 -0.041010 0.100870 -vn 3.095535 3.365988 0.404412 -v 0.025808 -0.038810 0.100870 -vn 3.107914 -3.365988 -0.294538 -v 0.025804 -0.041010 0.101094 -vn 3.107914 3.365988 -0.294538 -v 0.025804 -0.038810 0.101094 -vn 2.964452 -3.365992 -0.978724 -v 0.025850 -0.041010 0.101314 -vn 2.964453 3.365992 -0.978724 -v 0.025850 -0.038810 0.101314 -vn 2.672334 -3.366000 -1.613848 -v 0.025944 -0.041010 0.101517 -vn 2.672333 3.366000 -1.613848 -v 0.025944 -0.038810 0.101517 -vn 2.246208 -3.365994 -2.168047 -v 0.026080 -0.041010 0.101694 -vn 2.246208 3.365994 -2.168047 -v 0.026080 -0.038810 0.101694 -vn -0.768542 -2.976269 3.035072 -v 0.026370 -0.041010 0.102696 -vn -1.257605 -2.976228 2.867179 -v 0.026097 -0.041010 0.102603 -vn 1.257683 -2.976231 2.867145 -v 0.027503 -0.041010 0.102603 -vn 0.768583 -2.976240 3.035058 -v 0.027230 -0.041010 0.102696 -vn 0.258541 -2.976248 3.120170 -v 0.026945 -0.041010 0.102744 -vn -0.258543 -2.976247 3.120170 -v 0.026655 -0.041010 0.102744 -vn 2.753517 -2.976243 1.490115 -v 0.028339 -0.041010 0.101833 -vn 2.470700 -2.976249 1.923005 -v 0.028181 -0.041010 0.102075 -vn 2.120486 -2.976242 2.303441 -v 0.027985 -0.041010 0.102288 -vn 1.712448 -2.976261 2.621037 -v 0.027757 -0.041010 0.102465 -vn 3.130862 -2.976244 -0.000020 -v 0.028550 -0.041010 0.101000 -vn 3.088163 -2.976244 0.515310 -v 0.028526 -0.041010 0.101288 -vn 2.961228 -2.976247 1.016577 -v 0.028455 -0.041010 0.101568 -vn 2.120462 -2.976256 -2.303464 -v 0.027985 -0.041010 0.099712 -vn 2.470676 -2.976237 -1.923032 -v 0.028181 -0.041010 0.099925 -vn 2.753505 -2.976249 -1.490139 -v 0.028339 -0.041010 0.100167 -vn 2.961218 -2.976242 -1.016604 -v 0.028455 -0.041010 0.100432 -vn 3.088160 -2.976250 -0.515339 -v 0.028526 -0.041010 0.100712 -vn 2.753517 2.976243 1.490115 -v 0.028339 -0.038810 0.101833 -vn 2.961228 2.976247 1.016577 -v 0.028455 -0.038810 0.101568 -vn 1.257683 2.976231 2.867145 -v 0.027503 -0.038810 0.102603 -vn 1.712448 2.976261 2.621037 -v 0.027757 -0.038810 0.102465 -vn 2.120486 2.976242 2.303440 -v 0.027985 -0.038810 0.102288 -vn 2.470700 2.976249 1.923004 -v 0.028181 -0.038810 0.102075 -vn 2.470676 2.976237 -1.923032 -v 0.028181 -0.038810 0.099925 -vn 2.120462 2.976255 -2.303464 -v 0.027985 -0.038810 0.099712 -vn 3.088163 2.976243 0.515310 -v 0.028526 -0.038810 0.101288 -vn 3.130862 2.976244 -0.000020 -v 0.028550 -0.038810 0.101000 -vn 3.088159 2.976250 -0.515339 -v 0.028526 -0.038810 0.100712 -vn 2.961218 2.976242 -1.016604 -v 0.028455 -0.038810 0.100432 -vn 2.753505 2.976250 -1.490139 -v 0.028339 -0.038810 0.100167 -vn -0.768542 2.976269 3.035072 -v 0.026370 -0.038810 0.102696 -vn -0.258543 2.976247 3.120169 -v 0.026655 -0.038810 0.102744 -vn 0.258541 2.976248 3.120170 -v 0.026945 -0.038810 0.102744 -vn 0.768583 2.976240 3.035058 -v 0.027230 -0.038810 0.102696 -vn -1.257605 2.976228 2.867179 -v 0.026097 -0.038810 0.102603 -vn -1.257605 2.976228 2.867179 -v 0.026097 -0.040410 0.102603 -vn -0.768542 2.976270 3.035072 -v 0.026370 -0.040410 0.102696 -vn -0.258543 2.976247 3.120169 -v 0.026655 -0.040410 0.102744 -vn 0.258541 2.976248 3.120170 -v 0.026945 -0.040410 0.102744 -vn 0.768583 2.976240 3.035058 -v 0.027230 -0.040410 0.102696 -vn 1.257683 2.976231 2.867145 -v 0.027503 -0.040410 0.102603 -vn 1.712448 2.976261 2.621037 -v 0.027757 -0.040410 0.102465 -vn 2.120486 2.976242 2.303440 -v 0.027985 -0.040410 0.102288 -vn 2.470700 2.976249 1.923004 -v 0.028181 -0.040410 0.102075 -vn 2.753517 2.976243 1.490115 -v 0.028339 -0.040410 0.101833 -vn 2.961228 2.976247 1.016577 -v 0.028455 -0.040410 0.101568 -vn 3.088163 2.976244 0.515310 -v 0.028526 -0.040410 0.101288 -vn 3.130862 2.976244 -0.000020 -v 0.028550 -0.040410 0.101000 -vn 3.088159 2.976250 -0.515339 -v 0.028526 -0.040410 0.100712 -vn 2.961218 2.976242 -1.016604 -v 0.028455 -0.040410 0.100432 -vn 2.753505 2.976250 -1.490139 -v 0.028339 -0.040410 0.100167 -vn 2.470676 2.976237 -1.923032 -v 0.028181 -0.040410 0.099925 -vn 2.120462 2.976256 -2.303464 -v 0.027985 -0.040410 0.099712 -vn -1.257605 -2.976228 2.867179 -v 0.026097 -0.039410 0.102603 -vn -0.768542 -2.976270 3.035072 -v 0.026370 -0.039410 0.102696 -vn -0.258543 -2.976247 3.120170 -v 0.026655 -0.039410 0.102744 -vn 0.258541 -2.976248 3.120170 -v 0.026945 -0.039410 0.102744 -vn 0.768583 -2.976240 3.035058 -v 0.027230 -0.039410 0.102696 -vn 1.257683 -2.976231 2.867145 -v 0.027503 -0.039410 0.102603 -vn 1.712448 -2.976261 2.621037 -v 0.027757 -0.039410 0.102465 -vn 2.120486 -2.976242 2.303441 -v 0.027985 -0.039410 0.102288 -vn 2.470700 -2.976249 1.923005 -v 0.028181 -0.039410 0.102075 -vn 2.753517 -2.976243 1.490115 -v 0.028339 -0.039410 0.101833 -vn 2.961228 -2.976247 1.016577 -v 0.028455 -0.039410 0.101568 -vn 3.088163 -2.976244 0.515310 -v 0.028526 -0.039410 0.101288 -vn 3.130862 -2.976243 -0.000020 -v 0.028550 -0.039410 0.101000 -vn 3.088160 -2.976250 -0.515339 -v 0.028526 -0.039410 0.100712 -vn 2.961218 -2.976242 -1.016604 -v 0.028455 -0.039410 0.100432 -vn 2.753505 -2.976250 -1.490139 -v 0.028339 -0.039410 0.100167 -vn 2.470676 -2.976237 -1.923032 -v 0.028181 -0.039410 0.099925 -vn 2.120462 -2.976256 -2.303464 -v 0.027985 -0.039410 0.099712 -vn -1.200585 3.326417 2.888625 -v 0.026224 -0.040410 0.102385 -vn -0.649384 3.326352 3.060051 -v 0.026489 -0.040410 0.102467 -vn -0.076061 3.326421 3.127262 -v 0.026764 -0.040410 0.102500 -vn 0.499918 3.326396 3.087986 -v 0.027040 -0.040410 0.102481 -vn 3.028694 3.326394 -0.782682 -v 0.028252 -0.040410 0.100625 -vn 2.833313 3.326385 -1.325867 -v 0.028159 -0.040410 0.100364 -vn 2.541440 3.326401 -1.823912 -v 0.028019 -0.040410 0.100125 -vn 2.163013 3.326394 -2.259857 -v 0.027837 -0.040410 0.099916 -vn 1.058817 3.326384 2.943552 -v 0.027308 -0.040410 0.102411 -vn 1.581625 3.326370 2.698900 -v 0.027558 -0.040410 0.102294 -vn 2.050623 3.326425 2.362307 -v 0.027783 -0.040410 0.102133 -vn 2.449793 3.326366 1.945281 -v 0.027975 -0.040410 0.101933 -vn 2.765512 3.326407 1.462023 -v 0.028126 -0.040410 0.101701 -vn 2.987077 3.326388 0.928954 -v 0.028232 -0.040410 0.101445 -vn 3.106910 3.326397 0.364263 -v 0.028290 -0.040410 0.101175 -vn 3.120943 3.326390 -0.212836 -v 0.028297 -0.040410 0.100898 -vn 3.028694 -3.326393 -0.782681 -v 0.028252 -0.039410 0.100625 -vn 3.120943 -3.326390 -0.212836 -v 0.028297 -0.039410 0.100898 -vn 3.106910 -3.326396 0.364263 -v 0.028290 -0.039410 0.101175 -vn 2.987077 -3.326388 0.928954 -v 0.028232 -0.039410 0.101445 -vn 2.765512 -3.326407 1.462024 -v 0.028126 -0.039410 0.101701 -vn 2.449793 -3.326366 1.945281 -v 0.027975 -0.039410 0.101933 -vn 2.050623 -3.326425 2.362308 -v 0.027783 -0.039410 0.102133 -vn 1.581625 -3.326370 2.698900 -v 0.027558 -0.039410 0.102294 -vn 1.058817 -3.326384 2.943551 -v 0.027308 -0.039410 0.102411 -vn 0.499918 -3.326396 3.087986 -v 0.027040 -0.039410 0.102481 -vn 2.163013 -3.326394 -2.259857 -v 0.027837 -0.039410 0.099916 -vn 2.541440 -3.326401 -1.823912 -v 0.028019 -0.039410 0.100125 -vn 2.833313 -3.326385 -1.325867 -v 0.028159 -0.039410 0.100364 -vn -0.076061 -3.326421 3.127262 -v 0.026764 -0.039410 0.102500 -vn -0.649384 -3.326352 3.060052 -v 0.026489 -0.039410 0.102467 -vn -1.200585 -3.326417 2.888625 -v 0.026224 -0.039410 0.102385 -vn 1.707466 -3.365983 -2.613513 -v 0.045153 -0.041010 0.101837 -vn 1.707466 3.365983 -2.613513 -v 0.045153 -0.038810 0.101837 -vn 1.083110 -3.365991 -2.927927 -v 0.045353 -0.041010 0.101938 -vn 1.083110 3.365990 -2.927926 -v 0.045353 -0.038810 0.101938 -vn 0.404411 -3.366005 -3.095531 -v 0.045570 -0.041010 0.101992 -vn 0.404411 3.366005 -3.095532 -v 0.045570 -0.038810 0.101992 -vn -0.294508 -3.365952 -3.107924 -v 0.045794 -0.041010 0.101996 -vn -0.294508 3.365952 -3.107924 -v 0.045794 -0.038810 0.101996 -vn -0.978691 -3.366027 -2.964457 -v 0.046014 -0.041010 0.101950 -vn -0.978691 3.366027 -2.964457 -v 0.046014 -0.038810 0.101950 -vn -1.613845 -3.365983 -2.672338 -v 0.046217 -0.041010 0.101856 -vn -1.613845 3.365983 -2.672339 -v 0.046217 -0.038810 0.101856 -vn -2.168045 -3.366015 -2.246205 -v 0.046394 -0.041010 0.101720 -vn -2.168044 3.366015 -2.246204 -v 0.046394 -0.038810 0.101720 -vn -2.613528 -3.365979 -1.707442 -v 0.046537 -0.041010 0.101547 -vn -2.613529 3.365979 -1.707442 -v 0.046537 -0.038810 0.101547 -vn -2.927928 -3.365975 -1.083112 -v 0.046638 -0.041010 0.101347 -vn -2.927929 3.365975 -1.083112 -v 0.046638 -0.038810 0.101347 -vn -3.095529 -3.366013 -0.404423 -v 0.046692 -0.041010 0.101130 -vn -3.095529 3.366013 -0.404423 -v 0.046692 -0.038810 0.101130 -vn -3.107917 -3.365972 0.294539 -v 0.046696 -0.041010 0.100906 -vn -3.107917 3.365972 0.294539 -v 0.046696 -0.038810 0.100906 -vn -2.964455 -3.366000 0.978711 -v 0.046650 -0.041010 0.100686 -vn -2.964456 3.366000 0.978712 -v 0.046650 -0.038810 0.100686 -vn -2.672334 -3.366000 1.613848 -v 0.046556 -0.041010 0.100483 -vn -2.672333 3.365999 1.613848 -v 0.046556 -0.038810 0.100483 -vn -2.246239 -3.365969 2.168021 -v 0.046420 -0.041010 0.100306 -vn -2.246239 3.365969 2.168021 -v 0.046420 -0.038810 0.100306 -vn -1.707486 -3.366016 2.613492 -v 0.046247 -0.041010 0.100163 -vn -1.707486 3.366016 2.613492 -v 0.046247 -0.038810 0.100163 -vn 1.712412 2.976242 -2.621058 -v 0.046657 -0.040410 0.099535 -vn 1.712412 -2.976243 -2.621058 -v 0.046657 -0.041010 0.099535 -vn 1.257646 -2.976249 -2.867164 -v 0.046403 -0.041010 0.099397 -vn 1.257646 2.976249 -2.867164 -v 0.046403 -0.040410 0.099397 -vn 0.768578 -2.976245 -3.035060 -v 0.046130 -0.041010 0.099304 -vn 0.768578 2.976245 -3.035060 -v 0.046130 -0.040410 0.099304 -vn 0.258502 -2.976221 -3.120170 -v 0.045845 -0.041010 0.099256 -vn 0.258502 2.976221 -3.120169 -v 0.045845 -0.040410 0.099256 -vn -0.258583 -2.976273 -3.120169 -v 0.045555 -0.041010 0.099256 -vn -0.258583 2.976273 -3.120170 -v 0.045555 -0.040410 0.099256 -vn -0.768584 -2.976241 -3.035058 -v 0.045270 -0.041010 0.099304 -vn -0.768584 2.976241 -3.035058 -v 0.045270 -0.040410 0.099304 -vn -1.257652 -2.976254 -2.867162 -v 0.044997 -0.041010 0.099397 -vn -1.257652 2.976253 -2.867162 -v 0.044997 -0.040410 0.099397 -vn -1.712422 -2.976234 -2.621050 -v 0.044743 -0.041010 0.099535 -vn -1.712422 2.976234 -2.621050 -v 0.044743 -0.040410 0.099535 -vn -2.120491 -2.976246 -2.303436 -v 0.044515 -0.041010 0.099712 -vn -2.120491 2.976246 -2.303436 -v 0.044515 -0.040410 0.099712 -vn -2.470700 -2.976249 -1.923005 -v 0.044319 -0.041010 0.099925 -vn -2.470700 2.976249 -1.923004 -v 0.044319 -0.040410 0.099925 -vn -2.753523 -2.976233 -1.490100 -v 0.044161 -0.041010 0.100167 -vn -2.753523 2.976233 -1.490100 -v 0.044161 -0.040410 0.100167 -vn -2.961232 -2.976264 -1.016572 -v 0.044045 -0.041010 0.100432 -vn -2.961232 2.976264 -1.016572 -v 0.044045 -0.040410 0.100432 -vn -3.088161 -2.976243 -0.515329 -v 0.043974 -0.041010 0.100712 -vn -3.088160 2.976244 -0.515329 -v 0.043974 -0.040410 0.100712 -vn -3.130861 -2.976233 0.000017 -v 0.043950 -0.041010 0.101000 -vn -3.130861 2.976233 0.000017 -v 0.043950 -0.040410 0.101000 -vn -3.088159 -2.976254 0.515346 -v 0.043974 -0.041010 0.101288 -vn -3.088159 2.976254 0.515346 -v 0.043974 -0.040410 0.101288 -vn -2.961218 -2.976242 1.016604 -v 0.044045 -0.041010 0.101568 -vn -2.961218 2.976242 1.016604 -v 0.044045 -0.040410 0.101568 -vn -2.753500 -2.976244 1.490146 -v 0.044161 -0.041010 0.101833 -vn -2.753500 2.976245 1.490146 -v 0.044161 -0.040410 0.101833 -vn -2.470691 -2.976260 1.923019 -v 0.044319 -0.041010 0.102075 -vn -2.470691 2.976260 1.923019 -v 0.044319 -0.040410 0.102075 -vn -2.120481 -2.976238 2.303444 -v 0.044515 -0.041010 0.102288 -vn -2.120481 2.976238 2.303444 -v 0.044515 -0.040410 0.102288 -vn -1.712412 -2.976242 2.621058 -v 0.044743 -0.041010 0.102465 -vn -1.712412 2.976242 2.621058 -v 0.044743 -0.040410 0.102465 -vn 1.712412 2.976242 -2.621058 -v 0.046657 -0.038810 0.099535 -vn 1.712412 -2.976242 -2.621058 -v 0.046657 -0.039410 0.099535 -vn 1.257646 -2.976249 -2.867164 -v 0.046403 -0.039410 0.099397 -vn 1.257646 2.976249 -2.867164 -v 0.046403 -0.038810 0.099397 -vn 0.768578 -2.976245 -3.035060 -v 0.046130 -0.039410 0.099304 -vn 0.768578 2.976245 -3.035060 -v 0.046130 -0.038810 0.099304 -vn 0.258502 -2.976221 -3.120170 -v 0.045845 -0.039410 0.099256 -vn 0.258502 2.976221 -3.120169 -v 0.045845 -0.038810 0.099256 -vn -0.258583 -2.976273 -3.120169 -v 0.045555 -0.039410 0.099256 -vn -0.258583 2.976273 -3.120170 -v 0.045555 -0.038810 0.099256 -vn -0.768584 -2.976241 -3.035058 -v 0.045270 -0.039410 0.099304 -vn -0.768584 2.976241 -3.035058 -v 0.045270 -0.038810 0.099304 -vn -1.257652 -2.976254 -2.867162 -v 0.044997 -0.039410 0.099397 -vn -1.257652 2.976254 -2.867162 -v 0.044997 -0.038810 0.099397 -vn -1.712422 -2.976234 -2.621050 -v 0.044743 -0.039410 0.099535 -vn -1.712422 2.976234 -2.621050 -v 0.044743 -0.038810 0.099535 -vn -2.120491 -2.976246 -2.303436 -v 0.044515 -0.039410 0.099712 -vn -2.120491 2.976246 -2.303436 -v 0.044515 -0.038810 0.099712 -vn -2.470700 -2.976250 -1.923005 -v 0.044319 -0.039410 0.099925 -vn -2.470700 2.976249 -1.923004 -v 0.044319 -0.038810 0.099925 -vn -2.753523 -2.976233 -1.490100 -v 0.044161 -0.039410 0.100167 -vn -2.753523 2.976233 -1.490100 -v 0.044161 -0.038810 0.100167 -vn -2.961232 -2.976264 -1.016572 -v 0.044045 -0.039410 0.100432 -vn -2.961232 2.976264 -1.016572 -v 0.044045 -0.038810 0.100432 -vn -3.088161 -2.976244 -0.515329 -v 0.043974 -0.039410 0.100712 -vn -3.088160 2.976244 -0.515329 -v 0.043974 -0.038810 0.100712 -vn -3.130861 -2.976233 0.000017 -v 0.043950 -0.039410 0.101000 -vn -3.130861 2.976233 0.000017 -v 0.043950 -0.038810 0.101000 -vn -3.088159 -2.976254 0.515346 -v 0.043974 -0.039410 0.101288 -vn -3.088159 2.976254 0.515346 -v 0.043974 -0.038810 0.101288 -vn -2.961218 -2.976242 1.016604 -v 0.044045 -0.039410 0.101568 -vn -2.961218 2.976242 1.016604 -v 0.044045 -0.038810 0.101568 -vn -2.753500 -2.976245 1.490146 -v 0.044161 -0.039410 0.101833 -vn -2.753500 2.976244 1.490146 -v 0.044161 -0.038810 0.101833 -vn -2.470691 -2.976260 1.923019 -v 0.044319 -0.039410 0.102075 -vn -2.470691 2.976260 1.923019 -v 0.044319 -0.038810 0.102075 -vn -2.120481 -2.976238 2.303444 -v 0.044515 -0.039410 0.102288 -vn -2.120481 2.976238 2.303444 -v 0.044515 -0.038810 0.102288 -vn -1.712412 -2.976242 2.621058 -v 0.044743 -0.039410 0.102465 -vn -1.712412 2.976243 2.621058 -v 0.044743 -0.038810 0.102465 -vn 1.710957 -3.326375 -2.618821 -v 0.046520 -0.039410 0.099744 -vn 1.710957 3.326375 -2.618821 -v 0.046520 -0.040410 0.099744 -vn 1.200627 3.326402 -2.888610 -v 0.046276 -0.040410 0.099615 -vn 1.200626 -3.326402 -2.888610 -v 0.046276 -0.039410 0.099615 -vn 0.649375 3.326401 -3.060046 -v 0.046011 -0.040410 0.099533 -vn 0.649375 -3.326401 -3.060047 -v 0.046011 -0.039410 0.099533 -vn 0.076019 3.326394 -3.127267 -v 0.045736 -0.040410 0.099500 -vn 0.076019 -3.326395 -3.127267 -v 0.045736 -0.039410 0.099500 -vn -0.499879 3.326370 -3.087996 -v 0.045460 -0.040410 0.099519 -vn -0.499879 -3.326370 -3.087996 -v 0.045460 -0.039410 0.099519 -vn -1.058777 3.326411 -2.943562 -v 0.045192 -0.040410 0.099589 -vn -1.058777 -3.326410 -2.943562 -v 0.045192 -0.039410 0.099589 -vn -1.581653 3.326392 -2.698880 -v 0.044942 -0.040410 0.099706 -vn -1.581653 -3.326392 -2.698880 -v 0.044942 -0.039410 0.099706 -vn -2.050636 3.326389 -2.362303 -v 0.044717 -0.040410 0.099867 -vn -2.050636 -3.326389 -2.362303 -v 0.044717 -0.039410 0.099867 -vn -2.449786 3.326389 -1.945285 -v 0.044525 -0.040410 0.100067 -vn -2.449786 -3.326389 -1.945284 -v 0.044525 -0.039410 0.100067 -vn -2.765520 3.326397 -1.462011 -v 0.044374 -0.040410 0.100299 -vn -2.765520 -3.326398 -1.462011 -v 0.044374 -0.039410 0.100299 -vn -2.987077 3.326388 -0.928954 -v 0.044268 -0.040410 0.100555 -vn -2.987077 -3.326388 -0.928954 -v 0.044268 -0.039410 0.100555 -vn -3.106910 3.326396 -0.364263 -v 0.044210 -0.040410 0.100825 -vn -3.106910 -3.326396 -0.364263 -v 0.044210 -0.039410 0.100825 -vn -3.120943 3.326390 0.212836 -v 0.044203 -0.040410 0.101102 -vn -3.120943 -3.326390 0.212836 -v 0.044203 -0.039410 0.101102 -vn -3.028691 3.326400 0.782691 -v 0.044248 -0.040410 0.101375 -vn -3.028691 -3.326400 0.782691 -v 0.044248 -0.039410 0.101375 -vn -2.833299 3.326392 1.325895 -v 0.044341 -0.040410 0.101636 -vn -2.833299 -3.326392 1.325895 -v 0.044341 -0.039410 0.101636 -vn -2.541458 3.326360 1.823897 -v 0.044481 -0.040410 0.101875 -vn -2.541458 -3.326360 1.823897 -v 0.044481 -0.039410 0.101875 -vn -2.163031 3.326430 2.259832 -v 0.044663 -0.040410 0.102084 -vn -2.163031 -3.326430 2.259832 -v 0.044663 -0.039410 0.102084 -vn -1.710947 3.326367 2.618829 -v 0.044880 -0.040410 0.102256 -vn -1.710947 -3.326367 2.618829 -v 0.044880 -0.039410 0.102256 -vn -1.083056 -3.366011 2.927942 -v 0.046047 -0.041010 0.100062 -vn -1.083056 3.366011 2.927943 -v 0.046047 -0.038810 0.100062 -vn -0.404420 -3.365943 3.095541 -v 0.045830 -0.041010 0.100008 -vn -0.404420 3.365943 3.095541 -v 0.045830 -0.038810 0.100008 -vn 0.294506 -3.366019 3.107912 -v 0.045606 -0.041010 0.100004 -vn 0.294506 3.366019 3.107912 -v 0.045606 -0.038810 0.100004 -vn 0.978741 -3.365994 2.964446 -v 0.045386 -0.041010 0.100050 -vn 0.978741 3.365994 2.964446 -v 0.045386 -0.038810 0.100050 -vn 1.613845 -3.365983 2.672338 -v 0.045183 -0.041010 0.100144 -vn 1.613845 3.365983 2.672339 -v 0.045183 -0.038810 0.100144 -vn 2.168045 -3.366015 2.246205 -v 0.045006 -0.041010 0.100280 -vn 2.168044 3.366015 2.246204 -v 0.045006 -0.038810 0.100280 -vn 2.613518 -3.365965 1.707463 -v 0.044863 -0.041010 0.100453 -vn 2.613518 3.365965 1.707463 -v 0.044863 -0.038810 0.100453 -vn 2.927921 -3.365998 1.083120 -v 0.044762 -0.041010 0.100653 -vn 2.927921 3.365998 1.083120 -v 0.044762 -0.038810 0.100653 -vn 3.095531 -3.365988 0.404437 -v 0.044708 -0.041010 0.100870 -vn 3.095531 3.365988 0.404437 -v 0.044708 -0.038810 0.100870 -vn 3.107912 -3.366005 -0.294538 -v 0.044704 -0.041010 0.101094 -vn 3.107911 3.366005 -0.294538 -v 0.044704 -0.038810 0.101094 -vn 2.964449 -3.365984 -0.978736 -v 0.044750 -0.041010 0.101314 -vn 2.964450 3.365984 -0.978737 -v 0.044750 -0.038810 0.101314 -vn 2.672334 -3.366000 -1.613848 -v 0.044844 -0.041010 0.101517 -vn 2.672333 3.366000 -1.613848 -v 0.044844 -0.038810 0.101517 -vn 2.246208 -3.365994 -2.168047 -v 0.044980 -0.041010 0.101694 -vn 2.246208 3.365994 -2.168047 -v 0.044980 -0.038810 0.101694 -vn -0.768542 -2.976269 3.035072 -v 0.045270 -0.041010 0.102696 -vn -1.257609 -2.976225 2.867177 -v 0.044997 -0.041010 0.102603 -vn 1.257677 -2.976227 2.867147 -v 0.046403 -0.041010 0.102603 -vn 0.768578 -2.976245 3.035060 -v 0.046130 -0.041010 0.102696 -vn 0.258543 -2.976247 3.120169 -v 0.045845 -0.041010 0.102744 -vn -0.258543 -2.976247 3.120170 -v 0.045555 -0.041010 0.102744 -vn 2.470700 -2.976249 1.923005 -v 0.047081 -0.041010 0.102075 -vn 2.120491 -2.976246 2.303436 -v 0.046885 -0.041010 0.102288 -vn 1.712453 -2.976257 2.621033 -v 0.046657 -0.041010 0.102465 -vn 2.120462 -2.976256 -2.303464 -v 0.046885 -0.041010 0.099712 -vn 2.470672 -2.976243 -1.923039 -v 0.047081 -0.041010 0.099925 -vn 2.753500 -2.976244 -1.490146 -v 0.047239 -0.041010 0.100167 -vn 2.961221 -2.976236 -1.016594 -v 0.047355 -0.041010 0.100432 -vn 3.088161 -2.976263 -0.515340 -v 0.047426 -0.041010 0.100712 -vn 3.130860 -2.976231 -0.000020 -v 0.047450 -0.041010 0.101000 -vn 3.088163 -2.976250 0.515320 -v 0.047426 -0.041010 0.101288 -vn 2.961228 -2.976247 1.016577 -v 0.047355 -0.041010 0.101568 -vn 2.753517 -2.976243 1.490115 -v 0.047239 -0.041010 0.101833 -vn -1.257609 2.976225 2.867177 -v 0.044997 -0.038810 0.102603 -vn -0.768542 2.976269 3.035072 -v 0.045270 -0.038810 0.102696 -vn -0.258543 2.976247 3.120169 -v 0.045555 -0.038810 0.102744 -vn 0.258543 2.976247 3.120170 -v 0.045845 -0.038810 0.102744 -vn 2.470672 2.976243 -1.923039 -v 0.047081 -0.038810 0.099925 -vn 2.120462 2.976255 -2.303464 -v 0.046885 -0.038810 0.099712 -vn 0.768578 2.976245 3.035060 -v 0.046130 -0.038810 0.102696 -vn 1.257677 2.976227 2.867147 -v 0.046403 -0.038810 0.102603 -vn 1.712453 2.976257 2.621033 -v 0.046657 -0.038810 0.102465 -vn 3.130861 2.976231 -0.000020 -v 0.047450 -0.038810 0.101000 -vn 3.088161 2.976263 -0.515340 -v 0.047426 -0.038810 0.100712 -vn 2.961221 2.976235 -1.016594 -v 0.047355 -0.038810 0.100432 -vn 2.753500 2.976244 -1.490146 -v 0.047239 -0.038810 0.100167 -vn 2.120491 2.976246 2.303436 -v 0.046885 -0.038810 0.102288 -vn 2.470700 2.976249 1.923004 -v 0.047081 -0.038810 0.102075 -vn 2.753517 2.976243 1.490115 -v 0.047239 -0.038810 0.101833 -vn 2.961228 2.976247 1.016577 -v 0.047355 -0.038810 0.101568 -vn 3.088162 2.976250 0.515320 -v 0.047426 -0.038810 0.101288 -vn -1.257609 2.976225 2.867177 -v 0.044997 -0.040410 0.102603 -vn -0.768542 2.976270 3.035072 -v 0.045270 -0.040410 0.102696 -vn -0.258543 2.976247 3.120169 -v 0.045555 -0.040410 0.102744 -vn 0.258543 2.976247 3.120170 -v 0.045845 -0.040410 0.102744 -vn 0.768578 2.976245 3.035060 -v 0.046130 -0.040410 0.102696 -vn 1.257677 2.976227 2.867147 -v 0.046403 -0.040410 0.102603 -vn 1.712453 2.976257 2.621033 -v 0.046657 -0.040410 0.102465 -vn 2.120491 2.976246 2.303436 -v 0.046885 -0.040410 0.102288 -vn 2.470700 2.976250 1.923004 -v 0.047081 -0.040410 0.102075 -vn 2.753517 2.976243 1.490115 -v 0.047239 -0.040410 0.101833 -vn 2.961228 2.976247 1.016577 -v 0.047355 -0.040410 0.101568 -vn 3.088162 2.976250 0.515320 -v 0.047426 -0.040410 0.101288 -vn 3.130861 2.976231 -0.000020 -v 0.047450 -0.040410 0.101000 -vn 3.088161 2.976263 -0.515340 -v 0.047426 -0.040410 0.100712 -vn 2.961221 2.976235 -1.016594 -v 0.047355 -0.040410 0.100432 -vn 2.753500 2.976245 -1.490146 -v 0.047239 -0.040410 0.100167 -vn 2.470672 2.976243 -1.923039 -v 0.047081 -0.040410 0.099925 -vn 2.120462 2.976256 -2.303464 -v 0.046885 -0.040410 0.099712 -vn -1.257609 -2.976225 2.867177 -v 0.044997 -0.039410 0.102603 -vn -0.768542 -2.976270 3.035072 -v 0.045270 -0.039410 0.102696 -vn -0.258543 -2.976247 3.120170 -v 0.045555 -0.039410 0.102744 -vn 0.258543 -2.976247 3.120169 -v 0.045845 -0.039410 0.102744 -vn 0.768578 -2.976245 3.035060 -v 0.046130 -0.039410 0.102696 -vn 1.257677 -2.976226 2.867147 -v 0.046403 -0.039410 0.102603 -vn 1.712453 -2.976257 2.621033 -v 0.046657 -0.039410 0.102465 -vn 2.120491 -2.976246 2.303436 -v 0.046885 -0.039410 0.102288 -vn 2.470700 -2.976250 1.923005 -v 0.047081 -0.039410 0.102075 -vn 2.753517 -2.976243 1.490115 -v 0.047239 -0.039410 0.101833 -vn 2.961228 -2.976247 1.016577 -v 0.047355 -0.039410 0.101568 -vn 3.088163 -2.976250 0.515320 -v 0.047426 -0.039410 0.101288 -vn 3.130860 -2.976231 -0.000020 -v 0.047450 -0.039410 0.101000 -vn 3.088161 -2.976263 -0.515340 -v 0.047426 -0.039410 0.100712 -vn 2.961221 -2.976235 -1.016594 -v 0.047355 -0.039410 0.100432 -vn 2.753500 -2.976245 -1.490146 -v 0.047239 -0.039410 0.100167 -vn 2.470672 -2.976243 -1.923039 -v 0.047081 -0.039410 0.099925 -vn 2.120462 -2.976256 -2.303464 -v 0.046885 -0.039410 0.099712 -vn 0.499917 3.326397 3.087986 -v 0.045940 -0.040410 0.102481 -vn 1.058817 3.326384 2.943552 -v 0.046208 -0.040410 0.102411 -vn 1.581625 3.326370 2.698900 -v 0.046458 -0.040410 0.102294 -vn 2.050628 3.326430 2.362302 -v 0.046683 -0.040410 0.102133 -vn 2.449803 3.326367 1.945268 -v 0.046875 -0.040410 0.101933 -vn 2.765509 3.326389 1.462034 -v 0.047026 -0.040410 0.101701 -vn 2.987073 3.326413 0.928952 -v 0.047132 -0.040410 0.101445 -vn 3.106914 3.326370 0.364264 -v 0.047190 -0.040410 0.101175 -vn 3.120942 3.326403 -0.212815 -v 0.047197 -0.040410 0.100898 -vn 3.028691 3.326400 -0.782691 -v 0.047152 -0.040410 0.100625 -vn 2.833310 3.326378 -1.325876 -v 0.047059 -0.040410 0.100364 -vn 2.541440 3.326401 -1.823912 -v 0.046919 -0.040410 0.100125 -vn 2.163013 3.326394 -2.259857 -v 0.046737 -0.040410 0.099916 -vn -1.200588 3.326427 2.888622 -v 0.045124 -0.040410 0.102385 -vn -0.649381 3.326347 3.060053 -v 0.045389 -0.040410 0.102467 -vn -0.076065 3.326422 3.127262 -v 0.045664 -0.040410 0.102500 -vn 3.028691 -3.326400 -0.782691 -v 0.047152 -0.039410 0.100625 -vn 3.120942 -3.326404 -0.212815 -v 0.047197 -0.039410 0.100898 -vn 3.106914 -3.326370 0.364264 -v 0.047190 -0.039410 0.101175 -vn 2.987074 -3.326414 0.928952 -v 0.047132 -0.039410 0.101445 -vn 2.765509 -3.326389 1.462034 -v 0.047026 -0.039410 0.101701 -vn 2.449803 -3.326367 1.945268 -v 0.046875 -0.039410 0.101933 -vn 2.050628 -3.326430 2.362302 -v 0.046683 -0.039410 0.102133 -vn 1.581625 -3.326370 2.698900 -v 0.046458 -0.039410 0.102294 -vn 1.058817 -3.326384 2.943551 -v 0.046208 -0.039410 0.102411 -vn 0.499917 -3.326397 3.087986 -v 0.045940 -0.039410 0.102481 -vn 2.163013 -3.326394 -2.259857 -v 0.046737 -0.039410 0.099916 -vn 2.541440 -3.326401 -1.823912 -v 0.046919 -0.039410 0.100125 -vn 2.833310 -3.326378 -1.325876 -v 0.047059 -0.039410 0.100364 -vn -0.076065 -3.326422 3.127262 -v 0.045664 -0.039410 0.102500 -vn -0.649381 -3.326347 3.060053 -v 0.045389 -0.039410 0.102467 -vn -1.200588 -3.326427 2.888622 -v 0.045124 -0.039410 0.102385 -vn -0.000003 3.365984 3.121840 -v 0.001400 -0.038810 0.081100 -vn -0.000003 -3.365984 3.121840 -v 0.001400 -0.041010 0.081100 -vn -0.694635 3.365972 3.043581 -v 0.001623 -0.038810 0.081125 -vn -0.694635 -3.365972 3.043580 -v 0.001623 -0.041010 0.081125 -vn -1.354505 3.366034 2.812676 -v 0.001834 -0.038810 0.081199 -vn -1.354505 -3.366034 2.812676 -v 0.001834 -0.041010 0.081199 -vn -1.946459 3.365974 2.440736 -v 0.002023 -0.038810 0.081318 -vn -1.946459 -3.365974 2.440737 -v 0.002023 -0.041010 0.081318 -vn -2.440741 3.365979 1.946452 -v 0.002182 -0.038810 0.081477 -vn -2.440741 -3.365979 1.946452 -v 0.002182 -0.041010 0.081477 -vn -2.812673 3.366013 1.354521 -v 0.002301 -0.038810 0.081666 -vn -2.812673 -3.366013 1.354521 -v 0.002301 -0.041010 0.081666 -vn -3.043572 3.365988 0.694659 -v 0.002375 -0.038810 0.081877 -vn -3.043572 -3.365988 0.694659 -v 0.002375 -0.041010 0.081877 -vn -3.121840 3.365986 0.000000 -v 0.002400 -0.038810 0.082100 -vn -3.121840 -3.365986 0.000000 -v 0.002400 -0.041010 0.082100 -vn -3.043572 3.365987 -0.694659 -v 0.002375 -0.038810 0.082323 -vn -3.043572 -3.365987 -0.694659 -v 0.002375 -0.041010 0.082323 -vn -2.812687 3.365995 -1.354498 -v 0.002301 -0.038810 0.082534 -vn -2.812688 -3.365995 -1.354498 -v 0.002301 -0.041010 0.082534 -vn -2.440756 3.365997 -1.946429 -v 0.002182 -0.038810 0.082723 -vn -2.440756 -3.365997 -1.946429 -v 0.002182 -0.041010 0.082723 -vn -1.946422 3.366002 -2.440761 -v 0.002023 -0.038810 0.082882 -vn -1.946422 -3.366002 -2.440760 -v 0.002023 -0.041010 0.082882 -vn -1.354514 3.365974 -2.812683 -v 0.001834 -0.038810 0.083001 -vn -1.354514 -3.365974 -2.812683 -v 0.001834 -0.041010 0.083001 -vn -0.694682 3.366004 -3.043564 -v 0.001623 -0.038810 0.083075 -vn -0.694682 -3.366003 -3.043564 -v 0.001623 -0.041010 0.083075 -vn -0.000003 3.365984 -3.121840 -v 0.001400 -0.038810 0.083100 -vn -0.000003 -3.365984 -3.121840 -v 0.001400 -0.041010 0.083100 -vn 0.000000 -2.976269 3.130866 -v 0.001400 -0.039410 0.083850 -vn -0.515300 2.976237 3.088164 -v 0.001112 -0.038810 0.083826 -vn -0.515300 -2.976237 3.088164 -v 0.001112 -0.039410 0.083826 -vn -1.016594 2.976236 2.961221 -v 0.000832 -0.038810 0.083755 -vn -1.016594 -2.976236 2.961221 -v 0.000832 -0.039410 0.083755 -vn -1.490146 2.976244 2.753500 -v 0.000567 -0.038810 0.083639 -vn -1.490146 -2.976244 2.753500 -v 0.000567 -0.039410 0.083639 -vn -1.923018 2.976261 2.470691 -v 0.000325 -0.038810 0.083481 -vn -1.923018 -2.976261 2.470692 -v 0.000325 -0.039410 0.083481 -vn -2.303443 2.976237 2.120482 -v 0.000112 -0.038810 0.083285 -vn -2.303443 -2.976238 2.120482 -v 0.000112 -0.039410 0.083285 -vn -2.621049 2.976254 1.712428 -v -0.000065 -0.038810 0.083057 -vn -2.621049 -2.976254 1.712428 -v -0.000065 -0.039410 0.083057 -vn -2.867156 2.976238 1.257661 -v -0.000203 -0.038810 0.082803 -vn -2.867156 -2.976238 1.257661 -v -0.000203 -0.039410 0.082803 -vn -3.035059 2.976247 0.768581 -v -0.000296 -0.038810 0.082530 -vn -3.035059 -2.976247 0.768581 -v -0.000296 -0.039410 0.082530 -vn -3.120169 2.976244 0.258546 -v -0.000344 -0.038810 0.082245 -vn -3.120169 -2.976245 0.258546 -v -0.000344 -0.039410 0.082245 -vn -3.120170 2.976249 -0.258539 -v -0.000344 -0.038810 0.081955 -vn -3.120170 -2.976249 -0.258539 -v -0.000344 -0.039410 0.081955 -vn -3.035056 2.976235 -0.768587 -v -0.000296 -0.038810 0.081670 -vn -3.035056 -2.976235 -0.768587 -v -0.000296 -0.039410 0.081670 -vn -2.867161 2.976259 -1.257657 -v -0.000203 -0.038810 0.081397 -vn -2.867160 -2.976258 -1.257657 -v -0.000203 -0.039410 0.081397 -vn -2.621043 2.976225 -1.712430 -v -0.000065 -0.038810 0.081143 -vn -2.621043 -2.976225 -1.712430 -v -0.000065 -0.039410 0.081143 -vn -2.303450 2.976272 -2.120482 -v 0.000112 -0.038810 0.080915 -vn -2.303450 -2.976272 -2.120481 -v 0.000112 -0.039410 0.080915 -vn -1.923011 2.976220 -2.470690 -v 0.000325 -0.038810 0.080719 -vn -1.923011 -2.976220 -2.470690 -v 0.000325 -0.039410 0.080719 -vn -1.490118 2.976266 -2.753519 -v 0.000567 -0.038810 0.080561 -vn -1.490118 -2.976266 -2.753519 -v 0.000567 -0.039410 0.080561 -vn -1.016594 2.976235 -2.961221 -v 0.000832 -0.038810 0.080445 -vn -1.016594 -2.976235 -2.961221 -v 0.000832 -0.039410 0.080445 -vn -0.515340 2.976263 -3.088161 -v 0.001112 -0.038810 0.080374 -vn -0.515340 -2.976263 -3.088161 -v 0.001112 -0.039410 0.080374 -vn 0.000000 -2.976218 -3.130859 -v 0.001400 -0.039410 0.080350 -vn 0.000000 2.976269 3.130866 -v 0.001400 -0.040410 0.083850 -vn -0.515300 2.976237 3.088164 -v 0.001112 -0.040410 0.083826 -vn -0.515300 -2.976237 3.088164 -v 0.001112 -0.041010 0.083826 -vn -1.016594 2.976235 2.961221 -v 0.000832 -0.040410 0.083755 -vn -1.016594 -2.976236 2.961221 -v 0.000832 -0.041010 0.083755 -vn -1.490146 2.976244 2.753500 -v 0.000567 -0.040410 0.083639 -vn -1.490146 -2.976244 2.753500 -v 0.000567 -0.041010 0.083639 -vn -1.923018 2.976261 2.470691 -v 0.000325 -0.040410 0.083481 -vn -1.923018 -2.976261 2.470692 -v 0.000325 -0.041010 0.083481 -vn -2.303443 2.976237 2.120482 -v 0.000112 -0.040410 0.083285 -vn -2.303443 -2.976237 2.120482 -v 0.000112 -0.041010 0.083285 -vn -2.621049 2.976254 1.712428 -v -0.000065 -0.040410 0.083057 -vn -2.621049 -2.976254 1.712428 -v -0.000065 -0.041010 0.083057 -vn -2.867156 2.976238 1.257661 -v -0.000203 -0.040410 0.082803 -vn -2.867156 -2.976238 1.257661 -v -0.000203 -0.041010 0.082803 -vn -3.035059 2.976248 0.768581 -v -0.000296 -0.040410 0.082530 -vn -3.035059 -2.976247 0.768581 -v -0.000296 -0.041010 0.082530 -vn -3.120169 2.976245 0.258546 -v -0.000344 -0.040410 0.082245 -vn -3.120169 -2.976244 0.258546 -v -0.000344 -0.041010 0.082245 -vn -3.120170 2.976249 -0.258539 -v -0.000344 -0.040410 0.081955 -vn -3.120170 -2.976249 -0.258539 -v -0.000344 -0.041010 0.081955 -vn -3.035056 2.976235 -0.768587 -v -0.000296 -0.040410 0.081670 -vn -3.035056 -2.976235 -0.768587 -v -0.000296 -0.041010 0.081670 -vn -2.867161 2.976259 -1.257657 -v -0.000203 -0.040410 0.081397 -vn -2.867160 -2.976259 -1.257657 -v -0.000203 -0.041010 0.081397 -vn -2.621043 2.976226 -1.712430 -v -0.000065 -0.040410 0.081143 -vn -2.621043 -2.976225 -1.712430 -v -0.000065 -0.041010 0.081143 -vn -2.303450 2.976272 -2.120482 -v 0.000112 -0.040410 0.080915 -vn -2.303450 -2.976272 -2.120481 -v 0.000112 -0.041010 0.080915 -vn -1.923011 2.976220 -2.470690 -v 0.000325 -0.040410 0.080719 -vn -1.923011 -2.976220 -2.470690 -v 0.000325 -0.041010 0.080719 -vn -1.490118 2.976266 -2.753519 -v 0.000567 -0.040410 0.080561 -vn -1.490118 -2.976266 -2.753519 -v 0.000567 -0.041010 0.080561 -vn -1.016594 2.976236 -2.961221 -v 0.000832 -0.040410 0.080445 -vn -1.016594 -2.976235 -2.961221 -v 0.000832 -0.041010 0.080445 -vn -0.515340 2.976263 -3.088161 -v 0.001112 -0.040410 0.080374 -vn -0.515340 -2.976263 -3.088161 -v 0.001112 -0.041010 0.080374 -vn 0.000000 2.976218 -3.130859 -v 0.001400 -0.040410 0.080350 -vn 0.000000 3.326395 3.128191 -v 0.001400 -0.040410 0.083600 -vn -0.000000 -3.326395 3.128191 -v 0.001400 -0.039410 0.083600 -vn -0.574798 -3.326386 3.074930 -v 0.001124 -0.039410 0.083574 -vn -0.574798 3.326386 3.074930 -v 0.001124 -0.040410 0.083574 -vn -1.130016 -3.326391 2.916958 -v 0.000858 -0.039410 0.083499 -vn -1.130016 3.326391 2.916958 -v 0.000858 -0.040410 0.083499 -vn -1.646795 -3.326417 2.659629 -v 0.000610 -0.039410 0.083375 -vn -1.646795 3.326417 2.659629 -v 0.000610 -0.040410 0.083375 -vn -2.107463 -3.326364 2.311754 -v 0.000389 -0.039410 0.083209 -vn -2.107463 3.326364 2.311754 -v 0.000389 -0.040410 0.083209 -vn -2.496350 -3.326412 1.885153 -v 0.000203 -0.039410 0.083004 -vn -2.496350 3.326412 1.885153 -v 0.000203 -0.040410 0.083004 -vn -2.800247 -3.326376 1.394349 -v 0.000057 -0.039410 0.082769 -vn -2.800248 3.326376 1.394349 -v 0.000057 -0.040410 0.082769 -vn -3.008770 -3.326392 0.856088 -v -0.000043 -0.039410 0.082510 -vn -3.008770 3.326392 0.856088 -v -0.000043 -0.040410 0.082510 -vn -3.114845 -3.326398 0.288642 -v -0.000094 -0.039410 0.082238 -vn -3.114845 3.326398 0.288642 -v -0.000094 -0.040410 0.082238 -vn -3.114844 -3.326403 -0.288650 -v -0.000094 -0.039410 0.081962 -vn -3.114844 3.326403 -0.288650 -v -0.000094 -0.040410 0.081962 -vn -3.008774 -3.326377 -0.856081 -v -0.000043 -0.039410 0.081690 -vn -3.008774 3.326377 -0.856081 -v -0.000043 -0.040410 0.081690 -vn -2.800241 -3.326400 -1.394354 -v 0.000057 -0.039410 0.081431 -vn -2.800241 3.326400 -1.394354 -v 0.000057 -0.040410 0.081431 -vn -2.496357 -3.326380 -1.885151 -v 0.000203 -0.039410 0.081196 -vn -2.496357 3.326380 -1.885151 -v 0.000203 -0.040410 0.081196 -vn -2.107455 -3.326404 -2.311754 -v 0.000389 -0.039410 0.080991 -vn -2.107455 3.326404 -2.311753 -v 0.000389 -0.040410 0.080991 -vn -1.646768 -3.326396 -2.659649 -v 0.000610 -0.039410 0.080825 -vn -1.646768 3.326396 -2.659649 -v 0.000610 -0.040410 0.080825 -vn -1.130016 -3.326391 -2.916958 -v 0.000858 -0.039410 0.080701 -vn -1.130016 3.326391 -2.916958 -v 0.000858 -0.040410 0.080701 -vn -0.574798 -3.326386 -3.074930 -v 0.001124 -0.039410 0.080626 -vn -0.574798 3.326386 -3.074930 -v 0.001124 -0.040410 0.080626 -vn 0.000000 -3.326395 -3.128191 -v 0.001400 -0.039410 0.080600 -vn -0.000000 3.326395 -3.128191 -v 0.001400 -0.040410 0.080600 -vn 0.694687 3.366010 -3.043562 -v 0.001177 -0.038810 0.083075 -vn 0.694687 -3.366010 -3.043561 -v 0.001177 -0.041010 0.083075 -vn 1.354522 3.365969 -2.812681 -v 0.000966 -0.038810 0.083001 -vn 1.354522 -3.365969 -2.812681 -v 0.000966 -0.041010 0.083001 -vn 1.946422 3.366002 -2.440760 -v 0.000777 -0.038810 0.082882 -vn 1.946422 -3.366002 -2.440761 -v 0.000777 -0.041010 0.082882 -vn 2.440756 3.365997 -1.946429 -v 0.000618 -0.038810 0.082723 -vn 2.440756 -3.365997 -1.946429 -v 0.000618 -0.041010 0.082723 -vn 2.812688 3.365994 -1.354498 -v 0.000499 -0.038810 0.082534 -vn 2.812687 -3.365995 -1.354498 -v 0.000499 -0.041010 0.082534 -vn 3.043569 3.365971 -0.694684 -v 0.000425 -0.038810 0.082323 -vn 3.043569 -3.365971 -0.694684 -v 0.000425 -0.041010 0.082323 -vn 3.121834 3.366019 0.000000 -v 0.000400 -0.038810 0.082100 -vn 3.121834 -3.366019 -0.000000 -v 0.000400 -0.041010 0.082100 -vn 3.043569 3.365971 0.694684 -v 0.000425 -0.038810 0.081877 -vn 3.043569 -3.365971 0.694684 -v 0.000425 -0.041010 0.081877 -vn 2.812673 3.366013 1.354521 -v 0.000499 -0.038810 0.081666 -vn 2.812673 -3.366013 1.354521 -v 0.000499 -0.041010 0.081666 -vn 2.440741 3.365979 1.946452 -v 0.000618 -0.038810 0.081477 -vn 2.440741 -3.365979 1.946452 -v 0.000618 -0.041010 0.081477 -vn 1.946459 3.365974 2.440737 -v 0.000777 -0.038810 0.081318 -vn 1.946459 -3.365974 2.440736 -v 0.000777 -0.041010 0.081318 -vn 1.354513 3.366028 2.812674 -v 0.000966 -0.038810 0.081199 -vn 1.354513 -3.366028 2.812674 -v 0.000966 -0.041010 0.081199 -vn 0.694641 3.365979 3.043578 -v 0.001177 -0.038810 0.081125 -vn 0.694641 -3.365979 3.043578 -v 0.001177 -0.041010 0.081125 -vn 1.016592 2.976244 -2.961223 -v 0.001968 -0.038810 0.080445 -vn 0.515345 2.976260 -3.088160 -v 0.001688 -0.038810 0.080374 -vn 3.120169 2.976244 0.258546 -v 0.003144 -0.038810 0.082245 -vn 3.120170 2.976249 -0.258539 -v 0.003144 -0.038810 0.081955 -vn 3.035056 2.976235 -0.768587 -v 0.003096 -0.038810 0.081670 -vn 2.867169 2.976270 -1.257641 -v 0.003003 -0.038810 0.081397 -vn 2.621052 2.976214 -1.712415 -v 0.002865 -0.038810 0.081143 -vn 2.303450 2.976272 -2.120481 -v 0.002688 -0.038810 0.080915 -vn 1.923011 2.976220 -2.470690 -v 0.002475 -0.038810 0.080719 -vn 1.490110 2.976261 -2.753522 -v 0.002233 -0.038810 0.080561 -vn 2.621058 2.976242 1.712412 -v 0.002865 -0.038810 0.083057 -vn 2.867164 2.976249 1.257646 -v 0.003003 -0.038810 0.082803 -vn 3.035059 2.976247 0.768581 -v 0.003096 -0.038810 0.082530 -vn 1.016592 2.976244 2.961223 -v 0.001968 -0.038810 0.083755 -vn 1.490139 2.976239 2.753504 -v 0.002233 -0.038810 0.083639 -vn 1.923018 2.976261 2.470692 -v 0.002475 -0.038810 0.083481 -vn 2.303443 2.976237 2.120482 -v 0.002688 -0.038810 0.083285 -vn 0.515304 2.976234 3.088163 -v 0.001688 -0.038810 0.083826 -vn 1.016592 -2.976244 2.961223 -v 0.001968 -0.041010 0.083755 -vn 0.515304 -2.976234 3.088163 -v 0.001688 -0.041010 0.083826 -vn 3.120170 -2.976249 -0.258539 -v 0.003144 -0.041010 0.081955 -vn 3.120169 -2.976244 0.258546 -v 0.003144 -0.041010 0.082245 -vn 3.035059 -2.976247 0.768581 -v 0.003096 -0.041010 0.082530 -vn 2.867164 -2.976249 1.257646 -v 0.003003 -0.041010 0.082803 -vn 2.621058 -2.976242 1.712412 -v 0.002865 -0.041010 0.083057 -vn 2.303443 -2.976237 2.120482 -v 0.002688 -0.041010 0.083285 -vn 1.923018 -2.976261 2.470691 -v 0.002475 -0.041010 0.083481 -vn 1.490139 -2.976239 2.753504 -v 0.002233 -0.041010 0.083639 -vn 2.621051 -2.976214 -1.712415 -v 0.002865 -0.041010 0.081143 -vn 2.867169 -2.976270 -1.257641 -v 0.003003 -0.041010 0.081397 -vn 3.035056 -2.976235 -0.768587 -v 0.003096 -0.041010 0.081670 -vn 0.515345 -2.976260 -3.088160 -v 0.001688 -0.041010 0.080374 -vn 1.016592 -2.976244 -2.961223 -v 0.001968 -0.041010 0.080445 -vn 1.490111 -2.976261 -2.753522 -v 0.002233 -0.041010 0.080561 -vn 1.923011 -2.976220 -2.470690 -v 0.002475 -0.041010 0.080719 -vn 2.303450 -2.976272 -2.120481 -v 0.002688 -0.041010 0.080915 -vn 0.515345 -2.976260 -3.088160 -v 0.001688 -0.039410 0.080374 -vn 1.016592 -2.976244 -2.961223 -v 0.001968 -0.039410 0.080445 -vn 1.490111 -2.976261 -2.753522 -v 0.002233 -0.039410 0.080561 -vn 1.923011 -2.976220 -2.470690 -v 0.002475 -0.039410 0.080719 -vn 2.303450 -2.976272 -2.120481 -v 0.002688 -0.039410 0.080915 -vn 2.621051 -2.976214 -1.712415 -v 0.002865 -0.039410 0.081143 -vn 2.867169 -2.976270 -1.257641 -v 0.003003 -0.039410 0.081397 -vn 3.035056 -2.976235 -0.768587 -v 0.003096 -0.039410 0.081670 -vn 3.120170 -2.976249 -0.258539 -v 0.003144 -0.039410 0.081955 -vn 3.120169 -2.976245 0.258546 -v 0.003144 -0.039410 0.082245 -vn 3.035059 -2.976247 0.768581 -v 0.003096 -0.039410 0.082530 -vn 2.867164 -2.976249 1.257646 -v 0.003003 -0.039410 0.082803 -vn 2.621058 -2.976242 1.712412 -v 0.002865 -0.039410 0.083057 -vn 2.303443 -2.976237 2.120482 -v 0.002688 -0.039410 0.083285 -vn 1.923018 -2.976261 2.470691 -v 0.002475 -0.039410 0.083481 -vn 1.490139 -2.976239 2.753504 -v 0.002233 -0.039410 0.083639 -vn 1.016592 -2.976244 2.961223 -v 0.001968 -0.039410 0.083755 -vn 0.515304 -2.976234 3.088163 -v 0.001688 -0.039410 0.083826 -vn 0.515345 2.976260 -3.088160 -v 0.001688 -0.040410 0.080374 -vn 1.016592 2.976244 -2.961223 -v 0.001968 -0.040410 0.080445 -vn 1.490110 2.976261 -2.753522 -v 0.002233 -0.040410 0.080561 -vn 1.923011 2.976220 -2.470690 -v 0.002475 -0.040410 0.080719 -vn 2.303450 2.976272 -2.120481 -v 0.002688 -0.040410 0.080915 -vn 2.621052 2.976214 -1.712415 -v 0.002865 -0.040410 0.081143 -vn 2.867169 2.976270 -1.257641 -v 0.003003 -0.040410 0.081397 -vn 3.035056 2.976235 -0.768587 -v 0.003096 -0.040410 0.081670 -vn 3.120170 2.976249 -0.258539 -v 0.003144 -0.040410 0.081955 -vn 3.120169 2.976245 0.258546 -v 0.003144 -0.040410 0.082245 -vn 3.035059 2.976247 0.768581 -v 0.003096 -0.040410 0.082530 -vn 2.867164 2.976249 1.257646 -v 0.003003 -0.040410 0.082803 -vn 2.621058 2.976242 1.712412 -v 0.002865 -0.040410 0.083057 -vn 2.303443 2.976238 2.120482 -v 0.002688 -0.040410 0.083285 -vn 1.923018 2.976261 2.470692 -v 0.002475 -0.040410 0.083481 -vn 1.490139 2.976239 2.753504 -v 0.002233 -0.040410 0.083639 -vn 1.016592 2.976244 2.961223 -v 0.001968 -0.040410 0.083755 -vn 0.515304 2.976234 3.088163 -v 0.001688 -0.040410 0.083826 -vn 2.107452 -3.326372 2.311762 -v 0.002411 -0.039410 0.083209 -vn 1.646793 -3.326403 2.659632 -v 0.002190 -0.039410 0.083375 -vn 1.130025 -3.326397 2.916954 -v 0.001942 -0.039410 0.083499 -vn 0.574798 -3.326385 3.074930 -v 0.001676 -0.039410 0.083574 -vn 2.107445 -3.326412 -2.311761 -v 0.002411 -0.039410 0.080991 -vn 2.496357 -3.326380 -1.885151 -v 0.002597 -0.039410 0.081196 -vn 2.800241 -3.326400 -1.394354 -v 0.002743 -0.039410 0.081431 -vn 3.008778 -3.326391 -0.856061 -v 0.002843 -0.039410 0.081690 -vn 3.114848 -3.326390 -0.288630 -v 0.002894 -0.039410 0.081962 -vn 3.114849 -3.326385 0.288622 -v 0.002894 -0.039410 0.082238 -vn 3.008773 -3.326405 0.856068 -v 0.002843 -0.039410 0.082510 -vn 2.800248 -3.326376 1.394349 -v 0.002743 -0.039410 0.082769 -vn 2.496350 -3.326411 1.885153 -v 0.002597 -0.039410 0.083004 -vn 0.574798 -3.326386 -3.074930 -v 0.001676 -0.039410 0.080626 -vn 1.130025 -3.326397 -2.916954 -v 0.001942 -0.039410 0.080701 -vn 1.646766 -3.326382 -2.659653 -v 0.002190 -0.039410 0.080825 -vn 2.107453 3.326373 2.311762 -v 0.002411 -0.040410 0.083209 -vn 2.496350 3.326412 1.885153 -v 0.002597 -0.040410 0.083004 -vn 2.800247 3.326376 1.394349 -v 0.002743 -0.040410 0.082769 -vn 3.008774 3.326405 0.856068 -v 0.002843 -0.040410 0.082510 -vn 3.114849 3.326385 0.288622 -v 0.002894 -0.040410 0.082238 -vn 3.114848 3.326390 -0.288630 -v 0.002894 -0.040410 0.081962 -vn 3.008777 3.326391 -0.856061 -v 0.002843 -0.040410 0.081690 -vn 2.800241 3.326400 -1.394354 -v 0.002743 -0.040410 0.081431 -vn 2.496357 3.326379 -1.885151 -v 0.002597 -0.040410 0.081196 -vn 2.107444 3.326412 -2.311761 -v 0.002411 -0.040410 0.080991 -vn 1.646766 3.326382 -2.659652 -v 0.002190 -0.040410 0.080825 -vn 1.130025 3.326397 -2.916954 -v 0.001942 -0.040410 0.080701 -vn 0.574798 3.326385 -3.074930 -v 0.001676 -0.040410 0.080626 -vn 0.574798 3.326386 3.074930 -v 0.001676 -0.040410 0.083574 -vn 1.130025 3.326397 2.916954 -v 0.001942 -0.040410 0.083499 -vn 1.646793 3.326403 2.659632 -v 0.002190 -0.040410 0.083375 -vn 1.707460 -3.365987 -2.613516 -v 0.010303 -0.042610 0.084056 -vn 1.707460 3.365987 -2.613515 -v 0.010303 -0.040410 0.084056 -vn 1.083107 -3.365985 -2.927928 -v 0.010503 -0.042610 0.084157 -vn 1.083108 3.365984 -2.927929 -v 0.010503 -0.040410 0.084157 -vn 0.404414 -3.366007 -3.095531 -v 0.010720 -0.042610 0.084210 -vn 0.404414 3.366007 -3.095531 -v 0.010720 -0.040410 0.084210 -vn -0.294558 -3.365985 -3.107913 -v 0.010944 -0.042610 0.084214 -vn -0.294558 3.365985 -3.107913 -v 0.010944 -0.040410 0.084214 -vn -0.978741 -3.365994 -2.964446 -v 0.011164 -0.042610 0.084168 -vn -0.978741 3.365994 -2.964446 -v 0.011164 -0.040410 0.084168 -vn -1.613851 -3.365988 -2.672333 -v 0.011367 -0.042610 0.084075 -vn -1.613851 3.365988 -2.672334 -v 0.011367 -0.040410 0.084075 -vn -2.168017 -3.365976 -2.246241 -v 0.011544 -0.042610 0.083938 -vn -2.168017 3.365976 -2.246241 -v 0.011544 -0.040410 0.083938 -vn -2.613495 -3.366014 -1.707484 -v 0.011687 -0.042610 0.083766 -vn -2.613495 3.366014 -1.707483 -v 0.011687 -0.040410 0.083766 -vn -2.927935 -3.365991 -1.083087 -v 0.011788 -0.042610 0.083566 -vn -2.927935 3.365991 -1.083087 -v 0.011788 -0.040410 0.083566 -vn -3.095534 -3.365988 -0.404412 -v 0.011842 -0.042610 0.083348 -vn -3.095534 3.365988 -0.404412 -v 0.011842 -0.040410 0.083348 -vn -3.107913 -3.365991 0.294539 -v 0.011846 -0.042610 0.083124 -vn -3.107914 3.365990 0.294539 -v 0.011846 -0.040410 0.083124 -vn -2.964448 -3.365997 0.978735 -v 0.011800 -0.042610 0.082905 -vn -2.964447 3.365997 0.978735 -v 0.011800 -0.040410 0.082905 -vn -2.672348 -3.365973 1.613831 -v 0.011706 -0.042610 0.082702 -vn -2.672349 3.365973 1.613832 -v 0.011706 -0.040410 0.082702 -vn -2.246221 -3.366020 2.168027 -v 0.011570 -0.042610 0.082524 -vn -2.246220 3.366020 2.168026 -v 0.011570 -0.040410 0.082524 -vn -1.707459 -3.365978 2.613518 -v 0.011397 -0.042610 0.082382 -vn -1.707459 3.365977 2.613518 -v 0.011397 -0.040410 0.082382 -vn 1.712408 2.976239 -2.621060 -v 0.011807 -0.042010 0.081754 -vn 1.712408 -2.976239 -2.621060 -v 0.011807 -0.042610 0.081754 -vn 1.257645 -2.976255 -2.867166 -v 0.011553 -0.042610 0.081616 -vn 1.257645 2.976254 -2.867165 -v 0.011553 -0.042010 0.081616 -vn 0.768581 -2.976243 -3.035058 -v 0.011280 -0.042610 0.081522 -vn 0.768581 2.976243 -3.035059 -v 0.011280 -0.042010 0.081522 -vn 0.258543 -2.976247 -3.120170 -v 0.010995 -0.042610 0.081475 -vn 0.258543 2.976247 -3.120170 -v 0.010995 -0.042010 0.081475 -vn -0.258582 -2.976221 -3.120163 -v 0.010705 -0.042610 0.081475 -vn -0.258582 2.976222 -3.120163 -v 0.010705 -0.042010 0.081475 -vn -0.768621 -2.976269 -3.035052 -v 0.010420 -0.042610 0.081522 -vn -0.768621 2.976269 -3.035052 -v 0.010420 -0.042010 0.081522 -vn -1.257649 -2.976252 -2.867163 -v 0.010147 -0.042610 0.081616 -vn -1.257649 2.976251 -2.867163 -v 0.010147 -0.042010 0.081616 -vn -1.712417 -2.976238 -2.621054 -v 0.009893 -0.042610 0.081754 -vn -1.712417 2.976238 -2.621054 -v 0.009893 -0.042010 0.081754 -vn -2.120491 -2.976237 -2.303435 -v 0.009665 -0.042610 0.081931 -vn -2.120491 2.976237 -2.303435 -v 0.009665 -0.042010 0.081931 -vn -2.470705 -2.976254 -1.922999 -v 0.009469 -0.042610 0.082144 -vn -2.470705 2.976254 -1.922999 -v 0.009469 -0.042010 0.082144 -vn -2.753513 -2.976249 -1.490124 -v 0.009311 -0.042610 0.082386 -vn -2.753513 2.976249 -1.490124 -v 0.009311 -0.042010 0.082386 -vn -2.961227 -2.976235 -1.016576 -v 0.009195 -0.042610 0.082651 -vn -2.961227 2.976235 -1.016576 -v 0.009195 -0.042010 0.082651 -vn -3.088166 -2.976250 -0.515300 -v 0.009124 -0.042610 0.082931 -vn -3.088166 2.976250 -0.515300 -v 0.009124 -0.042010 0.082931 -vn -3.130863 -2.976250 0.000010 -v 0.009100 -0.042610 0.083219 -vn -3.130863 2.976250 0.000010 -v 0.009100 -0.042010 0.083219 -vn -3.088161 -2.976244 0.515329 -v 0.009124 -0.042610 0.083507 -vn -3.088160 2.976244 0.515329 -v 0.009124 -0.042010 0.083507 -vn -2.961218 -2.976242 1.016604 -v 0.009195 -0.042610 0.083787 -vn -2.961218 2.976242 1.016604 -v 0.009195 -0.042010 0.083787 -vn -2.753505 -2.976250 1.490139 -v 0.009311 -0.042610 0.084052 -vn -2.753505 2.976250 1.490139 -v 0.009311 -0.042010 0.084052 -vn -2.470672 -2.976233 1.923037 -v 0.009469 -0.042610 0.084294 -vn -2.470671 2.976232 1.923037 -v 0.009469 -0.042010 0.084294 -vn -2.120457 -2.976260 2.303470 -v 0.009665 -0.042610 0.084506 -vn -2.120457 2.976260 2.303470 -v 0.009665 -0.042010 0.084506 -vn -1.712412 -2.976242 2.621058 -v 0.009893 -0.042610 0.084684 -vn -1.712412 2.976243 2.621058 -v 0.009893 -0.042010 0.084684 -vn 1.712408 2.976239 -2.621060 -v 0.011807 -0.040410 0.081754 -vn 1.712408 -2.976239 -2.621060 -v 0.011807 -0.041010 0.081754 -vn 1.257644 -2.976254 -2.867165 -v 0.011553 -0.041010 0.081616 -vn 1.257645 2.976254 -2.867165 -v 0.011553 -0.040410 0.081616 -vn 0.768581 -2.976243 -3.035059 -v 0.011280 -0.041010 0.081522 -vn 0.768581 2.976243 -3.035059 -v 0.011280 -0.040410 0.081522 -vn 0.258543 -2.976247 -3.120170 -v 0.010995 -0.041010 0.081475 -vn 0.258543 2.976247 -3.120169 -v 0.010995 -0.040410 0.081475 -vn -0.258582 -2.976222 -3.120163 -v 0.010705 -0.041010 0.081475 -vn -0.258582 2.976221 -3.120162 -v 0.010705 -0.040410 0.081475 -vn -0.768621 -2.976269 -3.035052 -v 0.010420 -0.041010 0.081522 -vn -0.768621 2.976269 -3.035052 -v 0.010420 -0.040410 0.081522 -vn -1.257649 -2.976251 -2.867163 -v 0.010147 -0.041010 0.081616 -vn -1.257649 2.976252 -2.867163 -v 0.010147 -0.040410 0.081616 -vn -1.712417 -2.976238 -2.621054 -v 0.009893 -0.041010 0.081754 -vn -1.712417 2.976238 -2.621054 -v 0.009893 -0.040410 0.081754 -vn -2.120491 -2.976237 -2.303435 -v 0.009665 -0.041010 0.081931 -vn -2.120491 2.976237 -2.303435 -v 0.009665 -0.040410 0.081931 -vn -2.470705 -2.976254 -1.922999 -v 0.009469 -0.041010 0.082144 -vn -2.470705 2.976254 -1.922999 -v 0.009469 -0.040410 0.082144 -vn -2.753513 -2.976249 -1.490124 -v 0.009311 -0.041010 0.082386 -vn -2.753513 2.976250 -1.490124 -v 0.009311 -0.040410 0.082386 -vn -2.961227 -2.976235 -1.016576 -v 0.009195 -0.041010 0.082651 -vn -2.961227 2.976235 -1.016576 -v 0.009195 -0.040410 0.082651 -vn -3.088166 -2.976250 -0.515300 -v 0.009124 -0.041010 0.082931 -vn -3.088166 2.976250 -0.515300 -v 0.009124 -0.040410 0.082931 -vn -3.130863 -2.976250 0.000010 -v 0.009100 -0.041010 0.083219 -vn -3.130863 2.976250 0.000010 -v 0.009100 -0.040410 0.083219 -vn -3.088160 -2.976244 0.515329 -v 0.009124 -0.041010 0.083507 -vn -3.088160 2.976244 0.515329 -v 0.009124 -0.040410 0.083507 -vn -2.961218 -2.976242 1.016604 -v 0.009195 -0.041010 0.083787 -vn -2.961218 2.976242 1.016604 -v 0.009195 -0.040410 0.083787 -vn -2.753505 -2.976250 1.490139 -v 0.009311 -0.041010 0.084052 -vn -2.753505 2.976250 1.490139 -v 0.009311 -0.040410 0.084052 -vn -2.470671 -2.976233 1.923037 -v 0.009469 -0.041010 0.084294 -vn -2.470671 2.976233 1.923037 -v 0.009469 -0.040410 0.084294 -vn -2.120457 -2.976260 2.303470 -v 0.009665 -0.041010 0.084506 -vn -2.120457 2.976260 2.303470 -v 0.009665 -0.040410 0.084506 -vn -1.712412 -2.976243 2.621058 -v 0.009893 -0.041010 0.084684 -vn -1.712412 2.976242 2.621058 -v 0.009893 -0.040410 0.084684 -vn 1.710947 -3.326375 -2.618827 -v 0.011670 -0.041010 0.081963 -vn 1.710947 3.326375 -2.618827 -v 0.011670 -0.042010 0.081963 -vn 1.200625 3.326397 -2.888611 -v 0.011426 -0.042010 0.081834 -vn 1.200625 -3.326396 -2.888611 -v 0.011426 -0.041010 0.081834 -vn 0.649379 3.326402 -3.060045 -v 0.011161 -0.042010 0.081751 -vn 0.649379 -3.326402 -3.060045 -v 0.011161 -0.041010 0.081751 -vn 0.076021 3.326395 -3.127267 -v 0.010886 -0.042010 0.081719 -vn 0.076021 -3.326395 -3.127267 -v 0.010886 -0.041010 0.081719 -vn -0.499881 3.326372 -3.087996 -v 0.010610 -0.042010 0.081738 -vn -0.499881 -3.326372 -3.087996 -v 0.010610 -0.041010 0.081738 -vn -1.058780 3.326409 -2.943561 -v 0.010342 -0.042010 0.081807 -vn -1.058780 -3.326409 -2.943561 -v 0.010342 -0.041010 0.081807 -vn -1.581653 3.326392 -2.698880 -v 0.010092 -0.042010 0.081925 -vn -1.581653 -3.326392 -2.698880 -v 0.010092 -0.041010 0.081925 -vn -2.050625 3.326379 -2.362314 -v 0.009867 -0.042010 0.082086 -vn -2.050625 -3.326379 -2.362314 -v 0.009867 -0.041010 0.082086 -vn -2.449785 3.326410 -1.945281 -v 0.009675 -0.042010 0.082286 -vn -2.449785 -3.326410 -1.945281 -v 0.009675 -0.041010 0.082286 -vn -2.765529 3.326386 -1.461997 -v 0.009524 -0.042010 0.082518 -vn -2.765529 -3.326386 -1.461997 -v 0.009524 -0.041010 0.082518 -vn -2.987075 3.326382 -0.928962 -v 0.009418 -0.042010 0.082773 -vn -2.987075 -3.326382 -0.928962 -v 0.009418 -0.041010 0.082773 -vn -3.106908 3.326403 -0.364270 -v 0.009360 -0.042010 0.083044 -vn -3.106908 -3.326403 -0.364270 -v 0.009360 -0.041010 0.083044 -vn -3.120943 3.326387 0.212833 -v 0.009353 -0.042010 0.083321 -vn -3.120944 -3.326387 0.212833 -v 0.009353 -0.041010 0.083321 -vn -3.028700 3.326387 0.782665 -v 0.009398 -0.042010 0.083594 -vn -3.028699 -3.326386 0.782664 -v 0.009398 -0.041010 0.083594 -vn -2.833307 3.326407 1.325872 -v 0.009491 -0.042010 0.083855 -vn -2.833307 -3.326407 1.325872 -v 0.009491 -0.041010 0.083855 -vn -2.541430 3.326387 1.823930 -v 0.009631 -0.042010 0.084093 -vn -2.541430 -3.326388 1.823930 -v 0.009631 -0.041010 0.084093 -vn -2.163013 3.326394 2.259857 -v 0.009813 -0.042010 0.084302 -vn -2.163013 -3.326394 2.259856 -v 0.009813 -0.041010 0.084302 -vn -1.710948 3.326382 2.618825 -v 0.010030 -0.042010 0.084475 -vn -1.710948 -3.326382 2.618825 -v 0.010030 -0.041010 0.084475 -vn -1.083113 -3.365989 2.927926 -v 0.011197 -0.042610 0.082281 -vn -1.083113 3.365989 2.927926 -v 0.011197 -0.040410 0.082281 -vn -0.404414 -3.366007 3.095531 -v 0.010980 -0.042610 0.082227 -vn -0.404414 3.366007 3.095531 -v 0.010980 -0.040410 0.082227 -vn 0.294558 -3.365985 3.107913 -v 0.010756 -0.042610 0.082223 -vn 0.294558 3.365985 3.107913 -v 0.010756 -0.040410 0.082223 -vn 0.978741 -3.365994 2.964446 -v 0.010536 -0.042610 0.082269 -vn 0.978741 3.365994 2.964446 -v 0.010536 -0.040410 0.082269 -vn 1.613851 -3.365988 2.672333 -v 0.010333 -0.042610 0.082363 -vn 1.613851 3.365988 2.672334 -v 0.010333 -0.040410 0.082363 -vn 2.168017 -3.365976 2.246241 -v 0.010156 -0.042610 0.082499 -vn 2.168017 3.365976 2.246241 -v 0.010156 -0.040410 0.082499 -vn 2.613495 -3.366014 1.707484 -v 0.010013 -0.042610 0.082672 -vn 2.613495 3.366014 1.707483 -v 0.010013 -0.040410 0.082672 -vn 2.927935 -3.365991 1.083087 -v 0.009912 -0.042610 0.082872 -vn 2.927935 3.365992 1.083087 -v 0.009912 -0.040410 0.082872 -vn 3.095534 -3.365988 0.404412 -v 0.009858 -0.042610 0.083089 -vn 3.095534 3.365988 0.404412 -v 0.009858 -0.040410 0.083089 -vn 3.107913 -3.365990 -0.294539 -v 0.009854 -0.042610 0.083313 -vn 3.107914 3.365990 -0.294539 -v 0.009854 -0.040410 0.083313 -vn 2.964448 -3.365997 -0.978735 -v 0.009900 -0.042610 0.083532 -vn 2.964447 3.365997 -0.978735 -v 0.009900 -0.040410 0.083532 -vn 2.672348 -3.365973 -1.613831 -v 0.009994 -0.042610 0.083736 -vn 2.672349 3.365973 -1.613832 -v 0.009994 -0.040410 0.083736 -vn 2.246227 -3.366014 -2.168022 -v 0.010130 -0.042610 0.083913 -vn 2.246227 3.366014 -2.168022 -v 0.010130 -0.040410 0.083913 -vn 1.257649 -2.976252 2.867163 -v 0.011553 -0.042610 0.084821 -vn 0.768621 -2.976269 3.035052 -v 0.011280 -0.042610 0.084915 -vn 0.258582 -2.976221 3.120163 -v 0.010995 -0.042610 0.084963 -vn 2.470705 -2.976254 1.922999 -v 0.012231 -0.042610 0.084294 -vn 2.120491 -2.976237 2.303435 -v 0.012035 -0.042610 0.084506 -vn 1.712417 -2.976238 2.621054 -v 0.011807 -0.042610 0.084684 -vn 3.130862 -2.976243 -0.000020 -v 0.012600 -0.042610 0.083219 -vn 3.088164 -2.976243 0.515310 -v 0.012576 -0.042610 0.083507 -vn 2.961228 -2.976247 1.016577 -v 0.012505 -0.042610 0.083787 -vn 2.753517 -2.976243 1.490115 -v 0.012389 -0.042610 0.084052 -vn -0.258543 -2.976247 3.120170 -v 0.010705 -0.042610 0.084963 -vn -0.768578 -2.976245 3.035059 -v 0.010420 -0.042610 0.084915 -vn -1.257646 -2.976249 2.867164 -v 0.010147 -0.042610 0.084821 -vn 2.120457 -2.976260 -2.303470 -v 0.012035 -0.042610 0.081931 -vn 2.470672 -2.976233 -1.923037 -v 0.012231 -0.042610 0.082144 -vn 2.753509 -2.976244 -1.490131 -v 0.012389 -0.042610 0.082386 -vn 2.961222 -2.976248 -1.016595 -v 0.012505 -0.042610 0.082651 -vn 3.088160 -2.976250 -0.515339 -v 0.012576 -0.042610 0.082931 -vn 1.257649 2.976252 2.867163 -v 0.011553 -0.040410 0.084821 -vn 1.712417 2.976238 2.621054 -v 0.011807 -0.040410 0.084684 -vn -0.768578 2.976245 3.035060 -v 0.010420 -0.040410 0.084915 -vn -0.258543 2.976247 3.120169 -v 0.010705 -0.040410 0.084963 -vn 0.258582 2.976221 3.120162 -v 0.010995 -0.040410 0.084963 -vn 0.768621 2.976269 3.035052 -v 0.011280 -0.040410 0.084915 -vn -1.257646 2.976249 2.867164 -v 0.010147 -0.040410 0.084821 -vn 2.470671 2.976233 -1.923037 -v 0.012231 -0.040410 0.082144 -vn 2.120457 2.976260 -2.303470 -v 0.012035 -0.040410 0.081931 -vn 3.130862 2.976243 -0.000020 -v 0.012600 -0.040410 0.083219 -vn 3.088159 2.976250 -0.515339 -v 0.012576 -0.040410 0.082931 -vn 2.961222 2.976248 -1.016595 -v 0.012505 -0.040410 0.082651 -vn 2.753509 2.976244 -1.490130 -v 0.012389 -0.040410 0.082386 -vn 2.120491 2.976237 2.303435 -v 0.012035 -0.040410 0.084506 -vn 2.470705 2.976254 1.922999 -v 0.012231 -0.040410 0.084294 -vn 2.753517 2.976243 1.490115 -v 0.012389 -0.040410 0.084052 -vn 2.961228 2.976247 1.016577 -v 0.012505 -0.040410 0.083787 -vn 3.088163 2.976243 0.515310 -v 0.012576 -0.040410 0.083507 -vn -1.257646 2.976249 2.867164 -v 0.010147 -0.042010 0.084821 -vn -0.768578 2.976245 3.035060 -v 0.010420 -0.042010 0.084915 -vn -0.258543 2.976247 3.120170 -v 0.010705 -0.042010 0.084963 -vn 0.258582 2.976222 3.120163 -v 0.010995 -0.042010 0.084963 -vn 0.768621 2.976269 3.035052 -v 0.011280 -0.042010 0.084915 -vn 1.257649 2.976251 2.867163 -v 0.011553 -0.042010 0.084821 -vn 1.712417 2.976238 2.621054 -v 0.011807 -0.042010 0.084684 -vn 2.120491 2.976237 2.303435 -v 0.012035 -0.042010 0.084506 -vn 2.470705 2.976254 1.922999 -v 0.012231 -0.042010 0.084294 -vn 2.753517 2.976243 1.490115 -v 0.012389 -0.042010 0.084052 -vn 2.961228 2.976247 1.016577 -v 0.012505 -0.042010 0.083787 -vn 3.088164 2.976244 0.515310 -v 0.012576 -0.042010 0.083507 -vn 3.130862 2.976244 -0.000020 -v 0.012600 -0.042010 0.083219 -vn 3.088159 2.976250 -0.515339 -v 0.012576 -0.042010 0.082931 -vn 2.961222 2.976248 -1.016595 -v 0.012505 -0.042010 0.082651 -vn 2.753509 2.976244 -1.490131 -v 0.012389 -0.042010 0.082386 -vn 2.470671 2.976233 -1.923037 -v 0.012231 -0.042010 0.082144 -vn 2.120457 2.976260 -2.303470 -v 0.012035 -0.042010 0.081931 -vn -1.257646 -2.976249 2.867164 -v 0.010147 -0.041010 0.084821 -vn -0.768578 -2.976245 3.035060 -v 0.010420 -0.041010 0.084915 -vn -0.258543 -2.976247 3.120170 -v 0.010705 -0.041010 0.084963 -vn 0.258582 -2.976222 3.120163 -v 0.010995 -0.041010 0.084963 -vn 0.768621 -2.976269 3.035052 -v 0.011280 -0.041010 0.084915 -vn 1.257649 -2.976251 2.867163 -v 0.011553 -0.041010 0.084821 -vn 1.712417 -2.976238 2.621054 -v 0.011807 -0.041010 0.084684 -vn 2.120491 -2.976237 2.303435 -v 0.012035 -0.041010 0.084506 -vn 2.470705 -2.976254 1.922999 -v 0.012231 -0.041010 0.084294 -vn 2.753517 -2.976243 1.490115 -v 0.012389 -0.041010 0.084052 -vn 2.961228 -2.976247 1.016577 -v 0.012505 -0.041010 0.083787 -vn 3.088163 -2.976244 0.515310 -v 0.012576 -0.041010 0.083507 -vn 3.130862 -2.976243 -0.000020 -v 0.012600 -0.041010 0.083219 -vn 3.088160 -2.976250 -0.515339 -v 0.012576 -0.041010 0.082931 -vn 2.961222 -2.976248 -1.016595 -v 0.012505 -0.041010 0.082651 -vn 2.753509 -2.976244 -1.490131 -v 0.012389 -0.041010 0.082386 -vn 2.470671 -2.976233 -1.923037 -v 0.012231 -0.041010 0.082144 -vn 2.120457 -2.976260 -2.303470 -v 0.012035 -0.041010 0.081931 -vn 3.028699 3.326385 -0.782668 -v 0.012302 -0.042010 0.082843 -vn 2.833307 3.326407 -1.325872 -v 0.012209 -0.042010 0.082583 -vn 2.541435 3.326383 -1.823924 -v 0.012069 -0.042010 0.082344 -vn 2.163013 3.326403 -2.259855 -v 0.011887 -0.042010 0.082135 -vn -1.200624 3.326392 2.888613 -v 0.010274 -0.042010 0.084604 -vn -0.649381 3.326405 3.060044 -v 0.010539 -0.042010 0.084686 -vn -0.076019 3.326394 3.127267 -v 0.010814 -0.042010 0.084718 -vn 0.499879 3.326370 3.087996 -v 0.011090 -0.042010 0.084700 -vn 1.058777 3.326410 2.943562 -v 0.011358 -0.042010 0.084630 -vn 1.581653 3.326392 2.698880 -v 0.011608 -0.042010 0.084513 -vn 2.050631 3.326384 2.362308 -v 0.011833 -0.042010 0.084352 -vn 2.449786 3.326400 1.945282 -v 0.012025 -0.042010 0.084152 -vn 2.765518 3.326382 1.462019 -v 0.012176 -0.042010 0.083920 -vn 2.987071 3.326398 0.928969 -v 0.012282 -0.042010 0.083664 -vn 3.106910 3.326397 0.364263 -v 0.012340 -0.042010 0.083393 -vn 3.120943 3.326390 -0.212836 -v 0.012347 -0.042010 0.083117 -vn 0.499879 -3.326370 3.087996 -v 0.011090 -0.041010 0.084700 -vn -0.076019 -3.326395 3.127267 -v 0.010814 -0.041010 0.084718 -vn -0.649381 -3.326405 3.060045 -v 0.010539 -0.041010 0.084686 -vn -1.200624 -3.326391 2.888613 -v 0.010274 -0.041010 0.084604 -vn 3.028699 -3.326384 -0.782668 -v 0.012302 -0.041010 0.082843 -vn 3.120943 -3.326390 -0.212836 -v 0.012347 -0.041010 0.083117 -vn 3.106910 -3.326396 0.364263 -v 0.012340 -0.041010 0.083393 -vn 2.987071 -3.326398 0.928969 -v 0.012282 -0.041010 0.083664 -vn 2.765518 -3.326382 1.462019 -v 0.012176 -0.041010 0.083920 -vn 2.449785 -3.326400 1.945282 -v 0.012025 -0.041010 0.084152 -vn 2.050631 -3.326384 2.362308 -v 0.011833 -0.041010 0.084352 -vn 1.581653 -3.326392 2.698880 -v 0.011608 -0.041010 0.084513 -vn 1.058777 -3.326410 2.943562 -v 0.011358 -0.041010 0.084630 -vn 2.163013 -3.326403 -2.259855 -v 0.011887 -0.041010 0.082135 -vn 2.541435 -3.326382 -1.823924 -v 0.012069 -0.041010 0.082344 -vn 2.833307 -3.326407 -1.325872 -v 0.012209 -0.041010 0.082583 -vn 0.000003 3.365984 3.121840 -v 0.002519 -0.040410 0.090550 -vn 0.000003 -3.365984 3.121840 -v 0.002519 -0.042610 0.090550 -vn -0.694687 3.366011 3.043562 -v 0.002741 -0.040410 0.090575 -vn -0.694687 -3.366011 3.043561 -v 0.002741 -0.042610 0.090575 -vn -1.354522 3.365969 2.812681 -v 0.002953 -0.040410 0.090649 -vn -1.354522 -3.365969 2.812681 -v 0.002953 -0.042610 0.090649 -vn -1.946409 3.365991 2.440773 -v 0.003142 -0.040410 0.090768 -vn -1.946409 -3.365990 2.440773 -v 0.003142 -0.042610 0.090768 -vn -2.440754 3.366023 1.946423 -v 0.003301 -0.040410 0.090927 -vn -2.440755 -3.366023 1.946423 -v 0.003301 -0.042610 0.090927 -vn -2.812691 3.365965 1.354502 -v 0.003420 -0.040410 0.091116 -vn -2.812691 -3.365965 1.354502 -v 0.003420 -0.042610 0.091116 -vn -3.043564 3.366003 0.694682 -v 0.003494 -0.040410 0.091327 -vn -3.043564 -3.366003 0.694682 -v 0.003494 -0.042610 0.091327 -vn -3.121840 3.365986 0.000000 -v 0.003519 -0.040410 0.091550 -vn -3.121840 -3.365986 0.000000 -v 0.003519 -0.042610 0.091550 -vn -3.043564 3.366004 -0.694682 -v 0.003494 -0.040410 0.091773 -vn -3.043564 -3.366004 -0.694682 -v 0.003494 -0.042610 0.091773 -vn -2.812676 3.365983 -1.354526 -v 0.003420 -0.040410 0.091984 -vn -2.812676 -3.365983 -1.354526 -v 0.003420 -0.042610 0.091984 -vn -2.440740 3.366005 -1.946446 -v 0.003301 -0.040410 0.092173 -vn -2.440740 -3.366005 -1.946446 -v 0.003301 -0.042610 0.092173 -vn -1.946446 3.365962 -2.440750 -v 0.003142 -0.040410 0.092332 -vn -1.946446 -3.365962 -2.440750 -v 0.003142 -0.042610 0.092332 -vn -1.354513 3.366028 -2.812674 -v 0.002953 -0.040410 0.092451 -vn -1.354513 -3.366028 -2.812674 -v 0.002953 -0.042610 0.092451 -vn -0.694641 3.365979 -3.043578 -v 0.002741 -0.040410 0.092525 -vn -0.694641 -3.365979 -3.043578 -v 0.002741 -0.042610 0.092525 -vn 0.000003 3.365984 -3.121840 -v 0.002519 -0.040410 0.092550 -vn 0.000003 -3.365984 -3.121840 -v 0.002519 -0.042610 0.092550 -vn -0.000002 -2.976219 3.130859 -v 0.002519 -0.041010 0.093300 -vn -0.515345 2.976260 3.088160 -v 0.002231 -0.040410 0.093276 -vn -0.515345 -2.976260 3.088160 -v 0.002231 -0.041010 0.093276 -vn -1.016592 2.976244 2.961223 -v 0.001951 -0.040410 0.093205 -vn -1.016592 -2.976244 2.961223 -v 0.001951 -0.041010 0.093205 -vn -1.490120 2.976254 2.753516 -v 0.001686 -0.040410 0.093089 -vn -1.490120 -2.976254 2.753516 -v 0.001686 -0.041010 0.093089 -vn -1.923010 2.976236 2.470693 -v 0.001444 -0.040410 0.092931 -vn -1.923011 -2.976236 2.470693 -v 0.001444 -0.041010 0.092931 -vn -2.303440 2.976264 2.120491 -v 0.001231 -0.040410 0.092735 -vn -2.303440 -2.976264 2.120491 -v 0.001231 -0.041010 0.092735 -vn -2.621052 2.976214 1.712415 -v 0.001054 -0.040410 0.092507 -vn -2.621052 -2.976214 1.712415 -v 0.001054 -0.041010 0.092507 -vn -2.867169 2.976270 1.257641 -v 0.000916 -0.040410 0.092253 -vn -2.867169 -2.976270 1.257641 -v 0.000916 -0.041010 0.092253 -vn -3.035056 2.976235 0.768587 -v 0.000822 -0.040410 0.091980 -vn -3.035056 -2.976235 0.768587 -v 0.000822 -0.041010 0.091980 -vn -3.120170 2.976249 0.258539 -v 0.000775 -0.040410 0.091695 -vn -3.120170 -2.976249 0.258539 -v 0.000775 -0.041010 0.091695 -vn -3.120169 2.976244 -0.258546 -v 0.000775 -0.040410 0.091405 -vn -3.120169 -2.976245 -0.258546 -v 0.000775 -0.041010 0.091405 -vn -3.035059 2.976247 -0.768581 -v 0.000822 -0.040410 0.091120 -vn -3.035059 -2.976247 -0.768581 -v 0.000822 -0.041010 0.091120 -vn -2.867164 2.976249 -1.257645 -v 0.000916 -0.040410 0.090847 -vn -2.867164 -2.976249 -1.257645 -v 0.000916 -0.041010 0.090847 -vn -2.621058 2.976242 -1.712412 -v 0.001054 -0.040410 0.090593 -vn -2.621058 -2.976242 -1.712412 -v 0.001054 -0.041010 0.090593 -vn -2.303433 2.976229 -2.120491 -v 0.001231 -0.040410 0.090365 -vn -2.303433 -2.976229 -2.120491 -v 0.001231 -0.041010 0.090365 -vn -1.923017 2.976277 -2.470695 -v 0.001444 -0.040410 0.090169 -vn -1.923017 -2.976277 -2.470695 -v 0.001444 -0.041010 0.090169 -vn -1.490148 2.976232 -2.753498 -v 0.001686 -0.040410 0.090011 -vn -1.490148 -2.976233 -2.753497 -v 0.001686 -0.041010 0.090011 -vn -1.016592 2.976244 -2.961223 -v 0.001951 -0.040410 0.089895 -vn -1.016592 -2.976244 -2.961223 -v 0.001951 -0.041010 0.089895 -vn -0.515304 2.976234 -3.088163 -v 0.002231 -0.040410 0.089824 -vn -0.515304 -2.976234 -3.088163 -v 0.002231 -0.041010 0.089824 -vn -0.000002 -2.976270 -3.130866 -v 0.002519 -0.041010 0.089800 -vn -0.000002 2.976219 3.130859 -v 0.002519 -0.042010 0.093300 -vn -0.515345 2.976260 3.088160 -v 0.002231 -0.042010 0.093276 -vn -0.515345 -2.976260 3.088160 -v 0.002231 -0.042610 0.093276 -vn -1.016592 2.976244 2.961223 -v 0.001951 -0.042010 0.093205 -vn -1.016592 -2.976244 2.961223 -v 0.001951 -0.042610 0.093205 -vn -1.490120 2.976254 2.753516 -v 0.001686 -0.042010 0.093089 -vn -1.490120 -2.976254 2.753516 -v 0.001686 -0.042610 0.093089 -vn -1.923010 2.976236 2.470693 -v 0.001444 -0.042010 0.092931 -vn -1.923010 -2.976236 2.470693 -v 0.001444 -0.042610 0.092931 -vn -2.303440 2.976263 2.120491 -v 0.001231 -0.042010 0.092735 -vn -2.303440 -2.976264 2.120491 -v 0.001231 -0.042610 0.092735 -vn -2.621052 2.976214 1.712415 -v 0.001054 -0.042010 0.092507 -vn -2.621052 -2.976214 1.712414 -v 0.001054 -0.042610 0.092507 -vn -2.867169 2.976270 1.257641 -v 0.000916 -0.042010 0.092253 -vn -2.867169 -2.976270 1.257641 -v 0.000916 -0.042610 0.092253 -vn -3.035056 2.976235 0.768587 -v 0.000822 -0.042010 0.091980 -vn -3.035056 -2.976235 0.768587 -v 0.000822 -0.042610 0.091980 -vn -3.120170 2.976249 0.258539 -v 0.000775 -0.042010 0.091695 -vn -3.120170 -2.976249 0.258539 -v 0.000775 -0.042610 0.091695 -vn -3.120169 2.976245 -0.258546 -v 0.000775 -0.042010 0.091405 -vn -3.120169 -2.976244 -0.258546 -v 0.000775 -0.042610 0.091405 -vn -3.035059 2.976247 -0.768581 -v 0.000822 -0.042010 0.091120 -vn -3.035059 -2.976248 -0.768581 -v 0.000822 -0.042610 0.091120 -vn -2.867164 2.976249 -1.257645 -v 0.000916 -0.042010 0.090847 -vn -2.867164 -2.976249 -1.257645 -v 0.000916 -0.042610 0.090847 -vn -2.621058 2.976242 -1.712412 -v 0.001054 -0.042010 0.090593 -vn -2.621058 -2.976242 -1.712412 -v 0.001054 -0.042610 0.090593 -vn -2.303433 2.976229 -2.120491 -v 0.001231 -0.042010 0.090365 -vn -2.303433 -2.976229 -2.120491 -v 0.001231 -0.042610 0.090365 -vn -1.923017 2.976277 -2.470695 -v 0.001444 -0.042010 0.090169 -vn -1.923017 -2.976277 -2.470695 -v 0.001444 -0.042610 0.090169 -vn -1.490148 2.976233 -2.753498 -v 0.001686 -0.042010 0.090011 -vn -1.490148 -2.976232 -2.753497 -v 0.001686 -0.042610 0.090011 -vn -1.016592 2.976244 -2.961223 -v 0.001951 -0.042010 0.089895 -vn -1.016592 -2.976244 -2.961223 -v 0.001951 -0.042610 0.089895 -vn -0.515304 2.976234 -3.088163 -v 0.002231 -0.042010 0.089824 -vn -0.515304 -2.976234 -3.088163 -v 0.002231 -0.042610 0.089824 -vn -0.000002 2.976270 -3.130866 -v 0.002519 -0.042010 0.089800 -vn -0.000002 3.326394 3.128191 -v 0.002519 -0.042010 0.093050 -vn -0.000002 -3.326394 3.128191 -v 0.002519 -0.041010 0.093050 -vn -0.574798 -3.326386 3.074930 -v 0.002243 -0.041010 0.093024 -vn -0.574798 3.326385 3.074930 -v 0.002243 -0.042010 0.093024 -vn -1.130025 -3.326397 2.916954 -v 0.001977 -0.041010 0.092949 -vn -1.130025 3.326397 2.916954 -v 0.001977 -0.042010 0.092949 -vn -1.646776 -3.326390 2.659645 -v 0.001729 -0.041010 0.092825 -vn -1.646776 3.326390 2.659645 -v 0.001729 -0.042010 0.092825 -vn -2.107444 -3.326394 2.311765 -v 0.001508 -0.041010 0.092659 -vn -2.107444 3.326394 2.311765 -v 0.001508 -0.042010 0.092659 -vn -2.496346 -3.326390 1.885162 -v 0.001322 -0.041010 0.092454 -vn -2.496346 3.326390 1.885162 -v 0.001322 -0.042010 0.092454 -vn -2.800241 -3.326400 1.394354 -v 0.001176 -0.041010 0.092219 -vn -2.800241 3.326400 1.394354 -v 0.001176 -0.042010 0.092219 -vn -3.008777 -3.326391 0.856061 -v 0.001076 -0.041010 0.091960 -vn -3.008777 3.326391 0.856061 -v 0.001076 -0.042010 0.091960 -vn -3.114847 -3.326390 0.288630 -v 0.001025 -0.041010 0.091688 -vn -3.114848 3.326390 0.288630 -v 0.001025 -0.042010 0.091688 -vn -3.114849 -3.326385 -0.288622 -v 0.001025 -0.041010 0.091412 -vn -3.114849 3.326385 -0.288622 -v 0.001025 -0.042010 0.091412 -vn -3.008773 -3.326405 -0.856068 -v 0.001076 -0.041010 0.091140 -vn -3.008774 3.326405 -0.856068 -v 0.001076 -0.042010 0.091140 -vn -2.800248 -3.326376 -1.394349 -v 0.001176 -0.041010 0.090881 -vn -2.800247 3.326376 -1.394349 -v 0.001176 -0.042010 0.090881 -vn -2.496339 -3.326422 -1.885164 -v 0.001322 -0.041010 0.090646 -vn -2.496339 3.326422 -1.885164 -v 0.001322 -0.042010 0.090646 -vn -2.107452 -3.326354 -2.311765 -v 0.001508 -0.041010 0.090441 -vn -2.107452 3.326355 -2.311766 -v 0.001508 -0.042010 0.090441 -vn -1.646803 -3.326411 -2.659625 -v 0.001729 -0.041010 0.090275 -vn -1.646803 3.326411 -2.659625 -v 0.001729 -0.042010 0.090275 -vn -1.130025 -3.326397 -2.916954 -v 0.001977 -0.041010 0.090151 -vn -1.130025 3.326397 -2.916954 -v 0.001977 -0.042010 0.090151 -vn -0.574798 -3.326385 -3.074930 -v 0.002243 -0.041010 0.090076 -vn -0.574798 3.326386 -3.074930 -v 0.002243 -0.042010 0.090076 -vn -0.000002 -3.326394 -3.128191 -v 0.002519 -0.041010 0.090050 -vn -0.000002 3.326394 -3.128191 -v 0.002519 -0.042010 0.090050 -vn 0.694643 3.365977 -3.043578 -v 0.002296 -0.040410 0.092525 -vn 0.694643 -3.365977 -3.043578 -v 0.002296 -0.042610 0.092525 -vn 1.354513 3.366028 -2.812674 -v 0.002085 -0.040410 0.092451 -vn 1.354513 -3.366028 -2.812674 -v 0.002085 -0.042610 0.092451 -vn 1.946446 3.365962 -2.440750 -v 0.001895 -0.040410 0.092332 -vn 1.946446 -3.365962 -2.440750 -v 0.001895 -0.042610 0.092332 -vn 2.440728 3.365991 -1.946465 -v 0.001737 -0.040410 0.092173 -vn 2.440728 -3.365991 -1.946465 -v 0.001737 -0.042610 0.092173 -vn 2.812673 3.366013 -1.354521 -v 0.001618 -0.040410 0.091984 -vn 2.812673 -3.366013 -1.354521 -v 0.001618 -0.042610 0.091984 -vn 3.043572 3.365988 -0.694659 -v 0.001544 -0.040410 0.091773 -vn 3.043572 -3.365988 -0.694659 -v 0.001544 -0.042610 0.091773 -vn 3.121840 3.365986 0.000000 -v 0.001519 -0.040410 0.091550 -vn 3.121840 -3.365986 0.000000 -v 0.001519 -0.042610 0.091550 -vn 3.043572 3.365988 0.694659 -v 0.001544 -0.040410 0.091327 -vn 3.043572 -3.365987 0.694659 -v 0.001544 -0.042610 0.091327 -vn 2.812687 3.365995 1.354498 -v 0.001618 -0.040410 0.091116 -vn 2.812688 -3.365995 1.354498 -v 0.001618 -0.042610 0.091116 -vn 2.440743 3.366009 1.946442 -v 0.001737 -0.040410 0.090927 -vn 2.440743 -3.366009 1.946441 -v 0.001737 -0.042610 0.090927 -vn 1.946409 3.365991 2.440773 -v 0.001895 -0.040410 0.090768 -vn 1.946409 -3.365991 2.440773 -v 0.001895 -0.042610 0.090768 -vn 1.354522 3.365968 2.812681 -v 0.002085 -0.040410 0.090649 -vn 1.354522 -3.365968 2.812681 -v 0.002085 -0.042610 0.090649 -vn 0.694690 3.366009 3.043561 -v 0.002296 -0.040410 0.090575 -vn 0.694690 -3.366009 3.043561 -v 0.002296 -0.042610 0.090575 -vn 1.016599 2.976239 -2.961219 -v 0.003087 -0.040410 0.089895 -vn 0.515303 2.976233 -3.088163 -v 0.002807 -0.040410 0.089824 -vn 3.120170 2.976249 0.258539 -v 0.004263 -0.040410 0.091695 -vn 3.120169 2.976244 -0.258546 -v 0.004263 -0.040410 0.091405 -vn 3.035059 2.976247 -0.768581 -v 0.004215 -0.040410 0.091120 -vn 2.867164 2.976249 -1.257646 -v 0.004121 -0.040410 0.090847 -vn 2.621058 2.976243 -1.712412 -v 0.003984 -0.040410 0.090593 -vn 2.303433 2.976229 -2.120491 -v 0.003806 -0.040410 0.090365 -vn 1.923008 2.976270 -2.470701 -v 0.003594 -0.040410 0.090169 -vn 1.490146 2.976244 -2.753500 -v 0.003352 -0.040410 0.090011 -vn 2.621051 2.976214 1.712415 -v 0.003984 -0.040410 0.092507 -vn 2.867169 2.976270 1.257641 -v 0.004121 -0.040410 0.092253 -vn 3.035056 2.976235 0.768587 -v 0.004215 -0.040410 0.091980 -vn 1.016599 2.976238 2.961220 -v 0.003087 -0.040410 0.093205 -vn 1.490118 2.976266 2.753519 -v 0.003352 -0.040410 0.093089 -vn 1.923001 2.976229 2.470699 -v 0.003594 -0.040410 0.092931 -vn 2.303440 2.976264 2.120491 -v 0.003806 -0.040410 0.092735 -vn 0.515343 2.976259 3.088160 -v 0.002807 -0.040410 0.093276 -vn 1.016599 -2.976238 2.961220 -v 0.003087 -0.042610 0.093205 -vn 0.515343 -2.976259 3.088160 -v 0.002807 -0.042610 0.093276 -vn 3.120169 -2.976244 -0.258546 -v 0.004263 -0.042610 0.091405 -vn 3.120170 -2.976249 0.258539 -v 0.004263 -0.042610 0.091695 -vn 3.035056 -2.976235 0.768587 -v 0.004215 -0.042610 0.091980 -vn 2.867169 -2.976270 1.257641 -v 0.004121 -0.042610 0.092253 -vn 2.621052 -2.976214 1.712415 -v 0.003984 -0.042610 0.092507 -vn 2.303440 -2.976264 2.120491 -v 0.003806 -0.042610 0.092735 -vn 1.923001 -2.976229 2.470699 -v 0.003594 -0.042610 0.092931 -vn 1.490118 -2.976266 2.753519 -v 0.003352 -0.042610 0.093089 -vn 2.621058 -2.976243 -1.712412 -v 0.003984 -0.042610 0.090593 -vn 2.867164 -2.976249 -1.257646 -v 0.004121 -0.042610 0.090847 -vn 3.035059 -2.976247 -0.768581 -v 0.004215 -0.042610 0.091120 -vn 0.515303 -2.976233 -3.088163 -v 0.002807 -0.042610 0.089824 -vn 1.016599 -2.976239 -2.961220 -v 0.003087 -0.042610 0.089895 -vn 1.490146 -2.976244 -2.753500 -v 0.003352 -0.042610 0.090011 -vn 1.923008 -2.976270 -2.470701 -v 0.003594 -0.042610 0.090169 -vn 2.303433 -2.976229 -2.120491 -v 0.003806 -0.042610 0.090365 -vn 0.515303 -2.976233 -3.088163 -v 0.002807 -0.041010 0.089824 -vn 1.016599 -2.976239 -2.961220 -v 0.003087 -0.041010 0.089895 -vn 1.490146 -2.976244 -2.753500 -v 0.003352 -0.041010 0.090011 -vn 1.923008 -2.976270 -2.470701 -v 0.003594 -0.041010 0.090169 -vn 2.303433 -2.976229 -2.120491 -v 0.003806 -0.041010 0.090365 -vn 2.621058 -2.976242 -1.712412 -v 0.003984 -0.041010 0.090593 -vn 2.867164 -2.976249 -1.257646 -v 0.004121 -0.041010 0.090847 -vn 3.035059 -2.976247 -0.768581 -v 0.004215 -0.041010 0.091120 -vn 3.120169 -2.976245 -0.258546 -v 0.004263 -0.041010 0.091405 -vn 3.120170 -2.976249 0.258539 -v 0.004263 -0.041010 0.091695 -vn 3.035056 -2.976235 0.768587 -v 0.004215 -0.041010 0.091980 -vn 2.867169 -2.976270 1.257641 -v 0.004121 -0.041010 0.092253 -vn 2.621052 -2.976214 1.712415 -v 0.003984 -0.041010 0.092507 -vn 2.303440 -2.976263 2.120491 -v 0.003806 -0.041010 0.092735 -vn 1.923001 -2.976229 2.470699 -v 0.003594 -0.041010 0.092931 -vn 1.490118 -2.976266 2.753519 -v 0.003352 -0.041010 0.093089 -vn 1.016599 -2.976239 2.961219 -v 0.003087 -0.041010 0.093205 -vn 0.515343 -2.976259 3.088160 -v 0.002807 -0.041010 0.093276 -vn 0.515303 2.976233 -3.088164 -v 0.002807 -0.042010 0.089824 -vn 1.016599 2.976239 -2.961219 -v 0.003087 -0.042010 0.089895 -vn 1.490146 2.976244 -2.753500 -v 0.003352 -0.042010 0.090011 -vn 1.923008 2.976270 -2.470701 -v 0.003594 -0.042010 0.090169 -vn 2.303433 2.976229 -2.120491 -v 0.003806 -0.042010 0.090365 -vn 2.621058 2.976242 -1.712412 -v 0.003984 -0.042010 0.090593 -vn 2.867164 2.976249 -1.257646 -v 0.004121 -0.042010 0.090847 -vn 3.035059 2.976247 -0.768581 -v 0.004215 -0.042010 0.091120 -vn 3.120169 2.976245 -0.258546 -v 0.004263 -0.042010 0.091405 -vn 3.120170 2.976249 0.258539 -v 0.004263 -0.042010 0.091695 -vn 3.035056 2.976235 0.768587 -v 0.004215 -0.042010 0.091980 -vn 2.867169 2.976270 1.257641 -v 0.004121 -0.042010 0.092253 -vn 2.621052 2.976214 1.712415 -v 0.003984 -0.042010 0.092507 -vn 2.303440 2.976264 2.120491 -v 0.003806 -0.042010 0.092735 -vn 1.923001 2.976229 2.470699 -v 0.003594 -0.042010 0.092931 -vn 1.490118 2.976266 2.753519 -v 0.003352 -0.042010 0.093089 -vn 1.016599 2.976239 2.961220 -v 0.003087 -0.042010 0.093205 -vn 0.515343 2.976259 3.088160 -v 0.002807 -0.042010 0.093276 -vn 2.107444 -3.326394 2.311765 -v 0.003529 -0.041010 0.092659 -vn 1.646776 -3.326390 2.659645 -v 0.003308 -0.041010 0.092825 -vn 1.130025 -3.326397 2.916954 -v 0.003061 -0.041010 0.092949 -vn 0.574796 -3.326387 3.074930 -v 0.002794 -0.041010 0.093024 -vn 2.107452 -3.326355 -2.311766 -v 0.003529 -0.041010 0.090441 -vn 2.496339 -3.326422 -1.885164 -v 0.003716 -0.041010 0.090646 -vn 2.800247 -3.326376 -1.394349 -v 0.003862 -0.041010 0.090881 -vn 3.008774 -3.326405 -0.856068 -v 0.003962 -0.041010 0.091140 -vn 3.114849 -3.326385 -0.288622 -v 0.004012 -0.041010 0.091412 -vn 3.114848 -3.326390 0.288630 -v 0.004012 -0.041010 0.091688 -vn 3.008777 -3.326391 0.856061 -v 0.003962 -0.041010 0.091960 -vn 2.800241 -3.326400 1.394354 -v 0.003862 -0.041010 0.092219 -vn 2.496346 -3.326390 1.885162 -v 0.003716 -0.041010 0.092454 -vn 0.574796 -3.326387 -3.074930 -v 0.002794 -0.041010 0.090076 -vn 1.130025 -3.326397 -2.916954 -v 0.003061 -0.041010 0.090151 -vn 1.646803 -3.326411 -2.659625 -v 0.003308 -0.041010 0.090275 -vn 2.107444 3.326394 2.311765 -v 0.003529 -0.042010 0.092659 -vn 2.496346 3.326390 1.885162 -v 0.003716 -0.042010 0.092454 -vn 2.800241 3.326400 1.394354 -v 0.003862 -0.042010 0.092219 -vn 3.008777 3.326391 0.856061 -v 0.003962 -0.042010 0.091960 -vn 3.114847 3.326390 0.288630 -v 0.004012 -0.042010 0.091688 -vn 3.114849 3.326385 -0.288622 -v 0.004012 -0.042010 0.091412 -vn 3.008773 3.326405 -0.856068 -v 0.003962 -0.042010 0.091140 -vn 2.800248 3.326376 -1.394349 -v 0.003862 -0.042010 0.090881 -vn 2.496339 3.326422 -1.885164 -v 0.003716 -0.042010 0.090646 -vn 2.107452 3.326354 -2.311765 -v 0.003529 -0.042010 0.090441 -vn 1.646803 3.326411 -2.659625 -v 0.003308 -0.042010 0.090275 -vn 1.130025 3.326397 -2.916954 -v 0.003061 -0.042010 0.090151 -vn 0.574796 3.326387 -3.074930 -v 0.002794 -0.042010 0.090076 -vn 0.574796 3.326387 3.074930 -v 0.002794 -0.042010 0.093024 -vn 1.130025 3.326397 2.916954 -v 0.003061 -0.042010 0.092949 -vn 1.646776 3.326390 2.659645 -v 0.003308 -0.042010 0.092825 -vn 1.707466 -3.365983 -2.613513 -v 0.000853 -0.041010 0.101837 -vn 1.707466 3.365983 -2.613513 -v 0.000853 -0.038810 0.101837 -vn 1.083116 -3.365987 -2.927925 -v 0.001053 -0.041010 0.101938 -vn 1.083116 3.365987 -2.927925 -v 0.001053 -0.038810 0.101938 -vn 0.404417 -3.366009 -3.095531 -v 0.001270 -0.041010 0.101992 -vn 0.404417 3.366009 -3.095530 -v 0.001270 -0.038810 0.101992 -vn -0.294508 -3.365952 -3.107924 -v 0.001494 -0.041010 0.101996 -vn -0.294508 3.365953 -3.107924 -v 0.001494 -0.038810 0.101996 -vn -0.978691 -3.366027 -2.964457 -v 0.001714 -0.041010 0.101950 -vn -0.978691 3.366027 -2.964457 -v 0.001714 -0.038810 0.101950 -vn -1.613845 -3.365983 -2.672338 -v 0.001917 -0.041010 0.101856 -vn -1.613845 3.365983 -2.672339 -v 0.001917 -0.038810 0.101856 -vn -2.168032 -3.366002 -2.246221 -v 0.002094 -0.041010 0.101720 -vn -2.168032 3.366002 -2.246221 -v 0.002094 -0.038810 0.101720 -vn -2.613517 -3.365993 -1.707458 -v 0.002237 -0.041010 0.101547 -vn -2.613516 3.365993 -1.707458 -v 0.002237 -0.038810 0.101547 -vn -2.927935 -3.365991 -1.083087 -v 0.002338 -0.041010 0.101347 -vn -2.927935 3.365991 -1.083087 -v 0.002338 -0.038810 0.101347 -vn -3.095534 -3.365980 -0.404425 -v 0.002392 -0.041010 0.101130 -vn -3.095535 3.365980 -0.404425 -v 0.002392 -0.038810 0.101130 -vn -3.107912 -3.366005 0.294538 -v 0.002396 -0.041010 0.100906 -vn -3.107911 3.366005 0.294538 -v 0.002396 -0.038810 0.100906 -vn -2.964449 -3.365984 0.978736 -v 0.002350 -0.041010 0.100686 -vn -2.964450 3.365984 0.978737 -v 0.002350 -0.038810 0.100686 -vn -2.672334 -3.366000 1.613848 -v 0.002256 -0.041010 0.100483 -vn -2.672333 3.365999 1.613848 -v 0.002256 -0.038810 0.100483 -vn -2.246239 -3.365968 2.168021 -v 0.002120 -0.041010 0.100306 -vn -2.246239 3.365968 2.168021 -v 0.002120 -0.038810 0.100306 -vn -1.707497 -3.366009 2.613487 -v 0.001947 -0.041010 0.100163 -vn -1.707497 3.366009 2.613488 -v 0.001947 -0.038810 0.100163 -vn 1.712412 2.976242 -2.621058 -v 0.002357 -0.040410 0.099535 -vn 1.712412 -2.976243 -2.621058 -v 0.002357 -0.041010 0.099535 -vn 1.257646 -2.976249 -2.867164 -v 0.002103 -0.041010 0.099397 -vn 1.257646 2.976249 -2.867164 -v 0.002103 -0.040410 0.099397 -vn 0.768578 -2.976245 -3.035060 -v 0.001830 -0.041010 0.099304 -vn 0.768578 2.976245 -3.035060 -v 0.001830 -0.040410 0.099304 -vn 0.258502 -2.976221 -3.120170 -v 0.001545 -0.041010 0.099256 -vn 0.258502 2.976221 -3.120169 -v 0.001545 -0.040410 0.099256 -vn -0.258583 -2.976272 -3.120169 -v 0.001255 -0.041010 0.099256 -vn -0.258583 2.976273 -3.120169 -v 0.001255 -0.040410 0.099256 -vn -0.768584 -2.976242 -3.035058 -v 0.000970 -0.041010 0.099304 -vn -0.768584 2.976241 -3.035058 -v 0.000970 -0.040410 0.099304 -vn -1.257652 -2.976253 -2.867162 -v 0.000697 -0.041010 0.099397 -vn -1.257652 2.976253 -2.867162 -v 0.000697 -0.040410 0.099397 -vn -1.712412 -2.976242 -2.621058 -v 0.000443 -0.041010 0.099535 -vn -1.712412 2.976243 -2.621058 -v 0.000443 -0.040410 0.099535 -vn -2.120481 -2.976238 -2.303444 -v 0.000215 -0.041010 0.099712 -vn -2.120481 2.976238 -2.303444 -v 0.000215 -0.040410 0.099712 -vn -2.470700 -2.976249 -1.923005 -v 0.000019 -0.041010 0.099925 -vn -2.470700 2.976250 -1.923004 -v 0.000019 -0.040410 0.099925 -vn -2.753523 -2.976233 -1.490100 -v -0.000139 -0.041010 0.100167 -vn -2.753523 2.976233 -1.490100 -v -0.000139 -0.040410 0.100167 -vn -2.961232 -2.976264 -1.016572 -v -0.000255 -0.041010 0.100432 -vn -2.961232 2.976264 -1.016572 -v -0.000255 -0.040410 0.100432 -vn -3.088162 -2.976231 -0.515309 -v -0.000326 -0.041010 0.100712 -vn -3.088162 2.976231 -0.515309 -v -0.000326 -0.040410 0.100712 -vn -3.130864 -2.976259 0.000017 -v -0.000350 -0.041010 0.101000 -vn -3.130864 2.976259 0.000017 -v -0.000350 -0.040410 0.101000 -vn -3.088156 -2.976229 0.515345 -v -0.000326 -0.041010 0.101288 -vn -3.088156 2.976229 0.515345 -v -0.000326 -0.040410 0.101288 -vn -2.961214 -2.976254 1.016623 -v -0.000255 -0.041010 0.101568 -vn -2.961214 2.976254 1.016623 -v -0.000255 -0.040410 0.101568 -vn -2.753510 -2.976255 1.490132 -v -0.000139 -0.041010 0.101833 -vn -2.753510 2.976255 1.490132 -v -0.000139 -0.040410 0.101833 -vn -2.470700 -2.976249 1.923004 -v 0.000019 -0.041010 0.102075 -vn -2.470700 2.976249 1.923004 -v 0.000019 -0.040410 0.102075 -vn -2.120481 -2.976238 2.303444 -v 0.000215 -0.041010 0.102288 -vn -2.120481 2.976238 2.303444 -v 0.000215 -0.040410 0.102288 -vn -1.712404 -2.976236 2.621062 -v 0.000443 -0.041010 0.102465 -vn -1.712404 2.976236 2.621062 -v 0.000443 -0.040410 0.102465 -vn 1.712412 2.976242 -2.621058 -v 0.002357 -0.038810 0.099535 -vn 1.712412 -2.976242 -2.621058 -v 0.002357 -0.039410 0.099535 -vn 1.257646 -2.976249 -2.867164 -v 0.002103 -0.039410 0.099397 -vn 1.257646 2.976249 -2.867164 -v 0.002103 -0.038810 0.099397 -vn 0.768578 -2.976245 -3.035060 -v 0.001830 -0.039410 0.099304 -vn 0.768578 2.976245 -3.035060 -v 0.001830 -0.038810 0.099304 -vn 0.258502 -2.976221 -3.120170 -v 0.001545 -0.039410 0.099256 -vn 0.258502 2.976221 -3.120169 -v 0.001545 -0.038810 0.099256 -vn -0.258583 -2.976273 -3.120169 -v 0.001255 -0.039410 0.099256 -vn -0.258583 2.976273 -3.120169 -v 0.001255 -0.038810 0.099256 -vn -0.768584 -2.976241 -3.035058 -v 0.000970 -0.039410 0.099304 -vn -0.768584 2.976241 -3.035058 -v 0.000970 -0.038810 0.099304 -vn -1.257652 -2.976254 -2.867162 -v 0.000697 -0.039410 0.099397 -vn -1.257652 2.976253 -2.867162 -v 0.000697 -0.038810 0.099397 -vn -1.712412 -2.976242 -2.621058 -v 0.000443 -0.039410 0.099535 -vn -1.712412 2.976242 -2.621058 -v 0.000443 -0.038810 0.099535 -vn -2.120481 -2.976238 -2.303444 -v 0.000215 -0.039410 0.099712 -vn -2.120481 2.976238 -2.303444 -v 0.000215 -0.038810 0.099712 -vn -2.470700 -2.976249 -1.923005 -v 0.000019 -0.039410 0.099925 -vn -2.470700 2.976249 -1.923004 -v 0.000019 -0.038810 0.099925 -vn -2.753523 -2.976233 -1.490100 -v -0.000139 -0.039410 0.100167 -vn -2.753523 2.976233 -1.490100 -v -0.000139 -0.038810 0.100167 -vn -2.961232 -2.976264 -1.016572 -v -0.000255 -0.039410 0.100432 -vn -2.961232 2.976264 -1.016572 -v -0.000255 -0.038810 0.100432 -vn -3.088162 -2.976231 -0.515309 -v -0.000326 -0.039410 0.100712 -vn -3.088162 2.976231 -0.515309 -v -0.000326 -0.038810 0.100712 -vn -3.130864 -2.976259 0.000017 -v -0.000350 -0.039410 0.101000 -vn -3.130864 2.976259 0.000017 -v -0.000350 -0.038810 0.101000 -vn -3.088156 -2.976229 0.515345 -v -0.000326 -0.039410 0.101288 -vn -3.088156 2.976229 0.515345 -v -0.000326 -0.038810 0.101288 -vn -2.961214 -2.976254 1.016623 -v -0.000255 -0.039410 0.101568 -vn -2.961214 2.976254 1.016623 -v -0.000255 -0.038810 0.101568 -vn -2.753510 -2.976255 1.490132 -v -0.000139 -0.039410 0.101833 -vn -2.753510 2.976255 1.490132 -v -0.000139 -0.038810 0.101833 -vn -2.470700 -2.976249 1.923004 -v 0.000019 -0.039410 0.102075 -vn -2.470700 2.976249 1.923004 -v 0.000019 -0.038810 0.102075 -vn -2.120481 -2.976238 2.303444 -v 0.000215 -0.039410 0.102288 -vn -2.120481 2.976238 2.303444 -v 0.000215 -0.038810 0.102288 -vn -1.712404 -2.976236 2.621062 -v 0.000443 -0.039410 0.102465 -vn -1.712404 2.976236 2.621062 -v 0.000443 -0.038810 0.102465 -vn 1.710948 -3.326382 -2.618825 -v 0.002220 -0.039410 0.099744 -vn 1.710948 3.326382 -2.618825 -v 0.002220 -0.040410 0.099744 -vn 1.200624 3.326391 -2.888613 -v 0.001976 -0.040410 0.099615 -vn 1.200624 -3.326392 -2.888613 -v 0.001976 -0.039410 0.099615 -vn 0.649381 3.326405 -3.060045 -v 0.001711 -0.040410 0.099533 -vn 0.649381 -3.326405 -3.060045 -v 0.001711 -0.039410 0.099533 -vn 0.076019 3.326394 -3.127267 -v 0.001436 -0.040410 0.099500 -vn 0.076019 -3.326394 -3.127267 -v 0.001436 -0.039410 0.099500 -vn -0.499879 3.326370 -3.087996 -v 0.001160 -0.040410 0.099519 -vn -0.499879 -3.326370 -3.087996 -v 0.001160 -0.039410 0.099519 -vn -1.058777 3.326410 -2.943562 -v 0.000892 -0.040410 0.099589 -vn -1.058777 -3.326410 -2.943562 -v 0.000892 -0.039410 0.099589 -vn -1.581653 3.326392 -2.698880 -v 0.000642 -0.040410 0.099706 -vn -1.581653 -3.326392 -2.698880 -v 0.000642 -0.039410 0.099706 -vn -2.050625 3.326379 -2.362314 -v 0.000417 -0.040410 0.099867 -vn -2.050625 -3.326379 -2.362314 -v 0.000417 -0.039410 0.099867 -vn -2.449785 3.326410 -1.945281 -v 0.000225 -0.040410 0.100067 -vn -2.449785 -3.326410 -1.945281 -v 0.000225 -0.039410 0.100067 -vn -2.765530 3.326386 -1.461997 -v 0.000074 -0.040410 0.100299 -vn -2.765529 -3.326386 -1.461997 -v 0.000074 -0.039410 0.100299 -vn -2.987077 3.326388 -0.928954 -v -0.000032 -0.040410 0.100555 -vn -2.987077 -3.326388 -0.928954 -v -0.000032 -0.039410 0.100555 -vn -3.106910 3.326396 -0.364263 -v -0.000090 -0.040410 0.100825 -vn -3.106910 -3.326396 -0.364263 -v -0.000090 -0.039410 0.100825 -vn -3.120943 3.326390 0.212836 -v -0.000097 -0.040410 0.101102 -vn -3.120943 -3.326390 0.212836 -v -0.000097 -0.039410 0.101102 -vn -3.028697 3.326387 0.782672 -v -0.000052 -0.040410 0.101375 -vn -3.028697 -3.326387 0.782672 -v -0.000052 -0.039410 0.101375 -vn -2.833306 3.326404 1.325876 -v 0.000041 -0.040410 0.101636 -vn -2.833306 -3.326404 1.325876 -v 0.000041 -0.039410 0.101636 -vn -2.541448 3.326370 1.823909 -v 0.000181 -0.040410 0.101875 -vn -2.541448 -3.326370 1.823909 -v 0.000181 -0.039410 0.101875 -vn -2.163031 3.326412 2.259836 -v 0.000363 -0.040410 0.102084 -vn -2.163031 -3.326412 2.259836 -v 0.000363 -0.039410 0.102084 -vn -1.710948 3.326382 2.618825 -v 0.000580 -0.040410 0.102256 -vn -1.710948 -3.326382 2.618825 -v 0.000580 -0.039410 0.102256 -vn -1.083067 -3.366019 2.927937 -v 0.001747 -0.041010 0.100062 -vn -1.083067 3.366019 2.927937 -v 0.001747 -0.038810 0.100062 -vn -0.404420 -3.365944 3.095541 -v 0.001530 -0.041010 0.100008 -vn -0.404420 3.365944 3.095542 -v 0.001530 -0.038810 0.100008 -vn 0.294506 -3.366018 3.107912 -v 0.001306 -0.041010 0.100004 -vn 0.294506 3.366018 3.107912 -v 0.001306 -0.038810 0.100004 -vn 0.978741 -3.365994 2.964446 -v 0.001086 -0.041010 0.100050 -vn 0.978741 3.365995 2.964446 -v 0.001086 -0.038810 0.100050 -vn 1.613858 -3.365992 2.672329 -v 0.000883 -0.041010 0.100144 -vn 1.613858 3.365993 2.672329 -v 0.000883 -0.038810 0.100144 -vn 2.168045 -3.365992 2.246211 -v 0.000706 -0.041010 0.100280 -vn 2.168045 3.365992 2.246211 -v 0.000706 -0.038810 0.100280 -vn 2.613506 -3.365978 1.707479 -v 0.000563 -0.041010 0.100453 -vn 2.613505 3.365978 1.707479 -v 0.000563 -0.038810 0.100453 -vn 2.927921 -3.365998 1.083120 -v 0.000462 -0.041010 0.100653 -vn 2.927921 3.365998 1.083120 -v 0.000462 -0.038810 0.100653 -vn 3.095531 -3.366005 0.404411 -v 0.000408 -0.041010 0.100870 -vn 3.095532 3.366005 0.404411 -v 0.000408 -0.038810 0.100870 -vn 3.107912 -3.365988 -0.294564 -v 0.000404 -0.041010 0.101094 -vn 3.107911 3.365988 -0.294564 -v 0.000404 -0.038810 0.101094 -vn 2.964459 -3.365969 -0.978715 -v 0.000450 -0.041010 0.101314 -vn 2.964460 3.365969 -0.978715 -v 0.000450 -0.038810 0.101314 -vn 2.672331 -3.366028 -1.613842 -v 0.000544 -0.041010 0.101517 -vn 2.672330 3.366028 -1.613842 -v 0.000544 -0.038810 0.101517 -vn 2.246195 -3.365981 -2.168063 -v 0.000680 -0.041010 0.101694 -vn 2.246195 3.365981 -2.168063 -v 0.000680 -0.038810 0.101694 -vn 2.753519 -2.976266 1.490118 -v 0.002939 -0.041010 0.101833 -vn 2.470709 -2.976239 1.922990 -v 0.002781 -0.041010 0.102075 -vn 2.120481 -2.976238 2.303444 -v 0.002585 -0.041010 0.102288 -vn -0.768548 -2.976265 3.035070 -v 0.000970 -0.041010 0.102696 -vn -1.257607 -2.976235 2.867179 -v 0.000697 -0.041010 0.102603 -vn 1.712443 -2.976265 2.621041 -v 0.002357 -0.041010 0.102465 -vn 1.257683 -2.976231 2.867145 -v 0.002103 -0.041010 0.102603 -vn 0.768584 -2.976241 3.035058 -v 0.001830 -0.041010 0.102696 -vn 0.258543 -2.976247 3.120169 -v 0.001545 -0.041010 0.102744 -vn -0.258543 -2.976247 3.120169 -v 0.001255 -0.041010 0.102744 -vn 2.120452 -2.976265 -2.303475 -v 0.002585 -0.041010 0.099712 -vn 2.470671 -2.976222 -1.923036 -v 0.002781 -0.041010 0.099925 -vn 2.753510 -2.976255 -1.490132 -v 0.002939 -0.041010 0.100167 -vn 2.961216 -2.976248 -1.016613 -v 0.003055 -0.041010 0.100432 -vn 3.088158 -2.976238 -0.515339 -v 0.003126 -0.041010 0.100712 -vn 3.130862 -2.976244 -0.000000 -v 0.003150 -0.041010 0.101000 -vn 3.088168 -2.976263 0.515301 -v 0.003126 -0.041010 0.101288 -vn 2.961226 -2.976223 1.016575 -v 0.003055 -0.041010 0.101568 -vn 2.470671 2.976222 -1.923036 -v 0.002781 -0.038810 0.099925 -vn 2.120452 2.976265 -2.303475 -v 0.002585 -0.038810 0.099712 -vn 3.130862 2.976244 0.000000 -v 0.003150 -0.038810 0.101000 -vn 3.088158 2.976238 -0.515339 -v 0.003126 -0.038810 0.100712 -vn 2.961216 2.976248 -1.016613 -v 0.003055 -0.038810 0.100432 -vn 2.753510 2.976255 -1.490132 -v 0.002939 -0.038810 0.100167 -vn 2.753519 2.976266 1.490118 -v 0.002939 -0.038810 0.101833 -vn 2.961226 2.976223 1.016575 -v 0.003055 -0.038810 0.101568 -vn 3.088167 2.976263 0.515301 -v 0.003126 -0.038810 0.101288 -vn 1.257683 2.976231 2.867145 -v 0.002103 -0.038810 0.102603 -vn 1.712443 2.976265 2.621041 -v 0.002357 -0.038810 0.102465 -vn 2.120481 2.976238 2.303444 -v 0.002585 -0.038810 0.102288 -vn 2.470709 2.976239 1.922990 -v 0.002781 -0.038810 0.102075 -vn -1.257607 2.976235 2.867179 -v 0.000697 -0.038810 0.102603 -vn -0.768548 2.976265 3.035070 -v 0.000970 -0.038810 0.102696 -vn -0.258543 2.976247 3.120169 -v 0.001255 -0.038810 0.102744 -vn 0.258543 2.976247 3.120170 -v 0.001545 -0.038810 0.102744 -vn 0.768584 2.976241 3.035058 -v 0.001830 -0.038810 0.102696 -vn -1.257607 2.976235 2.867179 -v 0.000697 -0.040410 0.102603 -vn -0.768548 2.976266 3.035070 -v 0.000970 -0.040410 0.102696 -vn -0.258543 2.976247 3.120169 -v 0.001255 -0.040410 0.102744 -vn 0.258543 2.976247 3.120170 -v 0.001545 -0.040410 0.102744 -vn 0.768584 2.976241 3.035058 -v 0.001830 -0.040410 0.102696 -vn 1.257683 2.976231 2.867145 -v 0.002103 -0.040410 0.102603 -vn 1.712443 2.976265 2.621041 -v 0.002357 -0.040410 0.102465 -vn 2.120481 2.976238 2.303444 -v 0.002585 -0.040410 0.102288 -vn 2.470709 2.976239 1.922990 -v 0.002781 -0.040410 0.102075 -vn 2.753519 2.976266 1.490118 -v 0.002939 -0.040410 0.101833 -vn 2.961226 2.976223 1.016575 -v 0.003055 -0.040410 0.101568 -vn 3.088167 2.976263 0.515301 -v 0.003126 -0.040410 0.101288 -vn 3.130862 2.976244 0.000000 -v 0.003150 -0.040410 0.101000 -vn 3.088158 2.976238 -0.515339 -v 0.003126 -0.040410 0.100712 -vn 2.961216 2.976248 -1.016613 -v 0.003055 -0.040410 0.100432 -vn 2.753510 2.976255 -1.490132 -v 0.002939 -0.040410 0.100167 -vn 2.470671 2.976223 -1.923036 -v 0.002781 -0.040410 0.099925 -vn 2.120452 2.976265 -2.303475 -v 0.002585 -0.040410 0.099712 -vn -1.257607 -2.976235 2.867179 -v 0.000697 -0.039410 0.102603 -vn -0.768548 -2.976265 3.035070 -v 0.000970 -0.039410 0.102696 -vn -0.258543 -2.976247 3.120169 -v 0.001255 -0.039410 0.102744 -vn 0.258543 -2.976247 3.120169 -v 0.001545 -0.039410 0.102744 -vn 0.768584 -2.976241 3.035058 -v 0.001830 -0.039410 0.102696 -vn 1.257683 -2.976231 2.867145 -v 0.002103 -0.039410 0.102603 -vn 1.712443 -2.976264 2.621041 -v 0.002357 -0.039410 0.102465 -vn 2.120481 -2.976238 2.303444 -v 0.002585 -0.039410 0.102288 -vn 2.470709 -2.976239 1.922990 -v 0.002781 -0.039410 0.102075 -vn 2.753519 -2.976266 1.490118 -v 0.002939 -0.039410 0.101833 -vn 2.961226 -2.976223 1.016575 -v 0.003055 -0.039410 0.101568 -vn 3.088168 -2.976263 0.515301 -v 0.003126 -0.039410 0.101288 -vn 3.130862 -2.976244 -0.000000 -v 0.003150 -0.039410 0.101000 -vn 3.088158 -2.976238 -0.515339 -v 0.003126 -0.039410 0.100712 -vn 2.961216 -2.976248 -1.016613 -v 0.003055 -0.039410 0.100432 -vn 2.753510 -2.976256 -1.490132 -v 0.002939 -0.039410 0.100167 -vn 2.470671 -2.976222 -1.923036 -v 0.002781 -0.039410 0.099925 -vn 2.120452 -2.976265 -2.303475 -v 0.002585 -0.039410 0.099712 -vn 3.028697 3.326387 -0.782672 -v 0.002852 -0.040410 0.100625 -vn 2.833316 3.326391 -1.325858 -v 0.002759 -0.040410 0.100364 -vn 2.541440 3.326401 -1.823912 -v 0.002619 -0.040410 0.100125 -vn 2.163013 3.326394 -2.259857 -v 0.002437 -0.040410 0.099916 -vn -1.200585 3.326417 2.888625 -v 0.000824 -0.040410 0.102385 -vn -0.649384 3.326353 3.060051 -v 0.001089 -0.040410 0.102467 -vn -0.076061 3.326421 3.127262 -v 0.001364 -0.040410 0.102500 -vn 0.499918 3.326396 3.087986 -v 0.001640 -0.040410 0.102481 -vn 1.058817 3.326384 2.943552 -v 0.001908 -0.040410 0.102411 -vn 1.581625 3.326370 2.698900 -v 0.002158 -0.040410 0.102294 -vn 2.050618 3.326420 2.362313 -v 0.002383 -0.040410 0.102133 -vn 2.449793 3.326377 1.945279 -v 0.002575 -0.040410 0.101933 -vn 2.765517 3.326401 1.462016 -v 0.002726 -0.040410 0.101701 -vn 2.987077 3.326388 0.928954 -v 0.002832 -0.040410 0.101445 -vn 3.106910 3.326396 0.364263 -v 0.002890 -0.040410 0.101175 -vn 3.120943 3.326390 -0.212836 -v 0.002897 -0.040410 0.100898 -vn 0.499918 -3.326396 3.087986 -v 0.001640 -0.039410 0.102481 -vn -0.076061 -3.326421 3.127262 -v 0.001364 -0.039410 0.102500 -vn -0.649384 -3.326353 3.060052 -v 0.001089 -0.039410 0.102467 -vn -1.200585 -3.326417 2.888624 -v 0.000824 -0.039410 0.102385 -vn 3.028697 -3.326387 -0.782672 -v 0.002852 -0.039410 0.100625 -vn 3.120943 -3.326390 -0.212836 -v 0.002897 -0.039410 0.100898 -vn 3.106910 -3.326396 0.364263 -v 0.002890 -0.039410 0.101175 -vn 2.987077 -3.326388 0.928954 -v 0.002832 -0.039410 0.101445 -vn 2.765517 -3.326401 1.462016 -v 0.002726 -0.039410 0.101701 -vn 2.449793 -3.326377 1.945279 -v 0.002575 -0.039410 0.101933 -vn 2.050618 -3.326420 2.362313 -v 0.002383 -0.039410 0.102133 -vn 1.581625 -3.326370 2.698900 -v 0.002158 -0.039410 0.102294 -vn 1.058817 -3.326384 2.943551 -v 0.001908 -0.039410 0.102411 -vn 2.163013 -3.326394 -2.259857 -v 0.002437 -0.039410 0.099916 -vn 2.541440 -3.326401 -1.823912 -v 0.002619 -0.039410 0.100125 -vn 2.833317 -3.326391 -1.325858 -v 0.002759 -0.039410 0.100364 -vn -0.000000 3.365984 3.121840 -v 0.010850 -0.040410 0.098881 -vn 0.000000 -3.365984 3.121840 -v 0.010850 -0.042610 0.098881 -vn -0.694689 3.366010 3.043561 -v 0.011073 -0.040410 0.098906 -vn -0.694688 -3.366010 3.043561 -v 0.011073 -0.042610 0.098906 -vn -1.354522 3.365968 2.812681 -v 0.011284 -0.040410 0.098980 -vn -1.354522 -3.365969 2.812681 -v 0.011284 -0.042610 0.098980 -vn -1.946415 3.365996 2.440767 -v 0.011473 -0.040410 0.099099 -vn -1.946415 -3.365996 2.440767 -v 0.011473 -0.042610 0.099099 -vn -2.440749 3.366003 1.946435 -v 0.011632 -0.040410 0.099258 -vn -2.440750 -3.366003 1.946435 -v 0.011632 -0.042610 0.099258 -vn -2.812682 3.365984 1.354514 -v 0.011751 -0.040410 0.099447 -vn -2.812682 -3.365984 1.354514 -v 0.011751 -0.042610 0.099447 -vn -3.043566 3.365994 0.694682 -v 0.011825 -0.040410 0.099659 -vn -3.043566 -3.365994 0.694682 -v 0.011825 -0.042610 0.099659 -vn -3.121837 3.365999 -0.000006 -v 0.011850 -0.040410 0.099881 -vn -3.121838 -3.365999 -0.000006 -v 0.011850 -0.042610 0.099881 -vn -3.043565 3.365990 -0.694688 -v 0.011825 -0.040410 0.100104 -vn -3.043566 -3.365990 -0.694688 -v 0.011825 -0.042610 0.100104 -vn -2.812682 3.365984 -1.354514 -v 0.011751 -0.040410 0.100315 -vn -2.812682 -3.365984 -1.354514 -v 0.011751 -0.042610 0.100315 -vn -2.440750 3.366003 -1.946435 -v 0.011632 -0.040410 0.100505 -vn -2.440749 -3.366003 -1.946435 -v 0.011632 -0.042610 0.100505 -vn -1.946452 3.365968 -2.440743 -v 0.011473 -0.040410 0.100663 -vn -1.946452 -3.365968 -2.440743 -v 0.011473 -0.042610 0.100663 -vn -1.354513 3.366028 -2.812674 -v 0.011284 -0.040410 0.100782 -vn -1.354513 -3.366028 -2.812674 -v 0.011284 -0.042610 0.100782 -vn -0.694642 3.365978 -3.043578 -v 0.011073 -0.040410 0.100856 -vn -0.694642 -3.365978 -3.043578 -v 0.011073 -0.042610 0.100856 -vn 0.000000 3.365984 -3.121840 -v 0.010850 -0.040410 0.100881 -vn -0.000000 -3.365984 -3.121840 -v 0.010850 -0.042610 0.100881 -vn 0.000001 -2.976218 3.130859 -v 0.010850 -0.041010 0.101631 -vn -0.515344 2.976259 3.088160 -v 0.010562 -0.040410 0.101607 -vn -0.515344 -2.976259 3.088160 -v 0.010562 -0.041010 0.101607 -vn -1.016595 2.976241 2.961221 -v 0.010282 -0.040410 0.101536 -vn -1.016595 -2.976241 2.961221 -v 0.010282 -0.041010 0.101536 -vn -1.490114 2.976264 2.753520 -v 0.010017 -0.040410 0.101420 -vn -1.490114 -2.976264 2.753520 -v 0.010017 -0.041010 0.101420 -vn -1.923011 2.976220 2.470690 -v 0.009775 -0.040410 0.101262 -vn -1.923011 -2.976220 2.470690 -v 0.009775 -0.041010 0.101262 -vn -2.303465 2.976256 2.120461 -v 0.009562 -0.040410 0.101066 -vn -2.303465 -2.976256 2.120462 -v 0.009562 -0.041010 0.101066 -vn -2.621053 2.976248 1.712420 -v 0.009385 -0.040410 0.100838 -vn -2.621053 -2.976248 1.712420 -v 0.009385 -0.041010 0.100838 -vn -2.867160 2.976243 1.257653 -v 0.009247 -0.040410 0.100584 -vn -2.867160 -2.976244 1.257654 -v 0.009247 -0.041010 0.100584 -vn -3.035059 2.976248 0.768581 -v 0.009154 -0.040410 0.100311 -vn -3.035059 -2.976247 0.768581 -v 0.009154 -0.041010 0.100311 -vn -3.120169 2.976245 0.258546 -v 0.009106 -0.040410 0.100026 -vn -3.120169 -2.976245 0.258546 -v 0.009106 -0.041010 0.100026 -vn -3.120169 2.976245 -0.258546 -v 0.009106 -0.040410 0.099737 -vn -3.120169 -2.976244 -0.258546 -v 0.009106 -0.041010 0.099737 -vn -3.035059 2.976247 -0.768581 -v 0.009154 -0.040410 0.099452 -vn -3.035059 -2.976248 -0.768581 -v 0.009154 -0.041010 0.099452 -vn -2.867160 2.976243 -1.257653 -v 0.009247 -0.040410 0.099178 -vn -2.867160 -2.976243 -1.257653 -v 0.009247 -0.041010 0.099178 -vn -2.621053 2.976248 -1.712420 -v 0.009385 -0.040410 0.098924 -vn -2.621053 -2.976248 -1.712420 -v 0.009385 -0.041010 0.098924 -vn -2.303465 2.976256 -2.120462 -v 0.009562 -0.040410 0.098696 -vn -2.303465 -2.976256 -2.120462 -v 0.009562 -0.041010 0.098696 -vn -1.923011 2.976220 -2.470690 -v 0.009775 -0.040410 0.098500 -vn -1.923011 -2.976221 -2.470690 -v 0.009775 -0.041010 0.098500 -vn -1.490114 2.976264 -2.753520 -v 0.010017 -0.040410 0.098342 -vn -1.490114 -2.976263 -2.753520 -v 0.010017 -0.041010 0.098342 -vn -1.016595 2.976241 -2.961221 -v 0.010282 -0.040410 0.098226 -vn -1.016595 -2.976241 -2.961221 -v 0.010282 -0.041010 0.098226 -vn -0.515344 2.976259 -3.088160 -v 0.010562 -0.040410 0.098155 -vn -0.515344 -2.976259 -3.088160 -v 0.010562 -0.041010 0.098155 -vn 0.000001 -2.976218 -3.130859 -v 0.010850 -0.041010 0.098131 -vn 0.000001 2.976218 3.130859 -v 0.010850 -0.042010 0.101631 -vn -0.515344 2.976259 3.088160 -v 0.010562 -0.042010 0.101607 -vn -0.515344 -2.976259 3.088160 -v 0.010562 -0.042610 0.101607 -vn -1.016595 2.976241 2.961221 -v 0.010282 -0.042010 0.101536 -vn -1.016595 -2.976241 2.961221 -v 0.010282 -0.042610 0.101536 -vn -1.490114 2.976263 2.753520 -v 0.010017 -0.042010 0.101420 -vn -1.490114 -2.976264 2.753520 -v 0.010017 -0.042610 0.101420 -vn -1.923011 2.976221 2.470690 -v 0.009775 -0.042010 0.101262 -vn -1.923011 -2.976220 2.470690 -v 0.009775 -0.042610 0.101262 -vn -2.303465 2.976256 2.120461 -v 0.009562 -0.042010 0.101066 -vn -2.303465 -2.976256 2.120461 -v 0.009562 -0.042610 0.101066 -vn -2.621053 2.976248 1.712420 -v 0.009385 -0.042010 0.100838 -vn -2.621053 -2.976248 1.712420 -v 0.009385 -0.042610 0.100838 -vn -2.867160 2.976243 1.257653 -v 0.009247 -0.042010 0.100584 -vn -2.867160 -2.976243 1.257653 -v 0.009247 -0.042610 0.100584 -vn -3.035059 2.976248 0.768581 -v 0.009154 -0.042010 0.100311 -vn -3.035059 -2.976247 0.768581 -v 0.009154 -0.042610 0.100311 -vn -3.120169 2.976244 0.258546 -v 0.009106 -0.042010 0.100026 -vn -3.120169 -2.976245 0.258546 -v 0.009106 -0.042610 0.100026 -vn -3.120169 2.976245 -0.258546 -v 0.009106 -0.042010 0.099737 -vn -3.120169 -2.976245 -0.258546 -v 0.009106 -0.042610 0.099737 -vn -3.035059 2.976247 -0.768581 -v 0.009154 -0.042010 0.099452 -vn -3.035059 -2.976248 -0.768581 -v 0.009154 -0.042610 0.099452 -vn -2.867160 2.976244 -1.257653 -v 0.009247 -0.042010 0.099178 -vn -2.867160 -2.976243 -1.257653 -v 0.009247 -0.042610 0.099178 -vn -2.621053 2.976248 -1.712420 -v 0.009385 -0.042010 0.098924 -vn -2.621053 -2.976248 -1.712420 -v 0.009385 -0.042610 0.098924 -vn -2.303465 2.976256 -2.120461 -v 0.009562 -0.042010 0.098696 -vn -2.303465 -2.976256 -2.120461 -v 0.009562 -0.042610 0.098696 -vn -1.923011 2.976220 -2.470690 -v 0.009775 -0.042010 0.098500 -vn -1.923011 -2.976220 -2.470690 -v 0.009775 -0.042610 0.098500 -vn -1.490114 2.976264 -2.753520 -v 0.010017 -0.042010 0.098342 -vn -1.490114 -2.976264 -2.753520 -v 0.010017 -0.042610 0.098342 -vn -1.016595 2.976241 -2.961221 -v 0.010282 -0.042010 0.098226 -vn -1.016595 -2.976241 -2.961221 -v 0.010282 -0.042610 0.098226 -vn -0.515344 2.976259 -3.088160 -v 0.010562 -0.042010 0.098155 -vn -0.515344 -2.976259 -3.088160 -v 0.010562 -0.042610 0.098155 -vn 0.000001 2.976218 -3.130859 -v 0.010850 -0.042010 0.098131 -vn 0.000000 3.326394 3.128191 -v 0.010850 -0.042010 0.101381 -vn 0.000000 -3.326394 3.128191 -v 0.010850 -0.041010 0.101381 -vn -0.574800 -3.326388 3.074929 -v 0.010574 -0.041010 0.101356 -vn -0.574800 3.326388 3.074929 -v 0.010574 -0.042010 0.101356 -vn -1.130023 -3.326392 2.916955 -v 0.010308 -0.041010 0.101280 -vn -1.130023 3.326392 2.916955 -v 0.010308 -0.042010 0.101280 -vn -1.646767 -3.326389 2.659651 -v 0.010060 -0.041010 0.101157 -vn -1.646767 3.326389 2.659651 -v 0.010060 -0.042010 0.101157 -vn -2.107450 -3.326408 2.311758 -v 0.009839 -0.041010 0.100990 -vn -2.107450 3.326408 2.311757 -v 0.009839 -0.042010 0.100990 -vn -2.496364 -3.326388 1.885139 -v 0.009653 -0.041010 0.100785 -vn -2.496364 3.326388 1.885140 -v 0.009653 -0.042010 0.100785 -vn -2.800246 -3.326388 1.394348 -v 0.009507 -0.041010 0.100550 -vn -2.800246 3.326388 1.394348 -v 0.009507 -0.042010 0.100550 -vn -3.008774 -3.326387 0.856076 -v 0.009407 -0.041010 0.100292 -vn -3.008773 3.326387 0.856076 -v 0.009407 -0.042010 0.100292 -vn -3.114846 -3.326396 0.288640 -v 0.009356 -0.041010 0.100020 -vn -3.114846 3.326396 0.288640 -v 0.009356 -0.042010 0.100020 -vn -3.114846 -3.326396 -0.288640 -v 0.009356 -0.041010 0.099743 -vn -3.114846 3.326396 -0.288640 -v 0.009356 -0.042010 0.099743 -vn -3.008773 -3.326387 -0.856076 -v 0.009407 -0.041010 0.099471 -vn -3.008774 3.326387 -0.856076 -v 0.009407 -0.042010 0.099471 -vn -2.800246 -3.326388 -1.394348 -v 0.009507 -0.041010 0.099213 -vn -2.800246 3.326388 -1.394348 -v 0.009507 -0.042010 0.099213 -vn -2.496364 -3.326388 -1.885140 -v 0.009653 -0.041010 0.098977 -vn -2.496364 3.326388 -1.885139 -v 0.009653 -0.042010 0.098977 -vn -2.107450 -3.326408 -2.311757 -v 0.009839 -0.041010 0.098773 -vn -2.107450 3.326408 -2.311758 -v 0.009839 -0.042010 0.098773 -vn -1.646767 -3.326389 -2.659651 -v 0.010060 -0.041010 0.098606 -vn -1.646767 3.326389 -2.659651 -v 0.010060 -0.042010 0.098606 -vn -1.130023 -3.326392 -2.916955 -v 0.010308 -0.041010 0.098482 -vn -1.130023 3.326392 -2.916955 -v 0.010308 -0.042010 0.098482 -vn -0.574800 -3.326388 -3.074929 -v 0.010574 -0.041010 0.098407 -vn -0.574800 3.326388 -3.074929 -v 0.010574 -0.042010 0.098407 -vn 0.000000 -3.326394 -3.128191 -v 0.010850 -0.041010 0.098381 -vn 0.000000 3.326394 -3.128191 -v 0.010850 -0.042010 0.098381 -vn 0.694638 3.365975 -3.043579 -v 0.010627 -0.040410 0.100856 -vn 0.694638 -3.365975 -3.043579 -v 0.010627 -0.042610 0.100856 -vn 1.354509 3.366031 -2.812675 -v 0.010416 -0.040410 0.100782 -vn 1.354509 -3.366031 -2.812675 -v 0.010416 -0.042610 0.100782 -vn 1.946452 3.365968 -2.440743 -v 0.010227 -0.040410 0.100663 -vn 1.946452 -3.365968 -2.440743 -v 0.010227 -0.042610 0.100663 -vn 2.440755 3.366010 -1.946426 -v 0.010068 -0.040410 0.100505 -vn 2.440755 -3.366010 -1.946426 -v 0.010068 -0.042610 0.100505 -vn 2.812684 3.365969 -1.354516 -v 0.009949 -0.040410 0.100315 -vn 2.812684 -3.365969 -1.354516 -v 0.009949 -0.042610 0.100315 -vn 3.043562 3.366006 -0.694686 -v 0.009875 -0.040410 0.100104 -vn 3.043563 -3.366006 -0.694687 -v 0.009875 -0.042610 0.100104 -vn 3.121841 3.365982 -0.000006 -v 0.009850 -0.040410 0.099881 -vn 3.121840 -3.365982 -0.000006 -v 0.009850 -0.042610 0.099881 -vn 3.043563 3.366010 0.694681 -v 0.009875 -0.040410 0.099659 -vn 3.043563 -3.366010 0.694681 -v 0.009875 -0.042610 0.099659 -vn 2.812684 3.365969 1.354516 -v 0.009949 -0.040410 0.099447 -vn 2.812684 -3.365969 1.354516 -v 0.009949 -0.042610 0.099447 -vn 2.440755 3.366010 1.946426 -v 0.010068 -0.040410 0.099258 -vn 2.440755 -3.366010 1.946426 -v 0.010068 -0.042610 0.099258 -vn 1.946415 3.365996 2.440767 -v 0.010227 -0.040410 0.099099 -vn 1.946415 -3.365996 2.440767 -v 0.010227 -0.042610 0.099099 -vn 1.354518 3.365972 2.812682 -v 0.010416 -0.040410 0.098980 -vn 1.354518 -3.365971 2.812681 -v 0.010416 -0.042610 0.098980 -vn 0.694684 3.366007 3.043562 -v 0.010627 -0.040410 0.098906 -vn 0.694685 -3.366007 3.043563 -v 0.010627 -0.042610 0.098906 -vn 3.120169 2.976245 0.258546 -v 0.012594 -0.040410 0.100026 -vn 3.120169 2.976245 -0.258546 -v 0.012594 -0.040410 0.099737 -vn 3.035059 2.976248 -0.768581 -v 0.012546 -0.040410 0.099452 -vn 1.016593 2.976240 -2.961222 -v 0.011418 -0.040410 0.098226 -vn 0.515342 2.976261 -3.088161 -v 0.011138 -0.040410 0.098155 -vn 2.867160 2.976243 -1.257653 -v 0.012453 -0.040410 0.099178 -vn 2.621053 2.976248 -1.712420 -v 0.012315 -0.040410 0.098924 -vn 2.303465 2.976256 -2.120461 -v 0.012138 -0.040410 0.098696 -vn 1.923011 2.976220 -2.470690 -v 0.011925 -0.040410 0.098500 -vn 1.490114 2.976264 -2.753520 -v 0.011683 -0.040410 0.098342 -vn 2.621053 2.976248 1.712420 -v 0.012315 -0.040410 0.100838 -vn 2.867160 2.976243 1.257653 -v 0.012453 -0.040410 0.100584 -vn 3.035059 2.976247 0.768581 -v 0.012546 -0.040410 0.100311 -vn 1.016593 2.976240 2.961222 -v 0.011418 -0.040410 0.101536 -vn 1.490114 2.976263 2.753520 -v 0.011683 -0.040410 0.101420 -vn 1.923011 2.976220 2.470690 -v 0.011925 -0.040410 0.101262 -vn 2.303465 2.976256 2.120462 -v 0.012138 -0.040410 0.101066 -vn 0.515342 2.976261 3.088161 -v 0.011138 -0.040410 0.101607 -vn 1.016593 -2.976240 2.961222 -v 0.011418 -0.042610 0.101536 -vn 0.515342 -2.976261 3.088161 -v 0.011138 -0.042610 0.101607 -vn 2.621053 -2.976248 1.712420 -v 0.012315 -0.042610 0.100838 -vn 2.303465 -2.976256 2.120461 -v 0.012138 -0.042610 0.101066 -vn 1.923011 -2.976221 2.470690 -v 0.011925 -0.042610 0.101262 -vn 1.490114 -2.976264 2.753520 -v 0.011683 -0.042610 0.101420 -vn 3.120169 -2.976245 -0.258546 -v 0.012594 -0.042610 0.099737 -vn 3.120169 -2.976245 0.258546 -v 0.012594 -0.042610 0.100026 -vn 3.035059 -2.976248 0.768581 -v 0.012546 -0.042610 0.100311 -vn 2.867160 -2.976243 1.257653 -v 0.012453 -0.042610 0.100584 -vn 2.621053 -2.976248 -1.712420 -v 0.012315 -0.042610 0.098924 -vn 2.867160 -2.976243 -1.257653 -v 0.012453 -0.042610 0.099178 -vn 3.035059 -2.976247 -0.768581 -v 0.012546 -0.042610 0.099452 -vn 0.515342 -2.976261 -3.088160 -v 0.011138 -0.042610 0.098155 -vn 1.016593 -2.976240 -2.961222 -v 0.011418 -0.042610 0.098226 -vn 1.490114 -2.976264 -2.753520 -v 0.011683 -0.042610 0.098342 -vn 1.923011 -2.976220 -2.470690 -v 0.011925 -0.042610 0.098500 -vn 2.303465 -2.976256 -2.120461 -v 0.012138 -0.042610 0.098696 -vn 0.515342 -2.976261 -3.088161 -v 0.011138 -0.041010 0.098155 -vn 1.016593 -2.976240 -2.961222 -v 0.011418 -0.041010 0.098226 -vn 1.490114 -2.976264 -2.753520 -v 0.011683 -0.041010 0.098342 -vn 1.923011 -2.976220 -2.470690 -v 0.011925 -0.041010 0.098500 -vn 2.303465 -2.976256 -2.120462 -v 0.012138 -0.041010 0.098696 -vn 2.621053 -2.976248 -1.712420 -v 0.012315 -0.041010 0.098924 -vn 2.867160 -2.976244 -1.257654 -v 0.012453 -0.041010 0.099178 -vn 3.035059 -2.976247 -0.768581 -v 0.012546 -0.041010 0.099452 -vn 3.120169 -2.976245 -0.258546 -v 0.012594 -0.041010 0.099737 -vn 3.120169 -2.976244 0.258546 -v 0.012594 -0.041010 0.100026 -vn 3.035059 -2.976248 0.768581 -v 0.012546 -0.041010 0.100311 -vn 2.867160 -2.976243 1.257653 -v 0.012453 -0.041010 0.100584 -vn 2.621053 -2.976248 1.712420 -v 0.012315 -0.041010 0.100838 -vn 2.303465 -2.976256 2.120462 -v 0.012138 -0.041010 0.101066 -vn 1.923011 -2.976221 2.470690 -v 0.011925 -0.041010 0.101262 -vn 1.490114 -2.976263 2.753520 -v 0.011683 -0.041010 0.101420 -vn 1.016593 -2.976240 2.961222 -v 0.011418 -0.041010 0.101536 -vn 0.515342 -2.976262 3.088161 -v 0.011138 -0.041010 0.101607 -vn 0.515342 2.976262 -3.088161 -v 0.011138 -0.042010 0.098155 -vn 1.016593 2.976240 -2.961222 -v 0.011418 -0.042010 0.098226 -vn 1.490114 2.976263 -2.753520 -v 0.011683 -0.042010 0.098342 -vn 1.923011 2.976221 -2.470690 -v 0.011925 -0.042010 0.098500 -vn 2.303465 2.976256 -2.120461 -v 0.012138 -0.042010 0.098696 -vn 2.621053 2.976248 -1.712420 -v 0.012315 -0.042010 0.098924 -vn 2.867160 2.976243 -1.257653 -v 0.012453 -0.042010 0.099178 -vn 3.035059 2.976248 -0.768581 -v 0.012546 -0.042010 0.099452 -vn 3.120169 2.976244 -0.258546 -v 0.012594 -0.042010 0.099737 -vn 3.120169 2.976245 0.258546 -v 0.012594 -0.042010 0.100026 -vn 3.035059 2.976247 0.768581 -v 0.012546 -0.042010 0.100311 -vn 2.867160 2.976244 1.257653 -v 0.012453 -0.042010 0.100584 -vn 2.621053 2.976248 1.712420 -v 0.012315 -0.042010 0.100838 -vn 2.303465 2.976256 2.120461 -v 0.012138 -0.042010 0.101066 -vn 1.923011 2.976220 2.470690 -v 0.011925 -0.042010 0.101262 -vn 1.490114 2.976264 2.753520 -v 0.011683 -0.042010 0.101420 -vn 1.016593 2.976240 2.961222 -v 0.011418 -0.042010 0.101536 -vn 0.515342 2.976261 3.088160 -v 0.011138 -0.042010 0.101607 -vn 2.107450 -3.326399 2.311759 -v 0.011861 -0.041010 0.100990 -vn 1.646772 -3.326393 2.659647 -v 0.011640 -0.041010 0.101157 -vn 1.130023 -3.326392 2.916955 -v 0.011392 -0.041010 0.101280 -vn 0.574800 -3.326388 3.074929 -v 0.011126 -0.041010 0.101356 -vn 2.107449 -3.326399 -2.311759 -v 0.011861 -0.041010 0.098773 -vn 2.496359 -3.326393 -1.885145 -v 0.012047 -0.041010 0.098977 -vn 2.800246 -3.326388 -1.394348 -v 0.012193 -0.041010 0.099213 -vn 3.008774 -3.326387 -0.856076 -v 0.012293 -0.041010 0.099471 -vn 3.114846 -3.326396 -0.288640 -v 0.012344 -0.041010 0.099743 -vn 3.114846 -3.326396 0.288640 -v 0.012344 -0.041010 0.100020 -vn 3.008773 -3.326387 0.856076 -v 0.012293 -0.041010 0.100292 -vn 2.800246 -3.326388 1.394348 -v 0.012193 -0.041010 0.100550 -vn 2.496359 -3.326393 1.885145 -v 0.012047 -0.041010 0.100785 -vn 0.574800 -3.326388 -3.074929 -v 0.011126 -0.041010 0.098407 -vn 1.130023 -3.326392 -2.916955 -v 0.011392 -0.041010 0.098482 -vn 1.646772 -3.326393 -2.659647 -v 0.011640 -0.041010 0.098606 -vn 2.107450 3.326399 -2.311759 -v 0.011861 -0.042010 0.098773 -vn 1.646772 3.326393 -2.659647 -v 0.011640 -0.042010 0.098606 -vn 1.130023 3.326392 -2.916955 -v 0.011392 -0.042010 0.098482 -vn 0.574800 3.326388 -3.074929 -v 0.011126 -0.042010 0.098407 -vn 2.107449 3.326399 2.311759 -v 0.011861 -0.042010 0.100990 -vn 2.496359 3.326393 1.885145 -v 0.012047 -0.042010 0.100785 -vn 2.800246 3.326388 1.394348 -v 0.012193 -0.042010 0.100550 -vn 3.008774 3.326387 0.856076 -v 0.012293 -0.042010 0.100292 -vn 3.114846 3.326396 0.288640 -v 0.012344 -0.042010 0.100020 -vn 3.114846 3.326396 -0.288640 -v 0.012344 -0.042010 0.099743 -vn 3.008773 3.326387 -0.856076 -v 0.012293 -0.042010 0.099471 -vn 2.800246 3.326388 -1.394348 -v 0.012193 -0.042010 0.099213 -vn 2.496359 3.326393 -1.885145 -v 0.012047 -0.042010 0.098977 -vn 0.574800 3.326388 3.074929 -v 0.011126 -0.042010 0.101356 -vn 1.130023 3.326392 2.916955 -v 0.011392 -0.042010 0.101280 -vn 1.646772 3.326393 2.659647 -v 0.011640 -0.042010 0.101157 -vn 0.000002 -3.365963 -3.121844 -v 0.036250 -0.042010 0.093050 -vn 0.000002 3.365963 -3.121844 -v 0.036250 -0.039010 0.093050 -vn -0.694653 -3.366009 -3.043570 -v 0.036584 -0.042010 0.093012 -vn -0.694653 3.366009 -3.043570 -v 0.036584 -0.039010 0.093012 -vn -1.354533 -3.366003 -2.812669 -v 0.036901 -0.042010 0.092901 -vn -1.354533 3.366003 -2.812669 -v 0.036901 -0.039010 0.092901 -vn -1.946442 -3.365973 -2.440751 -v 0.037185 -0.042010 0.092723 -vn -1.946441 3.365973 -2.440751 -v 0.037185 -0.039010 0.092723 -vn -2.440746 -3.366003 -1.946439 -v 0.037423 -0.042010 0.092485 -vn -2.440746 3.366003 -1.946439 -v 0.037423 -0.039010 0.092485 -vn -2.812682 -3.365987 -1.354512 -v 0.037601 -0.042010 0.092201 -vn -2.812682 3.365988 -1.354512 -v 0.037601 -0.039010 0.092201 -vn -3.043568 -3.365996 -0.694672 -v 0.037712 -0.042010 0.091884 -vn -3.043568 3.365997 -0.694672 -v 0.037712 -0.039010 0.091884 -vn -3.121841 -3.365984 -0.000004 -v 0.037750 -0.042010 0.091550 -vn -3.121841 3.365984 -0.000004 -v 0.037750 -0.039010 0.091550 -vn -3.043569 -3.365999 0.694668 -v 0.037712 -0.042010 0.091216 -vn -3.043568 3.365999 0.694668 -v 0.037712 -0.039010 0.091216 -vn -2.812672 -3.365999 1.354528 -v 0.037601 -0.042010 0.090899 -vn -2.812673 3.365999 1.354528 -v 0.037601 -0.039010 0.090899 -vn -2.440754 -3.365976 1.946437 -v 0.037423 -0.042010 0.090615 -vn -2.440754 3.365976 1.946437 -v 0.037423 -0.039010 0.090615 -vn -1.946434 -3.366007 2.440749 -v 0.037185 -0.042010 0.090377 -vn -1.946434 3.366007 2.440750 -v 0.037185 -0.039010 0.090377 -vn -1.354508 -3.365984 2.812685 -v 0.036901 -0.042010 0.090199 -vn -1.354508 3.365983 2.812685 -v 0.036901 -0.039010 0.090199 -vn -0.694687 -3.365987 3.043566 -v 0.036584 -0.042010 0.090088 -vn -0.694687 3.365987 3.043566 -v 0.036584 -0.039010 0.090088 -vn 0.000002 -3.366007 3.121836 -v 0.036250 -0.042010 0.090050 -vn 0.000002 3.366007 3.121837 -v 0.036250 -0.039010 0.090050 -vn -0.000000 -2.976235 3.130862 -v 0.036250 -0.040010 0.094550 -vn -0.515328 2.976253 3.088162 -v 0.035756 -0.039010 0.094509 -vn -0.515328 -2.976253 3.088162 -v 0.035756 -0.040010 0.094509 -vn -1.016578 2.976250 2.961228 -v 0.035276 -0.039010 0.094387 -vn -1.016578 -2.976250 2.961228 -v 0.035276 -0.040010 0.094387 -vn -1.490117 2.976240 2.753515 -v 0.034822 -0.039010 0.094188 -vn -1.490117 -2.976239 2.753515 -v 0.034822 -0.040010 0.094188 -vn -1.923023 2.976240 2.470684 -v 0.034407 -0.039010 0.093917 -vn -1.923022 -2.976240 2.470684 -v 0.034407 -0.040010 0.093917 -vn -2.303458 2.976251 2.120469 -v 0.034043 -0.039010 0.093582 -vn -2.303458 -2.976251 2.120469 -v 0.034043 -0.040010 0.093582 -vn -2.621049 2.976252 1.712427 -v 0.033739 -0.039010 0.093191 -vn -2.621049 -2.976252 1.712427 -v 0.033739 -0.040010 0.093191 -vn -2.867158 2.976236 1.257656 -v 0.033503 -0.039010 0.092755 -vn -2.867158 -2.976236 1.257656 -v 0.033503 -0.040010 0.092755 -vn -3.035060 2.976254 0.768583 -v 0.033342 -0.039010 0.092286 -vn -3.035060 -2.976254 0.768583 -v 0.033342 -0.040010 0.092286 -vn -3.120168 2.976242 0.258551 -v 0.033260 -0.039010 0.091798 -vn -3.120168 -2.976241 0.258551 -v 0.033260 -0.040010 0.091798 -vn -3.120169 2.976244 -0.258548 -v 0.033260 -0.039010 0.091302 -vn -3.120169 -2.976244 -0.258548 -v 0.033260 -0.040010 0.091302 -vn -3.035058 2.976246 -0.768586 -v 0.033342 -0.039010 0.090814 -vn -3.035058 -2.976246 -0.768586 -v 0.033342 -0.040010 0.090814 -vn -2.867161 2.976248 -1.257654 -v 0.033503 -0.039010 0.090345 -vn -2.867161 -2.976248 -1.257654 -v 0.033503 -0.040010 0.090345 -vn -2.621055 2.976245 -1.712417 -v 0.033739 -0.039010 0.089909 -vn -2.621055 -2.976245 -1.712417 -v 0.033739 -0.040010 0.089909 -vn -2.303445 2.976240 -2.120481 -v 0.034043 -0.039010 0.089518 -vn -2.303445 -2.976240 -2.120481 -v 0.034043 -0.040010 0.089518 -vn -1.923010 2.976251 -2.470696 -v 0.034407 -0.039010 0.089183 -vn -1.923010 -2.976251 -2.470696 -v 0.034407 -0.040010 0.089183 -vn -1.490137 2.976253 -2.753506 -v 0.034822 -0.039010 0.088912 -vn -1.490137 -2.976253 -2.753506 -v 0.034822 -0.040010 0.088912 -vn -1.016598 2.976236 -2.961220 -v 0.035276 -0.039010 0.088713 -vn -1.016598 -2.976236 -2.961220 -v 0.035276 -0.040010 0.088713 -vn -0.515305 2.976238 -3.088164 -v 0.035756 -0.039010 0.088591 -vn -0.515305 -2.976238 -3.088164 -v 0.035756 -0.040010 0.088591 -vn 0.000000 -2.976266 -3.130865 -v 0.036250 -0.040010 0.088550 -vn 0.000000 2.976236 3.130861 -v 0.036250 -0.041010 0.094550 -vn -0.515328 2.976253 3.088162 -v 0.035756 -0.041010 0.094509 -vn -0.515328 -2.976253 3.088162 -v 0.035756 -0.042010 0.094509 -vn -1.016578 2.976250 2.961228 -v 0.035276 -0.041010 0.094387 -vn -1.016578 -2.976250 2.961228 -v 0.035276 -0.042010 0.094387 -vn -1.490118 2.976239 2.753515 -v 0.034822 -0.041010 0.094188 -vn -1.490117 -2.976239 2.753515 -v 0.034822 -0.042010 0.094188 -vn -1.923023 2.976240 2.470684 -v 0.034407 -0.041010 0.093917 -vn -1.923023 -2.976240 2.470684 -v 0.034407 -0.042010 0.093917 -vn -2.303458 2.976251 2.120469 -v 0.034043 -0.041010 0.093582 -vn -2.303458 -2.976251 2.120469 -v 0.034043 -0.042010 0.093582 -vn -2.621049 2.976252 1.712427 -v 0.033739 -0.041010 0.093191 -vn -2.621049 -2.976252 1.712427 -v 0.033739 -0.042010 0.093191 -vn -2.867158 2.976236 1.257656 -v 0.033503 -0.041010 0.092755 -vn -2.867158 -2.976236 1.257656 -v 0.033503 -0.042010 0.092755 -vn -3.035060 2.976254 0.768583 -v 0.033342 -0.041010 0.092286 -vn -3.035060 -2.976254 0.768583 -v 0.033342 -0.042010 0.092286 -vn -3.120168 2.976241 0.258551 -v 0.033260 -0.041010 0.091798 -vn -3.120168 -2.976242 0.258551 -v 0.033260 -0.042010 0.091798 -vn -3.120168 2.976244 -0.258548 -v 0.033260 -0.041010 0.091302 -vn -3.120169 -2.976244 -0.258548 -v 0.033260 -0.042010 0.091302 -vn -3.035058 2.976246 -0.768586 -v 0.033342 -0.041010 0.090814 -vn -3.035058 -2.976246 -0.768586 -v 0.033342 -0.042010 0.090814 -vn -2.867161 2.976248 -1.257654 -v 0.033503 -0.041010 0.090345 -vn -2.867161 -2.976248 -1.257654 -v 0.033503 -0.042010 0.090345 -vn -2.621055 2.976245 -1.712417 -v 0.033739 -0.041010 0.089909 -vn -2.621054 -2.976245 -1.712417 -v 0.033739 -0.042010 0.089909 -vn -2.303445 2.976240 -2.120480 -v 0.034043 -0.041010 0.089518 -vn -2.303445 -2.976240 -2.120481 -v 0.034043 -0.042010 0.089518 -vn -1.923010 2.976251 -2.470696 -v 0.034407 -0.041010 0.089183 -vn -1.923010 -2.976251 -2.470696 -v 0.034407 -0.042010 0.089183 -vn -1.490137 2.976253 -2.753507 -v 0.034822 -0.041010 0.088912 -vn -1.490137 -2.976253 -2.753507 -v 0.034822 -0.042010 0.088912 -vn -1.016598 2.976236 -2.961220 -v 0.035276 -0.041010 0.088713 -vn -1.016598 -2.976236 -2.961220 -v 0.035276 -0.042010 0.088713 -vn -0.515305 2.976238 -3.088164 -v 0.035756 -0.041010 0.088591 -vn -0.515305 -2.976238 -3.088164 -v 0.035756 -0.042010 0.088591 -vn 0.000000 2.976265 -3.130865 -v 0.036250 -0.041010 0.088550 -vn -0.000001 3.326367 3.128195 -v 0.036250 -0.041010 0.093950 -vn -0.000001 -3.326367 3.128195 -v 0.036250 -0.040010 0.093950 -vn -0.574796 -3.326411 3.074926 -v 0.035809 -0.040010 0.093909 -vn -0.574796 3.326411 3.074926 -v 0.035809 -0.041010 0.093909 -vn -1.130040 -3.326382 2.916950 -v 0.035383 -0.040010 0.093788 -vn -1.130040 3.326382 2.916950 -v 0.035383 -0.041010 0.093788 -vn -1.646781 -3.326398 2.659641 -v 0.034987 -0.040010 0.093591 -vn -1.646781 3.326398 2.659640 -v 0.034987 -0.041010 0.093591 -vn -2.107454 -3.326390 2.311757 -v 0.034633 -0.040010 0.093324 -vn -2.107454 3.326390 2.311757 -v 0.034633 -0.041010 0.093324 -vn -2.496352 -3.326392 1.885154 -v 0.034335 -0.040010 0.092996 -vn -2.496352 3.326392 1.885154 -v 0.034335 -0.041010 0.092996 -vn -2.800241 -3.326389 1.394359 -v 0.034102 -0.040010 0.092620 -vn -2.800241 3.326389 1.394358 -v 0.034102 -0.041010 0.092620 -vn -3.008772 -3.326393 0.856079 -v 0.033942 -0.040010 0.092207 -vn -3.008772 3.326392 0.856079 -v 0.033942 -0.041010 0.092207 -vn -3.114846 -3.326395 0.288637 -v 0.033860 -0.040010 0.091771 -vn -3.114846 3.326395 0.288637 -v 0.033860 -0.041010 0.091771 -vn -3.114845 -3.326398 -0.288642 -v 0.033860 -0.040010 0.091329 -vn -3.114845 3.326398 -0.288642 -v 0.033860 -0.041010 0.091329 -vn -3.008775 -3.326384 -0.856075 -v 0.033942 -0.040010 0.090893 -vn -3.008775 3.326383 -0.856075 -v 0.033942 -0.041010 0.090893 -vn -2.800237 -3.326403 -1.394361 -v 0.034102 -0.040010 0.090480 -vn -2.800237 3.326404 -1.394361 -v 0.034102 -0.041010 0.090480 -vn -2.496356 -3.326372 -1.885153 -v 0.034335 -0.040010 0.090104 -vn -2.496357 3.326372 -1.885153 -v 0.034335 -0.041010 0.090104 -vn -2.107449 -3.326415 -2.311757 -v 0.034633 -0.040010 0.089776 -vn -2.107449 3.326414 -2.311757 -v 0.034633 -0.041010 0.089776 -vn -1.646785 -3.326370 -2.659643 -v 0.034987 -0.040010 0.089509 -vn -1.646785 3.326370 -2.659643 -v 0.034987 -0.041010 0.089509 -vn -1.130037 -3.326414 -2.916946 -v 0.035383 -0.040010 0.089312 -vn -1.130037 3.326414 -2.916947 -v 0.035383 -0.041010 0.089312 -vn -0.574798 -3.326378 -3.074931 -v 0.035809 -0.040010 0.089191 -vn -0.574798 3.326378 -3.074931 -v 0.035809 -0.041010 0.089191 -vn -0.000001 -3.326401 -3.128190 -v 0.036250 -0.040010 0.089150 -vn -0.000001 3.326401 -3.128190 -v 0.036250 -0.041010 0.089150 -vn 1.016595 2.976234 -2.961221 -v 0.037224 -0.039010 0.088713 -vn 0.515302 2.976240 -3.088164 -v 0.036744 -0.039010 0.088591 -vn 0.694689 3.365985 3.043566 -v 0.035916 -0.039010 0.090088 -vn 2.621054 2.976233 -1.712416 -v 0.038762 -0.039010 0.089909 -vn 2.303445 2.976251 -2.120482 -v 0.038457 -0.039010 0.089518 -vn 1.923016 2.976246 -2.470690 -v 0.038093 -0.039010 0.089183 -vn 1.490137 2.976253 -2.753506 -v 0.037678 -0.039010 0.088912 -vn 3.120168 2.976242 0.258551 -v 0.039240 -0.039010 0.091798 -vn 3.120169 2.976244 -0.258548 -v 0.039240 -0.039010 0.091302 -vn 3.035058 2.976246 -0.768586 -v 0.039158 -0.039010 0.090814 -vn 2.867166 2.976255 -1.257645 -v 0.038997 -0.039010 0.090345 -vn 1.354525 3.365997 -2.812675 -v 0.035599 -0.039010 0.092901 -vn 0.694655 3.366007 -3.043570 -v 0.035916 -0.039010 0.093012 -vn 1.354500 3.365978 2.812690 -v 0.035599 -0.039010 0.090199 -vn 1.946427 3.366013 2.440754 -v 0.035315 -0.039010 0.090377 -vn 2.440754 3.365976 1.946437 -v 0.035077 -0.039010 0.090615 -vn 0.515325 2.976254 3.088163 -v 0.036744 -0.039010 0.094509 -vn 1.016575 2.976248 2.961229 -v 0.037224 -0.039010 0.094387 -vn 1.490117 2.976239 2.753515 -v 0.037678 -0.039010 0.094188 -vn 1.923028 2.976235 2.470679 -v 0.038093 -0.039010 0.093917 -vn 2.812682 3.365988 -1.354512 -v 0.034899 -0.039010 0.092201 -vn 2.440746 3.366003 -1.946439 -v 0.035077 -0.039010 0.092485 -vn 1.946434 3.365978 -2.440756 -v 0.035315 -0.039010 0.092723 -vn 2.303458 2.976262 2.120471 -v 0.038457 -0.039010 0.093582 -vn 2.621048 2.976240 1.712425 -v 0.038762 -0.039010 0.093191 -vn 2.867163 2.976243 1.257647 -v 0.038997 -0.039010 0.092755 -vn 3.035060 2.976254 0.768583 -v 0.039158 -0.039010 0.092286 -vn 3.043569 3.365999 0.694668 -v 0.034788 -0.039010 0.091216 -vn 3.121841 3.365984 -0.000004 -v 0.034750 -0.039010 0.091550 -vn 3.043568 3.365996 -0.694672 -v 0.034788 -0.039010 0.091884 -vn 2.812672 3.365999 1.354528 -v 0.034899 -0.039010 0.090899 -vn 0.694689 -3.365985 3.043566 -v 0.035916 -0.042010 0.090088 -vn 1.354500 -3.365978 2.812690 -v 0.035599 -0.042010 0.090199 -vn 1.946426 -3.366013 2.440754 -v 0.035315 -0.042010 0.090377 -vn 2.440754 -3.365976 1.946437 -v 0.035077 -0.042010 0.090615 -vn 2.812673 -3.365999 1.354528 -v 0.034899 -0.042010 0.090899 -vn 3.043568 -3.365999 0.694668 -v 0.034788 -0.042010 0.091216 -vn 3.121841 -3.365984 -0.000004 -v 0.034750 -0.042010 0.091550 -vn 3.043568 -3.365997 -0.694672 -v 0.034788 -0.042010 0.091884 -vn 2.812682 -3.365988 -1.354512 -v 0.034899 -0.042010 0.092201 -vn 2.440746 -3.366003 -1.946439 -v 0.035077 -0.042010 0.092485 -vn 1.946434 -3.365978 -2.440756 -v 0.035315 -0.042010 0.092723 -vn 1.354525 -3.365997 -2.812675 -v 0.035599 -0.042010 0.092901 -vn 0.694655 -3.366007 -3.043570 -v 0.035916 -0.042010 0.093012 -vn 0.515302 -2.976240 -3.088164 -v 0.036744 -0.040010 0.088591 -vn 1.016595 -2.976234 -2.961220 -v 0.037224 -0.040010 0.088713 -vn 1.490137 -2.976254 -2.753506 -v 0.037678 -0.040010 0.088912 -vn 1.923016 -2.976246 -2.470690 -v 0.038093 -0.040010 0.089183 -vn 2.303445 -2.976251 -2.120482 -v 0.038457 -0.040010 0.089518 -vn 2.621054 -2.976233 -1.712416 -v 0.038762 -0.040010 0.089909 -vn 2.867166 -2.976254 -1.257645 -v 0.038997 -0.040010 0.090345 -vn 3.035058 -2.976246 -0.768586 -v 0.039158 -0.040010 0.090814 -vn 3.120169 -2.976244 -0.258548 -v 0.039240 -0.040010 0.091302 -vn 3.120168 -2.976241 0.258551 -v 0.039240 -0.040010 0.091798 -vn 3.035060 -2.976254 0.768583 -v 0.039158 -0.040010 0.092286 -vn 2.867162 -2.976242 1.257647 -v 0.038997 -0.040010 0.092755 -vn 2.621048 -2.976240 1.712425 -v 0.038762 -0.040010 0.093191 -vn 2.303458 -2.976262 2.120471 -v 0.038457 -0.040010 0.093582 -vn 1.923028 -2.976235 2.470679 -v 0.038093 -0.040010 0.093917 -vn 1.490117 -2.976239 2.753515 -v 0.037678 -0.040010 0.094188 -vn 1.016575 -2.976248 2.961229 -v 0.037224 -0.040010 0.094387 -vn 0.515325 -2.976255 3.088163 -v 0.036744 -0.040010 0.094509 -vn 1.016595 -2.976234 -2.961221 -v 0.037224 -0.042010 0.088713 -vn 1.490137 -2.976253 -2.753507 -v 0.037678 -0.042010 0.088912 -vn 1.923016 -2.976246 -2.470690 -v 0.038093 -0.042010 0.089183 -vn 0.515302 -2.976240 -3.088164 -v 0.036744 -0.042010 0.088591 -vn 1.016575 -2.976248 2.961229 -v 0.037224 -0.042010 0.094387 -vn 0.515325 -2.976255 3.088162 -v 0.036744 -0.042010 0.094509 -vn 2.303445 -2.976251 -2.120482 -v 0.038457 -0.042010 0.089518 -vn 2.621054 -2.976233 -1.712416 -v 0.038762 -0.042010 0.089909 -vn 2.867166 -2.976255 -1.257645 -v 0.038997 -0.042010 0.090345 -vn 2.621048 -2.976240 1.712425 -v 0.038762 -0.042010 0.093191 -vn 2.303458 -2.976262 2.120471 -v 0.038457 -0.042010 0.093582 -vn 1.923028 -2.976236 2.470679 -v 0.038093 -0.042010 0.093917 -vn 1.490117 -2.976240 2.753515 -v 0.037678 -0.042010 0.094188 -vn 3.035058 -2.976246 -0.768586 -v 0.039158 -0.042010 0.090814 -vn 3.120168 -2.976244 -0.258548 -v 0.039240 -0.042010 0.091302 -vn 3.120168 -2.976242 0.258551 -v 0.039240 -0.042010 0.091798 -vn 3.035060 -2.976254 0.768583 -v 0.039158 -0.042010 0.092286 -vn 2.867163 -2.976243 1.257647 -v 0.038997 -0.042010 0.092755 -vn 2.496346 -3.326398 1.885162 -v 0.038165 -0.040010 0.092996 -vn 2.107453 -3.326378 2.311759 -v 0.037867 -0.040010 0.093324 -vn 1.646782 -3.326407 2.659638 -v 0.037513 -0.040010 0.093591 -vn 1.130038 -3.326376 2.916952 -v 0.037117 -0.040010 0.093788 -vn 0.574798 -3.326415 3.074926 -v 0.036691 -0.040010 0.093909 -vn 0.574800 -3.326382 -3.074930 -v 0.036691 -0.040010 0.089191 -vn 1.130035 -3.326407 -2.916948 -v 0.037117 -0.040010 0.089312 -vn 1.646786 -3.326378 -2.659641 -v 0.037513 -0.040010 0.089509 -vn 2.107449 -3.326403 -2.311759 -v 0.037867 -0.040010 0.089776 -vn 2.496350 -3.326378 -1.885160 -v 0.038165 -0.040010 0.090104 -vn 2.800237 -3.326404 -1.394361 -v 0.038398 -0.040010 0.090480 -vn 3.008777 -3.326392 -0.856062 -v 0.038558 -0.040010 0.090893 -vn 3.114847 -3.326390 -0.288629 -v 0.038640 -0.040010 0.091329 -vn 3.114849 -3.326386 0.288625 -v 0.038640 -0.040010 0.091771 -vn 3.008774 -3.326401 0.856066 -v 0.038558 -0.040010 0.092207 -vn 2.800241 -3.326389 1.394358 -v 0.038398 -0.040010 0.092620 -vn 0.515302 2.976239 -3.088164 -v 0.036744 -0.041010 0.088591 -vn 1.016595 2.976234 -2.961221 -v 0.037224 -0.041010 0.088713 -vn 1.490137 2.976253 -2.753507 -v 0.037678 -0.041010 0.088912 -vn 1.923016 2.976246 -2.470691 -v 0.038093 -0.041010 0.089183 -vn 2.303445 2.976251 -2.120482 -v 0.038457 -0.041010 0.089518 -vn 2.621054 2.976233 -1.712415 -v 0.038762 -0.041010 0.089909 -vn 2.867166 2.976255 -1.257644 -v 0.038997 -0.041010 0.090345 -vn 3.035058 2.976246 -0.768586 -v 0.039158 -0.041010 0.090814 -vn 3.120169 2.976243 -0.258548 -v 0.039240 -0.041010 0.091302 -vn 3.120168 2.976241 0.258551 -v 0.039240 -0.041010 0.091798 -vn 3.035060 2.976254 0.768583 -v 0.039158 -0.041010 0.092286 -vn 2.867163 2.976243 1.257647 -v 0.038997 -0.041010 0.092755 -vn 2.621048 2.976240 1.712425 -v 0.038762 -0.041010 0.093191 -vn 2.303458 2.976262 2.120471 -v 0.038457 -0.041010 0.093582 -vn 1.923028 2.976235 2.470679 -v 0.038093 -0.041010 0.093917 -vn 1.490117 2.976239 2.753515 -v 0.037678 -0.041010 0.094188 -vn 1.016575 2.976248 2.961229 -v 0.037224 -0.041010 0.094387 -vn 0.515325 2.976254 3.088162 -v 0.036744 -0.041010 0.094509 -vn 0.574800 3.326382 -3.074930 -v 0.036691 -0.041010 0.089191 -vn 1.130035 3.326407 -2.916948 -v 0.037117 -0.041010 0.089312 -vn 1.646786 3.326378 -2.659641 -v 0.037513 -0.041010 0.089509 -vn 2.107449 3.326403 -2.311759 -v 0.037867 -0.041010 0.089776 -vn 2.496350 3.326378 -1.885160 -v 0.038165 -0.041010 0.090104 -vn 2.800237 3.326404 -1.394361 -v 0.038398 -0.041010 0.090480 -vn 3.008777 3.326391 -0.856062 -v 0.038558 -0.041010 0.090893 -vn 3.114848 3.326390 -0.288629 -v 0.038640 -0.041010 0.091329 -vn 3.114849 3.326386 0.288625 -v 0.038640 -0.041010 0.091771 -vn 3.008775 3.326401 0.856066 -v 0.038558 -0.041010 0.092207 -vn 2.800241 3.326389 1.394359 -v 0.038398 -0.041010 0.092620 -vn 2.496345 3.326398 1.885162 -v 0.038165 -0.041010 0.092996 -vn 2.107454 3.326378 2.311759 -v 0.037867 -0.041010 0.093324 -vn 1.646782 3.326407 2.659638 -v 0.037513 -0.041010 0.093591 -vn 1.130038 3.326376 2.916952 -v 0.037117 -0.041010 0.093788 -vn 0.574798 3.326415 3.074925 -v 0.036691 -0.041010 0.093909 -vn -0.000001 -3.365962 -3.121845 -v 0.010850 -0.042010 0.093050 -vn -0.000001 3.365962 -3.121844 -v 0.010850 -0.039010 0.093050 -vn -0.694654 -3.366008 -3.043570 -v 0.011184 -0.042010 0.093012 -vn -0.694654 3.366008 -3.043570 -v 0.011184 -0.039010 0.093012 -vn -1.354529 -3.366000 -2.812672 -v 0.011501 -0.042010 0.092901 -vn -1.354529 3.366000 -2.812671 -v 0.011501 -0.039010 0.092901 -vn -1.946437 -3.365975 -2.440753 -v 0.011785 -0.042010 0.092723 -vn -1.946437 3.365976 -2.440753 -v 0.011785 -0.039010 0.092723 -vn -2.440746 -3.366003 -1.946439 -v 0.012023 -0.042010 0.092485 -vn -2.440746 3.366003 -1.946439 -v 0.012023 -0.039010 0.092485 -vn -2.812682 -3.365987 -1.354512 -v 0.012201 -0.042010 0.092201 -vn -2.812682 3.365987 -1.354512 -v 0.012201 -0.039010 0.092201 -vn -3.043568 -3.365996 -0.694672 -v 0.012312 -0.042010 0.091884 -vn -3.043568 3.365997 -0.694672 -v 0.012312 -0.039010 0.091884 -vn -3.121841 -3.365984 -0.000004 -v 0.012350 -0.042010 0.091550 -vn -3.121841 3.365984 -0.000004 -v 0.012350 -0.039010 0.091550 -vn -3.043569 -3.365999 0.694668 -v 0.012312 -0.042010 0.091216 -vn -3.043568 3.365999 0.694668 -v 0.012312 -0.039010 0.091216 -vn -2.812672 -3.365999 1.354528 -v 0.012201 -0.042010 0.090899 -vn -2.812673 3.365999 1.354528 -v 0.012201 -0.039010 0.090899 -vn -2.440754 -3.365976 1.946437 -v 0.012023 -0.042010 0.090615 -vn -2.440754 3.365976 1.946437 -v 0.012023 -0.039010 0.090615 -vn -1.946430 -3.366010 2.440752 -v 0.011785 -0.042010 0.090377 -vn -1.946430 3.366010 2.440752 -v 0.011785 -0.039010 0.090377 -vn -1.354504 -3.365981 2.812687 -v 0.011501 -0.042010 0.090199 -vn -1.354504 3.365981 2.812687 -v 0.011501 -0.039010 0.090199 -vn -0.694688 -3.365986 3.043566 -v 0.011184 -0.042010 0.090088 -vn -0.694688 3.365986 3.043566 -v 0.011184 -0.039010 0.090088 -vn -0.000001 -3.366006 3.121837 -v 0.010850 -0.042010 0.090050 -vn -0.000001 3.366006 3.121836 -v 0.010850 -0.039010 0.090050 -vn -0.000000 -2.976236 3.130862 -v 0.010850 -0.040010 0.094550 -vn -0.515327 2.976254 3.088162 -v 0.010356 -0.039010 0.094509 -vn -0.515327 -2.976254 3.088162 -v 0.010356 -0.040010 0.094509 -vn -1.016576 2.976248 2.961229 -v 0.009876 -0.039010 0.094387 -vn -1.016576 -2.976249 2.961229 -v 0.009876 -0.040010 0.094387 -vn -1.490117 2.976240 2.753515 -v 0.009422 -0.039010 0.094188 -vn -1.490117 -2.976239 2.753515 -v 0.009422 -0.040010 0.094188 -vn -1.923025 2.976238 2.470681 -v 0.009007 -0.039010 0.093917 -vn -1.923026 -2.976238 2.470682 -v 0.009007 -0.040010 0.093917 -vn -2.303458 2.976256 2.120470 -v 0.008643 -0.039010 0.093582 -vn -2.303458 -2.976257 2.120470 -v 0.008643 -0.040010 0.093582 -vn -2.621049 2.976246 1.712426 -v 0.008339 -0.039010 0.093191 -vn -2.621049 -2.976246 1.712426 -v 0.008339 -0.040010 0.093191 -vn -2.867158 2.976243 1.257657 -v 0.008103 -0.039010 0.092755 -vn -2.867158 -2.976243 1.257657 -v 0.008103 -0.040010 0.092755 -vn -3.035059 2.976246 0.768582 -v 0.007942 -0.039010 0.092286 -vn -3.035059 -2.976246 0.768582 -v 0.007942 -0.040010 0.092286 -vn -3.120169 2.976245 0.258546 -v 0.007860 -0.039010 0.091798 -vn -3.120169 -2.976245 0.258546 -v 0.007860 -0.040010 0.091798 -vn -3.120170 2.976248 -0.258542 -v 0.007860 -0.039010 0.091302 -vn -3.120170 -2.976247 -0.258542 -v 0.007860 -0.040010 0.091302 -vn -3.035057 2.976239 -0.768586 -v 0.007942 -0.039010 0.090814 -vn -3.035057 -2.976239 -0.768586 -v 0.007942 -0.040010 0.090814 -vn -2.867161 2.976255 -1.257654 -v 0.008103 -0.039010 0.090345 -vn -2.867161 -2.976255 -1.257654 -v 0.008103 -0.040010 0.090345 -vn -2.621054 2.976239 -1.712417 -v 0.008339 -0.039010 0.089909 -vn -2.621054 -2.976239 -1.712417 -v 0.008339 -0.040010 0.089909 -vn -2.303445 2.976245 -2.120481 -v 0.008643 -0.039010 0.089518 -vn -2.303445 -2.976245 -2.120481 -v 0.008643 -0.040010 0.089518 -vn -1.923012 2.976249 -2.470693 -v 0.009007 -0.039010 0.089183 -vn -1.923012 -2.976249 -2.470693 -v 0.009007 -0.040010 0.089183 -vn -1.490137 2.976254 -2.753506 -v 0.009422 -0.039010 0.088912 -vn -1.490137 -2.976253 -2.753506 -v 0.009422 -0.040010 0.088912 -vn -1.016596 2.976235 -2.961220 -v 0.009876 -0.039010 0.088713 -vn -1.016596 -2.976235 -2.961220 -v 0.009876 -0.040010 0.088713 -vn -0.515303 2.976239 -3.088164 -v 0.010356 -0.039010 0.088591 -vn -0.515303 -2.976238 -3.088164 -v 0.010356 -0.040010 0.088591 -vn 0.000000 -2.976265 -3.130865 -v 0.010850 -0.040010 0.088550 -vn 0.000000 2.976235 3.130861 -v 0.010850 -0.041010 0.094550 -vn -0.515327 2.976254 3.088162 -v 0.010356 -0.041010 0.094509 -vn -0.515327 -2.976254 3.088162 -v 0.010356 -0.042010 0.094509 -vn -1.016576 2.976249 2.961229 -v 0.009876 -0.041010 0.094387 -vn -1.016576 -2.976248 2.961229 -v 0.009876 -0.042010 0.094387 -vn -1.490118 2.976239 2.753515 -v 0.009422 -0.041010 0.094188 -vn -1.490117 -2.976240 2.753515 -v 0.009422 -0.042010 0.094188 -vn -1.923025 2.976237 2.470682 -v 0.009007 -0.041010 0.093917 -vn -1.923026 -2.976238 2.470682 -v 0.009007 -0.042010 0.093917 -vn -2.303458 2.976257 2.120470 -v 0.008643 -0.041010 0.093582 -vn -2.303458 -2.976256 2.120470 -v 0.008643 -0.042010 0.093582 -vn -2.621049 2.976246 1.712426 -v 0.008339 -0.041010 0.093191 -vn -2.621049 -2.976246 1.712426 -v 0.008339 -0.042010 0.093191 -vn -2.867158 2.976243 1.257657 -v 0.008103 -0.041010 0.092755 -vn -2.867158 -2.976243 1.257657 -v 0.008103 -0.042010 0.092755 -vn -3.035059 2.976246 0.768582 -v 0.007942 -0.041010 0.092286 -vn -3.035059 -2.976246 0.768582 -v 0.007942 -0.042010 0.092286 -vn -3.120169 2.976245 0.258546 -v 0.007860 -0.041010 0.091798 -vn -3.120169 -2.976245 0.258546 -v 0.007860 -0.042010 0.091798 -vn -3.120170 2.976247 -0.258542 -v 0.007860 -0.041010 0.091302 -vn -3.120170 -2.976248 -0.258542 -v 0.007860 -0.042010 0.091302 -vn -3.035057 2.976239 -0.768586 -v 0.007942 -0.041010 0.090814 -vn -3.035057 -2.976239 -0.768586 -v 0.007942 -0.042010 0.090814 -vn -2.867161 2.976255 -1.257654 -v 0.008103 -0.041010 0.090345 -vn -2.867161 -2.976255 -1.257654 -v 0.008103 -0.042010 0.090345 -vn -2.621054 2.976239 -1.712416 -v 0.008339 -0.041010 0.089909 -vn -2.621054 -2.976239 -1.712417 -v 0.008339 -0.042010 0.089909 -vn -2.303445 2.976245 -2.120481 -v 0.008643 -0.041010 0.089518 -vn -2.303445 -2.976245 -2.120481 -v 0.008643 -0.042010 0.089518 -vn -1.923013 2.976249 -2.470693 -v 0.009007 -0.041010 0.089183 -vn -1.923013 -2.976249 -2.470693 -v 0.009007 -0.042010 0.089183 -vn -1.490137 2.976253 -2.753507 -v 0.009422 -0.041010 0.088912 -vn -1.490137 -2.976253 -2.753507 -v 0.009422 -0.042010 0.088912 -vn -1.016596 2.976235 -2.961220 -v 0.009876 -0.041010 0.088713 -vn -1.016596 -2.976235 -2.961220 -v 0.009876 -0.042010 0.088713 -vn -0.515303 2.976239 -3.088164 -v 0.010356 -0.041010 0.088591 -vn -0.515303 -2.976239 -3.088164 -v 0.010356 -0.042010 0.088591 -vn 0.000000 2.976266 -3.130865 -v 0.010850 -0.041010 0.088550 -vn 0.000001 3.326367 3.128195 -v 0.010850 -0.041010 0.093950 -vn 0.000001 -3.326367 3.128195 -v 0.010850 -0.040010 0.093950 -vn -0.574798 -3.326415 3.074925 -v 0.010409 -0.040010 0.093909 -vn -0.574798 3.326415 3.074926 -v 0.010409 -0.041010 0.093909 -vn -1.130041 -3.326378 2.916951 -v 0.009983 -0.040010 0.093788 -vn -1.130041 3.326378 2.916951 -v 0.009983 -0.041010 0.093788 -vn -1.646781 -3.326403 2.659640 -v 0.009587 -0.040010 0.093591 -vn -1.646781 3.326403 2.659639 -v 0.009587 -0.041010 0.093591 -vn -2.107454 -3.326384 2.311758 -v 0.009233 -0.040010 0.093324 -vn -2.107454 3.326384 2.311759 -v 0.009233 -0.041010 0.093324 -vn -2.496349 -3.326395 1.885158 -v 0.008935 -0.040010 0.092996 -vn -2.496349 3.326395 1.885158 -v 0.008935 -0.041010 0.092996 -vn -2.800241 -3.326389 1.394359 -v 0.008702 -0.040010 0.092620 -vn -2.800241 3.326389 1.394358 -v 0.008702 -0.041010 0.092620 -vn -3.008773 -3.326396 0.856072 -v 0.008542 -0.040010 0.092207 -vn -3.008773 3.326396 0.856072 -v 0.008542 -0.041010 0.092207 -vn -3.114847 -3.326391 0.288631 -v 0.008460 -0.040010 0.091771 -vn -3.114848 3.326391 0.288631 -v 0.008460 -0.041010 0.091771 -vn -3.114847 -3.326394 -0.288636 -v 0.008460 -0.040010 0.091329 -vn -3.114846 3.326394 -0.288636 -v 0.008460 -0.041010 0.091329 -vn -3.008776 -3.326387 -0.856068 -v 0.008542 -0.040010 0.090893 -vn -3.008776 3.326387 -0.856068 -v 0.008542 -0.041010 0.090893 -vn -2.800237 -3.326404 -1.394361 -v 0.008702 -0.040010 0.090480 -vn -2.800237 3.326404 -1.394361 -v 0.008702 -0.041010 0.090480 -vn -2.496353 -3.326375 -1.885157 -v 0.008935 -0.040010 0.090104 -vn -2.496353 3.326375 -1.885157 -v 0.008935 -0.041010 0.090104 -vn -2.107449 -3.326409 -2.311758 -v 0.009233 -0.040010 0.089776 -vn -2.107449 3.326409 -2.311758 -v 0.009233 -0.041010 0.089776 -vn -1.646786 -3.326374 -2.659642 -v 0.009587 -0.040010 0.089509 -vn -1.646786 3.326374 -2.659642 -v 0.009587 -0.041010 0.089509 -vn -1.130038 -3.326409 -2.916947 -v 0.009983 -0.040010 0.089312 -vn -1.130038 3.326409 -2.916947 -v 0.009983 -0.041010 0.089312 -vn -0.574800 -3.326382 -3.074930 -v 0.010409 -0.040010 0.089191 -vn -0.574800 3.326382 -3.074930 -v 0.010409 -0.041010 0.089191 -vn 0.000001 -3.326401 -3.128190 -v 0.010850 -0.040010 0.089150 -vn 0.000001 3.326401 -3.128190 -v 0.010850 -0.041010 0.089150 -vn 1.016596 2.976235 -2.961220 -v 0.011824 -0.039010 0.088713 -vn 0.515303 2.976239 -3.088164 -v 0.011344 -0.039010 0.088591 -vn 0.694690 3.365989 3.043566 -v 0.010516 -0.039010 0.090088 -vn 1.354532 3.365998 -2.812671 -v 0.010199 -0.039010 0.092901 -vn 0.694655 3.366010 -3.043569 -v 0.010516 -0.039010 0.093012 -vn 2.621054 2.976239 -1.712417 -v 0.013361 -0.039010 0.089909 -vn 2.303445 2.976245 -2.120481 -v 0.013057 -0.039010 0.089518 -vn 1.923012 2.976249 -2.470693 -v 0.012693 -0.039010 0.089183 -vn 1.490137 2.976253 -2.753506 -v 0.012278 -0.039010 0.088912 -vn 3.120168 2.976242 0.258551 -v 0.013840 -0.039010 0.091798 -vn 3.120169 2.976244 -0.258548 -v 0.013840 -0.039010 0.091302 -vn 3.035058 2.976246 -0.768586 -v 0.013758 -0.039010 0.090814 -vn 2.867163 2.976251 -1.257649 -v 0.013597 -0.039010 0.090345 -vn 2.812682 3.365987 -1.354512 -v 0.009499 -0.039010 0.092201 -vn 2.440746 3.366003 -1.946439 -v 0.009677 -0.039010 0.092485 -vn 1.946437 3.365975 -2.440753 -v 0.009915 -0.039010 0.092723 -vn 3.043569 3.365999 0.694668 -v 0.009388 -0.039010 0.091216 -vn 3.121841 3.365984 -0.000004 -v 0.009350 -0.039010 0.091550 -vn 3.043568 3.365996 -0.694672 -v 0.009388 -0.039010 0.091884 -vn 2.621049 2.976246 1.712426 -v 0.013361 -0.039010 0.093191 -vn 2.867160 2.976239 1.257652 -v 0.013597 -0.039010 0.092755 -vn 3.035060 2.976254 0.768583 -v 0.013758 -0.039010 0.092286 -vn 0.515327 2.976254 3.088162 -v 0.011344 -0.039010 0.094509 -vn 1.016576 2.976249 2.961229 -v 0.011824 -0.039010 0.094387 -vn 1.490117 2.976240 2.753515 -v 0.012278 -0.039010 0.094188 -vn 1.923025 2.976238 2.470682 -v 0.012693 -0.039010 0.093917 -vn 2.303458 2.976256 2.120470 -v 0.013057 -0.039010 0.093582 -vn 2.440754 3.365976 1.946437 -v 0.009677 -0.039010 0.090615 -vn 2.812672 3.365999 1.354528 -v 0.009499 -0.039010 0.090899 -vn 1.354506 3.365979 2.812686 -v 0.010199 -0.039010 0.090199 -vn 1.946430 3.366010 2.440752 -v 0.009915 -0.039010 0.090377 -vn 0.694690 -3.365989 3.043565 -v 0.010516 -0.042010 0.090088 -vn 1.354507 -3.365979 2.812686 -v 0.010199 -0.042010 0.090199 -vn 1.946430 -3.366010 2.440752 -v 0.009915 -0.042010 0.090377 -vn 2.440754 -3.365976 1.946437 -v 0.009677 -0.042010 0.090615 -vn 2.812673 -3.365999 1.354528 -v 0.009499 -0.042010 0.090899 -vn 3.043568 -3.365999 0.694668 -v 0.009388 -0.042010 0.091216 -vn 3.121841 -3.365984 -0.000004 -v 0.009350 -0.042010 0.091550 -vn 3.043568 -3.365997 -0.694672 -v 0.009388 -0.042010 0.091884 -vn 2.812682 -3.365987 -1.354512 -v 0.009499 -0.042010 0.092201 -vn 2.440746 -3.366003 -1.946439 -v 0.009677 -0.042010 0.092485 -vn 1.946438 -3.365976 -2.440753 -v 0.009915 -0.042010 0.092723 -vn 1.354531 -3.365998 -2.812670 -v 0.010199 -0.042010 0.092901 -vn 0.694655 -3.366011 -3.043569 -v 0.010516 -0.042010 0.093012 -vn 0.515303 -2.976239 -3.088164 -v 0.011344 -0.040010 0.088591 -vn 1.016596 -2.976235 -2.961220 -v 0.011824 -0.040010 0.088713 -vn 1.490137 -2.976253 -2.753506 -v 0.012278 -0.040010 0.088912 -vn 1.923012 -2.976249 -2.470693 -v 0.012693 -0.040010 0.089183 -vn 2.303445 -2.976245 -2.120481 -v 0.013057 -0.040010 0.089518 -vn 2.621054 -2.976239 -1.712417 -v 0.013361 -0.040010 0.089909 -vn 2.867163 -2.976251 -1.257649 -v 0.013597 -0.040010 0.090345 -vn 3.035058 -2.976247 -0.768586 -v 0.013758 -0.040010 0.090814 -vn 3.120169 -2.976244 -0.258548 -v 0.013840 -0.040010 0.091302 -vn 3.120168 -2.976241 0.258551 -v 0.013840 -0.040010 0.091798 -vn 3.035060 -2.976254 0.768583 -v 0.013758 -0.040010 0.092286 -vn 2.867160 -2.976239 1.257652 -v 0.013597 -0.040010 0.092755 -vn 2.621049 -2.976246 1.712426 -v 0.013361 -0.040010 0.093191 -vn 2.303458 -2.976257 2.120470 -v 0.013057 -0.040010 0.093582 -vn 1.923025 -2.976237 2.470681 -v 0.012693 -0.040010 0.093917 -vn 1.490117 -2.976239 2.753515 -v 0.012278 -0.040010 0.094188 -vn 1.016576 -2.976249 2.961229 -v 0.011824 -0.040010 0.094387 -vn 0.515327 -2.976254 3.088162 -v 0.011344 -0.040010 0.094509 -vn 1.016596 -2.976235 -2.961220 -v 0.011824 -0.042010 0.088713 -vn 1.490137 -2.976254 -2.753507 -v 0.012278 -0.042010 0.088912 -vn 1.923013 -2.976249 -2.470693 -v 0.012693 -0.042010 0.089183 -vn 3.120168 -2.976244 -0.258548 -v 0.013840 -0.042010 0.091302 -vn 3.120168 -2.976242 0.258551 -v 0.013840 -0.042010 0.091798 -vn 3.035060 -2.976254 0.768583 -v 0.013758 -0.042010 0.092286 -vn 0.515303 -2.976239 -3.088164 -v 0.011344 -0.042010 0.088591 -vn 1.016576 -2.976249 2.961229 -v 0.011824 -0.042010 0.094387 -vn 0.515327 -2.976254 3.088162 -v 0.011344 -0.042010 0.094509 -vn 2.867160 -2.976239 1.257652 -v 0.013597 -0.042010 0.092755 -vn 2.621049 -2.976246 1.712426 -v 0.013361 -0.042010 0.093191 -vn 2.303458 -2.976256 2.120470 -v 0.013057 -0.042010 0.093582 -vn 1.923025 -2.976238 2.470682 -v 0.012693 -0.042010 0.093917 -vn 1.490117 -2.976240 2.753515 -v 0.012278 -0.042010 0.094188 -vn 2.303445 -2.976245 -2.120481 -v 0.013057 -0.042010 0.089518 -vn 2.621054 -2.976239 -1.712416 -v 0.013361 -0.042010 0.089909 -vn 2.867163 -2.976251 -1.257649 -v 0.013597 -0.042010 0.090345 -vn 3.035058 -2.976246 -0.768586 -v 0.013758 -0.042010 0.090814 -vn 0.574799 -3.326380 -3.074930 -v 0.011291 -0.040010 0.089191 -vn 1.130036 -3.326411 -2.916947 -v 0.011717 -0.040010 0.089312 -vn 1.646786 -3.326374 -2.659642 -v 0.012113 -0.040010 0.089509 -vn 2.107449 -3.326409 -2.311758 -v 0.012467 -0.040010 0.089776 -vn 2.496353 -3.326375 -1.885157 -v 0.012765 -0.040010 0.090104 -vn 2.800237 -3.326404 -1.394361 -v 0.012998 -0.040010 0.090480 -vn 3.008776 -3.326387 -0.856068 -v 0.013158 -0.040010 0.090893 -vn 3.114846 -3.326394 -0.288636 -v 0.013240 -0.040010 0.091329 -vn 3.114848 -3.326391 0.288631 -v 0.013240 -0.040010 0.091771 -vn 3.008773 -3.326397 0.856072 -v 0.013158 -0.040010 0.092207 -vn 2.800241 -3.326388 1.394358 -v 0.012998 -0.040010 0.092620 -vn 2.496349 -3.326395 1.885158 -v 0.012765 -0.040010 0.092996 -vn 2.107454 -3.326384 2.311759 -v 0.012467 -0.040010 0.093324 -vn 1.646781 -3.326403 2.659639 -v 0.012113 -0.040010 0.093591 -vn 1.130039 -3.326379 2.916951 -v 0.011717 -0.040010 0.093788 -vn 0.574797 -3.326413 3.074926 -v 0.011291 -0.040010 0.093909 -vn 0.515303 2.976239 -3.088164 -v 0.011344 -0.041010 0.088591 -vn 1.016596 2.976235 -2.961220 -v 0.011824 -0.041010 0.088713 -vn 1.490137 2.976253 -2.753507 -v 0.012278 -0.041010 0.088912 -vn 1.923013 2.976249 -2.470693 -v 0.012693 -0.041010 0.089183 -vn 2.303445 2.976245 -2.120481 -v 0.013057 -0.041010 0.089518 -vn 2.621054 2.976239 -1.712417 -v 0.013361 -0.041010 0.089909 -vn 2.867163 2.976251 -1.257649 -v 0.013597 -0.041010 0.090345 -vn 3.035058 2.976246 -0.768586 -v 0.013758 -0.041010 0.090814 -vn 3.120169 2.976243 -0.258548 -v 0.013840 -0.041010 0.091302 -vn 3.120168 2.976241 0.258551 -v 0.013840 -0.041010 0.091798 -vn 3.035060 2.976254 0.768583 -v 0.013758 -0.041010 0.092286 -vn 2.867160 2.976239 1.257652 -v 0.013597 -0.041010 0.092755 -vn 2.621049 2.976246 1.712426 -v 0.013361 -0.041010 0.093191 -vn 2.303458 2.976257 2.120470 -v 0.013057 -0.041010 0.093582 -vn 1.923026 2.976238 2.470682 -v 0.012693 -0.041010 0.093917 -vn 1.490117 2.976239 2.753515 -v 0.012278 -0.041010 0.094188 -vn 1.016576 2.976249 2.961229 -v 0.011824 -0.041010 0.094387 -vn 0.515327 2.976254 3.088162 -v 0.011344 -0.041010 0.094509 -vn 0.574799 3.326380 -3.074930 -v 0.011291 -0.041010 0.089191 -vn 1.130036 3.326411 -2.916947 -v 0.011717 -0.041010 0.089312 -vn 1.646786 3.326374 -2.659642 -v 0.012113 -0.041010 0.089509 -vn 2.107449 3.326409 -2.311758 -v 0.012467 -0.041010 0.089776 -vn 2.496353 3.326375 -1.885157 -v 0.012765 -0.041010 0.090104 -vn 2.800237 3.326403 -1.394361 -v 0.012998 -0.041010 0.090480 -vn 3.008776 3.326387 -0.856068 -v 0.013158 -0.041010 0.090893 -vn 3.114847 3.326394 -0.288636 -v 0.013240 -0.041010 0.091329 -vn 3.114847 3.326391 0.288631 -v 0.013240 -0.041010 0.091771 -vn 3.008773 3.326396 0.856072 -v 0.013158 -0.041010 0.092207 -vn 2.800241 3.326389 1.394359 -v 0.012998 -0.041010 0.092620 -vn 2.496349 3.326395 1.885158 -v 0.012765 -0.041010 0.092996 -vn 2.107454 3.326384 2.311758 -v 0.012467 -0.041010 0.093324 -vn 1.646781 3.326403 2.659640 -v 0.012113 -0.041010 0.093591 -vn 1.130039 3.326379 2.916951 -v 0.011717 -0.041010 0.093788 -vn 0.574797 3.326413 3.074926 -v 0.011291 -0.041010 0.093909 -vn -2.948195 -2.945236 1.040637 -v 0.033185 -0.011260 0.092632 -vn -2.948194 2.945236 1.040637 -v 0.033185 -0.009390 0.092632 -vn -3.094567 2.945241 0.445464 -v 0.033033 -0.009390 0.092013 -vn -3.094567 -2.945241 0.445464 -v 0.033033 -0.011260 0.092013 -vn -3.122012 2.945246 -0.166814 -v 0.033005 -0.009390 0.091377 -vn -3.122012 -2.945246 -0.166814 -v 0.033005 -0.011260 0.091377 -vn -3.029483 2.945248 -0.772671 -v 0.033101 -0.009390 0.090747 -vn -3.029483 -2.945248 -0.772671 -v 0.033101 -0.011260 0.090747 -vn -2.820526 2.945232 -1.348855 -v 0.033318 -0.009390 0.090148 -vn -2.820526 -2.945232 -1.348855 -v 0.033318 -0.011260 0.090148 -vn -2.503180 2.945250 -1.873201 -v 0.033648 -0.009390 0.089603 -vn -2.503180 -2.945250 -1.873201 -v 0.033648 -0.011260 0.089603 -vn -2.089646 2.945243 -2.325546 -v 0.034078 -0.009390 0.089133 -vn -2.089646 -2.945243 -2.325546 -v 0.034078 -0.011260 0.089133 -vn -1.595806 2.945246 -2.688529 -v 0.034591 -0.009390 0.088755 -vn -1.595806 -2.945246 -2.688529 -v 0.034591 -0.011260 0.088755 -vn -1.040627 2.945234 -2.948198 -v 0.035168 -0.009390 0.088485 -vn -1.040627 -2.945235 -2.948198 -v 0.035168 -0.011260 0.088485 -vn -0.445476 2.945257 -3.094568 -v 0.035787 -0.009390 0.088333 -vn -0.445476 -2.945257 -3.094568 -v 0.035787 -0.011260 0.088333 -vn 0.166812 2.945224 -3.122009 -v 0.036423 -0.009390 0.088305 -vn 0.166812 -2.945224 -3.122009 -v 0.036423 -0.011260 0.088305 -vn 0.772691 2.945256 -3.029480 -v 0.037053 -0.009390 0.088401 -vn 0.772691 -2.945258 -3.029479 -v 0.037053 -0.011260 0.088401 -vn 1.348847 2.945242 -2.820531 -v 0.037652 -0.009390 0.088618 -vn 1.348847 -2.945242 -2.820531 -v 0.037652 -0.011260 0.088618 -vn 1.873185 2.945247 -2.503191 -v 0.038197 -0.009390 0.088948 -vn 1.873185 -2.945246 -2.503191 -v 0.038197 -0.011260 0.088948 -vn 2.325544 2.945235 -2.089646 -v 0.038667 -0.009390 0.089378 -vn 2.325544 -2.945235 -2.089646 -v 0.038667 -0.011260 0.089378 -vn 2.688538 2.945241 -1.595791 -v 0.039045 -0.009390 0.089891 -vn 2.688538 -2.945241 -1.595791 -v 0.039045 -0.011260 0.089891 -vn 2.948200 2.945250 -1.040627 -v 0.039315 -0.009390 0.090468 -vn 2.948200 -2.945249 -1.040627 -v 0.039315 -0.011260 0.090468 -vn -2.946235 3.351027 1.039938 -v 0.033421 -0.009390 0.092549 -vn -2.946235 2.932159 1.039938 -v 0.033421 -0.005390 0.092549 -vn -3.098066 2.932153 0.404665 -v 0.033275 -0.005390 0.091939 -vn -3.098067 3.351032 0.404665 -v 0.033275 -0.009390 0.091939 -vn -3.114500 2.932149 -0.248307 -v 0.033259 -0.005390 0.091312 -vn -3.114500 3.351036 -0.248307 -v 0.033259 -0.009390 0.091312 -vn -2.994814 2.932154 -0.890425 -v 0.033374 -0.005390 0.090695 -vn -2.994814 3.351030 -0.890425 -v 0.033374 -0.009390 0.090695 -vn -2.744238 2.932149 -1.493627 -v 0.033615 -0.005390 0.090116 -vn -2.744238 3.351036 -1.493627 -v 0.033615 -0.009390 0.090116 -vn -2.373732 2.932161 -2.031544 -v 0.033971 -0.005390 0.089599 -vn -2.373732 3.351025 -2.031544 -v 0.033971 -0.009390 0.089599 -vn -1.899488 2.932154 -2.480668 -v 0.034426 -0.005390 0.089168 -vn -1.899488 3.351032 -2.480668 -v 0.034426 -0.009390 0.089168 -vn -1.342213 2.932148 -2.821387 -v 0.034961 -0.005390 0.088841 -vn -1.342213 3.351038 -2.821388 -v 0.034961 -0.009390 0.088841 -vn -0.726270 2.932151 -3.038799 -v 0.035553 -0.005390 0.088632 -vn -0.726270 3.351035 -3.038798 -v 0.035553 -0.009390 0.088632 -vn -0.078599 2.932157 -3.123394 -v 0.036175 -0.005390 0.088551 -vn -0.078599 3.351028 -3.123395 -v 0.036175 -0.009390 0.088551 -vn 0.572505 2.932152 -3.071483 -v 0.036800 -0.005390 0.088601 -vn 0.572505 3.351034 -3.071482 -v 0.036800 -0.009390 0.088601 -vn 1.198588 2.932158 -2.885335 -v 0.037401 -0.005390 0.088780 -vn 1.198588 3.351028 -2.885335 -v 0.037401 -0.009390 0.088780 -vn 1.772285 2.932152 -2.573085 -v 0.037952 -0.005390 0.089079 -vn 1.772285 3.351033 -2.573086 -v 0.037952 -0.009390 0.089079 -vn 2.268541 2.932144 -2.148367 -v 0.038428 -0.005390 0.089487 -vn 2.268541 3.351041 -2.148367 -v 0.038428 -0.009390 0.089487 -vn 2.665641 2.932162 -1.629765 -v 0.038810 -0.005390 0.089985 -vn 2.665641 3.351023 -1.629766 -v 0.038810 -0.009390 0.089985 -vn 2.946233 2.932150 -1.039942 -v 0.039079 -0.005390 0.090551 -vn 2.946233 3.351035 -1.039942 -v 0.039079 -0.009390 0.090551 -vn -4.589839 2.722199 1.744023 -v 0.037476 -0.008117 0.091117 -vn -2.949889 2.998080 1.054586 -v 0.037476 -0.008390 0.091117 -vn -4.656920 2.705886 1.350758 -v 0.037515 -0.008123 0.091252 -vn -3.089059 2.968370 0.472370 -v 0.037528 -0.008390 0.091314 -vn -4.718253 2.717816 1.039490 -v 0.037516 -0.008123 0.091256 -vn -4.842294 2.887822 0.407429 -v 0.037546 -0.008130 0.091451 -vn -4.840835 2.819862 -0.064146 -v 0.037546 -0.008137 0.091648 -vn -3.087906 2.935372 -0.400098 -v 0.037539 -0.008390 0.091721 -vn -4.837855 2.670958 -0.389274 -v 0.037544 -0.008138 0.091675 -vn -4.688155 2.867684 -1.162865 -v 0.037517 -0.008144 0.091842 -vn -4.757473 2.727375 -0.844600 -v 0.037523 -0.008143 0.091815 -vn -4.824435 2.683261 -0.571880 -v 0.037539 -0.008140 0.091721 -vn -4.598895 2.831011 -1.572255 -v 0.037458 -0.008152 0.092030 -vn -2.813166 2.943997 -1.337807 -v 0.037423 -0.008390 0.092111 -vn -4.425046 2.701489 -2.012757 -v 0.037423 -0.008155 0.092111 -vn -3.510544 2.691507 -3.309019 -v 0.037192 -0.008170 0.092446 -vn -3.638025 2.695871 -3.163947 -v 0.037199 -0.008170 0.092438 -vn -2.266178 2.958948 -2.140244 -v 0.037192 -0.008390 0.092446 -vn -3.911848 2.857758 -2.849270 -v 0.037260 -0.008166 0.092369 -vn -4.169322 2.853048 -2.469688 -v 0.037372 -0.008159 0.092207 -vn -2.421356 2.716896 -4.188461 -v 0.036869 -0.008185 0.092693 -vn -2.724220 2.777715 -3.990720 -v 0.036970 -0.008181 0.092633 -vn -1.481945 2.967003 -2.743697 -v 0.036869 -0.008390 0.092693 -vn -2.976956 2.884562 -3.806500 -v 0.037002 -0.008179 0.092610 -vn -3.270825 2.800908 -3.593157 -v 0.037125 -0.008173 0.092512 -vn -0.588291 2.804454 -4.798108 -v 0.036421 -0.008202 0.092839 -vn -1.051898 2.702874 -4.741756 -v 0.036481 -0.008200 0.092829 -vn -0.566792 2.968245 -3.066916 -v 0.036486 -0.008390 0.092828 -vn -1.529858 2.862478 -4.646425 -v 0.036614 -0.008195 0.092798 -vn -2.005778 2.821100 -4.403319 -v 0.036798 -0.008188 0.092729 -vn -0.081516 2.912949 -4.847612 -v 0.036225 -0.008210 0.092850 -vn 0.409758 2.973680 -3.092954 -v 0.036079 -0.008390 0.092839 -vn 0.442987 2.711771 -4.825517 -v 0.036079 -0.008215 0.092839 -vn 2.256879 2.758777 -4.288964 -v 0.035657 -0.008231 0.092707 -vn 1.898031 2.670902 -4.524754 -v 0.035689 -0.008230 0.092723 -vn 1.346005 2.976704 -2.815867 -v 0.035689 -0.008390 0.092723 -vn 1.406054 2.923727 -4.661682 -v 0.035838 -0.008224 0.092783 -vn 0.889351 2.777716 -4.765362 -v 0.036029 -0.008217 0.092831 -vn 2.733883 2.964852 -4.007450 -v 0.035489 -0.008238 0.092604 -vn 2.150359 2.977385 -2.263335 -v 0.035354 -0.008390 0.092492 -vn 3.159072 2.709467 -3.679242 -v 0.035354 -0.008245 0.092492 -vn 2.727542 2.978985 -1.530364 -v 0.035107 -0.008390 0.092169 -vn 2.953589 2.989170 -1.041287 -v 0.035024 -0.008390 0.091983 -vn 4.540168 2.772346 -1.728756 -v 0.035024 -0.008267 0.091983 -vn 4.256163 2.763803 -2.375603 -v 0.035103 -0.008260 0.092163 -vn 3.813182 3.001305 -2.989663 -v 0.035209 -0.008253 0.092329 -vn 3.437820 2.746062 -3.402567 -v 0.035338 -0.008246 0.092477 -vn -4.524055 2.761662 1.746375 -v 0.037476 -0.007817 0.091117 -vn -4.609447 -2.749551 1.564850 -v 0.037476 -0.007867 0.091117 -vn -4.718367 2.758061 1.158767 -v 0.037516 -0.007823 0.091256 -vn -4.754404 -2.758654 0.954258 -v 0.037516 -0.007873 0.091256 -vn -4.846455 2.769901 0.467262 -v 0.037546 -0.007830 0.091451 -vn -4.861068 -2.765309 0.279949 -v 0.037546 -0.007880 0.091450 -vn -4.839113 2.731548 -0.143506 -v 0.037546 -0.007837 0.091648 -vn -4.838352 -2.720989 -0.321998 -v 0.037546 -0.007887 0.091647 -vn -4.827007 -2.666142 -0.591735 -v 0.037544 -0.007888 0.091675 -vn -4.822662 2.684260 -0.584904 -v 0.037539 -0.007840 0.091721 -vn -4.798785 -2.678293 -0.759842 -v 0.037539 -0.007890 0.091721 -vn -4.813743 2.669913 -0.800514 -v 0.037525 -0.007843 0.091806 -vn -4.716096 -2.686826 -1.025828 -v 0.037523 -0.007893 0.091815 -vn -4.717060 2.725521 -1.121751 -v 0.037517 -0.007844 0.091842 -vn -4.651367 -2.723157 -1.329313 -v 0.037517 -0.007894 0.091841 -vn -4.571852 2.743274 -1.605348 -v 0.037458 -0.007852 0.092030 -vn -4.515340 -2.734877 -1.804737 -v 0.037458 -0.007902 0.092029 -vn -4.398479 2.717007 -2.016362 -v 0.037423 -0.007855 0.092111 -vn -4.330261 -2.708354 -2.188084 -v 0.037423 -0.007905 0.092111 -vn -4.196717 2.749437 -2.435839 -v 0.037372 -0.007859 0.092207 -vn -4.088925 -2.744320 -2.610092 -v 0.037372 -0.007909 0.092206 -vn -3.896848 2.737114 -2.911058 -v 0.037260 -0.007866 0.092369 -vn -3.762911 -2.750435 -3.052063 -v 0.037261 -0.007916 0.092368 -vn -3.575601 2.707919 -3.260921 -v 0.037192 -0.007870 0.092446 -vn -3.510598 -2.708216 -3.305028 -v 0.037199 -0.007920 0.092438 -vn -3.373255 -2.690421 -3.453813 -v 0.037192 -0.007920 0.092446 -vn -3.269114 2.744687 -3.582242 -v 0.037125 -0.007873 0.092512 -vn -3.138749 -2.733635 -3.714212 -v 0.037125 -0.007923 0.092511 -vn -2.802767 2.713222 -3.960479 -v 0.036970 -0.007881 0.092633 -vn -2.839847 -2.847321 -3.906850 -v 0.037002 -0.007929 0.092610 -vn -2.532807 -2.695353 -4.130007 -v 0.036970 -0.007931 0.092632 -vn -2.420688 2.716416 -4.189319 -v 0.036869 -0.007885 0.092693 -vn -2.257159 -2.713083 -4.288607 -v 0.036869 -0.007935 0.092693 -vn -2.044425 2.737458 -4.399484 -v 0.036798 -0.007888 0.092729 -vn -1.862260 -2.741351 -4.473159 -v 0.036799 -0.007938 0.092729 -vn -1.498799 2.741686 -4.636879 -v 0.036614 -0.007895 0.092798 -vn -1.316395 -2.741471 -4.686154 -v 0.036614 -0.007945 0.092798 -vn -1.121987 2.695954 -4.724436 -v 0.036491 -0.007900 0.092827 -vn -0.826703 -2.705765 -4.768427 -v 0.036481 -0.007950 0.092829 -vn 1.580527 -2.731676 -4.596628 -v 0.035839 -0.007974 0.092783 -vn 1.300864 2.718877 -4.682247 -v 0.035838 -0.007924 0.092783 -vn 1.054777 -2.726405 -4.733423 -v 0.036030 -0.007967 0.092831 -vn 0.875193 2.724978 -4.778611 -v 0.036029 -0.007917 0.092831 -vn 0.649617 -2.719249 -4.788339 -v 0.036079 -0.007965 0.092839 -vn 0.444229 2.715310 -4.822349 -v 0.036079 -0.007915 0.092839 -vn 0.134166 -2.755955 -4.856060 -v 0.036225 -0.007960 0.092850 -vn -0.043367 2.754655 -4.862386 -v 0.036225 -0.007910 0.092850 -vn -0.403018 -2.719613 -4.851311 -v 0.036422 -0.007952 0.092839 -vn -0.620931 2.740143 -4.797180 -v 0.036421 -0.007902 0.092839 -vn -0.921277 2.675161 -4.735874 -v 0.036486 -0.007900 0.092828 -vn 3.922445 -2.751667 -2.857618 -v 0.035210 -0.008003 0.092329 -vn 3.781269 2.747277 -3.040718 -v 0.035209 -0.007953 0.092329 -vn 3.570500 -2.724028 -3.262424 -v 0.035339 -0.007996 0.092477 -vn 3.431536 2.727130 -3.409079 -v 0.035338 -0.007946 0.092477 -vn 3.302530 -2.714745 -3.538906 -v 0.035354 -0.007995 0.092492 -vn 3.160213 2.701914 -3.694483 -v 0.035354 -0.007945 0.092492 -vn 2.918550 -2.766398 -3.889189 -v 0.035489 -0.007988 0.092604 -vn 2.757962 2.766400 -3.996220 -v 0.035489 -0.007938 0.092604 -vn 2.416565 -2.723716 -4.199439 -v 0.035657 -0.007981 0.092707 -vn 2.242916 2.715956 -4.314734 -v 0.035657 -0.007931 0.092707 -vn 2.084271 -2.699722 -4.392811 -v 0.035689 -0.007980 0.092723 -vn 1.935194 2.701834 -4.462692 -v 0.035689 -0.007930 0.092723 -vn 1.704788 2.847555 -4.515879 -v 0.035792 -0.007926 0.092767 -vn 4.329402 -2.726609 -2.230030 -v 0.035104 -0.008010 0.092163 -vn 4.601455 -2.746526 -1.566480 -v 0.035024 -0.008017 0.091983 -vn 4.524986 2.751775 -1.756312 -v 0.035024 -0.007967 0.091983 -vn 4.373984 2.930026 -2.046808 -v 0.035077 -0.007962 0.092110 -vn 4.170807 2.744290 -2.433038 -v 0.035103 -0.007960 0.092163 -vn 4.042735 3.179120 -2.578129 -v 0.035145 -0.007957 0.092235 -vn -4.544818 2.749772 1.743138 -v 0.037476 -0.007517 0.091117 -vn -4.609621 -2.750709 1.554931 -v 0.037476 -0.007567 0.091117 -vn -4.728824 2.746144 1.155454 -v 0.037516 -0.007523 0.091256 -vn -4.753391 -2.757935 1.021761 -v 0.037516 -0.007573 0.091256 -vn -4.855380 2.739919 0.448166 -v 0.037546 -0.007530 0.091451 -vn -4.601438 3.091338 -1.392861 -v 0.037492 -0.007548 0.091935 -vn -4.743116 2.697707 -0.990573 -v 0.037517 -0.007544 0.091842 -vn -4.672470 -2.693229 -1.284991 -v 0.037517 -0.007594 0.091843 -vn -4.710718 -3.280756 0.764279 -v 0.037529 -0.007575 0.091316 -vn -4.866733 -2.744624 0.210621 -v 0.037546 -0.007580 0.091451 -vn -4.854921 2.730916 -0.165165 -v 0.037546 -0.007537 0.091648 -vn -4.838491 -2.737415 -0.349921 -v 0.037546 -0.007587 0.091648 -vn -4.822361 2.701740 -0.575856 -v 0.037538 -0.007540 0.091725 -vn -4.784958 -2.713172 -0.782090 -v 0.037538 -0.007590 0.091725 -vn -4.753439 -2.753317 -0.980673 -v 0.037525 -0.007593 0.091806 -vn -4.566441 2.738630 -1.661211 -v 0.037458 -0.007552 0.092030 -vn -4.498707 -2.745215 -1.799343 -v 0.037458 -0.007602 0.092030 -vn -4.428240 2.691133 -1.990389 -v 0.037420 -0.007555 0.092116 -vn -4.317630 -2.699973 -2.205504 -v 0.037420 -0.007605 0.092116 -vn -4.292354 2.714654 -2.209419 -v 0.037389 -0.007558 0.092176 -vn -4.093328 -2.719353 -2.640061 -v 0.037372 -0.007609 0.092207 -vn -4.155815 2.724637 -2.481197 -v 0.037372 -0.007559 0.092207 -vn -3.891306 2.738678 -2.923783 -v 0.037260 -0.007566 0.092369 -vn -3.785842 -2.730936 -3.073227 -v 0.037260 -0.007616 0.092369 -vn -3.568823 2.715647 -3.267993 -v 0.037186 -0.007570 0.092452 -vn -3.428759 -2.712325 -3.423478 -v 0.037186 -0.007620 0.092452 -vn -3.262362 2.738237 -3.588542 -v 0.037125 -0.007573 0.092512 -vn -3.119609 -2.739292 -3.720182 -v 0.037125 -0.007623 0.092512 -vn -2.828400 2.750644 -3.947220 -v 0.036970 -0.007581 0.092633 -vn -2.649669 -2.751780 -4.068362 -v 0.036969 -0.007631 0.092633 -vn -2.398907 2.716379 -4.203559 -v 0.036859 -0.007585 0.092698 -vn -2.229307 -2.710810 -4.301960 -v 0.036859 -0.007635 0.092698 -vn -2.039015 2.726749 -4.412651 -v 0.036798 -0.007588 0.092729 -vn -1.856257 -2.732248 -4.485026 -v 0.036798 -0.007638 0.092729 -vn -1.483670 2.744370 -4.641764 -v 0.036614 -0.007595 0.092798 -vn -1.298875 -2.751781 -4.690490 -v 0.036613 -0.007645 0.092798 -vn -1.021174 2.675836 -4.763198 -v 0.036472 -0.007600 0.092831 -vn -0.923402 -2.731970 -4.755759 -v 0.036491 -0.007650 0.092827 -vn -0.698037 -2.681097 -4.769053 -v 0.036472 -0.007650 0.092831 -vn -0.610400 2.732107 -4.804176 -v 0.036421 -0.007602 0.092839 -vn -0.395687 -2.726143 -4.836121 -v 0.036421 -0.007652 0.092839 -vn -0.038638 2.760848 -4.855858 -v 0.036225 -0.007610 0.092850 -vn 0.156766 -2.760753 -4.861250 -v 0.036225 -0.007660 0.092850 -vn 0.480066 2.717640 -4.812660 -v 0.036063 -0.007615 0.092837 -vn 0.683837 -2.720648 -4.783171 -v 0.036063 -0.007666 0.092837 -vn 0.863633 2.729429 -4.758338 -v 0.036029 -0.007617 0.092831 -vn 1.081685 -2.718060 -4.734746 -v 0.036028 -0.007667 0.092831 -vn 1.390066 2.735705 -4.646660 -v 0.035838 -0.007624 0.092783 -vn 1.495131 -2.726144 -4.616035 -v 0.035838 -0.007674 0.092783 -vn 1.889088 -2.807232 -4.454293 -v 0.035792 -0.007676 0.092767 -vn 1.970339 2.685709 -4.439253 -v 0.035673 -0.007631 0.092715 -vn 2.159018 -2.685355 -4.355954 -v 0.035673 -0.007681 0.092715 -vn 2.258153 2.652584 -4.352522 -v 0.035657 -0.007631 0.092707 -vn 2.405342 -2.690741 -4.213630 -v 0.035656 -0.007681 0.092706 -vn 2.457959 2.850034 -4.183624 -v 0.035547 -0.007636 0.092644 -vn 2.958559 -2.738679 -3.845243 -v 0.035489 -0.007689 0.092604 -vn 2.840667 2.741997 -3.917897 -v 0.035489 -0.007638 0.092604 -vn 3.329661 2.775683 -3.529661 -v 0.035338 -0.007646 0.092477 -vn 4.092944 -3.038340 -2.537999 -v 0.035145 -0.007707 0.092235 -vn 4.232351 2.693218 -2.389143 -v 0.035103 -0.007660 0.092163 -vn 3.930576 -2.777548 -2.844916 -v 0.035209 -0.007703 0.092328 -vn 3.833613 2.774357 -2.986235 -v 0.035209 -0.007653 0.092329 -vn 3.476028 -2.779713 -3.387594 -v 0.035339 -0.007696 0.092478 -vn 4.602404 -2.741391 -1.523457 -v 0.035024 -0.007717 0.091983 -vn 4.538039 2.734769 -1.732227 -v 0.035024 -0.007667 0.091983 -vn 4.447600 -2.844304 -1.913546 -v 0.035077 -0.007712 0.092110 -vn 4.306752 -2.697637 -2.206197 -v 0.035103 -0.007710 0.092163 -vn -4.538265 2.783514 1.693533 -v 0.037476 -0.007217 0.091117 -vn -4.600936 -2.780322 1.531112 -v 0.037476 -0.007267 0.091117 -vn -4.757051 2.973783 0.887945 -v 0.037527 -0.007225 0.091308 -vn -4.724026 -2.908588 1.027969 -v 0.037516 -0.007273 0.091256 -vn -4.851094 2.965784 0.181330 -v 0.037549 -0.007232 0.091504 -vn -4.837482 -2.969409 0.353101 -v 0.037546 -0.007280 0.091450 -vn -4.829307 2.697441 -0.323810 -v 0.037541 -0.007239 0.091700 -vn -4.824386 -2.962706 -0.271864 -v 0.037546 -0.007287 0.091648 -vn -4.789882 -2.708777 -0.832811 -v 0.037539 -0.007290 0.091721 -vn -4.789965 2.719948 -0.672762 -v 0.037539 -0.007240 0.091721 -vn -4.705111 2.723658 -1.185956 -v 0.037504 -0.007246 0.091893 -vn -4.717625 -2.872243 -1.083926 -v 0.037517 -0.007294 0.091842 -vn -4.565531 -2.822215 -1.593173 -v 0.037492 -0.007298 0.091935 -vn -4.484888 2.767506 -1.812560 -v 0.037438 -0.007254 0.092078 -vn -4.498559 -2.828735 -1.848932 -v 0.037458 -0.007302 0.092030 -vn -4.398709 2.694416 -2.065023 -v 0.037423 -0.007255 0.092111 -vn -4.354340 -2.689327 -2.155316 -v 0.037423 -0.007305 0.092111 -vn -4.180739 -2.809231 -2.401285 -v 0.037389 -0.007308 0.092176 -vn -4.057987 2.968692 -2.642358 -v 0.037344 -0.007261 0.092252 -vn -4.071665 -2.770737 -2.612367 -v 0.037372 -0.007309 0.092207 -vn -3.764314 2.779033 -3.072347 -v 0.037226 -0.007268 0.092409 -vn -3.809111 -2.964312 -2.999279 -v 0.037260 -0.007316 0.092368 -vn -3.530255 2.728501 -3.324344 -v 0.037192 -0.007270 0.092446 -vn -3.420925 -2.735441 -3.420625 -v 0.037192 -0.007320 0.092446 -vn -3.111486 2.957052 -3.728096 -v 0.037085 -0.007275 0.092546 -vn -3.162248 -2.836724 -3.676058 -v 0.037125 -0.007323 0.092512 -vn -2.644821 2.816555 -4.047135 -v 0.036925 -0.007283 0.092661 -vn -2.732570 -2.969533 -3.994567 -v 0.036970 -0.007331 0.092633 -vn -2.354640 2.728151 -4.239777 -v 0.036869 -0.007285 0.092693 -vn -2.219939 -2.733542 -4.303992 -v 0.036869 -0.007335 0.092693 -vn -1.829395 2.968189 -4.474162 -v 0.036750 -0.007290 0.092750 -vn -1.920662 -2.814531 -4.462166 -v 0.036798 -0.007338 0.092729 -vn -1.281937 2.818110 -4.693615 -v 0.036563 -0.007297 0.092812 -vn -1.380689 -2.957638 -4.649525 -v 0.036614 -0.007345 0.092798 -vn -0.994946 2.706297 -4.781447 -v 0.036486 -0.007300 0.092828 -vn -0.836734 -2.718239 -4.794320 -v 0.036486 -0.007350 0.092828 -vn -0.393247 2.970520 -4.814347 -v 0.036369 -0.007304 0.092845 -vn -0.472507 -2.808943 -4.819261 -v 0.036421 -0.007352 0.092839 -vn 0.168707 2.848853 -4.838310 -v 0.036172 -0.007311 0.092848 -vn 0.056621 -2.962372 -4.840617 -v 0.036225 -0.007360 0.092850 -vn 0.513940 2.736832 -4.813545 -v 0.036079 -0.007315 0.092839 -vn 0.670782 -2.734234 -4.791803 -v 0.036079 -0.007365 0.092839 -vn 1.098798 2.939751 -4.738935 -v 0.035977 -0.007319 0.092821 -vn 1.001879 -2.792320 -4.737833 -v 0.036029 -0.007367 0.092831 -vn 1.507467 2.758453 -4.612044 -v 0.035797 -0.007326 0.092769 -vn 1.500026 -2.895782 -4.618393 -v 0.035838 -0.007374 0.092783 -vn 1.749470 2.806197 -4.498945 -v 0.035749 -0.007327 0.092750 -vn 2.126490 -2.670386 -4.371379 -v 0.035689 -0.007380 0.092723 -vn 1.975096 2.687556 -4.409351 -v 0.035689 -0.007330 0.092723 -vn 2.259176 2.716383 -4.305475 -v 0.035656 -0.007331 0.092707 -vn 2.400690 -2.712631 -4.231008 -v 0.035657 -0.007381 0.092707 -vn 2.768964 2.732236 -3.982896 -v 0.035489 -0.007338 0.092604 -vn 2.601594 -2.980076 -4.064357 -v 0.035547 -0.007386 0.092644 -vn 2.988122 -2.724549 -3.822640 -v 0.035489 -0.007388 0.092604 -vn 3.179169 2.709807 -3.668177 -v 0.035354 -0.007345 0.092492 -vn 3.310896 -2.711844 -3.531262 -v 0.035354 -0.007395 0.092492 -vn 3.389437 2.695330 -3.466693 -v 0.035338 -0.007346 0.092477 -vn 3.545660 -2.696075 -3.294785 -v 0.035339 -0.007396 0.092477 -vn 3.601374 2.862823 -3.223681 -v 0.035252 -0.007350 0.092383 -vn 3.981755 -2.731626 -2.790858 -v 0.035209 -0.007403 0.092329 -vn 4.605091 -2.747331 -1.588871 -v 0.035024 -0.007417 0.091983 -vn 4.520360 2.761637 -1.755638 -v 0.035024 -0.007367 0.091983 -vn 4.340653 -2.767492 -2.189649 -v 0.035103 -0.007410 0.092163 -vn 4.232454 2.780981 -2.372340 -v 0.035103 -0.007360 0.092163 -vn 3.884318 2.736963 -2.897222 -v 0.035209 -0.007353 0.092329 -vn 1.988724 2.687614 -4.413164 -v 0.035689 -0.007030 0.092723 -vn 1.531624 2.818196 -4.593924 -v 0.035789 -0.007026 0.092766 -vn 1.888908 -2.729265 -4.465144 -v 0.035749 -0.007078 0.092750 -vn 1.342983 -2.810186 -4.669059 -v 0.035936 -0.007070 0.092812 -vn 0.947655 2.770821 -4.751257 -v 0.035978 -0.007019 0.092821 -vn 0.829511 -2.696167 -4.760242 -v 0.036079 -0.007065 0.092839 -vn 0.547614 2.686951 -4.821421 -v 0.036079 -0.007015 0.092839 -vn 0.642046 -2.695239 -4.772227 -v 0.036098 -0.007064 0.092841 -vn 0.445579 -2.722979 -4.816633 -v 0.036131 -0.007063 0.092845 -vn 0.109242 2.805584 -4.853365 -v 0.036173 -0.007011 0.092848 -vn -0.123207 -2.712771 -4.853195 -v 0.036327 -0.007056 0.092848 -vn -0.209422 2.766391 -4.836238 -v 0.036304 -0.007007 0.092849 -vn -0.430971 -2.719940 -4.820572 -v 0.036382 -0.007054 0.092843 -vn -0.587387 2.712613 -4.808609 -v 0.036370 -0.007004 0.092845 -vn -0.734492 -2.685291 -4.808743 -v 0.036486 -0.007050 0.092828 -vn -0.931848 2.686142 -4.775187 -v 0.036486 -0.007000 0.092828 -vn -1.003523 -2.684973 -4.769056 -v 0.036522 -0.007049 0.092821 -vn -1.376696 2.809880 -4.647634 -v 0.036564 -0.006997 0.092811 -vn -1.590520 -2.813876 -4.588187 -v 0.036711 -0.007041 0.092765 -vn -1.957133 2.793477 -4.442460 -v 0.036750 -0.006990 0.092750 -vn -2.107914 -2.681142 -4.386166 -v 0.036869 -0.007035 0.092693 -vn -2.337608 2.708726 -4.236793 -v 0.036869 -0.006985 0.092693 -vn -2.390481 -2.691645 -4.207234 -v 0.036889 -0.007034 0.092682 -vn -2.706493 2.812334 -4.018844 -v 0.036926 -0.006982 0.092660 -vn -2.884908 -2.818496 -3.906762 -v 0.037053 -0.007027 0.092572 -vn -3.212747 2.808101 -3.633604 -v 0.037086 -0.006975 0.092546 -vn -3.330636 -2.700737 -3.505513 -v 0.037192 -0.007020 0.092446 -vn -3.525504 2.706788 -3.331380 -v 0.037192 -0.006970 0.092446 -vn -3.566700 -2.670251 -3.290284 -v 0.037198 -0.007020 0.092440 -vn -3.801504 2.799416 -3.036509 -v 0.037227 -0.006968 0.092408 -vn -3.921332 -2.813437 -2.886397 -v 0.037321 -0.007012 0.092286 -vn -4.168750 2.808187 -2.501903 -v 0.037345 -0.006961 0.092251 -vn -4.261878 -2.698981 -2.337450 -v 0.037420 -0.007005 0.092116 -vn -4.367029 2.701393 -2.100371 -v 0.037423 -0.006955 0.092111 -vn -4.385009 -2.669771 -2.074585 -v 0.037423 -0.007005 0.092111 -vn -4.514549 2.794004 -1.747168 -v 0.037438 -0.006954 0.092078 -vn -4.588935 -2.825824 -1.567451 -v 0.037492 -0.006998 0.091933 -vn -4.717520 2.810559 -1.178896 -v 0.037504 -0.006946 0.091892 -vn -4.741930 -2.900904 -0.880049 -v 0.037536 -0.006991 0.091741 -vn -4.733739 2.970803 -0.973233 -v 0.037519 -0.006944 0.091831 -vn -4.785038 -2.728161 -0.662200 -v 0.037539 -0.006990 0.091721 -vn -4.788302 2.696754 -0.616161 -v 0.037539 -0.006940 0.091721 -vn -4.822701 2.753555 -0.331157 -v 0.037541 -0.006939 0.091699 -vn -4.864669 -2.814477 0.002629 -v 0.037550 -0.006983 0.091545 -vn -4.860387 2.779564 0.002494 -v 0.037550 -0.006934 0.091571 -vn -4.812005 -2.826802 0.594311 -v 0.037534 -0.006976 0.091349 -vn -4.481874 2.725893 1.820076 -v 0.037476 -0.006917 0.091117 -vn -4.562805 -2.720775 1.636255 -v 0.037476 -0.006967 0.091117 -vn -4.597977 2.702075 1.487958 -v 0.037487 -0.006919 0.091151 -vn -4.684412 -2.738640 1.226303 -v 0.037492 -0.006969 0.091167 -vn -4.750553 2.799545 1.019234 -v 0.037527 -0.006925 0.091307 -vn -4.748334 3.424930 0.283271 -v 0.037549 -0.006932 0.091502 -vn 2.157276 -2.681358 -4.329527 -v 0.035689 -0.007080 0.092723 -vn 2.372123 -2.691672 -4.243561 -v 0.035658 -0.007081 0.092707 -vn 2.371560 2.890932 -4.209208 -v 0.035611 -0.007033 0.092682 -vn 2.656618 2.703582 -4.040509 -v 0.035500 -0.007038 0.092612 -vn 2.575124 -2.935178 -4.089108 -v 0.035555 -0.007086 0.092648 -vn 2.982984 -2.687372 -3.834055 -v 0.035490 -0.007088 0.092605 -vn 2.989094 2.883113 -3.791191 -v 0.035447 -0.007040 0.092573 -vn 3.201459 2.725181 -3.627701 -v 0.035354 -0.007045 0.092492 -vn 3.330555 -2.699085 -3.550728 -v 0.035354 -0.007095 0.092492 -vn 3.509854 -2.678013 -3.351650 -v 0.035339 -0.007096 0.092478 -vn 3.508460 2.749798 -3.334830 -v 0.035302 -0.007048 0.092440 -vn 3.786444 -2.867480 -3.012055 -v 0.035252 -0.007100 0.092383 -vn 4.003345 2.968698 -2.717534 -v 0.035179 -0.007055 0.092287 -vn 3.973440 -2.804643 -2.786216 -v 0.035209 -0.007103 0.092329 -vn 4.330228 2.899760 -2.177006 -v 0.035080 -0.007062 0.092116 -vn 4.265024 -2.969442 -2.294882 -v 0.035104 -0.007110 0.092163 -vn 4.558008 2.769053 -1.704324 -v 0.035024 -0.007067 0.091983 -vn 4.595083 -2.783082 -1.534936 -v 0.035024 -0.007117 0.091983 -vn -4.807130 3.136338 0.076221 -v 0.037550 -0.006633 0.091539 -vn -4.760345 2.851887 0.843230 -v 0.037529 -0.006625 0.091314 -vn -4.853341 -2.918694 0.270310 -v 0.037546 -0.006680 0.091450 -vn -4.736564 -2.767447 1.025807 -v 0.037516 -0.006673 0.091256 -vn -4.686722 2.723433 1.183261 -v 0.037522 -0.006624 0.091279 -vn -4.590795 -2.737640 1.584610 -v 0.037476 -0.006667 0.091117 -vn -4.592284 2.779734 1.484816 -v 0.037484 -0.006618 0.091142 -vn -4.480219 2.722574 1.841756 -v 0.037476 -0.006617 0.091117 -vn -4.823015 2.745334 -0.303617 -v 0.037543 -0.006638 0.091682 -vn -4.847904 -2.850848 -0.280427 -v 0.037546 -0.006687 0.091647 -vn -4.793616 2.720106 -0.578671 -v 0.037539 -0.006640 0.091721 -vn -4.781398 -2.699891 -0.779741 -v 0.037539 -0.006690 0.091721 -vn -4.751308 2.739950 -0.926572 -v 0.037521 -0.006644 0.091822 -vn -4.711884 -2.718636 -1.240330 -v 0.037517 -0.006694 0.091841 -vn -4.631988 2.867062 -1.397858 -v 0.037484 -0.006649 0.091959 -vn -4.493809 -2.767990 -1.825264 -v 0.037458 -0.006702 0.092029 -vn -4.464406 2.700383 -1.847606 -v 0.037432 -0.006654 0.092092 -vn -4.309463 -2.705309 -2.203938 -v 0.037423 -0.006705 0.092111 -vn -4.367650 2.693494 -2.102150 -v 0.037423 -0.006655 0.092111 -vn -4.248878 2.721355 -2.433850 -v 0.037366 -0.006659 0.092217 -vn -4.110612 -2.735527 -2.563225 -v 0.037372 -0.006709 0.092206 -vn -3.955336 2.815445 -2.807771 -v 0.037286 -0.006665 0.092335 -vn -3.739877 -2.735916 -3.148168 -v 0.037260 -0.006716 0.092368 -vn -3.669889 2.671399 -3.187963 -v 0.037195 -0.006670 0.092443 -vn -3.497988 -2.686511 -3.376826 -v 0.037192 -0.006720 0.092446 -vn -3.518035 2.665285 -3.335478 -v 0.037192 -0.006670 0.092446 -vn -3.265174 -2.770504 -3.546590 -v 0.037150 -0.006722 0.092488 -vn -3.139774 2.853009 -3.705051 -v 0.037091 -0.006675 0.092541 -vn -3.112707 -2.744517 -3.700480 -v 0.037125 -0.006723 0.092511 -vn -2.914042 2.715056 -3.966885 -v 0.036978 -0.006680 0.092627 -vn -2.646293 -2.743524 -4.063700 -v 0.036970 -0.006731 0.092632 -vn -2.477544 2.695302 -4.149099 -v 0.036869 -0.006685 0.092693 -vn -2.251296 -2.712375 -4.277233 -v 0.036869 -0.006735 0.092693 -vn -2.261426 2.691347 -4.265198 -v 0.036857 -0.006685 0.092700 -vn -1.875592 -2.767546 -4.471983 -v 0.036799 -0.006738 0.092729 -vn -1.769239 3.051847 -4.480466 -v 0.036728 -0.006691 0.092759 -vn -0.234651 3.054190 -4.811518 -v 0.036313 -0.006706 0.092848 -vn -0.798967 2.684908 -4.774340 -v 0.036454 -0.006701 0.092834 -vn -0.315030 -2.767440 -4.837054 -v 0.036391 -0.006753 0.092842 -vn -1.400685 2.776040 -4.632594 -v 0.036593 -0.006696 0.092804 -vn -1.363772 -2.801163 -4.657821 -v 0.036614 -0.006745 0.092798 -vn -1.046660 2.701935 -4.727960 -v 0.036486 -0.006700 0.092828 -vn -0.834662 -2.678555 -4.812026 -v 0.036486 -0.006750 0.092828 -vn -0.576221 -2.695383 -4.825529 -v 0.036422 -0.006752 0.092839 -vn 0.191682 2.859560 -4.828978 -v 0.036171 -0.006711 0.092848 -vn 0.063328 -2.910058 -4.875595 -v 0.036225 -0.006760 0.092850 -vn 0.477736 2.721570 -4.810420 -v 0.036079 -0.006715 0.092839 -vn 0.657246 -2.712297 -4.797000 -v 0.036079 -0.006765 0.092839 -vn 0.772477 2.687570 -4.776738 -v 0.036030 -0.006717 0.092831 -vn 0.900582 -2.684275 -4.744057 -v 0.036030 -0.006767 0.092831 -vn 1.154489 -2.758602 -4.695507 -v 0.035988 -0.006768 0.092823 -vn 1.221269 2.786861 -4.684788 -v 0.035891 -0.006722 0.092800 -vn 1.638978 -2.768370 -4.558465 -v 0.035839 -0.006774 0.092783 -vn 1.705183 2.805488 -4.530953 -v 0.035757 -0.006727 0.092753 -vn 2.107775 -2.684886 -4.353745 -v 0.035689 -0.006780 0.092723 -vn 2.069654 2.698432 -4.387374 -v 0.035689 -0.006730 0.092723 -vn 2.415406 -2.786533 -4.194625 -v 0.035657 -0.006781 0.092707 -vn 2.546933 2.814671 -4.131021 -v 0.035526 -0.006737 0.092630 -vn 2.830017 -2.737773 -3.919644 -v 0.035489 -0.006788 0.092604 -vn 3.041823 -2.773578 -3.759031 -v 0.035473 -0.006789 0.092593 -vn 3.956067 -2.751141 -2.814366 -v 0.035210 -0.006803 0.092329 -vn 3.757673 2.770717 -3.051713 -v 0.035216 -0.006752 0.092338 -vn 3.527663 -2.729840 -3.303616 -v 0.035339 -0.006796 0.092477 -vn 3.526021 2.833482 -3.357997 -v 0.035308 -0.006747 0.092446 -vn 3.325844 -2.720892 -3.511124 -v 0.035354 -0.006795 0.092492 -vn 3.245658 2.723717 -3.600537 -v 0.035354 -0.006745 0.092492 -vn 3.046301 2.942293 -3.737130 -v 0.035412 -0.006742 0.092544 -vn 4.614756 -2.769835 -1.543700 -v 0.035024 -0.006817 0.091983 -vn 4.613636 2.721442 -1.753540 -v 0.035024 -0.006767 0.091983 -vn 4.242803 -3.117626 -2.315569 -v 0.035104 -0.006810 0.092163 -vn 4.390119 2.997310 -2.055919 -v 0.035070 -0.006763 0.092096 -vn 4.056200 3.467505 -2.438941 -v 0.035136 -0.006758 0.092221 -vn 4.332256 2.972507 -2.132013 -v 0.035080 -0.006462 0.092116 -vn 3.944950 2.739685 -2.824998 -v 0.035178 -0.006455 0.092286 -vn 4.284067 -2.865436 -2.244999 -v 0.035110 -0.006510 0.092174 -vn -4.860022 2.758570 0.271851 -v 0.037549 -0.006332 0.091504 -vn -4.765515 2.724834 0.885663 -v 0.037527 -0.006325 0.091308 -vn -4.793182 -2.746654 0.732556 -v 0.037528 -0.006375 0.091312 -vn -4.665047 2.770408 1.261371 -v 0.037515 -0.006322 0.091249 -vn -4.672179 -2.764069 1.251178 -v 0.037494 -0.006370 0.091174 -vn -4.512075 2.741260 1.755730 -v 0.037476 -0.006317 0.091117 -vn -4.555802 -2.737591 1.630824 -v 0.037476 -0.006367 0.091117 -vn -4.827398 -2.887736 0.342760 -v 0.037546 -0.006380 0.091452 -vn -4.837461 -2.871026 -0.272346 -v 0.037549 -0.006385 0.091594 -vn -4.848052 2.707770 -0.332030 -v 0.037541 -0.006339 0.091700 -vn -4.787563 -2.684226 -0.653146 -v 0.037538 -0.006390 0.091725 -vn -4.789449 2.695764 -0.662931 -v 0.037538 -0.006340 0.091725 -vn -4.741824 -2.737605 -0.926569 -v 0.037537 -0.006391 0.091736 -vn -4.687434 2.800666 -1.258689 -v 0.037504 -0.006346 0.091893 -vn -4.665128 -2.780481 -1.308962 -v 0.037509 -0.006396 0.091875 -vn -4.484751 2.853770 -1.812012 -v 0.037438 -0.006354 0.092079 -vn -4.508536 -3.028855 -1.701540 -v 0.037466 -0.006401 0.092011 -vn -4.377649 2.714138 -2.054283 -v 0.037420 -0.006355 0.092116 -vn -4.339975 -2.705260 -2.121878 -v 0.037420 -0.006405 0.092116 -vn -4.212101 -2.745997 -2.391230 -v 0.037408 -0.006406 0.092140 -vn -4.123515 2.750712 -2.550413 -v 0.037344 -0.006361 0.092252 -vn -3.989164 -2.764621 -2.775580 -v 0.037337 -0.006411 0.092263 -vn -3.733536 2.769998 -3.075340 -v 0.037226 -0.006368 0.092409 -vn -3.732955 -2.829273 -3.117148 -v 0.037253 -0.006417 0.092377 -vn -3.531035 2.704287 -3.306872 -v 0.037186 -0.006370 0.092452 -vn -3.481547 -2.684219 -3.391800 -v 0.037186 -0.006420 0.092452 -vn -3.244344 -2.756451 -3.583579 -v 0.037157 -0.006422 0.092482 -vn -3.178757 2.761132 -3.661538 -v 0.037085 -0.006375 0.092546 -vn -2.847792 -2.824136 -3.928504 -v 0.037050 -0.006427 0.092575 -vn -2.660429 2.723639 -4.049117 -v 0.036925 -0.006383 0.092661 -vn -2.538782 -2.721900 -4.148782 -v 0.036933 -0.006432 0.092656 -vn -2.321878 2.722616 -4.240469 -v 0.036859 -0.006385 0.092698 -vn -2.168993 -2.726423 -4.313660 -v 0.036859 -0.006435 0.092698 -vn -1.922089 2.768310 -4.449899 -v 0.036750 -0.006390 0.092750 -vn -1.976105 -2.843530 -4.405061 -v 0.036808 -0.006437 0.092724 -vn -1.442823 -2.871545 -4.622831 -v 0.036677 -0.006443 0.092778 -vn -1.327505 2.904773 -4.651580 -v 0.036563 -0.006397 0.092812 -vn -0.796307 -2.717196 -4.775267 -v 0.036472 -0.006450 0.092831 -vn -0.904038 2.709011 -4.768753 -v 0.036472 -0.006400 0.092831 -vn -0.504594 2.751389 -4.842145 -v 0.036369 -0.006404 0.092845 -vn -0.517169 -2.792548 -4.802786 -v 0.036422 -0.006452 0.092839 -vn 0.005650 -2.877179 -4.839858 -v 0.036280 -0.006458 0.092850 -vn 0.126421 2.749346 -4.842765 -v 0.036172 -0.006411 0.092848 -vn 0.486317 -2.730415 -4.816851 -v 0.036137 -0.006463 0.092845 -vn 0.596975 2.700664 -4.808773 -v 0.036063 -0.006415 0.092837 -vn 0.809725 -2.694342 -4.783304 -v 0.036063 -0.006466 0.092837 -vn 1.041980 2.800302 -4.728365 -v 0.035977 -0.006419 0.092821 -vn 1.099744 -2.736863 -4.718512 -v 0.035997 -0.006468 0.092825 -vn 1.662511 3.003469 -4.532337 -v 0.035789 -0.006426 0.092765 -vn 1.477779 -3.040459 -4.590889 -v 0.035859 -0.006473 0.092790 -vn 2.007517 2.697541 -4.405074 -v 0.035673 -0.006431 0.092715 -vn 1.905381 -2.938993 -4.440077 -v 0.035726 -0.006478 0.092740 -vn 2.255054 -2.697014 -4.275236 -v 0.035673 -0.006481 0.092715 -vn 2.401798 2.713721 -4.228400 -v 0.035610 -0.006433 0.092682 -vn 2.585157 -2.754729 -4.099302 -v 0.035600 -0.006484 0.092676 -vn 2.837841 2.734995 -3.932708 -v 0.035447 -0.006440 0.092572 -vn 2.877912 -2.857836 -3.882487 -v 0.035481 -0.006489 0.092598 -vn 3.029291 2.773396 -3.757160 -v 0.035419 -0.006442 0.092550 -vn 3.294259 -2.732475 -3.535210 -v 0.035371 -0.006494 0.092508 -vn 3.290243 2.685026 -3.536185 -v 0.035339 -0.006446 0.092478 -vn 3.493922 -2.683585 -3.353683 -v 0.035339 -0.006496 0.092478 -vn 3.521695 2.718889 -3.321592 -v 0.035302 -0.006448 0.092439 -vn 3.759240 -2.818316 -3.062678 -v 0.035272 -0.006499 0.092406 -vn 4.010733 -2.754791 -2.707636 -v 0.035184 -0.006505 0.092295 -vn 4.538914 2.728740 -1.692902 -v 0.035024 -0.006467 0.091983 -vn 4.452534 -2.987834 -1.861977 -v 0.035048 -0.006515 0.092046 -vn 4.696590 -2.675420 -1.440629 -v 0.035024 -0.006517 0.091983 -vn -4.557893 2.745140 1.645079 -v 0.037476 -0.006017 0.091117 -vn -4.625235 -2.744059 1.452143 -v 0.037476 -0.006067 0.091117 -vn -4.743920 2.980535 0.895281 -v 0.037527 -0.006025 0.091308 -vn -4.734260 -2.902116 1.019197 -v 0.037516 -0.006073 0.091256 -vn -4.833094 2.975076 0.175985 -v 0.037549 -0.006032 0.091504 -vn -4.836732 -2.968005 0.375894 -v 0.037546 -0.006080 0.091451 -vn -4.840365 2.830851 -0.426120 -v 0.037541 -0.006039 0.091700 -vn -4.837529 -2.957749 -0.300825 -v 0.037546 -0.006087 0.091648 -vn -4.743792 2.959059 -0.853904 -v 0.037527 -0.006042 0.091791 -vn -4.773597 -2.896357 -0.723038 -v 0.037539 -0.006090 0.091721 -vn -4.639901 2.984669 -1.316534 -v 0.037504 -0.006046 0.091893 -vn -4.694818 -2.881052 -1.187884 -v 0.037517 -0.006094 0.091842 -vn -4.493302 2.774565 -1.783517 -v 0.037438 -0.006054 0.092078 -vn -4.529456 -2.961560 -1.707893 -v 0.037458 -0.006102 0.092030 -vn -4.368026 2.734566 -2.085682 -v 0.037423 -0.006055 0.092111 -vn -4.295199 -2.737005 -2.217052 -v 0.037423 -0.006105 0.092111 -vn -4.058900 2.976012 -2.626421 -v 0.037344 -0.006061 0.092252 -vn -4.119438 -2.863427 -2.536905 -v 0.037372 -0.006109 0.092207 -vn -3.743857 2.793237 -3.060595 -v 0.037226 -0.006068 0.092409 -vn -3.789873 -2.968570 -3.005996 -v 0.037260 -0.006116 0.092369 -vn -3.528476 2.733604 -3.313322 -v 0.037192 -0.006070 0.092446 -vn -3.432105 -2.730150 -3.421780 -v 0.037192 -0.006120 0.092446 -vn -3.086467 2.967474 -3.728597 -v 0.037085 -0.006075 0.092546 -vn -3.165061 -2.839694 -3.666433 -v 0.037125 -0.006123 0.092512 -vn -2.667314 2.709177 -4.057499 -v 0.036925 -0.006083 0.092661 -vn -2.758847 -2.974413 -3.953315 -v 0.036970 -0.006131 0.092633 -vn -2.452910 -2.697448 -4.163463 -v 0.036941 -0.006132 0.092651 -vn -2.360266 2.714643 -4.236219 -v 0.036869 -0.006085 0.092693 -vn -2.197197 -2.725859 -4.307021 -v 0.036869 -0.006135 0.092693 -vn -1.815458 2.970976 -4.473929 -v 0.036750 -0.006090 0.092750 -vn -1.895953 -2.821765 -4.458029 -v 0.036798 -0.006138 0.092729 -vn -1.319787 2.798619 -4.669079 -v 0.036563 -0.006097 0.092812 -vn -1.434009 -2.948420 -4.649012 -v 0.036614 -0.006145 0.092798 -vn -1.120009 2.726600 -4.695975 -v 0.036506 -0.006099 0.092825 -vn -0.787856 -2.710674 -4.782949 -v 0.036486 -0.006150 0.092828 -vn -0.856831 2.683843 -4.778994 -v 0.036486 -0.006100 0.092828 -vn -0.541188 2.711529 -4.881941 -v 0.036369 -0.006104 0.092845 -vn -0.543112 -2.786811 -4.830905 -v 0.036421 -0.006152 0.092839 -vn -0.044655 -2.868299 -4.839305 -v 0.036289 -0.006157 0.092849 -vn 0.193051 2.843113 -4.833369 -v 0.036172 -0.006111 0.092848 -vn 0.201514 -2.795380 -4.841761 -v 0.036225 -0.006160 0.092850 -vn 0.527198 2.734025 -4.815260 -v 0.036079 -0.006115 0.092839 -vn 0.686799 -2.728871 -4.798906 -v 0.036079 -0.006165 0.092839 -vn 1.066088 2.966969 -4.715907 -v 0.035977 -0.006119 0.092821 -vn 0.989397 -2.788294 -4.747423 -v 0.036029 -0.006167 0.092831 -vn 1.628244 2.856767 -4.567953 -v 0.035789 -0.006126 0.092765 -vn 1.514713 -2.965883 -4.590927 -v 0.035838 -0.006174 0.092783 -vn 1.950523 2.726150 -4.447835 -v 0.035689 -0.006130 0.092723 -vn 2.090515 -2.730245 -4.368756 -v 0.035689 -0.006180 0.092723 -vn 2.433575 2.978707 -4.162481 -v 0.035610 -0.006133 0.092682 -vn 2.401634 -2.766797 -4.215408 -v 0.035657 -0.006181 0.092707 -vn 2.913728 2.880269 -3.862036 -v 0.035447 -0.006140 0.092572 -vn 2.813257 -2.951980 -3.965387 -v 0.035489 -0.006189 0.092604 -vn 3.212430 2.736763 -3.620839 -v 0.035354 -0.006145 0.092492 -vn 3.321091 -2.735106 -3.511024 -v 0.035354 -0.006195 0.092492 -vn 3.578062 2.974860 -3.242577 -v 0.035302 -0.006148 0.092439 -vn 3.539057 -2.754791 -3.298932 -v 0.035339 -0.006196 0.092477 -vn 3.881632 2.783589 -2.889327 -v 0.035178 -0.006155 0.092286 -vn 3.866081 -2.972602 -2.903625 -v 0.035209 -0.006203 0.092329 -vn 4.596064 -2.783681 -1.532219 -v 0.035024 -0.006217 0.091983 -vn 4.571426 2.767129 -1.679574 -v 0.035024 -0.006167 0.091983 -vn 4.258663 -2.970774 -2.278169 -v 0.035103 -0.006210 0.092162 -vn 4.332857 2.910862 -2.155644 -v 0.035080 -0.006162 0.092116 -vn 4.063317 3.221359 -2.519944 -v 0.035153 -0.006157 0.092248 -vn -0.539779 2.732332 -4.814166 -v 0.036369 -0.005804 0.092845 -vn -0.968666 2.735502 -4.739772 -v 0.036486 -0.005800 0.092828 -vn -0.806545 -2.734840 -4.770714 -v 0.036486 -0.005850 0.092828 -vn -4.541177 2.782341 1.691924 -v 0.037476 -0.005717 0.091117 -vn -4.597355 -2.779940 1.543859 -v 0.037476 -0.005767 0.091117 -vn -4.727907 2.777603 1.058905 -v 0.037527 -0.005725 0.091307 -vn -4.713190 -2.904409 1.065325 -v 0.037517 -0.005773 0.091257 -vn -4.774011 2.801999 0.799699 -v 0.037536 -0.005727 0.091358 -vn -4.817822 -2.783902 0.436277 -v 0.037544 -0.005779 0.091421 -vn -4.834903 2.954264 0.124940 -v 0.037549 -0.005732 0.091503 -vn -4.837897 -2.763416 0.169262 -v 0.037546 -0.005780 0.091452 -vn -4.857721 2.674477 -0.335771 -v 0.037541 -0.005739 0.091699 -vn -4.840126 -2.947305 -0.291732 -v 0.037546 -0.005787 0.091648 -vn -4.779648 -2.724135 -0.804855 -v 0.037539 -0.005790 0.091721 -vn -4.500921 2.698102 -1.768625 -v 0.037438 -0.005754 0.092078 -vn -4.580942 3.113614 -1.443650 -v 0.037496 -0.005747 0.091920 -vn -4.689720 -2.880805 -1.168387 -v 0.037517 -0.005794 0.091843 -vn -4.711777 2.749348 -1.106816 -v 0.037504 -0.005746 0.091892 -vn -4.810727 2.700711 -0.662158 -v 0.037539 -0.005740 0.091721 -vn -3.774087 2.727734 -3.021323 -v 0.037226 -0.005768 0.092408 -vn -3.676211 -2.767973 -3.134976 -v 0.037259 -0.005816 0.092369 -vn -3.654687 2.725868 -3.134202 -v 0.037222 -0.005768 0.092413 -vn -3.415200 -2.716041 -3.432112 -v 0.037192 -0.005820 0.092446 -vn -4.512238 -2.960901 -1.704333 -v 0.037458 -0.005802 0.092031 -vn -4.355035 -2.681330 -2.067307 -v 0.037432 -0.005804 0.092092 -vn -4.355813 2.714447 -2.100754 -v 0.037423 -0.005755 0.092111 -vn -4.265779 -2.714406 -2.274515 -v 0.037423 -0.005805 0.092111 -vn -4.070791 2.948656 -2.633418 -v 0.037345 -0.005761 0.092251 -vn -4.129931 -2.863637 -2.527195 -v 0.037372 -0.005809 0.092207 -vn -3.853021 -3.196309 -2.842539 -v 0.037285 -0.005815 0.092336 -vn -2.636337 -2.745159 -4.077673 -v 0.036969 -0.005831 0.092633 -vn -2.985363 2.866966 -3.799357 -v 0.037030 -0.005778 0.092590 -vn -3.184197 -2.834117 -3.651197 -v 0.037124 -0.005823 0.092512 -vn -3.212665 2.796774 -3.636640 -v 0.037086 -0.005775 0.092546 -vn -3.510139 2.708500 -3.348306 -v 0.037192 -0.005770 0.092446 -vn -1.881674 -2.720586 -4.458293 -v 0.036797 -0.005838 0.092729 -vn -2.115330 2.701521 -4.341222 -v 0.036785 -0.005788 0.092735 -vn -2.246440 -2.715722 -4.292476 -v 0.036869 -0.005835 0.092693 -vn -2.386873 2.725309 -4.204443 -v 0.036869 -0.005785 0.092693 -vn -2.597426 2.794291 -4.078308 -v 0.036926 -0.005783 0.092661 -vn -1.387487 -2.967618 -4.625168 -v 0.036613 -0.005845 0.092798 -vn -1.316153 2.806065 -4.676998 -v 0.036564 -0.005797 0.092812 -vn -1.753763 2.962404 -4.491037 -v 0.036750 -0.005790 0.092750 -vn -0.540111 -2.780128 -4.828234 -v 0.036420 -0.005852 0.092839 -vn -0.143803 -2.752797 -4.850019 -v 0.036311 -0.005856 0.092849 -vn -0.085354 2.699698 -4.833408 -v 0.036233 -0.005809 0.092850 -vn 0.171602 -2.699850 -4.825538 -v 0.036224 -0.005860 0.092850 -vn 0.227656 2.693385 -4.832023 -v 0.036173 -0.005811 0.092848 -vn 0.434568 -2.706031 -4.812765 -v 0.036169 -0.005862 0.092848 -vn 0.554978 2.699494 -4.826297 -v 0.036079 -0.005815 0.092839 -vn 0.729449 -2.716664 -4.783847 -v 0.036079 -0.005865 0.092839 -vn 1.054827 2.949856 -4.738193 -v 0.035978 -0.005819 0.092821 -vn 0.990611 -2.780478 -4.748160 -v 0.036028 -0.005867 0.092831 -vn 1.618077 2.860388 -4.560992 -v 0.035789 -0.005826 0.092765 -vn 1.511764 -2.963607 -4.590818 -v 0.035837 -0.005874 0.092783 -vn 1.945131 2.717549 -4.433971 -v 0.035689 -0.005830 0.092723 -vn 2.091526 -2.713881 -4.372591 -v 0.035689 -0.005880 0.092723 -vn 2.287216 -2.704895 -4.252470 -v 0.035656 -0.005881 0.092706 -vn 2.281845 2.707457 -4.258669 -v 0.035611 -0.005833 0.092682 -vn 2.478681 -2.702314 -4.147290 -v 0.035628 -0.005882 0.092691 -vn 2.579405 3.057612 -4.055176 -v 0.035560 -0.005835 0.092652 -vn 2.934850 2.882350 -3.840869 -v 0.035447 -0.005840 0.092572 -vn 2.851937 -2.920884 -3.905682 -v 0.035488 -0.005889 0.092603 -vn 3.207598 2.723244 -3.624968 -v 0.035354 -0.005845 0.092492 -vn 3.319177 -2.712726 -3.529615 -v 0.035354 -0.005895 0.092492 -vn 3.478477 -2.687768 -3.357136 -v 0.035338 -0.005896 0.092476 -vn 3.531420 2.706340 -3.328853 -v 0.035302 -0.005848 0.092440 -vn 3.700691 -2.761689 -3.117130 -v 0.035293 -0.005898 0.092430 -vn 3.936955 2.758556 -2.830997 -v 0.035179 -0.005855 0.092286 -vn 3.889396 -2.873245 -2.879795 -v 0.035208 -0.005903 0.092328 -vn 4.215052 -2.859246 -2.395606 -v 0.035136 -0.005908 0.092220 -vn 4.343096 2.893846 -2.140254 -v 0.035080 -0.005862 0.092116 -vn 4.366921 -2.773690 -2.195611 -v 0.035103 -0.005910 0.092162 -vn 4.557275 2.772286 -1.691022 -v 0.035024 -0.005867 0.091983 -vn 4.600515 -2.779890 -1.533859 -v 0.035024 -0.005917 0.091983 -vn -4.503917 2.750143 1.774022 -v 0.037476 -0.005417 0.091117 -vn -4.584796 -2.743052 1.585035 -v 0.037476 -0.005467 0.091117 -vn -4.644383 2.773677 1.361292 -v 0.037505 -0.005421 0.091209 -vn -4.729668 -2.762633 1.019162 -v 0.037516 -0.005473 0.091256 -vn -4.805794 2.802452 0.768061 -v 0.037534 -0.005426 0.091348 -vn -4.817066 -2.723293 0.720347 -v 0.037528 -0.005475 0.091314 -vn -4.849414 2.716713 0.360225 -v 0.037549 -0.005431 0.091489 -vn -3.817903 2.731147 -2.993883 -v 0.037243 -0.005467 0.092389 -vn -4.251274 2.736454 -2.333283 -v 0.037391 -0.005457 0.092173 -vn -4.021165 -2.871364 -2.707047 -v 0.037370 -0.005509 0.092211 -vn -3.878714 -3.056052 -2.842831 -v 0.037291 -0.005514 0.092329 -vn -3.677561 -2.727537 -3.129194 -v 0.037260 -0.005516 0.092368 -vn -3.579819 2.700535 -3.249672 -v 0.037192 -0.005470 0.092446 -vn -4.829443 -2.825815 0.381567 -v 0.037546 -0.005480 0.091450 -vn -4.834388 -2.773447 -0.117176 -v 0.037550 -0.005484 0.091554 -vn -4.865740 2.690422 -0.205188 -v 0.037547 -0.005437 0.091631 -vn -4.843428 -2.684873 -0.473108 -v 0.037546 -0.005487 0.091647 -vn -4.879675 2.652038 -0.498806 -v 0.037539 -0.005440 0.091721 -vn -4.810651 -2.670509 -0.725499 -v 0.037539 -0.005490 0.091721 -vn -4.793459 2.708338 -0.773197 -v 0.037531 -0.005442 0.091773 -vn -4.705228 -2.762705 -1.071274 -v 0.037523 -0.005493 0.091814 -vn -4.638944 3.010325 -1.365164 -v 0.037499 -0.005447 0.091911 -vn -4.676136 -2.816110 -1.276687 -v 0.037517 -0.005494 0.091841 -vn -4.609155 2.695926 -1.680029 -v 0.037452 -0.005452 0.092045 -vn -4.516905 -2.787085 -1.754496 -v 0.037458 -0.005502 0.092029 -vn -4.414638 2.704069 -1.984110 -v 0.037423 -0.005455 0.092111 -vn -4.319266 -2.700438 -2.180453 -v 0.037423 -0.005505 0.092111 -vn -4.161956 -2.683570 -2.481623 -v 0.037372 -0.005509 0.092206 -vn -3.516036 -2.700686 -3.316881 -v 0.037200 -0.005520 0.092438 -vn -3.392813 -2.669973 -3.456513 -v 0.037192 -0.005520 0.092446 -vn -3.390384 2.682550 -3.530921 -v 0.037145 -0.005472 0.092493 -vn -3.149088 -2.728303 -3.704391 -v 0.037125 -0.005523 0.092511 -vn -3.056277 2.858727 -3.780086 -v 0.037036 -0.005478 0.092585 -vn -2.640325 -2.768062 -4.062581 -v 0.036970 -0.005531 0.092632 -vn -2.614515 2.737542 -4.069327 -v 0.036919 -0.005483 0.092665 -vn -2.283377 -2.681973 -4.249299 -v 0.036869 -0.005535 0.092693 -vn -2.365766 2.690015 -4.219113 -v 0.036869 -0.005485 0.092693 -vn -2.129071 -2.692357 -4.325734 -v 0.036863 -0.005535 0.092696 -vn -2.099044 2.694242 -4.371938 -v 0.036793 -0.005488 0.092731 -vn -1.956065 -2.702492 -4.416452 -v 0.036799 -0.005538 0.092729 -vn -1.655355 -2.754628 -4.565128 -v 0.036735 -0.005540 0.092756 -vn -1.632653 2.753160 -4.560677 -v 0.036661 -0.005493 0.092783 -vn -1.295425 -2.714871 -4.738999 -v 0.036614 -0.005545 0.092798 -vn -1.191655 2.745144 -4.686177 -v 0.036524 -0.005498 0.092821 -vn -0.802320 -2.706852 -4.771740 -v 0.036486 -0.005550 0.092828 -vn -0.918632 2.701414 -4.740514 -v 0.036486 -0.005500 0.092828 -vn -0.498723 2.819882 -4.829334 -v 0.036384 -0.005504 0.092843 -vn -0.486680 -2.763962 -4.816597 -v 0.036422 -0.005552 0.092839 -vn -0.150375 2.758162 -4.863394 -v 0.036242 -0.005509 0.092850 -vn 2.930239 -2.753522 -3.888518 -v 0.035489 -0.005588 0.092604 -vn 2.451296 2.872428 -4.178425 -v 0.035568 -0.005535 0.092657 -vn 2.391738 -2.742504 -4.204691 -v 0.035657 -0.005581 0.092707 -vn 2.084884 2.657733 -4.395736 -v 0.035689 -0.005530 0.092723 -vn 2.078585 -2.709760 -4.362000 -v 0.035689 -0.005580 0.092723 -vn 1.871330 2.656750 -4.552506 -v 0.035693 -0.005530 0.092725 -vn 1.687076 -2.720244 -4.535782 -v 0.035838 -0.005574 0.092783 -vn 1.567928 2.741956 -4.597789 -v 0.035824 -0.005525 0.092778 -vn 1.372175 -2.773442 -4.638301 -v 0.035899 -0.005572 0.092802 -vn 0.973870 2.729793 -4.787498 -v 0.035960 -0.005519 0.092817 -vn 0.973367 -2.739769 -4.736372 -v 0.036030 -0.005567 0.092831 -vn 0.627107 2.672351 -4.805006 -v 0.036079 -0.005515 0.092839 -vn 0.695697 -2.685947 -4.783764 -v 0.036079 -0.005565 0.092839 -vn 0.375052 2.707491 -4.817064 -v 0.036100 -0.005514 0.092841 -vn 0.405468 -2.769077 -4.813023 -v 0.036179 -0.005561 0.092848 -vn 0.091257 -2.718196 -4.835608 -v 0.036225 -0.005560 0.092850 -vn 3.951659 -2.775249 -2.812465 -v 0.035210 -0.005603 0.092329 -vn 3.641452 2.849726 -3.190942 -v 0.035248 -0.005551 0.092378 -vn 3.557460 -2.701172 -3.293885 -v 0.035339 -0.005596 0.092477 -vn 3.370926 2.702630 -3.455438 -v 0.035344 -0.005545 0.092483 -vn 3.305501 -2.706418 -3.542765 -v 0.035354 -0.005595 0.092492 -vn 3.158468 2.724845 -3.653836 -v 0.035354 -0.005545 0.092492 -vn 2.953144 2.842894 -3.859256 -v 0.035451 -0.005540 0.092576 -vn 4.584145 -2.741862 -1.585908 -v 0.035024 -0.005617 0.091983 -vn 4.499894 2.747706 -1.786774 -v 0.035024 -0.005567 0.091983 -vn 4.294447 -2.827215 -2.247051 -v 0.035104 -0.005610 0.092163 -vn 4.284200 2.826772 -2.249348 -v 0.035092 -0.005561 0.092141 -vn 4.021857 3.068787 -2.647470 -v 0.035163 -0.005556 0.092264 -vn -4.539973 2.712369 1.709723 -v 0.037476 -0.005117 0.091117 -vn -4.557694 -2.723505 1.601720 -v 0.037476 -0.005167 0.091117 -vn -4.672039 2.916989 1.372564 -v 0.037499 -0.005120 0.091188 -vn -4.620824 -2.779369 1.399539 -v 0.037479 -0.005168 0.091126 -vn -4.750275 2.724568 0.960482 -v 0.037527 -0.005125 0.091306 -vn -4.702314 -2.866488 1.099813 -v 0.037518 -0.005173 0.091262 -vn -4.830960 -2.727621 0.623051 -v 0.037529 -0.005175 0.091314 -vn -4.845823 2.788278 0.332990 -v 0.037549 -0.005132 0.091502 -vn -4.861309 -2.776825 0.027452 -v 0.037550 -0.005183 0.091522 -vn -4.832020 2.708182 -0.322022 -v 0.037543 -0.005139 0.091688 -vn -4.832442 -2.762522 -0.436018 -v 0.037545 -0.005188 0.091665 -vn -4.818046 2.706438 -0.652418 -v 0.037539 -0.005140 0.091721 -vn -4.834296 -2.684015 -0.828956 -v 0.037539 -0.005190 0.091721 -vn -4.725242 2.761150 -1.146435 -v 0.037507 -0.005146 0.091881 -vn -4.751661 -2.935061 -0.991678 -v 0.037525 -0.005193 0.091806 -vn -4.574592 -2.848782 -1.616852 -v 0.037489 -0.005198 0.091943 -vn -4.527472 2.712730 -1.741635 -v 0.037443 -0.005153 0.092067 -vn -4.450784 -2.682998 -1.965956 -v 0.037439 -0.005204 0.092076 -vn -4.387800 2.701854 -2.066655 -v 0.037423 -0.005155 0.092111 -vn -4.281123 -2.714873 -2.237413 -v 0.037423 -0.005205 0.092111 -vn -4.112709 2.861257 -2.547672 -v 0.037357 -0.005160 0.092231 -vn -4.124741 -2.790699 -2.549828 -v 0.037374 -0.005209 0.092202 -vn -3.813192 2.767728 -2.982825 -v 0.037242 -0.005167 0.092390 -vn -3.908887 -3.105978 -2.852035 -v 0.037297 -0.005214 0.092321 -vn -3.543493 -2.692005 -3.285423 -v 0.037206 -0.005219 0.092431 -vn -3.538025 2.706488 -3.301768 -v 0.037192 -0.005170 0.092446 -vn -3.372209 -2.690083 -3.484429 -v 0.037192 -0.005220 0.092446 -vn -3.230190 2.737469 -3.640507 -v 0.037103 -0.005174 0.092531 -vn -3.103754 -2.740956 -3.749548 -v 0.037104 -0.005224 0.092530 -vn -2.716123 2.815593 -4.005763 -v 0.036955 -0.005181 0.092642 -vn -2.731751 -2.867371 -3.988356 -v 0.036992 -0.005230 0.092617 -vn -2.410004 2.735034 -4.190291 -v 0.036869 -0.005185 0.092693 -vn -2.244994 -2.732072 -4.291706 -v 0.036872 -0.005235 0.092692 -vn -2.041683 2.767231 -4.390126 -v 0.036782 -0.005188 0.092736 -vn -1.692809 -2.820830 -4.539717 -v 0.036744 -0.005240 0.092753 -vn -1.421306 2.736780 -4.639545 -v 0.036597 -0.005196 0.092803 -vn -1.273894 -2.754400 -4.676932 -v 0.036610 -0.005245 0.092799 -vn -1.023491 2.709726 -4.726099 -v 0.036486 -0.005200 0.092828 -vn -0.882427 -2.701430 -4.750512 -v 0.036486 -0.005250 0.092828 -vn -0.636294 -2.686994 -4.788060 -v 0.036471 -0.005250 0.092831 -vn -0.637004 2.763064 -4.806214 -v 0.036416 -0.005202 0.092839 -vn -0.180028 -2.862001 -4.858785 -v 0.036330 -0.005256 0.092848 -vn -0.039656 2.733681 -4.867691 -v 0.036219 -0.005210 0.092850 -vn 0.333298 -2.754262 -4.835177 -v 0.036188 -0.005261 0.092849 -vn 0.476638 2.709790 -4.809927 -v 0.036079 -0.005215 0.092839 -vn 0.674399 -2.706615 -4.784494 -v 0.036079 -0.005265 0.092839 -vn 0.912042 2.812775 -4.750625 -v 0.036023 -0.005217 0.092830 -vn 0.966284 -2.717053 -4.743625 -v 0.036047 -0.005266 0.092834 -vn 1.418436 2.763220 -4.644251 -v 0.035833 -0.005224 0.092781 -vn 1.260556 -3.055508 -4.658212 -v 0.035908 -0.005271 0.092804 -vn 1.860301 -2.797902 -4.465863 -v 0.035773 -0.005277 0.092759 -vn 1.926625 2.694768 -4.433538 -v 0.035689 -0.005230 0.092723 -vn 2.287657 -2.675711 -4.328645 -v 0.035689 -0.005280 0.092723 -vn 2.304456 2.905666 -4.238327 -v 0.035652 -0.005231 0.092704 -vn 2.763502 2.768727 -3.991898 -v 0.035484 -0.005239 0.092600 -vn 2.623970 -3.014646 -4.086134 -v 0.035540 -0.005286 0.092639 -vn 3.139829 -2.805180 -3.718909 -v 0.035425 -0.005291 0.092555 -vn 3.186691 2.679020 -3.651651 -v 0.035354 -0.005245 0.092492 -vn 3.364684 -2.703769 -3.461928 -v 0.035354 -0.005295 0.092492 -vn 3.428686 2.694994 -3.415184 -v 0.035335 -0.005246 0.092473 -vn 3.609040 -2.776271 -3.213289 -v 0.035320 -0.005297 0.092459 -vn 3.840681 2.753606 -2.969673 -v 0.035206 -0.005253 0.092324 -vn 3.834171 -2.817520 -2.954509 -v 0.035227 -0.005302 0.092352 -vn 4.158239 -2.876813 -2.475683 -v 0.035145 -0.005307 0.092235 -vn 4.235017 2.762334 -2.361986 -v 0.035101 -0.005260 0.092158 -vn 4.430120 -2.835895 -1.954463 -v 0.035077 -0.005312 0.092111 -vn 4.553894 2.754727 -1.684348 -v 0.035024 -0.005267 0.091983 -vn 4.615386 -2.760319 -1.484592 -v 0.035024 -0.005317 0.091983 -vn 0.736132 -2.709796 -4.776705 -v 0.036063 -0.004966 0.092837 -vn 0.333095 2.812326 -4.811172 -v 0.036132 -0.004913 0.092845 -vn 0.051358 -2.945552 -4.852453 -v 0.036224 -0.004960 0.092850 -vn 0.078211 2.758915 -4.870495 -v 0.036172 -0.004911 0.092848 -vn -0.420899 -2.690635 -4.837161 -v 0.036416 -0.004953 0.092839 -vn -0.323576 2.922946 -4.833432 -v 0.036369 -0.004904 0.092845 -vn -0.722305 2.690417 -4.769814 -v 0.036415 -0.004903 0.092839 -vn -0.794832 -2.712011 -4.778141 -v 0.036472 -0.004950 0.092831 -vn -0.975252 2.723916 -4.730984 -v 0.036472 -0.004900 0.092831 -vn -1.367004 -2.878283 -4.676154 -v 0.036609 -0.004945 0.092799 -vn -1.264316 2.832996 -4.665777 -v 0.036563 -0.004897 0.092812 -vn -1.726353 -2.689371 -4.530979 -v 0.036764 -0.004939 0.092744 -vn -1.606575 3.041675 -4.535886 -v 0.036691 -0.004892 0.092773 -vn -1.976506 2.705970 -4.411810 -v 0.036750 -0.004890 0.092750 -vn -4.720555 2.704856 -1.184301 -v 0.037504 -0.004846 0.091893 -vn -4.564422 -2.789052 -1.588465 -v 0.037496 -0.004897 0.091922 -vn -4.504498 2.707316 -1.807241 -v 0.037438 -0.004854 0.092078 -vn -4.450064 -2.780350 -1.884361 -v 0.037447 -0.004903 0.092056 -vn -4.387616 2.702825 -2.111176 -v 0.037420 -0.004855 0.092116 -vn -4.278389 -2.727821 -2.256987 -v 0.037420 -0.004905 0.092116 -vn -4.114170 2.811706 -2.598270 -v 0.037344 -0.004861 0.092252 -vn -4.060808 -2.779565 -2.648256 -v 0.037357 -0.004910 0.092231 -vn -3.753843 2.752566 -3.067176 -v 0.037226 -0.004868 0.092409 -vn -3.763095 -2.852411 -3.062927 -v 0.037249 -0.004917 0.092381 -vn -3.514610 2.728301 -3.322932 -v 0.037186 -0.004870 0.092452 -vn -3.395087 -2.729407 -3.452591 -v 0.037186 -0.004920 0.092452 -vn -3.109060 2.861810 -3.735157 -v 0.037085 -0.004875 0.092546 -vn -3.123377 -2.775867 -3.738280 -v 0.037112 -0.004924 0.092523 -vn -2.647328 2.766052 -4.071233 -v 0.036925 -0.004883 0.092661 -vn -2.698772 -2.848075 -4.058060 -v 0.036955 -0.004931 0.092642 -vn -2.355910 2.716834 -4.246348 -v 0.036859 -0.004885 0.092698 -vn -2.185282 -2.729526 -4.318685 -v 0.036859 -0.004935 0.092698 -vn -1.992479 -2.797116 -4.398769 -v 0.036794 -0.004938 0.092731 -vn -4.845695 2.783045 0.231220 -v 0.037549 -0.004832 0.091503 -vn -4.873750 -2.744297 0.106287 -v 0.037549 -0.004881 0.091491 -vn -4.827415 2.715010 -0.316656 -v 0.037541 -0.004839 0.091700 -vn -4.824607 -2.756143 -0.464991 -v 0.037543 -0.004889 0.091688 -vn -4.810280 2.707151 -0.692696 -v 0.037538 -0.004840 0.091725 -vn -4.819711 -2.677237 -0.894741 -v 0.037538 -0.004890 0.091725 -vn -4.719250 -2.757074 -1.148915 -v 0.037510 -0.004896 0.091870 -vn -4.578218 2.730109 1.647434 -v 0.037476 -0.004817 0.091117 -vn -4.659975 -2.716663 1.371840 -v 0.037476 -0.004867 0.091117 -vn -4.764790 2.783996 0.992551 -v 0.037527 -0.004825 0.091308 -vn -4.759370 -2.788479 0.921949 -v 0.037525 -0.004874 0.091296 -vn -4.731187 -3.340430 0.592522 -v 0.037536 -0.004877 0.091359 -vn 3.459606 -2.729178 -3.415138 -v 0.035338 -0.004996 0.092477 -vn 3.827325 -2.969101 -2.943619 -v 0.035209 -0.005003 0.092328 -vn 3.928419 2.732016 -2.843939 -v 0.035178 -0.004955 0.092286 -vn 3.579289 2.977187 -3.225426 -v 0.035302 -0.004948 0.092439 -vn 3.234228 2.734166 -3.610848 -v 0.035339 -0.004946 0.092478 -vn 2.836465 -2.966748 -3.915639 -v 0.035488 -0.004989 0.092603 -vn 2.954606 2.887845 -3.861932 -v 0.035447 -0.004940 0.092572 -vn 2.393051 -2.758047 -4.197031 -v 0.035656 -0.004981 0.092707 -vn 2.454847 2.968975 -4.159638 -v 0.035610 -0.004933 0.092682 -vn 2.123625 -2.737646 -4.339250 -v 0.035673 -0.004981 0.092715 -vn 1.987787 2.738814 -4.409854 -v 0.035673 -0.004931 0.092715 -vn 1.520051 -2.965743 -4.587306 -v 0.035837 -0.004974 0.092783 -vn 1.632602 2.884855 -4.556498 -v 0.035789 -0.004926 0.092765 -vn 1.016325 -2.777899 -4.725477 -v 0.036028 -0.004967 0.092831 -vn 1.083105 2.964393 -4.709092 -v 0.035977 -0.004919 0.092821 -vn 0.619619 2.703250 -4.796048 -v 0.036063 -0.004915 0.092837 -vn 4.329355 -2.834635 -2.170679 -v 0.035103 -0.005010 0.092162 -vn 4.598528 -2.729761 -1.589819 -v 0.035024 -0.005017 0.091983 -vn 4.507328 2.722713 -1.825797 -v 0.035024 -0.004967 0.091983 -vn 4.167012 -2.836590 -2.445518 -v 0.035151 -0.005007 0.092244 -vn 4.347017 2.901726 -2.133744 -v 0.035080 -0.004962 0.092116 -vn -4.795792 -2.709062 -0.842427 -v 0.037538 -0.004590 0.091725 -vn -4.805461 2.700132 -0.704290 -v 0.037538 -0.004540 0.091725 -vn -4.830040 2.695477 -0.321490 -v 0.037541 -0.004539 0.091700 -vn -4.539082 2.783867 1.691366 -v 0.037476 -0.004517 0.091117 -vn -4.622234 -2.768622 1.521815 -v 0.037476 -0.004567 0.091117 -vn -4.747289 2.961590 0.900268 -v 0.037527 -0.004525 0.091307 -vn -4.747611 -2.894627 1.051899 -v 0.037517 -0.004573 0.091257 -vn -4.835912 2.963751 0.176994 -v 0.037549 -0.004532 0.091503 -vn -4.821396 -2.969207 0.350666 -v 0.037546 -0.004580 0.091452 -vn -4.821853 -2.961796 -0.283642 -v 0.037546 -0.004587 0.091648 -vn -4.687521 2.943051 -1.275281 -v 0.037504 -0.004546 0.091892 -vn -4.721336 -2.861984 -1.170088 -v 0.037517 -0.004594 0.091843 -vn -4.501377 2.767429 -1.824781 -v 0.037438 -0.004554 0.092078 -vn -4.506826 -2.964832 -1.724319 -v 0.037458 -0.004602 0.092031 -vn -4.427516 2.674043 -2.065231 -v 0.037420 -0.004555 0.092116 -vn -2.532052 2.813451 -4.101424 -v 0.036926 -0.004583 0.092661 -vn -2.774200 2.697087 -3.958004 -v 0.036954 -0.004581 0.092643 -vn -2.558102 -2.710286 -4.107224 -v 0.036969 -0.004631 0.092633 -vn -4.330088 -2.694163 -2.191082 -v 0.037420 -0.004605 0.092116 -vn -4.197463 -2.792930 -2.399248 -v 0.037390 -0.004608 0.092175 -vn -4.052741 2.954404 -2.635338 -v 0.037345 -0.004561 0.092251 -vn -4.072585 -2.774297 -2.622985 -v 0.037372 -0.004609 0.092207 -vn -3.740903 2.799450 -3.070861 -v 0.037226 -0.004568 0.092409 -vn -3.795795 -2.955497 -3.004769 -v 0.037259 -0.004616 0.092369 -vn -3.520391 2.737715 -3.314725 -v 0.037186 -0.004570 0.092452 -vn -3.410337 -2.735342 -3.430485 -v 0.037186 -0.004620 0.092452 -vn -3.106361 2.921582 -3.701517 -v 0.037085 -0.004575 0.092546 -vn -3.178384 -2.823150 -3.672362 -v 0.037124 -0.004623 0.092512 -vn -2.887333 -3.045060 -3.864063 -v 0.037018 -0.004628 0.092599 -vn -2.337369 2.724347 -4.259777 -v 0.036859 -0.004585 0.092698 -vn -2.211931 -2.727684 -4.313070 -v 0.036859 -0.004635 0.092698 -vn -1.826752 2.960711 -4.476445 -v 0.036750 -0.004590 0.092750 -vn -1.894203 -2.815278 -4.447906 -v 0.036797 -0.004638 0.092729 -vn -1.290013 2.839363 -4.658497 -v 0.036564 -0.004597 0.092812 -vn -1.380106 -2.970198 -4.626919 -v 0.036613 -0.004645 0.092798 -vn -0.935891 2.732667 -4.752243 -v 0.036472 -0.004600 0.092831 -vn -0.778069 -2.731642 -4.779314 -v 0.036472 -0.004650 0.092831 -vn -0.435037 2.768276 -4.830496 -v 0.036369 -0.004604 0.092845 -vn -0.576900 -2.780910 -4.791068 -v 0.036420 -0.004652 0.092839 -vn -0.253565 -2.708604 -4.847732 -v 0.036382 -0.004654 0.092843 -vn 0.185402 2.852688 -4.839930 -v 0.036173 -0.004611 0.092848 -vn 0.083447 -2.888044 -4.885141 -v 0.036224 -0.004660 0.092850 -vn 0.549549 2.733866 -4.806625 -v 0.036063 -0.004615 0.092836 -vn 0.709268 -2.737627 -4.783630 -v 0.036063 -0.004666 0.092837 -vn 1.088083 2.962421 -4.707216 -v 0.035978 -0.004619 0.092821 -vn 1.023881 -2.763815 -4.733996 -v 0.036028 -0.004667 0.092831 -vn 1.533479 2.773105 -4.599687 -v 0.035789 -0.004626 0.092765 -vn 1.505385 -2.954214 -4.604405 -v 0.035837 -0.004674 0.092783 -vn 1.774078 2.842901 -4.483573 -v 0.035749 -0.004627 0.092750 -vn 2.157320 -2.706562 -4.329388 -v 0.035673 -0.004681 0.092715 -vn 3.453824 -2.728290 -3.423905 -v 0.035338 -0.004696 0.092476 -vn 3.240207 2.718696 -3.626967 -v 0.035339 -0.004646 0.092478 -vn 2.852805 -2.951124 -3.923903 -v 0.035488 -0.004689 0.092603 -vn 2.949476 2.900905 -3.843647 -v 0.035447 -0.004640 0.092572 -vn 2.398219 -2.753583 -4.196966 -v 0.035656 -0.004681 0.092706 -vn 2.444118 2.961952 -4.160293 -v 0.035611 -0.004633 0.092682 -vn 2.044282 2.702558 -4.376723 -v 0.035673 -0.004631 0.092715 -vn 3.949596 2.842016 -2.806900 -v 0.035178 -0.004655 0.092286 -vn 3.616148 3.076509 -3.157448 -v 0.035288 -0.004648 0.092425 -vn 3.437864 2.744027 -3.377742 -v 0.035302 -0.004648 0.092440 -vn 4.306290 -2.837082 -2.218290 -v 0.035103 -0.004710 0.092162 -vn 4.589183 -2.785611 -1.541048 -v 0.035024 -0.004717 0.091983 -vn 4.539709 2.782341 -1.694105 -v 0.035024 -0.004667 0.091983 -vn 3.864426 -2.960267 -2.900642 -v 0.035208 -0.004703 0.092328 -vn 4.334540 2.897473 -2.146480 -v 0.035080 -0.004662 0.092116 -vn -4.778010 -2.712034 -0.835206 -v 0.037538 -0.004290 0.091725 -vn -4.785285 2.725388 -0.680880 -v 0.037538 -0.004240 0.091725 -vn -4.825164 2.707712 -0.324710 -v 0.037541 -0.004239 0.091699 -vn -4.538083 2.783710 1.692824 -v 0.037476 -0.004217 0.091117 -vn -4.595554 -2.783319 1.532037 -v 0.037476 -0.004267 0.091117 -vn -4.744516 2.979018 0.898713 -v 0.037527 -0.004225 0.091307 -vn -4.724279 -2.905167 1.026705 -v 0.037516 -0.004273 0.091256 -vn -4.823648 2.978113 0.186290 -v 0.037549 -0.004232 0.091502 -vn -4.823313 -2.972501 0.351404 -v 0.037546 -0.004280 0.091450 -vn -4.833198 -2.955396 -0.264815 -v 0.037546 -0.004287 0.091647 -vn -4.655126 2.974666 -1.287489 -v 0.037504 -0.004246 0.091892 -vn -4.718994 -2.861231 -1.171258 -v 0.037517 -0.004294 0.091841 -vn -4.488976 2.785495 -1.789340 -v 0.037438 -0.004254 0.092077 -vn -4.508675 -2.970858 -1.718879 -v 0.037458 -0.004302 0.092029 -vn -4.362228 2.739761 -2.089376 -v 0.037420 -0.004255 0.092116 -vn -4.314339 -2.711458 -2.257987 -v 0.037420 -0.004305 0.092116 -vn -4.055489 2.972193 -2.632615 -v 0.037345 -0.004261 0.092251 -vn -4.140511 -2.840705 -2.537314 -v 0.037372 -0.004309 0.092206 -vn -3.764927 2.696033 -3.062133 -v 0.037227 -0.004268 0.092408 -vn -3.811649 -2.970465 -2.951916 -v 0.037260 -0.004316 0.092368 -vn -3.575249 -2.693615 -3.249971 -v 0.037233 -0.004318 0.092400 -vn -3.526219 2.712529 -3.331286 -v 0.037186 -0.004270 0.092452 -vn -3.385751 -2.721887 -3.450361 -v 0.037186 -0.004320 0.092452 -vn -3.074646 2.955832 -3.764513 -v 0.037086 -0.004275 0.092546 -vn -3.153527 -2.830642 -3.667656 -v 0.037125 -0.004323 0.092511 -vn -2.697155 2.688472 -4.046985 -v 0.036926 -0.004282 0.092660 -vn -2.749032 -2.971500 -3.957844 -v 0.036970 -0.004331 0.092632 -vn -2.404698 -2.699216 -4.186810 -v 0.036926 -0.004333 0.092661 -vn -2.327452 2.714387 -4.243093 -v 0.036859 -0.004285 0.092698 -vn -2.163828 -2.720607 -4.321643 -v 0.036859 -0.004335 0.092698 -vn -1.972577 2.780722 -4.415291 -v 0.036751 -0.004290 0.092750 -vn -1.942581 -2.803586 -4.427111 -v 0.036798 -0.004338 0.092729 -vn -1.774628 2.764831 -4.506639 -v 0.036709 -0.004291 0.092766 -vn -1.472910 -2.769251 -4.609927 -v 0.036668 -0.004343 0.092781 -vn -1.238801 2.838886 -4.680265 -v 0.036564 -0.004297 0.092812 -vn -1.239344 -2.793546 -4.674789 -v 0.036614 -0.004345 0.092798 -vn -0.948443 2.734066 -4.745720 -v 0.036472 -0.004300 0.092831 -vn -0.781647 -2.731876 -4.781307 -v 0.036472 -0.004350 0.092831 -vn -0.547043 2.795352 -4.796453 -v 0.036370 -0.004304 0.092844 -vn -0.503203 -2.778301 -4.821662 -v 0.036422 -0.004352 0.092839 -vn -0.311230 2.883061 -4.821297 -v 0.036314 -0.004306 0.092848 -vn 0.174868 -2.758588 -4.852352 -v 0.036225 -0.004360 0.092850 -vn 3.948614 2.838051 -2.816387 -v 0.035179 -0.004355 0.092287 -vn 3.581136 2.969228 -3.236340 -v 0.035302 -0.004348 0.092440 -vn 3.454954 -2.737195 -3.401274 -v 0.035339 -0.004396 0.092477 -vn 3.253572 2.708797 -3.647327 -v 0.035339 -0.004346 0.092478 -vn 2.822527 -2.968335 -3.927327 -v 0.035489 -0.004388 0.092604 -vn 2.966257 2.892411 -3.854316 -v 0.035448 -0.004340 0.092573 -vn 2.396271 -2.750050 -4.201816 -v 0.035657 -0.004381 0.092707 -vn 2.446240 2.971635 -4.157624 -v 0.035611 -0.004333 0.092682 -vn 2.126969 -2.735610 -4.338611 -v 0.035673 -0.004381 0.092715 -vn 1.987205 2.740983 -4.407750 -v 0.035673 -0.004331 0.092715 -vn 1.514819 -2.969414 -4.585851 -v 0.035838 -0.004374 0.092783 -vn 1.629108 2.893729 -4.551407 -v 0.035789 -0.004326 0.092766 -vn 1.009302 -2.775141 -4.729776 -v 0.036030 -0.004367 0.092831 -vn 1.079613 2.969391 -4.703033 -v 0.035978 -0.004319 0.092821 -vn 0.701514 -2.736432 -4.783906 -v 0.036063 -0.004366 0.092836 -vn 0.542882 2.736128 -4.808170 -v 0.036063 -0.004315 0.092837 -vn 0.237142 2.849318 -4.853152 -v 0.036173 -0.004311 0.092848 -vn 4.307443 -2.832175 -2.228019 -v 0.035104 -0.004410 0.092163 -vn 4.595319 -2.784037 -1.531809 -v 0.035024 -0.004417 0.091983 -vn 4.552207 2.771837 -1.708577 -v 0.035024 -0.004367 0.091983 -vn 3.862301 -2.969116 -2.906147 -v 0.035209 -0.004403 0.092329 -vn 4.347565 2.901290 -2.145277 -v 0.035080 -0.004362 0.092116 -vn -4.311120 -2.703715 -2.205621 -v 0.037423 -0.004005 0.092111 -vn -4.369673 2.688003 -2.087655 -v 0.037423 -0.003955 0.092111 -vn -4.444445 2.700692 -1.873657 -v 0.037433 -0.003954 0.092090 -vn -4.486568 -2.698462 -1.827422 -v 0.037458 -0.004002 0.092030 -vn -4.527596 2.701961 -1.682062 -v 0.037458 -0.003952 0.092030 -vn -4.660654 2.854884 -1.355802 -v 0.037484 -0.003949 0.091957 -vn -4.698042 -2.724822 -1.210951 -v 0.037517 -0.003994 0.091842 -vn -4.769360 2.708319 -1.017125 -v 0.037517 -0.003944 0.091842 -vn -4.776482 -2.718044 -0.784622 -v 0.037539 -0.003990 0.091721 -vn -4.799785 2.716712 -0.579088 -v 0.037539 -0.003940 0.091721 -vn -4.827025 -2.744896 -0.354922 -v 0.037546 -0.003987 0.091647 -vn -4.840785 2.738345 -0.156365 -v 0.037546 -0.003937 0.091648 -vn -4.838230 -2.761927 0.217147 -v 0.037546 -0.003980 0.091451 -vn -4.819885 2.768920 0.385474 -v 0.037546 -0.003930 0.091451 -vn -4.773455 -2.924058 0.783090 -v 0.037528 -0.003975 0.091314 -vn -4.775695 2.922075 0.685543 -v 0.037541 -0.003928 0.091396 -vn -4.734916 -2.746709 1.033340 -v 0.037516 -0.003973 0.091256 -vn -4.695603 2.743484 1.190317 -v 0.037516 -0.003923 0.091256 -vn -4.630686 -2.709261 1.440626 -v 0.037476 -0.003967 0.091117 -vn -4.562482 2.710928 1.568017 -v 0.037477 -0.003918 0.091120 -vn -4.479450 2.673977 1.840529 -v 0.037476 -0.003917 0.091117 -vn -4.261514 2.703202 -2.374389 -v 0.037372 -0.003959 0.092207 -vn -4.113333 -2.725039 -2.573298 -v 0.037372 -0.004009 0.092207 -vn -4.004865 2.858374 -2.706633 -v 0.037300 -0.003964 0.092316 -vn -3.727405 -2.706134 -3.100572 -v 0.037260 -0.004016 0.092369 -vn -3.809443 2.697591 -3.007297 -v 0.037260 -0.003966 0.092369 -vn -3.588074 2.710227 -3.259180 -v 0.037192 -0.003970 0.092446 -vn -3.457334 -2.717842 -3.383325 -v 0.037192 -0.004020 0.092446 -vn -3.266300 2.729293 -3.585326 -v 0.037125 -0.003973 0.092512 -vn -3.316695 -2.764158 -3.499456 -v 0.037157 -0.004022 0.092481 -vn -3.075645 -2.723417 -3.758056 -v 0.037125 -0.004023 0.092511 -vn -2.826596 2.752582 -3.939762 -v 0.036970 -0.003981 0.092633 -vn -2.687491 -2.737399 -4.061877 -v 0.036969 -0.004031 0.092633 -vn -2.419544 2.718389 -4.187070 -v 0.036869 -0.003985 0.092693 -vn -2.243832 -2.719668 -4.281030 -v 0.036869 -0.004035 0.092693 -vn -2.040777 2.742777 -4.390553 -v 0.036798 -0.003988 0.092729 -vn -1.869538 -2.743374 -4.469019 -v 0.036798 -0.004038 0.092729 -vn -1.467758 2.717762 -4.617958 -v 0.036614 -0.003995 0.092798 -vn -1.616128 -2.963545 -4.552193 -v 0.036677 -0.004043 0.092778 -vn -1.193058 -2.714605 -4.694298 -v 0.036614 -0.004045 0.092798 -vn -1.034070 2.714409 -4.730781 -v 0.036486 -0.004000 0.092828 -vn -0.846447 -2.712849 -4.768820 -v 0.036486 -0.004050 0.092828 -vn -0.622258 2.739173 -4.800664 -v 0.036421 -0.004002 0.092839 -vn -0.423872 -2.740783 -4.818848 -v 0.036421 -0.004052 0.092839 -vn -0.051977 2.760102 -4.847969 -v 0.036225 -0.004010 0.092850 -vn 0.161572 -2.753212 -4.865086 -v 0.036225 -0.004060 0.092850 -vn 0.452430 2.719824 -4.812081 -v 0.036079 -0.004015 0.092839 -vn 0.644686 -2.714219 -4.798942 -v 0.036079 -0.004065 0.092839 -vn 0.857241 2.733439 -4.764564 -v 0.036029 -0.004017 0.092831 -vn 1.049803 -2.734570 -4.723442 -v 0.036029 -0.004067 0.092831 -vn 1.410874 2.763077 -4.642472 -v 0.035838 -0.004024 0.092783 -vn 1.599924 -2.773279 -4.572022 -v 0.035838 -0.004074 0.092783 -vn 1.893399 2.716464 -4.450502 -v 0.035689 -0.004030 0.092723 -vn 2.088668 -2.714643 -4.370193 -v 0.035689 -0.004080 0.092723 -vn 2.250798 2.726885 -4.285899 -v 0.035657 -0.004031 0.092707 -vn 2.417207 -2.727340 -4.197231 -v 0.035657 -0.004081 0.092707 -vn 2.743903 2.731615 -4.017746 -v 0.035489 -0.004038 0.092604 -vn 2.790000 -2.731126 -3.948124 -v 0.035489 -0.004089 0.092604 -vn 3.115546 -2.794492 -3.700431 -v 0.035465 -0.004090 0.092586 -vn 3.318524 -2.753320 -3.549957 -v 0.035354 -0.004095 0.092492 -vn 3.359746 2.727999 -3.529172 -v 0.035338 -0.004046 0.092477 -vn 3.570853 -2.720842 -3.278327 -v 0.035338 -0.004096 0.092477 -vn 3.866444 2.756870 -2.985010 -v 0.035209 -0.004053 0.092329 -vn 3.949802 -2.777093 -2.818314 -v 0.035209 -0.004103 0.092329 -vn 4.219288 2.767318 -2.402085 -v 0.035103 -0.004060 0.092163 -vn 4.331578 -2.769199 -2.210149 -v 0.035103 -0.004110 0.092163 -vn 4.451161 2.746858 -1.899430 -v 0.035029 -0.004067 0.091996 -vn 4.619316 -2.748817 -1.526073 -v 0.035024 -0.004117 0.091983 -vn 4.603008 2.712118 -1.550306 -v 0.035024 -0.004067 0.091983 -vn -4.523910 2.756347 1.767347 -v 0.037476 -0.003617 0.091117 -vn -4.595309 -2.759377 1.559002 -v 0.037476 -0.003667 0.091117 -vn -4.710927 2.762802 1.147436 -v 0.037516 -0.003623 0.091256 -vn -4.759441 -2.757102 0.958829 -v 0.037516 -0.003673 0.091256 -vn -4.837524 2.747072 0.449667 -v 0.037546 -0.003630 0.091451 -vn -4.805442 -2.779811 0.523925 -v 0.037544 -0.003679 0.091429 -vn -4.832792 -2.724107 0.117656 -v 0.037546 -0.003680 0.091450 -vn -4.856510 2.729890 -0.165932 -v 0.037546 -0.003637 0.091648 -vn -4.827753 -2.745895 -0.356702 -v 0.037546 -0.003687 0.091647 -vn -4.815067 2.708949 -0.583897 -v 0.037538 -0.003640 0.091725 -vn -4.775433 -2.714810 -0.792349 -v 0.037538 -0.003690 0.091725 -vn -4.738741 2.749921 -1.066081 -v 0.037517 -0.003644 0.091842 -vn -4.705504 -2.738452 -1.244237 -v 0.037517 -0.003694 0.091842 -vn -4.583309 2.681475 -1.581658 -v 0.037458 -0.003652 0.092030 -vn -4.566227 -2.865211 -1.579030 -v 0.037474 -0.003700 0.091989 -vn -4.435480 -2.690205 -1.905799 -v 0.037458 -0.003702 0.092029 -vn -3.573998 2.699099 -3.273621 -v 0.037186 -0.003670 0.092452 -vn -3.796133 2.717595 -2.991360 -v 0.037260 -0.003666 0.092369 -vn -3.739575 -2.680767 -3.153940 -v 0.037260 -0.003716 0.092368 -vn -4.015839 2.867899 -2.688457 -v 0.037305 -0.003663 0.092309 -vn -4.113136 -2.716776 -2.573823 -v 0.037372 -0.003709 0.092206 -vn -4.218457 2.724692 -2.378685 -v 0.037372 -0.003659 0.092207 -vn -4.304373 -2.719366 -2.205193 -v 0.037420 -0.003705 0.092116 -vn -4.382427 2.719699 -2.035509 -v 0.037420 -0.003655 0.092116 -vn -4.454110 2.742604 -1.846632 -v 0.037445 -0.003653 0.092061 -vn -3.499298 -2.688527 -3.355581 -v 0.037186 -0.003720 0.092452 -vn -3.318045 -2.700831 -3.498661 -v 0.037173 -0.003721 0.092466 -vn -3.303171 2.689857 -3.559376 -v 0.037125 -0.003673 0.092512 -vn -3.170860 -2.702829 -3.643970 -v 0.037125 -0.003723 0.092511 -vn -2.915145 -2.869586 -3.852768 -v 0.037067 -0.003726 0.092561 -vn -2.815491 2.677984 -4.026391 -v 0.036970 -0.003681 0.092633 -vn -2.601600 -2.722884 -4.080869 -v 0.036970 -0.003731 0.092632 -vn -2.543706 2.717897 -4.132709 -v 0.036885 -0.003684 0.092684 -vn -2.207218 -2.692390 -4.310567 -v 0.036859 -0.003735 0.092698 -vn 2.887113 -2.742491 -3.905274 -v 0.035489 -0.003788 0.092604 -vn 3.463251 -2.730940 -3.424011 -v 0.035339 -0.003796 0.092477 -vn 3.267840 2.711152 -3.603327 -v 0.035338 -0.003746 0.092477 -vn 3.060001 3.053810 -3.717224 -v 0.035421 -0.003742 0.092551 -vn 2.684815 2.735965 -4.042866 -v 0.035489 -0.003738 0.092604 -vn 2.442048 -2.716493 -4.186514 -v 0.035657 -0.003781 0.092707 -vn 2.260446 2.727625 -4.272229 -v 0.035657 -0.003731 0.092707 -vn 2.106440 -2.711862 -4.362941 -v 0.035673 -0.003781 0.092715 -vn 1.922461 2.718117 -4.438553 -v 0.035673 -0.003731 0.092715 -vn 1.634380 -2.768219 -4.578561 -v 0.035839 -0.003774 0.092783 -vn 1.435184 2.765180 -4.642531 -v 0.035838 -0.003724 0.092783 -vn 1.057756 -2.730452 -4.718072 -v 0.036030 -0.003767 0.092831 -vn 0.863782 2.729749 -4.762876 -v 0.036029 -0.003717 0.092831 -vn 0.680614 -2.719675 -4.782951 -v 0.036063 -0.003766 0.092836 -vn 0.466266 2.691711 -4.855812 -v 0.036063 -0.003715 0.092837 -vn 0.163918 -2.770533 -4.844259 -v 0.036225 -0.003760 0.092850 -vn -0.022215 2.759619 -4.860161 -v 0.036225 -0.003710 0.092850 -vn -0.413333 -2.735572 -4.820773 -v 0.036422 -0.003752 0.092839 -vn -0.604613 2.733362 -4.805375 -v 0.036421 -0.003702 0.092839 -vn -0.818265 -2.714444 -4.771842 -v 0.036472 -0.003750 0.092831 -vn -1.006044 2.720407 -4.727998 -v 0.036472 -0.003700 0.092831 -vn -1.307912 -2.756879 -4.675497 -v 0.036614 -0.003745 0.092798 -vn -1.495092 2.765378 -4.609347 -v 0.036614 -0.003695 0.092798 -vn -1.853230 -2.735704 -4.480833 -v 0.036799 -0.003738 0.092729 -vn -2.027715 2.742477 -4.391106 -v 0.036798 -0.003688 0.092729 -vn -2.316405 2.690203 -4.228838 -v 0.036859 -0.003685 0.092698 -vn 4.239261 2.781880 -2.345102 -v 0.035103 -0.003760 0.092163 -vn 4.034450 3.104393 -2.608013 -v 0.035154 -0.003756 0.092249 -vn 3.926015 -2.744790 -2.856683 -v 0.035209 -0.003803 0.092329 -vn 3.773040 2.741216 -3.051514 -v 0.035209 -0.003753 0.092329 -vn 3.532490 2.791379 -3.357217 -v 0.035316 -0.003747 0.092455 -vn 4.322784 -2.783755 -2.193528 -v 0.035104 -0.003810 0.092163 -vn 4.617242 -2.748418 -1.543934 -v 0.035024 -0.003817 0.091983 -vn 4.518832 2.763775 -1.750287 -v 0.035024 -0.003767 0.091983 -vn -4.523005 2.760571 1.752995 -v 0.037476 -0.003317 0.091117 -vn -4.595647 -2.758163 1.562046 -v 0.037476 -0.003367 0.091117 -vn -4.716579 2.722744 1.198956 -v 0.037516 -0.003323 0.091256 -vn -4.726853 -2.742842 1.045823 -v 0.037517 -0.003373 0.091257 -vn -4.794075 2.844257 0.737649 -v 0.037539 -0.003327 0.091378 -vn -4.784912 -2.837949 0.751586 -v 0.037529 -0.003375 0.091316 -vn -4.829360 2.757768 0.403391 -v 0.037546 -0.003330 0.091451 -vn -4.849874 -2.756933 0.224999 -v 0.037546 -0.003380 0.091452 -vn -4.861775 2.727734 -0.175129 -v 0.037546 -0.003337 0.091648 -vn -4.838177 -2.734343 -0.370521 -v 0.037546 -0.003387 0.091648 -vn -4.820421 2.684683 -0.521062 -v 0.037538 -0.003340 0.091725 -vn -4.781898 -2.698704 -0.765572 -v 0.037538 -0.003390 0.091725 -vn -4.769467 2.806463 -0.824881 -v 0.037529 -0.003342 0.091781 -vn -4.778126 2.717896 -1.062847 -v 0.037517 -0.003344 0.091842 -vn -4.683735 -2.754587 -1.265167 -v 0.037517 -0.003394 0.091843 -vn -4.567515 2.749652 -1.606779 -v 0.037458 -0.003352 0.092030 -vn -4.502409 -2.741950 -1.797794 -v 0.037458 -0.003402 0.092031 -vn -4.392180 2.717628 -2.024544 -v 0.037420 -0.003355 0.092116 -vn -4.305449 -2.716541 -2.207599 -v 0.037420 -0.003405 0.092116 -vn -4.189392 2.746111 -2.433782 -v 0.037372 -0.003359 0.092207 -vn -4.088150 -2.750502 -2.607312 -v 0.037372 -0.003409 0.092207 -vn -3.902501 2.734404 -2.870986 -v 0.037260 -0.003366 0.092369 -vn -3.749849 -2.726267 -3.087978 -v 0.037259 -0.003416 0.092369 -vn -3.657188 2.804815 -3.148744 -v 0.037223 -0.003368 0.092412 -vn -3.543599 2.716727 -3.293918 -v 0.037186 -0.003370 0.092452 -vn -3.492020 -2.675907 -3.436244 -v 0.037186 -0.003420 0.092452 -vn -3.313553 2.692983 -3.553629 -v 0.037125 -0.003373 0.092512 -vn -3.199129 -2.701050 -3.628924 -v 0.037124 -0.003423 0.092512 -vn -2.918749 -2.847320 -3.876200 -v 0.037075 -0.003426 0.092555 -vn -2.796177 2.715374 -3.989800 -v 0.036970 -0.003381 0.092633 -vn -2.650236 -2.702600 -4.117682 -v 0.036969 -0.003431 0.092633 -vn -2.413043 2.712726 -4.201130 -v 0.036859 -0.003385 0.092698 -vn -2.223813 -2.715483 -4.296114 -v 0.036859 -0.003435 0.092698 -vn -2.030315 2.740956 -4.392148 -v 0.036798 -0.003388 0.092729 -vn -1.837538 -2.735879 -4.484720 -v 0.036797 -0.003438 0.092729 -vn -1.496315 2.762855 -4.607467 -v 0.036614 -0.003395 0.092798 -vn -1.320028 -2.752390 -4.684063 -v 0.036613 -0.003445 0.092798 -vn -1.003984 2.719397 -4.728773 -v 0.036472 -0.003400 0.092831 -vn -0.807108 -2.717061 -4.768345 -v 0.036472 -0.003450 0.092831 -vn -0.602425 2.726617 -4.812538 -v 0.036421 -0.003402 0.092839 -vn -0.405781 -2.731971 -4.827837 -v 0.036420 -0.003452 0.092839 -vn -0.037351 2.755282 -4.865635 -v 0.036225 -0.003410 0.092850 -vn 0.182617 -2.757634 -4.861234 -v 0.036224 -0.003460 0.092850 -vn 0.472546 2.709230 -4.825544 -v 0.036063 -0.003415 0.092837 -vn 0.687837 -2.703243 -4.810443 -v 0.036063 -0.003466 0.092837 -vn 0.862549 2.730247 -4.755507 -v 0.036029 -0.003417 0.092831 -vn 1.037611 -2.727075 -4.732436 -v 0.036028 -0.003467 0.092831 -vn 1.470708 2.729959 -4.625166 -v 0.035838 -0.003424 0.092783 -vn 1.329381 -2.901886 -4.655554 -v 0.035891 -0.003472 0.092799 -vn 1.727784 -2.687871 -4.589027 -v 0.035837 -0.003474 0.092783 -vn 1.911075 2.708374 -4.449248 -v 0.035673 -0.003431 0.092715 -vn 2.108180 -2.720898 -4.351180 -v 0.035673 -0.003481 0.092715 -vn 2.076976 2.667151 -4.339015 -v 0.035666 -0.003431 0.092711 -vn 2.239237 2.682639 -4.286388 -v 0.035657 -0.003431 0.092707 -vn 2.305379 -2.674112 -4.235512 -v 0.035656 -0.003481 0.092706 -vn 2.511961 -2.796747 -4.128979 -v 0.035628 -0.003482 0.092691 -vn 2.781241 2.739868 -3.978317 -v 0.035489 -0.003438 0.092604 -vn 2.742877 -2.758386 -3.981120 -v 0.035507 -0.003488 0.092617 -vn 3.035747 -2.721010 -3.775549 -v 0.035488 -0.003489 0.092603 -vn 3.326244 2.780721 -3.523887 -v 0.035338 -0.003446 0.092477 -vn 3.485915 -2.768745 -3.399164 -v 0.035339 -0.003496 0.092478 -vn 3.824605 2.759709 -2.996324 -v 0.035209 -0.003453 0.092329 -vn 4.169543 -2.855947 -2.448000 -v 0.035125 -0.003509 0.092202 -vn 4.246153 2.734736 -2.351851 -v 0.035103 -0.003460 0.092163 -vn 4.030535 -2.744040 -2.655221 -v 0.035203 -0.003503 0.092321 -vn 3.829487 -2.720838 -2.945081 -v 0.035208 -0.003503 0.092328 -vn 4.379816 -2.727053 -2.082715 -v 0.035103 -0.003510 0.092162 -vn 4.590076 -2.762653 -1.558161 -v 0.035024 -0.003517 0.091983 -vn 4.518095 2.764412 -1.749389 -v 0.035024 -0.003467 0.091983 -vn -4.751801 -3.196339 0.584296 -v 0.037543 -0.003079 0.091411 -vn -4.842991 2.727679 0.279613 -v 0.037549 -0.003032 0.091504 -vn -4.733299 -2.903604 1.036229 -v 0.037516 -0.003073 0.091256 -vn -4.749653 2.975557 0.906480 -v 0.037527 -0.003025 0.091308 -vn -4.617503 -2.762947 1.566611 -v 0.037476 -0.003067 0.091117 -vn -4.554098 2.775096 1.688984 -v 0.037476 -0.003017 0.091117 -vn -4.818670 -2.777709 0.260103 -v 0.037546 -0.003080 0.091450 -vn -4.830024 -2.834802 -0.171150 -v 0.037550 -0.003084 0.091553 -vn -4.822888 2.750089 -0.372506 -v 0.037541 -0.003039 0.091700 -vn -4.829867 -2.831162 -0.407826 -v 0.037546 -0.003087 0.091647 -vn -4.795831 2.734566 -0.650059 -v 0.037539 -0.003040 0.091721 -vn -4.789022 -2.724281 -0.794414 -v 0.037539 -0.003090 0.091721 -vn -4.679451 2.963218 -1.327373 -v 0.037504 -0.003046 0.091893 -vn -4.692764 -2.884176 -1.174287 -v 0.037517 -0.003094 0.091841 -vn -4.512222 2.763826 -1.789423 -v 0.037438 -0.003054 0.092079 -vn -4.506929 -2.982449 -1.712485 -v 0.037458 -0.003102 0.092029 -vn -4.379210 2.727097 -2.084895 -v 0.037423 -0.003055 0.092111 -vn -4.297294 -2.737657 -2.216172 -v 0.037423 -0.003105 0.092111 -vn -4.069419 2.972832 -2.621886 -v 0.037344 -0.003061 0.092252 -vn -4.116492 -2.864909 -2.536640 -v 0.037372 -0.003109 0.092206 -vn -3.745285 2.794094 -3.068696 -v 0.037226 -0.003068 0.092409 -vn -3.790619 -2.976315 -2.998714 -v 0.037260 -0.003116 0.092368 -vn -3.531929 2.735536 -3.303983 -v 0.037192 -0.003070 0.092446 -vn -3.430923 -2.734344 -3.417960 -v 0.037192 -0.003120 0.092446 -vn -3.208719 2.779135 -3.663017 -v 0.037085 -0.003075 0.092546 -vn -3.185654 -2.837530 -3.642641 -v 0.037125 -0.003123 0.092511 -vn -3.013453 2.867963 -3.796503 -v 0.037039 -0.003077 0.092584 -vn -2.642879 -2.748630 -4.128666 -v 0.036970 -0.003131 0.092632 -vn -2.612236 2.717438 -4.104251 -v 0.036912 -0.003083 0.092669 -vn -2.308561 -2.666758 -4.274087 -v 0.036869 -0.003135 0.092693 -vn -2.359665 2.681061 -4.233366 -v 0.036869 -0.003085 0.092693 -vn -2.071803 -2.734287 -4.351648 -v 0.036846 -0.003136 0.092706 -vn -1.837906 2.932016 -4.467490 -v 0.036756 -0.003089 0.092747 -vn -1.865557 -2.757288 -4.491213 -v 0.036798 -0.003138 0.092729 -vn -1.326509 2.816561 -4.653842 -v 0.036570 -0.003097 0.092810 -vn -1.403630 -2.927978 -4.629091 -v 0.036614 -0.003145 0.092798 -vn -0.972547 2.733139 -4.739462 -v 0.036486 -0.003100 0.092828 -vn -0.813798 -2.736733 -4.765806 -v 0.036486 -0.003150 0.092828 -vn -0.470960 2.882747 -4.811028 -v 0.036376 -0.003104 0.092844 -vn -0.481750 -2.781198 -4.824680 -v 0.036422 -0.003152 0.092839 -vn -0.115282 2.735856 -4.831493 -v 0.036222 -0.003110 0.092850 -vn 0.122895 -2.735018 -4.854110 -v 0.036225 -0.003160 0.092850 -vn 0.255394 2.823673 -4.818559 -v 0.036179 -0.003111 0.092848 -vn 0.486818 2.728188 -4.811021 -v 0.036079 -0.003115 0.092839 -vn 0.653255 -2.722644 -4.795924 -v 0.036079 -0.003165 0.092839 -vn 0.950053 2.813443 -4.740335 -v 0.036006 -0.003118 0.092827 -vn 1.020457 -2.735666 -4.727151 -v 0.036030 -0.003167 0.092831 -vn 1.508707 2.791242 -4.601777 -v 0.035816 -0.003125 0.092776 -vn 1.561550 -2.816552 -4.588312 -v 0.035838 -0.003174 0.092783 -vn 1.939175 2.716683 -4.450837 -v 0.035689 -0.003130 0.092723 -vn 2.076760 -2.718509 -4.376226 -v 0.035689 -0.003180 0.092723 -vn 2.218578 2.726631 -4.298593 -v 0.035636 -0.003132 0.092696 -vn 2.368441 -2.703529 -4.218053 -v 0.035657 -0.003181 0.092707 -vn 2.483869 2.872752 -4.159664 -v 0.035569 -0.003135 0.092657 -vn 2.874537 -2.723423 -3.905979 -v 0.035489 -0.003188 0.092604 -vn 2.869763 2.678231 -3.985542 -v 0.035471 -0.003139 0.092590 -vn 3.245226 -2.970028 -3.562992 -v 0.035402 -0.003193 0.092536 -vn 3.323707 -2.757940 -3.488404 -v 0.035354 -0.003195 0.092492 -vn 3.388898 2.730657 -3.500163 -v 0.035338 -0.003146 0.092477 -vn 3.569761 -2.723210 -3.262928 -v 0.035339 -0.003196 0.092477 -vn 3.747474 2.738005 -3.073793 -v 0.035209 -0.003153 0.092329 -vn 3.921295 -2.740528 -2.863297 -v 0.035209 -0.003203 0.092329 -vn 4.052981 3.014610 -2.624587 -v 0.035164 -0.003156 0.092264 -vn 4.272541 2.691943 -2.459702 -v 0.035103 -0.003160 0.092163 -vn 4.607723 -2.735284 -1.488280 -v 0.035024 -0.003217 0.091983 -vn 4.534253 2.731798 -1.714230 -v 0.035024 -0.003167 0.091983 -vn 4.453715 -2.877209 -1.865800 -v 0.035065 -0.003213 0.092084 -vn 4.273867 -2.743630 -2.277543 -v 0.035104 -0.003210 0.092163 -vn -4.531459 2.736482 1.739851 -v 0.037476 -0.002717 0.091117 -vn -4.574994 -2.727229 1.624182 -v 0.037476 -0.002767 0.091117 -vn -4.713925 -2.825842 1.210948 -v 0.037494 -0.002770 0.091174 -vn -4.737723 2.842543 1.042961 -v 0.037527 -0.002725 0.091306 -vn -4.825668 -2.843864 0.565929 -v 0.037537 -0.002777 0.091366 -vn -4.841050 2.845439 0.317249 -v 0.037549 -0.002732 0.091502 -vn -4.856257 -2.843064 -0.184653 -v 0.037550 -0.002784 0.091563 -vn -4.825760 2.743742 -0.318974 -v 0.037541 -0.002739 0.091699 -vn -4.812963 -2.677810 -0.650900 -v 0.037539 -0.002790 0.091721 -vn -4.791701 2.684619 -0.637007 -v 0.037539 -0.002740 0.091721 -vn -4.752399 -2.769596 -1.005345 -v 0.037533 -0.002791 0.091758 -vn -4.708100 2.846588 -1.151508 -v 0.037504 -0.002746 0.091891 -vn -4.602270 -2.836603 -1.599160 -v 0.037487 -0.002799 0.091950 -vn -4.514185 2.780039 -1.748085 -v 0.037438 -0.002754 0.092077 -vn -4.386042 -2.659532 -2.114054 -v 0.037423 -0.002805 0.092111 -vn -4.369777 2.689816 -2.086974 -v 0.037423 -0.002755 0.092111 -vn -4.238288 -2.731484 -2.369924 -v 0.037412 -0.002806 0.092132 -vn -4.163752 2.839058 -2.496459 -v 0.037345 -0.002761 0.092250 -vn -3.923034 -2.820793 -2.831893 -v 0.037311 -0.002813 0.092301 -vn -3.798007 2.837136 -2.989054 -v 0.037244 -0.002767 0.092388 -vn -3.787543 -2.855246 -3.007545 -v 0.037292 -0.002814 0.092327 -vn -3.699260 2.779794 -3.115961 -v 0.037227 -0.002768 0.092408 -vn -3.512343 -2.672800 -3.328832 -v 0.037192 -0.002820 0.092446 -vn -3.569290 2.677483 -3.330974 -v 0.037192 -0.002770 0.092446 -vn -3.303302 -2.708839 -3.535567 -v 0.037186 -0.002820 0.092453 -vn -3.205902 2.842469 -3.649803 -v 0.037086 -0.002775 0.092545 -vn -2.850813 -2.843208 -3.932317 -v 0.037039 -0.002828 0.092584 -vn -2.695564 2.724135 -4.046237 -v 0.036927 -0.002782 0.092660 -vn -2.456390 -2.686503 -4.198070 -v 0.036912 -0.002833 0.092669 -vn -2.359882 2.700003 -4.246450 -v 0.036869 -0.002785 0.092693 -vn -2.161347 -2.707752 -4.331398 -v 0.036869 -0.002835 0.092693 -vn -1.925394 2.700557 -4.473497 -v 0.036751 -0.002790 0.092750 -vn -1.871833 -2.717871 -4.450767 -v 0.036757 -0.002840 0.092747 -vn -1.538330 -2.790333 -4.578963 -v 0.036724 -0.002841 0.092760 -vn -1.353503 2.716977 -4.667757 -v 0.036565 -0.002797 0.092811 -vn -1.164195 -2.743305 -4.696459 -v 0.036570 -0.002847 0.092810 -vn -0.955982 2.715093 -4.748294 -v 0.036486 -0.002800 0.092828 -vn -0.751234 -2.718230 -4.779001 -v 0.036486 -0.002850 0.092828 -vn -0.468111 2.763901 -4.824535 -v 0.036370 -0.002804 0.092844 -vn -0.305224 -2.750071 -4.836453 -v 0.036376 -0.002854 0.092844 -vn 0.105877 2.742908 -4.843903 -v 0.036173 -0.002811 0.092848 -vn 0.274658 -2.760161 -4.838260 -v 0.036179 -0.002861 0.092848 -vn 0.540930 2.716878 -4.809108 -v 0.036079 -0.002815 0.092839 -vn 0.719097 -2.718968 -4.783725 -v 0.036079 -0.002865 0.092839 -vn 1.046867 2.831148 -4.732326 -v 0.035979 -0.002819 0.092821 -vn 1.078114 -2.754312 -4.717075 -v 0.036006 -0.002868 0.092827 -vn 1.593394 2.773871 -4.584785 -v 0.035790 -0.002826 0.092766 -vn 1.608679 -2.843985 -4.563192 -v 0.035816 -0.002875 0.092776 -vn 1.973947 2.716716 -4.431624 -v 0.035689 -0.002830 0.092723 -vn 2.124322 -2.729418 -4.344249 -v 0.035689 -0.002880 0.092723 -vn 2.407450 2.823620 -4.209601 -v 0.035612 -0.002833 0.092683 -vn 2.450021 -2.745488 -4.169283 -v 0.035636 -0.002882 0.092696 -vn 2.893276 2.793309 -3.887323 -v 0.035448 -0.002840 0.092573 -vn 2.910458 -2.838323 -3.874854 -v 0.035471 -0.002889 0.092590 -vn 3.231924 2.706054 -3.621695 -v 0.035354 -0.002845 0.092492 -vn 3.319669 -2.714649 -3.512255 -v 0.035354 -0.002895 0.092492 -vn 3.557220 -2.696358 -3.284763 -v 0.035339 -0.002896 0.092477 -vn 4.313619 -2.739090 -2.231793 -v 0.035104 -0.002910 0.092163 -vn 4.593729 -2.784471 -1.531421 -v 0.035024 -0.002917 0.091983 -vn 4.540789 2.781518 -1.694579 -v 0.035024 -0.002867 0.091983 -vn 4.362329 2.898564 -2.065573 -v 0.035080 -0.002862 0.092117 -vn 4.164526 2.734755 -2.457447 -v 0.035103 -0.002860 0.092162 -vn 3.864852 -2.966380 -2.894768 -v 0.035209 -0.002903 0.092329 -vn 3.944542 2.909860 -2.801534 -v 0.035179 -0.002855 0.092287 -vn 3.572505 2.953775 -3.253757 -v 0.035303 -0.002848 0.092440 -vn -4.550811 2.774762 1.698734 -v 0.037476 -0.002417 0.091117 -vn -4.598757 -2.781324 1.534349 -v 0.037476 -0.002467 0.091117 -vn -4.750900 2.917857 0.950046 -v 0.037527 -0.002425 0.091308 -vn -4.725857 -2.903610 1.038780 -v 0.037516 -0.002473 0.091256 -vn -4.807990 2.729776 0.559229 -v 0.037547 -0.002430 0.091458 -vn -4.845548 -2.751759 0.299718 -v 0.037546 -0.002480 0.091450 -vn -4.823891 2.975738 0.068075 -v 0.037549 -0.002432 0.091503 -vn -4.766106 -2.723632 -0.822305 -v 0.037538 -0.002490 0.091725 -vn -4.791965 2.719353 -0.680578 -v 0.037538 -0.002440 0.091725 -vn -4.828116 2.702729 -0.324780 -v 0.037541 -0.002439 0.091700 -vn -4.826357 -2.967163 -0.268131 -v 0.037546 -0.002487 0.091647 -vn -4.657877 2.978553 -1.295251 -v 0.037504 -0.002446 0.091893 -vn -4.690824 -2.877266 -1.176475 -v 0.037517 -0.002494 0.091842 -vn -4.505803 2.690930 -1.773886 -v 0.037438 -0.002454 0.092078 -vn -4.520868 -2.972883 -1.686289 -v 0.037459 -0.002502 0.092029 -vn -4.375127 -2.691720 -2.029779 -v 0.037440 -0.002503 0.092074 -vn -4.355945 2.719080 -2.101386 -v 0.037420 -0.002455 0.092116 -vn -4.270260 -2.718823 -2.271432 -v 0.037420 -0.002505 0.092116 -vn -4.046927 2.983434 -2.628652 -v 0.037344 -0.002461 0.092252 -vn -4.126188 -2.844047 -2.553965 -v 0.037372 -0.002509 0.092206 -vn -3.736811 2.805512 -3.073481 -v 0.037226 -0.002468 0.092409 -vn -3.812256 -2.964417 -2.991461 -v 0.037260 -0.002516 0.092368 -vn -3.526173 2.733582 -3.313411 -v 0.037186 -0.002470 0.092452 -vn -3.415479 -2.726771 -3.451006 -v 0.037186 -0.002520 0.092452 -vn -3.207023 2.778590 -3.646096 -v 0.037085 -0.002475 0.092546 -vn -3.194323 -2.816564 -3.654863 -v 0.037125 -0.002523 0.092511 -vn -3.024109 2.877671 -3.779667 -v 0.037045 -0.002477 0.092578 -vn -2.641108 -2.764533 -4.073180 -v 0.036970 -0.002531 0.092632 -vn -2.593386 2.820064 -4.085075 -v 0.036925 -0.002483 0.092661 -vn -2.342082 2.736011 -4.230873 -v 0.036859 -0.002485 0.092698 -vn -2.210689 -2.735471 -4.307649 -v 0.036859 -0.002535 0.092698 -vn -1.812708 2.975782 -4.472043 -v 0.036750 -0.002490 0.092750 -vn -1.899816 -2.817198 -4.451482 -v 0.036799 -0.002538 0.092729 -vn -1.278837 2.850377 -4.662148 -v 0.036563 -0.002497 0.092812 -vn -1.497986 -3.056415 -4.589070 -v 0.036631 -0.002544 0.092793 -vn -1.223266 -2.706911 -4.737921 -v 0.036614 -0.002545 0.092798 -vn -0.933112 2.731227 -4.755554 -v 0.036472 -0.002500 0.092831 -vn -0.797486 -2.734077 -4.774686 -v 0.036472 -0.002550 0.092831 -vn -0.390029 2.967175 -4.820487 -v 0.036369 -0.002504 0.092844 -vn -0.464103 -2.797581 -4.816752 -v 0.036422 -0.002552 0.092839 -vn 0.197913 2.861119 -4.850569 -v 0.036172 -0.002511 0.092848 -vn 0.066439 -2.973837 -4.830027 -v 0.036225 -0.002560 0.092850 -vn 0.523256 2.712466 -4.840841 -v 0.036063 -0.002515 0.092837 -vn 0.697503 -2.731378 -4.781888 -v 0.036063 -0.002566 0.092836 -vn 0.822411 2.712378 -4.752631 -v 0.035992 -0.002518 0.092824 -vn 1.015138 -2.736431 -4.727913 -v 0.036030 -0.002567 0.092831 -vn 3.454176 -2.731352 -3.420192 -v 0.035339 -0.002596 0.092477 -vn 3.859069 -2.975255 -2.912245 -v 0.035210 -0.002603 0.092329 -vn 3.989437 2.811641 -2.823339 -v 0.035179 -0.002555 0.092286 -vn 4.304064 -2.840644 -2.225898 -v 0.035104 -0.002610 0.092163 -vn 4.339622 2.897437 -2.163098 -v 0.035080 -0.002562 0.092116 -vn 3.605634 2.965824 -3.226122 -v 0.035302 -0.002548 0.092439 -vn 3.232772 2.739525 -3.599052 -v 0.035339 -0.002546 0.092478 -vn 2.833593 -2.975418 -3.921904 -v 0.035489 -0.002588 0.092604 -vn 2.936868 2.899329 -3.858600 -v 0.035447 -0.002540 0.092572 -vn 2.391213 -2.755929 -4.197576 -v 0.035657 -0.002581 0.092707 -vn 2.465164 2.968366 -4.161633 -v 0.035610 -0.002533 0.092682 -vn 2.124273 -2.737429 -4.336767 -v 0.035673 -0.002581 0.092715 -vn 1.982467 2.732158 -4.425580 -v 0.035673 -0.002531 0.092715 -vn 1.516440 -2.976134 -4.589471 -v 0.035839 -0.002574 0.092783 -vn 1.643454 2.879674 -4.564952 -v 0.035789 -0.002526 0.092765 -vn 1.134064 2.973129 -4.686640 -v 0.035977 -0.002519 0.092821 -vn 4.574695 2.739685 -1.662233 -v 0.035024 -0.002567 0.091983 -vn 4.505239 -2.779203 -1.743497 -v 0.035031 -0.002617 0.092002 -vn 4.628884 -2.730284 -1.379764 -v 0.035024 -0.002617 0.091983 -vn -4.627010 2.911147 1.386728 -v 0.037493 -0.002119 0.091170 -vn -4.532724 2.682854 1.690816 -v 0.037476 -0.002117 0.091117 -vn -4.617871 -2.685510 1.527388 -v 0.037476 -0.002167 0.091117 -vn -4.744060 2.896558 0.941437 -v 0.037527 -0.002125 0.091307 -vn -4.707990 -2.914334 1.098226 -v 0.037517 -0.002173 0.091257 -vn -4.835157 2.731524 0.477878 -v 0.037546 -0.002130 0.091448 -vn -4.721416 -3.256992 0.759538 -v 0.037529 -0.002175 0.091316 -vn -4.856765 -2.729362 0.238786 -v 0.037546 -0.002180 0.091452 -vn -4.858388 2.833573 -0.001176 -v 0.037549 -0.002135 0.091590 -vn -4.834488 -2.760098 -0.399924 -v 0.037546 -0.002187 0.091648 -vn -4.824673 2.666846 -0.449631 -v 0.037538 -0.002140 0.091725 -vn -4.791185 -2.709297 -0.814628 -v 0.037538 -0.002190 0.091725 -vn -4.777460 2.712317 -0.700342 -v 0.037537 -0.002140 0.091731 -vn -4.708355 2.794048 -1.138661 -v 0.037510 -0.002146 0.091871 -vn -4.713147 -2.775441 -1.187209 -v 0.037517 -0.002194 0.091843 -vn -4.594608 2.787214 -1.544637 -v 0.037467 -0.002151 0.092006 -vn -4.489176 -2.736043 -1.838069 -v 0.037458 -0.002202 0.092031 -vn -4.422969 2.689474 -1.942266 -v 0.037420 -0.002155 0.092116 -vn -4.325671 -2.699082 -2.160571 -v 0.037420 -0.002205 0.092116 -vn -4.322846 2.681968 -2.174918 -v 0.037410 -0.002156 0.092136 -vn -4.173774 -2.768428 -2.423822 -v 0.037390 -0.002208 0.092174 -vn -4.062168 2.942077 -2.624434 -v 0.037339 -0.002161 0.092260 -vn -4.090081 -2.805099 -2.590750 -v 0.037372 -0.002209 0.092207 -vn -3.844088 2.751181 -2.948022 -v 0.037255 -0.002166 0.092374 -vn -3.750487 -2.762627 -3.064253 -v 0.037259 -0.002216 0.092369 -vn -3.525310 2.736784 -3.326362 -v 0.037186 -0.002170 0.092452 -vn -3.403153 -2.745202 -3.435770 -v 0.037186 -0.002220 0.092452 -vn -3.059614 3.009291 -3.738844 -v 0.037070 -0.002176 0.092559 -vn -3.168225 -2.927711 -3.649749 -v 0.037124 -0.002223 0.092512 -vn -2.734284 2.749519 -4.017931 -v 0.036954 -0.002181 0.092643 -vn -2.672611 -2.794795 -4.043211 -v 0.036969 -0.002231 0.092633 -vn -2.453017 2.682259 -4.209622 -v 0.036859 -0.002185 0.092698 -vn -2.230945 -2.706025 -4.292534 -v 0.036859 -0.002235 0.092698 -vn -2.190236 2.692240 -4.316189 -v 0.036831 -0.002186 0.092713 -vn -1.869502 -2.751569 -4.466470 -v 0.036797 -0.002238 0.092729 -vn -1.769435 2.852987 -4.536752 -v 0.036700 -0.002192 0.092769 -vn -1.277590 -2.763226 -4.687980 -v 0.036613 -0.002245 0.092798 -vn -1.251826 2.813557 -4.690766 -v 0.036565 -0.002197 0.092811 -vn -1.000968 2.713303 -4.737849 -v 0.036472 -0.002200 0.092831 -vn -0.813896 -2.705227 -4.782248 -v 0.036472 -0.002250 0.092831 -vn -0.669291 2.711192 -4.790228 -v 0.036425 -0.002202 0.092838 -vn -0.429000 -2.703221 -4.839946 -v 0.036420 -0.002252 0.092839 -vn -0.275835 2.842228 -4.837708 -v 0.036284 -0.002207 0.092850 -vn 0.168101 -2.757370 -4.875032 -v 0.036224 -0.002260 0.092850 -vn 0.326779 2.958747 -4.816950 -v 0.036142 -0.002213 0.092845 -vn 0.536186 2.731722 -4.799991 -v 0.036063 -0.002215 0.092837 -vn 0.711485 -2.711582 -4.807457 -v 0.036063 -0.002266 0.092837 -vn 0.948848 2.776767 -4.760104 -v 0.036001 -0.002218 0.092826 -vn 1.019330 -2.701533 -4.751705 -v 0.036028 -0.002267 0.092831 -vn 1.289722 2.782870 -4.683124 -v 0.035863 -0.002223 0.092791 -vn 1.625695 -2.743600 -4.589242 -v 0.035838 -0.002274 0.092783 -vn 1.769639 2.819902 -4.503884 -v 0.035730 -0.002228 0.092742 -vn 2.163083 -2.703737 -4.330252 -v 0.035673 -0.002281 0.092715 -vn 2.082672 2.690723 -4.370921 -v 0.035673 -0.002231 0.092715 -vn 2.411697 2.932123 -4.194061 -v 0.035604 -0.002233 0.092678 -vn 2.390947 -2.767681 -4.204386 -v 0.035656 -0.002281 0.092706 -vn 2.785221 2.749669 -3.995300 -v 0.035485 -0.002239 0.092601 -vn 2.906623 -2.755452 -3.900051 -v 0.035488 -0.002289 0.092603 -vn 3.114440 2.814122 -3.725992 -v 0.035375 -0.002244 0.092511 -vn 3.374771 -2.681730 -3.471741 -v 0.035338 -0.002296 0.092477 -vn 3.345455 2.667861 -3.523461 -v 0.035339 -0.002246 0.092478 -vn 3.587460 -2.701791 -3.244185 -v 0.035328 -0.002296 0.092467 -vn 3.625871 3.051378 -3.169626 -v 0.035275 -0.002249 0.092410 -vn 3.918667 2.838032 -2.843926 -v 0.035187 -0.002254 0.092298 -vn 3.901421 -2.861445 -2.877105 -v 0.035208 -0.002303 0.092328 -vn 4.169298 2.774215 -2.471418 -v 0.035112 -0.002260 0.092178 -vn 4.329768 -2.749532 -2.200136 -v 0.035103 -0.002310 0.092162 -vn 4.400295 2.859923 -2.007963 -v 0.035050 -0.002265 0.092050 -vn 4.618621 -2.738672 -1.491676 -v 0.035024 -0.002317 0.091983 -vn 4.573370 2.734237 -1.617399 -v 0.035024 -0.002267 0.091983 -vn -4.544920 2.719289 1.701929 -v 0.037476 -0.001817 0.091117 -vn -4.650476 -2.692102 1.427160 -v 0.037476 -0.001867 0.091117 -vn -4.722948 2.872078 1.084273 -v 0.037516 -0.001823 0.091256 -vn -4.723865 -2.789173 1.129799 -v 0.037508 -0.001871 0.091222 -vn -4.825676 2.770124 0.490089 -v 0.037546 -0.001830 0.091451 -vn -4.771151 -3.129004 0.698479 -v 0.037536 -0.001877 0.091361 -vn -4.873905 -2.816964 0.017894 -v 0.037549 -0.001882 0.091503 -vn -4.829400 2.906490 -0.157029 -v 0.037546 -0.001837 0.091648 -vn -4.803132 -2.687395 -0.633057 -v 0.037539 -0.001890 0.091721 -vn -4.801360 2.700646 -0.559275 -v 0.037539 -0.001840 0.091721 -vn -4.742062 -2.732332 -0.970037 -v 0.037532 -0.001892 0.091764 -vn -4.760756 2.754718 -1.053377 -v 0.037517 -0.001844 0.091842 -vn -4.636023 -2.839937 -1.459920 -v 0.037501 -0.001897 0.091903 -vn -4.588326 2.709592 -1.635715 -v 0.037458 -0.001852 0.092030 -vn -4.499504 -2.701282 -1.858579 -v 0.037455 -0.001902 0.092038 -vn -4.426792 2.697842 -2.018042 -v 0.037423 -0.001855 0.092111 -vn -4.309788 -2.716611 -2.179228 -v 0.037423 -0.001905 0.092111 -vn -4.213102 2.759992 -2.409848 -v 0.037372 -0.001859 0.092207 -vn -4.206329 -2.773914 -2.393461 -v 0.037395 -0.001907 0.092166 -vn -3.925757 -2.872160 -2.838856 -v 0.037321 -0.001912 0.092287 -vn -3.871280 2.752076 -2.922125 -v 0.037260 -0.001866 0.092369 -vn -3.631303 -2.721722 -3.202991 -v 0.037234 -0.001918 0.092400 -vn -3.584224 2.677983 -3.309349 -v 0.037192 -0.001870 0.092446 -vn -3.415580 -2.700224 -3.427871 -v 0.037192 -0.001920 0.092446 -vn -3.269302 2.770145 -3.596676 -v 0.037125 -0.001873 0.092512 -vn -3.182698 -2.736978 -3.654948 -v 0.037135 -0.001923 0.092502 -vn -2.745366 2.957868 -3.981918 -v 0.036970 -0.001881 0.092633 -vn -2.864142 -3.000302 -3.884035 -v 0.037026 -0.001928 0.092593 -vn -2.422498 2.689292 -4.214091 -v 0.036869 -0.001885 0.092693 -vn -2.470454 -2.859506 -4.150503 -v 0.036908 -0.001933 0.092671 -vn -2.179109 -2.673436 -4.349611 -v 0.036869 -0.001935 0.092693 -vn -2.081187 2.719981 -4.389219 -v 0.036798 -0.001888 0.092729 -vn -1.825041 -2.757257 -4.505013 -v 0.036782 -0.001939 0.092736 -vn -1.440585 2.819911 -4.630055 -v 0.036614 -0.001895 0.092798 -vn -1.440403 -2.816125 -4.641243 -v 0.036649 -0.001944 0.092787 -vn -1.024316 2.695171 -4.739175 -v 0.036486 -0.001900 0.092828 -vn 0.500621 2.701152 -4.822968 -v 0.036079 -0.001915 0.092839 -vn 0.281998 2.893346 -4.815269 -v 0.036164 -0.001912 0.092847 -vn 0.157219 -2.721697 -4.848032 -v 0.036230 -0.001959 0.092850 -vn -0.064997 2.703986 -4.863118 -v 0.036225 -0.001910 0.092850 -vn -0.324706 -2.734185 -4.835917 -v 0.036372 -0.001954 0.092844 -vn -1.032323 -2.759872 -4.753336 -v 0.036512 -0.001949 0.092823 -vn -0.722055 -2.684974 -4.778013 -v 0.036486 -0.001950 0.092828 -vn -0.694458 2.687859 -4.858990 -v 0.036421 -0.001902 0.092839 -vn -0.281220 2.861956 -4.852201 -v 0.036306 -0.001907 0.092849 -vn 0.563511 -2.720090 -4.801788 -v 0.036088 -0.001965 0.092840 -vn 0.819568 -2.676484 -4.759221 -v 0.036079 -0.001965 0.092839 -vn 0.799595 2.733100 -4.804802 -v 0.036029 -0.001917 0.092831 -vn 1.243358 -2.869841 -4.681323 -v 0.035948 -0.001970 0.092815 -vn 1.392098 2.730189 -4.664800 -v 0.035838 -0.001924 0.092783 -vn 1.757963 -2.692916 -4.547753 -v 0.035812 -0.001975 0.092774 -vn 1.778849 2.856929 -4.499092 -v 0.035751 -0.001927 0.092750 -vn 1.936795 2.714382 -4.419342 -v 0.035689 -0.001930 0.092723 -vn 2.285029 -2.669006 -4.263773 -v 0.035681 -0.001980 0.092719 -vn 2.728550 -2.794904 -4.017916 -v 0.035557 -0.001985 0.092650 -vn 2.303302 2.756924 -4.280923 -v 0.035623 -0.001933 0.092689 -vn 2.059210 -2.692657 -4.380695 -v 0.035689 -0.001980 0.092723 -vn 2.149553 2.695745 -4.339642 -v 0.035657 -0.001931 0.092707 -vn 3.833953 2.765781 -2.994532 -v 0.035209 -0.001953 0.092329 -vn 3.446011 2.778426 -3.392074 -v 0.035338 -0.001946 0.092477 -vn 3.377785 -2.763031 -3.482111 -v 0.035351 -0.001995 0.092489 -vn 3.117140 2.762945 -3.701819 -v 0.035354 -0.001945 0.092492 -vn 2.844107 3.143084 -3.877641 -v 0.035489 -0.001938 0.092604 -vn 3.706141 -3.010378 -3.092319 -v 0.035253 -0.002000 0.092385 -vn 4.114253 -2.855335 -2.570450 -v 0.035168 -0.002006 0.092270 -vn 4.246096 2.741440 -2.381196 -v 0.035103 -0.001960 0.092163 -vn 4.376693 -2.764070 -2.110201 -v 0.035096 -0.002011 0.092148 -vn 4.528360 2.713924 -1.736635 -v 0.035024 -0.001967 0.091983 -vn 4.490139 -2.829450 -1.776965 -v 0.035037 -0.002016 0.092019 -vn 4.615386 -2.709095 -1.433479 -v 0.035024 -0.002017 0.091983 -vn -4.221915 2.704458 -2.381880 -v 0.037372 -0.001559 0.092207 -vn -4.447267 2.677979 -2.020665 -v 0.037420 -0.001555 0.092116 -vn -4.307465 -2.691929 -2.222403 -v 0.037420 -0.001605 0.092116 -vn -4.802681 -2.767750 -0.527246 -v 0.037541 -0.001589 0.091699 -vn -4.838729 2.682899 -0.531210 -v 0.037538 -0.001540 0.091725 -vn -4.834499 -2.924118 -0.155456 -v 0.037550 -0.001584 0.091567 -vn -4.839131 2.941227 -0.273700 -v 0.037546 -0.001537 0.091648 -vn -4.856153 -2.830738 0.071990 -v 0.037549 -0.001582 0.091503 -vn -4.825186 2.827958 0.443620 -v 0.037546 -0.001530 0.091451 -vn -4.780871 -2.822761 0.683045 -v 0.037529 -0.001575 0.091316 -vn -4.778173 2.910930 0.683987 -v 0.037541 -0.001528 0.091395 -vn -4.769591 -2.760544 0.907930 -v 0.037527 -0.001575 0.091307 -vn -4.691329 2.832327 1.229152 -v 0.037516 -0.001523 0.091256 -vn -4.619105 -2.719266 1.551475 -v 0.037476 -0.001567 0.091117 -vn -4.585254 2.753118 1.518013 -v 0.037484 -0.001518 0.091140 -vn -4.504606 2.691928 1.880031 -v 0.037476 -0.001517 0.091117 -vn -4.765182 -2.680140 -0.777528 -v 0.037538 -0.001590 0.091725 -vn -4.738030 -2.736290 -0.987301 -v 0.037530 -0.001592 0.091780 -vn -4.744647 2.730562 -1.043511 -v 0.037517 -0.001544 0.091842 -vn -4.634666 -2.832591 -1.417036 -v 0.037504 -0.001596 0.091893 -vn -4.553998 2.801743 -1.711703 -v 0.037458 -0.001552 0.092030 -vn -4.530296 -2.826946 -1.682818 -v 0.037475 -0.001600 0.091986 -vn -4.425847 -2.786234 -1.994883 -v 0.037438 -0.001604 0.092078 -vn -4.184855 -2.741313 -2.412582 -v 0.037387 -0.001608 0.092181 -vn -3.997148 -2.769692 -2.748170 -v 0.037345 -0.001611 0.092251 -vn -3.978391 2.731149 -2.770324 -v 0.037288 -0.001564 0.092333 -vn -3.765287 -2.684555 -3.049889 -v 0.037268 -0.001616 0.092359 -vn -3.789682 2.688663 -2.999478 -v 0.037260 -0.001566 0.092369 -vn -3.565053 -2.722254 -3.278439 -v 0.037226 -0.001618 0.092408 -vn -3.558898 2.692016 -3.296381 -v 0.037186 -0.001570 0.092452 -vn -3.398119 -2.689880 -3.463621 -v 0.037186 -0.001620 0.092452 -vn -3.309152 2.758933 -3.549035 -v 0.037125 -0.001573 0.092512 -vn -2.979419 -2.830012 -3.830235 -v 0.037086 -0.001625 0.092546 -vn -2.830941 2.834902 -3.930093 -v 0.036970 -0.001581 0.092633 -vn -2.481566 -2.749515 -4.166307 -v 0.036926 -0.001633 0.092661 -vn -2.379805 2.693387 -4.222813 -v 0.036859 -0.001585 0.092698 -vn -2.165243 -2.662991 -4.387293 -v 0.036859 -0.001635 0.092698 -vn -2.136729 2.706566 -4.395196 -v 0.036798 -0.001588 0.092729 -vn -1.755214 -2.687706 -4.547024 -v 0.036750 -0.001640 0.092750 -vn -1.835385 2.742226 -4.491661 -v 0.036730 -0.001591 0.092758 -vn -1.494828 2.833160 -4.612946 -v 0.036614 -0.001595 0.092798 -vn -1.115843 -2.769269 -4.721606 -v 0.036563 -0.001647 0.092812 -vn -0.980804 2.697402 -4.739551 -v 0.036472 -0.001600 0.092831 -vn -0.703389 -2.683892 -4.822083 -v 0.036472 -0.001650 0.092831 -vn -0.629064 2.828332 -4.823587 -v 0.036421 -0.001602 0.092839 -vn -0.334919 2.840073 -4.831627 -v 0.036316 -0.001606 0.092848 -vn -0.366044 -2.842708 -4.850316 -v 0.036369 -0.001654 0.092845 -vn -0.022987 2.835386 -4.847307 -v 0.036225 -0.001610 0.092850 -vn 0.353417 -2.784349 -4.848477 -v 0.036173 -0.001661 0.092848 -vn 0.506912 2.699180 -4.809983 -v 0.036063 -0.001615 0.092837 -vn 0.778428 -2.689656 -4.795761 -v 0.036063 -0.001666 0.092837 -vn 0.856545 2.683105 -4.798882 -v 0.036029 -0.001617 0.092831 -vn 1.202168 -2.823085 -4.706801 -v 0.035978 -0.001669 0.092821 -vn 1.389730 2.821658 -4.665849 -v 0.035838 -0.001624 0.092783 -vn 1.788551 -2.814428 -4.506223 -v 0.035789 -0.001676 0.092766 -vn 1.961346 2.678207 -4.421881 -v 0.035673 -0.001631 0.092715 -vn 1.999422 -2.827398 -4.388384 -v 0.035723 -0.001679 0.092738 -vn 2.251461 -2.678867 -4.286620 -v 0.035673 -0.001681 0.092715 -vn 2.229634 2.688231 -4.295434 -v 0.035657 -0.001631 0.092707 -vn 2.522248 -2.830850 -4.135723 -v 0.035611 -0.001683 0.092682 -vn 2.774957 2.719362 -3.999835 -v 0.035489 -0.001638 0.092604 -vn 3.280693 -2.801060 -3.537180 -v 0.035367 -0.001694 0.092504 -vn 3.341120 2.681273 -3.541515 -v 0.035338 -0.001646 0.092477 -vn 3.105333 -2.837817 -3.709309 -v 0.035447 -0.001690 0.092573 -vn 2.705960 -2.850396 -4.002505 -v 0.035535 -0.001686 0.092636 -vn 3.465442 -2.682680 -3.364258 -v 0.035339 -0.001696 0.092478 -vn 3.661097 -2.832090 -3.165768 -v 0.035302 -0.001698 0.092440 -vn 3.877381 2.803636 -2.932907 -v 0.035209 -0.001653 0.092329 -vn 3.873816 -2.782691 -2.897749 -v 0.035223 -0.001702 0.092347 -vn 4.228442 2.822760 -2.416207 -v 0.035103 -0.001660 0.092163 -vn 4.547710 -2.706884 -1.630997 -v 0.035024 -0.001717 0.091983 -vn 4.498293 2.684273 -1.859194 -v 0.035024 -0.001667 0.091983 -vn 4.416244 -2.829789 -2.024202 -v 0.035080 -0.001712 0.092116 -vn 4.029426 -3.352745 -2.607675 -v 0.035179 -0.001705 0.092286 -vn -4.735904 -3.121109 0.735243 -v 0.037529 -0.001275 0.091316 -vn -4.850054 2.720091 0.472748 -v 0.037546 -0.001230 0.091451 -vn -4.772054 -2.838059 0.803968 -v 0.037527 -0.001275 0.091307 -vn -4.735763 2.732125 1.180870 -v 0.037516 -0.001223 0.091256 -vn -4.677256 -2.774849 1.236126 -v 0.037496 -0.001270 0.091181 -vn -4.579488 2.687348 1.739628 -v 0.037476 -0.001217 0.091117 -vn -4.579545 -2.716123 1.594226 -v 0.037476 -0.001267 0.091117 -vn -4.802428 -2.852945 0.518668 -v 0.037540 -0.001278 0.091390 -vn -4.846509 -2.832375 0.027825 -v 0.037549 -0.001282 0.091503 -vn -4.839118 2.786842 -0.226312 -v 0.037546 -0.001237 0.091648 -vn -4.826486 -2.818302 -0.256557 -v 0.037549 -0.001286 0.091603 -vn -4.807470 2.712542 -0.585212 -v 0.037538 -0.001240 0.091725 -vn -4.746201 2.702988 -1.028816 -v 0.037517 -0.001244 0.091842 -vn -4.640401 -2.813032 -1.482055 -v 0.037504 -0.001296 0.091893 -vn -4.564409 2.725207 -1.643469 -v 0.037458 -0.001252 0.092030 -vn -4.514419 -2.735493 -1.774269 -v 0.037462 -0.001301 0.092020 -vn -4.398114 2.698055 -2.045106 -v 0.037420 -0.001255 0.092116 -vn -4.815022 -2.728092 -0.581389 -v 0.037541 -0.001289 0.091699 -vn -4.779268 -2.691991 -0.808882 -v 0.037538 -0.001290 0.091725 -vn -4.718877 -2.748580 -1.042993 -v 0.037523 -0.001293 0.091815 -vn -4.393421 -2.759697 -2.019671 -v 0.037438 -0.001304 0.092078 -vn -4.319240 -2.655459 -2.317663 -v 0.037420 -0.001305 0.092116 -vn -4.231341 2.777979 -2.382517 -v 0.037372 -0.001259 0.092207 -vn -4.022022 -2.819408 -2.745693 -v 0.037345 -0.001311 0.092251 -vn -3.919042 2.789079 -2.956007 -v 0.037260 -0.001266 0.092369 -vn -3.629103 -2.704390 -3.212311 -v 0.037226 -0.001318 0.092408 -vn -3.661441 2.674487 -3.169011 -v 0.037203 -0.001269 0.092434 -vn -3.390741 -2.662743 -3.511845 -v 0.037186 -0.001320 0.092452 -vn -2.154325 -2.675160 -4.362184 -v 0.036859 -0.001335 0.092698 -vn -2.475150 2.676803 -4.159772 -v 0.036868 -0.001285 0.092694 -vn -2.482942 -2.743968 -4.155565 -v 0.036926 -0.001333 0.092661 -vn -2.835966 2.802626 -3.986076 -v 0.036970 -0.001281 0.092633 -vn -3.006717 -2.824345 -3.819603 -v 0.037086 -0.001325 0.092546 -vn -3.325234 2.750223 -3.551779 -v 0.037125 -0.001273 0.092512 -vn -3.506818 2.681496 -3.340940 -v 0.037186 -0.001270 0.092452 -vn 0.549957 2.675285 -4.816660 -v 0.036063 -0.001315 0.092837 -vn 0.211322 2.694492 -4.842102 -v 0.036183 -0.001311 0.092848 -vn 0.342365 -2.714900 -4.839834 -v 0.036173 -0.001361 0.092848 -vn -0.134744 2.831820 -4.837307 -v 0.036225 -0.001310 0.092850 -vn -0.264854 -2.824376 -4.850674 -v 0.036369 -0.001354 0.092845 -vn -0.647112 2.718918 -4.805916 -v 0.036421 -0.001302 0.092839 -vn -0.726398 -2.689548 -4.797541 -v 0.036472 -0.001350 0.092831 -vn -0.857316 2.680291 -4.739195 -v 0.036466 -0.001301 0.092832 -vn -1.026296 2.686893 -4.720366 -v 0.036472 -0.001300 0.092831 -vn -1.129585 -2.763235 -4.728052 -v 0.036563 -0.001347 0.092812 -vn -1.516137 2.828803 -4.612719 -v 0.036614 -0.001295 0.092798 -vn -1.707641 -2.817131 -4.559703 -v 0.036750 -0.001340 0.092750 -vn -2.108228 2.718947 -4.402281 -v 0.036798 -0.001288 0.092729 -vn -2.289720 2.671012 -4.265871 -v 0.036859 -0.001285 0.092698 -vn 0.599757 -2.760046 -4.784976 -v 0.036099 -0.001364 0.092841 -vn 0.832312 -2.676888 -4.764147 -v 0.036063 -0.001366 0.092837 -vn 0.819808 2.685538 -4.800539 -v 0.036029 -0.001317 0.092831 -vn 1.166876 -2.831645 -4.702366 -v 0.035978 -0.001369 0.092821 -vn 1.441813 2.719239 -4.643840 -v 0.035838 -0.001324 0.092783 -vn 1.394530 -2.842091 -4.626447 -v 0.035890 -0.001372 0.092799 -vn 1.888944 -2.782947 -4.505363 -v 0.035789 -0.001376 0.092766 -vn 1.952034 2.675836 -4.436602 -v 0.035673 -0.001331 0.092715 -vn 2.067116 -2.722282 -4.380461 -v 0.035690 -0.001380 0.092723 -vn 2.268873 -2.675755 -4.259027 -v 0.035673 -0.001381 0.092715 -vn 2.231798 2.687366 -4.295875 -v 0.035657 -0.001331 0.092707 -vn 2.554318 -2.826170 -4.123795 -v 0.035611 -0.001383 0.092682 -vn 2.758006 2.703624 -3.999438 -v 0.035489 -0.001338 0.092604 -vn 2.787613 -2.744398 -3.962450 -v 0.035505 -0.001388 0.092615 -vn 3.172161 -2.814268 -3.693449 -v 0.035447 -0.001390 0.092573 -vn 3.321707 2.709895 -3.551505 -v 0.035338 -0.001346 0.092477 -vn 3.396806 -2.710014 -3.462183 -v 0.035339 -0.001396 0.092478 -vn 3.679426 -2.831209 -3.146665 -v 0.035302 -0.001398 0.092440 -vn 3.814266 2.827085 -3.016258 -v 0.035209 -0.001353 0.092329 -vn 4.086598 -2.832072 -2.623253 -v 0.035179 -0.001405 0.092286 -vn 4.571954 -2.709683 -1.610521 -v 0.035024 -0.001417 0.091983 -vn 4.533452 2.713275 -1.734451 -v 0.035024 -0.001367 0.091983 -vn 4.389308 -2.773082 -2.079880 -v 0.035080 -0.001412 0.092116 -vn 4.335921 2.761644 -2.176764 -v 0.035075 -0.001362 0.092106 -vn 4.202487 3.311922 -2.354832 -v 0.035103 -0.001360 0.092163 -vn -4.567253 2.726674 1.724399 -v 0.037476 -0.000917 0.091117 -vn -4.651973 -2.722216 1.505721 -v 0.037476 -0.000967 0.091117 -vn -4.784021 2.665694 1.173460 -v 0.037521 -0.000924 0.091278 -vn -4.683846 -2.898519 1.239988 -v 0.037506 -0.000971 0.091216 -vn -4.768509 -2.681224 0.855493 -v 0.037527 -0.000975 0.091307 -vn -4.837709 -2.774472 0.633568 -v 0.037529 -0.000975 0.091316 -vn -4.854574 2.699690 0.392180 -v 0.037548 -0.000931 0.091473 -vn -4.825541 -2.828023 0.466611 -v 0.037544 -0.000979 0.091426 -vn -4.872082 -2.769076 -0.044403 -v 0.037549 -0.000982 0.091503 -vn -4.849926 2.724590 -0.273016 -v 0.037544 -0.000938 0.091670 -vn -4.837262 -2.788868 -0.318530 -v 0.037547 -0.000987 0.091640 -vn -4.799332 2.716303 -0.629088 -v 0.037538 -0.000940 0.091725 -vn -4.785408 -2.717404 -0.607904 -v 0.037541 -0.000989 0.091699 -vn -4.784377 -2.687754 -0.885926 -v 0.037538 -0.000990 0.091725 -vn -4.899346 2.647304 -1.058864 -v 0.037511 -0.000945 0.091864 -vn -4.668914 -2.694787 -1.385411 -v 0.037504 -0.000996 0.091893 -vn -4.666617 2.752020 -1.351377 -v 0.037498 -0.000947 0.091914 -vn -4.545578 2.788900 -1.666833 -v 0.037450 -0.000952 0.092051 -vn -4.426539 -2.704010 -1.963835 -v 0.037438 -0.001004 0.092078 -vn -4.389302 2.694690 -2.055283 -v 0.037420 -0.000955 0.092116 -vn -4.295009 -2.676148 -2.298006 -v 0.037420 -0.001005 0.092116 -vn -4.229475 2.778126 -2.371791 -v 0.037372 -0.000959 0.092207 -vn -4.039237 -2.738809 -2.726296 -v 0.037345 -0.001011 0.092251 -vn -3.998678 2.897490 -2.781701 -v 0.037299 -0.000964 0.092318 -vn -3.837209 2.833454 -2.956814 -v 0.037260 -0.000966 0.092369 -vn -3.631278 -2.729533 -3.212602 -v 0.037226 -0.001018 0.092408 -vn -3.604478 2.668358 -3.297643 -v 0.037186 -0.000970 0.092452 -vn -3.382297 -2.685795 -3.485991 -v 0.037186 -0.001020 0.092452 -vn -3.304793 2.761774 -3.547549 -v 0.037125 -0.000973 0.092512 -vn -2.996156 -2.818840 -3.838070 -v 0.037086 -0.001025 0.092546 -vn -2.827374 2.825795 -3.950007 -v 0.036970 -0.000981 0.092633 -vn -2.506365 -2.742119 -4.165297 -v 0.036926 -0.001033 0.092661 -vn -2.404863 2.688208 -4.216626 -v 0.036859 -0.000985 0.092698 -vn -2.156233 -2.693294 -4.341146 -v 0.036859 -0.001035 0.092698 -vn -2.068724 2.742189 -4.383006 -v 0.036798 -0.000988 0.092729 -vn -1.707702 -2.824994 -4.547840 -v 0.036750 -0.001040 0.092750 -vn -1.515648 2.831836 -4.607738 -v 0.036614 -0.000995 0.092798 -vn -1.120267 -2.769637 -4.719938 -v 0.036563 -0.001047 0.092812 -vn -0.986707 2.687404 -4.738901 -v 0.036472 -0.001000 0.092831 -vn -0.852794 -2.711020 -4.745138 -v 0.036489 -0.001050 0.092828 -vn -0.661975 -2.676329 -4.786253 -v 0.036472 -0.001050 0.092831 -vn -0.651677 2.722074 -4.800925 -v 0.036421 -0.001002 0.092839 -vn -0.296760 -2.832551 -4.836719 -v 0.036369 -0.001054 0.092845 -vn -0.021874 2.724858 -4.848969 -v 0.036225 -0.001010 0.092850 -vn -0.043348 -2.834279 -4.832294 -v 0.036276 -0.001058 0.092850 -vn 0.447606 -2.761580 -4.864240 -v 0.036173 -0.001061 0.092848 -vn 0.506613 2.701335 -4.806614 -v 0.036063 -0.001015 0.092837 -vn 0.741625 -2.691940 -4.798916 -v 0.036063 -0.001066 0.092837 -vn 0.848226 2.692250 -4.786191 -v 0.036029 -0.001017 0.092831 -vn 1.183015 -2.837224 -4.689466 -v 0.035978 -0.001069 0.092821 -vn 1.440394 2.690198 -4.658725 -v 0.035838 -0.001024 0.092783 -vn 1.494667 -2.746273 -4.596847 -v 0.035855 -0.001073 0.092788 -vn 1.879839 -2.811961 -4.457704 -v 0.035789 -0.001076 0.092766 -vn 1.945276 2.678627 -4.461315 -v 0.035673 -0.001031 0.092715 -vn 2.182827 -2.706912 -4.319519 -v 0.035673 -0.001081 0.092715 -vn 2.223489 2.688854 -4.297340 -v 0.035657 -0.001031 0.092707 -vn 2.562334 -2.834330 -4.104490 -v 0.035611 -0.001083 0.092682 -vn 2.725148 2.831062 -4.020354 -v 0.035489 -0.001038 0.092604 -vn 3.105350 -2.829786 -3.736696 -v 0.035447 -0.001090 0.092573 -vn 3.321128 2.711544 -3.548966 -v 0.035338 -0.001046 0.092477 -vn 4.066319 -2.723986 -2.662722 -v 0.035179 -0.001105 0.092286 -vn 3.820029 2.800896 -3.059160 -v 0.035209 -0.001053 0.092329 -vn 3.675309 -2.835209 -3.142067 -v 0.035302 -0.001098 0.092440 -vn 3.399323 -2.711400 -3.456849 -v 0.035339 -0.001096 0.092478 -vn 4.596869 -2.743310 -1.544805 -v 0.035024 -0.001117 0.091983 -vn 4.573244 2.720215 -1.714679 -v 0.035024 -0.001067 0.091983 -vn 4.421175 -2.830549 -2.012355 -v 0.035080 -0.001112 0.092116 -vn 4.227482 2.836704 -2.375122 -v 0.035103 -0.001060 0.092163 -vn 4.068095 2.839927 -2.633512 -v 0.035148 -0.001057 0.092239 -vn 4.632127 2.834222 -1.360172 -v 0.034988 -0.007972 0.091864 -vn 4.785656 -2.815270 -0.795273 -v 0.034975 -0.008024 0.091804 -vn 4.723453 2.718781 -1.083673 -v 0.034984 -0.007973 0.091844 -vn 4.837522 2.808466 -0.516964 -v 0.034954 -0.007980 0.091649 -vn 4.856713 -2.812159 -0.060567 -v 0.034951 -0.008032 0.091608 -vn 4.860733 2.794124 0.136574 -v 0.034954 -0.007987 0.091452 -vn 4.834466 -2.673431 0.470863 -v 0.034957 -0.008039 0.091412 -vn 4.818116 2.702812 0.535195 -v 0.034959 -0.007989 0.091400 -vn 4.770566 -2.705970 0.792542 -v 0.034959 -0.008039 0.091400 -vn 4.764679 2.794522 0.994668 -v 0.034983 -0.007994 0.091258 -vn 4.670889 -2.801816 1.390194 -v 0.034993 -0.008046 0.091218 -vn 4.584932 2.806583 1.572245 -v 0.035042 -0.008002 0.091070 -vn 4.453670 -2.692850 1.909421 -v 0.035057 -0.008053 0.091033 -vn 4.409537 2.706053 1.992199 -v 0.035069 -0.008004 0.091006 -vn 4.306807 -2.698249 2.221094 -v 0.035069 -0.008054 0.091006 -vn 4.232846 2.788352 2.363309 -v 0.035128 -0.008009 0.090893 -vn 4.034847 -2.810136 2.710057 -v 0.035149 -0.008060 0.090858 -vn 3.889841 2.812996 2.884495 -v 0.035240 -0.008016 0.090731 -vn 3.665751 -2.694492 3.197480 -v 0.035266 -0.008068 0.090700 -vn 3.591418 2.702244 3.248595 -v 0.035297 -0.008019 0.090666 -vn 3.456698 -2.685657 3.422352 -v 0.035297 -0.008069 0.090666 -vn 3.325718 2.765745 3.536119 -v 0.035375 -0.008023 0.090588 -vn 3.012159 -2.813538 3.805499 -v 0.035406 -0.008075 0.090561 -vn 2.859011 2.799472 3.939055 -v 0.035530 -0.008031 0.090467 -vn 2.553171 -2.715921 4.133016 -v 0.035565 -0.008082 0.090445 -vn 2.496778 2.678834 4.132090 -v 0.035619 -0.008034 0.090413 -vn 2.216056 -2.691876 4.309258 -v 0.035619 -0.008084 0.090413 -vn 2.340187 2.696305 4.215258 -v 0.035624 -0.008035 0.090411 -vn 2.092632 2.756322 4.368681 -v 0.035702 -0.008038 0.090371 -vn 1.748122 -2.808959 4.530632 -v 0.035739 -0.008089 0.090355 -vn 1.533902 2.809984 4.603840 -v 0.035886 -0.008045 0.090302 -vn 1.162857 -2.739524 4.708169 -v 0.035926 -0.008097 0.090291 -vn 1.046120 2.700109 4.728553 -v 0.036004 -0.008049 0.090274 -vn 0.808475 -2.698928 4.774451 -v 0.036004 -0.008100 0.090274 -vn 0.672010 2.735952 4.804226 -v 0.036079 -0.008052 0.090261 -vn 0.297878 -2.813082 4.835689 -v 0.036119 -0.008104 0.090257 -vn 0.066387 2.804275 4.860007 -v 0.036275 -0.008060 0.090250 -vn -0.310790 -2.761700 4.835737 -v 0.036316 -0.008111 0.090252 -vn -0.436846 2.672622 4.863092 -v 0.036412 -0.008065 0.090260 -vn -0.690064 -2.701887 4.790285 -v 0.036412 -0.008115 0.090260 -vn -0.802228 2.722131 4.779418 -v 0.036471 -0.008067 0.090269 -vn -1.171044 -2.813344 4.697601 -v 0.036511 -0.008118 0.090277 -vn -1.375392 2.804399 4.660221 -v 0.036662 -0.008074 0.090317 -vn -1.693049 -2.737619 4.537941 -v 0.036700 -0.008126 0.090330 -vn -1.904618 -2.799860 4.432304 -v 0.036731 -0.008127 0.090342 -vn -1.907408 2.688897 4.447893 -v 0.036805 -0.008080 0.090375 -vn -2.157053 -2.691973 4.333352 -v 0.036805 -0.008130 0.090375 -vn -2.233378 2.695520 4.317403 -v 0.036843 -0.008081 0.090393 -vn -2.534184 -2.802188 4.143069 -v 0.036880 -0.008133 0.090413 -vn -2.662152 2.802601 4.064083 -v 0.037011 -0.008088 0.090496 -vn -4.229224 -1.352994 3.742733 -v 0.037044 -0.008140 0.090521 -vn -3.016452 2.768740 3.781628 -v 0.037071 -0.008091 0.090542 -vn -2.272492 4.382200 1.353117 -v 0.037044 -0.008390 0.090521 -vn -2.235268 2.988804 2.189236 -v 0.037143 -0.008390 0.090605 -vn -3.228770 2.685221 3.638248 -v 0.037143 -0.008095 0.090605 -vn -2.709643 2.960232 1.555860 -v 0.037393 -0.008390 0.090930 -vn -4.229827 2.776254 2.381543 -v 0.037397 -0.008110 0.090937 -vn -3.833897 2.842889 2.991858 -v 0.037291 -0.008103 0.090771 -vn -3.453958 2.703997 3.458726 -v 0.037162 -0.008096 0.090623 -vn 4.726528 2.735640 -1.128044 -v 0.034984 -0.007673 0.091844 -vn 4.680991 -2.746221 -1.181010 -v 0.034988 -0.007722 0.091864 -vn 4.741739 -2.734267 -0.883870 -v 0.034984 -0.007723 0.091844 -vn 4.826417 2.699331 -0.587268 -v 0.034954 -0.007680 0.091649 -vn 4.748988 -3.259546 -0.755677 -v 0.034972 -0.007725 0.091786 -vn 4.838539 -2.710368 -0.357044 -v 0.034954 -0.007730 0.091649 -vn 4.834336 2.707458 -0.189161 -v 0.034951 -0.007682 0.091591 -vn 4.853578 -2.714323 0.070179 -v 0.034950 -0.007732 0.091582 -vn 4.845197 2.712908 0.220315 -v 0.034954 -0.007687 0.091452 -vn 4.875955 -2.682077 0.393374 -v 0.034954 -0.007737 0.091452 -vn 4.822992 2.690025 0.525758 -v 0.034961 -0.007690 0.091379 -vn 4.781737 -2.696154 0.753952 -v 0.034961 -0.007740 0.091379 -vn 4.764116 2.746504 0.775024 -v 0.034973 -0.007693 0.091309 -vn 4.695598 -2.723067 1.282853 -v 0.034983 -0.007744 0.091258 -vn 4.711799 2.730011 1.126939 -v 0.034983 -0.007694 0.091258 -vn 4.220680 2.718174 2.377224 -v 0.035128 -0.007709 0.090893 -vn 4.074687 -2.683000 2.638036 -v 0.035128 -0.007759 0.090893 -vn 4.014853 2.868507 2.688887 -v 0.035195 -0.007713 0.090791 -vn 3.722966 -2.711484 3.101185 -v 0.035240 -0.007766 0.090731 -vn 3.800933 2.711620 2.985435 -v 0.035240 -0.007716 0.090731 -vn 4.602979 2.718624 1.547853 -v 0.035042 -0.007702 0.091070 -vn 4.514602 -2.726402 1.751958 -v 0.035042 -0.007752 0.091070 -vn 4.463950 2.685880 1.821890 -v 0.035055 -0.007703 0.091037 -vn 4.376858 -2.683887 2.026110 -v 0.035059 -0.007753 0.091029 -vn 4.380101 2.705611 2.044955 -v 0.035077 -0.007705 0.090989 -vn 4.290813 -2.702098 2.222750 -v 0.035077 -0.007755 0.090989 -vn 4.180408 -2.700264 2.426262 -v 0.035123 -0.007759 0.090902 -vn 3.577482 2.709954 3.275405 -v 0.035308 -0.007720 0.090654 -vn 3.438632 -2.712657 3.408366 -v 0.035308 -0.007770 0.090654 -vn 3.293401 2.735099 3.578272 -v 0.035375 -0.007723 0.090588 -vn 3.121924 -2.740795 3.713329 -v 0.035376 -0.007773 0.090588 -vn 2.829348 2.738233 3.963187 -v 0.035530 -0.007731 0.090467 -vn 2.673228 -2.741641 4.066684 -v 0.035531 -0.007781 0.090467 -vn 2.426850 2.705605 4.191617 -v 0.035631 -0.007735 0.090407 -vn -0.654220 -2.708371 4.799902 -v 0.036421 -0.007815 0.090261 -vn -0.588869 2.671642 4.787946 -v 0.036421 -0.007765 0.090261 -vn -0.390940 2.705994 4.817385 -v 0.036417 -0.007765 0.090261 -vn -0.138884 -2.749633 4.860610 -v 0.036275 -0.007810 0.090250 -vn 0.024088 2.764748 4.847117 -v 0.036275 -0.007760 0.090250 -vn 0.450634 -2.690926 4.832401 -v 0.036079 -0.007802 0.090261 -vn 2.323910 -2.708185 4.228883 -v 0.035624 -0.007785 0.090411 -vn 2.147088 -2.684774 4.319298 -v 0.035631 -0.007785 0.090407 -vn 2.030065 2.728086 4.423120 -v 0.035702 -0.007738 0.090371 -vn 1.849454 -2.734846 4.485652 -v 0.035703 -0.007788 0.090371 -vn 1.526959 2.751026 4.611766 -v 0.035886 -0.007745 0.090302 -vn 1.330715 -2.748311 4.676255 -v 0.035886 -0.007795 0.090302 -vn 1.031585 2.719179 4.721970 -v 0.036014 -0.007750 0.090272 -vn 0.836498 -2.719388 4.762962 -v 0.036014 -0.007800 0.090272 -vn 0.716371 2.694868 4.788347 -v 0.036079 -0.007752 0.090261 -vn 0.352507 2.998075 4.823790 -v 0.036156 -0.007755 0.090253 -vn -0.752886 2.691408 4.784205 -v 0.036471 -0.007767 0.090269 -vn -1.026111 -2.691730 4.740293 -v 0.036471 -0.007817 0.090269 -vn -1.123963 3.060175 4.676570 -v 0.036558 -0.007770 0.090287 -vn -1.445343 2.771719 4.627181 -v 0.036662 -0.007774 0.090317 -vn -1.596704 -2.751858 4.597904 -v 0.036662 -0.007824 0.090317 -vn -1.869318 2.706455 4.467138 -v 0.036811 -0.007780 0.090377 -vn -2.074534 -2.716585 4.367337 -v 0.036811 -0.007830 0.090377 -vn -2.046379 2.681422 4.356378 -v 0.036825 -0.007780 0.090384 -vn -2.252719 2.731133 4.276973 -v 0.036843 -0.007781 0.090393 -vn -2.422552 -2.728195 4.192902 -v 0.036843 -0.007831 0.090393 -vn -2.714401 2.740386 4.024766 -v 0.037011 -0.007788 0.090496 -vn -2.833280 -2.739677 3.924925 -v 0.037012 -0.007839 0.090496 -vn -3.153539 -2.828051 3.660503 -v 0.037071 -0.007841 0.090542 -vn -3.189183 2.691630 3.640360 -v 0.037146 -0.007795 0.090608 -vn -3.371561 -2.676386 3.490997 -v 0.037146 -0.007845 0.090608 -vn -3.446275 2.686789 3.447991 -v 0.037162 -0.007796 0.090623 -vn -3.567611 -2.688366 3.312489 -v 0.037162 -0.007846 0.090623 -vn -3.628956 2.809022 3.221933 -v 0.037264 -0.007801 0.090737 -vn -3.969347 -2.736601 2.792217 -v 0.037291 -0.007853 0.090772 -vn -4.325036 -2.776557 2.191339 -v 0.037397 -0.007860 0.090938 -vn -4.231378 2.779887 2.377534 -v 0.037397 -0.007810 0.090937 -vn -3.891535 2.734500 2.869480 -v 0.037291 -0.007803 0.090771 -vn 4.728561 2.754170 -1.136537 -v 0.034984 -0.007373 0.091844 -vn 4.758197 -2.757599 -0.955588 -v 0.034984 -0.007423 0.091844 -vn 4.828529 2.734620 -0.525694 -v 0.034954 -0.007380 0.091649 -vn 4.731868 2.740565 1.051473 -v 0.034983 -0.007394 0.091258 -vn 4.660059 -2.731546 1.305689 -v 0.034983 -0.007444 0.091258 -vn 4.575905 2.737165 1.590931 -v 0.035042 -0.007402 0.091070 -vn 4.505477 -2.745730 1.753809 -v 0.035041 -0.007452 0.091071 -vn 4.410487 2.710651 1.983751 -v 0.035069 -0.007404 0.091006 -vn 4.820333 -2.737226 -0.394419 -v 0.034954 -0.007430 0.091650 -vn 4.832595 -2.845567 0.041893 -v 0.034951 -0.007432 0.091591 -vn 4.836487 2.713498 0.165043 -v 0.034954 -0.007387 0.091452 -vn 4.821990 -2.717294 0.381230 -v 0.034954 -0.007437 0.091453 -vn 4.811748 2.714530 0.545494 -v 0.034959 -0.007389 0.091400 -vn 4.789318 -2.712158 0.729560 -v 0.034959 -0.007439 0.091400 -vn 4.745422 -2.829292 0.910487 -v 0.034973 -0.007443 0.091309 -vn 3.886590 2.692203 2.900123 -v 0.035240 -0.007416 0.090731 -vn 3.692145 -2.698383 3.116855 -v 0.035240 -0.007466 0.090732 -vn 3.691525 2.704560 3.101538 -v 0.035278 -0.007418 0.090687 -vn 3.455178 -2.702761 3.392834 -v 0.035297 -0.007469 0.090666 -vn 4.394420 -2.724362 1.974713 -v 0.035055 -0.007453 0.091037 -vn 4.315423 -2.700339 2.202306 -v 0.035069 -0.007454 0.091006 -vn 4.207372 2.750253 2.431976 -v 0.035128 -0.007409 0.090893 -vn 4.118393 -2.754271 2.559177 -v 0.035128 -0.007459 0.090894 -vn 3.914275 -2.999900 2.804186 -v 0.035195 -0.007463 0.090791 -vn 1.307635 -2.722471 4.668951 -v 0.035886 -0.007495 0.090302 -vn 1.375033 2.688982 4.652438 -v 0.035886 -0.007445 0.090302 -vn 1.652185 2.746947 4.570504 -v 0.035868 -0.007444 0.090307 -vn 1.900900 -2.699230 4.470450 -v 0.035701 -0.007488 0.090371 -vn 1.879842 2.819183 4.448590 -v 0.035735 -0.007439 0.090357 -vn 2.170660 2.696867 4.311812 -v 0.035702 -0.007438 0.090371 -vn 2.278029 -2.715249 4.272436 -v 0.035619 -0.007484 0.090413 -vn 2.468718 2.702220 4.187141 -v 0.035619 -0.007434 0.090413 -vn 2.675313 -2.734493 4.065084 -v 0.035530 -0.007481 0.090468 -vn 2.830264 2.735089 3.964175 -v 0.035530 -0.007431 0.090467 -vn 3.140997 -2.745656 3.702560 -v 0.035375 -0.007473 0.090589 -vn 3.326400 2.723767 3.579514 -v 0.035375 -0.007423 0.090588 -vn 3.556520 2.686481 3.298508 -v 0.035297 -0.007419 0.090666 -vn 1.048541 2.713697 4.729464 -v 0.036004 -0.007449 0.090274 -vn 0.857209 -2.719204 4.757209 -v 0.036004 -0.007500 0.090274 -vn 0.685068 2.695100 4.804857 -v 0.036079 -0.007452 0.090261 -vn 0.526904 -2.690241 4.826586 -v 0.036078 -0.007502 0.090261 -vn 0.219349 -2.853644 4.857604 -v 0.036156 -0.007505 0.090253 -vn 0.022128 2.730070 4.850616 -v 0.036275 -0.007460 0.090250 -vn -0.216569 -2.731946 4.843611 -v 0.036275 -0.007510 0.090250 -vn -0.454819 2.696095 4.847010 -v 0.036412 -0.007465 0.090260 -vn -0.577750 -2.698914 4.798605 -v 0.036412 -0.007515 0.090260 -vn -0.764350 -2.679078 4.756024 -v 0.036417 -0.007515 0.090261 -vn -0.790657 2.681597 4.803975 -v 0.036471 -0.007467 0.090269 -vn -0.944150 -2.700694 4.737046 -v 0.036470 -0.007517 0.090269 -vn -1.270929 -2.878809 4.661809 -v 0.036558 -0.007520 0.090287 -vn -1.465454 2.725461 4.633504 -v 0.036662 -0.007474 0.090317 -vn -1.663973 -2.736058 4.554663 -v 0.036661 -0.007524 0.090317 -vn -1.875150 2.695537 4.489464 -v 0.036805 -0.007480 0.090375 -vn -2.044773 -2.711779 4.379256 -v 0.036805 -0.007530 0.090375 -vn -2.215365 -2.676075 4.274186 -v 0.036825 -0.007531 0.090384 -vn -2.246912 2.728373 4.288138 -v 0.036843 -0.007481 0.090393 -vn -2.449490 -2.714599 4.185980 -v 0.036843 -0.007531 0.090393 -vn -2.755518 2.758912 4.009185 -v 0.037011 -0.007488 0.090496 -vn -2.896188 -2.769018 3.899078 -v 0.037011 -0.007538 0.090496 -vn -3.151013 2.708838 3.687561 -v 0.037143 -0.007495 0.090605 -vn -3.311217 -2.714242 3.533257 -v 0.037143 -0.007545 0.090605 -vn -3.435377 2.725752 3.408824 -v 0.037162 -0.007496 0.090623 -vn -3.574731 -2.710501 3.294820 -v 0.037161 -0.007546 0.090623 -vn -3.794905 2.804409 3.004455 -v 0.037291 -0.007503 0.090771 -vn -3.750825 -2.875790 3.046995 -v 0.037264 -0.007551 0.090737 -vn -4.024659 3.074020 2.626497 -v 0.037342 -0.007506 0.090844 -vn -3.971613 -2.927783 2.765156 -v 0.037290 -0.007553 0.090771 -vn -4.249842 2.774731 2.350514 -v 0.037397 -0.007510 0.090937 -vn -4.330997 -2.773448 2.210052 -v 0.037396 -0.007560 0.090937 -vn 4.768475 2.773589 -0.935660 -v 0.034973 -0.007075 0.091793 -vn 4.690320 -2.901050 -1.131617 -v 0.034983 -0.007123 0.091843 -vn 4.779714 -2.721746 -0.754100 -v 0.034976 -0.007124 0.091808 -vn 4.830721 2.793001 -0.343052 -v 0.034951 -0.007082 0.091598 -vn 4.824839 -2.914856 -0.342850 -v 0.034954 -0.007130 0.091648 -vn 4.825859 2.878798 -0.036814 -v 0.034950 -0.007084 0.091535 -vn 4.826296 -2.754524 0.374906 -v 0.034954 -0.007137 0.091452 -vn 4.821546 2.716301 0.500355 -v 0.034959 -0.007089 0.091401 -vn 4.803084 -2.702776 0.763208 -v 0.034959 -0.007139 0.091400 -vn 4.329402 2.775098 2.134056 -v 0.035078 -0.007105 0.090986 -vn 4.413697 2.673698 1.926294 -v 0.035069 -0.007104 0.091006 -vn 4.321321 -2.697094 2.182828 -v 0.035069 -0.007154 0.091006 -vn 4.540499 2.679931 1.734437 -v 0.035062 -0.007104 0.091023 -vn 4.546074 -2.940145 1.693452 -v 0.035042 -0.007152 0.091069 -vn 4.712448 -2.721077 1.207337 -v 0.034983 -0.007144 0.091257 -vn 4.639090 2.944912 1.389820 -v 0.034996 -0.007096 0.091208 -vn 4.752652 2.710274 0.915335 -v 0.034984 -0.007095 0.091254 -vn 4.055554 2.965224 2.626350 -v 0.035155 -0.007111 0.090849 -vn 4.138544 -2.880374 2.525395 -v 0.035128 -0.007159 0.090893 -vn 3.781684 2.685375 3.034317 -v 0.035273 -0.007118 0.090692 -vn 1.638447 2.992940 4.526609 -v 0.035795 -0.007142 0.090332 -vn 2.004798 2.705653 4.399686 -v 0.035749 -0.007140 0.090350 -vn 1.736041 -2.683376 4.533119 -v 0.035735 -0.007189 0.090357 -vn 1.285831 2.802827 4.666877 -v 0.035936 -0.007147 0.090288 -vn 3.804978 -2.957593 2.965727 -v 0.035241 -0.007166 0.090731 -vn 3.555441 -2.683241 3.255704 -v 0.035278 -0.007168 0.090687 -vn 3.546404 2.705463 3.315645 -v 0.035297 -0.007119 0.090666 -vn 3.403087 -2.713396 3.439005 -v 0.035297 -0.007169 0.090666 -vn 3.117756 2.952665 3.720218 -v 0.035414 -0.007125 0.090554 -vn 3.193218 -2.852394 3.656652 -v 0.035376 -0.007173 0.090588 -vn 2.664603 2.768788 4.072610 -v 0.035574 -0.007132 0.090440 -vn 2.719899 -2.948755 4.015774 -v 0.035531 -0.007181 0.090467 -vn 2.411647 2.716291 4.225502 -v 0.035619 -0.007134 0.090413 -vn 2.262946 -2.726137 4.292006 -v 0.035619 -0.007184 0.090413 -vn 2.019038 -2.833388 4.379723 -v 0.035703 -0.007188 0.090371 -vn 0.440786 -2.701947 4.833074 -v 0.036080 -0.007202 0.090261 -vn -0.047852 -2.957751 4.842114 -v 0.036276 -0.007210 0.090250 -vn -0.045869 2.730834 4.841112 -v 0.036327 -0.007161 0.090252 -vn 1.512051 -2.979270 4.630626 -v 0.035868 -0.007194 0.090307 -vn 1.210545 -2.742481 4.688013 -v 0.035887 -0.007195 0.090302 -vn 1.058112 2.711204 4.709357 -v 0.036004 -0.007149 0.090274 -vn 0.860372 -2.707265 4.762498 -v 0.036004 -0.007200 0.090274 -vn 0.823948 2.700686 4.755919 -v 0.036049 -0.007151 0.090266 -vn 0.360351 2.958499 4.815271 -v 0.036130 -0.007154 0.090256 -vn -2.380494 -2.737020 4.208034 -v 0.036844 -0.007231 0.090394 -vn -2.193290 2.707271 4.295572 -v 0.036874 -0.007182 0.090410 -vn -2.079007 -2.727400 4.373138 -v 0.036805 -0.007230 0.090375 -vn -1.933552 2.730687 4.432693 -v 0.036805 -0.007180 0.090375 -vn -1.502035 -2.953366 4.606548 -v 0.036662 -0.007224 0.090317 -vn -1.604320 2.860188 4.559167 -v 0.036711 -0.007176 0.090334 -vn -0.980831 -2.775469 4.772470 -v 0.036472 -0.007217 0.090269 -vn -1.047180 2.943031 4.738385 -v 0.036522 -0.007169 0.090279 -vn -0.684705 -2.709381 4.830582 -v 0.036412 -0.007215 0.090260 -vn -0.527115 2.718262 4.834327 -v 0.036412 -0.007165 0.090260 -vn -0.301134 2.850140 4.804828 -v 0.036333 -0.007162 0.090253 -vn -3.916777 -2.772264 2.850741 -v 0.037292 -0.007253 0.090772 -vn -3.771364 2.711643 3.058435 -v 0.037298 -0.007203 0.090781 -vn -3.529036 -2.757827 3.308738 -v 0.037162 -0.007246 0.090623 -vn -3.581421 2.895212 3.285036 -v 0.037198 -0.007198 0.090660 -vn -3.317620 -2.735646 3.517892 -v 0.037143 -0.007245 0.090605 -vn -3.200556 2.737082 3.628385 -v 0.037143 -0.007195 0.090605 -vn -2.825307 -2.953203 3.930988 -v 0.037012 -0.007239 0.090497 -vn -2.912341 2.874816 3.864259 -v 0.037052 -0.007190 0.090527 -vn -2.468904 2.960600 4.136519 -v 0.036889 -0.007183 0.090418 -vn -4.273361 -2.956845 2.283823 -v 0.037397 -0.007260 0.090938 -vn -4.325233 2.909330 2.165053 -v 0.037420 -0.007212 0.090984 -vn -4.026453 2.961860 2.647207 -v 0.037321 -0.007205 0.090813 -vn -3.573987 2.971893 3.236029 -v 0.037198 -0.006898 0.090661 -vn -3.199266 2.717833 3.637707 -v 0.037146 -0.006895 0.090608 -vn -3.578137 -2.690176 3.281281 -v 0.037162 -0.006946 0.090623 -vn 4.750824 2.971878 -0.895714 -v 0.034973 -0.006775 0.091792 -vn 4.727816 -2.913734 -1.023632 -v 0.034984 -0.006823 0.091844 -vn 4.827451 2.981391 -0.184624 -v 0.034951 -0.006782 0.091596 -vn 4.822912 -2.973030 -0.368093 -v 0.034954 -0.006830 0.091649 -vn 4.813007 2.901733 0.482774 -v 0.034959 -0.006789 0.091400 -vn 4.813884 -2.984427 0.317367 -v 0.034954 -0.006837 0.091453 -vn 4.753526 2.716072 0.895721 -v 0.034982 -0.006794 0.091263 -vn 4.744419 -3.181114 0.698287 -v 0.034961 -0.006840 0.091379 -vn 4.701251 -2.704889 1.129031 -v 0.034983 -0.006844 0.091258 -vn 4.668264 2.724459 1.301559 -v 0.034996 -0.006796 0.091207 -vn 4.613087 -2.729339 1.521819 -v 0.034998 -0.006847 0.091201 -vn 4.511001 2.757075 1.803921 -v 0.035062 -0.006804 0.091021 -vn 4.529181 -2.881394 1.768917 -v 0.035042 -0.006852 0.091070 -vn 4.370000 2.731457 2.076783 -v 0.035077 -0.006805 0.090989 -vn 4.299268 -2.740427 2.217929 -v 0.035077 -0.006855 0.090989 -vn 4.056298 2.968477 2.637754 -v 0.035156 -0.006811 0.090848 -vn 4.120218 -2.866588 2.539235 -v 0.035128 -0.006859 0.090893 -vn 3.760336 2.745015 3.063019 -v 0.035274 -0.006818 0.090691 -vn 3.818635 -2.973523 2.936723 -v 0.035240 -0.006866 0.090731 -vn 3.617487 -2.713691 3.191828 -v 0.035249 -0.006867 0.090720 -vn 3.531705 2.723691 3.317324 -v 0.035308 -0.006820 0.090654 -vn 3.416314 -2.734256 3.423551 -v 0.035308 -0.006870 0.090654 -vn 3.086651 2.967391 3.721463 -v 0.035415 -0.006825 0.090554 -vn 3.160826 -2.854613 3.659614 -v 0.035375 -0.006873 0.090588 -vn 2.635987 2.800267 4.081531 -v 0.035575 -0.006833 0.090439 -vn 2.711133 -2.959070 4.019238 -v 0.035531 -0.006881 0.090467 -vn 2.396786 2.705034 4.256318 -v 0.035631 -0.006835 0.090407 -vn 2.249432 -2.720149 4.311471 -v 0.035631 -0.006885 0.090407 -vn 1.828202 2.967572 4.474814 -v 0.035750 -0.006840 0.090350 -vn 1.911610 -2.837429 4.440455 -v 0.035702 -0.006888 0.090371 -vn 1.296829 2.828096 4.663805 -v 0.035937 -0.006847 0.090288 -vn 1.388866 -2.972143 4.629095 -v 0.035886 -0.006895 0.090302 -vn 0.970524 2.736547 4.741180 -v 0.036014 -0.006850 0.090272 -vn 0.811358 -2.735403 4.768164 -v 0.036014 -0.006900 0.090272 -vn 0.390413 2.975235 4.810002 -v 0.036131 -0.006854 0.090255 -vn 0.482841 -2.816801 4.810862 -v 0.036079 -0.006902 0.090261 -vn -0.162951 2.845971 4.831943 -v 0.036328 -0.006861 0.090252 -vn -0.060294 -2.979831 4.827136 -v 0.036275 -0.006910 0.090250 -vn -0.533136 2.730428 4.819454 -v 0.036421 -0.006865 0.090261 -vn -0.694189 -2.720214 4.810060 -v 0.036421 -0.006915 0.090261 -vn -1.067053 2.959873 4.730223 -v 0.036523 -0.006869 0.090279 -vn -0.986158 -2.776065 4.764705 -v 0.036471 -0.006917 0.090269 -vn -1.615955 2.861567 4.559002 -v 0.036711 -0.006876 0.090335 -vn -1.513397 -2.977284 4.590518 -v 0.036662 -0.006924 0.090317 -vn -1.962832 2.732539 4.425994 -v 0.036811 -0.006880 0.090377 -vn -2.095266 -2.735677 4.362501 -v 0.036811 -0.006930 0.090377 -vn -2.436472 2.970025 4.173115 -v 0.036890 -0.006883 0.090418 -vn -2.379040 -2.776132 4.210405 -v 0.036844 -0.006931 0.090393 -vn -2.926409 2.876341 3.860990 -v 0.037053 -0.006890 0.090528 -vn -2.815203 -2.978483 3.927688 -v 0.037011 -0.006939 0.090496 -vn -3.303141 -2.724122 3.530910 -v 0.037146 -0.006945 0.090608 -vn -3.982687 2.975635 2.740632 -v 0.037322 -0.006905 0.090814 -vn -3.881419 -2.967865 2.912181 -v 0.037291 -0.006953 0.090771 -vn -4.337190 2.836271 2.177505 -v 0.037420 -0.006912 0.090984 -vn -4.389600 -2.718150 2.048707 -v 0.037402 -0.006961 0.090948 -vn -4.192171 -2.978031 2.377651 -v 0.037397 -0.006960 0.090937 -vn 4.672624 2.711998 -1.243638 -v 0.034982 -0.006473 0.091836 -vn 4.769005 -2.720782 -1.014906 -v 0.034984 -0.006523 0.091843 -vn 4.758702 2.955485 -0.801157 -v 0.034973 -0.006475 0.091793 -vn 4.831357 2.960859 -0.194517 -v 0.034951 -0.006482 0.091598 -vn 4.820700 -2.968657 -0.362214 -v 0.034954 -0.006530 0.091649 -vn 4.822088 2.700895 0.322707 -v 0.034959 -0.006489 0.091401 -vn 4.832733 -2.947369 0.297791 -v 0.034954 -0.006537 0.091452 -vn 4.781373 -2.720528 0.802247 -v 0.034961 -0.006540 0.091379 -vn 4.790352 2.715513 0.676790 -v 0.034961 -0.006490 0.091379 -vn 4.705648 2.724828 1.241695 -v 0.034996 -0.006496 0.091208 -vn 4.706029 -2.874929 1.068654 -v 0.034983 -0.006544 0.091258 -vn 4.617661 -2.726504 1.499456 -v 0.034995 -0.006546 0.091210 -vn 4.519235 2.750637 1.804573 -v 0.035062 -0.006504 0.091023 -vn 4.561662 -2.858804 1.766559 -v 0.035042 -0.006552 0.091069 -vn 4.379155 2.731056 2.075205 -v 0.035077 -0.006505 0.090989 -vn 4.303487 -2.731256 2.218996 -v 0.035077 -0.006555 0.090989 -vn 4.064918 2.949074 2.643002 -v 0.035155 -0.006511 0.090850 -vn 4.122591 -2.855636 2.549588 -v 0.035128 -0.006559 0.090893 -vn 3.756810 2.788096 3.052120 -v 0.035273 -0.006518 0.090692 -vn 3.813042 -2.949311 2.993536 -v 0.035240 -0.006566 0.090731 -vn 3.521882 2.736835 3.322978 -v 0.035309 -0.006520 0.090653 -vn 3.421280 -2.735677 3.414291 -v 0.035308 -0.006570 0.090654 -vn 3.098354 2.954762 3.721365 -v 0.035414 -0.006525 0.090554 -vn 3.157037 -2.842544 3.663794 -v 0.035376 -0.006573 0.090588 -vn 2.650385 2.800984 4.051253 -v 0.035574 -0.006532 0.090440 -vn 2.712717 -2.956770 4.007400 -v 0.035531 -0.006581 0.090467 -vn 2.370052 2.719374 4.247585 -v 0.035631 -0.006535 0.090407 -vn 2.229556 -2.702859 4.346837 -v 0.035631 -0.006585 0.090407 -vn 1.831856 2.957075 4.480083 -v 0.035749 -0.006540 0.090350 -vn 1.936802 -2.807494 4.456252 -v 0.035703 -0.006588 0.090371 -vn 1.302109 2.816602 4.667917 -v 0.035936 -0.006547 0.090289 -vn 1.384580 -2.961813 4.629351 -v 0.035887 -0.006595 0.090302 -vn 0.983258 2.725389 4.750736 -v 0.036014 -0.006550 0.090272 -vn 0.820202 -2.733804 4.771683 -v 0.036014 -0.006600 0.090272 -vn 0.396388 2.965362 4.810952 -v 0.036130 -0.006554 0.090256 -vn 0.474337 -2.803776 4.812368 -v 0.036080 -0.006602 0.090261 -vn -0.160501 2.844117 4.833896 -v 0.036327 -0.006561 0.090252 -vn -0.079586 -2.952063 4.844283 -v 0.036276 -0.006610 0.090250 -vn -0.521452 2.732334 4.811190 -v 0.036421 -0.006565 0.090261 -vn -0.673077 -2.727152 4.806459 -v 0.036421 -0.006615 0.090261 -vn -1.068836 2.946638 4.731316 -v 0.036521 -0.006569 0.090279 -vn -1.000903 -2.770804 4.760594 -v 0.036472 -0.006617 0.090269 -vn -1.609957 2.864554 4.559443 -v 0.036711 -0.006576 0.090334 -vn -1.518905 -2.950809 4.599511 -v 0.036663 -0.006624 0.090317 -vn -1.970359 2.728700 4.428845 -v 0.036811 -0.006580 0.090377 -vn -2.093297 -2.733586 4.365086 -v 0.036811 -0.006630 0.090377 -vn -2.425656 2.949316 4.190027 -v 0.036888 -0.006583 0.090418 -vn -2.379687 -2.771467 4.213939 -v 0.036844 -0.006631 0.090393 -vn -2.933697 2.873328 3.863180 -v 0.037052 -0.006590 0.090527 -vn -2.823409 -2.955303 3.925629 -v 0.037012 -0.006639 0.090497 -vn -3.203909 2.714852 3.651382 -v 0.037146 -0.006595 0.090608 -vn -3.303429 -2.714654 3.534915 -v 0.037146 -0.006645 0.090608 -vn -3.551378 -2.699421 3.278593 -v 0.037162 -0.006646 0.090623 -vn -3.585393 2.953996 3.242546 -v 0.037197 -0.006598 0.090660 -vn -3.946742 2.804320 2.848355 -v 0.037321 -0.006605 0.090813 -vn -3.857999 -2.955488 2.911722 -v 0.037291 -0.006653 0.090772 -vn -4.217373 -2.863336 2.343940 -v 0.037387 -0.006659 0.090920 -vn -4.344811 2.895257 2.137729 -v 0.037420 -0.006612 0.090983 -vn -4.375554 -2.735613 2.091978 -v 0.037397 -0.006660 0.090938 -vn 4.758030 2.708575 -0.992868 -v 0.034973 -0.006175 0.091793 -vn 4.685075 -2.907711 -1.135193 -v 0.034984 -0.006223 0.091844 -vn 4.736695 -2.690608 -0.875837 -v 0.034976 -0.006224 0.091808 -vn 4.791772 -2.746737 -0.629242 -v 0.034971 -0.006225 0.091783 -vn 4.840328 2.973848 -0.173033 -v 0.034951 -0.006182 0.091597 -vn 4.827642 -2.898364 -0.309288 -v 0.034954 -0.006230 0.091650 -vn 4.840170 2.720957 0.517509 -v 0.034959 -0.006189 0.091400 -vn 4.777989 -3.241330 0.125165 -v 0.034951 -0.006235 0.091500 -vn 4.807629 -2.783361 0.441643 -v 0.034954 -0.006237 0.091453 -vn 4.785406 -2.732351 0.771501 -v 0.034959 -0.006239 0.091400 -vn 4.700360 2.953816 1.259007 -v 0.034996 -0.006196 0.091207 -vn 4.704313 -2.904554 1.143880 -v 0.034983 -0.006244 0.091259 -vn 4.501341 2.754646 1.768391 -v 0.035062 -0.006204 0.091022 -vn 4.532883 -2.963123 1.719455 -v 0.035041 -0.006252 0.091071 -vn 4.404605 2.707025 1.979245 -v 0.035069 -0.006204 0.091006 -vn 4.355155 -2.696478 2.142609 -v 0.035069 -0.006254 0.091006 -vn 4.305431 2.736444 2.203834 -v 0.035111 -0.006208 0.090924 -vn 4.097625 -2.708646 2.596052 -v 0.035128 -0.006259 0.090894 -vn 4.070374 2.857338 2.601888 -v 0.035145 -0.006210 0.090865 -vn 3.798821 2.751204 3.000035 -v 0.035261 -0.006217 0.090706 -vn 3.798558 -2.857245 3.003374 -v 0.035240 -0.006266 0.090732 -vn 3.570839 2.729603 3.262318 -v 0.035297 -0.006219 0.090666 -vn 3.454187 -2.727791 3.393308 -v 0.035297 -0.006269 0.090666 -vn 3.155794 2.859597 3.674463 -v 0.035400 -0.006225 0.090566 -vn 3.169928 -2.792958 3.669473 -v 0.035375 -0.006273 0.090589 -vn 2.742222 2.709783 3.993034 -v 0.035558 -0.006232 0.090449 -vn -3.459998 2.706866 3.384447 -v 0.037189 -0.006297 0.090651 -vn -3.725228 -2.743326 3.120597 -v 0.037217 -0.006349 0.090682 -vn -3.841481 2.691088 3.038034 -v 0.037281 -0.006302 0.090759 -vn -3.996537 -2.714662 2.811374 -v 0.037290 -0.006353 0.090771 -vn 2.756474 -2.854164 3.964859 -v 0.035530 -0.006281 0.090468 -vn 2.463821 -2.685217 4.154927 -v 0.035554 -0.006282 0.090452 -vn 2.393019 2.715964 4.212493 -v 0.035619 -0.006234 0.090413 -vn 2.235938 -2.691286 4.336064 -v 0.035619 -0.006284 0.090413 -vn 1.905589 2.857021 4.457599 -v 0.035732 -0.006239 0.090358 -vn 1.944376 -2.766971 4.464935 -v 0.035701 -0.006288 0.090371 -vn 1.388265 2.775253 4.640703 -v 0.035918 -0.006246 0.090293 -vn 1.380262 -2.861678 4.635035 -v 0.035886 -0.006295 0.090302 -vn 1.027460 2.723750 4.727831 -v 0.036004 -0.006249 0.090274 -vn 0.852774 -2.721601 4.759692 -v 0.036004 -0.006300 0.090274 -vn 0.570939 2.776770 4.813416 -v 0.036092 -0.006253 0.090260 -vn 0.451590 -2.739735 4.820392 -v 0.036078 -0.006302 0.090261 -vn 0.005653 2.760131 4.847725 -v 0.036288 -0.006260 0.090251 -vn -0.114746 -2.787133 4.842794 -v 0.036275 -0.006310 0.090250 -vn -0.393421 2.706430 4.810943 -v 0.036412 -0.006265 0.090260 -vn -0.632297 -2.710789 4.794768 -v 0.036412 -0.006315 0.090260 -vn -0.682664 2.671106 4.806295 -v 0.036423 -0.006265 0.090262 -vn -1.022625 -2.772900 4.753280 -v 0.036470 -0.006317 0.090269 -vn -1.092603 2.783572 4.781779 -v 0.036585 -0.006271 0.090294 -vn -1.486249 -2.775887 4.604666 -v 0.036646 -0.006323 0.090312 -vn -1.681368 2.884477 4.527202 -v 0.036720 -0.006276 0.090338 -vn -1.693991 -2.775086 4.519112 -v 0.036661 -0.006324 0.090317 -vn -1.909190 2.728838 4.435279 -v 0.036805 -0.006280 0.090375 -vn -2.071420 -2.717281 4.369891 -v 0.036805 -0.006330 0.090375 -vn -2.226678 2.728322 4.294600 -v 0.036849 -0.006281 0.090396 -vn -2.390040 -2.702585 4.216592 -v 0.036843 -0.006331 0.090393 -vn -2.558490 2.823376 4.117252 -v 0.036971 -0.006287 0.090468 -vn -2.844246 -2.778769 3.905881 -v 0.037011 -0.006338 0.090496 -vn -3.033798 2.935313 3.752250 -v 0.037085 -0.006292 0.090554 -vn -3.015268 -2.830337 3.774845 -v 0.037024 -0.006339 0.090505 -vn -3.208286 2.733287 3.610103 -v 0.037143 -0.006295 0.090605 -vn -3.323130 -2.716411 3.526851 -v 0.037143 -0.006345 0.090605 -vn -3.467285 -2.720633 3.353626 -v 0.037161 -0.006346 0.090623 -vn -4.231978 -3.111162 2.288440 -v 0.037396 -0.006360 0.090937 -vn -4.344129 2.999836 2.086063 -v 0.037429 -0.006313 0.091001 -vn -4.058363 3.420089 2.489072 -v 0.037362 -0.006308 0.090876 -vn -2.422099 3.284542 4.115325 -v 0.036889 -0.005983 0.090418 -vn -1.957051 2.711100 4.422818 -v 0.036805 -0.005980 0.090375 -vn -2.274818 -2.696249 4.273820 -v 0.036805 -0.006030 0.090375 -vn -1.898394 -2.831825 4.440547 -v 0.036770 -0.006028 0.090359 -vn 4.754770 2.776929 -0.962025 -v 0.034973 -0.005875 0.091793 -vn 4.680846 -2.935313 -1.155812 -v 0.034986 -0.005922 0.091853 -vn 4.775400 -2.720460 -0.765967 -v 0.034976 -0.005924 0.091808 -vn 4.812374 2.738456 -0.425816 -v 0.034951 -0.005881 0.091608 -vn 4.827844 -2.899195 -0.414780 -v 0.034955 -0.005930 0.091659 -vn 4.820692 2.741226 -0.211502 -v 0.034951 -0.005882 0.091598 -vn 4.833351 -2.760315 0.106363 -v 0.034950 -0.005934 0.091543 -vn 4.830997 2.713866 0.189511 -v 0.034953 -0.005887 0.091465 -vn 4.816270 -2.710014 0.358191 -v 0.034952 -0.005936 0.091482 -vn 4.806378 2.749487 0.565716 -v 0.034959 -0.005889 0.091401 -vn 4.796754 -2.729403 0.757055 -v 0.034959 -0.005939 0.091401 -vn 3.183633 2.832435 3.662334 -v 0.035414 -0.005925 0.090554 -vn 3.545497 2.715179 3.295674 -v 0.035297 -0.005919 0.090666 -vn 3.461392 -2.726361 3.381480 -v 0.035297 -0.005969 0.090666 -vn 3.747564 2.721391 3.066663 -v 0.035273 -0.005918 0.090692 -vn 3.790985 -2.770522 3.019914 -v 0.035222 -0.005965 0.090755 -vn 4.015051 2.857081 2.681851 -v 0.035186 -0.005913 0.090803 -vn 4.162959 -2.702034 2.479742 -v 0.035114 -0.005958 0.090918 -vn 4.097595 2.921665 2.532849 -v 0.035155 -0.005911 0.090849 -vn 4.306905 2.706712 2.230611 -v 0.035111 -0.005908 0.090923 -vn 4.365170 -2.705997 2.107210 -v 0.035069 -0.005954 0.091006 -vn 4.441429 2.701821 1.975108 -v 0.035069 -0.005904 0.091006 -vn 4.533757 -3.169577 1.610499 -v 0.035031 -0.005951 0.091097 -vn 4.501677 2.837568 1.788521 -v 0.035062 -0.005904 0.091023 -vn 4.778231 -2.985280 1.034759 -v 0.034977 -0.005943 0.091287 -vn 4.626093 3.178337 1.288210 -v 0.034996 -0.005896 0.091208 -vn 0.709771 -2.698862 4.777855 -v 0.036030 -0.006001 0.090269 -vn 0.517586 -2.745665 4.816509 -v 0.036063 -0.006002 0.090264 -vn 1.039498 2.729538 4.721134 -v 0.036004 -0.005949 0.090274 -vn 3.259977 -2.955051 3.557832 -v 0.035354 -0.005972 0.090608 -vn 2.753048 -2.872934 3.982793 -v 0.035490 -0.005979 0.090495 -vn 2.682590 2.777627 4.024875 -v 0.035574 -0.005932 0.090440 -vn 2.317136 -2.681831 4.261212 -v 0.035619 -0.005984 0.090413 -vn 2.384861 2.686502 4.211614 -v 0.035619 -0.005934 0.090413 -vn 2.048555 -2.714380 4.459273 -v 0.035658 -0.005986 0.090393 -vn 1.942812 2.758301 4.457282 -v 0.035749 -0.005940 0.090350 -vn 1.630672 -2.814930 4.561912 -v 0.035788 -0.005991 0.090335 -vn 1.278592 3.048464 4.649651 -v 0.035936 -0.005947 0.090288 -vn 1.393001 -3.003280 4.633001 -v 0.035840 -0.005993 0.090316 -vn 0.951088 -2.706280 4.763123 -v 0.036004 -0.006000 0.090274 -vn -1.443923 -3.044919 4.610987 -v 0.036637 -0.006023 0.090309 -vn -1.626602 2.992234 4.539352 -v 0.036711 -0.005976 0.090334 -vn -1.099712 -2.734510 4.734593 -v 0.036499 -0.006018 0.090274 -vn -1.028807 2.812437 4.728760 -v 0.036522 -0.005969 0.090279 -vn -0.814753 -2.706182 4.753736 -v 0.036423 -0.006015 0.090262 -vn -0.516018 2.706089 4.810111 -v 0.036412 -0.005965 0.090260 -vn -0.584115 -2.686183 4.796352 -v 0.036412 -0.006015 0.090260 -vn -0.128538 2.851524 4.841066 -v 0.036327 -0.005961 0.090252 -vn -0.013292 -2.837384 4.863980 -v 0.036227 -0.006008 0.090250 -vn 0.409943 2.813576 4.817024 -v 0.036140 -0.005955 0.090255 -vn 0.602429 2.781827 4.786625 -v 0.036130 -0.005954 0.090256 -vn -2.907050 2.962039 3.852854 -v 0.037052 -0.005990 0.090527 -vn -2.711909 -3.111089 3.977414 -v 0.036998 -0.006038 0.090487 -vn -3.216603 2.708184 3.607145 -v 0.037143 -0.005995 0.090605 -vn -3.165687 -2.861636 3.640709 -v 0.037110 -0.006043 0.090575 -vn -3.417098 -2.695171 3.413123 -v 0.037143 -0.006045 0.090605 -vn -3.463571 2.707416 3.383183 -v 0.037198 -0.005998 0.090660 -vn -3.706529 -2.696562 3.144325 -v 0.037212 -0.006048 0.090675 -vn -3.726481 2.918946 3.079997 -v 0.037255 -0.006001 0.090725 -vn -3.969893 2.747902 2.816767 -v 0.037321 -0.006005 0.090813 -vn -3.966934 -2.771176 2.876209 -v 0.037301 -0.006054 0.090786 -vn -4.243883 -2.873419 2.326379 -v 0.037379 -0.006059 0.090905 -vn -4.302318 2.767607 2.232729 -v 0.037420 -0.006012 0.090983 -vn -4.479411 -2.771458 1.840909 -v 0.037442 -0.006064 0.091032 -vn 4.629825 2.771754 -1.395299 -v 0.034997 -0.005571 0.091897 -vn 4.753575 -2.736012 -0.951243 -v 0.034984 -0.005623 0.091844 -vn 4.751688 2.973553 -0.836173 -v 0.034973 -0.005575 0.091792 -vn 4.832442 2.979832 -0.171427 -v 0.034951 -0.005582 0.091596 -vn 4.815314 -2.978615 -0.360794 -v 0.034954 -0.005630 0.091649 -vn 4.843989 2.694625 0.374137 -v 0.034959 -0.005589 0.091400 -vn 4.810701 -2.978347 0.257387 -v 0.034954 -0.005637 0.091453 -vn 4.779214 -2.704845 0.618356 -v 0.034957 -0.005639 0.091410 -vn 4.772275 2.850513 0.799263 -v 0.034968 -0.005592 0.091333 -vn 4.773027 -2.748631 0.804555 -v 0.034961 -0.005640 0.091379 -vn 4.651388 2.978897 1.310585 -v 0.034996 -0.005596 0.091207 -vn 4.700294 -2.877733 1.169975 -v 0.034983 -0.005644 0.091258 -vn 4.489801 2.778052 1.785942 -v 0.035062 -0.005604 0.091022 -vn 4.517173 -2.969033 1.728239 -v 0.035042 -0.005652 0.091070 -vn 4.368548 2.730409 2.085074 -v 0.035077 -0.005605 0.090989 -vn 4.328613 -2.722461 2.221498 -v 0.035077 -0.005655 0.090989 -vn 4.155709 2.780751 2.477638 -v 0.035156 -0.005611 0.090848 -vn 4.128846 -2.860314 2.522668 -v 0.035128 -0.005659 0.090893 -vn 3.895258 3.233202 2.765049 -v 0.035181 -0.005612 0.090811 -vn 3.736430 2.789310 3.089527 -v 0.035274 -0.005618 0.090691 -vn 3.786270 -2.972325 2.999528 -v 0.035240 -0.005666 0.090732 -vn 3.546369 2.726823 3.305292 -v 0.035308 -0.005620 0.090654 -vn 3.431055 -2.736973 3.415391 -v 0.035308 -0.005670 0.090654 -vn 3.074812 2.975170 3.718763 -v 0.035415 -0.005625 0.090554 -vn 3.163868 -2.850453 3.664675 -v 0.035375 -0.005673 0.090589 -vn 2.644793 2.815840 4.048100 -v 0.035575 -0.005633 0.090439 -vn 2.711335 -2.972761 3.995579 -v 0.035530 -0.005681 0.090467 -vn 2.355670 2.735259 4.227135 -v 0.035631 -0.005635 0.090407 -vn 2.223865 -2.728087 4.310711 -v 0.035631 -0.005685 0.090407 -vn 1.924800 2.705024 4.460785 -v 0.035750 -0.005640 0.090350 -vn 1.999293 -2.824788 4.403428 -v 0.035702 -0.005688 0.090371 -vn 1.575971 -2.805764 4.568305 -v 0.035780 -0.005691 0.090338 -vn 1.285169 2.823502 4.667233 -v 0.035937 -0.005647 0.090288 -vn 1.288985 -2.852482 4.680930 -v 0.035886 -0.005695 0.090302 -vn 0.972321 2.716889 4.746580 -v 0.036014 -0.005650 0.090272 -vn 0.895115 -2.696176 4.756790 -v 0.036014 -0.005700 0.090272 -vn 0.655726 -2.718547 4.774704 -v 0.036032 -0.005701 0.090268 -vn 0.508541 2.709412 4.831736 -v 0.036131 -0.005654 0.090255 -vn -1.977258 2.697421 4.412961 -v 0.036811 -0.005680 0.090377 -vn -1.551740 2.698451 4.595863 -v 0.036711 -0.005676 0.090335 -vn -1.904134 -2.722476 4.441566 -v 0.036730 -0.005727 0.090342 -vn 0.530643 -2.778656 4.811080 -v 0.036078 -0.005702 0.090261 -vn 0.124477 -2.820251 4.840365 -v 0.036173 -0.005706 0.090252 -vn -0.198407 2.830515 4.847302 -v 0.036328 -0.005661 0.090252 -vn -0.166588 -2.858377 4.830879 -v 0.036275 -0.005710 0.090250 -vn -0.508520 2.725900 4.829247 -v 0.036421 -0.005665 0.090261 -vn -0.675280 -2.736692 4.787139 -v 0.036421 -0.005715 0.090261 -vn -1.092890 2.965308 4.717919 -v 0.036523 -0.005669 0.090279 -vn -0.994824 -2.795690 4.732306 -v 0.036471 -0.005717 0.090269 -vn -1.445907 -2.981110 4.597951 -v 0.036662 -0.005724 0.090317 -vn -2.131324 -2.695645 4.335559 -v 0.036811 -0.005730 0.090377 -vn -2.394701 -2.714097 4.201812 -v 0.036843 -0.005731 0.090393 -vn -2.448616 2.970259 4.164995 -v 0.036890 -0.005683 0.090418 -vn -2.920743 2.876603 3.853892 -v 0.037053 -0.005690 0.090528 -vn -2.629302 -3.182302 4.003973 -v 0.036981 -0.005737 0.090475 -vn -2.980290 -2.770798 3.822631 -v 0.037011 -0.005738 0.090496 -vn -3.204373 2.735445 3.618075 -v 0.037146 -0.005695 0.090608 -vn -3.328290 -2.731601 3.526732 -v 0.037146 -0.005745 0.090608 -vn -3.495183 2.812777 3.344916 -v 0.037198 -0.005698 0.090661 -vn -3.516965 -2.749315 3.324085 -v 0.037161 -0.005746 0.090623 -vn -3.677171 2.842845 3.182015 -v 0.037249 -0.005700 0.090718 -vn -3.943787 -2.728668 2.857441 -v 0.037291 -0.005753 0.090771 -vn -4.019387 2.691939 2.871847 -v 0.037322 -0.005705 0.090814 -vn -4.195330 -2.878613 2.406991 -v 0.037367 -0.005758 0.090885 -vn -4.336728 2.898362 2.142571 -v 0.037420 -0.005712 0.090984 -vn -4.357916 -2.797037 2.136565 -v 0.037396 -0.005760 0.090937 -vn 4.766612 2.947362 -0.909254 -v 0.034973 -0.005275 0.091793 -vn 4.728296 -2.906117 -1.029839 -v 0.034983 -0.005323 0.091843 -vn 4.833920 2.960150 -0.175252 -v 0.034951 -0.005282 0.091598 -vn 4.823525 -2.966834 -0.346011 -v 0.034954 -0.005330 0.091649 -vn 4.853737 2.684731 0.334322 -v 0.034959 -0.005289 0.091401 -vn 4.831805 -2.951100 0.269021 -v 0.034954 -0.005337 0.091452 -vn 4.776652 -2.698430 0.796467 -v 0.034961 -0.005340 0.091379 -vn 4.294854 -2.718816 2.236991 -v 0.035077 -0.005355 0.090989 -vn 4.454704 2.703922 1.863577 -v 0.035062 -0.005304 0.091022 -vn 4.503546 -2.733860 1.781417 -v 0.035042 -0.005352 0.091069 -vn 4.563052 2.740064 1.589890 -v 0.035042 -0.005302 0.091069 -vn 4.705961 -2.871711 1.167386 -v 0.034983 -0.005344 0.091257 -vn 4.671599 2.897698 1.239614 -v 0.034996 -0.005296 0.091208 -vn 4.767635 2.816868 0.788911 -v 0.034967 -0.005291 0.091342 -vn 4.135477 -2.852257 2.526953 -v 0.035128 -0.005359 0.090893 -vn 4.175433 2.754386 2.465700 -v 0.035155 -0.005311 0.090849 -vn 4.367578 2.710503 2.106653 -v 0.035077 -0.005305 0.090989 -vn 0.504961 2.718719 4.820601 -v 0.036130 -0.005354 0.090256 -vn 0.898183 2.702921 4.747389 -v 0.036014 -0.005350 0.090272 -vn 0.790074 -2.714909 4.769804 -v 0.036014 -0.005400 0.090272 -vn 1.138982 2.741163 4.688673 -v 0.035981 -0.005349 0.090278 -vn 1.396603 -2.962369 4.623366 -v 0.035887 -0.005395 0.090302 -vn 1.345145 2.778042 4.649275 -v 0.035936 -0.005347 0.090289 -vn 1.910370 -2.818154 4.450818 -v 0.035703 -0.005388 0.090371 -vn 1.827312 2.952539 4.490119 -v 0.035749 -0.005340 0.090350 -vn 2.217497 -2.733357 4.301061 -v 0.035631 -0.005385 0.090407 -vn 2.362114 2.736731 4.221177 -v 0.035631 -0.005335 0.090407 -vn 2.546972 -2.733743 4.114695 -v 0.035531 -0.005381 0.090467 -vn 2.598170 2.791682 4.080648 -v 0.035574 -0.005332 0.090440 -vn 2.684858 -2.755280 4.021938 -v 0.035520 -0.005380 0.090474 -vn 2.970284 2.772065 3.813747 -v 0.035468 -0.005328 0.090512 -vn 3.014270 -2.695884 3.778211 -v 0.035407 -0.005375 0.090560 -vn 3.172130 2.701091 3.642593 -v 0.035414 -0.005325 0.090554 -vn 3.195993 -2.700174 3.619588 -v 0.035376 -0.005373 0.090588 -vn 3.389212 2.712056 3.441175 -v 0.035359 -0.005323 0.090603 -vn 3.465350 -2.697917 3.396307 -v 0.035308 -0.005370 0.090654 -vn 3.566862 2.717152 3.253457 -v 0.035308 -0.005320 0.090654 -vn 3.788465 -2.952719 3.012709 -v 0.035241 -0.005366 0.090731 -vn 3.741976 2.790030 3.061089 -v 0.035273 -0.005318 0.090692 -vn 3.919753 3.161897 2.759450 -v 0.035175 -0.005312 0.090818 -vn 0.558612 -2.795035 4.797265 -v 0.036080 -0.005402 0.090261 -vn 0.131851 -2.801561 4.833672 -v 0.036165 -0.005405 0.090253 -vn -0.185023 2.831842 4.841250 -v 0.036327 -0.005361 0.090252 -vn -0.157933 -2.857364 4.835465 -v 0.036276 -0.005410 0.090250 -vn -0.515194 2.730096 4.814409 -v 0.036421 -0.005365 0.090261 -vn -0.672732 -2.735912 4.793887 -v 0.036421 -0.005415 0.090261 -vn -1.074100 2.956661 4.715209 -v 0.036522 -0.005369 0.090279 -vn -1.008157 -2.784806 4.735454 -v 0.036472 -0.005417 0.090269 -vn -1.587819 2.837088 4.572913 -v 0.036711 -0.005376 0.090334 -vn -1.501369 -2.955781 4.598404 -v 0.036663 -0.005424 0.090317 -vn -1.833506 2.744283 4.460860 -v 0.036794 -0.005379 0.090369 -vn -2.112463 -2.716031 4.347072 -v 0.036811 -0.005430 0.090377 -vn -2.058381 2.685964 4.370051 -v 0.036811 -0.005380 0.090377 -vn -2.407488 2.930783 4.191649 -v 0.036889 -0.005383 0.090418 -vn -2.385336 -2.768916 4.213025 -v 0.036844 -0.005431 0.090394 -vn -2.743556 2.726284 3.975752 -v 0.037037 -0.005390 0.090515 -vn -2.843172 -2.837645 3.930797 -v 0.037012 -0.005439 0.090497 -vn -3.007185 2.875105 3.770664 -v 0.037053 -0.005390 0.090527 -vn -3.199626 2.726171 3.629747 -v 0.037146 -0.005395 0.090608 -vn -3.319765 -2.708931 3.533201 -v 0.037146 -0.005445 0.090608 -vn -3.553396 -2.693928 3.292574 -v 0.037162 -0.005446 0.090623 -vn -4.312521 -2.747953 2.244141 -v 0.037397 -0.005460 0.090938 -vn -4.361143 2.899713 2.063133 -v 0.037420 -0.005412 0.090983 -vn -4.178191 2.730787 2.432393 -v 0.037401 -0.005411 0.090946 -vn -3.894005 -2.947129 2.893976 -v 0.037292 -0.005453 0.090772 -vn -3.950231 2.919403 2.787987 -v 0.037321 -0.005405 0.090813 -vn -3.571203 2.959521 3.242859 -v 0.037197 -0.005398 0.090660 -vn 4.304636 2.784408 2.252181 -v 0.035092 -0.005006 0.090960 -vn 4.420135 2.681705 1.949048 -v 0.035077 -0.005005 0.090989 -vn 4.282722 -2.693357 2.240838 -v 0.035077 -0.005055 0.090989 -vn 4.627787 2.939192 -1.360977 -v 0.035006 -0.004970 0.091926 -vn 4.765725 2.916026 -0.922357 -v 0.034972 -0.004975 0.091788 -vn 4.734357 -2.920969 -1.062148 -v 0.034984 -0.005023 0.091844 -vn 4.823992 2.728867 -0.459996 -v 0.034954 -0.004980 0.091648 -vn 4.784101 -2.956351 -0.636474 -v 0.034960 -0.005028 0.091713 -vn 4.858703 -2.701043 -0.166913 -v 0.034954 -0.005030 0.091650 -vn 4.841213 2.840074 0.017197 -v 0.034951 -0.004985 0.091506 -vn 4.831258 -2.768692 0.400580 -v 0.034954 -0.005037 0.091453 -vn 4.802770 2.747910 0.630460 -v 0.034963 -0.004990 0.091365 -vn 4.774390 -2.730316 0.776964 -v 0.034961 -0.005040 0.091379 -vn 4.698039 2.823551 1.158812 -v 0.034991 -0.004996 0.091225 -vn 4.698611 -2.799994 1.175992 -v 0.034983 -0.005044 0.091259 -vn 4.586896 2.779265 1.546235 -v 0.035034 -0.005001 0.091090 -vn 4.488436 -2.738990 1.804362 -v 0.035042 -0.005052 0.091071 -vn 4.380296 -2.732811 2.029397 -v 0.035063 -0.005054 0.091019 -vn 4.073390 2.973554 2.622915 -v 0.035163 -0.005011 0.090837 -vn 4.124413 -2.931541 2.513937 -v 0.035128 -0.005059 0.090894 -vn 3.829043 2.752979 2.955020 -v 0.035247 -0.005017 0.090722 -vn 3.768348 -2.777069 3.037107 -v 0.035239 -0.005066 0.090732 -vn 3.530589 2.728132 3.320900 -v 0.035308 -0.005020 0.090654 -vn 3.518063 -2.715600 3.297298 -v 0.035298 -0.005069 0.090665 -vn 3.346697 -2.724215 3.473424 -v 0.035308 -0.005070 0.090654 -vn 3.047092 3.051656 3.731290 -v 0.035434 -0.005026 0.090538 -vn 3.180520 -2.970953 3.623348 -v 0.035375 -0.005073 0.090589 -vn 2.701242 2.745121 4.020593 -v 0.035549 -0.005031 0.090455 -vn 2.839620 -2.989774 3.902262 -v 0.035494 -0.005079 0.090492 -vn 2.588665 -2.689399 4.123727 -v 0.035530 -0.005081 0.090468 -vn 2.447104 2.703239 4.178141 -v 0.035631 -0.005035 0.090407 -vn 2.258099 -2.707810 4.279229 -v 0.035631 -0.005085 0.090407 -vn 2.177724 2.703089 4.319718 -v 0.035673 -0.005037 0.090385 -vn 1.875281 -2.736162 4.484650 -v 0.035701 -0.005088 0.090371 -vn 1.779574 2.858149 4.524575 -v 0.035804 -0.005042 0.090329 -vn 1.298631 -2.764014 4.677609 -v 0.035886 -0.005095 0.090302 -vn 1.245694 2.831528 4.669616 -v 0.035940 -0.005047 0.090288 -vn 1.008849 2.724041 4.723324 -v 0.036014 -0.005050 0.090272 -vn 0.842161 -2.715098 4.765471 -v 0.036014 -0.005100 0.090272 -vn 0.664837 2.721706 4.793113 -v 0.036079 -0.005052 0.090261 -vn 0.455106 -2.718838 4.819824 -v 0.036078 -0.005102 0.090261 -vn 0.260755 2.838595 4.836456 -v 0.036220 -0.005058 0.090250 -vn -0.176962 -2.768111 4.848439 -v 0.036275 -0.005110 0.090250 -vn -0.259506 2.775468 4.828899 -v 0.036362 -0.005063 0.090255 -vn -0.689399 -2.704031 4.783683 -v 0.036421 -0.005115 0.090261 -vn -0.566071 2.698248 4.804093 -v 0.036421 -0.005065 0.090261 -vn -0.928539 2.808786 4.754090 -v 0.036503 -0.005068 0.090275 -vn -0.994841 -2.738769 4.734704 -v 0.036470 -0.005117 0.090269 -vn -1.344002 2.759124 4.691517 -v 0.036641 -0.005073 0.090310 -vn -1.615767 -2.753643 4.575125 -v 0.036661 -0.005124 0.090317 -vn -1.755852 2.761245 4.526190 -v 0.036774 -0.005078 0.090360 -vn -2.133759 -2.707714 4.342742 -v 0.036811 -0.005130 0.090377 -vn -2.044870 2.700919 4.376957 -v 0.036811 -0.005080 0.090377 -vn -2.414910 2.978456 4.173704 -v 0.036900 -0.005084 0.090424 -vn -2.336027 -2.814956 4.230396 -v 0.036843 -0.005131 0.090393 -vn -2.798209 2.739793 3.952374 -v 0.037019 -0.005089 0.090502 -vn -4.412849 -2.857720 1.966270 -v 0.037425 -0.005163 0.090994 -vn -4.421178 2.863626 1.935381 -v 0.037452 -0.005115 0.091054 -vn -4.283811 -2.763252 2.245857 -v 0.037396 -0.005160 0.090937 -vn -4.189829 2.755248 2.472909 -v 0.037390 -0.005110 0.090926 -vn -3.875824 -2.914588 2.898353 -v 0.037290 -0.005153 0.090771 -vn -3.943191 2.857741 2.819404 -v 0.037316 -0.005104 0.090805 -vn -3.510754 -2.924240 3.306914 -v 0.037161 -0.005146 0.090623 -vn -3.626503 3.165526 3.199654 -v 0.037228 -0.005099 0.090693 -vn -3.383490 -2.726395 3.447997 -v 0.037146 -0.005145 0.090608 -vn -3.324353 2.712892 3.524463 -v 0.037146 -0.005095 0.090608 -vn -3.128437 -2.890268 3.684942 -v 0.037079 -0.005142 0.090549 -vn -3.143999 2.795693 3.661397 -v 0.037129 -0.005094 0.090592 -vn -2.943682 -2.725888 3.827920 -v 0.037011 -0.005138 0.090496 -vn -2.617479 -2.982011 4.041296 -v 0.036965 -0.005136 0.090464 -vn 4.760729 3.062778 -0.922686 -v 0.034973 -0.004675 0.091793 -vn 4.702410 -3.021533 -1.131911 -v 0.034991 -0.004722 0.091874 -vn 4.815763 2.896645 -0.541633 -v 0.034954 -0.004680 0.091657 -vn 4.795817 -3.038203 -0.704166 -v 0.034963 -0.004727 0.091735 -vn 4.833017 2.761212 -0.208314 -v 0.034951 -0.004682 0.091598 -vn 4.844874 -2.767415 0.001438 -v 0.034951 -0.004732 0.091593 -vn 4.825408 2.787987 0.281448 -v 0.034959 -0.004689 0.091401 -vn 4.799921 -2.698644 0.619595 -v 0.034961 -0.004740 0.091379 -vn 4.790313 2.688984 0.635525 -v 0.034961 -0.004690 0.091379 -vn 4.728637 -2.797464 1.004546 -v 0.034968 -0.004742 0.091332 -vn 4.702299 2.748739 1.196900 -v 0.034996 -0.004696 0.091208 -vn 4.618360 -2.775162 1.473279 -v 0.035000 -0.004747 0.091193 -vn 4.504704 2.733834 1.784091 -v 0.035062 -0.004704 0.091023 -vn 4.478662 -2.832006 1.822004 -v 0.035047 -0.004752 0.091058 -vn 4.399052 2.696267 1.963517 -v 0.035077 -0.004705 0.090989 -vn 4.327052 -2.682011 2.168505 -v 0.035077 -0.004755 0.090989 -vn 4.334659 2.683827 2.175251 -v 0.035088 -0.004706 0.090968 -vn 4.196939 -2.731608 2.459745 -v 0.035107 -0.004757 0.090930 -vn 4.198068 2.732519 2.512067 -v 0.035155 -0.004711 0.090849 -vn 3.927171 -2.741206 2.848887 -v 0.035182 -0.004763 0.090809 -vn 3.888986 2.769154 2.877745 -v 0.035228 -0.004715 0.090747 -vn 3.621348 -2.695123 3.210009 -v 0.035269 -0.004768 0.090697 -vn 3.700516 2.694321 3.102789 -v 0.035273 -0.004718 0.090692 -vn 3.518759 2.716991 3.327773 -v 0.035308 -0.004720 0.090654 -vn 3.396273 -2.712140 3.457224 -v 0.035308 -0.004770 0.090654 -vn 3.187437 2.767902 3.668341 -v 0.035414 -0.004725 0.090554 -vn 3.237231 -2.855068 3.604979 -v 0.035368 -0.004773 0.090595 -vn 2.779273 -2.867917 3.961759 -v 0.035477 -0.004778 0.090505 -vn 2.690645 2.719270 4.060055 -v 0.035574 -0.004732 0.090440 -vn 2.405635 -2.699847 4.195383 -v 0.035596 -0.004783 0.090427 -vn 2.355270 2.697293 4.244746 -v 0.035631 -0.004735 0.090407 -vn 2.152951 -2.712547 4.324828 -v 0.035631 -0.004785 0.090407 -vn 1.842522 2.831043 4.503630 -v 0.035749 -0.004740 0.090350 -vn 1.841614 -2.762588 4.496926 -v 0.035722 -0.004789 0.090362 -vn 1.369641 2.758657 4.662239 -v 0.035936 -0.004747 0.090289 -vn 1.485728 -3.082776 4.597826 -v 0.035855 -0.004794 0.090312 -vn 0.940887 -2.699201 4.736526 -v 0.035992 -0.004799 0.090276 -vn 0.928514 2.700891 4.751678 -v 0.036014 -0.004750 0.090272 -vn 0.693655 -2.704213 4.777386 -v 0.036014 -0.004800 0.090272 -vn 0.488850 2.749268 4.825866 -v 0.036130 -0.004754 0.090256 -vn 0.282608 -2.758262 4.832409 -v 0.036133 -0.004804 0.090255 -vn -0.175680 2.850110 4.833466 -v 0.036327 -0.004761 0.090252 -vn -0.118067 -2.900918 4.829907 -v 0.036274 -0.004810 0.090250 -vn -0.537938 2.730526 4.817015 -v 0.036421 -0.004765 0.090261 -vn -0.697726 -2.737002 4.792963 -v 0.036416 -0.004815 0.090261 -vn -0.934218 2.749991 4.771389 -v 0.036521 -0.004769 0.090279 -vn -1.319864 -2.793616 4.682544 -v 0.036556 -0.004820 0.090286 -vn -1.606079 2.755415 4.576965 -v 0.036711 -0.004776 0.090334 -vn -1.689678 -2.727805 4.597914 -v 0.036692 -0.004825 0.090327 -vn -1.959663 2.714187 4.428300 -v 0.036811 -0.004780 0.090377 -vn -2.076756 -2.700264 4.358706 -v 0.036811 -0.004830 0.090377 -vn -2.295975 -2.691870 4.248628 -v 0.036823 -0.004830 0.090383 -vn -2.374783 2.753445 4.255724 -v 0.036888 -0.004783 0.090418 -vn -2.747922 -2.855855 3.992063 -v 0.036947 -0.004836 0.090452 -vn -2.857319 3.017007 3.903231 -v 0.037052 -0.004790 0.090527 -vn -3.293252 -2.691739 3.542436 -v 0.037146 -0.004845 0.090608 -vn -3.238404 2.710166 3.606826 -v 0.037146 -0.004795 0.090608 -vn -3.505304 -2.672222 3.339994 -v 0.037152 -0.004845 0.090614 -vn -3.507203 2.771054 3.344230 -v 0.037198 -0.004798 0.090660 -vn -3.804848 -2.855310 3.023026 -v 0.037250 -0.004851 0.090719 -vn -3.953676 2.745028 2.835241 -v 0.037321 -0.004805 0.090813 -vn -4.149264 -2.773738 2.540064 -v 0.037334 -0.004856 0.090833 -vn -4.335512 2.803588 2.199890 -v 0.037420 -0.004812 0.090983 -vn -4.338934 -2.797136 2.174958 -v 0.037406 -0.004861 0.090956 -vn -4.494372 -2.812138 1.757820 -v 0.037464 -0.004866 0.091085 -vn 4.786903 -2.717664 0.808100 -v 0.034961 -0.004440 0.091379 -vn 4.817817 2.699287 0.662558 -v 0.034961 -0.004390 0.091379 -vn 4.847628 2.681483 0.340220 -v 0.034959 -0.004389 0.091400 -vn 4.780238 2.959475 -0.877147 -v 0.034973 -0.004375 0.091792 -vn 4.745158 -2.901439 -1.016951 -v 0.034984 -0.004423 0.091844 -vn 4.847582 2.968967 -0.196626 -v 0.034951 -0.004382 0.091596 -vn 4.833298 -2.966789 -0.375010 -v 0.034954 -0.004430 0.091649 -vn 4.821128 -2.971940 0.282509 -v 0.034954 -0.004437 0.091453 -vn 4.659524 2.976649 1.293456 -v 0.034996 -0.004396 0.091207 -vn 4.702055 -2.872386 1.190856 -v 0.034983 -0.004444 0.091258 -vn 4.492669 2.775763 1.787722 -v 0.035062 -0.004404 0.091022 -vn 4.555877 -2.953171 1.700593 -v 0.035042 -0.004452 0.091071 -vn 4.367648 2.734202 2.075067 -v 0.035077 -0.004405 0.090989 -vn 4.299768 -2.738257 2.221474 -v 0.035077 -0.004455 0.090989 -vn 4.070452 2.964455 2.638381 -v 0.035156 -0.004411 0.090848 -vn 4.132300 -2.856763 2.542083 -v 0.035128 -0.004459 0.090893 -vn 3.743275 2.796472 3.063415 -v 0.035274 -0.004418 0.090691 -vn 3.785433 -2.978250 2.988174 -v 0.035240 -0.004466 0.090732 -vn 3.530542 2.736480 3.300728 -v 0.035308 -0.004420 0.090654 -vn 3.420535 -2.736448 3.426272 -v 0.035308 -0.004470 0.090654 -vn 3.075463 2.975033 3.721715 -v 0.035415 -0.004425 0.090554 -vn 3.180416 -2.844045 3.662000 -v 0.035375 -0.004473 0.090589 -vn 2.640093 2.809172 4.065619 -v 0.035575 -0.004433 0.090439 -vn 2.713270 -2.959594 4.018129 -v 0.035530 -0.004481 0.090467 -vn 2.381434 2.721903 4.234921 -v 0.035631 -0.004435 0.090407 -vn 2.246078 -2.724944 4.306082 -v 0.035631 -0.004485 0.090407 -vn 1.812667 2.964084 4.490164 -v 0.035750 -0.004440 0.090350 -vn 1.899338 -2.824573 4.466013 -v 0.035702 -0.004488 0.090371 -vn 1.319791 2.820861 4.672552 -v 0.035937 -0.004447 0.090288 -vn 1.426478 -2.954156 4.646402 -v 0.035886 -0.004495 0.090302 -vn 0.964567 2.741327 4.735088 -v 0.036014 -0.004450 0.090272 -vn 0.806557 -2.734134 4.770995 -v 0.036014 -0.004500 0.090272 -vn 0.383804 2.972388 4.816216 -v 0.036131 -0.004454 0.090255 -vn 0.485941 -2.812110 4.819290 -v 0.036078 -0.004502 0.090261 -vn -0.163980 2.842488 4.837131 -v 0.036328 -0.004461 0.090252 -vn 0.065486 -3.030950 4.812348 -v 0.036265 -0.004509 0.090250 -vn -0.276018 -2.742790 4.818350 -v 0.036275 -0.004510 0.090250 -vn -0.519461 2.740683 4.806274 -v 0.036421 -0.004465 0.090261 -vn -0.678129 -2.736612 4.786012 -v 0.036421 -0.004515 0.090261 -vn -1.093422 2.965731 4.718491 -v 0.036523 -0.004469 0.090279 -vn -0.992800 -2.793248 4.737246 -v 0.036471 -0.004517 0.090269 -vn -1.615226 2.750216 4.598074 -v 0.036711 -0.004476 0.090335 -vn -3.528411 -2.755698 3.300853 -v 0.037161 -0.004546 0.090623 -vn -3.870197 -2.976730 2.896858 -v 0.037291 -0.004553 0.090771 -vn -3.917392 2.841132 2.845575 -v 0.037322 -0.004505 0.090814 -vn -1.415737 -2.982409 4.601187 -v 0.036662 -0.004524 0.090317 -vn -1.783037 -2.712748 4.493388 -v 0.036683 -0.004525 0.090324 -vn -1.964072 2.716692 4.439930 -v 0.036811 -0.004480 0.090377 -vn -2.110419 -2.727675 4.352224 -v 0.036811 -0.004530 0.090377 -vn -2.437600 2.976349 4.164887 -v 0.036890 -0.004483 0.090418 -vn -2.395583 -2.767358 4.214027 -v 0.036843 -0.004531 0.090393 -vn -2.914924 2.880320 3.861828 -v 0.037053 -0.004490 0.090528 -vn -2.808279 -2.972248 3.947973 -v 0.037011 -0.004538 0.090496 -vn -3.218697 2.729923 3.619182 -v 0.037146 -0.004495 0.090608 -vn -3.317650 -2.742956 3.510075 -v 0.037146 -0.004545 0.090608 -vn -3.443679 2.747389 3.401103 -v 0.037198 -0.004498 0.090661 -vn -3.633528 3.114608 3.144129 -v 0.037216 -0.004499 0.090680 -vn -4.274138 -2.968081 2.298485 -v 0.037396 -0.004560 0.090937 -vn -4.328979 2.915499 2.135004 -v 0.037420 -0.004512 0.090984 -vn -4.059072 3.475440 2.416540 -v 0.037370 -0.004508 0.090891 -vn 4.759727 2.806614 -0.917606 -v 0.034972 -0.004075 0.091786 -vn 4.683510 -2.940353 -1.138208 -v 0.034983 -0.004123 0.091843 -vn 4.799675 -2.711527 -0.743933 -v 0.034976 -0.004124 0.091808 -vn 4.837169 2.993223 -0.138565 -v 0.034951 -0.004082 0.091590 -vn 4.841654 -2.951882 -0.345626 -v 0.034954 -0.004130 0.091648 -vn 4.843431 2.671160 0.301925 -v 0.034959 -0.004089 0.091400 -vn 4.829690 -2.955374 0.291043 -v 0.034954 -0.004137 0.091452 -vn 4.817880 -2.703188 0.749458 -v 0.034959 -0.004139 0.091400 -vn 3.510054 2.703273 3.343053 -v 0.035297 -0.004119 0.090666 -vn 3.631614 2.662914 3.182694 -v 0.035293 -0.004119 0.090670 -vn 3.437453 -2.722988 3.407481 -v 0.035297 -0.004169 0.090666 -vn 3.719036 2.696982 3.091247 -v 0.035278 -0.004118 0.090687 -vn 3.741538 -2.738028 3.087048 -v 0.035241 -0.004166 0.090731 -vn 3.968585 2.855992 2.757988 -v 0.035203 -0.004114 0.090780 -vn 4.159410 -2.899983 2.507890 -v 0.035128 -0.004159 0.090893 -vn 4.120667 2.846083 2.525681 -v 0.035159 -0.004111 0.090843 -vn 4.314381 -2.736651 2.191206 -v 0.035069 -0.004154 0.091006 -vn 4.377033 2.739989 2.049711 -v 0.035069 -0.004104 0.091006 -vn 4.517658 -3.001496 1.698739 -v 0.035042 -0.004152 0.091069 -vn 4.493128 2.757152 1.787119 -v 0.035065 -0.004104 0.091016 -vn 4.698213 -2.941442 1.155554 -v 0.034983 -0.004144 0.091257 -vn 4.648279 3.008317 1.301510 -v 0.034998 -0.004097 0.091201 -vn 4.787929 2.736250 0.660992 -v 0.034959 -0.004089 0.091394 -vn 3.109937 2.984865 3.739915 -v 0.035420 -0.004126 0.090550 -vn 3.176243 -2.895333 3.643695 -v 0.035376 -0.004173 0.090588 -vn 2.644696 2.795948 4.060965 -v 0.035580 -0.004133 0.090436 -vn 2.719569 -3.013207 3.979981 -v 0.035531 -0.004181 0.090467 -vn 2.376865 2.734035 4.220047 -v 0.035619 -0.004134 0.090413 -vn 2.235051 -2.731480 4.300833 -v 0.035619 -0.004184 0.090413 -vn 1.791774 2.992763 4.508121 -v 0.035756 -0.004140 0.090348 -vn 1.932028 -2.861145 4.444269 -v 0.035703 -0.004188 0.090371 -vn 1.336070 2.793959 4.694304 -v 0.035943 -0.004147 0.090287 -vn 1.413399 -3.000535 4.633867 -v 0.035887 -0.004195 0.090302 -vn 0.979174 2.738290 4.736459 -v 0.036004 -0.004149 0.090274 -vn 0.826913 -2.741737 4.761779 -v 0.036004 -0.004200 0.090274 -vn 0.364160 3.012507 4.813662 -v 0.036138 -0.004154 0.090255 -vn 0.482821 -2.843180 4.814982 -v 0.036080 -0.004202 0.090261 -vn -0.178297 2.840309 4.848641 -v 0.036334 -0.004162 0.090253 -vn -0.042023 -3.005640 4.836836 -v 0.036276 -0.004210 0.090250 -vn -0.500195 2.727212 4.825180 -v 0.036412 -0.004165 0.090260 -vn -0.663037 -2.740252 4.792328 -v 0.036412 -0.004215 0.090260 -vn -1.089025 3.015424 4.694833 -v 0.036529 -0.004169 0.090280 -vn -0.991463 -2.819608 4.740686 -v 0.036472 -0.004217 0.090269 -vn -1.628099 2.875758 4.552401 -v 0.036717 -0.004176 0.090337 -vn -1.521659 -2.986347 4.609182 -v 0.036663 -0.004224 0.090317 -vn -1.936954 2.729067 4.431061 -v 0.036805 -0.004180 0.090375 -vn -2.071597 -2.717856 4.395951 -v 0.036805 -0.004230 0.090375 -vn -2.202753 2.711265 4.295308 -v 0.036876 -0.004183 0.090410 -vn -2.381441 -2.738615 4.210499 -v 0.036844 -0.004231 0.090394 -vn -2.490253 3.002956 4.122154 -v 0.036895 -0.004183 0.090421 -vn -2.926726 2.894359 3.853478 -v 0.037057 -0.004191 0.090531 -vn -2.811664 -2.994357 3.927276 -v 0.037012 -0.004239 0.090497 -vn -3.199495 2.726356 3.627723 -v 0.037143 -0.004195 0.090605 -vn -3.297993 -2.720281 3.531768 -v 0.037143 -0.004245 0.090605 -vn -3.551584 -2.705229 3.283412 -v 0.037162 -0.004246 0.090624 -vn -4.256760 -2.996503 2.283111 -v 0.037397 -0.004260 0.090938 -vn -4.346759 2.913637 2.161200 -v 0.037422 -0.004212 0.090988 -vn -3.872543 -2.998270 2.883734 -v 0.037292 -0.004253 0.090772 -vn -3.990768 3.002127 2.726230 -v 0.037324 -0.004205 0.090818 -vn -3.582090 2.997082 3.225666 -v 0.037201 -0.004198 0.090664 -vn 4.686631 2.855644 -1.213776 -v 0.034984 -0.003773 0.091844 -vn 4.797638 -2.843854 -0.743410 -v 0.034972 -0.003825 0.091787 -vn 4.842231 2.831908 -0.508761 -v 0.034954 -0.003780 0.091649 -vn 4.871992 -2.829233 -0.022517 -v 0.034951 -0.003832 0.091591 -vn 4.837929 2.840916 0.158441 -v 0.034954 -0.003787 0.091452 -vn 4.816267 -2.684871 0.546556 -v 0.034959 -0.003839 0.091395 -vn 4.810129 2.699602 0.601091 -v 0.034961 -0.003790 0.091379 -vn 4.758295 -2.701002 0.853427 -v 0.034961 -0.003840 0.091379 -vn 4.761264 2.813583 0.983476 -v 0.034983 -0.003794 0.091258 -vn 4.628187 -2.845655 1.442465 -v 0.034998 -0.003847 0.091201 -vn 4.575848 2.833163 1.624675 -v 0.035042 -0.003802 0.091070 -vn 4.417216 -2.703287 1.978535 -v 0.035064 -0.003854 0.091017 -vn 4.425341 2.684625 2.020802 -v 0.035077 -0.003805 0.090989 -vn 4.273726 -2.699308 2.258847 -v 0.035077 -0.003855 0.090989 -vn 4.219618 2.799056 2.396699 -v 0.035128 -0.003809 0.090893 -vn 3.984547 -2.845209 2.763373 -v 0.035159 -0.003861 0.090844 -vn 3.913502 2.826006 2.897209 -v 0.035240 -0.003816 0.090731 -vn 3.614653 -2.716595 3.226276 -v 0.035278 -0.003868 0.090687 -vn 3.567684 2.692527 3.287195 -v 0.035308 -0.003820 0.090654 -vn 3.392940 -2.693440 3.453646 -v 0.035308 -0.003870 0.090654 -vn 3.328305 2.770668 3.545873 -v 0.035375 -0.003823 0.090588 -vn 3.050871 -2.782724 3.757278 -v 0.035419 -0.003876 0.090550 -vn 2.845884 -2.873446 3.914616 -v 0.035445 -0.003877 0.090529 -vn 2.817409 2.795754 3.945897 -v 0.035530 -0.003831 0.090467 -vn 2.500771 -2.712818 4.188580 -v 0.035580 -0.003883 0.090436 -vn 2.402353 2.700760 4.197685 -v 0.035631 -0.003835 0.090407 -vn 2.173980 -2.694523 4.322022 -v 0.035631 -0.003885 0.090407 -vn 2.083922 2.770138 4.368726 -v 0.035702 -0.003838 0.090371 -vn 1.701728 -2.844220 4.537189 -v 0.035756 -0.003890 0.090348 -vn 1.472670 2.734300 4.625042 -v 0.035886 -0.003845 0.090302 -vn 1.269617 -2.722474 4.698517 -v 0.035887 -0.003895 0.090302 -vn 1.045429 2.710068 4.733229 -v 0.036014 -0.003850 0.090272 -vn 0.837005 -2.717479 4.764525 -v 0.036014 -0.003900 0.090272 -vn 0.651410 2.701843 4.797258 -v 0.036079 -0.003852 0.090261 -vn 0.572717 -2.688737 4.789076 -v 0.036080 -0.003902 0.090261 -vn 0.290406 -2.785083 4.821422 -v 0.036105 -0.003903 0.090258 -vn 0.039699 2.756027 4.844698 -v 0.036275 -0.003860 0.090250 -vn -0.156923 -2.758187 4.836436 -v 0.036276 -0.003910 0.090250 -vn -0.480626 2.689668 4.817221 -v 0.036421 -0.003865 0.090261 -vn -0.462904 -2.843824 4.804817 -v 0.036367 -0.003913 0.090255 -vn -0.724181 -2.687482 4.776135 -v 0.036421 -0.003915 0.090261 -vn -0.855606 2.729069 4.770425 -v 0.036471 -0.003867 0.090269 -vn -1.048900 -2.736758 4.722424 -v 0.036471 -0.003917 0.090269 -vn -1.303704 2.724586 4.672632 -v 0.036662 -0.003874 0.090317 -vn -1.579303 -2.738408 4.584053 -v 0.036662 -0.003924 0.090317 -vn -1.738307 2.829433 4.531050 -v 0.036708 -0.003876 0.090333 -vn -1.917958 2.678808 4.506287 -v 0.036811 -0.003880 0.090377 -vn -2.079461 -2.715643 4.367181 -v 0.036811 -0.003930 0.090377 -vn -2.241196 2.723196 4.303665 -v 0.036843 -0.003881 0.090393 -vn -2.418800 -2.725511 4.194887 -v 0.036843 -0.003931 0.090393 -vn -2.753779 2.768840 3.995050 -v 0.037011 -0.003888 0.090496 -vn -2.898925 -2.773870 3.890076 -v 0.037010 -0.003938 0.090495 -vn -3.168213 2.685817 3.673615 -v 0.037146 -0.003895 0.090608 -vn -3.925335 -2.750462 2.858099 -v 0.037290 -0.003953 0.090771 -vn -4.040878 3.177226 2.577250 -v 0.037355 -0.003907 0.090864 -vn -3.783920 2.750440 3.029332 -v 0.037291 -0.003903 0.090771 -vn -3.551121 -2.690199 3.282977 -v 0.037161 -0.003946 0.090622 -vn -3.243317 -2.757207 3.581893 -v 0.037133 -0.003944 0.090595 -vn -3.390615 -2.671714 3.417811 -v 0.037146 -0.003945 0.090608 -vn -3.308521 2.676504 3.499523 -v 0.037162 -0.003896 0.090623 -vn -3.495506 2.804840 3.329074 -v 0.037180 -0.003897 0.090641 -vn -4.246890 2.784781 2.329548 -v 0.037397 -0.003910 0.090937 -vn -4.332269 -2.769789 2.215302 -v 0.037396 -0.003960 0.090937 -vn -4.457503 -2.942868 1.854169 -v 0.037454 -0.003965 0.091059 -vn 4.722544 2.757985 -1.140276 -v 0.034984 -0.003473 0.091844 -vn 4.752203 -2.760583 -0.952432 -v 0.034984 -0.003523 0.091844 -vn 4.850544 2.763170 -0.474890 -v 0.034954 -0.003480 0.091649 -vn 4.856778 -2.771281 -0.296765 -v 0.034954 -0.003530 0.091650 -vn 4.840803 2.700911 0.191133 -v 0.034954 -0.003487 0.091452 -vn 4.405508 2.703959 2.003771 -v 0.035077 -0.003505 0.090989 -vn 4.553375 2.749472 1.635180 -v 0.035042 -0.003502 0.091070 -vn 4.501433 -2.741833 1.803693 -v 0.035042 -0.003552 0.091070 -vn 4.699701 -2.718264 1.206962 -v 0.034983 -0.003544 0.091258 -vn 4.824159 -2.979355 0.092818 -v 0.034950 -0.003535 0.091523 -vn 4.821527 -2.692491 0.457077 -v 0.034954 -0.003537 0.091453 -vn 4.799747 2.721492 0.579710 -v 0.034961 -0.003490 0.091379 -vn 4.775448 -2.713364 0.783070 -v 0.034961 -0.003540 0.091379 -vn 4.741676 2.724684 0.967375 -v 0.034983 -0.003494 0.091258 -vn 4.596092 3.099556 1.395103 -v 0.035008 -0.003498 0.091166 -vn 4.355739 -2.677971 2.115665 -v 0.035077 -0.003555 0.090989 -vn 4.254637 -2.700434 2.293951 -v 0.035084 -0.003556 0.090975 -vn 4.193605 2.742491 2.445372 -v 0.035128 -0.003509 0.090893 -vn 4.091475 -2.733745 2.622210 -v 0.035128 -0.003559 0.090894 -vn 3.883222 2.744417 2.907201 -v 0.035240 -0.003516 0.090731 -vn 3.781147 -2.738693 3.061363 -v 0.035240 -0.003566 0.090732 -vn 3.581506 2.717034 3.253341 -v 0.035308 -0.003520 0.090654 -vn 3.442131 -2.707212 3.418656 -v 0.035308 -0.003570 0.090654 -vn 3.373010 2.687710 3.468234 -v 0.035375 -0.003523 0.090588 -vn 3.148082 -2.707529 3.702283 -v 0.035375 -0.003573 0.090588 -vn 3.160642 2.767722 3.662916 -v 0.035388 -0.003524 0.090577 -vn 2.816025 2.755473 3.941583 -v 0.035530 -0.003531 0.090467 -vn 2.658171 -2.753470 4.053749 -v 0.035530 -0.003581 0.090468 -vn 2.422398 2.717280 4.186671 -v 0.035631 -0.003535 0.090407 -vn 2.247523 -2.716641 4.286382 -v 0.035631 -0.003585 0.090407 -vn 2.145569 2.695492 4.331813 -v 0.035702 -0.003538 0.090371 -vn 1.950138 -2.696033 4.423529 -v 0.035702 -0.003588 0.090371 -vn 1.913581 2.712129 4.449201 -v 0.035748 -0.003540 0.090351 -vn 1.591831 -2.764685 4.565242 -v 0.035788 -0.003591 0.090335 -vn 1.455641 2.719880 4.626221 -v 0.035886 -0.003545 0.090302 -vn 1.240626 -2.718480 4.684506 -v 0.035886 -0.003595 0.090302 -vn 1.130906 2.719339 4.695875 -v 0.035998 -0.003549 0.090275 -vn 0.833346 -2.697643 4.771004 -v 0.036014 -0.003600 0.090272 -vn 0.925144 2.683961 4.731432 -v 0.036014 -0.003550 0.090272 -vn 0.737376 2.696439 4.772136 -v 0.036079 -0.003552 0.090261 -vn 0.460143 -2.697854 4.818770 -v 0.036079 -0.003602 0.090261 -vn 0.358587 2.934480 4.822685 -v 0.036139 -0.003555 0.090255 -vn 0.059775 2.723612 4.909764 -v 0.036275 -0.003560 0.090250 -vn -0.151528 -2.763772 4.840353 -v 0.036275 -0.003610 0.090250 -vn -0.445337 2.715560 4.819821 -v 0.036421 -0.003565 0.090261 -vn -0.659719 -2.712112 4.800119 -v 0.036421 -0.003615 0.090261 -vn -0.853723 2.734936 4.763631 -v 0.036471 -0.003567 0.090269 -vn -1.038390 -2.731129 4.732513 -v 0.036471 -0.003617 0.090269 -vn -1.407086 2.770872 4.637925 -v 0.036662 -0.003574 0.090317 -vn -1.610051 -2.764088 4.575171 -v 0.036662 -0.003624 0.090317 -vn -1.892760 2.720531 4.448976 -v 0.036811 -0.003580 0.090377 -vn -2.121827 -2.675054 4.414411 -v 0.036811 -0.003630 0.090377 -vn -2.244403 2.734262 4.282938 -v 0.036843 -0.003581 0.090393 -vn -2.413139 -2.704694 4.235519 -v 0.036843 -0.003631 0.090393 -vn -2.747879 2.773272 3.995705 -v 0.037011 -0.003588 0.090496 -vn -2.901785 -2.770798 3.887374 -v 0.037011 -0.003638 0.090496 -vn -3.290203 -2.767376 3.536266 -v 0.037146 -0.003645 0.090608 -vn -3.348436 2.749093 3.506669 -v 0.037162 -0.003596 0.090623 -vn -3.572555 -2.721984 3.262821 -v 0.037161 -0.003646 0.090623 -vn -3.824159 2.778172 2.985202 -v 0.037291 -0.003603 0.090771 -vn -3.941110 -2.779658 2.828428 -v 0.037291 -0.003653 0.090771 -vn -4.251743 2.769424 2.372617 -v 0.037397 -0.003610 0.090937 -vn -4.324441 -2.777280 2.192626 -v 0.037397 -0.003660 0.090937 -vn 4.691436 2.730804 -1.218472 -v 0.034984 -0.003173 0.091844 -vn 4.743839 -2.733087 -0.994451 -v 0.034984 -0.003223 0.091844 -vn 4.760946 2.878153 -0.826060 -v 0.034964 -0.003177 0.091737 -vn 4.861900 -2.730372 -0.248598 -v 0.034954 -0.003230 0.091650 -vn 4.832618 2.745897 -0.367788 -v 0.034954 -0.003180 0.091649 -vn 4.845654 2.689760 0.166178 -v 0.034954 -0.003187 0.091452 -vn 4.819934 -3.023792 0.055149 -v 0.034950 -0.003234 0.091532 -vn 4.813560 -2.698339 0.440519 -v 0.034954 -0.003237 0.091453 -vn 4.805275 2.705406 0.530300 -v 0.034959 -0.003189 0.091400 -vn 4.783505 -2.678655 0.610102 -v 0.034959 -0.003239 0.091400 -vn 4.758358 -2.719460 0.807955 -v 0.034960 -0.003240 0.091391 -vn 4.733107 2.761432 1.039318 -v 0.034983 -0.003194 0.091258 -vn 4.683492 -2.759300 1.239227 -v 0.034983 -0.003244 0.091258 -vn 4.574100 2.738212 1.590890 -v 0.035042 -0.003202 0.091070 -vn 4.526855 -2.720360 1.804861 -v 0.035042 -0.003252 0.091071 -vn 4.424263 2.690080 1.977284 -v 0.035069 -0.003204 0.091006 -vn 4.377220 -2.680879 2.062621 -v 0.035069 -0.003254 0.091006 -vn 4.266522 -2.730064 2.260959 -v 0.035080 -0.003255 0.090983 -vn 4.213453 2.739169 2.420834 -v 0.035128 -0.003209 0.090893 -vn 4.089031 -2.749480 2.598952 -v 0.035128 -0.003259 0.090893 -vn 3.882398 2.691885 2.936177 -v 0.035240 -0.003216 0.090731 -vn 3.875431 -2.835983 2.887220 -v 0.035217 -0.003265 0.090760 -vn 3.661589 -2.689518 3.160029 -v 0.035240 -0.003266 0.090732 -vn 3.605189 2.709795 3.242074 -v 0.035297 -0.003219 0.090666 -vn 3.472260 -2.713160 3.380356 -v 0.035297 -0.003269 0.090666 -vn 3.293904 2.742787 3.568906 -v 0.035375 -0.003223 0.090588 -vn 3.134401 -2.750986 3.700579 -v 0.035375 -0.003273 0.090589 -vn 2.833261 2.745345 3.941085 -v 0.035530 -0.003231 0.090467 -vn 2.664768 -2.748552 4.046560 -v 0.035530 -0.003281 0.090467 -vn 2.449549 2.711572 4.182583 -v 0.035619 -0.003234 0.090413 -vn 2.273160 -2.716439 4.271317 -v 0.035619 -0.003284 0.090413 -vn 2.054312 2.742034 4.393450 -v 0.035702 -0.003238 0.090371 -vn 1.870221 -2.746656 4.471521 -v 0.035701 -0.003288 0.090371 -vn 1.518703 2.755331 4.601674 -v 0.035886 -0.003245 0.090302 -vn 1.309628 -2.737448 4.693060 -v 0.035886 -0.003295 0.090302 -vn 1.052461 2.719208 4.719930 -v 0.036004 -0.003249 0.090274 -vn 0.876425 -2.707772 4.770776 -v 0.036004 -0.003300 0.090274 -vn 0.756997 2.697398 4.769338 -v 0.036079 -0.003252 0.090261 -vn 0.473521 -2.700725 4.819774 -v 0.036078 -0.003302 0.090261 -vn 0.405178 2.909389 4.803457 -v 0.036131 -0.003254 0.090255 -vn -1.918722 2.683314 4.450397 -v 0.036805 -0.003280 0.090375 -vn -1.437666 2.722406 4.630489 -v 0.036662 -0.003274 0.090317 -vn -1.688135 -2.728232 4.524041 -v 0.036661 -0.003324 0.090317 -vn 0.035419 2.762403 4.843238 -v 0.036275 -0.003260 0.090250 -vn -0.144332 -2.759667 4.850872 -v 0.036275 -0.003310 0.090250 -vn -0.436761 2.717012 4.817237 -v 0.036414 -0.003265 0.090260 -vn -0.635173 -2.718172 4.795545 -v 0.036412 -0.003315 0.090260 -vn -0.846294 2.739621 4.764215 -v 0.036471 -0.003267 0.090269 -vn -1.019472 -2.736943 4.730219 -v 0.036471 -0.003317 0.090269 -vn -1.314293 -2.896567 4.639907 -v 0.036615 -0.003322 0.090302 -vn -1.884639 -2.879574 4.448721 -v 0.036749 -0.003327 0.090350 -vn -2.130308 -2.686823 4.336673 -v 0.036805 -0.003330 0.090375 -vn -2.223113 2.669612 4.355638 -v 0.036843 -0.003281 0.090393 -vn -2.382481 -2.703314 4.210116 -v 0.036843 -0.003331 0.090393 -vn -2.447080 2.855643 4.191628 -v 0.036945 -0.003286 0.090451 -vn -2.937099 -2.734289 3.859954 -v 0.037011 -0.003338 0.090496 -vn -2.825521 2.734108 3.929481 -v 0.037011 -0.003288 0.090496 -vn -3.284258 -2.781194 3.541017 -v 0.037143 -0.003345 0.090605 -vn -3.350785 2.741222 3.506008 -v 0.037162 -0.003296 0.090623 -vn -3.566534 -2.728858 3.265100 -v 0.037161 -0.003346 0.090623 -vn -3.841339 2.767164 2.990609 -v 0.037291 -0.003303 0.090771 -vn -3.942319 -2.780216 2.824442 -v 0.037291 -0.003353 0.090771 -vn -4.228113 2.772763 2.386272 -v 0.037397 -0.003310 0.090937 -vn -4.336033 -2.776007 2.196460 -v 0.037396 -0.003360 0.090937 -vn 4.856515 2.722424 -0.283606 -v 0.034951 -0.002882 0.091597 -vn 4.761402 2.780653 -0.945755 -v 0.034973 -0.002875 0.091793 -vn 4.785142 -2.715240 -0.760070 -v 0.034976 -0.002924 0.091808 -vn 4.694332 -2.896379 -1.129514 -v 0.034983 -0.002923 0.091843 -vn 4.812634 -2.921200 -0.388231 -v 0.034954 -0.002930 0.091648 -vn 4.828630 -2.846277 0.180378 -v 0.034950 -0.002934 0.091541 -vn 4.835693 2.688971 0.381299 -v 0.034959 -0.002889 0.091401 -vn 4.807889 -2.829072 0.391062 -v 0.034954 -0.002937 0.091452 -vn 4.779176 -2.696414 0.726032 -v 0.034959 -0.002939 0.091400 -vn 4.751231 2.963776 0.818830 -v 0.034968 -0.002892 0.091335 -vn 4.677887 2.885086 1.234608 -v 0.034996 -0.002896 0.091207 -vn 4.714695 -2.910399 1.024076 -v 0.034983 -0.002944 0.091260 -vn 4.673448 -2.719805 1.294419 -v 0.034983 -0.002944 0.091257 -vn 4.593853 2.747353 1.578965 -v 0.035037 -0.002901 0.091082 -vn 4.496435 -2.715436 1.793853 -v 0.035042 -0.002952 0.091069 -vn 4.546238 2.631638 1.853702 -v 0.035062 -0.002904 0.091022 -vn 4.311882 -2.724669 2.198188 -v 0.035069 -0.002954 0.091006 -vn 4.417820 2.693989 2.063030 -v 0.035069 -0.002904 0.091006 -vn 4.070302 2.954937 2.644510 -v 0.035155 -0.002911 0.090849 -vn 4.137258 -2.880537 2.522595 -v 0.035128 -0.002959 0.090893 -vn 3.790989 2.696615 3.039295 -v 0.035274 -0.002918 0.090692 -vn 3.839873 -2.899771 3.067098 -v 0.035241 -0.002966 0.090731 -vn 3.556103 -2.656314 3.304074 -v 0.035297 -0.002969 0.090666 -vn 3.566247 2.691624 3.293108 -v 0.035297 -0.002919 0.090666 -vn 3.359323 -2.726473 3.467407 -v 0.035304 -0.002970 0.090659 -vn 3.086735 2.968218 3.719961 -v 0.035414 -0.002925 0.090554 -vn 3.170416 -2.840102 3.671532 -v 0.035376 -0.002973 0.090588 -vn 2.657191 2.788385 4.043941 -v 0.035574 -0.002932 0.090439 -vn 2.739609 -2.957890 3.993196 -v 0.035531 -0.002981 0.090467 -vn 2.389650 2.732889 4.209217 -v 0.035619 -0.002934 0.090413 -vn 2.241950 -2.737298 4.283270 -v 0.035619 -0.002984 0.090413 -vn 1.830974 2.964747 4.472445 -v 0.035750 -0.002940 0.090350 -vn 1.915085 -2.836847 4.445234 -v 0.035703 -0.002988 0.090371 -vn 1.314600 2.810606 4.659801 -v 0.035937 -0.002947 0.090288 -vn 1.407189 -2.960958 4.630643 -v 0.035887 -0.002995 0.090302 -vn 0.974970 2.728645 4.747959 -v 0.036004 -0.002949 0.090274 -vn 0.829736 -2.735475 4.767530 -v 0.036004 -0.003000 0.090274 -vn 0.420183 2.948659 4.830307 -v 0.036130 -0.002954 0.090256 -vn 0.488448 -2.817006 4.815522 -v 0.036080 -0.003002 0.090261 -vn -0.151741 2.838448 4.832324 -v 0.036328 -0.002961 0.090252 -vn -0.060773 -2.962997 4.831955 -v 0.036276 -0.003010 0.090250 -vn -0.513863 2.731700 4.816921 -v 0.036412 -0.002965 0.090260 -vn -0.655905 -2.735988 4.793690 -v 0.036412 -0.003015 0.090260 -vn -1.059551 2.955036 4.720177 -v 0.036522 -0.002969 0.090279 -vn -0.990186 -2.801312 4.733430 -v 0.036472 -0.003017 0.090269 -vn -1.550292 2.712002 4.594822 -v 0.036711 -0.002976 0.090334 -vn -1.458790 -2.958354 4.598932 -v 0.036663 -0.003024 0.090317 -vn -1.919056 -2.716191 4.435238 -v 0.036740 -0.003027 0.090346 -vn -1.986322 2.704448 4.417953 -v 0.036805 -0.002980 0.090375 -vn -2.165219 -2.698198 4.336967 -v 0.036805 -0.003030 0.090375 -vn -2.437498 2.959682 4.174115 -v 0.036889 -0.002983 0.090418 -vn -2.380000 -2.764068 4.243698 -v 0.036844 -0.003031 0.090394 -vn -2.924061 2.862896 3.873689 -v 0.037053 -0.002990 0.090527 -vn -2.816743 -2.959610 3.926147 -v 0.037012 -0.003039 0.090497 -vn -3.155753 2.706725 3.681719 -v 0.037143 -0.002995 0.090605 -vn -3.306261 -2.710415 3.534499 -v 0.037143 -0.003045 0.090605 -vn -3.301507 2.677882 3.516406 -v 0.037151 -0.002995 0.090612 -vn -3.474492 -2.682561 3.354840 -v 0.037162 -0.003046 0.090624 -vn -3.541407 2.718751 3.307788 -v 0.037198 -0.002998 0.090661 -vn -3.692663 -2.749614 3.127396 -v 0.037204 -0.003048 0.090667 -vn -3.958106 2.873032 2.801005 -v 0.037321 -0.003005 0.090814 -vn -3.972278 -2.841033 2.878063 -v 0.037292 -0.003053 0.090772 -vn -4.178523 2.824458 2.436365 -v 0.037390 -0.003010 0.090924 -vn -4.132920 -2.883691 2.533506 -v 0.037362 -0.003058 0.090876 -vn -4.357128 2.907092 2.088703 -v 0.037420 -0.003012 0.090984 -vn -4.343085 -2.804751 2.143226 -v 0.037397 -0.003060 0.090938 -vn 4.774518 -2.727066 0.823350 -v 0.034961 -0.002640 0.091379 -vn 4.784327 2.716203 0.670046 -v 0.034961 -0.002590 0.091379 -vn 4.824598 2.694104 0.325966 -v 0.034959 -0.002589 0.091400 -vn 4.757006 2.959807 -0.910984 -v 0.034973 -0.002575 0.091792 -vn 4.729223 -2.912812 -1.029886 -v 0.034984 -0.002623 0.091844 -vn 4.826582 2.977754 -0.181801 -v 0.034951 -0.002582 0.091597 -vn 4.829731 -2.966763 -0.347470 -v 0.034954 -0.002630 0.091649 -vn 4.837249 -2.959893 0.260924 -v 0.034954 -0.002637 0.091452 -vn 4.661804 2.964855 1.305465 -v 0.034996 -0.002596 0.091207 -vn 4.698580 -2.879581 1.176390 -v 0.034983 -0.002644 0.091257 -vn 4.503638 2.767854 1.788514 -v 0.035062 -0.002604 0.091021 -vn 4.512278 -2.971367 1.714252 -v 0.035042 -0.002652 0.091070 -vn 4.368315 2.733888 2.072713 -v 0.035077 -0.002605 0.090989 -vn 4.312999 -2.724566 2.240790 -v 0.035077 -0.002655 0.090989 -vn 4.052308 2.968872 2.626876 -v 0.035156 -0.002611 0.090848 -vn 4.138059 -2.858524 2.537779 -v 0.035128 -0.002659 0.090893 -vn 3.747573 2.792071 3.062562 -v 0.035274 -0.002618 0.090691 -vn 3.792327 -2.965500 2.997406 -v 0.035240 -0.002666 0.090731 -vn 3.527787 2.734999 3.310143 -v 0.035308 -0.002620 0.090654 -vn 3.429945 -2.733963 3.418825 -v 0.035308 -0.002670 0.090654 -vn 3.080521 2.965670 3.723033 -v 0.035415 -0.002625 0.090554 -vn 3.166823 -2.852184 3.658078 -v 0.035375 -0.002673 0.090588 -vn 2.642533 2.803434 4.055047 -v 0.035575 -0.002633 0.090439 -vn 2.823577 -3.170880 3.875266 -v 0.035501 -0.002679 0.090487 -vn 2.559884 -2.765689 4.101137 -v 0.035531 -0.002681 0.090467 -vn 2.399582 2.711713 4.204144 -v 0.035631 -0.002635 0.090407 -vn 2.255628 -2.709836 4.283659 -v 0.035631 -0.002685 0.090407 -vn 2.187873 2.688074 4.323911 -v 0.035691 -0.002637 0.090376 -vn 1.870962 -2.701543 4.470629 -v 0.035702 -0.002688 0.090371 -vn -0.151136 2.733527 4.851167 -v 0.036328 -0.002661 0.090252 -vn 0.329049 2.968953 4.810589 -v 0.036131 -0.002654 0.090255 -vn 0.461237 -2.717647 4.823863 -v 0.036079 -0.002702 0.090261 -vn 0.697406 2.701141 4.776838 -v 0.036099 -0.002653 0.090259 -vn 0.842470 -2.715333 4.775168 -v 0.036014 -0.002700 0.090272 -vn 1.013821 2.707460 4.758360 -v 0.036014 -0.002650 0.090272 -vn 1.378231 -2.958156 4.651482 -v 0.035887 -0.002695 0.090302 -vn 1.297797 2.812354 4.680402 -v 0.035937 -0.002647 0.090288 -vn 1.768511 2.963741 4.493683 -v 0.035750 -0.002640 0.090350 -vn 0.015327 -2.976717 4.815827 -v 0.036275 -0.002710 0.090250 -vn -0.367484 -2.709430 4.817573 -v 0.036305 -0.002711 0.090251 -vn -0.525051 2.717657 4.820014 -v 0.036421 -0.002665 0.090261 -vn -0.705628 -2.721650 4.791763 -v 0.036421 -0.002715 0.090261 -vn -1.099665 2.956255 4.725356 -v 0.036523 -0.002669 0.090279 -vn -1.008124 -2.780790 4.748179 -v 0.036472 -0.002717 0.090269 -vn -1.611687 2.850633 4.576182 -v 0.036711 -0.002676 0.090335 -vn -1.493199 -2.955926 4.626410 -v 0.036662 -0.002724 0.090317 -vn -1.960742 2.728224 4.430229 -v 0.036811 -0.002680 0.090377 -vn -2.119289 -2.726270 4.369869 -v 0.036811 -0.002730 0.090377 -vn -2.266869 2.759658 4.268242 -v 0.036890 -0.002683 0.090418 -vn -2.366504 -2.759838 4.234611 -v 0.036844 -0.002731 0.090394 -vn -2.528191 3.154601 4.068276 -v 0.036918 -0.002684 0.090435 -vn -2.926008 2.881516 3.853030 -v 0.037053 -0.002690 0.090528 -vn -2.818874 -2.970723 3.930500 -v 0.037011 -0.002739 0.090496 -vn -3.219680 2.714208 3.625950 -v 0.037146 -0.002695 0.090608 -vn -3.306306 -2.721880 3.534074 -v 0.037146 -0.002745 0.090608 -vn -3.562901 -2.700359 3.277410 -v 0.037162 -0.002746 0.090623 -vn -4.268445 -2.970126 2.286408 -v 0.037397 -0.002760 0.090937 -vn -4.329008 2.902258 2.163918 -v 0.037420 -0.002712 0.090984 -vn -3.884759 -2.966516 2.895865 -v 0.037291 -0.002753 0.090772 -vn -3.980011 2.974662 2.743474 -v 0.037322 -0.002705 0.090814 -vn -3.578609 2.952992 3.262853 -v 0.037198 -0.002698 0.090661 -vn 4.777229 2.871522 -0.951453 -v 0.034973 -0.002275 0.091794 -vn 4.729482 -2.896383 -1.039714 -v 0.034984 -0.002323 0.091844 -vn 4.824770 2.729751 -0.613606 -v 0.034955 -0.002280 0.091658 -vn 4.848506 -2.727617 -0.278199 -v 0.034954 -0.002330 0.091650 -vn 4.834851 2.950544 -0.099099 -v 0.034951 -0.002282 0.091598 -vn 4.829778 2.699312 0.318084 -v 0.034959 -0.002289 0.091401 -vn 4.826564 -2.953155 0.281392 -v 0.034954 -0.002337 0.091452 -vn 4.779705 -2.686165 0.731494 -v 0.034961 -0.002340 0.091379 -vn 4.798401 2.683086 0.646078 -v 0.034961 -0.002290 0.091379 -vn 4.718382 -2.829033 1.005231 -v 0.034972 -0.002342 0.091311 -vn 4.669372 2.949386 1.299684 -v 0.034996 -0.002296 0.091209 -vn 4.671916 -2.797696 1.250025 -v 0.034983 -0.002344 0.091258 -vn 4.502585 2.771161 1.776394 -v 0.035062 -0.002304 0.091023 -vn 4.520076 -2.952073 1.736225 -v 0.035042 -0.002352 0.091070 -vn 4.370059 2.736814 2.081112 -v 0.035077 -0.002305 0.090989 -vn 4.314381 -2.726246 2.210162 -v 0.035077 -0.002355 0.090989 -vn 4.094649 2.899234 2.587730 -v 0.035155 -0.002311 0.090850 -vn 4.124658 -2.858960 2.524928 -v 0.035128 -0.002359 0.090893 -vn 3.892941 2.729630 2.877382 -v 0.035241 -0.002316 0.090730 -vn 3.761168 -2.739739 3.057959 -v 0.035240 -0.002366 0.090732 -vn 3.670666 2.774081 3.149590 -v 0.035273 -0.002318 0.090692 -vn 3.558670 2.723095 3.308587 -v 0.035308 -0.002320 0.090654 -vn 3.420739 -2.733153 3.421787 -v 0.035308 -0.002370 0.090654 -vn 3.080734 2.952182 3.752017 -v 0.035414 -0.002325 0.090555 -vn 3.164032 -2.839579 3.660284 -v 0.035375 -0.002373 0.090588 -vn 2.665667 2.794759 4.057129 -v 0.035573 -0.002332 0.090440 -vn 2.717861 -2.964714 3.994083 -v 0.035530 -0.002381 0.090468 -vn 2.373965 2.731296 4.222203 -v 0.035631 -0.002335 0.090407 -vn 2.218163 -2.729586 4.309319 -v 0.035631 -0.002385 0.090407 -vn 1.823534 2.967265 4.474447 -v 0.035749 -0.002340 0.090350 -vn 1.913518 -2.808625 4.461965 -v 0.035702 -0.002388 0.090371 -vn 1.303590 2.827383 4.658028 -v 0.035936 -0.002347 0.090289 -vn 1.411911 -2.954124 4.636736 -v 0.035886 -0.002395 0.090302 -vn 0.957466 2.725787 4.754842 -v 0.036014 -0.002350 0.090272 -vn 0.802389 -2.719870 4.797498 -v 0.036014 -0.002400 0.090272 -vn 0.419909 2.948631 4.836236 -v 0.036130 -0.002354 0.090256 -vn 0.490556 -2.792244 4.831314 -v 0.036079 -0.002402 0.090261 -vn -0.160278 2.845619 4.837654 -v 0.036327 -0.002361 0.090252 -vn -0.056818 -2.958459 4.837320 -v 0.036275 -0.002410 0.090250 -vn -0.537230 2.730124 4.815778 -v 0.036421 -0.002365 0.090261 -vn -0.649524 -2.739597 4.797154 -v 0.036415 -0.002415 0.090261 -vn -1.056108 2.955341 4.723178 -v 0.036521 -0.002369 0.090279 -vn -0.995024 -2.795880 4.736667 -v 0.036471 -0.002417 0.090269 -vn -1.609067 2.868659 4.559069 -v 0.036710 -0.002376 0.090334 -vn -1.519511 -2.951410 4.599941 -v 0.036662 -0.002424 0.090317 -vn -1.958999 2.735668 4.425964 -v 0.036811 -0.002380 0.090377 -vn -2.088765 -2.731643 4.367694 -v 0.036811 -0.002430 0.090377 -vn -2.436032 2.959573 4.173643 -v 0.036888 -0.002383 0.090417 -vn -2.376590 -2.774104 4.209624 -v 0.036843 -0.002431 0.090393 -vn -2.930040 2.872768 3.870111 -v 0.037052 -0.002390 0.090527 -vn -2.845206 -2.945490 3.932887 -v 0.037011 -0.002438 0.090496 -vn -3.205915 2.713828 3.656237 -v 0.037146 -0.002395 0.090608 -vn -3.302880 -2.708031 3.545312 -v 0.037146 -0.002445 0.090608 -vn -3.555383 -2.691192 3.287640 -v 0.037161 -0.002446 0.090623 -vn -4.268548 -2.949498 2.303979 -v 0.037397 -0.002460 0.090937 -vn -4.335368 2.903958 2.169619 -v 0.037420 -0.002412 0.090983 -vn -3.887700 -2.962344 2.882504 -v 0.037291 -0.002453 0.090771 -vn -3.982249 2.963118 2.756821 -v 0.037321 -0.002405 0.090813 -vn -3.582192 2.960694 3.242334 -v 0.037197 -0.002398 0.090660 -vn 4.695504 2.750030 -1.233173 -v 0.034988 -0.001972 0.091861 -vn 4.733418 -2.785031 -0.982572 -v 0.034984 -0.002023 0.091844 -vn 4.829061 2.755864 -0.545215 -v 0.034955 -0.001979 0.091667 -vn 4.709460 -3.246728 -0.821074 -v 0.034976 -0.002024 0.091808 -vn 4.856444 -2.759273 -0.211244 -v 0.034954 -0.002030 0.091650 -vn 4.861125 2.778423 0.042923 -v 0.034952 -0.001986 0.091483 -vn 4.860275 -2.695070 0.347103 -v 0.034954 -0.002037 0.091453 -vn 4.828038 2.696976 0.485078 -v 0.034959 -0.001989 0.091400 -vn 4.783203 -2.706265 0.728091 -v 0.034959 -0.002039 0.091400 -vn 4.778437 2.747064 0.930653 -v 0.034977 -0.001993 0.091288 -vn 4.692501 -2.785635 1.267637 -v 0.034983 -0.002044 0.091258 -vn 4.625865 2.782996 1.482481 -v 0.035031 -0.002001 0.091099 -vn 4.513198 -2.716678 1.799850 -v 0.035042 -0.002052 0.091071 -vn 4.434021 2.704762 1.937965 -v 0.035069 -0.002004 0.091006 -vn 4.338490 -2.701624 2.162009 -v 0.035069 -0.002054 0.091006 -vn 4.266694 2.740503 2.314194 -v 0.035113 -0.002008 0.090920 -vn 4.099539 -2.785893 2.609805 -v 0.035128 -0.002059 0.090894 -vn 3.963499 2.785014 2.813334 -v 0.035221 -0.002015 0.090756 -vn 3.744325 -2.735421 3.082493 -v 0.035240 -0.002066 0.090732 -vn 3.638068 2.699603 3.197860 -v 0.035297 -0.002019 0.090666 -vn 3.481459 -2.691248 3.399554 -v 0.035297 -0.002069 0.090666 -vn 3.370111 2.728416 3.483195 -v 0.035353 -0.002022 0.090609 -vn 3.143581 -2.786194 3.706761 -v 0.035375 -0.002073 0.090589 -vn 2.892151 2.704688 3.894826 -v 0.035505 -0.002029 0.090484 -vn 2.853641 -2.751415 3.933618 -v 0.035486 -0.002079 0.090498 -vn 2.601700 -2.690779 4.159108 -v 0.035530 -0.002081 0.090468 -vn 2.478730 2.705026 4.154694 -v 0.035619 -0.002034 0.090413 -vn 2.295749 -2.701496 4.271777 -v 0.035619 -0.002084 0.090413 -vn 2.170214 2.704178 4.335199 -v 0.035674 -0.002037 0.090384 -vn -3.328747 -2.680466 3.516053 -v 0.037143 -0.002145 0.090605 -vn -3.042912 2.778118 3.761639 -v 0.037114 -0.002093 0.090579 -vn -2.931435 -2.788448 3.868248 -v 0.037011 -0.002138 0.090496 -vn -2.592556 2.802312 4.105206 -v 0.036980 -0.002087 0.090474 -vn -2.417388 -2.802471 4.192752 -v 0.036843 -0.002131 0.090393 -vn -2.104970 2.670394 4.372123 -v 0.036809 -0.002080 0.090376 -vn -2.068278 -2.710630 4.378212 -v 0.036805 -0.002130 0.090375 -vn -1.866893 2.680204 4.504092 -v 0.036805 -0.002080 0.090375 -vn -1.647384 -2.806373 4.573295 -v 0.036661 -0.002124 0.090317 -vn -1.265722 2.799117 4.696007 -v 0.036626 -0.002073 0.090305 -vn -1.050837 -2.773905 4.735975 -v 0.036471 -0.002117 0.090269 -vn -0.727179 2.691842 4.791481 -v 0.036441 -0.002066 0.090264 -vn -0.615327 -2.699612 4.811601 -v 0.036412 -0.002115 0.090260 -vn -0.402958 2.707597 4.821798 -v 0.036412 -0.002065 0.090260 -vn -0.215353 -2.761491 4.871377 -v 0.036275 -0.002110 0.090250 -vn 0.181479 2.795929 4.847959 -v 0.036245 -0.002058 0.090250 -vn 0.420992 -2.788851 4.826828 -v 0.036078 -0.002102 0.090261 -vn 0.763660 2.698103 4.792949 -v 0.036049 -0.002051 0.090266 -vn 0.865842 -2.710207 4.755058 -v 0.036004 -0.002100 0.090274 -vn 1.082188 2.700937 4.725739 -v 0.036004 -0.002049 0.090274 -vn 1.256392 -2.763267 4.675624 -v 0.035886 -0.002095 0.090302 -vn 1.613020 2.765037 4.579923 -v 0.035857 -0.002044 0.090311 -vn 1.733563 -2.854785 4.515450 -v 0.035732 -0.002089 0.090357 -vn 1.969628 -2.717535 4.409204 -v 0.035701 -0.002088 0.090371 -vn -4.440134 2.763161 1.879899 -v 0.037459 -0.002116 0.091072 -vn -4.365472 2.875349 2.072985 -v 0.037444 -0.002114 0.091036 -vn -4.342336 -2.757792 2.201111 -v 0.037396 -0.002160 0.090937 -vn -4.129139 2.796621 2.565627 -v 0.037378 -0.002109 0.090904 -vn -3.977808 -2.805711 2.794714 -v 0.037291 -0.002153 0.090771 -vn -3.723142 2.800752 3.129901 -v 0.037268 -0.002102 0.090741 -vn -3.566894 -2.766372 3.268672 -v 0.037161 -0.002146 0.090623 -vn -3.374544 2.637600 3.563311 -v 0.037143 -0.002095 0.090605 -vn -3.226458 2.663256 3.606507 -v 0.037134 -0.002094 0.090597 -vn -4.504432 -2.804793 1.750107 -v 0.037465 -0.001866 0.091086 -vn -0.519120 -2.769803 4.803982 -v 0.036397 -0.001814 0.090258 -vn -0.819012 -2.687212 4.763513 -v 0.036421 -0.001815 0.090261 -vn -0.470933 2.700119 4.806981 -v 0.036421 -0.001765 0.090261 -vn 4.581222 2.718727 -1.531518 -v 0.035018 -0.001668 0.091966 -vn 4.656746 -2.693075 -1.333567 -v 0.035020 -0.001718 0.091972 -vn 4.698755 2.882917 -1.189849 -v 0.034980 -0.001673 0.091829 -vn 4.809608 -2.764357 -0.699642 -v 0.034968 -0.001726 0.091764 -vn 4.801019 3.040617 -0.508580 -v 0.034957 -0.001678 0.091689 -vn 4.850030 2.764626 -0.133104 -v 0.034950 -0.001684 0.091547 -vn 4.856776 -2.768289 0.045028 -v 0.034950 -0.001734 0.091551 -vn 4.837382 2.756607 0.326947 -v 0.034958 -0.001689 0.091406 -vn 4.800646 -2.709992 0.671648 -v 0.034961 -0.001740 0.091379 -vn 4.804904 2.696634 0.608055 -v 0.034961 -0.001690 0.091379 -vn 4.706083 3.030691 1.069797 -v 0.034981 -0.001694 0.091266 -vn 4.742204 -2.848111 0.964827 -v 0.034967 -0.001741 0.091338 -vn 4.635921 2.764659 1.431382 -v 0.035020 -0.001699 0.091129 -vn 4.588975 -2.762336 1.602257 -v 0.035019 -0.001749 0.091131 -vn 4.476122 2.710350 1.863863 -v 0.035073 -0.001705 0.090998 -vn 4.343079 -2.731637 2.141866 -v 0.035077 -0.001755 0.090989 -vn 4.373390 2.691028 2.092476 -v 0.035077 -0.001705 0.090989 -vn 4.119462 3.020730 2.519857 -v 0.035141 -0.001710 0.090872 -vn 4.190957 -2.871631 2.425282 -v 0.035105 -0.001757 0.090935 -vn 3.932592 2.762971 2.840737 -v 0.035221 -0.001715 0.090755 -vn 3.838358 -2.760954 2.971413 -v 0.035221 -0.001765 0.090756 -vn 3.633729 2.675932 3.197693 -v 0.035308 -0.001720 0.090654 -vn 3.622752 -2.827615 3.201479 -v 0.035270 -0.001768 0.090696 -vn 3.392676 -2.711981 3.436921 -v 0.035308 -0.001770 0.090654 -vn 3.472202 2.716156 3.378679 -v 0.035314 -0.001720 0.090648 -vn 3.138671 2.769187 3.714639 -v 0.035418 -0.001725 0.090551 -vn 3.223926 -2.882246 3.603315 -v 0.035369 -0.001773 0.090594 -vn 2.700733 -2.981201 4.014254 -v 0.035478 -0.001778 0.090504 -vn 2.433567 2.733697 4.235551 -v 0.035635 -0.001735 0.090405 -vn 2.278891 -2.758456 4.282312 -v 0.035631 -0.001785 0.090407 -vn 1.834453 2.976019 4.479308 -v 0.035764 -0.001740 0.090344 -vn 1.939232 -2.874446 4.442020 -v 0.035704 -0.001788 0.090370 -vn 1.364930 2.944887 4.639064 -v 0.035899 -0.001746 0.090298 -vn 1.526676 -2.977191 4.587634 -v 0.035836 -0.001793 0.090318 -vn 1.056116 2.689036 4.714641 -v 0.036014 -0.001750 0.090272 -vn 1.057288 -2.845692 4.712386 -v 0.035974 -0.001798 0.090280 -vn 0.699865 -2.680475 4.808390 -v 0.036014 -0.001800 0.090272 -vn -0.027590 -2.967592 4.839015 -v 0.036256 -0.001809 0.090250 -vn -0.181063 2.916245 4.834154 -v 0.036321 -0.001761 0.090252 -vn 0.436503 -2.899297 4.829465 -v 0.036114 -0.001804 0.090257 -vn 0.297558 2.971300 4.831215 -v 0.036179 -0.001756 0.090252 -vn 0.743373 2.748564 4.804806 -v 0.036038 -0.001751 0.090267 -vn -2.158677 -2.721945 4.354978 -v 0.036805 -0.001830 0.090375 -vn -1.951784 2.725044 4.417347 -v 0.036811 -0.001780 0.090377 -vn -1.597891 -2.971271 4.558669 -v 0.036674 -0.001824 0.090321 -vn -1.709360 2.890073 4.526862 -v 0.036735 -0.001777 0.090344 -vn -1.122532 -2.942736 4.693340 -v 0.036537 -0.001819 0.090282 -vn -1.270128 2.971570 4.670219 -v 0.036601 -0.001772 0.090298 -vn -0.845063 2.824810 4.784036 -v 0.036462 -0.001766 0.090267 -vn -4.305868 -2.976364 2.185822 -v 0.037407 -0.001861 0.090957 -vn -4.396631 2.925522 2.038429 -v 0.037435 -0.001813 0.091016 -vn -4.049036 -2.966549 2.653256 -v 0.037335 -0.001856 0.090834 -vn -4.144811 2.979270 2.486045 -v 0.037370 -0.001808 0.090889 -vn -3.745205 -2.972706 3.061096 -v 0.037250 -0.001851 0.090720 -vn -3.849890 2.970285 2.931763 -v 0.037291 -0.001803 0.090771 -vn -3.495181 -2.777291 3.339337 -v 0.037154 -0.001845 0.090616 -vn -3.572041 2.962315 3.276197 -v 0.037200 -0.001798 0.090662 -vn -3.335584 -2.715906 3.506769 -v 0.037146 -0.001845 0.090608 -vn -3.238522 2.729145 3.582803 -v 0.037146 -0.001795 0.090608 -vn -2.998079 -2.953556 3.814610 -v 0.037047 -0.001840 0.090523 -vn -3.059883 2.859815 3.750180 -v 0.037098 -0.001792 0.090564 -vn -2.546371 -2.964459 4.126545 -v 0.036930 -0.001835 0.090442 -vn -2.701685 2.970375 4.015054 -v 0.036985 -0.001787 0.090478 -vn -2.337880 2.959838 4.245883 -v 0.036864 -0.001782 0.090404 -vn 4.669340 3.305823 -1.009645 -v 0.034984 -0.001373 0.091844 -vn 4.691040 -2.762733 -1.217111 -v 0.035009 -0.001419 0.091937 -vn 4.803299 3.159675 -0.355724 -v 0.034954 -0.001380 0.091649 -vn 4.765094 -3.192563 -0.687333 -v 0.034962 -0.001427 0.091728 -vn 4.839096 2.739632 0.149460 -v 0.034954 -0.001387 0.091452 -vn 4.826851 -3.055974 0.039436 -v 0.034950 -0.001435 0.091515 -vn 4.802569 -2.714252 0.682246 -v 0.034959 -0.001439 0.091400 -vn 3.099223 -2.713561 3.753829 -v 0.035392 -0.001474 0.090573 -vn 3.394325 2.722869 3.445628 -v 0.035375 -0.001423 0.090588 -vn 3.465612 -2.689815 3.429655 -v 0.035297 -0.001469 0.090666 -vn 3.597145 2.711175 3.244506 -v 0.035297 -0.001419 0.090666 -vn 3.762639 -2.735364 3.062192 -v 0.035244 -0.001466 0.090727 -vn 3.901714 2.752618 2.881492 -v 0.035240 -0.001416 0.090731 -vn 4.151095 -2.741556 2.549103 -v 0.035122 -0.001459 0.090903 -vn 4.201992 2.769389 2.431779 -v 0.035128 -0.001409 0.090893 -vn 4.372828 -2.697176 2.174200 -v 0.035069 -0.001454 0.091006 -vn 4.424627 2.720255 1.982693 -v 0.035069 -0.001404 0.091006 -vn 4.562194 -2.844202 1.636595 -v 0.035032 -0.001451 0.091097 -vn 4.576522 2.747979 1.606385 -v 0.035042 -0.001402 0.091070 -vn 4.730667 -2.822464 1.060136 -v 0.034974 -0.001443 0.091302 -vn 4.716193 2.918030 1.123419 -v 0.034983 -0.001394 0.091258 -vn 4.807755 2.715905 0.545561 -v 0.034959 -0.001389 0.091400 -vn 0.726631 -2.678421 4.806663 -v 0.036004 -0.001500 0.090274 -vn 1.033287 2.694467 4.726485 -v 0.036004 -0.001450 0.090274 -vn 1.097445 -2.735143 4.721921 -v 0.035957 -0.001498 0.090283 -vn 1.501104 2.889113 4.606997 -v 0.035886 -0.001445 0.090302 -vn 1.733027 -2.698201 4.555866 -v 0.035754 -0.001490 0.090348 -vn 1.883556 2.708558 4.470753 -v 0.035756 -0.001440 0.090347 -vn 2.163031 2.757757 4.359349 -v 0.035702 -0.001438 0.090371 -vn 2.211266 -2.682228 4.337162 -v 0.035619 -0.001484 0.090413 -vn 2.428083 2.703621 4.185908 -v 0.035619 -0.001434 0.090413 -vn 2.550590 -2.725114 4.123224 -v 0.035564 -0.001482 0.090446 -vn 2.853422 2.824686 3.921083 -v 0.035530 -0.001431 0.090467 -vn 3.153786 2.724150 3.660416 -v 0.035394 -0.001424 0.090571 -vn 0.207007 -2.726760 4.867155 -v 0.036169 -0.001506 0.090252 -vn -0.378060 -2.847577 4.822066 -v 0.036383 -0.001514 0.090257 -vn -0.407799 2.707543 4.822429 -v 0.036412 -0.001465 0.090260 -vn -0.840511 -2.678439 4.781053 -v 0.036412 -0.001515 0.090260 -vn -0.939082 3.003016 4.749130 -v 0.036471 -0.001467 0.090269 -vn -0.114967 3.247847 4.789935 -v 0.036275 -0.001460 0.090250 -vn 0.440308 2.735962 4.828577 -v 0.036169 -0.001456 0.090253 -vn 0.653829 2.943326 4.796225 -v 0.036079 -0.001452 0.090261 -vn -1.497177 3.027226 4.606282 -v 0.036662 -0.001474 0.090317 -vn -1.272141 -3.078219 4.666959 -v 0.036593 -0.001521 0.090296 -vn -1.855030 2.711987 4.477225 -v 0.036805 -0.001480 0.090375 -vn -1.926674 -2.767064 4.439050 -v 0.036794 -0.001529 0.090369 -vn -2.301552 -2.678126 4.267530 -v 0.036805 -0.001530 0.090375 -vn -2.301467 2.900799 4.253535 -v 0.036843 -0.001481 0.090393 -vn -2.784553 2.820023 3.985328 -v 0.037011 -0.001488 0.090496 -vn -2.736125 -2.878474 4.019855 -v 0.036980 -0.001537 0.090474 -vn -3.260293 -2.770317 3.579248 -v 0.037143 -0.001545 0.090605 -vn -3.376549 2.801166 3.493171 -v 0.037162 -0.001496 0.090623 -vn -3.528328 -2.698842 3.316505 -v 0.037146 -0.001545 0.090608 -vn -3.825003 2.782195 2.994450 -v 0.037291 -0.001503 0.090771 -vn -3.937232 -2.779388 2.858859 -v 0.037288 -0.001553 0.090768 -vn -4.238446 2.774849 2.397913 -v 0.037397 -0.001510 0.090937 -vn -4.364368 -2.774676 2.153633 -v 0.037403 -0.001561 0.090949 -vn 4.730200 3.006196 -1.060621 -v 0.034984 -0.001073 0.091844 -vn 4.688882 -2.868197 -1.176542 -v 0.034999 -0.001121 0.091902 -vn 4.840516 2.910574 -0.394355 -v 0.034954 -0.001080 0.091649 -vn 4.819662 -2.928284 -0.514807 -v 0.034958 -0.001128 0.091692 -vn 4.847984 2.731245 0.145110 -v 0.034954 -0.001087 0.091452 -vn 4.841187 -2.831908 0.197968 -v 0.034952 -0.001136 0.091478 -vn 4.808310 2.727022 0.533525 -v 0.034959 -0.001089 0.091400 -vn 4.792857 -2.718963 0.720429 -v 0.034959 -0.001139 0.091400 -vn 4.741104 2.769025 1.066651 -v 0.034983 -0.001094 0.091258 -vn 4.710188 -2.750823 1.203165 -v 0.034981 -0.001144 0.091267 -vn 4.594101 2.748057 1.558651 -v 0.035042 -0.001102 0.091070 -vn 4.506343 -2.722530 1.790265 -v 0.035045 -0.001152 0.091063 -vn 4.446856 2.684217 1.854229 -v 0.035066 -0.001104 0.091014 -vn 4.336452 -2.688242 2.211151 -v 0.035069 -0.001154 0.091006 -vn 3.419072 -2.694665 3.429212 -v 0.035297 -0.001169 0.090666 -vn 3.544205 2.687021 3.301429 -v 0.035297 -0.001119 0.090666 -vn 3.668427 2.678053 3.131219 -v 0.035287 -0.001119 0.090677 -vn 3.675894 -2.696027 3.160570 -v 0.035267 -0.001168 0.090699 -vn 3.889918 2.827141 2.896862 -v 0.035240 -0.001116 0.090731 -vn 4.089452 -2.718547 2.650833 -v 0.035141 -0.001160 0.090872 -vn 3.943160 3.053324 2.780150 -v 0.035197 -0.001114 0.090788 -vn 4.270929 2.742128 2.327995 -v 0.035128 -0.001109 0.090893 -vn 4.385375 2.694128 2.047907 -v 0.035069 -0.001104 0.091006 -vn 3.363756 2.785969 3.538364 -v 0.035375 -0.001123 0.090588 -vn 2.970653 -2.837714 3.841045 -v 0.035420 -0.001176 0.090550 -vn 2.828829 2.877345 3.963470 -v 0.035530 -0.001131 0.090467 -vn 2.464498 -2.709363 4.171527 -v 0.035595 -0.001183 0.090427 -vn 2.448377 2.690620 4.186845 -v 0.035620 -0.001134 0.090413 -vn 2.141812 -2.683978 4.355766 -v 0.035619 -0.001184 0.090413 -vn 1.934877 3.275471 4.376465 -v 0.035702 -0.001138 0.090371 -vn 1.400507 3.191052 4.599284 -v 0.035886 -0.001145 0.090302 -vn 1.721508 -3.328535 4.469656 -v 0.035788 -0.001191 0.090335 -vn 1.106532 2.730102 4.714967 -v 0.036004 -0.001149 0.090274 -vn 1.059591 -2.758047 4.721601 -v 0.035993 -0.001199 0.090276 -vn 0.665103 -2.678304 4.802303 -v 0.036004 -0.001200 0.090274 -vn -2.934530 -2.715593 3.882713 -v 0.037010 -0.001238 0.090495 -vn -2.494033 2.846716 4.152544 -v 0.036969 -0.001187 0.090467 -vn -2.354594 -2.698441 4.234365 -v 0.036827 -0.001231 0.090385 -vn -2.218181 2.758055 4.294550 -v 0.036843 -0.001181 0.090393 -vn -2.020033 -2.724122 4.403496 -v 0.036805 -0.001230 0.090375 -vn -1.860056 2.712247 4.495711 -v 0.036805 -0.001180 0.090375 -vn -1.412327 -2.880116 4.646656 -v 0.036628 -0.001223 0.090306 -vn -1.471514 2.832819 4.635872 -v 0.036662 -0.001174 0.090317 -vn -0.866365 -2.739435 4.762763 -v 0.036419 -0.001215 0.090261 -vn -0.921911 2.967233 4.742506 -v 0.036471 -0.001167 0.090269 -vn -0.532242 -2.737335 4.812786 -v 0.036412 -0.001215 0.090260 -vn -0.385655 2.733531 4.836817 -v 0.036412 -0.001165 0.090260 -vn 0.189510 -3.085954 4.833509 -v 0.036206 -0.001207 0.090251 -vn -0.041413 2.990839 4.841833 -v 0.036275 -0.001160 0.090250 -vn 0.533401 3.137647 4.779904 -v 0.036079 -0.001152 0.090261 -vn -4.027514 -2.729869 2.738584 -v 0.037310 -0.001254 0.090797 -vn -3.759774 2.810633 3.066986 -v 0.037291 -0.001203 0.090771 -vn -3.618082 -2.751520 3.225268 -v 0.037172 -0.001246 0.090634 -vn -3.413566 2.700588 3.432652 -v 0.037162 -0.001196 0.090623 -vn -3.307298 -2.713092 3.543040 -v 0.037143 -0.001245 0.090605 -vn -3.164328 2.689560 3.717936 -v 0.037143 -0.001195 0.090605 -vn -2.864545 2.719439 3.919419 -v 0.037011 -0.001188 0.090496 -vn -4.416948 -2.826486 2.024957 -v 0.037419 -0.001262 0.090981 -vn -4.225768 2.845780 2.401688 -v 0.037397 -0.001210 0.090937 -vn -4.091000 3.003943 2.557786 -v 0.037360 -0.001207 0.090874 -vn -1.622226 -3.138642 4.540734 -v 0.036717 -0.000926 0.090337 -vn -2.099424 -2.708391 4.373801 -v 0.036775 -0.000928 0.090361 -vn -1.277356 3.228358 2.862146 -v 0.036775 -0.000890 0.090361 -vn -2.521606 -3.285951 4.072702 -v 0.036895 -0.000933 0.090421 -vn -1.837793 3.270092 2.541507 -v 0.037044 -0.000890 0.090521 -vn -3.011386 -2.714783 3.795310 -v 0.037058 -0.000941 0.090531 -vn -3.934980 1.005088 4.704579 -v 0.037102 -0.000893 0.090568 -vn -3.323503 -2.670914 3.568964 -v 0.037102 -0.000943 0.090568 -vn -3.437714 2.640309 3.664076 -v 0.037162 -0.000896 0.090623 -vn -3.671140 -2.828260 3.198498 -v 0.037202 -0.000948 0.090665 -vn -3.858697 2.763442 3.126988 -v 0.037291 -0.000903 0.090771 -vn -4.085914 -2.840010 2.624097 -v 0.037325 -0.000955 0.090819 -vn -4.238637 2.808186 2.464944 -v 0.037397 -0.000910 0.090937 -vn -4.421892 -2.845787 1.985655 -v 0.037423 -0.000962 0.090989 -vn -1.279881 -3.881017 4.443792 -v 0.036529 -0.000919 0.090280 -vn -0.373815 3.195549 3.114452 -v 0.036402 -0.000890 0.090259 -vn -0.942348 -2.998578 4.717512 -v 0.036455 -0.000916 0.090266 -vn -0.012111 -4.382627 4.323249 -v 0.036242 -0.000908 0.090250 -vn -0.344618 -3.162652 4.803574 -v 0.036334 -0.000912 0.090253 -vn -0.633248 -2.683974 4.805261 -v 0.036402 -0.000914 0.090259 -vn 0.115810 -4.668717 4.120896 -v 0.036137 -0.000904 0.090255 -vn 0.589482 3.284514 3.080249 -v 0.036014 -0.000890 0.090272 -vn 0.623336 -2.877090 4.792232 -v 0.036029 -0.000900 0.090269 -vn 0.588114 0.509023 1.609340 -v 0.035756 -0.000890 0.090348 -vn 0.830839 -5.471922 2.947531 -v 0.035822 -0.000893 0.090322 -vn 1.036135 -4.179307 4.322287 -v 0.035943 -0.000897 0.090287 -vn 3.094565 2.945244 -0.445477 -v 0.039467 -0.009390 0.091087 -vn 3.094565 -2.945244 -0.445477 -v 0.039467 -0.011260 0.091087 -vn 3.122012 2.945242 0.166802 -v 0.039495 -0.009390 0.091723 -vn 3.122012 -2.945243 0.166802 -v 0.039495 -0.011260 0.091723 -vn 3.029479 2.945236 0.772682 -v 0.039399 -0.009390 0.092353 -vn 3.029479 -2.945236 0.772682 -v 0.039399 -0.011260 0.092353 -vn 2.820529 2.945253 1.348854 -v 0.039182 -0.009390 0.092952 -vn 2.820529 -2.945250 1.348854 -v 0.039182 -0.011260 0.092952 -vn 2.503189 2.945239 1.873186 -v 0.038852 -0.009390 0.093497 -vn 2.503189 -2.945239 1.873186 -v 0.038852 -0.011260 0.093497 -vn 2.089646 2.945243 2.325546 -v 0.038422 -0.009390 0.093967 -vn 2.089646 -2.945243 2.325546 -v 0.038422 -0.011260 0.093967 -vn 1.595787 2.945232 2.688538 -v 0.037909 -0.009390 0.094345 -vn 1.595787 -2.945232 2.688538 -v 0.037909 -0.011260 0.094345 -vn 1.040626 2.945259 2.948202 -v 0.037332 -0.009390 0.094615 -vn 1.040626 -2.945257 2.948202 -v 0.037332 -0.011260 0.094615 -vn 0.445475 2.945234 3.094564 -v 0.036713 -0.009390 0.094767 -vn 0.445475 -2.945234 3.094564 -v 0.036713 -0.011260 0.094767 -vn -0.166812 2.945247 3.122013 -v 0.036077 -0.009390 0.094795 -vn -0.166812 -2.945247 3.122012 -v 0.036077 -0.011260 0.094795 -vn -0.772670 2.945247 3.029483 -v 0.035447 -0.009390 0.094699 -vn -0.772670 -2.945248 3.029483 -v 0.035447 -0.011260 0.094699 -vn -1.348848 2.945237 2.820529 -v 0.034848 -0.009390 0.094482 -vn -1.348848 -2.945237 2.820529 -v 0.034848 -0.011260 0.094482 -vn -1.873199 2.945241 2.503180 -v 0.034303 -0.009390 0.094152 -vn -1.873199 -2.945241 2.503180 -v 0.034303 -0.011260 0.094152 -vn -2.325554 2.945244 2.089637 -v 0.033833 -0.009390 0.093722 -vn -2.325554 -2.945244 2.089637 -v 0.033833 -0.011260 0.093722 -vn -2.688531 2.945252 1.595805 -v 0.033455 -0.009390 0.093209 -vn -2.688530 -2.945251 1.595805 -v 0.033455 -0.011260 0.093209 -vn 0.726285 3.351022 3.038798 -v 0.036947 -0.009390 0.094468 -vn 1.342201 3.351032 2.821394 -v 0.037539 -0.009390 0.094259 -vn 1.899474 3.351034 2.480678 -v 0.038074 -0.009390 0.093932 -vn 2.373732 3.351034 2.031542 -v 0.038529 -0.009390 0.093501 -vn 2.744242 3.351031 1.493621 -v 0.038885 -0.009390 0.092984 -vn 2.994814 3.351030 0.890425 -v 0.039126 -0.009390 0.092405 -vn 3.114500 3.351030 0.248317 -v 0.039241 -0.009390 0.091788 -vn 3.098068 3.351035 -0.404652 -v 0.039225 -0.009390 0.091161 -vn -2.665640 3.351034 1.629764 -v 0.033690 -0.009390 0.093115 -vn -2.268537 3.351037 2.148373 -v 0.034072 -0.009390 0.093613 -vn -1.772300 3.351023 2.573078 -v 0.034548 -0.009390 0.094021 -vn -1.198585 3.351050 2.885333 -v 0.035099 -0.009390 0.094320 -vn -0.572507 3.351010 3.071486 -v 0.035700 -0.009390 0.094499 -vn 0.078598 3.351052 3.123391 -v 0.036325 -0.009390 0.094549 -vn 3.098067 2.932150 -0.404652 -v 0.039225 -0.005390 0.091161 -vn 3.114500 2.932155 0.248317 -v 0.039241 -0.005390 0.091788 -vn 2.994814 2.932154 0.890425 -v 0.039126 -0.005390 0.092405 -vn 2.744242 2.932154 1.493621 -v 0.038885 -0.005390 0.092984 -vn 2.373732 2.932151 2.031542 -v 0.038529 -0.005390 0.093501 -vn 1.899474 2.932150 2.480678 -v 0.038074 -0.005390 0.093932 -vn 1.342201 2.932153 2.821394 -v 0.037539 -0.005390 0.094259 -vn 0.726285 2.932164 3.038797 -v 0.036947 -0.005390 0.094468 -vn 0.078598 2.932133 3.123391 -v 0.036325 -0.005390 0.094549 -vn -0.572507 2.932175 3.071486 -v 0.035700 -0.005390 0.094499 -vn -1.198585 2.932136 2.885333 -v 0.035099 -0.005390 0.094320 -vn -1.772300 2.932163 2.573078 -v 0.034548 -0.005390 0.094021 -vn -2.268536 2.932149 2.148373 -v 0.034072 -0.005390 0.093613 -vn -2.665640 2.932152 1.629764 -v 0.033690 -0.005390 0.093115 -vn -0.459657 4.712378 -2.173377 -v 0.035655 -0.005390 0.088734 -vn -0.193024 1.832611 -2.484921 -v 0.036051 -0.005390 0.088993 -vn 0.118524 4.712379 -2.218288 -v 0.036404 -0.005390 0.088676 -vn 2.112015 4.712389 0.688615 -v 0.038986 -0.005390 0.092442 -vn 2.248503 1.832593 1.075289 -v 0.038564 -0.005390 0.092657 -vn 1.861818 4.712397 1.211777 -v 0.038662 -0.005390 0.093120 -vn -1.006507 4.712382 -1.980351 -v 0.034946 -0.005390 0.088984 -vn -2.112014 4.712391 -0.688614 -v 0.033514 -0.005390 0.090658 -vn -2.248509 1.832601 -1.075304 -v 0.033936 -0.005390 0.090443 -vn -1.861820 4.712390 -1.211789 -v 0.033838 -0.005390 0.089980 -vn -1.652377 4.712381 1.484756 -v 0.034109 -0.005390 0.093473 -vn -2.055474 1.832591 1.409618 -v 0.034135 -0.005390 0.093001 -vn -1.980336 4.712397 1.006499 -v 0.033684 -0.005390 0.092854 -vn 0.456694 1.832602 -2.450198 -v 0.036720 -0.005390 0.089028 -vn 0.688614 4.712391 -2.112014 -v 0.037142 -0.005390 0.088814 -vn 1.652379 4.712379 -1.484754 -v 0.038391 -0.005390 0.089627 -vn 2.055502 1.832608 -1.409611 -v 0.038365 -0.005390 0.090099 -vn 1.980364 4.712376 -1.006495 -v 0.038816 -0.005390 0.090246 -vn 0.459648 4.712400 2.173354 -v 0.036845 -0.005390 0.094366 -vn 0.193018 1.832586 2.484899 -v 0.036449 -0.005390 0.094107 -vn -0.118515 4.712395 2.218271 -v 0.036096 -0.005390 0.094424 -vn -1.211789 4.712385 1.861825 -v 0.034680 -0.005390 0.093962 -vn -1.893571 1.832591 -1.620610 -v 0.034301 -0.005390 0.089882 -vn -1.484743 4.712399 -1.652363 -v 0.034327 -0.005390 0.089409 -vn 2.350285 1.832602 -0.829582 -v 0.038669 -0.005390 0.090696 -vn 2.173372 4.712384 -0.459643 -v 0.039066 -0.005390 0.090955 -vn 2.218278 4.712387 0.118511 -v 0.039124 -0.005390 0.091704 -vn 1.484744 4.712397 1.652364 -v 0.038173 -0.005390 0.093691 -vn -0.456696 1.832595 2.450198 -v 0.035780 -0.005390 0.094072 -vn -0.688614 4.712388 2.112018 -v 0.035358 -0.005390 0.094286 -vn -2.218277 4.712390 -0.118533 -v 0.033376 -0.005390 0.091396 -vn -0.829591 1.832604 -2.350284 -v 0.035396 -0.005390 0.089131 -vn 1.075300 1.832601 -2.248508 -v 0.037357 -0.005390 0.089236 -vn 1.211788 4.712381 -1.861830 -v 0.037820 -0.005390 0.089138 -vn 1.620621 1.832605 -1.893588 -v 0.037918 -0.005390 0.089601 -vn 2.484904 1.832588 -0.193024 -v 0.038807 -0.005390 0.091351 -vn 1.409605 1.832584 2.055473 -v 0.037701 -0.005390 0.093665 -vn 1.006489 4.712405 1.980332 -v 0.037554 -0.005390 0.094116 -vn 0.829574 1.832582 2.350266 -v 0.037104 -0.005390 0.093969 -vn -1.075300 1.832600 2.248504 -v 0.035143 -0.005390 0.093864 -vn -1.620621 1.832602 1.893580 -v 0.034582 -0.005390 0.093499 -vn -2.350288 1.832600 0.829579 -v 0.033831 -0.005390 0.092404 -vn -2.173372 4.712388 0.459643 -v 0.033434 -0.005390 0.092145 -vn -2.484913 1.832600 0.193011 -v 0.033693 -0.005390 0.091749 -vn -2.450186 1.832591 -0.456706 -v 0.033728 -0.005390 0.091080 -vn -1.409600 1.832591 -2.055483 -v 0.034799 -0.005390 0.089435 -vn 2.450201 1.832600 0.456691 -v 0.038772 -0.005390 0.092020 -vn 1.893575 1.832590 1.620609 -v 0.038199 -0.005390 0.093218 -vn -1.934258 3.041601 2.351675 -v 0.035902 -0.000890 0.094207 -vn -0.456690 4.450598 2.450178 -v 0.035780 -0.000890 0.094072 -vn -2.438495 2.280289 4.258280 -v 0.036000 -0.000988 0.094316 -vn -0.210619 0.884659 3.942245 -v 0.036096 -0.001088 0.094424 -vn 1.672666 3.041627 2.544388 -v 0.036313 -0.000890 0.094229 -vn 1.970864 2.280302 4.493837 -v 0.036204 -0.000988 0.094327 -vn -0.193035 4.450568 -2.484917 -v 0.036051 -0.000890 0.088993 -vn 1.531268 0.533501 0.842372 -v 0.035026 -0.000890 0.090966 -vn 1.384639 0.526453 1.050063 -v 0.035136 -0.000890 0.090796 -vn 1.202065 0.523241 1.248550 -v 0.035269 -0.000890 0.090647 -vn 1.005716 0.527011 1.418120 -v 0.035423 -0.000890 0.090519 -vn 0.795181 0.524428 1.542177 -v 0.035594 -0.000890 0.090416 -vn -1.672627 3.041587 -2.544413 -v 0.036187 -0.000890 0.088871 -vn 1.934240 3.041521 -2.351683 -v 0.036598 -0.000890 0.088893 -vn -1.480499 5.819869 -0.709132 -v 0.037472 -0.000890 0.092253 -vn -1.403883 5.832918 -0.807990 -v 0.037460 -0.000890 0.092277 -vn 3.039838 3.041602 -0.176366 -v 0.038602 -0.000890 0.092835 -vn 0.499239 3.041643 -3.003748 -v 0.035223 -0.000890 0.089075 -vn -2.720752 3.041614 -1.367203 -v 0.034856 -0.000890 0.089261 -vn -0.829604 4.450584 -2.350278 -v 0.035396 -0.000890 0.089131 -vn -1.409590 4.450594 -2.055493 -v 0.034799 -0.000890 0.089435 -vn -0.295142 3.041631 -3.030610 -v 0.034617 -0.000890 0.089425 -vn -2.981894 3.041569 -0.616439 -v 0.034311 -0.000890 0.089700 -vn -1.893574 4.450602 -1.620593 -v 0.034301 -0.000890 0.089882 -vn -1.069401 3.041287 -2.850965 -v 0.034123 -0.000890 0.089920 -vn 2.981915 3.041649 0.616399 -v 0.038189 -0.000890 0.093400 -vn -1.173998 5.838116 -1.103282 -v 0.037218 -0.000890 0.092607 -vn -1.107746 5.833926 -1.179601 -v 0.037197 -0.000890 0.092628 -vn 2.450195 4.450588 0.456695 -v 0.038772 -0.000890 0.092020 -vn -1.613812 5.832806 -0.121644 -v 0.037619 -0.000890 0.091722 -vn 2.890609 3.041622 -0.957130 -v 0.038854 -0.000890 0.092183 -vn -1.565782 5.843894 -0.329331 -v 0.037590 -0.000890 0.091922 -vn 2.351676 3.041601 1.934257 -v 0.038907 -0.000890 0.091898 -vn 2.544360 3.041598 -1.672698 -v 0.038929 -0.000890 0.091487 -vn -1.592618 5.846254 0.112628 -v 0.037618 -0.000890 0.091520 -vn 2.484880 4.450617 -0.193054 -v 0.038807 -0.000890 0.091351 -vn -1.545174 5.853430 0.349280 -v 0.037588 -0.000890 0.091323 -vn 2.772184 3.041724 1.259660 -v 0.038907 -0.000890 0.091198 -vn 2.024801 3.041672 -2.274191 -v 0.038822 -0.000890 0.090796 -vn -1.473229 5.863060 0.534462 -v 0.037529 -0.000890 0.091132 -vn 2.350315 4.450568 -0.829549 -v 0.038669 -0.000890 0.090696 -vn -1.384912 5.854240 0.767037 -v 0.037443 -0.000890 0.090953 -vn 1.620624 4.450567 -1.893597 -v 0.037918 -0.000890 0.089601 -vn 0.616391 3.041667 -2.981912 -v 0.038100 -0.000890 0.089611 -vn -1.012038 5.930999 1.031223 -v 0.037198 -0.000890 0.090644 -vn 1.075334 4.450547 -2.248527 -v 0.037357 -0.000890 0.089236 -vn -0.176369 3.041690 -3.039848 -v 0.037535 -0.000890 0.089198 -vn 2.850950 3.041599 -1.069499 -v 0.037880 -0.000890 0.089423 -vn 2.476991 3.041497 -1.770934 -v 0.037274 -0.000890 0.089073 -vn -0.957084 3.041578 -2.890625 -v 0.036883 -0.000890 0.088946 -vn 0.456690 4.450582 -2.450202 -v 0.036720 -0.000890 0.089028 -vn 1.259676 3.041536 -2.772171 -v 0.035898 -0.000890 0.088893 -vn -2.274195 3.041603 -2.024783 -v 0.035496 -0.000890 0.088978 -vn 1.725482 0.523403 -0.186300 -v 0.034863 -0.000890 0.091750 -vn -2.024795 3.041587 2.274187 -v 0.033678 -0.000890 0.092304 -vn 1.708794 0.547349 -0.458722 -v 0.034896 -0.000890 0.091953 -vn -2.350274 4.450595 0.829591 -v 0.033831 -0.000890 0.092404 -vn 1.613460 0.530508 -0.660780 -v 0.034960 -0.000890 0.092149 -vn -3.003751 3.041757 -0.499237 -v 0.033775 -0.000890 0.092577 -vn -1.367167 3.041620 2.720767 -v 0.033961 -0.000890 0.092944 -vn 1.492810 0.517345 -0.862664 -v 0.035051 -0.000890 0.092337 -vn -2.055475 4.450584 1.409628 -v 0.034135 -0.000890 0.093001 -vn 1.376280 0.526590 -1.062565 -v 0.035168 -0.000890 0.092508 -vn -1.290732 5.841625 -0.951171 -v 0.037351 -0.000890 0.092451 -vn 1.893583 4.450577 1.620626 -v 0.038199 -0.000890 0.093218 -vn 1.069509 3.041713 2.850949 -v 0.038377 -0.000890 0.093180 -vn -1.529935 5.831493 -0.536088 -v 0.037542 -0.000890 0.092089 -vn 2.248525 4.450597 1.075270 -v 0.038564 -0.000890 0.092657 -vn 1.770926 3.041613 2.477004 -v 0.038727 -0.000890 0.092574 -vn 3.003741 3.041696 0.499270 -v 0.038725 -0.000890 0.090523 -vn 1.367205 3.041578 -2.720747 -v 0.038539 -0.000890 0.090156 -vn -1.243090 5.867623 0.943235 -v 0.037332 -0.000890 0.090789 -vn 2.055475 4.450597 -1.409617 -v 0.038365 -0.000890 0.090099 -vn 3.030615 3.041733 -0.295189 -v 0.038375 -0.000890 0.089917 -vn -3.039844 3.041624 0.176345 -v 0.033898 -0.000890 0.090265 -vn -2.248517 4.450572 -1.075305 -v 0.033936 -0.000890 0.090443 -vn 1.631552 0.545400 0.680641 -v 0.034943 -0.000890 0.091149 -vn -1.770950 3.041654 -2.476990 -v 0.033773 -0.000890 0.090526 -vn 1.621673 0.496824 0.492654 -v 0.034921 -0.000890 0.091214 -vn -2.890624 3.041577 0.957078 -v 0.033646 -0.000890 0.090917 -vn 1.671049 0.505291 0.353384 -v 0.034887 -0.000890 0.091345 -vn -2.450213 4.450573 -0.456680 -v 0.033728 -0.000890 0.091080 -vn 1.684404 0.500328 0.231916 -v 0.034871 -0.000890 0.091435 -vn -2.351702 3.041583 -1.934228 -v 0.033593 -0.000890 0.091202 -vn 1.730856 0.521911 0.095541 -v 0.034860 -0.000890 0.091546 -vn -2.544416 3.041623 1.672629 -v 0.033571 -0.000890 0.091613 -vn 1.701932 0.501626 -0.034907 -v 0.034858 -0.000890 0.091663 -vn -2.484929 4.450568 0.193011 -v 0.033693 -0.000890 0.091749 -vn -2.772176 3.041597 -1.259668 -v 0.033593 -0.000890 0.091902 -vn -3.030609 3.041390 0.295116 -v 0.034125 -0.000890 0.093183 -vn -0.616438 3.041622 2.981903 -v 0.034400 -0.000890 0.093489 -vn 1.244246 0.553068 -1.271318 -v 0.035309 -0.000890 0.092662 -vn -1.620628 4.450578 1.893577 -v 0.034582 -0.000890 0.093499 -vn 1.092108 0.609805 -1.505269 -v 0.035471 -0.000890 0.092793 -vn -2.850950 3.041499 1.069464 -v 0.034620 -0.000890 0.093677 -vn 0.885606 0.501344 -1.453328 -v 0.035542 -0.000890 0.092840 -vn 0.176373 3.041604 3.039836 -v 0.034965 -0.000890 0.093902 -vn 0.884540 0.709588 -1.781006 -v 0.035651 -0.000890 0.092902 -vn -1.075279 4.450596 2.248502 -v 0.035143 -0.000890 0.093864 -vn 0.654352 0.501986 -1.572165 -v 0.035759 -0.000890 0.092951 -vn -2.477001 3.041613 1.770928 -v 0.035226 -0.000890 0.094027 -vn 0.664475 1.061219 -2.258134 -v 0.035845 -0.000890 0.092983 -vn 0.957147 3.041614 2.890601 -v 0.035617 -0.000890 0.094154 -vn 0.166175 5.826221 -1.622529 -v 0.036050 -0.000890 0.093037 -vn 0.065322 5.821902 -1.637094 -v 0.036096 -0.000890 0.093040 -vn -0.027368 5.824491 -1.633746 -v 0.036209 -0.000890 0.093041 -vn -0.162122 5.831697 -1.613475 -v 0.036295 -0.000890 0.093037 -vn 0.193006 4.450597 2.484899 -v 0.036449 -0.000890 0.094107 -vn -0.352415 5.834727 -1.576796 -v 0.036502 -0.000890 0.093005 -vn -1.259748 3.041369 2.772123 -v 0.036602 -0.000890 0.094207 -vn -0.503652 5.824792 -1.553835 -v 0.036660 -0.000890 0.092960 -vn 2.274201 3.041597 2.024776 -v 0.037004 -0.000890 0.094122 -vn -0.620660 5.829004 -1.503192 -v 0.036702 -0.000890 0.092944 -vn 0.829570 4.450612 2.350259 -v 0.037104 -0.000890 0.093969 -vn -0.782986 5.837656 -1.407070 -v 0.036890 -0.000890 0.092857 -vn -0.499359 3.041392 3.003711 -v 0.037277 -0.000890 0.094025 -vn 2.720760 3.041592 1.367176 -v 0.037644 -0.000890 0.093839 -vn -0.968433 5.840629 -1.280712 -v 0.037063 -0.000890 0.092743 -vn 1.409602 4.450613 2.055464 -v 0.037701 -0.000890 0.093665 -vn 0.295140 3.041634 3.030609 -v 0.037883 -0.000890 0.093675 -vn -1.223831 0.884667 3.753452 -v 0.035358 -0.001088 0.094286 -vn 0.740612 2.280269 4.850842 -v 0.035487 -0.000988 0.094221 -vn 0.439001 -0.268399 -2.457511 -v 0.035992 -0.000892 0.093028 -vn 1.079232 0.028052 -3.035771 -v 0.035754 -0.000900 0.092966 -vn -2.386492 0.003692 -2.112791 -v 0.037370 -0.001143 0.092548 -vn 0.626985 -0.009181 3.133430 -v 0.035954 -0.001324 0.090080 -vn -2.447024 -0.006546 -2.066978 -v 0.037398 -0.001442 0.092516 -vn 2.477456 -0.006052 2.023391 -v 0.035089 -0.001591 0.090601 -vn -0.333200 -0.006474 3.177451 -v 0.036403 -0.001639 0.090058 -vn -0.756023 -0.001699 -3.107808 -v 0.036608 -0.001772 0.093007 -vn 2.561900 0.000653 1.927265 -v 0.035063 -0.001890 0.090634 -vn 2.808410 0.000279 1.601109 -v 0.034928 -0.001882 0.090841 -vn 2.963087 -0.003813 1.340391 -v 0.034892 -0.001880 0.090914 -vn 3.041266 0.001503 0.986747 -v 0.034830 -0.001874 0.091067 -vn 3.150906 -0.000676 0.531358 -v 0.034770 -0.001866 0.091306 -vn 3.199896 0.006057 0.019701 -v 0.034750 -0.001859 0.091552 -vn 3.227663 0.000303 -0.302833 -v 0.034759 -0.001853 0.091712 -vn 3.175941 -0.001274 -0.605636 -v 0.034771 -0.001851 0.091798 -vn 3.056784 -0.004830 -1.007764 -v 0.034831 -0.001843 0.092037 -vn 2.930632 0.018375 -1.343941 -v 0.034890 -0.001838 0.092183 -vn 2.770692 -0.006019 -1.588222 -v 0.034930 -0.001835 0.092262 -vn 2.561105 -0.000462 -1.923136 -v 0.035065 -0.001827 0.092469 -vn 2.370333 0.001089 -2.220657 -v 0.035167 -0.001822 0.092588 -vn 2.214607 0.006390 -2.398460 -v 0.035231 -0.001819 0.092651 -vn 2.054636 0.013325 -2.502241 -v 0.035287 -0.001817 0.092700 -vn 1.747223 0.000975 -2.709163 -v 0.035425 -0.001811 0.092803 -vn 1.299761 0.001601 -2.938126 -v 0.035642 -0.001804 0.092921 -vn 0.799770 0.000283 -3.096168 -v 0.035875 -0.001796 0.093002 -vn 0.275170 -0.003500 -3.190943 -v 0.036118 -0.001788 0.093044 -vn -0.249467 0.002277 -3.161771 -v 0.036365 -0.001780 0.093046 -vn -1.723075 -0.003182 -2.694290 -v 0.037060 -0.001756 0.092813 -vn -1.264355 -0.007258 -2.925703 -v 0.036842 -0.001764 0.092928 -vn -2.145205 0.006415 -2.373034 -v 0.037256 -0.001749 0.092663 -vn -2.503534 0.001836 -2.008194 -v 0.037424 -0.001741 0.092483 -vn -2.739610 0.004890 -1.728991 -v 0.037533 -0.001735 0.092327 -vn -2.861919 0.008565 -1.503858 -v 0.037562 -0.001733 0.092278 -vn -3.009378 0.013704 -1.059513 -v 0.037663 -0.001725 0.092053 -vn -3.167596 0.004389 -0.637416 -v 0.037726 -0.001717 0.091815 -vn -3.238691 -0.005174 -0.327461 -v 0.037742 -0.001714 0.091709 -vn -3.233080 -0.001710 -0.029280 -v 0.037750 -0.001709 0.091569 -vn -3.225699 -0.010843 0.279314 -v 0.037743 -0.001704 0.091407 -vn -3.172432 -0.008394 0.550875 -v 0.037733 -0.001701 0.091323 -vn -3.032210 -0.009889 0.989036 -v 0.037676 -0.001694 0.091083 -vn -2.834042 -0.007256 1.476179 -v 0.037580 -0.001686 0.090856 -vn -2.543047 -0.003464 1.923823 -v 0.037448 -0.001678 0.090648 -vn -2.204366 -0.008039 2.311332 -v 0.037284 -0.001670 0.090463 -vn -1.780879 -0.005802 2.638718 -v 0.037092 -0.001662 0.090309 -vn -1.342616 -0.007683 2.897970 -v 0.036877 -0.001654 0.090187 -vn -0.830295 -0.004478 3.074948 -v 0.036646 -0.001646 0.090103 -vn 0.712458 -0.005367 3.114880 -v 0.035912 -0.001623 0.090088 -vn 0.208641 -0.004174 3.177744 -v 0.036157 -0.001631 0.090053 -vn 1.224671 -0.003956 2.939163 -v 0.035678 -0.001615 0.090164 -vn 1.672162 0.013360 2.695292 -v 0.035458 -0.001607 0.090276 -vn 1.994600 0.003984 2.554949 -v 0.035290 -0.001600 0.090397 -vn 2.221428 -0.006100 2.372210 -v 0.035260 -0.001599 0.090423 -vn 2.998216 -0.005626 1.113351 -v 0.034844 -0.001576 0.091027 -vn 2.769568 -0.008828 1.588596 -v 0.034949 -0.001583 0.090804 -vn 3.143977 -0.002591 0.619874 -v 0.034777 -0.001568 0.091264 -vn 3.202150 -0.003069 0.076915 -v 0.034751 -0.001560 0.091510 -vn 3.164921 -0.006940 -0.435526 -v 0.034764 -0.001552 0.091756 -vn 3.046881 0.000359 -0.958944 -v 0.034818 -0.001544 0.091996 -vn 2.847228 0.008586 -1.420647 -v 0.034910 -0.001536 0.092225 -vn 2.624087 0.031712 -1.827630 -v 0.035039 -0.001528 0.092435 -vn 2.524948 0.011017 -2.016923 -v 0.035059 -0.001527 0.092462 -vn 2.217622 0.002401 -2.298168 -v 0.035201 -0.001521 0.092622 -vn 1.848772 0.001701 -2.607528 -v 0.035391 -0.001513 0.092779 -vn 1.564544 -0.001548 -2.846093 -v 0.035558 -0.001507 0.092881 -vn 1.308349 -0.006819 -2.960840 -v 0.035604 -0.001505 0.092904 -vn 0.875435 0.012557 -3.060868 -v 0.035834 -0.001497 0.092991 -vn 0.381490 0.006723 -3.180792 -v 0.036076 -0.001489 0.093040 -vn -0.160742 -0.000677 -3.196278 -v 0.036322 -0.001481 0.093048 -vn -0.678245 -0.002804 -3.128954 -v 0.036567 -0.001473 0.093016 -vn -1.176681 -0.006730 -2.962626 -v 0.036803 -0.001466 0.092944 -vn -1.603255 0.000877 -2.816160 -v 0.037024 -0.001458 0.092835 -vn -1.861722 -0.001891 -2.663943 -v 0.037093 -0.001455 0.092791 -vn -2.112257 -0.004709 -2.413736 -v 0.037224 -0.001450 0.092691 -vn -2.962519 -0.001002 -1.155219 -v 0.037648 -0.001426 0.092093 -vn -2.748776 -0.012835 -1.602431 -v 0.037540 -0.001434 0.092315 -vn -3.132397 0.002145 -0.663458 -v 0.037718 -0.001418 0.091856 -vn -3.203134 0.005921 -0.132116 -v 0.037749 -0.001411 0.091612 -vn -3.187582 0.001824 0.395622 -v 0.037739 -0.001403 0.091365 -vn -3.065521 0.005047 0.923656 -v 0.037688 -0.001395 0.091124 -vn -2.861349 0.010808 1.376854 -v 0.037599 -0.001387 0.090894 -vn -2.601967 -0.004498 1.847415 -v 0.037473 -0.001379 0.090682 -vn -2.267139 0.000293 2.248488 -v 0.037314 -0.001371 0.090493 -vn -1.859287 0.000412 2.588875 -v 0.037127 -0.001363 0.090333 -vn -1.418047 -0.001381 2.857936 -v 0.036915 -0.001356 0.090206 -vn -0.915024 0.003265 3.043645 -v 0.036686 -0.001348 0.090115 -vn -0.420869 -0.004186 3.160253 -v 0.036445 -0.001340 0.090063 -vn 0.111177 -0.010079 3.190084 -v 0.036199 -0.001332 0.090051 -vn 1.607614 -0.008439 2.763814 -v 0.035494 -0.001308 0.090254 -vn 1.140040 -0.008956 2.983187 -v 0.035717 -0.001316 0.090148 -vn 1.997512 -0.001630 2.563858 -v 0.035292 -0.001301 0.090396 -vn 2.207201 -0.001761 2.402324 -v 0.035263 -0.001299 0.090421 -vn 2.440743 -0.003302 2.084738 -v 0.035116 -0.001293 0.090568 -vn 2.960092 -0.002659 1.191309 -v 0.034859 -0.001277 0.090988 -vn 2.721367 -0.006102 1.662609 -v 0.034970 -0.001285 0.090767 -vn 3.117323 0.000153 0.732515 -v 0.034786 -0.001269 0.091223 -vn 3.230363 -0.002181 0.390146 -v 0.034758 -0.001264 0.091394 -vn 3.232269 -0.002904 0.093525 -v 0.034752 -0.001261 0.091467 -vn 3.184017 0.001479 -0.323050 -v 0.034759 -0.001253 0.091714 -vn 3.176446 -0.000934 -0.662679 -v 0.034787 -0.001248 0.091883 -vn 3.107081 0.000638 -0.950712 -v 0.034806 -0.001246 0.091956 -vn 2.891395 -0.000715 -1.369125 -v 0.034892 -0.001238 0.092187 -vn 2.659417 0.023656 -1.762661 -v 0.035015 -0.001230 0.092401 -vn 2.538839 0.008474 -2.001130 -v 0.035066 -0.001227 0.092471 -vn 2.288759 0.003488 -2.259784 -v 0.035171 -0.001222 0.092592 -vn 1.984898 -0.002273 -2.551457 -v 0.035356 -0.001214 0.092755 -vn 1.745173 0.002790 -2.726714 -v 0.035425 -0.001211 0.092803 -vn 1.463615 0.010670 -2.871830 -v 0.035566 -0.001206 0.092885 -vn 1.201498 0.010038 -3.008970 -v 0.035717 -0.001201 0.092952 -vn 0.975815 0.008551 -3.112463 -v 0.035794 -0.001198 0.092979 -vn 0.787220 0.020159 -3.127420 -v 0.035874 -0.001196 0.093002 -vn 0.424280 -0.003057 -3.185898 -v 0.036034 -0.001191 0.093034 -vn -0.059716 0.001144 -3.203342 -v 0.036280 -0.001183 0.093050 -vn -0.590298 0.001509 -3.157617 -v 0.036526 -0.001175 0.093024 -vn -1.098554 0.000544 -3.004447 -v 0.036763 -0.001167 0.092959 -vn -1.578433 0.005278 -2.768984 -v 0.036987 -0.001159 0.092856 -vn -1.989792 -0.004136 -2.484857 -v 0.037191 -0.001151 0.092718 -vn -2.946153 -0.004307 -1.244078 -v 0.037633 -0.001128 0.092132 -vn -2.693134 -0.004731 -1.701254 -v 0.037518 -0.001136 0.092351 -vn -3.103787 -0.008453 -0.742427 -v 0.037709 -0.001120 0.091898 -vn -3.231032 -0.005613 -0.393044 -v 0.037744 -0.001113 0.091689 -vn -3.239284 -0.004058 -0.114940 -v 0.037746 -0.001112 0.091654 -vn -3.164086 0.002189 0.310107 -v 0.037743 -0.001104 0.091407 -vn -3.062419 0.006663 0.823331 -v 0.037700 -0.001096 0.091164 -vn -2.932355 0.004676 1.287785 -v 0.037617 -0.001088 0.090932 -vn -2.809092 -0.000560 1.635254 -v 0.037531 -0.001083 0.090770 -vn -2.649879 -0.003948 1.875206 -v 0.037497 -0.001080 0.090716 -vn -1.949004 0.006537 2.514994 -v 0.037161 -0.001065 0.090358 -vn -2.309530 -0.003210 2.189484 -v 0.037344 -0.001073 0.090523 -vn -1.496861 0.002657 2.834322 -v 0.036953 -0.001057 0.090225 -vn -0.987113 -0.007683 3.006555 -v 0.036726 -0.001049 0.090128 -vn -0.519153 -0.000346 3.150076 -v 0.036487 -0.001041 0.090069 -vn 0.026172 -0.000421 3.190776 -v 0.036241 -0.001033 0.090050 -vn 0.536507 -0.000320 3.161330 -v 0.035995 -0.001025 0.090072 -vn 1.055380 0.003537 3.027713 -v 0.035756 -0.001018 0.090134 -vn 1.542532 -0.002860 2.802058 -v 0.035531 -0.001010 0.090234 -vn 2.348457 -0.001404 2.164049 -v 0.035144 -0.000994 0.090537 -vn 1.962512 -0.002603 2.507297 -v 0.035325 -0.001002 0.090369 -vn 3.078317 0.030890 0.850864 -v 0.034796 -0.000970 0.091182 -vn 3.010646 -0.020774 1.180347 -v 0.034876 -0.000978 0.090949 -vn 2.916675 -0.000699 1.442545 -v 0.034883 -0.000979 0.090932 -vn 2.679907 -0.007553 1.734563 -v 0.034993 -0.000986 0.090732 -vn 3.180768 0.011446 0.631247 -v 0.034782 -0.000968 0.091243 -vn 3.216225 0.009669 0.239087 -v 0.034755 -0.000963 0.091425 -vn 3.197818 0.017839 -0.259760 -v 0.034755 -0.000955 0.091672 -vn 3.081379 0.002838 -0.784696 -v 0.034795 -0.000947 0.091915 -vn 2.908582 -0.019025 -1.235469 -v 0.034875 -0.000939 0.092149 -vn 2.664739 -0.008218 -1.727229 -v 0.034991 -0.000931 0.092366 -vn 2.357842 -0.001850 -2.153834 -v 0.035142 -0.000923 0.092561 -vn 1.947308 -0.017606 -2.507710 -v 0.035323 -0.000915 0.092729 -vn 1.538771 0.022083 -2.836285 -v 0.035528 -0.000908 0.092865 -vn -3.457508 2.280285 3.482062 -v 0.035292 -0.000988 0.094157 -vn -0.540123 2.280238 4.877291 -v 0.034822 -0.000988 0.093932 -vn -4.240869 2.280295 2.468564 -v 0.034650 -0.000988 0.093821 -vn -2.153618 0.884660 3.308812 -v 0.034680 -0.001088 0.093962 -vn -1.784077 2.280293 4.571245 -v 0.034254 -0.000988 0.093481 -vn -4.735357 2.280289 1.286804 -v 0.034117 -0.000988 0.093329 -vn -2.936537 0.884655 2.638619 -v 0.034109 -0.001088 0.093473 -vn -2.906340 2.280283 3.953775 -v 0.033822 -0.000988 0.092899 -vn -4.906975 2.280315 0.017361 -v 0.033729 -0.000988 0.092716 -vn -3.519410 0.884667 1.788720 -v 0.033684 -0.001088 0.092854 -vn -3.830732 2.280288 3.066782 -v 0.033556 -0.000988 0.092224 -vn -4.744345 2.280278 -1.253287 -v 0.033513 -0.000988 0.092024 -vn -3.862386 0.884668 0.816842 -v 0.033434 -0.001088 0.092145 -vn -4.493900 2.280290 1.970851 -v 0.033473 -0.000988 0.091504 -vn -4.258316 2.280315 -2.438517 -v 0.033484 -0.000988 0.091300 -vn -3.942111 0.884661 -0.210704 -v 0.033376 -0.001088 0.091396 -vn -4.850930 2.280299 0.740558 -v 0.033579 -0.000988 0.090787 -vn -3.482054 2.280317 -3.457486 -v 0.033643 -0.000988 0.090592 -vn -3.753324 0.884658 -1.223695 -v 0.033514 -0.001088 0.090658 -vn -4.877256 2.280283 -0.540137 -v 0.033868 -0.000988 0.090122 -vn -2.468551 2.280265 -4.240957 -v 0.033979 -0.000988 0.089950 -vn -3.308743 0.884661 -2.153534 -v 0.033838 -0.001088 0.089980 -vn -4.571286 2.280293 -1.784136 -v 0.034319 -0.000988 0.089554 -vn -1.286760 2.280273 -4.735317 -v 0.034471 -0.000988 0.089417 -vn -2.638682 0.884657 -2.936465 -v 0.034327 -0.001088 0.089409 -vn -3.953761 2.280292 -2.906413 -v 0.034901 -0.000988 0.089122 -vn -0.017384 2.280284 -4.907032 -v 0.035084 -0.000988 0.089029 -vn -1.788737 0.884651 -3.519375 -v 0.034946 -0.001088 0.088984 -vn -3.066792 2.280267 -3.830693 -v 0.035576 -0.000988 0.088856 -vn 1.253249 2.280267 -4.744357 -v 0.035776 -0.000988 0.088813 -vn -0.816873 0.884663 -3.862474 -v 0.035655 -0.001088 0.088734 -vn -1.970813 2.280260 -4.493972 -v 0.036296 -0.000988 0.088773 -vn 2.438509 2.280229 -4.258362 -v 0.036500 -0.000988 0.088784 -vn 0.210618 0.884660 -3.942245 -v 0.036404 -0.001088 0.088676 -vn -0.740548 2.280287 -4.850940 -v 0.037013 -0.000988 0.088879 -vn 3.457573 2.280252 -3.482118 -v 0.037208 -0.000988 0.088943 -vn 1.223706 0.884666 -3.753285 -v 0.037142 -0.001088 0.088814 -vn 0.540058 2.280302 -4.877148 -v 0.037678 -0.000988 0.089168 -vn 4.240998 2.280269 -2.468553 -v 0.037850 -0.000988 0.089279 -vn 2.153601 0.884657 -3.308770 -v 0.037820 -0.001088 0.089138 -vn 1.783976 2.280255 -4.571203 -v 0.038246 -0.000988 0.089619 -vn 4.735372 2.280254 -1.286774 -v 0.038383 -0.000988 0.089771 -vn 2.936700 0.884673 -2.638691 -v 0.038391 -0.001088 0.089627 -vn 2.906488 2.280282 -3.953740 -v 0.038678 -0.000988 0.090201 -vn 4.906974 2.280285 -0.017369 -v 0.038771 -0.000988 0.090384 -vn 3.519470 0.884659 -1.788781 -v 0.038816 -0.001088 0.090246 -vn 3.830588 2.280282 -3.066823 -v 0.038944 -0.000988 0.090876 -vn 4.744308 2.280285 1.253278 -v 0.038987 -0.000988 0.091076 -vn 3.862473 0.884661 -0.816871 -v 0.039066 -0.001088 0.090955 -vn 4.493853 2.280269 -1.970843 -v 0.039027 -0.000988 0.091596 -vn 4.258293 2.280271 2.438476 -v 0.039016 -0.000988 0.091800 -vn 3.942369 0.884665 0.210664 -v 0.039124 -0.001088 0.091704 -vn 4.850833 2.280279 -0.740604 -v 0.038921 -0.000988 0.092313 -vn 3.482064 2.280279 3.457521 -v 0.038857 -0.000988 0.092508 -vn 3.753441 0.884655 1.223807 -v 0.038986 -0.001088 0.092442 -vn 4.877239 2.280293 0.540138 -v 0.038632 -0.000988 0.092978 -vn 2.468515 2.280307 4.240928 -v 0.038521 -0.000988 0.093150 -vn 3.308743 0.884661 2.153534 -v 0.038662 -0.001088 0.093120 -vn 4.571232 2.280310 1.783976 -v 0.038181 -0.000988 0.093546 -vn 1.286762 2.280293 4.735292 -v 0.038029 -0.000988 0.093683 -vn 2.638688 0.884655 2.936547 -v 0.038173 -0.001088 0.093691 -vn 3.953755 2.280295 2.906408 -v 0.037599 -0.000988 0.093978 -vn 0.017334 2.280279 4.907001 -v 0.037416 -0.000988 0.094071 -vn 1.788733 0.884648 3.519374 -v 0.037554 -0.001088 0.094116 -vn 3.066807 2.280280 3.830683 -v 0.036924 -0.000988 0.094244 -vn -1.253280 2.280254 4.744326 -v 0.036724 -0.000988 0.094287 -vn 0.816901 0.884648 3.862421 -v 0.036845 -0.001088 0.094366 -vn 4.733181 2.795762 -1.072307 -v 0.034975 -0.008274 0.091803 -vn 3.098537 2.978721 -0.424229 -v 0.034965 -0.008390 0.091748 -vn 4.804084 3.146944 -0.193187 -v 0.034951 -0.008281 0.091608 -vn 4.830330 2.964398 0.188443 -v 0.034957 -0.008289 0.091411 -vn 3.084682 3.007485 0.489083 -v 0.034967 -0.008390 0.091339 -vn 4.784028 2.715336 0.737717 -v 0.034967 -0.008291 0.091339 -vn 4.047109 3.110551 2.616582 -v 0.035150 -0.008310 0.090858 -vn 4.340415 2.707571 2.170591 -v 0.035096 -0.008306 0.090951 -vn 2.780231 3.024577 1.428842 -v 0.035096 -0.008390 0.090951 -vn 4.531651 3.057253 1.630688 -v 0.035058 -0.008303 0.091032 -vn 4.654278 3.117795 1.285020 -v 0.034993 -0.008296 0.091218 -vn 3.827360 3.161901 2.939630 -v 0.035267 -0.008318 0.090700 -vn 2.199770 3.037262 2.224405 -v 0.035339 -0.008390 0.090623 -vn 3.490382 2.706584 3.372483 -v 0.035339 -0.008322 0.090623 -vn 1.803843 3.100583 4.461771 -v 0.035740 -0.008339 0.090354 -vn 2.276325 2.713141 4.276071 -v 0.035672 -0.008337 0.090386 -vn 1.404747 3.046217 2.797863 -v 0.035672 -0.008390 0.090386 -vn 2.748719 3.351251 3.900857 -v 0.035565 -0.008332 0.090445 -vn 3.056336 3.098762 3.731629 -v 0.035406 -0.008325 0.090561 -vn 1.404456 3.624762 4.481182 -v 0.035926 -0.008347 0.090291 -vn 0.476880 3.052739 3.096332 -v 0.036062 -0.008390 0.090264 -vn 0.868569 2.716932 4.759465 -v 0.036062 -0.008352 0.090264 -vn -1.103334 3.148358 4.687159 -v 0.036512 -0.008368 0.090277 -vn -0.616558 2.715775 4.800309 -v 0.036471 -0.008367 0.090269 -vn -0.490477 3.058021 3.096330 -v 0.036471 -0.008390 0.090269 -vn -0.030792 4.089643 4.498663 -v 0.036317 -0.008361 0.090252 -vn 0.379914 3.113166 4.789281 -v 0.036120 -0.008354 0.090257 -vn -2.373411 3.437099 4.119287 -v 0.036880 -0.008383 0.090413 -vn -1.363005 2.616939 2.779419 -v 0.036857 -0.008390 0.090401 -vn -1.256821 4.950204 3.621135 -v 0.036731 -0.008377 0.090342 -vn -1.149645 4.919306 3.695599 -v 0.036701 -0.008376 0.090331 -vn 0.759021 -0.001554 3.128776 -v 0.035894 -0.001922 0.090093 -vn 2.947836 -0.001452 1.257286 -v 0.034873 -0.002178 0.090956 -vn -3.195388 -0.002666 -0.270184 -v 0.037744 -0.002313 0.091679 -vn 0.208584 0.000426 -3.191955 -v 0.036150 -0.002387 0.093047 -vn 1.877711 0.001006 -2.582576 -v 0.035365 -0.002414 0.092761 -vn 1.516947 0.000804 -2.822184 -v 0.035544 -0.002407 0.092873 -vn -1.654040 -0.006937 2.797837 -v 0.037021 -0.002559 0.090263 -vn -1.853914 -0.009388 2.646008 -v 0.037088 -0.002562 0.090306 -vn -3.241610 -0.004953 -0.253681 -v 0.037744 -0.002613 0.091680 -vn -2.426065 -0.001477 -2.096160 -v 0.037384 -0.002643 0.092532 -vn 3.212583 -0.005447 0.292675 -v 0.034759 -0.002764 0.091384 -vn -2.991987 0.010043 -1.076365 -v 0.037657 -0.002926 0.092071 -vn -1.916829 -0.001318 -2.556167 -v 0.037160 -0.002952 0.092743 -vn -2.283348 -0.005097 -2.259125 -v 0.037319 -0.002946 0.092603 -vn -2.569119 0.002259 -1.978829 -v 0.037456 -0.002939 0.092442 -vn -2.723478 0.000754 -1.764293 -v 0.037496 -0.002937 0.092385 -vn -2.826084 0.004991 -1.517261 -v 0.037569 -0.002932 0.092263 -vn -1.158538 -0.006421 2.994286 -v 0.036798 -0.002851 0.090154 -vn -1.589966 -0.000513 2.791142 -v 0.036989 -0.002858 0.090245 -vn -1.954762 0.003818 2.542127 -v 0.037165 -0.002865 0.090361 -vn -2.298273 -0.002833 2.236871 -v 0.037323 -0.002872 0.090502 -vn -2.580466 -0.003091 1.895648 -v 0.037460 -0.002878 0.090663 -vn -2.828351 -0.005247 1.519230 -v 0.037572 -0.002885 0.090842 -vn -3.013125 0.000367 1.097084 -v 0.037659 -0.002892 0.091035 -vn -3.121901 -0.012993 0.694274 -v 0.037717 -0.002899 0.091238 -vn -3.218046 -0.003020 0.433816 -v 0.037738 -0.002903 0.091364 -vn -3.257581 -0.004428 0.226342 -v 0.037746 -0.002905 0.091447 -vn -3.245929 -0.004925 0.008000 -v 0.037750 -0.002908 0.091527 -vn -3.199228 -0.009156 -0.245092 -v 0.037746 -0.002912 0.091659 -vn -3.108554 -0.006596 -0.703886 -v 0.037716 -0.002919 0.091868 -vn -0.756472 -0.012547 3.097296 -v 0.036596 -0.002845 0.090091 -vn -0.354485 -0.004630 3.226210 -v 0.036388 -0.002838 0.090056 -vn -0.109396 -0.001711 3.256960 -v 0.036313 -0.002836 0.090051 -vn 0.192172 0.003667 3.217095 -v 0.036176 -0.002831 0.090052 -vn 0.608195 -0.001366 3.152115 -v 0.035967 -0.002825 0.090077 -vn 1.037864 -0.003588 3.037667 -v 0.035762 -0.002818 0.090132 -vn 1.441967 -0.000535 2.901835 -v 0.035568 -0.002811 0.090214 -vn 1.681747 -0.003714 2.791199 -v 0.035471 -0.002808 0.090268 -vn 1.905472 0.001103 2.620004 -v 0.035387 -0.002804 0.090323 -vn 2.205658 0.000710 2.347983 -v 0.035223 -0.002798 0.090457 -vn 2.507330 0.008373 1.983954 -v 0.035080 -0.002791 0.090612 -vn 2.748547 0.003162 1.626375 -v 0.034959 -0.002784 0.090786 -vn 2.959946 0.009254 1.333783 -v 0.034865 -0.002777 0.090975 -vn 3.070693 -0.003228 1.104467 -v 0.034851 -0.002776 0.091010 -vn 3.124929 -0.001537 0.833725 -v 0.034798 -0.002771 0.091175 -vn 3.199224 -0.009729 0.550020 -v 0.034771 -0.002767 0.091302 -vn 2.787949 -0.003982 -1.686539 -v 0.034977 -0.002732 0.092343 -vn 2.915993 -0.002029 -1.413372 -v 0.034901 -0.002737 0.092206 -vn 3.043721 0.000298 -1.179084 -v 0.034844 -0.002742 0.092072 -vn 3.115698 0.003375 -0.931825 -v 0.034822 -0.002744 0.092010 -vn 3.165179 0.001559 -0.542539 -v 0.034772 -0.002750 0.091805 -vn 3.189698 -0.004708 -0.075623 -v 0.034751 -0.002757 0.091594 -vn 2.281811 -0.004245 -2.320081 -v 0.035179 -0.002722 0.092600 -vn 2.457226 -0.000130 -2.123496 -v 0.035137 -0.002724 0.092556 -vn 2.653337 -0.001999 -1.875850 -v 0.035007 -0.002730 0.092390 -vn 0.888470 0.013419 -3.084768 -v 0.035848 -0.002697 0.092995 -vn 1.254938 0.005555 -2.983132 -v 0.035648 -0.002703 0.092924 -vn 1.483372 0.009352 -2.896079 -v 0.035575 -0.002706 0.092889 -vn 1.721232 0.003018 -2.729122 -v 0.035461 -0.002710 0.092826 -vn 2.048425 -0.013115 -2.467244 -v 0.035290 -0.002717 0.092702 -vn -0.489725 -0.002975 -3.183106 -v 0.036477 -0.002676 0.093033 -vn -0.057420 -0.000628 -3.224226 -v 0.036266 -0.002683 0.093050 -vn 0.272488 0.001188 -3.249965 -v 0.036103 -0.002688 0.093043 -vn 0.453157 0.003843 -3.242350 -v 0.036055 -0.002690 0.093037 -vn 0.675549 0.005944 -3.177152 -v 0.035942 -0.002694 0.093018 -vn -0.933611 0.006395 -3.051779 -v 0.036682 -0.002670 0.092986 -vn -1.335742 0.003969 -2.917581 -v 0.036880 -0.002663 0.092911 -vn -1.752155 0.005463 -2.683619 -v 0.037065 -0.002656 0.092809 -vn -2.096342 0.001110 -2.420476 -v 0.037234 -0.002649 0.092682 -vn -2.921904 0.004009 -1.350594 -v 0.037612 -0.002629 0.092178 -vn -2.678843 -0.006905 -1.743057 -v 0.037510 -0.002636 0.092364 -vn -3.083921 0.000517 -0.958345 -v 0.037687 -0.002623 0.091980 -vn -3.236968 -0.001256 -0.485652 -v 0.037733 -0.002616 0.091774 -vn -3.191262 0.000478 -0.662055 -v 0.037721 -0.002618 0.091843 -vn -2.889005 -0.002503 1.476423 -v 0.037595 -0.002587 0.090885 -vn -2.979280 0.006116 1.254845 -v 0.037623 -0.002589 0.090946 -vn -3.101424 0.002246 0.868218 -v 0.037694 -0.002596 0.091145 -vn -3.189780 -0.000077 0.423771 -v 0.037737 -0.002602 0.091353 -vn -3.205872 -0.013667 -0.009135 -v 0.037750 -0.002609 0.091563 -vn -2.139501 -0.008914 2.389584 -v 0.037254 -0.002569 0.090436 -vn -2.463677 0.001247 2.064009 -v 0.037401 -0.002575 0.090588 -vn -2.713887 -0.017336 1.688559 -v 0.037525 -0.002582 0.090760 -vn -1.375739 -0.000917 2.924622 -v 0.036904 -0.002555 0.090200 -vn -0.959547 0.007246 3.040623 -v 0.036708 -0.002548 0.090122 -vn -0.553611 0.003435 3.161587 -v 0.036503 -0.002542 0.090071 -vn -0.186759 0.001062 3.263862 -v 0.036292 -0.002535 0.090051 -vn 0.037210 0.000201 3.260851 -v 0.036277 -0.002534 0.090050 -vn 0.812215 0.000615 3.096230 -v 0.035873 -0.002521 0.090098 -vn 0.364943 -0.004652 3.189756 -v 0.036081 -0.002528 0.090060 -vn 1.214132 -0.006837 2.959783 -v 0.035673 -0.002515 0.090165 -vn 1.645310 0.001237 2.768501 -v 0.035484 -0.002508 0.090260 -vn 1.982467 -0.000034 2.566409 -v 0.035310 -0.002501 0.090381 -vn 2.199471 0.002817 2.407352 -v 0.035249 -0.002499 0.090433 -vn 2.379424 0.002097 2.192695 -v 0.035156 -0.002495 0.090524 -vn 2.626836 -0.000002 1.875975 -v 0.035022 -0.002488 0.090689 -vn 2.826569 0.001791 1.629889 -v 0.034943 -0.002483 0.090814 -vn 2.924793 -0.001599 1.417925 -v 0.034913 -0.002481 0.090869 -vn 3.021561 0.013659 1.056974 -v 0.034831 -0.002474 0.091064 -vn 3.140213 0.005755 0.835327 -v 0.034797 -0.002471 0.091176 -vn 2.528718 0.015029 -1.943662 -v 0.035063 -0.002427 0.092467 -vn 2.758606 0.014755 -1.593831 -v 0.034946 -0.002434 0.092291 -vn 2.989866 0.002530 -1.168312 -v 0.034854 -0.002441 0.092100 -vn 3.108295 0.009766 -0.754273 -v 0.034791 -0.002447 0.091898 -vn 3.226744 0.000294 -0.381576 -v 0.034757 -0.002454 0.091690 -vn 3.256105 -0.004316 -0.131292 -v 0.034753 -0.002456 0.091639 -vn 3.225796 -0.005128 0.137059 -v 0.034752 -0.002461 0.091478 -vn 3.238972 -0.000853 0.430037 -v 0.034765 -0.002465 0.091337 -vn 3.213152 0.004006 0.624831 -v 0.034777 -0.002468 0.091269 -vn 2.201754 -0.004932 -2.402483 -v 0.035204 -0.002420 0.092625 -vn 2.377983 0.003715 -2.233256 -v 0.035186 -0.002421 0.092608 -vn 1.085377 -0.000485 -3.009519 -v 0.035737 -0.002400 0.092960 -vn 0.670902 -0.003946 -3.125024 -v 0.035940 -0.002394 0.093018 -vn -1.576467 -0.000380 -2.833767 -v 0.036965 -0.002360 0.092868 -vn -1.331326 -0.000611 -2.981901 -v 0.036854 -0.002364 0.092923 -vn -1.134566 -0.000917 -3.056818 -v 0.036773 -0.002367 0.092956 -vn -0.948290 -0.001187 -3.103101 -v 0.036700 -0.002369 0.092981 -vn -0.664383 -0.009699 -3.155363 -v 0.036570 -0.002373 0.093015 -vn -0.215990 -0.011129 -3.182753 -v 0.036361 -0.002380 0.093046 -vn -1.919308 -0.001349 -2.582905 -v 0.037144 -0.002353 0.092755 -vn -2.255273 0.001599 -2.321612 -v 0.037304 -0.002346 0.092617 -vn -2.487381 0.001201 -2.119278 -v 0.037403 -0.002342 0.092509 -vn -2.609654 -0.000008 -1.954150 -v 0.037443 -0.002340 0.092459 -vn -2.708971 -0.005905 -1.797925 -v 0.037501 -0.002337 0.092377 -vn -2.845367 0.002525 -1.620900 -v 0.037560 -0.002333 0.092281 -vn -2.929469 0.001168 -1.449878 -v 0.037584 -0.002331 0.092236 -vn -3.016521 -0.001543 -1.135187 -v 0.037649 -0.002326 0.092090 -vn -3.125701 -0.005109 -0.721226 -v 0.037711 -0.002319 0.091888 -vn -3.146673 0.001829 0.628477 -v 0.037721 -0.002299 0.091258 -vn -3.201977 -0.005240 0.167689 -v 0.037748 -0.002306 0.091468 -vn -2.328282 0.002985 2.205927 -v 0.037338 -0.002272 0.090517 -vn -2.605767 -0.000834 1.852550 -v 0.037472 -0.002279 0.090680 -vn -2.839020 -0.003207 1.472272 -v 0.037582 -0.002286 0.090860 -vn -3.022251 -0.000884 1.057721 -v 0.037666 -0.002293 0.091055 -vn -1.995121 0.005656 2.512106 -v 0.037181 -0.002266 0.090374 -vn -1.681488 0.025767 2.736524 -v 0.037007 -0.002259 0.090255 -vn -1.553655 0.010140 2.860107 -v 0.036989 -0.002258 0.090245 -vn -1.269518 -0.008911 2.988380 -v 0.036817 -0.002252 0.090161 -vn -1.041485 -0.010091 3.071203 -v 0.036749 -0.002250 0.090135 -vn -0.769964 -0.010726 3.107678 -v 0.036616 -0.002245 0.090095 -vn -0.330357 -0.007244 3.194143 -v 0.036409 -0.002239 0.090058 -vn 0.110911 -0.001022 3.200979 -v 0.036197 -0.002232 0.090051 -vn 0.508957 0.008206 3.201946 -v 0.035987 -0.002225 0.090073 -vn 0.770731 0.001356 3.174986 -v 0.035903 -0.002222 0.090091 -vn 1.044278 0.001969 3.063178 -v 0.035782 -0.002218 0.090125 -vn 1.432886 -0.001908 2.885568 -v 0.035586 -0.002212 0.090205 -vn 1.803839 0.004155 2.623585 -v 0.035404 -0.002205 0.090311 -vn 2.154168 -0.000784 2.366606 -v 0.035238 -0.002198 0.090443 -vn 2.478705 -0.003085 2.041188 -v 0.035092 -0.002192 0.090596 -vn 2.735541 -0.003144 1.675523 -v 0.034970 -0.002185 0.090768 -vn 3.180995 -0.001655 0.391932 -v 0.034762 -0.002165 0.091363 -vn 3.076247 -0.002859 0.852532 -v 0.034803 -0.002171 0.091155 -vn 3.187917 -0.012670 -0.029832 -v 0.034750 -0.002158 0.091574 -vn 3.167335 0.016541 -0.491739 -v 0.034768 -0.002151 0.091784 -vn 3.149210 0.008726 -0.787187 -v 0.034800 -0.002146 0.091935 -vn 3.112750 0.004658 -0.976063 -v 0.034816 -0.002144 0.091991 -vn 3.039528 0.001654 -1.174545 -v 0.034851 -0.002141 0.092091 -vn 2.910049 -0.007231 -1.416803 -v 0.034892 -0.002138 0.092187 -vn 2.691866 -0.004653 -1.759129 -v 0.034995 -0.002131 0.092372 -vn 2.418899 0.000456 -2.126633 -v 0.035124 -0.002124 0.092541 -vn 2.067689 0.000410 -2.436057 -v 0.035274 -0.002117 0.092689 -vn 1.733477 -0.000120 -2.700496 -v 0.035444 -0.002111 0.092815 -vn 1.317014 -0.007450 -2.925128 -v 0.035629 -0.002104 0.092916 -vn 0.906539 0.002539 -3.074748 -v 0.035827 -0.002097 0.092989 -vn 0.467210 -0.000527 -3.184813 -v 0.036034 -0.002090 0.093034 -vn 0.012881 -0.001585 -3.221156 -v 0.036245 -0.002084 0.093050 -vn -0.449509 -0.001743 -3.185834 -v 0.036456 -0.002077 0.093036 -vn -0.879851 -0.001203 -3.065079 -v 0.036663 -0.002070 0.092992 -vn -1.694676 0.006137 -2.721947 -v 0.037048 -0.002057 0.092820 -vn -1.304972 -0.000785 -2.922652 -v 0.036861 -0.002064 0.092920 -vn -2.078426 0.002758 -2.458843 -v 0.037218 -0.002050 0.092696 -vn -2.405615 -0.001030 -2.144051 -v 0.037370 -0.002043 0.092548 -vn -2.680357 0.000576 -1.781552 -v 0.037499 -0.002037 0.092381 -vn -2.906189 -0.000679 -1.384068 -v 0.037603 -0.002030 0.092197 -vn -3.056501 -0.010084 -0.969891 -v 0.037681 -0.002023 0.092000 -vn -3.172410 -0.000745 -0.521665 -v 0.037730 -0.002016 0.091795 -vn -3.197350 -0.001080 -0.068835 -v 0.037750 -0.002010 0.091584 -vn -3.183276 -0.006924 0.366597 -v 0.037739 -0.002003 0.091373 -vn -2.963789 -0.001507 1.251289 -v 0.037631 -0.001989 0.090965 -vn -3.104460 -0.007879 0.826994 -v 0.037700 -0.001996 0.091166 -vn -2.742908 0.005256 1.662009 -v 0.037536 -0.001983 0.090777 -vn -1.828613 -0.003149 2.634907 -v 0.037105 -0.001963 0.090318 -vn -2.174775 -0.002588 2.351943 -v 0.037269 -0.001969 0.090450 -vn -2.487413 0.003237 2.013890 -v 0.037414 -0.001976 0.090604 -vn -1.444510 -0.004176 2.857974 -v 0.036923 -0.001956 0.090209 -vn -1.077681 0.022830 3.028557 -v 0.036728 -0.001949 0.090128 -vn -0.884625 0.014309 3.119841 -v 0.036678 -0.001947 0.090112 -vn -0.608608 0.010023 3.176768 -v 0.036524 -0.001942 0.090075 -vn -0.314192 0.000231 3.246298 -v 0.036382 -0.001938 0.090056 -vn -0.074267 -0.002239 3.242440 -v 0.036313 -0.001936 0.090051 -vn 0.316442 -0.004555 3.192634 -v 0.036102 -0.001929 0.090057 -vn 2.317281 0.002244 2.251859 -v 0.035170 -0.001895 0.090509 -vn 2.066077 0.003172 2.516599 -v 0.035327 -0.001902 0.090368 -vn 1.877604 -0.003796 2.665727 -v 0.035360 -0.001903 0.090343 -vn 1.649096 -0.009499 2.787560 -v 0.035502 -0.001909 0.090250 -vn 1.409760 -0.002648 2.919038 -v 0.035585 -0.001912 0.090205 -vn 1.179267 0.001206 2.975665 -v 0.035692 -0.001915 0.090158 -vn 3.133080 0.000133 -0.746839 -v 0.034783 -0.003949 0.091863 -vn -1.665871 -0.005420 -2.818371 -v 0.036993 -0.003859 0.092853 -vn -3.175294 -0.010700 -0.590676 -v 0.037733 -0.003816 0.091774 -vn -3.056066 0.000289 -1.046479 -v 0.037655 -0.003826 0.092074 -vn -2.024624 -0.002163 -2.463371 -v 0.037217 -0.003550 0.092696 -vn -3.166578 0.001636 -0.716362 -v 0.037720 -0.003218 0.091847 -vn -0.911241 0.002251 3.116138 -v 0.036661 -0.003147 0.090107 -vn -1.252097 0.004212 2.966827 -v 0.036805 -0.003152 0.090157 -vn -0.346158 -0.016463 3.231971 -v 0.036439 -0.003140 0.090062 -vn -0.496928 -0.006997 3.236904 -v 0.036452 -0.003140 0.090064 -vn 3.252971 -0.006261 -0.384545 -v 0.034764 -0.003052 0.091754 -vn -1.465554 -0.001206 -2.882293 -v 0.036895 -0.002962 0.092904 -vn -0.729530 -0.000960 -3.206059 -v 0.036549 -0.002974 0.093020 -vn -0.962237 0.006489 -3.096656 -v 0.036703 -0.002969 0.092980 -vn -1.183805 0.006539 -3.038227 -v 0.036797 -0.002966 0.092947 -vn -0.566638 0.000040 -3.233562 -v 0.036544 -0.002974 0.093021 -vn -0.349353 0.000608 -3.253804 -v 0.036382 -0.002979 0.093044 -vn -0.154475 -0.002096 -3.266216 -v 0.036343 -0.002981 0.093047 -vn 0.019050 -0.005902 -3.272888 -v 0.036218 -0.002985 0.093050 -vn 0.209608 -0.000707 -3.266467 -v 0.036184 -0.002986 0.093049 -vn 0.493246 -0.000499 -3.211459 -v 0.036016 -0.002991 0.093032 -vn 0.888215 -0.003657 -3.129904 -v 0.035856 -0.002996 0.092997 -vn 0.768785 -0.001104 -3.163750 -v 0.035878 -0.002996 0.093003 -vn 1.085757 0.004048 -3.088445 -v 0.035736 -0.003000 0.092959 -vn 1.246560 0.008197 -3.010614 -v 0.035700 -0.003002 0.092946 -vn 1.459779 0.001916 -2.937126 -v 0.035551 -0.003007 0.092877 -vn 1.599470 0.001261 -2.884364 -v 0.035538 -0.003007 0.092870 -vn 1.709687 -0.006433 -2.787922 -v 0.035464 -0.003010 0.092828 -vn 1.865730 0.009840 -2.624219 -v 0.035411 -0.003012 0.092793 -vn 2.153790 0.010997 -2.370006 -v 0.035240 -0.003019 0.092659 -vn 2.618078 -0.000951 -2.006119 -v 0.035055 -0.003028 0.092457 -vn 2.435993 0.008848 -2.120460 -v 0.035094 -0.003026 0.092506 -vn 2.684304 -0.000512 -1.916574 -v 0.035033 -0.003029 0.092427 -vn 2.741249 -0.008077 -1.795293 -v 0.034997 -0.003031 0.092374 -vn 2.801523 0.011302 -1.574605 -v 0.034963 -0.003033 0.092321 -vn 2.969687 0.002647 -1.305342 -v 0.034857 -0.003040 0.092107 -vn 3.090712 -0.001274 -1.156585 -v 0.034848 -0.003041 0.092083 -vn 3.116345 0.001060 -1.011283 -v 0.034827 -0.003043 0.092024 -vn 3.150988 0.001848 -0.792172 -v 0.034798 -0.003047 0.091927 -vn 3.220161 -0.008113 -0.538309 -v 0.034766 -0.003052 0.091766 -vn 3.229569 0.011771 -0.096651 -v 0.034751 -0.003057 0.091603 -vn 3.272663 0.006775 0.143940 -v 0.034754 -0.003062 0.091444 -vn 3.296432 -0.000141 0.276893 -v 0.034754 -0.003062 0.091439 -vn 3.254401 0.001082 0.397906 -v 0.034760 -0.003064 0.091376 -vn 3.194216 0.001403 0.617330 -v 0.034775 -0.003067 0.091277 -vn 3.124124 0.003431 0.893449 -v 0.034814 -0.003073 0.091118 -vn 3.074898 0.001801 1.053284 -v 0.034824 -0.003074 0.091085 -vn 2.932392 0.002247 1.357290 -v 0.034885 -0.003079 0.090929 -vn 2.683313 -0.000310 1.730811 -v 0.034978 -0.003085 0.090754 -vn 1.757820 0.000188 2.707619 -v 0.035453 -0.003107 0.090279 -vn 2.054474 -0.003884 2.463566 -v 0.035277 -0.003100 0.090408 -vn 2.351007 -0.003571 2.175214 -v 0.035169 -0.003095 0.090510 -vn 1.294919 0.004835 2.972879 -v 0.035638 -0.003114 0.090181 -vn 1.530498 0.006079 2.877265 -v 0.035547 -0.003110 0.090225 -vn 1.027368 -0.023111 3.039438 -v 0.035783 -0.003119 0.090124 -vn 0.864000 -0.011212 3.141406 -v 0.035852 -0.003121 0.090104 -vn 0.637575 -0.001999 3.195295 -v 0.035950 -0.003124 0.090080 -vn -0.085708 -0.000540 3.249464 -v 0.036276 -0.003134 0.090050 -vn 0.412676 -0.001611 3.258729 -v 0.036086 -0.003128 0.090059 -vn 0.269023 -0.009363 3.275135 -v 0.036112 -0.003129 0.090056 -vn 0.154918 -0.012519 3.251776 -v 0.036175 -0.003131 0.090052 -vn -0.735009 0.004578 3.156242 -v 0.036600 -0.003145 0.090092 -vn -1.685691 -0.015778 2.735319 -v 0.037080 -0.003162 0.090301 -vn -1.879482 -0.008622 2.680978 -v 0.037104 -0.003163 0.090317 -vn -2.029234 0.001632 2.553814 -v 0.037185 -0.003166 0.090377 -vn -2.152448 0.001454 2.431433 -v 0.037233 -0.003168 0.090417 -vn -2.355491 0.000257 2.245588 -v 0.037351 -0.003173 0.090531 -vn -2.437733 -0.008068 2.080023 -v 0.037358 -0.003173 0.090538 -vn -2.684132 0.015100 1.726590 -v 0.037533 -0.003183 0.090772 -vn -2.864057 0.011352 1.563018 -v 0.037569 -0.003185 0.090836 -vn -2.946124 -0.011975 1.288721 -v 0.037610 -0.003188 0.090918 -vn -3.072083 -0.004303 0.900707 -v 0.037688 -0.003195 0.091123 -vn -3.203552 0.004660 0.420110 -v 0.037741 -0.003204 0.091390 -vn -3.275953 0.003597 0.177172 -v 0.037749 -0.003206 0.091483 -vn -3.286575 0.007627 0.071094 -v 0.037750 -0.003207 0.091515 -vn -3.242694 0.009495 -0.099957 -v 0.037750 -0.003209 0.091553 -vn -3.195733 -0.017453 -0.483877 -v 0.037726 -0.003217 0.091816 -vn -3.072389 0.002210 -1.003354 -v 0.037669 -0.003224 0.092036 -vn -2.987586 0.000055 -1.305394 -v 0.037628 -0.003228 0.092144 -vn -2.881166 -0.000360 -1.552848 -v 0.037561 -0.003233 0.092278 -vn -2.749572 0.002363 -1.745340 -v 0.037530 -0.003235 0.092332 -vn -2.602616 0.024725 -1.904403 -v 0.037443 -0.003240 0.092459 -vn -2.543624 0.010603 -2.033009 -v 0.037437 -0.003240 0.092467 -vn -2.329270 0.000280 -2.247826 -v 0.037330 -0.003245 0.092591 -vn -2.128705 0.008230 -2.466877 -v 0.037210 -0.003250 0.092702 -vn -1.926176 0.005856 -2.584601 -v 0.037189 -0.003251 0.092720 -vn -1.488783 -0.012618 -2.831814 -v 0.036928 -0.003261 0.092888 -vn -1.187978 -0.023872 -2.978922 -v 0.036788 -0.003266 0.092950 -vn -0.962054 -0.001221 -3.118457 -v 0.036692 -0.003269 0.092983 -vn -0.758408 0.000488 -3.187726 -v 0.036584 -0.003273 0.093012 -vn -0.614973 -0.001294 -3.231067 -v 0.036533 -0.003275 0.093023 -vn -0.387972 0.001021 -3.215463 -v 0.036471 -0.003277 0.093034 -vn -0.057752 0.000121 -3.255389 -v 0.036221 -0.003285 0.093050 -vn 0.192827 0.004866 -3.257852 -v 0.036207 -0.003285 0.093049 -vn 0.471811 0.003306 -3.210381 -v 0.036006 -0.003291 0.093030 -vn 0.719233 -0.001302 -3.182112 -v 0.035913 -0.003294 0.093012 -vn 0.794568 -0.005628 -3.164415 -v 0.035883 -0.003295 0.093004 -vn 0.913669 -0.002821 -3.138124 -v 0.035845 -0.003297 0.092994 -vn 1.162789 0.003091 -3.010195 -v 0.035726 -0.003301 0.092956 -vn 1.379641 -0.029323 -2.908161 -v 0.035576 -0.003306 0.092890 -vn 1.487653 -0.010992 -2.945454 -v 0.035570 -0.003306 0.092887 -vn 1.606552 0.002745 -2.838036 -v 0.035542 -0.003307 0.092872 -vn 1.813964 0.001715 -2.666570 -v 0.035402 -0.003312 0.092787 -vn 2.077848 0.006559 -2.529856 -v 0.035272 -0.003318 0.092687 -vn 2.190767 0.004519 -2.459839 -v 0.035267 -0.003318 0.092683 -vn 2.291934 0.000582 -2.351624 -v 0.035198 -0.003321 0.092619 -vn 2.410620 -0.002772 -2.177843 -v 0.035154 -0.003323 0.092574 -vn 2.554325 0.009398 -2.013507 -v 0.035055 -0.003328 0.092457 -vn 2.609779 0.037846 -1.875502 -v 0.035048 -0.003328 0.092448 -vn 2.771078 0.004340 -1.648286 -v 0.034958 -0.003333 0.092312 -vn 2.955351 0.007193 -1.397800 -v 0.034882 -0.003338 0.092166 -vn 3.027409 0.005822 -1.246724 -v 0.034872 -0.003339 0.092142 -vn 3.093312 -0.000792 -1.017303 -v 0.034823 -0.003344 0.092014 -vn 3.153910 0.007020 -0.771381 -v 0.034795 -0.003347 0.091916 -vn 3.157807 0.016484 -0.456509 -v 0.034769 -0.003351 0.091790 -vn 3.224113 0.001517 0.069379 -v 0.034752 -0.003361 0.091481 -vn 3.002147 -0.004321 1.245486 -v 0.034874 -0.003378 0.090953 -vn 3.092227 -0.014853 1.028921 -v 0.034817 -0.003373 0.091107 -vn 3.148775 -0.009871 0.882053 -v 0.034813 -0.003372 0.091121 -vn 3.195970 0.000468 0.637560 -v 0.034777 -0.003368 0.091266 -vn 3.242112 -0.000674 0.394415 -v 0.034761 -0.003364 0.091366 -vn 2.319019 -0.005892 2.277986 -v 0.035165 -0.003395 0.090514 -vn 2.426056 -0.000642 2.170916 -v 0.035144 -0.003394 0.090537 -vn 2.582860 0.000674 1.938589 -v 0.035058 -0.003390 0.090639 -vn 2.938682 0.003933 1.441650 -v 0.034900 -0.003380 0.090896 -vn 2.849174 0.013773 1.603838 -v 0.034947 -0.003383 0.090807 -vn 2.728080 0.034993 1.686702 -v 0.034959 -0.003384 0.090786 -vn 2.085239 -0.001771 2.474341 -v 0.035285 -0.003400 0.090401 -vn 1.929215 -0.002687 2.637250 -v 0.035384 -0.003404 0.090325 -vn 1.859115 -0.000708 2.745914 -v 0.035416 -0.003405 0.090303 -vn 1.751224 0.000148 2.779032 -v 0.035421 -0.003406 0.090300 -vn 1.478645 -0.000327 2.880099 -v 0.035557 -0.003411 0.090220 -vn 1.063651 -0.005259 3.032634 -v 0.035749 -0.003417 0.090136 -vn 0.688485 -0.006947 3.165423 -v 0.035960 -0.003424 0.090078 -vn 0.448838 -0.000278 3.248432 -v 0.036050 -0.003427 0.090063 -vn 0.273100 -0.007739 3.260854 -v 0.036123 -0.003430 0.090055 -vn 0.056225 0.007529 3.209982 -v 0.036186 -0.003432 0.090051 -vn -0.272649 0.019120 3.209765 -v 0.036415 -0.003439 0.090059 -vn -0.476180 0.005338 3.221790 -v 0.036450 -0.003440 0.090063 -vn -0.746499 0.012296 3.156349 -v 0.036611 -0.003445 0.090094 -vn -0.921186 0.009006 3.133543 -v 0.036671 -0.003447 0.090110 -vn -1.094672 -0.000055 3.105736 -v 0.036768 -0.003450 0.090142 -vn -1.207890 -0.000265 3.044039 -v 0.036771 -0.003451 0.090143 -vn -1.441787 0.000372 2.906705 -v 0.036918 -0.003456 0.090207 -vn -1.684252 -0.000918 2.793391 -v 0.037049 -0.003460 0.090280 -vn -1.818159 -0.002457 2.716422 -v 0.037061 -0.003461 0.090288 -vn -2.016050 0.003091 2.542758 -v 0.037194 -0.003466 0.090384 -vn -2.157392 0.003207 2.444240 -v 0.037241 -0.003468 0.090424 -vn -2.312339 0.000877 2.344894 -v 0.037315 -0.003471 0.090494 -vn -2.403795 0.001812 2.212699 -v 0.037332 -0.003472 0.090511 -vn -2.518796 -0.001034 2.066245 -v 0.037424 -0.003477 0.090616 -vn -2.664648 0.002064 1.871644 -v 0.037462 -0.003479 0.090666 -vn -2.794391 0.004131 1.559024 -v 0.037551 -0.003484 0.090804 -vn -3.012527 0.002119 1.196345 -v 0.037662 -0.003492 0.091043 -vn -3.123551 -0.002881 0.950934 -v 0.037677 -0.003494 0.091087 -vn -3.156097 -0.000885 0.644100 -v 0.037717 -0.003499 0.091238 -vn -3.212694 0.003977 0.259307 -v 0.037746 -0.003505 0.091446 -vn -3.212873 0.008297 -0.070976 -v 0.037750 -0.003509 0.091564 -vn -3.198383 0.005011 -0.498526 -v 0.037727 -0.003517 0.091811 -vn -3.126313 0.006248 -0.800127 -v 0.037711 -0.003520 0.091889 -vn -3.053962 0.000762 -1.113282 -v 0.037642 -0.003527 0.092108 -vn -3.025114 -0.000009 -1.311901 -v 0.037629 -0.003528 0.092140 -vn -2.944626 -0.001690 -1.433099 -v 0.037603 -0.003530 0.092198 -vn -2.816421 -0.000811 -1.619047 -v 0.037556 -0.003533 0.092287 -vn -2.690353 -0.011250 -1.846177 -v 0.037468 -0.003538 0.092426 -vn -2.629093 -0.021755 -1.946229 -v 0.037465 -0.003539 0.092429 -vn -2.566737 -0.007956 -2.023088 -v 0.037430 -0.003540 0.092476 -vn -2.354958 -0.011780 -2.204021 -v 0.037365 -0.003544 0.092553 -vn -1.643751 -0.001870 -2.789499 -v 0.036961 -0.003560 0.092871 -vn -1.459555 -0.003545 -2.943239 -v 0.036928 -0.003561 0.092888 -vn -1.288565 0.002213 -3.008395 -v 0.036836 -0.003564 0.092931 -vn -1.079404 -0.013837 -3.036869 -v 0.036778 -0.003566 0.092954 -vn -0.837363 -0.008232 -3.129609 -v 0.036621 -0.003572 0.093003 -vn -0.614675 -0.002450 -3.216857 -v 0.036522 -0.003575 0.093025 -vn -0.386486 0.000937 -3.228924 -v 0.036460 -0.003577 0.093035 -vn -0.046116 -0.006130 -3.218110 -v 0.036258 -0.003583 0.093050 -vn 0.791819 0.007550 -3.171902 -v 0.035873 -0.003596 0.093002 -vn 0.597838 0.008538 -3.175178 -v 0.035949 -0.003593 0.093019 -vn 0.279364 0.002229 -3.174680 -v 0.036133 -0.003587 0.093045 -vn 0.992434 -0.000311 -3.092020 -v 0.035836 -0.003597 0.092992 -vn 1.322973 -0.002335 -2.954511 -v 0.035603 -0.003605 0.092903 -vn 1.587241 0.004452 -2.848703 -v 0.035532 -0.003607 0.092867 -vn 1.789941 0.006176 -2.699465 -v 0.035425 -0.003611 0.092803 -vn 2.087713 -0.000638 -2.442459 -v 0.035295 -0.003617 0.092707 -vn 2.920831 -0.002525 -1.413446 -v 0.034886 -0.003638 0.092174 -vn 2.990755 -0.004280 -1.264047 -v 0.034878 -0.003639 0.092156 -vn 2.760396 0.000513 -1.709727 -v 0.034985 -0.003632 0.092357 -vn 2.631999 0.011343 -1.930169 -v 0.035042 -0.003628 0.092439 -vn 2.448431 0.018544 -2.066431 -v 0.035077 -0.003626 0.092485 -vn 3.091597 -0.002271 -1.002371 -v 0.034820 -0.003644 0.092003 -vn 3.177816 -0.002001 -0.800449 -v 0.034793 -0.003647 0.091905 -vn 3.198658 0.002312 0.442555 -v 0.034763 -0.003665 0.091355 -vn 3.212787 0.000324 0.016094 -v 0.034750 -0.003660 0.091516 -vn 3.209335 0.001903 -0.474416 -v 0.034776 -0.003650 0.091826 -vn 3.232547 0.001629 -0.667335 -v 0.034779 -0.003649 0.091844 -vn 2.417463 0.001093 2.091057 -v 0.035120 -0.003693 0.090564 -vn 2.652906 0.001001 1.793688 -v 0.034985 -0.003686 0.090744 -vn 2.855045 -0.005486 1.523786 -v 0.034941 -0.003683 0.090818 -vn 3.020440 0.000665 1.180570 -v 0.034840 -0.003675 0.091037 -vn 3.109637 0.002692 0.980342 -v 0.034820 -0.003673 0.091096 -vn 3.140038 0.006071 0.794444 -v 0.034803 -0.003671 0.091155 -vn 2.071728 0.002933 2.448410 -v 0.035293 -0.003701 0.090395 -vn 1.915225 0.000725 2.639772 -v 0.035393 -0.003705 0.090319 -vn 1.764099 -0.000970 2.763687 -v 0.035425 -0.003706 0.090297 -vn 1.599910 -0.002921 2.852984 -v 0.035532 -0.003710 0.090233 -vn 1.459181 -0.001962 2.931942 -v 0.035567 -0.003711 0.090215 -vn 1.277848 0.004934 3.017030 -v 0.035681 -0.003715 0.090162 -vn 1.129909 0.006871 3.068975 -v 0.035714 -0.003716 0.090149 -vn 0.864038 0.001646 3.118329 -v 0.035835 -0.003720 0.090108 -vn 0.600562 -0.000110 3.213327 -v 0.036014 -0.003726 0.090069 -vn 0.400975 0.000627 3.252182 -v 0.036033 -0.003727 0.090066 -vn 0.148801 -0.000059 3.241143 -v 0.036196 -0.003732 0.090051 -vn -0.085329 0.000254 3.278763 -v 0.036297 -0.003735 0.090051 -vn -0.221541 -0.000645 3.282183 -v 0.036360 -0.003737 0.090054 -vn -0.336434 -0.002864 3.254566 -v 0.036378 -0.003738 0.090056 -vn -0.573772 0.000364 3.202560 -v 0.036523 -0.003742 0.090075 -vn -0.822823 0.018397 3.113535 -v 0.036622 -0.003746 0.090097 -vn -1.100571 0.010394 3.008308 -v 0.036736 -0.003749 0.090131 -vn -1.577037 -0.007485 2.781023 -v 0.037017 -0.003759 0.090261 -vn -1.872241 -0.005025 2.660301 -v 0.037121 -0.003763 0.090329 -vn -2.076434 0.014649 2.474689 -v 0.037202 -0.003766 0.090391 -vn -2.250882 0.006343 2.375720 -v 0.037306 -0.003771 0.090485 -vn -2.374757 -0.009806 2.268948 -v 0.037323 -0.003772 0.090501 -vn -2.412697 -0.019047 2.159013 -v 0.037365 -0.003774 0.090547 -vn -2.568589 -0.000594 1.984352 -v 0.037431 -0.003777 0.090625 -vn -2.736838 -0.009581 1.774922 -v 0.037524 -0.003782 0.090759 -vn -2.827787 -0.008794 1.648904 -v 0.037532 -0.003783 0.090772 -vn -2.916208 0.007404 1.367554 -v 0.037603 -0.003787 0.090903 -vn -3.051436 0.003417 1.176137 -v 0.037665 -0.003792 0.091052 -vn -3.127301 -0.005843 1.047861 -v 0.037666 -0.003793 0.091054 -vn -3.229032 -0.007018 0.457907 -v 0.037739 -0.003803 0.091372 -vn -3.169338 -0.004151 0.695375 -v 0.037711 -0.003798 0.091211 -vn -3.118558 -0.011552 0.938737 -v 0.037685 -0.003795 0.091114 -vn -3.299581 0.000603 0.331496 -v 0.037743 -0.003804 0.091408 -vn -3.287401 -0.000023 0.242292 -v 0.037743 -0.003804 0.091410 -vn -3.251107 0.002752 0.057333 -v 0.037750 -0.003808 0.091536 -vn -3.246267 0.000805 -0.093699 -v 0.037750 -0.003809 0.091575 -vn -3.245665 -0.007038 -0.362503 -v 0.037738 -0.003815 0.091739 -vn -2.630017 -0.001956 -1.824322 -v 0.037487 -0.003837 0.092398 -vn -2.882998 0.007730 -1.509472 -v 0.037598 -0.003830 0.092208 -vn -3.004101 0.000056 -1.333881 -v 0.037615 -0.003829 0.092173 -vn -2.343675 -0.001764 -2.218694 -v 0.037315 -0.003846 0.092607 -vn -1.877309 0.005568 -2.640470 -v 0.037112 -0.003854 0.092777 -vn -2.127271 0.008121 -2.452790 -v 0.037245 -0.003849 0.092672 -vn -1.522501 -0.009785 -2.889336 -v 0.036973 -0.003860 0.092864 -vn -1.282210 0.002023 -2.990676 -v 0.036825 -0.003865 0.092935 -vn -1.092804 -0.010998 -3.048409 -v 0.036768 -0.003867 0.092958 -vn -0.976746 -0.007859 -3.135015 -v 0.036671 -0.003870 0.092990 -vn -0.794889 -0.000437 -3.173347 -v 0.036656 -0.003871 0.092994 -vn -0.449388 0.000336 -3.199729 -v 0.036450 -0.003877 0.093037 -vn -0.096884 0.001074 -3.228251 -v 0.036295 -0.003882 0.093049 -vn 0.246027 -0.001505 -3.243194 -v 0.036123 -0.003888 0.093045 -vn 0.467182 -0.001409 -3.256961 -v 0.036022 -0.003891 0.093032 -vn 0.632155 0.005522 -3.210327 -v 0.035986 -0.003892 0.093026 -vn 0.799616 0.005733 -3.145432 -v 0.035862 -0.003896 0.092999 -vn 1.032166 -0.005316 -3.080050 -v 0.035801 -0.003898 0.092981 -vn 1.272674 -0.010354 -2.974452 -v 0.035636 -0.003904 0.092919 -vn 1.553264 -0.001274 -2.841399 -v 0.035557 -0.003907 0.092880 -vn 1.815925 0.007572 -2.665606 -v 0.035384 -0.003913 0.092775 -vn 2.032968 0.022608 -2.462714 -v 0.035324 -0.003915 0.092730 -vn 2.431642 0.005340 -2.063677 -v 0.035101 -0.003925 0.092514 -vn 2.704217 0.011740 -1.755774 -v 0.034966 -0.003933 0.092326 -vn 2.866388 -0.001246 -1.604999 -v 0.034947 -0.003934 0.092293 -vn 2.931012 -0.002904 -1.421682 -v 0.034902 -0.003937 0.092207 -vn 2.977911 -0.005521 -1.204018 -v 0.034874 -0.003939 0.092146 -vn 3.198905 -0.008977 -0.371247 -v 0.034763 -0.003952 0.091746 -vn 3.189042 -0.002472 0.010679 -v 0.034750 -0.003958 0.091554 -vn 3.181453 0.004001 0.406233 -v 0.034764 -0.003965 0.091344 -vn 3.191958 0.000603 0.702791 -v 0.034794 -0.003970 0.091191 -vn 3.189379 -0.000481 0.844992 -v 0.034795 -0.003970 0.091184 -vn 3.104177 -0.003612 0.994571 -v 0.034820 -0.003973 0.091098 -vn 3.023158 -0.006697 1.148152 -v 0.034844 -0.003976 0.091027 -vn 2.953489 0.002372 1.413832 -v 0.034909 -0.003981 0.090877 -vn 2.865499 0.002304 1.569973 -v 0.034923 -0.003982 0.090850 -vn 2.711470 -0.003436 1.775515 -v 0.034991 -0.003986 0.090735 -vn 2.501820 -0.004352 2.055708 -v 0.035095 -0.003992 0.090593 -vn 2.218861 0.015774 2.317214 -v 0.035198 -0.003996 0.090481 -vn 1.880564 -0.002179 2.572481 -v 0.035361 -0.004003 0.090342 -vn 1.510278 0.000301 2.842506 -v 0.035565 -0.004011 0.090216 -vn 1.146156 0.012253 2.988218 -v 0.035680 -0.004015 0.090163 -vn -3.264056 -0.000359 -0.309399 -v 0.037740 -0.004114 0.091726 -vn -3.241310 -0.001762 -0.483531 -v 0.037738 -0.004115 0.091738 -vn -3.153618 -0.000840 -0.726425 -v 0.037712 -0.004119 0.091887 -vn -3.105449 0.000966 -1.001108 -v 0.037668 -0.004124 0.092040 -vn 2.845367 -0.007309 1.534819 -v 0.034907 -0.004281 0.090883 -vn 2.559941 -0.001435 1.941059 -v 0.035073 -0.004291 0.090620 -vn 0.164806 -0.002373 -3.230227 -v 0.036150 -0.004487 0.093047 -vn 0.427323 -0.001812 -3.229035 -v 0.036059 -0.004490 0.093038 -vn 2.975883 -0.009522 1.279690 -v 0.034891 -0.004579 0.090916 -vn 2.840128 -0.002216 1.535402 -v 0.034909 -0.004581 0.090878 -vn 2.641486 0.010298 1.854688 -v 0.035050 -0.004589 0.090650 -vn 1.855320 0.010882 2.615641 -v 0.035350 -0.004603 0.090350 -vn 1.334847 -0.002838 2.882937 -v 0.035612 -0.004613 0.090192 -vn -0.823045 -0.001619 -3.161794 -v 0.036602 -0.004772 0.093008 -vn -0.645599 -0.003847 -3.211643 -v 0.036564 -0.004774 0.093017 -vn 0.195841 -0.002703 -3.234076 -v 0.036095 -0.004789 0.093042 -vn 3.098715 0.009930 -1.010224 -v 0.034814 -0.004845 0.091984 -vn 3.131411 0.010568 -0.787937 -v 0.034810 -0.004845 0.091970 -vn -0.734379 -0.006591 -3.144925 -v 0.036567 -0.005073 0.093016 -vn -0.334877 -0.001478 -3.197863 -v 0.036442 -0.005077 0.093038 -vn -1.639490 -0.011111 -2.802495 -v 0.036990 -0.005059 0.092855 -vn -1.428338 -0.003834 -2.934588 -v 0.036911 -0.005062 0.092896 -vn -1.111573 -0.007233 -3.016757 -v 0.036796 -0.005066 0.092947 -vn -1.860296 -0.029682 -2.560617 -v 0.037118 -0.005054 0.092773 -vn -2.303906 0.001363 -2.292248 -v 0.037350 -0.005044 0.092569 -vn -2.486632 -0.005907 -2.113579 -v 0.037371 -0.005043 0.092547 -vn -2.609594 -0.011626 -1.874800 -v 0.037473 -0.005038 0.092419 -vn -3.213033 -0.004102 -0.275681 -v 0.037748 -0.005011 0.091628 -vn -3.113680 0.000627 -0.750245 -v 0.037700 -0.005021 0.091934 -vn -3.065529 0.010036 -1.074959 -v 0.037659 -0.005025 0.092064 -vn -2.991243 0.002065 -1.303791 -v 0.037632 -0.005028 0.092133 -vn -2.893503 0.004264 -1.520279 -v 0.037564 -0.005033 0.092274 -vn -2.824683 0.001875 -1.651358 -v 0.037560 -0.005033 0.092280 -vn -3.233469 -0.004633 0.016189 -v 0.037750 -0.005010 0.091582 -vn -3.215561 -0.000266 0.386863 -v 0.037734 -0.005002 0.091330 -vn -3.157858 -0.004643 0.711362 -v 0.037722 -0.004999 0.091264 -vn -3.070232 -0.000326 1.056408 -v 0.037651 -0.004991 0.091014 -vn -3.036204 -0.003336 1.272948 -v 0.037637 -0.004990 0.090978 -vn -2.888589 -0.003591 1.458058 -v 0.037609 -0.004988 0.090916 -vn -2.561712 0.001461 1.902827 -v 0.037450 -0.004978 0.090650 -vn -2.015648 -0.010267 2.537241 -v 0.037197 -0.004966 0.090387 -vn -2.200207 -0.003110 2.442255 -v 0.037264 -0.004969 0.090444 -vn -2.327377 0.004207 2.258581 -v 0.037291 -0.004970 0.090470 -vn -1.291582 0.000847 2.947227 -v 0.036887 -0.004955 0.090192 -vn -1.607268 -0.000080 2.848340 -v 0.037000 -0.004959 0.090251 -vn -1.792240 -0.000739 2.722585 -v 0.037054 -0.004961 0.090284 -vn -0.802179 -0.002767 3.099100 -v 0.036595 -0.004945 0.090090 -vn -0.463841 0.001215 3.229695 -v 0.036442 -0.004940 0.090062 -vn -0.240769 -0.000067 3.258189 -v 0.036380 -0.004938 0.090056 -vn -0.021806 -0.002214 3.276957 -v 0.036231 -0.004933 0.090050 -vn 0.141770 -0.004091 3.267486 -v 0.036216 -0.004933 0.090050 -vn 0.397900 0.002298 3.231054 -v 0.036053 -0.004927 0.090063 -vn 0.633997 0.000684 3.219138 -v 0.035953 -0.004924 0.090080 -vn 0.770283 -0.003757 3.205383 -v 0.035892 -0.004922 0.090093 -vn 0.944362 -0.004926 3.109157 -v 0.035869 -0.004921 0.090099 -vn 1.385693 0.002187 2.902104 -v 0.035579 -0.004911 0.090208 -vn 1.729694 0.002338 2.755047 -v 0.035441 -0.004906 0.090287 -vn 1.946390 -0.002231 2.619825 -v 0.035358 -0.004903 0.090344 -vn 2.419194 -0.002303 2.144691 -v 0.035118 -0.004893 0.090566 -vn 2.139232 -0.003634 2.425762 -v 0.035274 -0.004900 0.090411 -vn 2.656378 -0.001112 1.811098 -v 0.035028 -0.004888 0.090680 -vn 2.924274 0.001357 1.402156 -v 0.034875 -0.004878 0.090950 -vn 3.044090 -0.002527 1.181840 -v 0.034861 -0.004877 0.090983 -vn 3.112726 -0.002552 0.888682 -v 0.034808 -0.004872 0.091138 -vn 3.263985 0.005467 0.538384 -v 0.034771 -0.004867 0.091301 -vn 3.208817 0.009173 0.619395 -v 0.034771 -0.004867 0.091299 -vn 3.241972 -0.004022 0.144429 -v 0.034751 -0.004860 0.091499 -vn 3.246375 -0.000385 0.401226 -v 0.034765 -0.004865 0.091336 -vn 3.230289 -0.006720 -0.385769 -v 0.034754 -0.004855 0.091665 -vn 3.293519 -0.004264 -0.220200 -v 0.034754 -0.004855 0.091663 -vn 3.276245 0.001420 -0.090749 -v 0.034751 -0.004857 0.091600 -vn 2.985067 0.009523 -1.228583 -v 0.034870 -0.004839 0.092138 -vn 2.930685 -0.000700 -1.468946 -v 0.034913 -0.004836 0.092230 -vn 2.789446 0.000719 -1.693590 -v 0.034954 -0.004833 0.092306 -vn 2.874960 0.004777 -1.601951 -v 0.034943 -0.004834 0.092285 -vn 1.831417 0.007951 -2.614762 -v 0.035413 -0.004812 0.092795 -vn 2.251147 -0.005392 -2.298302 -v 0.035175 -0.004822 0.092597 -vn 2.500410 -0.000020 -2.076155 -v 0.035093 -0.004826 0.092504 -vn 2.657784 -0.000603 -1.878088 -v 0.035031 -0.004829 0.092424 -vn 0.988289 -0.000495 -3.109561 -v 0.035756 -0.004800 0.092966 -vn 1.181089 -0.003585 -3.055050 -v 0.035739 -0.004800 0.092960 -vn 1.372758 -0.002948 -2.948200 -v 0.035605 -0.004805 0.092904 -vn 1.615753 0.002670 -2.817329 -v 0.035515 -0.004808 0.092858 -vn 0.449874 0.000014 -3.246408 -v 0.036075 -0.004789 0.093040 -vn 0.739836 -0.005482 -3.129274 -v 0.035914 -0.004794 0.093012 -vn -0.462097 -0.002338 -3.249688 -v 0.036441 -0.004778 0.093038 -vn -0.195260 0.001060 -3.224752 -v 0.036405 -0.004779 0.093042 -vn -1.802611 0.002268 -2.640143 -v 0.037086 -0.004755 0.092795 -vn -1.395949 -0.000583 -2.920503 -v 0.036876 -0.004763 0.092913 -vn -1.087870 -0.002909 -3.056620 -v 0.036761 -0.004767 0.092960 -vn -2.278822 0.000415 -2.254474 -v 0.037325 -0.004745 0.092596 -vn -2.604343 -0.007916 -1.842044 -v 0.037479 -0.004738 0.092410 -vn -2.758888 0.012315 -1.604782 -v 0.037546 -0.004734 0.092306 -vn -2.982607 0.002390 -1.305233 -v 0.037636 -0.004727 0.092123 -vn -3.065946 0.005643 -1.082547 -v 0.037659 -0.004725 0.092065 -vn -3.094238 -0.000951 -0.827646 -v 0.037690 -0.004722 0.091971 -vn -3.219923 -0.004971 -0.370562 -v 0.037746 -0.004712 0.091664 -vn -3.253395 -0.003677 -0.135980 -v 0.037747 -0.004712 0.091646 -vn -3.223307 -0.001799 0.138008 -v 0.037748 -0.004706 0.091483 -vn -3.199514 0.016815 0.443505 -v 0.037732 -0.004701 0.091320 -vn -3.157877 0.007625 0.649994 -v 0.037729 -0.004701 0.091300 -vn -3.036453 -0.003930 1.077178 -v 0.037647 -0.004691 0.091003 -vn -2.910611 -0.008344 1.375619 -v 0.037625 -0.004689 0.090950 -vn -2.642452 0.003236 1.811225 -v 0.037472 -0.004679 0.090680 -vn -2.437653 0.000367 2.134549 -v 0.037371 -0.004674 0.090554 -vn -2.258206 0.006355 2.351544 -v 0.037284 -0.004670 0.090464 -vn -2.125894 -0.000653 2.481338 -v 0.037225 -0.004667 0.090410 -vn -1.871698 0.002198 2.618710 -v 0.037159 -0.004665 0.090357 -vn -1.474435 0.000065 2.842586 -v 0.036921 -0.004656 0.090208 -vn -1.104723 0.002110 3.042915 -v 0.036750 -0.004650 0.090136 -vn -0.786231 0.002802 3.130948 -v 0.036630 -0.004646 0.090099 -vn -0.455993 0.004623 3.220514 -v 0.036431 -0.004639 0.090061 -vn -0.247433 -0.000632 3.266105 -v 0.036369 -0.004637 0.090055 -vn 0.000744 -0.000201 3.242386 -v 0.036269 -0.004634 0.090050 -vn 0.305746 -0.002531 3.209776 -v 0.036104 -0.004629 0.090057 -vn 0.613272 0.000391 3.210841 -v 0.035942 -0.004624 0.090082 -vn 0.868022 -0.001409 3.114308 -v 0.035905 -0.004623 0.090090 -vn 2.136221 -0.000308 2.477638 -v 0.035300 -0.004601 0.090389 -vn 2.034305 0.001531 2.576313 -v 0.035304 -0.004601 0.090386 -vn 2.582838 0.006329 2.032778 -v 0.035070 -0.004590 0.090623 -vn 2.479396 0.000696 2.147848 -v 0.035111 -0.004592 0.090574 -vn 2.287377 0.002566 2.298092 -v 0.035179 -0.004596 0.090500 -vn 3.195155 -0.007160 0.622536 -v 0.034778 -0.004568 0.091263 -vn 3.194299 -0.003255 0.770543 -v 0.034795 -0.004570 0.091186 -vn 3.078504 -0.011292 0.976185 -v 0.034805 -0.004572 0.091148 -vn 3.113687 0.002741 -0.759864 -v 0.034800 -0.004546 0.091934 -vn 3.195332 -0.004953 -0.227606 -v 0.034752 -0.004556 0.091628 -vn 3.236051 -0.000439 0.145961 -v 0.034752 -0.004561 0.091472 -vn 3.225849 -0.007666 0.433760 -v 0.034764 -0.004565 0.091347 -vn 2.643032 -0.000077 -1.885145 -v 0.035037 -0.004529 0.092432 -vn 2.767179 -0.011574 -1.629148 -v 0.034948 -0.004534 0.092295 -vn 2.859909 -0.001284 -1.543692 -v 0.034936 -0.004535 0.092273 -vn 2.974405 -0.001279 -1.322689 -v 0.034874 -0.004539 0.092148 -vn 3.049644 0.001748 -1.137716 -v 0.034851 -0.004541 0.092090 -vn 2.454365 -0.009031 -2.189437 -v 0.035140 -0.004523 0.092559 -vn 2.508927 -0.004362 -2.081710 -v 0.035099 -0.004525 0.092512 -vn 1.603800 -0.003844 -2.821379 -v 0.035524 -0.004508 0.092863 -vn 1.800874 -0.013450 -2.636937 -v 0.035386 -0.004513 0.092776 -vn 1.912442 -0.001530 -2.622833 -v 0.035383 -0.004513 0.092774 -vn 2.137100 0.012036 -2.404449 -v 0.035257 -0.004518 0.092674 -vn 2.346823 0.003215 -2.280747 -v 0.035150 -0.004523 0.092569 -vn 1.401295 -0.001897 -2.963390 -v 0.035615 -0.004505 0.092909 -vn 1.279480 -0.005926 -3.027456 -v 0.035672 -0.004503 0.092934 -vn 1.131950 0.005936 -3.059744 -v 0.035705 -0.004501 0.092947 -vn 0.931070 0.016726 -3.082286 -v 0.035826 -0.004497 0.092989 -vn 0.699071 -0.003915 -3.173279 -v 0.035924 -0.004494 0.093014 -vn -0.244187 0.000750 -3.202978 -v 0.036368 -0.004480 0.093045 -vn -0.632015 -0.001858 -3.200257 -v 0.036575 -0.004473 0.093014 -vn -0.831071 -0.002290 -3.172154 -v 0.036612 -0.004472 0.093006 -vn -0.993935 0.008560 -3.123900 -v 0.036727 -0.004468 0.092972 -vn -1.121371 0.006485 -3.072410 -v 0.036733 -0.004468 0.092970 -vn -1.372388 0.007655 -2.921674 -v 0.036885 -0.004463 0.092909 -vn -1.640564 0.004020 -2.831162 -v 0.037030 -0.004458 0.092831 -vn -1.808037 0.000106 -2.739091 -v 0.037056 -0.004457 0.092815 -vn -1.990233 -0.002146 -2.556464 -v 0.037165 -0.004452 0.092738 -vn -2.238213 -0.001375 -2.384091 -v 0.037299 -0.004447 0.092622 -vn -2.531053 0.005026 -2.029798 -v 0.037425 -0.004441 0.092482 -vn -2.365227 -0.005753 -2.256894 -v 0.037316 -0.004446 0.092605 -vn -2.972550 0.002941 -1.298302 -v 0.037640 -0.004427 0.092113 -vn -2.800376 0.017645 -1.606500 -v 0.037527 -0.004435 0.092336 -vn -2.757124 -0.000232 -1.761182 -v 0.037519 -0.004435 0.092349 -vn -2.662518 -0.010767 -1.852440 -v 0.037485 -0.004437 0.092401 -vn -3.075244 0.003276 -1.085340 -v 0.037663 -0.004425 0.092055 -vn -3.167858 0.003257 -0.342606 -v 0.037742 -0.004413 0.091701 -vn -3.086643 -0.002353 -0.880725 -v 0.037680 -0.004423 0.092004 -vn -3.256973 0.005556 0.323999 -v 0.037743 -0.004404 0.091409 -vn -3.235572 -0.003763 0.079267 -v 0.037748 -0.004406 0.091472 -vn -3.120747 0.003138 0.865574 -v 0.037695 -0.004396 0.091149 -vn -3.210390 -0.006875 0.577940 -v 0.037730 -0.004401 0.091309 -vn -3.236487 -0.003011 0.445122 -v 0.037735 -0.004402 0.091335 -vn -3.001618 -0.004623 1.298728 -v 0.037639 -0.004390 0.090983 -vn -3.067695 -0.001593 1.150954 -v 0.037643 -0.004390 0.090994 -vn -2.757138 -0.006068 1.770328 -v 0.037493 -0.004380 0.090710 -vn -2.859879 -0.004537 1.528009 -v 0.037574 -0.004385 0.090845 -vn -2.198246 -0.003670 2.453974 -v 0.037253 -0.004369 0.090434 -vn -2.287920 0.002294 2.341912 -v 0.037276 -0.004370 0.090456 -vn -2.452834 0.005558 2.091455 -v 0.037390 -0.004375 0.090575 -vn -2.656964 0.002728 1.913936 -v 0.037489 -0.004380 0.090705 -vn -1.686486 -0.014426 2.766533 -v 0.037015 -0.004359 0.090260 -vn -1.881024 0.003685 2.631778 -v 0.037120 -0.004363 0.090328 -vn -2.115872 -0.008339 2.465760 -v 0.037248 -0.004368 0.090430 -vn -1.614076 -0.007907 2.858267 -v 0.036981 -0.004358 0.090240 -vn -1.413751 0.002020 2.919291 -v 0.036953 -0.004357 0.090225 -vn -0.912782 0.007635 3.032951 -v 0.036666 -0.004347 0.090109 -vn -0.630669 0.000309 3.174532 -v 0.036520 -0.004342 0.090075 -vn -0.361203 -0.003182 3.242613 -v 0.036421 -0.004339 0.090060 -vn -0.067205 -0.003282 3.224751 -v 0.036306 -0.004335 0.090051 -vn 0.256573 -0.003630 3.231743 -v 0.036093 -0.004329 0.090058 -vn 0.491257 0.001427 3.247899 -v 0.036031 -0.004327 0.090066 -vn 0.757072 0.000342 3.143856 -v 0.035942 -0.004324 0.090082 -vn 1.191551 0.006683 3.008353 -v 0.035646 -0.004314 0.090177 -vn 1.425933 0.007999 2.928344 -v 0.035621 -0.004313 0.090188 -vn 1.661522 0.003108 2.773995 -v 0.035476 -0.004308 0.090265 -vn 2.031807 0.000992 2.544870 -v 0.035332 -0.004302 0.090363 -vn 1.920839 0.008737 2.611091 -v 0.035341 -0.004303 0.090357 -vn 2.373012 -0.002604 2.243787 -v 0.035172 -0.004295 0.090507 -vn 2.222245 -0.000335 2.390429 -v 0.035216 -0.004297 0.090463 -vn 2.975870 -0.005629 1.375148 -v 0.034893 -0.004280 0.090911 -vn 3.032160 -0.002563 1.128717 -v 0.034853 -0.004276 0.091003 -vn 3.132639 0.005812 0.839542 -v 0.034792 -0.004270 0.091196 -vn 3.175621 0.013890 0.607889 -v 0.034785 -0.004269 0.091227 -vn 3.246563 0.013394 0.037920 -v 0.034750 -0.004260 0.091521 -vn 3.231856 0.004151 0.236253 -v 0.034752 -0.004261 0.091482 -vn 3.151567 0.002867 -0.651803 -v 0.034791 -0.004247 0.091898 -vn 3.202444 0.006579 -0.179514 -v 0.034751 -0.004257 0.091590 -vn 3.069513 -0.001956 -0.980141 -v 0.034810 -0.004245 0.091969 -vn 2.948386 -0.000991 -1.380817 -v 0.034918 -0.004236 0.092240 -vn 2.844470 -0.000048 -1.602132 -v 0.034923 -0.004235 0.092249 -vn 2.676265 -0.004699 -1.789207 -v 0.035007 -0.004230 0.092390 -vn 2.500081 0.009739 -2.059598 -v 0.035106 -0.004225 0.092520 -vn 2.345359 0.003497 -2.211309 -v 0.035125 -0.004224 0.092542 -vn 1.961015 0.009891 -2.529619 -v 0.035353 -0.004214 0.092752 -vn 1.713909 0.001858 -2.762912 -v 0.035480 -0.004209 0.092837 -vn 1.208847 -0.004338 -3.054580 -v 0.035682 -0.004202 0.092938 -vn 1.324302 -0.003130 -2.994679 -v 0.035670 -0.004203 0.092933 -vn 1.525310 -0.002552 -2.892705 -v 0.035534 -0.004207 0.092868 -vn 0.373469 -0.001294 -3.232954 -v 0.036022 -0.004191 0.093033 -vn 0.621275 -0.000836 -3.217251 -v 0.035996 -0.004192 0.093028 -vn 0.855412 0.007791 -3.125014 -v 0.035837 -0.004197 0.092992 -vn 1.034476 0.008139 -3.097595 -v 0.035777 -0.004199 0.092974 -vn -0.088578 -0.003286 -3.228010 -v 0.036332 -0.004181 0.093048 -vn -0.948349 -0.002287 -3.075859 -v 0.036691 -0.004169 0.092984 -vn -0.580960 -0.000393 -3.203269 -v 0.036487 -0.004176 0.093031 -vn -0.367687 0.000459 -3.259427 -v 0.036424 -0.004178 0.093040 -vn -1.325706 0.000665 -2.973396 -v 0.036894 -0.004162 0.092904 -vn -1.515451 0.003496 -2.908388 -v 0.036929 -0.004161 0.092887 -vn -1.740783 0.003432 -2.700729 -v 0.037025 -0.004158 0.092834 -vn -2.137341 0.001259 -2.377592 -v 0.037272 -0.004148 0.092648 -vn -2.474155 0.002612 -2.133013 -v 0.037408 -0.004142 0.092503 -vn -2.601766 0.005230 -1.954449 -v 0.037432 -0.004140 0.092474 -vn -2.814379 0.000684 -1.663368 -v 0.037525 -0.004135 0.092339 -vn -2.695225 -0.002058 -1.833615 -v 0.037507 -0.004136 0.092368 -vn -3.094397 0.006513 -1.105416 -v 0.037666 -0.004125 0.092044 -vn -3.038395 0.001099 -1.221820 -v 0.037644 -0.004127 0.092103 -vn -2.920021 -0.000738 -1.428803 -v 0.037604 -0.004130 0.092196 -vn -3.244080 -0.000124 -0.054223 -v 0.037750 -0.004109 0.091562 -vn -3.274053 -0.000276 0.175557 -v 0.037747 -0.004106 0.091460 -vn -3.269398 0.002614 0.322225 -v 0.037742 -0.004104 0.091398 -vn -3.232449 0.000066 0.432590 -v 0.037739 -0.004103 0.091373 -vn -3.186467 -0.000175 0.661808 -v 0.037717 -0.004099 0.091237 -vn -2.985423 -0.005623 1.199645 -v 0.037652 -0.004091 0.091018 -vn -3.107340 -0.007100 0.910619 -v 0.037692 -0.004095 0.091138 -vn -2.711966 0.000863 1.696863 -v 0.037513 -0.004081 0.090741 -vn -2.475964 -0.009495 2.074595 -v 0.037382 -0.004074 0.090566 -vn -2.376006 -0.008195 2.245273 -v 0.037340 -0.004072 0.090519 -vn -2.291785 0.001000 2.373956 -v 0.037280 -0.004070 0.090459 -vn -2.168114 -0.002725 2.457840 -v 0.037268 -0.004069 0.090449 -vn -1.682205 -0.015624 2.766754 -v 0.037005 -0.004059 0.090254 -vn -1.915882 0.001103 2.596197 -v 0.037142 -0.004064 0.090344 -vn -1.563485 -0.010543 2.865434 -v 0.036986 -0.004058 0.090243 -vn -1.307825 -0.001734 2.970932 -v 0.036860 -0.004054 0.090180 -vn -1.038294 0.004189 3.095101 -v 0.036701 -0.004048 0.090119 -vn -0.869271 0.000620 3.144542 -v 0.036669 -0.004047 0.090110 -vn -0.696458 -0.002964 3.200876 -v 0.036547 -0.004043 0.090080 -vn -0.502231 0.002847 3.233356 -v 0.036509 -0.004042 0.090073 -vn -0.291381 0.002059 3.266167 -v 0.036347 -0.004037 0.090053 -vn -0.112744 0.005257 3.271779 -v 0.036341 -0.004037 0.090053 -vn 0.104788 0.009351 3.235503 -v 0.036183 -0.004031 0.090052 -vn 0.370468 0.002198 3.245362 -v 0.036083 -0.004028 0.090059 -vn 0.674845 0.004896 3.150414 -v 0.035977 -0.004025 0.090075 -vn 1.092154 0.014091 3.026407 -v 0.035728 -0.006117 0.090144 -vn 3.198941 0.002602 -0.487496 -v 0.034773 -0.006050 0.091811 -vn 2.078813 -0.001766 -2.471855 -v 0.035283 -0.006017 0.092696 -vn 0.886503 -0.001037 -3.132047 -v 0.035880 -0.005996 0.093004 -vn 1.211452 0.005923 -2.984233 -v 0.035680 -0.006002 0.092937 -vn -0.579033 0.007456 -3.155985 -v 0.036551 -0.005974 0.093020 -vn -3.198220 0.024362 -0.034260 -v 0.037750 -0.005908 0.091517 -vn 2.545925 -0.002040 2.026020 -v 0.035059 -0.005790 0.090638 -vn 2.263365 0.000627 2.294713 -v 0.035194 -0.005796 0.090485 -vn -3.120473 0.004673 0.870590 -v 0.037700 -0.005596 0.091168 -vn -3.162446 0.000772 0.703164 -v 0.037706 -0.005597 0.091192 -vn 3.201867 0.026023 0.195494 -v 0.034752 -0.005161 0.091473 -vn 3.230779 0.005386 0.402130 -v 0.034765 -0.005165 0.091336 -vn 0.168626 -0.003231 -3.220790 -v 0.036132 -0.005087 0.093045 -vn 0.484439 -0.001037 -3.235251 -v 0.036026 -0.005091 0.093033 -vn 0.740881 0.006832 -3.146938 -v 0.035927 -0.005094 0.093015 -vn 0.949848 0.003612 -3.129838 -v 0.035774 -0.005099 0.092973 -vn 1.080364 0.000402 -3.135294 -v 0.035769 -0.005099 0.092971 -vn 1.174498 -0.001000 -3.054861 -v 0.035733 -0.005100 0.092958 -vn 1.335006 -0.003448 -2.989396 -v 0.035617 -0.005104 0.092910 -vn 1.500070 0.000443 -2.920219 -v 0.035582 -0.005106 0.092893 -vn 1.662074 0.002483 -2.796321 -v 0.035472 -0.005110 0.092833 -vn 1.775895 0.000670 -2.728739 -v 0.035444 -0.005111 0.092815 -vn 1.995398 0.001868 -2.533715 -v 0.035337 -0.005115 0.092740 -vn 2.191857 -0.034312 -2.337227 -v 0.035201 -0.005121 0.092622 -vn 2.344387 -0.010085 -2.245332 -v 0.035185 -0.005121 0.092606 -vn 2.516051 0.002500 -2.017465 -v 0.035076 -0.005127 0.092484 -vn 2.730645 0.006843 -1.802022 -v 0.034981 -0.005132 0.092350 -vn 2.817307 0.005828 -1.698086 -v 0.034973 -0.005132 0.092337 -vn 2.883144 0.000138 -1.574154 -v 0.034931 -0.005135 0.092264 -vn 2.943935 -0.006660 -1.341149 -v 0.034902 -0.005137 0.092207 -vn 3.051525 -0.002259 -0.945368 -v 0.034821 -0.005144 0.092005 -vn 3.184260 -0.007090 -0.376192 -v 0.034758 -0.005154 0.091701 -vn 3.209655 -0.026783 -0.078642 -v 0.034750 -0.005158 0.091575 -vn 3.207693 -0.005713 0.577981 -v 0.034769 -0.005166 0.091310 -vn 3.153785 -0.001810 0.825421 -v 0.034804 -0.005172 0.091150 -vn 3.105294 -0.004455 1.015848 -v 0.034822 -0.005173 0.091091 -vn 3.074162 -0.003142 1.175608 -v 0.034857 -0.005177 0.090995 -vn 3.013451 -0.001752 1.301687 -v 0.034861 -0.005177 0.090983 -vn 2.844399 0.012511 1.529896 -v 0.034925 -0.005182 0.090846 -vn 2.740013 -0.003487 1.763712 -v 0.035007 -0.005187 0.090710 -vn 2.009534 -0.002834 2.591216 -v 0.035348 -0.005203 0.090352 -vn 2.652809 -0.008887 1.892397 -v 0.035010 -0.005187 0.090706 -vn 2.514001 0.001625 2.077526 -v 0.035109 -0.005192 0.090576 -vn 2.390699 0.000154 2.247497 -v 0.035151 -0.005194 0.090529 -vn 2.277871 0.000548 2.373342 -v 0.035222 -0.005198 0.090457 -vn 2.156145 -0.001074 2.474284 -v 0.035248 -0.005199 0.090434 -vn 1.833672 -0.001651 2.700491 -v 0.035378 -0.005204 0.090329 -vn 1.475422 -0.001597 2.853699 -v 0.035547 -0.005210 0.090225 -vn 0.601145 -0.000996 3.194194 -v 0.035978 -0.005225 0.090075 -vn 0.855769 0.009757 3.147280 -v 0.035834 -0.005220 0.090109 -vn 1.030429 0.017419 3.053246 -v 0.035819 -0.005220 0.090113 -vn 0.333519 -0.000929 3.241314 -v 0.036102 -0.005229 0.090057 -vn 0.071093 -0.000776 3.236709 -v 0.036195 -0.005232 0.090051 -vn -0.275469 0.004939 3.237494 -v 0.036404 -0.005239 0.090058 -vn -0.484356 0.006902 3.238622 -v 0.036467 -0.005241 0.090066 -vn -0.712745 0.002924 3.158556 -v 0.036559 -0.005244 0.090082 -vn -0.995011 0.003942 3.069393 -v 0.036725 -0.005249 0.090127 -vn -1.271354 -0.005814 3.019854 -v 0.036854 -0.005253 0.090177 -vn -1.427345 -0.002274 2.944448 -v 0.036878 -0.005254 0.090188 -vn -1.638844 0.002908 2.817383 -v 0.037022 -0.005259 0.090264 -vn -1.812388 0.005090 2.725283 -v 0.037075 -0.005261 0.090297 -vn -1.959054 -0.001848 2.646826 -v 0.037158 -0.005265 0.090356 -vn -2.063076 -0.001976 2.545005 -v 0.037168 -0.005265 0.090364 -vn -2.212073 -0.000330 2.400066 -v 0.037283 -0.005270 0.090462 -vn -2.376240 -0.002251 2.234332 -v 0.037327 -0.005272 0.090506 -vn -2.536061 -0.000921 1.999898 -v 0.037427 -0.005277 0.090621 -vn -2.751472 -0.002934 1.711656 -v 0.037528 -0.005282 0.090764 -vn -2.917480 0.001211 1.503996 -v 0.037593 -0.005287 0.090883 -vn -2.984927 0.001082 1.335403 -v 0.037606 -0.005288 0.090909 -vn -3.059130 -0.003130 1.059861 -v 0.037668 -0.005293 0.091061 -vn -3.174867 -0.000541 0.792856 -v 0.037713 -0.005298 0.091218 -vn -3.191962 -0.000777 0.564883 -v 0.037715 -0.005298 0.091228 -vn -3.217838 -0.004055 0.175465 -v 0.037750 -0.005308 0.091518 -vn -3.222027 0.004683 -0.193536 -v 0.037749 -0.005310 0.091591 -vn -3.163144 -0.004576 -0.647278 -v 0.037709 -0.005320 0.091899 -vn -3.167298 -0.003208 -0.896978 -v 0.037691 -0.005322 0.091967 -vn -3.039364 0.009647 -1.091565 -v 0.037680 -0.005323 0.092004 -vn -2.929700 0.002750 -1.393732 -v 0.037581 -0.005331 0.092241 -vn -2.896362 0.000713 -1.582065 -v 0.037566 -0.005332 0.092269 -vn -2.350899 -0.001969 -2.233835 -v 0.037375 -0.005343 0.092542 -vn -2.542561 -0.004545 -2.004966 -v 0.037395 -0.005342 0.092518 -vn -2.738070 0.004495 -1.724132 -v 0.037547 -0.005334 0.092303 -vn -1.973736 0.005581 -2.530726 -v 0.037146 -0.005353 0.092753 -vn -1.715717 -0.000006 -2.780083 -v 0.037022 -0.005358 0.092836 -vn -1.519585 0.001454 -2.888269 -v 0.036967 -0.005360 0.092867 -vn -1.330235 0.004122 -2.991266 -v 0.036829 -0.005365 0.092934 -vn -1.176153 0.003986 -3.053687 -v 0.036819 -0.005365 0.092938 -vn -0.894334 -0.003335 -3.112111 -v 0.036665 -0.005370 0.092991 -vn -0.624127 -0.001705 -3.217091 -v 0.036505 -0.005375 0.093028 -vn -0.371943 0.002373 -3.230443 -v 0.036478 -0.005376 0.093032 -vn 0.089085 -0.001552 -3.227277 -v 0.036168 -0.005386 0.093048 -vn 0.362350 -0.002840 -3.258713 -v 0.036077 -0.005389 0.093040 -vn 0.589447 0.007955 -3.182541 -v 0.036015 -0.005391 0.093031 -vn 0.874114 0.000195 -3.128448 -v 0.035808 -0.005398 0.092983 -vn 1.081686 -0.002888 -3.106361 -v 0.035759 -0.005400 0.092967 -vn 1.285564 0.014660 -2.944238 -v 0.035699 -0.005402 0.092945 -vn 1.628164 -0.011847 -2.713040 -v 0.035475 -0.005410 0.092834 -vn 2.124067 -0.002227 -2.462148 -v 0.035228 -0.005419 0.092648 -vn 2.308646 0.000120 -2.368152 -v 0.035205 -0.005420 0.092626 -vn 2.690996 -0.007917 -1.855605 -v 0.034996 -0.005431 0.092373 -vn 2.514745 0.001150 -2.054356 -v 0.035094 -0.005426 0.092505 -vn 2.376603 0.001355 -2.259283 -v 0.035177 -0.005422 0.092598 -vn 2.764956 -0.016410 -1.780033 -v 0.034993 -0.005431 0.092368 -vn 2.799171 -0.004696 -1.692866 -v 0.034975 -0.005432 0.092341 -vn 2.899954 -0.001211 -1.529927 -v 0.034914 -0.005436 0.092232 -vn 2.975248 0.001772 -1.350743 -v 0.034897 -0.005437 0.092197 -vn 3.068690 -0.000613 -1.161114 -v 0.034834 -0.005443 0.092046 -vn 3.127895 -0.002694 -0.996818 -v 0.034832 -0.005443 0.092040 -vn 3.246739 0.006406 -0.323048 -v 0.034760 -0.005453 0.091727 -vn 3.226986 0.000809 -0.469654 -v 0.034762 -0.005453 0.091738 -vn 3.157864 -0.004538 -0.736009 -v 0.034789 -0.005448 0.091888 -vn 3.205368 -0.007550 -0.001513 -v 0.034750 -0.005458 0.091563 -vn 3.188318 0.033909 0.259938 -v 0.034758 -0.005463 0.091400 -vn 3.222185 0.012920 0.417587 -v 0.034761 -0.005464 0.091373 -vn 3.146061 -0.003836 0.701737 -v 0.034783 -0.005469 0.091238 -vn 3.047243 -0.000377 1.090392 -v 0.034848 -0.005476 0.091018 -vn 2.930493 0.001864 1.398114 -v 0.034885 -0.005479 0.090928 -vn 2.743924 -0.004005 1.707005 -v 0.034987 -0.005486 0.090741 -vn 2.544365 -0.005148 1.986129 -v 0.035053 -0.005489 0.090646 -vn 2.311647 0.003657 2.295891 -v 0.035220 -0.005497 0.090460 -vn 2.225809 0.004620 2.430188 -v 0.035231 -0.005498 0.090450 -vn 2.112687 0.000096 2.509164 -v 0.035277 -0.005500 0.090408 -vn 1.914043 0.003794 2.626015 -v 0.035356 -0.005503 0.090345 -vn 1.540601 -0.001107 2.880990 -v 0.035514 -0.005509 0.090243 -vn 1.699892 -0.005064 2.790429 -v 0.035493 -0.005508 0.090255 -vn 1.243081 0.001990 2.974739 -v 0.035674 -0.005515 0.090165 -vn 1.043474 0.007578 3.079029 -v 0.035798 -0.005519 0.090120 -vn 0.879705 0.001409 3.160764 -v 0.035829 -0.005520 0.090110 -vn 0.690820 0.003184 3.200132 -v 0.035950 -0.005524 0.090080 -vn 0.508392 0.008394 3.224555 -v 0.035989 -0.005525 0.090073 -vn 0.295879 0.004091 3.266677 -v 0.036151 -0.005530 0.090053 -vn 0.122741 0.005653 3.273713 -v 0.036157 -0.005531 0.090053 -vn -0.159922 0.004171 3.220507 -v 0.036315 -0.005536 0.090051 -vn -0.599490 0.001999 3.149670 -v 0.036523 -0.005542 0.090075 -vn -0.971125 0.004494 3.077811 -v 0.036734 -0.005549 0.090130 -vn -1.258232 -0.002446 3.011957 -v 0.036820 -0.005552 0.090163 -vn -1.536325 -0.003042 2.840256 -v 0.036944 -0.005557 0.090220 -vn -1.845533 -0.000573 2.677397 -v 0.037138 -0.005564 0.090341 -vn -2.028575 -0.007250 2.586842 -v 0.037167 -0.005565 0.090363 -vn -2.107663 -0.011468 2.488666 -v 0.037215 -0.005567 0.090402 -vn -2.276350 -0.002259 2.323295 -v 0.037291 -0.005570 0.090470 -vn -3.035634 -0.001482 1.145810 -v 0.037650 -0.005591 0.091012 -vn -2.457902 -0.013016 2.142199 -v 0.037402 -0.005575 0.090590 -vn -2.574160 0.000858 1.951856 -v 0.037404 -0.005576 0.090592 -vn -2.799960 0.002642 1.639778 -v 0.037577 -0.005585 0.090850 -vn -2.941011 -0.010399 1.469162 -v 0.037583 -0.005586 0.090862 -vn -2.938801 -0.023423 1.354425 -v 0.037610 -0.005588 0.090918 -vn -3.207668 -0.009690 0.401556 -v 0.037741 -0.005604 0.091390 -vn -3.262165 0.009800 0.129921 -v 0.037749 -0.005607 0.091491 -vn -3.201123 0.024130 -0.093327 -v 0.037750 -0.005609 0.091554 -vn -3.143933 -0.006517 -0.624388 -v 0.037717 -0.005619 0.091862 -vn -3.069054 -0.016068 -0.967063 -v 0.037677 -0.005624 0.092013 -vn -3.016597 0.000810 -1.244512 -v 0.037633 -0.005628 0.092131 -vn -2.874369 0.000808 -1.495484 -v 0.037598 -0.005630 0.092208 -vn -2.616921 0.014551 -1.871422 -v 0.037451 -0.005639 0.092449 -vn -2.527489 0.006394 -2.077915 -v 0.037399 -0.005642 0.092514 -vn -2.360941 -0.001260 -2.230845 -v 0.037372 -0.005643 0.092546 -vn -2.075663 -0.003602 -2.485577 -v 0.037176 -0.005652 0.092730 -vn -1.913199 -0.003735 -2.639933 -v 0.037149 -0.005653 0.092750 -vn -1.699640 0.001376 -2.786808 -v 0.037013 -0.005658 0.092842 -vn -1.528117 0.002571 -2.897460 -v 0.036958 -0.005660 0.092873 -vn -1.324462 -0.000397 -3.033748 -v 0.036863 -0.005664 0.092919 -vn -1.403354 0.000700 -2.982928 -v 0.036867 -0.005663 0.092917 -vn -0.619703 -0.002657 -3.152390 -v 0.036514 -0.005675 0.093026 -vn -1.093892 -0.003608 -3.039788 -v 0.036809 -0.005665 0.092942 -vn -0.198900 -0.003812 -3.234761 -v 0.036332 -0.005681 0.093048 -vn 0.053259 -0.001633 -3.282508 -v 0.036205 -0.005685 0.093049 -vn 0.243944 0.002022 -3.262553 -v 0.036168 -0.005686 0.093048 -vn 0.534675 0.010071 -3.179976 -v 0.036005 -0.005691 0.093030 -vn 0.862481 0.006590 -3.112754 -v 0.035845 -0.005697 0.092994 -vn 1.193666 0.001450 -3.021659 -v 0.035690 -0.005702 0.092941 -vn 1.417509 0.003948 -2.941139 -v 0.035597 -0.005705 0.092900 -vn 1.625123 -0.005856 -2.818608 -v 0.035507 -0.005708 0.092853 -vn 1.852376 -0.010936 -2.644085 -v 0.035401 -0.005712 0.092787 -vn 2.136064 -0.011256 -2.394324 -v 0.035255 -0.005718 0.092672 -vn 2.457376 0.006270 -2.106678 -v 0.035087 -0.005726 0.092497 -vn 2.777505 -0.005224 -1.679316 -v 0.034970 -0.005732 0.092332 -vn 2.699380 -0.007270 -1.838938 -v 0.035013 -0.005730 0.092398 -vn 2.598081 0.008724 -1.994727 -v 0.035063 -0.005727 0.092467 -vn 2.905367 -0.000406 -1.428959 -v 0.034909 -0.005736 0.092222 -vn 3.017405 0.004408 -1.123525 -v 0.034845 -0.005742 0.092074 -vn 3.120050 0.011491 -0.809370 -v 0.034795 -0.005747 0.091915 -vn 3.203831 -0.000556 -0.472524 -v 0.034767 -0.005751 0.091773 -vn 3.244734 -0.000339 0.430618 -v 0.034759 -0.005764 0.091389 -vn 3.154676 -0.000707 0.686203 -v 0.034785 -0.005769 0.091227 -vn 3.089245 -0.007757 0.989821 -v 0.034829 -0.005774 0.091069 -vn 3.009308 -0.000023 1.171916 -v 0.034835 -0.005775 0.091052 -vn 3.258302 -0.001102 -0.188669 -v 0.034752 -0.005757 0.091616 -vn 3.261760 -0.004665 0.030266 -v 0.034750 -0.005759 0.091553 -vn 3.275847 -0.001414 0.246850 -v 0.034757 -0.005763 0.091408 -vn 2.685652 -0.006815 1.867430 -v 0.035022 -0.005788 0.090688 -vn 2.805616 -0.002404 1.606725 -v 0.034968 -0.005785 0.090771 -vn 1.014423 0.016289 3.041908 -v 0.035765 -0.005818 0.090131 -vn 1.311665 0.008317 2.953480 -v 0.035649 -0.005814 0.090176 -vn 1.622263 -0.006892 2.814115 -v 0.035482 -0.005808 0.090261 -vn 1.812581 0.004180 2.715869 -v 0.035417 -0.005805 0.090303 -vn 1.953811 0.007592 2.573644 -v 0.035365 -0.005804 0.090339 -vn 0.500991 -0.001878 3.238374 -v 0.035998 -0.005826 0.090071 -vn 0.257248 -0.000583 3.225198 -v 0.036123 -0.005830 0.090055 -vn 0.710931 -0.007890 3.179943 -v 0.035961 -0.005824 0.090078 -vn -0.012259 0.006786 3.263153 -v 0.036287 -0.005835 0.090050 -vn -0.214389 -0.001325 3.270792 -v 0.036326 -0.005836 0.090052 -vn -0.393487 -0.001032 3.254228 -v 0.036451 -0.005840 0.090064 -vn -0.576092 -0.000440 3.221570 -v 0.036486 -0.005841 0.090069 -vn -0.844388 0.000260 3.127509 -v 0.036649 -0.005846 0.090104 -vn -1.083858 0.000656 3.102193 -v 0.036768 -0.005850 0.090142 -vn -1.185372 -0.000755 3.096673 -v 0.036786 -0.005851 0.090149 -vn -1.277467 0.000255 3.022121 -v 0.036804 -0.005852 0.090156 -vn -1.524238 -0.002619 2.858930 -v 0.036953 -0.005857 0.090225 -vn -1.775358 0.002722 2.740408 -v 0.037093 -0.005862 0.090310 -vn -1.926738 -0.003752 2.638320 -v 0.037108 -0.005863 0.090320 -vn -2.075541 -0.016041 2.483279 -v 0.037224 -0.005867 0.090409 -vn -2.770352 -0.007209 1.614108 -v 0.037559 -0.005884 0.090817 -vn -2.471535 0.000725 2.061344 -v 0.037380 -0.005874 0.090564 -vn -2.289233 -0.000242 2.324822 -v 0.037298 -0.005871 0.090477 -vn -2.916947 -0.026544 1.356316 -v 0.037615 -0.005888 0.090928 -vn -3.049755 -0.001096 1.134547 -v 0.037654 -0.005891 0.091022 -vn -3.133011 -0.000400 0.903351 -v 0.037697 -0.005896 0.091155 -vn -3.184834 0.001170 0.806443 -v 0.037703 -0.005897 0.091178 -vn -3.210816 -0.000530 0.660806 -v 0.037717 -0.005899 0.091239 -vn -3.218316 0.001785 0.429296 -v 0.037735 -0.005902 0.091339 -vn -3.248444 0.007464 0.150716 -v 0.037749 -0.005907 0.091502 -vn -3.227034 -0.003537 -0.467067 -v 0.037724 -0.005917 0.091826 -vn -3.240404 -0.002559 -0.642100 -v 0.037724 -0.005918 0.091828 -vn -3.190677 -0.000164 -0.760067 -v 0.037711 -0.005920 0.091890 -vn -3.093079 0.000003 -0.979483 -v 0.037685 -0.005923 0.091987 -vn -3.030406 0.001370 -1.227228 -v 0.037629 -0.005928 0.092141 -vn -3.024927 -0.000399 -1.361207 -v 0.037614 -0.005929 0.092174 -vn -2.941976 0.001807 -1.447821 -v 0.037613 -0.005929 0.092176 -vn -2.769899 0.001669 -1.652618 -v 0.037537 -0.005934 0.092321 -vn -2.617002 0.011334 -1.922045 -v 0.037444 -0.005940 0.092457 -vn -2.528565 0.007630 -2.062769 -v 0.037422 -0.005941 0.092486 -vn -2.333108 0.001026 -2.249572 -v 0.037338 -0.005945 0.092582 -vn -2.049361 0.000166 -2.477069 -v 0.037205 -0.005951 0.092707 -vn -1.783649 0.002794 -2.670200 -v 0.037089 -0.005955 0.092794 -vn -1.446917 0.000508 -2.905942 -v 0.036898 -0.005962 0.092903 -vn -1.178785 0.000558 -3.028983 -v 0.036799 -0.005966 0.092946 -vn -0.967500 0.007268 -3.084872 -v 0.036704 -0.005969 0.092980 -vn -0.114054 0.005778 -3.243270 -v 0.036242 -0.005984 0.093050 -vn 0.086102 0.001148 -3.298847 -v 0.036219 -0.005985 0.093050 -vn 0.226016 -0.000512 -3.269259 -v 0.036157 -0.005987 0.093047 -vn 0.450944 0.001655 -3.215434 -v 0.036056 -0.005990 0.093037 -vn 0.705434 -0.003306 -3.188698 -v 0.035895 -0.005995 0.093007 -vn 1.774738 0.002240 -2.712197 -v 0.035444 -0.006011 0.092815 -vn 1.514140 0.002555 -2.875912 -v 0.035539 -0.006007 0.092871 -vn 2.378214 0.003124 -2.180256 -v 0.035146 -0.006023 0.092565 -vn 2.605480 0.001042 -1.918453 -v 0.035034 -0.006029 0.092429 -vn 2.792505 -0.004946 -1.620263 -v 0.034965 -0.006033 0.092323 -vn 2.971373 0.001378 -1.196013 -v 0.034858 -0.006040 0.092109 -vn 3.116589 0.013336 -0.829391 -v 0.034793 -0.006047 0.091905 -vn 3.227015 0.007691 -0.047499 -v 0.034750 -0.006059 0.091542 -vn 3.262043 0.006695 0.206780 -v 0.034754 -0.006062 0.091445 -vn 3.049733 0.000358 0.935013 -v 0.034823 -0.006074 0.091087 -vn 3.183020 0.002506 0.487597 -v 0.034760 -0.006064 0.091378 -vn 2.940354 -0.000501 1.357497 -v 0.034895 -0.006080 0.090907 -vn 2.818963 -0.000924 1.624570 -v 0.034949 -0.006083 0.090804 -vn 2.679538 0.000592 1.844636 -v 0.035022 -0.006088 0.090689 -vn 2.549591 0.002664 2.025858 -v 0.035066 -0.006090 0.090629 -vn 2.413476 -0.003262 2.221289 -v 0.035168 -0.006095 0.090511 -vn 2.300579 -0.000647 2.334631 -v 0.035173 -0.006095 0.090506 -vn 2.052907 0.004751 2.494515 -v 0.035294 -0.006101 0.090394 -vn 1.846838 0.000034 2.684479 -v 0.035425 -0.006106 0.090297 -vn 1.647786 -0.011667 2.798469 -v 0.035451 -0.006107 0.090281 -vn 1.345853 -0.010794 2.907998 -v 0.035648 -0.006114 0.090176 -vn 0.852290 -0.018796 3.112207 -v 0.035873 -0.006121 0.090098 -vn 0.618798 -0.001040 3.199779 -v 0.035960 -0.006124 0.090078 -vn 0.309082 -0.002719 3.206344 -v 0.036084 -0.006128 0.090059 -vn 0.008821 -0.003344 3.253308 -v 0.036286 -0.006135 0.090051 -vn -0.203905 -0.004745 3.266559 -v 0.036324 -0.006136 0.090052 -vn -0.512228 0.009072 3.169513 -v 0.036450 -0.006140 0.090063 -vn -3.106682 0.000036 1.035606 -v 0.037683 -0.006194 0.091105 -vn -1.592957 -0.007340 -2.851550 -v 0.036960 -0.006260 0.092871 -vn -1.429239 -0.002584 -2.942003 -v 0.036929 -0.006261 0.092887 -vn 0.939068 -0.000417 -3.113060 -v 0.035810 -0.006298 0.092984 -vn -2.579441 0.001830 -1.880139 -v 0.037467 -0.006538 0.092427 -vn -0.922621 -0.004729 -3.133829 -v 0.036646 -0.006571 0.092997 -vn -0.742639 -0.007415 -3.177769 -v 0.036622 -0.006572 0.093003 -vn 0.282137 -0.003877 -3.226622 -v 0.036120 -0.006588 0.093044 -vn 1.390272 0.002905 -2.899690 -v 0.035605 -0.006605 0.092904 -vn 3.001255 0.003487 -1.208915 -v 0.034887 -0.006638 0.092176 -vn 2.066675 0.000365 2.493720 -v 0.035292 -0.006701 0.090395 -vn 1.891788 -0.006940 2.641095 -v 0.035390 -0.006704 0.090321 -vn 3.285237 -0.010503 0.052445 -v 0.034750 -0.006959 0.091533 -vn 3.266921 -0.002690 0.190681 -v 0.034752 -0.006961 0.091471 -vn 0.643630 -0.001891 3.183429 -v 0.035975 -0.007025 0.090076 -vn 0.985920 -0.004175 3.101210 -v 0.035762 -0.007018 0.090132 -vn 1.294787 -0.005265 -2.944976 -v 0.035672 -0.007203 0.092934 -vn 0.927875 0.001589 -3.053708 -v 0.035791 -0.007198 0.092978 -vn 0.574753 0.009463 -3.189890 -v 0.036025 -0.007191 0.093033 -vn 0.335086 0.008313 -3.240264 -v 0.036074 -0.007189 0.093040 -vn 0.024701 -0.000508 -3.230653 -v 0.036238 -0.007184 0.093050 -vn -0.357378 0.000875 -3.193970 -v 0.036390 -0.007179 0.093043 -vn -0.844984 0.001426 -3.124510 -v 0.036693 -0.007169 0.092983 -vn -1.589785 -0.004069 -2.854248 -v 0.037020 -0.007158 0.092837 -vn -1.357886 -0.013745 -2.897052 -v 0.036875 -0.007163 0.092914 -vn -1.083123 0.004303 -3.078878 -v 0.036722 -0.007168 0.092974 -vn -1.759536 -0.005679 -2.761153 -v 0.037026 -0.007158 0.092834 -vn -2.276282 0.001998 -2.225713 -v 0.037314 -0.007146 0.092607 -vn -1.962486 0.002055 -2.544051 -v 0.037155 -0.007153 0.092746 -vn -2.662226 -0.001066 -1.737255 -v 0.037508 -0.007136 0.092366 -vn -2.961397 -0.008692 -1.258878 -v 0.037645 -0.007127 0.092101 -vn -3.076560 -0.002732 -1.043465 -v 0.037668 -0.007124 0.092038 -vn -3.148728 0.000797 -0.771030 -v 0.037706 -0.007120 0.091909 -vn -3.210792 0.004501 -0.529685 -v 0.037731 -0.007116 0.091786 -vn -3.219865 0.000005 -0.195790 -v 0.037744 -0.007113 0.091681 -vn -3.179666 0.015670 0.318351 -v 0.037739 -0.007103 0.091371 -vn -3.180556 0.005036 0.629654 -v 0.037721 -0.007099 0.091258 -vn -3.123470 0.001802 0.893222 -v 0.037692 -0.007095 0.091136 -vn -3.010486 -0.007076 1.181223 -v 0.037652 -0.007091 0.091016 -vn -2.908937 -0.003266 1.452160 -v 0.037579 -0.007086 0.090855 -vn -2.797402 -0.001948 1.660779 -v 0.037549 -0.007084 0.090800 -vn -2.586944 -0.006466 1.891266 -v 0.037481 -0.007080 0.090693 -vn -2.017864 -0.002042 2.561571 -v 0.037160 -0.007065 0.090357 -vn -2.242723 -0.002838 2.288723 -v 0.037278 -0.007070 0.090458 -vn -1.514635 -0.000551 2.913474 -v 0.036970 -0.007058 0.090234 -vn -1.665724 -0.003806 2.815907 -v 0.036984 -0.007058 0.090242 -vn -1.822942 0.000666 2.697398 -v 0.037110 -0.007063 0.090321 -vn -0.239726 0.007538 3.197292 -v 0.036340 -0.007036 0.090053 -vn -0.745652 -0.005846 3.132510 -v 0.036646 -0.007046 0.090103 -vn -0.913559 0.001623 3.138597 -v 0.036668 -0.007047 0.090109 -vn -1.063934 -0.004058 3.088003 -v 0.036728 -0.007049 0.090128 -vn -1.252638 -0.011579 2.989125 -v 0.036823 -0.007052 0.090164 -vn 0.110318 0.008798 3.228355 -v 0.036181 -0.007031 0.090052 -vn 0.370319 -0.002068 3.247452 -v 0.036081 -0.007028 0.090060 -vn 1.171885 -0.008377 3.057479 -v 0.035726 -0.007017 0.090145 -vn 1.417753 -0.001333 2.902707 -v 0.035627 -0.007013 0.090186 -vn 1.827958 0.004530 2.648215 -v 0.035360 -0.007003 0.090343 -vn 2.024616 0.004461 2.522740 -v 0.035331 -0.007002 0.090364 -vn 2.227300 0.016794 2.322892 -v 0.035207 -0.006997 0.090472 -vn 2.477479 0.000307 2.162321 -v 0.035095 -0.006992 0.090593 -vn 2.561295 0.012513 2.074316 -v 0.035094 -0.006992 0.090594 -vn 2.573575 0.016251 1.955712 -v 0.035071 -0.006990 0.090622 -vn 2.732872 -0.002594 1.749137 -v 0.034977 -0.006985 0.090756 -vn 2.876956 -0.002215 1.551088 -v 0.034927 -0.006982 0.090844 -vn 2.958824 -0.002416 1.463938 -v 0.034898 -0.006980 0.090900 -vn 2.997320 0.001558 1.271129 -v 0.034897 -0.006980 0.090902 -vn 3.119213 0.003813 0.908533 -v 0.034793 -0.006970 0.091193 -vn 3.206234 0.002645 0.669975 -v 0.034790 -0.006970 0.091208 -vn 3.219142 0.001014 0.422052 -v 0.034761 -0.006964 0.091369 -vn 3.283804 -0.009985 -0.036753 -v 0.034750 -0.006958 0.091557 -vn 3.225474 0.002517 -0.260119 -v 0.034752 -0.006956 0.091635 -vn 3.188970 0.001551 -0.582262 -v 0.034782 -0.006949 0.091859 -vn 3.111014 0.002406 -0.897120 -v 0.034796 -0.006947 0.091919 -vn 2.868568 -0.002297 -1.386661 -v 0.034903 -0.006937 0.092210 -vn 2.472337 -0.005220 -2.157066 -v 0.035114 -0.006925 0.092530 -vn 2.521808 0.001132 -2.086316 -v 0.035102 -0.006925 0.092516 -vn 2.609606 0.003544 -1.983846 -v 0.035051 -0.006928 0.092451 -vn 2.712348 -0.006182 -1.752726 -v 0.035014 -0.006930 0.092400 -vn 1.228531 -0.001051 -3.034380 -v 0.035671 -0.006903 0.092934 -vn 1.383876 0.001573 -2.960894 -v 0.035638 -0.006904 0.092920 -vn 1.634738 -0.003610 -2.795541 -v 0.035490 -0.006909 0.092843 -vn 1.872503 -0.001582 -2.693078 -v 0.035370 -0.006914 0.092765 -vn 2.017228 -0.002243 -2.577419 -v 0.035354 -0.006914 0.092753 -vn 2.187640 -0.002962 -2.403150 -v 0.035228 -0.006919 0.092648 -vn 2.377532 -0.001978 -2.254210 -v 0.035157 -0.006923 0.092577 -vn 0.871786 0.011178 -3.129643 -v 0.035826 -0.006897 0.092989 -vn 1.032617 0.008828 -3.098346 -v 0.035789 -0.006899 0.092977 -vn 0.249260 0.001554 -3.206704 -v 0.036110 -0.006888 0.093043 -vn 0.576793 0.002945 -3.192741 -v 0.035987 -0.006892 0.093027 -vn -0.224625 -0.013195 -3.171486 -v 0.036352 -0.006880 0.093047 -vn -0.850763 -0.001203 -3.075834 -v 0.036658 -0.006870 0.092993 -vn -1.294217 0.000462 -2.970047 -v 0.036884 -0.006863 0.092909 -vn -1.509800 0.004840 -2.915347 -v 0.036940 -0.006861 0.092882 -vn -1.669161 0.003344 -2.795198 -v 0.036994 -0.006859 0.092852 -vn -1.929093 -0.007746 -2.596471 -v 0.037164 -0.006852 0.092739 -vn -2.101508 -0.002900 -2.489618 -v 0.037213 -0.006850 0.092700 -vn -2.281263 0.006870 -2.270167 -v 0.037287 -0.006847 0.092634 -vn -2.584165 0.016149 -1.900527 -v 0.037488 -0.006837 0.092397 -vn -2.736293 0.011892 -1.752341 -v 0.037498 -0.006837 0.092382 -vn -2.861975 0.009151 -1.497524 -v 0.037581 -0.006831 0.092241 -vn -3.019974 -0.009460 -1.221505 -v 0.037649 -0.006826 0.092092 -vn -3.036917 -0.022725 -1.019170 -v 0.037656 -0.006826 0.092073 -vn -3.217708 -0.010253 -0.262953 -v 0.037741 -0.006814 0.091718 -vn -3.171816 -0.013396 -0.574824 -v 0.037733 -0.006816 0.091775 -vn -3.173023 0.004138 0.259335 -v 0.037743 -0.006804 0.091407 -vn -3.171903 0.003345 0.620741 -v 0.037719 -0.006799 0.091248 -vn -3.140175 0.001336 0.897083 -v 0.037689 -0.006795 0.091126 -vn -3.023028 -0.006253 1.157011 -v 0.037665 -0.006792 0.091051 -vn -2.885203 0.000822 1.484078 -v 0.037562 -0.006784 0.090823 -vn -1.640273 -0.001649 2.782040 -v 0.037016 -0.006759 0.090261 -vn -1.815417 0.003932 2.700097 -v 0.037101 -0.006762 0.090315 -vn -2.010033 0.000067 2.556670 -v 0.037151 -0.006764 0.090351 -vn -2.249753 -0.001802 2.330524 -v 0.037305 -0.006771 0.090484 -vn -2.476995 -0.000119 2.082276 -v 0.037390 -0.006775 0.090575 -vn -2.684658 0.003652 1.811706 -v 0.037502 -0.006781 0.090724 -vn -2.795512 0.012239 1.679917 -v 0.037543 -0.006783 0.090790 -vn -1.329101 -0.005006 2.946953 -v 0.036870 -0.006754 0.090184 -vn -1.055377 -0.011962 3.070481 -v 0.036717 -0.006749 0.090125 -vn -0.829527 -0.019758 3.093352 -v 0.036681 -0.006748 0.090113 -vn -0.322420 -0.011495 3.189539 -v 0.036377 -0.006738 0.090055 -vn -0.003344 -0.002198 3.246266 -v 0.036234 -0.006733 0.090050 -vn 0.205972 -0.001444 3.245395 -v 0.036171 -0.006731 0.090052 -vn 0.457206 -0.006956 3.240212 -v 0.036012 -0.006726 0.090069 -vn 0.585318 -0.023164 3.189605 -v 0.036008 -0.006726 0.090070 -vn 0.843165 0.000147 3.135565 -v 0.035848 -0.006721 0.090105 -vn 1.206781 0.000838 3.036660 -v 0.035692 -0.006715 0.090158 -vn 1.072284 -0.003029 3.074121 -v 0.035751 -0.006717 0.090135 -vn 1.696020 -0.014073 2.736428 -v 0.035424 -0.006706 0.090298 -vn 1.352529 0.015475 2.923566 -v 0.035661 -0.006714 0.090171 -vn 2.268987 0.009198 2.327319 -v 0.035200 -0.006697 0.090479 -vn 2.470656 0.000729 2.074630 -v 0.035119 -0.006693 0.090565 -vn 2.656144 -0.007097 1.846316 -v 0.034992 -0.006686 0.090733 -vn 2.816866 0.001744 1.668881 -v 0.034971 -0.006685 0.090766 -vn 2.894686 -0.000377 1.392384 -v 0.034914 -0.006681 0.090868 -vn 3.073315 -0.003747 0.906059 -v 0.034802 -0.006671 0.091158 -vn 3.197402 -0.001940 0.481045 -v 0.034768 -0.006666 0.091318 -vn 3.244838 -0.002495 0.141143 -v 0.034750 -0.006660 0.091519 -vn 3.182057 -0.019483 -0.539168 -v 0.034772 -0.006650 0.091808 -vn 3.212962 0.006667 -0.329412 -v 0.034758 -0.006654 0.091707 -vn 3.258607 -0.006243 -0.040053 -v 0.034750 -0.006659 0.091544 -vn 3.220973 -0.010782 -0.657356 -v 0.034784 -0.006648 0.091869 -vn 3.117392 -0.002737 -0.866449 -v 0.034787 -0.006648 0.091883 -vn 2.801748 0.001238 -1.654805 -v 0.034965 -0.006633 0.092324 -vn 2.940554 -0.002848 -1.443971 -v 0.034888 -0.006638 0.092179 -vn 2.254240 0.003145 -2.339944 -v 0.035236 -0.006619 0.092655 -vn 2.483403 -0.001380 -2.105394 -v 0.035079 -0.006626 0.092488 -vn 2.626918 -0.003365 -1.987013 -v 0.035057 -0.006628 0.092460 -vn 2.697575 0.001342 -1.862620 -v 0.035020 -0.006629 0.092409 -vn 2.112214 -0.002271 -2.515064 -v 0.035283 -0.006617 0.092697 -vn 1.978956 0.001235 -2.611897 -v 0.035340 -0.006615 0.092743 -vn 1.753004 0.004205 -2.725457 -v 0.035415 -0.006612 0.092796 -vn 0.560466 -0.002149 -3.230944 -v 0.035958 -0.006593 0.093021 -vn 0.711207 0.002411 -3.211820 -v 0.035952 -0.006593 0.093020 -vn 0.863976 -0.001504 -3.165075 -v 0.035836 -0.006597 0.092992 -vn 1.057610 -0.001632 -3.083851 -v 0.035799 -0.006598 0.092981 -vn -0.446873 0.000649 -3.214663 -v 0.036448 -0.006577 0.093037 -vn -0.187786 0.004287 -3.265442 -v 0.036316 -0.006582 0.093049 -vn -0.018531 0.009653 -3.255937 -v 0.036284 -0.006583 0.093050 -vn -1.168846 0.001228 -3.036488 -v 0.036801 -0.006566 0.092945 -vn -1.391437 0.001306 -2.968164 -v 0.036894 -0.006562 0.092905 -vn -1.518380 0.000343 -2.935337 -v 0.036950 -0.006560 0.092877 -vn -1.657551 0.001964 -2.801932 -v 0.036963 -0.006560 0.092869 -vn -2.242538 0.009655 -2.314863 -v 0.037261 -0.006548 0.092658 -vn -2.127254 0.004118 -2.492719 -v 0.037221 -0.006550 0.092693 -vn -1.889789 0.014621 -2.600553 -v 0.037173 -0.006552 0.092733 -vn -3.135673 -0.003003 -0.811083 -v 0.037702 -0.006521 0.091925 -vn -3.080954 0.001807 -1.098520 -v 0.037653 -0.006526 0.092081 -vn -3.045010 0.001940 -1.241237 -v 0.037643 -0.006527 0.092106 -vn -2.988409 -0.003111 -1.359136 -v 0.037614 -0.006529 0.092175 -vn -2.834457 0.008556 -1.548788 -v 0.037586 -0.006531 0.092231 -vn -3.083302 0.002263 1.112249 -v 0.037674 -0.006493 0.091079 -vn -3.156227 -0.000340 1.014086 -v 0.037676 -0.006494 0.091085 -vn -3.149528 -0.000301 0.885186 -v 0.037686 -0.006495 0.091116 -vn -3.180579 -0.000802 0.588666 -v 0.037725 -0.006500 0.091275 -vn -3.250260 0.008164 0.324995 -v 0.037746 -0.006505 0.091437 -vn -3.271865 0.001698 0.157419 -v 0.037746 -0.006505 0.091444 -vn -3.237561 -0.004845 -0.108016 -v 0.037749 -0.006510 0.091601 -vn -3.261523 -0.003191 -0.371930 -v 0.037736 -0.006515 0.091753 -vn -3.235369 -0.001334 -0.545611 -v 0.037735 -0.006515 0.091765 -vn -2.954890 0.002701 1.318194 -v 0.037614 -0.006488 0.090926 -vn -2.868849 0.004298 1.572679 -v 0.037558 -0.006484 0.090815 -vn -2.800539 0.004968 1.680715 -v 0.037538 -0.006483 0.090781 -vn -2.669901 -0.003035 1.795340 -v 0.037522 -0.006482 0.090754 -vn -2.316859 0.002307 2.196424 -v 0.037331 -0.006472 0.090510 -vn -2.000149 0.002938 2.553608 -v 0.037143 -0.006464 0.090345 -vn -1.820377 0.001111 2.709889 -v 0.037092 -0.006462 0.090308 -vn -1.667812 -0.005139 2.761887 -v 0.037048 -0.006460 0.090280 -vn -1.381445 0.001594 2.943516 -v 0.036860 -0.006454 0.090180 -vn -1.200425 -0.002179 3.048823 -v 0.036802 -0.006452 0.090155 -vn -0.916758 0.000280 3.096282 -v 0.036717 -0.006449 0.090125 -vn 0.063755 -0.000529 3.231474 -v 0.036222 -0.006433 0.090050 -vn -0.236208 0.000455 3.263882 -v 0.036386 -0.006438 0.090056 -vn -0.471745 0.001916 3.216136 -v 0.036413 -0.006439 0.090059 -vn 0.719815 0.003480 3.184938 -v 0.035898 -0.006422 0.090092 -vn 0.510359 0.006682 3.236427 -v 0.036049 -0.006427 0.090064 -vn 0.343584 0.002317 3.256112 -v 0.036059 -0.006428 0.090062 -vn 1.697095 0.001889 2.772652 -v 0.035420 -0.006406 0.090301 -vn 1.234668 -0.000853 2.955518 -v 0.035696 -0.006416 0.090156 -vn 0.945557 0.003685 3.118466 -v 0.035838 -0.006420 0.090108 -vn 1.903465 0.000363 2.655834 -v 0.035394 -0.006405 0.090318 -vn 2.037952 -0.002871 2.496202 -v 0.035314 -0.006401 0.090378 -vn 2.294859 -0.006098 2.295688 -v 0.035165 -0.006395 0.090514 -vn 2.436860 -0.008610 2.196174 -v 0.035143 -0.006394 0.090538 -vn 2.552177 0.003991 1.970506 -v 0.035082 -0.006391 0.090609 -vn 2.730567 0.006558 1.729858 -v 0.034966 -0.006385 0.090775 -vn 2.881425 0.006876 1.458445 -v 0.034931 -0.006382 0.090835 -vn 3.026201 0.029305 0.977120 -v 0.034812 -0.006372 0.091122 -vn 3.149093 0.010143 0.727040 -v 0.034793 -0.006370 0.091193 -vn 3.219698 -0.002171 0.395519 -v 0.034758 -0.006364 0.091392 -vn 3.272161 0.006994 0.181843 -v 0.034752 -0.006361 0.091482 -vn 3.258723 0.007463 0.058355 -v 0.034751 -0.006360 0.091492 -vn 3.218080 0.002920 -0.234960 -v 0.034754 -0.006355 0.091656 -vn 3.225067 0.005454 -0.511995 -v 0.034774 -0.006350 0.091819 -vn 3.207499 0.001301 -0.697619 -v 0.034780 -0.006349 0.091847 -vn 2.978289 -0.003183 -1.272032 -v 0.034872 -0.006339 0.092143 -vn 3.105391 -0.000215 -0.941366 -v 0.034812 -0.006345 0.091978 -vn 2.362341 -0.003914 -2.230138 -v 0.035171 -0.006322 0.092592 -vn 2.501540 -0.012248 -1.995032 -v 0.035064 -0.006327 0.092468 -vn 2.604848 -0.001500 -1.937478 -v 0.035056 -0.006328 0.092458 -vn 2.754544 0.002045 -1.724359 -v 0.034971 -0.006332 0.092334 -vn 2.859190 0.005601 -1.556201 -v 0.034940 -0.006334 0.092280 -vn 2.208095 -0.002252 -2.421577 -v 0.035244 -0.006319 0.092663 -vn 2.118162 -0.005782 -2.517355 -v 0.035291 -0.006317 0.092704 -vn 1.922458 -0.003671 -2.605920 -v 0.035311 -0.006316 0.092720 -vn 1.499822 -0.004970 -2.823082 -v 0.035572 -0.006306 0.092888 -vn 1.193546 -0.004426 -3.014499 -v 0.035715 -0.006301 0.092951 -vn 0.283201 -0.002206 -3.221608 -v 0.036131 -0.006287 0.093045 -vn 0.687925 -0.005701 -3.153448 -v 0.035915 -0.006294 0.093012 -vn -0.122142 0.000297 -3.212099 -v 0.036279 -0.006283 0.093050 -vn -0.693548 -0.005153 -3.124302 -v 0.036587 -0.006273 0.093012 -vn -1.084588 -0.018517 -3.003919 -v 0.036776 -0.006267 0.092955 -vn -1.823879 0.005549 -2.679127 -v 0.037100 -0.006255 0.092786 -vn -1.998653 -0.013143 -2.549274 -v 0.037181 -0.006252 0.092726 -vn -2.113969 -0.010525 -2.523125 -v 0.037229 -0.006250 0.092686 -vn -2.210938 0.000786 -2.426857 -v 0.037233 -0.006249 0.092683 -vn -2.368438 -0.004137 -2.210126 -v 0.037347 -0.006244 0.092573 -vn -2.557652 -0.003668 -2.003797 -v 0.037445 -0.006240 0.092457 -vn -2.624583 -0.009988 -1.890397 -v 0.037452 -0.006239 0.092447 -vn -2.787115 0.000687 -1.668217 -v 0.037543 -0.006234 0.092310 -vn -2.918458 0.002346 -1.486596 -v 0.037591 -0.006231 0.092221 -vn -3.002776 0.000087 -1.371285 -v 0.037618 -0.006229 0.092165 -vn -3.029560 -0.001477 -1.179142 -v 0.037629 -0.006228 0.092141 -vn -3.115644 -0.002990 -0.875245 -v 0.037705 -0.006220 0.091914 -vn -3.213447 0.003756 -0.656830 -v 0.037719 -0.006218 0.091854 -vn -3.208196 0.001769 -0.419029 -v 0.037731 -0.006216 0.091790 -vn -3.179736 0.000087 0.124797 -v 0.037748 -0.006206 0.091481 -vn -3.155588 -0.003052 0.904522 -v 0.037687 -0.006195 0.091120 -vn -3.186819 -0.003068 0.776513 -v 0.037709 -0.006197 0.091202 -vn -3.189237 -0.004819 0.529126 -v 0.037723 -0.006199 0.091264 -vn -2.704464 -0.011046 1.750340 -v 0.037541 -0.006183 0.090786 -vn -2.861703 -0.004907 1.588430 -v 0.037552 -0.006184 0.090806 -vn -2.953207 -0.001229 1.424790 -v 0.037610 -0.006188 0.090917 -vn -3.024479 -0.000835 1.247073 -v 0.037626 -0.006189 0.090952 -vn -1.729010 -0.007246 2.772218 -v 0.037078 -0.006162 0.090299 -vn -1.886228 0.000865 2.685560 -v 0.037082 -0.006162 0.090302 -vn -2.051730 -0.000043 2.547202 -v 0.037213 -0.006167 0.090400 -vn -2.203592 0.000566 2.434671 -v 0.037243 -0.006168 0.090425 -vn -2.341135 0.005589 2.290247 -v 0.037333 -0.006172 0.090512 -vn -2.455512 0.008667 2.081113 -v 0.037356 -0.006173 0.090537 -vn -1.531570 -0.005073 2.857613 -v 0.036941 -0.006156 0.090219 -vn -1.299875 -0.003206 2.997297 -v 0.036850 -0.006153 0.090175 -vn -0.990296 -0.002423 3.060281 -v 0.036751 -0.006150 0.090136 -vn 3.024764 -0.016819 1.030774 -v 0.034840 -0.008175 0.091037 -vn 2.919763 -0.009984 1.363712 -v 0.034880 -0.008179 0.090939 -vn 2.187160 0.001239 -2.396404 -v 0.035203 -0.008121 0.092624 -vn -2.883515 0.007416 -1.475250 -v 0.037565 -0.008033 0.092272 -vn -3.032325 -0.005360 -1.054374 -v 0.037676 -0.008024 0.092014 -vn 3.146008 -0.001039 0.535468 -v 0.034771 -0.007867 0.091302 -vn 3.050395 -0.000645 1.077081 -v 0.034854 -0.007876 0.091002 -vn -2.132252 -0.000730 -2.411609 -v 0.037254 -0.007749 0.092665 -vn -1.836382 -0.003253 -2.649978 -v 0.037088 -0.007755 0.092794 -vn -2.110348 0.003005 2.407758 -v 0.037224 -0.007667 0.090409 -vn -0.402629 -0.001141 -3.164091 -v 0.036425 -0.007478 0.093040 -vn 0.054371 -0.002108 -3.215626 -v 0.036212 -0.007485 0.093049 -vn -2.120838 -0.001152 -2.427945 -v 0.037261 -0.007448 0.092658 -vn -1.809733 -0.002666 -2.677015 -v 0.037057 -0.007456 0.092814 -vn -3.167033 -0.006306 -0.597123 -v 0.037723 -0.007418 0.091835 -vn -3.144915 -0.004500 -0.902395 -v 0.037683 -0.007423 0.091994 -vn -0.718854 -0.013430 3.108172 -v 0.036610 -0.007345 0.090094 -vn -1.101988 0.001023 3.013640 -v 0.036752 -0.007350 0.090137 -vn 1.182857 -0.005861 3.008242 -v 0.035655 -0.007314 0.090173 -vn 0.717260 -0.002021 3.133069 -v 0.035940 -0.007324 0.090082 -vn 1.509923 -0.001184 2.869686 -v 0.035594 -0.007312 0.090201 -vn 1.764751 -0.006274 -2.684064 -v 0.035400 -0.007212 0.092786 -vn 2.028844 -0.020967 -2.472068 -v 0.035314 -0.007216 0.092722 -vn 2.397464 -0.001218 -2.147778 -v 0.035127 -0.007224 0.092544 -vn 2.670915 -0.009146 -1.779516 -v 0.035000 -0.007231 0.092379 -vn 2.857889 -0.003449 -1.482615 -v 0.034919 -0.007236 0.092243 -vn 3.008079 0.001408 -1.181906 -v 0.034850 -0.007241 0.092088 -vn 3.139603 -0.000810 -0.936740 -v 0.034806 -0.007246 0.091954 -vn 3.176204 0.005874 -0.757208 -v 0.034800 -0.007246 0.091932 -vn 3.173434 0.015947 -0.491388 -v 0.034766 -0.007252 0.091772 -vn 3.213264 -0.004520 0.256711 -v 0.034754 -0.007262 0.091445 -vn 3.167832 -0.005614 0.635039 -v 0.034785 -0.007269 0.091229 -vn 3.063677 -0.012560 0.970676 -v 0.034812 -0.007272 0.091123 -vn 2.960532 -0.008772 1.290983 -v 0.034882 -0.007279 0.090935 -vn 3.270920 0.001372 -0.195150 -v 0.034751 -0.007257 0.091609 -vn 3.263648 0.000616 -0.025092 -v 0.034751 -0.007257 0.091593 -vn 2.788779 -0.000248 1.605434 -v 0.034939 -0.007283 0.090821 -vn 2.587044 0.002655 1.937102 -v 0.035071 -0.007290 0.090622 -vn 2.363580 0.004856 2.212726 -v 0.035128 -0.007293 0.090555 -vn 1.946394 0.002568 2.520039 -v 0.035330 -0.007302 0.090365 -vn 0.286333 -0.004043 3.201524 -v 0.036105 -0.007329 0.090057 -vn -0.146497 -0.004041 3.196398 -v 0.036303 -0.007335 0.090051 -vn -2.091675 0.025393 2.421747 -v 0.037251 -0.007369 0.090433 -vn -1.748557 0.007505 2.698152 -v 0.037046 -0.007360 0.090279 -vn -1.469843 0.009028 2.871223 -v 0.036952 -0.007357 0.090225 -vn -2.294812 0.013628 2.280533 -v 0.037303 -0.007371 0.090482 -vn -2.482171 0.003125 2.088440 -v 0.037413 -0.007376 0.090603 -vn -2.650748 -0.000813 1.934411 -v 0.037459 -0.007378 0.090663 -vn -2.760202 -0.003136 1.690997 -v 0.037510 -0.007381 0.090736 -vn -2.954730 0.003081 1.230269 -v 0.037638 -0.007390 0.090982 -vn -3.113466 0.011519 0.804267 -v 0.037705 -0.007397 0.091184 -vn -3.162039 0.012944 0.412877 -v 0.037734 -0.007402 0.091334 -vn -3.192635 -0.030473 -0.097684 -v 0.037747 -0.007412 0.091644 -vn -3.229794 -0.011853 -0.324742 -v 0.037745 -0.007413 0.091673 -vn -2.887193 -0.000660 -1.477514 -v 0.037565 -0.007433 0.092272 -vn -3.055720 -0.008975 -1.095306 -v 0.037680 -0.007423 0.092003 -vn -2.396755 -0.001673 -2.163233 -v 0.037339 -0.007445 0.092582 -vn -2.698815 0.001321 -1.777516 -v 0.037528 -0.007435 0.092335 -vn -1.002559 0.001455 -3.018203 -v 0.036728 -0.007468 0.092972 -vn -1.535515 0.000183 -2.849069 -v 0.036997 -0.007459 0.092851 -vn 0.510523 -0.002553 -3.241104 -v 0.036049 -0.007490 0.093037 -vn 0.337425 -0.002234 -3.253394 -v 0.036060 -0.007490 0.093038 -vn 0.790774 -0.014025 -3.109352 -v 0.035889 -0.007495 0.093006 -vn 1.062168 -0.012620 -3.073533 -v 0.035732 -0.007500 0.092958 -vn 1.275319 -0.004599 -2.963537 -v 0.035706 -0.007501 0.092948 -vn 1.697453 0.002267 -2.723361 -v 0.035430 -0.007511 0.092806 -vn 2.050016 -0.000054 -2.493603 -v 0.035306 -0.007516 0.092716 -vn 2.344464 -0.001586 -2.217953 -v 0.035151 -0.007523 0.092571 -vn 2.550885 -0.000816 -1.961458 -v 0.035076 -0.007527 0.092483 -vn 2.793180 -0.000046 -1.652327 -v 0.034937 -0.007535 0.092275 -vn 2.931701 -0.004903 -1.369369 -v 0.034912 -0.007536 0.092229 -vn 3.057586 -0.003970 -0.957238 -v 0.034816 -0.007544 0.091989 -vn 3.156634 0.022069 -0.467845 -v 0.034765 -0.007552 0.091761 -vn 3.256245 0.010060 -0.241788 -v 0.034752 -0.007556 0.091630 -vn 3.269353 0.001706 -0.039053 -v 0.034751 -0.007557 0.091598 -vn 3.220480 0.001398 0.254532 -v 0.034754 -0.007562 0.091434 -vn 3.236320 -0.002190 0.523419 -v 0.034776 -0.007568 0.091272 -vn 3.213588 0.001075 0.697104 -v 0.034777 -0.007568 0.091265 -vn 3.063217 0.016719 0.953736 -v 0.034815 -0.007573 0.091112 -vn 3.046957 0.008128 1.185104 -v 0.034867 -0.007578 0.090969 -vn 2.979105 -0.002121 1.365911 -v 0.034872 -0.007578 0.090958 -vn 1.468038 0.003210 2.834163 -v 0.035560 -0.007611 0.090218 -vn 1.999696 0.001447 2.492549 -v 0.035302 -0.007601 0.090388 -vn 2.374532 0.002288 2.196579 -v 0.035135 -0.007594 0.090546 -vn 2.815883 -0.004337 1.588043 -v 0.034944 -0.007583 0.090812 -vn 2.699300 0.000577 1.856613 -v 0.035033 -0.007588 0.090674 -vn 2.600430 0.000489 2.009397 -v 0.035049 -0.007589 0.090652 -vn 0.000464 -0.001096 3.210708 -v 0.036266 -0.007634 0.090050 -vn 0.498989 -0.000455 3.205255 -v 0.035979 -0.007625 0.090075 -vn 0.763888 0.000520 3.188526 -v 0.035903 -0.007622 0.090091 -vn 1.016149 0.003692 3.061312 -v 0.035819 -0.007620 0.090113 -vn -0.391389 0.001533 3.214304 -v 0.036443 -0.007640 0.090063 -vn -0.661014 0.006580 3.206133 -v 0.036574 -0.007644 0.090085 -vn -0.831660 0.002399 3.160177 -v 0.036605 -0.007645 0.090093 -vn -1.111329 0.004305 3.028214 -v 0.036762 -0.007650 0.090140 -vn -1.368221 0.002555 2.976433 -v 0.036913 -0.007655 0.090205 -vn -1.539127 -0.006101 2.886497 -v 0.036918 -0.007656 0.090207 -vn -1.720811 -0.011808 2.701641 -v 0.037056 -0.007661 0.090285 -vn -2.498624 -0.005532 2.001840 -v 0.037437 -0.007677 0.090633 -vn -2.705616 -0.017126 1.701271 -v 0.037516 -0.007682 0.090745 -vn -3.148131 0.001088 0.526524 -v 0.037729 -0.007701 0.091298 -vn -3.048808 -0.009316 1.036499 -v 0.037660 -0.007692 0.091038 -vn -2.929888 -0.010190 1.330547 -v 0.037624 -0.007689 0.090947 -vn -3.192328 -0.023661 -0.043121 -v 0.037749 -0.007710 0.091607 -vn -3.205802 -0.007118 -0.361525 -v 0.037744 -0.007713 0.091683 -vn -3.084925 0.000367 -0.859733 -v 0.037691 -0.007722 0.091968 -vn -2.960411 -0.002594 -1.298357 -v 0.037621 -0.007729 0.092158 -vn -2.731434 -0.005537 -1.660573 -v 0.037547 -0.007734 0.092304 -vn -2.428812 -0.004767 -2.101075 -v 0.037364 -0.007744 0.092554 -vn -0.522888 -0.009704 -3.172091 -v 0.036462 -0.007777 0.093035 -vn -1.067854 0.001311 -3.008146 -v 0.036763 -0.007767 0.092960 -vn -1.549252 -0.003641 -2.834635 -v 0.036988 -0.007759 0.092856 -vn -0.196758 -0.022487 -3.185421 -v 0.036365 -0.007780 0.093045 -vn 0.255539 0.014626 -3.209680 -v 0.036096 -0.007789 0.093042 -vn 0.554564 0.009815 -3.173932 -v 0.036038 -0.007790 0.093035 -vn 1.070697 0.000153 -2.997786 -v 0.035741 -0.007800 0.092961 -vn 1.607106 -0.005147 -2.799064 -v 0.035462 -0.007810 0.092826 -vn 1.821218 -0.004577 -2.703025 -v 0.035430 -0.007811 0.092806 -vn 2.052182 0.014936 -2.465067 -v 0.035298 -0.007816 0.092709 -vn 2.295909 0.004413 -2.245728 -v 0.035177 -0.007822 0.092598 -vn 2.535009 -0.002544 -1.979802 -v 0.035069 -0.007827 0.092475 -vn 2.781749 -0.002169 -1.665691 -v 0.034955 -0.007833 0.092307 -vn 3.140373 0.002855 -0.717618 -v 0.034794 -0.007847 0.091912 -vn 3.057983 0.002990 -1.051439 -v 0.034827 -0.007843 0.092024 -vn 2.934058 -0.000040 -1.364751 -v 0.034896 -0.007837 0.092196 -vn 3.199186 0.015043 0.001076 -v 0.034750 -0.007857 0.091587 -vn 3.199246 0.006100 -0.323647 -v 0.034754 -0.007855 0.091666 -vn 2.690442 -0.001284 1.841436 -v 0.035028 -0.007888 0.090681 -vn 2.814380 0.002002 1.610227 -v 0.034950 -0.007884 0.090802 -vn 2.973787 0.001536 1.356874 -v 0.034876 -0.007878 0.090949 -vn 2.602256 -0.002182 1.977567 -v 0.035039 -0.007889 0.090665 -vn 2.387386 0.001105 2.191024 -v 0.035143 -0.007894 0.090538 -vn 1.598578 -0.001251 2.796861 -v 0.035529 -0.007910 0.090235 -vn 2.006331 0.020833 2.510217 -v 0.035273 -0.007900 0.090412 -vn 2.195880 0.011393 2.408608 -v 0.035260 -0.007899 0.090423 -vn 1.201637 -0.007331 2.981222 -v 0.035675 -0.007915 0.090165 -vn 0.856399 -0.000999 3.108078 -v 0.035868 -0.007921 0.090099 -vn 0.518645 0.003535 3.187942 -v 0.035989 -0.007925 0.090073 -vn 0.092397 -0.026158 3.191653 -v 0.036230 -0.007933 0.090050 -vn -0.197180 0.000411 3.210774 -v 0.036316 -0.007936 0.090051 -vn -1.072945 -0.000813 3.029559 -v 0.036771 -0.007951 0.090144 -vn -0.625623 -0.000931 3.129805 -v 0.036539 -0.007943 0.090078 -vn -2.072459 0.003111 2.464185 -v 0.037195 -0.007966 0.090385 -vn -1.714214 0.011408 2.709955 -v 0.037065 -0.007961 0.090291 -vn -1.397707 0.007628 2.905497 -v 0.036886 -0.007955 0.090192 -vn -2.426301 -0.016136 2.114249 -v 0.037415 -0.007976 0.090605 -vn -2.594252 -0.003100 1.963317 -v 0.037427 -0.007977 0.090620 -vn -2.713063 0.012378 1.718670 -v 0.037521 -0.007982 0.090754 -vn -2.914506 0.007104 1.471696 -v 0.037601 -0.007987 0.090897 -vn -2.967524 0.013272 1.257499 -v 0.037608 -0.007988 0.090914 -vn -3.118894 0.005722 0.855464 -v 0.037710 -0.007998 0.091206 -vn -3.196162 0.001067 0.515211 -v 0.037722 -0.007999 0.091261 -vn -3.187757 -0.000565 -0.034360 -v 0.037750 -0.008009 0.091570 -vn -3.192942 0.000074 -0.574875 -v 0.037718 -0.008018 0.091856 -vn -3.146500 -0.002787 -0.849377 -v 0.037701 -0.008021 0.091932 -vn -2.758994 0.003881 -1.707532 -v 0.037542 -0.008034 0.092313 -vn -2.301464 0.000426 -2.288234 -v 0.037345 -0.008045 0.092575 -vn -2.501964 -0.000843 -2.123626 -v 0.037389 -0.008042 0.092526 -vn -2.616453 -0.003588 -1.893468 -v 0.037451 -0.008039 0.092449 -vn -1.578705 -0.004499 -2.824171 -v 0.036979 -0.008059 0.092861 -vn -1.830317 -0.001365 -2.721857 -v 0.037118 -0.008054 0.092773 -vn -2.004176 -0.001893 -2.577150 -v 0.037119 -0.008054 0.092772 -vn -0.582346 -0.005200 -3.145967 -v 0.036499 -0.008076 0.093029 -vn -1.071930 0.011044 -3.036942 -v 0.036797 -0.008066 0.092947 -vn -1.305478 0.006303 -2.986342 -v 0.036831 -0.008065 0.092933 -vn -0.215193 -0.025078 -3.177784 -v 0.036355 -0.008080 0.093046 -vn 0.213702 0.010608 -3.217886 -v 0.036134 -0.008087 0.093045 -vn 0.537060 0.007581 -3.176189 -v 0.036028 -0.008091 0.093033 -vn 1.024469 0.008822 -3.001130 -v 0.035776 -0.008099 0.092973 -vn 1.842712 -0.000714 -2.640589 -v 0.035421 -0.008112 0.092800 -vn 1.541713 0.000926 -2.817859 -v 0.035493 -0.008109 0.092845 -vn 2.390075 0.000566 -2.209114 -v 0.035170 -0.008122 0.092590 -vn 2.547326 0.004125 -1.970844 -v 0.035063 -0.008127 0.092466 -vn 2.737499 0.011468 -1.636388 -v 0.034974 -0.008132 0.092339 -vn 2.964603 -0.032508 -1.181450 -v 0.034839 -0.008142 0.092059 -vn 3.090354 -0.010417 -0.998994 -v 0.034831 -0.008143 0.092035 -vn 3.146700 0.001819 -0.705990 -v 0.034786 -0.008148 0.091877 -vn 3.218017 0.000155 -0.355192 -v 0.034758 -0.008154 0.091703 -vn 3.218423 -0.005843 0.004457 -v 0.034750 -0.008158 0.091577 -vn 3.158473 -0.006144 0.467562 -v 0.034765 -0.008165 0.091338 -vn 2.719391 0.003214 1.743068 -v 0.035007 -0.008187 0.090711 -vn 2.533747 0.006722 1.986337 -v 0.035045 -0.008189 0.090656 -vn 2.166751 0.004324 2.360114 -v 0.035246 -0.008199 0.090436 -vn 1.831764 -0.013552 2.604249 -v 0.035397 -0.008205 0.090316 -vn 1.599450 -0.010354 2.806390 -v 0.035496 -0.008208 0.090253 -vn 1.225540 -0.000718 2.976114 -v 0.035685 -0.008215 0.090160 -vn 0.986919 -0.000059 3.112145 -v 0.035833 -0.008220 0.090109 -vn 0.819885 -0.001024 3.177928 -v 0.035840 -0.008220 0.090107 -vn 0.544344 -0.000168 3.195741 -v 0.036000 -0.008226 0.090071 -vn -1.299834 0.002292 2.944973 -v 0.036851 -0.008253 0.090176 -vn -0.857818 0.018538 3.078006 -v 0.036650 -0.008246 0.090104 -vn -0.539556 0.010502 3.183268 -v 0.036501 -0.008242 0.090071 -vn -0.184554 0.002248 3.232518 -v 0.036326 -0.008236 0.090052 -vn 0.076169 0.000587 3.259667 -v 0.036193 -0.008232 0.090051 -vn 0.248464 0.001487 3.259090 -v 0.036162 -0.008231 0.090053 -vn -1.713944 0.003778 2.690149 -v 0.037063 -0.008261 0.090289 -vn -1.791003 0.029552 0.644263 -v 0.037166 -0.008265 0.090363 -vn -2.879462 -3.416760 1.921652 -v 0.025251 -0.033207 0.097954 -vn -2.424102 -0.771151 1.826478 -v 0.025244 -0.033292 0.097908 -vn -3.410940 -1.751635 3.223794 -v 0.025309 -0.033292 0.098000 -vn -0.187686 -1.104705 -3.386721 -v 0.025480 -0.033292 0.098350 -vn -1.196478 -2.844121 -3.358138 -v 0.025364 -0.033272 0.098350 -vn -3.202107 -2.945667 0.455085 -v 0.025221 -0.033178 0.098000 -vn -3.171120 -0.316167 1.738829 -v 0.025171 -0.033292 0.097814 -vn -2.248593 -2.055293 -3.635259 -v 0.025221 -0.033178 0.098350 -vn -2.954030 -0.744356 -3.635275 -v 0.025140 -0.033027 0.098350 -vn -2.954030 -0.744356 0.000000 -v 0.025140 -0.033027 0.098000 -vn -2.954030 0.744356 -3.635275 -v 0.025140 -0.032856 0.098350 -vn -2.954030 0.744356 0.000000 -v 0.025140 -0.032856 0.098000 -vn -2.248593 2.055293 -3.635259 -v 0.025221 -0.032706 0.098350 -vn -2.248593 2.055293 0.000000 -v 0.025221 -0.032706 0.098000 -vn -1.128463 2.859542 -3.556750 -v 0.025364 -0.032611 0.098350 -vn -1.128463 2.859542 0.000000 -v 0.025364 -0.032611 0.098000 -vn -0.263104 1.548605 -3.478173 -v 0.025480 -0.032592 0.098350 -vn -0.263104 1.548605 0.000000 -v 0.025480 -0.032592 0.098000 -vn -2.879481 -3.416735 1.921680 -v 0.032751 -0.033207 0.097954 -vn -2.424109 -0.771143 1.826466 -v 0.032744 -0.033292 0.097908 -vn -3.410981 -1.751604 3.223796 -v 0.032809 -0.033292 0.098000 -vn -0.187683 -1.104701 -3.386721 -v 0.032980 -0.033292 0.098350 -vn -1.196489 -2.844111 -3.358153 -v 0.032864 -0.033272 0.098350 -vn -3.202145 -2.945637 0.455087 -v 0.032721 -0.033178 0.098000 -vn -3.171128 -0.316161 1.738826 -v 0.032671 -0.033292 0.097814 -vn -2.248601 -2.055296 -3.635237 -v 0.032721 -0.033178 0.098350 -vn -2.954023 -0.744370 -3.635284 -v 0.032640 -0.033027 0.098350 -vn -2.954023 -0.744370 0.000000 -v 0.032640 -0.033027 0.098000 -vn -2.954023 0.744370 -3.635285 -v 0.032640 -0.032856 0.098350 -vn -2.954023 0.744370 0.000000 -v 0.032640 -0.032856 0.098000 -vn -2.248601 2.055296 -3.635236 -v 0.032721 -0.032706 0.098350 -vn -2.248601 2.055296 0.000000 -v 0.032721 -0.032706 0.098000 -vn -1.128475 2.859532 -3.556766 -v 0.032864 -0.032611 0.098350 -vn -1.128475 2.859532 0.000000 -v 0.032864 -0.032611 0.098000 -vn -0.263100 1.548606 -3.478178 -v 0.032980 -0.032592 0.098350 -vn -0.263100 1.548606 0.000000 -v 0.032980 -0.032592 0.098000 -vn -2.879474 -3.416707 1.921631 -v 0.030251 -0.033207 0.097954 -vn -2.424131 -0.771091 1.826471 -v 0.030244 -0.033292 0.097908 -vn -3.410962 -1.751607 3.223795 -v 0.030309 -0.033292 0.098000 -vn -0.187686 -1.104705 -3.386720 -v 0.030480 -0.033292 0.098350 -vn -1.196486 -2.844115 -3.358144 -v 0.030364 -0.033272 0.098350 -vn -3.202124 -2.945648 0.455078 -v 0.030221 -0.033178 0.098000 -vn -3.171129 -0.316155 1.738824 -v 0.030171 -0.033292 0.097814 -vn -2.248600 -2.055288 -3.635252 -v 0.030221 -0.033178 0.098350 -vn -2.954030 -0.744356 -3.635273 -v 0.030140 -0.033027 0.098350 -vn -2.954030 -0.744356 0.000000 -v 0.030140 -0.033027 0.098000 -vn -2.954030 0.744356 -3.635272 -v 0.030140 -0.032856 0.098350 -vn -2.954030 0.744356 0.000000 -v 0.030140 -0.032856 0.098000 -vn -2.248600 2.055288 -3.635252 -v 0.030221 -0.032706 0.098350 -vn -2.248600 2.055287 0.000000 -v 0.030221 -0.032706 0.098000 -vn -1.128471 2.859536 -3.556756 -v 0.030364 -0.032611 0.098350 -vn -1.128471 2.859536 0.000000 -v 0.030364 -0.032611 0.098000 -vn -0.263104 1.548605 -3.478173 -v 0.030480 -0.032592 0.098350 -vn -0.263104 1.548605 0.000000 -v 0.030480 -0.032592 0.098000 -vn -2.879470 -3.416763 1.921710 -v 0.027751 -0.033207 0.097954 -vn -2.424102 -0.771151 1.826478 -v 0.027744 -0.033292 0.097908 -vn -3.410952 -1.751618 3.223804 -v 0.027809 -0.033292 0.098000 -vn -0.187686 -1.104705 -3.386721 -v 0.027980 -0.033292 0.098350 -vn -1.196486 -2.844115 -3.358144 -v 0.027864 -0.033272 0.098350 -vn -3.202128 -2.945655 0.455094 -v 0.027721 -0.033178 0.098000 -vn -3.171120 -0.316160 1.738826 -v 0.027671 -0.033292 0.097814 -vn -2.248593 -2.055301 -3.635243 -v 0.027721 -0.033178 0.098350 -vn -2.954023 -0.744370 -3.635283 -v 0.027640 -0.033027 0.098350 -vn -2.954023 -0.744370 0.000000 -v 0.027640 -0.033027 0.098000 -vn -2.954023 0.744370 -3.635283 -v 0.027640 -0.032856 0.098350 -vn -2.954023 0.744370 0.000000 -v 0.027640 -0.032856 0.098000 -vn -2.248593 2.055301 -3.635243 -v 0.027721 -0.032706 0.098350 -vn -2.248593 2.055301 0.000000 -v 0.027721 -0.032706 0.098000 -vn -1.128471 2.859536 -3.556756 -v 0.027864 -0.032611 0.098350 -vn -1.128471 2.859536 0.000000 -v 0.027864 -0.032611 0.098000 -vn -0.263104 1.548605 -3.478174 -v 0.027980 -0.032592 0.098350 -vn -0.263104 1.548605 0.000000 -v 0.027980 -0.032592 0.098000 -vn 6.055986 -0.877506 0.000000 -v 0.025830 -0.038062 0.097650 -vn 3.097522 0.002864 0.000000 -v 0.025830 -0.033292 0.097650 -vn 5.995529 -0.798909 1.193684 -v 0.025821 -0.038062 0.097728 -vn 2.860457 0.004421 1.127754 -v 0.025810 -0.033292 0.097766 -vn -3.073392 0.004799 0.115826 -v 0.025130 -0.033292 0.097650 -vn -5.969041 -1.077886 0.117120 -v 0.025130 -0.038062 0.097650 -vn -5.979476 -0.881312 1.094216 -v 0.025138 -0.038062 0.097728 -vn -5.600945 -0.850742 2.325550 -v 0.025149 -0.038062 0.097766 -vn -4.908897 -0.792536 3.570403 -v 0.025206 -0.038062 0.097868 -vn -2.517453 0.000523 1.879370 -v 0.025242 -0.033292 0.097910 -vn -3.936906 -0.881224 4.607181 -v 0.025244 -0.038062 0.097908 -vn -2.747484 -0.803767 5.413263 -v 0.025328 -0.038062 0.097965 -vn 0.185603 -0.007021 3.130302 -v 0.025394 -0.033292 0.097989 -vn -1.411517 -0.876337 5.889617 -v 0.025394 -0.038062 0.097989 -vn 0.000008 -0.790812 6.069571 -v 0.025480 -0.038062 0.098000 -vn 0.744666 0.006800 2.955057 -v 0.025565 -0.033292 0.097989 -vn 1.411526 -0.876335 5.889617 -v 0.025565 -0.038062 0.097989 -vn 2.754318 -0.790661 5.408704 -v 0.025632 -0.038062 0.097965 -vn 2.056107 0.006339 2.249178 -v 0.025716 -0.033292 0.097908 -vn 3.930451 -0.867768 4.611487 -v 0.025716 -0.038062 0.097908 -vn 4.909079 -0.790165 3.569842 -v 0.025753 -0.038062 0.097868 -vn 5.600042 -0.851467 2.327864 -v 0.025810 -0.038062 0.097766 -vn 5.969003 -1.077892 -0.117143 -v 0.033330 -0.038062 0.097650 -vn 3.097522 0.002863 0.000000 -v 0.033330 -0.033292 0.097650 -vn 5.995591 -0.798865 1.193629 -v 0.033321 -0.038062 0.097728 -vn 2.860461 0.004421 1.127740 -v 0.033310 -0.033292 0.097766 -vn -3.073380 0.004799 0.115794 -v 0.032630 -0.033292 0.097650 -vn -6.055969 -0.877473 0.000000 -v 0.032630 -0.038062 0.097650 -vn -5.995083 -0.796521 1.195305 -v 0.032638 -0.038062 0.097728 -vn -5.600961 -0.850686 2.325660 -v 0.032649 -0.038062 0.097766 -vn -4.908925 -0.792495 3.570375 -v 0.032706 -0.038062 0.097868 -vn -2.517465 0.000522 1.879354 -v 0.032742 -0.033292 0.097910 -vn -3.936923 -0.881213 4.607180 -v 0.032744 -0.038062 0.097908 -vn -2.747509 -0.803788 5.413235 -v 0.032828 -0.038062 0.097965 -vn 0.185603 -0.007021 3.130301 -v 0.032894 -0.033292 0.097989 -vn -1.411512 -0.876346 5.889613 -v 0.032894 -0.038062 0.097989 -vn 0.000016 -0.790812 6.069572 -v 0.032980 -0.038062 0.098000 -vn 0.744659 0.006800 2.955061 -v 0.033065 -0.033292 0.097989 -vn 1.411530 -0.876342 5.889614 -v 0.033065 -0.038062 0.097989 -vn 2.754292 -0.790685 5.408715 -v 0.033132 -0.038062 0.097965 -vn 2.056108 0.006339 2.249169 -v 0.033216 -0.033292 0.097908 -vn 3.930416 -0.867803 4.611492 -v 0.033216 -0.038062 0.097908 -vn 4.909084 -0.790204 3.569791 -v 0.033253 -0.038062 0.097868 -vn 5.600087 -0.851457 2.327715 -v 0.033310 -0.038062 0.097766 -vn 5.969041 -1.077886 -0.117120 -v 0.030830 -0.038062 0.097650 -vn 3.097514 0.002865 0.000000 -v 0.030830 -0.033292 0.097650 -vn 5.995479 -0.798905 1.193816 -v 0.030821 -0.038062 0.097728 -vn 2.860456 0.004422 1.127764 -v 0.030810 -0.033292 0.097766 -vn -3.073384 0.004800 0.115818 -v 0.030130 -0.033292 0.097650 -vn -6.055986 -0.877506 0.000000 -v 0.030130 -0.038062 0.097650 -vn -5.995070 -0.796568 1.195229 -v 0.030138 -0.038062 0.097728 -vn -5.600946 -0.850730 2.325653 -v 0.030149 -0.038062 0.097766 -vn -4.908913 -0.792534 3.570363 -v 0.030206 -0.038062 0.097868 -vn -2.517465 0.000523 1.879354 -v 0.030242 -0.033292 0.097910 -vn -3.936897 -0.881236 4.607183 -v 0.030244 -0.038062 0.097908 -vn -2.747484 -0.803789 5.413255 -v 0.030328 -0.038062 0.097965 -vn 0.185603 -0.007021 3.130302 -v 0.030394 -0.033292 0.097989 -vn -1.411521 -0.876344 5.889614 -v 0.030394 -0.038062 0.097989 -vn -0.000000 -0.790812 6.069572 -v 0.030480 -0.038062 0.098000 -vn 0.744666 0.006800 2.955057 -v 0.030565 -0.033292 0.097989 -vn 1.411521 -0.876344 5.889614 -v 0.030565 -0.038062 0.097989 -vn 2.754317 -0.790684 5.408696 -v 0.030632 -0.038062 0.097965 -vn 2.056115 0.006340 2.249166 -v 0.030716 -0.033292 0.097908 -vn 3.930442 -0.867779 4.611489 -v 0.030716 -0.038062 0.097908 -vn 4.909094 -0.790163 3.569802 -v 0.030753 -0.038062 0.097868 -vn 5.600045 -0.851455 2.327967 -v 0.030810 -0.038062 0.097766 -vn 6.055969 -0.877473 0.000000 -v 0.028330 -0.038062 0.097650 -vn 3.097514 0.002863 0.000000 -v 0.028330 -0.033292 0.097650 -vn 5.995542 -0.798861 1.193760 -v 0.028321 -0.038062 0.097728 -vn 2.860457 0.004421 1.127764 -v 0.028310 -0.033292 0.097766 -vn -3.073388 0.004800 0.115802 -v 0.027630 -0.033292 0.097650 -vn -5.969041 -1.077886 0.117120 -v 0.027630 -0.038062 0.097650 -vn -5.979427 -0.881310 1.094347 -v 0.027638 -0.038062 0.097728 -vn -5.600946 -0.850732 2.325653 -v 0.027649 -0.038062 0.097766 -vn -4.908915 -0.792535 3.570365 -v 0.027706 -0.038062 0.097868 -vn -2.517453 0.000523 1.879370 -v 0.027742 -0.033292 0.097910 -vn -3.936897 -0.881236 4.607183 -v 0.027744 -0.038062 0.097908 -vn -2.747484 -0.803789 5.413255 -v 0.027828 -0.038062 0.097965 -vn 0.185603 -0.007021 3.130302 -v 0.027894 -0.033292 0.097989 -vn -1.411521 -0.876344 5.889614 -v 0.027894 -0.038062 0.097989 -vn 0.000000 -0.790812 6.069572 -v 0.027980 -0.038062 0.098000 -vn 0.744666 0.006800 2.955057 -v 0.028065 -0.033292 0.097989 -vn 1.411521 -0.876344 5.889614 -v 0.028065 -0.038062 0.097989 -vn 2.754317 -0.790684 5.408696 -v 0.028132 -0.038062 0.097965 -vn 2.056115 0.006340 2.249166 -v 0.028216 -0.033292 0.097908 -vn 3.930442 -0.867779 4.611489 -v 0.028216 -0.038062 0.097908 -vn 4.909094 -0.790163 3.569802 -v 0.028253 -0.038062 0.097868 -vn 5.600074 -0.851433 2.327845 -v 0.028310 -0.038062 0.097766 -vn -2.195251 -2.939848 4.528641 -v 0.025339 -0.038162 0.097941 -vn -3.035388 -5.025118 -0.692827 -v 0.025236 -0.038235 0.097594 -vn -0.900505 -6.139815 -0.205527 -v 0.025333 -0.038262 0.097617 -vn -0.900516 -6.139809 0.205557 -v 0.025333 -0.038262 0.097683 -vn -2.434207 -5.025133 -1.941206 -v 0.025284 -0.038235 0.097494 -vn -0.722169 -6.139807 -0.575903 -v 0.025362 -0.038262 0.097556 -vn -1.350894 -5.025092 -2.805131 -v 0.025371 -0.038235 0.097425 -vn -0.400735 -6.139827 -0.832167 -v 0.025415 -0.038262 0.097515 -vn -0.000004 -6.139815 -0.923658 -v 0.025480 -0.038262 0.097500 -vn -0.000000 -5.025080 -3.113473 -v 0.025480 -0.038235 0.097400 -vn 0.000006 -2.944085 -5.032584 -v 0.025480 -0.038162 0.097327 -vn -3.035385 -5.025159 0.692754 -v 0.025236 -0.038235 0.097706 -vn -4.923483 -2.872626 1.059717 -v 0.025165 -0.038162 0.097722 -vn -4.906815 -2.930257 -1.092402 -v 0.025165 -0.038162 0.097578 -vn -0.722146 -6.139824 0.575853 -v 0.025362 -0.038262 0.097744 -vn -2.434163 -5.025105 1.941231 -v 0.025284 -0.038235 0.097806 -vn -3.950104 -2.926235 3.119604 -v 0.025227 -0.038162 0.097852 -vn -2.195300 -2.939770 -4.528719 -v 0.025339 -0.038162 0.097359 -vn -2.754318 -0.790661 -5.408704 -v 0.025328 -0.038062 0.097335 -vn -1.411517 -0.876337 -5.889617 -v 0.025394 -0.038062 0.097311 -vn 0.000008 -0.790812 -6.069571 -v 0.025480 -0.038062 0.097300 -vn -3.950130 -2.926219 -3.119606 -v 0.025227 -0.038162 0.097448 -vn -4.909079 -0.790165 -3.569842 -v 0.025206 -0.038062 0.097432 -vn -3.930451 -0.867768 -4.611487 -v 0.025244 -0.038062 0.097392 -vn -5.995529 -0.798909 -1.193684 -v 0.025138 -0.038062 0.097572 -vn -5.600043 -0.851467 -2.327864 -v 0.025149 -0.038062 0.097534 -vn -1.350852 -5.025216 2.805097 -v 0.025371 -0.038235 0.097875 -vn -0.400780 -6.139808 0.832206 -v 0.025415 -0.038262 0.097785 -vn 0.000010 -2.944177 5.032475 -v 0.025480 -0.038162 0.097973 -vn 0.000012 -5.025205 3.113414 -v 0.025480 -0.038235 0.097900 -vn 0.000010 -6.139795 0.923722 -v 0.025480 -0.038262 0.097800 -vn -2.195241 -2.939854 4.528659 -v 0.032839 -0.038162 0.097941 -vn -3.950102 -2.926192 3.119587 -v 0.032727 -0.038162 0.097852 -vn -4.900128 -2.951440 1.130998 -v 0.032665 -0.038162 0.097722 -vn -5.995492 -0.798857 -1.193892 -v 0.032638 -0.038062 0.097572 -vn -4.900154 -2.951421 -1.130988 -v 0.032665 -0.038162 0.097578 -vn -5.600060 -0.851410 -2.327974 -v 0.032649 -0.038062 0.097534 -vn -4.909104 -0.790123 -3.569812 -v 0.032706 -0.038062 0.097432 -vn -3.950118 -2.926177 -3.119600 -v 0.032727 -0.038162 0.097448 -vn -3.930469 -0.867756 -4.611486 -v 0.032744 -0.038062 0.097392 -vn -2.754342 -0.790683 -5.408677 -v 0.032828 -0.038062 0.097335 -vn -2.195297 -2.939780 -4.528728 -v 0.032839 -0.038162 0.097359 -vn -1.411512 -0.876346 -5.889613 -v 0.032894 -0.038062 0.097311 -vn 0.000016 -0.790812 -6.069572 -v 0.032980 -0.038062 0.097300 -vn 0.000016 -2.944087 -5.032583 -v 0.032980 -0.038162 0.097327 -vn -1.350918 -5.025070 -2.805131 -v 0.032871 -0.038235 0.097425 -vn 0.000009 -5.025080 -3.113474 -v 0.032980 -0.038235 0.097400 -vn -0.400743 -6.139824 -0.832169 -v 0.032915 -0.038262 0.097515 -vn -0.000001 -6.139816 -0.923657 -v 0.032980 -0.038262 0.097500 -vn -2.434176 -5.025165 -1.941214 -v 0.032784 -0.038235 0.097494 -vn -0.722171 -6.139809 -0.575896 -v 0.032862 -0.038262 0.097556 -vn -3.035370 -5.025120 -0.692834 -v 0.032736 -0.038235 0.097594 -vn -0.900492 -6.139819 -0.205529 -v 0.032833 -0.038262 0.097617 -vn -3.035372 -5.025153 0.692775 -v 0.032736 -0.038235 0.097706 -vn -0.900501 -6.139814 0.205554 -v 0.032833 -0.038262 0.097683 -vn -2.434151 -5.025138 1.941219 -v 0.032784 -0.038235 0.097806 -vn -0.722143 -6.139827 0.575844 -v 0.032862 -0.038262 0.097744 -vn -1.350855 -5.025203 2.805102 -v 0.032871 -0.038235 0.097875 -vn -0.400785 -6.139806 0.832208 -v 0.032915 -0.038262 0.097785 -vn 0.000017 -2.944179 5.032473 -v 0.032980 -0.038162 0.097973 -vn 0.000015 -5.025206 3.113415 -v 0.032980 -0.038235 0.097900 -vn 0.000013 -6.139795 0.923721 -v 0.032980 -0.038262 0.097800 -vn -2.195239 -2.939862 4.528662 -v 0.030339 -0.038162 0.097941 -vn -3.950103 -2.926221 3.119603 -v 0.030227 -0.038162 0.097852 -vn -4.900132 -2.951472 1.130977 -v 0.030165 -0.038162 0.097722 -vn -5.995480 -0.798905 -1.193816 -v 0.030138 -0.038062 0.097572 -vn -4.900150 -2.951458 -1.130973 -v 0.030165 -0.038162 0.097578 -vn -5.600045 -0.851455 -2.327967 -v 0.030149 -0.038062 0.097534 -vn -4.909094 -0.790163 -3.569802 -v 0.030206 -0.038062 0.097432 -vn -3.950124 -2.926207 -3.119605 -v 0.030227 -0.038162 0.097448 -vn -3.930442 -0.867779 -4.611489 -v 0.030244 -0.038062 0.097392 -vn -2.754317 -0.790684 -5.408696 -v 0.030328 -0.038062 0.097335 -vn -2.195292 -2.939785 -4.528737 -v 0.030339 -0.038162 0.097359 -vn -1.411521 -0.876344 -5.889614 -v 0.030394 -0.038062 0.097311 -vn 0.000000 -0.790812 -6.069572 -v 0.030480 -0.038062 0.097300 -vn -0.000000 -2.944088 -5.032583 -v 0.030480 -0.038162 0.097327 -vn -1.350907 -5.025079 -2.805134 -v 0.030371 -0.038235 0.097425 -vn -0.000003 -5.025080 -3.113474 -v 0.030480 -0.038235 0.097400 -vn -0.400745 -6.139825 -0.832167 -v 0.030415 -0.038262 0.097515 -vn -0.000007 -6.139816 -0.923657 -v 0.030480 -0.038262 0.097500 -vn -2.434199 -5.025130 -1.941210 -v 0.030284 -0.038235 0.097494 -vn -0.722147 -6.139814 -0.575900 -v 0.030362 -0.038262 0.097556 -vn -3.035388 -5.025118 -0.692827 -v 0.030236 -0.038235 0.097594 -vn -0.900504 -6.139815 -0.205532 -v 0.030333 -0.038262 0.097617 -vn -3.035382 -5.025160 0.692756 -v 0.030236 -0.038235 0.097706 -vn -0.900519 -6.139807 0.205572 -v 0.030333 -0.038262 0.097683 -vn -2.434160 -5.025106 1.941224 -v 0.030284 -0.038235 0.097806 -vn -0.722134 -6.139831 0.575841 -v 0.030362 -0.038262 0.097744 -vn -1.350855 -5.025206 2.805105 -v 0.030371 -0.038235 0.097875 -vn -0.400784 -6.139808 0.832205 -v 0.030415 -0.038262 0.097785 -vn 0.000000 -2.944179 5.032474 -v 0.030480 -0.038162 0.097973 -vn 0.000003 -5.025206 3.113415 -v 0.030480 -0.038235 0.097900 -vn 0.000007 -6.139796 0.923720 -v 0.030480 -0.038262 0.097800 -vn -2.195239 -2.939862 4.528662 -v 0.027839 -0.038162 0.097941 -vn -3.035388 -5.025118 -0.692827 -v 0.027736 -0.038235 0.097594 -vn -0.900505 -6.139815 -0.205527 -v 0.027833 -0.038262 0.097617 -vn -0.900516 -6.139809 0.205557 -v 0.027833 -0.038262 0.097683 -vn -2.434205 -5.025128 -1.941213 -v 0.027784 -0.038235 0.097494 -vn -0.722169 -6.139807 -0.575903 -v 0.027862 -0.038262 0.097556 -vn -1.350907 -5.025079 -2.805136 -v 0.027871 -0.038235 0.097425 -vn -0.400735 -6.139827 -0.832167 -v 0.027915 -0.038262 0.097515 -vn -0.000007 -6.139816 -0.923657 -v 0.027980 -0.038262 0.097500 -vn -0.000003 -5.025080 -3.113474 -v 0.027980 -0.038235 0.097400 -vn -0.000000 -2.944088 -5.032583 -v 0.027980 -0.038162 0.097327 -vn -3.035385 -5.025159 0.692754 -v 0.027736 -0.038235 0.097706 -vn -4.923482 -2.872607 1.059733 -v 0.027665 -0.038162 0.097722 -vn -4.906815 -2.930237 -1.092418 -v 0.027665 -0.038162 0.097578 -vn -0.722146 -6.139824 0.575853 -v 0.027862 -0.038262 0.097744 -vn -2.434163 -5.025105 1.941231 -v 0.027784 -0.038235 0.097806 -vn -3.950103 -2.926221 3.119603 -v 0.027727 -0.038162 0.097852 -vn -2.195292 -2.939785 -4.528737 -v 0.027839 -0.038162 0.097359 -vn -2.754317 -0.790684 -5.408696 -v 0.027828 -0.038062 0.097335 -vn -1.411521 -0.876344 -5.889614 -v 0.027894 -0.038062 0.097311 -vn 0.000000 -0.790812 -6.069572 -v 0.027980 -0.038062 0.097300 -vn -3.950124 -2.926207 -3.119606 -v 0.027727 -0.038162 0.097448 -vn -4.909094 -0.790163 -3.569802 -v 0.027706 -0.038062 0.097432 -vn -3.930442 -0.867779 -4.611489 -v 0.027744 -0.038062 0.097392 -vn -5.995480 -0.798905 -1.193816 -v 0.027638 -0.038062 0.097572 -vn -5.600045 -0.851455 -2.327967 -v 0.027649 -0.038062 0.097534 -vn -1.350855 -5.025206 2.805105 -v 0.027871 -0.038235 0.097875 -vn -0.400780 -6.139808 0.832206 -v 0.027915 -0.038262 0.097785 -vn 0.000000 -2.944179 5.032474 -v 0.027980 -0.038162 0.097973 -vn 0.000003 -5.025206 3.113415 -v 0.027980 -0.038235 0.097900 -vn 0.000007 -6.139796 0.923720 -v 0.027980 -0.038262 0.097800 -vn 0.000012 5.917474 0.764980 -v 0.025480 -0.032592 0.103550 -vn 0.000004 3.035458 3.659803 -v 0.025480 -0.032592 0.100250 -vn -2.113866 5.680759 0.786224 -v 0.025328 -0.032626 0.103550 -vn -1.516881 2.629617 3.657927 -v 0.025305 -0.032639 0.100250 -vn -3.424653 5.012281 0.833205 -v 0.025305 -0.032639 0.103550 -vn -4.521335 4.035954 0.788082 -v 0.025206 -0.032724 0.103550 -vn -2.629151 1.518596 3.655163 -v 0.025177 -0.032767 0.100250 -vn -5.360763 2.825755 0.865650 -v 0.025177 -0.032767 0.103550 -vn -5.882377 1.457647 0.789008 -v 0.025138 -0.032864 0.103550 -vn -3.036365 0.000008 3.654224 -v 0.025130 -0.032942 0.100250 -vn -6.055976 0.000016 0.877543 -v 0.025130 -0.032942 0.103550 -vn -5.882378 -1.457631 0.789008 -v 0.025138 -0.033020 0.103550 -vn -2.629154 -1.518588 3.655168 -v 0.025177 -0.033117 0.100250 -vn -5.360763 -2.825755 0.865650 -v 0.025177 -0.033117 0.103550 -vn -4.521335 -4.035955 0.788082 -v 0.025206 -0.033160 0.103550 -vn -1.516882 -2.629617 3.657927 -v 0.025305 -0.033245 0.100250 -vn -3.424653 -5.012281 0.833205 -v 0.025305 -0.033245 0.103550 -vn -2.113861 -5.680759 0.786228 -v 0.025328 -0.033257 0.103550 -vn 0.000004 -3.035458 3.659803 -v 0.025480 -0.033292 0.100250 -vn 0.000003 -5.917474 0.764980 -v 0.025480 -0.033292 0.103550 -vn 0.000022 5.917475 0.764982 -v 0.032980 -0.032592 0.103550 -vn 0.000008 3.035459 3.659801 -v 0.032980 -0.032592 0.100250 -vn -2.113862 5.680753 0.786239 -v 0.032828 -0.032626 0.103550 -vn -1.516878 2.629618 3.657929 -v 0.032805 -0.032639 0.100250 -vn -3.424659 5.012264 0.833216 -v 0.032805 -0.032639 0.103550 -vn -4.521321 4.036028 0.788049 -v 0.032706 -0.032724 0.103550 -vn -2.629151 1.518596 3.655165 -v 0.032677 -0.032767 0.100250 -vn -5.360730 2.825781 0.865620 -v 0.032677 -0.032767 0.103550 -vn -5.866770 1.356777 0.873719 -v 0.032638 -0.032864 0.103550 -vn -3.036365 0.000008 3.654226 -v 0.032630 -0.032942 0.100250 -vn -5.968989 0.117158 1.077932 -v 0.032630 -0.032942 0.103550 -vn -5.882414 -1.457662 0.788964 -v 0.032638 -0.033020 0.103550 -vn -2.629153 -1.518588 3.655170 -v 0.032677 -0.033117 0.100250 -vn -5.360730 -2.825781 0.865620 -v 0.032677 -0.033117 0.103550 -vn -4.521321 -4.036028 0.788049 -v 0.032706 -0.033160 0.103550 -vn -1.516878 -2.629618 3.657930 -v 0.032805 -0.033245 0.100250 -vn -3.424660 -5.012264 0.833216 -v 0.032805 -0.033245 0.103550 -vn -2.113854 -5.680753 0.786245 -v 0.032828 -0.033257 0.103550 -vn 0.000008 -3.035459 3.659800 -v 0.032980 -0.033292 0.100250 -vn 0.000009 -5.917476 0.764982 -v 0.032980 -0.033292 0.103550 -vn 0.000007 5.917475 0.764982 -v 0.030480 -0.032592 0.103550 -vn -0.000000 3.035456 3.659806 -v 0.030480 -0.032592 0.100250 -vn -2.113956 5.680697 0.786236 -v 0.030328 -0.032626 0.103550 -vn -1.516886 2.629618 3.657923 -v 0.030305 -0.032639 0.100250 -vn -3.424719 5.012263 0.833216 -v 0.030305 -0.032639 0.103550 -vn -4.521358 4.035894 0.788078 -v 0.030206 -0.032724 0.103550 -vn -2.629148 1.518611 3.655148 -v 0.030177 -0.032767 0.100250 -vn -5.360811 2.825737 0.865636 -v 0.030177 -0.032767 0.103550 -vn -5.866712 1.356814 0.873742 -v 0.030138 -0.032864 0.103550 -vn -3.036357 0.000008 3.654244 -v 0.030130 -0.032942 0.100250 -vn -5.969027 0.117135 1.077926 -v 0.030130 -0.032942 0.103550 -vn -5.882356 -1.457676 0.789006 -v 0.030138 -0.033020 0.103550 -vn -2.629150 -1.518603 3.655158 -v 0.030177 -0.033117 0.100250 -vn -5.360811 -2.825737 0.865636 -v 0.030177 -0.033117 0.103550 -vn -4.521358 -4.035894 0.788078 -v 0.030206 -0.033160 0.103550 -vn -1.516886 -2.629618 3.657923 -v 0.030305 -0.033245 0.100250 -vn -3.424719 -5.012263 0.833216 -v 0.030305 -0.033245 0.103550 -vn -2.113949 -5.680697 0.786242 -v 0.030328 -0.033257 0.103550 -vn 0.000000 -3.035456 3.659805 -v 0.030480 -0.033292 0.100250 -vn -0.000007 -5.917476 0.764982 -v 0.030480 -0.033292 0.103550 -vn 0.000007 5.917475 0.764982 -v 0.027980 -0.032592 0.103550 -vn 0.000004 3.035457 3.659803 -v 0.027980 -0.032592 0.100250 -vn -2.113870 5.680752 0.786239 -v 0.027828 -0.032626 0.103550 -vn -1.516881 2.629617 3.657926 -v 0.027805 -0.032639 0.100250 -vn -3.424644 5.012278 0.833224 -v 0.027805 -0.032639 0.103550 -vn -4.521335 4.035954 0.788082 -v 0.027706 -0.032724 0.103550 -vn -2.629151 1.518596 3.655163 -v 0.027677 -0.032767 0.100250 -vn -5.360763 2.825755 0.865650 -v 0.027677 -0.032767 0.103550 -vn -5.866735 1.356768 0.873744 -v 0.027638 -0.032864 0.103550 -vn -3.036365 0.000008 3.654225 -v 0.027630 -0.032942 0.100250 -vn -5.969027 0.117135 1.077926 -v 0.027630 -0.032942 0.103550 -vn -5.882378 -1.457631 0.789008 -v 0.027638 -0.033020 0.103550 -vn -2.629154 -1.518588 3.655169 -v 0.027677 -0.033117 0.100250 -vn -5.360763 -2.825755 0.865650 -v 0.027677 -0.033117 0.103550 -vn -4.521335 -4.035955 0.788082 -v 0.027706 -0.033160 0.103550 -vn -1.516882 -2.629617 3.657926 -v 0.027805 -0.033245 0.100250 -vn -3.424644 -5.012279 0.833224 -v 0.027805 -0.033245 0.103550 -vn -2.113862 -5.680752 0.786245 -v 0.027828 -0.033257 0.103550 -vn 0.000004 -3.035457 3.659803 -v 0.027980 -0.033292 0.100250 -vn -0.000007 -5.917476 0.764982 -v 0.027980 -0.033292 0.103550 -vn 0.000020 0.923564 6.139844 -v 0.025480 -0.032792 0.103750 -vn -0.000013 3.113407 5.025117 -v 0.025480 -0.032692 0.103723 -vn -1.350834 2.805115 5.025033 -v 0.025371 -0.032717 0.103723 -vn 0.000000 5.044616 2.795660 -v 0.025480 -0.032619 0.103650 -vn -2.142892 4.558990 2.858034 -v 0.025339 -0.032651 0.103650 -vn -3.913086 3.167867 2.911313 -v 0.025227 -0.032740 0.103650 -vn -4.904578 1.133635 2.934199 -v 0.025165 -0.032870 0.103650 -vn -4.904583 -1.133631 2.934194 -v 0.025165 -0.033014 0.103650 -vn -3.913080 -3.167873 2.911313 -v 0.025227 -0.033143 0.103650 -vn -2.142876 -4.558963 2.858056 -v 0.025339 -0.033233 0.103650 -vn -0.000000 -5.044603 2.795670 -v 0.025480 -0.033265 0.103650 -vn -2.434179 1.941174 5.025087 -v 0.025284 -0.032786 0.103723 -vn -3.035359 0.692824 5.025064 -v 0.025236 -0.032886 0.103723 -vn -3.035352 -0.692818 5.025071 -v 0.025236 -0.032997 0.103723 -vn -2.434159 -1.941194 5.025085 -v 0.025284 -0.033098 0.103723 -vn -1.350834 -2.805082 5.025118 -v 0.025371 -0.033167 0.103723 -vn -0.000000 -3.113406 5.025096 -v 0.025480 -0.033192 0.103723 -vn -0.400709 0.832058 6.139862 -v 0.025415 -0.032807 0.103750 -vn -0.722063 0.575855 6.139843 -v 0.025362 -0.032848 0.103750 -vn -0.900384 0.205488 6.139855 -v 0.025333 -0.032908 0.103750 -vn -0.900389 -0.205500 6.139853 -v 0.025333 -0.032975 0.103750 -vn -0.722076 -0.575839 6.139843 -v 0.025362 -0.033035 0.103750 -vn -0.400693 -0.832088 6.139855 -v 0.025415 -0.033077 0.103750 -vn -0.000004 -0.923571 6.139842 -v 0.025480 -0.033092 0.103750 -vn 0.000023 0.923563 6.139845 -v 0.032980 -0.032792 0.103750 -vn -0.000010 3.113409 5.025117 -v 0.032980 -0.032692 0.103723 -vn -1.350837 2.805120 5.025021 -v 0.032871 -0.032717 0.103723 -vn 0.000009 5.044616 2.795660 -v 0.032980 -0.032619 0.103650 -vn -2.142870 4.559014 2.858050 -v 0.032839 -0.032651 0.103650 -vn -3.913072 3.167860 2.911310 -v 0.032727 -0.032740 0.103650 -vn -4.927932 1.062380 2.855292 -v 0.032665 -0.032870 0.103650 -vn -4.911255 -1.095070 2.912946 -v 0.032665 -0.033014 0.103650 -vn -3.913056 -3.167877 2.911311 -v 0.032727 -0.033143 0.103650 -vn -2.142857 -4.558980 2.858074 -v 0.032839 -0.033233 0.103650 -vn 0.000006 -5.044602 2.795670 -v 0.032980 -0.033265 0.103650 -vn -2.434167 1.941163 5.025121 -v 0.032784 -0.032786 0.103723 -vn -3.035345 0.692845 5.025058 -v 0.032736 -0.032886 0.103723 -vn -3.035333 -0.692826 5.025073 -v 0.032736 -0.032997 0.103723 -vn -2.434128 -1.941203 5.025118 -v 0.032784 -0.033098 0.103723 -vn -1.350858 -2.805083 5.025097 -v 0.032871 -0.033167 0.103723 -vn 0.000009 -3.113407 5.025096 -v 0.032980 -0.033192 0.103723 -vn -0.400715 0.832060 6.139859 -v 0.032915 -0.032807 0.103750 -vn -0.722060 0.575847 6.139845 -v 0.032862 -0.032848 0.103750 -vn -0.900369 0.205485 6.139860 -v 0.032833 -0.032908 0.103750 -vn -0.900376 -0.205503 6.139856 -v 0.032833 -0.032975 0.103750 -vn -0.722078 -0.575832 6.139844 -v 0.032862 -0.033035 0.103750 -vn -0.400702 -0.832089 6.139853 -v 0.032915 -0.033077 0.103750 -vn -0.000001 -0.923570 6.139843 -v 0.032980 -0.033092 0.103750 -vn 0.000017 0.923563 6.139845 -v 0.030480 -0.032792 0.103750 -vn -0.000022 3.113409 5.025118 -v 0.030480 -0.032692 0.103723 -vn -1.350837 2.805123 5.025023 -v 0.030371 -0.032717 0.103723 -vn -0.000006 5.044616 2.795660 -v 0.030480 -0.032619 0.103650 -vn -2.142889 4.559010 2.858037 -v 0.030339 -0.032651 0.103650 -vn -3.913085 3.167869 2.911287 -v 0.030227 -0.032740 0.103650 -vn -4.927929 1.062401 2.855315 -v 0.030165 -0.032870 0.103650 -vn -4.911247 -1.095089 2.912961 -v 0.030165 -0.033014 0.103650 -vn -3.913075 -3.167876 2.911290 -v 0.030227 -0.033143 0.103650 -vn -2.142873 -4.558982 2.858059 -v 0.030339 -0.033233 0.103650 -vn -0.000009 -5.044601 2.795670 -v 0.030480 -0.033265 0.103650 -vn -2.434175 1.941168 5.025089 -v 0.030284 -0.032786 0.103723 -vn -3.035355 0.692826 5.025065 -v 0.030236 -0.032886 0.103723 -vn -3.035352 -0.692818 5.025071 -v 0.030236 -0.032997 0.103723 -vn -2.434151 -1.941198 5.025082 -v 0.030284 -0.033098 0.103723 -vn -1.350847 -2.805085 5.025105 -v 0.030371 -0.033167 0.103723 -vn -0.000003 -3.113407 5.025096 -v 0.030480 -0.033192 0.103723 -vn -0.400713 0.832056 6.139861 -v 0.030415 -0.032807 0.103750 -vn -0.722050 0.575843 6.139849 -v 0.030362 -0.032848 0.103750 -vn -0.900387 0.205503 6.139853 -v 0.030333 -0.032908 0.103750 -vn -0.900388 -0.205506 6.139853 -v 0.030333 -0.032975 0.103750 -vn -0.722054 -0.575836 6.139850 -v 0.030362 -0.033035 0.103750 -vn -0.400704 -0.832087 6.139853 -v 0.030415 -0.033077 0.103750 -vn -0.000007 -0.923570 6.139843 -v 0.030480 -0.033092 0.103750 -vn 0.000017 0.923563 6.139845 -v 0.027980 -0.032792 0.103750 -vn -0.000022 3.113409 5.025118 -v 0.027980 -0.032692 0.103723 -vn -1.350837 2.805123 5.025023 -v 0.027871 -0.032717 0.103723 -vn -0.000006 5.044616 2.795660 -v 0.027980 -0.032619 0.103650 -vn -2.142878 4.559013 2.858051 -v 0.027839 -0.032651 0.103650 -vn -3.913079 3.167872 2.911312 -v 0.027727 -0.032740 0.103650 -vn -4.927930 1.062388 2.855328 -v 0.027665 -0.032870 0.103650 -vn -4.911248 -1.095076 2.912974 -v 0.027665 -0.033014 0.103650 -vn -3.913068 -3.167879 2.911315 -v 0.027727 -0.033143 0.103650 -vn -2.142862 -4.558985 2.858073 -v 0.027839 -0.033233 0.103650 -vn -0.000009 -5.044601 2.795670 -v 0.027980 -0.033265 0.103650 -vn -2.434179 1.941174 5.025087 -v 0.027784 -0.032786 0.103723 -vn -3.035359 0.692824 5.025064 -v 0.027736 -0.032886 0.103723 -vn -3.035352 -0.692818 5.025071 -v 0.027736 -0.032997 0.103723 -vn -2.434157 -1.941201 5.025081 -v 0.027784 -0.033098 0.103723 -vn -1.350847 -2.805088 5.025105 -v 0.027871 -0.033167 0.103723 -vn -0.000003 -3.113407 5.025096 -v 0.027980 -0.033192 0.103723 -vn -0.400709 0.832058 6.139862 -v 0.027915 -0.032807 0.103750 -vn -0.722063 0.575855 6.139843 -v 0.027862 -0.032848 0.103750 -vn -0.900384 0.205488 6.139855 -v 0.027833 -0.032908 0.103750 -vn -0.900389 -0.205500 6.139853 -v 0.027833 -0.032975 0.103750 -vn -0.722076 -0.575839 6.139843 -v 0.027862 -0.033035 0.103750 -vn -0.400693 -0.832088 6.139855 -v 0.027915 -0.033077 0.103750 -vn -0.000007 -0.923570 6.139843 -v 0.027980 -0.033092 0.103750 -vn 1.570797 -1.570796 -1.570796 -v 0.035430 -0.034762 0.096350 -vn 1.570796 -1.570796 1.570796 -v 0.035430 -0.034762 0.099450 -vn 1.110721 -5.823110 0.785398 -v 0.033930 -0.034762 0.099450 -vn -1.570796 -4.712389 -1.570796 -v 0.025840 -0.034762 0.098450 -vn 1.110721 -2.681516 2.356194 -v 0.033930 -0.034762 0.104250 -vn 1.570796 -4.712389 -1.570796 -v 0.025120 -0.034762 0.098450 -vn -1.570796 -1.570796 1.570797 -v 0.023030 -0.034762 0.104250 -vn 3.070403 -2.839377 -0.467526 -v 0.025120 -0.034762 0.097200 -vn -1.570796 -1.570796 -1.570796 -v 0.023030 -0.034762 0.096350 -vn 1.499607 -1.873012 -2.038322 -v 0.024855 -0.034762 0.096350 -vn -1.570796 -4.712389 -1.570796 -v 0.028340 -0.034762 0.098450 -vn 1.570796 -4.712389 -1.570796 -v 0.027620 -0.034762 0.098450 -vn 3.070404 -2.839379 -0.467523 -v 0.027620 -0.034762 0.097200 -vn -3.070404 -2.839377 -0.467526 -v 0.025840 -0.034762 0.097200 -vn 1.499608 -1.873010 -2.038319 -v 0.027355 -0.034762 0.096350 -vn -1.499607 -1.873012 -2.038322 -v 0.026105 -0.034762 0.096350 -vn -1.499607 -1.873012 -2.038322 -v 0.028605 -0.034762 0.096350 -vn 1.499607 -1.873012 -2.038322 -v 0.029855 -0.034762 0.096350 -vn -3.070404 -2.839377 -0.467526 -v 0.028340 -0.034762 0.097200 -vn 3.070403 -2.839376 -0.467526 -v 0.030120 -0.034762 0.097200 -vn 1.570796 -4.712389 -1.570796 -v 0.030120 -0.034762 0.098450 -vn -1.499608 -1.873009 -2.038318 -v 0.031105 -0.034762 0.096350 -vn 1.499606 -1.873014 -2.038325 -v 0.032355 -0.034762 0.096350 -vn -3.070404 -2.839378 -0.467523 -v 0.030840 -0.034762 0.097200 -vn 3.070403 -2.839376 -0.467528 -v 0.032620 -0.034762 0.097200 -vn -1.570796 -4.712389 -1.570796 -v 0.030840 -0.034762 0.098450 -vn 1.570796 -4.712389 -1.570796 -v 0.032620 -0.034762 0.098450 -vn -1.570796 -4.712389 -1.570796 -v 0.033340 -0.034762 0.098450 -vn -3.070403 -2.839376 -0.467528 -v 0.033340 -0.034762 0.097200 -vn -1.499606 -1.873014 -2.038325 -v 0.033605 -0.034762 0.096350 -vn -3.070403 2.839377 -0.467526 -v 0.033340 -0.033762 0.097200 -vn -3.141593 0.000000 -3.141593 -v 0.033340 -0.033762 0.098350 -vn -1.570796 -1.570796 -1.570796 -v 0.033340 -0.033762 0.098450 -vn 1.570796 -1.570796 -1.570796 -v 0.032620 -0.033762 0.098450 -vn 3.141593 0.000000 -3.141593 -v 0.032620 -0.033762 0.098350 -vn 3.070403 2.839377 -0.467526 -v 0.032620 -0.033762 0.097200 -vn 2.227274 1.264155 -3.529335 -v 0.032355 -0.034262 0.096350 -vn 2.271544 2.830305 -1.665478 -v 0.032511 -0.033762 0.096850 -vn -2.227279 1.264153 -3.529320 -v 0.031105 -0.034262 0.096350 -vn -2.271544 2.830310 -1.665476 -v 0.030949 -0.033762 0.096850 -vn -3.070403 2.839377 -0.467526 -v 0.030840 -0.033762 0.097200 -vn -3.141593 -0.000000 -3.141593 -v 0.030840 -0.033762 0.098350 -vn -1.570796 -1.570796 -1.570796 -v 0.030840 -0.033762 0.098450 -vn 1.570796 -1.570797 -1.570796 -v 0.030120 -0.033762 0.098450 -vn 3.141593 0.000000 -3.141593 -v 0.030120 -0.033762 0.098350 -vn 3.070401 2.839372 -0.467533 -v 0.030120 -0.033762 0.097200 -vn 2.227277 1.264156 -3.529326 -v 0.029855 -0.034262 0.096350 -vn 2.271543 2.830317 -1.665483 -v 0.030011 -0.033762 0.096850 -vn -2.227276 1.264155 -3.529329 -v 0.028605 -0.034262 0.096350 -vn -2.271545 2.830307 -1.665477 -v 0.028449 -0.033762 0.096850 -vn -3.070403 2.839377 -0.467526 -v 0.028340 -0.033762 0.097200 -vn -3.141593 -0.000000 -3.141593 -v 0.028340 -0.033762 0.098350 -vn -1.570796 -1.570796 -1.570796 -v 0.028340 -0.033762 0.098450 -vn 1.570796 -1.570797 -1.570796 -v 0.027620 -0.033762 0.098450 -vn 3.141593 0.000000 -3.141593 -v 0.027620 -0.033762 0.098350 -vn 3.070403 2.839377 -0.467526 -v 0.027620 -0.033762 0.097200 -vn 2.227278 1.264154 -3.529322 -v 0.027355 -0.034262 0.096350 -vn 2.271545 2.830310 -1.665476 -v 0.027511 -0.033762 0.096850 -vn -2.227276 1.264155 -3.529329 -v 0.026105 -0.034262 0.096350 -vn -2.271545 2.830307 -1.665477 -v 0.025949 -0.033762 0.096850 -vn -3.070403 2.839377 -0.467526 -v 0.025840 -0.033762 0.097200 -vn -3.141593 -0.000000 -3.141593 -v 0.025840 -0.033762 0.098350 -vn -1.570796 -1.570796 -1.570796 -v 0.025840 -0.033762 0.098450 -vn 1.570796 -1.570797 -1.570796 -v 0.025120 -0.033762 0.098450 -vn 3.141593 0.000000 -3.141592 -v 0.025120 -0.033762 0.098350 -vn 3.070403 2.839377 -0.467526 -v 0.025120 -0.033762 0.097200 -vn 2.227276 1.264155 -3.529329 -v 0.024855 -0.034262 0.096350 -vn 2.271545 2.830307 -1.665477 -v 0.025011 -0.033762 0.096850 -vn -2.356191 1.110725 -2.681513 -v 0.023030 -0.034262 0.096350 -vn -4.712389 1.570796 -1.570797 -v 0.023030 -0.033762 0.098350 -vn -2.356198 2.681521 -1.110717 -v 0.023030 -0.033762 0.096850 -vn -2.268926 2.580482 1.203302 -v 0.023030 -0.031752 0.103850 -vn -1.570796 1.570796 -1.570796 -v 0.023030 -0.031752 0.103350 -vn -2.443464 1.009686 2.774099 -v 0.023030 -0.032229 0.104250 -vn -4.712389 1.570796 -1.570796 -v 0.023030 -0.032152 0.103350 -vn -1.570796 1.570795 -1.570798 -v 0.023030 -0.032152 0.098350 -vn 2.443463 1.009686 2.774098 -v 0.023730 -0.032229 0.104250 -vn 2.681507 1.110731 3.927001 -v 0.023730 -0.032972 0.104250 -vn 2.443464 1.009685 2.774099 -v 0.035430 -0.032229 0.104250 -vn -2.443464 1.009685 2.774098 -v 0.034730 -0.032229 0.104250 -vn 2.681518 -1.110721 2.356195 -v 0.035430 -0.033262 0.104250 -vn -2.681509 1.110729 3.926997 -v 0.034730 -0.032972 0.104250 -vn -2.681562 1.110616 2.356200 -v 0.033640 -0.034062 0.104250 -vn -0.785401 1.110757 5.823089 -v 0.033640 -0.034312 0.104250 -vn 0.785396 1.110742 5.823098 -v 0.024820 -0.034312 0.104250 -vn 2.681562 1.110631 2.356224 -v 0.024820 -0.034062 0.104250 -vn 5.823110 -1.110721 0.785398 -v 0.035430 -0.033262 0.099450 -vn 2.268926 2.580482 1.203302 -v 0.035430 -0.031752 0.103850 -vn 1.570796 1.570796 -1.570796 -v 0.035430 -0.031752 0.103350 -vn 4.712389 1.570796 -1.570796 -v 0.035430 -0.032152 0.103350 -vn 1.570797 1.570796 -1.570796 -v 0.035430 -0.032152 0.098350 -vn 4.712389 1.570796 -1.570796 -v 0.035430 -0.033762 0.098350 -vn 2.356191 1.110725 -2.681513 -v 0.035430 -0.034262 0.096350 -vn 2.356199 2.681521 -1.110717 -v 0.035430 -0.033762 0.096850 -vn -2.227273 1.264156 -3.529338 -v 0.033605 -0.034262 0.096350 -vn -2.271545 2.830305 -1.665478 -v 0.033449 -0.033762 0.096850 -vn 4.712389 1.570796 -1.570796 -v 0.023730 -0.032152 0.103350 -vn 0.000000 3.141593 3.141592 -v 0.023730 -0.032152 0.100250 -vn -1.570796 1.570796 -4.712388 -v 0.023730 -0.032152 0.098350 -vn 1.570796 1.570796 -1.570796 -v 0.023730 -0.031752 0.103350 -vn 2.268926 2.580482 1.203302 -v 0.023730 -0.031752 0.103850 -vn 3.006758 4.903040 1.110765 -v 0.024820 -0.034062 0.104000 -vn -1.278232 4.705226 3.171993 -v 0.026230 -0.034062 0.104000 -vn -1.278211 4.705226 3.172006 -v 0.031230 -0.034062 0.104000 -vn 1.278226 4.705224 3.172003 -v 0.032230 -0.034062 0.104000 -vn -3.006745 4.903060 1.110732 -v 0.033640 -0.034062 0.104000 -vn 1.278211 4.705226 3.172006 -v 0.029730 -0.034062 0.104000 -vn -1.278211 4.705227 3.172006 -v 0.028730 -0.034062 0.104000 -vn 1.278209 4.705228 3.172004 -v 0.027230 -0.034062 0.104000 -vn -2.268926 2.580482 1.203302 -v 0.034730 -0.031752 0.103850 -vn -4.712389 1.570796 -1.570796 -v 0.034730 -0.032152 0.103350 -vn -0.000000 3.141593 3.141593 -v 0.034730 -0.032152 0.100250 -vn 1.570795 1.570796 -4.712390 -v 0.034730 -0.032152 0.098350 -vn -1.570796 1.570796 -1.570796 -v 0.034730 -0.031752 0.103350 -vn 2.681514 1.110724 2.356191 -v 0.023730 -0.032972 0.100250 -vn -1.570796 1.570796 -4.712389 -v 0.023730 -0.030862 0.099350 -vn -1.570796 1.570796 -1.570782 -v 0.023730 -0.030862 0.098350 -vn -4.712389 -1.570796 -1.570796 -v 0.023730 -0.031052 0.099350 -vn 0.000000 -3.141593 3.141592 -v 0.023730 -0.031052 0.100250 -vn 0.000000 1.826010 1.240497 -v 0.029230 -0.033362 0.104000 -vn -0.000001 1.826013 1.240498 -v 0.026730 -0.033362 0.104000 -vn 0.000002 1.826008 1.240495 -v 0.031730 -0.033362 0.104000 -vn -0.000000 -3.141593 3.141592 -v 0.034730 -0.031052 0.100250 -vn 4.712389 -1.570796 -1.570796 -v 0.034730 -0.031052 0.099350 -vn 1.570796 1.570796 -4.712389 -v 0.034730 -0.030862 0.099350 -vn 1.570796 1.570796 -1.570786 -v 0.034730 -0.030862 0.098350 -vn -2.681517 1.110721 2.356195 -v 0.034730 -0.032972 0.100250 -vn 0.000000 0.000000 -3.635275 -v 0.025819 -0.032856 0.098350 -vn 0.000000 0.000000 -3.635275 -v 0.025819 -0.033027 0.098350 -vn 0.000000 0.000000 -3.635253 -v 0.025738 -0.033178 0.098350 -vn 0.000000 0.000000 -3.556756 -v 0.025595 -0.033272 0.098350 -vn 0.000000 0.000000 -3.556757 -v 0.030595 -0.033272 0.098350 -vn 0.000000 0.000000 -3.635254 -v 0.030738 -0.033178 0.098350 -vn 0.000000 0.000000 -3.635253 -v 0.025738 -0.032706 0.098350 -vn 0.000000 0.000000 -3.556755 -v 0.025595 -0.032611 0.098350 -vn 0.000000 0.000000 -3.635275 -v 0.028319 -0.032856 0.098350 -vn 0.000000 0.000000 -3.635275 -v 0.028319 -0.033027 0.098350 -vn 0.000000 0.000000 -3.635253 -v 0.028238 -0.033178 0.098350 -vn 0.000000 0.000000 -3.556756 -v 0.028095 -0.033272 0.098350 -vn 0.000000 0.000000 -3.635268 -v 0.033238 -0.033178 0.098350 -vn 0.000000 0.000000 -3.635253 -v 0.028238 -0.032706 0.098350 -vn 0.000000 0.000000 -3.556756 -v 0.028095 -0.032611 0.098350 -vn 0.000000 0.000000 -3.556747 -v 0.033095 -0.033272 0.098350 -vn 0.000000 0.000000 -3.635265 -v 0.033319 -0.033027 0.098350 -vn 0.000000 0.000000 -3.635266 -v 0.033319 -0.032856 0.098350 -vn 0.000000 0.000000 -3.635268 -v 0.033238 -0.032706 0.098350 -vn 0.000000 0.000000 -3.556747 -v 0.033095 -0.032611 0.098350 -vn 0.000000 0.000000 -3.635275 -v 0.030819 -0.033027 0.098350 -vn 0.000000 0.000000 -3.635304 -v 0.030819 -0.032856 0.098350 -vn 0.000000 0.000000 -3.635253 -v 0.030738 -0.032706 0.098350 -vn 0.000000 0.000000 -3.556756 -v 0.030595 -0.032611 0.098350 -vn 1.110727 2.681515 2.356196 -v 0.024820 -0.034062 0.100250 -vn -1.110721 2.681517 2.356194 -v 0.033640 -0.034062 0.100250 -vn -1.278215 2.483802 2.191051 -v 0.026230 -0.034062 0.100250 -vn 1.278209 2.483804 2.191048 -v 0.032230 -0.034062 0.100250 -vn -1.570796 -1.570796 -1.570796 -v 0.023030 -0.031052 0.099350 -vn -1.570797 1.570796 -1.570796 -v 0.023030 -0.029862 0.099350 -vn 1.570796 1.570796 -1.570796 -v 0.035430 -0.029862 0.099350 -vn 1.570796 -1.570796 -1.570796 -v 0.035430 -0.031052 0.099350 -vn -0.000001 1.826013 5.042687 -v 0.026730 -0.033362 0.100250 -vn -0.000001 1.826012 5.042688 -v 0.031730 -0.033362 0.100250 -vn 5.995529 -0.798909 -1.193684 -v 0.025821 -0.038062 0.097572 -vn 2.860457 0.004421 -1.127754 -v 0.025810 -0.033292 0.097534 -vn -2.860457 0.004421 -1.127754 -v 0.025149 -0.033292 0.097534 -vn 5.600043 -0.851467 -2.327864 -v 0.025810 -0.038062 0.097534 -vn 4.909079 -0.790165 -3.569842 -v 0.025753 -0.038062 0.097432 -vn 2.056107 0.006339 -2.249178 -v 0.025716 -0.033292 0.097392 -vn 3.930451 -0.867768 -4.611487 -v 0.025716 -0.038062 0.097392 -vn 2.754318 -0.790661 -5.408704 -v 0.025632 -0.038062 0.097335 -vn 0.744666 0.006800 -2.955057 -v 0.025565 -0.033292 0.097311 -vn 1.411526 -0.876335 -5.889617 -v 0.025565 -0.038062 0.097311 -vn -0.744666 0.006800 -2.955057 -v 0.025394 -0.033292 0.097311 -vn -2.056107 0.006339 -2.249178 -v 0.025244 -0.033292 0.097392 -vn 5.979948 -0.883625 -1.092725 -v 0.033321 -0.038062 0.097572 -vn 2.860461 0.004421 -1.127740 -v 0.033310 -0.033292 0.097534 -vn -2.860452 0.004422 -1.127789 -v 0.032649 -0.033292 0.097534 -vn 5.600087 -0.851457 -2.327715 -v 0.033310 -0.038062 0.097534 -vn 4.909084 -0.790204 -3.569791 -v 0.033253 -0.038062 0.097432 -vn 2.056108 0.006339 -2.249169 -v 0.033216 -0.033292 0.097392 -vn 3.930416 -0.867803 -4.611492 -v 0.033216 -0.038062 0.097392 -vn 2.754292 -0.790685 -5.408715 -v 0.033132 -0.038062 0.097335 -vn 0.744659 0.006800 -2.955061 -v 0.033065 -0.033292 0.097311 -vn 1.411530 -0.876342 -5.889614 -v 0.033065 -0.038062 0.097311 -vn -0.744673 0.006800 -2.955053 -v 0.032894 -0.033292 0.097311 -vn -2.056122 0.006340 -2.249162 -v 0.032744 -0.033292 0.097392 -vn 5.979836 -0.883646 -1.092934 -v 0.030821 -0.038062 0.097572 -vn 2.860456 0.004422 -1.127764 -v 0.030810 -0.033292 0.097534 -vn -2.860456 0.004422 -1.127764 -v 0.030149 -0.033292 0.097534 -vn 5.600045 -0.851455 -2.327967 -v 0.030810 -0.038062 0.097534 -vn 4.909094 -0.790163 -3.569802 -v 0.030753 -0.038062 0.097432 -vn 2.056115 0.006340 -2.249166 -v 0.030716 -0.033292 0.097392 -vn 3.930442 -0.867779 -4.611489 -v 0.030716 -0.038062 0.097392 -vn 2.754317 -0.790684 -5.408696 -v 0.030632 -0.038062 0.097335 -vn 0.744666 0.006800 -2.955057 -v 0.030565 -0.033292 0.097311 -vn 1.411521 -0.876344 -5.889614 -v 0.030565 -0.038062 0.097311 -vn -0.744666 0.006800 -2.955057 -v 0.030394 -0.033292 0.097311 -vn -2.056115 0.006340 -2.249166 -v 0.030244 -0.033292 0.097392 -vn 5.995542 -0.798861 -1.193760 -v 0.028321 -0.038062 0.097572 -vn 2.860457 0.004421 -1.127764 -v 0.028310 -0.033292 0.097534 -vn -2.860456 0.004422 -1.127764 -v 0.027649 -0.033292 0.097534 -vn 5.600074 -0.851433 -2.327845 -v 0.028310 -0.038062 0.097534 -vn 4.909094 -0.790163 -3.569802 -v 0.028253 -0.038062 0.097432 -vn 2.056115 0.006340 -2.249166 -v 0.028216 -0.033292 0.097392 -vn 3.930442 -0.867779 -4.611489 -v 0.028216 -0.038062 0.097392 -vn 2.754317 -0.790684 -5.408696 -v 0.028132 -0.038062 0.097335 -vn 0.744666 0.006800 -2.955057 -v 0.028065 -0.033292 0.097311 -vn 1.411521 -0.876344 -5.889614 -v 0.028065 -0.038062 0.097311 -vn -0.744666 0.006800 -2.955057 -v 0.027894 -0.033292 0.097311 -vn -2.056115 0.006340 -2.249166 -v 0.027744 -0.033292 0.097392 -vn -1.570796 1.570796 1.570796 -v 0.023030 -0.029862 0.104250 -vn 1.570796 1.570796 1.570797 -v 0.035430 -0.029862 0.104250 -vn 1.278209 2.483804 2.191046 -v 0.027230 -0.034062 0.100250 -vn -1.278211 2.483802 2.191045 -v 0.031230 -0.034062 0.100250 -vn 2.195306 -2.939765 -4.528725 -v 0.025620 -0.038162 0.097359 -vn 3.950135 -2.926218 -3.119599 -v 0.025732 -0.038162 0.097448 -vn 4.900146 -2.951480 -1.130960 -v 0.025795 -0.038162 0.097578 -vn 4.900124 -2.951498 1.130968 -v 0.025795 -0.038162 0.097722 -vn 3.950129 -2.926228 3.119588 -v 0.025732 -0.038162 0.097852 -vn 2.195245 -2.939836 4.528663 -v 0.025620 -0.038162 0.097941 -vn 1.350814 -5.025242 2.805083 -v 0.025588 -0.038235 0.097875 -vn 0.400808 -6.139800 0.832218 -v 0.025545 -0.038262 0.097785 -vn 2.434178 -5.025119 1.941190 -v 0.025675 -0.038235 0.097806 -vn 0.722129 -6.139822 0.575888 -v 0.025597 -0.038262 0.097744 -vn 3.035396 -5.025146 0.692770 -v 0.025723 -0.038235 0.097706 -vn 0.900509 -6.139812 0.205542 -v 0.025626 -0.038262 0.097683 -vn 3.035395 -5.025112 -0.692833 -v 0.025723 -0.038235 0.097594 -vn 0.900499 -6.139817 -0.205515 -v 0.025626 -0.038262 0.097617 -vn 2.434208 -5.025134 -1.941197 -v 0.025675 -0.038235 0.097494 -vn 0.722155 -6.139805 -0.575929 -v 0.025597 -0.038262 0.097556 -vn 1.350898 -5.025103 -2.805117 -v 0.025588 -0.038235 0.097425 -vn 0.400763 -6.139824 -0.832161 -v 0.025545 -0.038262 0.097515 -vn 2.195287 -2.939787 -4.528750 -v 0.033120 -0.038162 0.097359 -vn 3.035378 -5.025149 0.692777 -v 0.033223 -0.038235 0.097706 -vn 0.900497 -6.139816 0.205544 -v 0.033126 -0.038262 0.097683 -vn 0.900484 -6.139822 -0.205512 -v 0.033126 -0.038262 0.097617 -vn 2.434147 -5.025151 1.941200 -v 0.033175 -0.038235 0.097806 -vn 0.722132 -6.139823 0.575880 -v 0.033097 -0.038262 0.097744 -vn 1.350843 -5.025224 2.805081 -v 0.033088 -0.038235 0.097875 -vn 0.400819 -6.139799 0.832217 -v 0.033045 -0.038262 0.097785 -vn 3.035382 -5.025105 -0.692853 -v 0.033223 -0.038235 0.097594 -vn 4.923497 -2.872586 -1.059705 -v 0.033295 -0.038162 0.097578 -vn 4.906794 -2.930256 1.092404 -v 0.033295 -0.038162 0.097722 -vn 0.722152 -6.139808 -0.575921 -v 0.033097 -0.038262 0.097556 -vn 2.434196 -5.025168 -1.941186 -v 0.033175 -0.038235 0.097494 -vn 3.950117 -2.926262 -3.119581 -v 0.033232 -0.038162 0.097448 -vn 2.195231 -2.939862 4.528678 -v 0.033120 -0.038162 0.097941 -vn 3.950100 -2.926273 3.119581 -v 0.033232 -0.038162 0.097852 -vn 1.350908 -5.025092 -2.805119 -v 0.033088 -0.038235 0.097425 -vn 0.400771 -6.139823 -0.832161 -v 0.033045 -0.038262 0.097515 -vn 2.195289 -2.939779 -4.528748 -v 0.030620 -0.038162 0.097359 -vn 3.035396 -5.025147 0.692770 -v 0.030723 -0.038235 0.097706 -vn 0.900508 -6.139812 0.205548 -v 0.030626 -0.038262 0.097683 -vn 0.900502 -6.139816 -0.205529 -v 0.030626 -0.038262 0.097617 -vn 2.434170 -5.025115 1.941195 -v 0.030675 -0.038235 0.097806 -vn 0.722107 -6.139828 0.575885 -v 0.030597 -0.038262 0.097744 -vn 1.350822 -5.025229 2.805088 -v 0.030588 -0.038235 0.097875 -vn 0.400817 -6.139798 0.832219 -v 0.030545 -0.038262 0.097785 -vn 3.035391 -5.025112 -0.692834 -v 0.030723 -0.038235 0.097594 -vn 4.923495 -2.872596 -1.059732 -v 0.030795 -0.038162 0.097578 -vn 4.906787 -2.930258 1.092429 -v 0.030795 -0.038162 0.097722 -vn 0.722143 -6.139811 -0.575917 -v 0.030597 -0.038262 0.097556 -vn 2.434204 -5.025136 -1.941191 -v 0.030675 -0.038235 0.097494 -vn 3.950134 -2.926204 -3.119598 -v 0.030732 -0.038162 0.097448 -vn 2.195231 -2.939851 4.528681 -v 0.030620 -0.038162 0.097941 -vn 3.950122 -2.926216 3.119588 -v 0.030732 -0.038162 0.097852 -vn 1.350896 -5.025091 -2.805128 -v 0.030588 -0.038235 0.097425 -vn 0.400765 -6.139823 -0.832163 -v 0.030545 -0.038262 0.097515 -vn 2.195289 -2.939779 -4.528748 -v 0.028120 -0.038162 0.097359 -vn 3.950126 -2.926219 -3.119582 -v 0.028232 -0.038162 0.097448 -vn 4.900124 -2.951466 -1.130968 -v 0.028295 -0.038162 0.097578 -vn 4.900101 -2.951483 1.130977 -v 0.028295 -0.038162 0.097722 -vn 3.950107 -2.926234 3.119572 -v 0.028232 -0.038162 0.097852 -vn 2.195233 -2.939855 4.528676 -v 0.028120 -0.038162 0.097941 -vn 1.350838 -5.025222 2.805083 -v 0.028088 -0.038235 0.097875 -vn 0.400817 -6.139798 0.832219 -v 0.028045 -0.038262 0.097785 -vn 2.434164 -5.025141 1.941183 -v 0.028175 -0.038235 0.097806 -vn 0.722132 -6.139822 0.575880 -v 0.028097 -0.038262 0.097744 -vn 3.035370 -5.025180 0.692765 -v 0.028223 -0.038235 0.097706 -vn 0.900509 -6.139812 0.205542 -v 0.028126 -0.038262 0.097683 -vn 3.035369 -5.025145 -0.692828 -v 0.028223 -0.038235 0.097594 -vn 0.900499 -6.139818 -0.205515 -v 0.028126 -0.038262 0.097617 -vn 2.434200 -5.025168 -1.941174 -v 0.028175 -0.038235 0.097494 -vn 0.722158 -6.139807 -0.575919 -v 0.028097 -0.038262 0.097556 -vn 1.350902 -5.025090 -2.805121 -v 0.028088 -0.038235 0.097425 -vn 0.400768 -6.139822 -0.832163 -v 0.028045 -0.038262 0.097515 -vn 2.267532 -2.578804 1.204708 -v 0.035430 -0.031052 0.103840 -vn 2.444857 -1.008008 2.775504 -v 0.035430 -0.030562 0.104250 -vn -2.444857 -1.008008 2.775505 -v 0.034730 -0.030562 0.104250 -vn -0.785405 -1.110729 5.823101 -v 0.034730 -0.030312 0.104250 -vn 0.785406 -1.110729 5.823102 -v 0.023730 -0.030312 0.104250 -vn 2.444854 -1.008009 2.775503 -v 0.023730 -0.030562 0.104250 -vn -2.444860 -1.008005 2.775506 -v 0.023030 -0.030562 0.104250 -vn -2.267530 -2.578802 1.204710 -v 0.023030 -0.031052 0.103840 -vn -1.278211 2.483801 2.191045 -v 0.028730 -0.034062 0.100250 -vn 1.278209 2.483804 2.191047 -v 0.029730 -0.034062 0.100250 -vn -2.267532 -2.578804 1.204708 -v 0.034730 -0.031052 0.103840 -vn 3.926983 -2.681525 1.110712 -v 0.023730 -0.030562 0.104000 -vn -3.926984 -2.681525 1.110712 -v 0.034730 -0.030562 0.104000 -vn 2.267531 -2.578803 1.204709 -v 0.023730 -0.031052 0.103840 -vn -0.000001 1.826012 5.042688 -v 0.029230 -0.033362 0.100250 -vn -1.570796 -1.570796 1.570799 -v 0.034730 -0.030562 0.100250 -vn 1.570797 -1.570796 1.570807 -v 0.023730 -0.030562 0.100250 -vn 2.629152 1.518595 3.655163 -v 0.033283 -0.032767 0.100250 -vn 3.036365 0.000008 3.654227 -v 0.033330 -0.032942 0.100250 -vn 2.629154 -1.518588 3.655169 -v 0.033283 -0.033117 0.100250 -vn 1.516886 -2.629617 3.657923 -v 0.033155 -0.033245 0.100250 -vn 1.516886 -2.629618 3.657923 -v 0.030655 -0.033245 0.100250 -vn 1.516886 -2.629618 3.657923 -v 0.028155 -0.033245 0.100250 -vn 1.516885 -2.629616 3.657924 -v 0.025655 -0.033245 0.100250 -vn 2.629154 -1.518588 3.655169 -v 0.025783 -0.033117 0.100250 -vn 3.036365 0.000008 3.654217 -v 0.025830 -0.032942 0.100250 -vn 2.629150 -1.518603 3.655157 -v 0.030783 -0.033117 0.100250 -vn 3.036357 0.000008 3.654235 -v 0.030830 -0.032942 0.100250 -vn 2.629151 1.518596 3.655164 -v 0.025783 -0.032767 0.100250 -vn 1.516886 2.629616 3.657924 -v 0.025655 -0.032639 0.100250 -vn 2.629150 -1.518603 3.655158 -v 0.028283 -0.033117 0.100250 -vn 3.036357 0.000008 3.654237 -v 0.028330 -0.032942 0.100250 -vn 2.629148 1.518611 3.655152 -v 0.030783 -0.032767 0.100250 -vn 2.629148 1.518611 3.655153 -v 0.028283 -0.032767 0.100250 -vn 1.516886 2.629618 3.657923 -v 0.028155 -0.032639 0.100250 -vn 1.516886 2.629618 3.657923 -v 0.030655 -0.032639 0.100250 -vn 1.516886 2.629617 3.657923 -v 0.033155 -0.032639 0.100250 -vn 2.113874 -5.680758 0.786224 -v 0.025632 -0.033257 0.103550 -vn 3.424653 -5.012281 0.833205 -v 0.025655 -0.033245 0.103550 -vn 4.521335 -4.035954 0.788082 -v 0.025753 -0.033160 0.103550 -vn 5.360763 -2.825755 0.865650 -v 0.025783 -0.033117 0.103550 -vn 5.866736 -1.356756 0.873739 -v 0.025821 -0.033020 0.103550 -vn 5.969034 -0.117100 1.077910 -v 0.025830 -0.032942 0.103550 -vn 5.882378 1.457647 0.789008 -v 0.025821 -0.032864 0.103550 -vn 5.360763 2.825755 0.865650 -v 0.025783 -0.032767 0.103550 -vn 4.521335 4.035955 0.788082 -v 0.025753 -0.032724 0.103550 -vn 3.424653 5.012281 0.833205 -v 0.025655 -0.032639 0.103550 -vn 2.113869 5.680758 0.786228 -v 0.025632 -0.032626 0.103550 -vn 2.113878 -5.680751 0.786239 -v 0.033132 -0.033257 0.103550 -vn 3.424628 -5.012292 0.833232 -v 0.033155 -0.033245 0.103550 -vn 4.521350 -4.035883 0.788116 -v 0.033253 -0.033160 0.103550 -vn 5.360824 -2.825656 0.865653 -v 0.033283 -0.033117 0.103550 -vn 5.866771 -1.356766 0.873714 -v 0.033321 -0.033020 0.103550 -vn 5.968997 -0.117122 1.077917 -v 0.033330 -0.032942 0.103550 -vn 5.882413 1.457679 0.788964 -v 0.033321 -0.032864 0.103550 -vn 5.360824 2.825656 0.865653 -v 0.033283 -0.032767 0.103550 -vn 4.521350 4.035883 0.788116 -v 0.033253 -0.032724 0.103550 -vn 3.424629 5.012292 0.833232 -v 0.033155 -0.032639 0.103550 -vn 2.113870 5.680751 0.786246 -v 0.033132 -0.032626 0.103550 -vn 2.113956 -5.680697 0.786236 -v 0.030632 -0.033257 0.103550 -vn 3.424719 -5.012263 0.833216 -v 0.030655 -0.033245 0.103550 -vn 4.521358 -4.035894 0.788078 -v 0.030753 -0.033160 0.103550 -vn 5.360811 -2.825737 0.865636 -v 0.030783 -0.033117 0.103550 -vn 5.882356 -1.457677 0.789006 -v 0.030821 -0.033020 0.103550 -vn 6.055976 0.000016 0.877543 -v 0.030830 -0.032942 0.103550 -vn 5.882355 1.457693 0.789006 -v 0.030821 -0.032864 0.103550 -vn 5.360811 2.825737 0.865636 -v 0.030783 -0.032767 0.103550 -vn 4.521358 4.035894 0.788078 -v 0.030753 -0.032724 0.103550 -vn 3.424719 5.012263 0.833216 -v 0.030655 -0.032639 0.103550 -vn 2.113949 5.680697 0.786242 -v 0.030632 -0.032626 0.103550 -vn 2.113956 -5.680697 0.786236 -v 0.028132 -0.033257 0.103550 -vn 3.424719 -5.012263 0.833216 -v 0.028155 -0.033245 0.103550 -vn 4.521358 -4.035894 0.788078 -v 0.028253 -0.033160 0.103550 -vn 5.360824 -2.825701 0.865623 -v 0.028283 -0.033117 0.103550 -vn 5.866749 -1.356812 0.873712 -v 0.028321 -0.033020 0.103550 -vn 5.968997 -0.117122 1.077917 -v 0.028330 -0.032942 0.103550 -vn 5.882391 1.457725 0.788962 -v 0.028321 -0.032864 0.103550 -vn 5.360824 2.825701 0.865623 -v 0.028283 -0.032767 0.103550 -vn 4.521358 4.035894 0.788078 -v 0.028253 -0.032724 0.103550 -vn 3.424719 5.012263 0.833216 -v 0.028155 -0.032639 0.103550 -vn 2.113949 5.680697 0.786242 -v 0.028132 -0.032626 0.103550 -vn 1.350861 -2.805072 5.025113 -v 0.025588 -0.033167 0.103723 -vn 2.142894 -4.558951 2.858066 -v 0.025620 -0.033233 0.103650 -vn 3.913070 -3.167869 2.911321 -v 0.025732 -0.033143 0.103650 -vn 4.927930 -1.062388 2.855328 -v 0.025795 -0.033014 0.103650 -vn 4.911248 1.095076 2.912976 -v 0.025795 -0.032870 0.103650 -vn 3.913080 3.167873 2.911313 -v 0.025732 -0.032740 0.103650 -vn 2.142913 4.558990 2.858025 -v 0.025620 -0.032651 0.103650 -vn 2.434158 -1.941210 5.025071 -v 0.025675 -0.033098 0.103723 -vn 3.035359 -0.692824 5.025064 -v 0.025723 -0.032997 0.103723 -vn 3.035352 0.692818 5.025071 -v 0.025723 -0.032886 0.103723 -vn 2.434178 1.941182 5.025086 -v 0.025675 -0.032786 0.103723 -vn 1.350855 2.805098 5.025045 -v 0.025588 -0.032717 0.103723 -vn 0.400712 -0.832080 6.139855 -v 0.025545 -0.033077 0.103750 -vn 0.722063 -0.575855 6.139843 -v 0.025597 -0.033035 0.103750 -vn 0.900384 -0.205488 6.139855 -v 0.025626 -0.032975 0.103750 -vn 0.900389 0.205500 6.139853 -v 0.025626 -0.032908 0.103750 -vn 0.722076 0.575829 6.139845 -v 0.025597 -0.032848 0.103750 -vn 0.400679 0.832070 6.139861 -v 0.025545 -0.032807 0.103750 -vn 1.350871 -2.805074 5.025103 -v 0.033088 -0.033167 0.103723 -vn 2.142880 -4.558975 2.858084 -v 0.033120 -0.033233 0.103650 -vn 3.913053 -3.167854 2.911352 -v 0.033232 -0.033143 0.103650 -vn 4.927932 -1.062380 2.855292 -v 0.033295 -0.033014 0.103650 -vn 4.911254 1.095070 2.912947 -v 0.033295 -0.032870 0.103650 -vn 3.913053 3.167869 2.911345 -v 0.033232 -0.032740 0.103650 -vn 2.142902 4.559005 2.858045 -v 0.033120 -0.032651 0.103650 -vn 2.434146 -1.941198 5.025104 -v 0.033175 -0.033098 0.103723 -vn 3.035345 -0.692845 5.025058 -v 0.033223 -0.032997 0.103723 -vn 3.035333 0.692826 5.025073 -v 0.033223 -0.032886 0.103723 -vn 2.434147 1.941191 5.025118 -v 0.033175 -0.032786 0.103723 -vn 1.350884 2.805096 5.025026 -v 0.033088 -0.032717 0.103723 -vn 0.400720 -0.832079 6.139853 -v 0.033045 -0.033077 0.103750 -vn 0.722060 -0.575847 6.139845 -v 0.033097 -0.033035 0.103750 -vn 0.900369 -0.205485 6.139860 -v 0.033126 -0.032975 0.103750 -vn 0.900376 0.205503 6.139856 -v 0.033126 -0.032908 0.103750 -vn 0.722079 0.575822 6.139846 -v 0.033097 -0.032848 0.103750 -vn 0.400690 0.832070 6.139860 -v 0.033045 -0.032807 0.103750 -vn 1.350859 -2.805083 5.025101 -v 0.030588 -0.033167 0.103723 -vn 2.142883 -4.558973 2.858068 -v 0.030620 -0.033233 0.103650 -vn 3.913069 -3.167871 2.911295 -v 0.030732 -0.033143 0.103650 -vn 4.904577 -1.133647 2.934184 -v 0.030795 -0.033014 0.103650 -vn 4.904581 1.133645 2.934183 -v 0.030795 -0.032870 0.103650 -vn 3.913075 3.167876 2.911290 -v 0.030732 -0.032740 0.103650 -vn 2.142903 4.559010 2.858026 -v 0.030620 -0.032651 0.103650 -vn 2.434155 -1.941203 5.025073 -v 0.030675 -0.033098 0.103723 -vn 3.035355 -0.692826 5.025065 -v 0.030723 -0.032997 0.103723 -vn 3.035352 0.692818 5.025071 -v 0.030723 -0.032886 0.103723 -vn 2.434170 1.941187 5.025083 -v 0.030675 -0.032786 0.103723 -vn 1.350864 2.805103 5.025031 -v 0.030588 -0.032717 0.103723 -vn 0.400713 -0.832081 6.139853 -v 0.030545 -0.033077 0.103750 -vn 0.722050 -0.575843 6.139849 -v 0.030597 -0.033035 0.103750 -vn 0.900387 -0.205503 6.139853 -v 0.030626 -0.032975 0.103750 -vn 0.900388 0.205506 6.139853 -v 0.030626 -0.032908 0.103750 -vn 0.722054 0.575826 6.139852 -v 0.030597 -0.032848 0.103750 -vn 0.400688 0.832071 6.139860 -v 0.030545 -0.032807 0.103750 -vn 1.350865 -2.805077 5.025101 -v 0.028088 -0.033167 0.103723 -vn 2.142883 -4.558973 2.858068 -v 0.028120 -0.033233 0.103650 -vn 3.913061 -3.167855 2.911310 -v 0.028232 -0.033143 0.103650 -vn 4.927913 -1.062381 2.855297 -v 0.028295 -0.033014 0.103650 -vn 4.911227 1.095076 2.912957 -v 0.028295 -0.032870 0.103650 -vn 3.913060 3.167860 2.911308 -v 0.028232 -0.032740 0.103650 -vn 2.142906 4.559003 2.858029 -v 0.028120 -0.032651 0.103650 -vn 2.434150 -1.941186 5.025104 -v 0.028175 -0.033098 0.103723 -vn 3.035332 -0.692820 5.025098 -v 0.028223 -0.032997 0.103723 -vn 3.035326 0.692814 5.025105 -v 0.028223 -0.032886 0.103723 -vn 2.434164 1.941175 5.025108 -v 0.028175 -0.032786 0.103723 -vn 1.350879 2.805098 5.025024 -v 0.028088 -0.032717 0.103723 -vn 0.400717 -0.832082 6.139853 -v 0.028045 -0.033077 0.103750 -vn 0.722065 -0.575845 6.139844 -v 0.028097 -0.033035 0.103750 -vn 0.900384 -0.205488 6.139855 -v 0.028126 -0.032975 0.103750 -vn 0.900389 0.205500 6.139853 -v 0.028126 -0.032908 0.103750 -vn 0.722079 0.575822 6.139846 -v 0.028097 -0.032848 0.103750 -vn 0.400688 0.832071 6.139860 -v 0.028045 -0.032807 0.103750 -vn 2.879276 -3.416672 -1.921598 -v 0.033208 -0.033207 0.085146 -vn 2.424175 -0.771018 -1.826440 -v 0.033216 -0.033292 0.085192 -vn 3.410982 -1.751626 -3.223747 -v 0.033150 -0.033292 0.085100 -vn 0.187690 -1.104709 3.386720 -v 0.032980 -0.033292 0.084750 -vn 1.196482 -2.844120 3.358134 -v 0.033095 -0.033272 0.084750 -vn 3.202115 -2.945675 -0.455026 -v 0.033238 -0.033178 0.085100 -vn 3.171155 -0.316159 -1.738774 -v 0.033289 -0.033292 0.085286 -vn 2.248600 -2.055280 3.635268 -v 0.033238 -0.033178 0.084750 -vn 2.954037 -0.744343 3.635265 -v 0.033319 -0.033027 0.084750 -vn 2.954037 -0.744343 0.000000 -v 0.033319 -0.033027 0.085100 -vn 2.954037 0.744343 3.635266 -v 0.033319 -0.032856 0.084750 -vn 2.954037 0.744343 0.000000 -v 0.033319 -0.032856 0.085100 -vn 2.248600 2.055279 3.635268 -v 0.033238 -0.032706 0.084750 -vn 2.248600 2.055279 0.000000 -v 0.033238 -0.032706 0.085100 -vn 1.128467 2.859541 3.556747 -v 0.033095 -0.032611 0.084750 -vn 1.128467 2.859541 0.000000 -v 0.033095 -0.032611 0.085100 -vn 0.263108 1.548604 3.478172 -v 0.032980 -0.032592 0.084750 -vn 0.263108 1.548604 0.000000 -v 0.032980 -0.032592 0.085100 -vn 2.879271 -3.416754 -1.921668 -v 0.025708 -0.033207 0.085146 -vn 2.424123 -0.771129 -1.826442 -v 0.025716 -0.033292 0.085192 -vn 3.410978 -1.751651 -3.223740 -v 0.025650 -0.033292 0.085100 -vn 0.187687 -1.104709 3.386721 -v 0.025480 -0.033292 0.084750 -vn 1.196485 -2.844115 3.358147 -v 0.025595 -0.033272 0.084750 -vn 3.202123 -2.945679 -0.455037 -v 0.025738 -0.033178 0.085100 -vn 3.171140 -0.316175 -1.738779 -v 0.025789 -0.033292 0.085286 -vn 2.248600 -2.055288 3.635252 -v 0.025738 -0.033178 0.084750 -vn 2.954030 -0.744356 3.635274 -v 0.025819 -0.033027 0.084750 -vn 2.954030 -0.744356 0.000000 -v 0.025819 -0.033027 0.085100 -vn 2.954030 0.744356 3.635276 -v 0.025819 -0.032856 0.084750 -vn 2.954030 0.744356 0.000000 -v 0.025819 -0.032856 0.085100 -vn 2.248600 2.055288 3.635251 -v 0.025738 -0.032706 0.084750 -vn 2.248600 2.055287 0.000000 -v 0.025738 -0.032706 0.085100 -vn 1.128471 2.859536 3.556755 -v 0.025595 -0.032611 0.084750 -vn 1.128471 2.859536 0.000000 -v 0.025595 -0.032611 0.085100 -vn 0.263104 1.548605 3.478173 -v 0.025480 -0.032592 0.084750 -vn 0.263104 1.548605 0.000000 -v 0.025480 -0.032592 0.085100 -vn 2.879283 -3.416701 -1.921647 -v 0.028208 -0.033207 0.085146 -vn 2.424153 -0.771070 -1.826435 -v 0.028216 -0.033292 0.085192 -vn 3.411000 -1.751623 -3.223748 -v 0.028150 -0.033292 0.085100 -vn 0.187686 -1.104705 3.386720 -v 0.027980 -0.033292 0.084750 -vn 1.196486 -2.844115 3.358144 -v 0.028095 -0.033272 0.084750 -vn 3.202136 -2.945664 -0.455035 -v 0.028238 -0.033178 0.085100 -vn 3.171151 -0.316164 -1.738775 -v 0.028289 -0.033292 0.085286 -vn 2.248600 -2.055288 3.635252 -v 0.028238 -0.033178 0.084750 -vn 2.954030 -0.744356 3.635273 -v 0.028319 -0.033027 0.084750 -vn 2.954030 -0.744356 0.000000 -v 0.028319 -0.033027 0.085100 -vn 2.954030 0.744356 3.635272 -v 0.028319 -0.032856 0.084750 -vn 2.954030 0.744356 0.000000 -v 0.028319 -0.032856 0.085100 -vn 2.248600 2.055288 3.635252 -v 0.028238 -0.032706 0.084750 -vn 2.248600 2.055287 0.000000 -v 0.028238 -0.032706 0.085100 -vn 1.128471 2.859536 3.556756 -v 0.028095 -0.032611 0.084750 -vn 1.128471 2.859536 0.000000 -v 0.028095 -0.032611 0.085100 -vn 0.263104 1.548605 3.478173 -v 0.027980 -0.032592 0.084750 -vn 0.263104 1.548605 0.000000 -v 0.027980 -0.032592 0.085100 -vn 2.879283 -3.416701 -1.921647 -v 0.030708 -0.033207 0.085146 -vn 2.424153 -0.771070 -1.826435 -v 0.030716 -0.033292 0.085192 -vn 3.411000 -1.751623 -3.223748 -v 0.030650 -0.033292 0.085100 -vn 0.187686 -1.104705 3.386721 -v 0.030480 -0.033292 0.084750 -vn 1.196486 -2.844115 3.358144 -v 0.030595 -0.033272 0.084750 -vn 3.202136 -2.945664 -0.455035 -v 0.030738 -0.033178 0.085100 -vn 3.171151 -0.316163 -1.738775 -v 0.030789 -0.033292 0.085286 -vn 2.248600 -2.055288 3.635252 -v 0.030738 -0.033178 0.084750 -vn 2.954030 -0.744356 3.635275 -v 0.030819 -0.033027 0.084750 -vn 2.954030 -0.744356 0.000000 -v 0.030819 -0.033027 0.085100 -vn 2.954030 0.744356 3.635275 -v 0.030819 -0.032856 0.084750 -vn 2.954030 0.744356 0.000000 -v 0.030819 -0.032856 0.085100 -vn 2.248600 2.055288 3.635252 -v 0.030738 -0.032706 0.084750 -vn 2.248600 2.055287 0.000000 -v 0.030738 -0.032706 0.085100 -vn 1.128471 2.859536 3.556756 -v 0.030595 -0.032611 0.084750 -vn 1.128471 2.859536 0.000000 -v 0.030595 -0.032611 0.085100 -vn 0.263104 1.548605 3.478174 -v 0.030480 -0.032592 0.084750 -vn 0.263104 1.548605 0.000000 -v 0.030480 -0.032592 0.085100 -vn -5.969007 -1.077900 0.117169 -v 0.032630 -0.038062 0.085450 -vn -3.097507 0.002864 0.000017 -v 0.032630 -0.033292 0.085450 -vn -5.995479 -0.798896 -1.193868 -v 0.032638 -0.038062 0.085372 -vn -2.860435 0.004423 -1.127803 -v 0.032649 -0.033292 0.085334 -vn 3.073386 0.004799 -0.115842 -v 0.033330 -0.033292 0.085450 -vn 6.055973 -0.877480 0.000026 -v 0.033330 -0.038062 0.085450 -vn 5.995168 -0.796564 -1.195019 -v 0.033321 -0.038062 0.085372 -vn 5.600959 -0.850805 -2.325399 -v 0.033310 -0.038062 0.085334 -vn 4.908654 -0.792684 -3.570531 -v 0.033253 -0.038062 0.085232 -vn 2.517500 0.000523 -1.879309 -v 0.033218 -0.033292 0.085190 -vn 3.936712 -0.881317 -4.607370 -v 0.033216 -0.038062 0.085192 -vn 2.747752 -0.803803 -5.413193 -v 0.033132 -0.038062 0.085135 -vn -0.185602 -0.007024 -3.130302 -v 0.033065 -0.033292 0.085111 -vn 1.411744 -0.876465 -5.889452 -v 0.033065 -0.038062 0.085111 -vn 0.000016 -0.791013 -6.069503 -v 0.032980 -0.038062 0.085100 -vn -0.744726 0.006799 -2.955023 -v 0.032894 -0.033292 0.085111 -vn -1.411726 -0.876470 -5.889451 -v 0.032894 -0.038062 0.085111 -vn -2.754637 -0.790693 -5.408596 -v 0.032828 -0.038062 0.085135 -vn -2.056154 0.006339 -2.249167 -v 0.032744 -0.033292 0.085192 -vn -3.930309 -0.867810 -4.611671 -v 0.032744 -0.038062 0.085192 -vn -4.908852 -0.790232 -3.569990 -v 0.032706 -0.038062 0.085232 -vn -5.600030 -0.851487 -2.327973 -v 0.032649 -0.038062 0.085334 -vn -6.055990 -0.877514 0.000026 -v 0.025130 -0.038062 0.085450 -vn -3.097523 0.002864 0.000017 -v 0.025130 -0.033292 0.085450 -vn -5.995516 -0.798948 -1.193660 -v 0.025138 -0.038062 0.085372 -vn -2.860440 0.004423 -1.127769 -v 0.025149 -0.033292 0.085334 -vn 3.073390 0.004800 -0.115826 -v 0.025830 -0.033292 0.085450 -vn 5.969054 -1.077876 -0.117084 -v 0.025830 -0.038062 0.085450 -vn 5.979466 -0.881332 -1.094207 -v 0.025821 -0.038062 0.085372 -vn 5.600915 -0.850817 -2.325549 -v 0.025810 -0.038062 0.085334 -vn 4.908646 -0.792646 -3.570580 -v 0.025753 -0.038062 0.085232 -vn 2.517488 0.000522 -1.879325 -v 0.025718 -0.033292 0.085190 -vn 3.936747 -0.881283 -4.607366 -v 0.025716 -0.038062 0.085192 -vn 2.747777 -0.803779 -5.413182 -v 0.025632 -0.038062 0.085135 -vn -0.185602 -0.007024 -3.130302 -v 0.025565 -0.033292 0.085111 -vn 1.411740 -0.876458 -5.889455 -v 0.025565 -0.038062 0.085111 -vn 0.000008 -0.791013 -6.069501 -v 0.025480 -0.038062 0.085100 -vn -0.744719 0.006799 -2.955028 -v 0.025394 -0.033292 0.085111 -vn -1.411731 -0.876461 -5.889455 -v 0.025394 -0.038062 0.085111 -vn -2.754612 -0.790672 -5.408623 -v 0.025328 -0.038062 0.085135 -vn -2.056139 0.006339 -2.249182 -v 0.025244 -0.033292 0.085192 -vn -3.930292 -0.867822 -4.611672 -v 0.025244 -0.038062 0.085192 -vn -4.908827 -0.790275 -3.570020 -v 0.025206 -0.038062 0.085232 -vn -5.600013 -0.851544 -2.327863 -v 0.025149 -0.038062 0.085334 -vn -6.055990 -0.877514 0.000026 -v 0.027630 -0.038062 0.085450 -vn -3.097515 0.002865 0.000017 -v 0.027630 -0.033292 0.085450 -vn -5.995467 -0.798944 -1.193792 -v 0.027638 -0.038062 0.085372 -vn -2.860439 0.004423 -1.127779 -v 0.027649 -0.033292 0.085334 -vn 3.073382 0.004799 -0.115818 -v 0.028330 -0.033292 0.085450 -vn 5.969016 -1.077882 -0.117106 -v 0.028330 -0.038062 0.085450 -vn 5.979478 -0.881303 -1.094261 -v 0.028321 -0.038062 0.085372 -vn 5.600945 -0.850783 -2.325529 -v 0.028310 -0.038062 0.085334 -vn 4.908664 -0.792644 -3.570541 -v 0.028253 -0.038062 0.085232 -vn 2.517500 0.000522 -1.879309 -v 0.028218 -0.033292 0.085190 -vn 3.936738 -0.881294 -4.607368 -v 0.028216 -0.038062 0.085192 -vn 2.747777 -0.803802 -5.413174 -v 0.028132 -0.038062 0.085135 -vn -0.185602 -0.007024 -3.130302 -v 0.028065 -0.033292 0.085111 -vn 1.411735 -0.876467 -5.889451 -v 0.028065 -0.038062 0.085111 -vn 0.000000 -0.791013 -6.069502 -v 0.027980 -0.038062 0.085100 -vn -0.744719 0.006799 -2.955028 -v 0.027894 -0.033292 0.085111 -vn -1.411735 -0.876467 -5.889451 -v 0.027894 -0.038062 0.085111 -vn -2.754612 -0.790694 -5.408615 -v 0.027828 -0.038062 0.085135 -vn -2.056147 0.006339 -2.249170 -v 0.027744 -0.033292 0.085192 -vn -3.930283 -0.867834 -4.611674 -v 0.027744 -0.038062 0.085192 -vn -4.908842 -0.790273 -3.569980 -v 0.027706 -0.038062 0.085232 -vn -5.600015 -0.851533 -2.327966 -v 0.027649 -0.038062 0.085334 -vn -5.969045 -1.077894 0.117146 -v 0.030130 -0.038062 0.085450 -vn -3.097515 0.002865 0.000017 -v 0.030130 -0.033292 0.085450 -vn -5.995466 -0.798944 -1.193792 -v 0.030138 -0.038062 0.085372 -vn -2.860439 0.004423 -1.127779 -v 0.030149 -0.033292 0.085334 -vn 3.073382 0.004801 -0.115818 -v 0.030830 -0.033292 0.085450 -vn 6.055990 -0.877514 0.000026 -v 0.030830 -0.038062 0.085450 -vn 5.995056 -0.796606 -1.195205 -v 0.030821 -0.038062 0.085372 -vn 5.600917 -0.850806 -2.325652 -v 0.030810 -0.038062 0.085334 -vn 4.908664 -0.792644 -3.570541 -v 0.030753 -0.038062 0.085232 -vn 2.517500 0.000522 -1.879309 -v 0.030718 -0.033292 0.085190 -vn 3.936738 -0.881294 -4.607368 -v 0.030716 -0.038062 0.085192 -vn 2.747777 -0.803802 -5.413174 -v 0.030632 -0.038062 0.085135 -vn -0.185602 -0.007024 -3.130302 -v 0.030565 -0.033292 0.085111 -vn 1.411735 -0.876467 -5.889451 -v 0.030565 -0.038062 0.085111 -vn 0.000000 -0.791013 -6.069502 -v 0.030480 -0.038062 0.085100 -vn -0.744719 0.006799 -2.955028 -v 0.030394 -0.033292 0.085111 -vn -1.411735 -0.876467 -5.889452 -v 0.030394 -0.038062 0.085111 -vn -2.754611 -0.790694 -5.408615 -v 0.030328 -0.038062 0.085135 -vn -2.056147 0.006339 -2.249170 -v 0.030244 -0.033292 0.085192 -vn -3.930283 -0.867834 -4.611674 -v 0.030244 -0.038062 0.085192 -vn -4.908842 -0.790273 -3.569980 -v 0.030206 -0.038062 0.085232 -vn -5.600015 -0.851532 -2.327966 -v 0.030149 -0.038062 0.085334 -vn 2.195339 -2.939853 -4.528716 -v 0.033120 -0.038162 0.085159 -vn 3.950088 -2.926338 -3.119596 -v 0.033232 -0.038162 0.085248 -vn 4.900142 -2.951513 -1.130934 -v 0.033295 -0.038162 0.085378 -vn 5.995591 -0.798865 1.193629 -v 0.033321 -0.038062 0.085528 -vn 4.900128 -2.951481 1.130967 -v 0.033295 -0.038162 0.085522 -vn 5.600088 -0.851457 2.327715 -v 0.033310 -0.038062 0.085566 -vn 4.909084 -0.790204 3.569791 -v 0.033253 -0.038062 0.085668 -vn 3.950039 -2.926320 3.119567 -v 0.033232 -0.038162 0.085652 -vn 3.930416 -0.867803 4.611492 -v 0.033216 -0.038062 0.085708 -vn 2.754292 -0.790685 5.408715 -v 0.033132 -0.038062 0.085765 -vn 2.195142 -2.939882 4.528657 -v 0.033120 -0.038162 0.085741 -vn 1.411468 -0.876431 5.889594 -v 0.033065 -0.038062 0.085789 -vn 0.000016 -0.791013 6.069503 -v 0.032980 -0.038062 0.085800 -vn 0.000039 -2.944309 5.032596 -v 0.032980 -0.038162 0.085773 -vn 1.350891 -5.025161 2.805093 -v 0.033088 -0.038235 0.085675 -vn 0.000047 -5.025105 3.113471 -v 0.032980 -0.038235 0.085700 -vn 0.400796 -6.139796 0.832230 -v 0.033045 -0.038262 0.085585 -vn -0.000021 -6.139828 0.923630 -v 0.032980 -0.038262 0.085600 -vn 2.434139 -5.025249 1.941163 -v 0.033175 -0.038235 0.085606 -vn 0.722157 -6.139813 0.575892 -v 0.033097 -0.038262 0.085544 -vn 3.035364 -5.025147 0.692798 -v 0.033223 -0.038235 0.085506 -vn 0.900501 -6.139813 0.205555 -v 0.033126 -0.038262 0.085483 -vn 3.035382 -5.025105 -0.692853 -v 0.033223 -0.038235 0.085394 -vn 0.900484 -6.139823 -0.205512 -v 0.033126 -0.038262 0.085417 -vn 2.434196 -5.025168 -1.941186 -v 0.033175 -0.038235 0.085294 -vn 0.722152 -6.139809 -0.575921 -v 0.033097 -0.038262 0.085356 -vn 1.350908 -5.025092 -2.805119 -v 0.033088 -0.038235 0.085225 -vn 0.400771 -6.139823 -0.832161 -v 0.033045 -0.038262 0.085315 -vn 0.000016 -2.944305 -5.032547 -v 0.032980 -0.038162 0.085127 -vn 0.000009 -5.025080 -3.113474 -v 0.032980 -0.038235 0.085200 -vn -0.000001 -6.139816 -0.923657 -v 0.032980 -0.038262 0.085300 -vn 2.195359 -2.939831 -4.528691 -v 0.025620 -0.038162 0.085159 -vn 3.035383 -5.025146 0.692790 -v 0.025723 -0.038235 0.085506 -vn 0.900514 -6.139810 0.205552 -v 0.025626 -0.038262 0.085483 -vn 0.900499 -6.139817 -0.205515 -v 0.025626 -0.038262 0.085417 -vn 2.434170 -5.025217 1.941154 -v 0.025675 -0.038235 0.085606 -vn 0.722155 -6.139813 0.575899 -v 0.025597 -0.038262 0.085544 -vn 1.350861 -5.025181 2.805095 -v 0.025588 -0.038235 0.085675 -vn 0.400786 -6.139798 0.832230 -v 0.025545 -0.038262 0.085585 -vn -0.000023 -6.139827 0.923631 -v 0.025480 -0.038262 0.085600 -vn 0.000044 -5.025105 3.113469 -v 0.025480 -0.038235 0.085700 -vn 0.000033 -2.944307 5.032597 -v 0.025480 -0.038162 0.085773 -vn 3.035395 -5.025111 -0.692833 -v 0.025723 -0.038235 0.085394 -vn 4.923497 -2.872656 -1.059685 -v 0.025795 -0.038162 0.085378 -vn 4.906787 -2.930279 1.092414 -v 0.025795 -0.038162 0.085522 -vn 0.722155 -6.139805 -0.575929 -v 0.025597 -0.038262 0.085356 -vn 2.434208 -5.025134 -1.941197 -v 0.025675 -0.038235 0.085294 -vn 3.950106 -2.926294 -3.119614 -v 0.025732 -0.038162 0.085248 -vn 2.195155 -2.939856 4.528642 -v 0.025620 -0.038162 0.085741 -vn 2.754318 -0.790661 5.408704 -v 0.025632 -0.038062 0.085765 -vn 1.411464 -0.876424 5.889598 -v 0.025565 -0.038062 0.085789 -vn 0.000008 -0.791013 6.069501 -v 0.025480 -0.038062 0.085800 -vn 3.950068 -2.926276 3.119574 -v 0.025732 -0.038162 0.085652 -vn 4.909079 -0.790165 3.569842 -v 0.025753 -0.038062 0.085668 -vn 3.930451 -0.867768 4.611487 -v 0.025716 -0.038062 0.085708 -vn 5.995529 -0.798909 1.193684 -v 0.025821 -0.038062 0.085528 -vn 5.600043 -0.851467 2.327864 -v 0.025810 -0.038062 0.085566 -vn 1.350898 -5.025103 -2.805117 -v 0.025588 -0.038235 0.085225 -vn 0.400763 -6.139824 -0.832161 -v 0.025545 -0.038262 0.085315 -vn 0.000006 -2.944304 -5.032547 -v 0.025480 -0.038162 0.085127 -vn -0.000000 -5.025079 -3.113473 -v 0.025480 -0.038235 0.085200 -vn -0.000004 -6.139816 -0.923658 -v 0.025480 -0.038262 0.085300 -vn 2.195341 -2.939846 -4.528713 -v 0.028120 -0.038162 0.085159 -vn 3.035357 -5.025179 0.692786 -v 0.028223 -0.038235 0.085506 -vn 0.900514 -6.139810 0.205552 -v 0.028126 -0.038262 0.085483 -vn 0.900499 -6.139818 -0.205515 -v 0.028126 -0.038262 0.085417 -vn 2.434157 -5.025239 1.941146 -v 0.028175 -0.038235 0.085606 -vn 0.722157 -6.139814 0.575892 -v 0.028097 -0.038262 0.085544 -vn 1.350885 -5.025159 2.805095 -v 0.028088 -0.038235 0.085675 -vn 0.400794 -6.139796 0.832232 -v 0.028045 -0.038262 0.085585 -vn -0.000027 -6.139828 0.923629 -v 0.027980 -0.038262 0.085600 -vn 0.000035 -5.025105 3.113470 -v 0.027980 -0.038235 0.085700 -vn 0.000023 -2.944309 5.032596 -v 0.027980 -0.038162 0.085773 -vn 3.035369 -5.025145 -0.692828 -v 0.028223 -0.038235 0.085394 -vn 4.923479 -2.872624 -1.059678 -v 0.028295 -0.038162 0.085378 -vn 4.906766 -2.930260 1.092414 -v 0.028295 -0.038162 0.085522 -vn 0.722158 -6.139807 -0.575919 -v 0.028097 -0.038262 0.085356 -vn 2.434200 -5.025168 -1.941174 -v 0.028175 -0.038235 0.085294 -vn 3.950096 -2.926295 -3.119597 -v 0.028232 -0.038162 0.085248 -vn 2.195144 -2.939874 4.528655 -v 0.028120 -0.038162 0.085741 -vn 2.754317 -0.790684 5.408696 -v 0.028132 -0.038062 0.085765 -vn 1.411459 -0.876433 5.889594 -v 0.028065 -0.038062 0.085789 -vn 0.000000 -0.791013 6.069502 -v 0.027980 -0.038062 0.085800 -vn 3.950047 -2.926282 3.119558 -v 0.028232 -0.038162 0.085652 -vn 4.909094 -0.790163 3.569802 -v 0.028253 -0.038062 0.085668 -vn 3.930442 -0.867779 4.611489 -v 0.028216 -0.038062 0.085708 -vn 5.995542 -0.798861 1.193760 -v 0.028321 -0.038062 0.085528 -vn 5.600073 -0.851433 2.327845 -v 0.028310 -0.038062 0.085566 -vn 1.350902 -5.025090 -2.805121 -v 0.028088 -0.038235 0.085225 -vn 0.400768 -6.139822 -0.832163 -v 0.028045 -0.038262 0.085315 -vn -0.000000 -2.944305 -5.032546 -v 0.027980 -0.038162 0.085127 -vn -0.000003 -5.025080 -3.113474 -v 0.027980 -0.038235 0.085200 -vn -0.000007 -6.139816 -0.923657 -v 0.027980 -0.038262 0.085300 -vn 2.195341 -2.939846 -4.528713 -v 0.030620 -0.038162 0.085159 -vn 3.950105 -2.926280 -3.119613 -v 0.030732 -0.038162 0.085248 -vn 4.900145 -2.951506 -1.130946 -v 0.030795 -0.038162 0.085378 -vn 5.995480 -0.798905 1.193816 -v 0.030821 -0.038062 0.085528 -vn 4.900123 -2.951478 1.130984 -v 0.030795 -0.038162 0.085522 -vn 5.600045 -0.851455 2.327967 -v 0.030810 -0.038062 0.085566 -vn 4.909094 -0.790163 3.569802 -v 0.030753 -0.038062 0.085668 -vn 3.950062 -2.926264 3.119574 -v 0.030732 -0.038162 0.085652 -vn 3.930442 -0.867779 4.611489 -v 0.030716 -0.038062 0.085708 -vn 2.754317 -0.790684 5.408696 -v 0.030632 -0.038062 0.085765 -vn 2.195142 -2.939871 4.528661 -v 0.030620 -0.038162 0.085741 -vn 1.411459 -0.876433 5.889594 -v 0.030565 -0.038062 0.085789 -vn 0.000000 -0.791013 6.069502 -v 0.030480 -0.038062 0.085800 -vn 0.000023 -2.944309 5.032596 -v 0.030480 -0.038162 0.085773 -vn 1.350870 -5.025166 2.805099 -v 0.030588 -0.038235 0.085675 -vn 0.000035 -5.025105 3.113470 -v 0.030480 -0.038235 0.085700 -vn 0.400794 -6.139796 0.832232 -v 0.030545 -0.038262 0.085585 -vn -0.000027 -6.139828 0.923629 -v 0.030480 -0.038262 0.085600 -vn 2.434163 -5.025214 1.941159 -v 0.030675 -0.038235 0.085606 -vn 0.722133 -6.139820 0.575897 -v 0.030597 -0.038262 0.085544 -vn 3.035383 -5.025146 0.692791 -v 0.030723 -0.038235 0.085506 -vn 0.900513 -6.139810 0.205558 -v 0.030626 -0.038262 0.085483 -vn 3.035391 -5.025112 -0.692834 -v 0.030723 -0.038235 0.085394 -vn 0.900502 -6.139816 -0.205529 -v 0.030626 -0.038262 0.085417 -vn 2.434204 -5.025136 -1.941191 -v 0.030675 -0.038235 0.085294 -vn 0.722143 -6.139811 -0.575917 -v 0.030597 -0.038262 0.085356 -vn 1.350896 -5.025091 -2.805128 -v 0.030588 -0.038235 0.085225 -vn 0.400765 -6.139823 -0.832163 -v 0.030545 -0.038262 0.085315 -vn -0.000000 -2.944305 -5.032546 -v 0.030480 -0.038162 0.085127 -vn -0.000003 -5.025080 -3.113474 -v 0.030480 -0.038235 0.085200 -vn -0.000007 -6.139816 -0.923657 -v 0.030480 -0.038262 0.085300 -vn 0.000009 5.917497 -0.764931 -v 0.032980 -0.032592 0.079550 -vn 0.000008 3.035459 -3.659801 -v 0.032980 -0.032592 0.082850 -vn 2.113884 5.680769 -0.786186 -v 0.033132 -0.032626 0.079550 -vn 1.516886 2.629617 -3.657923 -v 0.033155 -0.032639 0.082850 -vn 3.424639 5.012310 -0.833174 -v 0.033155 -0.032639 0.079550 -vn 4.521364 4.035896 -0.788062 -v 0.033253 -0.032724 0.079550 -vn 2.629152 1.518595 -3.655163 -v 0.033283 -0.032767 0.082850 -vn 5.360843 2.825667 -0.865592 -v 0.033283 -0.032767 0.079550 -vn 5.866790 1.356785 -0.873665 -v 0.033321 -0.032864 0.079550 -vn 3.036365 0.000008 -3.654226 -v 0.033330 -0.032942 0.082850 -vn 5.969022 0.117153 -1.077860 -v 0.033330 -0.032942 0.079550 -vn 5.882432 -1.457667 -0.788910 -v 0.033321 -0.033020 0.079550 -vn 2.629154 -1.518588 -3.655169 -v 0.033283 -0.033117 0.082850 -vn 5.360843 -2.825667 -0.865592 -v 0.033283 -0.033117 0.079550 -vn 4.521364 -4.035895 -0.788062 -v 0.033253 -0.033160 0.079550 -vn 1.516886 -2.629617 -3.657923 -v 0.033155 -0.033245 0.082850 -vn 3.424639 -5.012310 -0.833174 -v 0.033155 -0.033245 0.079550 -vn 2.113876 -5.680769 -0.786192 -v 0.033132 -0.033257 0.079550 -vn 0.000008 -3.035459 -3.659801 -v 0.032980 -0.033292 0.082850 -vn 0.000023 -5.917497 -0.764931 -v 0.032980 -0.033292 0.079550 -vn 0.000003 5.917496 -0.764928 -v 0.025480 -0.032592 0.079550 -vn 0.000004 3.035457 -3.659804 -v 0.025480 -0.032592 0.082850 -vn 2.113880 5.680776 -0.786170 -v 0.025632 -0.032626 0.079550 -vn 1.516885 2.629616 -3.657924 -v 0.025655 -0.032639 0.082850 -vn 3.424663 5.012299 -0.833146 -v 0.025655 -0.032639 0.079550 -vn 4.521348 4.035968 -0.788029 -v 0.025753 -0.032724 0.079550 -vn 2.629151 1.518596 -3.655159 -v 0.025783 -0.032767 0.082850 -vn 5.360783 2.825766 -0.865588 -v 0.025783 -0.032767 0.079550 -vn 5.882396 1.457652 -0.788955 -v 0.025821 -0.032864 0.079550 -vn 3.036365 0.000008 -3.654225 -v 0.025830 -0.032942 0.082850 -vn 6.055999 0.000016 -0.877480 -v 0.025830 -0.032942 0.079550 -vn 5.882396 -1.457635 -0.788954 -v 0.025821 -0.033020 0.079550 -vn 2.629154 -1.518588 -3.655169 -v 0.025783 -0.033117 0.082850 -vn 5.360783 -2.825766 -0.865588 -v 0.025783 -0.033117 0.079550 -vn 4.521348 -4.035967 -0.788029 -v 0.025753 -0.033160 0.079550 -vn 1.516886 -2.629616 -3.657924 -v 0.025655 -0.033245 0.082850 -vn 3.424663 -5.012299 -0.833146 -v 0.025655 -0.033245 0.079550 -vn 2.113875 -5.680776 -0.786174 -v 0.025632 -0.033257 0.079550 -vn 0.000004 -3.035458 -3.659803 -v 0.025480 -0.033292 0.082850 -vn 0.000012 -5.917495 -0.764928 -v 0.025480 -0.033292 0.079550 -vn -0.000007 5.917497 -0.764931 -v 0.027980 -0.032592 0.079550 -vn 0.000004 3.035457 -3.659803 -v 0.027980 -0.032592 0.082850 -vn 2.113963 5.680715 -0.786183 -v 0.028132 -0.032626 0.079550 -vn 1.516886 2.629618 -3.657923 -v 0.028155 -0.032639 0.082850 -vn 3.424730 5.012280 -0.833158 -v 0.028155 -0.032639 0.079550 -vn 4.521372 4.035907 -0.788025 -v 0.028253 -0.032724 0.079550 -vn 2.629148 1.518611 -3.655149 -v 0.028283 -0.032767 0.082850 -vn 5.360844 2.825712 -0.865561 -v 0.028283 -0.032767 0.079550 -vn 5.882410 1.457729 -0.788909 -v 0.028321 -0.032864 0.079550 -vn 3.036357 0.000008 -3.654245 -v 0.028330 -0.032942 0.082850 -vn 6.055983 0.000016 -0.877447 -v 0.028330 -0.032942 0.079550 -vn 5.882410 -1.457713 -0.788908 -v 0.028321 -0.033020 0.079550 -vn 2.629150 -1.518603 -3.655159 -v 0.028283 -0.033117 0.082850 -vn 5.360843 -2.825712 -0.865561 -v 0.028283 -0.033117 0.079550 -vn 4.521372 -4.035907 -0.788025 -v 0.028253 -0.033160 0.079550 -vn 1.516886 -2.629618 -3.657923 -v 0.028155 -0.033245 0.082850 -vn 3.424729 -5.012280 -0.833158 -v 0.028155 -0.033245 0.079550 -vn 2.113955 -5.680715 -0.786189 -v 0.028132 -0.033257 0.079550 -vn 0.000004 -3.035457 -3.659803 -v 0.027980 -0.033292 0.082850 -vn 0.000007 -5.917497 -0.764931 -v 0.027980 -0.033292 0.079550 -vn -0.000007 5.917497 -0.764931 -v 0.030480 -0.032592 0.079550 -vn 0.000000 3.035456 -3.659807 -v 0.030480 -0.032592 0.082850 -vn 2.113963 5.680715 -0.786183 -v 0.030632 -0.032626 0.079550 -vn 1.516886 2.629618 -3.657923 -v 0.030655 -0.032639 0.082850 -vn 3.424730 5.012280 -0.833158 -v 0.030655 -0.032639 0.079550 -vn 4.521372 4.035907 -0.788025 -v 0.030753 -0.032724 0.079550 -vn 2.629148 1.518611 -3.655153 -v 0.030783 -0.032767 0.082850 -vn 5.360830 2.825749 -0.865574 -v 0.030783 -0.032767 0.079550 -vn 5.866732 1.356821 -0.873688 -v 0.030821 -0.032864 0.079550 -vn 3.036357 0.000008 -3.654244 -v 0.030830 -0.032942 0.082850 -vn 5.969059 0.117131 -1.077854 -v 0.030830 -0.032942 0.079550 -vn 5.882374 -1.457681 -0.788952 -v 0.030821 -0.033020 0.079550 -vn 2.629150 -1.518603 -3.655158 -v 0.030783 -0.033117 0.082850 -vn 5.360830 -2.825749 -0.865574 -v 0.030783 -0.033117 0.079550 -vn 4.521372 -4.035907 -0.788025 -v 0.030753 -0.033160 0.079550 -vn 1.516886 -2.629618 -3.657923 -v 0.030655 -0.033245 0.082850 -vn 3.424729 -5.012280 -0.833158 -v 0.030655 -0.033245 0.079550 -vn 2.113955 -5.680715 -0.786189 -v 0.030632 -0.033257 0.079550 -vn 0.000000 -3.035456 -3.659805 -v 0.030480 -0.033292 0.082850 -vn 0.000007 -5.917497 -0.764931 -v 0.030480 -0.033292 0.079550 -vn -0.000011 0.923799 -6.139771 -v 0.032980 -0.032792 0.079350 -vn 0.000033 3.113483 -5.025212 -v 0.032980 -0.032692 0.079377 -vn 1.350881 2.805182 -5.025118 -v 0.033088 -0.032717 0.079377 -vn 0.000020 5.044514 -2.795692 -v 0.032980 -0.032619 0.079450 -vn 2.142845 4.558920 -2.858082 -v 0.033120 -0.032651 0.079450 -vn 3.912992 3.167787 -2.911372 -v 0.033232 -0.032740 0.079450 -vn 4.927833 1.062360 -2.855323 -v 0.033295 -0.032870 0.079450 -vn 4.911158 -1.095047 -2.912974 -v 0.033295 -0.033014 0.079450 -vn 3.912976 -3.167804 -2.911373 -v 0.033232 -0.033143 0.079450 -vn 2.142831 -4.558886 -2.858106 -v 0.033120 -0.033233 0.079450 -vn 0.000023 -5.044499 -2.795702 -v 0.032980 -0.033265 0.079450 -vn 2.434225 1.941209 -5.025215 -v 0.033175 -0.032786 0.079377 -vn 3.035418 0.692862 -5.025152 -v 0.033223 -0.032886 0.079377 -vn 3.035406 -0.692843 -5.025167 -v 0.033223 -0.032997 0.079377 -vn 2.434186 -1.941249 -5.025211 -v 0.033175 -0.033098 0.079377 -vn 1.350900 -2.805145 -5.025194 -v 0.033088 -0.033167 0.079377 -vn 0.000015 -3.113482 -5.025189 -v 0.032980 -0.033192 0.079377 -vn 0.400822 0.832267 -6.139785 -v 0.033045 -0.032807 0.079350 -vn 0.722245 0.575994 -6.139771 -v 0.033097 -0.032848 0.079350 -vn 0.900600 0.205538 -6.139785 -v 0.033126 -0.032908 0.079350 -vn 0.900607 -0.205555 -6.139781 -v 0.033126 -0.032975 0.079350 -vn 0.722263 -0.575979 -6.139769 -v 0.033097 -0.033035 0.079350 -vn 0.400808 -0.832298 -6.139778 -v 0.033045 -0.033077 0.079350 -vn 0.000013 -0.923808 -6.139768 -v 0.032980 -0.033092 0.079350 -vn -0.000014 0.923801 -6.139770 -v 0.025480 -0.032792 0.079350 -vn 0.000024 3.113482 -5.025211 -v 0.025480 -0.032692 0.079377 -vn 1.350872 2.805180 -5.025130 -v 0.025588 -0.032717 0.079377 -vn 0.000014 5.044514 -2.795692 -v 0.025480 -0.032619 0.079450 -vn 2.142859 4.558897 -2.858065 -v 0.025620 -0.032651 0.079450 -vn 3.913010 3.167802 -2.911341 -v 0.025732 -0.032740 0.079450 -vn 4.904481 1.133612 -2.934228 -v 0.025795 -0.032870 0.079450 -vn 4.904487 -1.133608 -2.934223 -v 0.025795 -0.033014 0.079450 -vn 3.913004 -3.167809 -2.911341 -v 0.025732 -0.033143 0.079450 -vn 2.142842 -4.558870 -2.858087 -v 0.025620 -0.033233 0.079450 -vn 0.000015 -5.044500 -2.795702 -v 0.025480 -0.033265 0.079450 -vn 2.434237 1.941221 -5.025182 -v 0.025675 -0.032786 0.079377 -vn 3.035431 0.692841 -5.025159 -v 0.025723 -0.032886 0.079377 -vn 3.035424 -0.692835 -5.025165 -v 0.025723 -0.032997 0.079377 -vn 2.434217 -1.941240 -5.025179 -v 0.025675 -0.033098 0.079377 -vn 1.350871 -2.805147 -5.025214 -v 0.025588 -0.033167 0.079377 -vn 0.000012 -3.113480 -5.025189 -v 0.025480 -0.033192 0.079377 -vn 0.400814 0.832268 -6.139786 -v 0.025545 -0.032807 0.079350 -vn 0.722248 0.576003 -6.139768 -v 0.025597 -0.032848 0.079350 -vn 0.900615 0.205541 -6.139780 -v 0.025626 -0.032908 0.079350 -vn 0.900620 -0.205553 -6.139778 -v 0.025626 -0.032975 0.079350 -vn 0.722261 -0.575987 -6.139768 -v 0.025597 -0.033035 0.079350 -vn 0.400798 -0.832299 -6.139780 -v 0.025545 -0.033077 0.079350 -vn 0.000010 -0.923809 -6.139767 -v 0.025480 -0.033092 0.079350 -vn -0.000017 0.923800 -6.139770 -v 0.027980 -0.032792 0.079350 -vn 0.000022 3.113483 -5.025212 -v 0.027980 -0.032692 0.079377 -vn 1.350876 2.805184 -5.025117 -v 0.028088 -0.032717 0.079377 -vn 0.000006 5.044514 -2.795692 -v 0.027980 -0.032619 0.079450 -vn 2.142848 4.558918 -2.858066 -v 0.028120 -0.032651 0.079450 -vn 3.913000 3.167788 -2.911330 -v 0.028232 -0.032740 0.079450 -vn 4.904459 1.133620 -2.934213 -v 0.028295 -0.032870 0.079450 -vn 4.904464 -1.133616 -2.934208 -v 0.028295 -0.033014 0.079450 -vn 3.912983 -3.167796 -2.911336 -v 0.028232 -0.033143 0.079450 -vn 2.142834 -4.558884 -2.858091 -v 0.028120 -0.033233 0.079450 -vn 0.000009 -5.044500 -2.795702 -v 0.027980 -0.033265 0.079450 -vn 2.434229 1.941197 -5.025215 -v 0.028175 -0.032786 0.079377 -vn 3.035405 0.692837 -5.025192 -v 0.028223 -0.032886 0.079377 -vn 3.035398 -0.692830 -5.025198 -v 0.028223 -0.032997 0.079377 -vn 2.434203 -1.941233 -5.025202 -v 0.028175 -0.033098 0.079377 -vn 1.350895 -2.805147 -5.025193 -v 0.028088 -0.033167 0.079377 -vn 0.000003 -3.113482 -5.025190 -v 0.027980 -0.033192 0.079377 -vn 0.400820 0.832270 -6.139785 -v 0.028045 -0.032807 0.079350 -vn 0.722250 0.575993 -6.139769 -v 0.028097 -0.032848 0.079350 -vn 0.900615 0.205541 -6.139780 -v 0.028126 -0.032908 0.079350 -vn 0.900620 -0.205553 -6.139778 -v 0.028126 -0.032975 0.079350 -vn 0.722263 -0.575979 -6.139769 -v 0.028097 -0.033035 0.079350 -vn 0.400806 -0.832300 -6.139778 -v 0.028045 -0.033077 0.079350 -vn 0.000007 -0.923807 -6.139768 -v 0.027980 -0.033092 0.079350 -vn -0.000017 0.923800 -6.139770 -v 0.030480 -0.032792 0.079350 -vn 0.000022 3.113483 -5.025212 -v 0.030480 -0.032692 0.079377 -vn 1.350870 2.805191 -5.025117 -v 0.030588 -0.032717 0.079377 -vn 0.000006 5.044514 -2.795692 -v 0.030480 -0.032619 0.079450 -vn 2.142848 4.558918 -2.858066 -v 0.030620 -0.032651 0.079450 -vn 3.913009 3.167804 -2.911316 -v 0.030732 -0.032740 0.079450 -vn 4.927829 1.062381 -2.855346 -v 0.030795 -0.032870 0.079450 -vn 4.911149 -1.095065 -2.912989 -v 0.030795 -0.033014 0.079450 -vn 3.912998 -3.167811 -2.911318 -v 0.030732 -0.033143 0.079450 -vn 2.142832 -4.558889 -2.858088 -v 0.030620 -0.033233 0.079450 -vn 0.000009 -5.044500 -2.795702 -v 0.030480 -0.033265 0.079450 -vn 2.434234 1.941214 -5.025184 -v 0.030675 -0.032786 0.079377 -vn 3.035427 0.692843 -5.025159 -v 0.030723 -0.032886 0.079377 -vn 3.035424 -0.692835 -5.025165 -v 0.030723 -0.032997 0.079377 -vn 2.434209 -1.941245 -5.025177 -v 0.030675 -0.033098 0.079377 -vn 1.350879 -2.805152 -5.025199 -v 0.030588 -0.033167 0.079377 -vn 0.000003 -3.113482 -5.025190 -v 0.030480 -0.033192 0.079377 -vn 0.400816 0.832269 -6.139785 -v 0.030545 -0.032807 0.079350 -vn 0.722236 0.575991 -6.139773 -v 0.030597 -0.032848 0.079350 -vn 0.900618 0.205556 -6.139777 -v 0.030626 -0.032908 0.079350 -vn 0.900619 -0.205559 -6.139777 -v 0.030626 -0.032975 0.079350 -vn 0.722239 -0.575984 -6.139774 -v 0.030597 -0.033035 0.079350 -vn 0.400806 -0.832300 -6.139778 -v 0.030545 -0.033077 0.079350 -vn 0.000007 -0.923807 -6.139768 -v 0.030480 -0.033092 0.079350 -vn -1.570796 -1.570796 1.570796 -v 0.023030 -0.034762 0.086750 -vn -1.570796 -1.570796 -1.570796 -v 0.023030 -0.034762 0.083650 -vn -1.110721 -5.823110 -0.785398 -v 0.024530 -0.034762 0.083650 -vn 1.570796 -4.712389 1.570796 -v 0.032620 -0.034762 0.084650 -vn -1.110721 -2.681517 -2.356194 -v 0.024530 -0.034762 0.078850 -vn -1.570796 -4.712389 1.570796 -v 0.033340 -0.034762 0.084650 -vn 1.570796 -1.570796 -1.570796 -v 0.035430 -0.034762 0.078850 -vn -3.070403 -2.839375 0.467528 -v 0.033340 -0.034762 0.085900 -vn 1.570796 -1.570796 1.570796 -v 0.035430 -0.034762 0.086750 -vn -1.499606 -1.873014 2.038325 -v 0.033605 -0.034762 0.086750 -vn 1.570796 -4.712389 1.570796 -v 0.030120 -0.034762 0.084650 -vn -1.570796 -4.712389 1.570796 -v 0.030840 -0.034762 0.084650 -vn -3.070404 -2.839379 0.467523 -v 0.030840 -0.034762 0.085900 -vn 3.070403 -2.839376 0.467528 -v 0.032620 -0.034762 0.085900 -vn -1.499608 -1.873010 2.038319 -v 0.031105 -0.034762 0.086750 -vn 1.499606 -1.873014 2.038325 -v 0.032355 -0.034762 0.086750 -vn 1.499607 -1.873010 2.038320 -v 0.029855 -0.034762 0.086750 -vn -1.499607 -1.873012 2.038322 -v 0.028605 -0.034762 0.086750 -vn 3.070403 -2.839375 0.467527 -v 0.030120 -0.034762 0.085900 -vn -3.070403 -2.839377 0.467526 -v 0.028340 -0.034762 0.085900 -vn -1.570796 -4.712389 1.570796 -v 0.028340 -0.034762 0.084650 -vn 1.499608 -1.873009 2.038318 -v 0.027355 -0.034762 0.086750 -vn -1.499607 -1.873012 2.038322 -v 0.026105 -0.034762 0.086750 -vn 3.070404 -2.839378 0.467523 -v 0.027620 -0.034762 0.085900 -vn -3.070403 -2.839377 0.467526 -v 0.025840 -0.034762 0.085900 -vn 1.570796 -4.712389 1.570796 -v 0.027620 -0.034762 0.084650 -vn -1.570796 -4.712389 1.570796 -v 0.025840 -0.034762 0.084650 -vn 1.570796 -4.712389 1.570796 -v 0.025120 -0.034762 0.084650 -vn 3.070403 -2.839377 0.467526 -v 0.025120 -0.034762 0.085900 -vn 1.499607 -1.873012 2.038321 -v 0.024855 -0.034762 0.086750 -vn 3.070403 2.839377 0.467526 -v 0.025120 -0.033762 0.085900 -vn 3.141593 -0.000000 3.141593 -v 0.025120 -0.033762 0.084750 -vn 1.570796 -1.570796 1.570796 -v 0.025120 -0.033762 0.084650 -vn -1.570796 -1.570797 1.570796 -v 0.025840 -0.033762 0.084650 -vn -3.141593 -0.000000 3.141593 -v 0.025840 -0.033762 0.084750 -vn -3.070403 2.839377 0.467526 -v 0.025840 -0.033762 0.085900 -vn -2.227276 1.264155 3.529329 -v 0.026105 -0.034262 0.086750 -vn -2.271545 2.830307 1.665478 -v 0.025949 -0.033762 0.086250 -vn 2.227279 1.264153 3.529320 -v 0.027355 -0.034262 0.086750 -vn 2.271544 2.830310 1.665476 -v 0.027511 -0.033762 0.086250 -vn 3.070403 2.839377 0.467526 -v 0.027620 -0.033762 0.085900 -vn 3.141593 -0.000000 3.141593 -v 0.027620 -0.033762 0.084750 -vn 1.570796 -1.570796 1.570796 -v 0.027620 -0.033762 0.084650 -vn -1.570796 -1.570797 1.570796 -v 0.028340 -0.033762 0.084650 -vn -3.141593 -0.000000 3.141593 -v 0.028340 -0.033762 0.084750 -vn -3.070403 2.839377 0.467526 -v 0.028340 -0.033762 0.085900 -vn -2.227276 1.264155 3.529329 -v 0.028605 -0.034262 0.086750 -vn -2.271545 2.830307 1.665478 -v 0.028449 -0.033762 0.086250 -vn 2.227279 1.264153 3.529320 -v 0.029855 -0.034262 0.086750 -vn 2.271542 2.830316 1.665483 -v 0.030011 -0.033762 0.086250 -vn 3.070401 2.839372 0.467533 -v 0.030120 -0.033762 0.085900 -vn 3.141593 -0.000000 3.141593 -v 0.030120 -0.033762 0.084750 -vn 1.570796 -1.570796 1.570796 -v 0.030120 -0.033762 0.084650 -vn -1.570796 -1.570797 1.570796 -v 0.030840 -0.033762 0.084650 -vn -3.141593 -0.000000 3.141595 -v 0.030840 -0.033762 0.084750 -vn -3.070403 2.839377 0.467526 -v 0.030840 -0.033762 0.085900 -vn -2.227278 1.264154 3.529322 -v 0.031105 -0.034262 0.086750 -vn -2.271545 2.830310 1.665476 -v 0.030949 -0.033762 0.086250 -vn 2.227273 1.264156 3.529338 -v 0.032355 -0.034262 0.086750 -vn 2.271545 2.830305 1.665478 -v 0.032511 -0.033762 0.086250 -vn 3.070403 2.839377 0.467526 -v 0.032620 -0.033762 0.085900 -vn 3.141593 0.000000 3.141593 -v 0.032620 -0.033762 0.084750 -vn 1.570796 -1.570796 1.570796 -v 0.032620 -0.033762 0.084650 -vn -1.570796 -1.570796 1.570796 -v 0.033340 -0.033762 0.084650 -vn -3.141593 0.000000 3.141593 -v 0.033340 -0.033762 0.084750 -vn -3.070403 2.839377 0.467526 -v 0.033340 -0.033762 0.085900 -vn -2.227274 1.264155 3.529335 -v 0.033605 -0.034262 0.086750 -vn -2.271544 2.830305 1.665478 -v 0.033449 -0.033762 0.086250 -vn 2.356191 1.110725 2.681513 -v 0.035430 -0.034262 0.086750 -vn 4.712389 1.570796 1.570796 -v 0.035430 -0.033762 0.084750 -vn 2.356198 2.681521 1.110717 -v 0.035430 -0.033762 0.086250 -vn 2.268926 2.580482 -1.203302 -v 0.035430 -0.031752 0.079250 -vn 1.570796 1.570796 1.570796 -v 0.035430 -0.031752 0.079750 -vn 2.443464 1.009685 -2.774099 -v 0.035430 -0.032229 0.078850 -vn 4.712389 1.570796 1.570796 -v 0.035430 -0.032152 0.079750 -vn 1.570796 1.570796 1.570797 -v 0.035430 -0.032152 0.084750 -vn -2.443463 1.009685 -2.774098 -v 0.034730 -0.032229 0.078850 -vn -2.681507 1.110731 -3.927001 -v 0.034730 -0.032972 0.078850 -vn -2.443464 1.009686 -2.774099 -v 0.023030 -0.032229 0.078850 -vn 2.443464 1.009686 -2.774098 -v 0.023730 -0.032229 0.078850 -vn -2.681518 -1.110721 -2.356194 -v 0.023030 -0.033262 0.078850 -vn 2.681510 1.110729 -3.926997 -v 0.023730 -0.032972 0.078850 -vn 2.681558 1.110613 -2.356180 -v 0.024820 -0.034062 0.078850 -vn 0.785391 1.110747 -5.823101 -v 0.024820 -0.034312 0.078850 -vn -0.785386 1.110728 -5.823112 -v 0.033640 -0.034312 0.078850 -vn -2.681562 1.110631 -2.356224 -v 0.033640 -0.034062 0.078850 -vn -5.823110 -1.110721 -0.785398 -v 0.023030 -0.033262 0.083650 -vn -2.268926 2.580482 -1.203302 -v 0.023030 -0.031752 0.079250 -vn -1.570796 1.570796 1.570796 -v 0.023030 -0.031752 0.079750 -vn -4.712389 1.570796 1.570796 -v 0.023030 -0.032152 0.079750 -vn -1.570796 1.570796 1.570796 -v 0.023030 -0.032152 0.084750 -vn -4.712389 1.570796 1.570796 -v 0.023030 -0.033762 0.084750 -vn -2.356191 1.110725 2.681513 -v 0.023030 -0.034262 0.086750 -vn -2.356199 2.681521 1.110717 -v 0.023030 -0.033762 0.086250 -vn 2.227276 1.264155 3.529329 -v 0.024855 -0.034262 0.086750 -vn 2.271545 2.830307 1.665477 -v 0.025011 -0.033762 0.086250 -vn -4.712389 1.570796 1.570796 -v 0.034730 -0.032152 0.079750 -vn 0.000000 3.141593 -3.141592 -v 0.034730 -0.032152 0.082850 -vn 1.570796 1.570796 4.712401 -v 0.034730 -0.032152 0.084750 -vn -1.570796 1.570796 1.570796 -v 0.034730 -0.031752 0.079750 -vn -2.268926 2.580482 -1.203302 -v 0.034730 -0.031752 0.079250 -vn -3.006779 4.903020 -1.110784 -v 0.033640 -0.034062 0.079100 -vn 1.278229 4.705229 -3.171991 -v 0.032230 -0.034062 0.079100 -vn 1.278209 4.705229 -3.172004 -v 0.027230 -0.034062 0.079100 -vn -1.278227 4.705222 -3.172004 -v 0.026230 -0.034062 0.079100 -vn 3.006771 4.903039 -1.110736 -v 0.024820 -0.034062 0.079100 -vn -1.278212 4.705224 -3.172008 -v 0.028730 -0.034062 0.079100 -vn 1.278209 4.705229 -3.172005 -v 0.029730 -0.034062 0.079100 -vn -1.278211 4.705226 -3.172006 -v 0.031230 -0.034062 0.079100 -vn 2.268926 2.580482 -1.203302 -v 0.023730 -0.031752 0.079250 -vn 4.712389 1.570796 1.570796 -v 0.023730 -0.032152 0.079750 -vn 0.000000 3.141593 -3.141593 -v 0.023730 -0.032152 0.082850 -vn -1.570795 1.570796 4.712387 -v 0.023730 -0.032152 0.084750 -vn 1.570796 1.570796 1.570796 -v 0.023730 -0.031752 0.079750 -vn -2.681514 1.110724 -2.356191 -v 0.034730 -0.032972 0.082850 -vn 1.570796 1.570796 4.712389 -v 0.034730 -0.030862 0.083750 -vn 1.570796 1.570796 1.570782 -v 0.034730 -0.030862 0.084750 -vn 4.712389 -1.570796 1.570796 -v 0.034730 -0.031052 0.083750 -vn 0.000000 -3.141593 -3.141592 -v 0.034730 -0.031052 0.082850 -vn -0.000003 1.826010 -1.240497 -v 0.029230 -0.033362 0.079100 -vn -0.000001 1.826013 -1.240498 -v 0.031730 -0.033362 0.079100 -vn -0.000005 1.826008 -1.240495 -v 0.026730 -0.033362 0.079100 -vn -0.000000 -3.141593 -3.141592 -v 0.023730 -0.031052 0.082850 -vn -4.712389 -1.570796 1.570796 -v 0.023730 -0.031052 0.083750 -vn -1.570796 1.570796 4.712388 -v 0.023730 -0.030862 0.083750 -vn -1.570796 1.570796 1.570786 -v 0.023730 -0.030862 0.084750 -vn 2.681516 1.110722 -2.356194 -v 0.023730 -0.032972 0.082850 -vn 0.000000 0.000000 3.635275 -v 0.030140 -0.032856 0.084750 -vn 0.000000 0.000000 3.635275 -v 0.030140 -0.033027 0.084750 -vn 0.000000 0.000000 3.556756 -v 0.027864 -0.033272 0.084750 -vn 0.000000 0.000000 3.635259 -v 0.025221 -0.033178 0.084750 -vn 0.000000 0.000000 3.635275 -v 0.025140 -0.033027 0.084750 -vn 0.000000 0.000000 3.635275 -v 0.025140 -0.032856 0.084750 -vn 0.000000 0.000000 3.556765 -v 0.032864 -0.033272 0.084750 -vn 0.000000 0.000000 3.635237 -v 0.032721 -0.033178 0.084750 -vn 0.000000 0.000000 3.635285 -v 0.032640 -0.033027 0.084750 -vn 0.000000 0.000000 3.635253 -v 0.030221 -0.032706 0.084750 -vn 0.000000 0.000000 3.556756 -v 0.030364 -0.032611 0.084750 -vn 0.000000 0.000000 3.635283 -v 0.027640 -0.032856 0.084750 -vn 0.000000 0.000000 3.635282 -v 0.027640 -0.033027 0.084750 -vn 0.000000 0.000000 3.635243 -v 0.027721 -0.033178 0.084750 -vn 0.000000 0.000000 3.635259 -v 0.025221 -0.032706 0.084750 -vn 0.000000 0.000000 3.556750 -v 0.025364 -0.032611 0.084750 -vn 0.000000 0.000000 3.556756 -v 0.030364 -0.033272 0.084750 -vn 0.000000 0.000000 3.635253 -v 0.030221 -0.033178 0.084750 -vn 0.000000 0.000000 3.556756 -v 0.027864 -0.032611 0.084750 -vn 0.000000 0.000000 3.556750 -v 0.025364 -0.033272 0.084750 -vn 0.000000 0.000000 3.635243 -v 0.027721 -0.032706 0.084750 -vn 0.000000 0.000000 3.635285 -v 0.032640 -0.032856 0.084750 -vn 0.000000 0.000000 3.635237 -v 0.032721 -0.032706 0.084750 -vn 0.000000 0.000000 3.556764 -v 0.032864 -0.032611 0.084750 -vn -1.110729 2.681514 -2.356194 -v 0.033640 -0.034062 0.082850 -vn 1.110720 2.681518 -2.356195 -v 0.024820 -0.034062 0.082850 -vn 1.278214 2.483804 -2.191052 -v 0.032230 -0.034062 0.082850 -vn -1.278210 2.483802 -2.191046 -v 0.026230 -0.034062 0.082850 -vn 1.570796 -1.570796 1.570796 -v 0.035430 -0.031052 0.083750 -vn 1.570797 1.570796 1.570796 -v 0.035430 -0.029862 0.083750 -vn -1.570796 1.570796 1.570796 -v 0.023030 -0.029862 0.083750 -vn -1.570796 -1.570796 1.570796 -v 0.023030 -0.031052 0.083750 -vn -0.000001 1.826013 -5.042687 -v 0.031730 -0.033362 0.082850 -vn -0.000002 1.826012 -5.042688 -v 0.026730 -0.033362 0.082850 -vn -5.979849 -0.883617 1.092988 -v 0.032638 -0.038062 0.085528 -vn -2.860452 0.004422 1.127789 -v 0.032649 -0.033292 0.085566 -vn 2.860461 0.004421 1.127740 -v 0.033310 -0.033292 0.085566 -vn -5.600060 -0.851410 2.327974 -v 0.032649 -0.038062 0.085566 -vn -4.909104 -0.790123 3.569812 -v 0.032706 -0.038062 0.085668 -vn -2.056122 0.006340 2.249162 -v 0.032744 -0.033292 0.085708 -vn -3.930469 -0.867756 4.611486 -v 0.032744 -0.038062 0.085708 -vn -2.754342 -0.790683 5.408677 -v 0.032828 -0.038062 0.085765 -vn -0.744673 0.006800 2.955053 -v 0.032894 -0.033292 0.085789 -vn -1.411450 -0.876436 5.889594 -v 0.032894 -0.038062 0.085789 -vn 0.744659 0.006800 2.955061 -v 0.033065 -0.033292 0.085789 -vn 2.056108 0.006339 2.249169 -v 0.033216 -0.033292 0.085708 -vn -5.995529 -0.798909 1.193684 -v 0.025138 -0.038062 0.085528 -vn -2.860457 0.004421 1.127754 -v 0.025149 -0.033292 0.085566 -vn 2.860457 0.004421 1.127754 -v 0.025810 -0.033292 0.085566 -vn -5.600043 -0.851467 2.327864 -v 0.025149 -0.038062 0.085566 -vn -4.909079 -0.790165 3.569842 -v 0.025206 -0.038062 0.085668 -vn -2.056107 0.006339 2.249178 -v 0.025244 -0.033292 0.085708 -vn -3.930451 -0.867768 4.611487 -v 0.025244 -0.038062 0.085708 -vn -2.754318 -0.790661 5.408704 -v 0.025328 -0.038062 0.085765 -vn -0.744666 0.006800 2.955057 -v 0.025394 -0.033292 0.085789 -vn -1.411455 -0.876426 5.889598 -v 0.025394 -0.038062 0.085789 -vn 0.744666 0.006800 2.955057 -v 0.025565 -0.033292 0.085789 -vn 2.056107 0.006339 2.249178 -v 0.025716 -0.033292 0.085708 -vn -5.995479 -0.798905 1.193816 -v 0.027638 -0.038062 0.085528 -vn -2.860456 0.004422 1.127764 -v 0.027649 -0.033292 0.085566 -vn 2.860457 0.004421 1.127764 -v 0.028310 -0.033292 0.085566 -vn -5.600045 -0.851455 2.327967 -v 0.027649 -0.038062 0.085566 -vn -4.909094 -0.790163 3.569802 -v 0.027706 -0.038062 0.085668 -vn -2.056115 0.006340 2.249166 -v 0.027744 -0.033292 0.085708 -vn -3.930442 -0.867779 4.611489 -v 0.027744 -0.038062 0.085708 -vn -2.754317 -0.790684 5.408696 -v 0.027828 -0.038062 0.085765 -vn -0.744666 0.006800 2.955057 -v 0.027894 -0.033292 0.085789 -vn -1.411459 -0.876433 5.889594 -v 0.027894 -0.038062 0.085789 -vn 0.744666 0.006800 2.955057 -v 0.028065 -0.033292 0.085789 -vn 2.056115 0.006340 2.249166 -v 0.028216 -0.033292 0.085708 -vn -5.979836 -0.883646 1.092934 -v 0.030138 -0.038062 0.085528 -vn -2.860456 0.004422 1.127764 -v 0.030149 -0.033292 0.085566 -vn 2.860456 0.004422 1.127764 -v 0.030810 -0.033292 0.085566 -vn -5.600045 -0.851455 2.327967 -v 0.030149 -0.038062 0.085566 -vn -4.909094 -0.790163 3.569802 -v 0.030206 -0.038062 0.085668 -vn -2.056115 0.006340 2.249166 -v 0.030244 -0.033292 0.085708 -vn -3.930442 -0.867779 4.611489 -v 0.030244 -0.038062 0.085708 -vn -2.754317 -0.790684 5.408696 -v 0.030328 -0.038062 0.085765 -vn -0.744666 0.006800 2.955057 -v 0.030394 -0.033292 0.085789 -vn -1.411459 -0.876433 5.889594 -v 0.030394 -0.038062 0.085789 -vn 0.744666 0.006800 2.955057 -v 0.030565 -0.033292 0.085789 -vn 2.056115 0.006340 2.249166 -v 0.030716 -0.033292 0.085708 -vn 1.570796 1.570796 -1.570796 -v 0.035430 -0.029862 0.078850 -vn -1.570796 1.570796 -1.570797 -v 0.023030 -0.029862 0.078850 -vn -1.278211 2.483802 -2.191045 -v 0.031230 -0.034062 0.082850 -vn 1.278209 2.483804 -2.191046 -v 0.027230 -0.034062 0.082850 -vn -2.195170 -2.939841 4.528677 -v 0.032839 -0.038162 0.085741 -vn -3.035370 -5.025120 -0.692834 -v 0.032736 -0.038235 0.085394 -vn -0.900492 -6.139819 -0.205529 -v 0.032833 -0.038262 0.085417 -vn -0.900501 -6.139813 0.205554 -v 0.032833 -0.038262 0.085483 -vn -2.434176 -5.025165 -1.941214 -v 0.032784 -0.038235 0.085294 -vn -0.722171 -6.139808 -0.575896 -v 0.032862 -0.038262 0.085356 -vn -1.350918 -5.025071 -2.805131 -v 0.032871 -0.038235 0.085225 -vn -0.400743 -6.139824 -0.832169 -v 0.032915 -0.038262 0.085315 -vn -3.035369 -5.025135 0.692821 -v 0.032736 -0.038235 0.085506 -vn -4.923468 -2.872567 1.059748 -v 0.032665 -0.038162 0.085522 -vn -4.906819 -2.930242 -1.092395 -v 0.032665 -0.038162 0.085378 -vn -0.722158 -6.139817 0.575879 -v 0.032862 -0.038262 0.085544 -vn -2.434172 -5.025251 1.941127 -v 0.032784 -0.038235 0.085606 -vn -3.950072 -2.926232 3.119551 -v 0.032727 -0.038162 0.085652 -vn -2.195349 -2.939847 -4.528694 -v 0.032839 -0.038162 0.085159 -vn -3.950088 -2.926253 -3.119615 -v 0.032727 -0.038162 0.085248 -vn -1.350869 -5.025205 2.805061 -v 0.032871 -0.038235 0.085675 -vn -0.400763 -6.139791 0.832261 -v 0.032915 -0.038262 0.085585 -vn -2.195179 -2.939835 4.528659 -v 0.025339 -0.038162 0.085741 -vn -3.950074 -2.926276 3.119567 -v 0.025227 -0.038162 0.085652 -vn -4.900118 -2.951501 1.130971 -v 0.025165 -0.038162 0.085522 -vn -4.900150 -2.951523 -1.130927 -v 0.025165 -0.038162 0.085378 -vn -3.950100 -2.926295 -3.119621 -v 0.025227 -0.038162 0.085248 -vn -2.195352 -2.939837 -4.528684 -v 0.025339 -0.038162 0.085159 -vn -1.350894 -5.025092 -2.805131 -v 0.025371 -0.038235 0.085225 -vn -0.400735 -6.139827 -0.832167 -v 0.025415 -0.038262 0.085315 -vn -2.434207 -5.025133 -1.941205 -v 0.025284 -0.038235 0.085294 -vn -0.722169 -6.139807 -0.575903 -v 0.025362 -0.038262 0.085356 -vn -3.035388 -5.025118 -0.692827 -v 0.025236 -0.038235 0.085394 -vn -0.900505 -6.139816 -0.205527 -v 0.025333 -0.038262 0.085417 -vn -3.035382 -5.025141 0.692800 -v 0.025236 -0.038235 0.085506 -vn -0.900516 -6.139809 0.205557 -v 0.025333 -0.038262 0.085483 -vn -2.434185 -5.025218 1.941138 -v 0.025284 -0.038235 0.085606 -vn -0.722161 -6.139814 0.575887 -v 0.025362 -0.038262 0.085544 -vn -1.350866 -5.025218 2.805056 -v 0.025371 -0.038235 0.085675 -vn -0.400758 -6.139793 0.832259 -v 0.025415 -0.038262 0.085585 -vn -2.195168 -2.939849 4.528681 -v 0.027839 -0.038162 0.085741 -vn -3.950073 -2.926261 3.119567 -v 0.027727 -0.038162 0.085652 -vn -4.900117 -2.951481 1.130987 -v 0.027665 -0.038162 0.085522 -vn -4.900150 -2.951503 -1.130943 -v 0.027665 -0.038162 0.085378 -vn -3.950094 -2.926283 -3.119620 -v 0.027727 -0.038162 0.085248 -vn -2.195344 -2.939852 -4.528702 -v 0.027839 -0.038162 0.085159 -vn -1.350907 -5.025079 -2.805137 -v 0.027871 -0.038235 0.085225 -vn -0.400735 -6.139826 -0.832167 -v 0.027915 -0.038262 0.085315 -vn -2.434205 -5.025128 -1.941213 -v 0.027784 -0.038235 0.085294 -vn -0.722169 -6.139807 -0.575903 -v 0.027862 -0.038262 0.085356 -vn -3.035388 -5.025118 -0.692827 -v 0.027736 -0.038235 0.085394 -vn -0.900505 -6.139815 -0.205527 -v 0.027833 -0.038262 0.085417 -vn -3.035382 -5.025141 0.692800 -v 0.027736 -0.038235 0.085506 -vn -0.900516 -6.139809 0.205557 -v 0.027833 -0.038262 0.085483 -vn -2.434185 -5.025218 1.941138 -v 0.027784 -0.038235 0.085606 -vn -0.722161 -6.139814 0.575887 -v 0.027862 -0.038262 0.085544 -vn -1.350869 -5.025208 2.805064 -v 0.027871 -0.038235 0.085675 -vn -0.400758 -6.139793 0.832259 -v 0.027915 -0.038262 0.085585 -vn -2.195168 -2.939849 4.528681 -v 0.030339 -0.038162 0.085741 -vn -3.035388 -5.025118 -0.692827 -v 0.030236 -0.038235 0.085394 -vn -0.900504 -6.139815 -0.205532 -v 0.030333 -0.038262 0.085417 -vn -0.900519 -6.139807 0.205572 -v 0.030333 -0.038262 0.085483 -vn -2.434199 -5.025130 -1.941210 -v 0.030284 -0.038235 0.085294 -vn -0.722147 -6.139814 -0.575900 -v 0.030362 -0.038262 0.085356 -vn -1.350907 -5.025079 -2.805134 -v 0.030371 -0.038235 0.085225 -vn -0.400745 -6.139825 -0.832167 -v 0.030415 -0.038262 0.085315 -vn -3.035378 -5.025142 0.692802 -v 0.030236 -0.038235 0.085506 -vn -4.923468 -2.872616 1.059743 -v 0.030165 -0.038162 0.085522 -vn -4.906814 -2.930283 -1.092388 -v 0.030165 -0.038162 0.085378 -vn -0.722148 -6.139820 0.575876 -v 0.030362 -0.038262 0.085544 -vn -2.434181 -5.025219 1.941132 -v 0.030284 -0.038235 0.085606 -vn -3.950073 -2.926261 3.119567 -v 0.030227 -0.038162 0.085652 -vn -2.195344 -2.939852 -4.528702 -v 0.030339 -0.038162 0.085159 -vn -3.950094 -2.926283 -3.119620 -v 0.030227 -0.038162 0.085248 -vn -1.350869 -5.025208 2.805064 -v 0.030371 -0.038235 0.085675 -vn -0.400762 -6.139793 0.832258 -v 0.030415 -0.038262 0.085585 -vn -2.267532 -2.578804 -1.204708 -v 0.023030 -0.031052 0.079260 -vn -2.444857 -1.008008 -2.775505 -v 0.023030 -0.030562 0.078850 -vn 2.444857 -1.008008 -2.775505 -v 0.023730 -0.030562 0.078850 -vn 0.785391 -1.110712 -5.823118 -v 0.023730 -0.030312 0.078850 -vn -0.785391 -1.110713 -5.823119 -v 0.034730 -0.030312 0.078850 -vn -2.444854 -1.008009 -2.775503 -v 0.034730 -0.030562 0.078850 -vn 2.444860 -1.008005 -2.775506 -v 0.035430 -0.030562 0.078850 -vn 2.267530 -2.578802 -1.204710 -v 0.035430 -0.031052 0.079260 -vn 1.278209 2.483804 -2.191047 -v 0.029730 -0.034062 0.082850 -vn -1.278210 2.483802 -2.191045 -v 0.028730 -0.034062 0.082850 -vn 2.267532 -2.578804 -1.204708 -v 0.023730 -0.031052 0.079260 -vn -3.926998 -2.681509 -1.110729 -v 0.034730 -0.030562 0.079100 -vn 3.926998 -2.681509 -1.110729 -v 0.023730 -0.030562 0.079100 -vn -2.267531 -2.578803 -1.204709 -v 0.034730 -0.031052 0.079260 -vn -0.000002 1.826012 -5.042688 -v 0.029230 -0.033362 0.082850 -vn 1.570796 -1.570796 -1.570799 -v 0.023730 -0.030562 0.082850 -vn -1.570797 -1.570796 -1.570797 -v 0.034730 -0.030562 0.082850 -vn -2.629151 1.518596 -3.655163 -v 0.025177 -0.032767 0.082850 -vn -3.036365 0.000008 -3.654225 -v 0.025130 -0.032942 0.082850 -vn -2.629154 -1.518588 -3.655169 -v 0.025177 -0.033117 0.082850 -vn -1.516881 -2.629617 -3.657927 -v 0.025305 -0.033245 0.082850 -vn -1.516881 -2.629617 -3.657927 -v 0.027805 -0.033245 0.082850 -vn -1.516886 -2.629618 -3.657923 -v 0.030305 -0.033245 0.082850 -vn -2.629154 -1.518588 -3.655169 -v 0.027677 -0.033117 0.082850 -vn -3.036365 0.000008 -3.654216 -v 0.027630 -0.032942 0.082850 -vn -1.516882 2.629617 -3.657927 -v 0.025305 -0.032639 0.082850 -vn -1.516878 -2.629618 -3.657929 -v 0.032805 -0.033245 0.082850 -vn -2.629153 -1.518588 -3.655170 -v 0.032677 -0.033117 0.082850 -vn -3.036365 0.000008 -3.654218 -v 0.032630 -0.032942 0.082850 -vn -2.629151 1.518596 -3.655164 -v 0.027677 -0.032767 0.082850 -vn -1.516882 2.629617 -3.657926 -v 0.027805 -0.032639 0.082850 -vn -2.629151 1.518596 -3.655160 -v 0.032677 -0.032767 0.082850 -vn -1.516878 2.629618 -3.657930 -v 0.032805 -0.032639 0.082850 -vn -2.629150 -1.518603 -3.655158 -v 0.030177 -0.033117 0.082850 -vn -3.036357 0.000008 -3.654235 -v 0.030130 -0.032942 0.082850 -vn -2.629148 1.518611 -3.655152 -v 0.030177 -0.032767 0.082850 -vn -1.516886 2.629618 -3.657923 -v 0.030305 -0.032639 0.082850 -vn -2.113868 -5.680771 -0.786185 -v 0.032828 -0.033257 0.079550 -vn -3.424670 -5.012282 -0.833158 -v 0.032805 -0.033245 0.079550 -vn -4.521336 -4.036041 -0.787995 -v 0.032706 -0.033160 0.079550 -vn -5.360749 -2.825792 -0.865558 -v 0.032677 -0.033117 0.079550 -vn -5.866791 -1.356773 -0.873660 -v 0.032638 -0.033020 0.079550 -vn -5.969029 -0.117118 -1.077845 -v 0.032630 -0.032942 0.079550 -vn -5.882432 1.457683 -0.788911 -v 0.032638 -0.032864 0.079550 -vn -5.360749 2.825792 -0.865558 -v 0.032677 -0.032767 0.079550 -vn -4.521335 4.036041 -0.787995 -v 0.032706 -0.032724 0.079550 -vn -3.424670 5.012282 -0.833158 -v 0.032805 -0.032639 0.079550 -vn -2.113860 5.680771 -0.786191 -v 0.032828 -0.032626 0.079550 -vn -2.113872 -5.680777 -0.786170 -v 0.025328 -0.033257 0.079550 -vn -3.424663 -5.012299 -0.833146 -v 0.025305 -0.033245 0.079550 -vn -4.521348 -4.035968 -0.788029 -v 0.025206 -0.033160 0.079550 -vn -5.360783 -2.825766 -0.865588 -v 0.025177 -0.033117 0.079550 -vn -5.866756 -1.356764 -0.873685 -v 0.025138 -0.033020 0.079550 -vn -5.969067 -0.117095 -1.077838 -v 0.025130 -0.032942 0.079550 -vn -5.882396 1.457652 -0.788955 -v 0.025138 -0.032864 0.079550 -vn -5.360783 2.825766 -0.865588 -v 0.025177 -0.032767 0.079550 -vn -4.521348 4.035967 -0.788029 -v 0.025206 -0.032724 0.079550 -vn -3.424663 5.012299 -0.833146 -v 0.025305 -0.032639 0.079550 -vn -2.113867 5.680777 -0.786174 -v 0.025328 -0.032626 0.079550 -vn -2.113876 -5.680770 -0.786185 -v 0.027828 -0.033257 0.079550 -vn -3.424655 -5.012296 -0.833166 -v 0.027805 -0.033245 0.079550 -vn -4.521348 -4.035968 -0.788029 -v 0.027706 -0.033160 0.079550 -vn -5.360783 -2.825766 -0.865588 -v 0.027677 -0.033117 0.079550 -vn -5.866756 -1.356764 -0.873685 -v 0.027638 -0.033020 0.079550 -vn -5.969067 -0.117095 -1.077838 -v 0.027630 -0.032942 0.079550 -vn -5.882396 1.457652 -0.788955 -v 0.027638 -0.032864 0.079550 -vn -5.360783 2.825766 -0.865588 -v 0.027677 -0.032767 0.079550 -vn -4.521348 4.035967 -0.788029 -v 0.027706 -0.032724 0.079550 -vn -3.424655 5.012296 -0.833166 -v 0.027805 -0.032639 0.079550 -vn -2.113868 5.680770 -0.786192 -v 0.027828 -0.032626 0.079550 -vn -2.113963 -5.680715 -0.786183 -v 0.030328 -0.033257 0.079550 -vn -3.424730 -5.012280 -0.833158 -v 0.030305 -0.033245 0.079550 -vn -4.521372 -4.035907 -0.788025 -v 0.030206 -0.033160 0.079550 -vn -5.360830 -2.825749 -0.865574 -v 0.030177 -0.033117 0.079550 -vn -5.882374 -1.457681 -0.788952 -v 0.030138 -0.033020 0.079550 -vn -6.055999 0.000016 -0.877480 -v 0.030130 -0.032942 0.079550 -vn -5.882373 1.457697 -0.788953 -v 0.030138 -0.032864 0.079550 -vn -5.360830 2.825749 -0.865574 -v 0.030177 -0.032767 0.079550 -vn -4.521372 4.035907 -0.788025 -v 0.030206 -0.032724 0.079550 -vn -3.424729 5.012280 -0.833158 -v 0.030305 -0.032639 0.079550 -vn -2.113955 5.680715 -0.786189 -v 0.030328 -0.032626 0.079550 -vn -1.350892 -2.805147 -5.025193 -v 0.032871 -0.033167 0.079377 -vn -2.142823 -4.558886 -2.858110 -v 0.032839 -0.033233 0.079450 -vn -3.912980 -3.167798 -2.911346 -v 0.032727 -0.033143 0.079450 -vn -4.927833 -1.062360 -2.855323 -v 0.032665 -0.033014 0.079450 -vn -4.911158 1.095047 -2.912975 -v 0.032665 -0.032870 0.079450 -vn -3.912979 3.167813 -2.911340 -v 0.032727 -0.032740 0.079450 -vn -2.142847 4.558915 -2.858070 -v 0.032839 -0.032651 0.079450 -vn -2.434204 -1.941245 -5.025198 -v 0.032784 -0.033098 0.079377 -vn -3.035418 -0.692862 -5.025152 -v 0.032736 -0.032997 0.079377 -vn -3.035406 0.692843 -5.025167 -v 0.032736 -0.032886 0.079377 -vn -2.434205 1.941237 -5.025212 -v 0.032784 -0.032786 0.079377 -vn -1.350907 2.805168 -5.025117 -v 0.032871 -0.032717 0.079377 -vn -0.400818 -0.832298 -6.139777 -v 0.032915 -0.033077 0.079350 -vn -0.722245 -0.575994 -6.139771 -v 0.032862 -0.033035 0.079350 -vn -0.900600 -0.205538 -6.139785 -v 0.032833 -0.032975 0.079350 -vn -0.900607 0.205555 -6.139781 -v 0.032833 -0.032908 0.079350 -vn -0.722264 0.575969 -6.139771 -v 0.032862 -0.032848 0.079350 -vn -0.400788 0.832287 -6.139784 -v 0.032915 -0.032807 0.079350 -vn -1.350888 -2.805142 -5.025206 -v 0.025371 -0.033167 0.079377 -vn -2.142846 -4.558861 -2.858094 -v 0.025339 -0.033233 0.079450 -vn -3.912994 -3.167804 -2.911349 -v 0.025227 -0.033143 0.079450 -vn -4.927831 -1.062368 -2.855359 -v 0.025165 -0.033014 0.079450 -vn -4.911151 1.095052 -2.913003 -v 0.025165 -0.032870 0.079450 -vn -3.913004 3.167809 -2.911341 -v 0.025227 -0.032740 0.079450 -vn -2.142865 4.558899 -2.858052 -v 0.025339 -0.032651 0.079450 -vn -2.434217 -1.941256 -5.025165 -v 0.025284 -0.033098 0.079377 -vn -3.035431 -0.692841 -5.025159 -v 0.025236 -0.032997 0.079377 -vn -3.035424 0.692835 -5.025165 -v 0.025236 -0.032886 0.079377 -vn -2.434236 1.941229 -5.025180 -v 0.025284 -0.032786 0.079377 -vn -1.350883 2.805167 -5.025138 -v 0.025371 -0.032717 0.079377 -vn -0.400812 -0.832296 -6.139779 -v 0.025415 -0.033077 0.079350 -vn -0.722248 -0.576003 -6.139768 -v 0.025362 -0.033035 0.079350 -vn -0.900615 -0.205541 -6.139780 -v 0.025333 -0.032975 0.079350 -vn -0.900620 0.205553 -6.139778 -v 0.025333 -0.032908 0.079350 -vn -0.722261 0.575977 -6.139770 -v 0.025362 -0.032848 0.079350 -vn -0.400780 0.832285 -6.139787 -v 0.025415 -0.032807 0.079350 -vn -1.350892 -2.805150 -5.025195 -v 0.027871 -0.033167 0.079377 -vn -2.142831 -4.558885 -2.858111 -v 0.027839 -0.033233 0.079450 -vn -3.912987 -3.167810 -2.911349 -v 0.027727 -0.033143 0.079450 -vn -4.927831 -1.062368 -2.855359 -v 0.027665 -0.033014 0.079450 -vn -4.911151 1.095052 -2.913003 -v 0.027665 -0.032870 0.079450 -vn -3.912992 3.167815 -2.911343 -v 0.027727 -0.032740 0.079450 -vn -2.142852 4.558920 -2.858068 -v 0.027839 -0.032651 0.079450 -vn -2.434217 -1.941256 -5.025165 -v 0.027784 -0.033098 0.079377 -vn -3.035431 -0.692841 -5.025159 -v 0.027736 -0.032997 0.079377 -vn -3.035424 0.692835 -5.025165 -v 0.027736 -0.032886 0.079377 -vn -2.434234 1.941236 -5.025175 -v 0.027784 -0.032786 0.079377 -vn -1.350895 2.805173 -5.025125 -v 0.027871 -0.032717 0.079377 -vn -0.400812 -0.832296 -6.139779 -v 0.027915 -0.033077 0.079350 -vn -0.722248 -0.576003 -6.139768 -v 0.027862 -0.033035 0.079350 -vn -0.900615 -0.205541 -6.139780 -v 0.027833 -0.032975 0.079350 -vn -0.900620 0.205553 -6.139778 -v 0.027833 -0.032908 0.079350 -vn -0.722261 0.575977 -6.139770 -v 0.027862 -0.032848 0.079350 -vn -0.400780 0.832285 -6.139786 -v 0.027915 -0.032807 0.079350 -vn -1.350892 -2.805150 -5.025195 -v 0.030371 -0.033167 0.079377 -vn -2.142842 -4.558881 -2.858097 -v 0.030339 -0.033233 0.079450 -vn -3.912993 -3.167806 -2.911324 -v 0.030227 -0.033143 0.079450 -vn -4.904480 -1.133624 -2.934213 -v 0.030165 -0.033014 0.079450 -vn -4.904484 1.133621 -2.934212 -v 0.030165 -0.032870 0.079450 -vn -3.912998 3.167811 -2.911318 -v 0.030227 -0.032740 0.079450 -vn -2.142863 4.558917 -2.858054 -v 0.030339 -0.032651 0.079450 -vn -2.434213 -1.941250 -5.025167 -v 0.030284 -0.033098 0.079377 -vn -3.035427 -0.692843 -5.025159 -v 0.030236 -0.032997 0.079377 -vn -3.035424 0.692835 -5.025165 -v 0.030236 -0.032886 0.079377 -vn -2.434228 1.941233 -5.025177 -v 0.030284 -0.032786 0.079377 -vn -1.350896 2.805170 -5.025125 -v 0.030371 -0.032717 0.079377 -vn -0.400816 -0.832294 -6.139778 -v 0.030415 -0.033077 0.079350 -vn -0.722236 -0.575991 -6.139773 -v 0.030362 -0.033035 0.079350 -vn -0.900618 -0.205556 -6.139777 -v 0.030333 -0.032975 0.079350 -vn -0.900619 0.205559 -6.139777 -v 0.030333 -0.032908 0.079350 -vn -0.722239 0.575974 -6.139776 -v 0.030362 -0.032848 0.079350 -vn -0.400790 0.832285 -6.139785 -v 0.030415 -0.032807 0.079350 -vn 0.000000 2.984516 -3.131909 -v 0.036250 -0.000890 0.079300 -vn -0.000000 -2.984516 -3.131909 -v 0.036250 -0.003390 0.079300 -vn -0.489937 -2.984511 -3.093349 -v 0.034334 -0.003390 0.079451 -vn -0.489937 2.984510 -3.093349 -v 0.034334 -0.000890 0.079451 -vn -0.967813 -2.984514 -2.978622 -v 0.032465 -0.003390 0.079900 -vn -0.967813 2.984514 -2.978622 -v 0.032465 -0.000890 0.079900 -vn -1.421858 -2.984511 -2.790550 -v 0.030689 -0.003390 0.080635 -vn -1.421858 2.984511 -2.790550 -v 0.030689 -0.000890 0.080635 -vn -1.840890 -2.984516 -2.533767 -v 0.029050 -0.003390 0.081640 -vn -1.840890 2.984516 -2.533767 -v 0.029050 -0.000890 0.081640 -vn -2.214593 -2.984511 -2.214593 -v 0.027588 -0.003390 0.082888 -vn -2.214593 2.984511 -2.214594 -v 0.027588 -0.000890 0.082888 -vn -2.533766 -2.984513 -1.840891 -v 0.026340 -0.003390 0.084350 -vn -2.533766 2.984514 -1.840891 -v 0.026340 -0.000890 0.084350 -vn -2.790549 -2.984510 -1.421859 -v 0.025335 -0.003390 0.085989 -vn -2.790549 2.984511 -1.421859 -v 0.025335 -0.000890 0.085989 -vn -2.978622 -2.984512 -0.967812 -v 0.024600 -0.003390 0.087765 -vn -2.978622 2.984513 -0.967812 -v 0.024600 -0.000890 0.087765 -vn -3.093349 -2.984515 -0.489938 -v 0.024151 -0.003390 0.089634 -vn -3.093349 2.984514 -0.489938 -v 0.024151 -0.000890 0.089634 -vn -3.131908 -2.984513 0.000000 -v 0.024000 -0.003390 0.091550 -vn -3.131908 2.984513 0.000000 -v 0.024000 -0.000890 0.091550 -vn -3.093349 -2.984513 0.489939 -v 0.024151 -0.003390 0.093466 -vn -3.093349 2.984513 0.489939 -v 0.024151 -0.000890 0.093466 -vn -2.978622 -2.984514 0.967812 -v 0.024600 -0.003390 0.095335 -vn -2.978622 2.984513 0.967812 -v 0.024600 -0.000890 0.095335 -vn -2.790551 -2.984513 1.421856 -v 0.025335 -0.003390 0.097111 -vn -2.790551 2.984512 1.421856 -v 0.025335 -0.000890 0.097111 -vn -2.533768 -2.984512 1.840888 -v 0.026340 -0.003390 0.098750 -vn -2.533768 2.984512 1.840888 -v 0.026340 -0.000890 0.098750 -vn -2.214593 -2.984511 2.214593 -v 0.027588 -0.003390 0.100212 -vn -2.214593 2.984511 2.214593 -v 0.027588 -0.000890 0.100212 -vn -1.840890 -2.984516 2.533767 -v 0.029050 -0.003390 0.101460 -vn -1.840890 2.984516 2.533767 -v 0.029050 -0.000890 0.101460 -vn -1.421858 -2.984511 2.790550 -v 0.030689 -0.003390 0.102465 -vn -1.421858 2.984511 2.790550 -v 0.030689 -0.000890 0.102465 -vn -0.967813 -2.984517 2.978621 -v 0.032465 -0.003390 0.103200 -vn -0.967813 2.984515 2.978622 -v 0.032465 -0.000890 0.103200 -vn -0.489937 -2.984511 3.093349 -v 0.034334 -0.003390 0.103649 -vn -0.489937 2.984511 3.093349 -v 0.034334 -0.000890 0.103649 -vn 0.000000 -2.984516 3.131909 -v 0.036250 -0.003390 0.103800 -vn -0.000000 2.984517 3.131909 -v 0.036250 -0.000890 0.103800 -vn 0.000003 3.665199 3.034542 -v 0.036250 -0.000890 0.082550 -vn 0.000003 -3.665199 3.034542 -v 0.036250 -0.003390 0.082550 -vn -1.517277 3.665189 2.627992 -v 0.036750 -0.000890 0.082684 -vn -1.517277 -3.665189 2.627992 -v 0.036750 -0.003390 0.082684 -vn -2.627993 3.665189 1.517277 -v 0.037116 -0.000890 0.083050 -vn -2.627992 -3.665189 1.517277 -v 0.037116 -0.003390 0.083050 -vn -3.034543 3.665197 -0.000000 -v 0.037250 -0.000890 0.083550 -vn -3.034543 -3.665197 0.000000 -v 0.037250 -0.003390 0.083550 -vn -2.627992 3.665189 -1.517277 -v 0.037116 -0.000890 0.084050 -vn -2.627992 -3.665189 -1.517277 -v 0.037116 -0.003390 0.084050 -vn -1.517277 3.665189 -2.627993 -v 0.036750 -0.000890 0.084416 -vn -1.517277 -3.665189 -2.627992 -v 0.036750 -0.003390 0.084416 -vn 0.000003 3.665199 -3.034542 -v 0.036250 -0.000890 0.084550 -vn 0.000003 -3.665199 -3.034542 -v 0.036250 -0.003390 0.084550 -vn -0.000000 3.665199 3.034542 -v 0.029322 -0.000890 0.086550 -vn 0.000000 -3.665199 3.034542 -v 0.029322 -0.003390 0.086550 -vn -1.517275 3.665185 2.627995 -v 0.029822 -0.000890 0.086684 -vn -1.517275 -3.665185 2.627995 -v 0.029822 -0.003390 0.086684 -vn -2.627991 3.665195 1.517274 -v 0.030188 -0.000890 0.087050 -vn -2.627991 -3.665195 1.517275 -v 0.030188 -0.003390 0.087050 -vn -3.034546 3.665190 0.000000 -v 0.030322 -0.000890 0.087550 -vn -3.034546 -3.665190 0.000000 -v 0.030322 -0.003390 0.087550 -vn -2.627991 3.665195 -1.517275 -v 0.030188 -0.000890 0.088050 -vn -2.627991 -3.665195 -1.517274 -v 0.030188 -0.003390 0.088050 -vn -1.517275 3.665185 -2.627995 -v 0.029822 -0.000890 0.088416 -vn -1.517275 -3.665185 -2.627995 -v 0.029822 -0.003390 0.088416 -vn 0.000000 3.665198 -3.034542 -v 0.029322 -0.000890 0.088550 -vn -0.000000 -3.665198 -3.034542 -v 0.029322 -0.003390 0.088550 -vn -0.000000 3.665199 3.034542 -v 0.029322 -0.000890 0.094550 -vn 0.000000 -3.665199 3.034542 -v 0.029322 -0.003390 0.094550 -vn -1.517275 3.665185 2.627995 -v 0.029822 -0.000890 0.094684 -vn -1.517275 -3.665185 2.627995 -v 0.029822 -0.003390 0.094684 -vn -2.627991 3.665195 1.517274 -v 0.030188 -0.000890 0.095050 -vn -2.627991 -3.665195 1.517275 -v 0.030188 -0.003390 0.095050 -vn -3.034546 3.665190 0.000000 -v 0.030322 -0.000890 0.095550 -vn -3.034546 -3.665190 0.000000 -v 0.030322 -0.003390 0.095550 -vn -2.627991 3.665195 -1.517275 -v 0.030188 -0.000890 0.096050 -vn -2.627991 -3.665195 -1.517274 -v 0.030188 -0.003390 0.096050 -vn -1.517254 3.665199 -2.628000 -v 0.029822 -0.000890 0.096416 -vn -1.517254 -3.665199 -2.628000 -v 0.029822 -0.003390 0.096416 -vn 0.000000 3.665171 -3.034554 -v 0.029322 -0.000890 0.096550 -vn -0.000000 -3.665171 -3.034554 -v 0.029322 -0.003390 0.096550 -vn 0.000003 3.665199 3.034542 -v 0.036250 -0.000890 0.098550 -vn 0.000003 -3.665199 3.034542 -v 0.036250 -0.003390 0.098550 -vn -1.517277 3.665189 2.627992 -v 0.036750 -0.000890 0.098684 -vn -1.517277 -3.665189 2.627992 -v 0.036750 -0.003390 0.098684 -vn -2.627993 3.665189 1.517277 -v 0.037116 -0.000890 0.099050 -vn -2.627992 -3.665189 1.517277 -v 0.037116 -0.003390 0.099050 -vn -3.034542 3.665201 -0.000006 -v 0.037250 -0.000890 0.099550 -vn -3.034542 -3.665201 -0.000006 -v 0.037250 -0.003390 0.099550 -vn -2.628002 3.665175 -1.517271 -v 0.037116 -0.000890 0.100050 -vn -2.628002 -3.665175 -1.517271 -v 0.037116 -0.003390 0.100050 -vn -1.517267 3.665213 -2.627987 -v 0.036750 -0.000890 0.100416 -vn -1.517267 -3.665213 -2.627987 -v 0.036750 -0.003390 0.100416 -vn 0.000003 3.665171 -3.034554 -v 0.036250 -0.000890 0.100550 -vn 0.000003 -3.665171 -3.034554 -v 0.036250 -0.003390 0.100550 -vn -0.000003 3.665198 3.034542 -v 0.043178 -0.000890 0.094550 -vn -0.000003 -3.665198 3.034542 -v 0.043178 -0.003390 0.094550 -vn -1.517274 3.665182 2.627997 -v 0.043678 -0.000890 0.094684 -vn -1.517274 -3.665182 2.627997 -v 0.043678 -0.003390 0.094684 -vn -2.627989 3.665201 1.517272 -v 0.044044 -0.000890 0.095050 -vn -2.627990 -3.665201 1.517272 -v 0.044044 -0.003390 0.095050 -vn -3.034549 3.665183 0.000000 -v 0.044178 -0.000890 0.095550 -vn -3.034549 -3.665183 -0.000000 -v 0.044178 -0.003390 0.095550 -vn -2.627990 3.665201 -1.517272 -v 0.044044 -0.000890 0.096050 -vn -2.627989 -3.665201 -1.517272 -v 0.044044 -0.003390 0.096050 -vn -1.517253 3.665195 -2.628003 -v 0.043678 -0.000890 0.096416 -vn -1.517253 -3.665195 -2.628003 -v 0.043678 -0.003390 0.096416 -vn -0.000003 3.665171 -3.034554 -v 0.043178 -0.000890 0.096550 -vn -0.000003 -3.665171 -3.034554 -v 0.043178 -0.003390 0.096550 -vn -0.000003 3.665199 3.034542 -v 0.043178 -0.000890 0.086550 -vn -0.000003 -3.665199 3.034542 -v 0.043178 -0.003390 0.086550 -vn -1.517274 3.665182 2.627997 -v 0.043678 -0.000890 0.086684 -vn -1.517274 -3.665182 2.627997 -v 0.043678 -0.003390 0.086684 -vn -2.627989 3.665201 1.517272 -v 0.044044 -0.000890 0.087050 -vn -2.627990 -3.665201 1.517272 -v 0.044044 -0.003390 0.087050 -vn -3.034549 3.665183 0.000000 -v 0.044178 -0.000890 0.087550 -vn -3.034549 -3.665183 -0.000000 -v 0.044178 -0.003390 0.087550 -vn -2.627990 3.665201 -1.517272 -v 0.044044 -0.000890 0.088050 -vn -2.627989 -3.665201 -1.517272 -v 0.044044 -0.003390 0.088050 -vn -1.517274 3.665182 -2.627997 -v 0.043678 -0.000890 0.088416 -vn -1.517274 -3.665182 -2.627997 -v 0.043678 -0.003390 0.088416 -vn -0.000003 3.665198 -3.034542 -v 0.043178 -0.000890 0.088550 -vn -0.000003 -3.665198 -3.034542 -v 0.043178 -0.003390 0.088550 -vn 0.000001 3.455754 3.102914 -v 0.036250 -0.000890 0.088700 -vn 0.000001 -3.455754 3.102914 -v 0.036250 -0.003390 0.088700 -vn -0.958854 3.455751 2.951047 -v 0.037131 -0.000890 0.088839 -vn -0.958855 -3.455751 2.951047 -v 0.037131 -0.003390 0.088839 -vn -1.823851 3.455755 2.510307 -v 0.037925 -0.000890 0.089244 -vn -1.823851 -3.455755 2.510307 -v 0.037925 -0.003390 0.089244 -vn -2.510310 3.455743 1.823852 -v 0.038556 -0.000890 0.089875 -vn -2.510310 -3.455743 1.823852 -v 0.038556 -0.003390 0.089875 -vn -2.951044 3.455762 0.958855 -v 0.038961 -0.000890 0.090669 -vn -2.951044 -3.455762 0.958855 -v 0.038961 -0.003390 0.090669 -vn -3.102916 3.455745 -0.000002 -v 0.039100 -0.000890 0.091550 -vn -3.102916 -3.455745 -0.000002 -v 0.039100 -0.003390 0.091550 -vn -2.951046 3.455757 -0.958852 -v 0.038961 -0.000890 0.092431 -vn -2.951046 -3.455757 -0.958852 -v 0.038961 -0.003390 0.092431 -vn -2.510306 3.455753 -1.823853 -v 0.038556 -0.000890 0.093225 -vn -2.510306 -3.455753 -1.823853 -v 0.038556 -0.003390 0.093225 -vn -1.823844 3.455749 -2.510314 -v 0.037925 -0.000890 0.093856 -vn -1.823844 -3.455749 -2.510314 -v 0.037925 -0.003390 0.093856 -vn -0.958855 3.455751 -2.951047 -v 0.037131 -0.000890 0.094261 -vn -0.958854 -3.455751 -2.951047 -v 0.037131 -0.003390 0.094261 -vn 0.000001 3.455753 -3.102914 -v 0.036250 -0.000890 0.094400 -vn 0.000001 -3.455753 -3.102914 -v 0.036250 -0.003390 0.094400 -vn 0.958853 3.455749 -2.951048 -v 0.035369 -0.000890 0.094261 -vn 0.958853 -3.455749 -2.951048 -v 0.035369 -0.003390 0.094261 -vn 1.823842 3.455751 -2.510315 -v 0.034575 -0.000890 0.093856 -vn 1.823841 -3.455751 -2.510315 -v 0.034575 -0.003390 0.093856 -vn 2.510309 3.455757 -1.823848 -v 0.033944 -0.000890 0.093225 -vn 2.510309 -3.455757 -1.823848 -v 0.033944 -0.003390 0.093225 -vn 2.951048 3.455749 -0.958853 -v 0.033539 -0.000890 0.092431 -vn 2.951048 -3.455749 -0.958853 -v 0.033539 -0.003390 0.092431 -vn 3.102914 3.455753 -0.000002 -v 0.033400 -0.000890 0.091550 -vn 3.102914 -3.455754 -0.000002 -v 0.033400 -0.003390 0.091550 -vn 2.951046 3.455754 0.958856 -v 0.033539 -0.000890 0.090669 -vn 2.951046 -3.455754 0.958856 -v 0.033539 -0.003390 0.090669 -vn 2.510312 3.455747 1.823847 -v 0.033944 -0.000890 0.089875 -vn 2.510313 -3.455747 1.823847 -v 0.033944 -0.003390 0.089875 -vn 1.823848 3.455757 2.510309 -v 0.034575 -0.000890 0.089244 -vn 1.823848 -3.455757 2.510309 -v 0.034575 -0.003390 0.089244 -vn 0.958853 3.455749 2.951048 -v 0.035369 -0.000890 0.088839 -vn 0.958853 -3.455749 2.951048 -v 0.035369 -0.003390 0.088839 -vn 1.517277 3.665189 -2.627992 -v 0.042678 -0.000890 0.088416 -vn 1.517277 -3.665189 -2.627992 -v 0.042678 -0.003390 0.088416 -vn 2.627993 3.665189 -1.517277 -v 0.042312 -0.000890 0.088050 -vn 2.627992 -3.665189 -1.517277 -v 0.042312 -0.003390 0.088050 -vn 3.034543 3.665197 0.000000 -v 0.042178 -0.000890 0.087550 -vn 3.034543 -3.665197 -0.000000 -v 0.042178 -0.003390 0.087550 -vn 2.627992 3.665189 1.517277 -v 0.042312 -0.000890 0.087050 -vn 2.627992 -3.665189 1.517277 -v 0.042312 -0.003390 0.087050 -vn 1.517277 3.665189 2.627993 -v 0.042678 -0.000890 0.086684 -vn 1.517277 -3.665189 2.627992 -v 0.042678 -0.003390 0.086684 -vn 1.517256 3.665203 -2.627998 -v 0.042678 -0.000890 0.096416 -vn 1.517256 -3.665203 -2.627998 -v 0.042678 -0.003390 0.096416 -vn 2.627993 3.665189 -1.517277 -v 0.042312 -0.000890 0.096050 -vn 2.627992 -3.665189 -1.517277 -v 0.042312 -0.003390 0.096050 -vn 3.034543 3.665197 0.000000 -v 0.042178 -0.000890 0.095550 -vn 3.034543 -3.665197 -0.000000 -v 0.042178 -0.003390 0.095550 -vn 2.627992 3.665189 1.517277 -v 0.042312 -0.000890 0.095050 -vn 2.627992 -3.665189 1.517277 -v 0.042312 -0.003390 0.095050 -vn 1.517277 3.665189 2.627993 -v 0.042678 -0.000890 0.094684 -vn 1.517277 -3.665189 2.627992 -v 0.042678 -0.003390 0.094684 -vn 1.517264 3.665206 -2.627991 -v 0.035750 -0.000890 0.100416 -vn 1.517264 -3.665206 -2.627992 -v 0.035750 -0.003390 0.100416 -vn 2.627999 3.665187 -1.517266 -v 0.035384 -0.000890 0.100050 -vn 2.627999 -3.665187 -1.517266 -v 0.035384 -0.003390 0.100050 -vn 3.034547 3.665187 -0.000006 -v 0.035250 -0.000890 0.099550 -vn 3.034548 -3.665186 -0.000006 -v 0.035250 -0.003390 0.099550 -vn 2.627990 3.665201 1.517272 -v 0.035384 -0.000890 0.099050 -vn 2.627989 -3.665201 1.517272 -v 0.035384 -0.003390 0.099050 -vn 1.517274 3.665182 2.627997 -v 0.035750 -0.000890 0.098684 -vn 1.517274 -3.665182 2.627997 -v 0.035750 -0.003390 0.098684 -vn 1.517254 3.665199 -2.628000 -v 0.028822 -0.000890 0.096416 -vn 1.517254 -3.665199 -2.628000 -v 0.028822 -0.003390 0.096416 -vn 2.627991 3.665195 -1.517274 -v 0.028456 -0.000890 0.096050 -vn 2.627991 -3.665195 -1.517275 -v 0.028456 -0.003390 0.096050 -vn 3.034546 3.665190 0.000000 -v 0.028322 -0.000890 0.095550 -vn 3.034546 -3.665190 0.000000 -v 0.028322 -0.003390 0.095550 -vn 2.627991 3.665195 1.517275 -v 0.028456 -0.000890 0.095050 -vn 2.627991 -3.665195 1.517274 -v 0.028456 -0.003390 0.095050 -vn 1.517275 3.665185 2.627995 -v 0.028822 -0.000890 0.094684 -vn 1.517275 -3.665185 2.627995 -v 0.028822 -0.003390 0.094684 -vn 1.517275 3.665185 -2.627995 -v 0.028822 -0.000890 0.088416 -vn 1.517275 -3.665185 -2.627995 -v 0.028822 -0.003390 0.088416 -vn 2.627991 3.665195 -1.517274 -v 0.028456 -0.000890 0.088050 -vn 2.627991 -3.665195 -1.517275 -v 0.028456 -0.003390 0.088050 -vn 3.034546 3.665190 0.000000 -v 0.028322 -0.000890 0.087550 -vn 3.034546 -3.665190 0.000000 -v 0.028322 -0.003390 0.087550 -vn 2.627991 3.665195 1.517275 -v 0.028456 -0.000890 0.087050 -vn 2.627991 -3.665195 1.517274 -v 0.028456 -0.003390 0.087050 -vn 1.517275 3.665185 2.627995 -v 0.028822 -0.000890 0.086684 -vn 1.517275 -3.665185 2.627995 -v 0.028822 -0.003390 0.086684 -vn 1.517274 3.665182 -2.627997 -v 0.035750 -0.000890 0.084416 -vn 1.517274 -3.665182 -2.627997 -v 0.035750 -0.003390 0.084416 -vn 2.627989 3.665201 -1.517272 -v 0.035384 -0.000890 0.084050 -vn 2.627990 -3.665201 -1.517272 -v 0.035384 -0.003390 0.084050 -vn 3.034549 3.665183 -0.000000 -v 0.035250 -0.000890 0.083550 -vn 3.034549 -3.665183 0.000000 -v 0.035250 -0.003390 0.083550 -vn 2.627990 3.665201 1.517272 -v 0.035384 -0.000890 0.083050 -vn 2.627989 -3.665201 1.517272 -v 0.035384 -0.003390 0.083050 -vn 1.517274 3.665182 2.627997 -v 0.035750 -0.000890 0.082684 -vn 1.517274 -3.665182 2.627997 -v 0.035750 -0.003390 0.082684 -vn 0.489937 -2.984511 3.093349 -v 0.038166 -0.003390 0.103649 -vn 0.489937 2.984510 3.093349 -v 0.038166 -0.000890 0.103649 -vn 0.967812 -2.984515 2.978622 -v 0.040035 -0.003390 0.103200 -vn 0.967812 2.984515 2.978622 -v 0.040035 -0.000890 0.103200 -vn 1.421857 -2.984510 2.790550 -v 0.041811 -0.003390 0.102465 -vn 1.421857 2.984510 2.790550 -v 0.041811 -0.000890 0.102465 -vn 1.840890 -2.984516 2.533767 -v 0.043450 -0.003390 0.101460 -vn 1.840890 2.984516 2.533767 -v 0.043450 -0.000890 0.101460 -vn 2.214593 -2.984511 2.214593 -v 0.044912 -0.003390 0.100212 -vn 2.214593 2.984512 2.214594 -v 0.044912 -0.000890 0.100212 -vn 2.533768 -2.984514 1.840888 -v 0.046160 -0.003390 0.098750 -vn 2.533768 2.984514 1.840888 -v 0.046160 -0.000890 0.098750 -vn 2.790551 -2.984512 1.421854 -v 0.047165 -0.003390 0.097111 -vn 2.790551 2.984512 1.421854 -v 0.047165 -0.000890 0.097111 -vn 2.978622 -2.984515 0.967812 -v 0.047900 -0.003390 0.095335 -vn 2.978622 2.984515 0.967812 -v 0.047900 -0.000890 0.095335 -vn 3.093349 -2.984513 0.489940 -v 0.048349 -0.003390 0.093466 -vn 3.093349 2.984513 0.489940 -v 0.048349 -0.000890 0.093466 -vn 3.131908 -2.984512 0.000000 -v 0.048500 -0.003390 0.091550 -vn 3.131908 2.984513 0.000000 -v 0.048500 -0.000890 0.091550 -vn 3.093349 -2.984512 -0.489940 -v 0.048349 -0.003390 0.089634 -vn 3.093349 2.984512 -0.489940 -v 0.048349 -0.000890 0.089634 -vn 2.978622 -2.984515 -0.967812 -v 0.047900 -0.003390 0.087765 -vn 2.978622 2.984515 -0.967812 -v 0.047900 -0.000890 0.087765 -vn 2.790550 -2.984510 -1.421857 -v 0.047165 -0.003390 0.085989 -vn 2.790550 2.984510 -1.421857 -v 0.047165 -0.000890 0.085989 -vn 2.533766 -2.984516 -1.840891 -v 0.046160 -0.003390 0.084350 -vn 2.533766 2.984516 -1.840891 -v 0.046160 -0.000890 0.084350 -vn 2.214593 -2.984511 -2.214593 -v 0.044912 -0.003390 0.082888 -vn 2.214593 2.984511 -2.214593 -v 0.044912 -0.000890 0.082888 -vn 1.840890 -2.984516 -2.533767 -v 0.043450 -0.003390 0.081640 -vn 1.840890 2.984516 -2.533767 -v 0.043450 -0.000890 0.081640 -vn 1.421857 -2.984510 -2.790550 -v 0.041811 -0.003390 0.080635 -vn 1.421857 2.984510 -2.790550 -v 0.041811 -0.000890 0.080635 -vn 0.967812 -2.984515 -2.978622 -v 0.040035 -0.003390 0.079900 -vn 0.967812 2.984515 -2.978622 -v 0.040035 -0.000890 0.079900 -vn 0.489937 -2.984511 -3.093349 -v 0.038166 -0.003390 0.079451 -vn 0.489937 2.984511 -3.093349 -v 0.038166 -0.000890 0.079451 -vn 0.000000 6.283186 0.000000 -v 0.046339 -0.000890 0.085550 -vn 0.000000 6.283186 0.000000 -v 0.034325 -0.000890 0.094475 -vn 0.000000 6.283185 0.000000 -v 0.034325 -0.000890 0.088625 -vn 0.000000 6.283185 0.000000 -v 0.038175 -0.000890 0.088625 -vn 0.000000 6.283186 0.000000 -v 0.031861 -0.000890 0.094475 -vn 0.000000 6.283185 0.000000 -v 0.031861 -0.000890 0.088625 -vn 0.000000 6.283186 0.000000 -v 0.038175 -0.000890 0.094475 -vn 0.000000 6.283187 0.000000 -v 0.040639 -0.000890 0.094475 -vn 0.000000 6.283186 0.000000 -v 0.040639 -0.000890 0.088625 -vn 0.000000 6.283185 0.000000 -v 0.038175 -0.000890 0.097550 -vn 0.000000 6.283185 0.000000 -v 0.034325 -0.000890 0.097550 -vn 0.000000 6.283186 0.000000 -v 0.031861 -0.000890 0.097550 -vn 0.000000 6.283186 0.000000 -v 0.031861 -0.000890 0.085550 -vn 0.000000 6.283185 0.000000 -v 0.031861 -0.000890 0.080925 -vn 0.000000 6.283185 0.000000 -v 0.034325 -0.000890 0.080925 -vn 0.000000 6.283186 0.000000 -v 0.038175 -0.000890 0.080925 -vn 0.000000 6.283185 0.000000 -v 0.040639 -0.000890 0.085550 -vn 0.000000 6.283185 0.000000 -v 0.040639 -0.000890 0.080925 -vn 0.000000 6.283189 0.000000 -v 0.046339 -0.000890 0.088625 -vn 0.000000 6.283189 0.000000 -v 0.046339 -0.000890 0.094475 -vn 0.000000 6.283184 0.000000 -v 0.046339 -0.000890 0.097550 -vn 0.000000 6.283185 0.000000 -v 0.040639 -0.000890 0.097550 -vn 0.000000 6.283185 0.000000 -v 0.034325 -0.000890 0.085550 -vn 0.000000 6.283185 0.000000 -v 0.038175 -0.000890 0.085550 -vn 0.000000 -6.283187 0.000000 -v 0.040639 -0.003390 0.088625 -vn 0.000000 -6.283189 0.000000 -v 0.046339 -0.003390 0.088625 -vn 0.000000 -6.283189 0.000000 -v 0.046339 -0.003390 0.094475 -vn 0.000000 -6.283185 0.000000 -v 0.038175 -0.003390 0.080925 -vn 0.000000 -6.283185 0.000000 -v 0.040639 -0.003390 0.080925 -vn 0.000000 -6.283185 0.000000 -v 0.040639 -0.003390 0.085550 -vn 0.000000 -6.283185 0.000000 -v 0.038175 -0.003390 0.097550 -vn 0.000000 -6.283185 0.000000 -v 0.040639 -0.003390 0.097550 -vn 0.000000 -6.283185 0.000000 -v 0.031861 -0.003390 0.080925 -vn 0.000000 -6.283186 0.000000 -v 0.038175 -0.003390 0.094475 -vn 0.000000 -6.283186 0.000000 -v 0.034325 -0.003390 0.094475 -vn 0.000000 -6.283185 0.000000 -v 0.031861 -0.003390 0.088625 -vn 0.000000 -6.283185 0.000000 -v 0.034325 -0.003390 0.088625 -vn 0.000000 -6.283185 0.000000 -v 0.031861 -0.003390 0.094475 -vn 0.000000 -6.283185 0.000000 -v 0.038175 -0.003390 0.088625 -vn 0.000000 -6.283187 0.000000 -v 0.040639 -0.003390 0.094475 -vn 0.000000 -6.283185 0.000000 -v 0.034325 -0.003390 0.080925 -vn 0.000000 -6.283185 0.000000 -v 0.031861 -0.003390 0.085550 -vn 0.000000 -6.283185 0.000000 -v 0.031861 -0.003390 0.097550 -vn 0.000000 -6.283185 0.000000 -v 0.034325 -0.003390 0.097550 -vn 0.000000 -6.283184 0.000000 -v 0.046339 -0.003390 0.097550 -vn 0.000000 -6.283185 0.000000 -v 0.046339 -0.003390 0.085550 -vn 0.000000 -6.283184 0.000000 -v 0.034325 -0.003390 0.085550 -vn 0.000000 -6.283184 0.000000 -v 0.038175 -0.003390 0.085550 -# 26495 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 131//131 -f 131//131 130//130 132//132 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 141//141 -f 141//141 140//140 142//142 -f 141//141 142//142 143//143 -f 143//143 142//142 144//144 -f 143//143 144//144 145//145 -f 145//145 144//144 146//146 -f 145//145 146//146 147//147 -f 147//147 146//146 148//148 -f 149//149 150//150 151//151 -f 151//151 150//150 152//152 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 158//158 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 185//185 -f 185//185 184//184 186//186 -f 185//185 186//186 187//187 -f 187//187 186//186 188//188 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 197//197 196//196 198//198 -f 197//197 198//198 199//199 -f 199//199 198//198 200//200 -f 199//199 200//200 201//201 -f 201//201 200//200 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 205//205 206//206 207//207 -f 207//207 206//206 208//208 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 213//213 212//212 214//214 -f 213//213 214//214 215//215 -f 215//215 214//214 216//216 -f 215//215 216//216 217//217 -f 217//217 216//216 218//218 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 225//225 224//224 226//226 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 229//229 -f 229//229 228//228 230//230 -f 229//229 230//230 231//231 -f 231//231 230//230 232//232 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 237//237 -f 237//237 236//236 238//238 -f 237//237 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 241//241 -f 241//241 240//240 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 247//247 248//248 249//249 -f 249//249 248//248 250//250 -f 249//249 250//250 251//251 -f 251//251 250//250 252//252 -f 251//251 252//252 253//253 -f 253//253 252//252 254//254 -f 253//253 254//254 255//255 -f 255//255 254//254 256//256 -f 255//255 256//256 257//257 -f 257//257 256//256 258//258 -f 257//257 258//258 259//259 -f 259//259 258//258 260//260 -f 261//261 262//262 263//263 -f 263//263 262//262 264//264 -f 263//263 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 267//267 -f 267//267 266//266 268//268 -f 267//267 268//268 269//269 -f 269//269 268//268 270//270 -f 269//269 270//270 271//271 -f 271//271 270//270 272//272 -f 271//271 272//272 273//273 -f 273//273 272//272 274//274 -f 275//275 276//276 277//277 -f 277//277 276//276 278//278 -f 277//277 278//278 279//279 -f 279//279 278//278 280//280 -f 279//279 280//280 281//281 -f 281//281 280//280 282//282 -f 281//281 282//282 283//283 -f 283//283 282//282 284//284 -f 283//283 284//284 285//285 -f 285//285 284//284 286//286 -f 285//285 286//286 287//287 -f 287//287 286//286 288//288 -f 289//289 290//290 291//291 -f 291//291 290//290 292//292 -f 291//291 292//292 293//293 -f 293//293 292//292 294//294 -f 293//293 294//294 295//295 -f 295//295 294//294 296//296 -f 295//295 296//296 297//297 -f 297//297 296//296 298//298 -f 297//297 298//298 299//299 -f 299//299 298//298 300//300 -f 299//299 300//300 301//301 -f 301//301 300//300 302//302 -f 303//303 304//304 305//305 -f 305//305 304//304 306//306 -f 305//305 306//306 307//307 -f 307//307 306//306 308//308 -f 307//307 308//308 309//309 -f 309//309 308//308 310//310 -f 309//309 310//310 311//311 -f 311//311 310//310 312//312 -f 311//311 312//312 313//313 -f 313//313 312//312 314//314 -f 313//313 314//314 315//315 -f 315//315 314//314 316//316 -f 317//317 318//318 319//319 -f 319//319 318//318 320//320 -f 319//319 320//320 321//321 -f 321//321 320//320 322//322 -f 321//321 322//322 323//323 -f 323//323 322//322 324//324 -f 323//323 324//324 325//325 -f 325//325 324//324 326//326 -f 325//325 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 331//331 332//332 333//333 -f 333//333 332//332 334//334 -f 333//333 334//334 335//335 -f 335//335 334//334 336//336 -f 335//335 336//336 337//337 -f 337//337 336//336 338//338 -f 337//337 338//338 339//339 -f 339//339 338//338 340//340 -f 339//339 340//340 341//341 -f 341//341 340//340 342//342 -f 341//341 342//342 343//343 -f 343//343 342//342 344//344 -f 345//345 346//346 347//347 -f 347//347 346//346 348//348 -f 347//347 348//348 349//349 -f 349//349 348//348 350//350 -f 349//349 350//350 351//351 -f 351//351 350//350 352//352 -f 351//351 352//352 353//353 -f 353//353 352//352 354//354 -f 353//353 354//354 355//355 -f 355//355 354//354 356//356 -f 355//355 356//356 357//357 -f 357//357 356//356 358//358 -f 359//359 360//360 361//361 -f 361//361 360//360 362//362 -f 361//361 362//362 363//363 -f 363//363 362//362 364//364 -f 363//363 364//364 365//365 -f 365//365 364//364 366//366 -f 365//365 366//366 367//367 -f 367//367 366//366 368//368 -f 367//367 368//368 369//369 -f 369//369 368//368 370//370 -f 369//369 370//370 371//371 -f 371//371 370//370 372//372 -f 373//373 374//374 375//375 -f 375//375 374//374 376//376 -f 375//375 376//376 377//377 -f 377//377 376//376 378//378 -f 377//377 378//378 379//379 -f 379//379 378//378 380//380 -f 379//379 380//380 381//381 -f 381//381 380//380 382//382 -f 381//381 382//382 383//383 -f 383//383 382//382 384//384 -f 383//383 384//384 385//385 -f 385//385 384//384 386//386 -f 387//387 388//388 389//389 -f 389//389 388//388 390//390 -f 389//389 390//390 391//391 -f 391//391 390//390 392//392 -f 391//391 392//392 393//393 -f 393//393 392//392 394//394 -f 393//393 394//394 395//395 -f 395//395 394//394 396//396 -f 395//395 396//396 397//397 -f 397//397 396//396 398//398 -f 397//397 398//398 399//399 -f 399//399 398//398 400//400 -f 401//401 402//402 403//403 -f 403//403 402//402 404//404 -f 403//403 404//404 405//405 -f 405//405 404//404 406//406 -f 405//405 406//406 407//407 -f 407//407 406//406 408//408 -f 407//407 408//408 409//409 -f 409//409 408//408 410//410 -f 409//409 410//410 411//411 -f 411//411 410//410 412//412 -f 411//411 412//412 413//413 -f 413//413 412//412 414//414 -f 415//415 416//416 417//417 -f 417//417 416//416 418//418 -f 417//417 418//418 419//419 -f 419//419 418//418 420//420 -f 419//419 420//420 421//421 -f 421//421 420//420 422//422 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 423//423 424//424 425//425 -f 425//425 424//424 426//426 -f 425//425 426//426 427//427 -f 427//427 426//426 428//428 -f 427//427 428//428 429//429 -f 429//429 428//428 430//430 -f 431//431 432//432 433//433 -f 433//433 432//432 434//434 -f 433//433 434//434 435//435 -f 435//435 434//434 436//436 -f 435//435 436//436 437//437 -f 437//437 436//436 438//438 -f 437//437 438//438 439//439 -f 439//439 438//438 440//440 -f 439//439 440//440 441//441 -f 441//441 440//440 442//442 -f 441//441 442//442 443//443 -f 443//443 442//442 444//444 -f 445//445 446//446 447//447 -f 447//447 446//446 448//448 -f 447//447 448//448 449//449 -f 449//449 448//448 450//450 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 453//453 454//454 455//455 -f 455//455 454//454 456//456 -f 455//455 456//456 457//457 -f 457//457 456//456 458//458 -f 459//459 460//460 461//461 -f 461//461 460//460 462//462 -f 461//461 462//462 463//463 -f 463//463 462//462 464//464 -f 463//463 464//464 465//465 -f 465//465 464//464 466//466 -f 465//465 466//466 467//467 -f 467//467 466//466 468//468 -f 467//467 468//468 469//469 -f 469//469 468//468 470//470 -f 469//469 470//470 471//471 -f 471//471 470//470 472//472 -f 473//473 474//474 475//475 -f 475//475 474//474 476//476 -f 475//475 476//476 477//477 -f 477//477 476//476 478//478 -f 477//477 478//478 479//479 -f 479//479 478//478 480//480 -f 479//479 480//480 481//481 -f 481//481 480//480 482//482 -f 481//481 482//482 483//483 -f 483//483 482//482 484//484 -f 483//483 484//484 485//485 -f 485//485 484//484 486//486 -f 487//487 488//488 489//489 -f 489//489 488//488 490//490 -f 489//489 490//490 491//491 -f 491//491 490//490 492//492 -f 491//491 492//492 493//493 -f 493//493 492//492 494//494 -f 493//493 494//494 495//495 -f 495//495 494//494 496//496 -f 495//495 496//496 497//497 -f 497//497 496//496 498//498 -f 497//497 498//498 499//499 -f 499//499 498//498 500//500 -f 501//501 502//502 503//503 -f 503//503 502//502 504//504 -f 503//503 504//504 505//505 -f 505//505 504//504 506//506 -f 505//505 506//506 507//507 -f 507//507 506//506 508//508 -f 507//507 508//508 509//509 -f 509//509 508//508 510//510 -f 509//509 510//510 511//511 -f 511//511 510//510 512//512 -f 511//511 512//512 513//513 -f 513//513 512//512 514//514 -f 515//515 516//516 517//517 -f 517//517 516//516 518//518 -f 517//517 518//518 519//519 -f 519//519 518//518 520//520 -f 519//519 520//520 521//521 -f 521//521 520//520 522//522 -f 521//521 522//522 523//523 -f 523//523 522//522 524//524 -f 523//523 524//524 525//525 -f 525//525 524//524 526//526 -f 525//525 526//526 527//527 -f 527//527 526//526 528//528 -f 529//529 530//530 531//531 -f 531//531 530//530 532//532 -f 531//531 532//532 533//533 -f 533//533 532//532 534//534 -f 533//533 534//534 535//535 -f 535//535 534//534 536//536 -f 535//535 536//536 537//537 -f 537//537 536//536 538//538 -f 537//537 538//538 539//539 -f 539//539 538//538 540//540 -f 539//539 540//540 541//541 -f 541//541 540//540 542//542 -f 543//543 544//544 545//545 -f 545//545 544//544 546//546 -f 545//545 546//546 547//547 -f 547//547 546//546 548//548 -f 547//547 548//548 549//549 -f 549//549 548//548 550//550 -f 549//549 550//550 551//551 -f 551//551 550//550 552//552 -f 551//551 552//552 553//553 -f 553//553 552//552 554//554 -f 553//553 554//554 555//555 -f 555//555 554//554 556//556 -f 557//557 558//558 559//559 -f 559//559 558//558 560//560 -f 559//559 560//560 561//561 -f 561//561 560//560 562//562 -f 561//561 562//562 563//563 -f 563//563 562//562 564//564 -f 563//563 564//564 565//565 -f 565//565 564//564 566//566 -f 565//565 566//566 567//567 -f 567//567 566//566 568//568 -f 567//567 568//568 569//569 -f 569//569 568//568 570//570 -f 571//571 572//572 573//573 -f 573//573 572//572 574//574 -f 573//573 574//574 575//575 -f 575//575 574//574 576//576 -f 575//575 576//576 577//577 -f 577//577 576//576 578//578 -f 577//577 578//578 579//579 -f 579//579 578//578 580//580 -f 579//579 580//580 581//581 -f 581//581 580//580 582//582 -f 581//581 582//582 583//583 -f 583//583 582//582 584//584 -f 585//585 586//586 587//587 -f 587//587 586//586 588//588 -f 587//587 588//588 589//589 -f 589//589 588//588 590//590 -f 589//589 590//590 591//591 -f 591//591 590//590 592//592 -f 591//591 592//592 593//593 -f 593//593 592//592 594//594 -f 593//593 594//594 595//595 -f 595//595 594//594 596//596 -f 595//595 596//596 597//597 -f 597//597 596//596 598//598 -f 599//599 600//600 601//601 -f 601//601 600//600 602//602 -f 601//601 602//602 603//603 -f 603//603 602//602 604//604 -f 603//603 604//604 605//605 -f 605//605 604//604 606//606 -f 605//605 606//606 607//607 -f 607//607 606//606 608//608 -f 607//607 608//608 609//609 -f 609//609 608//608 610//610 -f 609//609 610//610 611//611 -f 611//611 610//610 612//612 -f 613//613 614//614 615//615 -f 615//615 614//614 616//616 -f 615//615 616//616 617//617 -f 617//617 616//616 618//618 -f 617//617 618//618 619//619 -f 619//619 618//618 620//620 -f 619//619 620//620 621//621 -f 621//621 620//620 622//622 -f 621//621 622//622 623//623 -f 623//623 622//622 624//624 -f 623//623 624//624 625//625 -f 625//625 624//624 626//626 -f 625//625 626//626 627//627 -f 627//627 626//626 628//628 -f 627//627 628//628 629//629 -f 629//629 628//628 630//630 -f 629//629 630//630 631//631 -f 631//631 630//630 632//632 -f 633//633 634//634 635//635 -f 635//635 634//634 636//636 -f 635//635 636//636 637//637 -f 637//637 636//636 638//638 -f 637//637 638//638 639//639 -f 639//639 638//638 640//640 -f 639//639 640//640 641//641 -f 641//641 640//640 642//642 -f 641//641 642//642 643//643 -f 643//643 642//642 644//644 -f 643//643 644//644 645//645 -f 645//645 644//644 646//646 -f 645//645 646//646 647//647 -f 647//647 646//646 648//648 -f 647//647 648//648 649//649 -f 649//649 648//648 650//650 -f 649//649 650//650 651//651 -f 651//651 650//650 652//652 -f 653//653 654//654 655//655 -f 655//655 654//654 656//656 -f 655//655 656//656 657//657 -f 657//657 656//656 658//658 -f 657//657 658//658 659//659 -f 659//659 658//658 660//660 -f 659//659 660//660 661//661 -f 661//661 660//660 662//662 -f 661//661 662//662 663//663 -f 663//663 662//662 664//664 -f 663//663 664//664 665//665 -f 665//665 664//664 666//666 -f 667//667 668//668 669//669 -f 669//669 668//668 670//670 -f 669//669 670//670 671//671 -f 671//671 670//670 672//672 -f 671//671 672//672 673//673 -f 673//673 672//672 674//674 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 677//677 -f 677//677 676//676 678//678 -f 677//677 678//678 679//679 -f 679//679 678//678 680//680 -f 681//681 682//682 683//683 -f 683//683 682//682 684//684 -f 683//683 684//684 685//685 -f 685//685 684//684 686//686 -f 685//685 686//686 687//687 -f 687//687 686//686 688//688 -f 687//687 688//688 689//689 -f 689//689 688//688 690//690 -f 689//689 690//690 691//691 -f 691//691 690//690 692//692 -f 691//691 692//692 693//693 -f 693//693 692//692 694//694 -f 695//695 696//696 697//697 -f 697//697 696//696 698//698 -f 697//697 698//698 699//699 -f 699//699 698//698 700//700 -f 699//699 700//700 701//701 -f 701//701 700//700 702//702 -f 701//701 702//702 703//703 -f 703//703 702//702 704//704 -f 703//703 704//704 705//705 -f 705//705 704//704 706//706 -f 705//705 706//706 707//707 -f 707//707 706//706 708//708 -f 709//709 710//710 711//711 -f 711//711 710//710 712//712 -f 711//711 712//712 713//713 -f 713//713 712//712 714//714 -f 713//713 714//714 715//715 -f 715//715 714//714 716//716 -f 715//715 716//716 717//717 -f 717//717 716//716 718//718 -f 717//717 718//718 719//719 -f 719//719 718//718 720//720 -f 719//719 720//720 721//721 -f 721//721 720//720 722//722 -f 723//723 724//724 725//725 -f 725//725 724//724 726//726 -f 725//725 726//726 727//727 -f 727//727 726//726 728//728 -f 727//727 728//728 729//729 -f 729//729 728//728 730//730 -f 729//729 730//730 731//731 -f 731//731 730//730 732//732 -f 731//731 732//732 733//733 -f 733//733 732//732 734//734 -f 733//733 734//734 735//735 -f 735//735 734//734 736//736 -f 737//737 738//738 739//739 -f 739//739 738//738 740//740 -f 739//739 740//740 741//741 -f 741//741 740//740 742//742 -f 741//741 742//742 743//743 -f 743//743 742//742 744//744 -f 743//743 744//744 745//745 -f 745//745 744//744 746//746 -f 745//745 746//746 747//747 -f 747//747 746//746 748//748 -f 747//747 748//748 749//749 -f 749//749 748//748 750//750 -f 751//751 752//752 753//753 -f 753//753 752//752 754//754 -f 753//753 754//754 755//755 -f 755//755 754//754 756//756 -f 755//755 756//756 757//757 -f 757//757 756//756 758//758 -f 757//757 758//758 759//759 -f 759//759 758//758 760//760 -f 759//759 760//760 761//761 -f 761//761 760//760 762//762 -f 761//761 762//762 763//763 -f 763//763 762//762 764//764 -f 765//765 766//766 767//767 -f 767//767 766//766 768//768 -f 767//767 768//768 769//769 -f 769//769 768//768 770//770 -f 769//769 770//770 771//771 -f 771//771 770//770 772//772 -f 771//771 772//772 773//773 -f 773//773 772//772 774//774 -f 773//773 774//774 775//775 -f 775//775 774//774 776//776 -f 775//775 776//776 777//777 -f 777//777 776//776 778//778 -f 779//779 780//780 781//781 -f 781//781 780//780 782//782 -f 781//781 782//782 783//783 -f 783//783 782//782 784//784 -f 783//783 784//784 785//785 -f 785//785 784//784 786//786 -f 785//785 786//786 787//787 -f 787//787 786//786 788//788 -f 787//787 788//788 789//789 -f 789//789 788//788 790//790 -f 789//789 790//790 791//791 -f 791//791 790//790 792//792 -f 793//793 794//794 795//795 -f 795//795 794//794 796//796 -f 795//795 796//796 797//797 -f 797//797 796//796 798//798 -f 797//797 798//798 799//799 -f 799//799 798//798 800//800 -f 799//799 800//800 801//801 -f 801//801 800//800 802//802 -f 801//801 802//802 803//803 -f 803//803 802//802 804//804 -f 803//803 804//804 805//805 -f 805//805 804//804 806//806 -f 807//807 808//808 809//809 -f 809//809 808//808 810//810 -f 809//809 810//810 811//811 -f 811//811 810//810 812//812 -f 811//811 812//812 813//813 -f 813//813 812//812 814//814 -f 813//813 814//814 815//815 -f 815//815 814//814 816//816 -f 815//815 816//816 817//817 -f 817//817 816//816 818//818 -f 817//817 818//818 819//819 -f 819//819 818//818 820//820 -f 821//821 822//822 823//823 -f 823//823 822//822 824//824 -f 823//823 824//824 825//825 -f 825//825 824//824 826//826 -f 825//825 826//826 827//827 -f 827//827 826//826 828//828 -f 827//827 828//828 829//829 -f 829//829 828//828 830//830 -f 829//829 830//830 831//831 -f 831//831 830//830 832//832 -f 831//831 832//832 833//833 -f 833//833 832//832 834//834 -f 835//835 836//836 837//837 -f 837//837 836//836 838//838 -f 837//837 838//838 839//839 -f 839//839 838//838 840//840 -f 839//839 840//840 841//841 -f 841//841 840//840 842//842 -f 841//841 842//842 843//843 -f 843//843 842//842 844//844 -f 843//843 844//844 845//845 -f 845//845 844//844 846//846 -f 845//845 846//846 847//847 -f 847//847 846//846 848//848 -f 849//849 850//850 851//851 -f 851//851 850//850 852//852 -f 851//851 852//852 853//853 -f 853//853 852//852 854//854 -f 853//853 854//854 855//855 -f 855//855 854//854 856//856 -f 855//855 856//856 857//857 -f 857//857 856//856 858//858 -f 857//857 858//858 859//859 -f 859//859 858//858 860//860 -f 859//859 860//860 861//861 -f 861//861 860//860 862//862 -f 863//863 864//864 865//865 -f 865//865 864//864 866//866 -f 865//865 866//866 867//867 -f 867//867 866//866 868//868 -f 867//867 868//868 869//869 -f 869//869 868//868 870//870 -f 869//869 870//870 871//871 -f 871//871 870//870 872//872 -f 871//871 872//872 873//873 -f 873//873 872//872 874//874 -f 873//873 874//874 875//875 -f 875//875 874//874 876//876 -f 877//877 878//878 879//879 -f 879//879 878//878 880//880 -f 879//879 880//880 881//881 -f 881//881 880//880 882//882 -f 881//881 882//882 883//883 -f 883//883 882//882 884//884 -f 883//883 884//884 885//885 -f 885//885 884//884 886//886 -f 885//885 886//886 887//887 -f 887//887 886//886 888//888 -f 887//887 888//888 889//889 -f 889//889 888//888 890//890 -f 891//891 892//892 893//893 -f 893//893 892//892 894//894 -f 893//893 894//894 895//895 -f 895//895 894//894 896//896 -f 895//895 896//896 897//897 -f 897//897 896//896 898//898 -f 897//897 898//898 899//899 -f 899//899 898//898 900//900 -f 899//899 900//900 901//901 -f 901//901 900//900 902//902 -f 901//901 902//902 903//903 -f 903//903 902//902 904//904 -f 905//905 906//906 907//907 -f 907//907 906//906 908//908 -f 907//907 908//908 909//909 -f 909//909 908//908 910//910 -f 909//909 910//910 911//911 -f 911//911 910//910 912//912 -f 911//911 912//912 913//913 -f 913//913 912//912 914//914 -f 913//913 914//914 915//915 -f 915//915 914//914 916//916 -f 915//915 916//916 917//917 -f 917//917 916//916 918//918 -f 919//919 920//920 921//921 -f 921//921 920//920 922//922 -f 921//921 922//922 923//923 -f 923//923 922//922 924//924 -f 923//923 924//924 925//925 -f 925//925 924//924 926//926 -f 925//925 926//926 927//927 -f 927//927 926//926 928//928 -f 927//927 928//928 929//929 -f 929//929 928//928 930//930 -f 929//929 930//930 931//931 -f 931//931 930//930 932//932 -f 933//933 934//934 935//935 -f 935//935 934//934 936//936 -f 935//935 936//936 937//937 -f 937//937 936//936 938//938 -f 937//937 938//938 939//939 -f 939//939 938//938 940//940 -f 939//939 940//940 941//941 -f 941//941 940//940 942//942 -f 941//941 942//942 943//943 -f 943//943 942//942 944//944 -f 943//943 944//944 945//945 -f 945//945 944//944 946//946 -f 947//947 948//948 949//949 -f 949//949 948//948 950//950 -f 949//949 950//950 951//951 -f 951//951 950//950 952//952 -f 951//951 952//952 953//953 -f 953//953 952//952 954//954 -f 953//953 954//954 955//955 -f 955//955 954//954 956//956 -f 955//955 956//956 957//957 -f 957//957 956//956 958//958 -f 957//957 958//958 959//959 -f 959//959 958//958 960//960 -f 961//961 962//962 963//963 -f 963//963 962//962 964//964 -f 963//963 964//964 965//965 -f 965//965 964//964 966//966 -f 965//965 966//966 967//967 -f 967//967 966//966 968//968 -f 967//967 968//968 969//969 -f 969//969 968//968 970//970 -f 969//969 970//970 971//971 -f 971//971 970//970 972//972 -f 971//971 972//972 973//973 -f 973//973 972//972 974//974 -f 975//975 976//976 977//977 -f 977//977 976//976 978//978 -f 977//977 978//978 979//979 -f 979//979 978//978 980//980 -f 979//979 980//980 981//981 -f 981//981 980//980 982//982 -f 981//981 982//982 983//983 -f 983//983 982//982 984//984 -f 983//983 984//984 985//985 -f 985//985 984//984 986//986 -f 985//985 986//986 987//987 -f 987//987 986//986 988//988 -f 989//989 990//990 991//991 -f 991//991 990//990 992//992 -f 991//991 992//992 993//993 -f 993//993 992//992 994//994 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 997//997 996//996 998//998 -f 997//997 998//998 999//999 -f 999//999 998//998 1000//1000 -f 999//999 1000//1000 1001//1001 -f 1001//1001 1000//1000 1002//1002 -f 1003//1003 1004//1004 1005//1005 -f 1005//1005 1004//1004 1006//1006 -f 1005//1005 1006//1006 1007//1007 -f 1007//1007 1006//1006 1008//1008 -f 1007//1007 1008//1008 1009//1009 -f 1009//1009 1008//1008 1010//1010 -f 1009//1009 1010//1010 1011//1011 -f 1011//1011 1010//1010 1012//1012 -f 1011//1011 1012//1012 1013//1013 -f 1013//1013 1012//1012 1014//1014 -f 1013//1013 1014//1014 1015//1015 -f 1015//1015 1014//1014 1016//1016 -f 1017//1017 1018//1018 1019//1019 -f 1019//1019 1018//1018 1020//1020 -f 1019//1019 1020//1020 1021//1021 -f 1021//1021 1020//1020 1022//1022 -f 1021//1021 1022//1022 1023//1023 -f 1023//1023 1022//1022 1024//1024 -f 1023//1023 1024//1024 1025//1025 -f 1025//1025 1024//1024 1026//1026 -f 1025//1025 1026//1026 1027//1027 -f 1027//1027 1026//1026 1028//1028 -f 1027//1027 1028//1028 1029//1029 -f 1029//1029 1028//1028 1030//1030 -f 1031//1031 1032//1032 1033//1033 -f 1033//1033 1032//1032 1034//1034 -f 1033//1033 1034//1034 1035//1035 -f 1035//1035 1034//1034 1036//1036 -f 1035//1035 1036//1036 1037//1037 -f 1037//1037 1036//1036 1038//1038 -f 1037//1037 1038//1038 1039//1039 -f 1039//1039 1038//1038 1040//1040 -f 1039//1039 1040//1040 1041//1041 -f 1041//1041 1040//1040 1042//1042 -f 1041//1041 1042//1042 1043//1043 -f 1043//1043 1042//1042 1044//1044 -f 1045//1045 1046//1046 1047//1047 -f 1047//1047 1046//1046 1048//1048 -f 1047//1047 1048//1048 1049//1049 -f 1049//1049 1048//1048 1050//1050 -f 1049//1049 1050//1050 1051//1051 -f 1051//1051 1050//1050 1052//1052 -f 1051//1051 1052//1052 1053//1053 -f 1053//1053 1052//1052 1054//1054 -f 1053//1053 1054//1054 1055//1055 -f 1055//1055 1054//1054 1056//1056 -f 1055//1055 1056//1056 1057//1057 -f 1057//1057 1056//1056 1058//1058 -f 1059//1059 1060//1060 1061//1061 -f 1061//1061 1060//1060 1062//1062 -f 1061//1061 1062//1062 1063//1063 -f 1063//1063 1062//1062 1064//1064 -f 1063//1063 1064//1064 1065//1065 -f 1065//1065 1064//1064 1066//1066 -f 1065//1065 1066//1066 1067//1067 -f 1067//1067 1066//1066 1068//1068 -f 1067//1067 1068//1068 1069//1069 -f 1069//1069 1068//1068 1070//1070 -f 1069//1069 1070//1070 1071//1071 -f 1071//1071 1070//1070 1072//1072 -f 1073//1073 1074//1074 1075//1075 -f 1075//1075 1074//1074 1076//1076 -f 1075//1075 1076//1076 1077//1077 -f 1077//1077 1076//1076 1078//1078 -f 1077//1077 1078//1078 1079//1079 -f 1079//1079 1078//1078 1080//1080 -f 1079//1079 1080//1080 1081//1081 -f 1081//1081 1080//1080 1082//1082 -f 1081//1081 1082//1082 1083//1083 -f 1083//1083 1082//1082 1084//1084 -f 1083//1083 1084//1084 1085//1085 -f 1085//1085 1084//1084 1086//1086 -f 1087//1087 1088//1088 1089//1089 -f 1089//1089 1088//1088 1090//1090 -f 1089//1089 1090//1090 1091//1091 -f 1091//1091 1090//1090 1092//1092 -f 1091//1091 1092//1092 1093//1093 -f 1093//1093 1092//1092 1094//1094 -f 1093//1093 1094//1094 1095//1095 -f 1095//1095 1094//1094 1096//1096 -f 1095//1095 1096//1096 1097//1097 -f 1097//1097 1096//1096 1098//1098 -f 1097//1097 1098//1098 1099//1099 -f 1099//1099 1098//1098 1100//1100 -f 1101//1101 1102//1102 1103//1103 -f 1103//1103 1102//1102 1104//1104 -f 1103//1103 1104//1104 1105//1105 -f 1105//1105 1104//1104 1106//1106 -f 1105//1105 1106//1106 1107//1107 -f 1107//1107 1106//1106 1108//1108 -f 1107//1107 1108//1108 1109//1109 -f 1109//1109 1108//1108 1110//1110 -f 1109//1109 1110//1110 1111//1111 -f 1111//1111 1110//1110 1112//1112 -f 1111//1111 1112//1112 1113//1113 -f 1113//1113 1112//1112 1114//1114 -f 1115//1115 1116//1116 1117//1117 -f 1117//1117 1116//1116 1118//1118 -f 1117//1117 1118//1118 1119//1119 -f 1119//1119 1118//1118 1120//1120 -f 1119//1119 1120//1120 1121//1121 -f 1121//1121 1120//1120 1122//1122 -f 1121//1121 1122//1122 1123//1123 -f 1123//1123 1122//1122 1124//1124 -f 1123//1123 1124//1124 1125//1125 -f 1125//1125 1124//1124 1126//1126 -f 1125//1125 1126//1126 1127//1127 -f 1127//1127 1126//1126 1128//1128 -f 1129//1129 1130//1130 1131//1131 -f 1131//1131 1130//1130 1132//1132 -f 1131//1131 1132//1132 1133//1133 -f 1133//1133 1132//1132 1134//1134 -f 1133//1133 1134//1134 1135//1135 -f 1135//1135 1134//1134 1136//1136 -f 1135//1135 1136//1136 1137//1137 -f 1137//1137 1136//1136 1138//1138 -f 1137//1137 1138//1138 1139//1139 -f 1139//1139 1138//1138 1140//1140 -f 1139//1139 1140//1140 1141//1141 -f 1141//1141 1140//1140 1142//1142 -f 1143//1143 1144//1144 1145//1145 -f 1145//1145 1144//1144 1146//1146 -f 1145//1145 1146//1146 1147//1147 -f 1147//1147 1146//1146 1148//1148 -f 1147//1147 1148//1148 1149//1149 -f 1149//1149 1148//1148 1150//1150 -f 1149//1149 1150//1150 1151//1151 -f 1151//1151 1150//1150 1152//1152 -f 1151//1151 1152//1152 1153//1153 -f 1153//1153 1152//1152 1154//1154 -f 1153//1153 1154//1154 1155//1155 -f 1155//1155 1154//1154 1156//1156 -f 1157//1157 1158//1158 1159//1159 -f 1159//1159 1158//1158 1160//1160 -f 1159//1159 1160//1160 1161//1161 -f 1161//1161 1160//1160 1162//1162 -f 1161//1161 1162//1162 1163//1163 -f 1163//1163 1162//1162 1164//1164 -f 1163//1163 1164//1164 1165//1165 -f 1165//1165 1164//1164 1166//1166 -f 1165//1165 1166//1166 1167//1167 -f 1167//1167 1166//1166 1168//1168 -f 1167//1167 1168//1168 1169//1169 -f 1169//1169 1168//1168 1170//1170 -f 1171//1171 1172//1172 1173//1173 -f 1173//1173 1172//1172 1174//1174 -f 1173//1173 1174//1174 1175//1175 -f 1175//1175 1174//1174 1176//1176 -f 1175//1175 1176//1176 1177//1177 -f 1177//1177 1176//1176 1178//1178 -f 1177//1177 1178//1178 1179//1179 -f 1179//1179 1178//1178 1180//1180 -f 1179//1179 1180//1180 1181//1181 -f 1181//1181 1180//1180 1182//1182 -f 1181//1181 1182//1182 1183//1183 -f 1183//1183 1182//1182 1184//1184 -f 1183//1183 1184//1184 1185//1185 -f 1185//1185 1184//1184 1186//1186 -f 1187//1187 1188//1188 1189//1189 -f 1189//1189 1188//1188 1190//1190 -f 1189//1189 1190//1190 1191//1191 -f 1191//1191 1190//1190 1192//1192 -f 1191//1191 1192//1192 1193//1193 -f 1193//1193 1192//1192 1194//1194 -f 1193//1193 1194//1194 1195//1195 -f 1195//1195 1194//1194 1196//1196 -f 1195//1195 1196//1196 1197//1197 -f 1197//1197 1196//1196 1198//1198 -f 1197//1197 1198//1198 1199//1199 -f 1199//1199 1198//1198 1200//1200 -f 1199//1199 1200//1200 1201//1201 -f 1201//1201 1200//1200 1202//1202 -f 1203//1203 1204//1204 1205//1205 -f 1205//1205 1204//1204 1206//1206 -f 1205//1205 1206//1206 1207//1207 -f 1207//1207 1206//1206 1208//1208 -f 1207//1207 1208//1208 1209//1209 -f 1209//1209 1208//1208 1210//1210 -f 1209//1209 1210//1210 1211//1211 -f 1211//1211 1210//1210 1212//1212 -f 1211//1211 1212//1212 1213//1213 -f 1213//1213 1212//1212 1214//1214 -f 1213//1213 1214//1214 1215//1215 -f 1215//1215 1214//1214 1216//1216 -f 1217//1217 1218//1218 1219//1219 -f 1219//1219 1218//1218 1220//1220 -f 1219//1219 1220//1220 1221//1221 -f 1221//1221 1220//1220 1222//1222 -f 1221//1221 1222//1222 1223//1223 -f 1223//1223 1222//1222 1224//1224 -f 1223//1223 1224//1224 1225//1225 -f 1225//1225 1224//1224 1226//1226 -f 1225//1225 1226//1226 1227//1227 -f 1227//1227 1226//1226 1228//1228 -f 1227//1227 1228//1228 1229//1229 -f 1229//1229 1228//1228 1230//1230 -f 1231//1231 1232//1232 1233//1233 -f 1233//1233 1232//1232 1234//1234 -f 1233//1233 1234//1234 1235//1235 -f 1235//1235 1234//1234 1236//1236 -f 1235//1235 1236//1236 1237//1237 -f 1237//1237 1236//1236 1238//1238 -f 1237//1237 1238//1238 1239//1239 -f 1239//1239 1238//1238 1240//1240 -f 1239//1239 1240//1240 1241//1241 -f 1241//1241 1240//1240 1242//1242 -f 1241//1241 1242//1242 1243//1243 -f 1243//1243 1242//1242 1244//1244 -f 1245//1245 1246//1246 1247//1247 -f 1247//1247 1246//1246 1248//1248 -f 1247//1247 1248//1248 1249//1249 -f 1249//1249 1248//1248 1250//1250 -f 1249//1249 1250//1250 1251//1251 -f 1251//1251 1250//1250 1252//1252 -f 1251//1251 1252//1252 1253//1253 -f 1253//1253 1252//1252 1254//1254 -f 1253//1253 1254//1254 1255//1255 -f 1255//1255 1254//1254 1256//1256 -f 1255//1255 1256//1256 1257//1257 -f 1257//1257 1256//1256 1258//1258 -f 1259//1259 1260//1260 1261//1261 -f 1261//1261 1260//1260 1262//1262 -f 1261//1261 1262//1262 1263//1263 -f 1263//1263 1262//1262 1264//1264 -f 1263//1263 1264//1264 1265//1265 -f 1265//1265 1264//1264 1266//1266 -f 1265//1265 1266//1266 1267//1267 -f 1267//1267 1266//1266 1268//1268 -f 1267//1267 1268//1268 1269//1269 -f 1269//1269 1268//1268 1270//1270 -f 1269//1269 1270//1270 1271//1271 -f 1271//1271 1270//1270 1272//1272 -f 1273//1273 1274//1274 1275//1275 -f 1275//1275 1274//1274 1276//1276 -f 1275//1275 1276//1276 1277//1277 -f 1277//1277 1276//1276 1278//1278 -f 1277//1277 1278//1278 1279//1279 -f 1279//1279 1278//1278 1280//1280 -f 1279//1279 1280//1280 1281//1281 -f 1281//1281 1280//1280 1282//1282 -f 1281//1281 1282//1282 1283//1283 -f 1283//1283 1282//1282 1284//1284 -f 1283//1283 1284//1284 1285//1285 -f 1285//1285 1284//1284 1286//1286 -f 1287//1287 1288//1288 1289//1289 -f 1289//1289 1288//1288 1290//1290 -f 1289//1289 1290//1290 1291//1291 -f 1291//1291 1290//1290 1292//1292 -f 1291//1291 1292//1292 1293//1293 -f 1293//1293 1292//1292 1294//1294 -f 1293//1293 1294//1294 1295//1295 -f 1295//1295 1294//1294 1296//1296 -f 1295//1295 1296//1296 1297//1297 -f 1297//1297 1296//1296 1298//1298 -f 1297//1297 1298//1298 1299//1299 -f 1299//1299 1298//1298 1300//1300 -f 1301//1301 1302//1302 1303//1303 -f 1303//1303 1302//1302 1304//1304 -f 1303//1303 1304//1304 1305//1305 -f 1305//1305 1304//1304 1306//1306 -f 1305//1305 1306//1306 1307//1307 -f 1307//1307 1306//1306 1308//1308 -f 1307//1307 1308//1308 1309//1309 -f 1309//1309 1308//1308 1310//1310 -f 1309//1309 1310//1310 1311//1311 -f 1311//1311 1310//1310 1312//1312 -f 1311//1311 1312//1312 1313//1313 -f 1313//1313 1312//1312 1314//1314 -f 1315//1315 1316//1316 1317//1317 -f 1317//1317 1316//1316 1318//1318 -f 1317//1317 1318//1318 1319//1319 -f 1319//1319 1318//1318 1320//1320 -f 1319//1319 1320//1320 1321//1321 -f 1321//1321 1320//1320 1322//1322 -f 1321//1321 1322//1322 1323//1323 -f 1323//1323 1322//1322 1324//1324 -f 1323//1323 1324//1324 1325//1325 -f 1325//1325 1324//1324 1326//1326 -f 1325//1325 1326//1326 1327//1327 -f 1327//1327 1326//1326 1328//1328 -f 1329//1329 1330//1330 1331//1331 -f 1331//1331 1330//1330 1332//1332 -f 1331//1331 1332//1332 1333//1333 -f 1333//1333 1332//1332 1334//1334 -f 1333//1333 1334//1334 1335//1335 -f 1335//1335 1334//1334 1336//1336 -f 1335//1335 1336//1336 1337//1337 -f 1337//1337 1336//1336 1338//1338 -f 1337//1337 1338//1338 1339//1339 -f 1339//1339 1338//1338 1340//1340 -f 1339//1339 1340//1340 1341//1341 -f 1341//1341 1340//1340 1342//1342 -f 1343//1343 1344//1344 1345//1345 -f 1345//1345 1344//1344 1346//1346 -f 1345//1345 1346//1346 1347//1347 -f 1347//1347 1346//1346 1348//1348 -f 1347//1347 1348//1348 1349//1349 -f 1349//1349 1348//1348 1350//1350 -f 1349//1349 1350//1350 1351//1351 -f 1351//1351 1350//1350 1352//1352 -f 1351//1351 1352//1352 1353//1353 -f 1353//1353 1352//1352 1354//1354 -f 1353//1353 1354//1354 1355//1355 -f 1355//1355 1354//1354 1356//1356 -f 1357//1357 1358//1358 1359//1359 -f 1359//1359 1358//1358 1360//1360 -f 1359//1359 1360//1360 1361//1361 -f 1361//1361 1360//1360 1362//1362 -f 1361//1361 1362//1362 1363//1363 -f 1363//1363 1362//1362 1364//1364 -f 1363//1363 1364//1364 1365//1365 -f 1365//1365 1364//1364 1366//1366 -f 1365//1365 1366//1366 1367//1367 -f 1367//1367 1366//1366 1368//1368 -f 1367//1367 1368//1368 1369//1369 -f 1369//1369 1368//1368 1370//1370 -f 1371//1371 1372//1372 1373//1373 -f 1373//1373 1372//1372 1374//1374 -f 1373//1373 1374//1374 1375//1375 -f 1375//1375 1374//1374 1376//1376 -f 1375//1375 1376//1376 1377//1377 -f 1377//1377 1376//1376 1378//1378 -f 1377//1377 1378//1378 1379//1379 -f 1379//1379 1378//1378 1380//1380 -f 1379//1379 1380//1380 1381//1381 -f 1381//1381 1380//1380 1382//1382 -f 1381//1381 1382//1382 1383//1383 -f 1383//1383 1382//1382 1384//1384 -f 1385//1385 1386//1386 1387//1387 -f 1387//1387 1386//1386 1388//1388 -f 1387//1387 1388//1388 1389//1389 -f 1389//1389 1388//1388 1390//1390 -f 1389//1389 1390//1390 1391//1391 -f 1391//1391 1390//1390 1392//1392 -f 1391//1391 1392//1392 1393//1393 -f 1393//1393 1392//1392 1394//1394 -f 1393//1393 1394//1394 1395//1395 -f 1395//1395 1394//1394 1396//1396 -f 1395//1395 1396//1396 1397//1397 -f 1397//1397 1396//1396 1398//1398 -f 1399//1399 1400//1400 1401//1401 -f 1401//1401 1400//1400 1402//1402 -f 1401//1401 1402//1402 1403//1403 -f 1403//1403 1402//1402 1404//1404 -f 1403//1403 1404//1404 1405//1405 -f 1405//1405 1404//1404 1406//1406 -f 1405//1405 1406//1406 1407//1407 -f 1407//1407 1406//1406 1408//1408 -f 1407//1407 1408//1408 1409//1409 -f 1409//1409 1408//1408 1410//1410 -f 1409//1409 1410//1410 1411//1411 -f 1411//1411 1410//1410 1412//1412 -f 1413//1413 1414//1414 1415//1415 -f 1415//1415 1414//1414 1416//1416 -f 1415//1415 1416//1416 1417//1417 -f 1417//1417 1416//1416 1418//1418 -f 1417//1417 1418//1418 1419//1419 -f 1419//1419 1418//1418 1420//1420 -f 1419//1419 1420//1420 1421//1421 -f 1421//1421 1420//1420 1422//1422 -f 1421//1421 1422//1422 1423//1423 -f 1423//1423 1422//1422 1424//1424 -f 1423//1423 1424//1424 1425//1425 -f 1425//1425 1424//1424 1426//1426 -f 1427//1427 1428//1428 1429//1429 -f 1429//1429 1428//1428 1430//1430 -f 1429//1429 1430//1430 1431//1431 -f 1431//1431 1430//1430 1432//1432 -f 1431//1431 1432//1432 1433//1433 -f 1433//1433 1432//1432 1434//1434 -f 1433//1433 1434//1434 1435//1435 -f 1435//1435 1434//1434 1436//1436 -f 1435//1435 1436//1436 1437//1437 -f 1437//1437 1436//1436 1438//1438 -f 1437//1437 1438//1438 1439//1439 -f 1439//1439 1438//1438 1440//1440 -f 1441//1441 1442//1442 1443//1443 -f 1443//1443 1442//1442 1444//1444 -f 1443//1443 1444//1444 1445//1445 -f 1445//1445 1444//1444 1446//1446 -f 1445//1445 1446//1446 1447//1447 -f 1447//1447 1446//1446 1448//1448 -f 1447//1447 1448//1448 1441//1441 -f 1441//1441 1448//1448 1442//1442 -f 1449//1449 1450//1450 1451//1451 -f 1451//1451 1450//1450 1452//1452 -f 1451//1451 1452//1452 1453//1453 -f 1453//1453 1452//1452 1454//1454 -f 1453//1453 1454//1454 1455//1455 -f 1455//1455 1454//1454 1456//1456 -f 1455//1455 1456//1456 1457//1457 -f 1457//1457 1456//1456 1458//1458 -f 1457//1457 1458//1458 1459//1459 -f 1459//1459 1458//1458 1460//1460 -f 1459//1459 1460//1460 1461//1461 -f 1461//1461 1460//1460 1462//1462 -f 1463//1463 1444//1444 1464//1464 -f 1464//1464 1444//1444 1442//1442 -f 1465//1465 1466//1466 1467//1467 -f 1467//1467 1466//1466 1468//1468 -f 1467//1467 1468//1468 1469//1469 -f 1469//1469 1468//1468 1470//1470 -f 1469//1469 1470//1470 1471//1471 -f 1471//1471 1470//1470 1472//1472 -f 1471//1471 1472//1472 1473//1473 -f 1473//1473 1472//1472 1474//1474 -f 1473//1473 1474//1474 1475//1475 -f 1475//1475 1474//1474 1476//1476 -f 1475//1475 1476//1476 1477//1477 -f 1477//1477 1476//1476 1478//1478 -f 1449//1449 1451//1451 1477//1477 -f 1477//1477 1451//1451 1475//1475 -f 1479//1479 1480//1480 1481//1481 -f 1481//1481 1480//1480 1482//1482 -f 1481//1481 1482//1482 1483//1483 -f 1483//1483 1482//1482 1484//1484 -f 1483//1483 1484//1484 1485//1485 -f 1485//1485 1484//1484 1486//1486 -f 1485//1485 1486//1486 1487//1487 -f 1487//1487 1486//1486 1488//1488 -f 1487//1487 1488//1488 1489//1489 -f 1489//1489 1488//1488 1490//1490 -f 1489//1489 1490//1490 1491//1491 -f 1491//1491 1490//1490 1492//1492 -f 1479//1479 1481//1481 1493//1493 -f 1493//1493 1481//1481 1494//1494 -f 1495//1495 1496//1496 1497//1497 -f 1497//1497 1496//1496 1498//1498 -f 1497//1497 1498//1498 1499//1499 -f 1499//1499 1498//1498 1500//1500 -f 1499//1499 1500//1500 1501//1501 -f 1501//1501 1500//1500 1502//1502 -f 1501//1501 1502//1502 1503//1503 -f 1503//1503 1502//1502 1504//1504 -f 1503//1503 1504//1504 1494//1494 -f 1494//1494 1504//1504 1505//1505 -f 1494//1494 1505//1505 1493//1493 -f 1493//1493 1505//1505 1506//1506 -f 1507//1507 1508//1508 1509//1509 -f 1509//1509 1508//1508 1510//1510 -f 1511//1511 1512//1512 1513//1513 -f 1513//1513 1512//1512 1514//1514 -f 1513//1513 1514//1514 1515//1515 -f 1515//1515 1514//1514 1516//1516 -f 1515//1515 1516//1516 1466//1466 -f 1466//1466 1516//1516 1468//1468 -f 1517//1517 1518//1518 1519//1519 -f 1519//1519 1518//1518 1520//1520 -f 1519//1519 1520//1520 1521//1521 -f 1521//1521 1520//1520 1522//1522 -f 1521//1521 1522//1522 1523//1523 -f 1523//1523 1522//1522 1524//1524 -f 1523//1523 1524//1524 1525//1525 -f 1525//1525 1524//1524 1526//1526 -f 1525//1525 1526//1526 1527//1527 -f 1527//1527 1526//1526 1528//1528 -f 1527//1527 1528//1528 1529//1529 -f 1529//1529 1528//1528 1530//1530 -f 1529//1529 1530//1530 1531//1531 -f 1531//1531 1530//1530 1532//1532 -f 1531//1531 1532//1532 1533//1533 -f 1533//1533 1532//1532 1534//1534 -f 1533//1533 1534//1534 1535//1535 -f 1535//1535 1534//1534 1536//1536 -f 1535//1535 1536//1536 1537//1537 -f 1537//1537 1536//1536 1512//1512 -f 1537//1537 1512//1512 1538//1538 -f 1538//1538 1512//1512 1511//1511 -f 1539//1539 1537//1537 1508//1508 -f 1508//1508 1537//1537 1538//1538 -f 1508//1508 1538//1538 1510//1510 -f 1465//1465 1467//1467 1461//1461 -f 1461//1461 1467//1467 1459//1459 -f 1540//1540 1541//1541 1542//1542 -f 1507//1507 1509//1509 1542//1542 -f 1542//1542 1509//1509 1543//1543 -f 1542//1542 1543//1543 1540//1540 -f 1540//1540 1543//1543 1544//1544 -f 1460//1460 1545//1545 1462//1462 -f 1462//1462 1545//1545 1546//1546 -f 1547//1547 1548//1548 1543//1543 -f 1543//1543 1548//1548 1549//1549 -f 1543//1543 1549//1549 1544//1544 -f 1544//1544 1549//1549 1550//1550 -f 1544//1544 1550//1550 1551//1551 -f 1547//1547 1462//1462 1548//1548 -f 1548//1548 1462//1462 1546//1546 -f 1548//1548 1546//1546 1552//1552 -f 1552//1552 1546//1546 1553//1553 -f 1554//1554 1555//1555 1556//1556 -f 1556//1556 1555//1555 1557//1557 -f 1554//1554 1517//1517 1555//1555 -f 1555//1555 1517//1517 1519//1519 -f 1555//1555 1519//1519 1558//1558 -f 1559//1559 1560//1560 1561//1561 -f 1561//1561 1560//1560 1562//1562 -f 1561//1561 1562//1562 1563//1563 -f 1564//1564 1562//1562 1560//1560 -f 1439//1439 1440//1440 1565//1565 -f 1565//1565 1440//1440 1566//1566 -f 1565//1565 1566//1566 1567//1567 -f 1567//1567 1566//1566 1568//1568 -f 1428//1428 1427//1427 1569//1569 -f 1569//1569 1427//1427 1570//1570 -f 1569//1569 1570//1570 1571//1571 -f 1563//1563 1567//1567 1561//1561 -f 1561//1561 1567//1567 1568//1568 -f 1561//1561 1568//1568 1559//1559 -f 1559//1559 1568//1568 1572//1572 -f 1559//1559 1572//1572 1560//1560 -f 1560//1560 1572//1572 1571//1571 -f 1560//1560 1571//1571 1564//1564 -f 1564//1564 1571//1571 1570//1570 -f 1492//1492 1490//1490 1573//1573 -f 1573//1573 1490//1490 1574//1574 -f 1573//1573 1574//1574 1575//1575 -f 1575//1575 1574//1574 1576//1576 -f 1575//1575 1576//1576 1518//1518 -f 1518//1518 1576//1576 1520//1520 -f 1577//1577 1528//1528 1526//1526 -f 1577//1577 1526//1526 1578//1578 -f 1578//1578 1526//1526 1524//1524 -f 1578//1578 1524//1524 1579//1579 -f 1579//1579 1524//1524 1522//1522 -f 1579//1579 1522//1522 1580//1580 -f 1580//1580 1522//1522 1520//1520 -f 1580//1580 1520//1520 1576//1576 -f 1574//1574 1490//1490 1488//1488 -f 1574//1574 1488//1488 1581//1581 -f 1581//1581 1488//1488 1486//1486 -f 1581//1581 1486//1486 1582//1582 -f 1582//1582 1486//1486 1484//1484 -f 1582//1582 1484//1484 1583//1583 -f 1583//1583 1484//1484 1482//1482 -f 1583//1583 1482//1482 1584//1584 -f 1585//1585 1476//1476 1474//1474 -f 1585//1585 1474//1474 1586//1586 -f 1586//1586 1474//1474 1472//1472 -f 1586//1586 1472//1472 1587//1587 -f 1587//1587 1472//1472 1470//1470 -f 1587//1587 1470//1470 1588//1588 -f 1588//1588 1470//1470 1468//1468 -f 1588//1588 1468//1468 1516//1516 -f 1530//1530 1528//1528 1589//1589 -f 1589//1589 1528//1528 1577//1577 -f 1514//1514 1512//1512 1536//1536 -f 1514//1514 1536//1536 1590//1590 -f 1590//1590 1536//1536 1534//1534 -f 1590//1590 1534//1534 1591//1591 -f 1591//1591 1534//1534 1532//1532 -f 1591//1591 1532//1532 1592//1592 -f 1592//1592 1532//1532 1530//1530 -f 1592//1592 1530//1530 1589//1589 -f 1537//1537 1539//1539 1593//1593 -f 1537//1537 1593//1593 1535//1535 -f 1535//1535 1593//1593 1594//1594 -f 1535//1535 1594//1594 1533//1533 -f 1533//1533 1594//1594 1595//1595 -f 1533//1533 1595//1595 1531//1531 -f 1531//1531 1595//1595 1596//1596 -f 1531//1531 1596//1596 1529//1529 -f 1527//1527 1529//1529 1597//1597 -f 1597//1597 1529//1529 1596//1596 -f 1527//1527 1597//1597 1598//1598 -f 1527//1527 1598//1598 1525//1525 -f 1525//1525 1598//1598 1599//1599 -f 1525//1525 1599//1599 1523//1523 -f 1523//1523 1599//1599 1600//1600 -f 1523//1523 1600//1600 1521//1521 -f 1521//1521 1600//1600 1558//1558 -f 1521//1521 1558//1558 1519//1519 -f 1497//1497 1489//1489 1495//1495 -f 1495//1495 1489//1489 1491//1491 -f 1489//1489 1497//1497 1499//1499 -f 1489//1489 1499//1499 1487//1487 -f 1487//1487 1499//1499 1501//1501 -f 1487//1487 1501//1501 1485//1485 -f 1485//1485 1501//1501 1503//1503 -f 1485//1485 1503//1503 1483//1483 -f 1483//1483 1503//1503 1494//1494 -f 1483//1483 1494//1494 1481//1481 -f 1475//1475 1451//1451 1453//1453 -f 1475//1475 1453//1453 1473//1473 -f 1473//1473 1453//1453 1455//1455 -f 1473//1473 1455//1455 1471//1471 -f 1471//1471 1455//1455 1457//1457 -f 1471//1471 1457//1457 1469//1469 -f 1469//1469 1457//1457 1459//1459 -f 1469//1469 1459//1459 1467//1467 -f 1601//1601 1602//1602 1603//1603 -f 1419//1419 1421//1421 1417//1417 -f 1417//1417 1421//1421 1423//1423 -f 1417//1417 1423//1423 1415//1415 -f 1415//1415 1423//1423 1413//1413 -f 1423//1423 1425//1425 1413//1413 -f 1413//1413 1425//1425 1601//1601 -f 1413//1413 1601//1601 1604//1604 -f 1604//1604 1601//1601 1603//1603 -f 1604//1604 1603//1603 1605//1605 -f 1606//1606 1607//1607 1608//1608 -f 1407//1407 1409//1409 1405//1405 -f 1405//1405 1409//1409 1399//1399 -f 1405//1405 1399//1399 1403//1403 -f 1403//1403 1399//1399 1401//1401 -f 1409//1409 1411//1411 1399//1399 -f 1399//1399 1411//1411 1606//1606 -f 1399//1399 1606//1606 1609//1609 -f 1609//1609 1606//1606 1608//1608 -f 1609//1609 1608//1608 1610//1610 -f 1425//1425 1426//1426 1601//1601 -f 1601//1601 1426//1426 1611//1611 -f 1601//1601 1611//1611 1602//1602 -f 1602//1602 1611//1611 1612//1612 -f 1602//1602 1612//1612 1603//1603 -f 1603//1603 1612//1612 1613//1613 -f 1603//1603 1613//1613 1605//1605 -f 1605//1605 1613//1613 1614//1614 -f 1605//1605 1614//1614 1604//1604 -f 1604//1604 1614//1614 1615//1615 -f 1604//1604 1615//1615 1413//1413 -f 1413//1413 1615//1615 1414//1414 -f 1411//1411 1412//1412 1606//1606 -f 1606//1606 1412//1412 1616//1616 -f 1606//1606 1616//1616 1607//1607 -f 1607//1607 1616//1616 1617//1617 -f 1607//1607 1617//1617 1608//1608 -f 1608//1608 1617//1617 1618//1618 -f 1608//1608 1618//1618 1610//1610 -f 1610//1610 1618//1618 1619//1619 -f 1610//1610 1619//1619 1609//1609 -f 1609//1609 1619//1619 1620//1620 -f 1609//1609 1620//1620 1399//1399 -f 1399//1399 1620//1620 1400//1400 -f 1395//1395 1397//1397 1621//1621 -f 1622//1622 1385//1385 1387//1387 -f 1623//1623 1624//1624 1622//1622 -f 1621//1621 1625//1625 1623//1623 -f 1387//1387 1389//1389 1391//1391 -f 1623//1623 1622//1622 1621//1621 -f 1621//1621 1622//1622 1387//1387 -f 1621//1621 1387//1387 1395//1395 -f 1395//1395 1387//1387 1391//1391 -f 1395//1395 1391//1391 1393//1393 -f 1626//1626 1627//1627 1371//1371 -f 1379//1379 1381//1381 1383//1383 -f 1377//1377 1379//1379 1375//1375 -f 1375//1375 1379//1379 1626//1626 -f 1375//1375 1626//1626 1373//1373 -f 1373//1373 1626//1626 1371//1371 -f 1628//1628 1626//1626 1629//1629 -f 1629//1629 1626//1626 1379//1379 -f 1629//1629 1379//1379 1630//1630 -f 1630//1630 1379//1379 1383//1383 -f 1631//1631 1632//1632 1363//1363 -f 1631//1631 1363//1363 1633//1633 -f 1633//1633 1363//1363 1365//1365 -f 1633//1633 1365//1365 1367//1367 -f 1632//1632 1357//1357 1363//1363 -f 1363//1363 1357//1357 1359//1359 -f 1363//1363 1359//1359 1361//1361 -f 1367//1367 1369//1369 1633//1633 -f 1633//1633 1369//1369 1634//1634 -f 1633//1633 1634//1634 1635//1635 -f 1353//1353 1355//1355 1636//1636 -f 1637//1637 1638//1638 1639//1639 -f 1640//1640 1637//1637 1636//1636 -f 1636//1636 1637//1637 1639//1639 -f 1636//1636 1639//1639 1345//1345 -f 1345//1345 1639//1639 1343//1343 -f 1351//1351 1353//1353 1349//1349 -f 1349//1349 1353//1353 1636//1636 -f 1349//1349 1636//1636 1347//1347 -f 1347//1347 1636//1636 1345//1345 -f 1641//1641 1642//1642 1643//1643 -f 1339//1339 1341//1341 1644//1644 -f 1645//1645 1329//1329 1643//1643 -f 1643//1643 1329//1329 1331//1331 -f 1643//1643 1331//1331 1333//1333 -f 1644//1644 1641//1641 1339//1339 -f 1339//1339 1641//1641 1643//1643 -f 1339//1339 1643//1643 1337//1337 -f 1337//1337 1643//1643 1333//1333 -f 1337//1337 1333//1333 1335//1335 -f 1646//1646 1647//1647 1648//1648 -f 1321//1321 1323//1323 1325//1325 -f 1648//1648 1649//1649 1321//1321 -f 1321//1321 1649//1649 1650//1650 -f 1648//1648 1321//1321 1646//1646 -f 1646//1646 1321//1321 1325//1325 -f 1646//1646 1325//1325 1327//1327 -f 1650//1650 1315//1315 1321//1321 -f 1321//1321 1315//1315 1317//1317 -f 1321//1321 1317//1317 1319//1319 -f 1295//1295 1297//1297 1299//1299 -f 1651//1651 1652//1652 1287//1287 -f 1287//1287 1289//1289 1291//1291 -f 1653//1653 1654//1654 1655//1655 -f 1655//1655 1654//1654 1651//1651 -f 1655//1655 1651//1651 1299//1299 -f 1299//1299 1651//1651 1287//1287 -f 1299//1299 1287//1287 1295//1295 -f 1295//1295 1287//1287 1291//1291 -f 1295//1295 1291//1291 1293//1293 -f 1656//1656 1657//1657 1658//1658 -f 1279//1279 1281//1281 1283//1283 -f 1277//1277 1279//1279 1275//1275 -f 1275//1275 1279//1279 1656//1656 -f 1275//1275 1656//1656 1273//1273 -f 1273//1273 1656//1656 1658//1658 -f 1659//1659 1656//1656 1660//1660 -f 1660//1660 1656//1656 1279//1279 -f 1660//1660 1279//1279 1285//1285 -f 1285//1285 1279//1279 1283//1283 -f 1661//1661 1662//1662 1259//1259 -f 1267//1267 1269//1269 1271//1271 -f 1271//1271 1663//1663 1664//1664 -f 1263//1263 1265//1265 1261//1261 -f 1261//1261 1265//1265 1267//1267 -f 1261//1261 1267//1267 1259//1259 -f 1259//1259 1267//1267 1271//1271 -f 1259//1259 1271//1271 1661//1661 -f 1661//1661 1271//1271 1664//1664 -f 1661//1661 1664//1664 1665//1665 -f 1253//1253 1255//1255 1257//1257 -f 1666//1666 1667//1667 1245//1245 -f 1245//1245 1247//1247 1249//1249 -f 1668//1668 1669//1669 1670//1670 -f 1670//1670 1669//1669 1666//1666 -f 1670//1670 1666//1666 1257//1257 -f 1257//1257 1666//1666 1245//1245 -f 1257//1257 1245//1245 1253//1253 -f 1253//1253 1245//1245 1249//1249 -f 1253//1253 1249//1249 1251//1251 -f 1241//1241 1243//1243 1231//1231 -f 1231//1231 1243//1243 1671//1671 -f 1672//1672 1673//1673 1674//1674 -f 1674//1674 1673//1673 1231//1231 -f 1674//1674 1231//1231 1675//1675 -f 1675//1675 1231//1231 1671//1671 -f 1239//1239 1241//1241 1237//1237 -f 1237//1237 1241//1241 1231//1231 -f 1237//1237 1231//1231 1235//1235 -f 1235//1235 1231//1231 1233//1233 -f 1676//1676 1217//1217 1229//1229 -f 1229//1229 1217//1217 1219//1219 -f 1227//1227 1229//1229 1225//1225 -f 1225//1225 1229//1229 1219//1219 -f 1225//1225 1219//1219 1223//1223 -f 1223//1223 1219//1219 1221//1221 -f 1677//1677 1678//1678 1679//1679 -f 1679//1679 1678//1678 1676//1676 -f 1679//1679 1676//1676 1680//1680 -f 1680//1680 1676//1676 1229//1229 -f 1213//1213 1215//1215 1203//1203 -f 1203//1203 1215//1215 1681//1681 -f 1203//1203 1681//1681 1682//1682 -f 1203//1203 1205//1205 1207//1207 -f 1682//1682 1683//1683 1203//1203 -f 1203//1203 1683//1683 1684//1684 -f 1203//1203 1684//1684 1685//1685 -f 1213//1213 1203//1203 1211//1211 -f 1211//1211 1203//1203 1207//1207 -f 1211//1211 1207//1207 1209//1209 -f 1613//1613 1686//1686 1614//1614 -f 1614//1614 1686//1686 1687//1687 -f 1614//1614 1687//1687 1615//1615 -f 1615//1615 1687//1687 1688//1688 -f 1615//1615 1688//1688 1414//1414 -f 1414//1414 1688//1688 1202//1202 -f 1414//1414 1202//1202 1416//1416 -f 1416//1416 1202//1202 1200//1200 -f 1416//1416 1200//1200 1418//1418 -f 1418//1418 1200//1200 1198//1198 -f 1418//1418 1198//1198 1420//1420 -f 1198//1198 1196//1196 1420//1420 -f 1420//1420 1196//1196 1194//1194 -f 1420//1420 1194//1194 1422//1422 -f 1422//1422 1194//1194 1192//1192 -f 1422//1422 1192//1192 1424//1424 -f 1424//1424 1192//1192 1190//1190 -f 1424//1424 1190//1190 1426//1426 -f 1426//1426 1190//1190 1188//1188 -f 1426//1426 1188//1188 1611//1611 -f 1611//1611 1188//1188 1689//1689 -f 1611//1611 1689//1689 1612//1612 -f 1612//1612 1689//1689 1690//1690 -f 1612//1612 1690//1690 1613//1613 -f 1613//1613 1690//1690 1691//1691 -f 1613//1613 1691//1691 1686//1686 -f 1618//1618 1692//1692 1619//1619 -f 1619//1619 1692//1692 1693//1693 -f 1619//1619 1693//1693 1620//1620 -f 1620//1620 1693//1693 1694//1694 -f 1620//1620 1694//1694 1400//1400 -f 1400//1400 1694//1694 1171//1171 -f 1400//1400 1171//1171 1402//1402 -f 1402//1402 1171//1171 1173//1173 -f 1402//1402 1173//1173 1404//1404 -f 1404//1404 1173//1173 1175//1175 -f 1404//1404 1175//1175 1406//1406 -f 1175//1175 1177//1177 1406//1406 -f 1406//1406 1177//1177 1179//1179 -f 1406//1406 1179//1179 1408//1408 -f 1408//1408 1179//1179 1181//1181 -f 1408//1408 1181//1181 1410//1410 -f 1410//1410 1181//1181 1183//1183 -f 1410//1410 1183//1183 1412//1412 -f 1412//1412 1183//1183 1185//1185 -f 1412//1412 1185//1185 1616//1616 -f 1616//1616 1185//1185 1695//1695 -f 1616//1616 1695//1695 1617//1617 -f 1617//1617 1695//1695 1696//1696 -f 1617//1617 1696//1696 1618//1618 -f 1618//1618 1696//1696 1697//1697 -f 1618//1618 1697//1697 1692//1692 -f 1397//1397 1398//1398 1621//1621 -f 1621//1621 1398//1398 1698//1698 -f 1621//1621 1698//1698 1625//1625 -f 1625//1625 1698//1698 1699//1699 -f 1625//1625 1699//1699 1623//1623 -f 1623//1623 1699//1699 1700//1700 -f 1623//1623 1700//1700 1624//1624 -f 1624//1624 1700//1700 1701//1701 -f 1624//1624 1701//1701 1622//1622 -f 1622//1622 1701//1701 1702//1702 -f 1622//1622 1702//1702 1385//1385 -f 1385//1385 1702//1702 1386//1386 -f 1383//1383 1384//1384 1630//1630 -f 1630//1630 1384//1384 1703//1703 -f 1630//1630 1703//1703 1629//1629 -f 1629//1629 1703//1703 1704//1704 -f 1629//1629 1704//1704 1628//1628 -f 1628//1628 1704//1704 1705//1705 -f 1628//1628 1705//1705 1626//1626 -f 1626//1626 1705//1705 1706//1706 -f 1626//1626 1706//1706 1627//1627 -f 1627//1627 1706//1706 1707//1707 -f 1627//1627 1707//1707 1371//1371 -f 1371//1371 1707//1707 1372//1372 -f 1369//1369 1370//1370 1634//1634 -f 1634//1634 1370//1370 1708//1708 -f 1634//1634 1708//1708 1635//1635 -f 1635//1635 1708//1708 1709//1709 -f 1635//1635 1709//1709 1633//1633 -f 1633//1633 1709//1709 1710//1710 -f 1633//1633 1710//1710 1631//1631 -f 1631//1631 1710//1710 1711//1711 -f 1631//1631 1711//1711 1632//1632 -f 1632//1632 1711//1711 1712//1712 -f 1632//1632 1712//1712 1357//1357 -f 1357//1357 1712//1712 1358//1358 -f 1355//1355 1356//1356 1636//1636 -f 1636//1636 1356//1356 1713//1713 -f 1636//1636 1713//1713 1640//1640 -f 1640//1640 1713//1713 1714//1714 -f 1640//1640 1714//1714 1637//1637 -f 1637//1637 1714//1714 1715//1715 -f 1637//1637 1715//1715 1638//1638 -f 1638//1638 1715//1715 1716//1716 -f 1638//1638 1716//1716 1639//1639 -f 1639//1639 1716//1716 1717//1717 -f 1639//1639 1717//1717 1343//1343 -f 1343//1343 1717//1717 1344//1344 -f 1341//1341 1342//1342 1644//1644 -f 1644//1644 1342//1342 1718//1718 -f 1644//1644 1718//1718 1641//1641 -f 1641//1641 1718//1718 1719//1719 -f 1641//1641 1719//1719 1642//1642 -f 1642//1642 1719//1719 1720//1720 -f 1642//1642 1720//1720 1643//1643 -f 1643//1643 1720//1720 1721//1721 -f 1643//1643 1721//1721 1645//1645 -f 1645//1645 1721//1721 1722//1722 -f 1645//1645 1722//1722 1329//1329 -f 1329//1329 1722//1722 1330//1330 -f 1327//1327 1328//1328 1646//1646 -f 1646//1646 1328//1328 1723//1723 -f 1646//1646 1723//1723 1647//1647 -f 1647//1647 1723//1723 1724//1724 -f 1647//1647 1724//1724 1648//1648 -f 1648//1648 1724//1724 1725//1725 -f 1648//1648 1725//1725 1649//1649 -f 1649//1649 1725//1725 1726//1726 -f 1649//1649 1726//1726 1650//1650 -f 1650//1650 1726//1726 1727//1727 -f 1650//1650 1727//1727 1315//1315 -f 1315//1315 1727//1727 1316//1316 -f 1313//1313 1314//1314 1728//1728 -f 1728//1728 1314//1314 1729//1729 -f 1728//1728 1729//1729 1730//1730 -f 1730//1730 1729//1729 1731//1731 -f 1730//1730 1731//1731 1732//1732 -f 1732//1732 1731//1731 1733//1733 -f 1732//1732 1733//1733 1734//1734 -f 1734//1734 1733//1733 1735//1735 -f 1734//1734 1735//1735 1736//1736 -f 1736//1736 1735//1735 1737//1737 -f 1736//1736 1737//1737 1301//1301 -f 1301//1301 1737//1737 1302//1302 -f 1299//1299 1300//1300 1655//1655 -f 1655//1655 1300//1300 1738//1738 -f 1655//1655 1738//1738 1653//1653 -f 1653//1653 1738//1738 1739//1739 -f 1653//1653 1739//1739 1654//1654 -f 1654//1654 1739//1739 1740//1740 -f 1654//1654 1740//1740 1651//1651 -f 1651//1651 1740//1740 1741//1741 -f 1651//1651 1741//1741 1652//1652 -f 1652//1652 1741//1741 1742//1742 -f 1652//1652 1742//1742 1287//1287 -f 1287//1287 1742//1742 1288//1288 -f 1285//1285 1286//1286 1660//1660 -f 1660//1660 1286//1286 1743//1743 -f 1660//1660 1743//1743 1659//1659 -f 1659//1659 1743//1743 1744//1744 -f 1659//1659 1744//1744 1656//1656 -f 1656//1656 1744//1744 1745//1745 -f 1656//1656 1745//1745 1657//1657 -f 1657//1657 1745//1745 1746//1746 -f 1657//1657 1746//1746 1658//1658 -f 1658//1658 1746//1746 1747//1747 -f 1658//1658 1747//1747 1273//1273 -f 1273//1273 1747//1747 1274//1274 -f 1271//1271 1272//1272 1663//1663 -f 1663//1663 1272//1272 1748//1748 -f 1663//1663 1748//1748 1664//1664 -f 1664//1664 1748//1748 1749//1749 -f 1664//1664 1749//1749 1665//1665 -f 1665//1665 1749//1749 1750//1750 -f 1665//1665 1750//1750 1661//1661 -f 1661//1661 1750//1750 1751//1751 -f 1661//1661 1751//1751 1662//1662 -f 1662//1662 1751//1751 1752//1752 -f 1662//1662 1752//1752 1259//1259 -f 1259//1259 1752//1752 1260//1260 -f 1257//1257 1258//1258 1670//1670 -f 1670//1670 1258//1258 1753//1753 -f 1670//1670 1753//1753 1668//1668 -f 1668//1668 1753//1753 1754//1754 -f 1668//1668 1754//1754 1669//1669 -f 1669//1669 1754//1754 1755//1755 -f 1669//1669 1755//1755 1666//1666 -f 1666//1666 1755//1755 1756//1756 -f 1666//1666 1756//1756 1667//1667 -f 1667//1667 1756//1756 1757//1757 -f 1667//1667 1757//1757 1245//1245 -f 1245//1245 1757//1757 1246//1246 -f 1243//1243 1244//1244 1671//1671 -f 1671//1671 1244//1244 1758//1758 -f 1671//1671 1758//1758 1675//1675 -f 1675//1675 1758//1758 1759//1759 -f 1675//1675 1759//1759 1674//1674 -f 1674//1674 1759//1759 1760//1760 -f 1674//1674 1760//1760 1672//1672 -f 1672//1672 1760//1760 1761//1761 -f 1672//1672 1761//1761 1673//1673 -f 1673//1673 1761//1761 1762//1762 -f 1673//1673 1762//1762 1231//1231 -f 1231//1231 1762//1762 1232//1232 -f 1229//1229 1230//1230 1680//1680 -f 1680//1680 1230//1230 1763//1763 -f 1680//1680 1763//1763 1679//1679 -f 1679//1679 1763//1763 1764//1764 -f 1679//1679 1764//1764 1677//1677 -f 1677//1677 1764//1764 1765//1765 -f 1677//1677 1765//1765 1678//1678 -f 1678//1678 1765//1765 1766//1766 -f 1678//1678 1766//1766 1676//1676 -f 1676//1676 1766//1766 1767//1767 -f 1676//1676 1767//1767 1217//1217 -f 1217//1217 1767//1767 1218//1218 -f 1215//1215 1216//1216 1681//1681 -f 1681//1681 1216//1216 1768//1768 -f 1681//1681 1768//1768 1682//1682 -f 1682//1682 1768//1768 1769//1769 -f 1682//1682 1769//1769 1683//1683 -f 1683//1683 1769//1769 1770//1770 -f 1683//1683 1770//1770 1684//1684 -f 1684//1684 1770//1770 1771//1771 -f 1684//1684 1771//1771 1685//1685 -f 1685//1685 1771//1771 1772//1772 -f 1685//1685 1772//1772 1203//1203 -f 1203//1203 1772//1772 1204//1204 -f 1201//1201 1202//1202 1773//1773 -f 1773//1773 1202//1202 1688//1688 -f 1773//1773 1688//1688 1774//1774 -f 1774//1774 1688//1688 1687//1687 -f 1774//1774 1687//1687 1775//1775 -f 1775//1775 1687//1687 1686//1686 -f 1775//1775 1686//1686 1776//1776 -f 1776//1776 1686//1686 1691//1691 -f 1776//1776 1691//1691 1777//1777 -f 1777//1777 1691//1691 1690//1690 -f 1777//1777 1690//1690 1778//1778 -f 1778//1778 1690//1690 1689//1689 -f 1778//1778 1689//1689 1187//1187 -f 1187//1187 1689//1689 1188//1188 -f 1185//1185 1186//1186 1695//1695 -f 1695//1695 1186//1186 1779//1779 -f 1695//1695 1779//1779 1696//1696 -f 1696//1696 1779//1779 1780//1780 -f 1696//1696 1780//1780 1697//1697 -f 1697//1697 1780//1780 1781//1781 -f 1697//1697 1781//1781 1692//1692 -f 1692//1692 1781//1781 1782//1782 -f 1692//1692 1782//1782 1693//1693 -f 1693//1693 1782//1782 1783//1783 -f 1693//1693 1783//1783 1694//1694 -f 1694//1694 1783//1783 1784//1784 -f 1694//1694 1784//1784 1171//1171 -f 1171//1171 1784//1784 1172//1172 -f 1169//1169 1170//1170 1785//1785 -f 1785//1785 1170//1170 1786//1786 -f 1785//1785 1786//1786 1787//1787 -f 1787//1787 1786//1786 1788//1788 -f 1787//1787 1788//1788 1789//1789 -f 1789//1789 1788//1788 1790//1790 -f 1789//1789 1790//1790 1791//1791 -f 1791//1791 1790//1790 1792//1792 -f 1791//1791 1792//1792 1793//1793 -f 1793//1793 1792//1792 1794//1794 -f 1793//1793 1794//1794 1157//1157 -f 1157//1157 1794//1794 1158//1158 -f 1698//1698 1795//1795 1699//1699 -f 1699//1699 1795//1795 1796//1796 -f 1699//1699 1796//1796 1700//1700 -f 1700//1700 1796//1796 1797//1797 -f 1700//1700 1797//1797 1701//1701 -f 1701//1701 1797//1797 1798//1798 -f 1701//1701 1798//1798 1702//1702 -f 1702//1702 1798//1798 1799//1799 -f 1702//1702 1799//1799 1386//1386 -f 1386//1386 1799//1799 1143//1143 -f 1386//1386 1143//1143 1388//1388 -f 1388//1388 1143//1143 1145//1145 -f 1388//1388 1145//1145 1390//1390 -f 1390//1390 1145//1145 1147//1147 -f 1390//1390 1147//1147 1392//1392 -f 1392//1392 1147//1147 1149//1149 -f 1392//1392 1149//1149 1394//1394 -f 1394//1394 1149//1149 1151//1151 -f 1394//1394 1151//1151 1396//1396 -f 1396//1396 1151//1151 1153//1153 -f 1396//1396 1153//1153 1398//1398 -f 1398//1398 1153//1153 1155//1155 -f 1398//1398 1155//1155 1698//1698 -f 1698//1698 1155//1155 1795//1795 -f 1703//1703 1800//1800 1704//1704 -f 1704//1704 1800//1800 1801//1801 -f 1704//1704 1801//1801 1705//1705 -f 1705//1705 1801//1801 1802//1802 -f 1705//1705 1802//1802 1706//1706 -f 1706//1706 1802//1802 1803//1803 -f 1706//1706 1803//1803 1707//1707 -f 1707//1707 1803//1803 1804//1804 -f 1707//1707 1804//1804 1372//1372 -f 1372//1372 1804//1804 1129//1129 -f 1372//1372 1129//1129 1374//1374 -f 1374//1374 1129//1129 1131//1131 -f 1374//1374 1131//1131 1376//1376 -f 1376//1376 1131//1131 1133//1133 -f 1376//1376 1133//1133 1378//1378 -f 1378//1378 1133//1133 1135//1135 -f 1378//1378 1135//1135 1380//1380 -f 1380//1380 1135//1135 1137//1137 -f 1380//1380 1137//1137 1382//1382 -f 1382//1382 1137//1137 1139//1139 -f 1382//1382 1139//1139 1384//1384 -f 1384//1384 1139//1139 1141//1141 -f 1384//1384 1141//1141 1703//1703 -f 1703//1703 1141//1141 1800//1800 -f 1708//1708 1805//1805 1709//1709 -f 1709//1709 1805//1805 1806//1806 -f 1709//1709 1806//1806 1710//1710 -f 1710//1710 1806//1806 1807//1807 -f 1710//1710 1807//1807 1711//1711 -f 1711//1711 1807//1807 1808//1808 -f 1711//1711 1808//1808 1712//1712 -f 1712//1712 1808//1808 1809//1809 -f 1712//1712 1809//1809 1358//1358 -f 1358//1358 1809//1809 1115//1115 -f 1358//1358 1115//1115 1360//1360 -f 1360//1360 1115//1115 1117//1117 -f 1360//1360 1117//1117 1362//1362 -f 1362//1362 1117//1117 1119//1119 -f 1362//1362 1119//1119 1364//1364 -f 1364//1364 1119//1119 1121//1121 -f 1364//1364 1121//1121 1366//1366 -f 1366//1366 1121//1121 1123//1123 -f 1366//1366 1123//1123 1368//1368 -f 1368//1368 1123//1123 1125//1125 -f 1368//1368 1125//1125 1370//1370 -f 1370//1370 1125//1125 1127//1127 -f 1370//1370 1127//1127 1708//1708 -f 1708//1708 1127//1127 1805//1805 -f 1715//1715 1810//1810 1716//1716 -f 1716//1716 1810//1810 1811//1811 -f 1716//1716 1811//1811 1717//1717 -f 1717//1717 1811//1811 1812//1812 -f 1717//1717 1812//1812 1344//1344 -f 1344//1344 1812//1812 1101//1101 -f 1344//1344 1101//1101 1346//1346 -f 1346//1346 1101//1101 1103//1103 -f 1346//1346 1103//1103 1348//1348 -f 1348//1348 1103//1103 1105//1105 -f 1348//1348 1105//1105 1350//1350 -f 1350//1350 1105//1105 1107//1107 -f 1350//1350 1107//1107 1352//1352 -f 1352//1352 1107//1107 1109//1109 -f 1352//1352 1109//1109 1354//1354 -f 1354//1354 1109//1109 1111//1111 -f 1354//1354 1111//1111 1356//1356 -f 1356//1356 1111//1111 1113//1113 -f 1356//1356 1113//1113 1713//1713 -f 1713//1713 1113//1113 1813//1813 -f 1713//1713 1813//1813 1714//1714 -f 1714//1714 1813//1813 1814//1814 -f 1714//1714 1814//1814 1715//1715 -f 1715//1715 1814//1814 1810//1810 -f 1332//1332 1089//1089 1334//1334 -f 1334//1334 1089//1089 1091//1091 -f 1334//1334 1091//1091 1336//1336 -f 1336//1336 1091//1091 1093//1093 -f 1336//1336 1093//1093 1338//1338 -f 1338//1338 1093//1093 1095//1095 -f 1338//1338 1095//1095 1340//1340 -f 1340//1340 1095//1095 1097//1097 -f 1340//1340 1097//1097 1342//1342 -f 1342//1342 1097//1097 1099//1099 -f 1342//1342 1099//1099 1718//1718 -f 1718//1718 1099//1099 1815//1815 -f 1718//1718 1815//1815 1719//1719 -f 1719//1719 1815//1815 1816//1816 -f 1719//1719 1816//1816 1720//1720 -f 1720//1720 1816//1816 1817//1817 -f 1720//1720 1817//1817 1721//1721 -f 1721//1721 1817//1817 1818//1818 -f 1721//1721 1818//1818 1722//1722 -f 1722//1722 1818//1818 1819//1819 -f 1722//1722 1819//1819 1330//1330 -f 1330//1330 1819//1819 1087//1087 -f 1330//1330 1087//1087 1332//1332 -f 1332//1332 1087//1087 1089//1089 -f 1727//1727 1820//1820 1316//1316 -f 1316//1316 1820//1820 1073//1073 -f 1316//1316 1073//1073 1318//1318 -f 1318//1318 1073//1073 1075//1075 -f 1318//1318 1075//1075 1320//1320 -f 1320//1320 1075//1075 1077//1077 -f 1320//1320 1077//1077 1322//1322 -f 1322//1322 1077//1077 1079//1079 -f 1322//1322 1079//1079 1324//1324 -f 1324//1324 1079//1079 1081//1081 -f 1324//1324 1081//1081 1326//1326 -f 1326//1326 1081//1081 1083//1083 -f 1326//1326 1083//1083 1328//1328 -f 1328//1328 1083//1083 1085//1085 -f 1328//1328 1085//1085 1723//1723 -f 1723//1723 1085//1085 1821//1821 -f 1723//1723 1821//1821 1724//1724 -f 1724//1724 1821//1821 1822//1822 -f 1724//1724 1822//1822 1725//1725 -f 1725//1725 1822//1822 1823//1823 -f 1725//1725 1823//1823 1726//1726 -f 1726//1726 1823//1823 1824//1824 -f 1726//1726 1824//1824 1727//1727 -f 1727//1727 1824//1824 1820//1820 -f 1729//1729 1825//1825 1731//1731 -f 1731//1731 1825//1825 1826//1826 -f 1731//1731 1826//1826 1733//1733 -f 1733//1733 1826//1826 1827//1827 -f 1733//1733 1827//1827 1735//1735 -f 1735//1735 1827//1827 1828//1828 -f 1735//1735 1828//1828 1737//1737 -f 1737//1737 1828//1828 1829//1829 -f 1737//1737 1829//1829 1302//1302 -f 1302//1302 1829//1829 1059//1059 -f 1302//1302 1059//1059 1304//1304 -f 1304//1304 1059//1059 1061//1061 -f 1304//1304 1061//1061 1306//1306 -f 1306//1306 1061//1061 1063//1063 -f 1306//1306 1063//1063 1308//1308 -f 1308//1308 1063//1063 1065//1065 -f 1308//1308 1065//1065 1310//1310 -f 1310//1310 1065//1065 1067//1067 -f 1310//1310 1067//1067 1312//1312 -f 1312//1312 1067//1067 1069//1069 -f 1312//1312 1069//1069 1314//1314 -f 1314//1314 1069//1069 1071//1071 -f 1314//1314 1071//1071 1729//1729 -f 1729//1729 1071//1071 1825//1825 -f 1296//1296 1053//1053 1298//1298 -f 1298//1298 1053//1053 1055//1055 -f 1298//1298 1055//1055 1300//1300 -f 1300//1300 1055//1055 1057//1057 -f 1300//1300 1057//1057 1738//1738 -f 1738//1738 1057//1057 1830//1830 -f 1738//1738 1830//1830 1739//1739 -f 1739//1739 1830//1830 1831//1831 -f 1739//1739 1831//1831 1740//1740 -f 1740//1740 1831//1831 1832//1832 -f 1740//1740 1832//1832 1741//1741 -f 1741//1741 1832//1832 1833//1833 -f 1741//1741 1833//1833 1742//1742 -f 1742//1742 1833//1833 1834//1834 -f 1742//1742 1834//1834 1288//1288 -f 1288//1288 1834//1834 1045//1045 -f 1288//1288 1045//1045 1290//1290 -f 1290//1290 1045//1045 1047//1047 -f 1290//1290 1047//1047 1292//1292 -f 1292//1292 1047//1047 1049//1049 -f 1292//1292 1049//1049 1294//1294 -f 1294//1294 1049//1049 1051//1051 -f 1294//1294 1051//1051 1296//1296 -f 1296//1296 1051//1051 1053//1053 -f 1274//1274 1031//1031 1276//1276 -f 1276//1276 1031//1031 1033//1033 -f 1276//1276 1033//1033 1278//1278 -f 1278//1278 1033//1033 1035//1035 -f 1278//1278 1035//1035 1280//1280 -f 1280//1280 1035//1035 1037//1037 -f 1280//1280 1037//1037 1282//1282 -f 1282//1282 1037//1037 1039//1039 -f 1282//1282 1039//1039 1284//1284 -f 1284//1284 1039//1039 1041//1041 -f 1284//1284 1041//1041 1286//1286 -f 1286//1286 1041//1041 1043//1043 -f 1286//1286 1043//1043 1743//1743 -f 1743//1743 1043//1043 1835//1835 -f 1743//1743 1835//1835 1744//1744 -f 1744//1744 1835//1835 1836//1836 -f 1744//1744 1836//1836 1745//1745 -f 1745//1745 1836//1836 1837//1837 -f 1745//1745 1837//1837 1746//1746 -f 1746//1746 1837//1837 1838//1838 -f 1746//1746 1838//1838 1747//1747 -f 1747//1747 1838//1838 1839//1839 -f 1747//1747 1839//1839 1274//1274 -f 1274//1274 1839//1839 1031//1031 -f 1751//1751 1840//1840 1752//1752 -f 1752//1752 1840//1840 1841//1841 -f 1752//1752 1841//1841 1260//1260 -f 1260//1260 1841//1841 1017//1017 -f 1260//1260 1017//1017 1262//1262 -f 1262//1262 1017//1017 1019//1019 -f 1262//1262 1019//1019 1264//1264 -f 1264//1264 1019//1019 1021//1021 -f 1264//1264 1021//1021 1266//1266 -f 1266//1266 1021//1021 1023//1023 -f 1266//1266 1023//1023 1268//1268 -f 1268//1268 1023//1023 1025//1025 -f 1268//1268 1025//1025 1270//1270 -f 1270//1270 1025//1025 1027//1027 -f 1270//1270 1027//1027 1272//1272 -f 1272//1272 1027//1027 1029//1029 -f 1272//1272 1029//1029 1748//1748 -f 1748//1748 1029//1029 1842//1842 -f 1748//1748 1842//1842 1749//1749 -f 1749//1749 1842//1842 1843//1843 -f 1749//1749 1843//1843 1750//1750 -f 1750//1750 1843//1843 1844//1844 -f 1750//1750 1844//1844 1751//1751 -f 1751//1751 1844//1844 1840//1840 -f 1254//1254 1011//1011 1256//1256 -f 1256//1256 1011//1011 1013//1013 -f 1256//1256 1013//1013 1258//1258 -f 1258//1258 1013//1013 1015//1015 -f 1258//1258 1015//1015 1753//1753 -f 1753//1753 1015//1015 1845//1845 -f 1753//1753 1845//1845 1754//1754 -f 1754//1754 1845//1845 1846//1846 -f 1754//1754 1846//1846 1755//1755 -f 1755//1755 1846//1846 1847//1847 -f 1755//1755 1847//1847 1756//1756 -f 1756//1756 1847//1847 1848//1848 -f 1756//1756 1848//1848 1757//1757 -f 1757//1757 1848//1848 1849//1849 -f 1757//1757 1849//1849 1246//1246 -f 1246//1246 1849//1849 1003//1003 -f 1246//1246 1003//1003 1248//1248 -f 1248//1248 1003//1003 1005//1005 -f 1248//1248 1005//1005 1250//1250 -f 1250//1250 1005//1005 1007//1007 -f 1250//1250 1007//1007 1252//1252 -f 1252//1252 1007//1007 1009//1009 -f 1252//1252 1009//1009 1254//1254 -f 1254//1254 1009//1009 1011//1011 -f 1238//1238 996//996 1240//1240 -f 1240//1240 996//996 994//994 -f 1240//1240 994//994 1242//1242 -f 1242//1242 994//994 992//992 -f 1242//1242 992//992 1244//1244 -f 1244//1244 992//992 990//990 -f 1244//1244 990//990 1758//1758 -f 1758//1758 990//990 1850//1850 -f 1758//1758 1850//1850 1759//1759 -f 1759//1759 1850//1850 1851//1851 -f 1759//1759 1851//1851 1760//1760 -f 1760//1760 1851//1851 1852//1852 -f 1760//1760 1852//1852 1761//1761 -f 1761//1761 1852//1852 1853//1853 -f 1761//1761 1853//1853 1762//1762 -f 1762//1762 1853//1853 1854//1854 -f 1762//1762 1854//1854 1232//1232 -f 1232//1232 1854//1854 1002//1002 -f 1232//1232 1002//1002 1234//1234 -f 1234//1234 1002//1002 1000//1000 -f 1234//1234 1000//1000 1236//1236 -f 1236//1236 1000//1000 998//998 -f 1236//1236 998//998 1238//1238 -f 1238//1238 998//998 996//996 -f 1767//1767 1855//1855 1218//1218 -f 1218//1218 1855//1855 988//988 -f 1218//1218 988//988 1220//1220 -f 1220//1220 988//988 986//986 -f 1220//1220 986//986 1222//1222 -f 1222//1222 986//986 984//984 -f 1222//1222 984//984 1224//1224 -f 1224//1224 984//984 982//982 -f 1224//1224 982//982 1226//1226 -f 1226//1226 982//982 980//980 -f 1226//1226 980//980 1228//1228 -f 1228//1228 980//980 978//978 -f 1228//1228 978//978 1230//1230 -f 1230//1230 978//978 976//976 -f 1230//1230 976//976 1763//1763 -f 1763//1763 976//976 1856//1856 -f 1763//1763 1856//1856 1764//1764 -f 1764//1764 1856//1856 1857//1857 -f 1764//1764 1857//1857 1765//1765 -f 1765//1765 1857//1857 1858//1858 -f 1765//1765 1858//1858 1766//1766 -f 1766//1766 1858//1858 1859//1859 -f 1766//1766 1859//1859 1767//1767 -f 1767//1767 1859//1859 1855//1855 -f 1568//1568 1860//1860 1572//1572 -f 1572//1572 1860//1860 1861//1861 -f 1572//1572 1861//1861 1571//1571 -f 1571//1571 1861//1861 1862//1862 -f 1571//1571 1862//1862 1569//1569 -f 1569//1569 1862//1862 1863//1863 -f 1569//1569 1863//1863 1428//1428 -f 1428//1428 1863//1863 974//974 -f 1428//1428 974//974 1430//1430 -f 1430//1430 974//974 972//972 -f 1430//1430 972//972 1432//1432 -f 1432//1432 972//972 970//970 -f 1432//1432 970//970 1434//1434 -f 1434//1434 970//970 968//968 -f 1434//1434 968//968 1436//1436 -f 1436//1436 968//968 966//966 -f 1436//1436 966//966 1438//1438 -f 1438//1438 966//966 964//964 -f 1438//1438 964//964 1440//1440 -f 1440//1440 964//964 962//962 -f 1440//1440 962//962 1566//1566 -f 1566//1566 962//962 1864//1864 -f 1566//1566 1864//1864 1568//1568 -f 1568//1568 1864//1864 1860//1860 -f 1214//1214 950//950 1216//1216 -f 1216//1216 950//950 948//948 -f 1216//1216 948//948 1768//1768 -f 1768//1768 948//948 1865//1865 -f 1768//1768 1865//1865 1769//1769 -f 1769//1769 1865//1865 1866//1866 -f 1769//1769 1866//1866 1770//1770 -f 1770//1770 1866//1866 1867//1867 -f 1770//1770 1867//1867 1771//1771 -f 1771//1771 1867//1867 1868//1868 -f 1771//1771 1868//1868 1772//1772 -f 1772//1772 1868//1868 1869//1869 -f 1772//1772 1869//1869 1204//1204 -f 1204//1204 1869//1869 960//960 -f 1204//1204 960//960 1206//1206 -f 1206//1206 960//960 958//958 -f 1206//1206 958//958 1208//1208 -f 1208//1208 958//958 956//956 -f 1208//1208 956//956 1210//1210 -f 1210//1210 956//956 954//954 -f 1210//1210 954//954 1212//1212 -f 1212//1212 954//954 952//952 -f 1212//1212 952//952 1214//1214 -f 1214//1214 952//952 950//950 -f 1870//1870 1776//1776 1871//1871 -f 1871//1871 1776//1776 1777//1777 -f 1871//1871 1777//1777 1872//1872 -f 1872//1872 1777//1777 1778//1778 -f 1872//1872 1778//1778 945//945 -f 945//945 1778//1778 1187//1187 -f 945//945 1187//1187 943//943 -f 943//943 1187//1187 1189//1189 -f 943//943 1189//1189 941//941 -f 941//941 1189//1189 1191//1191 -f 941//941 1191//1191 939//939 -f 1191//1191 1193//1193 939//939 -f 939//939 1193//1193 1195//1195 -f 939//939 1195//1195 937//937 -f 937//937 1195//1195 1197//1197 -f 937//937 1197//1197 935//935 -f 935//935 1197//1197 1199//1199 -f 935//935 1199//1199 933//933 -f 933//933 1199//1199 1201//1201 -f 933//933 1201//1201 1873//1873 -f 1873//1873 1201//1201 1773//1773 -f 1873//1873 1773//1773 1874//1874 -f 1874//1874 1773//1773 1774//1774 -f 1874//1874 1774//1774 1870//1870 -f 1870//1870 1774//1774 1775//1775 -f 1870//1870 1775//1775 1776//1776 -f 925//925 1178//1178 923//923 -f 923//923 1178//1178 1176//1176 -f 923//923 1176//1176 921//921 -f 921//921 1176//1176 1174//1174 -f 921//921 1174//1174 919//919 -f 919//919 1174//1174 1172//1172 -f 919//919 1172//1172 1875//1875 -f 1875//1875 1172//1172 1784//1784 -f 1875//1875 1784//1784 1876//1876 -f 1876//1876 1784//1784 1783//1783 -f 1876//1876 1783//1783 1877//1877 -f 1783//1783 1782//1782 1877//1877 -f 1877//1877 1782//1782 1781//1781 -f 1877//1877 1781//1781 1878//1878 -f 1878//1878 1781//1781 1780//1780 -f 1878//1878 1780//1780 1879//1879 -f 1879//1879 1780//1780 1779//1779 -f 1879//1879 1779//1779 931//931 -f 931//931 1779//1779 1186//1186 -f 931//931 1186//1186 929//929 -f 929//929 1186//1186 1184//1184 -f 929//929 1184//1184 927//927 -f 927//927 1184//1184 1182//1182 -f 927//927 1182//1182 925//925 -f 925//925 1182//1182 1180//1180 -f 925//925 1180//1180 1178//1178 -f 1794//1794 1880//1880 1158//1158 -f 1158//1158 1880//1880 905//905 -f 1158//1158 905//905 1160//1160 -f 1160//1160 905//905 907//907 -f 1160//1160 907//907 1162//1162 -f 1162//1162 907//907 909//909 -f 1162//1162 909//909 1164//1164 -f 1164//1164 909//909 911//911 -f 1164//1164 911//911 1166//1166 -f 1166//1166 911//911 913//913 -f 1166//1166 913//913 1168//1168 -f 1168//1168 913//913 915//915 -f 1168//1168 915//915 1170//1170 -f 1170//1170 915//915 917//917 -f 1170//1170 917//917 1786//1786 -f 1786//1786 917//917 1881//1881 -f 1786//1786 1881//1881 1788//1788 -f 1788//1788 1881//1881 1882//1882 -f 1788//1788 1882//1882 1790//1790 -f 1790//1790 1882//1882 1883//1883 -f 1790//1790 1883//1883 1792//1792 -f 1792//1792 1883//1883 1884//1884 -f 1792//1792 1884//1884 1794//1794 -f 1794//1794 1884//1884 1880//1880 -f 1155//1155 1156//1156 1795//1795 -f 1795//1795 1156//1156 1885//1885 -f 1795//1795 1885//1885 1796//1796 -f 1796//1796 1885//1885 1886//1886 -f 1796//1796 1886//1886 1797//1797 -f 1797//1797 1886//1886 1887//1887 -f 1797//1797 1887//1887 1798//1798 -f 1798//1798 1887//1887 1888//1888 -f 1798//1798 1888//1888 1799//1799 -f 1799//1799 1888//1888 1889//1889 -f 1799//1799 1889//1889 1143//1143 -f 1143//1143 1889//1889 1144//1144 -f 1141//1141 1142//1142 1800//1800 -f 1800//1800 1142//1142 1890//1890 -f 1800//1800 1890//1890 1801//1801 -f 1801//1801 1890//1890 1891//1891 -f 1801//1801 1891//1891 1802//1802 -f 1802//1802 1891//1891 1892//1892 -f 1802//1802 1892//1892 1803//1803 -f 1803//1803 1892//1892 1893//1893 -f 1803//1803 1893//1893 1804//1804 -f 1804//1804 1893//1893 1894//1894 -f 1804//1804 1894//1894 1129//1129 -f 1129//1129 1894//1894 1130//1130 -f 1127//1127 1128//1128 1805//1805 -f 1805//1805 1128//1128 1895//1895 -f 1805//1805 1895//1895 1806//1806 -f 1806//1806 1895//1895 1896//1896 -f 1806//1806 1896//1896 1807//1807 -f 1807//1807 1896//1896 1897//1897 -f 1807//1807 1897//1897 1808//1808 -f 1808//1808 1897//1897 1898//1898 -f 1808//1808 1898//1898 1809//1809 -f 1809//1809 1898//1898 1899//1899 -f 1809//1809 1899//1899 1115//1115 -f 1115//1115 1899//1899 1116//1116 -f 1113//1113 1114//1114 1813//1813 -f 1813//1813 1114//1114 1900//1900 -f 1813//1813 1900//1900 1814//1814 -f 1814//1814 1900//1900 1901//1901 -f 1814//1814 1901//1901 1810//1810 -f 1810//1810 1901//1901 1902//1902 -f 1810//1810 1902//1902 1811//1811 -f 1811//1811 1902//1902 1903//1903 -f 1811//1811 1903//1903 1812//1812 -f 1812//1812 1903//1903 1904//1904 -f 1812//1812 1904//1904 1101//1101 -f 1101//1101 1904//1904 1102//1102 -f 1099//1099 1100//1100 1815//1815 -f 1815//1815 1100//1100 1905//1905 -f 1815//1815 1905//1905 1816//1816 -f 1816//1816 1905//1905 1906//1906 -f 1816//1816 1906//1906 1817//1817 -f 1817//1817 1906//1906 1907//1907 -f 1817//1817 1907//1907 1818//1818 -f 1818//1818 1907//1907 1908//1908 -f 1818//1818 1908//1908 1819//1819 -f 1819//1819 1908//1908 1909//1909 -f 1819//1819 1909//1909 1087//1087 -f 1087//1087 1909//1909 1088//1088 -f 1085//1085 1086//1086 1821//1821 -f 1821//1821 1086//1086 1910//1910 -f 1821//1821 1910//1910 1822//1822 -f 1822//1822 1910//1910 1911//1911 -f 1822//1822 1911//1911 1823//1823 -f 1823//1823 1911//1911 1912//1912 -f 1823//1823 1912//1912 1824//1824 -f 1824//1824 1912//1912 1913//1913 -f 1824//1824 1913//1913 1820//1820 -f 1820//1820 1913//1913 1914//1914 -f 1820//1820 1914//1914 1073//1073 -f 1073//1073 1914//1914 1074//1074 -f 1071//1071 1072//1072 1825//1825 -f 1825//1825 1072//1072 1915//1915 -f 1825//1825 1915//1915 1826//1826 -f 1826//1826 1915//1915 1916//1916 -f 1826//1826 1916//1916 1827//1827 -f 1827//1827 1916//1916 1917//1917 -f 1827//1827 1917//1917 1828//1828 -f 1828//1828 1917//1917 1918//1918 -f 1828//1828 1918//1918 1829//1829 -f 1829//1829 1918//1918 1919//1919 -f 1829//1829 1919//1919 1059//1059 -f 1059//1059 1919//1919 1060//1060 -f 1057//1057 1058//1058 1830//1830 -f 1830//1830 1058//1058 1920//1920 -f 1830//1830 1920//1920 1831//1831 -f 1831//1831 1920//1920 1921//1921 -f 1831//1831 1921//1921 1832//1832 -f 1832//1832 1921//1921 1922//1922 -f 1832//1832 1922//1922 1833//1833 -f 1833//1833 1922//1922 1923//1923 -f 1833//1833 1923//1923 1834//1834 -f 1834//1834 1923//1923 1924//1924 -f 1834//1834 1924//1924 1045//1045 -f 1045//1045 1924//1924 1046//1046 -f 1043//1043 1044//1044 1835//1835 -f 1835//1835 1044//1044 1925//1925 -f 1835//1835 1925//1925 1836//1836 -f 1836//1836 1925//1925 1926//1926 -f 1836//1836 1926//1926 1837//1837 -f 1837//1837 1926//1926 1927//1927 -f 1837//1837 1927//1927 1838//1838 -f 1838//1838 1927//1927 1928//1928 -f 1838//1838 1928//1928 1839//1839 -f 1839//1839 1928//1928 1929//1929 -f 1839//1839 1929//1929 1031//1031 -f 1031//1031 1929//1929 1032//1032 -f 1029//1029 1030//1030 1842//1842 -f 1842//1842 1030//1030 1930//1930 -f 1842//1842 1930//1930 1843//1843 -f 1843//1843 1930//1930 1931//1931 -f 1843//1843 1931//1931 1844//1844 -f 1844//1844 1931//1931 1932//1932 -f 1844//1844 1932//1932 1840//1840 -f 1840//1840 1932//1932 1933//1933 -f 1840//1840 1933//1933 1841//1841 -f 1841//1841 1933//1933 1934//1934 -f 1841//1841 1934//1934 1017//1017 -f 1017//1017 1934//1934 1018//1018 -f 1015//1015 1016//1016 1845//1845 -f 1845//1845 1016//1016 1935//1935 -f 1845//1845 1935//1935 1846//1846 -f 1846//1846 1935//1935 1936//1936 -f 1846//1846 1936//1936 1847//1847 -f 1847//1847 1936//1936 1937//1937 -f 1847//1847 1937//1937 1848//1848 -f 1848//1848 1937//1937 1938//1938 -f 1848//1848 1938//1938 1849//1849 -f 1849//1849 1938//1938 1939//1939 -f 1849//1849 1939//1939 1003//1003 -f 1003//1003 1939//1939 1004//1004 -f 1001//1001 1002//1002 1940//1940 -f 1940//1940 1002//1002 1854//1854 -f 1940//1940 1854//1854 1941//1941 -f 1941//1941 1854//1854 1853//1853 -f 1941//1941 1853//1853 1942//1942 -f 1942//1942 1853//1853 1852//1852 -f 1942//1942 1852//1852 1943//1943 -f 1943//1943 1852//1852 1851//1851 -f 1943//1943 1851//1851 1944//1944 -f 1944//1944 1851//1851 1850//1850 -f 1944//1944 1850//1850 989//989 -f 989//989 1850//1850 990//990 -f 987//987 988//988 1945//1945 -f 1945//1945 988//988 1855//1855 -f 1945//1945 1855//1855 1946//1946 -f 1946//1946 1855//1855 1859//1859 -f 1946//1946 1859//1859 1947//1947 -f 1947//1947 1859//1859 1858//1858 -f 1947//1947 1858//1858 1948//1948 -f 1948//1948 1858//1858 1857//1857 -f 1948//1948 1857//1857 1949//1949 -f 1949//1949 1857//1857 1856//1856 -f 1949//1949 1856//1856 975//975 -f 975//975 1856//1856 976//976 -f 973//973 974//974 1950//1950 -f 1950//1950 974//974 1863//1863 -f 1950//1950 1863//1863 1951//1951 -f 1951//1951 1863//1863 1862//1862 -f 1951//1951 1862//1862 1952//1952 -f 1952//1952 1862//1862 1861//1861 -f 1952//1952 1861//1861 1953//1953 -f 1953//1953 1861//1861 1860//1860 -f 1953//1953 1860//1860 1954//1954 -f 1954//1954 1860//1860 1864//1864 -f 1954//1954 1864//1864 961//961 -f 961//961 1864//1864 962//962 -f 959//959 960//960 1955//1955 -f 1955//1955 960//960 1869//1869 -f 1955//1955 1869//1869 1956//1956 -f 1956//1956 1869//1869 1868//1868 -f 1956//1956 1868//1868 1957//1957 -f 1957//1957 1868//1868 1867//1867 -f 1957//1957 1867//1867 1958//1958 -f 1958//1958 1867//1867 1866//1866 -f 1958//1958 1866//1866 1959//1959 -f 1959//1959 1866//1866 1865//1865 -f 1959//1959 1865//1865 947//947 -f 947//947 1865//1865 948//948 -f 945//945 946//946 1872//1872 -f 1872//1872 946//946 1960//1960 -f 1872//1872 1960//1960 1871//1871 -f 1871//1871 1960//1960 1961//1961 -f 1871//1871 1961//1961 1870//1870 -f 1870//1870 1961//1961 1962//1962 -f 1870//1870 1962//1962 1874//1874 -f 1874//1874 1962//1962 1963//1963 -f 1874//1874 1963//1963 1873//1873 -f 1873//1873 1963//1963 1964//1964 -f 1873//1873 1964//1964 933//933 -f 933//933 1964//1964 934//934 -f 931//931 932//932 1879//1879 -f 1879//1879 932//932 1965//1965 -f 1879//1879 1965//1965 1878//1878 -f 1878//1878 1965//1965 1966//1966 -f 1878//1878 1966//1966 1877//1877 -f 1877//1877 1966//1966 1967//1967 -f 1877//1877 1967//1967 1876//1876 -f 1876//1876 1967//1967 1968//1968 -f 1876//1876 1968//1968 1875//1875 -f 1875//1875 1968//1968 1969//1969 -f 1875//1875 1969//1969 919//919 -f 919//919 1969//1969 920//920 -f 917//917 918//918 1881//1881 -f 1881//1881 918//918 1970//1970 -f 1881//1881 1970//1970 1882//1882 -f 1882//1882 1970//1970 1971//1971 -f 1882//1882 1971//1971 1883//1883 -f 1883//1883 1971//1971 1972//1972 -f 1883//1883 1972//1972 1884//1884 -f 1884//1884 1972//1972 1973//1973 -f 1884//1884 1973//1973 1880//1880 -f 1880//1880 1973//1973 1974//1974 -f 1880//1880 1974//1974 905//905 -f 905//905 1974//1974 906//906 -f 1975//1975 1889//1889 1976//1976 -f 1976//1976 1889//1889 1888//1888 -f 1976//1976 1888//1888 1977//1977 -f 1977//1977 1888//1888 1887//1887 -f 1977//1977 1887//1887 1978//1978 -f 1978//1978 1887//1887 1886//1886 -f 1978//1978 1886//1886 1979//1979 -f 1979//1979 1886//1886 1885//1885 -f 1979//1979 1885//1885 903//903 -f 903//903 1885//1885 1156//1156 -f 903//903 1156//1156 901//901 -f 901//901 1156//1156 1154//1154 -f 901//901 1154//1154 899//899 -f 899//899 1154//1154 1152//1152 -f 899//899 1152//1152 897//897 -f 897//897 1152//1152 1150//1150 -f 897//897 1150//1150 895//895 -f 895//895 1150//1150 1148//1148 -f 895//895 1148//1148 893//893 -f 893//893 1148//1148 1146//1146 -f 893//893 1146//1146 891//891 -f 891//891 1146//1146 1144//1144 -f 891//891 1144//1144 1975//1975 -f 1975//1975 1144//1144 1889//1889 -f 1980//1980 1893//1893 1981//1981 -f 1981//1981 1893//1893 1892//1892 -f 1981//1981 1892//1892 1982//1982 -f 1982//1982 1892//1892 1891//1891 -f 1982//1982 1891//1891 1983//1983 -f 1983//1983 1891//1891 1890//1890 -f 1983//1983 1890//1890 889//889 -f 889//889 1890//1890 1142//1142 -f 889//889 1142//1142 887//887 -f 887//887 1142//1142 1140//1140 -f 887//887 1140//1140 885//885 -f 885//885 1140//1140 1138//1138 -f 885//885 1138//1138 883//883 -f 883//883 1138//1138 1136//1136 -f 883//883 1136//1136 881//881 -f 881//881 1136//1136 1134//1134 -f 881//881 1134//1134 879//879 -f 879//879 1134//1134 1132//1132 -f 879//879 1132//1132 877//877 -f 877//877 1132//1132 1130//1130 -f 877//877 1130//1130 1984//1984 -f 1984//1984 1130//1130 1894//1894 -f 1984//1984 1894//1894 1980//1980 -f 1980//1980 1894//1894 1893//1893 -f 1985//1985 1899//1899 1986//1986 -f 1986//1986 1899//1899 1898//1898 -f 1986//1986 1898//1898 1987//1987 -f 1987//1987 1898//1898 1897//1897 -f 1987//1987 1897//1897 1988//1988 -f 1988//1988 1897//1897 1896//1896 -f 1988//1988 1896//1896 1989//1989 -f 1989//1989 1896//1896 1895//1895 -f 1989//1989 1895//1895 875//875 -f 875//875 1895//1895 1128//1128 -f 875//875 1128//1128 873//873 -f 873//873 1128//1128 1126//1126 -f 873//873 1126//1126 871//871 -f 871//871 1126//1126 1124//1124 -f 871//871 1124//1124 869//869 -f 869//869 1124//1124 1122//1122 -f 869//869 1122//1122 867//867 -f 867//867 1122//1122 1120//1120 -f 867//867 1120//1120 865//865 -f 865//865 1120//1120 1118//1118 -f 865//865 1118//1118 863//863 -f 863//863 1118//1118 1116//1116 -f 863//863 1116//1116 1985//1985 -f 1985//1985 1116//1116 1899//1899 -f 859//859 861//861 849//849 -f 1990//1990 1991//1991 849//849 -f 857//857 859//859 855//855 -f 855//855 859//859 849//849 -f 855//855 849//849 853//853 -f 853//853 849//849 851//851 -f 1992//1992 1990//1990 1993//1993 -f 1993//1993 1990//1990 849//849 -f 1993//1993 849//849 1994//1994 -f 1994//1994 849//849 861//861 -f 1995//1995 1904//1904 1996//1996 -f 1996//1996 1904//1904 1903//1903 -f 1996//1996 1903//1903 1997//1997 -f 1997//1997 1903//1903 1902//1902 -f 1997//1997 1902//1902 1998//1998 -f 1998//1998 1902//1902 1901//1901 -f 1998//1998 1901//1901 1999//1999 -f 1999//1999 1901//1901 1900//1900 -f 1999//1999 1900//1900 847//847 -f 847//847 1900//1900 1114//1114 -f 847//847 1114//1114 845//845 -f 845//845 1114//1114 1112//1112 -f 845//845 1112//1112 843//843 -f 843//843 1112//1112 1110//1110 -f 843//843 1110//1110 841//841 -f 841//841 1110//1110 1108//1108 -f 841//841 1108//1108 839//839 -f 839//839 1108//1108 1106//1106 -f 839//839 1106//1106 837//837 -f 837//837 1106//1106 1104//1104 -f 837//837 1104//1104 835//835 -f 835//835 1104//1104 1102//1102 -f 835//835 1102//1102 1995//1995 -f 1995//1995 1102//1102 1904//1904 -f 831//831 1098//1098 829//829 -f 829//829 1098//1098 1096//1096 -f 829//829 1096//1096 827//827 -f 827//827 1096//1096 1094//1094 -f 827//827 1094//1094 825//825 -f 825//825 1094//1094 1092//1092 -f 825//825 1092//1092 823//823 -f 823//823 1092//1092 1090//1090 -f 823//823 1090//1090 821//821 -f 821//821 1090//1090 1088//1088 -f 821//821 1088//1088 2000//2000 -f 2000//2000 1088//1088 1909//1909 -f 2000//2000 1909//1909 2001//2001 -f 2001//2001 1909//1909 1908//1908 -f 2001//2001 1908//1908 2002//2002 -f 2002//2002 1908//1908 1907//1907 -f 2002//2002 1907//1907 2003//2003 -f 2003//2003 1907//1907 1906//1906 -f 2003//2003 1906//1906 2004//2004 -f 2004//2004 1906//1906 1905//1905 -f 2004//2004 1905//1905 833//833 -f 833//833 1905//1905 1100//1100 -f 833//833 1100//1100 831//831 -f 831//831 1100//1100 1098//1098 -f 2005//2005 1910//1910 819//819 -f 819//819 1910//1910 1086//1086 -f 819//819 1086//1086 817//817 -f 817//817 1086//1086 1084//1084 -f 817//817 1084//1084 815//815 -f 815//815 1084//1084 1082//1082 -f 815//815 1082//1082 813//813 -f 813//813 1082//1082 1080//1080 -f 813//813 1080//1080 811//811 -f 811//811 1080//1080 1078//1078 -f 811//811 1078//1078 809//809 -f 809//809 1078//1078 1076//1076 -f 809//809 1076//1076 807//807 -f 807//807 1076//1076 1074//1074 -f 807//807 1074//1074 2006//2006 -f 2006//2006 1074//1074 1914//1914 -f 2006//2006 1914//1914 2007//2007 -f 2007//2007 1914//1914 1913//1913 -f 2007//2007 1913//1913 2008//2008 -f 2008//2008 1913//1913 1912//1912 -f 2008//2008 1912//1912 2009//2009 -f 2009//2009 1912//1912 1911//1911 -f 2009//2009 1911//1911 2005//2005 -f 2005//2005 1911//1911 1910//1910 -f 2010//2010 2011//2011 793//793 -f 793//793 795//795 805//805 -f 805//805 795//795 797//797 -f 2012//2012 2010//2010 2013//2013 -f 2013//2013 2010//2010 793//793 -f 2013//2013 793//793 2014//2014 -f 2014//2014 793//793 805//805 -f 797//797 799//799 805//805 -f 805//805 799//799 801//801 -f 805//805 801//801 803//803 -f 2015//2015 1919//1919 2016//2016 -f 2016//2016 1919//1919 1918//1918 -f 2016//2016 1918//1918 2017//2017 -f 2017//2017 1918//1918 1917//1917 -f 2017//2017 1917//1917 2018//2018 -f 2018//2018 1917//1917 1916//1916 -f 2018//2018 1916//1916 2019//2019 -f 2019//2019 1916//1916 1915//1915 -f 2019//2019 1915//1915 791//791 -f 791//791 1915//1915 1072//1072 -f 791//791 1072//1072 789//789 -f 789//789 1072//1072 1070//1070 -f 789//789 1070//1070 787//787 -f 787//787 1070//1070 1068//1068 -f 787//787 1068//1068 785//785 -f 785//785 1068//1068 1066//1066 -f 785//785 1066//1066 783//783 -f 783//783 1066//1066 1064//1064 -f 783//783 1064//1064 781//781 -f 781//781 1064//1064 1062//1062 -f 781//781 1062//1062 779//779 -f 779//779 1062//1062 1060//1060 -f 779//779 1060//1060 2015//2015 -f 2015//2015 1060//1060 1919//1919 -f 775//775 777//777 765//765 -f 765//765 777//777 2020//2020 -f 2021//2021 2022//2022 2023//2023 -f 2023//2023 2022//2022 765//765 -f 2023//2023 765//765 2024//2024 -f 2024//2024 765//765 2020//2020 -f 773//773 775//775 771//771 -f 771//771 775//775 765//765 -f 771//771 765//765 769//769 -f 769//769 765//765 767//767 -f 2025//2025 1920//1920 763//763 -f 763//763 1920//1920 1058//1058 -f 763//763 1058//1058 761//761 -f 761//761 1058//1058 1056//1056 -f 761//761 1056//1056 759//759 -f 759//759 1056//1056 1054//1054 -f 759//759 1054//1054 757//757 -f 757//757 1054//1054 1052//1052 -f 757//757 1052//1052 755//755 -f 755//755 1052//1052 1050//1050 -f 755//755 1050//1050 753//753 -f 753//753 1050//1050 1048//1048 -f 753//753 1048//1048 751//751 -f 751//751 1048//1048 1046//1046 -f 751//751 1046//1046 2026//2026 -f 2026//2026 1046//1046 1924//1924 -f 2026//2026 1924//1924 2027//2027 -f 2027//2027 1924//1924 1923//1923 -f 2027//2027 1923//1923 2028//2028 -f 2028//2028 1923//1923 1922//1922 -f 2028//2028 1922//1922 2029//2029 -f 2029//2029 1922//1922 1921//1921 -f 2029//2029 1921//1921 2025//2025 -f 2025//2025 1921//1921 1920//1920 -f 749//749 1044//1044 747//747 -f 747//747 1044//1044 1042//1042 -f 747//747 1042//1042 745//745 -f 745//745 1042//1042 1040//1040 -f 745//745 1040//1040 743//743 -f 743//743 1040//1040 1038//1038 -f 743//743 1038//1038 741//741 -f 741//741 1038//1038 1036//1036 -f 741//741 1036//1036 739//739 -f 739//739 1036//1036 1034//1034 -f 739//739 1034//1034 737//737 -f 737//737 1034//1034 1032//1032 -f 737//737 1032//1032 2030//2030 -f 2030//2030 1032//1032 1929//1929 -f 2030//2030 1929//1929 2031//2031 -f 2031//2031 1929//1929 1928//1928 -f 2031//2031 1928//1928 2032//2032 -f 2032//2032 1928//1928 1927//1927 -f 2032//2032 1927//1927 2033//2033 -f 2033//2033 1927//1927 1926//1926 -f 2033//2033 1926//1926 2034//2034 -f 2034//2034 1926//1926 1925//1925 -f 2034//2034 1925//1925 749//749 -f 749//749 1925//1925 1044//1044 -f 2035//2035 1933//1933 2036//2036 -f 2036//2036 1933//1933 1932//1932 -f 2036//2036 1932//1932 2037//2037 -f 2037//2037 1932//1932 1931//1931 -f 2037//2037 1931//1931 2038//2038 -f 2038//2038 1931//1931 1930//1930 -f 2038//2038 1930//1930 735//735 -f 735//735 1930//1930 1030//1030 -f 735//735 1030//1030 733//733 -f 733//733 1030//1030 1028//1028 -f 733//733 1028//1028 731//731 -f 731//731 1028//1028 1026//1026 -f 731//731 1026//1026 729//729 -f 729//729 1026//1026 1024//1024 -f 729//729 1024//1024 727//727 -f 727//727 1024//1024 1022//1022 -f 727//727 1022//1022 725//725 -f 725//725 1022//1022 1020//1020 -f 725//725 1020//1020 723//723 -f 723//723 1020//1020 1018//1018 -f 723//723 1018//1018 2039//2039 -f 2039//2039 1018//1018 1934//1934 -f 2039//2039 1934//1934 2035//2035 -f 2035//2035 1934//1934 1933//1933 -f 2040//2040 1935//1935 721//721 -f 721//721 1935//1935 1016//1016 -f 721//721 1016//1016 719//719 -f 719//719 1016//1016 1014//1014 -f 719//719 1014//1014 717//717 -f 717//717 1014//1014 1012//1012 -f 717//717 1012//1012 715//715 -f 715//715 1012//1012 1010//1010 -f 715//715 1010//1010 713//713 -f 713//713 1010//1010 1008//1008 -f 713//713 1008//1008 711//711 -f 711//711 1008//1008 1006//1006 -f 711//711 1006//1006 709//709 -f 709//709 1006//1006 1004//1004 -f 709//709 1004//1004 2041//2041 -f 2041//2041 1004//1004 1939//1939 -f 2041//2041 1939//1939 2042//2042 -f 2042//2042 1939//1939 1938//1938 -f 2042//2042 1938//1938 2043//2043 -f 2043//2043 1938//1938 1937//1937 -f 2043//2043 1937//1937 2044//2044 -f 2044//2044 1937//1937 1936//1936 -f 2044//2044 1936//1936 2040//2040 -f 2040//2040 1936//1936 1935//1935 -f 2045//2045 1942//1942 2046//2046 -f 2046//2046 1942//1942 1943//1943 -f 2046//2046 1943//1943 2047//2047 -f 2047//2047 1943//1943 1944//1944 -f 2047//2047 1944//1944 707//707 -f 707//707 1944//1944 989//989 -f 707//707 989//989 705//705 -f 705//705 989//989 991//991 -f 705//705 991//991 703//703 -f 703//703 991//991 993//993 -f 703//703 993//993 701//701 -f 701//701 993//993 995//995 -f 701//701 995//995 699//699 -f 699//699 995//995 997//997 -f 699//699 997//997 697//697 -f 697//697 997//997 999//999 -f 697//697 999//999 695//695 -f 695//695 999//999 1001//1001 -f 695//695 1001//1001 2048//2048 -f 2048//2048 1001//1001 1940//1940 -f 2048//2048 1940//1940 2049//2049 -f 2049//2049 1940//1940 1941//1941 -f 2049//2049 1941//1941 2045//2045 -f 2045//2045 1941//1941 1942//1942 -f 689//689 979//979 687//687 -f 687//687 979//979 981//981 -f 687//687 981//981 685//685 -f 685//685 981//981 983//983 -f 685//685 983//983 683//683 -f 683//683 983//983 985//985 -f 683//683 985//985 681//681 -f 681//681 985//985 987//987 -f 681//681 987//987 2050//2050 -f 2050//2050 987//987 1945//1945 -f 2050//2050 1945//1945 2051//2051 -f 2051//2051 1945//1945 1946//1946 -f 2051//2051 1946//1946 2052//2052 -f 2052//2052 1946//1946 1947//1947 -f 2052//2052 1947//1947 2053//2053 -f 2053//2053 1947//1947 1948//1948 -f 2053//2053 1948//1948 2054//2054 -f 2054//2054 1948//1948 1949//1949 -f 2054//2054 1949//1949 693//693 -f 693//693 1949//1949 975//975 -f 693//693 975//975 691//691 -f 691//691 975//975 977//977 -f 691//691 977//977 689//689 -f 689//689 977//977 979//979 -f 2055//2055 1951//1951 2056//2056 -f 2056//2056 1951//1951 1952//1952 -f 2056//2056 1952//1952 2057//2057 -f 2057//2057 1952//1952 1953//1953 -f 2057//2057 1953//1953 2058//2058 -f 2058//2058 1953//1953 1954//1954 -f 2058//2058 1954//1954 679//679 -f 679//679 1954//1954 961//961 -f 679//679 961//961 677//677 -f 677//677 961//961 963//963 -f 677//677 963//963 675//675 -f 675//675 963//963 965//965 -f 675//675 965//965 673//673 -f 673//673 965//965 967//967 -f 673//673 967//967 671//671 -f 671//671 967//967 969//969 -f 671//671 969//969 669//669 -f 669//669 969//969 971//971 -f 669//669 971//971 667//667 -f 667//667 971//971 973//973 -f 667//667 973//973 2059//2059 -f 2059//2059 973//973 1950//1950 -f 2059//2059 1950//1950 2055//2055 -f 2055//2055 1950//1950 1951//1951 -f 663//663 949//949 661//661 -f 661//661 949//949 951//951 -f 661//661 951//951 659//659 -f 659//659 951//951 953//953 -f 659//659 953//953 657//657 -f 657//657 953//953 955//955 -f 657//657 955//955 655//655 -f 655//655 955//955 957//957 -f 655//655 957//957 653//653 -f 653//653 957//957 959//959 -f 653//653 959//959 2060//2060 -f 2060//2060 959//959 1955//1955 -f 2060//2060 1955//1955 2061//2061 -f 2061//2061 1955//1955 1956//1956 -f 2061//2061 1956//1956 2062//2062 -f 2062//2062 1956//1956 1957//1957 -f 2062//2062 1957//1957 2063//2063 -f 2063//2063 1957//1957 1958//1958 -f 2063//2063 1958//1958 2064//2064 -f 2064//2064 1958//1958 1959//1959 -f 2064//2064 1959//1959 665//665 -f 665//665 1959//1959 947//947 -f 665//665 947//947 663//663 -f 663//663 947//947 949//949 -f 942//942 647//647 944//944 -f 944//944 647//647 649//649 -f 944//944 649//649 946//946 -f 938//938 641//641 940//940 -f 940//940 641//641 643//643 -f 940//940 643//643 942//942 -f 942//942 643//643 645//645 -f 942//942 645//645 647//647 -f 1963//1963 2065//2065 1964//1964 -f 1964//1964 2065//2065 2066//2066 -f 1964//1964 2066//2066 934//934 -f 934//934 2066//2066 633//633 -f 934//934 633//633 936//936 -f 1961//1961 2067//2067 1962//1962 -f 1962//1962 2067//2067 2068//2068 -f 1962//1962 2068//2068 1963//1963 -f 1963//1963 2068//2068 2069//2069 -f 1963//1963 2069//2069 2065//2065 -f 649//649 651//651 946//946 -f 946//946 651//651 2070//2070 -f 946//946 2070//2070 1960//1960 -f 1960//1960 2070//2070 2071//2071 -f 1960//1960 2071//2071 1961//1961 -f 1961//1961 2071//2071 2072//2072 -f 1961//1961 2072//2072 2067//2067 -f 633//633 635//635 936//936 -f 936//936 635//635 637//637 -f 936//936 637//637 938//938 -f 938//938 637//637 639//639 -f 938//938 639//639 641//641 -f 928//928 627//627 930//930 -f 930//930 627//627 629//629 -f 930//930 629//629 932//932 -f 932//932 629//629 631//631 -f 932//932 631//631 1965//1965 -f 924//924 621//621 926//926 -f 926//926 621//621 623//623 -f 926//926 623//623 928//928 -f 928//928 623//623 625//625 -f 928//928 625//625 627//627 -f 922//922 617//617 924//924 -f 924//924 617//617 619//619 -f 924//924 619//619 621//621 -f 1966//1966 2073//2073 1967//1967 -f 1967//1967 2073//2073 2074//2074 -f 1967//1967 2074//2074 1968//1968 -f 631//631 2075//2075 1965//1965 -f 1965//1965 2075//2075 2076//2076 -f 1965//1965 2076//2076 1966//1966 -f 1966//1966 2076//2076 2077//2077 -f 1966//1966 2077//2077 2073//2073 -f 2074//2074 2078//2078 1968//1968 -f 1968//1968 2078//2078 2079//2079 -f 1968//1968 2079//2079 1969//1969 -f 1969//1969 2079//2079 2080//2080 -f 1969//1969 2080//2080 920//920 -f 920//920 2080//2080 613//613 -f 920//920 613//613 922//922 -f 922//922 613//613 615//615 -f 922//922 615//615 617//617 -f 2081//2081 2082//2082 2083//2083 -f 2082//2082 2084//2084 2085//2085 -f 2086//2086 2087//2087 2088//2088 -f 2085//2085 2087//2087 2086//2086 -f 2082//2082 2085//2085 2083//2083 -f 2083//2083 2085//2085 2086//2086 -f 2083//2083 2086//2086 2089//2089 -f 2084//2084 2087//2087 2085//2085 -f 2088//2088 2090//2090 2086//2086 -f 2086//2086 2090//2090 2091//2091 -f 2086//2086 2091//2091 2089//2089 -f 2089//2089 2091//2091 2092//2092 -f 2089//2089 2092//2092 2093//2093 -f 2081//2081 2083//2083 2094//2094 -f 2094//2094 2083//2083 2089//2089 -f 2094//2094 2089//2089 2095//2095 -f 2095//2095 2089//2089 2093//2093 -f 2095//2095 2093//2093 2096//2096 -f 2097//2097 2098//2098 2099//2099 -f 2100//2100 2101//2101 2102//2102 -f 2098//2098 2103//2103 2099//2099 -f 2099//2099 2103//2103 2102//2102 -f 2099//2099 2102//2102 2104//2104 -f 2104//2104 2102//2102 2101//2101 -f 2104//2104 2101//2101 2105//2105 -f 2097//2097 2099//2099 2106//2106 -f 2106//2106 2099//2099 2104//2104 -f 2106//2106 2104//2104 2107//2107 -f 2107//2107 2104//2104 2105//2105 -f 2107//2107 2105//2105 2108//2108 -f 2103//2103 2100//2100 2102//2102 -f 2098//2098 2109//2109 2103//2103 -f 2103//2103 2109//2109 2100//2100 -f 2110//2110 2111//2111 2112//2112 -f 2113//2113 2114//2114 2115//2115 -f 2111//2111 2116//2116 2112//2112 -f 2112//2112 2116//2116 2115//2115 -f 2112//2112 2115//2115 2117//2117 -f 2117//2117 2115//2115 2114//2114 -f 2117//2117 2114//2114 2118//2118 -f 2110//2110 2112//2112 2119//2119 -f 2119//2119 2112//2112 2117//2117 -f 2119//2119 2117//2117 2120//2120 -f 2120//2120 2117//2117 2118//2118 -f 2120//2120 2118//2118 2121//2121 -f 2116//2116 2113//2113 2115//2115 -f 2111//2111 2122//2122 2116//2116 -f 2116//2116 2122//2122 2113//2113 -f 2123//2123 1974//1974 2124//2124 -f 2124//2124 1974//1974 1973//1973 -f 2124//2124 1973//1973 2125//2125 -f 2125//2125 1973//1973 1972//1972 -f 2125//2125 1972//1972 2126//2126 -f 2126//2126 1972//1972 1971//1971 -f 2126//2126 1971//1971 2127//2127 -f 2127//2127 1971//1971 1970//1970 -f 2127//2127 1970//1970 611//611 -f 611//611 1970//1970 918//918 -f 611//611 918//918 609//609 -f 609//609 918//918 916//916 -f 609//609 916//916 607//607 -f 607//607 916//916 914//914 -f 607//607 914//914 605//605 -f 605//605 914//914 912//912 -f 605//605 912//912 603//603 -f 603//603 912//912 910//910 -f 603//603 910//910 601//601 -f 601//601 910//910 908//908 -f 601//601 908//908 599//599 -f 599//599 908//908 906//906 -f 599//599 906//906 2123//2123 -f 2123//2123 906//906 1974//1974 -f 2128//2128 2129//2129 2130//2130 -f 2131//2131 2132//2132 2133//2133 -f 2129//2129 2134//2134 2130//2130 -f 2130//2130 2134//2134 2133//2133 -f 2130//2130 2133//2133 2135//2135 -f 2135//2135 2133//2133 2132//2132 -f 2135//2135 2132//2132 2136//2136 -f 2128//2128 2130//2130 2137//2137 -f 2137//2137 2130//2130 2135//2135 -f 2137//2137 2135//2135 2138//2138 -f 2138//2138 2135//2135 2136//2136 -f 2138//2138 2136//2136 2139//2139 -f 2134//2134 2131//2131 2133//2133 -f 2129//2129 2140//2140 2134//2134 -f 2134//2134 2140//2140 2131//2131 -f 2141//2141 2142//2142 585//585 -f 2141//2141 585//585 597//597 -f 597//597 585//585 587//587 -f 597//597 587//587 589//589 -f 2142//2142 2143//2143 585//585 -f 585//585 2143//2143 2144//2144 -f 585//585 2144//2144 2145//2145 -f 589//589 591//591 597//597 -f 597//597 591//591 593//593 -f 597//597 593//593 595//595 -f 2146//2146 2147//2147 2148//2148 -f 2148//2148 2147//2147 2149//2149 -f 2150//2150 2151//2151 2152//2152 -f 2152//2152 2151//2151 2153//2153 -f 2152//2152 2153//2153 2149//2149 -f 2149//2149 2153//2153 2154//2154 -f 2149//2149 2154//2154 2148//2148 -f 2150//2150 2152//2152 2155//2155 -f 2155//2155 2152//2152 2156//2156 -f 2155//2155 2156//2156 2157//2157 -f 2157//2157 2156//2156 2158//2158 -f 2158//2158 2156//2156 2159//2159 -f 903//903 904//904 1979//1979 -f 1979//1979 904//904 2160//2160 -f 1979//1979 2160//2160 1978//1978 -f 1978//1978 2160//2160 2161//2161 -f 1978//1978 2161//2161 1977//1977 -f 1977//1977 2161//2161 2162//2162 -f 1977//1977 2162//2162 1976//1976 -f 1976//1976 2162//2162 2163//2163 -f 1976//1976 2163//2163 1975//1975 -f 1975//1975 2163//2163 2164//2164 -f 1975//1975 2164//2164 891//891 -f 891//891 2164//2164 892//892 -f 889//889 890//890 1983//1983 -f 1983//1983 890//890 2165//2165 -f 1983//1983 2165//2165 1982//1982 -f 1982//1982 2165//2165 2166//2166 -f 1982//1982 2166//2166 1981//1981 -f 1981//1981 2166//2166 2167//2167 -f 1981//1981 2167//2167 1980//1980 -f 1980//1980 2167//2167 2168//2168 -f 1980//1980 2168//2168 1984//1984 -f 1984//1984 2168//2168 2169//2169 -f 1984//1984 2169//2169 877//877 -f 877//877 2169//2169 878//878 -f 2170//2170 2171//2171 2172//2172 -f 2172//2172 2173//2173 2170//2170 -f 2170//2170 2173//2173 2174//2174 -f 2170//2170 2174//2174 2175//2175 -f 2174//2174 2176//2176 2175//2175 -f 2175//2175 2176//2176 2177//2177 -f 2175//2175 2177//2177 2159//2159 -f 2159//2159 2177//2177 2178//2178 -f 2159//2159 2178//2178 2158//2158 -f 875//875 876//876 1989//1989 -f 1989//1989 876//876 2179//2179 -f 1989//1989 2179//2179 1988//1988 -f 1988//1988 2179//2179 2180//2180 -f 1988//1988 2180//2180 1987//1987 -f 1987//1987 2180//2180 2181//2181 -f 1987//1987 2181//2181 1986//1986 -f 1986//1986 2181//2181 2182//2182 -f 1986//1986 2182//2182 1985//1985 -f 1985//1985 2182//2182 2183//2183 -f 1985//1985 2183//2183 863//863 -f 863//863 2183//2183 864//864 -f 2184//2184 2185//2185 2186//2186 -f 2186//2186 2185//2185 2187//2187 -f 2186//2186 2187//2187 2188//2188 -f 2188//2188 2187//2187 2189//2189 -f 2188//2188 2189//2189 2096//2096 -f 2190//2190 2191//2191 2192//2192 -f 2192//2192 2191//2191 2185//2185 -f 2192//2192 2185//2185 2193//2193 -f 2193//2193 2185//2185 2184//2184 -f 2194//2194 2081//2081 2094//2094 -f 2194//2194 2094//2094 2195//2195 -f 2195//2195 2094//2094 2095//2095 -f 2195//2195 2095//2095 2196//2196 -f 2196//2196 2095//2095 2096//2096 -f 2196//2196 2096//2096 2189//2189 -f 2081//2081 2194//2194 2197//2197 -f 2197//2197 2194//2194 2198//2198 -f 2199//2199 2200//2200 2201//2201 -f 2199//2199 2201//2201 2202//2202 -f 2202//2202 2201//2201 2203//2203 -f 2202//2202 2203//2203 2204//2204 -f 2203//2203 2205//2205 2204//2204 -f 2204//2204 2205//2205 2206//2206 -f 2204//2204 2206//2206 2198//2198 -f 2198//2198 2206//2206 2207//2207 -f 2198//2198 2207//2207 2197//2197 -f 861//861 862//862 1994//1994 -f 1994//1994 862//862 2208//2208 -f 1994//1994 2208//2208 1993//1993 -f 1993//1993 2208//2208 2209//2209 -f 1993//1993 2209//2209 1992//1992 -f 1992//1992 2209//2209 2210//2210 -f 1992//1992 2210//2210 1990//1990 -f 1990//1990 2210//2210 2211//2211 -f 1990//1990 2211//2211 1991//1991 -f 1991//1991 2211//2211 2212//2212 -f 1991//1991 2212//2212 849//849 -f 849//849 2212//2212 850//850 -f 2213//2213 2214//2214 2215//2215 -f 2215//2215 2216//2216 2213//2213 -f 2213//2213 2216//2216 2217//2217 -f 2213//2213 2217//2217 2218//2218 -f 2217//2217 2219//2219 2218//2218 -f 2218//2218 2219//2219 2220//2220 -f 2218//2218 2220//2220 2221//2221 -f 2221//2221 2220//2220 2222//2222 -f 2221//2221 2222//2222 2223//2223 -f 2215//2215 2214//2214 2224//2224 -f 2224//2224 2214//2214 2225//2225 -f 847//847 848//848 1999//1999 -f 1999//1999 848//848 2226//2226 -f 1999//1999 2226//2226 1998//1998 -f 1998//1998 2226//2226 2227//2227 -f 1998//1998 2227//2227 1997//1997 -f 1997//1997 2227//2227 2228//2228 -f 1997//1997 2228//2228 1996//1996 -f 1996//1996 2228//2228 2229//2229 -f 1996//1996 2229//2229 1995//1995 -f 1995//1995 2229//2229 2230//2230 -f 1995//1995 2230//2230 835//835 -f 835//835 2230//2230 836//836 -f 833//833 834//834 2004//2004 -f 2004//2004 834//834 2231//2231 -f 2004//2004 2231//2231 2003//2003 -f 2003//2003 2231//2231 2232//2232 -f 2003//2003 2232//2232 2002//2002 -f 2002//2002 2232//2232 2233//2233 -f 2002//2002 2233//2233 2001//2001 -f 2001//2001 2233//2233 2234//2234 -f 2001//2001 2234//2234 2000//2000 -f 2000//2000 2234//2234 2235//2235 -f 2000//2000 2235//2235 821//821 -f 821//821 2235//2235 822//822 -f 2224//2224 2225//2225 2236//2236 -f 2236//2236 2225//2225 2237//2237 -f 2238//2238 2239//2239 2240//2240 -f 2240//2240 2239//2239 2241//2241 -f 2240//2240 2241//2241 2237//2237 -f 2237//2237 2241//2241 2242//2242 -f 2237//2237 2242//2242 2236//2236 -f 2238//2238 2240//2240 2243//2243 -f 2243//2243 2240//2240 2244//2244 -f 2243//2243 2244//2244 2245//2245 -f 819//819 820//820 2005//2005 -f 2005//2005 820//820 2246//2246 -f 2005//2005 2246//2246 2009//2009 -f 2009//2009 2246//2246 2247//2247 -f 2009//2009 2247//2247 2008//2008 -f 2008//2008 2247//2247 2248//2248 -f 2008//2008 2248//2248 2007//2007 -f 2007//2007 2248//2248 2249//2249 -f 2007//2007 2249//2249 2006//2006 -f 2006//2006 2249//2249 2250//2250 -f 2006//2006 2250//2250 807//807 -f 807//807 2250//2250 808//808 -f 2251//2251 2252//2252 2253//2253 -f 2253//2253 2254//2254 2251//2251 -f 2251//2251 2254//2254 2255//2255 -f 2251//2251 2255//2255 2256//2256 -f 2255//2255 2257//2257 2256//2256 -f 2256//2256 2257//2257 2258//2258 -f 2256//2256 2258//2258 2259//2259 -f 2259//2259 2258//2258 2260//2260 -f 2259//2259 2260//2260 2261//2261 -f 2253//2253 2252//2252 2108//2108 -f 2108//2108 2252//2252 2262//2262 -f 2263//2263 2097//2097 2106//2106 -f 2263//2263 2106//2106 2264//2264 -f 2264//2264 2106//2106 2107//2107 -f 2264//2264 2107//2107 2265//2265 -f 2265//2265 2107//2107 2108//2108 -f 2265//2265 2108//2108 2262//2262 -f 2266//2266 2267//2267 2268//2268 -f 2268//2268 2267//2267 2269//2269 -f 2269//2269 2270//2270 2268//2268 -f 2268//2268 2270//2270 2271//2271 -f 2268//2268 2271//2271 2272//2272 -f 2272//2272 2271//2271 2273//2273 -f 2272//2272 2273//2273 2263//2263 -f 2263//2263 2273//2273 2274//2274 -f 2263//2263 2274//2274 2097//2097 -f 805//805 806//806 2014//2014 -f 2014//2014 806//806 2275//2275 -f 2014//2014 2275//2275 2013//2013 -f 2013//2013 2275//2275 2276//2276 -f 2013//2013 2276//2276 2012//2012 -f 2012//2012 2276//2276 2277//2277 -f 2012//2012 2277//2277 2010//2010 -f 2010//2010 2277//2277 2278//2278 -f 2010//2010 2278//2278 2011//2011 -f 2011//2011 2278//2278 2279//2279 -f 2011//2011 2279//2279 793//793 -f 793//793 2279//2279 794//794 -f 791//791 792//792 2019//2019 -f 2019//2019 792//792 2280//2280 -f 2019//2019 2280//2280 2018//2018 -f 2018//2018 2280//2280 2281//2281 -f 2018//2018 2281//2281 2017//2017 -f 2017//2017 2281//2281 2282//2282 -f 2017//2017 2282//2282 2016//2016 -f 2016//2016 2282//2282 2283//2283 -f 2016//2016 2283//2283 2015//2015 -f 2015//2015 2283//2283 2284//2284 -f 2015//2015 2284//2284 779//779 -f 779//779 2284//2284 780//780 -f 2285//2285 2286//2286 2287//2287 -f 2287//2287 2286//2286 2288//2288 -f 2287//2287 2288//2288 2289//2289 -f 2289//2289 2288//2288 2290//2290 -f 2289//2289 2290//2290 2291//2291 -f 2292//2292 2293//2293 2294//2294 -f 2294//2294 2293//2293 2286//2286 -f 2294//2294 2286//2286 2295//2295 -f 2295//2295 2286//2286 2285//2285 -f 2291//2291 2290//2290 2121//2121 -f 2121//2121 2290//2290 2296//2296 -f 2297//2297 2110//2110 2119//2119 -f 2297//2297 2119//2119 2298//2298 -f 2298//2298 2119//2119 2120//2120 -f 2298//2298 2120//2120 2299//2299 -f 2299//2299 2120//2120 2121//2121 -f 2299//2299 2121//2121 2296//2296 -f 777//777 778//778 2020//2020 -f 2020//2020 778//778 2300//2300 -f 2020//2020 2300//2300 2024//2024 -f 2024//2024 2300//2300 2301//2301 -f 2024//2024 2301//2301 2023//2023 -f 2023//2023 2301//2301 2302//2302 -f 2023//2023 2302//2302 2021//2021 -f 2021//2021 2302//2302 2303//2303 -f 2021//2021 2303//2303 2022//2022 -f 2022//2022 2303//2303 2304//2304 -f 2022//2022 2304//2304 765//765 -f 765//765 2304//2304 766//766 -f 2305//2305 2306//2306 2307//2307 -f 2307//2307 2306//2306 2308//2308 -f 2308//2308 2309//2309 2307//2307 -f 2307//2307 2309//2309 2310//2310 -f 2307//2307 2310//2310 2311//2311 -f 2110//2110 2297//2297 2312//2312 -f 2312//2312 2297//2297 2311//2311 -f 2312//2312 2311//2311 2313//2313 -f 2313//2313 2311//2311 2310//2310 -f 763//763 764//764 2025//2025 -f 2025//2025 764//764 2314//2314 -f 2025//2025 2314//2314 2029//2029 -f 2029//2029 2314//2314 2315//2315 -f 2029//2029 2315//2315 2028//2028 -f 2028//2028 2315//2315 2316//2316 -f 2028//2028 2316//2316 2027//2027 -f 2027//2027 2316//2316 2317//2317 -f 2027//2027 2317//2317 2026//2026 -f 2026//2026 2317//2317 2318//2318 -f 2026//2026 2318//2318 751//751 -f 751//751 2318//2318 752//752 -f 749//749 750//750 2034//2034 -f 2034//2034 750//750 2319//2319 -f 2034//2034 2319//2319 2033//2033 -f 2033//2033 2319//2319 2320//2320 -f 2033//2033 2320//2320 2032//2032 -f 2032//2032 2320//2320 2321//2321 -f 2032//2032 2321//2321 2031//2031 -f 2031//2031 2321//2321 2322//2322 -f 2031//2031 2322//2322 2030//2030 -f 2030//2030 2322//2322 2323//2323 -f 2030//2030 2323//2323 737//737 -f 737//737 2323//2323 738//738 -f 735//735 736//736 2038//2038 -f 2038//2038 736//736 2324//2324 -f 2038//2038 2324//2324 2037//2037 -f 2037//2037 2324//2324 2325//2325 -f 2037//2037 2325//2325 2036//2036 -f 2036//2036 2325//2325 2326//2326 -f 2036//2036 2326//2326 2035//2035 -f 2035//2035 2326//2326 2327//2327 -f 2035//2035 2327//2327 2039//2039 -f 2039//2039 2327//2327 2328//2328 -f 2039//2039 2328//2328 723//723 -f 723//723 2328//2328 724//724 -f 721//721 722//722 2040//2040 -f 2040//2040 722//722 2329//2329 -f 2040//2040 2329//2329 2044//2044 -f 2044//2044 2329//2329 2330//2330 -f 2044//2044 2330//2330 2043//2043 -f 2043//2043 2330//2330 2331//2331 -f 2043//2043 2331//2331 2042//2042 -f 2042//2042 2331//2331 2332//2332 -f 2042//2042 2332//2332 2041//2041 -f 2041//2041 2332//2332 2333//2333 -f 2041//2041 2333//2333 709//709 -f 709//709 2333//2333 710//710 -f 707//707 708//708 2047//2047 -f 2047//2047 708//708 2334//2334 -f 2047//2047 2334//2334 2046//2046 -f 2046//2046 2334//2334 2335//2335 -f 2046//2046 2335//2335 2045//2045 -f 2045//2045 2335//2335 2336//2336 -f 2045//2045 2336//2336 2049//2049 -f 2049//2049 2336//2336 2337//2337 -f 2049//2049 2337//2337 2048//2048 -f 2048//2048 2337//2337 2338//2338 -f 2048//2048 2338//2338 695//695 -f 695//695 2338//2338 696//696 -f 693//693 694//694 2054//2054 -f 2054//2054 694//694 2339//2339 -f 2054//2054 2339//2339 2053//2053 -f 2053//2053 2339//2339 2340//2340 -f 2053//2053 2340//2340 2052//2052 -f 2052//2052 2340//2340 2341//2341 -f 2052//2052 2341//2341 2051//2051 -f 2051//2051 2341//2341 2342//2342 -f 2051//2051 2342//2342 2050//2050 -f 2050//2050 2342//2342 2343//2343 -f 2050//2050 2343//2343 681//681 -f 681//681 2343//2343 682//682 -f 679//679 680//680 2058//2058 -f 2058//2058 680//680 2344//2344 -f 2058//2058 2344//2344 2057//2057 -f 2057//2057 2344//2344 2345//2345 -f 2057//2057 2345//2345 2056//2056 -f 2056//2056 2345//2345 2346//2346 -f 2056//2056 2346//2346 2055//2055 -f 2055//2055 2346//2346 2347//2347 -f 2055//2055 2347//2347 2059//2059 -f 2059//2059 2347//2347 2348//2348 -f 2059//2059 2348//2348 667//667 -f 667//667 2348//2348 668//668 -f 665//665 666//666 2064//2064 -f 2064//2064 666//666 2349//2349 -f 2064//2064 2349//2349 2063//2063 -f 2063//2063 2349//2349 2350//2350 -f 2063//2063 2350//2350 2062//2062 -f 2062//2062 2350//2350 2351//2351 -f 2062//2062 2351//2351 2061//2061 -f 2061//2061 2351//2351 2352//2352 -f 2061//2061 2352//2352 2060//2060 -f 2060//2060 2352//2352 2353//2353 -f 2060//2060 2353//2353 653//653 -f 653//653 2353//2353 654//654 -f 651//651 652//652 2070//2070 -f 2070//2070 652//652 2354//2354 -f 2070//2070 2354//2354 2071//2071 -f 2071//2071 2354//2354 2355//2355 -f 2071//2071 2355//2355 2072//2072 -f 2072//2072 2355//2355 2356//2356 -f 2072//2072 2356//2356 2067//2067 -f 2067//2067 2356//2356 2357//2357 -f 2067//2067 2357//2357 2068//2068 -f 2068//2068 2357//2357 2358//2358 -f 2068//2068 2358//2358 2069//2069 -f 2069//2069 2358//2358 2359//2359 -f 2069//2069 2359//2359 2065//2065 -f 2065//2065 2359//2359 2360//2360 -f 2065//2065 2360//2360 2066//2066 -f 2066//2066 2360//2360 2361//2361 -f 2066//2066 2361//2361 633//633 -f 633//633 2361//2361 634//634 -f 631//631 632//632 2075//2075 -f 2075//2075 632//632 2362//2362 -f 2075//2075 2362//2362 2076//2076 -f 2076//2076 2362//2362 2363//2363 -f 2076//2076 2363//2363 2077//2077 -f 2077//2077 2363//2363 2364//2364 -f 2077//2077 2364//2364 2073//2073 -f 2073//2073 2364//2364 2365//2365 -f 2073//2073 2365//2365 2074//2074 -f 2074//2074 2365//2365 2366//2366 -f 2074//2074 2366//2366 2078//2078 -f 2078//2078 2366//2366 2367//2367 -f 2078//2078 2367//2367 2079//2079 -f 2079//2079 2367//2367 2368//2368 -f 2079//2079 2368//2368 2080//2080 -f 2080//2080 2368//2368 2369//2369 -f 2080//2080 2369//2369 613//613 -f 613//613 2369//2369 614//614 -f 2370//2370 2371//2371 2372//2372 -f 2372//2372 2371//2371 2373//2373 -f 2372//2372 2373//2373 2374//2374 -f 2374//2374 2373//2373 2375//2375 -f 2375//2375 2373//2373 2376//2376 -f 2375//2375 2376//2376 2377//2377 -f 2377//2377 2376//2376 2378//2378 -f 2378//2378 2376//2376 2200//2200 -f 2378//2378 2200//2200 2379//2379 -f 2200//2200 2376//2376 2380//2380 -f 2376//2376 2373//2373 2381//2381 -f 2373//2373 2371//2371 2382//2382 -f 2373//2373 2382//2382 2381//2381 -f 2381//2381 2382//2382 2383//2383 -f 2381//2381 2383//2383 2384//2384 -f 2384//2384 2383//2383 2385//2385 -f 2384//2384 2385//2385 2386//2386 -f 2386//2386 2385//2385 2387//2387 -f 2386//2386 2387//2387 2388//2388 -f 2388//2388 2387//2387 2389//2389 -f 2388//2388 2389//2389 2390//2390 -f 2390//2390 2389//2389 2391//2391 -f 2390//2390 2391//2391 2392//2392 -f 2376//2376 2381//2381 2380//2380 -f 2380//2380 2381//2381 2384//2384 -f 2380//2380 2384//2384 2393//2393 -f 2393//2393 2384//2384 2386//2386 -f 2393//2393 2386//2386 2394//2394 -f 2394//2394 2386//2386 2388//2388 -f 2394//2394 2388//2388 2395//2395 -f 2395//2395 2388//2388 2390//2390 -f 2395//2395 2390//2390 2396//2396 -f 2396//2396 2390//2390 2392//2392 -f 2396//2396 2392//2392 2397//2397 -f 2200//2200 2380//2380 2201//2201 -f 2201//2201 2380//2380 2393//2393 -f 2201//2201 2393//2393 2203//2203 -f 2203//2203 2393//2393 2394//2394 -f 2203//2203 2394//2394 2205//2205 -f 2205//2205 2394//2394 2395//2395 -f 2205//2205 2395//2395 2206//2206 -f 2206//2206 2395//2395 2396//2396 -f 2206//2206 2396//2396 2207//2207 -f 2207//2207 2396//2396 2397//2397 -f 2207//2207 2397//2397 2197//2197 -f 2391//2391 2087//2087 2084//2084 -f 2391//2391 2084//2084 2392//2392 -f 2392//2392 2084//2084 2082//2082 -f 2392//2392 2082//2082 2397//2397 -f 2397//2397 2082//2082 2081//2081 -f 2397//2397 2081//2081 2197//2197 -f 2193//2193 2184//2184 2398//2398 -f 2087//2087 2399//2399 2088//2088 -f 2088//2088 2399//2399 2400//2400 -f 2401//2401 2092//2092 2402//2402 -f 2402//2402 2092//2092 2091//2091 -f 2402//2402 2091//2091 2400//2400 -f 2400//2400 2091//2091 2090//2090 -f 2400//2400 2090//2090 2088//2088 -f 2399//2399 2403//2403 2400//2400 -f 2400//2400 2403//2403 2404//2404 -f 2400//2400 2404//2404 2402//2402 -f 2402//2402 2404//2404 2405//2405 -f 2402//2402 2405//2405 2401//2401 -f 2401//2401 2405//2405 2398//2398 -f 2188//2188 2096//2096 2401//2401 -f 2401//2401 2096//2096 2093//2093 -f 2401//2401 2093//2093 2092//2092 -f 2398//2398 2184//2184 2401//2401 -f 2401//2401 2184//2184 2186//2186 -f 2401//2401 2186//2186 2188//2188 -f 2192//2192 2193//2193 2406//2406 -f 2406//2406 2193//2193 2398//2398 -f 2406//2406 2398//2398 2407//2407 -f 2407//2407 2398//2398 2405//2405 -f 2407//2407 2405//2405 2408//2408 -f 2408//2408 2405//2405 2404//2404 -f 2408//2408 2404//2404 2409//2409 -f 2409//2409 2404//2404 2403//2403 -f 2409//2409 2410//2410 2408//2408 -f 2408//2408 2410//2410 2411//2411 -f 2408//2408 2411//2411 2407//2407 -f 2407//2407 2411//2411 2412//2412 -f 2407//2407 2412//2412 2406//2406 -f 2406//2406 2412//2412 2413//2413 -f 2406//2406 2413//2413 2192//2192 -f 2192//2192 2413//2413 2190//2190 -f 2410//2410 2414//2414 2415//2415 -f 2410//2410 2415//2415 2411//2411 -f 2411//2411 2415//2415 2416//2416 -f 2411//2411 2416//2416 2412//2412 -f 2412//2412 2416//2416 2417//2417 -f 2412//2412 2417//2417 2413//2413 -f 2413//2413 2417//2417 2418//2418 -f 2413//2413 2418//2418 2190//2190 -f 2419//2419 2420//2420 2421//2421 -f 2421//2421 2420//2420 2422//2422 -f 2421//2421 2422//2422 2423//2423 -f 2423//2423 2422//2422 2424//2424 -f 2424//2424 2422//2422 2425//2425 -f 2424//2424 2425//2425 2426//2426 -f 2426//2426 2425//2425 2427//2427 -f 2427//2427 2425//2425 2267//2267 -f 2427//2427 2267//2267 2428//2428 -f 2267//2267 2425//2425 2429//2429 -f 2425//2425 2422//2422 2430//2430 -f 2422//2422 2420//2420 2431//2431 -f 2422//2422 2431//2431 2430//2430 -f 2430//2430 2431//2431 2432//2432 -f 2430//2430 2432//2432 2433//2433 -f 2433//2433 2432//2432 2434//2434 -f 2433//2433 2434//2434 2435//2435 -f 2435//2435 2434//2434 2436//2436 -f 2435//2435 2436//2436 2437//2437 -f 2437//2437 2436//2436 2438//2438 -f 2437//2437 2438//2438 2439//2439 -f 2439//2439 2438//2438 2100//2100 -f 2439//2439 2100//2100 2109//2109 -f 2425//2425 2430//2430 2429//2429 -f 2429//2429 2430//2430 2433//2433 -f 2429//2429 2433//2433 2440//2440 -f 2440//2440 2433//2433 2435//2435 -f 2440//2440 2435//2435 2441//2441 -f 2441//2441 2435//2435 2437//2437 -f 2441//2441 2437//2437 2442//2442 -f 2442//2442 2437//2437 2439//2439 -f 2442//2442 2439//2439 2443//2443 -f 2443//2443 2439//2439 2109//2109 -f 2443//2443 2109//2109 2098//2098 -f 2267//2267 2429//2429 2269//2269 -f 2269//2269 2429//2429 2440//2440 -f 2269//2269 2440//2440 2270//2270 -f 2270//2270 2440//2440 2441//2441 -f 2270//2270 2441//2441 2271//2271 -f 2271//2271 2441//2441 2442//2442 -f 2271//2271 2442//2442 2273//2273 -f 2273//2273 2442//2442 2443//2443 -f 2273//2273 2443//2443 2274//2274 -f 2274//2274 2443//2443 2098//2098 -f 2274//2274 2098//2098 2097//2097 -f 2100//2100 2444//2444 2445//2445 -f 2100//2100 2445//2445 2101//2101 -f 2101//2101 2445//2445 2446//2446 -f 2101//2101 2446//2446 2105//2105 -f 2105//2105 2446//2446 2253//2253 -f 2105//2105 2253//2253 2108//2108 -f 2253//2253 2446//2446 2447//2447 -f 2446//2446 2445//2445 2448//2448 -f 2445//2445 2444//2444 2449//2449 -f 2445//2445 2449//2449 2448//2448 -f 2448//2448 2449//2449 2450//2450 -f 2448//2448 2450//2450 2451//2451 -f 2451//2451 2450//2450 2452//2452 -f 2451//2451 2452//2452 2453//2453 -f 2453//2453 2452//2452 2454//2454 -f 2453//2453 2454//2454 2455//2455 -f 2455//2455 2454//2454 2456//2456 -f 2455//2455 2456//2456 2457//2457 -f 2457//2457 2456//2456 2458//2458 -f 2457//2457 2458//2458 2459//2459 -f 2446//2446 2448//2448 2447//2447 -f 2447//2447 2448//2448 2451//2451 -f 2447//2447 2451//2451 2460//2460 -f 2460//2460 2451//2451 2453//2453 -f 2460//2460 2453//2453 2461//2461 -f 2461//2461 2453//2453 2455//2455 -f 2461//2461 2455//2455 2462//2462 -f 2462//2462 2455//2455 2457//2457 -f 2462//2462 2457//2457 2463//2463 -f 2463//2463 2457//2457 2459//2459 -f 2463//2463 2459//2459 2464//2464 -f 2253//2253 2447//2447 2254//2254 -f 2254//2254 2447//2447 2460//2460 -f 2254//2254 2460//2460 2255//2255 -f 2255//2255 2460//2460 2461//2461 -f 2255//2255 2461//2461 2257//2257 -f 2257//2257 2461//2461 2462//2462 -f 2257//2257 2462//2462 2258//2258 -f 2258//2258 2462//2462 2463//2463 -f 2258//2258 2463//2463 2260//2260 -f 2260//2260 2463//2463 2464//2464 -f 2260//2260 2464//2464 2261//2261 -f 2458//2458 2465//2465 2466//2466 -f 2458//2458 2466//2466 2459//2459 -f 2459//2459 2466//2466 2467//2467 -f 2459//2459 2467//2467 2464//2464 -f 2464//2464 2467//2467 2468//2468 -f 2464//2464 2468//2468 2261//2261 -f 2469//2469 2470//2470 2471//2471 -f 2469//2469 2471//2471 2472//2472 -f 2472//2472 2471//2471 2473//2473 -f 2472//2472 2473//2473 2474//2474 -f 2474//2474 2473//2473 2245//2245 -f 2474//2474 2245//2245 2475//2475 -f 2238//2238 2243//2243 2476//2476 -f 2477//2477 2478//2478 2479//2479 -f 2479//2479 2478//2478 2480//2480 -f 2479//2479 2480//2480 2481//2481 -f 2481//2481 2480//2480 2482//2482 -f 2481//2481 2482//2482 2239//2239 -f 2483//2483 2484//2484 2485//2485 -f 2485//2485 2484//2484 2486//2486 -f 2485//2485 2486//2486 2487//2487 -f 2487//2487 2486//2486 2488//2488 -f 2470//2470 2489//2489 2471//2471 -f 2471//2471 2489//2489 2490//2490 -f 2471//2471 2490//2490 2473//2473 -f 2473//2473 2490//2490 2476//2476 -f 2473//2473 2476//2476 2245//2245 -f 2245//2245 2476//2476 2243//2243 -f 2239//2239 2238//2238 2481//2481 -f 2481//2481 2238//2238 2476//2476 -f 2481//2481 2476//2476 2479//2479 -f 2479//2479 2476//2476 2490//2490 -f 2479//2479 2490//2490 2477//2477 -f 2477//2477 2490//2490 2489//2489 -f 2236//2236 2242//2242 2482//2482 -f 2482//2482 2242//2242 2241//2241 -f 2482//2482 2241//2241 2239//2239 -f 2478//2478 2483//2483 2480//2480 -f 2480//2480 2483//2483 2485//2485 -f 2480//2480 2485//2485 2482//2482 -f 2482//2482 2485//2485 2487//2487 -f 2482//2482 2487//2487 2236//2236 -f 2236//2236 2487//2487 2488//2488 -f 2236//2236 2488//2488 2224//2224 -f 2484//2484 2491//2491 2492//2492 -f 2484//2484 2492//2492 2486//2486 -f 2486//2486 2492//2492 2493//2493 -f 2486//2486 2493//2493 2488//2488 -f 2488//2488 2493//2493 2215//2215 -f 2488//2488 2215//2215 2224//2224 -f 2215//2215 2493//2493 2494//2494 -f 2493//2493 2492//2492 2495//2495 -f 2492//2492 2491//2491 2496//2496 -f 2492//2492 2496//2496 2495//2495 -f 2495//2495 2496//2496 2497//2497 -f 2495//2495 2497//2497 2498//2498 -f 2498//2498 2497//2497 2499//2499 -f 2498//2498 2499//2499 2500//2500 -f 2500//2500 2499//2499 2501//2501 -f 2500//2500 2501//2501 2502//2502 -f 2502//2502 2501//2501 2503//2503 -f 2502//2502 2503//2503 2504//2504 -f 2504//2504 2503//2503 2505//2505 -f 2504//2504 2505//2505 2506//2506 -f 2493//2493 2495//2495 2494//2494 -f 2494//2494 2495//2495 2498//2498 -f 2494//2494 2498//2498 2507//2507 -f 2507//2507 2498//2498 2500//2500 -f 2507//2507 2500//2500 2508//2508 -f 2508//2508 2500//2500 2502//2502 -f 2508//2508 2502//2502 2509//2509 -f 2509//2509 2502//2502 2504//2504 -f 2509//2509 2504//2504 2510//2510 -f 2510//2510 2504//2504 2506//2506 -f 2510//2510 2506//2506 2511//2511 -f 2215//2215 2494//2494 2216//2216 -f 2216//2216 2494//2494 2507//2507 -f 2216//2216 2507//2507 2217//2217 -f 2217//2217 2507//2507 2508//2508 -f 2217//2217 2508//2508 2219//2219 -f 2219//2219 2508//2508 2509//2509 -f 2219//2219 2509//2509 2220//2220 -f 2220//2220 2509//2509 2510//2510 -f 2220//2220 2510//2510 2222//2222 -f 2222//2222 2510//2510 2511//2511 -f 2222//2222 2511//2511 2223//2223 -f 2505//2505 2512//2512 2513//2513 -f 2505//2505 2513//2513 2506//2506 -f 2506//2506 2513//2513 2514//2514 -f 2506//2506 2514//2514 2511//2511 -f 2511//2511 2514//2514 2515//2515 -f 2511//2511 2515//2515 2223//2223 -f 2516//2516 2517//2517 2518//2518 -f 2516//2516 2518//2518 2519//2519 -f 2519//2519 2518//2518 2520//2520 -f 2519//2519 2520//2520 2521//2521 -f 2521//2521 2520//2520 2522//2522 -f 2521//2521 2522//2522 2523//2523 -f 2522//2522 2520//2520 2524//2524 -f 2520//2520 2518//2518 2525//2525 -f 2518//2518 2517//2517 2526//2526 -f 2518//2518 2526//2526 2525//2525 -f 2525//2525 2526//2526 2527//2527 -f 2525//2525 2527//2527 2528//2528 -f 2528//2528 2527//2527 2529//2529 -f 2528//2528 2529//2529 2530//2530 -f 2530//2530 2529//2529 2531//2531 -f 2530//2530 2531//2531 2532//2532 -f 2532//2532 2531//2531 2533//2533 -f 2532//2532 2533//2533 2534//2534 -f 2534//2534 2533//2533 2535//2535 -f 2534//2534 2535//2535 2536//2536 -f 2520//2520 2525//2525 2524//2524 -f 2524//2524 2525//2525 2528//2528 -f 2524//2524 2528//2528 2537//2537 -f 2537//2537 2528//2528 2530//2530 -f 2537//2537 2530//2530 2538//2538 -f 2538//2538 2530//2530 2532//2532 -f 2538//2538 2532//2532 2539//2539 -f 2539//2539 2532//2532 2534//2534 -f 2539//2539 2534//2534 2540//2540 -f 2540//2540 2534//2534 2536//2536 -f 2540//2540 2536//2536 2541//2541 -f 2522//2522 2524//2524 2542//2542 -f 2542//2542 2524//2524 2537//2537 -f 2542//2542 2537//2537 2543//2543 -f 2543//2543 2537//2537 2538//2538 -f 2543//2543 2538//2538 2544//2544 -f 2544//2544 2538//2538 2539//2539 -f 2544//2544 2539//2539 2545//2545 -f 2545//2545 2539//2539 2540//2540 -f 2545//2545 2540//2540 2546//2546 -f 2546//2546 2540//2540 2541//2541 -f 2546//2546 2541//2541 2547//2547 -f 2535//2535 2131//2131 2140//2140 -f 2535//2535 2140//2140 2536//2536 -f 2536//2536 2140//2140 2129//2129 -f 2536//2536 2129//2129 2541//2541 -f 2541//2541 2129//2129 2128//2128 -f 2541//2541 2128//2128 2547//2547 -f 2139//2139 2136//2136 2548//2548 -f 2136//2136 2132//2132 2549//2549 -f 2132//2132 2131//2131 2550//2550 -f 2132//2132 2550//2550 2549//2549 -f 2549//2549 2550//2550 2551//2551 -f 2549//2549 2551//2551 2552//2552 -f 2552//2552 2551//2551 2553//2553 -f 2552//2552 2553//2553 2554//2554 -f 2554//2554 2553//2553 2555//2555 -f 2554//2554 2555//2555 2556//2556 -f 2556//2556 2555//2555 2557//2557 -f 2556//2556 2557//2557 2558//2558 -f 2558//2558 2557//2557 2559//2559 -f 2558//2558 2559//2559 2560//2560 -f 2136//2136 2549//2549 2548//2548 -f 2548//2548 2549//2549 2552//2552 -f 2548//2548 2552//2552 2561//2561 -f 2561//2561 2552//2552 2554//2554 -f 2561//2561 2554//2554 2562//2562 -f 2562//2562 2554//2554 2556//2556 -f 2562//2562 2556//2556 2563//2563 -f 2563//2563 2556//2556 2558//2558 -f 2563//2563 2558//2558 2564//2564 -f 2564//2564 2558//2558 2560//2560 -f 2564//2564 2560//2560 2565//2565 -f 2139//2139 2548//2548 2566//2566 -f 2566//2566 2548//2548 2561//2561 -f 2566//2566 2561//2561 2567//2567 -f 2567//2567 2561//2561 2562//2562 -f 2567//2567 2562//2562 2568//2568 -f 2568//2568 2562//2562 2563//2563 -f 2568//2568 2563//2563 2569//2569 -f 2569//2569 2563//2563 2564//2564 -f 2569//2569 2564//2564 2570//2570 -f 2570//2570 2564//2564 2565//2565 -f 2570//2570 2565//2565 2571//2571 -f 2572//2572 2573//2573 2574//2574 -f 2572//2572 2574//2574 2575//2575 -f 2575//2575 2574//2574 2576//2576 -f 2575//2575 2576//2576 2577//2577 -f 2577//2577 2576//2576 2306//2306 -f 2577//2577 2306//2306 2578//2578 -f 2306//2306 2576//2576 2579//2579 -f 2576//2576 2574//2574 2580//2580 -f 2574//2574 2573//2573 2581//2581 -f 2574//2574 2581//2581 2580//2580 -f 2580//2580 2581//2581 2582//2582 -f 2580//2580 2582//2582 2583//2583 -f 2583//2583 2582//2582 2584//2584 -f 2583//2583 2584//2584 2585//2585 -f 2585//2585 2584//2584 2586//2586 -f 2585//2585 2586//2586 2587//2587 -f 2587//2587 2586//2586 2588//2588 -f 2587//2587 2588//2588 2589//2589 -f 2589//2589 2588//2588 2113//2113 -f 2589//2589 2113//2113 2122//2122 -f 2576//2576 2580//2580 2579//2579 -f 2579//2579 2580//2580 2583//2583 -f 2579//2579 2583//2583 2590//2590 -f 2590//2590 2583//2583 2585//2585 -f 2590//2590 2585//2585 2591//2591 -f 2591//2591 2585//2585 2587//2587 -f 2591//2591 2587//2587 2592//2592 -f 2592//2592 2587//2587 2589//2589 -f 2592//2592 2589//2589 2593//2593 -f 2593//2593 2589//2589 2122//2122 -f 2593//2593 2122//2122 2111//2111 -f 2306//2306 2579//2579 2308//2308 -f 2308//2308 2579//2579 2590//2590 -f 2308//2308 2590//2590 2309//2309 -f 2309//2309 2590//2590 2591//2591 -f 2309//2309 2591//2591 2310//2310 -f 2310//2310 2591//2591 2592//2592 -f 2310//2310 2592//2592 2313//2313 -f 2313//2313 2592//2592 2593//2593 -f 2313//2313 2593//2593 2312//2312 -f 2312//2312 2593//2593 2111//2111 -f 2312//2312 2111//2111 2110//2110 -f 2113//2113 2594//2594 2595//2595 -f 2113//2113 2595//2595 2114//2114 -f 2114//2114 2595//2595 2596//2596 -f 2114//2114 2596//2596 2118//2118 -f 2118//2118 2596//2596 2291//2291 -f 2118//2118 2291//2291 2121//2121 -f 2291//2291 2596//2596 2597//2597 -f 2596//2596 2595//2595 2598//2598 -f 2595//2595 2594//2594 2599//2599 -f 2595//2595 2599//2599 2598//2598 -f 2598//2598 2599//2599 2600//2600 -f 2598//2598 2600//2600 2601//2601 -f 2601//2601 2600//2600 2602//2602 -f 2601//2601 2602//2602 2603//2603 -f 2603//2603 2602//2602 2604//2604 -f 2603//2603 2604//2604 2605//2605 -f 2605//2605 2604//2604 2606//2606 -f 2605//2605 2606//2606 2607//2607 -f 2607//2607 2606//2606 2608//2608 -f 2607//2607 2608//2608 2609//2609 -f 2596//2596 2598//2598 2597//2597 -f 2597//2597 2598//2598 2601//2601 -f 2597//2597 2601//2601 2610//2610 -f 2610//2610 2601//2601 2603//2603 -f 2610//2610 2603//2603 2611//2611 -f 2611//2611 2603//2603 2605//2605 -f 2611//2611 2605//2605 2612//2612 -f 2612//2612 2605//2605 2607//2607 -f 2612//2612 2607//2607 2613//2613 -f 2613//2613 2607//2607 2609//2609 -f 2613//2613 2609//2609 2614//2614 -f 2291//2291 2597//2597 2289//2289 -f 2289//2289 2597//2597 2610//2610 -f 2289//2289 2610//2610 2287//2287 -f 2287//2287 2610//2610 2611//2611 -f 2287//2287 2611//2611 2285//2285 -f 2285//2285 2611//2611 2612//2612 -f 2285//2285 2612//2612 2295//2295 -f 2295//2295 2612//2612 2613//2613 -f 2295//2295 2613//2613 2294//2294 -f 2294//2294 2613//2613 2614//2614 -f 2294//2294 2614//2614 2292//2292 -f 2608//2608 2615//2615 2616//2616 -f 2608//2608 2616//2616 2609//2609 -f 2609//2609 2616//2616 2617//2617 -f 2609//2609 2617//2617 2614//2614 -f 2614//2614 2617//2617 2618//2618 -f 2614//2614 2618//2618 2292//2292 -f 2619//2619 2620//2620 2621//2621 -f 2621//2621 2620//2620 2622//2622 -f 2621//2621 2622//2622 2623//2623 -f 2623//2623 2622//2622 2624//2624 -f 2624//2624 2622//2622 2625//2625 -f 2624//2624 2625//2625 2626//2626 -f 2626//2626 2625//2625 2627//2627 -f 2627//2627 2625//2625 2172//2172 -f 2627//2627 2172//2172 2628//2628 -f 2172//2172 2625//2625 2629//2629 -f 2625//2625 2622//2622 2630//2630 -f 2622//2622 2620//2620 2631//2631 -f 2622//2622 2631//2631 2630//2630 -f 2630//2630 2631//2631 2632//2632 -f 2630//2630 2632//2632 2633//2633 -f 2633//2633 2632//2632 2634//2634 -f 2633//2633 2634//2634 2635//2635 -f 2635//2635 2634//2634 2636//2636 -f 2635//2635 2636//2636 2637//2637 -f 2637//2637 2636//2636 2638//2638 -f 2637//2637 2638//2638 2639//2639 -f 2639//2639 2638//2638 2640//2640 -f 2639//2639 2640//2640 2641//2641 -f 2625//2625 2630//2630 2629//2629 -f 2629//2629 2630//2630 2633//2633 -f 2629//2629 2633//2633 2642//2642 -f 2642//2642 2633//2633 2635//2635 -f 2642//2642 2635//2635 2643//2643 -f 2643//2643 2635//2635 2637//2637 -f 2643//2643 2637//2637 2644//2644 -f 2644//2644 2637//2637 2639//2639 -f 2644//2644 2639//2639 2645//2645 -f 2645//2645 2639//2639 2641//2641 -f 2645//2645 2641//2641 2646//2646 -f 2172//2172 2629//2629 2173//2173 -f 2173//2173 2629//2629 2642//2642 -f 2173//2173 2642//2642 2174//2174 -f 2174//2174 2642//2642 2643//2643 -f 2174//2174 2643//2643 2176//2176 -f 2176//2176 2643//2643 2644//2644 -f 2176//2176 2644//2644 2177//2177 -f 2177//2177 2644//2644 2645//2645 -f 2177//2177 2645//2645 2178//2178 -f 2178//2178 2645//2645 2646//2646 -f 2178//2178 2646//2646 2158//2158 -f 2640//2640 2647//2647 2648//2648 -f 2640//2640 2648//2648 2641//2641 -f 2641//2641 2648//2648 2649//2649 -f 2641//2641 2649//2649 2646//2646 -f 2646//2646 2649//2649 2157//2157 -f 2646//2646 2157//2157 2158//2158 -f 2150//2150 2155//2155 2650//2650 -f 2651//2651 2652//2652 2653//2653 -f 2651//2651 2653//2653 2654//2654 -f 2655//2655 2656//2656 2657//2657 -f 2657//2657 2656//2656 2658//2658 -f 2657//2657 2658//2658 2659//2659 -f 2659//2659 2658//2658 2660//2660 -f 2659//2659 2660//2660 2151//2151 -f 2647//2647 2661//2661 2648//2648 -f 2648//2648 2661//2661 2662//2662 -f 2648//2648 2662//2662 2649//2649 -f 2649//2649 2662//2662 2650//2650 -f 2649//2649 2650//2650 2157//2157 -f 2157//2157 2650//2650 2155//2155 -f 2151//2151 2150//2150 2659//2659 -f 2659//2659 2150//2150 2650//2650 -f 2659//2659 2650//2650 2657//2657 -f 2657//2657 2650//2650 2662//2662 -f 2657//2657 2662//2662 2655//2655 -f 2655//2655 2662//2662 2661//2661 -f 2148//2148 2154//2154 2660//2660 -f 2660//2660 2154//2154 2153//2153 -f 2660//2660 2153//2153 2151//2151 -f 2653//2653 2663//2663 2654//2654 -f 2654//2654 2663//2663 2664//2664 -f 2654//2654 2664//2664 2665//2665 -f 2665//2665 2664//2664 2666//2666 -f 2665//2665 2666//2666 2667//2667 -f 2656//2656 2651//2651 2658//2658 -f 2658//2658 2651//2651 2654//2654 -f 2658//2658 2654//2654 2660//2660 -f 2660//2660 2654//2654 2665//2665 -f 2660//2660 2665//2665 2148//2148 -f 2148//2148 2665//2665 2667//2667 -f 2148//2148 2667//2667 2146//2146 -f 2668//2668 2669//2669 2652//2652 -f 2652//2652 2669//2669 2653//2653 -f 2653//2653 2669//2669 2663//2663 -f 2663//2663 2669//2669 2670//2670 -f 2663//2663 2670//2670 2664//2664 -f 2664//2664 2670//2670 2671//2671 -f 2664//2664 2671//2671 2666//2666 -f 2666//2666 2671//2671 2672//2672 -f 2666//2666 2672//2672 2667//2667 -f 2672//2672 2673//2673 2667//2667 -f 2667//2667 2673//2673 2674//2674 -f 2667//2667 2674//2674 2146//2146 -f 2675//2675 2676//2676 2559//2559 -f 2559//2559 2676//2676 2560//2560 -f 2676//2676 2677//2677 2560//2560 -f 2560//2560 2677//2677 2678//2678 -f 2560//2560 2678//2678 2565//2565 -f 2679//2679 2571//2571 2680//2680 -f 2680//2680 2571//2571 2565//2565 -f 2680//2680 2565//2565 2681//2681 -f 2681//2681 2565//2565 2678//2678 -f 611//611 612//612 2127//2127 -f 2127//2127 612//612 2682//2682 -f 2127//2127 2682//2682 2126//2126 -f 2126//2126 2682//2682 2683//2683 -f 2126//2126 2683//2683 2125//2125 -f 2125//2125 2683//2683 2684//2684 -f 2125//2125 2684//2684 2124//2124 -f 2124//2124 2684//2684 2685//2685 -f 2124//2124 2685//2685 2123//2123 -f 2123//2123 2685//2685 2686//2686 -f 2123//2123 2686//2686 599//599 -f 599//599 2686//2686 600//600 -f 2687//2687 2139//2139 2566//2566 -f 2687//2687 2566//2566 2688//2688 -f 2566//2566 2567//2567 2688//2688 -f 2688//2688 2567//2567 2568//2568 -f 2688//2688 2568//2568 2689//2689 -f 2571//2571 2690//2690 2570//2570 -f 2570//2570 2690//2690 2689//2689 -f 2570//2570 2689//2689 2569//2569 -f 2569//2569 2689//2689 2568//2568 -f 2691//2691 2128//2128 2137//2137 -f 2691//2691 2137//2137 2692//2692 -f 2692//2692 2137//2137 2138//2138 -f 2692//2692 2138//2138 2693//2693 -f 2693//2693 2138//2138 2139//2139 -f 2693//2693 2139//2139 2687//2687 -f 2128//2128 2691//2691 2547//2547 -f 2547//2547 2691//2691 2694//2694 -f 2695//2695 2522//2522 2542//2542 -f 2695//2695 2542//2542 2696//2696 -f 2542//2542 2543//2543 2696//2696 -f 2696//2696 2543//2543 2544//2544 -f 2696//2696 2544//2544 2697//2697 -f 2547//2547 2694//2694 2546//2546 -f 2546//2546 2694//2694 2697//2697 -f 2546//2546 2697//2697 2545//2545 -f 2545//2545 2697//2697 2544//2544 -f 597//597 598//598 2141//2141 -f 2141//2141 598//598 2698//2698 -f 2141//2141 2698//2698 2142//2142 -f 2142//2142 2698//2698 2699//2699 -f 2142//2142 2699//2699 2143//2143 -f 2143//2143 2699//2699 2700//2700 -f 2143//2143 2700//2700 2144//2144 -f 2144//2144 2700//2700 2701//2701 -f 2144//2144 2701//2701 2145//2145 -f 2145//2145 2701//2701 2702//2702 -f 2145//2145 2702//2702 585//585 -f 585//585 2702//2702 586//586 -f 2200//2200 2199//2199 2379//2379 -f 2379//2379 2199//2199 2703//2703 -f 2377//2377 2378//2378 2704//2704 -f 2705//2705 2706//2706 2707//2707 -f 2707//2707 2706//2706 2708//2708 -f 2707//2707 2708//2708 2709//2709 -f 2709//2709 2708//2708 2704//2704 -f 2709//2709 2704//2704 2710//2710 -f 2710//2710 2704//2704 2378//2378 -f 2710//2710 2378//2378 2379//2379 -f 2374//2374 2375//2375 2711//2711 -f 2711//2711 2375//2375 2377//2377 -f 2377//2377 2704//2704 2711//2711 -f 2711//2711 2704//2704 2708//2708 -f 2711//2711 2708//2708 2712//2712 -f 2712//2712 2708//2708 2706//2706 -f 2712//2712 2706//2706 2713//2713 -f 2370//2370 2372//2372 2714//2714 -f 2714//2714 2372//2372 2374//2374 -f 2705//2705 2715//2715 2706//2706 -f 2706//2706 2715//2715 2716//2716 -f 2706//2706 2716//2716 2713//2713 -f 2713//2713 2716//2716 2717//2717 -f 2713//2713 2717//2717 2718//2718 -f 2374//2374 2711//2711 2714//2714 -f 2714//2714 2711//2711 2712//2712 -f 2714//2714 2712//2712 2719//2719 -f 2719//2719 2712//2712 2713//2713 -f 2719//2719 2713//2713 2720//2720 -f 2720//2720 2713//2713 2718//2718 -f 2720//2720 2718//2718 2721//2721 -f 2370//2370 2714//2714 2722//2722 -f 2722//2722 2714//2714 2719//2719 -f 2722//2722 2719//2719 2723//2723 -f 2723//2723 2719//2719 2720//2720 -f 2723//2723 2720//2720 2724//2724 -f 2724//2724 2720//2720 2721//2721 -f 2724//2724 2721//2721 2725//2725 -f 2726//2726 2727//2727 2728//2728 -f 2727//2727 2729//2729 2730//2730 -f 2731//2731 2674//2674 2673//2673 -f 2673//2673 2732//2732 2731//2731 -f 2731//2731 2732//2732 2733//2733 -f 2731//2731 2733//2733 2734//2734 -f 2734//2734 2733//2733 2730//2730 -f 2734//2734 2730//2730 2735//2735 -f 2735//2735 2730//2730 2729//2729 -f 2735//2735 2729//2729 2736//2736 -f 2727//2727 2730//2730 2728//2728 -f 2728//2728 2730//2730 2733//2733 -f 2728//2728 2733//2733 2737//2737 -f 2737//2737 2733//2733 2732//2732 -f 2737//2737 2732//2732 2738//2738 -f 2673//2673 2672//2672 2732//2732 -f 2732//2732 2672//2672 2671//2671 -f 2732//2732 2671//2671 2738//2738 -f 2738//2738 2671//2671 2670//2670 -f 2738//2738 2670//2670 2669//2669 -f 2726//2726 2728//2728 2739//2739 -f 2739//2739 2728//2728 2737//2737 -f 2739//2739 2737//2737 2740//2740 -f 2740//2740 2737//2737 2738//2738 -f 2740//2740 2738//2738 2741//2741 -f 2741//2741 2738//2738 2669//2669 -f 2741//2741 2669//2669 2668//2668 -f 2674//2674 2742//2742 2146//2146 -f 2146//2146 2742//2742 2147//2147 -f 2164//2164 2163//2163 2743//2743 -f 2152//2152 2149//2149 2147//2147 -f 2159//2159 902//902 2175//2175 -f 2175//2175 902//902 900//900 -f 2164//2164 2743//2743 892//892 -f 892//892 2743//2743 2744//2744 -f 892//892 2744//2744 894//894 -f 894//894 2744//2744 2745//2745 -f 894//894 2745//2745 896//896 -f 896//896 2745//2745 2746//2746 -f 896//896 2746//2746 898//898 -f 898//898 2746//2746 2171//2171 -f 898//898 2171//2171 900//900 -f 900//900 2171//2171 2170//2170 -f 900//900 2170//2170 2175//2175 -f 888//888 2159//2159 890//890 -f 890//890 2159//2159 2156//2156 -f 890//890 2156//2156 2165//2165 -f 2165//2165 2156//2156 2166//2166 -f 882//882 2163//2163 884//884 -f 884//884 2163//2163 2162//2162 -f 884//884 2162//2162 886//886 -f 886//886 2162//2162 2161//2161 -f 886//886 2161//2161 888//888 -f 888//888 2161//2161 2160//2160 -f 888//888 2160//2160 2159//2159 -f 2159//2159 2160//2160 904//904 -f 2159//2159 904//904 902//902 -f 882//882 880//880 2163//2163 -f 2163//2163 880//880 878//878 -f 2163//2163 878//878 2743//2743 -f 2743//2743 878//878 2169//2169 -f 2743//2743 2169//2169 2747//2747 -f 2747//2747 2169//2169 2742//2742 -f 2156//2156 2152//2152 2166//2166 -f 2166//2166 2152//2152 2147//2147 -f 2166//2166 2147//2147 2167//2167 -f 2167//2167 2147//2147 2742//2742 -f 2167//2167 2742//2742 2168//2168 -f 2168//2168 2742//2742 2169//2169 -f 2172//2172 2171//2171 2628//2628 -f 2628//2628 2171//2171 2746//2746 -f 2626//2626 2627//2627 2748//2748 -f 2749//2749 2750//2750 2751//2751 -f 2751//2751 2750//2750 2752//2752 -f 2751//2751 2752//2752 2753//2753 -f 2753//2753 2752//2752 2748//2748 -f 2753//2753 2748//2748 2754//2754 -f 2754//2754 2748//2748 2627//2627 -f 2754//2754 2627//2627 2628//2628 -f 2623//2623 2624//2624 2755//2755 -f 2755//2755 2624//2624 2626//2626 -f 2626//2626 2748//2748 2755//2755 -f 2755//2755 2748//2748 2752//2752 -f 2755//2755 2752//2752 2756//2756 -f 2756//2756 2752//2752 2750//2750 -f 2756//2756 2750//2750 2757//2757 -f 2619//2619 2621//2621 2758//2758 -f 2758//2758 2621//2621 2623//2623 -f 2749//2749 2759//2759 2750//2750 -f 2750//2750 2759//2759 2760//2760 -f 2750//2750 2760//2760 2757//2757 -f 2757//2757 2760//2760 2761//2761 -f 2757//2757 2761//2761 2762//2762 -f 2623//2623 2755//2755 2758//2758 -f 2758//2758 2755//2755 2756//2756 -f 2758//2758 2756//2756 2763//2763 -f 2763//2763 2756//2756 2757//2757 -f 2763//2763 2757//2757 2764//2764 -f 2764//2764 2757//2757 2762//2762 -f 2764//2764 2762//2762 2765//2765 -f 2619//2619 2758//2758 2766//2766 -f 2766//2766 2758//2758 2763//2763 -f 2766//2766 2763//2763 2767//2767 -f 2767//2767 2763//2763 2764//2764 -f 2767//2767 2764//2764 2768//2768 -f 2768//2768 2764//2764 2765//2765 -f 2768//2768 2765//2765 2769//2769 -f 2770//2770 2771//2771 2772//2772 -f 2771//2771 2773//2773 2774//2774 -f 2773//2773 2775//2775 2776//2776 -f 2773//2773 2776//2776 2774//2774 -f 2774//2774 2776//2776 2777//2777 -f 2774//2774 2777//2777 2778//2778 -f 2778//2778 2777//2777 2779//2779 -f 2778//2778 2779//2779 2780//2780 -f 2780//2780 2779//2779 2618//2618 -f 2780//2780 2618//2618 2617//2617 -f 2771//2771 2774//2774 2772//2772 -f 2772//2772 2774//2774 2778//2778 -f 2772//2772 2778//2778 2781//2781 -f 2781//2781 2778//2778 2780//2780 -f 2781//2781 2780//2780 2782//2782 -f 2782//2782 2780//2780 2617//2617 -f 2782//2782 2617//2617 2616//2616 -f 2770//2770 2772//2772 2783//2783 -f 2783//2783 2772//2772 2781//2781 -f 2783//2783 2781//2781 2784//2784 -f 2784//2784 2781//2781 2782//2782 -f 2784//2784 2782//2782 2785//2785 -f 2785//2785 2782//2782 2616//2616 -f 2785//2785 2616//2616 2615//2615 -f 2618//2618 2786//2786 2292//2292 -f 2292//2292 2786//2786 2293//2293 -f 2267//2267 2266//2266 2428//2428 -f 2428//2428 2266//2266 2787//2787 -f 2426//2426 2427//2427 2788//2788 -f 2789//2789 2790//2790 2791//2791 -f 2791//2791 2790//2790 2792//2792 -f 2791//2791 2792//2792 2793//2793 -f 2793//2793 2792//2792 2788//2788 -f 2793//2793 2788//2788 2794//2794 -f 2794//2794 2788//2788 2427//2427 -f 2794//2794 2427//2427 2428//2428 -f 2423//2423 2424//2424 2795//2795 -f 2795//2795 2424//2424 2426//2426 -f 2426//2426 2788//2788 2795//2795 -f 2795//2795 2788//2788 2792//2792 -f 2795//2795 2792//2792 2796//2796 -f 2796//2796 2792//2792 2790//2790 -f 2796//2796 2790//2790 2797//2797 -f 2419//2419 2421//2421 2798//2798 -f 2798//2798 2421//2421 2423//2423 -f 2789//2789 2799//2799 2790//2790 -f 2790//2790 2799//2799 2800//2800 -f 2790//2790 2800//2800 2797//2797 -f 2797//2797 2800//2800 2801//2801 -f 2797//2797 2801//2801 2802//2802 -f 2423//2423 2795//2795 2798//2798 -f 2798//2798 2795//2795 2796//2796 -f 2798//2798 2796//2796 2803//2803 -f 2803//2803 2796//2796 2797//2797 -f 2803//2803 2797//2797 2804//2804 -f 2804//2804 2797//2797 2802//2802 -f 2804//2804 2802//2802 2805//2805 -f 2419//2419 2798//2798 2806//2806 -f 2806//2806 2798//2798 2803//2803 -f 2806//2806 2803//2803 2807//2807 -f 2807//2807 2803//2803 2804//2804 -f 2807//2807 2804//2804 2808//2808 -f 2808//2808 2804//2804 2805//2805 -f 2808//2808 2805//2805 2809//2809 -f 2810//2810 2811//2811 2812//2812 -f 2812//2812 2811//2811 2813//2813 -f 2812//2812 2813//2813 2814//2814 -f 2814//2814 2813//2813 2815//2815 -f 2816//2816 2817//2817 2815//2815 -f 2815//2815 2817//2817 2818//2818 -f 2815//2815 2818//2818 2814//2814 -f 2819//2819 2820//2820 2816//2816 -f 2816//2816 2820//2820 2821//2821 -f 2816//2816 2821//2821 2817//2817 -f 2811//2811 2822//2822 2813//2813 -f 2813//2813 2822//2822 2823//2823 -f 2813//2813 2823//2823 2815//2815 -f 2815//2815 2823//2823 2824//2824 -f 2815//2815 2824//2824 2816//2816 -f 2816//2816 2824//2824 2825//2825 -f 2816//2816 2825//2825 2819//2819 -f 2819//2819 2825//2825 2826//2826 -f 2822//2822 2827//2827 2823//2823 -f 2823//2823 2827//2827 2828//2828 -f 2823//2823 2828//2828 2824//2824 -f 2824//2824 2828//2828 2829//2829 -f 2824//2824 2829//2829 2825//2825 -f 2825//2825 2829//2829 2830//2830 -f 2825//2825 2830//2830 2826//2826 -f 2826//2826 2830//2830 2831//2831 -f 2827//2827 2418//2418 2828//2828 -f 2828//2828 2418//2418 2417//2417 -f 2828//2828 2417//2417 2829//2829 -f 2829//2829 2417//2417 2416//2416 -f 2829//2829 2416//2416 2830//2830 -f 2830//2830 2416//2416 2415//2415 -f 2830//2830 2415//2415 2831//2831 -f 2831//2831 2415//2415 2414//2414 -f 2418//2418 2832//2832 2190//2190 -f 2190//2190 2832//2832 2191//2191 -f 872//872 2210//2210 874//874 -f 874//874 2210//2210 2209//2209 -f 874//874 2209//2209 2832//2832 -f 2832//2832 2209//2209 2208//2208 -f 2189//2189 2187//2187 2185//2185 -f 854//854 852//852 2833//2833 -f 864//864 2834//2834 866//866 -f 866//866 2834//2834 2833//2833 -f 866//866 2833//2833 868//868 -f 2182//2182 2835//2835 2836//2836 -f 2180//2180 2179//2179 2832//2832 -f 2832//2832 2179//2179 876//876 -f 2832//2832 876//876 874//874 -f 2185//2185 2191//2191 2189//2189 -f 2189//2189 2191//2191 2832//2832 -f 2189//2189 2832//2832 2196//2196 -f 2196//2196 2832//2832 2208//2208 -f 2196//2196 2208//2208 2195//2195 -f 2833//2833 2837//2837 854//854 -f 854//854 2837//2837 2703//2703 -f 854//854 2703//2703 856//856 -f 856//856 2703//2703 2199//2199 -f 856//856 2199//2199 858//858 -f 858//858 2199//2199 2202//2202 -f 858//858 2202//2202 860//860 -f 860//860 2202//2202 2204//2204 -f 860//860 2204//2204 862//862 -f 862//862 2204//2204 2198//2198 -f 862//862 2198//2198 2208//2208 -f 2208//2208 2198//2198 2194//2194 -f 2208//2208 2194//2194 2195//2195 -f 870//870 2212//2212 872//872 -f 872//872 2212//2212 2211//2211 -f 872//872 2211//2211 2210//2210 -f 2182//2182 2836//2836 2183//2183 -f 2835//2835 2182//2182 2838//2838 -f 2838//2838 2182//2182 2181//2181 -f 2838//2838 2181//2181 2839//2839 -f 2832//2832 2840//2840 2180//2180 -f 2180//2180 2840//2840 2841//2841 -f 2180//2180 2841//2841 2181//2181 -f 2181//2181 2841//2841 2842//2842 -f 2181//2181 2842//2842 2839//2839 -f 2836//2836 2843//2843 2183//2183 -f 2183//2183 2843//2843 2844//2844 -f 2183//2183 2844//2844 864//864 -f 864//864 2844//2844 2845//2845 -f 864//864 2845//2845 2834//2834 -f 852//852 850//850 2833//2833 -f 2833//2833 850//850 2212//2212 -f 2833//2833 2212//2212 868//868 -f 868//868 2212//2212 870//870 -f 2522//2522 2695//2695 2523//2523 -f 2523//2523 2695//2695 2846//2846 -f 2516//2516 2519//2519 2847//2847 -f 2519//2519 2521//2521 2848//2848 -f 2521//2521 2523//2523 2849//2849 -f 2521//2521 2849//2849 2848//2848 -f 2848//2848 2849//2849 2850//2850 -f 2848//2848 2850//2850 2851//2851 -f 2851//2851 2850//2850 2852//2852 -f 2851//2851 2852//2852 2853//2853 -f 2853//2853 2852//2852 1551//1551 -f 2853//2853 1551//1551 2854//2854 -f 2519//2519 2848//2848 2847//2847 -f 2847//2847 2848//2848 2851//2851 -f 2847//2847 2851//2851 2855//2855 -f 2855//2855 2851//2851 2853//2853 -f 2855//2855 2853//2853 2856//2856 -f 2856//2856 2853//2853 2854//2854 -f 2856//2856 2854//2854 2857//2857 -f 2516//2516 2847//2847 2858//2858 -f 2858//2858 2847//2847 2855//2855 -f 2858//2858 2855//2855 2859//2859 -f 2859//2859 2855//2855 2856//2856 -f 2859//2859 2856//2856 2860//2860 -f 2860//2860 2856//2856 2857//2857 -f 2860//2860 2857//2857 2861//2861 -f 2862//2862 2863//2863 2864//2864 -f 2863//2863 2865//2865 2866//2866 -f 2865//2865 1550//1550 2867//2867 -f 2865//2865 2867//2867 2866//2866 -f 2866//2866 2867//2867 2868//2868 -f 2866//2866 2868//2868 2869//2869 -f 2869//2869 2868//2868 2870//2870 -f 2869//2869 2870//2870 2871//2871 -f 2871//2871 2870//2870 2515//2515 -f 2871//2871 2515//2515 2514//2514 -f 2863//2863 2866//2866 2864//2864 -f 2864//2864 2866//2866 2869//2869 -f 2864//2864 2869//2869 2872//2872 -f 2872//2872 2869//2869 2871//2871 -f 2872//2872 2871//2871 2873//2873 -f 2873//2873 2871//2871 2514//2514 -f 2873//2873 2514//2514 2513//2513 -f 2862//2862 2864//2864 2874//2874 -f 2874//2874 2864//2864 2872//2872 -f 2874//2874 2872//2872 2875//2875 -f 2875//2875 2872//2872 2873//2873 -f 2875//2875 2873//2873 2876//2876 -f 2876//2876 2873//2873 2513//2513 -f 2876//2876 2513//2513 2512//2512 -f 2515//2515 2877//2877 2223//2223 -f 2223//2223 2877//2877 2221//2221 -f 842//842 840//840 2221//2221 -f 846//846 2878//2878 848//848 -f 848//848 2878//2878 2879//2879 -f 848//848 2879//2879 2226//2226 -f 2221//2221 840//840 2218//2218 -f 2218//2218 840//840 838//838 -f 2218//2218 838//838 2213//2213 -f 2227//2227 2226//2226 830//830 -f 842//842 2221//2221 844//844 -f 844//844 2221//2221 2877//2877 -f 844//844 2877//2877 846//846 -f 846//846 2877//2877 2880//2880 -f 846//846 2880//2880 2878//2878 -f 2227//2227 830//830 2228//2228 -f 2228//2228 830//830 828//828 -f 2228//2228 828//828 2229//2229 -f 2225//2225 2235//2235 2237//2237 -f 2237//2237 2235//2235 2234//2234 -f 2237//2237 2234//2234 2240//2240 -f 2240//2240 2234//2234 2244//2244 -f 2244//2244 2234//2234 2233//2233 -f 2244//2244 2233//2233 2881//2881 -f 2881//2881 2233//2233 2232//2232 -f 2881//2881 2232//2232 2882//2882 -f 2882//2882 2232//2232 2231//2231 -f 2882//2882 2231//2231 2879//2879 -f 2879//2879 2231//2231 834//834 -f 2879//2879 834//834 2226//2226 -f 2226//2226 834//834 832//832 -f 2226//2226 832//832 830//830 -f 2213//2213 838//838 2214//2214 -f 2214//2214 838//838 836//836 -f 2214//2214 836//836 2225//2225 -f 2225//2225 836//836 2230//2230 -f 2225//2225 2230//2230 2229//2229 -f 828//828 826//826 2229//2229 -f 2229//2229 826//826 824//824 -f 2229//2229 824//824 2225//2225 -f 2225//2225 824//824 822//822 -f 2225//2225 822//822 2235//2235 -f 2245//2245 2244//2244 2475//2475 -f 2475//2475 2244//2244 2881//2881 -f 2469//2469 2472//2472 2883//2883 -f 2472//2472 2474//2474 2884//2884 -f 2474//2474 2475//2475 2885//2885 -f 2474//2474 2885//2885 2884//2884 -f 2884//2884 2885//2885 2886//2886 -f 2884//2884 2886//2886 2887//2887 -f 2887//2887 2886//2886 2888//2888 -f 2887//2887 2888//2888 2889//2889 -f 2889//2889 2888//2888 1552//1552 -f 2889//2889 1552//1552 2890//2890 -f 2472//2472 2884//2884 2883//2883 -f 2883//2883 2884//2884 2887//2887 -f 2883//2883 2887//2887 2891//2891 -f 2891//2891 2887//2887 2889//2889 -f 2891//2891 2889//2889 2892//2892 -f 2892//2892 2889//2889 2890//2890 -f 2892//2892 2890//2890 2893//2893 -f 2469//2469 2883//2883 2894//2894 -f 2894//2894 2883//2883 2891//2891 -f 2894//2894 2891//2891 2895//2895 -f 2895//2895 2891//2891 2892//2892 -f 2895//2895 2892//2892 2896//2896 -f 2896//2896 2892//2892 2893//2893 -f 2896//2896 2893//2893 2897//2897 -f 2898//2898 2899//2899 2900//2900 -f 2899//2899 2901//2901 2902//2902 -f 2901//2901 1553//1553 2903//2903 -f 2901//2901 2903//2903 2902//2902 -f 2902//2902 2903//2903 2904//2904 -f 2902//2902 2904//2904 2905//2905 -f 2905//2905 2904//2904 2906//2906 -f 2905//2905 2906//2906 2907//2907 -f 2907//2907 2906//2906 2468//2468 -f 2907//2907 2468//2468 2467//2467 -f 2899//2899 2902//2902 2900//2900 -f 2900//2900 2902//2902 2905//2905 -f 2900//2900 2905//2905 2908//2908 -f 2908//2908 2905//2905 2907//2907 -f 2908//2908 2907//2907 2909//2909 -f 2909//2909 2907//2907 2467//2467 -f 2909//2909 2467//2467 2466//2466 -f 2898//2898 2900//2900 2910//2910 -f 2910//2910 2900//2900 2908//2908 -f 2910//2910 2908//2908 2911//2911 -f 2911//2911 2908//2908 2909//2909 -f 2911//2911 2909//2909 2912//2912 -f 2912//2912 2909//2909 2466//2466 -f 2912//2912 2466//2466 2465//2465 -f 2468//2468 2913//2913 2261//2261 -f 2261//2261 2913//2913 2259//2259 -f 2914//2914 2915//2915 2246//2246 -f 2246//2246 2915//2915 2247//2247 -f 818//818 2916//2916 820//820 -f 820//820 2916//2916 2917//2917 -f 820//820 2917//2917 2246//2246 -f 2246//2246 2917//2917 2918//2918 -f 2246//2246 2918//2918 2914//2914 -f 2249//2249 2248//2248 2919//2919 -f 802//802 2920//2920 804//804 -f 804//804 2920//2920 2921//2921 -f 804//804 2921//2921 806//806 -f 806//806 2921//2921 2916//2916 -f 806//806 2916//2916 2275//2275 -f 2275//2275 2916//2916 2276//2276 -f 2276//2276 2916//2916 818//818 -f 2276//2276 818//818 2277//2277 -f 2277//2277 818//818 816//816 -f 2277//2277 816//816 2278//2278 -f 2278//2278 816//816 814//814 -f 2278//2278 814//814 812//812 -f 2264//2264 2265//2265 2279//2279 -f 2279//2279 2265//2265 2262//2262 -f 2279//2279 2262//2262 794//794 -f 794//794 2262//2262 2252//2252 -f 794//794 2252//2252 796//796 -f 796//796 2252//2252 2251//2251 -f 796//796 2251//2251 798//798 -f 798//798 2251//2251 2256//2256 -f 798//798 2256//2256 800//800 -f 800//800 2256//2256 2259//2259 -f 800//800 2259//2259 802//802 -f 802//802 2259//2259 2913//2913 -f 802//802 2913//2913 2920//2920 -f 2266//2266 2268//2268 812//812 -f 2279//2279 2278//2278 2264//2264 -f 2264//2264 2278//2278 812//812 -f 2264//2264 812//812 2263//2263 -f 2263//2263 812//812 2268//2268 -f 2263//2263 2268//2268 2272//2272 -f 812//812 810//810 2266//2266 -f 2266//2266 810//810 808//808 -f 2266//2266 808//808 2787//2787 -f 2787//2787 808//808 2250//2250 -f 2787//2787 2250//2250 2922//2922 -f 2922//2922 2250//2250 2249//2249 -f 2922//2922 2249//2249 2923//2923 -f 2923//2923 2249//2249 2919//2919 -f 2915//2915 2924//2924 2247//2247 -f 2247//2247 2924//2924 2925//2925 -f 2247//2247 2925//2925 2248//2248 -f 2248//2248 2925//2925 2926//2926 -f 2248//2248 2926//2926 2919//2919 -f 788//788 786//786 2927//2927 -f 2928//2928 784//784 782//782 -f 778//778 2282//2282 2299//2299 -f 2305//2305 792//792 2929//2929 -f 2929//2929 792//792 790//790 -f 2929//2929 790//790 2930//2930 -f 2930//2930 790//790 788//788 -f 2930//2930 788//788 2931//2931 -f 2931//2931 788//788 2927//2927 -f 2928//2928 2932//2932 784//784 -f 784//784 2932//2932 2933//2933 -f 784//784 2933//2933 786//786 -f 786//786 2933//2933 2934//2934 -f 786//786 2934//2934 2927//2927 -f 780//780 2935//2935 782//782 -f 782//782 2935//2935 2936//2936 -f 782//782 2936//2936 2928//2928 -f 2284//2284 2937//2937 780//780 -f 780//780 2937//2937 2938//2938 -f 780//780 2938//2938 2935//2935 -f 2281//2281 2297//2297 2282//2282 -f 2282//2282 2297//2297 2298//2298 -f 2282//2282 2298//2298 2299//2299 -f 2311//2311 2297//2297 2307//2307 -f 2307//2307 2297//2297 2281//2281 -f 2307//2307 2281//2281 2305//2305 -f 2305//2305 2281//2281 2280//2280 -f 2305//2305 2280//2280 792//792 -f 2303//2303 2939//2939 2304//2304 -f 2304//2304 2939//2939 2940//2940 -f 2304//2304 2940//2940 766//766 -f 766//766 2940//2940 2937//2937 -f 778//778 776//776 2282//2282 -f 2282//2282 776//776 774//774 -f 2282//2282 774//774 2283//2283 -f 2283//2283 774//774 772//772 -f 2283//2283 772//772 2284//2284 -f 2284//2284 772//772 770//770 -f 2284//2284 770//770 2937//2937 -f 2937//2937 770//770 768//768 -f 2937//2937 768//768 766//766 -f 2299//2299 2296//2296 778//778 -f 778//778 2296//2296 2290//2290 -f 778//778 2290//2290 2300//2300 -f 2300//2300 2290//2290 2288//2288 -f 2300//2300 2288//2288 2301//2301 -f 2301//2301 2288//2288 2286//2286 -f 2301//2301 2286//2286 2302//2302 -f 2302//2302 2286//2286 2293//2293 -f 2302//2302 2293//2293 2303//2303 -f 2303//2303 2293//2293 2786//2786 -f 2303//2303 2786//2786 2939//2939 -f 2306//2306 2305//2305 2578//2578 -f 2578//2578 2305//2305 2929//2929 -f 2572//2572 2575//2575 2941//2941 -f 2575//2575 2577//2577 2942//2942 -f 2577//2577 2578//2578 2943//2943 -f 2577//2577 2943//2943 2942//2942 -f 2942//2942 2943//2943 2944//2944 -f 2942//2942 2944//2944 2945//2945 -f 2945//2945 2944//2944 2946//2946 -f 2945//2945 2946//2946 2947//2947 -f 2947//2947 2946//2946 2948//2948 -f 2947//2947 2948//2948 2949//2949 -f 2575//2575 2942//2942 2941//2941 -f 2941//2941 2942//2942 2945//2945 -f 2941//2941 2945//2945 2950//2950 -f 2950//2950 2945//2945 2947//2947 -f 2950//2950 2947//2947 2951//2951 -f 2951//2951 2947//2947 2949//2949 -f 2951//2951 2949//2949 2952//2952 -f 2572//2572 2941//2941 2953//2953 -f 2953//2953 2941//2941 2950//2950 -f 2953//2953 2950//2950 2954//2954 -f 2954//2954 2950//2950 2951//2951 -f 2954//2954 2951//2951 2955//2955 -f 2955//2955 2951//2951 2952//2952 -f 2955//2955 2952//2952 2956//2956 -f 2344//2344 680//680 2957//2957 -f 2555//2555 2553//2553 2957//2957 -f 2501//2501 2499//2499 2958//2958 -f 2895//2895 2896//2896 2897//2897 -f 650//650 648//648 2959//2959 -f 638//638 636//636 2960//2960 -f 2960//2960 636//636 634//634 -f 2960//2960 634//634 2961//2961 -f 2961//2961 634//634 2361//2361 -f 2961//2961 2361//2361 2360//2360 -f 2957//2957 646//646 644//644 -f 2957//2957 644//644 2962//2962 -f 650//650 2959//2959 652//652 -f 652//652 2959//2959 2958//2958 -f 652//652 2958//2958 2354//2354 -f 2354//2354 2958//2958 2355//2355 -f 2355//2355 2958//2958 2499//2499 -f 2355//2355 2499//2499 2497//2497 -f 2497//2497 2496//2496 2355//2355 -f 2355//2355 2496//2496 2491//2491 -f 2355//2355 2491//2491 2963//2963 -f 2338//2338 2964//2964 696//696 -f 696//696 2964//2964 2360//2360 -f 696//696 2360//2360 698//698 -f 698//698 2360//2360 2359//2359 -f 698//698 2359//2359 700//700 -f 2335//2335 2963//2963 2336//2336 -f 2336//2336 2963//2963 2964//2964 -f 2336//2336 2964//2964 2337//2337 -f 2337//2337 2964//2964 2338//2338 -f 700//700 2359//2359 702//702 -f 702//702 2359//2359 2358//2358 -f 702//702 2358//2358 704//704 -f 2335//2335 2334//2334 2963//2963 -f 2963//2963 2334//2334 708//708 -f 2963//2963 708//708 2355//2355 -f 2355//2355 708//708 706//706 -f 2355//2355 706//706 2356//2356 -f 2356//2356 706//706 704//704 -f 2356//2356 704//704 2357//2357 -f 2357//2357 704//704 2358//2358 -f 2369//2369 2965//2965 614//614 -f 614//614 2965//2965 2966//2966 -f 614//614 2966//2966 616//616 -f 616//616 2966//2966 618//618 -f 2966//2966 2656//2656 618//618 -f 618//618 2656//2656 2655//2655 -f 618//618 2655//2655 620//620 -f 620//620 2655//2655 2967//2967 -f 628//628 626//626 2968//2968 -f 2968//2968 626//626 624//624 -f 2968//2968 624//624 2967//2967 -f 2967//2967 624//624 622//622 -f 2967//2967 622//622 620//620 -f 2478//2478 2477//2477 2969//2969 -f 2970//2970 2363//2363 2362//2362 -f 2434//2434 2432//2432 2363//2363 -f 2419//2419 2806//2806 2807//2807 -f 2432//2432 2431//2431 2363//2363 -f 2363//2363 2431//2431 2420//2420 -f 2363//2363 2420//2420 2809//2809 -f 2809//2809 2420//2420 2419//2419 -f 2809//2809 2419//2419 2808//2808 -f 2808//2808 2419//2419 2807//2807 -f 746//746 744//744 2366//2366 -f 2366//2366 744//744 2367//2367 -f 744//744 742//742 2367//2367 -f 2367//2367 742//742 740//740 -f 2367//2367 740//740 2368//2368 -f 2366//2366 2365//2365 746//746 -f 746//746 2365//2365 2364//2364 -f 746//746 2364//2364 748//748 -f 748//748 2364//2364 2363//2363 -f 748//748 2363//2363 750//750 -f 750//750 2363//2363 2809//2809 -f 750//750 2809//2809 2319//2319 -f 2368//2368 740//740 2820//2820 -f 2820//2820 740//740 738//738 -f 2820//2820 738//738 2323//2323 -f 2323//2323 2322//2322 2820//2820 -f 2820//2820 2322//2322 2321//2321 -f 2820//2820 2321//2321 2809//2809 -f 2809//2809 2321//2321 2320//2320 -f 2809//2809 2320//2320 2319//2319 -f 2369//2369 2368//2368 2965//2965 -f 2965//2965 2368//2368 2403//2403 -f 2965//2965 2403//2403 2399//2399 -f 2826//2826 2831//2831 2819//2819 -f 2819//2819 2831//2831 2414//2414 -f 2819//2819 2414//2414 2820//2820 -f 2820//2820 2414//2414 2410//2410 -f 2820//2820 2410//2410 2368//2368 -f 2368//2368 2410//2410 2409//2409 -f 2368//2368 2409//2409 2403//2403 -f 2971//2971 2370//2370 2725//2725 -f 2722//2722 2723//2723 2370//2370 -f 2370//2370 2723//2723 2724//2724 -f 2370//2370 2724//2724 2725//2725 -f 2325//2325 2324//2324 2965//2965 -f 2965//2965 2324//2324 736//736 -f 2965//2965 736//736 2966//2966 -f 2966//2966 736//736 734//734 -f 2966//2966 734//734 732//732 -f 730//730 728//728 2971//2971 -f 2971//2971 728//728 726//726 -f 2971//2971 726//726 2370//2370 -f 2370//2370 726//726 724//724 -f 2370//2370 724//724 2371//2371 -f 2371//2371 724//724 2328//2328 -f 2371//2371 2328//2328 2382//2382 -f 2382//2382 2328//2328 2327//2327 -f 2382//2382 2327//2327 2383//2383 -f 2383//2383 2327//2327 2326//2326 -f 2383//2383 2326//2326 2385//2385 -f 2385//2385 2326//2326 2325//2325 -f 2385//2385 2325//2325 2387//2387 -f 2387//2387 2325//2325 2965//2965 -f 2387//2387 2965//2965 2389//2389 -f 2399//2399 2087//2087 2965//2965 -f 2965//2965 2087//2087 2391//2391 -f 2965//2965 2391//2391 2389//2389 -f 2434//2434 2363//2363 2436//2436 -f 2436//2436 2363//2363 2970//2970 -f 2436//2436 2970//2970 2438//2438 -f 2438//2438 2970//2970 2444//2444 -f 2438//2438 2444//2444 2100//2100 -f 754//754 752//752 2969//2969 -f 2969//2969 752//752 2970//2970 -f 2969//2969 2970//2970 632//632 -f 632//632 2970//2970 2362//2362 -f 2452//2452 2450//2450 2970//2970 -f 2970//2970 2450//2450 2449//2449 -f 2970//2970 2449//2449 2444//2444 -f 2316//2316 2315//2315 2456//2456 -f 2456//2456 2315//2315 2458//2458 -f 2898//2898 764//764 2897//2897 -f 2897//2897 764//764 762//762 -f 762//762 760//760 2897//2897 -f 2897//2897 760//760 758//758 -f 2897//2897 758//758 2969//2969 -f 2969//2969 758//758 756//756 -f 2969//2969 756//756 754//754 -f 2911//2911 2912//2912 2465//2465 -f 2456//2456 2454//2454 2316//2316 -f 2316//2316 2454//2454 2452//2452 -f 2316//2316 2452//2452 2317//2317 -f 2317//2317 2452//2452 2970//2970 -f 2317//2317 2970//2970 2318//2318 -f 2318//2318 2970//2970 752//752 -f 2911//2911 2465//2465 2910//2910 -f 2315//2315 2314//2314 2458//2458 -f 2458//2458 2314//2314 764//764 -f 2458//2458 764//764 2465//2465 -f 2465//2465 764//764 2898//2898 -f 2465//2465 2898//2898 2910//2910 -f 2894//2894 2895//2895 2469//2469 -f 2469//2469 2895//2895 2897//2897 -f 2469//2469 2897//2897 2470//2470 -f 2470//2470 2897//2897 2969//2969 -f 2470//2470 2969//2969 2489//2489 -f 2489//2489 2969//2969 2477//2477 -f 632//632 630//630 2969//2969 -f 2969//2969 630//630 628//628 -f 2969//2969 628//628 2478//2478 -f 2478//2478 628//628 2968//2968 -f 2478//2478 2968//2968 2483//2483 -f 2483//2483 2968//2968 2484//2484 -f 2512//2512 2505//2505 2958//2958 -f 2958//2958 2505//2505 2503//2503 -f 2958//2958 2503//2503 2501//2501 -f 2875//2875 2876//2876 2512//2512 -f 2352//2352 2351//2351 2862//2862 -f 2353//2353 2958//2958 654//654 -f 654//654 2958//2958 2959//2959 -f 654//654 2959//2959 656//656 -f 656//656 2959//2959 658//658 -f 2353//2353 2352//2352 2958//2958 -f 2958//2958 2352//2352 2862//2862 -f 2958//2958 2862//2862 2512//2512 -f 2512//2512 2862//2862 2874//2874 -f 2512//2512 2874//2874 2875//2875 -f 2517//2517 2516//2516 2861//2861 -f 2860//2860 2861//2861 2859//2859 -f 2859//2859 2861//2861 2516//2516 -f 2859//2859 2516//2516 2858//2858 -f 2351//2351 2350//2350 2862//2862 -f 2862//2862 2350//2350 2349//2349 -f 2862//2862 2349//2349 2861//2861 -f 2861//2861 2349//2349 666//666 -f 2861//2861 666//666 2517//2517 -f 2517//2517 666//666 664//664 -f 2517//2517 664//664 2526//2526 -f 2526//2526 664//664 662//662 -f 2526//2526 662//662 2527//2527 -f 2527//2527 662//662 660//660 -f 2527//2527 660//660 2529//2529 -f 2529//2529 660//660 658//658 -f 2529//2529 658//658 2531//2531 -f 2531//2531 658//658 2959//2959 -f 2531//2531 2959//2959 2533//2533 -f 646//646 2957//2957 648//648 -f 648//648 2957//2957 2553//2553 -f 648//648 2553//2553 2959//2959 -f 2959//2959 2553//2553 2551//2551 -f 2959//2959 2551//2551 2550//2550 -f 2550//2550 2131//2131 2959//2959 -f 2959//2959 2131//2131 2535//2535 -f 2959//2959 2535//2535 2533//2533 -f 2675//2675 2559//2559 2957//2957 -f 2957//2957 2559//2559 2557//2557 -f 2957//2957 2557//2557 2555//2555 -f 2972//2972 2675//2675 2973//2973 -f 2973//2973 2675//2675 2974//2974 -f 2973//2973 2974//2974 2975//2975 -f 2953//2953 2954//2954 2976//2976 -f 2962//2962 2584//2584 2582//2582 -f 2582//2582 2581//2581 2962//2962 -f 2962//2962 2581//2581 2573//2573 -f 2962//2962 2573//2573 2976//2976 -f 2976//2976 2573//2573 2572//2572 -f 2976//2976 2572//2572 2953//2953 -f 644//644 642//642 2962//2962 -f 2962//2962 642//642 640//640 -f 2962//2962 640//640 2584//2584 -f 2584//2584 640//640 638//638 -f 2584//2584 638//638 2586//2586 -f 2586//2586 638//638 2960//2960 -f 2586//2586 2960//2960 2588//2588 -f 2588//2588 2960//2960 2594//2594 -f 2588//2588 2594//2594 2113//2113 -f 2340//2340 2339//2339 2961//2961 -f 2961//2961 2339//2339 694//694 -f 2961//2961 694//694 2960//2960 -f 2602//2602 2600//2600 2960//2960 -f 2960//2960 2600//2600 2599//2599 -f 2960//2960 2599//2599 2594//2594 -f 688//688 686//686 2606//2606 -f 2977//2977 2342//2342 2961//2961 -f 2961//2961 2342//2342 2341//2341 -f 2961//2961 2341//2341 2340//2340 -f 2606//2606 686//686 2608//2608 -f 2608//2608 686//686 684//684 -f 2608//2608 684//684 2615//2615 -f 2615//2615 684//684 682//682 -f 2615//2615 682//682 2977//2977 -f 2977//2977 682//682 2343//2343 -f 2977//2977 2343//2343 2342//2342 -f 2606//2606 2604//2604 688//688 -f 688//688 2604//2604 2602//2602 -f 688//688 2602//2602 690//690 -f 690//690 2602//2602 2960//2960 -f 690//690 2960//2960 692//692 -f 692//692 2960//2960 694//694 -f 2784//2784 2785//2785 2783//2783 -f 2783//2783 2785//2785 2615//2615 -f 2783//2783 2615//2615 2770//2770 -f 2770//2770 2615//2615 2769//2769 -f 2769//2769 2615//2615 2977//2977 -f 2769//2769 2977//2977 2768//2768 -f 2768//2768 2977//2977 2766//2766 -f 2768//2768 2766//2766 2767//2767 -f 2360//2360 2636//2636 2961//2961 -f 2961//2961 2636//2636 2634//2634 -f 2961//2961 2634//2634 2632//2632 -f 2632//2632 2631//2631 2961//2961 -f 2961//2961 2631//2631 2620//2620 -f 2961//2961 2620//2620 2977//2977 -f 2977//2977 2620//2620 2619//2619 -f 2977//2977 2619//2619 2766//2766 -f 2655//2655 2661//2661 2967//2967 -f 2967//2967 2661//2661 2647//2647 -f 2967//2967 2647//2647 2964//2964 -f 2964//2964 2647//2647 2640//2640 -f 2964//2964 2640//2640 2360//2360 -f 2360//2360 2640//2640 2638//2638 -f 2360//2360 2638//2638 2636//2636 -f 2668//2668 2652//2652 2966//2966 -f 2966//2966 2652//2652 2651//2651 -f 2966//2966 2651//2651 2656//2656 -f 2725//2725 2726//2726 2971//2971 -f 2971//2971 2726//2726 2739//2739 -f 2971//2971 2739//2739 2740//2740 -f 732//732 730//730 2966//2966 -f 2966//2966 730//730 2971//2971 -f 2966//2966 2971//2971 2668//2668 -f 2668//2668 2971//2971 2740//2740 -f 2668//2668 2740//2740 2741//2741 -f 714//714 712//712 2964//2964 -f 2329//2329 722//722 2968//2968 -f 2968//2968 722//722 2963//2963 -f 2968//2968 2963//2963 2484//2484 -f 2484//2484 2963//2963 2491//2491 -f 2964//2964 712//712 2967//2967 -f 2967//2967 712//712 710//710 -f 2967//2967 710//710 2333//2333 -f 2333//2333 2332//2332 2967//2967 -f 2967//2967 2332//2332 2331//2331 -f 2967//2967 2331//2331 2968//2968 -f 2968//2968 2331//2331 2330//2330 -f 2968//2968 2330//2330 2329//2329 -f 722//722 720//720 2963//2963 -f 2963//2963 720//720 718//718 -f 2963//2963 718//718 2964//2964 -f 2964//2964 718//718 716//716 -f 2964//2964 716//716 714//714 -f 2675//2675 2957//2957 2974//2974 -f 2974//2974 2957//2957 680//680 -f 2974//2974 680//680 678//678 -f 678//678 676//676 2974//2974 -f 2974//2974 676//676 674//674 -f 2974//2974 674//674 2976//2976 -f 674//674 672//672 2976//2976 -f 2976//2976 672//672 670//670 -f 2976//2976 670//670 2962//2962 -f 2962//2962 670//670 668//668 -f 2962//2962 668//668 2348//2348 -f 2348//2348 2347//2347 2962//2962 -f 2962//2962 2347//2347 2346//2346 -f 2962//2962 2346//2346 2957//2957 -f 2957//2957 2346//2346 2345//2345 -f 2957//2957 2345//2345 2344//2344 -f 2975//2975 2974//2974 2978//2978 -f 2978//2978 2974//2974 2976//2976 -f 2978//2978 2976//2976 2956//2956 -f 2956//2956 2976//2976 2954//2954 -f 2956//2956 2954//2954 2955//2955 -f 2979//2979 2980//2980 2981//2981 -f 2679//2679 2982//2982 2983//2983 -f 2983//2983 2982//2982 2984//2984 -f 2983//2983 2984//2984 2985//2985 -f 2985//2985 2984//2984 2981//2981 -f 2985//2985 2981//2981 2986//2986 -f 2986//2986 2981//2981 2980//2980 -f 2986//2986 2980//2980 2987//2987 -f 2988//2988 2989//2989 2990//2990 -f 2990//2990 2989//2989 2979//2979 -f 2979//2979 2981//2981 2990//2990 -f 2990//2990 2981//2981 2984//2984 -f 2990//2990 2984//2984 2991//2991 -f 2991//2991 2984//2984 2982//2982 -f 2991//2991 2982//2982 2992//2992 -f 2978//2978 2993//2993 2994//2994 -f 2994//2994 2993//2993 2988//2988 -f 2679//2679 2680//2680 2982//2982 -f 2982//2982 2680//2680 2681//2681 -f 2982//2982 2681//2681 2992//2992 -f 2992//2992 2681//2681 2678//2678 -f 2992//2992 2678//2678 2677//2677 -f 2988//2988 2990//2990 2994//2994 -f 2994//2994 2990//2990 2991//2991 -f 2994//2994 2991//2991 2995//2995 -f 2995//2995 2991//2991 2992//2992 -f 2995//2995 2992//2992 2996//2996 -f 2996//2996 2992//2992 2677//2677 -f 2996//2996 2677//2677 2676//2676 -f 2978//2978 2994//2994 2975//2975 -f 2975//2975 2994//2994 2995//2995 -f 2975//2975 2995//2995 2973//2973 -f 2973//2973 2995//2995 2996//2996 -f 2973//2973 2996//2996 2972//2972 -f 2972//2972 2996//2996 2676//2676 -f 2972//2972 2676//2676 2675//2675 -f 2679//2679 2997//2997 2571//2571 -f 2571//2571 2997//2997 2690//2690 -f 2682//2682 612//612 2998//2998 -f 608//608 2999//2999 3000//3000 -f 608//608 3000//3000 610//610 -f 2699//2699 2698//2698 3001//3001 -f 3001//3001 2698//2698 598//598 -f 3001//3001 598//598 2998//2998 -f 3000//3000 3002//3002 610//610 -f 610//610 3002//3002 3003//3003 -f 610//610 3003//3003 612//612 -f 612//612 3003//3003 3004//3004 -f 612//612 3004//3004 2998//2998 -f 606//606 3005//3005 608//608 -f 608//608 3005//3005 3006//3006 -f 608//608 3006//3006 2999//2999 -f 604//604 602//602 2997//2997 -f 2997//2997 602//602 2690//2690 -f 2997//2997 3007//3007 604//604 -f 604//604 3007//3007 3008//3008 -f 604//604 3008//3008 606//606 -f 606//606 3008//3008 3009//3009 -f 606//606 3009//3009 3005//3005 -f 2687//2687 2685//2685 2693//2693 -f 2693//2693 2685//2685 2684//2684 -f 602//602 600//600 2690//2690 -f 2690//2690 600//600 2686//2686 -f 2690//2690 2686//2686 2689//2689 -f 2689//2689 2686//2686 2685//2685 -f 2689//2689 2685//2685 2688//2688 -f 2688//2688 2685//2685 2687//2687 -f 2692//2692 2693//2693 588//588 -f 588//588 2693//2693 2684//2684 -f 588//588 2684//2684 590//590 -f 590//590 2684//2684 592//592 -f 598//598 596//596 2998//2998 -f 2998//2998 596//596 594//594 -f 2998//2998 594//594 2682//2682 -f 2682//2682 594//594 592//592 -f 2682//2682 592//592 2683//2683 -f 2683//2683 592//592 2684//2684 -f 3001//3001 3010//3010 2699//2699 -f 2699//2699 3010//3010 2846//2846 -f 2699//2699 2846//2846 2700//2700 -f 2700//2700 2846//2846 2695//2695 -f 2700//2700 2695//2695 2701//2701 -f 2701//2701 2695//2695 2696//2696 -f 2701//2701 2696//2696 2702//2702 -f 2702//2702 2696//2696 2697//2697 -f 2702//2702 2697//2697 586//586 -f 586//586 2697//2697 2694//2694 -f 586//586 2694//2694 588//588 -f 588//588 2694//2694 2691//2691 -f 588//588 2691//2691 2692//2692 -f 3011//3011 3012//3012 3013//3013 -f 3013//3013 3012//3012 3014//3014 -f 3013//3013 3014//3014 3015//3015 -f 2833//2833 2834//2834 3016//3016 -f 3016//3016 2834//2834 3017//3017 -f 3016//3016 3017//3017 3013//3013 -f 3015//3015 3018//3018 3013//3013 -f 3013//3013 3018//3018 3019//3019 -f 3013//3013 3019//3019 3016//3016 -f 3014//3014 3012//3012 2705//2705 -f 2833//2833 3016//3016 2707//2707 -f 3016//3016 3019//3019 2707//2707 -f 2707//2707 3019//3019 3018//3018 -f 2707//2707 3018//3018 2705//2705 -f 2705//2705 3018//3018 3015//3015 -f 2705//2705 3015//3015 3014//3014 -f 2707//2707 2709//2709 2833//2833 -f 2833//2833 2709//2709 2710//2710 -f 2833//2833 2710//2710 2837//2837 -f 2837//2837 2710//2710 2379//2379 -f 2837//2837 2379//2379 2703//2703 -f 2725//2725 2721//2721 2726//2726 -f 2726//2726 2721//2721 2727//2727 -f 2721//2721 2718//2718 2727//2727 -f 2727//2727 2718//2718 2717//2717 -f 2727//2727 2717//2717 2729//2729 -f 2705//2705 2736//2736 2715//2715 -f 2715//2715 2736//2736 2729//2729 -f 2715//2715 2729//2729 2716//2716 -f 2716//2716 2729//2729 2717//2717 -f 2742//2742 2674//2674 2731//2731 -f 2742//2742 2731//2731 2747//2747 -f 2747//2747 2731//2731 2734//2734 -f 2747//2747 2734//2734 2743//2743 -f 2743//2743 2734//2734 3020//3020 -f 3020//3020 2734//2734 2735//2735 -f 3020//3020 2735//2735 3021//3021 -f 3021//3021 2735//2735 3022//3022 -f 3022//3022 2735//2735 2736//2736 -f 3022//3022 2736//2736 3023//3023 -f 3023//3023 3024//3024 3022//3022 -f 3022//3022 3024//3024 3025//3025 -f 3025//3025 3026//3026 3022//3022 -f 3022//3022 3026//3026 3027//3027 -f 3022//3022 3027//3027 3021//3021 -f 3027//3027 3028//3028 3021//3021 -f 3021//3021 3028//3028 3029//3029 -f 3021//3021 3029//3029 3020//3020 -f 3020//3020 3029//3029 2744//2744 -f 3020//3020 2744//2744 2743//2743 -f 3025//3025 3024//3024 2749//2749 -f 2744//2744 3029//3029 2751//2751 -f 3029//3029 3028//3028 2751//2751 -f 2751//2751 3028//3028 3027//3027 -f 2751//2751 3027//3027 2749//2749 -f 2749//2749 3027//3027 3026//3026 -f 2749//2749 3026//3026 3025//3025 -f 2751//2751 2753//2753 2744//2744 -f 2744//2744 2753//2753 2754//2754 -f 2744//2744 2754//2754 2745//2745 -f 2745//2745 2754//2754 2628//2628 -f 2745//2745 2628//2628 2746//2746 -f 2769//2769 2765//2765 2770//2770 -f 2770//2770 2765//2765 2771//2771 -f 2765//2765 2762//2762 2771//2771 -f 2771//2771 2762//2762 2761//2761 -f 2771//2771 2761//2761 2773//2773 -f 2749//2749 2775//2775 2759//2759 -f 2759//2759 2775//2775 2773//2773 -f 2759//2759 2773//2773 2760//2760 -f 2760//2760 2773//2773 2761//2761 -f 2777//2777 2939//2939 2779//2779 -f 2779//2779 2939//2939 2786//2786 -f 2779//2779 2786//2786 2618//2618 -f 3030//3030 3031//3031 2776//2776 -f 2776//2776 3031//3031 3032//3032 -f 2776//2776 3032//3032 2777//2777 -f 2777//2777 3032//3032 2940//2940 -f 2777//2777 2940//2940 2939//2939 -f 3030//3030 2776//2776 3033//3033 -f 3033//3033 2776//2776 2775//2775 -f 3033//3033 2775//2775 3034//3034 -f 3035//3035 2937//2937 2940//2940 -f 3034//3034 3036//3036 3033//3033 -f 3033//3033 3036//3036 3037//3037 -f 3033//3033 3037//3037 3030//3030 -f 3030//3030 3037//3037 3031//3031 -f 2940//2940 3032//3032 3035//3035 -f 3035//3035 3032//3032 3031//3031 -f 3035//3035 3031//3031 3038//3038 -f 3038//3038 3031//3031 3037//3037 -f 3039//3039 3040//3040 3041//3041 -f 3040//3040 3042//3042 3043//3043 -f 3042//3042 2927//2927 2934//2934 -f 3042//3042 2934//2934 3043//3043 -f 3043//3043 2934//2934 2933//2933 -f 3043//3043 2933//2933 3044//3044 -f 3044//3044 2933//2933 2932//2932 -f 3044//3044 2932//2932 3045//3045 -f 3045//3045 2932//2932 2928//2928 -f 3045//3045 2928//2928 3046//3046 -f 3046//3046 2928//2928 2936//2936 -f 3046//3046 2936//2936 3047//3047 -f 3047//3047 2936//2936 2935//2935 -f 3047//3047 2935//2935 3048//3048 -f 3048//3048 2935//2935 2938//2938 -f 3048//3048 2938//2938 3049//3049 -f 2938//2938 2937//2937 3049//3049 -f 3049//3049 2937//2937 3035//3035 -f 3049//3049 3035//3035 3038//3038 -f 3040//3040 3043//3043 3041//3041 -f 3041//3041 3043//3043 3044//3044 -f 3041//3041 3044//3044 3050//3050 -f 3050//3050 3044//3044 3045//3045 -f 3050//3050 3045//3045 3051//3051 -f 3051//3051 3045//3045 3046//3046 -f 3051//3051 3046//3046 3052//3052 -f 3052//3052 3046//3046 3047//3047 -f 3052//3052 3047//3047 3053//3053 -f 3053//3053 3047//3047 3048//3048 -f 3053//3053 3048//3048 3054//3054 -f 3054//3054 3048//3048 3049//3049 -f 3054//3054 3049//3049 3055//3055 -f 3055//3055 3049//3049 3038//3038 -f 3055//3055 3038//3038 3037//3037 -f 3039//3039 3041//3041 3056//3056 -f 3056//3056 3041//3041 3050//3050 -f 3056//3056 3050//3050 3057//3057 -f 3057//3057 3050//3050 3051//3051 -f 3057//3057 3051//3051 3058//3058 -f 3058//3058 3051//3051 3052//3052 -f 3058//3058 3052//3052 3059//3059 -f 3059//3059 3052//3052 3053//3053 -f 3059//3059 3053//3053 3060//3060 -f 3060//3060 3053//3053 3054//3054 -f 3060//3060 3054//3054 3061//3061 -f 3061//3061 3054//3054 3055//3055 -f 3061//3061 3055//3055 3062//3062 -f 3062//3062 3055//3055 3037//3037 -f 3062//3062 3037//3037 3036//3036 -f 3011//3011 3013//3013 3063//3063 -f 3013//3013 3017//3017 3064//3064 -f 3017//3017 2834//2834 2845//2845 -f 3017//3017 2845//2845 3064//3064 -f 3064//3064 2845//2845 2844//2844 -f 3064//3064 2844//2844 3065//3065 -f 3065//3065 2844//2844 2843//2843 -f 3065//3065 2843//2843 3066//3066 -f 3066//3066 2843//2843 2836//2836 -f 3066//3066 2836//2836 3067//3067 -f 3067//3067 2836//2836 2835//2835 -f 3067//3067 2835//2835 3068//3068 -f 3068//3068 2835//2835 2838//2838 -f 3068//3068 2838//2838 3069//3069 -f 3069//3069 2838//2838 2839//2839 -f 3069//3069 2839//2839 3070//3070 -f 2839//2839 2842//2842 3070//3070 -f 3070//3070 2842//2842 3071//3071 -f 3070//3070 3071//3071 3072//3072 -f 3013//3013 3064//3064 3063//3063 -f 3063//3063 3064//3064 3065//3065 -f 3063//3063 3065//3065 3073//3073 -f 3073//3073 3065//3065 3066//3066 -f 3073//3073 3066//3066 3074//3074 -f 3074//3074 3066//3066 3067//3067 -f 3074//3074 3067//3067 3075//3075 -f 3075//3075 3067//3067 3068//3068 -f 3075//3075 3068//3068 3076//3076 -f 3076//3076 3068//3068 3069//3069 -f 3076//3076 3069//3069 3077//3077 -f 3077//3077 3069//3069 3070//3070 -f 3077//3077 3070//3070 3078//3078 -f 3078//3078 3070//3070 3072//3072 -f 3078//3078 3072//3072 3079//3079 -f 3011//3011 3063//3063 3080//3080 -f 3080//3080 3063//3063 3073//3073 -f 3080//3080 3073//3073 3081//3081 -f 3081//3081 3073//3073 3074//3074 -f 3081//3081 3074//3074 3082//3082 -f 3082//3082 3074//3074 3075//3075 -f 3082//3082 3075//3075 3083//3083 -f 3083//3083 3075//3075 3076//3076 -f 3083//3083 3076//3076 3084//3084 -f 3084//3084 3076//3076 3077//3077 -f 3084//3084 3077//3077 3085//3085 -f 3085//3085 3077//3077 3078//3078 -f 3085//3085 3078//3078 3086//3086 -f 3086//3086 3078//3078 3079//3079 -f 3086//3086 3079//3079 3087//3087 -f 3088//3088 3089//3089 3090//3090 -f 3090//3090 3089//3089 3091//3091 -f 3090//3090 3091//3091 3092//3092 -f 2923//2923 2919//2919 3093//3093 -f 3093//3093 2919//2919 3094//3094 -f 3093//3093 3094//3094 3090//3090 -f 3092//3092 3095//3095 3090//3090 -f 3090//3090 3095//3095 3096//3096 -f 3090//3090 3096//3096 3093//3093 -f 3091//3091 3089//3089 2789//2789 -f 2923//2923 3093//3093 2791//2791 -f 3093//3093 3096//3096 2791//2791 -f 2791//2791 3096//3096 3095//3095 -f 2791//2791 3095//3095 2789//2789 -f 2789//2789 3095//3095 3092//3092 -f 2789//2789 3092//3092 3091//3091 -f 2791//2791 2793//2793 2923//2923 -f 2923//2923 2793//2793 2794//2794 -f 2923//2923 2794//2794 2922//2922 -f 2922//2922 2794//2794 2428//2428 -f 2922//2922 2428//2428 2787//2787 -f 2820//2820 2809//2809 2821//2821 -f 2821//2821 2809//2809 2805//2805 -f 2821//2821 2805//2805 2817//2817 -f 2817//2817 2805//2805 2802//2802 -f 2817//2817 2802//2802 2818//2818 -f 2818//2818 2802//2802 2801//2801 -f 2818//2818 2801//2801 2814//2814 -f 2814//2814 2801//2801 2800//2800 -f 2814//2814 2800//2800 2812//2812 -f 2812//2812 2800//2800 2799//2799 -f 2812//2812 2799//2799 2810//2810 -f 2810//2810 2799//2799 2789//2789 -f 2822//2822 2840//2840 2827//2827 -f 2827//2827 2840//2840 2832//2832 -f 2827//2827 2832//2832 2418//2418 -f 3097//3097 3098//3098 2811//2811 -f 2811//2811 3098//3098 3099//3099 -f 2811//2811 3099//3099 2822//2822 -f 2822//2822 3099//3099 2841//2841 -f 2822//2822 2841//2841 2840//2840 -f 3097//3097 2811//2811 3100//3100 -f 3100//3100 2811//2811 2810//2810 -f 3100//3100 2810//2810 3101//3101 -f 3071//3071 2842//2842 2841//2841 -f 3101//3101 3087//3087 3100//3100 -f 3100//3100 3087//3087 3079//3079 -f 3100//3100 3079//3079 3097//3097 -f 3097//3097 3079//3079 3098//3098 -f 2841//2841 3099//3099 3071//3071 -f 3071//3071 3099//3099 3098//3098 -f 3071//3071 3098//3098 3072//3072 -f 3072//3072 3098//3098 3079//3079 -f 3088//3088 3090//3090 3102//3102 -f 3090//3090 3094//3094 3103//3103 -f 3094//3094 2919//2919 2926//2926 -f 3094//3094 2926//2926 3103//3103 -f 3103//3103 2926//2926 2925//2925 -f 3103//3103 2925//2925 3104//3104 -f 3104//3104 2925//2925 2924//2924 -f 3104//3104 2924//2924 3105//3105 -f 3105//3105 2924//2924 2915//2915 -f 3105//3105 2915//2915 3106//3106 -f 3106//3106 2915//2915 2914//2914 -f 3106//3106 2914//2914 3107//3107 -f 3107//3107 2914//2914 2918//2918 -f 3107//3107 2918//2918 3108//3108 -f 3108//3108 2918//2918 2917//2917 -f 3108//3108 2917//2917 3109//3109 -f 2917//2917 2916//2916 3109//3109 -f 3109//3109 2916//2916 3110//3110 -f 3109//3109 3110//3110 3111//3111 -f 3090//3090 3103//3103 3102//3102 -f 3102//3102 3103//3103 3104//3104 -f 3102//3102 3104//3104 3112//3112 -f 3112//3112 3104//3104 3105//3105 -f 3112//3112 3105//3105 3113//3113 -f 3113//3113 3105//3105 3106//3106 -f 3113//3113 3106//3106 3114//3114 -f 3114//3114 3106//3106 3107//3107 -f 3114//3114 3107//3107 3115//3115 -f 3115//3115 3107//3107 3108//3108 -f 3115//3115 3108//3108 3116//3116 -f 3116//3116 3108//3108 3109//3109 -f 3116//3116 3109//3109 3117//3117 -f 3117//3117 3109//3109 3111//3111 -f 3117//3117 3111//3111 3118//3118 -f 3088//3088 3102//3102 3119//3119 -f 3119//3119 3102//3102 3112//3112 -f 3119//3119 3112//3112 3120//3120 -f 3120//3120 3112//3112 3113//3113 -f 3120//3120 3113//3113 3121//3121 -f 3121//3121 3113//3113 3114//3114 -f 3121//3121 3114//3114 3122//3122 -f 3122//3122 3114//3114 3115//3115 -f 3122//3122 3115//3115 3123//3123 -f 3123//3123 3115//3115 3116//3116 -f 3123//3123 3116//3116 3124//3124 -f 3124//3124 3116//3116 3117//3117 -f 3124//3124 3117//3117 3125//3125 -f 3125//3125 3117//3117 3118//3118 -f 3125//3125 3118//3118 1545//1545 -f 1540//1540 1544//1544 3126//3126 -f 3126//3126 1544//1544 3127//3127 -f 3001//3001 2998//2998 3128//3128 -f 3128//3128 2998//2998 3129//3129 -f 3128//3128 3129//3129 3130//3130 -f 3127//3127 3131//3131 3126//3126 -f 3126//3126 3131//3131 3132//3132 -f 3126//3126 3132//3132 3130//3130 -f 3130//3130 3132//3132 3133//3133 -f 3130//3130 3133//3133 3128//3128 -f 3127//3127 1544//1544 1551//1551 -f 3001//3001 3128//3128 2852//2852 -f 3128//3128 3133//3133 2852//2852 -f 2852//2852 3133//3133 3132//3132 -f 2852//2852 3132//3132 1551//1551 -f 1551//1551 3132//3132 3131//3131 -f 1551//1551 3131//3131 3127//3127 -f 2852//2852 2850//2850 3001//3001 -f 3001//3001 2850//2850 2849//2849 -f 3001//3001 2849//2849 3010//3010 -f 3010//3010 2849//2849 2523//2523 -f 3010//3010 2523//2523 2846//2846 -f 2862//2862 2861//2861 2857//2857 -f 2862//2862 2857//2857 2863//2863 -f 2863//2863 2857//2857 2854//2854 -f 2863//2863 2854//2854 2865//2865 -f 2865//2865 2854//2854 1551//1551 -f 2865//2865 1551//1551 1550//1550 -f 2877//2877 2515//2515 2870//2870 -f 2877//2877 2870//2870 2880//2880 -f 2880//2880 2870//2870 2868//2868 -f 2880//2880 2868//2868 2878//2878 -f 2878//2878 2868//2868 3134//3134 -f 3134//3134 2868//2868 2867//2867 -f 3134//3134 2867//2867 3135//3135 -f 3135//3135 2867//2867 3136//3136 -f 3136//3136 2867//2867 1550//1550 -f 3136//3136 1550//1550 1549//1549 -f 1549//1549 1548//1548 3136//3136 -f 3136//3136 1548//1548 3137//3137 -f 3137//3137 3138//3138 3136//3136 -f 3136//3136 3138//3138 3139//3139 -f 3136//3136 3139//3139 3135//3135 -f 3139//3139 3140//3140 3135//3135 -f 3135//3135 3140//3140 3141//3141 -f 3135//3135 3141//3141 3134//3134 -f 3134//3134 3141//3141 2879//2879 -f 3134//3134 2879//2879 2878//2878 -f 3137//3137 1548//1548 1552//1552 -f 2879//2879 3141//3141 2888//2888 -f 3141//3141 3140//3140 2888//2888 -f 2888//2888 3140//3140 3139//3139 -f 2888//2888 3139//3139 1552//1552 -f 1552//1552 3139//3139 3138//3138 -f 1552//1552 3138//3138 3137//3137 -f 2888//2888 2886//2886 2879//2879 -f 2879//2879 2886//2886 2885//2885 -f 2879//2879 2885//2885 2882//2882 -f 2882//2882 2885//2885 2475//2475 -f 2882//2882 2475//2475 2881//2881 -f 2898//2898 2897//2897 2893//2893 -f 2898//2898 2893//2893 2899//2899 -f 2899//2899 2893//2893 2890//2890 -f 2899//2899 2890//2890 2901//2901 -f 2901//2901 2890//2890 1552//1552 -f 2901//2901 1552//1552 1553//1553 -f 2904//2904 2920//2920 2906//2906 -f 2906//2906 2920//2920 2913//2913 -f 2906//2906 2913//2913 2468//2468 -f 3142//3142 3143//3143 2903//2903 -f 2903//2903 3143//3143 3144//3144 -f 2903//2903 3144//3144 2904//2904 -f 2904//2904 3144//3144 2921//2921 -f 2904//2904 2921//2921 2920//2920 -f 3142//3142 2903//2903 3145//3145 -f 3145//3145 2903//2903 1553//1553 -f 3145//3145 1553//1553 1546//1546 -f 3110//3110 2916//2916 2921//2921 -f 1546//1546 1545//1545 3145//3145 -f 3145//3145 1545//1545 3118//3118 -f 3145//3145 3118//3118 3142//3142 -f 3142//3142 3118//3118 3143//3143 -f 2921//2921 3144//3144 3110//3110 -f 3110//3110 3144//3144 3143//3143 -f 3110//3110 3143//3143 3111//3111 -f 3111//3111 3143//3143 3118//3118 -f 3039//3039 3146//3146 3040//3040 -f 3040//3040 3146//3146 3147//3147 -f 3040//3040 3147//3147 3148//3148 -f 2931//2931 2927//2927 3149//3149 -f 3149//3149 2927//2927 3042//3042 -f 3149//3149 3042//3042 3040//3040 -f 3148//3148 3150//3150 3040//3040 -f 3040//3040 3150//3150 3151//3151 -f 3040//3040 3151//3151 3149//3149 -f 3147//3147 3146//3146 2948//2948 -f 2931//2931 3149//3149 2946//2946 -f 3149//3149 3151//3151 2946//2946 -f 2946//2946 3151//3151 3150//3150 -f 2946//2946 3150//3150 2948//2948 -f 2948//2948 3150//3150 3148//3148 -f 2948//2948 3148//3148 3147//3147 -f 2946//2946 2944//2944 2931//2931 -f 2931//2931 2944//2944 2943//2943 -f 2931//2931 2943//2943 2930//2930 -f 2930//2930 2943//2943 2578//2578 -f 2930//2930 2578//2578 2929//2929 -f 2978//2978 2956//2956 2993//2993 -f 2993//2993 2956//2956 2952//2952 -f 2993//2993 2952//2952 2988//2988 -f 2988//2988 2952//2952 2989//2989 -f 2989//2989 2952//2952 2949//2949 -f 2989//2989 2949//2949 2979//2979 -f 2979//2979 2949//2949 2980//2980 -f 2980//2980 2949//2949 2948//2948 -f 2980//2980 2948//2948 2987//2987 -f 2997//2997 2679//2679 2983//2983 -f 2997//2997 2983//2983 3007//3007 -f 3007//3007 2983//2983 2985//2985 -f 3007//3007 2985//2985 3008//3008 -f 3008//3008 2985//2985 3152//3152 -f 3152//3152 2985//2985 2986//2986 -f 3152//3152 2986//2986 3153//3153 -f 3153//3153 2986//2986 3154//3154 -f 3154//3154 2986//2986 2987//2987 -f 3154//3154 2987//2987 3155//3155 -f 3154//3154 3155//3155 3156//3156 -f 3156//3156 3157//3157 3154//3154 -f 3154//3154 3157//3157 3158//3158 -f 3154//3154 3158//3158 3153//3153 -f 3153//3153 3158//3158 3159//3159 -f 3153//3153 3159//3159 3152//3152 -f 3152//3152 3159//3159 3009//3009 -f 3152//3152 3009//3009 3008//3008 -f 3130//3130 3129//3129 3160//3160 -f 3129//3129 2998//2998 3004//3004 -f 1540//1540 3126//3126 3161//3161 -f 3161//3161 3126//3126 3130//3130 -f 3129//3129 3004//3004 3160//3160 -f 3160//3160 3004//3004 3003//3003 -f 3160//3160 3003//3003 3162//3162 -f 3162//3162 3003//3003 3002//3002 -f 3162//3162 3002//3002 3163//3163 -f 3163//3163 3002//3002 3000//3000 -f 3163//3163 3000//3000 3164//3164 -f 3164//3164 3000//3000 2999//2999 -f 3164//3164 2999//2999 3165//3165 -f 3165//3165 2999//2999 3006//3006 -f 3165//3165 3006//3006 3166//3166 -f 3166//3166 3006//3006 3005//3005 -f 3166//3166 3005//3005 3167//3167 -f 3005//3005 3009//3009 3167//3167 -f 3167//3167 3009//3009 3159//3159 -f 3167//3167 3159//3159 3158//3158 -f 3130//3130 3160//3160 3161//3161 -f 3161//3161 3160//3160 3162//3162 -f 3161//3161 3162//3162 3168//3168 -f 3168//3168 3162//3162 3163//3163 -f 3168//3168 3163//3163 3169//3169 -f 3169//3169 3163//3163 3164//3164 -f 3169//3169 3164//3164 3170//3170 -f 3170//3170 3164//3164 3165//3165 -f 3170//3170 3165//3165 3171//3171 -f 3171//3171 3165//3165 3166//3166 -f 3171//3171 3166//3166 3172//3172 -f 3172//3172 3166//3166 3167//3167 -f 3172//3172 3167//3167 3173//3173 -f 3173//3173 3167//3167 3158//3158 -f 3173//3173 3158//3158 3157//3157 -f 1540//1540 3161//3161 3174//3174 -f 3174//3174 3161//3161 3168//3168 -f 3174//3174 3168//3168 3175//3175 -f 3175//3175 3168//3168 3169//3169 -f 3175//3175 3169//3169 3176//3176 -f 3176//3176 3169//3169 3170//3170 -f 3176//3176 3170//3170 3177//3177 -f 3177//3177 3170//3170 3171//3171 -f 3177//3177 3171//3171 3178//3178 -f 3178//3178 3171//3171 3172//3172 -f 3178//3178 3172//3172 3179//3179 -f 3179//3179 3172//3172 3173//3173 -f 3179//3179 3173//3173 3180//3180 -f 3180//3180 3173//3173 3157//3157 -f 3180//3180 3157//3157 3156//3156 -f 1540//1540 3174//3174 1541//1541 -f 1541//1541 3174//3174 3181//3181 -f 3174//3174 3175//3175 3181//3181 -f 3181//3181 3175//3175 3176//3176 -f 3181//3181 3176//3176 3182//3182 -f 3176//3176 3177//3177 3182//3182 -f 3182//3182 3177//3177 3178//3178 -f 3182//3182 3178//3178 3183//3183 -f 3156//3156 3184//3184 3180//3180 -f 3180//3180 3184//3184 3183//3183 -f 3180//3180 3183//3183 3179//3179 -f 3179//3179 3183//3183 3178//3178 -f 3185//3185 3184//3184 3155//3155 -f 3155//3155 3184//3184 3156//3156 -f 3039//3039 3185//3185 3146//3146 -f 3146//3146 3185//3185 3155//3155 -f 3146//3146 3155//3155 2948//2948 -f 2948//2948 3155//3155 2987//2987 -f 3088//3088 3119//3119 1452//1452 -f 1452//1452 3119//3119 1454//1454 -f 3119//3119 3120//3120 1454//1454 -f 1454//1454 3120//3120 3121//3121 -f 1454//1454 3121//3121 1456//1456 -f 3121//3121 3122//3122 1456//1456 -f 1456//1456 3122//3122 3123//3123 -f 1456//1456 3123//3123 1458//1458 -f 1545//1545 1460//1460 3125//3125 -f 3125//3125 1460//1460 1458//1458 -f 3125//3125 1458//1458 3124//3124 -f 3124//3124 1458//1458 3123//3123 -f 1478//1478 1476//1476 1585//1585 -f 1506//1506 1505//1505 3087//3087 -f 1584//1584 3186//3186 1585//1585 -f 1585//1585 3186//3186 3187//3187 -f 1585//1585 3187//3187 1478//1478 -f 1478//1478 3187//3187 3188//3188 -f 1478//1478 3188//3188 1450//1450 -f 2810//2810 2789//2789 3089//3089 -f 2810//2810 3089//3089 3101//3101 -f 1584//1584 1482//1482 3186//3186 -f 3186//3186 1482//1482 1480//1480 -f 3186//3186 1480//1480 3189//3189 -f 1480//1480 1506//1506 3189//3189 -f 3189//3189 1506//1506 3087//3087 -f 3189//3189 3087//3087 3188//3188 -f 3188//3188 3087//3087 3101//3101 -f 3188//3188 3101//3101 1450//1450 -f 1450//1450 3101//3101 3089//3089 -f 1450//1450 3089//3089 1452//1452 -f 1452//1452 3089//3089 3088//3088 -f 3011//3011 3080//3080 1498//1498 -f 1498//1498 3080//3080 1500//1500 -f 3080//3080 3081//3081 1500//1500 -f 1500//1500 3081//3081 3082//3082 -f 1500//1500 3082//3082 1502//1502 -f 3082//3082 3083//3083 1502//1502 -f 1502//1502 3083//3083 3084//3084 -f 1502//1502 3084//3084 1504//1504 -f 3087//3087 1505//1505 3086//3086 -f 3086//3086 1505//1505 1504//1504 -f 3086//3086 1504//1504 3085//3085 -f 3085//3085 1504//1504 3084//3084 -f 3039//3039 3056//3056 3185//3185 -f 3185//3185 3056//3056 3190//3190 -f 3056//3056 3057//3057 3190//3190 -f 3190//3190 3057//3057 3058//3058 -f 3190//3190 3058//3058 3191//3191 -f 3058//3058 3059//3059 3191//3191 -f 3191//3191 3059//3059 3060//3060 -f 3191//3191 3060//3060 3192//3192 -f 3036//3036 3193//3193 3062//3062 -f 3062//3062 3193//3193 3192//3192 -f 3062//3062 3192//3192 3061//3061 -f 3061//3061 3192//3192 3060//3060 -f 3194//3194 3036//3036 3195//3195 -f 3195//3195 3036//3036 3034//3034 -f 3193//3193 3036//3036 3196//3196 -f 3196//3196 3036//3036 3194//3194 -f 3196//3196 3194//3194 1557//1557 -f 1557//1557 3194//3194 1556//1556 -f 1498//1498 1496//1496 3023//3023 -f 3023//3023 1496//1496 3195//3195 -f 3023//3023 3195//3195 3024//3024 -f 3024//3024 3195//3195 3034//3034 -f 3024//3024 3034//3034 2749//2749 -f 2749//2749 3034//3034 2775//2775 -f 3011//3011 1498//1498 3012//3012 -f 3012//3012 1498//1498 3023//3023 -f 3012//3012 3023//3023 2705//2705 -f 2705//2705 3023//3023 2736//2736 -f 3197//3197 1516//1516 3198//3198 -f 3198//3198 1516//1516 1514//1514 -f 3198//3198 1514//1514 3199//3199 -f 3199//3199 1514//1514 1590//1590 -f 3199//3199 1590//1590 3200//3200 -f 3200//3200 1590//1590 1591//1591 -f 3200//3200 1591//1591 3201//3201 -f 3201//3201 1591//1591 1592//1592 -f 3201//3201 1592//1592 3202//3202 -f 3202//3202 1592//1592 1589//1589 -f 3202//3202 1589//1589 3203//3203 -f 3203//3203 1589//1589 1577//1577 -f 3203//3203 1577//1577 3204//3204 -f 3204//3204 1577//1577 1578//1578 -f 3204//3204 1578//1578 3205//3205 -f 3205//3205 1578//1578 1579//1579 -f 3205//3205 1579//1579 3206//3206 -f 3206//3206 1579//1579 1580//1580 -f 3206//3206 1580//1580 3207//3207 -f 3207//3207 1580//1580 1576//1576 -f 3207//3207 1576//1576 3208//3208 -f 3208//3208 1576//1576 1574//1574 -f 3208//3208 1574//1574 3209//3209 -f 3209//3209 1574//1574 1581//1581 -f 3209//3209 1581//1581 3210//3210 -f 3210//3210 1581//1581 1582//1582 -f 3210//3210 1582//1582 3211//3211 -f 3211//3211 1582//1582 1583//1583 -f 3211//3211 1583//1583 3212//3212 -f 3212//3212 1583//1583 1584//1584 -f 3212//3212 1584//1584 3213//3213 -f 3213//3213 1584//1584 1585//1585 -f 3213//3213 1585//1585 3214//3214 -f 3214//3214 1585//1585 1586//1586 -f 3214//3214 1586//1586 3215//3215 -f 3215//3215 1586//1586 1587//1587 -f 3215//3215 1587//1587 3216//3216 -f 3216//3216 1587//1587 1588//1588 -f 3216//3216 1588//1588 3197//3197 -f 3197//3197 1588//1588 1516//1516 -f 3217//3217 3218//3218 3219//3219 -f 3219//3219 3218//3218 3220//3220 -f 3219//3219 3220//3220 3221//3221 -f 3221//3221 3220//3220 3222//3222 -f 3221//3221 3222//3222 3223//3223 -f 3223//3223 3222//3222 3224//3224 -f 3223//3223 3224//3224 3225//3225 -f 3225//3225 3224//3224 3226//3226 -f 3225//3225 3226//3226 3227//3227 -f 3227//3227 3226//3226 3228//3228 -f 3227//3227 3228//3228 3229//3229 -f 3229//3229 3228//3228 3230//3230 -f 3229//3229 3230//3230 3231//3231 -f 3231//3231 3230//3230 3232//3232 -f 3231//3231 3232//3232 3233//3233 -f 3233//3233 3232//3232 3234//3234 -f 3233//3233 3234//3234 3235//3235 -f 3235//3235 3234//3234 3236//3236 -f 3235//3235 3236//3236 3237//3237 -f 3237//3237 3236//3236 3238//3238 -f 3237//3237 3238//3238 3239//3239 -f 3239//3239 3238//3238 3240//3240 -f 3239//3239 3240//3240 3241//3241 -f 3241//3241 3240//3240 3242//3242 -f 3241//3241 3242//3242 3243//3243 -f 3243//3243 3242//3242 3244//3244 -f 3243//3243 3244//3244 3245//3245 -f 3245//3245 3244//3244 3246//3246 -f 3245//3245 3246//3246 3247//3247 -f 3247//3247 3246//3246 3248//3248 -f 3247//3247 3248//3248 3249//3249 -f 3249//3249 3248//3248 3250//3250 -f 3249//3249 3250//3250 3251//3251 -f 3251//3251 3250//3250 3252//3252 -f 3251//3251 3252//3252 3253//3253 -f 3253//3253 3252//3252 3254//3254 -f 3253//3253 3254//3254 3255//3255 -f 3255//3255 3254//3254 3256//3256 -f 3255//3255 3256//3256 3217//3217 -f 3217//3217 3256//3256 3218//3218 -f 3207//3207 3219//3219 3221//3221 -f 3207//3207 3221//3221 3206//3206 -f 3206//3206 3221//3221 3223//3223 -f 3206//3206 3223//3223 3205//3205 -f 3205//3205 3223//3223 3225//3225 -f 3205//3205 3225//3225 3204//3204 -f 3204//3204 3225//3225 3227//3227 -f 3204//3204 3227//3227 3203//3203 -f 3202//3202 3203//3203 3229//3229 -f 3229//3229 3203//3203 3227//3227 -f 3202//3202 3229//3229 3231//3231 -f 3202//3202 3231//3231 3201//3201 -f 3201//3201 3231//3231 3233//3233 -f 3201//3201 3233//3233 3200//3200 -f 3200//3200 3233//3233 3235//3235 -f 3200//3200 3235//3235 3199//3199 -f 3199//3199 3235//3235 3237//3237 -f 3199//3199 3237//3237 3198//3198 -f 3197//3197 3198//3198 3239//3239 -f 3239//3239 3198//3198 3237//3237 -f 3197//3197 3239//3239 3241//3241 -f 3197//3197 3241//3241 3216//3216 -f 3216//3216 3241//3241 3243//3243 -f 3216//3216 3243//3243 3215//3215 -f 3215//3215 3243//3243 3245//3245 -f 3215//3215 3245//3245 3214//3214 -f 3214//3214 3245//3245 3247//3247 -f 3214//3214 3247//3247 3213//3213 -f 3212//3212 3213//3213 3249//3249 -f 3249//3249 3213//3213 3247//3247 -f 3212//3212 3249//3249 3251//3251 -f 3212//3212 3251//3251 3211//3211 -f 3211//3211 3251//3251 3253//3253 -f 3211//3211 3253//3253 3210//3210 -f 3210//3210 3253//3253 3255//3255 -f 3210//3210 3255//3255 3209//3209 -f 3209//3209 3255//3255 3217//3217 -f 3209//3209 3217//3217 3208//3208 -f 3207//3207 3208//3208 3219//3219 -f 3219//3219 3208//3208 3217//3217 -f 3257//3257 3258//3258 3259//3259 -f 579//579 581//581 577//577 -f 577//577 581//581 571//571 -f 577//577 571//571 575//575 -f 575//575 571//571 573//573 -f 581//581 583//583 571//571 -f 571//571 583//583 3257//3257 -f 571//571 3257//3257 3260//3260 -f 3260//3260 3257//3257 3259//3259 -f 3260//3260 3259//3259 3261//3261 -f 583//583 584//584 3257//3257 -f 3257//3257 584//584 3262//3262 -f 3257//3257 3262//3262 3258//3258 -f 3258//3258 3262//3262 3263//3263 -f 3258//3258 3263//3263 3259//3259 -f 3259//3259 3263//3263 3264//3264 -f 3259//3259 3264//3264 3261//3261 -f 3261//3261 3264//3264 3265//3265 -f 3261//3261 3265//3265 3260//3260 -f 3260//3260 3265//3265 3266//3266 -f 3260//3260 3266//3266 571//571 -f 571//571 3266//3266 572//572 -f 567//567 569//569 3267//3267 -f 3268//3268 557//557 559//559 -f 3269//3269 3270//3270 3268//3268 -f 3267//3267 3271//3271 3269//3269 -f 559//559 561//561 563//563 -f 3269//3269 3268//3268 3267//3267 -f 3267//3267 3268//3268 559//559 -f 3267//3267 559//559 567//567 -f 567//567 559//559 563//563 -f 567//567 563//563 565//565 -f 551//551 553//553 555//555 -f 3272//3272 3273//3273 543//543 -f 3274//3274 3272//3272 3275//3275 -f 3275//3275 3272//3272 551//551 -f 3275//3275 551//551 3276//3276 -f 3276//3276 551//551 555//555 -f 549//549 551//551 547//547 -f 547//547 551//551 3272//3272 -f 547//547 3272//3272 545//545 -f 545//545 3272//3272 543//543 -f 537//537 539//539 3277//3277 -f 537//537 3277//3277 535//535 -f 535//535 3277//3277 3278//3278 -f 535//535 3278//3278 3279//3279 -f 539//539 541//541 3277//3277 -f 3277//3277 541//541 3280//3280 -f 3277//3277 3280//3280 3281//3281 -f 3279//3279 529//529 535//535 -f 535//535 529//529 531//531 -f 535//535 531//531 533//533 -f 517//517 519//519 521//521 -f 3282//3282 3283//3283 3284//3284 -f 521//521 523//523 3282//3282 -f 3282//3282 523//523 525//525 -f 521//521 3282//3282 517//517 -f 517//517 3282//3282 3284//3284 -f 517//517 3284//3284 515//515 -f 525//525 527//527 3282//3282 -f 3282//3282 527//527 3285//3285 -f 3282//3282 3285//3285 3286//3286 -f 507//507 509//509 511//511 -f 3287//3287 3288//3288 3289//3289 -f 505//505 507//507 503//503 -f 503//503 507//507 511//511 -f 503//503 511//511 3287//3287 -f 3287//3287 511//511 513//513 -f 501//501 503//503 3290//3290 -f 3290//3290 503//503 3287//3287 -f 3290//3290 3287//3287 3291//3291 -f 3291//3291 3287//3287 3289//3289 -f 491//491 493//493 495//495 -f 3292//3292 487//487 489//489 -f 497//497 499//499 495//495 -f 495//495 499//499 3293//3293 -f 495//495 3293//3293 3294//3294 -f 489//489 491//491 3292//3292 -f 3292//3292 491//491 495//495 -f 3292//3292 495//495 3295//3295 -f 3295//3295 495//495 3294//3294 -f 3295//3295 3294//3294 3296//3296 -f 3297//3297 3298//3298 473//473 -f 481//481 483//483 485//485 -f 485//485 3299//3299 3300//3300 -f 477//477 479//479 475//475 -f 475//475 479//479 481//481 -f 475//475 481//481 473//473 -f 473//473 481//481 485//485 -f 473//473 485//485 3297//3297 -f 3297//3297 485//485 3300//3300 -f 3297//3297 3300//3300 3301//3301 -f 465//465 467//467 469//469 -f 3302//3302 3303//3303 3304//3304 -f 3305//3305 3302//3302 3306//3306 -f 3306//3306 3302//3302 465//465 -f 3306//3306 465//465 471//471 -f 471//471 465//465 469//469 -f 463//463 465//465 461//461 -f 461//461 465//465 3302//3302 -f 461//461 3302//3302 459//459 -f 459//459 3302//3302 3304//3304 -f 453//453 455//455 457//457 -f 3307//3307 3308//3308 445//445 -f 445//445 447//447 449//449 -f 3309//3309 3310//3310 3311//3311 -f 3311//3311 3310//3310 3307//3307 -f 3311//3311 3307//3307 457//457 -f 457//457 3307//3307 445//445 -f 457//457 445//445 453//453 -f 453//453 445//445 449//449 -f 453//453 449//449 451//451 -f 3312//3312 3313//3313 431//431 -f 439//439 441//441 443//443 -f 443//443 3314//3314 3315//3315 -f 435//435 437//437 433//433 -f 433//433 437//437 439//439 -f 433//433 439//439 431//431 -f 431//431 439//439 443//443 -f 431//431 443//443 3312//3312 -f 3312//3312 443//443 3315//3315 -f 3312//3312 3315//3315 3316//3316 -f 3264//3264 3317//3317 3265//3265 -f 3265//3265 3317//3317 3318//3318 -f 3265//3265 3318//3318 3266//3266 -f 3266//3266 3318//3318 3319//3319 -f 3266//3266 3319//3319 572//572 -f 572//572 3319//3319 415//415 -f 572//572 415//415 574//574 -f 574//574 415//415 417//417 -f 574//574 417//417 576//576 -f 576//576 417//417 419//419 -f 576//576 419//419 578//578 -f 419//419 421//421 578//578 -f 578//578 421//421 423//423 -f 578//578 423//423 580//580 -f 580//580 423//423 425//425 -f 580//580 425//425 582//582 -f 582//582 425//425 427//427 -f 582//582 427//427 584//584 -f 584//584 427//427 429//429 -f 584//584 429//429 3262//3262 -f 3262//3262 429//429 3320//3320 -f 3262//3262 3320//3320 3263//3263 -f 3263//3263 3320//3320 3321//3321 -f 3263//3263 3321//3321 3264//3264 -f 3264//3264 3321//3321 3322//3322 -f 3264//3264 3322//3322 3317//3317 -f 411//411 413//413 3323//3323 -f 3324//3324 401//401 403//403 -f 403//403 405//405 407//407 -f 3325//3325 3326//3326 3327//3327 -f 3327//3327 3326//3326 3324//3324 -f 3327//3327 3324//3324 3323//3323 -f 3323//3323 3324//3324 403//403 -f 3323//3323 403//403 411//411 -f 411//411 403//403 407//407 -f 411//411 407//407 409//409 -f 3328//3328 387//387 389//389 -f 397//397 399//399 3329//3329 -f 389//389 391//391 393//393 -f 3330//3330 3331//3331 3332//3332 -f 3332//3332 3331//3331 3328//3328 -f 3332//3332 3328//3328 3329//3329 -f 3329//3329 3328//3328 389//389 -f 3329//3329 389//389 397//397 -f 397//397 389//389 393//393 -f 397//397 393//393 395//395 -f 569//569 570//570 3267//3267 -f 3267//3267 570//570 3333//3333 -f 3267//3267 3333//3333 3271//3271 -f 3271//3271 3333//3333 3334//3334 -f 3271//3271 3334//3334 3269//3269 -f 3269//3269 3334//3334 3335//3335 -f 3269//3269 3335//3335 3270//3270 -f 3270//3270 3335//3335 3336//3336 -f 3270//3270 3336//3336 3268//3268 -f 3268//3268 3336//3336 3337//3337 -f 3268//3268 3337//3337 557//557 -f 557//557 3337//3337 558//558 -f 555//555 556//556 3276//3276 -f 3276//3276 556//556 3338//3338 -f 3276//3276 3338//3338 3275//3275 -f 3275//3275 3338//3338 3339//3339 -f 3275//3275 3339//3339 3274//3274 -f 3274//3274 3339//3339 3340//3340 -f 3274//3274 3340//3340 3272//3272 -f 3272//3272 3340//3340 3341//3341 -f 3272//3272 3341//3341 3273//3273 -f 3273//3273 3341//3341 3342//3342 -f 3273//3273 3342//3342 543//543 -f 543//543 3342//3342 544//544 -f 541//541 542//542 3280//3280 -f 3280//3280 542//542 3343//3343 -f 3280//3280 3343//3343 3281//3281 -f 3281//3281 3343//3343 3344//3344 -f 3281//3281 3344//3344 3277//3277 -f 3277//3277 3344//3344 3345//3345 -f 3277//3277 3345//3345 3278//3278 -f 3278//3278 3345//3345 3346//3346 -f 3278//3278 3346//3346 3279//3279 -f 3279//3279 3346//3346 3347//3347 -f 3279//3279 3347//3347 529//529 -f 529//529 3347//3347 530//530 -f 527//527 528//528 3285//3285 -f 3285//3285 528//528 3348//3348 -f 3285//3285 3348//3348 3286//3286 -f 3286//3286 3348//3348 3349//3349 -f 3286//3286 3349//3349 3282//3282 -f 3282//3282 3349//3349 3350//3350 -f 3282//3282 3350//3350 3283//3283 -f 3283//3283 3350//3350 3351//3351 -f 3283//3283 3351//3351 3284//3284 -f 3284//3284 3351//3351 3352//3352 -f 3284//3284 3352//3352 515//515 -f 515//515 3352//3352 516//516 -f 513//513 514//514 3287//3287 -f 3287//3287 514//514 3353//3353 -f 3287//3287 3353//3353 3288//3288 -f 3288//3288 3353//3353 3354//3354 -f 3288//3288 3354//3354 3289//3289 -f 3289//3289 3354//3354 3355//3355 -f 3289//3289 3355//3355 3291//3291 -f 3291//3291 3355//3355 3356//3356 -f 3291//3291 3356//3356 3290//3290 -f 3290//3290 3356//3356 3357//3357 -f 3290//3290 3357//3357 501//501 -f 501//501 3357//3357 502//502 -f 499//499 500//500 3293//3293 -f 3293//3293 500//500 3358//3358 -f 3293//3293 3358//3358 3294//3294 -f 3294//3294 3358//3358 3359//3359 -f 3294//3294 3359//3359 3296//3296 -f 3296//3296 3359//3359 3360//3360 -f 3296//3296 3360//3360 3295//3295 -f 3295//3295 3360//3360 3361//3361 -f 3295//3295 3361//3361 3292//3292 -f 3292//3292 3361//3361 3362//3362 -f 3292//3292 3362//3362 487//487 -f 487//487 3362//3362 488//488 -f 485//485 486//486 3299//3299 -f 3299//3299 486//486 3363//3363 -f 3299//3299 3363//3363 3300//3300 -f 3300//3300 3363//3363 3364//3364 -f 3300//3300 3364//3364 3301//3301 -f 3301//3301 3364//3364 3365//3365 -f 3301//3301 3365//3365 3297//3297 -f 3297//3297 3365//3365 3366//3366 -f 3297//3297 3366//3366 3298//3298 -f 3298//3298 3366//3366 3367//3367 -f 3298//3298 3367//3367 473//473 -f 473//473 3367//3367 474//474 -f 471//471 472//472 3306//3306 -f 3306//3306 472//472 3368//3368 -f 3306//3306 3368//3368 3305//3305 -f 3305//3305 3368//3368 3369//3369 -f 3305//3305 3369//3369 3302//3302 -f 3302//3302 3369//3369 3370//3370 -f 3302//3302 3370//3370 3303//3303 -f 3303//3303 3370//3370 3371//3371 -f 3303//3303 3371//3371 3304//3304 -f 3304//3304 3371//3371 3372//3372 -f 3304//3304 3372//3372 459//459 -f 459//459 3372//3372 460//460 -f 457//457 458//458 3311//3311 -f 3311//3311 458//458 3373//3373 -f 3311//3311 3373//3373 3309//3309 -f 3309//3309 3373//3373 3374//3374 -f 3309//3309 3374//3374 3310//3310 -f 3310//3310 3374//3374 3375//3375 -f 3310//3310 3375//3375 3307//3307 -f 3307//3307 3375//3375 3376//3376 -f 3307//3307 3376//3376 3308//3308 -f 3308//3308 3376//3376 3377//3377 -f 3308//3308 3377//3377 445//445 -f 445//445 3377//3377 446//446 -f 443//443 444//444 3314//3314 -f 3314//3314 444//444 3378//3378 -f 3314//3314 3378//3378 3315//3315 -f 3315//3315 3378//3378 3379//3379 -f 3315//3315 3379//3379 3316//3316 -f 3316//3316 3379//3379 3380//3380 -f 3316//3316 3380//3380 3312//3312 -f 3312//3312 3380//3380 3381//3381 -f 3312//3312 3381//3381 3313//3313 -f 3313//3313 3381//3381 3382//3382 -f 3313//3313 3382//3382 431//431 -f 431//431 3382//3382 432//432 -f 429//429 430//430 3320//3320 -f 3320//3320 430//430 3383//3383 -f 3320//3320 3383//3383 3321//3321 -f 3321//3321 3383//3383 3384//3384 -f 3321//3321 3384//3384 3322//3322 -f 3322//3322 3384//3384 3385//3385 -f 3322//3322 3385//3385 3317//3317 -f 3317//3317 3385//3385 3386//3386 -f 3317//3317 3386//3386 3318//3318 -f 3318//3318 3386//3386 3387//3387 -f 3318//3318 3387//3387 3319//3319 -f 3319//3319 3387//3387 3388//3388 -f 3319//3319 3388//3388 415//415 -f 415//415 3388//3388 416//416 -f 413//413 414//414 3323//3323 -f 3323//3323 414//414 3389//3389 -f 3323//3323 3389//3389 3327//3327 -f 3327//3327 3389//3389 3390//3390 -f 3327//3327 3390//3390 3325//3325 -f 3325//3325 3390//3390 3391//3391 -f 3325//3325 3391//3391 3326//3326 -f 3326//3326 3391//3391 3392//3392 -f 3326//3326 3392//3392 3324//3324 -f 3324//3324 3392//3392 3393//3393 -f 3324//3324 3393//3393 401//401 -f 401//401 3393//3393 402//402 -f 399//399 400//400 3329//3329 -f 3329//3329 400//400 3394//3394 -f 3329//3329 3394//3394 3332//3332 -f 3332//3332 3394//3394 3395//3395 -f 3332//3332 3395//3395 3330//3330 -f 3330//3330 3395//3395 3396//3396 -f 3330//3330 3396//3396 3331//3331 -f 3331//3331 3396//3396 3397//3397 -f 3331//3331 3397//3397 3328//3328 -f 3328//3328 3397//3397 3398//3398 -f 3328//3328 3398//3398 387//387 -f 387//387 3398//3398 388//388 -f 3333//3333 3399//3399 3334//3334 -f 3334//3334 3399//3399 3400//3400 -f 3334//3334 3400//3400 3335//3335 -f 3335//3335 3400//3400 3401//3401 -f 3335//3335 3401//3401 3336//3336 -f 3336//3336 3401//3401 3402//3402 -f 3336//3336 3402//3402 3337//3337 -f 3337//3337 3402//3402 3403//3403 -f 3337//3337 3403//3403 558//558 -f 558//558 3403//3403 373//373 -f 558//558 373//373 560//560 -f 560//560 373//373 375//375 -f 560//560 375//375 562//562 -f 562//562 375//375 377//377 -f 562//562 377//377 564//564 -f 564//564 377//377 379//379 -f 564//564 379//379 566//566 -f 566//566 379//379 381//381 -f 566//566 381//381 568//568 -f 568//568 381//381 383//383 -f 568//568 383//383 570//570 -f 570//570 383//383 385//385 -f 570//570 385//385 3333//3333 -f 3333//3333 385//385 3399//3399 -f 3338//3338 3404//3404 3339//3339 -f 3339//3339 3404//3404 3405//3405 -f 3339//3339 3405//3405 3340//3340 -f 3340//3340 3405//3405 3406//3406 -f 3340//3340 3406//3406 3341//3341 -f 3341//3341 3406//3406 3407//3407 -f 3341//3341 3407//3407 3342//3342 -f 3342//3342 3407//3407 3408//3408 -f 3342//3342 3408//3408 544//544 -f 544//544 3408//3408 359//359 -f 544//544 359//359 546//546 -f 546//546 359//359 361//361 -f 546//546 361//361 548//548 -f 548//548 361//361 363//363 -f 548//548 363//363 550//550 -f 550//550 363//363 365//365 -f 550//550 365//365 552//552 -f 552//552 365//365 367//367 -f 552//552 367//367 554//554 -f 554//554 367//367 369//369 -f 554//554 369//369 556//556 -f 556//556 369//369 371//371 -f 556//556 371//371 3338//3338 -f 3338//3338 371//371 3404//3404 -f 3347//3347 3409//3409 530//530 -f 530//530 3409//3409 345//345 -f 530//530 345//345 532//532 -f 532//532 345//345 347//347 -f 532//532 347//347 534//534 -f 534//534 347//347 349//349 -f 534//534 349//349 536//536 -f 536//536 349//349 351//351 -f 536//536 351//351 538//538 -f 538//538 351//351 353//353 -f 538//538 353//353 540//540 -f 540//540 353//353 355//355 -f 540//540 355//355 542//542 -f 542//542 355//355 357//357 -f 542//542 357//357 3343//3343 -f 3343//3343 357//357 3410//3410 -f 3343//3343 3410//3410 3344//3344 -f 3344//3344 3410//3410 3411//3411 -f 3344//3344 3411//3411 3345//3345 -f 3345//3345 3411//3411 3412//3412 -f 3345//3345 3412//3412 3346//3346 -f 3346//3346 3412//3412 3413//3413 -f 3346//3346 3413//3413 3347//3347 -f 3347//3347 3413//3413 3409//3409 -f 3352//3352 3414//3414 516//516 -f 516//516 3414//3414 331//331 -f 516//516 331//331 518//518 -f 518//518 331//331 333//333 -f 518//518 333//333 520//520 -f 520//520 333//333 335//335 -f 520//520 335//335 522//522 -f 522//522 335//335 337//337 -f 522//522 337//337 524//524 -f 524//524 337//337 339//339 -f 524//524 339//339 526//526 -f 526//526 339//339 341//341 -f 526//526 341//341 528//528 -f 528//528 341//341 343//343 -f 528//528 343//343 3348//3348 -f 3348//3348 343//343 3415//3415 -f 3348//3348 3415//3415 3349//3349 -f 3349//3349 3415//3415 3416//3416 -f 3349//3349 3416//3416 3350//3350 -f 3350//3350 3416//3416 3417//3417 -f 3350//3350 3417//3417 3351//3351 -f 3351//3351 3417//3417 3418//3418 -f 3351//3351 3418//3418 3352//3352 -f 3352//3352 3418//3418 3414//3414 -f 3353//3353 3419//3419 3354//3354 -f 3354//3354 3419//3419 3420//3420 -f 3354//3354 3420//3420 3355//3355 -f 3355//3355 3420//3420 3421//3421 -f 3355//3355 3421//3421 3356//3356 -f 3356//3356 3421//3421 3422//3422 -f 3356//3356 3422//3422 3357//3357 -f 3357//3357 3422//3422 3423//3423 -f 3357//3357 3423//3423 502//502 -f 502//502 3423//3423 317//317 -f 502//502 317//317 504//504 -f 504//504 317//317 319//319 -f 504//504 319//319 506//506 -f 506//506 319//319 321//321 -f 506//506 321//321 508//508 -f 508//508 321//321 323//323 -f 508//508 323//323 510//510 -f 510//510 323//323 325//325 -f 510//510 325//325 512//512 -f 512//512 325//325 327//327 -f 512//512 327//327 514//514 -f 514//514 327//327 329//329 -f 514//514 329//329 3353//3353 -f 3353//3353 329//329 3419//3419 -f 3358//3358 3424//3424 3359//3359 -f 3359//3359 3424//3424 3425//3425 -f 3359//3359 3425//3425 3360//3360 -f 3360//3360 3425//3425 3426//3426 -f 3360//3360 3426//3426 3361//3361 -f 3361//3361 3426//3426 3427//3427 -f 3361//3361 3427//3427 3362//3362 -f 3362//3362 3427//3427 3428//3428 -f 3362//3362 3428//3428 488//488 -f 488//488 3428//3428 303//303 -f 488//488 303//303 490//490 -f 490//490 303//303 305//305 -f 490//490 305//305 492//492 -f 492//492 305//305 307//307 -f 492//492 307//307 494//494 -f 494//494 307//307 309//309 -f 494//494 309//309 496//496 -f 496//496 309//309 311//311 -f 496//496 311//311 498//498 -f 498//498 311//311 313//313 -f 498//498 313//313 500//500 -f 500//500 313//313 315//315 -f 500//500 315//315 3358//3358 -f 3358//3358 315//315 3424//3424 -f 3366//3366 3429//3429 3367//3367 -f 3367//3367 3429//3429 3430//3430 -f 3367//3367 3430//3430 474//474 -f 474//474 3430//3430 289//289 -f 474//474 289//289 476//476 -f 476//476 289//289 291//291 -f 476//476 291//291 478//478 -f 478//478 291//291 293//293 -f 478//478 293//293 480//480 -f 480//480 293//293 295//295 -f 480//480 295//295 482//482 -f 482//482 295//295 297//297 -f 482//482 297//297 484//484 -f 484//484 297//297 299//299 -f 484//484 299//299 486//486 -f 486//486 299//299 301//301 -f 486//486 301//301 3363//3363 -f 3363//3363 301//301 3431//3431 -f 3363//3363 3431//3431 3364//3364 -f 3364//3364 3431//3431 3432//3432 -f 3364//3364 3432//3432 3365//3365 -f 3365//3365 3432//3432 3433//3433 -f 3365//3365 3433//3433 3366//3366 -f 3366//3366 3433//3433 3429//3429 -f 3368//3368 3434//3434 3369//3369 -f 3369//3369 3434//3434 3435//3435 -f 3369//3369 3435//3435 3370//3370 -f 3370//3370 3435//3435 3436//3436 -f 3370//3370 3436//3436 3371//3371 -f 3371//3371 3436//3436 3437//3437 -f 3371//3371 3437//3437 3372//3372 -f 3372//3372 3437//3437 3438//3438 -f 3372//3372 3438//3438 460//460 -f 460//460 3438//3438 275//275 -f 460//460 275//275 462//462 -f 462//462 275//275 277//277 -f 462//462 277//277 464//464 -f 464//464 277//277 279//279 -f 464//464 279//279 466//466 -f 466//466 279//279 281//281 -f 466//466 281//281 468//468 -f 468//468 281//281 283//283 -f 468//468 283//283 470//470 -f 470//470 283//283 285//285 -f 470//470 285//285 472//472 -f 472//472 285//285 287//287 -f 472//472 287//287 3368//3368 -f 3368//3368 287//287 3434//3434 -f 454//454 269//269 456//456 -f 456//456 269//269 271//271 -f 456//456 271//271 458//458 -f 458//458 271//271 273//273 -f 458//458 273//273 3373//3373 -f 3373//3373 273//273 3439//3439 -f 3373//3373 3439//3439 3374//3374 -f 3374//3374 3439//3439 3440//3440 -f 3374//3374 3440//3440 3375//3375 -f 3375//3375 3440//3440 3441//3441 -f 3375//3375 3441//3441 3376//3376 -f 3376//3376 3441//3441 3442//3442 -f 3376//3376 3442//3442 3377//3377 -f 3377//3377 3442//3442 3443//3443 -f 3377//3377 3443//3443 446//446 -f 446//446 3443//3443 261//261 -f 446//446 261//261 448//448 -f 448//448 261//261 263//263 -f 448//448 263//263 450//450 -f 450//450 263//263 265//265 -f 450//450 265//265 452//452 -f 452//452 265//265 267//267 -f 452//452 267//267 454//454 -f 454//454 267//267 269//269 -f 3381//3381 3444//3444 3382//3382 -f 3382//3382 3444//3444 3445//3445 -f 3382//3382 3445//3445 432//432 -f 432//432 3445//3445 247//247 -f 432//432 247//247 434//434 -f 434//434 247//247 249//249 -f 434//434 249//249 436//436 -f 436//436 249//249 251//251 -f 436//436 251//251 438//438 -f 438//438 251//251 253//253 -f 438//438 253//253 440//440 -f 440//440 253//253 255//255 -f 440//440 255//255 442//442 -f 442//442 255//255 257//257 -f 442//442 257//257 444//444 -f 444//444 257//257 259//259 -f 444//444 259//259 3378//3378 -f 3378//3378 259//259 3446//3446 -f 3378//3378 3446//3446 3379//3379 -f 3379//3379 3446//3446 3447//3447 -f 3379//3379 3447//3447 3380//3380 -f 3380//3380 3447//3447 3448//3448 -f 3380//3380 3448//3448 3381//3381 -f 3381//3381 3448//3448 3444//3444 -f 239//239 422//422 237//237 -f 237//237 422//422 420//420 -f 237//237 420//420 235//235 -f 235//235 420//420 418//418 -f 235//235 418//418 233//233 -f 233//233 418//418 416//416 -f 233//233 416//416 3449//3449 -f 3449//3449 416//416 3388//3388 -f 3449//3449 3388//3388 3450//3450 -f 3450//3450 3388//3388 3387//3387 -f 3450//3450 3387//3387 3451//3451 -f 3387//3387 3386//3386 3451//3451 -f 3451//3451 3386//3386 3385//3385 -f 3451//3451 3385//3385 3452//3452 -f 3452//3452 3385//3385 3384//3384 -f 3452//3452 3384//3384 3453//3453 -f 3453//3453 3384//3384 3383//3383 -f 3453//3453 3383//3383 245//245 -f 245//245 3383//3383 430//430 -f 245//245 430//430 243//243 -f 243//243 430//430 428//428 -f 243//243 428//428 241//241 -f 241//241 428//428 426//426 -f 241//241 426//426 239//239 -f 239//239 426//426 424//424 -f 239//239 424//424 422//422 -f 3389//3389 3454//3454 3390//3390 -f 3390//3390 3454//3454 3455//3455 -f 3390//3390 3455//3455 3391//3391 -f 3391//3391 3455//3455 3456//3456 -f 3391//3391 3456//3456 3392//3392 -f 3392//3392 3456//3456 3457//3457 -f 3392//3392 3457//3457 3393//3393 -f 3393//3393 3457//3457 3458//3458 -f 3393//3393 3458//3458 402//402 -f 402//402 3458//3458 219//219 -f 402//402 219//219 404//404 -f 404//404 219//219 221//221 -f 404//404 221//221 406//406 -f 406//406 221//221 223//223 -f 406//406 223//223 408//408 -f 408//408 223//223 225//225 -f 408//408 225//225 410//410 -f 410//410 225//225 227//227 -f 410//410 227//227 412//412 -f 412//412 227//227 229//229 -f 412//412 229//229 414//414 -f 414//414 229//229 231//231 -f 414//414 231//231 3389//3389 -f 3389//3389 231//231 3454//3454 -f 3394//3394 3459//3459 3395//3395 -f 3395//3395 3459//3459 3460//3460 -f 3395//3395 3460//3460 3396//3396 -f 3396//3396 3460//3460 3461//3461 -f 3396//3396 3461//3461 3397//3397 -f 3397//3397 3461//3461 3462//3462 -f 3397//3397 3462//3462 3398//3398 -f 3398//3398 3462//3462 3463//3463 -f 3398//3398 3463//3463 388//388 -f 388//388 3463//3463 205//205 -f 388//388 205//205 390//390 -f 390//390 205//205 207//207 -f 390//390 207//207 392//392 -f 392//392 207//207 209//209 -f 392//392 209//209 394//394 -f 394//394 209//209 211//211 -f 394//394 211//211 396//396 -f 396//396 211//211 213//213 -f 396//396 213//213 398//398 -f 398//398 213//213 215//215 -f 398//398 215//215 400//400 -f 400//400 215//215 217//217 -f 400//400 217//217 3394//3394 -f 3394//3394 217//217 3459//3459 -f 385//385 386//386 3399//3399 -f 3399//3399 386//386 3464//3464 -f 3399//3399 3464//3464 3400//3400 -f 3400//3400 3464//3464 3465//3465 -f 3400//3400 3465//3465 3401//3401 -f 3401//3401 3465//3465 3466//3466 -f 3401//3401 3466//3466 3402//3402 -f 3402//3402 3466//3466 3467//3467 -f 3402//3402 3467//3467 3403//3403 -f 3403//3403 3467//3467 3468//3468 -f 3403//3403 3468//3468 373//373 -f 373//373 3468//3468 374//374 -f 371//371 372//372 3404//3404 -f 3404//3404 372//372 3469//3469 -f 3404//3404 3469//3469 3405//3405 -f 3405//3405 3469//3469 3470//3470 -f 3405//3405 3470//3470 3406//3406 -f 3406//3406 3470//3470 3471//3471 -f 3406//3406 3471//3471 3407//3407 -f 3407//3407 3471//3471 3472//3472 -f 3407//3407 3472//3472 3408//3408 -f 3408//3408 3472//3472 3473//3473 -f 3408//3408 3473//3473 359//359 -f 359//359 3473//3473 360//360 -f 357//357 358//358 3410//3410 -f 3410//3410 358//358 3474//3474 -f 3410//3410 3474//3474 3411//3411 -f 3411//3411 3474//3474 3475//3475 -f 3411//3411 3475//3475 3412//3412 -f 3412//3412 3475//3475 3476//3476 -f 3412//3412 3476//3476 3413//3413 -f 3413//3413 3476//3476 3477//3477 -f 3413//3413 3477//3477 3409//3409 -f 3409//3409 3477//3477 3478//3478 -f 3409//3409 3478//3478 345//345 -f 345//345 3478//3478 346//346 -f 343//343 344//344 3415//3415 -f 3415//3415 344//344 3479//3479 -f 3415//3415 3479//3479 3416//3416 -f 3416//3416 3479//3479 3480//3480 -f 3416//3416 3480//3480 3417//3417 -f 3417//3417 3480//3480 3481//3481 -f 3417//3417 3481//3481 3418//3418 -f 3418//3418 3481//3481 3482//3482 -f 3418//3418 3482//3482 3414//3414 -f 3414//3414 3482//3482 3483//3483 -f 3414//3414 3483//3483 331//331 -f 331//331 3483//3483 332//332 -f 329//329 330//330 3419//3419 -f 3419//3419 330//330 3484//3484 -f 3419//3419 3484//3484 3420//3420 -f 3420//3420 3484//3484 3485//3485 -f 3420//3420 3485//3485 3421//3421 -f 3421//3421 3485//3485 3486//3486 -f 3421//3421 3486//3486 3422//3422 -f 3422//3422 3486//3486 3487//3487 -f 3422//3422 3487//3487 3423//3423 -f 3423//3423 3487//3487 3488//3488 -f 3423//3423 3488//3488 317//317 -f 317//317 3488//3488 318//318 -f 315//315 316//316 3424//3424 -f 3424//3424 316//316 3489//3489 -f 3424//3424 3489//3489 3425//3425 -f 3425//3425 3489//3489 3490//3490 -f 3425//3425 3490//3490 3426//3426 -f 3426//3426 3490//3490 3491//3491 -f 3426//3426 3491//3491 3427//3427 -f 3427//3427 3491//3491 3492//3492 -f 3427//3427 3492//3492 3428//3428 -f 3428//3428 3492//3492 3493//3493 -f 3428//3428 3493//3493 303//303 -f 303//303 3493//3493 304//304 -f 301//301 302//302 3431//3431 -f 3431//3431 302//302 3494//3494 -f 3431//3431 3494//3494 3432//3432 -f 3432//3432 3494//3494 3495//3495 -f 3432//3432 3495//3495 3433//3433 -f 3433//3433 3495//3495 3496//3496 -f 3433//3433 3496//3496 3429//3429 -f 3429//3429 3496//3496 3497//3497 -f 3429//3429 3497//3497 3430//3430 -f 3430//3430 3497//3497 3498//3498 -f 3430//3430 3498//3498 289//289 -f 289//289 3498//3498 290//290 -f 287//287 288//288 3434//3434 -f 3434//3434 288//288 3499//3499 -f 3434//3434 3499//3499 3435//3435 -f 3435//3435 3499//3499 3500//3500 -f 3435//3435 3500//3500 3436//3436 -f 3436//3436 3500//3500 3501//3501 -f 3436//3436 3501//3501 3437//3437 -f 3437//3437 3501//3501 3502//3502 -f 3437//3437 3502//3502 3438//3438 -f 3438//3438 3502//3502 3503//3503 -f 3438//3438 3503//3503 275//275 -f 275//275 3503//3503 276//276 -f 273//273 274//274 3439//3439 -f 3439//3439 274//274 3504//3504 -f 3439//3439 3504//3504 3440//3440 -f 3440//3440 3504//3504 3505//3505 -f 3440//3440 3505//3505 3441//3441 -f 3441//3441 3505//3505 3506//3506 -f 3441//3441 3506//3506 3442//3442 -f 3442//3442 3506//3506 3507//3507 -f 3442//3442 3507//3507 3443//3443 -f 3443//3443 3507//3507 3508//3508 -f 3443//3443 3508//3508 261//261 -f 261//261 3508//3508 262//262 -f 259//259 260//260 3446//3446 -f 3446//3446 260//260 3509//3509 -f 3446//3446 3509//3509 3447//3447 -f 3447//3447 3509//3509 3510//3510 -f 3447//3447 3510//3510 3448//3448 -f 3448//3448 3510//3510 3511//3511 -f 3448//3448 3511//3511 3444//3444 -f 3444//3444 3511//3511 3512//3512 -f 3444//3444 3512//3512 3445//3445 -f 3445//3445 3512//3512 3513//3513 -f 3445//3445 3513//3513 247//247 -f 247//247 3513//3513 248//248 -f 245//245 246//246 3453//3453 -f 3453//3453 246//246 3514//3514 -f 3453//3453 3514//3514 3452//3452 -f 3452//3452 3514//3514 3515//3515 -f 3452//3452 3515//3515 3451//3451 -f 3451//3451 3515//3515 3516//3516 -f 3451//3451 3516//3516 3450//3450 -f 3450//3450 3516//3516 3517//3517 -f 3450//3450 3517//3517 3449//3449 -f 3449//3449 3517//3517 3518//3518 -f 3449//3449 3518//3518 233//233 -f 233//233 3518//3518 234//234 -f 231//231 232//232 3454//3454 -f 3454//3454 232//232 3519//3519 -f 3454//3454 3519//3519 3455//3455 -f 3455//3455 3519//3519 3520//3520 -f 3455//3455 3520//3520 3456//3456 -f 3456//3456 3520//3520 3521//3521 -f 3456//3456 3521//3521 3457//3457 -f 3457//3457 3521//3521 3522//3522 -f 3457//3457 3522//3522 3458//3458 -f 3458//3458 3522//3522 3523//3523 -f 3458//3458 3523//3523 219//219 -f 219//219 3523//3523 220//220 -f 217//217 218//218 3459//3459 -f 3459//3459 218//218 3524//3524 -f 3459//3459 3524//3524 3460//3460 -f 3460//3460 3524//3524 3525//3525 -f 3460//3460 3525//3525 3461//3461 -f 3461//3461 3525//3525 3526//3526 -f 3461//3461 3526//3526 3462//3462 -f 3462//3462 3526//3526 3527//3527 -f 3462//3462 3527//3527 3463//3463 -f 3463//3463 3527//3527 3528//3528 -f 3463//3463 3528//3528 205//205 -f 205//205 3528//3528 206//206 -f 3529//3529 3468//3468 3530//3530 -f 3530//3530 3468//3468 3467//3467 -f 3530//3530 3467//3467 3531//3531 -f 3531//3531 3467//3467 3466//3466 -f 3531//3531 3466//3466 3532//3532 -f 3532//3532 3466//3466 3465//3465 -f 3532//3532 3465//3465 3533//3533 -f 3533//3533 3465//3465 3464//3464 -f 3533//3533 3464//3464 203//203 -f 203//203 3464//3464 386//386 -f 203//203 386//386 201//201 -f 201//201 386//386 384//384 -f 201//201 384//384 199//199 -f 199//199 384//384 382//382 -f 199//199 382//382 197//197 -f 197//197 382//382 380//380 -f 197//197 380//380 195//195 -f 195//195 380//380 378//378 -f 195//195 378//378 193//193 -f 193//193 378//378 376//376 -f 193//193 376//376 191//191 -f 191//191 376//376 374//374 -f 191//191 374//374 3529//3529 -f 3529//3529 374//374 3468//3468 -f 3534//3534 3472//3472 3535//3535 -f 3535//3535 3472//3472 3471//3471 -f 3535//3535 3471//3471 3536//3536 -f 3536//3536 3471//3471 3470//3470 -f 3536//3536 3470//3470 3537//3537 -f 3537//3537 3470//3470 3469//3469 -f 3537//3537 3469//3469 189//189 -f 189//189 3469//3469 372//372 -f 189//189 372//372 187//187 -f 187//187 372//372 370//370 -f 187//187 370//370 185//185 -f 185//185 370//370 368//368 -f 185//185 368//368 183//183 -f 183//183 368//368 366//366 -f 183//183 366//366 181//181 -f 181//181 366//366 364//364 -f 181//181 364//364 179//179 -f 179//179 364//364 362//362 -f 179//179 362//362 177//177 -f 177//177 362//362 360//360 -f 177//177 360//360 3538//3538 -f 3538//3538 360//360 3473//3473 -f 3538//3538 3473//3473 3534//3534 -f 3534//3534 3473//3473 3472//3472 -f 3539//3539 3474//3474 175//175 -f 175//175 3474//3474 358//358 -f 175//175 358//358 173//173 -f 173//173 358//358 356//356 -f 173//173 356//356 171//171 -f 171//171 356//356 354//354 -f 171//171 354//354 169//169 -f 169//169 354//354 352//352 -f 169//169 352//352 167//167 -f 167//167 352//352 350//350 -f 167//167 350//350 165//165 -f 165//165 350//350 348//348 -f 165//165 348//348 163//163 -f 163//163 348//348 346//346 -f 163//163 346//346 3540//3540 -f 3540//3540 346//346 3478//3478 -f 3540//3540 3478//3478 3541//3541 -f 3541//3541 3478//3478 3477//3477 -f 3541//3541 3477//3477 3542//3542 -f 3542//3542 3477//3477 3476//3476 -f 3542//3542 3476//3476 3543//3543 -f 3543//3543 3476//3476 3475//3475 -f 3543//3543 3475//3475 3539//3539 -f 3539//3539 3475//3475 3474//3474 -f 3544//3544 3483//3483 3545//3545 -f 3545//3545 3483//3483 3482//3482 -f 3545//3545 3482//3482 3546//3546 -f 3546//3546 3482//3482 3481//3481 -f 3546//3546 3481//3481 3547//3547 -f 3547//3547 3481//3481 3480//3480 -f 3547//3547 3480//3480 3548//3548 -f 3548//3548 3480//3480 3479//3479 -f 3548//3548 3479//3479 161//161 -f 161//161 3479//3479 344//344 -f 161//161 344//344 159//159 -f 159//159 344//344 342//342 -f 159//159 342//342 157//157 -f 157//157 342//342 340//340 -f 157//157 340//340 155//155 -f 155//155 340//340 338//338 -f 155//155 338//338 153//153 -f 153//153 338//338 336//336 -f 153//153 336//336 151//151 -f 151//151 336//336 334//334 -f 151//151 334//334 149//149 -f 149//149 334//334 332//332 -f 149//149 332//332 3544//3544 -f 3544//3544 332//332 3483//3483 -f 3549//3549 3488//3488 3550//3550 -f 3550//3550 3488//3488 3487//3487 -f 3550//3550 3487//3487 3551//3551 -f 3551//3551 3487//3487 3486//3486 -f 3551//3551 3486//3486 3552//3552 -f 3552//3552 3486//3486 3485//3485 -f 3552//3552 3485//3485 3553//3553 -f 3553//3553 3485//3485 3484//3484 -f 3553//3553 3484//3484 147//147 -f 147//147 3484//3484 330//330 -f 147//147 330//330 145//145 -f 145//145 330//330 328//328 -f 145//145 328//328 143//143 -f 143//143 328//328 326//326 -f 143//143 326//326 141//141 -f 141//141 326//326 324//324 -f 141//141 324//324 139//139 -f 139//139 324//324 322//322 -f 139//139 322//322 137//137 -f 137//137 322//322 320//320 -f 137//137 320//320 135//135 -f 135//135 320//320 318//318 -f 135//135 318//318 3549//3549 -f 3549//3549 318//318 3488//3488 -f 3554//3554 3489//3489 133//133 -f 133//133 3489//3489 316//316 -f 133//133 316//316 131//131 -f 131//131 316//316 314//314 -f 131//131 314//314 129//129 -f 129//129 314//314 312//312 -f 129//129 312//312 127//127 -f 127//127 312//312 310//310 -f 127//127 310//310 125//125 -f 125//125 310//310 308//308 -f 125//125 308//308 123//123 -f 123//123 308//308 306//306 -f 123//123 306//306 121//121 -f 121//121 306//306 304//304 -f 121//121 304//304 3555//3555 -f 3555//3555 304//304 3493//3493 -f 3555//3555 3493//3493 3556//3556 -f 3556//3556 3493//3493 3492//3492 -f 3556//3556 3492//3492 3557//3557 -f 3557//3557 3492//3492 3491//3491 -f 3557//3557 3491//3491 3558//3558 -f 3558//3558 3491//3491 3490//3490 -f 3558//3558 3490//3490 3554//3554 -f 3554//3554 3490//3490 3489//3489 -f 3559//3559 3497//3497 3560//3560 -f 3560//3560 3497//3497 3496//3496 -f 3560//3560 3496//3496 3561//3561 -f 3561//3561 3496//3496 3495//3495 -f 3561//3561 3495//3495 3562//3562 -f 3562//3562 3495//3495 3494//3494 -f 3562//3562 3494//3494 119//119 -f 119//119 3494//3494 302//302 -f 119//119 302//302 117//117 -f 117//117 302//302 300//300 -f 117//117 300//300 115//115 -f 115//115 300//300 298//298 -f 115//115 298//298 113//113 -f 113//113 298//298 296//296 -f 113//113 296//296 111//111 -f 111//111 296//296 294//294 -f 111//111 294//294 109//109 -f 109//109 294//294 292//292 -f 109//109 292//292 107//107 -f 107//107 292//292 290//290 -f 107//107 290//290 3563//3563 -f 3563//3563 290//290 3498//3498 -f 3563//3563 3498//3498 3559//3559 -f 3559//3559 3498//3498 3497//3497 -f 3564//3564 3503//3503 3565//3565 -f 3565//3565 3503//3503 3502//3502 -f 3565//3565 3502//3502 3566//3566 -f 3566//3566 3502//3502 3501//3501 -f 3566//3566 3501//3501 3567//3567 -f 3567//3567 3501//3501 3500//3500 -f 3567//3567 3500//3500 3568//3568 -f 3568//3568 3500//3500 3499//3499 -f 3568//3568 3499//3499 105//105 -f 105//105 3499//3499 288//288 -f 105//105 288//288 103//103 -f 103//103 288//288 286//286 -f 103//103 286//286 101//101 -f 101//101 286//286 284//284 -f 101//101 284//284 99//99 -f 99//99 284//284 282//282 -f 99//99 282//282 97//97 -f 97//97 282//282 280//280 -f 97//97 280//280 95//95 -f 95//95 280//280 278//278 -f 95//95 278//278 93//93 -f 93//93 278//278 276//276 -f 93//93 276//276 3564//3564 -f 3564//3564 276//276 3503//3503 -f 3569//3569 3504//3504 91//91 -f 91//91 3504//3504 274//274 -f 91//91 274//274 89//89 -f 89//89 274//274 272//272 -f 89//89 272//272 87//87 -f 87//87 272//272 270//270 -f 87//87 270//270 85//85 -f 85//85 270//270 268//268 -f 85//85 268//268 83//83 -f 83//83 268//268 266//266 -f 83//83 266//266 81//81 -f 81//81 266//266 264//264 -f 81//81 264//264 79//79 -f 79//79 264//264 262//262 -f 79//79 262//262 3570//3570 -f 3570//3570 262//262 3508//3508 -f 3570//3570 3508//3508 3571//3571 -f 3571//3571 3508//3508 3507//3507 -f 3571//3571 3507//3507 3572//3572 -f 3572//3572 3507//3507 3506//3506 -f 3572//3572 3506//3506 3573//3573 -f 3573//3573 3506//3506 3505//3505 -f 3573//3573 3505//3505 3569//3569 -f 3569//3569 3505//3505 3504//3504 -f 3574//3574 3512//3512 3575//3575 -f 3575//3575 3512//3512 3511//3511 -f 3575//3575 3511//3511 3576//3576 -f 3576//3576 3511//3511 3510//3510 -f 3576//3576 3510//3510 3577//3577 -f 3577//3577 3510//3510 3509//3509 -f 3577//3577 3509//3509 77//77 -f 77//77 3509//3509 260//260 -f 77//77 260//260 75//75 -f 75//75 260//260 258//258 -f 75//75 258//258 73//73 -f 73//73 258//258 256//256 -f 73//73 256//256 71//71 -f 71//71 256//256 254//254 -f 71//71 254//254 69//69 -f 69//69 254//254 252//252 -f 69//69 252//252 67//67 -f 67//67 252//252 250//250 -f 67//67 250//250 65//65 -f 65//65 250//250 248//248 -f 65//65 248//248 3578//3578 -f 3578//3578 248//248 3513//3513 -f 3578//3578 3513//3513 3574//3574 -f 3574//3574 3513//3513 3512//3512 -f 242//242 59//59 244//244 -f 244//244 59//59 61//61 -f 244//244 61//61 246//246 -f 246//246 61//61 63//63 -f 246//246 63//63 3514//3514 -f 238//238 53//53 240//240 -f 240//240 53//53 55//55 -f 240//240 55//55 242//242 -f 242//242 55//55 57//57 -f 242//242 57//57 59//59 -f 236//236 49//49 238//238 -f 238//238 49//49 51//51 -f 238//238 51//51 53//53 -f 3515//3515 3579//3579 3516//3516 -f 3516//3516 3579//3579 3580//3580 -f 3516//3516 3580//3580 3517//3517 -f 63//63 3581//3581 3514//3514 -f 3514//3514 3581//3581 3582//3582 -f 3514//3514 3582//3582 3515//3515 -f 3515//3515 3582//3582 3583//3583 -f 3515//3515 3583//3583 3579//3579 -f 3580//3580 3584//3584 3517//3517 -f 3517//3517 3584//3584 3585//3585 -f 3517//3517 3585//3585 3518//3518 -f 3518//3518 3585//3585 3586//3586 -f 3518//3518 3586//3586 234//234 -f 234//234 3586//3586 45//45 -f 234//234 45//45 236//236 -f 236//236 45//45 47//47 -f 236//236 47//47 49//49 -f 33//33 43//43 31//31 -f 31//31 43//43 3587//3587 -f 31//31 3587//3587 29//29 -f 3588//3588 3589//3589 3590//3590 -f 3590//3590 3589//3589 3591//3591 -f 3590//3590 3591//3591 3587//3587 -f 3587//3587 3591//3591 3592//3592 -f 3587//3587 3592//3592 29//29 -f 39//39 41//41 37//37 -f 37//37 41//41 43//43 -f 37//37 43//43 35//35 -f 35//35 43//43 33//33 -f 3593//3593 3523//3523 3594//3594 -f 3594//3594 3523//3523 3522//3522 -f 3594//3594 3522//3522 3595//3595 -f 3595//3595 3522//3522 3521//3521 -f 3595//3595 3521//3521 3596//3596 -f 3596//3596 3521//3521 3520//3520 -f 3596//3596 3520//3520 3597//3597 -f 3597//3597 3520//3520 3519//3519 -f 3597//3597 3519//3519 27//27 -f 27//27 3519//3519 232//232 -f 27//27 232//232 25//25 -f 25//25 232//232 230//230 -f 25//25 230//230 23//23 -f 23//23 230//230 228//228 -f 23//23 228//228 21//21 -f 21//21 228//228 226//226 -f 21//21 226//226 19//19 -f 19//19 226//226 224//224 -f 19//19 224//224 17//17 -f 17//17 224//224 222//222 -f 17//17 222//222 15//15 -f 15//15 222//222 220//220 -f 15//15 220//220 3593//3593 -f 3593//3593 220//220 3523//3523 -f 3598//3598 3528//3528 3599//3599 -f 3599//3599 3528//3528 3527//3527 -f 3599//3599 3527//3527 3600//3600 -f 3600//3600 3527//3527 3526//3526 -f 3600//3600 3526//3526 3601//3601 -f 3601//3601 3526//3526 3525//3525 -f 3601//3601 3525//3525 3602//3602 -f 3602//3602 3525//3525 3524//3524 -f 3602//3602 3524//3524 13//13 -f 13//13 3524//3524 218//218 -f 13//13 218//218 11//11 -f 11//11 218//218 216//216 -f 11//11 216//216 9//9 -f 9//9 216//216 214//214 -f 9//9 214//214 7//7 -f 7//7 214//214 212//212 -f 7//7 212//212 5//5 -f 5//5 212//212 210//210 -f 5//5 210//210 3//3 -f 3//3 210//210 208//208 -f 3//3 208//208 1//1 -f 1//1 208//208 206//206 -f 1//1 206//206 3598//3598 -f 3598//3598 206//206 3528//3528 -f 3603//3603 3604//3604 3605//3605 -f 3605//3605 3606//3606 3603//3603 -f 3603//3603 3606//3606 3607//3607 -f 3603//3603 3607//3607 3608//3608 -f 3608//3608 3607//3607 3609//3609 -f 3610//3610 3611//3611 3612//3612 -f 3612//3612 3611//3611 3608//3608 -f 3612//3612 3608//3608 3613//3613 -f 3613//3613 3608//3608 3609//3609 -f 3605//3605 3604//3604 3614//3614 -f 3614//3614 3604//3604 3615//3615 -f 203//203 204//204 3533//3533 -f 3533//3533 204//204 3616//3616 -f 3533//3533 3616//3616 3532//3532 -f 3532//3532 3616//3616 3617//3617 -f 3532//3532 3617//3617 3531//3531 -f 3531//3531 3617//3617 3618//3618 -f 3531//3531 3618//3618 3530//3530 -f 3530//3530 3618//3618 3619//3619 -f 3530//3530 3619//3619 3529//3529 -f 3529//3529 3619//3619 3620//3620 -f 3529//3529 3620//3620 191//191 -f 191//191 3620//3620 192//192 -f 189//189 190//190 3537//3537 -f 3537//3537 190//190 3621//3621 -f 3537//3537 3621//3621 3536//3536 -f 3536//3536 3621//3621 3622//3622 -f 3536//3536 3622//3622 3535//3535 -f 3535//3535 3622//3622 3623//3623 -f 3535//3535 3623//3623 3534//3534 -f 3534//3534 3623//3623 3624//3624 -f 3534//3534 3624//3624 3538//3538 -f 3538//3538 3624//3624 3625//3625 -f 3538//3538 3625//3625 177//177 -f 177//177 3625//3625 178//178 -f 3614//3614 3615//3615 3626//3626 -f 3626//3626 3615//3615 3627//3627 -f 3628//3628 3629//3629 3630//3630 -f 3630//3630 3629//3629 3631//3631 -f 3630//3630 3631//3631 3627//3627 -f 3627//3627 3631//3631 3632//3632 -f 3627//3627 3632//3632 3626//3626 -f 3628//3628 3630//3630 3633//3633 -f 3633//3633 3630//3630 3634//3634 -f 3633//3633 3634//3634 3635//3635 -f 175//175 176//176 3539//3539 -f 3539//3539 176//176 3636//3636 -f 3539//3539 3636//3636 3543//3543 -f 3543//3543 3636//3636 3637//3637 -f 3543//3543 3637//3637 3542//3542 -f 3542//3542 3637//3637 3638//3638 -f 3542//3542 3638//3638 3541//3541 -f 3541//3541 3638//3638 3639//3639 -f 3541//3541 3639//3639 3540//3540 -f 3540//3540 3639//3639 3640//3640 -f 3540//3540 3640//3640 163//163 -f 163//163 3640//3640 164//164 -f 3641//3641 3642//3642 3643//3643 -f 3641//3641 3643//3643 3644//3644 -f 3643//3643 3645//3645 3644//3644 -f 3644//3644 3645//3645 3646//3646 -f 3644//3644 3646//3646 3647//3647 -f 3648//3648 3649//3649 3650//3650 -f 3650//3650 3649//3649 3647//3647 -f 3650//3650 3647//3647 3651//3651 -f 3651//3651 3647//3647 3646//3646 -f 161//161 162//162 3548//3548 -f 3548//3548 162//162 3652//3652 -f 3548//3548 3652//3652 3547//3547 -f 3547//3547 3652//3652 3653//3653 -f 3547//3547 3653//3653 3546//3546 -f 3546//3546 3653//3653 3654//3654 -f 3546//3546 3654//3654 3545//3545 -f 3545//3545 3654//3654 3655//3655 -f 3545//3545 3655//3655 3544//3544 -f 3544//3544 3655//3655 3656//3656 -f 3544//3544 3656//3656 149//149 -f 149//149 3656//3656 150//150 -f 3657//3657 3658//3658 3659//3659 -f 3657//3657 3659//3659 3660//3660 -f 3659//3659 3661//3661 3660//3660 -f 3660//3660 3661//3661 3662//3662 -f 3660//3660 3662//3662 3663//3663 -f 3664//3664 3665//3665 3666//3666 -f 3666//3666 3665//3665 3663//3663 -f 3666//3666 3663//3663 3667//3667 -f 3667//3667 3663//3663 3662//3662 -f 3668//3668 3669//3669 3670//3670 -f 3670//3670 3669//3669 3671//3671 -f 3672//3672 3673//3673 3674//3674 -f 3674//3674 3673//3673 3675//3675 -f 3674//3674 3675//3675 3671//3671 -f 3671//3671 3675//3675 3676//3676 -f 3671//3671 3676//3676 3670//3670 -f 3672//3672 3674//3674 3677//3677 -f 3677//3677 3674//3674 3678//3678 -f 3677//3677 3678//3678 3679//3679 -f 3679//3679 3678//3678 3680//3680 -f 3680//3680 3678//3678 3681//3681 -f 147//147 148//148 3553//3553 -f 3553//3553 148//148 3682//3682 -f 3553//3553 3682//3682 3552//3552 -f 3552//3552 3682//3682 3683//3683 -f 3552//3552 3683//3683 3551//3551 -f 3551//3551 3683//3683 3684//3684 -f 3551//3551 3684//3684 3550//3550 -f 3550//3550 3684//3684 3685//3685 -f 3550//3550 3685//3685 3549//3549 -f 3549//3549 3685//3685 3686//3686 -f 3549//3549 3686//3686 135//135 -f 135//135 3686//3686 136//136 -f 133//133 134//134 3554//3554 -f 3554//3554 134//134 3687//3687 -f 3554//3554 3687//3687 3558//3558 -f 3558//3558 3687//3687 3688//3688 -f 3558//3558 3688//3688 3557//3557 -f 3557//3557 3688//3688 3689//3689 -f 3557//3557 3689//3689 3556//3556 -f 3556//3556 3689//3689 3690//3690 -f 3556//3556 3690//3690 3555//3555 -f 3555//3555 3690//3690 3691//3691 -f 3555//3555 3691//3691 121//121 -f 121//121 3691//3691 122//122 -f 3692//3692 3693//3693 3694//3694 -f 3692//3692 3694//3694 3695//3695 -f 3695//3695 3694//3694 3696//3696 -f 3695//3695 3696//3696 3697//3697 -f 3696//3696 3698//3698 3697//3697 -f 3697//3697 3698//3698 3699//3699 -f 3697//3697 3699//3699 3681//3681 -f 3681//3681 3699//3699 3700//3700 -f 3681//3681 3700//3700 3680//3680 -f 119//119 120//120 3562//3562 -f 3562//3562 120//120 3701//3701 -f 3562//3562 3701//3701 3561//3561 -f 3561//3561 3701//3701 3702//3702 -f 3561//3561 3702//3702 3560//3560 -f 3560//3560 3702//3702 3703//3703 -f 3560//3560 3703//3703 3559//3559 -f 3559//3559 3703//3703 3704//3704 -f 3559//3559 3704//3704 3563//3563 -f 3563//3563 3704//3704 3705//3705 -f 3563//3563 3705//3705 107//107 -f 107//107 3705//3705 108//108 -f 105//105 106//106 3568//3568 -f 3568//3568 106//106 3706//3706 -f 3568//3568 3706//3706 3567//3567 -f 3567//3567 3706//3706 3707//3707 -f 3567//3567 3707//3707 3566//3566 -f 3566//3566 3707//3707 3708//3708 -f 3566//3566 3708//3708 3565//3565 -f 3565//3565 3708//3708 3709//3709 -f 3565//3565 3709//3709 3564//3564 -f 3564//3564 3709//3709 3710//3710 -f 3564//3564 3710//3710 93//93 -f 93//93 3710//3710 94//94 -f 91//91 92//92 3569//3569 -f 3569//3569 92//92 3711//3711 -f 3569//3569 3711//3711 3573//3573 -f 3573//3573 3711//3711 3712//3712 -f 3573//3573 3712//3712 3572//3572 -f 3572//3572 3712//3712 3713//3713 -f 3572//3572 3713//3713 3571//3571 -f 3571//3571 3713//3713 3714//3714 -f 3571//3571 3714//3714 3570//3570 -f 3570//3570 3714//3714 3715//3715 -f 3570//3570 3715//3715 79//79 -f 79//79 3715//3715 80//80 -f 77//77 78//78 3577//3577 -f 3577//3577 78//78 3716//3716 -f 3577//3577 3716//3716 3576//3576 -f 3576//3576 3716//3716 3717//3717 -f 3576//3576 3717//3717 3575//3575 -f 3575//3575 3717//3717 3718//3718 -f 3575//3575 3718//3718 3574//3574 -f 3574//3574 3718//3718 3719//3719 -f 3574//3574 3719//3719 3578//3578 -f 3578//3578 3719//3719 3720//3720 -f 3578//3578 3720//3720 65//65 -f 65//65 3720//3720 66//66 -f 63//63 64//64 3581//3581 -f 3581//3581 64//64 3721//3721 -f 3581//3581 3721//3721 3582//3582 -f 3582//3582 3721//3721 3722//3722 -f 3582//3582 3722//3722 3583//3583 -f 3583//3583 3722//3722 3723//3723 -f 3583//3583 3723//3723 3579//3579 -f 3579//3579 3723//3723 3724//3724 -f 3579//3579 3724//3724 3580//3580 -f 3580//3580 3724//3724 3725//3725 -f 3580//3580 3725//3725 3584//3584 -f 3584//3584 3725//3725 3726//3726 -f 3584//3584 3726//3726 3585//3585 -f 3585//3585 3726//3726 3727//3727 -f 3585//3585 3727//3727 3586//3586 -f 3586//3586 3727//3727 3728//3728 -f 3586//3586 3728//3728 45//45 -f 45//45 3728//3728 46//46 -f 43//43 44//44 3587//3587 -f 3587//3587 44//44 3729//3729 -f 3587//3587 3729//3729 3590//3590 -f 3590//3590 3729//3729 3730//3730 -f 3590//3590 3730//3730 3588//3588 -f 3588//3588 3730//3730 3731//3731 -f 3588//3588 3731//3731 3589//3589 -f 3589//3589 3731//3731 3732//3732 -f 3589//3589 3732//3732 3591//3591 -f 3591//3591 3732//3732 3733//3733 -f 3591//3591 3733//3733 3592//3592 -f 3592//3592 3733//3733 3734//3734 -f 3592//3592 3734//3734 29//29 -f 29//29 3734//3734 30//30 -f 3735//3735 3736//3736 3737//3737 -f 3738//3738 3739//3739 3740//3740 -f 3741//3741 3742//3742 3743//3743 -f 3744//3744 3614//3614 3626//3626 -f 3739//3739 3744//3744 3745//3745 -f 3745//3745 3744//3744 3626//3626 -f 3745//3745 3626//3626 3746//3746 -f 3746//3746 3626//3626 3632//3632 -f 3633//3633 3747//3747 3628//3628 -f 3628//3628 3747//3747 3748//3748 -f 3628//3628 3748//3748 3629//3629 -f 3629//3629 3748//3748 3746//3746 -f 3629//3629 3746//3746 3631//3631 -f 3631//3631 3746//3746 3632//3632 -f 3633//3633 3635//3635 3747//3747 -f 3747//3747 3635//3635 3749//3749 -f 3747//3747 3749//3749 3750//3750 -f 3739//3739 3745//3745 3740//3740 -f 3740//3740 3745//3745 3746//3746 -f 3740//3740 3746//3746 3751//3751 -f 3751//3751 3746//3746 3748//3748 -f 3751//3751 3748//3748 3752//3752 -f 3752//3752 3748//3748 3747//3747 -f 3752//3752 3747//3747 3743//3743 -f 3743//3743 3747//3747 3750//3750 -f 3743//3743 3750//3750 3741//3741 -f 3738//3738 3740//3740 3753//3753 -f 3753//3753 3740//3740 3751//3751 -f 3753//3753 3751//3751 3754//3754 -f 3754//3754 3751//3751 3752//3752 -f 3754//3754 3752//3752 3755//3755 -f 3755//3755 3752//3752 3743//3743 -f 3755//3755 3743//3743 3737//3737 -f 3737//3737 3743//3743 3742//3742 -f 3737//3737 3742//3742 3735//3735 -f 3605//3605 3614//3614 3744//3744 -f 3605//3605 3744//3744 3756//3756 -f 3756//3756 3744//3744 3739//3739 -f 3756//3756 3739//3739 3757//3757 -f 3757//3757 3739//3739 3738//3738 -f 3757//3757 3738//3738 3758//3758 -f 3759//3759 3760//3760 3761//3761 -f 3760//3760 3762//3762 3763//3763 -f 3762//3762 3610//3610 3612//3612 -f 3762//3762 3612//3612 3763//3763 -f 3763//3763 3612//3612 3613//3613 -f 3763//3763 3613//3613 3764//3764 -f 3764//3764 3613//3613 3609//3609 -f 3764//3764 3609//3609 3765//3765 -f 3765//3765 3609//3609 3607//3607 -f 3765//3765 3607//3607 3766//3766 -f 3766//3766 3607//3607 3606//3606 -f 3766//3766 3606//3606 3767//3767 -f 3767//3767 3606//3606 3605//3605 -f 3767//3767 3605//3605 3756//3756 -f 3760//3760 3763//3763 3761//3761 -f 3761//3761 3763//3763 3764//3764 -f 3761//3761 3764//3764 3768//3768 -f 3768//3768 3764//3764 3765//3765 -f 3768//3768 3765//3765 3769//3769 -f 3769//3769 3765//3765 3766//3766 -f 3769//3769 3766//3766 3770//3770 -f 3770//3770 3766//3766 3767//3767 -f 3770//3770 3767//3767 3771//3771 -f 3771//3771 3767//3767 3756//3756 -f 3771//3771 3756//3756 3757//3757 -f 3759//3759 3761//3761 3772//3772 -f 3772//3772 3761//3761 3768//3768 -f 3772//3772 3768//3768 3773//3773 -f 3773//3773 3768//3768 3769//3769 -f 3773//3773 3769//3769 3774//3774 -f 3774//3774 3769//3769 3770//3770 -f 3774//3774 3770//3770 3775//3775 -f 3775//3775 3770//3770 3771//3771 -f 3775//3775 3771//3771 3776//3776 -f 3776//3776 3771//3771 3757//3757 -f 3776//3776 3757//3757 3758//3758 -f 3777//3777 3610//3610 3778//3778 -f 3778//3778 3610//3610 3762//3762 -f 3778//3778 3762//3762 3779//3779 -f 3779//3779 3762//3762 3780//3780 -f 3780//3780 3762//3762 3760//3760 -f 3780//3780 3760//3760 3781//3781 -f 3760//3760 3759//3759 3781//3781 -f 3781//3781 3759//3759 3782//3782 -f 3781//3781 3782//3782 3783//3783 -f 3783//3783 3782//3782 3784//3784 -f 3785//3785 3786//3786 3787//3787 -f 3788//3788 3789//3789 3790//3790 -f 3785//3785 3787//3787 3791//3791 -f 3791//3791 3787//3787 3788//3788 -f 3791//3791 3788//3788 3792//3792 -f 3792//3792 3788//3788 3790//3790 -f 3792//3792 3790//3790 3793//3793 -f 3794//3794 3795//3795 3796//3796 -f 3795//3795 3797//3797 3798//3798 -f 3797//3797 3799//3799 3800//3800 -f 3797//3797 3800//3800 3798//3798 -f 3798//3798 3800//3800 3801//3801 -f 3798//3798 3801//3801 3802//3802 -f 3802//3802 3801//3801 3803//3803 -f 3802//3802 3803//3803 3804//3804 -f 3804//3804 3803//3803 3805//3805 -f 3804//3804 3805//3805 3806//3806 -f 3806//3806 3805//3805 3807//3807 -f 3806//3806 3807//3807 3808//3808 -f 3808//3808 3807//3807 3785//3785 -f 3808//3808 3785//3785 3791//3791 -f 3795//3795 3798//3798 3796//3796 -f 3796//3796 3798//3798 3802//3802 -f 3796//3796 3802//3802 3809//3809 -f 3809//3809 3802//3802 3804//3804 -f 3809//3809 3804//3804 3810//3810 -f 3810//3810 3804//3804 3806//3806 -f 3810//3810 3806//3806 3811//3811 -f 3811//3811 3806//3806 3808//3808 -f 3811//3811 3808//3808 3812//3812 -f 3812//3812 3808//3808 3791//3791 -f 3812//3812 3791//3791 3792//3792 -f 3794//3794 3796//3796 3813//3813 -f 3813//3813 3796//3796 3809//3809 -f 3813//3813 3809//3809 3814//3814 -f 3814//3814 3809//3809 3810//3810 -f 3814//3814 3810//3810 3815//3815 -f 3815//3815 3810//3810 3811//3811 -f 3815//3815 3811//3811 3816//3816 -f 3816//3816 3811//3811 3812//3812 -f 3816//3816 3812//3812 3817//3817 -f 3817//3817 3812//3812 3792//3792 -f 3817//3817 3792//3792 3793//3793 -f 3818//3818 3819//3819 3820//3820 -f 3819//3819 3821//3821 3822//3822 -f 3821//3821 3823//3823 3824//3824 -f 3821//3821 3824//3824 3822//3822 -f 3822//3822 3824//3824 3825//3825 -f 3822//3822 3825//3825 3826//3826 -f 3826//3826 3825//3825 3827//3827 -f 3826//3826 3827//3827 3828//3828 -f 3828//3828 3827//3827 3829//3829 -f 3828//3828 3829//3829 3830//3830 -f 3830//3830 3829//3829 3831//3831 -f 3830//3830 3831//3831 3832//3832 -f 3832//3832 3831//3831 3833//3833 -f 3832//3832 3833//3833 3834//3834 -f 3819//3819 3822//3822 3820//3820 -f 3820//3820 3822//3822 3826//3826 -f 3820//3820 3826//3826 3835//3835 -f 3835//3835 3826//3826 3828//3828 -f 3835//3835 3828//3828 3836//3836 -f 3836//3836 3828//3828 3830//3830 -f 3836//3836 3830//3830 3837//3837 -f 3837//3837 3830//3830 3832//3832 -f 3837//3837 3832//3832 3838//3838 -f 3838//3838 3832//3832 3834//3834 -f 3838//3838 3834//3834 3839//3839 -f 3818//3818 3820//3820 3840//3840 -f 3840//3840 3820//3820 3835//3835 -f 3840//3840 3835//3835 3841//3841 -f 3841//3841 3835//3835 3836//3836 -f 3841//3841 3836//3836 3842//3842 -f 3842//3842 3836//3836 3837//3837 -f 3842//3842 3837//3837 3843//3843 -f 3843//3843 3837//3837 3838//3838 -f 3843//3843 3838//3838 3844//3844 -f 3844//3844 3838//3838 3839//3839 -f 3844//3844 3839//3839 3845//3845 -f 3846//3846 3823//3823 3821//3821 -f 3846//3846 3821//3821 3847//3847 -f 3847//3847 3821//3821 3819//3819 -f 3847//3847 3819//3819 3848//3848 -f 3848//3848 3819//3819 3818//3818 -f 3848//3848 3818//3818 3849//3849 -f 3693//3693 3850//3850 3851//3851 -f 3693//3693 3851//3851 3852//3852 -f 3852//3852 3851//3851 3853//3853 -f 3852//3852 3853//3853 3854//3854 -f 3854//3854 3853//3853 3855//3855 -f 3854//3854 3855//3855 3856//3856 -f 3857//3857 3858//3858 3859//3859 -f 3858//3858 3860//3860 3861//3861 -f 3860//3860 3680//3680 3700//3700 -f 3860//3860 3700//3700 3861//3861 -f 3861//3861 3700//3700 3699//3699 -f 3861//3861 3699//3699 3862//3862 -f 3862//3862 3699//3699 3698//3698 -f 3862//3862 3698//3698 3863//3863 -f 3863//3863 3698//3698 3696//3696 -f 3863//3863 3696//3696 3864//3864 -f 3864//3864 3696//3696 3694//3694 -f 3864//3864 3694//3694 3865//3865 -f 3865//3865 3694//3694 3693//3693 -f 3865//3865 3693//3693 3852//3852 -f 3858//3858 3861//3861 3859//3859 -f 3859//3859 3861//3861 3862//3862 -f 3859//3859 3862//3862 3866//3866 -f 3866//3866 3862//3862 3863//3863 -f 3866//3866 3863//3863 3867//3867 -f 3867//3867 3863//3863 3864//3864 -f 3867//3867 3864//3864 3868//3868 -f 3868//3868 3864//3864 3865//3865 -f 3868//3868 3865//3865 3869//3869 -f 3869//3869 3865//3865 3852//3852 -f 3869//3869 3852//3852 3854//3854 -f 3857//3857 3859//3859 3870//3870 -f 3870//3870 3859//3859 3866//3866 -f 3870//3870 3866//3866 3871//3871 -f 3871//3871 3866//3866 3867//3867 -f 3871//3871 3867//3867 3872//3872 -f 3872//3872 3867//3867 3868//3868 -f 3872//3872 3868//3868 3873//3873 -f 3873//3873 3868//3868 3869//3869 -f 3873//3873 3869//3869 3874//3874 -f 3874//3874 3869//3869 3854//3854 -f 3874//3874 3854//3854 3856//3856 -f 3679//3679 3680//3680 3860//3860 -f 3679//3679 3860//3860 3875//3875 -f 3875//3875 3860//3860 3858//3858 -f 3875//3875 3858//3858 3876//3876 -f 3876//3876 3858//3858 3857//3857 -f 3876//3876 3857//3857 3877//3877 -f 3878//3878 3879//3879 3880//3880 -f 3881//3881 3668//3668 3670//3670 -f 3879//3879 3881//3881 3882//3882 -f 3882//3882 3881//3881 3670//3670 -f 3882//3882 3670//3670 3883//3883 -f 3883//3883 3670//3670 3676//3676 -f 3676//3676 3675//3675 3883//3883 -f 3883//3883 3675//3675 3673//3673 -f 3883//3883 3673//3673 3884//3884 -f 3884//3884 3673//3673 3672//3672 -f 3884//3884 3672//3672 3885//3885 -f 3672//3672 3677//3677 3885//3885 -f 3885//3885 3677//3677 3679//3679 -f 3885//3885 3679//3679 3875//3875 -f 3879//3879 3882//3882 3880//3880 -f 3880//3880 3882//3882 3883//3883 -f 3880//3880 3883//3883 3886//3886 -f 3886//3886 3883//3883 3884//3884 -f 3886//3886 3884//3884 3887//3887 -f 3887//3887 3884//3884 3885//3885 -f 3887//3887 3885//3885 3888//3888 -f 3888//3888 3885//3885 3875//3875 -f 3888//3888 3875//3875 3876//3876 -f 3878//3878 3880//3880 3889//3889 -f 3889//3889 3880//3880 3886//3886 -f 3889//3889 3886//3886 3890//3890 -f 3890//3890 3886//3886 3887//3887 -f 3890//3890 3887//3887 3891//3891 -f 3891//3891 3887//3887 3888//3888 -f 3891//3891 3888//3888 3892//3892 -f 3892//3892 3888//3888 3876//3876 -f 3892//3892 3876//3876 3877//3877 -f 3893//3893 3668//3668 3881//3881 -f 3893//3893 3881//3881 3894//3894 -f 3894//3894 3881//3881 3879//3879 -f 3894//3894 3879//3879 3895//3895 -f 3895//3895 3879//3879 3878//3878 -f 3895//3895 3878//3878 3896//3896 -f 3897//3897 3898//3898 3658//3658 -f 3658//3658 3898//3898 3899//3899 -f 3898//3898 3900//3900 3899//3899 -f 3899//3899 3900//3900 3901//3901 -f 3899//3899 3901//3901 3902//3902 -f 3903//3903 3904//3904 3905//3905 -f 3905//3905 3904//3904 3902//3902 -f 3905//3905 3902//3902 3906//3906 -f 3906//3906 3902//3902 3901//3901 -f 3907//3907 3908//3908 3909//3909 -f 3908//3908 3910//3910 3911//3911 -f 3910//3910 3664//3664 3666//3666 -f 3910//3910 3666//3666 3911//3911 -f 3911//3911 3666//3666 3667//3667 -f 3911//3911 3667//3667 3912//3912 -f 3912//3912 3667//3667 3662//3662 -f 3912//3912 3662//3662 3913//3913 -f 3913//3913 3662//3662 3661//3661 -f 3913//3913 3661//3661 3914//3914 -f 3914//3914 3661//3661 3659//3659 -f 3914//3914 3659//3659 3915//3915 -f 3915//3915 3659//3659 3658//3658 -f 3915//3915 3658//3658 3899//3899 -f 3908//3908 3911//3911 3909//3909 -f 3909//3909 3911//3911 3912//3912 -f 3909//3909 3912//3912 3916//3916 -f 3916//3916 3912//3912 3913//3913 -f 3916//3916 3913//3913 3917//3917 -f 3917//3917 3913//3913 3914//3914 -f 3917//3917 3914//3914 3918//3918 -f 3918//3918 3914//3914 3915//3915 -f 3918//3918 3915//3915 3919//3919 -f 3919//3919 3915//3915 3899//3899 -f 3919//3919 3899//3899 3902//3902 -f 3907//3907 3909//3909 3920//3920 -f 3920//3920 3909//3909 3916//3916 -f 3920//3920 3916//3916 3921//3921 -f 3921//3921 3916//3916 3917//3917 -f 3921//3921 3917//3917 3922//3922 -f 3922//3922 3917//3917 3918//3918 -f 3922//3922 3918//3918 3923//3923 -f 3923//3923 3918//3918 3919//3919 -f 3923//3923 3919//3919 3924//3924 -f 3924//3924 3919//3919 3902//3902 -f 3924//3924 3902//3902 3904//3904 -f 3925//3925 3664//3664 3926//3926 -f 3926//3926 3664//3664 3910//3910 -f 3926//3926 3910//3910 3927//3927 -f 3927//3927 3910//3910 3928//3928 -f 3928//3928 3910//3910 3908//3908 -f 3928//3928 3908//3908 3929//3929 -f 3929//3929 3908//3908 3930//3930 -f 3930//3930 3908//3908 3907//3907 -f 3930//3930 3907//3907 3931//3931 -f 3642//3642 3932//3932 3933//3933 -f 3642//3642 3933//3933 3934//3934 -f 3934//3934 3933//3933 3935//3935 -f 3934//3934 3935//3935 3936//3936 -f 3936//3936 3935//3935 3937//3937 -f 3936//3936 3937//3937 3938//3938 -f 3938//3938 3937//3937 3939//3939 -f 3938//3938 3939//3939 3940//3940 -f 3936//3936 3938//3938 3941//3941 -f 3942//3942 3943//3943 3944//3944 -f 3943//3943 3945//3945 3946//3946 -f 3945//3945 3648//3648 3650//3650 -f 3945//3945 3650//3650 3946//3946 -f 3946//3946 3650//3650 3651//3651 -f 3946//3946 3651//3651 3947//3947 -f 3947//3947 3651//3651 3646//3646 -f 3947//3947 3646//3646 3948//3948 -f 3948//3948 3646//3646 3645//3645 -f 3948//3948 3645//3645 3949//3949 -f 3949//3949 3645//3645 3643//3643 -f 3949//3949 3643//3643 3950//3950 -f 3950//3950 3643//3643 3642//3642 -f 3950//3950 3642//3642 3934//3934 -f 3943//3943 3946//3946 3944//3944 -f 3944//3944 3946//3946 3947//3947 -f 3944//3944 3947//3947 3951//3951 -f 3951//3951 3947//3947 3948//3948 -f 3951//3951 3948//3948 3952//3952 -f 3952//3952 3948//3948 3949//3949 -f 3952//3952 3949//3949 3953//3953 -f 3953//3953 3949//3949 3950//3950 -f 3953//3953 3950//3950 3941//3941 -f 3941//3941 3950//3950 3934//3934 -f 3941//3941 3934//3934 3936//3936 -f 3942//3942 3944//3944 3954//3954 -f 3954//3954 3944//3944 3951//3951 -f 3954//3954 3951//3951 3955//3955 -f 3955//3955 3951//3951 3952//3952 -f 3955//3955 3952//3952 3956//3956 -f 3956//3956 3952//3952 3953//3953 -f 3956//3956 3953//3953 3957//3957 -f 3957//3957 3953//3953 3941//3941 -f 3957//3957 3941//3941 3958//3958 -f 3958//3958 3941//3941 3938//3938 -f 3958//3958 3938//3938 3940//3940 -f 3959//3959 3648//3648 3960//3960 -f 3960//3960 3648//3648 3945//3945 -f 3960//3960 3945//3945 3961//3961 -f 3961//3961 3945//3945 3962//3962 -f 3962//3962 3945//3945 3943//3943 -f 3962//3962 3943//3943 3963//3963 -f 3963//3963 3943//3943 3964//3964 -f 3964//3964 3943//3943 3942//3942 -f 3964//3964 3942//3942 3965//3965 -f 3966//3966 3967//3967 3635//3635 -f 3635//3635 3967//3967 3749//3749 -f 3749//3749 3967//3967 3750//3750 -f 3750//3750 3967//3967 3968//3968 -f 3750//3750 3968//3968 3741//3741 -f 3741//3741 3968//3968 3969//3969 -f 3741//3741 3969//3969 3742//3742 -f 3742//3742 3969//3969 3970//3970 -f 3742//3742 3970//3970 3735//3735 -f 3970//3970 3971//3971 3735//3735 -f 3735//3735 3971//3971 3972//3972 -f 3735//3735 3972//3972 3736//3736 -f 3973//3973 3974//3974 3833//3833 -f 3833//3833 3974//3974 3834//3834 -f 3974//3974 3975//3975 3834//3834 -f 3834//3834 3975//3975 3976//3976 -f 3834//3834 3976//3976 3839//3839 -f 3977//3977 3845//3845 3978//3978 -f 3978//3978 3845//3845 3839//3839 -f 3978//3978 3839//3839 3979//3979 -f 3979//3979 3839//3839 3976//3976 -f 3980//3980 3799//3799 3797//3797 -f 3980//3980 3797//3797 3981//3981 -f 3981//3981 3797//3797 3795//3795 -f 3981//3981 3795//3795 3982//3982 -f 3982//3982 3795//3795 3794//3794 -f 3982//3982 3794//3794 3983//3983 -f 27//27 28//28 3597//3597 -f 3597//3597 28//28 3984//3984 -f 3597//3597 3984//3984 3596//3596 -f 3596//3596 3984//3984 3985//3985 -f 3596//3596 3985//3985 3595//3595 -f 3595//3595 3985//3985 3986//3986 -f 3595//3595 3986//3986 3594//3594 -f 3594//3594 3986//3986 3987//3987 -f 3594//3594 3987//3987 3593//3593 -f 3593//3593 3987//3987 3988//3988 -f 3593//3593 3988//3988 15//15 -f 15//15 3988//3988 16//16 -f 3803//3803 3989//3989 3805//3805 -f 3805//3805 3989//3989 3990//3990 -f 3805//3805 3990//3990 3807//3807 -f 3807//3807 3990//3990 3991//3991 -f 3807//3807 3991//3991 3785//3785 -f 3799//3799 3992//3992 3800//3800 -f 3800//3800 3992//3992 3989//3989 -f 3800//3800 3989//3989 3801//3801 -f 3801//3801 3989//3989 3803//3803 -f 13//13 14//14 3602//3602 -f 3602//3602 14//14 3993//3993 -f 3602//3602 3993//3993 3601//3601 -f 3601//3601 3993//3993 3994//3994 -f 3601//3601 3994//3994 3600//3600 -f 3600//3600 3994//3994 3995//3995 -f 3600//3600 3995//3995 3599//3599 -f 3599//3599 3995//3995 3996//3996 -f 3599//3599 3996//3996 3598//3598 -f 3598//3598 3996//3996 3997//3997 -f 3598//3598 3997//3997 1//1 -f 1//1 3997//3997 2//2 -f 3998//3998 3833//3833 3831//3831 -f 3998//3998 3831//3831 3999//3999 -f 3831//3831 3829//3829 3999//3999 -f 3999//3999 3829//3829 3827//3827 -f 3999//3999 3827//3827 4000//4000 -f 4000//4000 3827//3827 3825//3825 -f 4000//4000 3825//3825 4001//4001 -f 4001//4001 3825//3825 3824//3824 -f 4001//4001 3824//3824 3823//3823 -f 3785//3785 3991//3991 3786//3786 -f 3786//3786 3991//3991 4002//4002 -f 4003//4003 4004//4004 4005//4005 -f 4004//4004 4006//4006 4007//4007 -f 4006//4006 4008//4008 4009//4009 -f 4006//4006 4009//4009 4007//4007 -f 4007//4007 4009//4009 4010//4010 -f 4007//4007 4010//4010 4011//4011 -f 4011//4011 4010//4010 4012//4012 -f 4011//4011 4012//4012 4013//4013 -f 4013//4013 4012//4012 3789//3789 -f 4013//4013 3789//3789 3788//3788 -f 4004//4004 4007//4007 4005//4005 -f 4005//4005 4007//4007 4011//4011 -f 4005//4005 4011//4011 4014//4014 -f 4014//4014 4011//4011 4013//4013 -f 4014//4014 4013//4013 4015//4015 -f 4015//4015 4013//4013 3788//3788 -f 4015//4015 3788//3788 3787//3787 -f 4003//4003 4005//4005 4016//4016 -f 4016//4016 4005//4005 4014//4014 -f 4016//4016 4014//4014 4017//4017 -f 4017//4017 4014//4014 4015//4015 -f 4017//4017 4015//4015 4018//4018 -f 4018//4018 4015//4015 3787//3787 -f 4018//4018 3787//3787 3786//3786 -f 3781//3781 3783//3783 4019//4019 -f 4020//4020 4021//4021 4022//4022 -f 4022//4022 4021//4021 4023//4023 -f 4022//4022 4023//4023 4024//4024 -f 4024//4024 4023//4023 4019//4019 -f 4024//4024 4019//4019 4025//4025 -f 4025//4025 4019//4019 3783//3783 -f 4025//4025 3783//3783 3784//3784 -f 3779//3779 3780//3780 4026//4026 -f 4026//4026 3780//3780 3781//3781 -f 3781//3781 4019//4019 4026//4026 -f 4026//4026 4019//4019 4023//4023 -f 4026//4026 4023//4023 4027//4027 -f 4027//4027 4023//4023 4021//4021 -f 4027//4027 4021//4021 4028//4028 -f 3777//3777 3778//3778 4029//4029 -f 4029//4029 3778//3778 3779//3779 -f 4020//4020 4030//4030 4021//4021 -f 4021//4021 4030//4030 4031//4031 -f 4021//4021 4031//4031 4028//4028 -f 4028//4028 4031//4031 4032//4032 -f 4028//4028 4032//4032 4033//4033 -f 3779//3779 4026//4026 4029//4029 -f 4029//4029 4026//4026 4027//4027 -f 4029//4029 4027//4027 4034//4034 -f 4034//4034 4027//4027 4028//4028 -f 4034//4034 4028//4028 4035//4035 -f 4035//4035 4028//4028 4033//4033 -f 4035//4035 4033//4033 4036//4036 -f 3777//3777 4029//4029 4037//4037 -f 4037//4037 4029//4029 4034//4034 -f 4037//4037 4034//4034 4038//4038 -f 4038//4038 4034//4034 4035//4035 -f 4038//4038 4035//4035 4039//4039 -f 4039//4039 4035//4035 4036//4036 -f 4039//4039 4036//4036 4040//4040 -f 3777//3777 4041//4041 3610//3610 -f 3610//3610 4041//4041 3611//3611 -f 4042//4042 204//204 202//202 -f 4041//4041 200//200 198//198 -f 4041//4041 198//198 3611//3611 -f 3611//3611 198//198 196//196 -f 3611//3611 196//196 3608//3608 -f 3608//3608 196//196 194//194 -f 3608//3608 194//194 3603//3603 -f 3603//3603 194//194 3604//3604 -f 3604//3604 194//194 192//192 -f 3604//3604 192//192 3615//3615 -f 200//200 4041//4041 202//202 -f 202//202 4041//4041 4043//4043 -f 202//202 4043//4043 4042//4042 -f 182//182 3619//3619 184//184 -f 184//184 3619//3619 3618//3618 -f 184//184 3618//3618 186//186 -f 186//186 3618//3618 3617//3617 -f 186//186 3617//3617 188//188 -f 188//188 3617//3617 3616//3616 -f 182//182 180//180 3619//3619 -f 3619//3619 180//180 3615//3615 -f 3619//3619 3615//3615 3620//3620 -f 3620//3620 3615//3615 192//192 -f 180//180 178//178 3615//3615 -f 3615//3615 178//178 3625//3625 -f 3615//3615 3625//3625 3627//3627 -f 3627//3627 3625//3625 3624//3624 -f 3616//3616 204//204 188//188 -f 188//188 204//204 4042//4042 -f 188//188 4042//4042 190//190 -f 190//190 4042//4042 4044//4044 -f 190//190 4044//4044 3621//3621 -f 3621//3621 4044//4044 4045//4045 -f 3621//3621 4045//4045 3622//3622 -f 3622//3622 4045//4045 4046//4046 -f 3622//3622 4046//4046 3623//3623 -f 3623//3623 4046//4046 3634//3634 -f 3623//3623 3634//3634 3624//3624 -f 3624//3624 3634//3634 3630//3630 -f 3624//3624 3630//3630 3627//3627 -f 3635//3635 3634//3634 3966//3966 -f 3966//3966 3634//3634 4046//4046 -f 4047//4047 4048//4048 4049//4049 -f 4048//4048 4050//4050 4051//4051 -f 4052//4052 3972//3972 3971//3971 -f 3971//3971 4053//4053 4052//4052 -f 4052//4052 4053//4053 4054//4054 -f 4052//4052 4054//4054 4055//4055 -f 4055//4055 4054//4054 4051//4051 -f 4055//4055 4051//4051 4056//4056 -f 4056//4056 4051//4051 4050//4050 -f 4056//4056 4050//4050 4057//4057 -f 4048//4048 4051//4051 4049//4049 -f 4049//4049 4051//4051 4054//4054 -f 4049//4049 4054//4054 4058//4058 -f 4058//4058 4054//4054 4053//4053 -f 4058//4058 4053//4053 4059//4059 -f 3971//3971 3970//3970 4053//4053 -f 4053//4053 3970//3970 3969//3969 -f 4053//4053 3969//3969 4059//4059 -f 4059//4059 3969//3969 3968//3968 -f 4059//4059 3968//3968 3967//3967 -f 4047//4047 4049//4049 4060//4060 -f 4060//4060 4049//4049 4058//4058 -f 4060//4060 4058//4058 4061//4061 -f 4061//4061 4058//4058 4059//4059 -f 4061//4061 4059//4059 4062//4062 -f 4062//4062 4059//4059 3967//3967 -f 4062//4062 3967//3967 3966//3966 -f 3963//3963 3964//3964 4063//4063 -f 4064//4064 4065//4065 4066//4066 -f 4066//4066 4065//4065 4067//4067 -f 4066//4066 4067//4067 4068//4068 -f 4068//4068 4067//4067 4063//4063 -f 4068//4068 4063//4063 4069//4069 -f 4069//4069 4063//4063 3964//3964 -f 4069//4069 3964//3964 3965//3965 -f 3961//3961 3962//3962 4070//4070 -f 4070//4070 3962//3962 3963//3963 -f 3963//3963 4063//4063 4070//4070 -f 4070//4070 4063//4063 4067//4067 -f 4070//4070 4067//4067 4071//4071 -f 4071//4071 4067//4067 4065//4065 -f 4071//4071 4065//4065 4072//4072 -f 3959//3959 3960//3960 4073//4073 -f 4073//4073 3960//3960 3961//3961 -f 4064//4064 4074//4074 4065//4065 -f 4065//4065 4074//4074 4075//4075 -f 4065//4065 4075//4075 4072//4072 -f 4072//4072 4075//4075 4076//4076 -f 4072//4072 4076//4076 4077//4077 -f 3961//3961 4070//4070 4073//4073 -f 4073//4073 4070//4070 4071//4071 -f 4073//4073 4071//4071 4078//4078 -f 4078//4078 4071//4071 4072//4072 -f 4078//4078 4072//4072 4079//4079 -f 4079//4079 4072//4072 4077//4077 -f 4079//4079 4077//4077 4080//4080 -f 3959//3959 4073//4073 4081//4081 -f 4081//4081 4073//4073 4078//4078 -f 4081//4081 4078//4078 4082//4082 -f 4082//4082 4078//4078 4079//4079 -f 4082//4082 4079//4079 4083//4083 -f 4083//4083 4079//4079 4080//4080 -f 4083//4083 4080//4080 4084//4084 -f 3959//3959 4085//4085 3648//3648 -f 3648//3648 4085//4085 3649//3649 -f 3639//3639 3638//3638 4086//4086 -f 4087//4087 3637//3637 3636//3636 -f 4088//4088 176//176 4089//4089 -f 4089//4089 176//176 174//174 -f 4089//4089 174//174 4090//4090 -f 4090//4090 174//174 4085//4085 -f 4088//4088 4091//4091 176//176 -f 176//176 4091//4091 4092//4092 -f 176//176 4092//4092 3636//3636 -f 3636//3636 4092//4092 4093//4093 -f 3636//3636 4093//4093 4087//4087 -f 4087//4087 4094//4094 3637//3637 -f 3637//3637 4094//4094 4095//4095 -f 3637//3637 4095//4095 3638//3638 -f 3638//3638 4095//4095 4096//4096 -f 3638//3638 4096//4096 4086//4086 -f 174//174 172//172 4085//4085 -f 4085//4085 172//172 170//170 -f 4085//4085 170//170 3649//3649 -f 3649//3649 170//170 168//168 -f 3649//3649 168//168 3647//3647 -f 3647//3647 168//168 166//166 -f 4086//4086 4097//4097 3639//3639 -f 3639//3639 4097//4097 4098//4098 -f 3639//3639 4098//4098 3640//3640 -f 3640//3640 4098//4098 4099//4099 -f 3640//3640 4099//4099 164//164 -f 164//164 4099//4099 3641//3641 -f 164//164 3641//3641 166//166 -f 166//166 3641//3641 3644//3644 -f 166//166 3644//3644 3647//3647 -f 3642//3642 3641//3641 3932//3932 -f 3932//3932 3641//3641 4099//4099 -f 4100//4100 4101//4101 4102//4102 -f 4102//4102 4101//4101 4103//4103 -f 4102//4102 4103//4103 4104//4104 -f 4104//4104 4103//4103 4105//4105 -f 4106//4106 4107//4107 4105//4105 -f 4105//4105 4107//4107 4108//4108 -f 4105//4105 4108//4108 4104//4104 -f 4109//4109 4110//4110 4106//4106 -f 4106//4106 4110//4110 4111//4111 -f 4106//4106 4111//4111 4107//4107 -f 4101//4101 4112//4112 4103//4103 -f 4103//4103 4112//4112 4113//4113 -f 4103//4103 4113//4113 4105//4105 -f 4105//4105 4113//4113 4114//4114 -f 4105//4105 4114//4114 4106//4106 -f 4106//4106 4114//4114 4115//4115 -f 4106//4106 4115//4115 4109//4109 -f 4109//4109 4115//4115 4116//4116 -f 4112//4112 4117//4117 4113//4113 -f 4113//4113 4117//4117 4118//4118 -f 4113//4113 4118//4118 4114//4114 -f 4114//4114 4118//4118 4119//4119 -f 4114//4114 4119//4119 4115//4115 -f 4115//4115 4119//4119 4120//4120 -f 4115//4115 4120//4120 4116//4116 -f 4116//4116 4120//4120 4121//4121 -f 4117//4117 3939//3939 4118//4118 -f 4118//4118 3939//3939 3937//3937 -f 4118//4118 3937//3937 4119//4119 -f 4119//4119 3937//3937 3935//3935 -f 4119//4119 3935//3935 4120//4120 -f 4120//4120 3935//3935 3933//3933 -f 4120//4120 3933//3933 4121//4121 -f 4121//4121 3933//3933 3932//3932 -f 3929//3929 3930//3930 4122//4122 -f 4123//4123 4124//4124 4125//4125 -f 4125//4125 4124//4124 4126//4126 -f 4125//4125 4126//4126 4127//4127 -f 4127//4127 4126//4126 4122//4122 -f 4127//4127 4122//4122 4128//4128 -f 4128//4128 4122//4122 3930//3930 -f 4128//4128 3930//3930 3931//3931 -f 3927//3927 3928//3928 4129//4129 -f 4129//4129 3928//3928 3929//3929 -f 3929//3929 4122//4122 4129//4129 -f 4129//4129 4122//4122 4126//4126 -f 4129//4129 4126//4126 4130//4130 -f 4130//4130 4126//4126 4124//4124 -f 4130//4130 4124//4124 4131//4131 -f 3925//3925 3926//3926 4132//4132 -f 4132//4132 3926//3926 3927//3927 -f 4123//4123 4133//4133 4124//4124 -f 4124//4124 4133//4133 4134//4134 -f 4124//4124 4134//4134 4131//4131 -f 4131//4131 4134//4134 4135//4135 -f 4131//4131 4135//4135 4136//4136 -f 3927//3927 4129//4129 4132//4132 -f 4132//4132 4129//4129 4130//4130 -f 4132//4132 4130//4130 4137//4137 -f 4137//4137 4130//4130 4131//4131 -f 4137//4137 4131//4131 4138//4138 -f 4138//4138 4131//4131 4136//4136 -f 4138//4138 4136//4136 4139//4139 -f 3925//3925 4132//4132 4140//4140 -f 4140//4140 4132//4132 4137//4137 -f 4140//4140 4137//4137 4141//4141 -f 4141//4141 4137//4137 4138//4138 -f 4141//4141 4138//4138 4142//4142 -f 4142//4142 4138//4138 4139//4139 -f 4142//4142 4139//4139 4143//4143 -f 3925//3925 4144//4144 3664//3664 -f 3664//3664 4144//4144 3665//3665 -f 152//152 150//150 4145//4145 -f 158//158 3663//3663 160//160 -f 160//160 3663//3663 3665//3665 -f 160//160 3665//3665 162//162 -f 162//162 3665//3665 4144//4144 -f 162//162 4144//4144 3652//3652 -f 3653//3653 4146//4146 3654//3654 -f 3654//3654 4146//4146 4147//4147 -f 3652//3652 4144//4144 3653//3653 -f 3653//3653 4144//4144 4148//4148 -f 3653//3653 4148//4148 4146//4146 -f 4149//4149 3656//3656 3655//3655 -f 4147//4147 4150//4150 3654//3654 -f 3654//3654 4150//4150 4151//4151 -f 3654//3654 4151//4151 3655//3655 -f 3655//3655 4151//4151 4152//4152 -f 3655//3655 4152//4152 4149//4149 -f 4145//4145 4153//4153 152//152 -f 152//152 4153//4153 4154//4154 -f 152//152 4154//4154 154//154 -f 154//154 4154//4154 4155//4155 -f 154//154 4155//4155 156//156 -f 156//156 4155//4155 3657//3657 -f 156//156 3657//3657 158//158 -f 158//158 3657//3657 3660//3660 -f 158//158 3660//3660 3663//3663 -f 4149//4149 4156//4156 3656//3656 -f 3656//3656 4156//4156 4157//4157 -f 3656//3656 4157//4157 150//150 -f 150//150 4157//4157 4158//4158 -f 150//150 4158//4158 4145//4145 -f 3658//3658 3657//3657 3897//3897 -f 3897//3897 3657//3657 4155//4155 -f 4159//4159 4160//4160 4161//4161 -f 3903//3903 4162//4162 4163//4163 -f 4163//4163 4162//4162 4164//4164 -f 4163//4163 4164//4164 4165//4165 -f 4165//4165 4164//4164 4161//4161 -f 4165//4165 4161//4161 4166//4166 -f 4166//4166 4161//4161 4160//4160 -f 4166//4166 4160//4160 4167//4167 -f 4168//4168 4169//4169 4170//4170 -f 4170//4170 4169//4169 4159//4159 -f 4159//4159 4161//4161 4170//4170 -f 4170//4170 4161//4161 4164//4164 -f 4170//4170 4164//4164 4171//4171 -f 4171//4171 4164//4164 4162//4162 -f 4171//4171 4162//4162 4172//4172 -f 4173//4173 4174//4174 4175//4175 -f 4175//4175 4174//4174 4168//4168 -f 3903//3903 3905//3905 4162//4162 -f 4162//4162 3905//3905 3906//3906 -f 4162//4162 3906//3906 4172//4172 -f 4172//4172 3906//3906 3901//3901 -f 4172//4172 3901//3901 3900//3900 -f 4168//4168 4170//4170 4175//4175 -f 4175//4175 4170//4170 4171//4171 -f 4175//4175 4171//4171 4176//4176 -f 4176//4176 4171//4171 4172//4172 -f 4176//4176 4172//4172 4177//4177 -f 4177//4177 4172//4172 3900//3900 -f 4177//4177 3900//3900 3898//3898 -f 4173//4173 4175//4175 4178//4178 -f 4178//4178 4175//4175 4176//4176 -f 4178//4178 4176//4176 4179//4179 -f 4179//4179 4176//4176 4177//4177 -f 4179//4179 4177//4177 4180//4180 -f 4180//4180 4177//4177 3898//3898 -f 4180//4180 3898//3898 3897//3897 -f 3893//3893 3894//3894 4181//4181 -f 3894//3894 3895//3895 4182//4182 -f 3895//3895 3896//3896 4183//4183 -f 3895//3895 4183//4183 4182//4182 -f 4182//4182 4183//4183 4184//4184 -f 4182//4182 4184//4184 4185//4185 -f 4185//4185 4184//4184 4186//4186 -f 4185//4185 4186//4186 4187//4187 -f 4187//4187 4186//4186 4188//4188 -f 4187//4187 4188//4188 4189//4189 -f 3894//3894 4182//4182 4181//4181 -f 4181//4181 4182//4182 4185//4185 -f 4181//4181 4185//4185 4190//4190 -f 4190//4190 4185//4185 4187//4187 -f 4190//4190 4187//4187 4191//4191 -f 4191//4191 4187//4187 4189//4189 -f 4191//4191 4189//4189 4192//4192 -f 3893//3893 4181//4181 4193//4193 -f 4193//4193 4181//4181 4190//4190 -f 4193//4193 4190//4190 4194//4194 -f 4194//4194 4190//4190 4191//4191 -f 4194//4194 4191//4191 4195//4195 -f 4195//4195 4191//4191 4192//4192 -f 4195//4195 4192//4192 4196//4196 -f 3893//3893 4197//4197 3668//3668 -f 3668//3668 4197//4197 3669//3669 -f 3678//3678 134//134 3681//3681 -f 3681//3681 134//134 132//132 -f 128//128 136//136 3686//3686 -f 3686//3686 3685//3685 128//128 -f 128//128 3685//3685 3684//3684 -f 128//128 3684//3684 130//130 -f 130//130 3684//3684 3683//3683 -f 130//130 3683//3683 132//132 -f 132//132 3683//3683 3682//3682 -f 132//132 3682//3682 3681//3681 -f 3682//3682 148//148 3681//3681 -f 3681//3681 148//148 146//146 -f 3681//3681 146//146 3697//3697 -f 3697//3697 146//146 144//144 -f 126//126 124//124 4198//4198 -f 4198//4198 124//124 122//122 -f 4198//4198 122//122 4199//4199 -f 4199//4199 122//122 3691//3691 -f 3669//3669 3689//3689 3688//3688 -f 128//128 126//126 136//136 -f 136//136 126//126 4198//4198 -f 136//136 4198//4198 138//138 -f 138//138 4198//4198 4200//4200 -f 138//138 4200//4200 140//140 -f 140//140 4200//4200 4201//4201 -f 140//140 4201//4201 142//142 -f 142//142 4201//4201 3692//3692 -f 142//142 3692//3692 144//144 -f 144//144 3692//3692 3695//3695 -f 144//144 3695//3695 3697//3697 -f 3689//3689 3669//3669 3690//3690 -f 3690//3690 3669//3669 4197//4197 -f 3690//3690 4197//4197 3691//3691 -f 3691//3691 4197//4197 4202//4202 -f 3691//3691 4202//4202 4199//4199 -f 3671//3671 3669//3669 3674//3674 -f 3674//3674 3669//3669 3688//3688 -f 3674//3674 3688//3688 3678//3678 -f 3678//3678 3688//3688 3687//3687 -f 3678//3678 3687//3687 134//134 -f 3693//3693 3692//3692 3850//3850 -f 3850//3850 3692//3692 4201//4201 -f 4203//4203 4204//4204 4205//4205 -f 4204//4204 4206//4206 4207//4207 -f 4206//4206 4208//4208 4209//4209 -f 4206//4206 4209//4209 4207//4207 -f 4207//4207 4209//4209 4210//4210 -f 4207//4207 4210//4210 4211//4211 -f 4211//4211 4210//4210 4212//4212 -f 4211//4211 4212//4212 4213//4213 -f 4213//4213 4212//4212 3855//3855 -f 4213//4213 3855//3855 3853//3853 -f 4204//4204 4207//4207 4205//4205 -f 4205//4205 4207//4207 4211//4211 -f 4205//4205 4211//4211 4214//4214 -f 4214//4214 4211//4211 4213//4213 -f 4214//4214 4213//4213 4215//4215 -f 4215//4215 4213//4213 3853//3853 -f 4215//4215 3853//3853 3851//3851 -f 4203//4203 4205//4205 4216//4216 -f 4216//4216 4205//4205 4214//4214 -f 4216//4216 4214//4214 4217//4217 -f 4217//4217 4214//4214 4215//4215 -f 4217//4217 4215//4215 4218//4218 -f 4218//4218 4215//4215 3851//3851 -f 4218//4218 3851//3851 3850//3850 -f 3846//3846 3847//3847 4219//4219 -f 3847//3847 3848//3848 4220//4220 -f 3848//3848 3849//3849 4221//4221 -f 3848//3848 4221//4221 4220//4220 -f 4220//4220 4221//4221 4222//4222 -f 4220//4220 4222//4222 4223//4223 -f 4223//4223 4222//4222 4224//4224 -f 4223//4223 4224//4224 4225//4225 -f 4225//4225 4224//4224 4226//4226 -f 4225//4225 4226//4226 4227//4227 -f 3847//3847 4220//4220 4219//4219 -f 4219//4219 4220//4220 4223//4223 -f 4219//4219 4223//4223 4228//4228 -f 4228//4228 4223//4223 4225//4225 -f 4228//4228 4225//4225 4229//4229 -f 4229//4229 4225//4225 4227//4227 -f 4229//4229 4227//4227 4230//4230 -f 3846//3846 4219//4219 4231//4231 -f 4231//4231 4219//4219 4228//4228 -f 4231//4231 4228//4228 4232//4232 -f 4232//4232 4228//4228 4229//4229 -f 4232//4232 4229//4229 4233//4233 -f 4233//4233 4229//4229 4230//4230 -f 4233//4233 4230//4230 4234//4234 -f 3846//3846 4235//4235 3823//3823 -f 3823//3823 4235//4235 4001//4001 -f 3833//3833 3998//3998 3973//3973 -f 3973//3973 3998//3998 4236//4236 -f 3706//3706 106//106 4100//4100 -f 4055//4055 4056//4056 4057//4057 -f 3921//3921 3922//3922 4237//4237 -f 4165//4165 4166//4166 4167//4167 -f 4238//4238 4239//4239 3983//3983 -f 3753//3753 3754//3754 4240//4240 -f 3728//3728 3727//3727 4241//4241 -f 3728//3728 4241//4241 46//46 -f 4242//4242 50//50 48//48 -f 4243//4243 52//52 3891//3891 -f 3891//3891 52//52 50//50 -f 3891//3891 50//50 3890//3890 -f 3890//3890 50//50 4242//4242 -f 3890//3890 4242//4242 3889//3889 -f 4240//4240 56//56 4243//4243 -f 4243//4243 56//56 54//54 -f 4243//4243 54//54 52//52 -f 3755//3755 4244//4244 3754//3754 -f 3754//3754 4244//4244 60//60 -f 3754//3754 60//60 4240//4240 -f 4240//4240 60//60 58//58 -f 4240//4240 58//58 56//56 -f 3722//3722 3721//3721 4245//4245 -f 4245//4245 3721//3721 64//64 -f 4245//4245 64//64 4244//4244 -f 4244//4244 64//64 62//62 -f 4244//4244 62//62 60//60 -f 3725//3725 3724//3724 4246//4246 -f 3733//3733 3871//3871 3734//3734 -f 3734//3734 3871//3871 3872//3872 -f 3734//3734 3872//3872 30//30 -f 4247//4247 40//40 38//38 -f 4247//4247 38//38 4248//4248 -f 38//38 36//36 4248//4248 -f 4248//4248 36//36 34//34 -f 4248//4248 34//34 4249//4249 -f 4249//4249 34//34 32//32 -f 4249//4249 32//32 30//30 -f 40//40 4247//4247 42//42 -f 42//42 4247//4247 4250//4250 -f 42//42 4250//4250 44//44 -f 3730//3730 3729//3729 3774//3774 -f 4251//4251 3733//3733 3732//3732 -f 4251//4251 3732//3732 4252//4252 -f 4252//4252 3732//3732 3731//3731 -f 4252//4252 3731//3731 3730//3730 -f 3774//3774 3775//3775 3730//3730 -f 3730//3730 3775//3775 3776//3776 -f 3730//3730 3776//3776 4252//4252 -f 4252//4252 3776//3776 3758//3758 -f 4252//4252 3758//3758 4240//4240 -f 4240//4240 3758//3758 3738//3738 -f 4240//4240 3738//3738 3753//3753 -f 3729//3729 44//44 3774//3774 -f 3774//3774 44//44 4250//4250 -f 3774//3774 4250//4250 3773//3773 -f 3773//3773 4250//4250 3772//3772 -f 4024//4024 4025//4025 4022//4022 -f 4022//4022 4025//4025 3784//3784 -f 4022//4022 3784//3784 4020//4020 -f 4020//4020 3784//3784 4008//4008 -f 4012//4012 4010//4010 3789//3789 -f 3789//3789 4010//4010 4009//4009 -f 3813//3813 3814//3814 4247//4247 -f 4247//4247 3814//3814 3815//3815 -f 4247//4247 3815//3815 4250//4250 -f 4250//4250 3815//3815 3816//3816 -f 4250//4250 3816//3816 3772//3772 -f 3772//3772 3816//3816 3817//3817 -f 3772//3772 3817//3817 3759//3759 -f 3759//3759 3817//3817 3793//3793 -f 3759//3759 3793//3793 3782//3782 -f 3782//3782 3793//3793 3790//3790 -f 3782//3782 3790//3790 3784//3784 -f 3784//3784 3790//3790 3789//3789 -f 3784//3784 3789//3789 4008//4008 -f 4008//4008 3789//3789 4009//4009 -f 4253//4253 4238//4238 4254//4254 -f 4254//4254 4238//4238 3983//3983 -f 4254//4254 3983//3983 4247//4247 -f 4247//4247 3983//3983 3794//3794 -f 4247//4247 3794//3794 3813//3813 -f 4255//4255 4256//4256 4257//4257 -f 3843//3843 4248//4248 3842//3842 -f 3842//3842 4248//4248 4249//4249 -f 3842//3842 4249//4249 3841//3841 -f 3841//3841 4249//4249 3874//3874 -f 3843//3843 3844//3844 4248//4248 -f 4248//4248 3844//3844 3845//3845 -f 4248//4248 3845//3845 4257//4257 -f 4257//4257 3845//3845 3977//3977 -f 4257//4257 3977//3977 4255//4255 -f 30//30 3872//3872 4249//4249 -f 4249//4249 3872//3872 3873//3873 -f 4249//4249 3873//3873 3874//3874 -f 3855//3855 3849//3849 3856//3856 -f 3856//3856 3849//3849 3818//3818 -f 3856//3856 3818//3818 3874//3874 -f 3874//3874 3818//3818 3840//3840 -f 3874//3874 3840//3840 3841//3841 -f 4210//4210 4209//4209 4208//4208 -f 4226//4226 4224//4224 4222//4222 -f 4212//4212 4210//4210 3855//3855 -f 3855//3855 4210//4210 4208//4208 -f 3855//3855 4208//4208 3849//3849 -f 3849//3849 4208//4208 4226//4226 -f 3849//3849 4226//4226 4221//4221 -f 4221//4221 4226//4226 4222//4222 -f 3891//3891 3892//3892 4243//4243 -f 4243//4243 3892//3892 3877//3877 -f 4243//4243 3877//3877 4251//4251 -f 4251//4251 3877//3877 3857//3857 -f 4251//4251 3857//3857 3733//3733 -f 3733//3733 3857//3857 3870//3870 -f 3733//3733 3870//3870 3871//3871 -f 4188//4188 3896//3896 4242//4242 -f 4242//4242 3896//3896 3878//3878 -f 4242//4242 3878//3878 3889//3889 -f 4188//4188 4186//4186 3896//3896 -f 3896//3896 4186//4186 4184//4184 -f 3896//3896 4184//4184 4183//4183 -f 3726//3726 4237//4237 3727//3727 -f 3727//3727 4237//4237 3922//3922 -f 3727//3727 3922//3922 4241//4241 -f 4241//4241 3922//3922 3923//3923 -f 4163//4163 4165//4165 3903//3903 -f 3903//3903 4165//4165 4167//4167 -f 3903//3903 4167//4167 3904//3904 -f 3904//3904 4167//4167 4241//4241 -f 3904//3904 4241//4241 3924//3924 -f 3924//3924 4241//4241 3923//3923 -f 3931//3931 3907//3907 4237//4237 -f 4237//4237 3907//3907 3920//3920 -f 4237//4237 3920//3920 3921//3921 -f 4127//4127 4128//4128 4125//4125 -f 4125//4125 4128//4128 3931//3931 -f 4125//4125 3931//3931 4123//4123 -f 4123//4123 3931//3931 4237//4237 -f 3724//3724 3723//3723 4246//4246 -f 4246//4246 3723//3723 3956//3956 -f 4246//4246 3956//3956 3957//3957 -f 3939//3939 4117//4117 4112//4112 -f 3957//3957 3958//3958 4246//4246 -f 4246//4246 3958//3958 3940//3940 -f 4246//4246 3940//3940 4100//4100 -f 4100//4100 3940//3940 3939//3939 -f 4100//4100 3939//3939 4101//4101 -f 4101//4101 3939//3939 4112//4112 -f 3723//3723 3722//3722 3956//3956 -f 3956//3956 3722//3722 4245//4245 -f 3956//3956 4245//4245 3955//3955 -f 3955//3955 4245//4245 3954//3954 -f 4258//4258 4066//4066 4068//4068 -f 4068//4068 4069//4069 4258//4258 -f 4258//4258 4069//4069 3965//3965 -f 4258//4258 3965//3965 4245//4245 -f 4245//4245 3965//3965 3942//3942 -f 4245//4245 3942//3942 3954//3954 -f 3755//3755 3737//3737 4244//4244 -f 4244//4244 3737//3737 3736//3736 -f 4244//4244 3736//3736 4259//4259 -f 4259//4259 3736//3736 3972//3972 -f 4259//4259 3972//3972 4052//4052 -f 3701//3701 120//120 4241//4241 -f 4241//4241 120//120 4242//4242 -f 4241//4241 4242//4242 46//46 -f 46//46 4242//4242 48//48 -f 120//120 118//118 4242//4242 -f 4242//4242 118//118 116//116 -f 4242//4242 116//116 4188//4188 -f 4188//4188 116//116 114//114 -f 4188//4188 114//114 112//112 -f 3705//3705 4167//4167 108//108 -f 108//108 4167//4167 4188//4188 -f 108//108 4188//4188 110//110 -f 110//110 4188//4188 112//112 -f 3705//3705 3704//3704 4167//4167 -f 4167//4167 3704//3704 3703//3703 -f 4167//4167 3703//3703 4241//4241 -f 4241//4241 3703//3703 3702//3702 -f 4241//4241 3702//3702 3701//3701 -f 4100//4100 106//106 4246//4246 -f 4246//4246 106//106 104//104 -f 4246//4246 104//104 102//102 -f 3710//3710 3709//3709 4123//4123 -f 4123//4123 3709//3709 3708//3708 -f 4123//4123 3708//3708 4100//4100 -f 4100//4100 3708//3708 3707//3707 -f 4100//4100 3707//3707 3706//3706 -f 3726//3726 3725//3725 4237//4237 -f 4237//4237 3725//3725 4246//4246 -f 4237//4237 4246//4246 100//100 -f 100//100 4246//4246 102//102 -f 100//100 98//98 4237//4237 -f 4237//4237 98//98 96//96 -f 4237//4237 96//96 4123//4123 -f 4123//4123 96//96 94//94 -f 4123//4123 94//94 3710//3710 -f 76//76 4252//4252 78//78 -f 78//78 4252//4252 4240//4240 -f 78//78 4240//4240 3716//3716 -f 3716//3716 4240//4240 3717//3717 -f 76//76 74//74 4252//4252 -f 4252//4252 74//74 72//72 -f 4252//4252 72//72 4251//4251 -f 4251//4251 72//72 70//70 -f 3717//3717 4240//4240 3718//3718 -f 3718//3718 4240//4240 4243//4243 -f 3718//3718 4243//4243 3719//3719 -f 70//70 68//68 4251//4251 -f 4251//4251 68//68 66//66 -f 4251//4251 66//66 4243//4243 -f 4243//4243 66//66 3720//3720 -f 4243//4243 3720//3720 3719//3719 -f 4257//4257 4260//4260 4248//4248 -f 4248//4248 4260//4260 4261//4261 -f 4248//4248 4261//4261 4247//4247 -f 4247//4247 4261//4261 4262//4262 -f 4247//4247 4262//4262 4254//4254 -f 4254//4254 4262//4262 4263//4263 -f 4254//4254 4263//4263 4257//4257 -f 4257//4257 4263//4263 4260//4260 -f 4253//4253 4254//4254 4264//4264 -f 4264//4264 4254//4254 4257//4257 -f 4264//4264 4257//4257 4265//4265 -f 4265//4265 4257//4257 4256//4256 -f 4265//4265 4256//4256 4266//4266 -f 3715//3715 4245//4245 80//80 -f 80//80 4245//4245 4244//4244 -f 80//80 4244//4244 82//82 -f 82//82 4244//4244 84//84 -f 3715//3715 3714//3714 4245//4245 -f 4245//4245 3714//3714 3713//3713 -f 4245//4245 3713//3713 4258//4258 -f 4258//4258 3713//3713 3712//3712 -f 3712//3712 3711//3711 4258//4258 -f 4258//4258 3711//3711 92//92 -f 4258//4258 92//92 4259//4259 -f 92//92 90//90 4259//4259 -f 4259//4259 90//90 88//88 -f 4259//4259 88//88 4244//4244 -f 4244//4244 88//88 86//86 -f 4244//4244 86//86 84//84 -f 4052//4052 4055//4055 4259//4259 -f 4259//4259 4055//4055 4057//4057 -f 4259//4259 4057//4057 4258//4258 -f 4258//4258 4057//4057 4064//4064 -f 4258//4258 4064//4064 4066//4066 -f 4267//4267 4268//4268 4269//4269 -f 3977//3977 4270//4270 4255//4255 -f 4255//4255 4270//4270 4271//4271 -f 4255//4255 4271//4271 4256//4256 -f 4256//4256 4271//4271 4269//4269 -f 4256//4256 4269//4269 4266//4266 -f 4266//4266 4269//4269 4268//4268 -f 4266//4266 4268//4268 4265//4265 -f 4272//4272 4273//4273 4274//4274 -f 4274//4274 4273//4273 4267//4267 -f 4267//4267 4269//4269 4274//4274 -f 4274//4274 4269//4269 4271//4271 -f 4274//4274 4271//4271 4275//4275 -f 4275//4275 4271//4271 4270//4270 -f 4275//4275 4270//4270 4276//4276 -f 4277//4277 4278//4278 4279//4279 -f 4279//4279 4278//4278 4272//4272 -f 3977//3977 3978//3978 4270//4270 -f 4270//4270 3978//3978 3979//3979 -f 4270//4270 3979//3979 4276//4276 -f 4276//4276 3979//3979 3976//3976 -f 4276//4276 3976//3976 3975//3975 -f 4272//4272 4274//4274 4279//4279 -f 4279//4279 4274//4274 4275//4275 -f 4279//4279 4275//4275 4280//4280 -f 4280//4280 4275//4275 4276//4276 -f 4280//4280 4276//4276 4281//4281 -f 4281//4281 4276//4276 3975//3975 -f 4281//4281 3975//3975 3974//3974 -f 4277//4277 4279//4279 4282//4282 -f 4282//4282 4279//4279 4280//4280 -f 4282//4282 4280//4280 4283//4283 -f 4283//4283 4280//4280 4281//4281 -f 4283//4283 4281//4281 4284//4284 -f 4284//4284 4281//4281 3974//3974 -f 4284//4284 3974//3974 3973//3973 -f 3980//3980 3981//3981 4285//4285 -f 3981//3981 3982//3982 4286//4286 -f 3982//3982 3983//3983 4239//4239 -f 3982//3982 4239//4239 4286//4286 -f 4286//4286 4239//4239 4238//4238 -f 4286//4286 4238//4238 4287//4287 -f 4287//4287 4238//4238 4253//4253 -f 4287//4287 4253//4253 4288//4288 -f 4288//4288 4253//4253 4264//4264 -f 4288//4288 4264//4264 4289//4289 -f 3981//3981 4286//4286 4285//4285 -f 4285//4285 4286//4286 4287//4287 -f 4285//4285 4287//4287 4290//4290 -f 4290//4290 4287//4287 4288//4288 -f 4290//4290 4288//4288 4291//4291 -f 4291//4291 4288//4288 4289//4289 -f 4291//4291 4289//4289 4292//4292 -f 3980//3980 4285//4285 4293//4293 -f 4293//4293 4285//4285 4290//4290 -f 4293//4293 4290//4290 4294//4294 -f 4294//4294 4290//4290 4291//4291 -f 4294//4294 4291//4291 4295//4295 -f 4295//4295 4291//4291 4292//4292 -f 4295//4295 4292//4292 4296//4296 -f 3980//3980 4297//4297 3799//3799 -f 3799//3799 4297//4297 3992//3992 -f 3984//3984 28//28 4298//4298 -f 24//24 4299//4299 4300//4300 -f 20//20 18//18 4297//4297 -f 4297//4297 18//18 3992//3992 -f 24//24 4300//4300 26//26 -f 22//22 4301//4301 24//24 -f 24//24 4301//4301 4302//4302 -f 24//24 4302//4302 4299//4299 -f 4297//4297 4303//4303 20//20 -f 20//20 4303//4303 4304//4304 -f 20//20 4304//4304 22//22 -f 22//22 4304//4304 4305//4305 -f 22//22 4305//4305 4301//4301 -f 18//18 16//16 3992//3992 -f 3992//3992 16//16 3988//3988 -f 3992//3992 3988//3988 3989//3989 -f 3989//3989 3988//3988 3987//3987 -f 4298//4298 4306//4306 3984//3984 -f 3984//3984 4306//4306 4307//4307 -f 3984//3984 4307//4307 3985//3985 -f 3985//3985 4307//4307 4002//4002 -f 3985//3985 4002//4002 3986//3986 -f 3986//3986 4002//4002 3991//3991 -f 3986//3986 3991//3991 3987//3987 -f 3987//3987 3991//3991 3990//3990 -f 3987//3987 3990//3990 3989//3989 -f 4300//4300 4308//4308 26//26 -f 26//26 4308//4308 4309//4309 -f 26//26 4309//4309 28//28 -f 28//28 4309//4309 4310//4310 -f 28//28 4310//4310 4298//4298 -f 10//10 8//8 4311//4311 -f 4312//4312 4313//4313 4//4 -f 4//4 4313//4313 6//6 -f 3998//3998 14//14 4236//4236 -f 4236//4236 14//14 12//12 -f 4236//4236 12//12 4314//4314 -f 4314//4314 12//12 10//10 -f 4314//4314 10//10 4315//4315 -f 4315//4315 10//10 4311//4311 -f 4001//4001 3995//3995 3994//3994 -f 4313//4313 4316//4316 6//6 -f 6//6 4316//4316 4317//4317 -f 6//6 4317//4317 8//8 -f 8//8 4317//4317 4318//4318 -f 8//8 4318//4318 4311//4311 -f 4312//4312 4//4 4319//4319 -f 4319//4319 4//4 2//2 -f 4319//4319 2//2 4320//4320 -f 3997//3997 4321//4321 2//2 -f 2//2 4321//4321 4322//4322 -f 2//2 4322//4322 4320//4320 -f 3995//3995 4001//4001 3996//3996 -f 3996//3996 4001//4001 4235//4235 -f 3996//3996 4235//4235 3997//3997 -f 3997//3997 4235//4235 4323//4323 -f 3997//3997 4323//4323 4321//4321 -f 4000//4000 4001//4001 3999//3999 -f 3999//3999 4001//4001 3994//3994 -f 3999//3999 3994//3994 3998//3998 -f 3998//3998 3994//3994 3993//3993 -f 3998//3998 3993//3993 14//14 -f 4324//4324 4325//4325 4326//4326 -f 4326//4326 4325//4325 4327//4327 -f 4306//4306 4298//4298 4328//4328 -f 4328//4328 4298//4298 4329//4329 -f 4328//4328 4329//4329 4330//4330 -f 4327//4327 4331//4331 4326//4326 -f 4326//4326 4331//4331 4332//4332 -f 4326//4326 4332//4332 4330//4330 -f 4330//4330 4332//4332 4333//4333 -f 4330//4330 4333//4333 4328//4328 -f 4327//4327 4325//4325 4003//4003 -f 4306//4306 4328//4328 4016//4016 -f 4328//4328 4333//4333 4016//4016 -f 4016//4016 4333//4333 4332//4332 -f 4016//4016 4332//4332 4003//4003 -f 4003//4003 4332//4332 4331//4331 -f 4003//4003 4331//4331 4327//4327 -f 4016//4016 4017//4017 4306//4306 -f 4306//4306 4017//4017 4018//4018 -f 4306//4306 4018//4018 4307//4307 -f 4307//4307 4018//4018 3786//3786 -f 4307//4307 3786//3786 4002//4002 -f 4020//4020 4008//4008 4030//4030 -f 4030//4030 4008//4008 4006//4006 -f 4030//4030 4006//4006 4031//4031 -f 4031//4031 4006//4006 4032//4032 -f 4032//4032 4006//4006 4004//4004 -f 4032//4032 4004//4004 4033//4033 -f 4033//4033 4004//4004 4036//4036 -f 4036//4036 4004//4004 4003//4003 -f 4036//4036 4003//4003 4040//4040 -f 4041//4041 3777//3777 4037//4037 -f 4041//4041 4037//4037 4043//4043 -f 4043//4043 4037//4037 4038//4038 -f 4043//4043 4038//4038 4042//4042 -f 4042//4042 4038//4038 4334//4334 -f 4334//4334 4038//4038 4039//4039 -f 4334//4334 4039//4039 4335//4335 -f 4335//4335 4039//4039 4336//4336 -f 4336//4336 4039//4039 4040//4040 -f 4336//4336 4040//4040 4337//4337 -f 4338//4338 4044//4044 4042//4042 -f 4042//4042 4334//4334 4338//4338 -f 4338//4338 4334//4334 4335//4335 -f 4338//4338 4335//4335 4339//4339 -f 4339//4339 4335//4335 4336//4336 -f 4339//4339 4336//4336 4340//4340 -f 4337//4337 4341//4341 4336//4336 -f 4336//4336 4341//4341 4342//4342 -f 4336//4336 4342//4342 4340//4340 -f 4342//4342 4341//4341 4047//4047 -f 4044//4044 4338//4338 4060//4060 -f 4060//4060 4338//4338 4339//4339 -f 4060//4060 4339//4339 4047//4047 -f 4047//4047 4339//4339 4340//4340 -f 4047//4047 4340//4340 4342//4342 -f 4060//4060 4061//4061 4044//4044 -f 4044//4044 4061//4061 4062//4062 -f 4044//4044 4062//4062 4045//4045 -f 4045//4045 4062//4062 3966//3966 -f 4045//4045 3966//3966 4046//4046 -f 4064//4064 4057//4057 4074//4074 -f 4074//4074 4057//4057 4050//4050 -f 4074//4074 4050//4050 4075//4075 -f 4075//4075 4050//4050 4076//4076 -f 4076//4076 4050//4050 4048//4048 -f 4076//4076 4048//4048 4077//4077 -f 4077//4077 4048//4048 4080//4080 -f 4080//4080 4048//4048 4047//4047 -f 4080//4080 4047//4047 4084//4084 -f 4082//4082 4090//4090 4081//4081 -f 4081//4081 4090//4090 4085//4085 -f 4081//4081 4085//4085 3959//3959 -f 4343//4343 4344//4344 4083//4083 -f 4083//4083 4344//4344 4345//4345 -f 4083//4083 4345//4345 4082//4082 -f 4082//4082 4345//4345 4089//4089 -f 4082//4082 4089//4089 4090//4090 -f 4343//4343 4083//4083 4346//4346 -f 4346//4346 4083//4083 4084//4084 -f 4346//4346 4084//4084 4347//4347 -f 4348//4348 4088//4088 4089//4089 -f 4347//4347 4349//4349 4346//4346 -f 4346//4346 4349//4349 4350//4350 -f 4346//4346 4350//4350 4343//4343 -f 4343//4343 4350//4350 4344//4344 -f 4089//4089 4345//4345 4348//4348 -f 4348//4348 4345//4345 4344//4344 -f 4348//4348 4344//4344 4351//4351 -f 4351//4351 4344//4344 4350//4350 -f 4330//4330 4329//4329 4352//4352 -f 4329//4329 4298//4298 4310//4310 -f 4324//4324 4326//4326 4353//4353 -f 4353//4353 4326//4326 4330//4330 -f 4329//4329 4310//4310 4352//4352 -f 4352//4352 4310//4310 4309//4309 -f 4352//4352 4309//4309 4354//4354 -f 4354//4354 4309//4309 4308//4308 -f 4354//4354 4308//4308 4355//4355 -f 4355//4355 4308//4308 4300//4300 -f 4355//4355 4300//4300 4356//4356 -f 4356//4356 4300//4300 4299//4299 -f 4356//4356 4299//4299 4357//4357 -f 4357//4357 4299//4299 4302//4302 -f 4357//4357 4302//4302 4358//4358 -f 4358//4358 4302//4302 4301//4301 -f 4358//4358 4301//4301 4359//4359 -f 4301//4301 4305//4305 4359//4359 -f 4359//4359 4305//4305 4360//4360 -f 4359//4359 4360//4360 4361//4361 -f 4330//4330 4352//4352 4353//4353 -f 4353//4353 4352//4352 4354//4354 -f 4353//4353 4354//4354 4362//4362 -f 4362//4362 4354//4354 4355//4355 -f 4362//4362 4355//4355 4363//4363 -f 4363//4363 4355//4355 4356//4356 -f 4363//4363 4356//4356 4364//4364 -f 4364//4364 4356//4356 4357//4357 -f 4364//4364 4357//4357 4365//4365 -f 4365//4365 4357//4357 4358//4358 -f 4365//4365 4358//4358 4366//4366 -f 4366//4366 4358//4358 4359//4359 -f 4366//4366 4359//4359 4367//4367 -f 4367//4367 4359//4359 4361//4361 -f 4367//4367 4361//4361 4368//4368 -f 4324//4324 4353//4353 4369//4369 -f 4369//4369 4353//4353 4362//4362 -f 4369//4369 4362//4362 4370//4370 -f 4370//4370 4362//4362 4363//4363 -f 4370//4370 4363//4363 4371//4371 -f 4371//4371 4363//4363 4364//4364 -f 4371//4371 4364//4364 4372//4372 -f 4372//4372 4364//4364 4365//4365 -f 4372//4372 4365//4365 4373//4373 -f 4373//4373 4365//4365 4366//4366 -f 4373//4373 4366//4366 4374//4374 -f 4374//4374 4366//4366 4367//4367 -f 4374//4374 4367//4367 4375//4375 -f 4375//4375 4367//4367 4368//4368 -f 4375//4375 4368//4368 4376//4376 -f 4377//4377 4378//4378 4379//4379 -f 4378//4378 4086//4086 4096//4096 -f 4380//4380 4381//4381 4382//4382 -f 4382//4382 4381//4381 4377//4377 -f 4378//4378 4096//4096 4379//4379 -f 4379//4379 4096//4096 4095//4095 -f 4379//4379 4095//4095 4383//4383 -f 4383//4383 4095//4095 4094//4094 -f 4383//4383 4094//4094 4384//4384 -f 4384//4384 4094//4094 4087//4087 -f 4384//4384 4087//4087 4385//4385 -f 4385//4385 4087//4087 4093//4093 -f 4385//4385 4093//4093 4386//4386 -f 4386//4386 4093//4093 4092//4092 -f 4386//4386 4092//4092 4387//4387 -f 4387//4387 4092//4092 4091//4091 -f 4387//4387 4091//4091 4388//4388 -f 4091//4091 4088//4088 4388//4388 -f 4388//4388 4088//4088 4348//4348 -f 4388//4388 4348//4348 4351//4351 -f 4377//4377 4379//4379 4382//4382 -f 4382//4382 4379//4379 4383//4383 -f 4382//4382 4383//4383 4389//4389 -f 4389//4389 4383//4383 4384//4384 -f 4389//4389 4384//4384 4390//4390 -f 4390//4390 4384//4384 4385//4385 -f 4390//4390 4385//4385 4391//4391 -f 4391//4391 4385//4385 4386//4386 -f 4391//4391 4386//4386 4392//4392 -f 4392//4392 4386//4386 4387//4387 -f 4392//4392 4387//4387 4393//4393 -f 4393//4393 4387//4387 4388//4388 -f 4393//4393 4388//4388 4394//4394 -f 4394//4394 4388//4388 4351//4351 -f 4394//4394 4351//4351 4350//4350 -f 4380//4380 4382//4382 4395//4395 -f 4395//4395 4382//4382 4389//4389 -f 4395//4395 4389//4389 4396//4396 -f 4396//4396 4389//4389 4390//4390 -f 4396//4396 4390//4390 4397//4397 -f 4397//4397 4390//4390 4391//4391 -f 4397//4397 4391//4391 4398//4398 -f 4398//4398 4391//4391 4392//4392 -f 4398//4398 4392//4392 4399//4399 -f 4399//4399 4392//4392 4393//4393 -f 4399//4399 4393//4393 4400//4400 -f 4400//4400 4393//4393 4394//4394 -f 4400//4400 4394//4394 4401//4401 -f 4401//4401 4394//4394 4350//4350 -f 4401//4401 4350//4350 4349//4349 -f 4402//4402 4097//4097 4086//4086 -f 4086//4086 4378//4378 4402//4402 -f 4402//4402 4378//4378 4377//4377 -f 4402//4402 4377//4377 4403//4403 -f 4403//4403 4377//4377 4381//4381 -f 4403//4403 4381//4381 4404//4404 -f 4380//4380 4405//4405 4381//4381 -f 4381//4381 4405//4405 4406//4406 -f 4381//4381 4406//4406 4404//4404 -f 4406//4406 4405//4405 4110//4110 -f 4097//4097 4402//4402 4109//4109 -f 4109//4109 4402//4402 4403//4403 -f 4109//4109 4403//4403 4110//4110 -f 4110//4110 4403//4403 4404//4404 -f 4110//4110 4404//4404 4406//4406 -f 4109//4109 4116//4116 4097//4097 -f 4097//4097 4116//4116 4121//4121 -f 4097//4097 4121//4121 4098//4098 -f 4098//4098 4121//4121 3932//3932 -f 4098//4098 3932//3932 4099//4099 -f 4123//4123 4100//4100 4133//4133 -f 4133//4133 4100//4100 4102//4102 -f 4133//4133 4102//4102 4134//4134 -f 4134//4134 4102//4102 4104//4104 -f 4134//4134 4104//4104 4135//4135 -f 4135//4135 4104//4104 4108//4108 -f 4135//4135 4108//4108 4136//4136 -f 4136//4136 4108//4108 4107//4107 -f 4136//4136 4107//4107 4139//4139 -f 4139//4139 4107//4107 4111//4111 -f 4139//4139 4111//4111 4143//4143 -f 4143//4143 4111//4111 4110//4110 -f 4141//4141 4148//4148 4140//4140 -f 4140//4140 4148//4148 4144//4144 -f 4140//4140 4144//4144 3925//3925 -f 4407//4407 4408//4408 4142//4142 -f 4142//4142 4408//4408 4409//4409 -f 4142//4142 4409//4409 4141//4141 -f 4141//4141 4409//4409 4146//4146 -f 4141//4141 4146//4146 4148//4148 -f 4407//4407 4142//4142 4410//4410 -f 4410//4410 4142//4142 4143//4143 -f 4410//4410 4143//4143 4411//4411 -f 4412//4412 4147//4147 4146//4146 -f 4411//4411 4413//4413 4410//4410 -f 4410//4410 4413//4413 4414//4414 -f 4410//4410 4414//4414 4407//4407 -f 4407//4407 4414//4414 4408//4408 -f 4146//4146 4409//4409 4412//4412 -f 4412//4412 4409//4409 4408//4408 -f 4412//4412 4408//4408 4415//4415 -f 4415//4415 4408//4408 4414//4414 -f 4416//4416 4417//4417 4418//4418 -f 4417//4417 4145//4145 4158//4158 -f 4419//4419 4420//4420 4421//4421 -f 4421//4421 4420//4420 4416//4416 -f 4417//4417 4158//4158 4418//4418 -f 4418//4418 4158//4158 4157//4157 -f 4418//4418 4157//4157 4422//4422 -f 4422//4422 4157//4157 4156//4156 -f 4422//4422 4156//4156 4423//4423 -f 4423//4423 4156//4156 4149//4149 -f 4423//4423 4149//4149 4424//4424 -f 4424//4424 4149//4149 4152//4152 -f 4424//4424 4152//4152 4425//4425 -f 4425//4425 4152//4152 4151//4151 -f 4425//4425 4151//4151 4426//4426 -f 4426//4426 4151//4151 4150//4150 -f 4426//4426 4150//4150 4427//4427 -f 4150//4150 4147//4147 4427//4427 -f 4427//4427 4147//4147 4412//4412 -f 4427//4427 4412//4412 4415//4415 -f 4416//4416 4418//4418 4421//4421 -f 4421//4421 4418//4418 4422//4422 -f 4421//4421 4422//4422 4428//4428 -f 4428//4428 4422//4422 4423//4423 -f 4428//4428 4423//4423 4429//4429 -f 4429//4429 4423//4423 4424//4424 -f 4429//4429 4424//4424 4430//4430 -f 4430//4430 4424//4424 4425//4425 -f 4430//4430 4425//4425 4431//4431 -f 4431//4431 4425//4425 4426//4426 -f 4431//4431 4426//4426 4432//4432 -f 4432//4432 4426//4426 4427//4427 -f 4432//4432 4427//4427 4433//4433 -f 4433//4433 4427//4427 4415//4415 -f 4433//4433 4415//4415 4414//4414 -f 4419//4419 4421//4421 4434//4434 -f 4434//4434 4421//4421 4428//4428 -f 4434//4434 4428//4428 4435//4435 -f 4435//4435 4428//4428 4429//4429 -f 4435//4435 4429//4429 4436//4436 -f 4436//4436 4429//4429 4430//4430 -f 4436//4436 4430//4430 4437//4437 -f 4437//4437 4430//4430 4431//4431 -f 4437//4437 4431//4431 4438//4438 -f 4438//4438 4431//4431 4432//4432 -f 4438//4438 4432//4432 4439//4439 -f 4439//4439 4432//4432 4433//4433 -f 4439//4439 4433//4433 4440//4440 -f 4440//4440 4433//4433 4414//4414 -f 4440//4440 4414//4414 4413//4413 -f 4419//4419 4441//4441 4420//4420 -f 4420//4420 4441//4441 4442//4442 -f 4153//4153 4145//4145 4443//4443 -f 4443//4443 4145//4145 4417//4417 -f 4443//4443 4417//4417 4416//4416 -f 4442//4442 4444//4444 4420//4420 -f 4420//4420 4444//4444 4445//4445 -f 4420//4420 4445//4445 4416//4416 -f 4416//4416 4445//4445 4446//4446 -f 4416//4416 4446//4446 4443//4443 -f 4442//4442 4441//4441 4173//4173 -f 4153//4153 4443//4443 4178//4178 -f 4443//4443 4446//4446 4178//4178 -f 4178//4178 4446//4446 4445//4445 -f 4178//4178 4445//4445 4173//4173 -f 4173//4173 4445//4445 4444//4444 -f 4173//4173 4444//4444 4442//4442 -f 4178//4178 4179//4179 4153//4153 -f 4153//4153 4179//4179 4180//4180 -f 4153//4153 4180//4180 4154//4154 -f 4154//4154 4180//4180 3897//3897 -f 4154//4154 3897//3897 4155//4155 -f 4167//4167 4160//4160 4188//4188 -f 4188//4188 4160//4160 4189//4189 -f 4160//4160 4159//4159 4189//4189 -f 4189//4189 4159//4159 4169//4169 -f 4189//4189 4169//4169 4192//4192 -f 4173//4173 4196//4196 4174//4174 -f 4174//4174 4196//4196 4192//4192 -f 4174//4174 4192//4192 4168//4168 -f 4168//4168 4192//4192 4169//4169 -f 4197//4197 3893//3893 4193//4193 -f 4197//4197 4193//4193 4202//4202 -f 4202//4202 4193//4193 4194//4194 -f 4202//4202 4194//4194 4199//4199 -f 4199//4199 4194//4194 4447//4447 -f 4447//4447 4194//4194 4195//4195 -f 4447//4447 4195//4195 4448//4448 -f 4448//4448 4195//4195 4449//4449 -f 4449//4449 4195//4195 4196//4196 -f 4449//4449 4196//4196 4450//4450 -f 4451//4451 4198//4198 4199//4199 -f 4199//4199 4447//4447 4451//4451 -f 4451//4451 4447//4447 4448//4448 -f 4451//4451 4448//4448 4452//4452 -f 4452//4452 4448//4448 4449//4449 -f 4452//4452 4449//4449 4453//4453 -f 4450//4450 4454//4454 4449//4449 -f 4449//4449 4454//4454 4455//4455 -f 4449//4449 4455//4455 4453//4453 -f 4455//4455 4454//4454 4203//4203 -f 4198//4198 4451//4451 4216//4216 -f 4216//4216 4451//4451 4452//4452 -f 4216//4216 4452//4452 4203//4203 -f 4203//4203 4452//4452 4453//4453 -f 4203//4203 4453//4453 4455//4455 -f 4216//4216 4217//4217 4198//4198 -f 4198//4198 4217//4217 4218//4218 -f 4198//4198 4218//4218 4200//4200 -f 4200//4200 4218//4218 3850//3850 -f 4200//4200 3850//3850 4201//4201 -f 4226//4226 4208//4208 4206//4206 -f 4226//4226 4206//4206 4227//4227 -f 4227//4227 4206//4206 4204//4204 -f 4227//4227 4204//4204 4230//4230 -f 4230//4230 4204//4204 4203//4203 -f 4230//4230 4203//4203 4234//4234 -f 4232//4232 4323//4323 4231//4231 -f 4231//4231 4323//4323 4235//4235 -f 4231//4231 4235//4235 3846//3846 -f 4456//4456 4457//4457 4233//4233 -f 4233//4233 4457//4457 4458//4458 -f 4233//4233 4458//4458 4232//4232 -f 4232//4232 4458//4458 4321//4321 -f 4232//4232 4321//4321 4323//4323 -f 4456//4456 4233//4233 4459//4459 -f 4459//4459 4233//4233 4234//4234 -f 4459//4459 4234//4234 4460//4460 -f 4461//4461 4322//4322 4321//4321 -f 4460//4460 4462//4462 4459//4459 -f 4459//4459 4462//4462 4463//4463 -f 4459//4459 4463//4463 4456//4456 -f 4456//4456 4463//4463 4457//4457 -f 4321//4321 4458//4458 4461//4461 -f 4461//4461 4458//4458 4457//4457 -f 4461//4461 4457//4457 4464//4464 -f 4464//4464 4457//4457 4463//4463 -f 4465//4465 4466//4466 4467//4467 -f 4467//4467 4466//4466 4468//4468 -f 4315//4315 4311//4311 4469//4469 -f 4469//4469 4311//4311 4470//4470 -f 4469//4469 4470//4470 4471//4471 -f 4468//4468 4472//4472 4467//4467 -f 4467//4467 4472//4472 4473//4473 -f 4467//4467 4473//4473 4471//4471 -f 4471//4471 4473//4473 4474//4474 -f 4471//4471 4474//4474 4469//4469 -f 4468//4468 4466//4466 4277//4277 -f 4315//4315 4469//4469 4282//4282 -f 4469//4469 4474//4474 4282//4282 -f 4282//4282 4474//4474 4473//4473 -f 4282//4282 4473//4473 4277//4277 -f 4277//4277 4473//4473 4472//4472 -f 4277//4277 4472//4472 4468//4468 -f 4282//4282 4283//4283 4315//4315 -f 4315//4315 4283//4283 4284//4284 -f 4315//4315 4284//4284 4314//4314 -f 4314//4314 4284//4284 3973//3973 -f 4314//4314 3973//3973 4236//4236 -f 4265//4265 4268//4268 4264//4264 -f 4264//4264 4268//4268 4289//4289 -f 4268//4268 4267//4267 4289//4289 -f 4289//4289 4267//4267 4273//4273 -f 4289//4289 4273//4273 4292//4292 -f 4277//4277 4296//4296 4278//4278 -f 4278//4278 4296//4296 4292//4292 -f 4278//4278 4292//4292 4272//4272 -f 4272//4272 4292//4292 4273//4273 -f 4294//4294 4303//4303 4293//4293 -f 4293//4293 4303//4303 4297//4297 -f 4293//4293 4297//4297 3980//3980 -f 4475//4475 4476//4476 4295//4295 -f 4295//4295 4476//4476 4477//4477 -f 4295//4295 4477//4477 4294//4294 -f 4294//4294 4477//4477 4304//4304 -f 4294//4294 4304//4304 4303//4303 -f 4475//4475 4295//4295 4478//4478 -f 4478//4478 4295//4295 4296//4296 -f 4478//4478 4296//4296 4479//4479 -f 4360//4360 4305//4305 4304//4304 -f 4479//4479 4376//4376 4478//4478 -f 4478//4478 4376//4376 4368//4368 -f 4478//4478 4368//4368 4475//4475 -f 4475//4475 4368//4368 4476//4476 -f 4304//4304 4477//4477 4360//4360 -f 4360//4360 4477//4477 4476//4476 -f 4360//4360 4476//4476 4361//4361 -f 4361//4361 4476//4476 4368//4368 -f 4471//4471 4470//4470 4480//4480 -f 4470//4470 4311//4311 4318//4318 -f 4465//4465 4467//4467 4481//4481 -f 4481//4481 4467//4467 4471//4471 -f 4470//4470 4318//4318 4480//4480 -f 4480//4480 4318//4318 4317//4317 -f 4480//4480 4317//4317 4482//4482 -f 4482//4482 4317//4317 4316//4316 -f 4482//4482 4316//4316 4483//4483 -f 4483//4483 4316//4316 4313//4313 -f 4483//4483 4313//4313 4484//4484 -f 4484//4484 4313//4313 4312//4312 -f 4484//4484 4312//4312 4485//4485 -f 4485//4485 4312//4312 4319//4319 -f 4485//4485 4319//4319 4486//4486 -f 4486//4486 4319//4319 4320//4320 -f 4486//4486 4320//4320 4487//4487 -f 4320//4320 4322//4322 4487//4487 -f 4487//4487 4322//4322 4461//4461 -f 4487//4487 4461//4461 4464//4464 -f 4471//4471 4480//4480 4481//4481 -f 4481//4481 4480//4480 4482//4482 -f 4481//4481 4482//4482 4488//4488 -f 4488//4488 4482//4482 4483//4483 -f 4488//4488 4483//4483 4489//4489 -f 4489//4489 4483//4483 4484//4484 -f 4489//4489 4484//4484 4490//4490 -f 4490//4490 4484//4484 4485//4485 -f 4490//4490 4485//4485 4491//4491 -f 4491//4491 4485//4485 4486//4486 -f 4491//4491 4486//4486 4492//4492 -f 4492//4492 4486//4486 4487//4487 -f 4492//4492 4487//4487 4493//4493 -f 4493//4493 4487//4487 4464//4464 -f 4493//4493 4464//4464 4463//4463 -f 4465//4465 4481//4481 4494//4494 -f 4494//4494 4481//4481 4488//4488 -f 4494//4494 4488//4488 4495//4495 -f 4495//4495 4488//4488 4489//4489 -f 4495//4495 4489//4489 4496//4496 -f 4496//4496 4489//4489 4490//4490 -f 4496//4496 4490//4490 4497//4497 -f 4497//4497 4490//4490 4491//4491 -f 4497//4497 4491//4491 4498//4498 -f 4498//4498 4491//4491 4492//4492 -f 4498//4498 4492//4492 4499//4499 -f 4499//4499 4492//4492 4493//4493 -f 4499//4499 4493//4493 4500//4500 -f 4500//4500 4493//4493 4463//4463 -f 4500//4500 4463//4463 4462//4462 -f 4462//4462 3238//3238 4500//4500 -f 4500//4500 3238//3238 3236//3236 -f 4500//4500 3236//3236 4499//4499 -f 4499//4499 3236//3236 4498//4498 -f 4498//4498 3236//3236 3234//3234 -f 4498//4498 3234//3234 4497//4497 -f 4497//4497 3234//3234 4496//4496 -f 4496//4496 3234//3234 3232//3232 -f 4496//4496 3232//3232 4495//4495 -f 4495//4495 3232//3232 4494//4494 -f 4494//4494 3232//3232 3230//3230 -f 4494//4494 3230//3230 4465//4465 -f 3228//3228 4376//4376 3230//3230 -f 3230//3230 4376//4376 4479//4479 -f 4465//4465 3230//3230 4466//4466 -f 4466//4466 3230//3230 4479//4479 -f 4466//4466 4479//4479 4277//4277 -f 4277//4277 4479//4479 4296//4296 -f 4441//4441 4419//4419 3240//3240 -f 3240//3240 3238//3238 4460//4460 -f 4460//4460 3238//3238 4462//4462 -f 4450//4450 4196//4196 4173//4173 -f 4173//4173 4441//4441 4450//4450 -f 4450//4450 4441//4441 3240//3240 -f 4450//4450 3240//3240 4454//4454 -f 4454//4454 3240//3240 4460//4460 -f 4454//4454 4460//4460 4203//4203 -f 4203//4203 4460//4460 4234//4234 -f 4413//4413 3248//3248 4440//4440 -f 4440//4440 3248//3248 3246//3246 -f 4440//4440 3246//3246 4439//4439 -f 4439//4439 3246//3246 4438//4438 -f 4438//4438 3246//3246 3244//3244 -f 4438//4438 3244//3244 4437//4437 -f 4437//4437 3244//3244 4436//4436 -f 4436//4436 3244//3244 3242//3242 -f 4436//4436 3242//3242 4435//4435 -f 4435//4435 3242//3242 4434//4434 -f 4434//4434 3242//3242 3240//3240 -f 4434//4434 3240//3240 4419//4419 -f 3248//3248 4413//4413 3250//3250 -f 3250//3250 4413//4413 4411//4411 -f 4380//4380 3250//3250 4405//4405 -f 4405//4405 3250//3250 4411//4411 -f 4405//4405 4411//4411 4110//4110 -f 4110//4110 4411//4411 4143//4143 -f 4349//4349 3218//3218 4401//4401 -f 4401//4401 3218//3218 3256//3256 -f 4401//4401 3256//3256 4400//4400 -f 4400//4400 3256//3256 4399//4399 -f 4399//4399 3256//3256 3254//3254 -f 4399//4399 3254//3254 4398//4398 -f 4398//4398 3254//3254 4397//4397 -f 4397//4397 3254//3254 3252//3252 -f 4397//4397 3252//3252 4396//4396 -f 4396//4396 3252//3252 4395//4395 -f 4395//4395 3252//3252 3250//3250 -f 4395//4395 3250//3250 4380//4380 -f 4376//4376 3228//3228 4375//4375 -f 4375//4375 3228//3228 3226//3226 -f 4375//4375 3226//3226 4374//4374 -f 4374//4374 3226//3226 4373//4373 -f 4373//4373 3226//3226 3224//3224 -f 4373//4373 3224//3224 4372//4372 -f 4372//4372 3224//3224 4371//4371 -f 4371//4371 3224//3224 3222//3222 -f 4371//4371 3222//3222 4370//4370 -f 4370//4370 3222//3222 4369//4369 -f 4369//4369 3222//3222 3220//3220 -f 4369//4369 3220//3220 4324//4324 -f 4325//4325 4324//4324 3220//3220 -f 3220//3220 3218//3218 4347//4347 -f 4347//4347 3218//3218 4349//4349 -f 4337//4337 4040//4040 4003//4003 -f 4003//4003 4325//4325 4337//4337 -f 4337//4337 4325//4325 3220//3220 -f 4337//4337 3220//3220 4341//4341 -f 4341//4341 3220//3220 4347//4347 -f 4341//4341 4347//4347 4047//4047 -f 4047//4047 4347//4347 4084//4084 -f 1597//1597 1555//1555 1558//1558 -f 1596//1596 1595//1595 1594//1594 -f 1555//1555 1597//1597 1508//1508 -f 1508//1508 1597//1597 1596//1596 -f 1508//1508 1596//1596 1539//1539 -f 1539//1539 1596//1596 1594//1594 -f 1539//1539 1594//1594 1593//1593 -f 1558//1558 1600//1600 1597//1597 -f 1597//1597 1600//1600 1599//1599 -f 1597//1597 1599//1599 1598//1598 -f 1565//1565 1567//1567 1542//1542 -f 1429//1429 1307//1307 1309//1309 -f 3184//3184 3185//3185 1159//1159 -f 1728//1728 1730//1730 1564//1564 -f 1564//1564 1730//1730 1732//1732 -f 1564//1564 1732//1732 3196//3196 -f 1157//1157 1159//1159 1307//1307 -f 1307//1307 1159//1159 3185//3185 -f 1307//1307 3185//3185 1305//1305 -f 1789//1789 1437//1437 1439//1439 -f 3185//3185 3190//3190 1305//1305 -f 1305//1305 3190//3190 3191//3191 -f 1305//1305 3191//3191 1303//1303 -f 1303//1303 3191//3191 3192//3192 -f 1303//1303 3192//3192 1301//1301 -f 1301//1301 3192//3192 3193//3193 -f 1301//1301 3193//3193 1736//1736 -f 1736//1736 3193//3193 3196//3196 -f 1736//1736 3196//3196 1734//1734 -f 1734//1734 3196//3196 1732//1732 -f 1429//1429 1431//1431 1307//1307 -f 1307//1307 1431//1431 1433//1433 -f 1307//1307 1433//1433 1157//1157 -f 1157//1157 1433//1433 1435//1435 -f 1157//1157 1435//1435 1793//1793 -f 1793//1793 1435//1435 1437//1437 -f 1793//1793 1437//1437 1791//1791 -f 1791//1791 1437//1437 1789//1789 -f 1785//1785 1542//1542 1169//1169 -f 1169//1169 1542//1542 1541//1541 -f 1169//1169 1541//1541 1167//1167 -f 1309//1309 1311//1311 1429//1429 -f 1429//1429 1311//1311 1313//1313 -f 1429//1429 1313//1313 1427//1427 -f 1427//1427 1313//1313 1728//1728 -f 1427//1427 1728//1728 1570//1570 -f 1570//1570 1728//1728 1564//1564 -f 1159//1159 1161//1161 3184//3184 -f 3184//3184 1161//1161 1163//1163 -f 3184//3184 1163//1163 3183//3183 -f 3183//3183 1163//1163 1165//1165 -f 3183//3183 1165//1165 3182//3182 -f 3182//3182 1165//1165 1167//1167 -f 3182//3182 1167//1167 3181//3181 -f 3181//3181 1167//1167 1541//1541 -f 1439//1439 1565//1565 1789//1789 -f 1789//1789 1565//1565 1542//1542 -f 1789//1789 1542//1542 1787//1787 -f 1787//1787 1542//1542 1785//1785 -f 1508//1508 1507//1507 1542//1542 -f 1562//1562 1555//1555 1563//1563 -f 1563//1563 1555//1555 1508//1508 -f 1563//1563 1508//1508 1567//1567 -f 1567//1567 1508//1508 1542//1542 -f 1562//1562 1564//1564 1555//1555 -f 1555//1555 1564//1564 3196//3196 -f 1555//1555 3196//3196 1557//1557 -f 1556//1556 3194//3194 1554//1554 -f 1554//1554 3194//3194 4501//4501 -f 1554//1554 4501//4501 1517//1517 -f 1517//1517 4501//4501 4502//4502 -f 1517//1517 4502//4502 1518//1518 -f 1518//1518 4502//4502 1575//1575 -f 3195//3195 1496//1496 1495//1495 -f 1492//1492 1573//1573 1491//1491 -f 1491//1491 1573//1573 4503//4503 -f 1491//1491 4503//4503 1495//1495 -f 1495//1495 4503//4503 4504//4504 -f 1495//1495 4504//4504 3195//3195 -f 4502//4502 4503//4503 1575//1575 -f 1575//1575 4503//4503 1573//1573 -f 4504//4504 4501//4501 3195//3195 -f 3195//3195 4501//4501 3194//3194 -f 4504//4504 4503//4503 4501//4501 -f 4501//4501 4503//4503 4502//4502 -f 1543//1543 1509//1509 1510//1510 -f 1511//1511 1513//1513 1538//1538 -f 1538//1538 1513//1513 4505//4505 -f 1538//1538 4505//4505 1510//1510 -f 1510//1510 4505//4505 4506//4506 -f 1510//1510 4506//4506 1543//1543 -f 1462//1462 1547//1547 1461//1461 -f 1461//1461 1547//1547 4507//4507 -f 1461//1461 4507//4507 1465//1465 -f 1465//1465 4507//4507 4508//4508 -f 1465//1465 4508//4508 1466//1466 -f 1466//1466 4508//4508 1515//1515 -f 4506//4506 4507//4507 1543//1543 -f 1543//1543 4507//4507 1547//1547 -f 4508//4508 4505//4505 1515//1515 -f 1515//1515 4505//4505 1513//1513 -f 4508//4508 4507//4507 4505//4505 -f 4505//4505 4507//4507 4506//4506 -f 4509//4509 4510//4510 1448//1448 -f 1448//1448 4510//4510 1464//1464 -f 1448//1448 1464//1464 1442//1442 -f 4509//4509 4511//4511 4510//4510 -f 4510//4510 4511//4511 4512//4512 -f 4510//4510 4512//4512 3186//3186 -f 3186//3186 4512//4512 3187//3187 -f 4512//4512 4511//4511 1463//1463 -f 1463//1463 4511//4511 1446//1446 -f 1463//1463 1446//1446 1444//1444 -f 1480//1480 1479//1479 1506//1506 -f 1506//1506 1479//1479 1493//1493 -f 1450//1450 1449//1449 1478//1478 -f 1478//1478 1449//1449 1477//1477 -f 4513//4513 4514//4514 1441//1441 -f 1441//1441 4514//4514 1447//1447 -f 4515//4515 4513//4513 1443//1443 -f 1443//1443 4513//4513 1441//1441 -f 4516//4516 4515//4515 1445//1445 -f 1445//1445 4515//4515 1443//1443 -f 4514//4514 4516//4516 1447//1447 -f 1447//1447 4516//4516 1445//1445 -f 4515//4515 4516//4516 4513//4513 -f 4513//4513 4516//4516 4514//4514 -f 4509//4509 1448//1448 4511//4511 -f 4511//4511 1448//1448 1446//1446 -f 1463//1463 3188//3188 4512//4512 -f 4512//4512 3188//3188 3187//3187 -f 1464//1464 3189//3189 1463//1463 -f 1463//1463 3189//3189 3188//3188 -f 3189//3189 1464//1464 3186//3186 -f 3186//3186 1464//1464 4510//4510 -f 4517//4517 4518//4518 4262//4262 -f 4262//4262 4518//4518 4263//4263 -f 4518//4518 4519//4519 4263//4263 -f 4263//4263 4519//4519 4260//4260 -f 4519//4519 4520//4520 4260//4260 -f 4260//4260 4520//4520 4261//4261 -f 4520//4520 4517//4517 4261//4261 -f 4261//4261 4517//4517 4262//4262 -f 4520//4520 4519//4519 4517//4517 -f 4517//4517 4519//4519 4518//4518 -f 4521//4521 4522//4522 4523//4523 -f 4523//4523 4522//4522 4524//4524 -f 4523//4523 4524//4524 4525//4525 -f 4525//4525 4524//4524 4526//4526 -f 4525//4525 4526//4526 4527//4527 -f 4527//4527 4526//4526 4528//4528 -f 4527//4527 4528//4528 4529//4529 -f 4529//4529 4528//4528 4530//4530 -f 4529//4529 4530//4530 4531//4531 -f 4531//4531 4530//4530 4532//4532 -f 4531//4531 4532//4532 4533//4533 -f 4533//4533 4532//4532 4534//4534 -f 4533//4533 4534//4534 4535//4535 -f 4535//4535 4534//4534 4536//4536 -f 4537//4537 4538//4538 4539//4539 -f 4539//4539 4538//4538 4540//4540 -f 4539//4539 4540//4540 4541//4541 -f 4541//4541 4540//4540 4542//4542 -f 4541//4541 4542//4542 4543//4543 -f 4543//4543 4542//4542 4544//4544 -f 4543//4543 4544//4544 4545//4545 -f 4545//4545 4544//4544 4546//4546 -f 4545//4545 4546//4546 4547//4547 -f 4547//4547 4546//4546 4548//4548 -f 4547//4547 4548//4548 4549//4549 -f 4549//4549 4548//4548 4550//4550 -f 4549//4549 4550//4550 4551//4551 -f 4551//4551 4550//4550 4552//4552 -f 4553//4553 4554//4554 4555//4555 -f 4555//4555 4554//4554 4556//4556 -f 4555//4555 4556//4556 4557//4557 -f 4557//4557 4556//4556 4558//4558 -f 4557//4557 4558//4558 4559//4559 -f 4559//4559 4558//4558 4560//4560 -f 4559//4559 4560//4560 4561//4561 -f 4561//4561 4560//4560 4562//4562 -f 4561//4561 4562//4562 4563//4563 -f 4563//4563 4562//4562 4564//4564 -f 4563//4563 4564//4564 4565//4565 -f 4565//4565 4564//4564 4566//4566 -f 4565//4565 4566//4566 4567//4567 -f 4567//4567 4566//4566 4568//4568 -f 4569//4569 4570//4570 4571//4571 -f 4571//4571 4570//4570 4572//4572 -f 4571//4571 4572//4572 4573//4573 -f 4573//4573 4572//4572 4574//4574 -f 4573//4573 4574//4574 4575//4575 -f 4575//4575 4574//4574 4576//4576 -f 4575//4575 4576//4576 4577//4577 -f 4577//4577 4576//4576 4578//4578 -f 4577//4577 4578//4578 4579//4579 -f 4579//4579 4578//4578 4580//4580 -f 4579//4579 4580//4580 4581//4581 -f 4581//4581 4580//4580 4582//4582 -f 4581//4581 4582//4582 4583//4583 -f 4583//4583 4582//4582 4584//4584 -f 4585//4585 4586//4586 4587//4587 -f 4587//4587 4586//4586 4588//4588 -f 4587//4587 4588//4588 4589//4589 -f 4589//4589 4588//4588 4590//4590 -f 4589//4589 4590//4590 4591//4591 -f 4591//4591 4590//4590 4592//4592 -f 4591//4591 4592//4592 4593//4593 -f 4593//4593 4592//4592 4594//4594 -f 4593//4593 4594//4594 4595//4595 -f 4595//4595 4594//4594 4596//4596 -f 4595//4595 4596//4596 4597//4597 -f 4597//4597 4596//4596 4598//4598 -f 4597//4597 4598//4598 4599//4599 -f 4599//4599 4598//4598 4600//4600 -f 4601//4601 4576//4576 4574//4574 -f 4584//4584 4582//4582 4602//4602 -f 4602//4602 4582//4582 4580//4580 -f 4602//4602 4580//4580 4578//4578 -f 4601//4601 4574//4574 4603//4603 -f 4604//4604 4605//4605 4606//4606 -f 4606//4606 4605//4605 4607//4607 -f 4606//4606 4607//4607 4608//4608 -f 4608//4608 4607//4607 4609//4609 -f 4608//4608 4609//4609 4610//4610 -f 4610//4610 4611//4611 4612//4612 -f 4612//4612 4611//4611 4613//4613 -f 4574//4574 4572//4572 4603//4603 -f 4603//4603 4572//4572 4570//4570 -f 4603//4603 4570//4570 4614//4614 -f 4614//4614 4570//4570 4615//4615 -f 4614//4614 4615//4615 4616//4616 -f 4616//4616 4615//4615 4605//4605 -f 4616//4616 4605//4605 4617//4617 -f 4617//4617 4605//4605 4604//4604 -f 4618//4618 4608//4608 4619//4619 -f 4619//4619 4608//4608 4610//4610 -f 4619//4619 4610//4610 4620//4620 -f 4620//4620 4610//4610 4612//4612 -f 4621//4621 4622//4622 4623//4623 -f 4596//4596 4624//4624 4598//4598 -f 4598//4598 4624//4624 4625//4625 -f 4598//4598 4625//4625 4600//4600 -f 4596//4596 4594//4594 4624//4624 -f 4624//4624 4594//4594 4592//4592 -f 4624//4624 4592//4592 4602//4602 -f 4602//4602 4592//4592 4590//4590 -f 4602//4602 4590//4590 4588//4588 -f 4600//4600 4625//4625 4626//4626 -f 4626//4626 4625//4625 4627//4627 -f 4626//4626 4627//4627 4628//4628 -f 4629//4629 4630//4630 4602//4602 -f 4631//4631 4586//4586 4632//4632 -f 4632//4632 4586//4586 4633//4633 -f 4632//4632 4633//4633 4634//4634 -f 4634//4634 4633//4633 4635//4635 -f 4634//4634 4635//4635 4636//4636 -f 4611//4611 4584//4584 4613//4613 -f 4613//4613 4584//4584 4602//4602 -f 4613//4613 4602//4602 4637//4637 -f 4637//4637 4602//4602 4630//4630 -f 4627//4627 4621//4621 4628//4628 -f 4628//4628 4621//4621 4623//4623 -f 4628//4628 4623//4623 4638//4638 -f 4638//4638 4623//4623 4639//4639 -f 4638//4638 4639//4639 4640//4640 -f 4640//4640 4639//4639 4641//4641 -f 4640//4640 4641//4641 4635//4635 -f 4635//4635 4641//4641 4642//4642 -f 4635//4635 4642//4642 4636//4636 -f 4631//4631 4643//4643 4586//4586 -f 4586//4586 4643//4643 4644//4644 -f 4586//4586 4644//4644 4588//4588 -f 4588//4588 4644//4644 4645//4645 -f 4588//4588 4645//4645 4602//4602 -f 4602//4602 4645//4645 4646//4646 -f 4602//4602 4646//4646 4629//4629 -f 4546//4546 4647//4647 4548//4548 -f 4548//4548 4647//4647 4648//4648 -f 4548//4548 4648//4648 4550//4550 -f 4649//4649 4530//4530 4650//4650 -f 4650//4650 4530//4530 4528//4528 -f 4650//4650 4528//4528 4526//4526 -f 4524//4524 4522//4522 4602//4602 -f 4602//4602 4522//4522 4651//4651 -f 4602//4602 4651//4651 4652//4652 -f 4648//4648 4653//4653 4550//4550 -f 4550//4550 4653//4653 4654//4654 -f 4550//4550 4654//4654 4552//4552 -f 4552//4552 4654//4654 4655//4655 -f 4552//4552 4655//4655 4656//4656 -f 4656//4656 4655//4655 1542//1542 -f 4656//4656 1542//1542 4657//4657 -f 4652//4652 4658//4658 4602//4602 -f 4602//4602 4658//4658 4659//4659 -f 4602//4602 4659//4659 4624//4624 -f 4624//4624 4659//4659 4660//4660 -f 4624//4624 4660//4660 4661//4661 -f 4662//4662 4663//4663 4664//4664 -f 4664//4664 4663//4663 4665//4665 -f 4657//4657 1542//1542 4666//4666 -f 4666//4666 1542//1542 4667//4667 -f 4666//4666 4667//4667 4662//4662 -f 4662//4662 4667//4667 4668//4668 -f 4662//4662 4668//4668 4663//4663 -f 4536//4536 4534//4534 4540//4540 -f 4540//4540 4534//4534 4532//4532 -f 4540//4540 4532//4532 4542//4542 -f 4542//4542 4532//4532 4530//4530 -f 4542//4542 4530//4530 4544//4544 -f 4544//4544 4530//4530 4649//4649 -f 4544//4544 4649//4649 4546//4546 -f 4546//4546 4649//4649 4669//4669 -f 4546//4546 4669//4669 4647//4647 -f 4540//4540 4538//4538 4536//4536 -f 4536//4536 4538//4538 4670//4670 -f 4536//4536 4670//4670 4661//4661 -f 4661//4661 4670//4670 4664//4664 -f 4661//4661 4664//4664 4624//4624 -f 4624//4624 4664//4664 4665//4665 -f 4671//4671 4568//4568 4602//4602 -f 4602//4602 4568//4568 4650//4650 -f 4602//4602 4650//4650 4524//4524 -f 4524//4524 4650//4650 4526//4526 -f 3196//3196 4672//4672 4554//4554 -f 4554//4554 4672//4672 4673//4673 -f 4554//4554 4673//4673 4556//4556 -f 4556//4556 4673//4673 4674//4674 -f 4556//4556 4674//4674 4558//4558 -f 4675//4675 4602//4602 4601//4601 -f 4601//4601 4602//4602 4578//4578 -f 4601//4601 4578//4578 4576//4576 -f 4554//4554 4676//4676 3196//3196 -f 3196//3196 4676//4676 4677//4677 -f 3196//3196 4677//4677 4678//4678 -f 4678//4678 4677//4677 4679//4679 -f 4678//4678 4679//4679 4680//4680 -f 4680//4680 4679//4679 4681//4681 -f 4671//4671 4602//4602 4682//4682 -f 4682//4682 4602//4602 4675//4675 -f 4682//4682 4675//4675 4681//4681 -f 4681//4681 4675//4675 4683//4683 -f 4681//4681 4683//4683 4680//4680 -f 4568//4568 4566//4566 4650//4650 -f 4650//4650 4566//4566 4564//4564 -f 4650//4650 4564//4564 4684//4684 -f 4684//4684 4564//4564 4562//4562 -f 4684//4684 4562//4562 4685//4685 -f 4685//4685 4562//4562 4560//4560 -f 4685//4685 4560//4560 4686//4686 -f 4686//4686 4560//4560 4558//4558 -f 4686//4686 4558//4558 4687//4687 -f 4687//4687 4558//4558 4674//4674 -f 4535//4535 4536//4536 4688//4688 -f 4688//4688 4536//4536 4661//4661 -f 4688//4688 4661//4661 4689//4689 -f 4689//4689 4661//4661 4660//4660 -f 4689//4689 4660//4660 4690//4690 -f 4690//4690 4660//4660 4659//4659 -f 4690//4690 4659//4659 4691//4691 -f 4691//4691 4659//4659 4658//4658 -f 4691//4691 4658//4658 4692//4692 -f 4692//4692 4658//4658 4652//4652 -f 4692//4692 4652//4652 4693//4693 -f 4693//4693 4652//4652 4651//4651 -f 4693//4693 4651//4651 4521//4521 -f 4521//4521 4651//4651 4522//4522 -f 4551//4551 4552//4552 4694//4694 -f 4694//4694 4552//4552 4656//4656 -f 4694//4694 4656//4656 4695//4695 -f 4695//4695 4656//4656 4657//4657 -f 4695//4695 4657//4657 4696//4696 -f 4696//4696 4657//4657 4666//4666 -f 4696//4696 4666//4666 4697//4697 -f 4697//4697 4666//4666 4662//4662 -f 4697//4697 4662//4662 4698//4698 -f 4698//4698 4662//4662 4664//4664 -f 4698//4698 4664//4664 4699//4699 -f 4699//4699 4664//4664 4670//4670 -f 4699//4699 4670//4670 4537//4537 -f 4537//4537 4670//4670 4538//4538 -f 4567//4567 4568//4568 4700//4700 -f 4700//4700 4568//4568 4671//4671 -f 4700//4700 4671//4671 4701//4701 -f 4701//4701 4671//4671 4682//4682 -f 4701//4701 4682//4682 4702//4702 -f 4702//4702 4682//4682 4681//4681 -f 4702//4702 4681//4681 4703//4703 -f 4703//4703 4681//4681 4679//4679 -f 4703//4703 4679//4679 4704//4704 -f 4704//4704 4679//4679 4677//4677 -f 4704//4704 4677//4677 4705//4705 -f 4705//4705 4677//4677 4676//4676 -f 4705//4705 4676//4676 4553//4553 -f 4553//4553 4676//4676 4554//4554 -f 4583//4583 4584//4584 4706//4706 -f 4706//4706 4584//4584 4611//4611 -f 4706//4706 4611//4611 4707//4707 -f 4707//4707 4611//4611 4610//4610 -f 4707//4707 4610//4610 4708//4708 -f 4708//4708 4610//4610 4609//4609 -f 4708//4708 4609//4609 4709//4709 -f 4709//4709 4609//4609 4607//4607 -f 4709//4709 4607//4607 4710//4710 -f 4710//4710 4607//4607 4605//4605 -f 4710//4710 4605//4605 4711//4711 -f 4711//4711 4605//4605 4615//4615 -f 4711//4711 4615//4615 4569//4569 -f 4569//4569 4615//4615 4570//4570 -f 4599//4599 4600//4600 4712//4712 -f 4712//4712 4600//4600 4626//4626 -f 4712//4712 4626//4626 4713//4713 -f 4713//4713 4626//4626 4628//4628 -f 4713//4713 4628//4628 4714//4714 -f 4714//4714 4628//4628 4638//4638 -f 4714//4714 4638//4638 4715//4715 -f 4715//4715 4638//4638 4640//4640 -f 4715//4715 4640//4640 4716//4716 -f 4716//4716 4640//4640 4635//4635 -f 4716//4716 4635//4635 4717//4717 -f 4717//4717 4635//4635 4633//4633 -f 4717//4717 4633//4633 4585//4585 -f 4585//4585 4633//4633 4586//4586 -f 4718//4718 4719//4719 4720//4720 -f 4721//4721 4606//4606 4720//4720 -f 4720//4720 4606//4606 4608//4608 -f 4720//4720 4608//4608 4718//4718 -f 4606//4606 4721//4721 4722//4722 -f 4606//4606 4722//4722 4604//4604 -f 4604//4604 4722//4722 4723//4723 -f 4604//4604 4723//4723 4617//4617 -f 4617//4617 4723//4723 4724//4724 -f 4617//4617 4724//4724 4616//4616 -f 4616//4616 4724//4724 4725//4725 -f 4616//4616 4725//4725 4614//4614 -f 4725//4725 4726//4726 4614//4614 -f 4614//4614 4726//4726 4603//4603 -f 4727//4727 4678//4678 4728//4728 -f 4728//4728 4678//4678 4680//4680 -f 4728//4728 4680//4680 4729//4729 -f 4729//4729 4680//4680 4683//4683 -f 4729//4729 4683//4683 4730//4730 -f 4603//4603 4726//4726 4601//4601 -f 4601//4601 4726//4726 4730//4730 -f 4601//4601 4730//4730 4675//4675 -f 4675//4675 4730//4730 4683//4683 -f 4731//4731 4667//4667 1542//1542 -f 3196//3196 4678//4678 4727//4727 -f 3196//3196 4727//4727 1557//1557 -f 1557//1557 4727//4727 4732//4732 -f 4732//4732 4727//4727 4733//4733 -f 4732//4732 4733//4733 4734//4734 -f 4735//4735 4736//4736 4731//4731 -f 1542//1542 1507//1507 4731//4731 -f 4731//4731 1507//1507 4737//4737 -f 4731//4731 4737//4737 4735//4735 -f 4735//4735 4737//4737 4738//4738 -f 4735//4735 4738//4738 4734//4734 -f 4734//4734 4738//4738 4739//4739 -f 4734//4734 4739//4739 4732//4732 -f 4740//4740 4672//4672 1557//1557 -f 1557//1557 4672//4672 3196//3196 -f 4741//4741 4684//4684 4685//4685 -f 4741//4741 4685//4685 4742//4742 -f 4742//4742 4685//4685 4686//4686 -f 4742//4742 4686//4686 4743//4743 -f 4743//4743 4686//4686 4687//4687 -f 4743//4743 4687//4687 4744//4744 -f 4744//4744 4687//4687 4674//4674 -f 4744//4744 4674//4674 4745//4745 -f 4745//4745 4674//4674 4673//4673 -f 4745//4745 4673//4673 4746//4746 -f 4746//4746 4673//4673 4672//4672 -f 4746//4746 4672//4672 4740//4740 -f 4747//4747 4649//4649 4741//4741 -f 4741//4741 4649//4649 4650//4650 -f 4741//4741 4650//4650 4684//4684 -f 4748//4748 4655//4655 4654//4654 -f 4748//4748 4654//4654 4749//4749 -f 4749//4749 4654//4654 4653//4653 -f 4749//4749 4653//4653 4750//4750 -f 4750//4750 4653//4653 4648//4648 -f 4750//4750 4648//4648 4751//4751 -f 4751//4751 4648//4648 4647//4647 -f 4751//4751 4647//4647 4752//4752 -f 4752//4752 4647//4647 4669//4669 -f 4752//4752 4669//4669 4753//4753 -f 4753//4753 4669//4669 4649//4649 -f 4753//4753 4649//4649 4747//4747 -f 1507//1507 1542//1542 4748//4748 -f 4748//4748 1542//1542 4655//4655 -f 4667//4667 4731//4731 4668//4668 -f 4668//4668 4731//4731 4754//4754 -f 4668//4668 4754//4754 4663//4663 -f 4663//4663 4754//4754 4755//4755 -f 4663//4663 4755//4755 4665//4665 -f 4665//4665 4755//4755 4756//4756 -f 4665//4665 4756//4756 4624//4624 -f 4624//4624 4756//4756 4757//4757 -f 4624//4624 4757//4757 4625//4625 -f 4627//4627 4625//4625 4758//4758 -f 4758//4758 4625//4625 4757//4757 -f 4759//4759 4639//4639 4623//4623 -f 4759//4759 4623//4623 4760//4760 -f 4760//4760 4623//4623 4622//4622 -f 4760//4760 4622//4622 4761//4761 -f 4761//4761 4622//4622 4621//4621 -f 4761//4761 4621//4621 4762//4762 -f 4762//4762 4621//4621 4627//4627 -f 4762//4762 4627//4627 4758//4758 -f 4763//4763 4764//4764 4765//4765 -f 4765//4765 4764//4764 4641//4641 -f 4765//4765 4641//4641 4759//4759 -f 4759//4759 4641//4641 4639//4639 -f 4766//4766 4767//4767 4620//4620 -f 4620//4620 4612//4612 4766//4766 -f 4766//4766 4612//4612 4613//4613 -f 4766//4766 4613//4613 4768//4768 -f 4768//4768 4613//4613 4637//4637 -f 4768//4768 4637//4637 4769//4769 -f 4769//4769 4637//4637 4630//4630 -f 4769//4769 4630//4630 4770//4770 -f 4770//4770 4630//4630 4629//4629 -f 4770//4770 4629//4629 4771//4771 -f 4771//4771 4629//4629 4646//4646 -f 4771//4771 4646//4646 4772//4772 -f 4772//4772 4646//4646 4645//4645 -f 4772//4772 4645//4645 4773//4773 -f 4773//4773 4645//4645 4644//4644 -f 4773//4773 4644//4644 4774//4774 -f 4774//4774 4644//4644 4643//4643 -f 4774//4774 4643//4643 4775//4775 -f 4775//4775 4643//4643 4631//4631 -f 4775//4775 4631//4631 4776//4776 -f 4776//4776 4631//4631 4632//4632 -f 4776//4776 4632//4632 4777//4777 -f 4777//4777 4632//4632 4634//4634 -f 4533//4533 4535//4535 4688//4688 -f 4533//4533 4688//4688 4523//4523 -f 4523//4523 4688//4688 4693//4693 -f 4523//4523 4693//4693 4521//4521 -f 4692//4692 4693//4693 4691//4691 -f 4691//4691 4693//4693 4688//4688 -f 4691//4691 4688//4688 4690//4690 -f 4690//4690 4688//4688 4689//4689 -f 4529//4529 4531//4531 4527//4527 -f 4527//4527 4531//4531 4533//4533 -f 4527//4527 4533//4533 4525//4525 -f 4525//4525 4533//4533 4523//4523 -f 4699//4699 4537//4537 4539//4539 -f 4549//4549 4551//4551 4694//4694 -f 4545//4545 4547//4547 4543//4543 -f 4543//4543 4547//4547 4549//4549 -f 4543//4543 4549//4549 4541//4541 -f 4695//4695 4696//4696 4694//4694 -f 4694//4694 4696//4696 4697//4697 -f 4541//4541 4549//4549 4539//4539 -f 4539//4539 4549//4549 4694//4694 -f 4539//4539 4694//4694 4699//4699 -f 4699//4699 4694//4694 4697//4697 -f 4699//4699 4697//4697 4698//4698 -f 4705//4705 4553//4553 4555//4555 -f 4565//4565 4567//4567 4700//4700 -f 4561//4561 4563//4563 4559//4559 -f 4559//4559 4563//4563 4565//4565 -f 4559//4559 4565//4565 4557//4557 -f 4701//4701 4702//4702 4700//4700 -f 4700//4700 4702//4702 4703//4703 -f 4557//4557 4565//4565 4555//4555 -f 4555//4555 4565//4565 4700//4700 -f 4555//4555 4700//4700 4705//4705 -f 4705//4705 4700//4700 4703//4703 -f 4705//4705 4703//4703 4704//4704 -f 4733//4733 4727//4727 4728//4728 -f 4724//4724 4723//4723 4722//4722 -f 4573//4573 4575//4575 4728//4728 -f 4728//4728 4575//4575 4577//4577 -f 4728//4728 4577//4577 4733//4733 -f 4733//4733 4577//4577 4579//4579 -f 4733//4733 4579//4579 4581//4581 -f 4725//4725 4724//4724 4710//4710 -f 4710//4710 4724//4724 4722//4722 -f 4710//4710 4722//4722 4709//4709 -f 4709//4709 4722//4722 4721//4721 -f 4709//4709 4721//4721 4708//4708 -f 4708//4708 4721//4721 4720//4720 -f 4708//4708 4720//4720 4707//4707 -f 4707//4707 4720//4720 4778//4778 -f 4707//4707 4778//4778 4706//4706 -f 4706//4706 4778//4778 4779//4779 -f 4706//4706 4779//4779 4583//4583 -f 4583//4583 4779//4779 4780//4780 -f 4583//4583 4780//4780 4581//4581 -f 4581//4581 4780//4780 4781//4781 -f 4581//4581 4781//4781 4733//4733 -f 4733//4733 4781//4781 4782//4782 -f 4710//4710 4711//4711 4725//4725 -f 4725//4725 4711//4711 4569//4569 -f 4725//4725 4569//4569 4726//4726 -f 4726//4726 4569//4569 4571//4571 -f 4726//4726 4571//4571 4730//4730 -f 4730//4730 4571//4571 4573//4573 -f 4730//4730 4573//4573 4729//4729 -f 4729//4729 4573//4573 4728//4728 -f 4754//4754 4731//4731 4736//4736 -f 4587//4587 4589//4589 4736//4736 -f 4589//4589 4591//4591 4736//4736 -f 4736//4736 4591//4591 4593//4593 -f 4736//4736 4593//4593 4754//4754 -f 4754//4754 4593//4593 4595//4595 -f 4754//4754 4595//4595 4755//4755 -f 4760//4760 4713//4713 4759//4759 -f 4759//4759 4713//4713 4714//4714 -f 4759//4759 4714//4714 4765//4765 -f 4765//4765 4714//4714 4715//4715 -f 4765//4765 4715//4715 4716//4716 -f 4760//4760 4761//4761 4713//4713 -f 4713//4713 4761//4761 4762//4762 -f 4713//4713 4762//4762 4712//4712 -f 4712//4712 4762//4762 4758//4758 -f 4712//4712 4758//4758 4599//4599 -f 4599//4599 4758//4758 4757//4757 -f 4599//4599 4757//4757 4597//4597 -f 4736//4736 4783//4783 4587//4587 -f 4587//4587 4783//4783 4784//4784 -f 4587//4587 4784//4784 4585//4585 -f 4585//4585 4784//4784 4785//4785 -f 4585//4585 4785//4785 4717//4717 -f 4717//4717 4785//4785 4786//4786 -f 4717//4717 4786//4786 4716//4716 -f 4716//4716 4786//4786 4787//4787 -f 4716//4716 4787//4787 4765//4765 -f 4597//4597 4757//4757 4595//4595 -f 4595//4595 4757//4757 4756//4756 -f 4595//4595 4756//4756 4755//4755 -f 4718//4718 4608//4608 4618//4618 -f 4718//4718 4618//4618 4788//4788 -f 4788//4788 4618//4618 4619//4619 -f 4788//4788 4619//4619 4789//4789 -f 4789//4789 4619//4619 4620//4620 -f 4789//4789 4620//4620 4767//4767 -f 4735//4735 4790//4790 4736//4736 -f 4736//4736 4790//4790 4783//4783 -f 4764//4764 4763//4763 4791//4791 -f 4791//4791 4792//4792 4776//4776 -f 4719//4719 4718//4718 4793//4793 -f 4793//4793 4718//4718 4788//4788 -f 4776//4776 4792//4792 4775//4775 -f 4775//4775 4792//4792 4794//4794 -f 4775//4775 4794//4794 4774//4774 -f 4774//4774 4794//4794 4795//4795 -f 4774//4774 4795//4795 4773//4773 -f 4773//4773 4795//4795 4790//4790 -f 4773//4773 4790//4790 4772//4772 -f 4772//4772 4790//4790 4735//4735 -f 4772//4772 4735//4735 4771//4771 -f 4771//4771 4735//4735 4734//4734 -f 4771//4771 4734//4734 4796//4796 -f 4788//4788 4789//4789 4793//4793 -f 4793//4793 4789//4789 4767//4767 -f 4793//4793 4767//4767 4797//4797 -f 4797//4797 4767//4767 4766//4766 -f 4797//4797 4766//4766 4798//4798 -f 4798//4798 4766//4766 4768//4768 -f 4798//4798 4768//4768 4799//4799 -f 4799//4799 4768//4768 4769//4769 -f 4799//4799 4769//4769 4796//4796 -f 4796//4796 4769//4769 4770//4770 -f 4796//4796 4770//4770 4771//4771 -f 4800//4800 4764//4764 4801//4801 -f 4801//4801 4764//4764 4791//4791 -f 4801//4801 4791//4791 4777//4777 -f 4777//4777 4791//4791 4776//4776 -f 4733//4733 4782//4782 4734//4734 -f 4734//4734 4782//4782 4796//4796 -f 4739//4739 4738//4738 4802//4802 -f 4802//4802 4738//4738 4803//4803 -f 4804//4804 4805//4805 4806//4806 -f 4806//4806 4805//4805 4802//4802 -f 4806//4806 4802//4802 4807//4807 -f 4808//4808 4809//4809 4810//4810 -f 4810//4810 4809//4809 4803//4803 -f 4809//4809 4811//4811 4803//4803 -f 4803//4803 4811//4811 4812//4812 -f 4803//4803 4812//4812 4802//4802 -f 4802//4802 4812//4812 4813//4813 -f 4802//4802 4813//4813 4807//4807 -f 1557//1557 4732//4732 4740//4740 -f 4740//4740 4732//4732 4814//4814 -f 4740//4740 4814//4814 4746//4746 -f 4746//4746 4814//4814 4815//4815 -f 4746//4746 4815//4815 4745//4745 -f 4745//4745 4815//4815 4816//4816 -f 4745//4745 4816//4816 4744//4744 -f 4744//4744 4816//4816 4817//4817 -f 4818//4818 4752//4752 4819//4819 -f 4819//4819 4752//4752 4753//4753 -f 4819//4819 4753//4753 4820//4820 -f 4820//4820 4753//4753 4747//4747 -f 4820//4820 4747//4747 4821//4821 -f 4821//4821 4747//4747 4741//4741 -f 4821//4821 4741//4741 4822//4822 -f 4822//4822 4741//4741 4742//4742 -f 4822//4822 4742//4742 4817//4817 -f 4817//4817 4742//4742 4743//4743 -f 4817//4817 4743//4743 4744//4744 -f 4737//4737 1507//1507 4823//4823 -f 4823//4823 1507//1507 4748//4748 -f 4823//4823 4748//4748 4824//4824 -f 4824//4824 4748//4748 4749//4749 -f 4824//4824 4749//4749 4825//4825 -f 4825//4825 4749//4749 4750//4750 -f 4825//4825 4750//4750 4818//4818 -f 4818//4818 4750//4750 4751//4751 -f 4818//4818 4751//4751 4752//4752 -f 4641//4641 4764//4764 4800//4800 -f 4641//4641 4800//4800 4642//4642 -f 4642//4642 4800//4800 4801//4801 -f 4642//4642 4801//4801 4636//4636 -f 4636//4636 4801//4801 4777//4777 -f 4636//4636 4777//4777 4634//4634 -f 4720//4720 4719//4719 4793//4793 -f 4720//4720 4793//4793 4778//4778 -f 4778//4778 4793//4793 4797//4797 -f 4778//4778 4797//4797 4779//4779 -f 4779//4779 4797//4797 4798//4798 -f 4779//4779 4798//4798 4780//4780 -f 4780//4780 4798//4798 4799//4799 -f 4780//4780 4799//4799 4781//4781 -f 4781//4781 4799//4799 4796//4796 -f 4781//4781 4796//4796 4782//4782 -f 4783//4783 4790//4790 4795//4795 -f 4783//4783 4795//4795 4784//4784 -f 4784//4784 4795//4795 4794//4794 -f 4784//4784 4794//4794 4785//4785 -f 4785//4785 4794//4794 4792//4792 -f 4785//4785 4792//4792 4786//4786 -f 4786//4786 4792//4792 4791//4791 -f 4786//4786 4791//4791 4787//4787 -f 4787//4787 4791//4791 4763//4763 -f 4787//4787 4763//4763 4765//4765 -f 4814//4814 4732//4732 4802//4802 -f 4802//4802 4732//4732 4739//4739 -f 4814//4814 4802//4802 4805//4805 -f 4814//4814 4805//4805 4815//4815 -f 4815//4815 4805//4805 4804//4804 -f 4815//4815 4804//4804 4816//4816 -f 4816//4816 4804//4804 4806//4806 -f 4816//4816 4806//4806 4817//4817 -f 4817//4817 4806//4806 4807//4807 -f 4817//4817 4807//4807 4822//4822 -f 4822//4822 4807//4807 4813//4813 -f 4822//4822 4813//4813 4821//4821 -f 4813//4813 4812//4812 4821//4821 -f 4821//4821 4812//4812 4820//4820 -f 4820//4820 4812//4812 4811//4811 -f 4820//4820 4811//4811 4819//4819 -f 4819//4819 4811//4811 4809//4809 -f 4819//4819 4809//4809 4818//4818 -f 4818//4818 4809//4809 4808//4808 -f 4818//4818 4808//4808 4825//4825 -f 4825//4825 4808//4808 4810//4810 -f 4825//4825 4810//4810 4824//4824 -f 4824//4824 4810//4810 4803//4803 -f 4824//4824 4803//4803 4823//4823 -f 4737//4737 4823//4823 4738//4738 -f 4738//4738 4823//4823 4803//4803 -f 4826//4826 4827//4827 4828//4828 -f 4828//4828 4827//4827 4829//4829 -f 4830//4830 4831//4831 4832//4832 -f 4833//4833 4834//4834 4835//4835 -f 4835//4835 4834//4834 4836//4836 -f 4836//4836 4834//4834 4837//4837 -f 4836//4836 4837//4837 4838//4838 -f 4833//4833 4835//4835 4839//4839 -f 4839//4839 4835//4835 4840//4840 -f 4839//4839 4840//4840 4841//4841 -f 4841//4841 4840//4840 4842//4842 -f 4841//4841 4842//4842 4843//4843 -f 4843//4843 4842//4842 4844//4844 -f 4844//4844 4842//4842 4845//4845 -f 4844//4844 4845//4845 4846//4846 -f 4846//4846 4845//4845 4847//4847 -f 4847//4847 4845//4845 4848//4848 -f 4847//4847 4848//4848 4849//4849 -f 4849//4849 4848//4848 4850//4850 -f 4849//4849 4850//4850 4851//4851 -f 4832//4832 4831//4831 4850//4850 -f 4850//4850 4831//4831 4852//4852 -f 4850//4850 4852//4852 4851//4851 -f 4830//4830 4832//4832 4853//4853 -f 4853//4853 4832//4832 4854//4854 -f 4853//4853 4854//4854 4855//4855 -f 4855//4855 4854//4854 4856//4856 -f 4855//4855 4856//4856 4857//4857 -f 4857//4857 4856//4856 4858//4858 -f 4858//4858 4856//4856 4859//4859 -f 4858//4858 4859//4859 4860//4860 -f 4860//4860 4859//4859 4861//4861 -f 4860//4860 4861//4861 4862//4862 -f 4863//4863 4864//4864 4865//4865 -f 4865//4865 4864//4864 4866//4866 -f 4865//4865 4866//4866 4867//4867 -f 4867//4867 4866//4866 4868//4868 -f 4869//4869 4870//4870 4868//4868 -f 4868//4868 4870//4870 4871//4871 -f 4868//4868 4871//4871 4867//4867 -f 4872//4872 4873//4873 4874//4874 -f 4874//4874 4873//4873 4875//4875 -f 4874//4874 4875//4875 4876//4876 -f 4876//4876 4875//4875 4877//4877 -f 4876//4876 4877//4877 4869//4869 -f 4869//4869 4877//4877 4878//4878 -f 4869//4869 4878//4878 4870//4870 -f 4827//4827 4879//4879 4829//4829 -f 4829//4829 4879//4879 4880//4880 -f 4829//4829 4880//4880 4872//4872 -f 4872//4872 4880//4880 4881//4881 -f 4872//4872 4881//4881 4873//4873 -f 4826//4826 4828//4828 4882//4882 -f 4882//4882 4828//4828 4883//4883 -f 4882//4882 4883//4883 4884//4884 -f 4884//4884 4883//4883 4885//4885 -f 4884//4884 4885//4885 4886//4886 -f 4886//4886 4885//4885 4887//4887 -f 4887//4887 4885//4885 4888//4888 -f 4887//4887 4888//4888 4889//4889 -f 4890//4890 4888//4888 4891//4891 -f 4891//4891 4888//4888 4885//4885 -f 4891//4891 4885//4885 4892//4892 -f 4892//4892 4885//4885 4883//4883 -f 4892//4892 4883//4883 4893//4893 -f 4893//4893 4883//4883 4828//4828 -f 4893//4893 4828//4828 4894//4894 -f 4894//4894 4828//4828 4829//4829 -f 4894//4894 4829//4829 4895//4895 -f 4895//4895 4829//4829 4872//4872 -f 4895//4895 4872//4872 4896//4896 -f 4896//4896 4872//4872 4874//4874 -f 4896//4896 4874//4874 4897//4897 -f 4897//4897 4874//4874 4876//4876 -f 4897//4897 4876//4876 4898//4898 -f 4898//4898 4876//4876 4869//4869 -f 4898//4898 4869//4869 4899//4899 -f 4899//4899 4869//4869 4868//4868 -f 4899//4899 4868//4868 4900//4900 -f 4900//4900 4868//4868 4866//4866 -f 4900//4900 4866//4866 4901//4901 -f 4901//4901 4866//4866 4864//4864 -f 4836//4836 4890//4890 4835//4835 -f 4835//4835 4890//4890 4891//4891 -f 4835//4835 4891//4891 4840//4840 -f 4840//4840 4891//4891 4892//4892 -f 4840//4840 4892//4892 4842//4842 -f 4842//4842 4892//4892 4893//4893 -f 4842//4842 4893//4893 4845//4845 -f 4845//4845 4893//4893 4894//4894 -f 4845//4845 4894//4894 4848//4848 -f 4848//4848 4894//4894 4895//4895 -f 4848//4848 4895//4895 4850//4850 -f 4850//4850 4895//4895 4896//4896 -f 4850//4850 4896//4896 4832//4832 -f 4832//4832 4896//4896 4897//4897 -f 4832//4832 4897//4897 4854//4854 -f 4854//4854 4897//4897 4898//4898 -f 4854//4854 4898//4898 4856//4856 -f 4856//4856 4898//4898 4899//4899 -f 4856//4856 4899//4899 4859//4859 -f 4859//4859 4899//4899 4900//4900 -f 4859//4859 4900//4900 4861//4861 -f 4861//4861 4900//4900 4901//4901 -f 4902//4902 4903//4903 4904//4904 -f 4905//4905 4906//4906 4907//4907 -f 4908//4908 4909//4909 4906//4906 -f 4910//4910 4911//4911 4912//4912 -f 4913//4913 4911//4911 4914//4914 -f 4914//4914 4911//4911 4910//4910 -f 4914//4914 4910//4910 4915//4915 -f 4916//4916 4917//4917 4918//4918 -f 4919//4919 4920//4920 4917//4917 -f 4921//4921 4922//4922 4920//4920 -f 4923//4923 4924//4924 4925//4925 -f 4926//4926 4915//4915 4927//4927 -f 4927//4927 4915//4915 4910//4910 -f 4927//4927 4910//4910 4928//4928 -f 4928//4928 4910//4910 4912//4912 -f 4928//4928 4912//4912 4909//4909 -f 4929//4929 4930//4930 4931//4931 -f 4932//4932 4930//4930 4933//4933 -f 4933//4933 4930//4930 4929//4929 -f 4933//4933 4929//4929 4934//4934 -f 4935//4935 4936//4936 4937//4937 -f 4923//4923 4925//4925 4938//4938 -f 4938//4938 4925//4925 4935//4935 -f 4938//4938 4935//4935 4939//4939 -f 4939//4939 4935//4935 4937//4937 -f 4939//4939 4937//4937 4940//4940 -f 4940//4940 4941//4941 4939//4939 -f 4939//4939 4941//4941 4942//4942 -f 4939//4939 4942//4942 4938//4938 -f 4938//4938 4942//4942 4905//4905 -f 4938//4938 4905//4905 4923//4923 -f 4923//4923 4905//4905 4907//4907 -f 4923//4923 4907//4907 4924//4924 -f 4924//4924 4907//4907 4943//4943 -f 4924//4924 4943//4943 4944//4944 -f 4940//4940 4945//4945 4941//4941 -f 4941//4941 4945//4945 4946//4946 -f 4941//4941 4946//4946 4947//4947 -f 4906//4906 4905//4905 4908//4908 -f 4908//4908 4905//4905 4942//4942 -f 4908//4908 4942//4942 4948//4948 -f 4948//4948 4942//4942 4941//4941 -f 4948//4948 4941//4941 4949//4949 -f 4949//4949 4941//4941 4947//4947 -f 4949//4949 4947//4947 4950//4950 -f 4909//4909 4908//4908 4928//4928 -f 4928//4928 4908//4908 4948//4948 -f 4928//4928 4948//4948 4927//4927 -f 4927//4927 4948//4948 4949//4949 -f 4927//4927 4949//4949 4926//4926 -f 4926//4926 4949//4949 4950//4950 -f 4926//4926 4950//4950 4951//4951 -f 4951//4951 4952//4952 4926//4926 -f 4926//4926 4952//4952 4953//4953 -f 4926//4926 4953//4953 4915//4915 -f 4915//4915 4953//4953 4954//4954 -f 4915//4915 4954//4954 4914//4914 -f 4914//4914 4954//4954 4955//4955 -f 4914//4914 4955//4955 4913//4913 -f 4913//4913 4955//4955 4956//4956 -f 4952//4952 4957//4957 4953//4953 -f 4953//4953 4957//4957 4934//4934 -f 4953//4953 4934//4934 4954//4954 -f 4954//4954 4934//4934 4929//4929 -f 4954//4954 4929//4929 4955//4955 -f 4955//4955 4929//4929 4931//4931 -f 4955//4955 4931//4931 4956//4956 -f 4956//4956 4931//4931 4918//4918 -f 4957//4957 4958//4958 4934//4934 -f 4934//4934 4958//4958 4959//4959 -f 4934//4934 4959//4959 4933//4933 -f 4933//4933 4959//4959 4960//4960 -f 4933//4933 4960//4960 4932//4932 -f 4932//4932 4960//4960 4961//4961 -f 4932//4932 4961//4961 4962//4962 -f 4918//4918 4931//4931 4916//4916 -f 4916//4916 4931//4931 4930//4930 -f 4916//4916 4930//4930 4963//4963 -f 4963//4963 4930//4930 4932//4932 -f 4963//4963 4932//4932 4964//4964 -f 4964//4964 4932//4932 4962//4962 -f 4964//4964 4962//4962 4965//4965 -f 4917//4917 4916//4916 4919//4919 -f 4919//4919 4916//4916 4963//4963 -f 4919//4919 4963//4963 4966//4966 -f 4966//4966 4963//4963 4964//4964 -f 4966//4966 4964//4964 4904//4904 -f 4904//4904 4964//4964 4965//4965 -f 4904//4904 4965//4965 4902//4902 -f 4920//4920 4919//4919 4921//4921 -f 4921//4921 4919//4919 4966//4966 -f 4921//4921 4966//4966 4967//4967 -f 4967//4967 4966//4966 4904//4904 -f 4967//4967 4904//4904 4968//4968 -f 4968//4968 4904//4904 4903//4903 -f 4968//4968 4903//4903 4969//4969 -f 4970//4970 4971//4971 4972//4972 -f 4973//4973 4974//4974 4975//4975 -f 4975//4975 4974//4974 4976//4976 -f 4975//4975 4976//4976 4977//4977 -f 4977//4977 4976//4976 4978//4978 -f 4977//4977 4978//4978 4979//4979 -f 4979//4979 4978//4978 4980//4980 -f 4979//4979 4980//4980 4981//4981 -f 4981//4981 4980//4980 4982//4982 -f 4981//4981 4982//4982 4983//4983 -f 4983//4983 4982//4982 4984//4984 -f 4983//4983 4984//4984 4985//4985 -f 4985//4985 4984//4984 4986//4986 -f 4985//4985 4986//4986 4987//4987 -f 4986//4986 4988//4988 4987//4987 -f 4987//4987 4988//4988 4989//4989 -f 4987//4987 4989//4989 4990//4990 -f 4990//4990 4989//4989 4991//4991 -f 4990//4990 4991//4991 4992//4992 -f 4992//4992 4991//4991 4993//4993 -f 4992//4992 4993//4993 4994//4994 -f 4994//4994 4993//4993 4995//4995 -f 4994//4994 4995//4995 4996//4996 -f 4996//4996 4995//4995 4997//4997 -f 4996//4996 4997//4997 4998//4998 -f 4998//4998 4997//4997 4999//4999 -f 4998//4998 4999//4999 5000//5000 -f 5000//5000 4999//4999 4972//4972 -f 4972//4972 4999//4999 5001//5001 -f 4972//4972 5001//5001 4970//4970 -f 5002//5002 5003//5003 5004//5004 -f 5002//5002 5004//5004 5005//5005 -f 5005//5005 5004//5004 5006//5006 -f 5005//5005 5006//5006 4971//4971 -f 4971//4971 5006//5006 5007//5007 -f 4971//4971 5007//5007 4972//4972 -f 5008//5008 5009//5009 5010//5010 -f 5011//5011 794//794 5012//5012 -f 5012//5012 794//794 5013//5013 -f 5014//5014 5015//5015 5016//5016 -f 5010//5010 5009//5009 5017//5017 -f 5009//5009 5018//5018 5017//5017 -f 5017//5017 5018//5018 5019//5019 -f 5017//5017 5019//5019 5020//5020 -f 5020//5020 5019//5019 5021//5021 -f 5020//5020 5021//5021 5015//5015 -f 5015//5015 5021//5021 5022//5022 -f 5015//5015 5022//5022 5016//5016 -f 5016//5016 5022//5022 5023//5023 -f 5016//5016 5023//5023 5013//5013 -f 5013//5013 5023//5023 5024//5024 -f 5013//5013 5024//5024 5012//5012 -f 5010//5010 5025//5025 5008//5008 -f 5008//5008 5025//5025 5026//5026 -f 5008//5008 5026//5026 5027//5027 -f 5027//5027 5026//5026 5028//5028 -f 5027//5027 5028//5028 5029//5029 -f 5029//5029 5028//5028 5030//5030 -f 5031//5031 5032//5032 5033//5033 -f 5033//5033 5034//5034 5031//5031 -f 5031//5031 5034//5034 5035//5035 -f 5031//5031 5035//5035 5036//5036 -f 5036//5036 5035//5035 5037//5037 -f 5036//5036 5037//5037 5038//5038 -f 5038//5038 5037//5037 5039//5039 -f 5038//5038 5039//5039 5040//5040 -f 5040//5040 5039//5039 5041//5041 -f 5040//5040 5041//5041 5030//5030 -f 5030//5030 5041//5041 5042//5042 -f 5030//5030 5042//5042 5029//5029 -f 5043//5043 5044//5044 5045//5045 -f 5045//5045 5044//5044 5046//5046 -f 5045//5045 5046//5046 5047//5047 -f 5047//5047 5046//5046 5048//5048 -f 5047//5047 5048//5048 5016//5016 -f 5016//5016 5048//5048 5049//5049 -f 5016//5016 5049//5049 5014//5014 -f 5043//5043 5045//5045 5050//5050 -f 5050//5050 5045//5045 5051//5051 -f 5050//5050 5051//5051 5052//5052 -f 5052//5052 5051//5051 5053//5053 -f 5053//5053 5051//5051 5054//5054 -f 5053//5053 5054//5054 5055//5055 -f 5055//5055 5054//5054 5056//5056 -f 5056//5056 5054//5054 806//806 -f 5056//5056 806//806 5057//5057 -f 5057//5057 806//806 5058//5058 -f 5058//5058 806//806 5059//5059 -f 5058//5058 5059//5059 5060//5060 -f 5061//5061 5062//5062 5063//5063 -f 5063//5063 5062//5062 5064//5064 -f 5063//5063 5064//5064 5059//5059 -f 5059//5059 5064//5064 5065//5065 -f 5059//5059 5065//5065 5060//5060 -f 5066//5066 5067//5067 5061//5061 -f 5061//5061 5067//5067 5068//5068 -f 5061//5061 5068//5068 5062//5062 -f 5069//5069 5070//5070 5071//5071 -f 5071//5071 5070//5070 5072//5072 -f 5071//5071 5072//5072 5066//5066 -f 5066//5066 5072//5072 5073//5073 -f 5066//5066 5073//5073 5067//5067 -f 5011//5011 5074//5074 794//794 -f 794//794 5074//5074 5075//5075 -f 794//794 5075//5075 5069//5069 -f 5069//5069 5075//5075 5076//5076 -f 5069//5069 5076//5076 5070//5070 -f 5077//5077 5078//5078 5079//5079 -f 5079//5079 5078//5078 5080//5080 -f 5079//5079 5080//5080 5081//5081 -f 5081//5081 5080//5080 5082//5082 -f 5082//5082 5080//5080 5083//5083 -f 5082//5082 5083//5083 5084//5084 -f 5084//5084 5083//5083 5085//5085 -f 5084//5084 5085//5085 5086//5086 -f 5086//5086 5085//5085 5087//5087 -f 5086//5086 5087//5087 5088//5088 -f 5089//5089 5090//5090 5091//5091 -f 5091//5091 5090//5090 5092//5092 -f 5091//5091 5092//5092 5093//5093 -f 5087//5087 5094//5094 5088//5088 -f 5088//5088 5094//5094 5095//5095 -f 5088//5088 5095//5095 5093//5093 -f 5093//5093 5095//5095 5096//5096 -f 5093//5093 5096//5096 5091//5091 -f 5097//5097 5098//5098 5099//5099 -f 5099//5099 5098//5098 5100//5100 -f 5099//5099 5100//5100 5077//5077 -f 5077//5077 5100//5100 5101//5101 -f 5077//5077 5101//5101 5078//5078 -f 5099//5099 5102//5102 5097//5097 -f 5097//5097 5102//5102 5103//5103 -f 5097//5097 5103//5103 5104//5104 -f 5105//5105 5106//5106 5107//5107 -f 5107//5107 5106//5106 5104//5104 -f 5107//5107 5104//5104 5108//5108 -f 5108//5108 5104//5104 5103//5103 -f 5109//5109 5110//5110 5111//5111 -f 5111//5111 5110//5110 5112//5112 -f 5111//5111 5112//5112 5113//5113 -f 5113//5113 5112//5112 5114//5114 -f 5113//5113 5114//5114 5105//5105 -f 5105//5105 5114//5114 5115//5115 -f 5105//5105 5115//5115 5106//5106 -f 5116//5116 5117//5117 5118//5118 -f 5119//5119 5120//5120 5121//5121 -f 5121//5121 5120//5120 5122//5122 -f 5121//5121 5122//5122 5123//5123 -f 5123//5123 5122//5122 5124//5124 -f 5123//5123 5124//5124 5125//5125 -f 5125//5125 5124//5124 5126//5126 -f 5125//5125 5126//5126 5127//5127 -f 5127//5127 5126//5126 5128//5128 -f 5127//5127 5128//5128 5129//5129 -f 5129//5129 5128//5128 5130//5130 -f 5129//5129 5130//5130 5131//5131 -f 5130//5130 5132//5132 5131//5131 -f 5131//5131 5132//5132 5133//5133 -f 5131//5131 5133//5133 5134//5134 -f 5134//5134 5133//5133 5135//5135 -f 5134//5134 5135//5135 5136//5136 -f 5136//5136 5135//5135 5137//5137 -f 5137//5137 5135//5135 5138//5138 -f 5137//5137 5138//5138 5117//5117 -f 5117//5117 5138//5138 5139//5139 -f 5117//5117 5139//5139 5118//5118 -f 5116//5116 5118//5118 5140//5140 -f 5140//5140 5118//5118 5141//5141 -f 5140//5140 5141//5141 5142//5142 -f 5142//5142 5141//5141 5143//5143 -f 5142//5142 5143//5143 5144//5144 -f 5144//5144 5143//5143 5145//5145 -f 5144//5144 5145//5145 5146//5146 -f 5146//5146 5145//5145 5147//5147 -f 5146//5146 5147//5147 5148//5148 -f 5148//5148 5147//5147 5149//5149 -f 5148//5148 5149//5149 5150//5150 -f 5150//5150 5149//5149 5151//5151 -f 5150//5150 5151//5151 5152//5152 -f 5153//5153 5154//5154 5155//5155 -f 5153//5153 5155//5155 5156//5156 -f 5156//5156 5155//5155 5157//5157 -f 5156//5156 5157//5157 5158//5158 -f 5159//5159 5160//5160 5161//5161 -f 5161//5161 5160//5160 5162//5162 -f 5161//5161 5162//5162 5163//5163 -f 5163//5163 5162//5162 5164//5164 -f 5163//5163 5164//5164 5154//5154 -f 5154//5154 5164//5164 5165//5165 -f 5154//5154 5165//5165 5155//5155 -f 5166//5166 5167//5167 5168//5168 -f 5168//5168 5169//5169 5166//5166 -f 5166//5166 5169//5169 5170//5170 -f 5166//5166 5170//5170 5159//5159 -f 5159//5159 5170//5170 5171//5171 -f 5159//5159 5171//5171 5160//5160 -f 5172//5172 5173//5173 5174//5174 -f 5174//5174 5173//5173 5175//5175 -f 5174//5174 5175//5175 5176//5176 -f 5176//5176 5175//5175 5177//5177 -f 5176//5176 5177//5177 5178//5178 -f 5178//5178 5177//5177 5179//5179 -f 5178//5178 5179//5179 5167//5167 -f 5167//5167 5179//5179 5180//5180 -f 5167//5167 5180//5180 5168//5168 -f 5181//5181 5182//5182 5183//5183 -f 5183//5183 5182//5182 5184//5184 -f 5183//5183 5184//5184 5185//5185 -f 5184//5184 5186//5186 5185//5185 -f 5185//5185 5186//5186 5187//5187 -f 5185//5185 5187//5187 5188//5188 -f 5188//5188 5187//5187 5189//5189 -f 5188//5188 5189//5189 5174//5174 -f 5174//5174 5189//5189 5190//5190 -f 5174//5174 5190//5190 5172//5172 -f 5191//5191 5192//5192 5193//5193 -f 5193//5193 5192//5192 5194//5194 -f 5193//5193 5194//5194 5195//5195 -f 5195//5195 5194//5194 5196//5196 -f 5195//5195 5196//5196 5197//5197 -f 5193//5193 5198//5198 5191//5191 -f 5191//5191 5198//5198 5199//5199 -f 5191//5191 5199//5199 5200//5200 -f 5200//5200 5199//5199 5201//5201 -f 5200//5200 5201//5201 5202//5202 -f 5202//5202 5201//5201 5203//5203 -f 5202//5202 5203//5203 5204//5204 -f 5203//5203 5205//5205 5204//5204 -f 5204//5204 5205//5205 5206//5206 -f 5204//5204 5206//5206 5207//5207 -f 5207//5207 5206//5206 5208//5208 -f 5207//5207 5208//5208 5209//5209 -f 5209//5209 5208//5208 5210//5210 -f 5209//5209 5210//5210 5211//5211 -f 5211//5211 5210//5210 5212//5212 -f 5211//5211 5212//5212 5213//5213 -f 5213//5213 5212//5212 5214//5214 -f 5213//5213 5214//5214 5215//5215 -f 5215//5215 5214//5214 5216//5216 -f 5216//5216 5214//5214 5217//5217 -f 5216//5216 5217//5217 5218//5218 -f 5218//5218 5217//5217 5219//5219 -f 5218//5218 5219//5219 5220//5220 -f 5220//5220 5219//5219 5221//5221 -f 5220//5220 5221//5221 5222//5222 -f 5223//5223 5224//5224 5225//5225 -f 5225//5225 5224//5224 5226//5226 -f 5225//5225 5226//5226 5222//5222 -f 5222//5222 5226//5226 5227//5227 -f 5222//5222 5227//5227 5220//5220 -f 5228//5228 5229//5229 5230//5230 -f 5230//5230 5229//5229 5231//5231 -f 5230//5230 5231//5231 5232//5232 -f 5232//5232 5231//5231 5233//5233 -f 5232//5232 5233//5233 5234//5234 -f 5234//5234 5233//5233 5235//5235 -f 5234//5234 5235//5235 5236//5236 -f 5236//5236 5235//5235 5237//5237 -f 5236//5236 5237//5237 5238//5238 -f 5238//5238 5237//5237 5239//5239 -f 5238//5238 5239//5239 5240//5240 -f 5241//5241 5242//5242 5243//5243 -f 5243//5243 5242//5242 5240//5240 -f 5243//5243 5240//5240 5244//5244 -f 5244//5244 5240//5240 5239//5239 -f 5245//5245 5246//5246 5247//5247 -f 5247//5247 5246//5246 5248//5248 -f 5247//5247 5248//5248 5228//5228 -f 5228//5228 5248//5248 5249//5249 -f 5228//5228 5249//5249 5229//5229 -f 5247//5247 5250//5250 5245//5245 -f 5245//5245 5250//5250 5251//5251 -f 5245//5245 5251//5251 5252//5252 -f 5253//5253 5254//5254 5255//5255 -f 5255//5255 5254//5254 5252//5252 -f 5255//5255 5252//5252 5256//5256 -f 5256//5256 5252//5252 5251//5251 -f 5257//5257 5258//5258 5259//5259 -f 5259//5259 5258//5258 5260//5260 -f 5259//5259 5260//5260 5261//5261 -f 5261//5261 5260//5260 5262//5262 -f 5261//5261 5262//5262 5253//5253 -f 5253//5253 5262//5262 5263//5263 -f 5253//5253 5263//5263 5254//5254 -f 5264//5264 5265//5265 5266//5266 -f 5267//5267 5268//5268 5269//5269 -f 5269//5269 5268//5268 5270//5270 -f 5269//5269 5270//5270 5271//5271 -f 5271//5271 5270//5270 5272//5272 -f 5271//5271 5272//5272 5273//5273 -f 5273//5273 5272//5272 5274//5274 -f 5273//5273 5274//5274 5275//5275 -f 5275//5275 5274//5274 5276//5276 -f 5275//5275 5276//5276 5277//5277 -f 5277//5277 5276//5276 5278//5278 -f 5277//5277 5278//5278 5279//5279 -f 5278//5278 5280//5280 5279//5279 -f 5279//5279 5280//5280 5281//5281 -f 5279//5279 5281//5281 5282//5282 -f 5282//5282 5281//5281 5283//5283 -f 5282//5282 5283//5283 5284//5284 -f 5284//5284 5283//5283 5285//5285 -f 5285//5285 5283//5283 5286//5286 -f 5285//5285 5286//5286 5265//5265 -f 5265//5265 5286//5286 5287//5287 -f 5265//5265 5287//5287 5266//5266 -f 5264//5264 5266//5266 5288//5288 -f 5288//5288 5266//5266 5289//5289 -f 5288//5288 5289//5289 5290//5290 -f 5290//5290 5289//5289 5291//5291 -f 5290//5290 5291//5291 5292//5292 -f 5292//5292 5291//5291 5293//5293 -f 5292//5292 5293//5293 5294//5294 -f 5294//5294 5293//5293 5295//5295 -f 5294//5294 5295//5295 5296//5296 -f 5296//5296 5295//5295 5297//5297 -f 5296//5296 5297//5297 5298//5298 -f 5298//5298 5297//5297 5299//5299 -f 5298//5298 5299//5299 5300//5300 -f 5301//5301 5302//5302 5303//5303 -f 5301//5301 5303//5303 5304//5304 -f 5304//5304 5303//5303 5305//5305 -f 5304//5304 5305//5305 5306//5306 -f 5307//5307 5308//5308 5309//5309 -f 5309//5309 5308//5308 5310//5310 -f 5309//5309 5310//5310 5311//5311 -f 5311//5311 5310//5310 5312//5312 -f 5311//5311 5312//5312 5302//5302 -f 5302//5302 5312//5312 5313//5313 -f 5302//5302 5313//5313 5303//5303 -f 5314//5314 5315//5315 5316//5316 -f 5316//5316 5317//5317 5314//5314 -f 5314//5314 5317//5317 5318//5318 -f 5314//5314 5318//5318 5307//5307 -f 5307//5307 5318//5318 5319//5319 -f 5307//5307 5319//5319 5308//5308 -f 5320//5320 5321//5321 5322//5322 -f 5322//5322 5321//5321 5323//5323 -f 5322//5322 5323//5323 5324//5324 -f 5324//5324 5323//5323 5325//5325 -f 5324//5324 5325//5325 5326//5326 -f 5326//5326 5325//5325 5327//5327 -f 5326//5326 5327//5327 5315//5315 -f 5315//5315 5327//5327 5328//5328 -f 5315//5315 5328//5328 5316//5316 -f 5329//5329 5330//5330 5331//5331 -f 5331//5331 5330//5330 5332//5332 -f 5331//5331 5332//5332 5333//5333 -f 5332//5332 5334//5334 5333//5333 -f 5333//5333 5334//5334 5335//5335 -f 5333//5333 5335//5335 5336//5336 -f 5336//5336 5335//5335 5337//5337 -f 5336//5336 5337//5337 5322//5322 -f 5322//5322 5337//5337 5338//5338 -f 5322//5322 5338//5338 5320//5320 -f 5339//5339 5340//5340 5341//5341 -f 5341//5341 5340//5340 5342//5342 -f 5341//5341 5342//5342 5343//5343 -f 5343//5343 5342//5342 5344//5344 -f 5343//5343 5344//5344 5345//5345 -f 5341//5341 5346//5346 5339//5339 -f 5339//5339 5346//5346 5347//5347 -f 5339//5339 5347//5347 5348//5348 -f 5348//5348 5347//5347 5349//5349 -f 5348//5348 5349//5349 5350//5350 -f 5350//5350 5349//5349 5351//5351 -f 5350//5350 5351//5351 5352//5352 -f 5351//5351 5353//5353 5352//5352 -f 5352//5352 5353//5353 5354//5354 -f 5352//5352 5354//5354 5355//5355 -f 5355//5355 5354//5354 5356//5356 -f 5355//5355 5356//5356 5357//5357 -f 5357//5357 5356//5356 5358//5358 -f 5357//5357 5358//5358 5359//5359 -f 5359//5359 5358//5358 5360//5360 -f 5359//5359 5360//5360 5361//5361 -f 5361//5361 5360//5360 5362//5362 -f 5361//5361 5362//5362 5363//5363 -f 5363//5363 5362//5362 5364//5364 -f 5364//5364 5362//5362 5365//5365 -f 5364//5364 5365//5365 5366//5366 -f 5366//5366 5365//5365 5367//5367 -f 5366//5366 5367//5367 5368//5368 -f 5368//5368 5367//5367 5369//5369 -f 5368//5368 5369//5369 5370//5370 -f 5371//5371 5372//5372 5373//5373 -f 5373//5373 5372//5372 5374//5374 -f 5373//5373 5374//5374 5370//5370 -f 5370//5370 5374//5374 5375//5375 -f 5370//5370 5375//5375 5368//5368 -f 5376//5376 5377//5377 5378//5378 -f 5378//5378 5377//5377 5379//5379 -f 5378//5378 5379//5379 5380//5380 -f 5380//5380 5379//5379 5381//5381 -f 5380//5380 5381//5381 5382//5382 -f 5382//5382 5381//5381 5383//5383 -f 5382//5382 5383//5383 5384//5384 -f 5384//5384 5383//5383 5385//5385 -f 5384//5384 5385//5385 5386//5386 -f 5386//5386 5385//5385 5387//5387 -f 5386//5386 5387//5387 5388//5388 -f 5389//5389 5390//5390 5391//5391 -f 5391//5391 5390//5390 5388//5388 -f 5391//5391 5388//5388 5392//5392 -f 5392//5392 5388//5388 5387//5387 -f 5393//5393 5394//5394 5395//5395 -f 5395//5395 5394//5394 5396//5396 -f 5395//5395 5396//5396 5376//5376 -f 5376//5376 5396//5396 5397//5397 -f 5376//5376 5397//5397 5377//5377 -f 5395//5395 5398//5398 5393//5393 -f 5393//5393 5398//5398 5399//5399 -f 5393//5393 5399//5399 5400//5400 -f 5401//5401 5402//5402 5403//5403 -f 5403//5403 5402//5402 5400//5400 -f 5403//5403 5400//5400 5404//5404 -f 5404//5404 5400//5400 5399//5399 -f 5405//5405 5406//5406 5407//5407 -f 5407//5407 5406//5406 5408//5408 -f 5407//5407 5408//5408 5409//5409 -f 5409//5409 5408//5408 5410//5410 -f 5409//5409 5410//5410 5401//5401 -f 5401//5401 5410//5410 5411//5411 -f 5401//5401 5411//5411 5402//5402 -f 5412//5412 5413//5413 5414//5414 -f 5415//5415 5416//5416 5417//5417 -f 5417//5417 5416//5416 5418//5418 -f 5417//5417 5418//5418 5419//5419 -f 5419//5419 5418//5418 5420//5420 -f 5419//5419 5420//5420 5421//5421 -f 5421//5421 5420//5420 5422//5422 -f 5421//5421 5422//5422 5423//5423 -f 5423//5423 5422//5422 5424//5424 -f 5423//5423 5424//5424 5425//5425 -f 5425//5425 5424//5424 5426//5426 -f 5425//5425 5426//5426 5427//5427 -f 5426//5426 5428//5428 5427//5427 -f 5427//5427 5428//5428 5429//5429 -f 5427//5427 5429//5429 5430//5430 -f 5430//5430 5429//5429 5431//5431 -f 5430//5430 5431//5431 5432//5432 -f 5432//5432 5431//5431 5433//5433 -f 5433//5433 5431//5431 5434//5434 -f 5433//5433 5434//5434 5413//5413 -f 5413//5413 5434//5434 5435//5435 -f 5413//5413 5435//5435 5414//5414 -f 5412//5412 5414//5414 5436//5436 -f 5436//5436 5414//5414 5437//5437 -f 5436//5436 5437//5437 5438//5438 -f 5438//5438 5437//5437 5439//5439 -f 5438//5438 5439//5439 5440//5440 -f 5440//5440 5439//5439 5441//5441 -f 5440//5440 5441//5441 5442//5442 -f 5442//5442 5441//5441 5443//5443 -f 5442//5442 5443//5443 5444//5444 -f 5444//5444 5443//5443 5445//5445 -f 5444//5444 5445//5445 5446//5446 -f 5446//5446 5445//5445 5447//5447 -f 5446//5446 5447//5447 5448//5448 -f 5449//5449 5450//5450 5451//5451 -f 5449//5449 5451//5451 5452//5452 -f 5452//5452 5451//5451 5453//5453 -f 5452//5452 5453//5453 5454//5454 -f 5455//5455 5456//5456 5457//5457 -f 5457//5457 5456//5456 5458//5458 -f 5457//5457 5458//5458 5459//5459 -f 5459//5459 5458//5458 5460//5460 -f 5459//5459 5460//5460 5450//5450 -f 5450//5450 5460//5460 5461//5461 -f 5450//5450 5461//5461 5451//5451 -f 5462//5462 5463//5463 5464//5464 -f 5464//5464 5465//5465 5462//5462 -f 5462//5462 5465//5465 5466//5466 -f 5462//5462 5466//5466 5455//5455 -f 5455//5455 5466//5466 5467//5467 -f 5455//5455 5467//5467 5456//5456 -f 5468//5468 5469//5469 5470//5470 -f 5470//5470 5469//5469 5471//5471 -f 5470//5470 5471//5471 5472//5472 -f 5472//5472 5471//5471 5473//5473 -f 5472//5472 5473//5473 5474//5474 -f 5474//5474 5473//5473 5475//5475 -f 5474//5474 5475//5475 5463//5463 -f 5463//5463 5475//5475 5476//5476 -f 5463//5463 5476//5476 5464//5464 -f 5477//5477 5478//5478 5479//5479 -f 5479//5479 5478//5478 5480//5480 -f 5479//5479 5480//5480 5481//5481 -f 5480//5480 5482//5482 5481//5481 -f 5481//5481 5482//5482 5483//5483 -f 5481//5481 5483//5483 5484//5484 -f 5484//5484 5483//5483 5485//5485 -f 5484//5484 5485//5485 5470//5470 -f 5470//5470 5485//5485 5486//5486 -f 5470//5470 5486//5486 5468//5468 -f 5487//5487 5488//5488 5489//5489 -f 5490//5490 5491//5491 5492//5492 -f 5492//5492 5491//5491 5493//5493 -f 5492//5492 5493//5493 5494//5494 -f 5494//5494 5493//5493 5495//5495 -f 5494//5494 5495//5495 5496//5496 -f 5492//5492 5497//5497 5490//5490 -f 5490//5490 5497//5497 5498//5498 -f 5490//5490 5498//5498 5499//5499 -f 5499//5499 5498//5498 5500//5500 -f 5499//5499 5500//5500 5501//5501 -f 5501//5501 5500//5500 5502//5502 -f 5501//5501 5502//5502 5503//5503 -f 5502//5502 5504//5504 5503//5503 -f 5503//5503 5504//5504 5505//5505 -f 5503//5503 5505//5505 5506//5506 -f 5506//5506 5505//5505 5507//5507 -f 5506//5506 5507//5507 5508//5508 -f 5508//5508 5507//5507 5509//5509 -f 5508//5508 5509//5509 5510//5510 -f 5510//5510 5509//5509 5511//5511 -f 5510//5510 5511//5511 5512//5512 -f 5512//5512 5511//5511 5513//5513 -f 5512//5512 5513//5513 5514//5514 -f 5514//5514 5513//5513 5515//5515 -f 5515//5515 5513//5513 5516//5516 -f 5516//5516 5513//5513 5517//5517 -f 5516//5516 5517//5517 5489//5489 -f 5489//5489 5517//5517 5518//5518 -f 5489//5489 5518//5518 5487//5487 -f 5519//5519 5520//5520 5521//5521 -f 5521//5521 5522//5522 5519//5519 -f 5519//5519 5522//5522 5523//5523 -f 5519//5519 5523//5523 5488//5488 -f 5488//5488 5523//5523 5524//5524 -f 5488//5488 5524//5524 5489//5489 -f 5525//5525 5526//5526 5527//5527 -f 5527//5527 5526//5526 5528//5528 -f 5527//5527 5528//5528 5529//5529 -f 5530//5530 5531//5531 5532//5532 -f 5532//5532 5531//5531 5533//5533 -f 5532//5532 5533//5533 5534//5534 -f 5534//5534 5533//5533 5535//5535 -f 5534//5534 5535//5535 5536//5536 -f 5536//5536 5535//5535 5529//5529 -f 5536//5536 5529//5529 5537//5537 -f 5537//5537 5529//5529 5528//5528 -f 5538//5538 5539//5539 5540//5540 -f 5540//5540 5539//5539 5541//5541 -f 5540//5540 5541//5541 5542//5542 -f 5542//5542 5541//5541 5543//5543 -f 5542//5542 5543//5543 5544//5544 -f 5544//5544 5543//5543 5545//5545 -f 5544//5544 5545//5545 5546//5546 -f 5546//5546 5545//5545 5547//5547 -f 5546//5546 5547//5547 5525//5525 -f 5525//5525 5547//5547 5548//5548 -f 5525//5525 5548//5548 5526//5526 -f 5540//5540 5549//5549 5538//5538 -f 5538//5538 5549//5549 5550//5550 -f 5538//5538 5550//5550 5551//5551 -f 5551//5551 5550//5550 5552//5552 -f 5551//5551 5552//5552 5553//5553 -f 5553//5553 5552//5552 5554//5554 -f 5553//5553 5554//5554 5555//5555 -f 5555//5555 5554//5554 5556//5556 -f 5555//5555 5556//5556 5557//5557 -f 5557//5557 5556//5556 5558//5558 -f 5556//5556 5559//5559 5558//5558 -f 5558//5558 5559//5559 5560//5560 -f 5558//5558 5560//5560 5561//5561 -f 5561//5561 5560//5560 5562//5562 -f 5561//5561 5562//5562 5563//5563 -f 5564//5564 5565//5565 5566//5566 -f 5567//5567 5568//5568 5569//5569 -f 5570//5570 5571//5571 5572//5572 -f 5572//5572 5571//5571 5573//5573 -f 5572//5572 5573//5573 5574//5574 -f 5574//5574 5573//5573 5575//5575 -f 5574//5574 5575//5575 5576//5576 -f 5576//5576 5575//5575 5577//5577 -f 5576//5576 5577//5577 5578//5578 -f 5578//5578 5577//5577 5579//5579 -f 5578//5578 5579//5579 5580//5580 -f 5580//5580 5579//5579 5581//5581 -f 5580//5580 5581//5581 5569//5569 -f 5569//5569 5581//5581 5582//5582 -f 5569//5569 5582//5582 5567//5567 -f 5568//5568 5567//5567 5583//5583 -f 5583//5583 5567//5567 5584//5584 -f 5583//5583 5584//5584 5585//5585 -f 5585//5585 5584//5584 5586//5586 -f 5585//5585 5586//5586 5565//5565 -f 5565//5565 5586//5586 5587//5587 -f 5565//5565 5587//5587 5566//5566 -f 5564//5564 5566//5566 5588//5588 -f 5588//5588 5566//5566 5589//5589 -f 5588//5588 5589//5589 5590//5590 -f 5590//5590 5589//5589 5591//5591 -f 5590//5590 5591//5591 5592//5592 -f 5592//5592 5591//5591 5593//5593 -f 5592//5592 5593//5593 5594//5594 -f 5594//5594 5593//5593 5595//5595 -f 5595//5595 5593//5593 5596//5596 -f 5595//5595 5596//5596 5597//5597 -f 5597//5597 5596//5596 5598//5598 -f 5597//5597 5598//5598 5599//5599 -f 5599//5599 5598//5598 5600//5600 -f 5599//5599 5600//5600 5601//5601 -f 5602//5602 5603//5603 5604//5604 -f 5602//5602 5604//5604 5605//5605 -f 5605//5605 5604//5604 5606//5606 -f 5605//5605 5606//5606 5607//5607 -f 5608//5608 5609//5609 5610//5610 -f 5610//5610 5611//5611 5608//5608 -f 5608//5608 5611//5611 5612//5612 -f 5608//5608 5612//5612 5613//5613 -f 5613//5613 5612//5612 5614//5614 -f 5613//5613 5614//5614 5603//5603 -f 5603//5603 5614//5614 5615//5615 -f 5603//5603 5615//5615 5604//5604 -f 5616//5616 5617//5617 5618//5618 -f 5618//5618 5619//5619 5616//5616 -f 5616//5616 5619//5619 5620//5620 -f 5616//5616 5620//5620 5609//5609 -f 5609//5609 5620//5620 5621//5621 -f 5609//5609 5621//5621 5610//5610 -f 5622//5622 5623//5623 5624//5624 -f 5624//5624 5623//5623 5625//5625 -f 5624//5624 5625//5625 5626//5626 -f 5625//5625 5627//5627 5626//5626 -f 5626//5626 5627//5627 5628//5628 -f 5626//5626 5628//5628 5629//5629 -f 5629//5629 5628//5628 5630//5630 -f 5629//5629 5630//5630 5617//5617 -f 5617//5617 5630//5630 5631//5631 -f 5617//5617 5631//5631 5618//5618 -f 5632//5632 5633//5633 5634//5634 -f 5632//5632 5634//5634 5624//5624 -f 5624//5624 5634//5634 5635//5635 -f 5624//5624 5635//5635 5622//5622 -f 5636//5636 5637//5637 5638//5638 -f 5638//5638 5637//5637 5639//5639 -f 5638//5638 5639//5639 5633//5633 -f 5633//5633 5639//5639 5640//5640 -f 5633//5633 5640//5640 5634//5634 -f 5641//5641 5642//5642 5643//5643 -f 5643//5643 5642//5642 5644//5644 -f 5643//5643 5644//5644 5645//5645 -f 5645//5645 5644//5644 5646//5646 -f 5645//5645 5646//5646 5647//5647 -f 5647//5647 5646//5646 5648//5648 -f 5647//5647 5648//5648 5649//5649 -f 5648//5648 5650//5650 5649//5649 -f 5649//5649 5650//5650 5651//5651 -f 5649//5649 5651//5651 5652//5652 -f 5652//5652 5651//5651 5653//5653 -f 5652//5652 5653//5653 5654//5654 -f 5654//5654 5653//5653 5655//5655 -f 5653//5653 5656//5656 5655//5655 -f 5655//5655 5656//5656 5657//5657 -f 5655//5655 5657//5657 5658//5658 -f 5658//5658 5657//5657 5659//5659 -f 5658//5658 5659//5659 5660//5660 -f 5660//5660 5659//5659 5661//5661 -f 5660//5660 5661//5661 5662//5662 -f 5662//5662 5661//5661 5663//5663 -f 5662//5662 5663//5663 5664//5664 -f 5664//5664 5663//5663 5665//5665 -f 5664//5664 5665//5665 5666//5666 -f 5666//5666 5665//5665 5667//5667 -f 5667//5667 5665//5665 5668//5668 -f 5667//5667 5668//5668 5669//5669 -f 5669//5669 5668//5668 5670//5670 -f 5669//5669 5670//5670 5671//5671 -f 5672//5672 5673//5673 5674//5674 -f 5670//5670 5675//5675 5671//5671 -f 5671//5671 5675//5675 5676//5676 -f 5671//5671 5676//5676 5677//5677 -f 5677//5677 5676//5676 5672//5672 -f 5677//5677 5672//5672 5678//5678 -f 5678//5678 5672//5672 5674//5674 -f 5679//5679 5680//5680 5681//5681 -f 5679//5679 5681//5681 5682//5682 -f 5681//5681 5683//5683 5682//5682 -f 5682//5682 5683//5683 5684//5684 -f 5682//5682 5684//5684 5685//5685 -f 5685//5685 5684//5684 5686//5686 -f 5685//5685 5686//5686 5687//5687 -f 5687//5687 5686//5686 5688//5688 -f 5687//5687 5688//5688 5689//5689 -f 5689//5689 5688//5688 5690//5690 -f 5689//5689 5690//5690 5691//5691 -f 5691//5691 5690//5690 5692//5692 -f 5691//5691 5692//5692 5693//5693 -f 5693//5693 5692//5692 5694//5694 -f 5693//5693 5694//5694 5695//5695 -f 5696//5696 5697//5697 5698//5698 -f 5698//5698 5697//5697 5695//5695 -f 5698//5698 5695//5695 5699//5699 -f 5699//5699 5695//5695 5694//5694 -f 5680//5680 5679//5679 5700//5700 -f 5700//5700 5679//5679 5701//5701 -f 5700//5700 5701//5701 5702//5702 -f 5702//5702 5701//5701 5703//5703 -f 5702//5702 5703//5703 5704//5704 -f 5704//5704 5703//5703 5705//5705 -f 5704//5704 5705//5705 5706//5706 -f 5706//5706 5705//5705 5707//5707 -f 5706//5706 5707//5707 5708//5708 -f 5709//5709 5710//5710 5711//5711 -f 5711//5711 5710//5710 5708//5708 -f 5711//5711 5708//5708 5712//5712 -f 5712//5712 5708//5708 5707//5707 -f 5033//5033 5032//5032 5713//5713 -f 5713//5713 5032//5032 5714//5714 -f 5715//5715 5716//5716 5717//5717 -f 5715//5715 5717//5717 5718//5718 -f 5718//5718 5717//5717 5719//5719 -f 5718//5718 5719//5719 5720//5720 -f 5720//5720 5719//5719 5721//5721 -f 5720//5720 5721//5721 5722//5722 -f 5722//5722 5721//5721 5723//5723 -f 5722//5722 5723//5723 5724//5724 -f 5724//5724 5723//5723 5725//5725 -f 5724//5724 5725//5725 5726//5726 -f 5726//5726 5725//5725 5727//5727 -f 5726//5726 5727//5727 5728//5728 -f 5728//5728 5727//5727 5729//5729 -f 5728//5728 5729//5729 5730//5730 -f 5730//5730 5729//5729 5731//5731 -f 5730//5730 5731//5731 5714//5714 -f 5714//5714 5731//5731 5732//5732 -f 5714//5714 5732//5732 5713//5713 -f 5716//5716 5715//5715 5733//5733 -f 5733//5733 5715//5715 5734//5734 -f 5733//5733 5734//5734 5735//5735 -f 5734//5734 5736//5736 5735//5735 -f 5735//5735 5736//5736 5737//5737 -f 5735//5735 5737//5737 5738//5738 -f 5738//5738 5737//5737 5739//5739 -f 5740//5740 5741//5741 5739//5739 -f 5739//5739 5741//5741 5742//5742 -f 5739//5739 5742//5742 5738//5738 -f 5739//5739 5743//5743 5740//5740 -f 5740//5740 5743//5743 5744//5744 -f 5740//5740 5744//5744 5745//5745 -f 5745//5745 5744//5744 5090//5090 -f 5745//5745 5090//5090 5089//5089 -f 5110//5110 5109//5109 5746//5746 -f 5746//5746 5109//5109 5747//5747 -f 5746//5746 5747//5747 5748//5748 -f 5748//5748 5747//5747 5749//5749 -f 5748//5748 5749//5749 5750//5750 -f 5750//5750 5749//5749 5751//5751 -f 5750//5750 5751//5751 5752//5752 -f 5752//5752 5751//5751 5753//5753 -f 5754//5754 5755//5755 5756//5756 -f 5756//5756 5755//5755 5757//5757 -f 5756//5756 5757//5757 5758//5758 -f 5753//5753 5751//5751 5759//5759 -f 5759//5759 5751//5751 5760//5760 -f 5759//5759 5760//5760 5754//5754 -f 5754//5754 5760//5760 5761//5761 -f 5754//5754 5761//5761 5755//5755 -f 5758//5758 5757//5757 5762//5762 -f 5762//5762 5757//5757 5763//5763 -f 5762//5762 5763//5763 5764//5764 -f 5764//5764 5763//5763 5765//5765 -f 5765//5765 5763//5763 5766//5766 -f 5765//5765 5766//5766 5767//5767 -f 5767//5767 5766//5766 5768//5768 -f 5767//5767 5768//5768 5769//5769 -f 5769//5769 5768//5768 5770//5770 -f 5769//5769 5770//5770 5771//5771 -f 5770//5770 5772//5772 5771//5771 -f 5771//5771 5772//5772 5773//5773 -f 5771//5771 5773//5773 5774//5774 -f 5774//5774 5773//5773 5775//5775 -f 5774//5774 5775//5775 5776//5776 -f 5775//5775 5777//5777 5776//5776 -f 5776//5776 5777//5777 5778//5778 -f 5776//5776 5778//5778 5779//5779 -f 5779//5779 5778//5778 5780//5780 -f 5779//5779 5780//5780 5781//5781 -f 5781//5781 5780//5780 5120//5120 -f 5781//5781 5120//5120 5119//5119 -f 5782//5782 5783//5783 5784//5784 -f 5784//5784 5783//5783 5785//5785 -f 5784//5784 5785//5785 5786//5786 -f 5786//5786 5785//5785 5787//5787 -f 5786//5786 5787//5787 5788//5788 -f 5788//5788 5787//5787 5789//5789 -f 5788//5788 5789//5789 5152//5152 -f 5152//5152 5789//5789 5790//5790 -f 5152//5152 5790//5790 5150//5150 -f 5782//5782 5791//5791 5783//5783 -f 5783//5783 5791//5791 5792//5792 -f 5783//5783 5792//5792 5793//5793 -f 5793//5793 5792//5792 5794//5794 -f 5793//5793 5794//5794 5795//5795 -f 5795//5795 5794//5794 5796//5796 -f 5796//5796 5794//5794 5797//5797 -f 5796//5796 5797//5797 5798//5798 -f 5798//5798 5797//5797 5799//5799 -f 5798//5798 5799//5799 5800//5800 -f 5800//5800 5799//5799 5801//5801 -f 5800//5800 5801//5801 5802//5802 -f 5802//5802 5801//5801 5803//5803 -f 5802//5802 5803//5803 5804//5804 -f 5804//5804 5803//5803 5805//5805 -f 5804//5804 5805//5805 5806//5806 -f 5806//5806 5805//5805 5807//5807 -f 5806//5806 5807//5807 5808//5808 -f 5807//5807 5809//5809 5808//5808 -f 5808//5808 5809//5809 5810//5810 -f 5808//5808 5810//5810 5811//5811 -f 5811//5811 5810//5810 5812//5812 -f 5811//5811 5812//5812 5813//5813 -f 5813//5813 5812//5812 5814//5814 -f 5813//5813 5814//5814 5158//5158 -f 5158//5158 5814//5814 5815//5815 -f 5158//5158 5815//5815 5156//5156 -f 5816//5816 5817//5817 5818//5818 -f 5182//5182 5181//5181 5819//5819 -f 5819//5819 5181//5181 5820//5820 -f 5819//5819 5820//5820 5821//5821 -f 5821//5821 5820//5820 5822//5822 -f 5821//5821 5822//5822 5823//5823 -f 5823//5823 5822//5822 5824//5824 -f 5823//5823 5824//5824 5825//5825 -f 5824//5824 5826//5826 5825//5825 -f 5825//5825 5826//5826 5827//5827 -f 5825//5825 5827//5827 5828//5828 -f 5828//5828 5827//5827 5829//5829 -f 5828//5828 5829//5829 5830//5830 -f 5830//5830 5829//5829 5831//5831 -f 5830//5830 5831//5831 5817//5817 -f 5817//5817 5831//5831 5832//5832 -f 5817//5817 5832//5832 5818//5818 -f 5816//5816 5818//5818 5833//5833 -f 5833//5833 5818//5818 5834//5834 -f 5833//5833 5834//5834 5835//5835 -f 5835//5835 5834//5834 5836//5836 -f 5835//5835 5836//5836 5837//5837 -f 5837//5837 5836//5836 5838//5838 -f 5837//5837 5838//5838 5839//5839 -f 5838//5838 5840//5840 5839//5839 -f 5839//5839 5840//5840 5841//5841 -f 5839//5839 5841//5841 5842//5842 -f 5842//5842 5841//5841 5843//5843 -f 5197//5197 5196//5196 5844//5844 -f 5844//5844 5196//5196 5845//5845 -f 5844//5844 5845//5845 5846//5846 -f 5846//5846 5845//5845 5847//5847 -f 5846//5846 5847//5847 5848//5848 -f 5848//5848 5847//5847 5849//5849 -f 5848//5848 5849//5849 5843//5843 -f 5843//5843 5849//5849 5850//5850 -f 5843//5843 5850//5850 5842//5842 -f 5851//5851 5852//5852 5853//5853 -f 5853//5853 5852//5852 5854//5854 -f 5853//5853 5854//5854 5855//5855 -f 5855//5855 5854//5854 5224//5224 -f 5855//5855 5224//5224 5223//5223 -f 5853//5853 5856//5856 5851//5851 -f 5851//5851 5856//5856 5857//5857 -f 5851//5851 5857//5857 5858//5858 -f 5858//5858 5857//5857 5859//5859 -f 5858//5858 5859//5859 5860//5860 -f 5860//5860 5859//5859 5861//5861 -f 5860//5860 5861//5861 5862//5862 -f 5862//5862 5861//5861 5863//5863 -f 5862//5862 5863//5863 5864//5864 -f 5864//5864 5863//5863 5865//5865 -f 5863//5863 5866//5866 5865//5865 -f 5865//5865 5866//5866 5867//5867 -f 5865//5865 5867//5867 5868//5868 -f 5868//5868 5867//5867 5869//5869 -f 5868//5868 5869//5869 5870//5870 -f 5870//5870 5869//5869 5871//5871 -f 5870//5870 5871//5871 5872//5872 -f 5872//5872 5871//5871 5873//5873 -f 5872//5872 5873//5873 5874//5874 -f 5874//5874 5873//5873 5875//5875 -f 5874//5874 5875//5875 5876//5876 -f 5876//5876 5875//5875 5877//5877 -f 5876//5876 5877//5877 5878//5878 -f 5878//5878 5877//5877 5879//5879 -f 5878//5878 5879//5879 5880//5880 -f 5880//5880 5879//5879 5881//5881 -f 5880//5880 5881//5881 5882//5882 -f 5882//5882 5881//5881 5883//5883 -f 5882//5882 5883//5883 5884//5884 -f 5884//5884 5883//5883 5885//5885 -f 5884//5884 5885//5885 5886//5886 -f 5886//5886 5885//5885 5242//5242 -f 5886//5886 5242//5242 5241//5241 -f 5258//5258 5257//5257 5887//5887 -f 5887//5887 5257//5257 5888//5888 -f 5887//5887 5888//5888 5889//5889 -f 5889//5889 5888//5888 5890//5890 -f 5889//5889 5890//5890 5891//5891 -f 5891//5891 5890//5890 5892//5892 -f 5891//5891 5892//5892 5893//5893 -f 5893//5893 5892//5892 5894//5894 -f 5895//5895 5896//5896 5897//5897 -f 5897//5897 5896//5896 5898//5898 -f 5897//5897 5898//5898 5899//5899 -f 5894//5894 5892//5892 5900//5900 -f 5900//5900 5892//5892 5901//5901 -f 5900//5900 5901//5901 5895//5895 -f 5895//5895 5901//5901 5902//5902 -f 5895//5895 5902//5902 5896//5896 -f 5899//5899 5898//5898 5903//5903 -f 5903//5903 5898//5898 5904//5904 -f 5903//5903 5904//5904 5905//5905 -f 5905//5905 5904//5904 5906//5906 -f 5906//5906 5904//5904 5907//5907 -f 5906//5906 5907//5907 5908//5908 -f 5908//5908 5907//5907 5909//5909 -f 5908//5908 5909//5909 5910//5910 -f 5910//5910 5909//5909 5911//5911 -f 5910//5910 5911//5911 5912//5912 -f 5911//5911 5913//5913 5912//5912 -f 5912//5912 5913//5913 5914//5914 -f 5912//5912 5914//5914 5915//5915 -f 5915//5915 5914//5914 5916//5916 -f 5915//5915 5916//5916 5917//5917 -f 5916//5916 5918//5918 5917//5917 -f 5917//5917 5918//5918 5919//5919 -f 5917//5917 5919//5919 5920//5920 -f 5920//5920 5919//5919 5921//5921 -f 5920//5920 5921//5921 5922//5922 -f 5922//5922 5921//5921 5268//5268 -f 5922//5922 5268//5268 5267//5267 -f 5923//5923 5924//5924 5925//5925 -f 5925//5925 5924//5924 5926//5926 -f 5925//5925 5926//5926 5927//5927 -f 5927//5927 5926//5926 5928//5928 -f 5927//5927 5928//5928 5929//5929 -f 5929//5929 5928//5928 5930//5930 -f 5929//5929 5930//5930 5300//5300 -f 5300//5300 5930//5930 5931//5931 -f 5300//5300 5931//5931 5298//5298 -f 5923//5923 5932//5932 5924//5924 -f 5924//5924 5932//5932 5933//5933 -f 5924//5924 5933//5933 5934//5934 -f 5934//5934 5933//5933 5935//5935 -f 5934//5934 5935//5935 5936//5936 -f 5936//5936 5935//5935 5937//5937 -f 5937//5937 5935//5935 5938//5938 -f 5937//5937 5938//5938 5939//5939 -f 5939//5939 5938//5938 5940//5940 -f 5939//5939 5940//5940 5941//5941 -f 5941//5941 5940//5940 5942//5942 -f 5941//5941 5942//5942 5943//5943 -f 5943//5943 5942//5942 5944//5944 -f 5943//5943 5944//5944 5945//5945 -f 5945//5945 5944//5944 5946//5946 -f 5945//5945 5946//5946 5947//5947 -f 5947//5947 5946//5946 5948//5948 -f 5947//5947 5948//5948 5949//5949 -f 5948//5948 5950//5950 5949//5949 -f 5949//5949 5950//5950 5951//5951 -f 5949//5949 5951//5951 5952//5952 -f 5952//5952 5951//5951 5953//5953 -f 5952//5952 5953//5953 5954//5954 -f 5954//5954 5953//5953 5955//5955 -f 5954//5954 5955//5955 5306//5306 -f 5306//5306 5955//5955 5956//5956 -f 5306//5306 5956//5956 5304//5304 -f 5957//5957 5958//5958 5959//5959 -f 5330//5330 5329//5329 5960//5960 -f 5960//5960 5329//5329 5961//5961 -f 5960//5960 5961//5961 5962//5962 -f 5962//5962 5961//5961 5963//5963 -f 5962//5962 5963//5963 5964//5964 -f 5964//5964 5963//5963 5965//5965 -f 5964//5964 5965//5965 5966//5966 -f 5965//5965 5967//5967 5966//5966 -f 5966//5966 5967//5967 5968//5968 -f 5966//5966 5968//5968 5969//5969 -f 5969//5969 5968//5968 5970//5970 -f 5969//5969 5970//5970 5971//5971 -f 5971//5971 5970//5970 5972//5972 -f 5971//5971 5972//5972 5958//5958 -f 5958//5958 5972//5972 5973//5973 -f 5958//5958 5973//5973 5959//5959 -f 5957//5957 5959//5959 5974//5974 -f 5974//5974 5959//5959 5975//5975 -f 5974//5974 5975//5975 5976//5976 -f 5976//5976 5975//5975 5977//5977 -f 5976//5976 5977//5977 5978//5978 -f 5978//5978 5977//5977 5979//5979 -f 5978//5978 5979//5979 5980//5980 -f 5979//5979 5981//5981 5980//5980 -f 5980//5980 5981//5981 5982//5982 -f 5980//5980 5982//5982 5983//5983 -f 5983//5983 5982//5982 5984//5984 -f 5345//5345 5344//5344 5985//5985 -f 5985//5985 5344//5344 5986//5986 -f 5985//5985 5986//5986 5987//5987 -f 5987//5987 5986//5986 5988//5988 -f 5987//5987 5988//5988 5989//5989 -f 5989//5989 5988//5988 5990//5990 -f 5989//5989 5990//5990 5984//5984 -f 5984//5984 5990//5990 5991//5991 -f 5984//5984 5991//5991 5983//5983 -f 5992//5992 5993//5993 5994//5994 -f 5994//5994 5993//5993 5995//5995 -f 5994//5994 5995//5995 5996//5996 -f 5996//5996 5995//5995 5372//5372 -f 5996//5996 5372//5372 5371//5371 -f 5994//5994 5997//5997 5992//5992 -f 5992//5992 5997//5997 5998//5998 -f 5992//5992 5998//5998 5999//5999 -f 5999//5999 5998//5998 6000//6000 -f 5999//5999 6000//6000 6001//6001 -f 6001//6001 6000//6000 6002//6002 -f 6001//6001 6002//6002 6003//6003 -f 6003//6003 6002//6002 6004//6004 -f 6003//6003 6004//6004 6005//6005 -f 6005//6005 6004//6004 6006//6006 -f 6004//6004 6007//6007 6006//6006 -f 6006//6006 6007//6007 6008//6008 -f 6006//6006 6008//6008 6009//6009 -f 6009//6009 6008//6008 6010//6010 -f 6009//6009 6010//6010 6011//6011 -f 6011//6011 6010//6010 6012//6012 -f 6011//6011 6012//6012 6013//6013 -f 6013//6013 6012//6012 6014//6014 -f 6013//6013 6014//6014 6015//6015 -f 6015//6015 6014//6014 6016//6016 -f 6015//6015 6016//6016 6017//6017 -f 6017//6017 6016//6016 6018//6018 -f 6017//6017 6018//6018 6019//6019 -f 6019//6019 6018//6018 6020//6020 -f 6019//6019 6020//6020 6021//6021 -f 6021//6021 6020//6020 6022//6022 -f 6021//6021 6022//6022 6023//6023 -f 6023//6023 6022//6022 6024//6024 -f 6023//6023 6024//6024 6025//6025 -f 6025//6025 6024//6024 6026//6026 -f 6025//6025 6026//6026 6027//6027 -f 6027//6027 6026//6026 5390//5390 -f 6027//6027 5390//5390 5389//5389 -f 5406//5406 5405//5405 6028//6028 -f 6028//6028 5405//5405 6029//6029 -f 6028//6028 6029//6029 6030//6030 -f 6030//6030 6029//6029 6031//6031 -f 6030//6030 6031//6031 6032//6032 -f 6032//6032 6031//6031 6033//6033 -f 6032//6032 6033//6033 6034//6034 -f 6034//6034 6033//6033 6035//6035 -f 6036//6036 6037//6037 6038//6038 -f 6038//6038 6037//6037 6039//6039 -f 6038//6038 6039//6039 6040//6040 -f 6035//6035 6033//6033 6041//6041 -f 6041//6041 6033//6033 6042//6042 -f 6041//6041 6042//6042 6036//6036 -f 6036//6036 6042//6042 6043//6043 -f 6036//6036 6043//6043 6037//6037 -f 6040//6040 6039//6039 6044//6044 -f 6044//6044 6039//6039 6045//6045 -f 6044//6044 6045//6045 6046//6046 -f 6046//6046 6045//6045 6047//6047 -f 6047//6047 6045//6045 6048//6048 -f 6047//6047 6048//6048 6049//6049 -f 6049//6049 6048//6048 6050//6050 -f 6049//6049 6050//6050 6051//6051 -f 6051//6051 6050//6050 6052//6052 -f 6051//6051 6052//6052 6053//6053 -f 6052//6052 6054//6054 6053//6053 -f 6053//6053 6054//6054 6055//6055 -f 6053//6053 6055//6055 6056//6056 -f 6056//6056 6055//6055 6057//6057 -f 6056//6056 6057//6057 6058//6058 -f 6057//6057 6059//6059 6058//6058 -f 6058//6058 6059//6059 6060//6060 -f 6058//6058 6060//6060 6061//6061 -f 6061//6061 6060//6060 6062//6062 -f 6061//6061 6062//6062 6063//6063 -f 6063//6063 6062//6062 5416//5416 -f 6063//6063 5416//5416 5415//5415 -f 6064//6064 6065//6065 6066//6066 -f 6066//6066 6065//6065 6067//6067 -f 6066//6066 6067//6067 6068//6068 -f 6068//6068 6067//6067 6069//6069 -f 6068//6068 6069//6069 6070//6070 -f 6070//6070 6069//6069 6071//6071 -f 6070//6070 6071//6071 5448//5448 -f 5448//5448 6071//6071 6072//6072 -f 5448//5448 6072//6072 5446//5446 -f 6064//6064 6073//6073 6065//6065 -f 6065//6065 6073//6073 6074//6074 -f 6065//6065 6074//6074 6075//6075 -f 6075//6075 6074//6074 6076//6076 -f 6075//6075 6076//6076 6077//6077 -f 6077//6077 6076//6076 6078//6078 -f 6078//6078 6076//6076 6079//6079 -f 6078//6078 6079//6079 6080//6080 -f 6080//6080 6079//6079 6081//6081 -f 6080//6080 6081//6081 6082//6082 -f 6082//6082 6081//6081 6083//6083 -f 6082//6082 6083//6083 6084//6084 -f 6084//6084 6083//6083 6085//6085 -f 6084//6084 6085//6085 6086//6086 -f 6086//6086 6085//6085 6087//6087 -f 6086//6086 6087//6087 6088//6088 -f 6088//6088 6087//6087 6089//6089 -f 6088//6088 6089//6089 6090//6090 -f 6089//6089 6091//6091 6090//6090 -f 6090//6090 6091//6091 6092//6092 -f 6090//6090 6092//6092 6093//6093 -f 6093//6093 6092//6092 6094//6094 -f 6093//6093 6094//6094 6095//6095 -f 6095//6095 6094//6094 6096//6096 -f 6095//6095 6096//6096 5454//5454 -f 5454//5454 6096//6096 6097//6097 -f 5454//5454 6097//6097 5452//5452 -f 6098//6098 6099//6099 6100//6100 -f 5478//5478 5477//5477 6101//6101 -f 6101//6101 5477//5477 6102//6102 -f 6101//6101 6102//6102 6103//6103 -f 6103//6103 6102//6102 6104//6104 -f 6103//6103 6104//6104 6105//6105 -f 6105//6105 6104//6104 6106//6106 -f 6105//6105 6106//6106 6107//6107 -f 6106//6106 6108//6108 6107//6107 -f 6107//6107 6108//6108 6109//6109 -f 6107//6107 6109//6109 6110//6110 -f 6110//6110 6109//6109 6111//6111 -f 6110//6110 6111//6111 6112//6112 -f 6112//6112 6111//6111 6113//6113 -f 6112//6112 6113//6113 6099//6099 -f 6099//6099 6113//6113 6114//6114 -f 6099//6099 6114//6114 6100//6100 -f 6098//6098 6100//6100 6115//6115 -f 6115//6115 6100//6100 6116//6116 -f 6115//6115 6116//6116 6117//6117 -f 6117//6117 6116//6116 6118//6118 -f 6117//6117 6118//6118 6119//6119 -f 6119//6119 6118//6118 6120//6120 -f 6119//6119 6120//6120 6121//6121 -f 6120//6120 6122//6122 6121//6121 -f 6121//6121 6122//6122 6123//6123 -f 6121//6121 6123//6123 6124//6124 -f 6124//6124 6123//6123 6125//6125 -f 5496//5496 5495//5495 6126//6126 -f 6126//6126 5495//5495 6127//6127 -f 6126//6126 6127//6127 6128//6128 -f 6128//6128 6127//6127 6129//6129 -f 6128//6128 6129//6129 6130//6130 -f 6130//6130 6129//6129 6131//6131 -f 6130//6130 6131//6131 6125//6125 -f 6125//6125 6131//6131 6132//6132 -f 6125//6125 6132//6132 6124//6124 -f 6133//6133 6134//6134 6135//6135 -f 6135//6135 6134//6134 6136//6136 -f 6135//6135 6136//6136 6137//6137 -f 6137//6137 6136//6136 5521//5521 -f 6137//6137 5521//5521 5520//5520 -f 6135//6135 6138//6138 6133//6133 -f 6133//6133 6138//6138 6139//6139 -f 6133//6133 6139//6139 6140//6140 -f 6140//6140 6139//6139 6141//6141 -f 6140//6140 6141//6141 6142//6142 -f 6142//6142 6141//6141 6143//6143 -f 6142//6142 6143//6143 6144//6144 -f 6144//6144 6143//6143 6145//6145 -f 6144//6144 6145//6145 6146//6146 -f 6146//6146 6145//6145 6147//6147 -f 6147//6147 6145//6145 6148//6148 -f 6147//6147 6148//6148 6149//6149 -f 6149//6149 6148//6148 6150//6150 -f 6149//6149 6150//6150 6151//6151 -f 6151//6151 6150//6150 6152//6152 -f 6151//6151 6152//6152 6153//6153 -f 6152//6152 6154//6154 6153//6153 -f 6153//6153 6154//6154 6155//6155 -f 6153//6153 6155//6155 6156//6156 -f 6156//6156 6155//6155 6157//6157 -f 5531//5531 5530//5530 6158//6158 -f 5531//5531 6158//6158 6159//6159 -f 6159//6159 6158//6158 6160//6160 -f 6159//6159 6160//6160 6161//6161 -f 6161//6161 6160//6160 6162//6162 -f 6161//6161 6162//6162 6163//6163 -f 6163//6163 6162//6162 6164//6164 -f 6163//6163 6164//6164 6165//6165 -f 6165//6165 6164//6164 6166//6166 -f 6165//6165 6166//6166 6167//6167 -f 6167//6167 6166//6166 6168//6168 -f 6167//6167 6168//6168 6157//6157 -f 6157//6157 6168//6168 6169//6169 -f 6157//6157 6169//6169 6156//6156 -f 5563//5563 5562//5562 6170//6170 -f 6170//6170 5562//5562 6171//6171 -f 6170//6170 6171//6171 6172//6172 -f 6173//6173 6174//6174 6175//6175 -f 6175//6175 6174//6174 6176//6176 -f 6171//6171 6177//6177 6172//6172 -f 6172//6172 6177//6177 6175//6175 -f 6172//6172 6175//6175 6178//6178 -f 6178//6178 6175//6175 6176//6176 -f 6179//6179 6180//6180 6181//6181 -f 6181//6181 6180//6180 6182//6182 -f 6181//6181 6182//6182 6183//6183 -f 6183//6183 6182//6182 6184//6184 -f 6183//6183 6184//6184 6173//6173 -f 6173//6173 6184//6184 6185//6185 -f 6173//6173 6185//6185 6174//6174 -f 6186//6186 6187//6187 6179//6179 -f 6179//6179 6187//6187 6188//6188 -f 6179//6179 6188//6188 6180//6180 -f 6189//6189 6190//6190 6191//6191 -f 6189//6189 6191//6191 6192//6192 -f 6192//6192 6191//6191 6193//6193 -f 6192//6192 6193//6193 6194//6194 -f 6193//6193 6195//6195 6194//6194 -f 6194//6194 6195//6195 6196//6196 -f 6194//6194 6196//6196 6197//6197 -f 6197//6197 6196//6196 6198//6198 -f 6197//6197 6198//6198 6186//6186 -f 6186//6186 6198//6198 6199//6199 -f 6186//6186 6199//6199 6187//6187 -f 5571//5571 5570//5570 6200//6200 -f 6200//6200 5570//5570 6201//6201 -f 6200//6200 6201//6201 6202//6202 -f 6202//6202 6201//6201 6203//6203 -f 6202//6202 6203//6203 6204//6204 -f 6204//6204 6203//6203 6205//6205 -f 6204//6204 6205//6205 6206//6206 -f 6206//6206 6205//6205 6207//6207 -f 6206//6206 6207//6207 6208//6208 -f 6208//6208 6207//6207 6209//6209 -f 6208//6208 6209//6209 6190//6190 -f 6190//6190 6209//6209 6210//6210 -f 6190//6190 6210//6210 6191//6191 -f 5599//5599 5601//5601 6211//6211 -f 6211//6211 5601//5601 6212//6212 -f 6211//6211 6212//6212 6213//6213 -f 6213//6213 6212//6212 6214//6214 -f 6214//6214 6212//6212 6215//6215 -f 6214//6214 6215//6215 6216//6216 -f 6216//6216 6215//6215 6217//6217 -f 6216//6216 6217//6217 6218//6218 -f 6218//6218 6217//6217 6219//6219 -f 6218//6218 6219//6219 6220//6220 -f 6220//6220 6219//6219 6221//6221 -f 6220//6220 6221//6221 6222//6222 -f 6223//6223 6224//6224 6225//6225 -f 6225//6225 6224//6224 6222//6222 -f 6225//6225 6222//6222 6226//6226 -f 6226//6226 6222//6222 6221//6221 -f 6227//6227 6228//6228 6223//6223 -f 6223//6223 6228//6228 6229//6229 -f 6223//6223 6229//6229 6224//6224 -f 6230//6230 6231//6231 6232//6232 -f 6230//6230 6232//6232 6233//6233 -f 6232//6232 6234//6234 6233//6233 -f 6233//6233 6234//6234 6235//6235 -f 6233//6233 6235//6235 6236//6236 -f 6236//6236 6235//6235 6237//6237 -f 6236//6236 6237//6237 6238//6238 -f 6238//6238 6237//6237 6239//6239 -f 6238//6238 6239//6239 6240//6240 -f 6240//6240 6239//6239 6241//6241 -f 6240//6240 6241//6241 6242//6242 -f 6242//6242 6241//6241 6243//6243 -f 6242//6242 6243//6243 6227//6227 -f 6227//6227 6243//6243 6244//6244 -f 6227//6227 6244//6244 6228//6228 -f 6231//6231 6230//6230 6245//6245 -f 6245//6245 6230//6230 6246//6246 -f 6245//6245 6246//6246 5607//5607 -f 5607//5607 6246//6246 6247//6247 -f 5607//5607 6247//6247 5605//5605 -f 5637//5637 5636//5636 6248//6248 -f 6248//6248 5636//5636 6249//6249 -f 6248//6248 6249//6249 6250//6250 -f 6250//6250 6249//6249 6251//6251 -f 6250//6250 6251//6251 6252//6252 -f 6252//6252 6251//6251 6253//6253 -f 6252//6252 6253//6253 6254//6254 -f 6253//6253 6255//6255 6254//6254 -f 6254//6254 6255//6255 6256//6256 -f 6254//6254 6256//6256 6257//6257 -f 6257//6257 6256//6256 6258//6258 -f 6257//6257 6258//6258 6259//6259 -f 6259//6259 6258//6258 6260//6260 -f 6260//6260 6258//6258 6261//6261 -f 6260//6260 6261//6261 6262//6262 -f 6262//6262 6261//6261 6263//6263 -f 6262//6262 6263//6263 6264//6264 -f 6265//6265 6266//6266 6267//6267 -f 6267//6267 6266//6266 6268//6268 -f 6267//6267 6268//6268 6264//6264 -f 6264//6264 6268//6268 6269//6269 -f 6264//6264 6269//6269 6262//6262 -f 6267//6267 6270//6270 6265//6265 -f 6265//6265 6270//6270 6271//6271 -f 6265//6265 6271//6271 6272//6272 -f 6272//6272 6271//6271 6273//6273 -f 6272//6272 6273//6273 6274//6274 -f 6274//6274 6273//6273 6275//6275 -f 6274//6274 6275//6275 6276//6276 -f 6276//6276 6275//6275 6277//6277 -f 6276//6276 6277//6277 6278//6278 -f 6278//6278 6277//6277 6279//6279 -f 6278//6278 6279//6279 6280//6280 -f 5642//5642 5641//5641 6281//6281 -f 6281//6281 5641//5641 6280//6280 -f 6281//6281 6280//6280 6282//6282 -f 6282//6282 6280//6280 6279//6279 -f 5674//5674 5673//5673 6283//6283 -f 5674//5674 6283//6283 6284//6284 -f 6284//6284 6283//6283 6285//6285 -f 6284//6284 6285//6285 6286//6286 -f 6286//6286 6285//6285 6287//6287 -f 6286//6286 6287//6287 6288//6288 -f 6287//6287 6289//6289 6288//6288 -f 6288//6288 6289//6289 6290//6290 -f 6288//6288 6290//6290 6291//6291 -f 6291//6291 6290//6290 6292//6292 -f 6291//6291 6292//6292 6293//6293 -f 6293//6293 6292//6292 6294//6294 -f 6293//6293 6294//6294 6295//6295 -f 6295//6295 6294//6294 6296//6296 -f 6294//6294 6297//6297 6296//6296 -f 6296//6296 6297//6297 6298//6298 -f 6296//6296 6298//6298 6299//6299 -f 6299//6299 6298//6298 6300//6300 -f 6299//6299 6300//6300 6301//6301 -f 6301//6301 6300//6300 6302//6302 -f 6300//6300 6303//6303 6302//6302 -f 6302//6302 6303//6303 6304//6304 -f 6302//6302 6304//6304 6305//6305 -f 6305//6305 6304//6304 6306//6306 -f 6305//6305 6306//6306 6307//6307 -f 6306//6306 6308//6308 6307//6307 -f 6307//6307 6308//6308 6309//6309 -f 6307//6307 6309//6309 6310//6310 -f 6310//6310 6309//6309 6311//6311 -f 6310//6310 6311//6311 6312//6312 -f 6312//6312 6311//6311 6313//6313 -f 6312//6312 6313//6313 6314//6314 -f 6314//6314 6313//6313 6315//6315 -f 6314//6314 6315//6315 6316//6316 -f 6316//6316 6315//6315 5697//5697 -f 6316//6316 5697//5697 5696//5696 -f 6317//6317 6318//6318 6319//6319 -f 6319//6319 6318//6318 6320//6320 -f 6319//6319 6320//6320 6321//6321 -f 6321//6321 6320//6320 6322//6322 -f 6321//6321 6322//6322 6323//6323 -f 6323//6323 6322//6322 6324//6324 -f 6323//6323 6324//6324 5709//5709 -f 5709//5709 6324//6324 6325//6325 -f 5709//5709 6325//6325 5710//5710 -f 6319//6319 6326//6326 6317//6317 -f 6317//6317 6326//6326 6327//6327 -f 6317//6317 6327//6327 6328//6328 -f 6328//6328 6327//6327 6329//6329 -f 6328//6328 6329//6329 6330//6330 -f 6330//6330 6329//6329 6331//6331 -f 6330//6330 6331//6331 6332//6332 -f 6332//6332 6331//6331 6333//6333 -f 4974//4974 4973//4973 6334//6334 -f 6334//6334 4973//4973 6335//6335 -f 6334//6334 6335//6335 6336//6336 -f 6336//6336 6335//6335 6337//6337 -f 6336//6336 6337//6337 6338//6338 -f 6338//6338 6337//6337 6339//6339 -f 6338//6338 6339//6339 6340//6340 -f 6340//6340 6339//6339 6341//6341 -f 6340//6340 6341//6341 6342//6342 -f 6342//6342 6341//6341 6343//6343 -f 6342//6342 6343//6343 6344//6344 -f 6344//6344 6343//6343 6345//6345 -f 6344//6344 6345//6345 6346//6346 -f 6346//6346 6345//6345 6347//6347 -f 6346//6346 6347//6347 6348//6348 -f 6348//6348 6347//6347 6349//6349 -f 6348//6348 6349//6349 6350//6350 -f 6350//6350 6349//6349 6333//6333 -f 6350//6350 6333//6333 6351//6351 -f 6351//6351 6333//6333 6331//6331 -f 4958//4958 6352//6352 4959//4959 -f 4959//4959 6352//6352 6353//6353 -f 4959//4959 6353//6353 4960//4960 -f 6353//6353 6354//6354 4960//4960 -f 4960//4960 6354//6354 6355//6355 -f 4960//4960 6355//6355 4961//4961 -f 4961//4961 6355//6355 6356//6356 -f 4961//4961 6356//6356 4962//4962 -f 4962//4962 6356//6356 6357//6357 -f 4962//4962 6357//6357 4965//4965 -f 4965//4965 6357//6357 6358//6358 -f 4965//4965 6358//6358 4902//4902 -f 4902//4902 6358//6358 6359//6359 -f 4902//4902 6359//6359 4903//4903 -f 4903//4903 6359//6359 6360//6360 -f 4903//4903 6360//6360 4969//4969 -f 4969//4969 6360//6360 6361//6361 -f 4969//4969 6361//6361 6362//6362 -f 6362//6362 6361//6361 4863//4863 -f 6362//6362 4863//4863 6363//6363 -f 6363//6363 4863//4863 4865//4865 -f 6363//6363 4865//4865 6364//6364 -f 6364//6364 4865//4865 4867//4867 -f 6364//6364 4867//4867 6365//6365 -f 6365//6365 4867//4867 4871//4871 -f 6365//6365 4871//4871 6366//6366 -f 6366//6366 4871//4871 4870//4870 -f 6366//6366 4870//4870 6367//6367 -f 6367//6367 4870//4870 4878//4878 -f 6367//6367 4878//4878 6368//6368 -f 6368//6368 4878//4878 4877//4877 -f 4873//4873 6369//6369 4875//4875 -f 4875//4875 6369//6369 6370//6370 -f 4875//4875 6370//6370 4877//4877 -f 4877//4877 6370//6370 6371//6371 -f 4877//4877 6371//6371 6368//6368 -f 5004//5004 5003//5003 6372//6372 -f 6372//6372 5003//5003 6373//6373 -f 6372//6372 6373//6373 6374//6374 -f 6373//6373 6375//6375 6374//6374 -f 6374//6374 6375//6375 6376//6376 -f 6374//6374 6376//6376 6377//6377 -f 6377//6377 6376//6376 6378//6378 -f 6376//6376 6379//6379 6378//6378 -f 6378//6378 6379//6379 6380//6380 -f 6378//6378 6380//6380 6381//6381 -f 6381//6381 6380//6380 6382//6382 -f 6381//6381 6382//6382 6383//6383 -f 4844//4844 4846//4846 5069//5069 -f 6384//6384 6385//6385 5045//5045 -f 5045//5045 6385//6385 5051//5051 -f 4858//4858 4860//4860 5047//5047 -f 4860//4860 4862//4862 5047//5047 -f 5047//5047 4862//4862 6386//6386 -f 5047//5047 6386//6386 5045//5045 -f 5045//5045 6386//6386 6387//6387 -f 5045//5045 6387//6387 6384//6384 -f 4846//4846 4847//4847 5069//5069 -f 5069//5069 4847//4847 4849//4849 -f 5069//5069 4849//4849 794//794 -f 4844//4844 5069//5069 4843//4843 -f 4843//4843 5069//5069 5071//5071 -f 4843//4843 5071//5071 4841//4841 -f 4841//4841 5071//5071 4839//4839 -f 4839//4839 5071//5071 5066//5066 -f 4839//4839 5066//5066 4833//4833 -f 6388//6388 6389//6389 5059//5059 -f 5059//5059 6389//6389 5063//5063 -f 6390//6390 4838//4838 5061//5061 -f 5061//5061 4838//4838 4837//4837 -f 5061//5061 4837//4837 5066//5066 -f 5066//5066 4837//4837 4834//4834 -f 5066//5066 4834//4834 4833//4833 -f 4858//4858 5047//5047 4857//4857 -f 4857//4857 5047//5047 5016//5016 -f 4857//4857 5016//5016 4855//4855 -f 4855//4855 5016//5016 4853//4853 -f 4853//4853 5016//5016 5013//5013 -f 4853//4853 5013//5013 4830//4830 -f 4849//4849 4851//4851 794//794 -f 794//794 4851//4851 4852//4852 -f 794//794 4852//4852 5013//5013 -f 5013//5013 4852//4852 4831//4831 -f 5013//5013 4831//4831 4830//4830 -f 6389//6389 6391//6391 5063//5063 -f 5063//5063 6391//6391 6392//6392 -f 5063//5063 6392//6392 5061//5061 -f 5061//5061 6392//6392 6393//6393 -f 5061//5061 6393//6393 6390//6390 -f 806//806 6394//6394 5059//5059 -f 5059//5059 6394//6394 6395//6395 -f 5059//5059 6395//6395 6388//6388 -f 6385//6385 6396//6396 5051//5051 -f 5051//5051 6396//6396 6397//6397 -f 5051//5051 6397//6397 5054//5054 -f 5054//5054 6397//6397 6398//6398 -f 5054//5054 6398//6398 6399//6399 -f 6399//6399 6400//6400 5054//5054 -f 5054//5054 6400//6400 6401//6401 -f 5054//5054 6401//6401 806//806 -f 806//806 6401//6401 6402//6402 -f 806//806 6402//6402 6394//6394 -f 5014//5014 6403//6403 5015//5015 -f 6403//6403 5014//5014 5049//5049 -f 5046//5046 5044//5044 6404//6404 -f 5055//5055 6405//6405 6406//6406 -f 5008//5008 6407//6407 5009//5009 -f 5009//5009 6407//6407 6408//6408 -f 5009//5009 6408//6408 5018//5018 -f 5018//5018 6408//6408 5019//5019 -f 5019//5019 6408//6408 6409//6409 -f 5019//5019 6409//6409 5021//5021 -f 5021//5021 6409//6409 5022//5022 -f 5022//5022 6409//6409 6410//6410 -f 5022//5022 6410//6410 5023//5023 -f 5023//5023 6410//6410 5024//5024 -f 5024//5024 6410//6410 6411//6411 -f 5024//5024 6411//6411 5012//5012 -f 5012//5012 6411//6411 6412//6412 -f 5012//5012 6412//6412 5011//5011 -f 5011//5011 6412//6412 6413//6413 -f 5011//5011 6413//6413 5074//5074 -f 5074//5074 6413//6413 6414//6414 -f 5074//5074 6414//6414 5075//5075 -f 5075//5075 6414//6414 6415//6415 -f 5075//5075 6415//6415 5076//5076 -f 5076//5076 6415//6415 6416//6416 -f 5076//5076 6416//6416 5070//5070 -f 5070//5070 6416//6416 6417//6417 -f 5070//5070 6417//6417 5072//5072 -f 5072//5072 6417//6417 6418//6418 -f 5072//5072 6418//6418 5073//5073 -f 6418//6418 6419//6419 5073//5073 -f 5073//5073 6419//6419 6420//6420 -f 5073//5073 6420//6420 5067//5067 -f 6420//6420 6421//6421 5067//5067 -f 5067//5067 6421//6421 6422//6422 -f 5067//5067 6422//6422 5068//5068 -f 5068//5068 6422//6422 6423//6423 -f 5068//5068 6423//6423 5062//5062 -f 6423//6423 6424//6424 5062//5062 -f 5062//5062 6424//6424 6425//6425 -f 5062//5062 6425//6425 5064//5064 -f 5064//5064 6425//6425 5065//5065 -f 5065//5065 6425//6425 6426//6426 -f 5065//5065 6426//6426 5060//5060 -f 5060//5060 6426//6426 6427//6427 -f 5060//5060 6427//6427 5058//5058 -f 6427//6427 6428//6428 5058//5058 -f 5058//5058 6428//6428 6429//6429 -f 5058//5058 6429//6429 5057//5057 -f 6429//6429 6430//6430 5057//5057 -f 5057//5057 6430//6430 6431//6431 -f 5057//5057 6431//6431 5056//5056 -f 5056//5056 6431//6431 6432//6432 -f 5056//5056 6432//6432 5055//5055 -f 5055//5055 6432//6432 6433//6433 -f 5055//5055 6433//6433 6405//6405 -f 6404//6404 5044//5044 6434//6434 -f 5044//5044 5043//5043 6434//6434 -f 6434//6434 5043//5043 5050//5050 -f 6434//6434 5050//5050 6435//6435 -f 6435//6435 5050//5050 5052//5052 -f 6435//6435 5052//5052 6406//6406 -f 6406//6406 5052//5052 5053//5053 -f 6406//6406 5053//5053 5055//5055 -f 5046//5046 6404//6404 5048//5048 -f 5048//5048 6404//6404 6436//6436 -f 5048//5048 6436//6436 5049//5049 -f 5049//5049 6436//6436 6437//6437 -f 5049//5049 6437//6437 6403//6403 -f 6357//6357 6356//6356 6438//6438 -f 6438//6438 6356//6356 6439//6439 -f 6388//6388 6395//6395 6440//6440 -f 6384//6384 6387//6387 6441//6441 -f 6441//6441 6387//6387 4861//4861 -f 4861//4861 6387//6387 6386//6386 -f 4861//4861 6386//6386 4862//4862 -f 6384//6384 6441//6441 6385//6385 -f 6385//6385 6441//6441 6442//6442 -f 6385//6385 6442//6442 6396//6396 -f 6396//6396 6442//6442 6443//6443 -f 6396//6396 6443//6443 6397//6397 -f 6397//6397 6443//6443 6398//6398 -f 6398//6398 6443//6443 6444//6444 -f 6398//6398 6444//6444 6399//6399 -f 6399//6399 6444//6444 6400//6400 -f 6400//6400 6444//6444 6445//6445 -f 6400//6400 6445//6445 6401//6401 -f 6401//6401 6445//6445 6446//6446 -f 6401//6401 6446//6446 6402//6402 -f 6440//6440 6395//6395 6446//6446 -f 6446//6446 6395//6395 6394//6394 -f 6446//6446 6394//6394 6402//6402 -f 6388//6388 6440//6440 6389//6389 -f 6389//6389 6440//6440 6447//6447 -f 6389//6389 6447//6447 6391//6391 -f 6391//6391 6447//6447 6448//6448 -f 6391//6391 6448//6448 6392//6392 -f 6392//6392 6448//6448 6393//6393 -f 6393//6393 6448//6448 6449//6449 -f 6393//6393 6449//6449 6390//6390 -f 6390//6390 6449//6449 4836//4836 -f 6390//6390 4836//4836 4838//4838 -f 4889//4889 4888//4888 6450//6450 -f 6450//6450 4888//4888 6451//6451 -f 6450//6450 6451//6451 6452//6452 -f 6452//6452 6451//6451 6453//6453 -f 6454//6454 6455//6455 6453//6453 -f 6453//6453 6455//6455 6456//6456 -f 6453//6453 6456//6456 6452//6452 -f 6457//6457 6352//6352 6458//6458 -f 6458//6458 6352//6352 6459//6459 -f 6458//6458 6459//6459 6460//6460 -f 6460//6460 6459//6459 6461//6461 -f 6460//6460 6461//6461 6454//6454 -f 6454//6454 6461//6461 6462//6462 -f 6454//6454 6462//6462 6455//6455 -f 6356//6356 6355//6355 6439//6439 -f 6439//6439 6355//6355 6354//6354 -f 6439//6439 6354//6354 6457//6457 -f 6457//6457 6354//6354 6353//6353 -f 6457//6457 6353//6353 6352//6352 -f 6357//6357 6438//6438 6358//6358 -f 6358//6358 6438//6438 6463//6463 -f 6358//6358 6463//6463 6359//6359 -f 6359//6359 6463//6463 6464//6464 -f 6359//6359 6464//6464 6360//6360 -f 6360//6360 6464//6464 6361//6361 -f 6361//6361 6464//6464 4864//4864 -f 6361//6361 4864//4864 4863//4863 -f 4901//4901 4864//4864 6465//6465 -f 6465//6465 4864//4864 6464//6464 -f 6465//6465 6464//6464 6466//6466 -f 6466//6466 6464//6464 6463//6463 -f 6466//6466 6463//6463 6467//6467 -f 6467//6467 6463//6463 6438//6438 -f 6467//6467 6438//6438 6468//6468 -f 6468//6468 6438//6438 6439//6439 -f 6468//6468 6439//6439 6469//6469 -f 6469//6469 6439//6439 6457//6457 -f 6469//6469 6457//6457 6470//6470 -f 6470//6470 6457//6457 6458//6458 -f 6470//6470 6458//6458 6471//6471 -f 6471//6471 6458//6458 6460//6460 -f 6471//6471 6460//6460 6472//6472 -f 6472//6472 6460//6460 6454//6454 -f 6472//6472 6454//6454 6473//6473 -f 6473//6473 6454//6454 6453//6453 -f 6473//6473 6453//6453 6474//6474 -f 6474//6474 6453//6453 6451//6451 -f 6474//6474 6451//6451 4890//4890 -f 4890//4890 6451//6451 4888//4888 -f 4861//4861 4901//4901 6441//6441 -f 6441//6441 4901//4901 6465//6465 -f 6441//6441 6465//6465 6442//6442 -f 6442//6442 6465//6465 6466//6466 -f 6442//6442 6466//6466 6443//6443 -f 6443//6443 6466//6466 6467//6467 -f 6443//6443 6467//6467 6444//6444 -f 6444//6444 6467//6467 6468//6468 -f 6444//6444 6468//6468 6445//6445 -f 6445//6445 6468//6468 6469//6469 -f 6445//6445 6469//6469 6446//6446 -f 6446//6446 6469//6469 6470//6470 -f 6446//6446 6470//6470 6440//6440 -f 6440//6440 6470//6470 6471//6471 -f 6440//6440 6471//6471 6447//6447 -f 6447//6447 6471//6471 6472//6472 -f 6447//6447 6472//6472 6448//6448 -f 6448//6448 6472//6472 6473//6473 -f 6448//6448 6473//6473 6449//6449 -f 6449//6449 6473//6473 6474//6474 -f 6449//6449 6474//6474 4836//4836 -f 4836//4836 6474//6474 4890//4890 -f 6420//6420 6419//6419 5715//5715 -f 5077//5077 5079//5079 6407//6407 -f 6407//6407 5079//5079 6408//6408 -f 5079//5079 5081//5081 6408//6408 -f 6408//6408 5081//5081 5082//5082 -f 6408//6408 5082//5082 6409//6409 -f 5082//5082 5084//5084 6409//6409 -f 6409//6409 5084//5084 5086//5086 -f 6409//6409 5086//5086 6410//6410 -f 6410//6410 5086//5086 5088//5088 -f 6410//6410 5088//5088 6411//6411 -f 6411//6411 5088//5088 5093//5093 -f 6411//6411 5093//5093 6412//6412 -f 6412//6412 5093//5093 5092//5092 -f 6412//6412 5092//5092 6413//6413 -f 6413//6413 5092//5092 5090//5090 -f 6413//6413 5090//5090 6414//6414 -f 5090//5090 5744//5744 6414//6414 -f 6414//6414 5744//5744 5743//5743 -f 6414//6414 5743//5743 6415//6415 -f 5715//5715 6419//6419 5734//5734 -f 5743//5743 5739//5739 6415//6415 -f 6415//6415 5739//5739 5737//5737 -f 6415//6415 5737//5737 6416//6416 -f 6416//6416 5737//5737 5736//5736 -f 6416//6416 5736//5736 6417//6417 -f 6417//6417 5736//5736 5734//5734 -f 6417//6417 5734//5734 6418//6418 -f 6418//6418 5734//5734 6419//6419 -f 6420//6420 5715//5715 6421//6421 -f 6421//6421 5715//5715 5718//5718 -f 6421//6421 5718//5718 6422//6422 -f 6422//6422 5718//5718 5720//5720 -f 6422//6422 5720//5720 6423//6423 -f 6423//6423 5720//5720 5722//5722 -f 6423//6423 5722//5722 5724//5724 -f 5726//5726 6425//6425 5724//5724 -f 5724//5724 6425//6425 6424//6424 -f 5724//5724 6424//6424 6423//6423 -f 6427//6427 6426//6426 5730//5730 -f 5730//5730 6426//6426 6425//6425 -f 5730//5730 6425//6425 5728//5728 -f 5728//5728 6425//6425 5726//5726 -f 6427//6427 5730//5730 6428//6428 -f 6428//6428 5730//5730 5714//5714 -f 6428//6428 5714//5714 6429//6429 -f 6429//6429 5714//5714 5032//5032 -f 6429//6429 5032//5032 6430//6430 -f 6430//6430 5032//5032 5031//5031 -f 6430//6430 5031//5031 6431//6431 -f 6431//6431 5031//5031 6432//6432 -f 6432//6432 5031//5031 5036//5036 -f 6432//6432 5036//5036 6433//6433 -f 6433//6433 5036//5036 5038//5038 -f 6433//6433 5038//5038 5040//5040 -f 6434//6434 6435//6435 5030//5030 -f 5030//5030 6435//6435 6406//6406 -f 5030//5030 6406//6406 5040//5040 -f 5040//5040 6406//6406 6405//6405 -f 5040//5040 6405//6405 6433//6433 -f 5030//5030 5028//5028 6434//6434 -f 6434//6434 5028//5028 5026//5026 -f 6434//6434 5026//5026 6404//6404 -f 6404//6404 5026//5026 5025//5025 -f 6404//6404 5025//5025 6436//6436 -f 6436//6436 5025//5025 5010//5010 -f 6436//6436 5010//5010 6437//6437 -f 6437//6437 5010//5010 5017//5017 -f 6437//6437 5017//5017 6403//6403 -f 6403//6403 5017//5017 5020//5020 -f 6403//6403 5020//5020 5015//5015 -f 6369//6369 4873//4873 6475//6475 -f 6475//6475 4873//4873 4881//4881 -f 6475//6475 4881//4881 6476//6476 -f 4881//4881 4880//4880 6476//6476 -f 6476//6476 4880//4880 4879//4879 -f 6476//6476 4879//4879 6477//6477 -f 6477//6477 4879//4879 4827//4827 -f 6477//6477 4827//4827 6478//6478 -f 6478//6478 4827//4827 4826//4826 -f 6478//6478 4826//4826 6479//6479 -f 6479//6479 4826//4826 4882//4882 -f 6479//6479 4882//4882 6480//6480 -f 6480//6480 4882//4882 4884//4884 -f 6480//6480 4884//4884 6481//6481 -f 6481//6481 4884//4884 4886//4886 -f 6481//6481 4886//4886 4936//4936 -f 4936//4936 4886//4886 4887//4887 -f 4936//4936 4887//4887 4937//4937 -f 4937//4937 4887//4887 4889//4889 -f 4937//4937 4889//4889 4940//4940 -f 4940//4940 4889//4889 6450//6450 -f 4940//4940 6450//6450 4945//4945 -f 4945//4945 6450//6450 6452//6452 -f 4945//4945 6452//6452 4946//4946 -f 4946//4946 6452//6452 6456//6456 -f 4946//4946 6456//6456 4947//4947 -f 4947//4947 6456//6456 6455//6455 -f 4947//4947 6455//6455 4950//4950 -f 4950//4950 6455//6455 6462//6462 -f 4950//4950 6462//6462 4951//4951 -f 4951//4951 6462//6462 6461//6461 -f 6352//6352 4958//4958 6459//6459 -f 6459//6459 4958//4958 4957//4957 -f 6459//6459 4957//4957 6461//6461 -f 6461//6461 4957//4957 4952//4952 -f 6461//6461 4952//4952 4951//4951 -f 6480//6480 6481//6481 6482//6482 -f 6483//6483 6484//6484 6485//6485 -f 6486//6486 6487//6487 6488//6488 -f 6489//6489 4922//4922 4921//4921 -f 6489//6489 4921//4921 6490//6490 -f 6491//6491 6492//6492 6493//6493 -f 6494//6494 6495//6495 6492//6492 -f 6496//6496 6497//6497 6495//6495 -f 6498//6498 6499//6499 6483//6483 -f 6483//6483 6499//6499 6500//6500 -f 6483//6483 6500//6500 6484//6484 -f 6484//6484 6500//6500 6501//6501 -f 6484//6484 6501//6501 6502//6502 -f 6503//6503 6504//6504 6505//6505 -f 6505//6505 6504//6504 6486//6486 -f 6506//6506 6507//6507 6503//6503 -f 4924//4924 4944//4944 6507//6507 -f 6508//6508 6485//6485 6509//6509 -f 6509//6509 6485//6485 6484//6484 -f 6509//6509 6484//6484 6496//6496 -f 6496//6496 6484//6484 6502//6502 -f 6496//6496 6502//6502 6497//6497 -f 6510//6510 6511//6511 6488//6488 -f 6512//6512 6511//6511 6513//6513 -f 6513//6513 6511//6511 6510//6510 -f 6513//6513 6510//6510 6514//6514 -f 4968//4968 4969//4969 6362//6362 -f 6490//6490 4921//4921 6515//6515 -f 6515//6515 4921//4921 4967//4967 -f 6515//6515 4967//4967 6516//6516 -f 6516//6516 4967//4967 4968//4968 -f 6516//6516 4968//4968 6517//6517 -f 6517//6517 4968//4968 6362//6362 -f 6517//6517 6362//6362 6363//6363 -f 6363//6363 6518//6518 6517//6517 -f 6517//6517 6518//6518 6519//6519 -f 6517//6517 6519//6519 6516//6516 -f 6516//6516 6519//6519 6491//6491 -f 6516//6516 6491//6491 6515//6515 -f 6515//6515 6491//6491 6493//6493 -f 6515//6515 6493//6493 6490//6490 -f 6363//6363 6364//6364 6518//6518 -f 6518//6518 6364//6364 6365//6365 -f 6518//6518 6365//6365 6366//6366 -f 6492//6492 6491//6491 6494//6494 -f 6494//6494 6491//6491 6519//6519 -f 6494//6494 6519//6519 6520//6520 -f 6520//6520 6519//6519 6518//6518 -f 6520//6520 6518//6518 6521//6521 -f 6521//6521 6518//6518 6366//6366 -f 6521//6521 6366//6366 6367//6367 -f 6495//6495 6494//6494 6496//6496 -f 6496//6496 6494//6494 6520//6520 -f 6496//6496 6520//6520 6509//6509 -f 6509//6509 6520//6520 6521//6521 -f 6509//6509 6521//6521 6508//6508 -f 6508//6508 6521//6521 6367//6367 -f 6508//6508 6367//6367 6368//6368 -f 6368//6368 6371//6371 6508//6508 -f 6508//6508 6371//6371 6522//6522 -f 6508//6508 6522//6522 6485//6485 -f 6485//6485 6522//6522 6523//6523 -f 6485//6485 6523//6523 6483//6483 -f 6483//6483 6523//6523 6524//6524 -f 6483//6483 6524//6524 6498//6498 -f 6498//6498 6524//6524 6525//6525 -f 6371//6371 6370//6370 6522//6522 -f 6522//6522 6370//6370 6514//6514 -f 6522//6522 6514//6514 6523//6523 -f 6523//6523 6514//6514 6510//6510 -f 6523//6523 6510//6510 6524//6524 -f 6524//6524 6510//6510 6488//6488 -f 6524//6524 6488//6488 6525//6525 -f 6525//6525 6488//6488 6487//6487 -f 6370//6370 6369//6369 6514//6514 -f 6514//6514 6369//6369 6475//6475 -f 6514//6514 6475//6475 6513//6513 -f 6513//6513 6475//6475 6476//6476 -f 6513//6513 6476//6476 6512//6512 -f 6512//6512 6476//6476 6477//6477 -f 6512//6512 6477//6477 6478//6478 -f 6486//6486 6488//6488 6505//6505 -f 6505//6505 6488//6488 6511//6511 -f 6505//6505 6511//6511 6526//6526 -f 6526//6526 6511//6511 6512//6512 -f 6526//6526 6512//6512 6527//6527 -f 6527//6527 6512//6512 6478//6478 -f 6527//6527 6478//6478 6479//6479 -f 6503//6503 6505//6505 6506//6506 -f 6506//6506 6505//6505 6526//6526 -f 6506//6506 6526//6526 6528//6528 -f 6528//6528 6526//6526 6527//6527 -f 6528//6528 6527//6527 6482//6482 -f 6482//6482 6527//6527 6479//6479 -f 6482//6482 6479//6479 6480//6480 -f 6507//6507 6506//6506 4924//4924 -f 4924//4924 6506//6506 6528//6528 -f 4924//4924 6528//6528 4925//4925 -f 4925//4925 6528//6528 6482//6482 -f 4925//4925 6482//6482 4935//4935 -f 4935//4935 6482//6482 6481//6481 -f 4935//4935 6481//6481 4936//4936 -f 6529//6529 6530//6530 5845//5845 -f 5845//5845 6530//6530 5847//5847 -f 5847//5847 6530//6530 6531//6531 -f 5847//5847 6531//6531 5849//5849 -f 5849//5849 6531//6531 6532//6532 -f 5849//5849 6532//6532 5850//5850 -f 5850//5850 6532//6532 5842//5842 -f 5842//5842 6532//6532 6533//6533 -f 5842//5842 6533//6533 5839//5839 -f 5839//5839 6533//6533 6534//6534 -f 5839//5839 6534//6534 5837//5837 -f 5837//5837 6534//6534 6535//6535 -f 5837//5837 6535//6535 5835//5835 -f 5835//5835 6535//6535 5833//5833 -f 5833//5833 6535//6535 6536//6536 -f 5833//5833 6536//6536 5816//5816 -f 5816//5816 6536//6536 5817//5817 -f 5817//5817 6536//6536 6537//6537 -f 5817//5817 6537//6537 5830//5830 -f 5830//5830 6537//6537 6538//6538 -f 5830//5830 6538//6538 6539//6539 -f 6540//6540 5825//5825 6539//6539 -f 6539//6539 5825//5825 5828//5828 -f 6539//6539 5828//5828 5830//5830 -f 6541//6541 5184//5184 6542//6542 -f 6542//6542 5184//5184 5182//5182 -f 6542//6542 5182//5182 6543//6543 -f 6543//6543 5182//5182 5819//5819 -f 6543//6543 5819//5819 6544//6544 -f 6544//6544 5819//5819 5821//5821 -f 6544//6544 5821//5821 6540//6540 -f 6540//6540 5821//5821 5823//5823 -f 6540//6540 5823//5823 5825//5825 -f 6545//6545 5172//5172 6546//6546 -f 6546//6546 5172//5172 5190//5190 -f 6546//6546 5190//5190 6547//6547 -f 6547//6547 5190//5190 5189//5189 -f 6547//6547 5189//5189 6548//6548 -f 6548//6548 5189//5189 5187//5187 -f 6548//6548 5187//5187 6541//6541 -f 6541//6541 5187//5187 5186//5186 -f 6541//6541 5186//5186 5184//5184 -f 6549//6549 5179//5179 6550//6550 -f 6550//6550 5179//5179 5177//5177 -f 6550//6550 5177//5177 6551//6551 -f 6551//6551 5177//5177 5175//5175 -f 6551//6551 5175//5175 6545//6545 -f 6545//6545 5175//5175 5173//5173 -f 6545//6545 5173//5173 5172//5172 -f 6552//6552 5169//5169 6553//6553 -f 6553//6553 5169//5169 5168//5168 -f 6553//6553 5168//5168 6549//6549 -f 6549//6549 5168//5168 5180//5180 -f 6549//6549 5180//5180 5179//5179 -f 5162//5162 5160//5160 6554//6554 -f 6554//6554 5160//5160 5171//5171 -f 6554//6554 5171//5171 6552//6552 -f 6552//6552 5171//5171 5170//5170 -f 6552//6552 5170//5170 5169//5169 -f 6554//6554 6555//6555 5162//5162 -f 5162//5162 6555//6555 6556//6556 -f 5162//5162 6556//6556 5164//5164 -f 5164//5164 6556//6556 6557//6557 -f 5164//5164 6557//6557 5165//5165 -f 5165//5165 6557//6557 6558//6558 -f 5165//5165 6558//6558 5155//5155 -f 5155//5155 6558//6558 6559//6559 -f 5813//5813 6559//6559 6560//6560 -f 5813//5813 5158//5158 6559//6559 -f 6559//6559 5158//5158 5157//5157 -f 6559//6559 5157//5157 5155//5155 -f 6560//6560 6561//6561 5813//5813 -f 5813//5813 6561//6561 6562//6562 -f 5813//5813 6562//6562 5811//5811 -f 5811//5811 6562//6562 5808//5808 -f 5808//5808 6562//6562 6563//6563 -f 5808//5808 6563//6563 5806//5806 -f 5806//5806 6563//6563 6564//6564 -f 5806//5806 6564//6564 5804//5804 -f 5804//5804 6564//6564 6565//6565 -f 5804//5804 6565//6565 5802//5802 -f 5802//5802 6565//6565 5800//5800 -f 5800//5800 6565//6565 6566//6566 -f 5800//5800 6566//6566 5798//5798 -f 6566//6566 6567//6567 5798//5798 -f 5798//5798 6567//6567 6568//6568 -f 5798//5798 6568//6568 5796//5796 -f 5796//5796 6568//6568 6569//6569 -f 5796//5796 6569//6569 5795//5795 -f 5795//5795 6569//6569 6570//6570 -f 5795//5795 6570//6570 5793//5793 -f 5793//5793 6570//6570 6571//6571 -f 5793//5793 6571//6571 5783//5783 -f 5783//5783 6571//6571 6572//6572 -f 5783//5783 6572//6572 5785//5785 -f 5785//5785 6572//6572 6573//6573 -f 5785//5785 6573//6573 5787//5787 -f 5787//5787 6573//6573 6574//6574 -f 5787//5787 6574//6574 5789//5789 -f 5789//5789 6574//6574 6575//6575 -f 5789//5789 6575//6575 5790//5790 -f 5790//5790 6575//6575 6576//6576 -f 5790//5790 6576//6576 5150//5150 -f 5150//5150 6576//6576 6577//6577 -f 5150//5150 6577//6577 5148//5148 -f 5148//5148 6577//6577 6578//6578 -f 5148//5148 6578//6578 5146//5146 -f 5146//5146 6578//6578 6579//6579 -f 5146//5146 6579//6579 5144//5144 -f 5144//5144 6579//6579 6580//6580 -f 5144//5144 6580//6580 5142//5142 -f 5142//5142 6580//6580 6581//6581 -f 5142//5142 6581//6581 5140//5140 -f 5140//5140 6581//6581 6582//6582 -f 5140//5140 6582//6582 5116//5116 -f 5116//5116 6582//6582 6583//6583 -f 5116//5116 6583//6583 5117//5117 -f 5117//5117 6583//6583 6584//6584 -f 5117//5117 6584//6584 5137//5137 -f 5137//5137 6584//6584 6585//6585 -f 5137//5137 6585//6585 5136//5136 -f 5136//5136 6585//6585 6586//6586 -f 5136//5136 6586//6586 5134//5134 -f 5134//5134 6586//6586 6587//6587 -f 5134//5134 6587//6587 5131//5131 -f 5131//5131 6587//6587 6588//6588 -f 6589//6589 5127//5127 6588//6588 -f 6588//6588 5127//5127 5129//5129 -f 6588//6588 5129//5129 5131//5131 -f 6590//6590 5123//5123 6589//6589 -f 6589//6589 5123//5123 5125//5125 -f 6589//6589 5125//5125 5127//5127 -f 6591//6591 5119//5119 6590//6590 -f 6590//6590 5119//5119 5121//5121 -f 6590//6590 5121//5121 5123//5123 -f 6592//6592 5779//5779 6591//6591 -f 6591//6591 5779//5779 5781//5781 -f 6591//6591 5781//5781 5119//5119 -f 6593//6593 5769//5769 6594//6594 -f 6594//6594 5769//5769 5771//5771 -f 6594//6594 5771//5771 6595//6595 -f 6595//6595 5771//5771 5774//5774 -f 6595//6595 5774//5774 6592//6592 -f 6592//6592 5774//5774 5776//5776 -f 6592//6592 5776//5776 5779//5779 -f 6596//6596 5764//5764 6597//6597 -f 6597//6597 5764//5764 5765//5765 -f 6597//6597 5765//5765 6593//6593 -f 6593//6593 5765//5765 5767//5767 -f 6593//6593 5767//5767 5769//5769 -f 5759//5759 5754//5754 6598//6598 -f 6598//6598 5754//5754 5756//5756 -f 6598//6598 5756//5756 6599//6599 -f 6599//6599 5756//5756 5758//5758 -f 6599//6599 5758//5758 6596//6596 -f 6596//6596 5758//5758 5762//5762 -f 6596//6596 5762//5762 5764//5764 -f 5759//5759 6598//6598 6600//6600 -f 5759//5759 6600//6600 5753//5753 -f 5753//5753 6600//6600 6601//6601 -f 6602//6602 5110//5110 6603//6603 -f 6603//6603 5110//5110 5746//5746 -f 6603//6603 5746//5746 6604//6604 -f 6604//6604 5746//5746 5748//5748 -f 6604//6604 5748//5748 6605//6605 -f 6605//6605 5748//5748 5750//5750 -f 6605//6605 5750//5750 6601//6601 -f 6601//6601 5750//5750 5752//5752 -f 6601//6601 5752//5752 5753//5753 -f 5097//5097 5104//5104 6606//6606 -f 6606//6606 5104//5104 5106//5106 -f 6606//6606 5106//5106 6607//6607 -f 6607//6607 5106//5106 5115//5115 -f 6607//6607 5115//5115 6608//6608 -f 6608//6608 5115//5115 5114//5114 -f 6608//6608 5114//5114 6602//6602 -f 6602//6602 5114//5114 5112//5112 -f 6602//6602 5112//5112 5110//5110 -f 6606//6606 6609//6609 5097//5097 -f 5097//5097 6609//6609 6610//6610 -f 5097//5097 6610//6610 5098//5098 -f 5098//5098 6610//6610 6611//6611 -f 5098//5098 6611//6611 5100//5100 -f 5100//5100 6611//6611 6612//6612 -f 5100//5100 6612//6612 5101//5101 -f 5101//5101 6612//6612 6613//6613 -f 5101//5101 6613//6613 5078//5078 -f 5078//5078 6613//6613 6614//6614 -f 5078//5078 6614//6614 5080//5080 -f 5080//5080 6614//6614 6615//6615 -f 5080//5080 6615//6615 5083//5083 -f 5083//5083 6615//6615 6616//6616 -f 5083//5083 6616//6616 5085//5085 -f 5085//5085 6616//6616 6617//6617 -f 5096//5096 5095//5095 6618//6618 -f 6618//6618 5095//5095 5094//5094 -f 6618//6618 5094//5094 6617//6617 -f 6617//6617 5094//5094 5087//5087 -f 6617//6617 5087//5087 5085//5085 -f 6619//6619 5089//5089 6618//6618 -f 6618//6618 5089//5089 5091//5091 -f 6618//6618 5091//5091 5096//5096 -f 5735//5735 5738//5738 6620//6620 -f 6620//6620 5738//5738 5742//5742 -f 6620//6620 5742//5742 6621//6621 -f 6621//6621 5742//5742 5741//5741 -f 6621//6621 5741//5741 6622//6622 -f 6622//6622 5741//5741 5740//5740 -f 6622//6622 5740//5740 6619//6619 -f 6619//6619 5740//5740 5745//5745 -f 6619//6619 5745//5745 5089//5089 -f 6623//6623 5733//5733 6624//6624 -f 6624//6624 5733//5733 5735//5735 -f 6624//6624 5735//5735 6620//6620 -f 5733//5733 6623//6623 6625//6625 -f 5733//5733 6625//6625 5716//5716 -f 5716//5716 6625//6625 6626//6626 -f 5716//5716 6626//6626 5717//5717 -f 5717//5717 6626//6626 5719//5719 -f 6627//6627 5721//5721 6628//6628 -f 6628//6628 5721//5721 5719//5719 -f 6628//6628 5719//5719 6626//6626 -f 5721//5721 6627//6627 6629//6629 -f 5721//5721 6629//6629 5723//5723 -f 5723//5723 6629//6629 6630//6630 -f 5723//5723 6630//6630 5725//5725 -f 5725//5725 6630//6630 6631//6631 -f 5725//5725 6631//6631 5727//5727 -f 5727//5727 6631//6631 6632//6632 -f 5727//5727 6632//6632 5729//5729 -f 5729//5729 6632//6632 5731//5731 -f 5731//5731 6632//6632 6633//6633 -f 5731//5731 6633//6633 5732//5732 -f 5732//5732 6633//6633 6634//6634 -f 5732//5732 6634//6634 5713//5713 -f 5713//5713 6634//6634 6635//6635 -f 5713//5713 6635//6635 5033//5033 -f 5033//5033 6635//6635 6636//6636 -f 5033//5033 6636//6636 5034//5034 -f 5034//5034 6636//6636 6637//6637 -f 6638//6638 5042//5042 6639//6639 -f 6639//6639 5042//5042 5041//5041 -f 6639//6639 5041//5041 6640//6640 -f 6640//6640 5041//5041 5039//5039 -f 6640//6640 5039//5039 6641//6641 -f 6641//6641 5039//5039 5037//5037 -f 6641//6641 5037//5037 6637//6637 -f 6637//6637 5037//5037 5035//5035 -f 6637//6637 5035//5035 5034//5034 -f 6642//6642 5027//5027 6638//6638 -f 6638//6638 5027//5027 5029//5029 -f 6638//6638 5029//5029 5042//5042 -f 6642//6642 6643//6643 5027//5027 -f 5027//5027 6643//6643 6407//6407 -f 5027//5027 6407//6407 5008//5008 -f 5845//5845 5196//5196 6529//6529 -f 6529//6529 5196//5196 5194//5194 -f 6529//6529 5194//5194 6644//6644 -f 6644//6644 5194//5194 5192//5192 -f 6644//6644 5192//5192 6645//6645 -f 6645//6645 5192//5192 5191//5191 -f 6645//6645 5191//5191 6646//6646 -f 6646//6646 5191//5191 5200//5200 -f 6646//6646 5200//5200 6647//6647 -f 6647//6647 5200//5200 5202//5202 -f 6647//6647 5202//5202 6648//6648 -f 5202//5202 5204//5204 6648//6648 -f 6648//6648 5204//5204 5207//5207 -f 6648//6648 5207//5207 6649//6649 -f 6649//6649 5207//5207 5209//5209 -f 6649//6649 5209//5209 6650//6650 -f 4922//4922 6489//6489 6651//6651 -f 6652//6652 4911//4911 6653//6653 -f 6653//6653 4911//4911 4913//4913 -f 6653//6653 4913//4913 4956//4956 -f 6654//6654 4907//4907 6652//6652 -f 6652//6652 4907//4907 4906//4906 -f 4906//4906 4909//4909 6652//6652 -f 6652//6652 4909//4909 4912//4912 -f 6652//6652 4912//4912 4911//4911 -f 6507//6507 4944//4944 6654//6654 -f 6654//6654 4944//4944 4943//4943 -f 6654//6654 4943//4943 4907//4907 -f 6655//6655 6525//6525 6487//6487 -f 4956//4956 4918//4918 6653//6653 -f 6653//6653 4918//4918 4917//4917 -f 6653//6653 4917//4917 6651//6651 -f 6651//6651 4917//4917 4920//4920 -f 6651//6651 4920//4920 4922//4922 -f 6487//6487 6486//6486 6655//6655 -f 6655//6655 6486//6486 6504//6504 -f 6655//6655 6504//6504 6654//6654 -f 6654//6654 6504//6504 6503//6503 -f 6654//6654 6503//6503 6507//6507 -f 6495//6495 6497//6497 6656//6656 -f 6656//6656 6497//6497 6502//6502 -f 6656//6656 6499//6499 6655//6655 -f 6655//6655 6499//6499 6498//6498 -f 6655//6655 6498//6498 6525//6525 -f 6502//6502 6501//6501 6656//6656 -f 6656//6656 6501//6501 6500//6500 -f 6656//6656 6500//6500 6499//6499 -f 6489//6489 6490//6490 6651//6651 -f 6651//6651 6490//6490 6493//6493 -f 6651//6651 6493//6493 6656//6656 -f 6656//6656 6493//6493 6492//6492 -f 6656//6656 6492//6492 6495//6495 -f 6650//6650 5228//5228 5230//5230 -f 6650//6650 5230//5230 6649//6649 -f 6649//6649 5230//5230 5232//5232 -f 6649//6649 5232//5232 6648//6648 -f 6648//6648 5232//5232 6647//6647 -f 6647//6647 5232//5232 5234//5234 -f 6647//6647 5234//5234 6646//6646 -f 6646//6646 5234//5234 5236//5236 -f 6646//6646 5236//5236 6645//6645 -f 6645//6645 5236//5236 5238//5238 -f 6645//6645 5238//5238 6644//6644 -f 5238//5238 5240//5240 6644//6644 -f 6644//6644 5240//5240 5242//5242 -f 6644//6644 5242//5242 6529//6529 -f 6529//6529 5242//5242 5885//5885 -f 6529//6529 5885//5885 6530//6530 -f 6530//6530 5885//5885 5883//5883 -f 6530//6530 5883//5883 6531//6531 -f 6531//6531 5883//5883 5881//5881 -f 6531//6531 5881//5881 6532//6532 -f 5881//5881 5879//5879 6532//6532 -f 6532//6532 5879//5879 5877//5877 -f 6532//6532 5877//5877 6533//6533 -f 6533//6533 5877//5877 5875//5875 -f 6533//6533 5875//5875 6534//6534 -f 6534//6534 5875//5875 5873//5873 -f 6534//6534 5873//5873 6535//6535 -f 5873//5873 5871//5871 6535//6535 -f 6535//6535 5871//5871 5869//5869 -f 6535//6535 5869//5869 6536//6536 -f 5869//5869 5867//5867 6536//6536 -f 6536//6536 5867//5867 5866//5866 -f 6536//6536 5866//5866 6537//6537 -f 6537//6537 5866//5866 5863//5863 -f 6537//6537 5863//5863 6538//6538 -f 6538//6538 5863//5863 5861//5861 -f 6538//6538 5861//5861 6539//6539 -f 5861//5861 5859//5859 6539//6539 -f 6539//6539 5859//5859 5857//5857 -f 6539//6539 5857//5857 6540//6540 -f 6540//6540 5857//5857 5856//5856 -f 6540//6540 5856//5856 6544//6544 -f 6544//6544 5856//5856 5853//5853 -f 6544//6544 5853//5853 6543//6543 -f 5853//5853 5855//5855 6543//6543 -f 6543//6543 5855//5855 5223//5223 -f 6543//6543 5223//5223 6542//6542 -f 6542//6542 5223//5223 5225//5225 -f 6542//6542 5225//5225 6541//6541 -f 6541//6541 5225//5225 5222//5222 -f 6541//6541 5222//5222 6548//6548 -f 6548//6548 5222//5222 5221//5221 -f 6548//6548 5221//5221 6547//6547 -f 6547//6547 5221//5221 5219//5219 -f 6547//6547 5219//5219 6546//6546 -f 6546//6546 5219//5219 5217//5217 -f 6546//6546 5217//5217 6545//6545 -f 6545//6545 5217//5217 5214//5214 -f 6545//6545 5214//5214 6551//6551 -f 6551//6551 5214//5214 5212//5212 -f 5201//5201 6556//6556 5203//5203 -f 5203//5203 6556//6556 6555//6555 -f 5203//5203 6555//6555 5205//5205 -f 5205//5205 6555//6555 6554//6554 -f 5205//5205 6554//6554 5206//5206 -f 5206//5206 6554//6554 6552//6552 -f 5206//5206 6552//6552 5208//5208 -f 5208//5208 6552//6552 6553//6553 -f 5208//5208 6553//6553 5210//5210 -f 5210//5210 6553//6553 6549//6549 -f 5210//5210 6549//6549 5212//5212 -f 5212//5212 6549//6549 6550//6550 -f 5212//5212 6550//6550 6551//6551 -f 6557//6557 6556//6556 5201//5201 -f 6557//6557 5201//5201 6558//6558 -f 6558//6558 5201//5201 5199//5199 -f 5199//5199 5198//5198 6558//6558 -f 6558//6558 5198//5198 5193//5193 -f 6558//6558 5193//5193 6559//6559 -f 5193//5193 5195//5195 6559//6559 -f 6559//6559 5195//5195 5197//5197 -f 6559//6559 5197//5197 6560//6560 -f 6560//6560 5197//5197 5844//5844 -f 6560//6560 5844//5844 6561//6561 -f 5844//5844 5846//5846 6561//6561 -f 6561//6561 5846//5846 6562//6562 -f 5846//5846 5848//5848 6562//6562 -f 6562//6562 5848//5848 5843//5843 -f 6562//6562 5843//5843 6563//6563 -f 6563//6563 5843//5843 5841//5841 -f 6563//6563 5841//5841 6564//6564 -f 6564//6564 5841//5841 5840//5840 -f 6564//6564 5840//5840 6565//6565 -f 6565//6565 5840//5840 5838//5838 -f 6565//6565 5838//5838 6566//6566 -f 6566//6566 5838//5838 5836//5836 -f 6566//6566 5836//5836 6567//6567 -f 6567//6567 5836//5836 5834//5834 -f 6567//6567 5834//5834 6568//6568 -f 6568//6568 5834//5834 5818//5818 -f 6568//6568 5818//5818 6569//6569 -f 6569//6569 5818//5818 5832//5832 -f 6569//6569 5832//5832 6570//6570 -f 5832//5832 5831//5831 6570//6570 -f 6570//6570 5831//5831 5829//5829 -f 6570//6570 5829//5829 6571//6571 -f 6571//6571 5829//5829 5827//5827 -f 6571//6571 5827//5827 6572//6572 -f 6572//6572 5827//5827 5826//5826 -f 6572//6572 5826//5826 6573//6573 -f 6573//6573 5826//5826 5824//5824 -f 6573//6573 5824//5824 6574//6574 -f 6574//6574 5824//5824 5822//5822 -f 6574//6574 5822//5822 6575//6575 -f 6575//6575 5822//5822 5820//5820 -f 6575//6575 5820//5820 6576//6576 -f 6576//6576 5820//5820 5181//5181 -f 5174//5174 6580//6580 5188//5188 -f 5188//5188 6580//6580 6579//6579 -f 5188//5188 6579//6579 5185//5185 -f 5185//5185 6579//6579 6578//6578 -f 5185//5185 6578//6578 5183//5183 -f 5183//5183 6578//6578 6577//6577 -f 5183//5183 6577//6577 5181//5181 -f 5181//5181 6577//6577 6576//6576 -f 5167//5167 6585//6585 6584//6584 -f 5167//5167 6584//6584 5178//5178 -f 5178//5178 6584//6584 6583//6583 -f 5178//5178 6583//6583 5176//5176 -f 5176//5176 6583//6583 6582//6582 -f 5176//5176 6582//6582 5174//5174 -f 5174//5174 6582//6582 6581//6581 -f 5174//5174 6581//6581 6580//6580 -f 6585//6585 5167//5167 6586//6586 -f 6586//6586 5167//5167 5166//5166 -f 6586//6586 5166//5166 6587//6587 -f 5166//5166 5159//5159 6587//6587 -f 6587//6587 5159//5159 5161//5161 -f 6587//6587 5161//5161 6588//6588 -f 6588//6588 5161//5161 5163//5163 -f 6588//6588 5163//5163 6589//6589 -f 6589//6589 5163//5163 5154//5154 -f 6589//6589 5154//5154 6590//6590 -f 5154//5154 5153//5153 6590//6590 -f 6590//6590 5153//5153 5156//5156 -f 6590//6590 5156//5156 6591//6591 -f 5812//5812 6592//6592 5814//5814 -f 5814//5814 6592//6592 6591//6591 -f 5814//5814 6591//6591 5815//5815 -f 5815//5815 6591//6591 5156//5156 -f 5812//5812 5810//5810 6592//6592 -f 6592//6592 5810//5810 5809//5809 -f 6592//6592 5809//5809 6595//6595 -f 5809//5809 5807//5807 6595//6595 -f 6595//6595 5807//5807 5805//5805 -f 6595//6595 5805//5805 6594//6594 -f 6594//6594 5805//5805 5803//5803 -f 6594//6594 5803//5803 6593//6593 -f 6593//6593 5803//5803 5801//5801 -f 6593//6593 5801//5801 6597//6597 -f 6597//6597 5801//5801 5799//5799 -f 6597//6597 5799//5799 6596//6596 -f 6596//6596 5799//5799 5797//5797 -f 6596//6596 5797//5797 6599//6599 -f 6599//6599 5797//5797 6598//6598 -f 6598//6598 5797//5797 5794//5794 -f 5794//5794 5792//5792 6598//6598 -f 6598//6598 5792//5792 5791//5791 -f 6598//6598 5791//5791 6600//6600 -f 6600//6600 5791//5791 5782//5782 -f 6600//6600 5782//5782 6601//6601 -f 5782//5782 5784//5784 6601//6601 -f 6601//6601 5784//5784 5786//5786 -f 6601//6601 5786//5786 6605//6605 -f 6605//6605 5786//5786 5788//5788 -f 6605//6605 5788//5788 6604//6604 -f 6604//6604 5788//5788 6603//6603 -f 6603//6603 5788//5788 5152//5152 -f 6603//6603 5152//5152 6602//6602 -f 6602//6602 5152//5152 5151//5151 -f 6602//6602 5151//5151 6608//6608 -f 6608//6608 5151//5151 5149//5149 -f 6608//6608 5149//5149 6607//6607 -f 5149//5149 5147//5147 6607//6607 -f 6607//6607 5147//5147 5145//5145 -f 6607//6607 5145//5145 6606//6606 -f 6606//6606 5145//5145 5143//5143 -f 6606//6606 5143//5143 6609//6609 -f 6609//6609 5143//5143 5141//5141 -f 5132//5132 6616//6616 6615//6615 -f 5132//5132 6615//6615 5133//5133 -f 5133//5133 6615//6615 6614//6614 -f 5133//5133 6614//6614 5135//5135 -f 5135//5135 6614//6614 6613//6613 -f 5135//5135 6613//6613 5138//5138 -f 5138//5138 6613//6613 6612//6612 -f 5138//5138 6612//6612 5139//5139 -f 5139//5139 6612//6612 6611//6611 -f 5139//5139 6611//6611 5118//5118 -f 5118//5118 6611//6611 6610//6610 -f 5118//5118 6610//6610 5141//5141 -f 5141//5141 6610//6610 6609//6609 -f 5132//5132 5130//5130 6616//6616 -f 6616//6616 5130//5130 5128//5128 -f 6616//6616 5128//5128 6617//6617 -f 5128//5128 5126//5126 6617//6617 -f 6617//6617 5126//5126 5124//5124 -f 6617//6617 5124//5124 6618//6618 -f 5124//5124 5122//5122 6618//6618 -f 6618//6618 5122//5122 5120//5120 -f 6618//6618 5120//5120 6619//6619 -f 6619//6619 5120//5120 5780//5780 -f 6619//6619 5780//5780 6622//6622 -f 6622//6622 5780//5780 5778//5778 -f 6622//6622 5778//5778 6621//6621 -f 6621//6621 5778//5778 5777//5777 -f 6621//6621 5777//5777 6620//6620 -f 6620//6620 5777//5777 5775//5775 -f 6620//6620 5775//5775 6624//6624 -f 6624//6624 5775//5775 5773//5773 -f 6624//6624 5773//5773 6623//6623 -f 6623//6623 5773//5773 5772//5772 -f 6623//6623 5772//5772 5770//5770 -f 6623//6623 5770//5770 6625//6625 -f 6625//6625 5770//5770 5768//5768 -f 6625//6625 5768//5768 6626//6626 -f 6626//6626 5768//5768 5766//5766 -f 6626//6626 5766//5766 6628//6628 -f 6628//6628 5766//5766 5763//5763 -f 6628//6628 5763//5763 6627//6627 -f 6627//6627 5763//5763 5757//5757 -f 6627//6627 5757//5757 6629//6629 -f 6629//6629 5757//5757 5755//5755 -f 6629//6629 5755//5755 6630//6630 -f 6630//6630 5755//5755 5761//5761 -f 6630//6630 5761//5761 6631//6631 -f 6631//6631 5761//5761 5760//5760 -f 6631//6631 5760//5760 6632//6632 -f 6632//6632 5760//5760 5751//5751 -f 6632//6632 5751//5751 6633//6633 -f 6633//6633 5751//5751 6634//6634 -f 6634//6634 5751//5751 5749//5749 -f 6634//6634 5749//5749 5747//5747 -f 6634//6634 5747//5747 6635//6635 -f 6635//6635 5747//5747 5109//5109 -f 6635//6635 5109//5109 6636//6636 -f 5109//5109 5111//5111 6636//6636 -f 6636//6636 5111//5111 5113//5113 -f 6636//6636 5113//5113 6637//6637 -f 6637//6637 5113//5113 5105//5105 -f 6637//6637 5105//5105 6641//6641 -f 6641//6641 5105//5105 6640//6640 -f 5105//5105 5107//5107 6640//6640 -f 6640//6640 5107//5107 5108//5108 -f 6640//6640 5108//5108 6639//6639 -f 6639//6639 5108//5108 5103//5103 -f 6639//6639 5103//5103 6638//6638 -f 6638//6638 5103//5103 5102//5102 -f 6638//6638 5102//5102 6642//6642 -f 6642//6642 5102//5102 5099//5099 -f 6642//6642 5099//5099 6643//6643 -f 6643//6643 5099//5099 5077//5077 -f 6643//6643 5077//5077 6407//6407 -f 6651//6651 6656//6656 6657//6657 -f 6657//6657 6656//6656 6658//6658 -f 6653//6653 6651//6651 6659//6659 -f 6659//6659 6651//6651 6657//6657 -f 6652//6652 6653//6653 6660//6660 -f 6660//6660 6653//6653 6659//6659 -f 6654//6654 6652//6652 6661//6661 -f 6661//6661 6652//6652 6660//6660 -f 6655//6655 6654//6654 6662//6662 -f 6662//6662 6654//6654 6661//6661 -f 6656//6656 6655//6655 6658//6658 -f 6658//6658 6655//6655 6662//6662 -f 6662//6662 6661//6661 6658//6658 -f 6658//6658 6661//6661 6660//6660 -f 6658//6658 6660//6660 6657//6657 -f 6657//6657 6660//6660 6659//6659 -f 6663//6663 6664//6664 5986//5986 -f 5986//5986 6664//6664 5988//5988 -f 5988//5988 6664//6664 6665//6665 -f 5988//5988 6665//6665 5990//5990 -f 5990//5990 6665//6665 6666//6666 -f 5990//5990 6666//6666 5991//5991 -f 5991//5991 6666//6666 5983//5983 -f 5983//5983 6666//6666 6667//6667 -f 5983//5983 6667//6667 5980//5980 -f 5980//5980 6667//6667 6668//6668 -f 5980//5980 6668//6668 5978//5978 -f 5978//5978 6668//6668 6669//6669 -f 5978//5978 6669//6669 5976//5976 -f 5976//5976 6669//6669 5974//5974 -f 5974//5974 6669//6669 6670//6670 -f 5974//5974 6670//6670 5957//5957 -f 5957//5957 6670//6670 5958//5958 -f 5958//5958 6670//6670 6671//6671 -f 5958//5958 6671//6671 5971//5971 -f 6671//6671 6672//6672 5971//5971 -f 5971//5971 6672//6672 6673//6673 -f 5971//5971 6673//6673 5969//5969 -f 5969//5969 6673//6673 5966//5966 -f 5966//5966 6673//6673 6674//6674 -f 5966//5966 6674//6674 5964//5964 -f 5964//5964 6674//6674 5962//5962 -f 5962//5962 6674//6674 6675//6675 -f 5962//5962 6675//6675 5960//5960 -f 5960//5960 6675//6675 6676//6676 -f 5960//5960 6676//6676 5330//5330 -f 5330//5330 6676//6676 6677//6677 -f 5330//5330 6677//6677 5332//5332 -f 5332//5332 6677//6677 6678//6678 -f 5332//5332 6678//6678 5334//5334 -f 5334//5334 6678//6678 5335//5335 -f 5335//5335 6678//6678 6679//6679 -f 5335//5335 6679//6679 5337//5337 -f 5337//5337 6679//6679 6680//6680 -f 5337//5337 6680//6680 5338//5338 -f 5338//5338 6680//6680 6681//6681 -f 5338//5338 6681//6681 5320//5320 -f 5320//5320 6681//6681 6682//6682 -f 5320//5320 6682//6682 5321//5321 -f 5321//5321 6682//6682 5323//5323 -f 5323//5323 6682//6682 6683//6683 -f 5323//5323 6683//6683 5325//5325 -f 5325//5325 6683//6683 6684//6684 -f 5325//5325 6684//6684 5327//5327 -f 5327//5327 6684//6684 6685//6685 -f 5327//5327 6685//6685 5328//5328 -f 5328//5328 6685//6685 5316//5316 -f 5316//5316 6685//6685 6686//6686 -f 5316//5316 6686//6686 5317//5317 -f 5317//5317 6686//6686 6687//6687 -f 5317//5317 6687//6687 5318//5318 -f 5318//5318 6687//6687 5319//5319 -f 5319//5319 6687//6687 6688//6688 -f 5319//5319 6688//6688 5308//5308 -f 5308//5308 6688//6688 6689//6689 -f 5308//5308 6689//6689 5310//5310 -f 5310//5310 6689//6689 6690//6690 -f 5310//5310 6690//6690 5312//5312 -f 5312//5312 6690//6690 6691//6691 -f 5312//5312 6691//6691 5313//5313 -f 5313//5313 6691//6691 6692//6692 -f 5313//5313 6692//6692 5303//5303 -f 5303//5303 6692//6692 6693//6693 -f 5303//5303 6693//6693 5305//5305 -f 5305//5305 6693//6693 5306//5306 -f 5306//5306 6693//6693 6694//6694 -f 5306//5306 6694//6694 5954//5954 -f 6694//6694 6695//6695 5954//5954 -f 5954//5954 6695//6695 6696//6696 -f 5954//5954 6696//6696 5952//5952 -f 5952//5952 6696//6696 5949//5949 -f 5949//5949 6696//6696 6697//6697 -f 5949//5949 6697//6697 5947//5947 -f 5947//5947 6697//6697 6698//6698 -f 5947//5947 6698//6698 5945//5945 -f 5945//5945 6698//6698 6699//6699 -f 5945//5945 6699//6699 5943//5943 -f 5943//5943 6699//6699 5941//5941 -f 5941//5941 6699//6699 6700//6700 -f 5941//5941 6700//6700 5939//5939 -f 6700//6700 6701//6701 5939//5939 -f 5939//5939 6701//6701 6702//6702 -f 5939//5939 6702//6702 5937//5937 -f 5937//5937 6702//6702 6703//6703 -f 5937//5937 6703//6703 5936//5936 -f 5936//5936 6703//6703 6704//6704 -f 5936//5936 6704//6704 5934//5934 -f 5934//5934 6704//6704 6705//6705 -f 5934//5934 6705//6705 5924//5924 -f 5924//5924 6705//6705 6706//6706 -f 5924//5924 6706//6706 5926//5926 -f 5926//5926 6706//6706 6707//6707 -f 5926//5926 6707//6707 5928//5928 -f 5928//5928 6707//6707 6708//6708 -f 5928//5928 6708//6708 5930//5930 -f 5930//5930 6708//6708 6709//6709 -f 5930//5930 6709//6709 5931//5931 -f 5931//5931 6709//6709 6710//6710 -f 5931//5931 6710//6710 5298//5298 -f 5298//5298 6710//6710 6711//6711 -f 5298//5298 6711//6711 5296//5296 -f 5296//5296 6711//6711 6712//6712 -f 5296//5296 6712//6712 5294//5294 -f 5294//5294 6712//6712 6713//6713 -f 5294//5294 6713//6713 5292//5292 -f 5292//5292 6713//6713 6714//6714 -f 5292//5292 6714//6714 5290//5290 -f 5290//5290 6714//6714 6715//6715 -f 5290//5290 6715//6715 5288//5288 -f 5288//5288 6715//6715 6716//6716 -f 5288//5288 6716//6716 5264//5264 -f 5264//5264 6716//6716 6717//6717 -f 5264//5264 6717//6717 5265//5265 -f 5265//5265 6717//6717 6718//6718 -f 5265//5265 6718//6718 5285//5285 -f 5285//5285 6718//6718 6719//6719 -f 5285//5285 6719//6719 5284//5284 -f 5284//5284 6719//6719 6720//6720 -f 5284//5284 6720//6720 5282//5282 -f 5282//5282 6720//6720 6721//6721 -f 5282//5282 6721//6721 5279//5279 -f 5279//5279 6721//6721 6722//6722 -f 6723//6723 5275//5275 6722//6722 -f 6722//6722 5275//5275 5277//5277 -f 6722//6722 5277//5277 5279//5279 -f 6724//6724 5271//5271 6723//6723 -f 6723//6723 5271//5271 5273//5273 -f 6723//6723 5273//5273 5275//5275 -f 6725//6725 5267//5267 6724//6724 -f 6724//6724 5267//5267 5269//5269 -f 6724//6724 5269//5269 5271//5271 -f 6726//6726 5920//5920 6725//6725 -f 6725//6725 5920//5920 5922//5922 -f 6725//6725 5922//5922 5267//5267 -f 6727//6727 5910//5910 6728//6728 -f 6728//6728 5910//5910 5912//5912 -f 6728//6728 5912//5912 6729//6729 -f 6729//6729 5912//5912 5915//5915 -f 6729//6729 5915//5915 6726//6726 -f 6726//6726 5915//5915 5917//5917 -f 6726//6726 5917//5917 5920//5920 -f 6730//6730 5905//5905 6731//6731 -f 6731//6731 5905//5905 5906//5906 -f 6731//6731 5906//5906 6727//6727 -f 6727//6727 5906//5906 5908//5908 -f 6727//6727 5908//5908 5910//5910 -f 6732//6732 5897//5897 6733//6733 -f 6733//6733 5897//5897 5899//5899 -f 6733//6733 5899//5899 6730//6730 -f 6730//6730 5899//5899 5903//5903 -f 6730//6730 5903//5903 5905//5905 -f 6734//6734 5894//5894 6735//6735 -f 6735//6735 5894//5894 5900//5900 -f 6735//6735 5900//5900 6732//6732 -f 6732//6732 5900//5900 5895//5895 -f 6732//6732 5895//5895 5897//5897 -f 6736//6736 5258//5258 6737//6737 -f 6737//6737 5258//5258 5887//5887 -f 6737//6737 5887//5887 6738//6738 -f 6738//6738 5887//5887 5889//5889 -f 6738//6738 5889//5889 6739//6739 -f 6739//6739 5889//5889 5891//5891 -f 6739//6739 5891//5891 6734//6734 -f 6734//6734 5891//5891 5893//5893 -f 6734//6734 5893//5893 5894//5894 -f 5245//5245 5252//5252 6740//6740 -f 6740//6740 5252//5252 5254//5254 -f 6740//6740 5254//5254 6741//6741 -f 6741//6741 5254//5254 5263//5263 -f 6741//6741 5263//5263 6742//6742 -f 6742//6742 5263//5263 5262//5262 -f 6742//6742 5262//5262 6736//6736 -f 6736//6736 5262//5262 5260//5260 -f 6736//6736 5260//5260 5258//5258 -f 6740//6740 6743//6743 5245//5245 -f 5245//5245 6743//6743 6744//6744 -f 5245//5245 6744//6744 5246//5246 -f 5246//5246 6744//6744 6745//6745 -f 5246//5246 6745//6745 5248//5248 -f 5248//5248 6745//6745 6746//6746 -f 5248//5248 6746//6746 5249//5249 -f 5249//5249 6746//6746 6747//6747 -f 5249//5249 6747//6747 5229//5229 -f 5229//5229 6747//6747 6748//6748 -f 5229//5229 6748//6748 5231//5231 -f 5231//5231 6748//6748 6749//6749 -f 5231//5231 6749//6749 5233//5233 -f 5233//5233 6749//6749 6750//6750 -f 5233//5233 6750//6750 5235//5235 -f 5235//5235 6750//6750 6751//6751 -f 5243//5243 5244//5244 6752//6752 -f 6752//6752 5244//5244 5239//5239 -f 6752//6752 5239//5239 6751//6751 -f 6751//6751 5239//5239 5237//5237 -f 6751//6751 5237//5237 5235//5235 -f 5243//5243 6752//6752 5241//5241 -f 5241//5241 6752//6752 6753//6753 -f 5241//5241 6753//6753 5886//5886 -f 5886//5886 6753//6753 5884//5884 -f 5884//5884 6753//6753 6754//6754 -f 5884//5884 6754//6754 5882//5882 -f 5882//5882 6754//6754 6755//6755 -f 5882//5882 6755//6755 5880//5880 -f 5880//5880 6755//6755 6756//6756 -f 5880//5880 6756//6756 5878//5878 -f 5878//5878 6756//6756 5876//5876 -f 5876//5876 6756//6756 6757//6757 -f 5876//5876 6757//6757 5874//5874 -f 6757//6757 6758//6758 5874//5874 -f 5874//5874 6758//6758 6759//6759 -f 5874//5874 6759//6759 5872//5872 -f 5872//5872 6759//6759 6760//6760 -f 5872//5872 6760//6760 5870//5870 -f 5870//5870 6760//6760 5868//5868 -f 5868//5868 6760//6760 6761//6761 -f 5868//5868 6761//6761 5865//5865 -f 6761//6761 6762//6762 5865//5865 -f 5865//5865 6762//6762 6763//6763 -f 5865//5865 6763//6763 5864//5864 -f 5864//5864 6763//6763 6764//6764 -f 5864//5864 6764//6764 5862//5862 -f 5862//5862 6764//6764 6765//6765 -f 5862//5862 6765//6765 5860//5860 -f 5860//5860 6765//6765 6766//6766 -f 6767//6767 5226//5226 6768//6768 -f 6768//6768 5226//5226 5224//5224 -f 6768//6768 5224//5224 6769//6769 -f 6769//6769 5224//5224 5854//5854 -f 6769//6769 5854//5854 6770//6770 -f 6770//6770 5854//5854 5852//5852 -f 6770//6770 5852//5852 6771//6771 -f 6771//6771 5852//5852 5851//5851 -f 6771//6771 5851//5851 6766//6766 -f 6766//6766 5851//5851 5858//5858 -f 6766//6766 5858//5858 5860//5860 -f 6772//6772 5215//5215 6773//6773 -f 6773//6773 5215//5215 5216//5216 -f 6773//6773 5216//5216 6774//6774 -f 6774//6774 5216//5216 5218//5218 -f 6774//6774 5218//5218 6775//6775 -f 6775//6775 5218//5218 5220//5220 -f 6775//6775 5220//5220 6767//6767 -f 6767//6767 5220//5220 5227//5227 -f 6767//6767 5227//5227 5226//5226 -f 6776//6776 5211//5211 6772//6772 -f 6772//6772 5211//5211 5213//5213 -f 6772//6772 5213//5213 5215//5215 -f 6776//6776 6777//6777 5211//5211 -f 5211//5211 6777//6777 6650//6650 -f 5211//5211 6650//6650 5209//5209 -f 5986//5986 5344//5344 6663//6663 -f 6663//6663 5344//5344 5342//5342 -f 6663//6663 5342//5342 6778//6778 -f 6778//6778 5342//5342 5340//5340 -f 6778//6778 5340//5340 6779//6779 -f 6779//6779 5340//5340 5339//5339 -f 6779//6779 5339//5339 6780//6780 -f 6780//6780 5339//5339 5348//5348 -f 6780//6780 5348//5348 6781//6781 -f 6781//6781 5348//5348 5350//5350 -f 6781//6781 5350//5350 6782//6782 -f 5350//5350 5352//5352 6782//6782 -f 6782//6782 5352//5352 5355//5355 -f 6782//6782 5355//5355 6783//6783 -f 6783//6783 5355//5355 5357//5357 -f 6783//6783 5357//5357 6784//6784 -f 6784//6784 5376//5376 5378//5378 -f 6784//6784 5378//5378 6783//6783 -f 6783//6783 5378//5378 5380//5380 -f 6783//6783 5380//5380 6782//6782 -f 6782//6782 5380//5380 6781//6781 -f 6781//6781 5380//5380 5382//5382 -f 6781//6781 5382//5382 6780//6780 -f 6780//6780 5382//5382 5384//5384 -f 6780//6780 5384//5384 6779//6779 -f 6779//6779 5384//5384 5386//5386 -f 6779//6779 5386//5386 6778//6778 -f 5386//5386 5388//5388 6778//6778 -f 6778//6778 5388//5388 5390//5390 -f 6778//6778 5390//5390 6663//6663 -f 6663//6663 5390//5390 6026//6026 -f 6663//6663 6026//6026 6664//6664 -f 6664//6664 6026//6026 6024//6024 -f 6664//6664 6024//6024 6665//6665 -f 6665//6665 6024//6024 6022//6022 -f 6665//6665 6022//6022 6666//6666 -f 6022//6022 6020//6020 6666//6666 -f 6666//6666 6020//6020 6018//6018 -f 6666//6666 6018//6018 6667//6667 -f 6667//6667 6018//6018 6016//6016 -f 6667//6667 6016//6016 6668//6668 -f 6668//6668 6016//6016 6014//6014 -f 6668//6668 6014//6014 6669//6669 -f 6014//6014 6012//6012 6669//6669 -f 6669//6669 6012//6012 6010//6010 -f 6669//6669 6010//6010 6670//6670 -f 6010//6010 6008//6008 6670//6670 -f 6670//6670 6008//6008 6007//6007 -f 6670//6670 6007//6007 6671//6671 -f 6671//6671 6007//6007 6004//6004 -f 6671//6671 6004//6004 6672//6672 -f 6672//6672 6004//6004 6002//6002 -f 6672//6672 6002//6002 6673//6673 -f 6002//6002 6000//6000 6673//6673 -f 6673//6673 6000//6000 5998//5998 -f 6673//6673 5998//5998 6674//6674 -f 6674//6674 5998//5998 5997//5997 -f 6674//6674 5997//5997 6675//6675 -f 6675//6675 5997//5997 5994//5994 -f 6675//6675 5994//5994 6676//6676 -f 5994//5994 5996//5996 6676//6676 -f 6676//6676 5996//5996 5371//5371 -f 6676//6676 5371//5371 6677//6677 -f 6677//6677 5371//5371 5373//5373 -f 6677//6677 5373//5373 6678//6678 -f 6678//6678 5373//5373 5370//5370 -f 6678//6678 5370//5370 6679//6679 -f 6679//6679 5370//5370 5369//5369 -f 6679//6679 5369//5369 6680//6680 -f 6680//6680 5369//5369 5367//5367 -f 6680//6680 5367//5367 6681//6681 -f 6681//6681 5367//5367 5365//5365 -f 6681//6681 5365//5365 6682//6682 -f 6682//6682 5365//5365 5362//5362 -f 6682//6682 5362//5362 6683//6683 -f 6683//6683 5362//5362 5360//5360 -f 6690//6690 6689//6689 5351//5351 -f 5351//5351 6689//6689 5353//5353 -f 5353//5353 6689//6689 6688//6688 -f 5353//5353 6688//6688 5354//5354 -f 5354//5354 6688//6688 6687//6687 -f 5354//5354 6687//6687 5356//5356 -f 5356//5356 6687//6687 6686//6686 -f 5356//5356 6686//6686 5358//5358 -f 5358//5358 6686//6686 6685//6685 -f 5358//5358 6685//6685 5360//5360 -f 5360//5360 6685//6685 6684//6684 -f 5360//5360 6684//6684 6683//6683 -f 5351//5351 5349//5349 6690//6690 -f 6690//6690 5349//5349 5347//5347 -f 6690//6690 5347//5347 6691//6691 -f 6691//6691 5347//5347 5346//5346 -f 6691//6691 5346//5346 6692//6692 -f 6692//6692 5346//5346 5341//5341 -f 6692//6692 5341//5341 6693//6693 -f 5341//5341 5343//5343 6693//6693 -f 6693//6693 5343//5343 5345//5345 -f 6693//6693 5345//5345 6694//6694 -f 6694//6694 5345//5345 5985//5985 -f 6694//6694 5985//5985 6695//6695 -f 5985//5985 5987//5987 6695//6695 -f 6695//6695 5987//5987 5989//5989 -f 6695//6695 5989//5989 6696//6696 -f 6696//6696 5989//5989 5984//5984 -f 6696//6696 5984//5984 6697//6697 -f 6697//6697 5984//5984 5982//5982 -f 6697//6697 5982//5982 6698//6698 -f 6698//6698 5982//5982 5981//5981 -f 6698//6698 5981//5981 6699//6699 -f 6699//6699 5981//5981 5979//5979 -f 6699//6699 5979//5979 6700//6700 -f 6700//6700 5979//5979 5977//5977 -f 6700//6700 5977//5977 6701//6701 -f 6701//6701 5977//5977 5975//5975 -f 6701//6701 5975//5975 6702//6702 -f 6702//6702 5975//5975 5959//5959 -f 6702//6702 5959//5959 6703//6703 -f 6703//6703 5959//5959 5973//5973 -f 6703//6703 5973//5973 6704//6704 -f 5973//5973 5972//5972 6704//6704 -f 6704//6704 5972//5972 5970//5970 -f 6704//6704 5970//5970 6705//6705 -f 6705//6705 5970//5970 5968//5968 -f 6705//6705 5968//5968 6706//6706 -f 6706//6706 5968//5968 5967//5967 -f 6706//6706 5967//5967 6707//6707 -f 6707//6707 5967//5967 5965//5965 -f 6707//6707 5965//5965 6708//6708 -f 6708//6708 5965//5965 5963//5963 -f 6708//6708 5963//5963 6709//6709 -f 6709//6709 5963//5963 5961//5961 -f 6709//6709 5961//5961 6710//6710 -f 6710//6710 5961//5961 5329//5329 -f 6710//6710 5329//5329 6711//6711 -f 6711//6711 5329//5329 5331//5331 -f 6711//6711 5331//5331 6712//6712 -f 6712//6712 5331//5331 5333//5333 -f 6712//6712 5333//5333 6713//6713 -f 6713//6713 5333//5333 5336//5336 -f 6713//6713 5336//5336 6714//6714 -f 6714//6714 5336//5336 5322//5322 -f 5315//5315 6719//6719 6718//6718 -f 5315//5315 6718//6718 5326//5326 -f 5326//5326 6718//6718 6717//6717 -f 5326//5326 6717//6717 5324//5324 -f 5324//5324 6717//6717 6716//6716 -f 5324//5324 6716//6716 5322//5322 -f 5322//5322 6716//6716 6715//6715 -f 5322//5322 6715//6715 6714//6714 -f 6719//6719 5315//5315 6720//6720 -f 6720//6720 5315//5315 5314//5314 -f 6720//6720 5314//5314 6721//6721 -f 5314//5314 5307//5307 6721//6721 -f 6721//6721 5307//5307 5309//5309 -f 6721//6721 5309//5309 6722//6722 -f 6722//6722 5309//5309 5311//5311 -f 6722//6722 5311//5311 6723//6723 -f 6723//6723 5311//5311 5302//5302 -f 6723//6723 5302//5302 6724//6724 -f 5302//5302 5301//5301 6724//6724 -f 6724//6724 5301//5301 5304//5304 -f 6724//6724 5304//5304 6725//6725 -f 5953//5953 6726//6726 5955//5955 -f 5955//5955 6726//6726 6725//6725 -f 5955//5955 6725//6725 5956//5956 -f 5956//5956 6725//6725 5304//5304 -f 5953//5953 5951//5951 6726//6726 -f 6726//6726 5951//5951 5950//5950 -f 6726//6726 5950//5950 6729//6729 -f 5950//5950 5948//5948 6729//6729 -f 6729//6729 5948//5948 5946//5946 -f 6729//6729 5946//5946 6728//6728 -f 6728//6728 5946//5946 5944//5944 -f 6728//6728 5944//5944 6727//6727 -f 6727//6727 5944//5944 5942//5942 -f 6727//6727 5942//5942 6731//6731 -f 6731//6731 5942//5942 5940//5940 -f 6731//6731 5940//5940 6730//6730 -f 6730//6730 5940//5940 5938//5938 -f 6730//6730 5938//5938 6733//6733 -f 6733//6733 5938//5938 5935//5935 -f 6733//6733 5935//5935 6732//6732 -f 5935//5935 5933//5933 6732//6732 -f 6732//6732 5933//5933 5932//5932 -f 6732//6732 5932//5932 6735//6735 -f 6735//6735 5932//5932 5923//5923 -f 6735//6735 5923//5923 6734//6734 -f 5923//5923 5925//5925 6734//6734 -f 6734//6734 5925//5925 5927//5927 -f 6734//6734 5927//5927 6739//6739 -f 6739//6739 5927//5927 5929//5929 -f 6739//6739 5929//5929 6738//6738 -f 6738//6738 5929//5929 6737//6737 -f 6737//6737 5929//5929 5300//5300 -f 6737//6737 5300//5300 6736//6736 -f 6736//6736 5300//5300 5299//5299 -f 6736//6736 5299//5299 6742//6742 -f 6742//6742 5299//5299 5297//5297 -f 6742//6742 5297//5297 6741//6741 -f 5297//5297 5295//5295 6741//6741 -f 6741//6741 5295//5295 5293//5293 -f 6741//6741 5293//5293 6740//6740 -f 6740//6740 5293//5293 5291//5291 -f 6740//6740 5291//5291 6743//6743 -f 6743//6743 5291//5291 5289//5289 -f 6743//6743 5289//5289 6744//6744 -f 6744//6744 5289//5289 5266//5266 -f 6744//6744 5266//5266 6745//6745 -f 6745//6745 5266//5266 5287//5287 -f 6745//6745 5287//5287 6746//6746 -f 6746//6746 5287//5287 5286//5286 -f 6746//6746 5286//5286 6747//6747 -f 6747//6747 5286//5286 5283//5283 -f 6747//6747 5283//5283 6748//6748 -f 6748//6748 5283//5283 5281//5281 -f 6748//6748 5281//5281 6749//6749 -f 6749//6749 5281//5281 5280//5280 -f 6749//6749 5280//5280 6750//6750 -f 5280//5280 5278//5278 6750//6750 -f 6750//6750 5278//5278 5276//5276 -f 6750//6750 5276//5276 6751//6751 -f 5276//5276 5274//5274 6751//6751 -f 6751//6751 5274//5274 5272//5272 -f 6751//6751 5272//5272 6752//6752 -f 5272//5272 5270//5270 6752//6752 -f 6752//6752 5270//5270 5268//5268 -f 6752//6752 5268//5268 6753//6753 -f 6753//6753 5268//5268 5921//5921 -f 6753//6753 5921//5921 6754//6754 -f 6754//6754 5921//5921 5919//5919 -f 6754//6754 5919//5919 6755//6755 -f 6755//6755 5919//5919 5918//5918 -f 6755//6755 5918//5918 6756//6756 -f 6756//6756 5918//5918 5916//5916 -f 6756//6756 5916//5916 6757//6757 -f 5916//5916 5914//5914 6757//6757 -f 6757//6757 5914//5914 5913//5913 -f 6757//6757 5913//5913 6758//6758 -f 6758//6758 5913//5913 5911//5911 -f 6758//6758 5911//5911 6759//6759 -f 6759//6759 5911//5911 5909//5909 -f 6759//6759 5909//5909 6760//6760 -f 6760//6760 5909//5909 5907//5907 -f 6760//6760 5907//5907 6761//6761 -f 6761//6761 5907//5907 5904//5904 -f 6761//6761 5904//5904 6762//6762 -f 6762//6762 5904//5904 5898//5898 -f 6762//6762 5898//5898 6763//6763 -f 6763//6763 5898//5898 5896//5896 -f 6763//6763 5896//5896 6764//6764 -f 6764//6764 5896//5896 5902//5902 -f 6764//6764 5902//5902 6765//6765 -f 6765//6765 5902//5902 5901//5901 -f 6765//6765 5901//5901 6766//6766 -f 6766//6766 5901//5901 5892//5892 -f 6766//6766 5892//5892 6771//6771 -f 6771//6771 5892//5892 5890//5890 -f 6771//6771 5890//5890 6770//6770 -f 6770//6770 5890//5890 5888//5888 -f 6770//6770 5888//5888 6769//6769 -f 6769//6769 5888//5888 5257//5257 -f 6769//6769 5257//5257 6768//6768 -f 5257//5257 5259//5259 6768//6768 -f 6768//6768 5259//5259 5261//5261 -f 6768//6768 5261//5261 6767//6767 -f 6767//6767 5261//5261 5253//5253 -f 6767//6767 5253//5253 6775//6775 -f 6775//6775 5253//5253 6774//6774 -f 5253//5253 5255//5255 6774//6774 -f 6774//6774 5255//5255 5256//5256 -f 6774//6774 5256//5256 6773//6773 -f 6773//6773 5256//5256 5251//5251 -f 6773//6773 5251//5251 6772//6772 -f 6772//6772 5251//5251 5250//5250 -f 6772//6772 5250//5250 6776//6776 -f 6776//6776 5250//5250 5247//5247 -f 6776//6776 5247//5247 6777//6777 -f 6777//6777 5247//5247 5228//5228 -f 6777//6777 5228//5228 6650//6650 -f 6785//6785 6786//6786 6127//6127 -f 6127//6127 6786//6786 6129//6129 -f 6129//6129 6786//6786 6787//6787 -f 6129//6129 6787//6787 6131//6131 -f 6131//6131 6787//6787 6788//6788 -f 6131//6131 6788//6788 6132//6132 -f 6132//6132 6788//6788 6124//6124 -f 6124//6124 6788//6788 6789//6789 -f 6124//6124 6789//6789 6121//6121 -f 6121//6121 6789//6789 6790//6790 -f 6121//6121 6790//6790 6119//6119 -f 6119//6119 6790//6790 6791//6791 -f 6119//6119 6791//6791 6117//6117 -f 6117//6117 6791//6791 6115//6115 -f 6115//6115 6791//6791 6792//6792 -f 6115//6115 6792//6792 6098//6098 -f 6098//6098 6792//6792 6099//6099 -f 6099//6099 6792//6792 6793//6793 -f 6099//6099 6793//6793 6112//6112 -f 6793//6793 6794//6794 6112//6112 -f 6112//6112 6794//6794 6795//6795 -f 6112//6112 6795//6795 6110//6110 -f 6110//6110 6795//6795 6107//6107 -f 6107//6107 6795//6795 6796//6796 -f 6107//6107 6796//6796 6105//6105 -f 6105//6105 6796//6796 6103//6103 -f 6103//6103 6796//6796 6797//6797 -f 6103//6103 6797//6797 6101//6101 -f 6101//6101 6797//6797 6798//6798 -f 6101//6101 6798//6798 5478//5478 -f 5478//5478 6798//6798 6799//6799 -f 5478//5478 6799//6799 5480//5480 -f 5480//5480 6799//6799 6800//6800 -f 5480//5480 6800//6800 5482//5482 -f 5482//5482 6800//6800 5483//5483 -f 5483//5483 6800//6800 6801//6801 -f 5483//5483 6801//6801 5485//5485 -f 5485//5485 6801//6801 6802//6802 -f 5485//5485 6802//6802 5486//5486 -f 5486//5486 6802//6802 6803//6803 -f 5486//5486 6803//6803 5468//5468 -f 5468//5468 6803//6803 6804//6804 -f 5468//5468 6804//6804 5469//5469 -f 5469//5469 6804//6804 5471//5471 -f 5471//5471 6804//6804 6805//6805 -f 5471//5471 6805//6805 5473//5473 -f 5473//5473 6805//6805 6806//6806 -f 5473//5473 6806//6806 5475//5475 -f 5475//5475 6806//6806 6807//6807 -f 5475//5475 6807//6807 5476//5476 -f 5476//5476 6807//6807 5464//5464 -f 5464//5464 6807//6807 6808//6808 -f 5464//5464 6808//6808 5465//5465 -f 5465//5465 6808//6808 6809//6809 -f 5465//5465 6809//6809 5466//5466 -f 5466//5466 6809//6809 5467//5467 -f 5467//5467 6809//6809 6810//6810 -f 5467//5467 6810//6810 5456//5456 -f 5456//5456 6810//6810 6811//6811 -f 5456//5456 6811//6811 5458//5458 -f 5458//5458 6811//6811 6812//6812 -f 5458//5458 6812//6812 5460//5460 -f 5460//5460 6812//6812 6813//6813 -f 5460//5460 6813//6813 5461//5461 -f 5461//5461 6813//6813 6814//6814 -f 5461//5461 6814//6814 5451//5451 -f 5451//5451 6814//6814 6815//6815 -f 5451//5451 6815//6815 5453//5453 -f 5453//5453 6815//6815 5454//5454 -f 5454//5454 6815//6815 6816//6816 -f 5454//5454 6816//6816 6095//6095 -f 6816//6816 6817//6817 6095//6095 -f 6095//6095 6817//6817 6818//6818 -f 6095//6095 6818//6818 6093//6093 -f 6093//6093 6818//6818 6090//6090 -f 6090//6090 6818//6818 6819//6819 -f 6090//6090 6819//6819 6088//6088 -f 6088//6088 6819//6819 6820//6820 -f 6088//6088 6820//6820 6086//6086 -f 6086//6086 6820//6820 6821//6821 -f 6086//6086 6821//6821 6084//6084 -f 6084//6084 6821//6821 6082//6082 -f 6082//6082 6821//6821 6822//6822 -f 6082//6082 6822//6822 6080//6080 -f 6822//6822 6823//6823 6080//6080 -f 6080//6080 6823//6823 6824//6824 -f 6080//6080 6824//6824 6078//6078 -f 6078//6078 6824//6824 6825//6825 -f 6078//6078 6825//6825 6077//6077 -f 6077//6077 6825//6825 6826//6826 -f 6077//6077 6826//6826 6075//6075 -f 6075//6075 6826//6826 6827//6827 -f 6075//6075 6827//6827 6065//6065 -f 6065//6065 6827//6827 6828//6828 -f 6065//6065 6828//6828 6067//6067 -f 6067//6067 6828//6828 6829//6829 -f 6067//6067 6829//6829 6069//6069 -f 6069//6069 6829//6829 6830//6830 -f 6069//6069 6830//6830 6071//6071 -f 6071//6071 6830//6830 6831//6831 -f 6071//6071 6831//6831 6072//6072 -f 6072//6072 6831//6831 6832//6832 -f 6072//6072 6832//6832 5446//5446 -f 5446//5446 6832//6832 6833//6833 -f 5446//5446 6833//6833 5444//5444 -f 5444//5444 6833//6833 6834//6834 -f 5444//5444 6834//6834 5442//5442 -f 5442//5442 6834//6834 6835//6835 -f 5442//5442 6835//6835 5440//5440 -f 5440//5440 6835//6835 6836//6836 -f 5440//5440 6836//6836 5438//5438 -f 5438//5438 6836//6836 6837//6837 -f 5438//5438 6837//6837 5436//5436 -f 5436//5436 6837//6837 6838//6838 -f 5436//5436 6838//6838 5412//5412 -f 5412//5412 6838//6838 6839//6839 -f 5412//5412 6839//6839 5413//5413 -f 5413//5413 6839//6839 6840//6840 -f 5413//5413 6840//6840 5433//5433 -f 5433//5433 6840//6840 6841//6841 -f 5433//5433 6841//6841 5432//5432 -f 5432//5432 6841//6841 6842//6842 -f 5432//5432 6842//6842 5430//5430 -f 5430//5430 6842//6842 6843//6843 -f 5430//5430 6843//6843 5427//5427 -f 5427//5427 6843//6843 6844//6844 -f 6845//6845 5423//5423 6844//6844 -f 6844//6844 5423//5423 5425//5425 -f 6844//6844 5425//5425 5427//5427 -f 6846//6846 5419//5419 6845//6845 -f 6845//6845 5419//5419 5421//5421 -f 6845//6845 5421//5421 5423//5423 -f 6847//6847 5415//5415 6846//6846 -f 6846//6846 5415//5415 5417//5417 -f 6846//6846 5417//5417 5419//5419 -f 6848//6848 6061//6061 6847//6847 -f 6847//6847 6061//6061 6063//6063 -f 6847//6847 6063//6063 5415//5415 -f 6849//6849 6051//6051 6850//6850 -f 6850//6850 6051//6051 6053//6053 -f 6850//6850 6053//6053 6851//6851 -f 6851//6851 6053//6053 6056//6056 -f 6851//6851 6056//6056 6848//6848 -f 6848//6848 6056//6056 6058//6058 -f 6848//6848 6058//6058 6061//6061 -f 6852//6852 6046//6046 6853//6853 -f 6853//6853 6046//6046 6047//6047 -f 6853//6853 6047//6047 6849//6849 -f 6849//6849 6047//6047 6049//6049 -f 6849//6849 6049//6049 6051//6051 -f 6854//6854 6038//6038 6855//6855 -f 6855//6855 6038//6038 6040//6040 -f 6855//6855 6040//6040 6852//6852 -f 6852//6852 6040//6040 6044//6044 -f 6852//6852 6044//6044 6046//6046 -f 6856//6856 6035//6035 6857//6857 -f 6857//6857 6035//6035 6041//6041 -f 6857//6857 6041//6041 6854//6854 -f 6854//6854 6041//6041 6036//6036 -f 6854//6854 6036//6036 6038//6038 -f 6858//6858 5406//5406 6859//6859 -f 6859//6859 5406//5406 6028//6028 -f 6859//6859 6028//6028 6860//6860 -f 6860//6860 6028//6028 6030//6030 -f 6860//6860 6030//6030 6861//6861 -f 6861//6861 6030//6030 6032//6032 -f 6861//6861 6032//6032 6856//6856 -f 6856//6856 6032//6032 6034//6034 -f 6856//6856 6034//6034 6035//6035 -f 5393//5393 5400//5400 6862//6862 -f 6862//6862 5400//5400 5402//5402 -f 6862//6862 5402//5402 6863//6863 -f 6863//6863 5402//5402 5411//5411 -f 6863//6863 5411//5411 6864//6864 -f 6864//6864 5411//5411 5410//5410 -f 6864//6864 5410//5410 6858//6858 -f 6858//6858 5410//5410 5408//5408 -f 6858//6858 5408//5408 5406//5406 -f 6862//6862 6865//6865 5393//5393 -f 5393//5393 6865//6865 6866//6866 -f 5393//5393 6866//6866 5394//5394 -f 5394//5394 6866//6866 6867//6867 -f 5394//5394 6867//6867 5396//5396 -f 5396//5396 6867//6867 6868//6868 -f 5396//5396 6868//6868 5397//5397 -f 5397//5397 6868//6868 6869//6869 -f 5397//5397 6869//6869 5377//5377 -f 5377//5377 6869//6869 6870//6870 -f 5377//5377 6870//6870 5379//5379 -f 5379//5379 6870//6870 6871//6871 -f 5379//5379 6871//6871 5381//5381 -f 5381//5381 6871//6871 6872//6872 -f 5381//5381 6872//6872 5383//5383 -f 5383//5383 6872//6872 6873//6873 -f 5391//5391 5392//5392 6874//6874 -f 6874//6874 5392//5392 5387//5387 -f 6874//6874 5387//5387 6873//6873 -f 6873//6873 5387//5387 5385//5385 -f 6873//6873 5385//5385 5383//5383 -f 5391//5391 6874//6874 5389//5389 -f 5389//5389 6874//6874 6875//6875 -f 5389//5389 6875//6875 6027//6027 -f 6027//6027 6875//6875 6025//6025 -f 6025//6025 6875//6875 6876//6876 -f 6025//6025 6876//6876 6023//6023 -f 6023//6023 6876//6876 6877//6877 -f 6023//6023 6877//6877 6021//6021 -f 6021//6021 6877//6877 6878//6878 -f 6021//6021 6878//6878 6019//6019 -f 6019//6019 6878//6878 6017//6017 -f 6017//6017 6878//6878 6879//6879 -f 6017//6017 6879//6879 6015//6015 -f 6879//6879 6880//6880 6015//6015 -f 6015//6015 6880//6880 6881//6881 -f 6015//6015 6881//6881 6013//6013 -f 6013//6013 6881//6881 6882//6882 -f 6013//6013 6882//6882 6011//6011 -f 6011//6011 6882//6882 6009//6009 -f 6009//6009 6882//6882 6883//6883 -f 6009//6009 6883//6883 6006//6006 -f 6883//6883 6884//6884 6006//6006 -f 6006//6006 6884//6884 6885//6885 -f 6006//6006 6885//6885 6005//6005 -f 6005//6005 6885//6885 6886//6886 -f 6005//6005 6886//6886 6003//6003 -f 6003//6003 6886//6886 6887//6887 -f 6003//6003 6887//6887 6001//6001 -f 6001//6001 6887//6887 6888//6888 -f 6889//6889 5374//5374 6890//6890 -f 6890//6890 5374//5374 5372//5372 -f 6890//6890 5372//5372 6891//6891 -f 6891//6891 5372//5372 5995//5995 -f 6891//6891 5995//5995 6892//6892 -f 6892//6892 5995//5995 5993//5993 -f 6892//6892 5993//5993 6893//6893 -f 6893//6893 5993//5993 5992//5992 -f 6893//6893 5992//5992 6888//6888 -f 6888//6888 5992//5992 5999//5999 -f 6888//6888 5999//5999 6001//6001 -f 6894//6894 5363//5363 6895//6895 -f 6895//6895 5363//5363 5364//5364 -f 6895//6895 5364//5364 6896//6896 -f 6896//6896 5364//5364 5366//5366 -f 6896//6896 5366//5366 6897//6897 -f 6897//6897 5366//5366 5368//5368 -f 6897//6897 5368//5368 6889//6889 -f 6889//6889 5368//5368 5375//5375 -f 6889//6889 5375//5375 5374//5374 -f 6898//6898 5359//5359 6894//6894 -f 6894//6894 5359//5359 5361//5361 -f 6894//6894 5361//5361 5363//5363 -f 6898//6898 6899//6899 5359//5359 -f 5359//5359 6899//6899 6784//6784 -f 5359//5359 6784//6784 5357//5357 -f 6127//6127 5495//5495 6785//6785 -f 6785//6785 5495//5495 5493//5493 -f 6785//6785 5493//5493 6900//6900 -f 6900//6900 5493//5493 5491//5491 -f 6900//6900 5491//5491 6901//6901 -f 6901//6901 5491//5491 5490//5490 -f 6901//6901 5490//5490 6902//6902 -f 6902//6902 5490//5490 5499//5499 -f 6902//6902 5499//5499 6903//6903 -f 6903//6903 5499//5499 5501//5501 -f 6903//6903 5501//5501 6904//6904 -f 5501//5501 5503//5503 6904//6904 -f 6904//6904 5503//5503 5506//5506 -f 6904//6904 5506//5506 6905//6905 -f 6905//6905 5506//5506 5508//5508 -f 6905//6905 5508//5508 6906//6906 -f 6906//6906 5544//5544 5546//5546 -f 6906//6906 5546//5546 6905//6905 -f 6905//6905 5546//5546 5525//5525 -f 6905//6905 5525//5525 6904//6904 -f 6904//6904 5525//5525 6903//6903 -f 6903//6903 5525//5525 5527//5527 -f 6903//6903 5527//5527 6902//6902 -f 6902//6902 5527//5527 5529//5529 -f 6902//6902 5529//5529 6901//6901 -f 6901//6901 5529//5529 5535//5535 -f 6901//6901 5535//5535 6900//6900 -f 5535//5535 5533//5533 6900//6900 -f 6900//6900 5533//5533 5531//5531 -f 6900//6900 5531//5531 6785//6785 -f 6785//6785 5531//5531 6159//6159 -f 6785//6785 6159//6159 6786//6786 -f 6786//6786 6159//6159 6161//6161 -f 6786//6786 6161//6161 6787//6787 -f 6787//6787 6161//6161 6163//6163 -f 6787//6787 6163//6163 6788//6788 -f 6163//6163 6165//6165 6788//6788 -f 6788//6788 6165//6165 6167//6167 -f 6788//6788 6167//6167 6789//6789 -f 6789//6789 6167//6167 6157//6157 -f 6789//6789 6157//6157 6790//6790 -f 6790//6790 6157//6157 6155//6155 -f 6790//6790 6155//6155 6791//6791 -f 6155//6155 6154//6154 6791//6791 -f 6791//6791 6154//6154 6152//6152 -f 6791//6791 6152//6152 6792//6792 -f 6152//6152 6150//6150 6792//6792 -f 6792//6792 6150//6150 6148//6148 -f 6792//6792 6148//6148 6793//6793 -f 6793//6793 6148//6148 6145//6145 -f 6793//6793 6145//6145 6794//6794 -f 6794//6794 6145//6145 6143//6143 -f 6794//6794 6143//6143 6795//6795 -f 6143//6143 6141//6141 6795//6795 -f 6795//6795 6141//6141 6139//6139 -f 6795//6795 6139//6139 6796//6796 -f 6796//6796 6139//6139 6138//6138 -f 6796//6796 6138//6138 6797//6797 -f 6797//6797 6138//6138 6135//6135 -f 6797//6797 6135//6135 6798//6798 -f 6135//6135 6137//6137 6798//6798 -f 6798//6798 6137//6137 5520//5520 -f 6798//6798 5520//5520 6799//6799 -f 6799//6799 5520//5520 5519//5519 -f 6799//6799 5519//5519 6800//6800 -f 6800//6800 5519//5519 5488//5488 -f 6800//6800 5488//5488 6801//6801 -f 6801//6801 5488//5488 5487//5487 -f 6801//6801 5487//5487 6802//6802 -f 6802//6802 5487//5487 5518//5518 -f 6802//6802 5518//5518 6803//6803 -f 6803//6803 5518//5518 5517//5517 -f 6803//6803 5517//5517 6804//6804 -f 6804//6804 5517//5517 5513//5513 -f 6804//6804 5513//5513 6805//6805 -f 6805//6805 5513//5513 5511//5511 -f 6812//6812 6811//6811 5502//5502 -f 5502//5502 6811//6811 5504//5504 -f 5504//5504 6811//6811 6810//6810 -f 5504//5504 6810//6810 5505//5505 -f 5505//5505 6810//6810 6809//6809 -f 5505//5505 6809//6809 5507//5507 -f 5507//5507 6809//6809 6808//6808 -f 5507//5507 6808//6808 5509//5509 -f 5509//5509 6808//6808 6807//6807 -f 5509//5509 6807//6807 5511//5511 -f 5511//5511 6807//6807 6806//6806 -f 5511//5511 6806//6806 6805//6805 -f 5502//5502 5500//5500 6812//6812 -f 6812//6812 5500//5500 5498//5498 -f 6812//6812 5498//5498 6813//6813 -f 6813//6813 5498//5498 5497//5497 -f 6813//6813 5497//5497 6814//6814 -f 6814//6814 5497//5497 5492//5492 -f 6814//6814 5492//5492 6815//6815 -f 5492//5492 5494//5494 6815//6815 -f 6815//6815 5494//5494 5496//5496 -f 6815//6815 5496//5496 6816//6816 -f 6816//6816 5496//5496 6126//6126 -f 6816//6816 6126//6126 6817//6817 -f 6126//6126 6128//6128 6817//6817 -f 6817//6817 6128//6128 6130//6130 -f 6817//6817 6130//6130 6818//6818 -f 6818//6818 6130//6130 6125//6125 -f 6818//6818 6125//6125 6819//6819 -f 6819//6819 6125//6125 6123//6123 -f 6819//6819 6123//6123 6820//6820 -f 6820//6820 6123//6123 6122//6122 -f 6820//6820 6122//6122 6821//6821 -f 6821//6821 6122//6122 6120//6120 -f 6821//6821 6120//6120 6822//6822 -f 6822//6822 6120//6120 6118//6118 -f 6822//6822 6118//6118 6823//6823 -f 6823//6823 6118//6118 6116//6116 -f 6823//6823 6116//6116 6824//6824 -f 6824//6824 6116//6116 6100//6100 -f 6824//6824 6100//6100 6825//6825 -f 6825//6825 6100//6100 6114//6114 -f 6825//6825 6114//6114 6826//6826 -f 6114//6114 6113//6113 6826//6826 -f 6826//6826 6113//6113 6111//6111 -f 6826//6826 6111//6111 6827//6827 -f 6827//6827 6111//6111 6109//6109 -f 6827//6827 6109//6109 6828//6828 -f 6828//6828 6109//6109 6108//6108 -f 6828//6828 6108//6108 6829//6829 -f 6829//6829 6108//6108 6106//6106 -f 6829//6829 6106//6106 6830//6830 -f 6830//6830 6106//6106 6104//6104 -f 6830//6830 6104//6104 6831//6831 -f 6831//6831 6104//6104 6102//6102 -f 6831//6831 6102//6102 6832//6832 -f 6832//6832 6102//6102 5477//5477 -f 6832//6832 5477//5477 6833//6833 -f 6833//6833 5477//5477 5479//5479 -f 6833//6833 5479//5479 6834//6834 -f 6834//6834 5479//5479 5481//5481 -f 6834//6834 5481//5481 6835//6835 -f 6835//6835 5481//5481 5484//5484 -f 6835//6835 5484//5484 6836//6836 -f 6836//6836 5484//5484 5470//5470 -f 5463//5463 6841//6841 6840//6840 -f 5463//5463 6840//6840 5474//5474 -f 5474//5474 6840//6840 6839//6839 -f 5474//5474 6839//6839 5472//5472 -f 5472//5472 6839//6839 6838//6838 -f 5472//5472 6838//6838 5470//5470 -f 5470//5470 6838//6838 6837//6837 -f 5470//5470 6837//6837 6836//6836 -f 6841//6841 5463//5463 6842//6842 -f 6842//6842 5463//5463 5462//5462 -f 6842//6842 5462//5462 6843//6843 -f 5462//5462 5455//5455 6843//6843 -f 6843//6843 5455//5455 5457//5457 -f 6843//6843 5457//5457 6844//6844 -f 6844//6844 5457//5457 5459//5459 -f 6844//6844 5459//5459 6845//6845 -f 6845//6845 5459//5459 5450//5450 -f 6845//6845 5450//5450 6846//6846 -f 5450//5450 5449//5449 6846//6846 -f 6846//6846 5449//5449 5452//5452 -f 6846//6846 5452//5452 6847//6847 -f 6094//6094 6848//6848 6096//6096 -f 6096//6096 6848//6848 6847//6847 -f 6096//6096 6847//6847 6097//6097 -f 6097//6097 6847//6847 5452//5452 -f 6094//6094 6092//6092 6848//6848 -f 6848//6848 6092//6092 6091//6091 -f 6848//6848 6091//6091 6851//6851 -f 6091//6091 6089//6089 6851//6851 -f 6851//6851 6089//6089 6087//6087 -f 6851//6851 6087//6087 6850//6850 -f 6850//6850 6087//6087 6085//6085 -f 6850//6850 6085//6085 6849//6849 -f 6849//6849 6085//6085 6083//6083 -f 6849//6849 6083//6083 6853//6853 -f 6853//6853 6083//6083 6081//6081 -f 6853//6853 6081//6081 6852//6852 -f 6852//6852 6081//6081 6079//6079 -f 6852//6852 6079//6079 6855//6855 -f 6855//6855 6079//6079 6076//6076 -f 6855//6855 6076//6076 6854//6854 -f 6076//6076 6074//6074 6854//6854 -f 6854//6854 6074//6074 6073//6073 -f 6854//6854 6073//6073 6857//6857 -f 6857//6857 6073//6073 6064//6064 -f 6857//6857 6064//6064 6856//6856 -f 6064//6064 6066//6066 6856//6856 -f 6856//6856 6066//6066 6068//6068 -f 6856//6856 6068//6068 6861//6861 -f 6861//6861 6068//6068 6070//6070 -f 6861//6861 6070//6070 6860//6860 -f 6860//6860 6070//6070 6859//6859 -f 6859//6859 6070//6070 5448//5448 -f 6859//6859 5448//5448 6858//6858 -f 6858//6858 5448//5448 5447//5447 -f 6858//6858 5447//5447 6864//6864 -f 6864//6864 5447//5447 5445//5445 -f 6864//6864 5445//5445 6863//6863 -f 5445//5445 5443//5443 6863//6863 -f 6863//6863 5443//5443 5441//5441 -f 6863//6863 5441//5441 6862//6862 -f 6862//6862 5441//5441 5439//5439 -f 6862//6862 5439//5439 6865//6865 -f 6865//6865 5439//5439 5437//5437 -f 6865//6865 5437//5437 6866//6866 -f 6866//6866 5437//5437 5414//5414 -f 6866//6866 5414//5414 6867//6867 -f 6867//6867 5414//5414 5435//5435 -f 6867//6867 5435//5435 6868//6868 -f 6868//6868 5435//5435 5434//5434 -f 6868//6868 5434//5434 6869//6869 -f 6869//6869 5434//5434 5431//5431 -f 6869//6869 5431//5431 6870//6870 -f 6870//6870 5431//5431 5429//5429 -f 6870//6870 5429//5429 6871//6871 -f 6871//6871 5429//5429 5428//5428 -f 6871//6871 5428//5428 6872//6872 -f 5428//5428 5426//5426 6872//6872 -f 6872//6872 5426//5426 5424//5424 -f 6872//6872 5424//5424 6873//6873 -f 5424//5424 5422//5422 6873//6873 -f 6873//6873 5422//5422 5420//5420 -f 6873//6873 5420//5420 6874//6874 -f 5420//5420 5418//5418 6874//6874 -f 6874//6874 5418//5418 5416//5416 -f 6874//6874 5416//5416 6875//6875 -f 6875//6875 5416//5416 6062//6062 -f 6875//6875 6062//6062 6876//6876 -f 6876//6876 6062//6062 6060//6060 -f 6876//6876 6060//6060 6877//6877 -f 6877//6877 6060//6060 6059//6059 -f 6877//6877 6059//6059 6878//6878 -f 6878//6878 6059//6059 6057//6057 -f 6878//6878 6057//6057 6879//6879 -f 6057//6057 6055//6055 6879//6879 -f 6879//6879 6055//6055 6054//6054 -f 6879//6879 6054//6054 6880//6880 -f 6880//6880 6054//6054 6052//6052 -f 6880//6880 6052//6052 6881//6881 -f 6881//6881 6052//6052 6050//6050 -f 6881//6881 6050//6050 6882//6882 -f 6882//6882 6050//6050 6048//6048 -f 6882//6882 6048//6048 6883//6883 -f 6883//6883 6048//6048 6045//6045 -f 6883//6883 6045//6045 6884//6884 -f 6884//6884 6045//6045 6039//6039 -f 6884//6884 6039//6039 6885//6885 -f 6885//6885 6039//6039 6037//6037 -f 6885//6885 6037//6037 6886//6886 -f 6886//6886 6037//6037 6043//6043 -f 6886//6886 6043//6043 6887//6887 -f 6887//6887 6043//6043 6042//6042 -f 6887//6887 6042//6042 6888//6888 -f 6888//6888 6042//6042 6033//6033 -f 6888//6888 6033//6033 6893//6893 -f 6893//6893 6033//6033 6031//6031 -f 6893//6893 6031//6031 6892//6892 -f 6892//6892 6031//6031 6029//6029 -f 6892//6892 6029//6029 6891//6891 -f 6891//6891 6029//6029 5405//5405 -f 6891//6891 5405//5405 6890//6890 -f 5405//5405 5407//5407 6890//6890 -f 6890//6890 5407//5407 5409//5409 -f 6890//6890 5409//5409 6889//6889 -f 6889//6889 5409//5409 5401//5401 -f 6889//6889 5401//5401 6897//6897 -f 6897//6897 5401//5401 6896//6896 -f 5401//5401 5403//5403 6896//6896 -f 6896//6896 5403//5403 5404//5404 -f 6896//6896 5404//5404 6895//6895 -f 6895//6895 5404//5404 5399//5399 -f 6895//6895 5399//5399 6894//6894 -f 6894//6894 5399//5399 5398//5398 -f 6894//6894 5398//5398 6898//6898 -f 6898//6898 5398//5398 5395//5395 -f 6898//6898 5395//5395 6899//6899 -f 6899//6899 5395//5395 5376//5376 -f 6899//6899 5376//5376 6784//6784 -f 6196//6196 6195//6195 6907//6907 -f 6908//6908 6909//6909 5643//5643 -f 5643//5643 6909//6909 6910//6910 -f 5643//5643 6910//6910 5641//5641 -f 5641//5641 6910//6910 6911//6911 -f 5641//5641 6911//6911 6280//6280 -f 6280//6280 6911//6911 6912//6912 -f 6280//6280 6912//6912 6278//6278 -f 6278//6278 6912//6912 6913//6913 -f 6914//6914 6274//6274 6913//6913 -f 6913//6913 6274//6274 6276//6276 -f 6913//6913 6276//6276 6278//6278 -f 6915//6915 6269//6269 6916//6916 -f 6916//6916 6269//6269 6268//6268 -f 6916//6916 6268//6268 6917//6917 -f 6917//6917 6268//6268 6266//6266 -f 6917//6917 6266//6266 6918//6918 -f 6918//6918 6266//6266 6265//6265 -f 6918//6918 6265//6265 6914//6914 -f 6914//6914 6265//6265 6272//6272 -f 6914//6914 6272//6272 6274//6274 -f 6919//6919 6250//6250 6920//6920 -f 6920//6920 6250//6250 6252//6252 -f 6920//6920 6252//6252 6921//6921 -f 6921//6921 6252//6252 6254//6254 -f 6921//6921 6254//6254 6922//6922 -f 6922//6922 6254//6254 6257//6257 -f 6922//6922 6257//6257 6923//6923 -f 6923//6923 6257//6257 6259//6259 -f 6923//6923 6259//6259 6924//6924 -f 6924//6924 6259//6259 6260//6260 -f 6924//6924 6260//6260 6915//6915 -f 6915//6915 6260//6260 6262//6262 -f 6915//6915 6262//6262 6269//6269 -f 5640//5640 5639//5639 6925//6925 -f 6925//6925 5639//5639 5637//5637 -f 6925//6925 5637//5637 6919//6919 -f 6919//6919 5637//5637 6248//6248 -f 6919//6919 6248//6248 6250//6250 -f 5640//5640 6925//6925 5634//5634 -f 5634//5634 6925//6925 6926//6926 -f 5634//5634 6926//6926 5635//5635 -f 6927//6927 5623//5623 6926//6926 -f 6926//6926 5623//5623 5622//5622 -f 6926//6926 5622//5622 5635//5635 -f 6928//6928 5628//5628 6929//6929 -f 6929//6929 5628//5628 5627//5627 -f 6929//6929 5627//5627 6927//6927 -f 6927//6927 5627//5627 5625//5625 -f 6927//6927 5625//5625 5623//5623 -f 5621//5621 5620//5620 6930//6930 -f 6930//6930 5620//5620 5619//5619 -f 6930//6930 5619//5619 6931//6931 -f 6931//6931 5619//5619 5618//5618 -f 6931//6931 5618//5618 6932//6932 -f 6932//6932 5618//5618 5631//5631 -f 6932//6932 5631//5631 6928//6928 -f 6928//6928 5631//5631 5630//5630 -f 6928//6928 5630//5630 5628//5628 -f 5621//5621 6930//6930 5610//5610 -f 5610//5610 6930//6930 6933//6933 -f 5610//5610 6933//6933 5611//5611 -f 5611//5611 6933//6933 6934//6934 -f 5611//5611 6934//6934 5612//5612 -f 5612//5612 6934//6934 6935//6935 -f 5612//5612 6935//6935 5614//5614 -f 5614//5614 6935//6935 6936//6936 -f 5614//5614 6936//6936 5615//5615 -f 5615//5615 6936//6936 5604//5604 -f 5604//5604 6936//6936 6937//6937 -f 5604//5604 6937//6937 5606//5606 -f 5606//5606 6937//6937 5607//5607 -f 5607//5607 6937//6937 6938//6938 -f 5607//5607 6938//6938 6245//6245 -f 6245//6245 6938//6938 6231//6231 -f 6231//6231 6938//6938 6939//6939 -f 6231//6231 6939//6939 6232//6232 -f 6232//6232 6939//6939 6940//6940 -f 6232//6232 6940//6940 6234//6234 -f 6234//6234 6940//6940 6941//6941 -f 6234//6234 6941//6941 6235//6235 -f 6235//6235 6941//6941 6942//6942 -f 6235//6235 6942//6942 6237//6237 -f 6237//6237 6942//6942 6239//6239 -f 6239//6239 6942//6942 6943//6943 -f 6239//6239 6943//6943 6241//6241 -f 6241//6241 6943//6943 6944//6944 -f 6241//6241 6944//6944 6243//6243 -f 6243//6243 6944//6944 6945//6945 -f 6243//6243 6945//6945 6244//6244 -f 6244//6244 6945//6945 6228//6228 -f 6228//6228 6945//6945 6946//6946 -f 6228//6228 6946//6946 6229//6229 -f 6229//6229 6946//6946 6947//6947 -f 6229//6229 6947//6947 6224//6224 -f 6224//6224 6947//6947 6948//6948 -f 6224//6224 6948//6948 6222//6222 -f 6222//6222 6948//6948 6949//6949 -f 6222//6222 6949//6949 6220//6220 -f 6950//6950 6216//6216 6949//6949 -f 6949//6949 6216//6216 6218//6218 -f 6949//6949 6218//6218 6220//6220 -f 6951//6951 5597//5597 6952//6952 -f 6952//6952 5597//5597 5599//5599 -f 6952//6952 5599//5599 6953//6953 -f 6953//6953 5599//5599 6211//6211 -f 6953//6953 6211//6211 6954//6954 -f 6954//6954 6211//6211 6213//6213 -f 6954//6954 6213//6213 6950//6950 -f 6950//6950 6213//6213 6214//6214 -f 6950//6950 6214//6214 6216//6216 -f 6955//6955 5588//5588 6956//6956 -f 6956//6956 5588//5588 5590//5590 -f 6956//6956 5590//5590 6957//6957 -f 6957//6957 5590//5590 5592//5592 -f 6957//6957 5592//5592 6958//6958 -f 6958//6958 5592//5592 5594//5594 -f 6958//6958 5594//5594 6951//6951 -f 6951//6951 5594//5594 5595//5595 -f 6951//6951 5595//5595 5597//5597 -f 6959//6959 5565//5565 6955//6955 -f 6955//6955 5565//5565 5564//5564 -f 6955//6955 5564//5564 5588//5588 -f 6960//6960 5583//5583 6959//6959 -f 6959//6959 5583//5583 5585//5585 -f 6959//6959 5585//5585 5565//5565 -f 6961//6961 5569//5569 6960//6960 -f 6960//6960 5569//5569 5568//5568 -f 6960//6960 5568//5568 5583//5583 -f 6962//6962 6203//6203 6963//6963 -f 6963//6963 6203//6203 6201//6201 -f 6963//6963 6201//6201 6964//6964 -f 6964//6964 6201//6201 5570//5570 -f 6964//6964 5570//5570 6965//6965 -f 6965//6965 5570//5570 5572//5572 -f 6965//6965 5572//5572 6966//6966 -f 6966//6966 5572//5572 5574//5574 -f 6966//6966 5574//5574 6967//6967 -f 6967//6967 5574//5574 5576//5576 -f 6967//6967 5576//5576 6968//6968 -f 6968//6968 5576//5576 5578//5578 -f 6968//6968 5578//5578 6961//6961 -f 6961//6961 5578//5578 5580//5580 -f 6961//6961 5580//5580 5569//5569 -f 6195//6195 6193//6193 6907//6907 -f 6907//6907 6193//6193 6191//6191 -f 6907//6907 6191//6191 6969//6969 -f 6969//6969 6191//6191 6210//6210 -f 6969//6969 6210//6210 6970//6970 -f 6970//6970 6210//6210 6209//6209 -f 6970//6970 6209//6209 6971//6971 -f 6971//6971 6209//6209 6207//6207 -f 6971//6971 6207//6207 6962//6962 -f 6962//6962 6207//6207 6205//6205 -f 6962//6962 6205//6205 6203//6203 -f 6196//6196 6907//6907 6198//6198 -f 6198//6198 6907//6907 6972//6972 -f 6198//6198 6972//6972 6199//6199 -f 6199//6199 6972//6972 6187//6187 -f 6187//6187 6972//6972 6973//6973 -f 6187//6187 6973//6973 6188//6188 -f 6188//6188 6973//6973 6180//6180 -f 6180//6180 6973//6973 6974//6974 -f 6180//6180 6974//6974 6182//6182 -f 6182//6182 6974//6974 6184//6184 -f 6184//6184 6974//6974 6975//6975 -f 6184//6184 6975//6975 6185//6185 -f 6185//6185 6975//6975 6976//6976 -f 6185//6185 6976//6976 6174//6174 -f 6174//6174 6976//6976 6176//6176 -f 6176//6176 6976//6976 6977//6977 -f 6176//6176 6977//6977 6178//6178 -f 6178//6178 6977//6977 6978//6978 -f 6178//6178 6978//6978 6172//6172 -f 6172//6172 6978//6978 6979//6979 -f 6172//6172 6979//6979 6170//6170 -f 6170//6170 6979//6979 6980//6980 -f 6170//6170 6980//6980 5563//5563 -f 5563//5563 6980//6980 5561//5561 -f 5561//5561 6980//6980 6981//6981 -f 5561//5561 6981//6981 5558//5558 -f 5558//5558 6981//6981 6982//6982 -f 5558//5558 6982//6982 5557//5557 -f 5557//5557 6982//6982 5555//5555 -f 5555//5555 6982//6982 6983//6983 -f 5555//5555 6983//6983 5553//5553 -f 6984//6984 5543//5543 6985//6985 -f 6985//6985 5543//5543 5541//5541 -f 6985//6985 5541//5541 6986//6986 -f 6986//6986 5541//5541 5539//5539 -f 6986//6986 5539//5539 6987//6987 -f 6987//6987 5539//5539 5538//5538 -f 6987//6987 5538//5538 6983//6983 -f 6983//6983 5538//5538 5551//5551 -f 6983//6983 5551//5551 5553//5553 -f 5532//5532 5534//5534 6988//6988 -f 6988//6988 5534//5534 5536//5536 -f 6988//6988 5536//5536 6989//6989 -f 6989//6989 5536//5536 5537//5537 -f 6989//6989 5537//5537 6990//6990 -f 6990//6990 5537//5537 5528//5528 -f 6990//6990 5528//5528 6991//6991 -f 6991//6991 5528//5528 5526//5526 -f 6991//6991 5526//5526 6992//6992 -f 6992//6992 5526//5526 5548//5548 -f 6992//6992 5548//5548 6993//6993 -f 6993//6993 5548//5548 5547//5547 -f 6993//6993 5547//5547 6984//6984 -f 6984//6984 5547//5547 5545//5545 -f 6984//6984 5545//5545 5543//5543 -f 5532//5532 6988//6988 5530//5530 -f 5530//5530 6988//6988 6994//6994 -f 5530//5530 6994//6994 6158//6158 -f 6158//6158 6994//6994 6160//6160 -f 6160//6160 6994//6994 6995//6995 -f 6160//6160 6995//6995 6162//6162 -f 6162//6162 6995//6995 6164//6164 -f 6164//6164 6995//6995 6996//6996 -f 6164//6164 6996//6996 6166//6166 -f 6166//6166 6996//6996 6997//6997 -f 6166//6166 6997//6997 6168//6168 -f 6168//6168 6997//6997 6169//6169 -f 6169//6169 6997//6997 6998//6998 -f 6169//6169 6998//6998 6156//6156 -f 6156//6156 6998//6998 6999//6999 -f 6156//6156 6999//6999 6153//6153 -f 6153//6153 6999//6999 7000//7000 -f 6153//6153 7000//7000 6151//6151 -f 6151//6151 7000//7000 7001//7001 -f 6151//6151 7001//7001 6149//6149 -f 6149//6149 7001//7001 6147//6147 -f 6147//6147 7001//7001 7002//7002 -f 6147//6147 7002//7002 6146//6146 -f 6146//6146 7002//7002 7003//7003 -f 6146//6146 7003//7003 6144//6144 -f 6144//6144 7003//7003 7004//7004 -f 6144//6144 7004//7004 6142//6142 -f 6142//6142 7004//7004 7005//7005 -f 6142//6142 7005//7005 6140//6140 -f 6140//6140 7005//7005 7006//7006 -f 6140//6140 7006//7006 6133//6133 -f 6133//6133 7006//7006 7007//7007 -f 6133//6133 7007//7007 6134//6134 -f 6134//6134 7007//7007 6136//6136 -f 6136//6136 7007//7007 7008//7008 -f 6136//6136 7008//7008 5521//5521 -f 5521//5521 7008//7008 7009//7009 -f 5521//5521 7009//7009 5522//5522 -f 5522//5522 7009//7009 5523//5523 -f 5523//5523 7009//7009 7010//7010 -f 5523//5523 7010//7010 5524//5524 -f 5524//5524 7010//7010 5489//5489 -f 5489//5489 7010//7010 7011//7011 -f 5489//5489 7011//7011 5516//5516 -f 5516//5516 7011//7011 5515//5515 -f 5515//5515 7011//7011 7012//7012 -f 5515//5515 7012//7012 5514//5514 -f 5514//5514 7012//7012 7013//7013 -f 5514//5514 7013//7013 5512//5512 -f 5512//5512 7013//7013 7014//7014 -f 5512//5512 7014//7014 5510//5510 -f 5510//5510 7014//7014 6906//6906 -f 5510//5510 6906//6906 5508//5508 -f 5643//5643 5645//5645 6908//6908 -f 6908//6908 5645//5645 5647//5647 -f 6908//6908 5647//5647 7015//7015 -f 7015//7015 5647//5647 5649//5649 -f 7015//7015 5649//5649 7016//7016 -f 7016//7016 5649//5649 5652//5652 -f 7016//7016 5652//5652 7017//7017 -f 7017//7017 5652//5652 5654//5654 -f 7017//7017 5654//5654 7018//7018 -f 7018//7018 5654//5654 5655//5655 -f 7018//7018 5655//5655 7019//7019 -f 5655//5655 5658//5658 7019//7019 -f 7019//7019 5658//5658 5660//5660 -f 7019//7019 5660//5660 7020//7020 -f 7020//7020 5682//5682 5685//5685 -f 7020//7020 5685//5685 7019//7019 -f 7019//7019 5685//5685 5687//5687 -f 7019//7019 5687//5687 7018//7018 -f 7018//7018 5687//5687 7017//7017 -f 7017//7017 5687//5687 5689//5689 -f 7017//7017 5689//5689 7016//7016 -f 7016//7016 5689//5689 5691//5691 -f 7016//7016 5691//5691 7015//7015 -f 7015//7015 5691//5691 5693//5693 -f 7015//7015 5693//5693 6908//6908 -f 6908//6908 5693//5693 5695//5695 -f 6908//6908 5695//5695 6909//6909 -f 6909//6909 5695//5695 5697//5697 -f 6909//6909 5697//5697 6910//6910 -f 6910//6910 5697//5697 6911//6911 -f 6911//6911 5697//5697 6315//6315 -f 6911//6911 6315//6315 6912//6912 -f 6315//6315 6313//6313 6912//6912 -f 6912//6912 6313//6313 6311//6311 -f 6912//6912 6311//6311 6913//6913 -f 6311//6311 6309//6309 6913//6913 -f 6913//6913 6309//6309 6308//6308 -f 6913//6913 6308//6308 6914//6914 -f 6308//6308 6306//6306 6914//6914 -f 6914//6914 6306//6306 6304//6304 -f 6914//6914 6304//6304 6918//6918 -f 6918//6918 6304//6304 6303//6303 -f 6918//6918 6303//6303 6917//6917 -f 6917//6917 6303//6303 6300//6300 -f 6917//6917 6300//6300 6916//6916 -f 6916//6916 6300//6300 6298//6298 -f 6916//6916 6298//6298 6915//6915 -f 6915//6915 6298//6298 6297//6297 -f 6915//6915 6297//6297 6924//6924 -f 6924//6924 6297//6297 6294//6294 -f 6924//6924 6294//6294 6923//6923 -f 6923//6923 6294//6294 6292//6292 -f 6923//6923 6292//6292 6922//6922 -f 6283//6283 6919//6919 6285//6285 -f 6285//6285 6919//6919 6920//6920 -f 6285//6285 6920//6920 6287//6287 -f 6287//6287 6920//6920 6921//6921 -f 6287//6287 6921//6921 6289//6289 -f 6289//6289 6921//6921 6922//6922 -f 6289//6289 6922//6922 6290//6290 -f 6290//6290 6922//6922 6292//6292 -f 6283//6283 5673//5673 6919//6919 -f 6919//6919 5673//5673 5672//5672 -f 6919//6919 5672//5672 6925//6925 -f 5672//5672 5676//5676 6925//6925 -f 6925//6925 5676//5676 5675//5675 -f 6925//6925 5675//5675 6926//6926 -f 5675//5675 5670//5670 6926//6926 -f 6926//6926 5670//5670 5668//5668 -f 6926//6926 5668//5668 6927//6927 -f 6927//6927 5668//5668 5665//5665 -f 6927//6927 5665//5665 6929//6929 -f 6929//6929 5665//5665 5663//5663 -f 6935//6935 6934//6934 5653//5653 -f 5653//5653 6934//6934 5656//5656 -f 5656//5656 6934//6934 6933//6933 -f 5656//5656 6933//6933 5657//5657 -f 5657//5657 6933//6933 6930//6930 -f 5657//5657 6930//6930 5659//5659 -f 5659//5659 6930//6930 6931//6931 -f 5659//5659 6931//6931 5661//5661 -f 5661//5661 6931//6931 6932//6932 -f 5661//5661 6932//6932 5663//5663 -f 5663//5663 6932//6932 6928//6928 -f 5663//5663 6928//6928 6929//6929 -f 5653//5653 5651//5651 6935//6935 -f 6935//6935 5651//5651 5650//5650 -f 6935//6935 5650//5650 6936//6936 -f 5650//5650 5648//5648 6936//6936 -f 6936//6936 5648//5648 5646//5646 -f 6936//6936 5646//5646 6937//6937 -f 5646//5646 5644//5644 6937//6937 -f 6937//6937 5644//5644 5642//5642 -f 6937//6937 5642//5642 6938//6938 -f 6258//6258 6949//6949 6261//6261 -f 6261//6261 6949//6949 6948//6948 -f 6261//6261 6948//6948 6263//6263 -f 6263//6263 6948//6948 6947//6947 -f 6263//6263 6947//6947 6264//6264 -f 6264//6264 6947//6947 6946//6946 -f 6264//6264 6946//6946 6267//6267 -f 6267//6267 6946//6946 6945//6945 -f 6267//6267 6945//6945 6270//6270 -f 6270//6270 6945//6945 6944//6944 -f 6270//6270 6944//6944 6271//6271 -f 6271//6271 6944//6944 6943//6943 -f 6271//6271 6943//6943 6273//6273 -f 6273//6273 6943//6943 6942//6942 -f 6273//6273 6942//6942 6275//6275 -f 6275//6275 6942//6942 6941//6941 -f 6275//6275 6941//6941 6277//6277 -f 6277//6277 6941//6941 6940//6940 -f 6277//6277 6940//6940 6279//6279 -f 6279//6279 6940//6940 6939//6939 -f 6279//6279 6939//6939 6282//6282 -f 6282//6282 6939//6939 6938//6938 -f 6282//6282 6938//6938 6281//6281 -f 6281//6281 6938//6938 5642//5642 -f 6258//6258 6256//6256 6949//6949 -f 6949//6949 6256//6256 6255//6255 -f 6949//6949 6255//6255 6950//6950 -f 6255//6255 6253//6253 6950//6950 -f 6950//6950 6253//6253 6251//6251 -f 6950//6950 6251//6251 6954//6954 -f 6954//6954 6251//6251 6249//6249 -f 6954//6954 6249//6249 6953//6953 -f 6953//6953 6249//6249 5636//5636 -f 6953//6953 5636//5636 6952//6952 -f 6952//6952 5636//5636 5638//5638 -f 6952//6952 5638//5638 6951//6951 -f 6951//6951 5638//5638 5633//5633 -f 6951//6951 5633//5633 6958//6958 -f 6958//6958 5633//5633 5632//5632 -f 6958//6958 5632//5632 6957//6957 -f 6957//6957 5632//5632 5624//5624 -f 6957//6957 5624//5624 6956//6956 -f 6956//6956 5624//5624 5626//5626 -f 6956//6956 5626//5626 6955//6955 -f 6955//6955 5626//5626 5629//5629 -f 6955//6955 5629//5629 6959//6959 -f 5629//5629 5617//5617 6959//6959 -f 6959//6959 5617//5617 5616//5616 -f 6959//6959 5616//5616 6960//6960 -f 6968//6968 6961//6961 5608//5608 -f 5608//5608 6961//6961 6960//6960 -f 5608//5608 6960//6960 5609//5609 -f 5609//5609 6960//6960 5616//5616 -f 6968//6968 5608//5608 6967//6967 -f 6967//6967 5608//5608 5613//5613 -f 6967//6967 5613//5613 6966//6966 -f 6966//6966 5613//5613 5603//5603 -f 6966//6966 5603//5603 6965//6965 -f 6965//6965 5603//5603 5602//5602 -f 6965//6965 5602//5602 6964//6964 -f 6964//6964 5602//5602 5605//5605 -f 6964//6964 5605//5605 6963//6963 -f 5605//5605 6247//6247 6963//6963 -f 6963//6963 6247//6247 6246//6246 -f 6963//6963 6246//6246 6962//6962 -f 6962//6962 6246//6246 6230//6230 -f 6962//6962 6230//6230 6971//6971 -f 6971//6971 6230//6230 6233//6233 -f 6971//6971 6233//6233 6970//6970 -f 6970//6970 6233//6233 6236//6236 -f 6970//6970 6236//6236 6969//6969 -f 6969//6969 6236//6236 6238//6238 -f 6969//6969 6238//6238 6907//6907 -f 6238//6238 6240//6240 6907//6907 -f 6907//6907 6240//6240 6242//6242 -f 6907//6907 6242//6242 6972//6972 -f 6242//6242 6227//6227 6972//6972 -f 6972//6972 6227//6227 6223//6223 -f 6972//6972 6223//6223 6973//6973 -f 6973//6973 6223//6223 6974//6974 -f 6974//6974 6223//6223 6225//6225 -f 6974//6974 6225//6225 6975//6975 -f 6225//6225 6226//6226 6975//6975 -f 6975//6975 6226//6226 6221//6221 -f 6975//6975 6221//6221 6976//6976 -f 6976//6976 6221//6221 6219//6219 -f 6976//6976 6219//6219 6977//6977 -f 6219//6219 6217//6217 6977//6977 -f 6977//6977 6217//6217 6215//6215 -f 6977//6977 6215//6215 6978//6978 -f 6978//6978 6215//6215 6212//6212 -f 6978//6978 6212//6212 6979//6979 -f 6979//6979 6212//6212 5601//5601 -f 6979//6979 5601//5601 6980//6980 -f 6980//6980 5601//5601 5600//5600 -f 6980//6980 5600//5600 6981//6981 -f 6981//6981 5600//5600 5598//5598 -f 6981//6981 5598//5598 6982//6982 -f 5598//5598 5596//5596 6982//6982 -f 6982//6982 5596//5596 5593//5593 -f 6982//6982 5593//5593 6983//6983 -f 6983//6983 5593//5593 5591//5591 -f 6983//6983 5591//5591 5589//5589 -f 5582//5582 6991//6991 5567//5567 -f 5567//5567 6991//6991 6992//6992 -f 5567//5567 6992//6992 5584//5584 -f 5584//5584 6992//6992 6993//6993 -f 5584//5584 6993//6993 5586//5586 -f 5586//5586 6993//6993 6984//6984 -f 5586//5586 6984//6984 5587//5587 -f 5587//5587 6984//6984 6985//6985 -f 5587//5587 6985//6985 5566//5566 -f 5566//5566 6985//6985 6986//6986 -f 5566//5566 6986//6986 5589//5589 -f 5589//5589 6986//6986 6987//6987 -f 5589//5589 6987//6987 6983//6983 -f 5582//5582 5581//5581 6991//6991 -f 6991//6991 5581//5581 5579//5579 -f 6991//6991 5579//5579 6990//6990 -f 6990//6990 5579//5579 5577//5577 -f 6990//6990 5577//5577 6989//6989 -f 6989//6989 5577//5577 5575//5575 -f 6989//6989 5575//5575 6988//6988 -f 5575//5575 5573//5573 6988//6988 -f 6988//6988 5573//5573 5571//5571 -f 6988//6988 5571//5571 6994//6994 -f 5571//5571 6200//6200 6994//6994 -f 6994//6994 6200//6200 6202//6202 -f 6994//6994 6202//6202 6995//6995 -f 6202//6202 6204//6204 6995//6995 -f 6995//6995 6204//6204 6206//6206 -f 6995//6995 6206//6206 6996//6996 -f 6206//6206 6208//6208 6996//6996 -f 6996//6996 6208//6208 6190//6190 -f 6996//6996 6190//6190 6997//6997 -f 6997//6997 6190//6190 6189//6189 -f 6997//6997 6189//6189 6998//6998 -f 6998//6998 6189//6189 6192//6192 -f 6998//6998 6192//6192 6999//6999 -f 6999//6999 6192//6192 6194//6194 -f 6999//6999 6194//6194 7000//7000 -f 6194//6194 6197//6197 7000//7000 -f 7000//7000 6197//6197 6186//6186 -f 7000//7000 6186//6186 7001//7001 -f 7001//7001 6186//6186 6179//6179 -f 7001//7001 6179//6179 7002//7002 -f 7002//7002 6179//6179 7003//7003 -f 7003//7003 6179//6179 6181//6181 -f 7003//7003 6181//6181 7004//7004 -f 6181//6181 6183//6183 7004//7004 -f 7004//7004 6183//6183 6173//6173 -f 7004//7004 6173//6173 7005//7005 -f 7005//7005 6173//6173 6175//6175 -f 7005//7005 6175//6175 7006//7006 -f 7006//7006 6175//6175 7007//7007 -f 7007//7007 6175//6175 6177//6177 -f 7007//7007 6177//6177 7008//7008 -f 6177//6177 6171//6171 7008//7008 -f 7008//7008 6171//6171 5562//5562 -f 7008//7008 5562//5562 7009//7009 -f 5562//5562 5560//5560 7009//7009 -f 7009//7009 5560//5560 5559//5559 -f 7009//7009 5559//5559 7010//7010 -f 5559//5559 5556//5556 7010//7010 -f 7010//7010 5556//5556 5554//5554 -f 7010//7010 5554//5554 7011//7011 -f 7011//7011 5554//5554 5552//5552 -f 7011//7011 5552//5552 7012//7012 -f 7012//7012 5552//5552 5550//5550 -f 7012//7012 5550//5550 7013//7013 -f 5550//5550 5549//5549 7013//7013 -f 7013//7013 5549//5549 5540//5540 -f 7013//7013 5540//5540 7014//7014 -f 5540//5540 5542//5542 7014//7014 -f 7014//7014 5542//5542 5544//5544 -f 7014//7014 5544//5544 6906//6906 -f 7021//7021 7022//7022 5006//5006 -f 5006//5006 7022//7022 5007//5007 -f 5007//5007 7022//7022 7023//7023 -f 5007//5007 7023//7023 4972//4972 -f 4972//4972 7023//7023 7024//7024 -f 4972//4972 7024//7024 5000//5000 -f 5000//5000 7024//7024 7025//7025 -f 5000//5000 7025//7025 4998//4998 -f 4998//4998 7025//7025 7026//7026 -f 4998//4998 7026//7026 4996//4996 -f 4996//4996 7026//7026 7027//7027 -f 4996//4996 7027//7027 4994//4994 -f 4994//4994 7027//7027 4992//4992 -f 4992//4992 7027//7027 7028//7028 -f 4992//4992 7028//7028 4990//4990 -f 4990//4990 7028//7028 7029//7029 -f 4990//4990 7029//7029 4987//4987 -f 4987//4987 7029//7029 7030//7030 -f 4987//4987 7030//7030 4985//4985 -f 7030//7030 7031//7031 4985//4985 -f 4985//4985 7031//7031 7032//7032 -f 4985//4985 7032//7032 4983//4983 -f 4983//4983 7032//7032 7033//7033 -f 4983//4983 7033//7033 4981//4981 -f 4981//4981 7033//7033 7034//7034 -f 4981//4981 7034//7034 4979//4979 -f 4979//4979 7034//7034 7035//7035 -f 7036//7036 4973//4973 7037//7037 -f 7037//7037 4973//4973 4975//4975 -f 7037//7037 4975//4975 7035//7035 -f 7035//7035 4975//4975 4977//4977 -f 7035//7035 4977//4977 4979//4979 -f 7038//7038 6345//6345 7039//7039 -f 7039//7039 6345//6345 6343//6343 -f 7039//7039 6343//6343 7040//7040 -f 7040//7040 6343//6343 6341//6341 -f 7040//7040 6341//6341 7041//7041 -f 7041//7041 6341//6341 6339//6339 -f 7041//7041 6339//6339 7042//7042 -f 7042//7042 6339//6339 6337//6337 -f 7042//7042 6337//6337 7036//7036 -f 7036//7036 6337//6337 6335//6335 -f 7036//7036 6335//6335 4973//4973 -f 7043//7043 6349//6349 7038//7038 -f 7038//7038 6349//6349 6347//6347 -f 7038//7038 6347//6347 6345//6345 -f 7043//7043 7044//7044 6349//6349 -f 6349//6349 7044//7044 7045//7045 -f 6349//6349 7045//7045 6333//6333 -f 6333//6333 7045//7045 7046//7046 -f 6333//6333 7046//7046 6332//6332 -f 6332//6332 7046//7046 7047//7047 -f 6332//6332 7047//7047 6330//6330 -f 6330//6330 7047//7047 7048//7048 -f 6330//6330 7048//7048 6328//6328 -f 7048//7048 7049//7049 6328//6328 -f 6328//6328 7049//7049 7050//7050 -f 6328//6328 7050//7050 6317//6317 -f 6317//6317 7050//7050 7051//7051 -f 6317//6317 7051//7051 6318//6318 -f 6318//6318 7051//7051 7052//7052 -f 6318//6318 7052//7052 6320//6320 -f 6320//6320 7052//7052 7053//7053 -f 6320//6320 7053//7053 6322//6322 -f 6322//6322 7053//7053 6324//6324 -f 7053//7053 7054//7054 6324//6324 -f 6324//6324 7054//7054 7055//7055 -f 6324//6324 7055//7055 6325//6325 -f 6325//6325 7055//7055 7056//7056 -f 6325//6325 7056//7056 5710//5710 -f 5710//5710 7056//7056 7057//7057 -f 5710//5710 7057//7057 5708//5708 -f 7057//7057 7058//7058 5708//5708 -f 5708//5708 7058//7058 7059//7059 -f 5708//5708 7059//7059 5706//5706 -f 5706//5706 7059//7059 7060//7060 -f 5706//5706 7060//7060 5704//5704 -f 5704//5704 7060//7060 7061//7061 -f 5704//5704 7061//7061 5702//5702 -f 7062//7062 5700//5700 7063//7063 -f 7063//7063 5700//5700 5702//5702 -f 7063//7063 5702//5702 7064//7064 -f 7064//7064 5702//5702 7061//7061 -f 7062//7062 7065//7065 5700//5700 -f 5700//5700 7065//7065 7066//7066 -f 5700//5700 7066//7066 5680//5680 -f 5680//5680 7066//7066 7067//7067 -f 5680//5680 7067//7067 5681//5681 -f 5681//5681 7067//7067 7068//7068 -f 5681//5681 7068//7068 5683//5683 -f 5683//5683 7068//7068 7069//7069 -f 5683//5683 7069//7069 5684//5684 -f 7069//7069 7070//7070 5684//5684 -f 5684//5684 7070//7070 7071//7071 -f 5684//5684 7071//7071 5686//5686 -f 5686//5686 7071//7071 7072//7072 -f 5686//5686 7072//7072 5688//5688 -f 5688//5688 7072//7072 7073//7073 -f 5688//5688 7073//7073 5690//5690 -f 5690//5690 7073//7073 7074//7074 -f 5690//5690 7074//7074 5692//5692 -f 5692//5692 7074//7074 5694//5694 -f 5694//5694 7074//7074 7075//7075 -f 5694//5694 7075//7075 5699//5699 -f 5699//5699 7075//7075 7076//7076 -f 5699//5699 7076//7076 5698//5698 -f 5698//5698 7076//7076 7077//7077 -f 5698//5698 7077//7077 5696//5696 -f 5696//5696 7077//7077 6316//6316 -f 6316//6316 7077//7077 7078//7078 -f 6316//6316 7078//7078 6314//6314 -f 6314//6314 7078//7078 7079//7079 -f 6314//6314 7079//7079 6312//6312 -f 6312//6312 7079//7079 7080//7080 -f 6312//6312 7080//7080 6310//6310 -f 6310//6310 7080//7080 7081//7081 -f 6310//6310 7081//7081 6307//6307 -f 7081//7081 7082//7082 6307//6307 -f 6307//6307 7082//7082 7083//7083 -f 6307//6307 7083//7083 6305//6305 -f 6305//6305 7083//7083 7084//7084 -f 6305//6305 7084//7084 6302//6302 -f 7084//7084 7085//7085 6302//6302 -f 6302//6302 7085//7085 7086//7086 -f 6302//6302 7086//7086 6301//6301 -f 6301//6301 7086//7086 7087//7087 -f 6301//6301 7087//7087 6299//6299 -f 6299//6299 7087//7087 7088//7088 -f 6299//6299 7088//7088 6296//6296 -f 6296//6296 7088//7088 7089//7089 -f 6296//6296 7089//7089 6295//6295 -f 6295//6295 7089//7089 7090//7090 -f 6295//6295 7090//7090 6293//6293 -f 7090//7090 7091//7091 6293//6293 -f 6293//6293 7091//7091 7092//7092 -f 6293//6293 7092//7092 6291//6291 -f 7092//7092 7093//7093 6291//6291 -f 6291//6291 7093//7093 7094//7094 -f 6291//6291 7094//7094 6288//6288 -f 6288//6288 7094//7094 7095//7095 -f 6288//6288 7095//7095 6286//6286 -f 7095//7095 7096//7096 6286//6286 -f 6286//6286 7096//7096 7097//7097 -f 6286//6286 7097//7097 6284//6284 -f 6284//6284 7097//7097 7098//7098 -f 6284//6284 7098//7098 5674//5674 -f 7098//7098 7099//7099 5674//5674 -f 5674//5674 7099//7099 7100//7100 -f 5674//5674 7100//7100 5678//5678 -f 5678//5678 7100//7100 7101//7101 -f 5678//5678 7101//7101 5677//5677 -f 5677//5677 7101//7101 7102//7102 -f 5677//5677 7102//7102 5671//5671 -f 5671//5671 7102//7102 7103//7103 -f 5671//5671 7103//7103 5669//5669 -f 5669//5669 7103//7103 7104//7104 -f 5669//5669 7104//7104 5667//5667 -f 5667//5667 7104//7104 7105//7105 -f 5667//5667 7105//7105 5666//5666 -f 5666//5666 7105//7105 7106//7106 -f 5666//5666 7106//7106 5664//5664 -f 7106//7106 7107//7107 5664//5664 -f 5664//5664 7107//7107 7108//7108 -f 5664//5664 7108//7108 5662//5662 -f 5662//5662 7108//7108 7020//7020 -f 5662//5662 7020//7020 5660//5660 -f 5006//5006 5004//5004 7021//7021 -f 7021//7021 5004//5004 6372//6372 -f 7021//7021 6372//6372 7109//7109 -f 7109//7109 6372//6372 7110//7110 -f 7109//7109 7110//7110 7111//7111 -f 7111//7111 7110//7110 7112//7112 -f 7111//7111 7112//7112 7113//7113 -f 7113//7113 7112//7112 7114//7114 -f 7113//7113 7114//7114 7115//7115 -f 7115//7115 7114//7114 7116//7116 -f 7115//7115 7116//7116 7117//7117 -f 7117//7117 7116//7116 7118//7118 -f 7117//7117 7118//7118 7119//7119 -f 7119//7119 7118//7118 7120//7120 -f 7119//7119 7120//7120 7121//7121 -f 7121//7121 7120//7120 7122//7122 -f 7121//7121 7122//7122 7123//7123 -f 7113//7113 7115//7115 7124//7124 -f 5679//5679 5682//5682 7020//7020 -f 7020//7020 7108//7108 5679//5679 -f 5679//5679 7108//7108 7107//7107 -f 5679//5679 7107//7107 5701//5701 -f 7107//7107 7106//7106 5701//5701 -f 5701//5701 7106//7106 7105//7105 -f 5701//5701 7105//7105 5703//5703 -f 5703//5703 7105//7105 7104//7104 -f 5703//5703 7104//7104 5705//5705 -f 5705//5705 7104//7104 7103//7103 -f 5705//5705 7103//7103 5707//5707 -f 5707//5707 7103//7103 7102//7102 -f 5707//5707 7102//7102 5712//5712 -f 5712//5712 7102//7102 7101//7101 -f 5712//5712 7101//7101 5711//5711 -f 5711//5711 7101//7101 7100//7100 -f 5711//5711 7100//7100 5709//5709 -f 5709//5709 7100//7100 7099//7099 -f 7099//7099 7098//7098 5709//5709 -f 5709//5709 7098//7098 7097//7097 -f 5709//5709 7097//7097 6323//6323 -f 6323//6323 7097//7097 7096//7096 -f 6323//6323 7096//7096 6321//6321 -f 7096//7096 7095//7095 6321//6321 -f 6321//6321 7095//7095 7094//7094 -f 6321//6321 7094//7094 6319//6319 -f 6319//6319 7094//7094 7093//7093 -f 6319//6319 7093//7093 6326//6326 -f 6326//6326 7093//7093 7092//7092 -f 6326//6326 7092//7092 6327//6327 -f 6327//6327 7092//7092 7091//7091 -f 6327//6327 7091//7091 6329//6329 -f 6329//6329 7091//7091 7090//7090 -f 6329//6329 7090//7090 6331//6331 -f 7090//7090 7089//7089 6331//6331 -f 6331//6331 7089//7089 7088//7088 -f 6331//6331 7088//7088 6351//6351 -f 6351//6351 7088//7088 7087//7087 -f 6351//6351 7087//7087 6350//6350 -f 7087//7087 7086//7086 6350//6350 -f 6350//6350 7086//7086 7085//7085 -f 6350//6350 7085//7085 6348//6348 -f 6348//6348 7085//7085 7084//7084 -f 6348//6348 7084//7084 6346//6346 -f 6346//6346 7084//7084 7083//7083 -f 6346//6346 7083//7083 6344//6344 -f 6344//6344 7083//7083 7082//7082 -f 6344//6344 7082//7082 6342//6342 -f 6342//6342 7082//7082 7081//7081 -f 6342//6342 7081//7081 6340//6340 -f 6340//6340 7081//7081 7080//7080 -f 6340//6340 7080//7080 6338//6338 -f 6338//6338 7080//7080 7079//7079 -f 6338//6338 7079//7079 6336//6336 -f 6336//6336 7079//7079 7078//7078 -f 6336//6336 7078//7078 6334//6334 -f 6334//6334 7078//7078 7077//7077 -f 6334//6334 7077//7077 4974//4974 -f 4974//4974 7077//7077 7076//7076 -f 4974//4974 7076//7076 4976//4976 -f 4976//4976 7076//7076 7075//7075 -f 4976//4976 7075//7075 4978//4978 -f 4978//4978 7075//7075 7074//7074 -f 7073//7073 4982//4982 7074//7074 -f 7074//7074 4982//4982 4980//4980 -f 7074//7074 4980//4980 4978//4978 -f 4989//4989 4988//4988 7072//7072 -f 7072//7072 4988//4988 4986//4986 -f 7072//7072 4986//4986 7073//7073 -f 7073//7073 4986//4986 4984//4984 -f 7073//7073 4984//4984 4982//4982 -f 7072//7072 7071//7071 4989//4989 -f 4989//4989 7071//7071 7070//7070 -f 4989//4989 7070//7070 4991//4991 -f 7070//7070 7069//7069 4991//4991 -f 4991//4991 7069//7069 7068//7068 -f 4991//4991 7068//7068 4993//4993 -f 4993//4993 7068//7068 7067//7067 -f 4993//4993 7067//7067 4995//4995 -f 7063//7063 4999//4999 7062//7062 -f 7062//7062 4999//4999 4997//4997 -f 7062//7062 4997//4997 7065//7065 -f 7065//7065 4997//4997 4995//4995 -f 7065//7065 4995//4995 7066//7066 -f 7066//7066 4995//4995 7067//7067 -f 7063//7063 7064//7064 4999//4999 -f 4999//4999 7064//7064 7061//7061 -f 4999//4999 7061//7061 5001//5001 -f 5001//5001 7061//7061 7060//7060 -f 5001//5001 7060//7060 4970//4970 -f 4970//4970 7060//7060 7059//7059 -f 4970//4970 7059//7059 4971//4971 -f 4971//4971 7059//7059 7058//7058 -f 4971//4971 7058//7058 5005//5005 -f 5005//5005 7058//7058 7057//7057 -f 5005//5005 7057//7057 5002//5002 -f 5002//5002 7057//7057 7056//7056 -f 5002//5002 7056//7056 5003//5003 -f 5003//5003 7056//7056 6373//6373 -f 6373//6373 7056//7056 7055//7055 -f 6373//6373 7055//7055 6375//6375 -f 6375//6375 7055//7055 7054//7054 -f 6375//6375 7054//7054 6376//6376 -f 7054//7054 7053//7053 6376//6376 -f 6376//6376 7053//7053 7052//7052 -f 6376//6376 7052//7052 6379//6379 -f 6379//6379 7052//7052 7051//7051 -f 6379//6379 7051//7051 6380//6380 -f 7051//7051 7050//7050 6380//6380 -f 6380//6380 7050//7050 7049//7049 -f 6380//6380 7049//7049 6382//6382 -f 6382//6382 7049//7049 7048//7048 -f 6382//6382 7048//7048 6383//6383 -f 6383//6383 7048//7048 7125//7125 -f 7048//7048 7047//7047 7125//7125 -f 7125//7125 7047//7047 7046//7046 -f 7125//7125 7046//7046 7126//7126 -f 7126//7126 7046//7046 7045//7045 -f 7126//7126 7045//7045 7127//7127 -f 7127//7127 7045//7045 7044//7044 -f 7127//7127 7044//7044 7128//7128 -f 7044//7044 7043//7043 7128//7128 -f 7128//7128 7043//7043 7038//7038 -f 7128//7128 7038//7038 7129//7129 -f 7129//7129 7038//7038 7130//7130 -f 7130//7130 7038//7038 7039//7039 -f 7130//7130 7039//7039 7131//7131 -f 7131//7131 7039//7039 7132//7132 -f 7132//7132 7039//7039 7040//7040 -f 7132//7132 7040//7040 7133//7133 -f 7133//7133 7040//7040 7041//7041 -f 7133//7133 7041//7041 7134//7134 -f 7134//7134 7041//7041 7042//7042 -f 7134//7134 7042//7042 7135//7135 -f 7135//7135 7042//7042 7036//7036 -f 7135//7135 7036//7036 7136//7136 -f 7136//7136 7036//7036 7137//7137 -f 7137//7137 7036//7036 7037//7037 -f 7137//7137 7037//7037 7138//7138 -f 7138//7138 7037//7037 7035//7035 -f 7138//7138 7035//7035 7139//7139 -f 7139//7139 7035//7035 7034//7034 -f 7139//7139 7034//7034 7140//7140 -f 7140//7140 7034//7034 7141//7141 -f 7141//7141 7034//7034 7033//7033 -f 7141//7141 7033//7033 7142//7142 -f 7033//7033 7032//7032 7142//7142 -f 7142//7142 7032//7032 7031//7031 -f 7142//7142 7031//7031 7143//7143 -f 7031//7031 7030//7030 7143//7143 -f 7143//7143 7030//7030 7029//7029 -f 7143//7143 7029//7029 7144//7144 -f 7144//7144 7029//7029 7028//7028 -f 7144//7144 7028//7028 7145//7145 -f 7145//7145 7028//7028 7027//7027 -f 7145//7145 7027//7027 7146//7146 -f 7146//7146 7027//7027 7147//7147 -f 7147//7147 7027//7027 7026//7026 -f 7147//7147 7026//7026 7148//7148 -f 7148//7148 7026//7026 7025//7025 -f 7148//7148 7025//7025 7149//7149 -f 7149//7149 7025//7025 7024//7024 -f 7149//7149 7024//7024 7150//7150 -f 7150//7150 7024//7024 7023//7023 -f 7150//7150 7023//7023 7151//7151 -f 7151//7151 7023//7023 7022//7022 -f 7151//7151 7022//7022 7152//7152 -f 7022//7022 7021//7021 7152//7152 -f 7152//7152 7021//7021 7109//7109 -f 7152//7152 7109//7109 7124//7124 -f 7124//7124 7109//7109 7111//7111 -f 7124//7124 7111//7111 7113//7113 -f 7110//7110 6372//6372 6374//6374 -f 7150//7150 7151//7151 7153//7153 -f 7146//7146 7147//7147 7154//7154 -f 7154//7154 7147//7147 7148//7148 -f 7154//7154 7148//7148 7153//7153 -f 7153//7153 7148//7148 7149//7149 -f 7153//7153 7149//7149 7150//7150 -f 7146//7146 7154//7154 7145//7145 -f 7145//7145 7154//7154 7155//7155 -f 7145//7145 7155//7155 7144//7144 -f 7144//7144 7155//7155 7156//7156 -f 7144//7144 7156//7156 7143//7143 -f 7143//7143 7156//7156 7157//7157 -f 7143//7143 7157//7157 7142//7142 -f 7157//7157 7158//7158 7142//7142 -f 7142//7142 7158//7158 7159//7159 -f 7142//7142 7159//7159 7141//7141 -f 7141//7141 7159//7159 7160//7160 -f 7141//7141 7160//7160 7140//7140 -f 7140//7140 7160//7160 7139//7139 -f 7139//7139 7160//7160 7161//7161 -f 7139//7139 7161//7161 7138//7138 -f 7138//7138 7161//7161 7137//7137 -f 7137//7137 7161//7161 7162//7162 -f 7137//7137 7162//7162 7136//7136 -f 7136//7136 7162//7162 7135//7135 -f 7135//7135 7162//7162 7163//7163 -f 7135//7135 7163//7163 7134//7134 -f 7130//7130 7131//7131 7164//7164 -f 7164//7164 7131//7131 7132//7132 -f 7164//7164 7132//7132 7163//7163 -f 7163//7163 7132//7132 7133//7133 -f 7163//7163 7133//7133 7134//7134 -f 7165//7165 7128//7128 7164//7164 -f 7164//7164 7128//7128 7129//7129 -f 7164//7164 7129//7129 7130//7130 -f 6377//6377 6378//6378 7118//7118 -f 7118//7118 6378//6378 6381//6381 -f 7118//7118 6381//6381 7120//7120 -f 7120//7120 6381//6381 6383//6383 -f 7120//7120 6383//6383 7122//7122 -f 7122//7122 6383//6383 7125//7125 -f 7122//7122 7125//7125 7123//7123 -f 7123//7123 7125//7125 7126//7126 -f 7123//7123 7126//7126 7165//7165 -f 7165//7165 7126//7126 7127//7127 -f 7165//7165 7127//7127 7128//7128 -f 7118//7118 7116//7116 6377//6377 -f 6377//6377 7116//7116 7114//7114 -f 6377//6377 7114//7114 6374//6374 -f 6374//6374 7114//7114 7112//7112 -f 6374//6374 7112//7112 7110//7110 -f 7152//7152 7124//7124 7115//7115 -f 7158//7158 7115//7115 7159//7159 -f 7159//7159 7115//7115 7160//7160 -f 7160//7160 7115//7115 7161//7161 -f 7161//7161 7115//7115 7117//7117 -f 7161//7161 7117//7117 7119//7119 -f 7121//7121 7123//7123 7165//7165 -f 7165//7165 7164//7164 7163//7163 -f 7119//7119 7121//7121 7161//7161 -f 7161//7161 7121//7121 7165//7165 -f 7161//7161 7165//7165 7162//7162 -f 7162//7162 7165//7165 7163//7163 -f 7155//7155 7154//7154 7156//7156 -f 7156//7156 7154//7154 7153//7153 -f 7158//7158 7157//7157 7115//7115 -f 7115//7115 7157//7157 7156//7156 -f 7115//7115 7156//7156 7152//7152 -f 7152//7152 7156//7156 7153//7153 -f 7152//7152 7153//7153 7151//7151 -f 7166//7166 7167//7167 7168//7168 -f 7168//7168 7167//7167 7169//7169 -f 7170//7170 7171//7171 7172//7172 -f 7173//7173 7174//7174 7175//7175 -f 7175//7175 7174//7174 7176//7176 -f 7176//7176 7174//7174 7177//7177 -f 7176//7176 7177//7177 7178//7178 -f 7173//7173 7175//7175 7179//7179 -f 7179//7179 7175//7175 7180//7180 -f 7179//7179 7180//7180 7181//7181 -f 7181//7181 7180//7180 7182//7182 -f 7181//7181 7182//7182 7183//7183 -f 7183//7183 7182//7182 7184//7184 -f 7184//7184 7182//7182 7185//7185 -f 7184//7184 7185//7185 7186//7186 -f 7186//7186 7185//7185 7187//7187 -f 7187//7187 7185//7185 7188//7188 -f 7187//7187 7188//7188 7189//7189 -f 7189//7189 7188//7188 7190//7190 -f 7189//7189 7190//7190 7191//7191 -f 7172//7172 7171//7171 7190//7190 -f 7190//7190 7171//7171 7192//7192 -f 7190//7190 7192//7192 7191//7191 -f 7170//7170 7172//7172 7193//7193 -f 7193//7193 7172//7172 7194//7194 -f 7193//7193 7194//7194 7195//7195 -f 7195//7195 7194//7194 7196//7196 -f 7195//7195 7196//7196 7197//7197 -f 7197//7197 7196//7196 7198//7198 -f 7198//7198 7196//7196 7199//7199 -f 7198//7198 7199//7199 7200//7200 -f 7200//7200 7199//7199 7201//7201 -f 7200//7200 7201//7201 7202//7202 -f 7203//7203 7204//7204 7205//7205 -f 7205//7205 7204//7204 7206//7206 -f 7205//7205 7206//7206 7207//7207 -f 7207//7207 7206//7206 7208//7208 -f 7209//7209 7210//7210 7208//7208 -f 7208//7208 7210//7210 7211//7211 -f 7208//7208 7211//7211 7207//7207 -f 7212//7212 7213//7213 7214//7214 -f 7214//7214 7213//7213 7215//7215 -f 7214//7214 7215//7215 7216//7216 -f 7216//7216 7215//7215 7217//7217 -f 7216//7216 7217//7217 7209//7209 -f 7209//7209 7217//7217 7218//7218 -f 7209//7209 7218//7218 7210//7210 -f 7167//7167 7219//7219 7169//7169 -f 7169//7169 7219//7219 7220//7220 -f 7169//7169 7220//7220 7212//7212 -f 7212//7212 7220//7220 7221//7221 -f 7212//7212 7221//7221 7213//7213 -f 7166//7166 7168//7168 7222//7222 -f 7222//7222 7168//7168 7223//7223 -f 7222//7222 7223//7223 7224//7224 -f 7224//7224 7223//7223 7225//7225 -f 7224//7224 7225//7225 7226//7226 -f 7226//7226 7225//7225 7227//7227 -f 7227//7227 7225//7225 7228//7228 -f 7227//7227 7228//7228 7229//7229 -f 7230//7230 7228//7228 7231//7231 -f 7231//7231 7228//7228 7225//7225 -f 7231//7231 7225//7225 7232//7232 -f 7232//7232 7225//7225 7223//7223 -f 7232//7232 7223//7223 7233//7233 -f 7233//7233 7223//7223 7168//7168 -f 7233//7233 7168//7168 7234//7234 -f 7234//7234 7168//7168 7169//7169 -f 7234//7234 7169//7169 7235//7235 -f 7235//7235 7169//7169 7212//7212 -f 7235//7235 7212//7212 7236//7236 -f 7236//7236 7212//7212 7214//7214 -f 7236//7236 7214//7214 7237//7237 -f 7237//7237 7214//7214 7216//7216 -f 7237//7237 7216//7216 7238//7238 -f 7238//7238 7216//7216 7209//7209 -f 7238//7238 7209//7209 7239//7239 -f 7239//7239 7209//7209 7208//7208 -f 7239//7239 7208//7208 7240//7240 -f 7240//7240 7208//7208 7206//7206 -f 7240//7240 7206//7206 7241//7241 -f 7241//7241 7206//7206 7204//7204 -f 7176//7176 7230//7230 7175//7175 -f 7175//7175 7230//7230 7231//7231 -f 7175//7175 7231//7231 7180//7180 -f 7180//7180 7231//7231 7232//7232 -f 7180//7180 7232//7232 7182//7182 -f 7182//7182 7232//7232 7233//7233 -f 7182//7182 7233//7233 7185//7185 -f 7185//7185 7233//7233 7234//7234 -f 7185//7185 7234//7234 7188//7188 -f 7188//7188 7234//7234 7235//7235 -f 7188//7188 7235//7235 7190//7190 -f 7190//7190 7235//7235 7236//7236 -f 7190//7190 7236//7236 7172//7172 -f 7172//7172 7236//7236 7237//7237 -f 7172//7172 7237//7237 7194//7194 -f 7194//7194 7237//7237 7238//7238 -f 7194//7194 7238//7238 7196//7196 -f 7196//7196 7238//7238 7239//7239 -f 7196//7196 7239//7239 7199//7199 -f 7199//7199 7239//7239 7240//7240 -f 7199//7199 7240//7240 7201//7201 -f 7201//7201 7240//7240 7241//7241 -f 7242//7242 7243//7243 7244//7244 -f 7245//7245 7246//7246 7247//7247 -f 7248//7248 7249//7249 7246//7246 -f 7250//7250 7251//7251 7252//7252 -f 7253//7253 7251//7251 7254//7254 -f 7254//7254 7251//7251 7250//7250 -f 7254//7254 7250//7250 7255//7255 -f 7256//7256 7257//7257 7258//7258 -f 7259//7259 7260//7260 7257//7257 -f 7261//7261 7262//7262 7260//7260 -f 7263//7263 7264//7264 7265//7265 -f 7266//7266 7255//7255 7267//7267 -f 7267//7267 7255//7255 7250//7250 -f 7267//7267 7250//7250 7268//7268 -f 7268//7268 7250//7250 7252//7252 -f 7268//7268 7252//7252 7249//7249 -f 7269//7269 7270//7270 7271//7271 -f 7272//7272 7270//7270 7273//7273 -f 7273//7273 7270//7270 7269//7269 -f 7273//7273 7269//7269 7274//7274 -f 7275//7275 7276//7276 7277//7277 -f 7263//7263 7265//7265 7278//7278 -f 7278//7278 7265//7265 7275//7275 -f 7278//7278 7275//7275 7279//7279 -f 7279//7279 7275//7275 7277//7277 -f 7279//7279 7277//7277 7280//7280 -f 7280//7280 7281//7281 7279//7279 -f 7279//7279 7281//7281 7282//7282 -f 7279//7279 7282//7282 7278//7278 -f 7278//7278 7282//7282 7245//7245 -f 7278//7278 7245//7245 7263//7263 -f 7263//7263 7245//7245 7247//7247 -f 7263//7263 7247//7247 7264//7264 -f 7264//7264 7247//7247 7283//7283 -f 7264//7264 7283//7283 7284//7284 -f 7280//7280 7285//7285 7281//7281 -f 7281//7281 7285//7285 7286//7286 -f 7281//7281 7286//7286 7287//7287 -f 7246//7246 7245//7245 7248//7248 -f 7248//7248 7245//7245 7282//7282 -f 7248//7248 7282//7282 7288//7288 -f 7288//7288 7282//7282 7281//7281 -f 7288//7288 7281//7281 7289//7289 -f 7289//7289 7281//7281 7287//7287 -f 7289//7289 7287//7287 7290//7290 -f 7249//7249 7248//7248 7268//7268 -f 7268//7268 7248//7248 7288//7288 -f 7268//7268 7288//7288 7267//7267 -f 7267//7267 7288//7288 7289//7289 -f 7267//7267 7289//7289 7266//7266 -f 7266//7266 7289//7289 7290//7290 -f 7266//7266 7290//7290 7291//7291 -f 7291//7291 7292//7292 7266//7266 -f 7266//7266 7292//7292 7293//7293 -f 7266//7266 7293//7293 7255//7255 -f 7255//7255 7293//7293 7294//7294 -f 7255//7255 7294//7294 7254//7254 -f 7254//7254 7294//7294 7295//7295 -f 7254//7254 7295//7295 7253//7253 -f 7253//7253 7295//7295 7296//7296 -f 7292//7292 7297//7297 7293//7293 -f 7293//7293 7297//7297 7274//7274 -f 7293//7293 7274//7274 7294//7294 -f 7294//7294 7274//7274 7269//7269 -f 7294//7294 7269//7269 7295//7295 -f 7295//7295 7269//7269 7271//7271 -f 7295//7295 7271//7271 7296//7296 -f 7296//7296 7271//7271 7258//7258 -f 7297//7297 7298//7298 7274//7274 -f 7274//7274 7298//7298 7299//7299 -f 7274//7274 7299//7299 7273//7273 -f 7273//7273 7299//7299 7300//7300 -f 7273//7273 7300//7300 7272//7272 -f 7272//7272 7300//7300 7301//7301 -f 7272//7272 7301//7301 7302//7302 -f 7258//7258 7271//7271 7256//7256 -f 7256//7256 7271//7271 7270//7270 -f 7256//7256 7270//7270 7303//7303 -f 7303//7303 7270//7270 7272//7272 -f 7303//7303 7272//7272 7304//7304 -f 7304//7304 7272//7272 7302//7302 -f 7304//7304 7302//7302 7305//7305 -f 7257//7257 7256//7256 7259//7259 -f 7259//7259 7256//7256 7303//7303 -f 7259//7259 7303//7303 7306//7306 -f 7306//7306 7303//7303 7304//7304 -f 7306//7306 7304//7304 7244//7244 -f 7244//7244 7304//7304 7305//7305 -f 7244//7244 7305//7305 7242//7242 -f 7260//7260 7259//7259 7261//7261 -f 7261//7261 7259//7259 7306//7306 -f 7261//7261 7306//7306 7307//7307 -f 7307//7307 7306//7306 7244//7244 -f 7307//7307 7244//7244 7308//7308 -f 7308//7308 7244//7244 7243//7243 -f 7308//7308 7243//7243 7309//7309 -f 7310//7310 7311//7311 7312//7312 -f 7313//7313 7314//7314 7315//7315 -f 7315//7315 7314//7314 7316//7316 -f 7315//7315 7316//7316 7317//7317 -f 7317//7317 7316//7316 7318//7318 -f 7317//7317 7318//7318 7319//7319 -f 7319//7319 7318//7318 7320//7320 -f 7319//7319 7320//7320 7321//7321 -f 7321//7321 7320//7320 7322//7322 -f 7321//7321 7322//7322 7323//7323 -f 7323//7323 7322//7322 7324//7324 -f 7323//7323 7324//7324 7325//7325 -f 7325//7325 7324//7324 7326//7326 -f 7325//7325 7326//7326 7327//7327 -f 7326//7326 7328//7328 7327//7327 -f 7327//7327 7328//7328 7329//7329 -f 7327//7327 7329//7329 7330//7330 -f 7330//7330 7329//7329 7331//7331 -f 7330//7330 7331//7331 7332//7332 -f 7332//7332 7331//7331 7333//7333 -f 7332//7332 7333//7333 7334//7334 -f 7334//7334 7333//7333 7335//7335 -f 7334//7334 7335//7335 7336//7336 -f 7336//7336 7335//7335 7337//7337 -f 7336//7336 7337//7337 7338//7338 -f 7338//7338 7337//7337 7339//7339 -f 7338//7338 7339//7339 7340//7340 -f 7340//7340 7339//7339 7312//7312 -f 7312//7312 7339//7339 7341//7341 -f 7312//7312 7341//7341 7310//7310 -f 7342//7342 7343//7343 7344//7344 -f 7342//7342 7344//7344 7345//7345 -f 7345//7345 7344//7344 7346//7346 -f 7345//7345 7346//7346 7311//7311 -f 7311//7311 7346//7346 7347//7347 -f 7311//7311 7347//7347 7312//7312 -f 7348//7348 7349//7349 7350//7350 -f 7351//7351 586//586 7352//7352 -f 7352//7352 586//586 7353//7353 -f 7354//7354 7355//7355 7356//7356 -f 7350//7350 7349//7349 7357//7357 -f 7349//7349 7358//7358 7357//7357 -f 7357//7357 7358//7358 7359//7359 -f 7357//7357 7359//7359 7360//7360 -f 7360//7360 7359//7359 7361//7361 -f 7360//7360 7361//7361 7355//7355 -f 7355//7355 7361//7361 7362//7362 -f 7355//7355 7362//7362 7356//7356 -f 7356//7356 7362//7362 7363//7363 -f 7356//7356 7363//7363 7353//7353 -f 7353//7353 7363//7363 7364//7364 -f 7353//7353 7364//7364 7352//7352 -f 7350//7350 7365//7365 7348//7348 -f 7348//7348 7365//7365 7366//7366 -f 7348//7348 7366//7366 7367//7367 -f 7367//7367 7366//7366 7368//7368 -f 7367//7367 7368//7368 7369//7369 -f 7369//7369 7368//7368 7370//7370 -f 7371//7371 7372//7372 7373//7373 -f 7373//7373 7374//7374 7371//7371 -f 7371//7371 7374//7374 7375//7375 -f 7371//7371 7375//7375 7376//7376 -f 7376//7376 7375//7375 7377//7377 -f 7376//7376 7377//7377 7378//7378 -f 7378//7378 7377//7377 7379//7379 -f 7378//7378 7379//7379 7380//7380 -f 7380//7380 7379//7379 7381//7381 -f 7380//7380 7381//7381 7370//7370 -f 7370//7370 7381//7381 7382//7382 -f 7370//7370 7382//7382 7369//7369 -f 7383//7383 7384//7384 7385//7385 -f 7385//7385 7384//7384 7386//7386 -f 7385//7385 7386//7386 7387//7387 -f 7387//7387 7386//7386 7388//7388 -f 7387//7387 7388//7388 7356//7356 -f 7356//7356 7388//7388 7389//7389 -f 7356//7356 7389//7389 7354//7354 -f 7383//7383 7385//7385 7390//7390 -f 7390//7390 7385//7385 7391//7391 -f 7390//7390 7391//7391 7392//7392 -f 7392//7392 7391//7391 7393//7393 -f 7393//7393 7391//7391 7394//7394 -f 7393//7393 7394//7394 7395//7395 -f 7395//7395 7394//7394 7396//7396 -f 7396//7396 7394//7394 598//598 -f 7396//7396 598//598 7397//7397 -f 7397//7397 598//598 7398//7398 -f 7398//7398 598//598 7399//7399 -f 7398//7398 7399//7399 7400//7400 -f 7401//7401 7402//7402 7403//7403 -f 7403//7403 7402//7402 7404//7404 -f 7403//7403 7404//7404 7399//7399 -f 7399//7399 7404//7404 7405//7405 -f 7399//7399 7405//7405 7400//7400 -f 7406//7406 7407//7407 7401//7401 -f 7401//7401 7407//7407 7408//7408 -f 7401//7401 7408//7408 7402//7402 -f 7409//7409 7410//7410 7411//7411 -f 7411//7411 7410//7410 7412//7412 -f 7411//7411 7412//7412 7406//7406 -f 7406//7406 7412//7412 7413//7413 -f 7406//7406 7413//7413 7407//7407 -f 7351//7351 7414//7414 586//586 -f 586//586 7414//7414 7415//7415 -f 586//586 7415//7415 7409//7409 -f 7409//7409 7415//7415 7416//7416 -f 7409//7409 7416//7416 7410//7410 -f 7417//7417 7418//7418 7419//7419 -f 7419//7419 7418//7418 7420//7420 -f 7419//7419 7420//7420 7421//7421 -f 7421//7421 7420//7420 7422//7422 -f 7422//7422 7420//7420 7423//7423 -f 7422//7422 7423//7423 7424//7424 -f 7424//7424 7423//7423 7425//7425 -f 7424//7424 7425//7425 7426//7426 -f 7426//7426 7425//7425 7427//7427 -f 7426//7426 7427//7427 7428//7428 -f 7429//7429 7430//7430 7431//7431 -f 7431//7431 7430//7430 7432//7432 -f 7431//7431 7432//7432 7433//7433 -f 7427//7427 7434//7434 7428//7428 -f 7428//7428 7434//7434 7435//7435 -f 7428//7428 7435//7435 7433//7433 -f 7433//7433 7435//7435 7436//7436 -f 7433//7433 7436//7436 7431//7431 -f 7437//7437 7438//7438 7439//7439 -f 7439//7439 7438//7438 7440//7440 -f 7439//7439 7440//7440 7417//7417 -f 7417//7417 7440//7440 7441//7441 -f 7417//7417 7441//7441 7418//7418 -f 7439//7439 7442//7442 7437//7437 -f 7437//7437 7442//7442 7443//7443 -f 7437//7437 7443//7443 7444//7444 -f 7445//7445 7446//7446 7447//7447 -f 7447//7447 7446//7446 7444//7444 -f 7447//7447 7444//7444 7448//7448 -f 7448//7448 7444//7444 7443//7443 -f 7449//7449 7450//7450 7451//7451 -f 7451//7451 7450//7450 7452//7452 -f 7451//7451 7452//7452 7453//7453 -f 7453//7453 7452//7452 7454//7454 -f 7453//7453 7454//7454 7445//7445 -f 7445//7445 7454//7454 7455//7455 -f 7445//7445 7455//7455 7446//7446 -f 7456//7456 7457//7457 7458//7458 -f 7459//7459 7460//7460 7461//7461 -f 7461//7461 7460//7460 7462//7462 -f 7461//7461 7462//7462 7463//7463 -f 7463//7463 7462//7462 7464//7464 -f 7463//7463 7464//7464 7465//7465 -f 7465//7465 7464//7464 7466//7466 -f 7465//7465 7466//7466 7467//7467 -f 7467//7467 7466//7466 7468//7468 -f 7467//7467 7468//7468 7469//7469 -f 7469//7469 7468//7468 7470//7470 -f 7469//7469 7470//7470 7471//7471 -f 7470//7470 7472//7472 7471//7471 -f 7471//7471 7472//7472 7473//7473 -f 7471//7471 7473//7473 7474//7474 -f 7474//7474 7473//7473 7475//7475 -f 7474//7474 7475//7475 7476//7476 -f 7476//7476 7475//7475 7477//7477 -f 7477//7477 7475//7475 7478//7478 -f 7477//7477 7478//7478 7457//7457 -f 7457//7457 7478//7478 7479//7479 -f 7457//7457 7479//7479 7458//7458 -f 7456//7456 7458//7458 7480//7480 -f 7480//7480 7458//7458 7481//7481 -f 7480//7480 7481//7481 7482//7482 -f 7482//7482 7481//7481 7483//7483 -f 7482//7482 7483//7483 7484//7484 -f 7484//7484 7483//7483 7485//7485 -f 7484//7484 7485//7485 7486//7486 -f 7486//7486 7485//7485 7487//7487 -f 7486//7486 7487//7487 7488//7488 -f 7488//7488 7487//7487 7489//7489 -f 7488//7488 7489//7489 7490//7490 -f 7490//7490 7489//7489 7491//7491 -f 7490//7490 7491//7491 7492//7492 -f 7493//7493 7494//7494 7495//7495 -f 7493//7493 7495//7495 7496//7496 -f 7496//7496 7495//7495 7497//7497 -f 7496//7496 7497//7497 7498//7498 -f 7499//7499 7500//7500 7501//7501 -f 7501//7501 7500//7500 7502//7502 -f 7501//7501 7502//7502 7503//7503 -f 7503//7503 7502//7502 7504//7504 -f 7503//7503 7504//7504 7494//7494 -f 7494//7494 7504//7504 7505//7505 -f 7494//7494 7505//7505 7495//7495 -f 7506//7506 7507//7507 7508//7508 -f 7508//7508 7509//7509 7506//7506 -f 7506//7506 7509//7509 7510//7510 -f 7506//7506 7510//7510 7499//7499 -f 7499//7499 7510//7510 7511//7511 -f 7499//7499 7511//7511 7500//7500 -f 7512//7512 7513//7513 7514//7514 -f 7514//7514 7513//7513 7515//7515 -f 7514//7514 7515//7515 7516//7516 -f 7516//7516 7515//7515 7517//7517 -f 7516//7516 7517//7517 7518//7518 -f 7518//7518 7517//7517 7519//7519 -f 7518//7518 7519//7519 7507//7507 -f 7507//7507 7519//7519 7520//7520 -f 7507//7507 7520//7520 7508//7508 -f 7521//7521 7522//7522 7523//7523 -f 7523//7523 7522//7522 7524//7524 -f 7523//7523 7524//7524 7525//7525 -f 7524//7524 7526//7526 7525//7525 -f 7525//7525 7526//7526 7527//7527 -f 7525//7525 7527//7527 7528//7528 -f 7528//7528 7527//7527 7529//7529 -f 7528//7528 7529//7529 7514//7514 -f 7514//7514 7529//7529 7530//7530 -f 7514//7514 7530//7530 7512//7512 -f 7531//7531 7532//7532 7533//7533 -f 7533//7533 7532//7532 7534//7534 -f 7533//7533 7534//7534 7535//7535 -f 7535//7535 7534//7534 7536//7536 -f 7535//7535 7536//7536 7537//7537 -f 7533//7533 7538//7538 7531//7531 -f 7531//7531 7538//7538 7539//7539 -f 7531//7531 7539//7539 7540//7540 -f 7540//7540 7539//7539 7541//7541 -f 7540//7540 7541//7541 7542//7542 -f 7542//7542 7541//7541 7543//7543 -f 7542//7542 7543//7543 7544//7544 -f 7543//7543 7545//7545 7544//7544 -f 7544//7544 7545//7545 7546//7546 -f 7544//7544 7546//7546 7547//7547 -f 7547//7547 7546//7546 7548//7548 -f 7547//7547 7548//7548 7549//7549 -f 7549//7549 7548//7548 7550//7550 -f 7549//7549 7550//7550 7551//7551 -f 7551//7551 7550//7550 7552//7552 -f 7551//7551 7552//7552 7553//7553 -f 7553//7553 7552//7552 7554//7554 -f 7553//7553 7554//7554 7555//7555 -f 7555//7555 7554//7554 7556//7556 -f 7556//7556 7554//7554 7557//7557 -f 7556//7556 7557//7557 7558//7558 -f 7558//7558 7557//7557 7559//7559 -f 7558//7558 7559//7559 7560//7560 -f 7560//7560 7559//7559 7561//7561 -f 7560//7560 7561//7561 7562//7562 -f 7563//7563 7564//7564 7565//7565 -f 7565//7565 7564//7564 7566//7566 -f 7565//7565 7566//7566 7562//7562 -f 7562//7562 7566//7566 7567//7567 -f 7562//7562 7567//7567 7560//7560 -f 7568//7568 7569//7569 7570//7570 -f 7570//7570 7569//7569 7571//7571 -f 7570//7570 7571//7571 7572//7572 -f 7572//7572 7571//7571 7573//7573 -f 7572//7572 7573//7573 7574//7574 -f 7574//7574 7573//7573 7575//7575 -f 7574//7574 7575//7575 7576//7576 -f 7576//7576 7575//7575 7577//7577 -f 7576//7576 7577//7577 7578//7578 -f 7578//7578 7577//7577 7579//7579 -f 7578//7578 7579//7579 7580//7580 -f 7581//7581 7582//7582 7583//7583 -f 7583//7583 7582//7582 7580//7580 -f 7583//7583 7580//7580 7584//7584 -f 7584//7584 7580//7580 7579//7579 -f 7585//7585 7586//7586 7587//7587 -f 7587//7587 7586//7586 7588//7588 -f 7587//7587 7588//7588 7568//7568 -f 7568//7568 7588//7588 7589//7589 -f 7568//7568 7589//7589 7569//7569 -f 7587//7587 7590//7590 7585//7585 -f 7585//7585 7590//7590 7591//7591 -f 7585//7585 7591//7591 7592//7592 -f 7593//7593 7594//7594 7595//7595 -f 7595//7595 7594//7594 7592//7592 -f 7595//7595 7592//7592 7596//7596 -f 7596//7596 7592//7592 7591//7591 -f 7597//7597 7598//7598 7599//7599 -f 7599//7599 7598//7598 7600//7600 -f 7599//7599 7600//7600 7601//7601 -f 7601//7601 7600//7600 7602//7602 -f 7601//7601 7602//7602 7593//7593 -f 7593//7593 7602//7602 7603//7603 -f 7593//7593 7603//7603 7594//7594 -f 7604//7604 7605//7605 7606//7606 -f 7607//7607 7608//7608 7609//7609 -f 7609//7609 7608//7608 7610//7610 -f 7609//7609 7610//7610 7611//7611 -f 7611//7611 7610//7610 7612//7612 -f 7611//7611 7612//7612 7613//7613 -f 7613//7613 7612//7612 7614//7614 -f 7613//7613 7614//7614 7615//7615 -f 7615//7615 7614//7614 7616//7616 -f 7615//7615 7616//7616 7617//7617 -f 7617//7617 7616//7616 7618//7618 -f 7617//7617 7618//7618 7619//7619 -f 7618//7618 7620//7620 7619//7619 -f 7619//7619 7620//7620 7621//7621 -f 7619//7619 7621//7621 7622//7622 -f 7622//7622 7621//7621 7623//7623 -f 7622//7622 7623//7623 7624//7624 -f 7624//7624 7623//7623 7625//7625 -f 7625//7625 7623//7623 7626//7626 -f 7625//7625 7626//7626 7605//7605 -f 7605//7605 7626//7626 7627//7627 -f 7605//7605 7627//7627 7606//7606 -f 7604//7604 7606//7606 7628//7628 -f 7628//7628 7606//7606 7629//7629 -f 7628//7628 7629//7629 7630//7630 -f 7630//7630 7629//7629 7631//7631 -f 7630//7630 7631//7631 7632//7632 -f 7632//7632 7631//7631 7633//7633 -f 7632//7632 7633//7633 7634//7634 -f 7634//7634 7633//7633 7635//7635 -f 7634//7634 7635//7635 7636//7636 -f 7636//7636 7635//7635 7637//7637 -f 7636//7636 7637//7637 7638//7638 -f 7638//7638 7637//7637 7639//7639 -f 7638//7638 7639//7639 7640//7640 -f 7641//7641 7642//7642 7643//7643 -f 7641//7641 7643//7643 7644//7644 -f 7644//7644 7643//7643 7645//7645 -f 7644//7644 7645//7645 7646//7646 -f 7647//7647 7648//7648 7649//7649 -f 7649//7649 7648//7648 7650//7650 -f 7649//7649 7650//7650 7651//7651 -f 7651//7651 7650//7650 7652//7652 -f 7651//7651 7652//7652 7642//7642 -f 7642//7642 7652//7652 7653//7653 -f 7642//7642 7653//7653 7643//7643 -f 7654//7654 7655//7655 7656//7656 -f 7656//7656 7657//7657 7654//7654 -f 7654//7654 7657//7657 7658//7658 -f 7654//7654 7658//7658 7647//7647 -f 7647//7647 7658//7658 7659//7659 -f 7647//7647 7659//7659 7648//7648 -f 7660//7660 7661//7661 7662//7662 -f 7662//7662 7661//7661 7663//7663 -f 7662//7662 7663//7663 7664//7664 -f 7664//7664 7663//7663 7665//7665 -f 7664//7664 7665//7665 7666//7666 -f 7666//7666 7665//7665 7667//7667 -f 7666//7666 7667//7667 7655//7655 -f 7655//7655 7667//7667 7668//7668 -f 7655//7655 7668//7668 7656//7656 -f 7669//7669 7670//7670 7671//7671 -f 7671//7671 7670//7670 7672//7672 -f 7671//7671 7672//7672 7673//7673 -f 7672//7672 7674//7674 7673//7673 -f 7673//7673 7674//7674 7675//7675 -f 7673//7673 7675//7675 7676//7676 -f 7676//7676 7675//7675 7677//7677 -f 7676//7676 7677//7677 7662//7662 -f 7662//7662 7677//7677 7678//7678 -f 7662//7662 7678//7678 7660//7660 -f 7679//7679 7680//7680 7681//7681 -f 7681//7681 7680//7680 7682//7682 -f 7681//7681 7682//7682 7683//7683 -f 7683//7683 7682//7682 7684//7684 -f 7683//7683 7684//7684 7685//7685 -f 7681//7681 7686//7686 7679//7679 -f 7679//7679 7686//7686 7687//7687 -f 7679//7679 7687//7687 7688//7688 -f 7688//7688 7687//7687 7689//7689 -f 7688//7688 7689//7689 7690//7690 -f 7690//7690 7689//7689 7691//7691 -f 7690//7690 7691//7691 7692//7692 -f 7691//7691 7693//7693 7692//7692 -f 7692//7692 7693//7693 7694//7694 -f 7692//7692 7694//7694 7695//7695 -f 7695//7695 7694//7694 7696//7696 -f 7695//7695 7696//7696 7697//7697 -f 7697//7697 7696//7696 7698//7698 -f 7697//7697 7698//7698 7699//7699 -f 7699//7699 7698//7698 7700//7700 -f 7699//7699 7700//7700 7701//7701 -f 7701//7701 7700//7700 7702//7702 -f 7701//7701 7702//7702 7703//7703 -f 7703//7703 7702//7702 7704//7704 -f 7704//7704 7702//7702 7705//7705 -f 7704//7704 7705//7705 7706//7706 -f 7706//7706 7705//7705 7707//7707 -f 7706//7706 7707//7707 7708//7708 -f 7708//7708 7707//7707 7709//7709 -f 7708//7708 7709//7709 7710//7710 -f 7711//7711 7712//7712 7713//7713 -f 7713//7713 7712//7712 7714//7714 -f 7713//7713 7714//7714 7710//7710 -f 7710//7710 7714//7714 7715//7715 -f 7710//7710 7715//7715 7708//7708 -f 7716//7716 7717//7717 7718//7718 -f 7718//7718 7717//7717 7719//7719 -f 7718//7718 7719//7719 7720//7720 -f 7720//7720 7719//7719 7721//7721 -f 7720//7720 7721//7721 7722//7722 -f 7722//7722 7721//7721 7723//7723 -f 7722//7722 7723//7723 7724//7724 -f 7724//7724 7723//7723 7725//7725 -f 7724//7724 7725//7725 7726//7726 -f 7726//7726 7725//7725 7727//7727 -f 7726//7726 7727//7727 7728//7728 -f 7729//7729 7730//7730 7731//7731 -f 7731//7731 7730//7730 7728//7728 -f 7731//7731 7728//7728 7732//7732 -f 7732//7732 7728//7728 7727//7727 -f 7733//7733 7734//7734 7735//7735 -f 7735//7735 7734//7734 7736//7736 -f 7735//7735 7736//7736 7716//7716 -f 7716//7716 7736//7736 7737//7737 -f 7716//7716 7737//7737 7717//7717 -f 7735//7735 7738//7738 7733//7733 -f 7733//7733 7738//7738 7739//7739 -f 7733//7733 7739//7739 7740//7740 -f 7741//7741 7742//7742 7743//7743 -f 7743//7743 7742//7742 7740//7740 -f 7743//7743 7740//7740 7744//7744 -f 7744//7744 7740//7740 7739//7739 -f 7745//7745 7746//7746 7747//7747 -f 7747//7747 7746//7746 7748//7748 -f 7747//7747 7748//7748 7749//7749 -f 7749//7749 7748//7748 7750//7750 -f 7749//7749 7750//7750 7741//7741 -f 7741//7741 7750//7750 7751//7751 -f 7741//7741 7751//7751 7742//7742 -f 7752//7752 7753//7753 7754//7754 -f 7755//7755 7756//7756 7757//7757 -f 7757//7757 7756//7756 7758//7758 -f 7757//7757 7758//7758 7759//7759 -f 7759//7759 7758//7758 7760//7760 -f 7759//7759 7760//7760 7761//7761 -f 7761//7761 7760//7760 7762//7762 -f 7761//7761 7762//7762 7763//7763 -f 7763//7763 7762//7762 7764//7764 -f 7763//7763 7764//7764 7765//7765 -f 7765//7765 7764//7764 7766//7766 -f 7765//7765 7766//7766 7767//7767 -f 7766//7766 7768//7768 7767//7767 -f 7767//7767 7768//7768 7769//7769 -f 7767//7767 7769//7769 7770//7770 -f 7770//7770 7769//7769 7771//7771 -f 7770//7770 7771//7771 7772//7772 -f 7772//7772 7771//7771 7773//7773 -f 7773//7773 7771//7771 7774//7774 -f 7773//7773 7774//7774 7753//7753 -f 7753//7753 7774//7774 7775//7775 -f 7753//7753 7775//7775 7754//7754 -f 7752//7752 7754//7754 7776//7776 -f 7776//7776 7754//7754 7777//7777 -f 7776//7776 7777//7777 7778//7778 -f 7778//7778 7777//7777 7779//7779 -f 7778//7778 7779//7779 7780//7780 -f 7780//7780 7779//7779 7781//7781 -f 7780//7780 7781//7781 7782//7782 -f 7782//7782 7781//7781 7783//7783 -f 7782//7782 7783//7783 7784//7784 -f 7784//7784 7783//7783 7785//7785 -f 7784//7784 7785//7785 7786//7786 -f 7786//7786 7785//7785 7787//7787 -f 7786//7786 7787//7787 7788//7788 -f 7789//7789 7790//7790 7791//7791 -f 7789//7789 7791//7791 7792//7792 -f 7792//7792 7791//7791 7793//7793 -f 7792//7792 7793//7793 7794//7794 -f 7795//7795 7796//7796 7797//7797 -f 7797//7797 7796//7796 7798//7798 -f 7797//7797 7798//7798 7799//7799 -f 7799//7799 7798//7798 7800//7800 -f 7799//7799 7800//7800 7790//7790 -f 7790//7790 7800//7800 7801//7801 -f 7790//7790 7801//7801 7791//7791 -f 7802//7802 7803//7803 7804//7804 -f 7804//7804 7805//7805 7802//7802 -f 7802//7802 7805//7805 7806//7806 -f 7802//7802 7806//7806 7795//7795 -f 7795//7795 7806//7806 7807//7807 -f 7795//7795 7807//7807 7796//7796 -f 7808//7808 7809//7809 7810//7810 -f 7810//7810 7809//7809 7811//7811 -f 7810//7810 7811//7811 7812//7812 -f 7812//7812 7811//7811 7813//7813 -f 7812//7812 7813//7813 7814//7814 -f 7814//7814 7813//7813 7815//7815 -f 7814//7814 7815//7815 7803//7803 -f 7803//7803 7815//7815 7816//7816 -f 7803//7803 7816//7816 7804//7804 -f 7817//7817 7818//7818 7819//7819 -f 7819//7819 7818//7818 7820//7820 -f 7819//7819 7820//7820 7821//7821 -f 7820//7820 7822//7822 7821//7821 -f 7821//7821 7822//7822 7823//7823 -f 7821//7821 7823//7823 7824//7824 -f 7824//7824 7823//7823 7825//7825 -f 7824//7824 7825//7825 7810//7810 -f 7810//7810 7825//7825 7826//7826 -f 7810//7810 7826//7826 7808//7808 -f 7827//7827 7828//7828 7829//7829 -f 7830//7830 7831//7831 7832//7832 -f 7832//7832 7831//7831 7833//7833 -f 7832//7832 7833//7833 7834//7834 -f 7834//7834 7833//7833 7835//7835 -f 7834//7834 7835//7835 7836//7836 -f 7832//7832 7837//7837 7830//7830 -f 7830//7830 7837//7837 7838//7838 -f 7830//7830 7838//7838 7839//7839 -f 7839//7839 7838//7838 7840//7840 -f 7839//7839 7840//7840 7841//7841 -f 7841//7841 7840//7840 7842//7842 -f 7841//7841 7842//7842 7843//7843 -f 7842//7842 7844//7844 7843//7843 -f 7843//7843 7844//7844 7845//7845 -f 7843//7843 7845//7845 7846//7846 -f 7846//7846 7845//7845 7847//7847 -f 7846//7846 7847//7847 7848//7848 -f 7848//7848 7847//7847 7849//7849 -f 7848//7848 7849//7849 7850//7850 -f 7850//7850 7849//7849 7851//7851 -f 7850//7850 7851//7851 7852//7852 -f 7852//7852 7851//7851 7853//7853 -f 7852//7852 7853//7853 7854//7854 -f 7854//7854 7853//7853 7855//7855 -f 7855//7855 7853//7853 7856//7856 -f 7856//7856 7853//7853 7857//7857 -f 7856//7856 7857//7857 7829//7829 -f 7829//7829 7857//7857 7858//7858 -f 7829//7829 7858//7858 7827//7827 -f 7859//7859 7860//7860 7861//7861 -f 7861//7861 7862//7862 7859//7859 -f 7859//7859 7862//7862 7863//7863 -f 7859//7859 7863//7863 7828//7828 -f 7828//7828 7863//7863 7864//7864 -f 7828//7828 7864//7864 7829//7829 -f 7865//7865 7866//7866 7867//7867 -f 7867//7867 7866//7866 7868//7868 -f 7867//7867 7868//7868 7869//7869 -f 7870//7870 7871//7871 7872//7872 -f 7872//7872 7871//7871 7873//7873 -f 7872//7872 7873//7873 7874//7874 -f 7874//7874 7873//7873 7875//7875 -f 7874//7874 7875//7875 7876//7876 -f 7876//7876 7875//7875 7869//7869 -f 7876//7876 7869//7869 7877//7877 -f 7877//7877 7869//7869 7868//7868 -f 7878//7878 7879//7879 7880//7880 -f 7880//7880 7879//7879 7881//7881 -f 7880//7880 7881//7881 7882//7882 -f 7882//7882 7881//7881 7883//7883 -f 7882//7882 7883//7883 7884//7884 -f 7884//7884 7883//7883 7885//7885 -f 7884//7884 7885//7885 7886//7886 -f 7886//7886 7885//7885 7887//7887 -f 7886//7886 7887//7887 7865//7865 -f 7865//7865 7887//7887 7888//7888 -f 7865//7865 7888//7888 7866//7866 -f 7880//7880 7889//7889 7878//7878 -f 7878//7878 7889//7889 7890//7890 -f 7878//7878 7890//7890 7891//7891 -f 7891//7891 7890//7890 7892//7892 -f 7891//7891 7892//7892 7893//7893 -f 7893//7893 7892//7892 7894//7894 -f 7893//7893 7894//7894 7895//7895 -f 7895//7895 7894//7894 7896//7896 -f 7895//7895 7896//7896 7897//7897 -f 7897//7897 7896//7896 7898//7898 -f 7896//7896 7899//7899 7898//7898 -f 7898//7898 7899//7899 7900//7900 -f 7898//7898 7900//7900 7901//7901 -f 7901//7901 7900//7900 7902//7902 -f 7901//7901 7902//7902 7903//7903 -f 7904//7904 7905//7905 7906//7906 -f 7907//7907 7908//7908 7909//7909 -f 7910//7910 7911//7911 7912//7912 -f 7912//7912 7911//7911 7913//7913 -f 7912//7912 7913//7913 7914//7914 -f 7914//7914 7913//7913 7915//7915 -f 7914//7914 7915//7915 7916//7916 -f 7916//7916 7915//7915 7917//7917 -f 7916//7916 7917//7917 7918//7918 -f 7918//7918 7917//7917 7919//7919 -f 7918//7918 7919//7919 7920//7920 -f 7920//7920 7919//7919 7921//7921 -f 7920//7920 7921//7921 7909//7909 -f 7909//7909 7921//7921 7922//7922 -f 7909//7909 7922//7922 7907//7907 -f 7908//7908 7907//7907 7923//7923 -f 7923//7923 7907//7907 7924//7924 -f 7923//7923 7924//7924 7925//7925 -f 7925//7925 7924//7924 7926//7926 -f 7925//7925 7926//7926 7905//7905 -f 7905//7905 7926//7926 7927//7927 -f 7905//7905 7927//7927 7906//7906 -f 7904//7904 7906//7906 7928//7928 -f 7928//7928 7906//7906 7929//7929 -f 7928//7928 7929//7929 7930//7930 -f 7930//7930 7929//7929 7931//7931 -f 7930//7930 7931//7931 7932//7932 -f 7932//7932 7931//7931 7933//7933 -f 7932//7932 7933//7933 7934//7934 -f 7934//7934 7933//7933 7935//7935 -f 7935//7935 7933//7933 7936//7936 -f 7935//7935 7936//7936 7937//7937 -f 7937//7937 7936//7936 7938//7938 -f 7937//7937 7938//7938 7939//7939 -f 7939//7939 7938//7938 7940//7940 -f 7939//7939 7940//7940 7941//7941 -f 7942//7942 7943//7943 7944//7944 -f 7942//7942 7944//7944 7945//7945 -f 7945//7945 7944//7944 7946//7946 -f 7945//7945 7946//7946 7947//7947 -f 7948//7948 7949//7949 7950//7950 -f 7950//7950 7951//7951 7948//7948 -f 7948//7948 7951//7951 7952//7952 -f 7948//7948 7952//7952 7953//7953 -f 7953//7953 7952//7952 7954//7954 -f 7953//7953 7954//7954 7943//7943 -f 7943//7943 7954//7954 7955//7955 -f 7943//7943 7955//7955 7944//7944 -f 7956//7956 7957//7957 7958//7958 -f 7958//7958 7959//7959 7956//7956 -f 7956//7956 7959//7959 7960//7960 -f 7956//7956 7960//7960 7949//7949 -f 7949//7949 7960//7960 7961//7961 -f 7949//7949 7961//7961 7950//7950 -f 7962//7962 7963//7963 7964//7964 -f 7964//7964 7963//7963 7965//7965 -f 7964//7964 7965//7965 7966//7966 -f 7965//7965 7967//7967 7966//7966 -f 7966//7966 7967//7967 7968//7968 -f 7966//7966 7968//7968 7969//7969 -f 7969//7969 7968//7968 7970//7970 -f 7969//7969 7970//7970 7957//7957 -f 7957//7957 7970//7970 7971//7971 -f 7957//7957 7971//7971 7958//7958 -f 7972//7972 7973//7973 7974//7974 -f 7972//7972 7974//7974 7964//7964 -f 7964//7964 7974//7974 7975//7975 -f 7964//7964 7975//7975 7962//7962 -f 7976//7976 7977//7977 7978//7978 -f 7978//7978 7977//7977 7979//7979 -f 7978//7978 7979//7979 7973//7973 -f 7973//7973 7979//7979 7980//7980 -f 7973//7973 7980//7980 7974//7974 -f 7981//7981 7982//7982 7983//7983 -f 7983//7983 7982//7982 7984//7984 -f 7983//7983 7984//7984 7985//7985 -f 7985//7985 7984//7984 7986//7986 -f 7985//7985 7986//7986 7987//7987 -f 7987//7987 7986//7986 7988//7988 -f 7987//7987 7988//7988 7989//7989 -f 7988//7988 7990//7990 7989//7989 -f 7989//7989 7990//7990 7991//7991 -f 7989//7989 7991//7991 7992//7992 -f 7992//7992 7991//7991 7993//7993 -f 7992//7992 7993//7993 7994//7994 -f 7994//7994 7993//7993 7995//7995 -f 7993//7993 7996//7996 7995//7995 -f 7995//7995 7996//7996 7997//7997 -f 7995//7995 7997//7997 7998//7998 -f 7998//7998 7997//7997 7999//7999 -f 7998//7998 7999//7999 8000//8000 -f 8000//8000 7999//7999 8001//8001 -f 8000//8000 8001//8001 8002//8002 -f 8002//8002 8001//8001 8003//8003 -f 8002//8002 8003//8003 8004//8004 -f 8004//8004 8003//8003 8005//8005 -f 8004//8004 8005//8005 8006//8006 -f 8006//8006 8005//8005 8007//8007 -f 8007//8007 8005//8005 8008//8008 -f 8007//8007 8008//8008 8009//8009 -f 8009//8009 8008//8008 8010//8010 -f 8009//8009 8010//8010 8011//8011 -f 8012//8012 8013//8013 8014//8014 -f 8010//8010 8015//8015 8011//8011 -f 8011//8011 8015//8015 8016//8016 -f 8011//8011 8016//8016 8017//8017 -f 8017//8017 8016//8016 8012//8012 -f 8017//8017 8012//8012 8018//8018 -f 8018//8018 8012//8012 8014//8014 -f 8019//8019 8020//8020 8021//8021 -f 8019//8019 8021//8021 8022//8022 -f 8021//8021 8023//8023 8022//8022 -f 8022//8022 8023//8023 8024//8024 -f 8022//8022 8024//8024 8025//8025 -f 8025//8025 8024//8024 8026//8026 -f 8025//8025 8026//8026 8027//8027 -f 8027//8027 8026//8026 8028//8028 -f 8027//8027 8028//8028 8029//8029 -f 8029//8029 8028//8028 8030//8030 -f 8029//8029 8030//8030 8031//8031 -f 8031//8031 8030//8030 8032//8032 -f 8031//8031 8032//8032 8033//8033 -f 8033//8033 8032//8032 8034//8034 -f 8033//8033 8034//8034 8035//8035 -f 8036//8036 8037//8037 8038//8038 -f 8038//8038 8037//8037 8035//8035 -f 8038//8038 8035//8035 8039//8039 -f 8039//8039 8035//8035 8034//8034 -f 8020//8020 8019//8019 8040//8040 -f 8040//8040 8019//8019 8041//8041 -f 8040//8040 8041//8041 8042//8042 -f 8042//8042 8041//8041 8043//8043 -f 8042//8042 8043//8043 8044//8044 -f 8044//8044 8043//8043 8045//8045 -f 8044//8044 8045//8045 8046//8046 -f 8046//8046 8045//8045 8047//8047 -f 8046//8046 8047//8047 8048//8048 -f 8049//8049 8050//8050 8051//8051 -f 8051//8051 8050//8050 8048//8048 -f 8051//8051 8048//8048 8052//8052 -f 8052//8052 8048//8048 8047//8047 -f 7373//7373 7372//7372 8053//8053 -f 8053//8053 7372//7372 8054//8054 -f 8055//8055 8056//8056 8057//8057 -f 8055//8055 8057//8057 8058//8058 -f 8058//8058 8057//8057 8059//8059 -f 8058//8058 8059//8059 8060//8060 -f 8060//8060 8059//8059 8061//8061 -f 8060//8060 8061//8061 8062//8062 -f 8062//8062 8061//8061 8063//8063 -f 8062//8062 8063//8063 8064//8064 -f 8064//8064 8063//8063 8065//8065 -f 8064//8064 8065//8065 8066//8066 -f 8066//8066 8065//8065 8067//8067 -f 8066//8066 8067//8067 8068//8068 -f 8068//8068 8067//8067 8069//8069 -f 8068//8068 8069//8069 8070//8070 -f 8070//8070 8069//8069 8071//8071 -f 8070//8070 8071//8071 8054//8054 -f 8054//8054 8071//8071 8072//8072 -f 8054//8054 8072//8072 8053//8053 -f 8056//8056 8055//8055 8073//8073 -f 8073//8073 8055//8055 8074//8074 -f 8073//8073 8074//8074 8075//8075 -f 8074//8074 8076//8076 8075//8075 -f 8075//8075 8076//8076 8077//8077 -f 8075//8075 8077//8077 8078//8078 -f 8078//8078 8077//8077 8079//8079 -f 8080//8080 8081//8081 8079//8079 -f 8079//8079 8081//8081 8082//8082 -f 8079//8079 8082//8082 8078//8078 -f 8079//8079 8083//8083 8080//8080 -f 8080//8080 8083//8083 8084//8084 -f 8080//8080 8084//8084 8085//8085 -f 8085//8085 8084//8084 7430//7430 -f 8085//8085 7430//7430 7429//7429 -f 7450//7450 7449//7449 8086//8086 -f 8086//8086 7449//7449 8087//8087 -f 8086//8086 8087//8087 8088//8088 -f 8088//8088 8087//8087 8089//8089 -f 8088//8088 8089//8089 8090//8090 -f 8090//8090 8089//8089 8091//8091 -f 8090//8090 8091//8091 8092//8092 -f 8092//8092 8091//8091 8093//8093 -f 8094//8094 8095//8095 8096//8096 -f 8096//8096 8095//8095 8097//8097 -f 8096//8096 8097//8097 8098//8098 -f 8093//8093 8091//8091 8099//8099 -f 8099//8099 8091//8091 8100//8100 -f 8099//8099 8100//8100 8094//8094 -f 8094//8094 8100//8100 8101//8101 -f 8094//8094 8101//8101 8095//8095 -f 8098//8098 8097//8097 8102//8102 -f 8102//8102 8097//8097 8103//8103 -f 8102//8102 8103//8103 8104//8104 -f 8104//8104 8103//8103 8105//8105 -f 8105//8105 8103//8103 8106//8106 -f 8105//8105 8106//8106 8107//8107 -f 8107//8107 8106//8106 8108//8108 -f 8107//8107 8108//8108 8109//8109 -f 8109//8109 8108//8108 8110//8110 -f 8109//8109 8110//8110 8111//8111 -f 8110//8110 8112//8112 8111//8111 -f 8111//8111 8112//8112 8113//8113 -f 8111//8111 8113//8113 8114//8114 -f 8114//8114 8113//8113 8115//8115 -f 8114//8114 8115//8115 8116//8116 -f 8115//8115 8117//8117 8116//8116 -f 8116//8116 8117//8117 8118//8118 -f 8116//8116 8118//8118 8119//8119 -f 8119//8119 8118//8118 8120//8120 -f 8119//8119 8120//8120 8121//8121 -f 8121//8121 8120//8120 7460//7460 -f 8121//8121 7460//7460 7459//7459 -f 8122//8122 8123//8123 8124//8124 -f 8124//8124 8123//8123 8125//8125 -f 8124//8124 8125//8125 8126//8126 -f 8126//8126 8125//8125 8127//8127 -f 8126//8126 8127//8127 8128//8128 -f 8128//8128 8127//8127 8129//8129 -f 8128//8128 8129//8129 7492//7492 -f 7492//7492 8129//8129 8130//8130 -f 7492//7492 8130//8130 7490//7490 -f 8122//8122 8131//8131 8123//8123 -f 8123//8123 8131//8131 8132//8132 -f 8123//8123 8132//8132 8133//8133 -f 8133//8133 8132//8132 8134//8134 -f 8133//8133 8134//8134 8135//8135 -f 8135//8135 8134//8134 8136//8136 -f 8136//8136 8134//8134 8137//8137 -f 8136//8136 8137//8137 8138//8138 -f 8138//8138 8137//8137 8139//8139 -f 8138//8138 8139//8139 8140//8140 -f 8140//8140 8139//8139 8141//8141 -f 8140//8140 8141//8141 8142//8142 -f 8142//8142 8141//8141 8143//8143 -f 8142//8142 8143//8143 8144//8144 -f 8144//8144 8143//8143 8145//8145 -f 8144//8144 8145//8145 8146//8146 -f 8146//8146 8145//8145 8147//8147 -f 8146//8146 8147//8147 8148//8148 -f 8147//8147 8149//8149 8148//8148 -f 8148//8148 8149//8149 8150//8150 -f 8148//8148 8150//8150 8151//8151 -f 8151//8151 8150//8150 8152//8152 -f 8151//8151 8152//8152 8153//8153 -f 8153//8153 8152//8152 8154//8154 -f 8153//8153 8154//8154 7498//7498 -f 7498//7498 8154//8154 8155//8155 -f 7498//7498 8155//8155 7496//7496 -f 8156//8156 8157//8157 8158//8158 -f 7522//7522 7521//7521 8159//8159 -f 8159//8159 7521//7521 8160//8160 -f 8159//8159 8160//8160 8161//8161 -f 8161//8161 8160//8160 8162//8162 -f 8161//8161 8162//8162 8163//8163 -f 8163//8163 8162//8162 8164//8164 -f 8163//8163 8164//8164 8165//8165 -f 8164//8164 8166//8166 8165//8165 -f 8165//8165 8166//8166 8167//8167 -f 8165//8165 8167//8167 8168//8168 -f 8168//8168 8167//8167 8169//8169 -f 8168//8168 8169//8169 8170//8170 -f 8170//8170 8169//8169 8171//8171 -f 8170//8170 8171//8171 8157//8157 -f 8157//8157 8171//8171 8172//8172 -f 8157//8157 8172//8172 8158//8158 -f 8156//8156 8158//8158 8173//8173 -f 8173//8173 8158//8158 8174//8174 -f 8173//8173 8174//8174 8175//8175 -f 8175//8175 8174//8174 8176//8176 -f 8175//8175 8176//8176 8177//8177 -f 8177//8177 8176//8176 8178//8178 -f 8177//8177 8178//8178 8179//8179 -f 8178//8178 8180//8180 8179//8179 -f 8179//8179 8180//8180 8181//8181 -f 8179//8179 8181//8181 8182//8182 -f 8182//8182 8181//8181 8183//8183 -f 7537//7537 7536//7536 8184//8184 -f 8184//8184 7536//7536 8185//8185 -f 8184//8184 8185//8185 8186//8186 -f 8186//8186 8185//8185 8187//8187 -f 8186//8186 8187//8187 8188//8188 -f 8188//8188 8187//8187 8189//8189 -f 8188//8188 8189//8189 8183//8183 -f 8183//8183 8189//8189 8190//8190 -f 8183//8183 8190//8190 8182//8182 -f 8191//8191 8192//8192 8193//8193 -f 8193//8193 8192//8192 8194//8194 -f 8193//8193 8194//8194 8195//8195 -f 8195//8195 8194//8194 7564//7564 -f 8195//8195 7564//7564 7563//7563 -f 8193//8193 8196//8196 8191//8191 -f 8191//8191 8196//8196 8197//8197 -f 8191//8191 8197//8197 8198//8198 -f 8198//8198 8197//8197 8199//8199 -f 8198//8198 8199//8199 8200//8200 -f 8200//8200 8199//8199 8201//8201 -f 8200//8200 8201//8201 8202//8202 -f 8202//8202 8201//8201 8203//8203 -f 8202//8202 8203//8203 8204//8204 -f 8204//8204 8203//8203 8205//8205 -f 8203//8203 8206//8206 8205//8205 -f 8205//8205 8206//8206 8207//8207 -f 8205//8205 8207//8207 8208//8208 -f 8208//8208 8207//8207 8209//8209 -f 8208//8208 8209//8209 8210//8210 -f 8210//8210 8209//8209 8211//8211 -f 8210//8210 8211//8211 8212//8212 -f 8212//8212 8211//8211 8213//8213 -f 8212//8212 8213//8213 8214//8214 -f 8214//8214 8213//8213 8215//8215 -f 8214//8214 8215//8215 8216//8216 -f 8216//8216 8215//8215 8217//8217 -f 8216//8216 8217//8217 8218//8218 -f 8218//8218 8217//8217 8219//8219 -f 8218//8218 8219//8219 8220//8220 -f 8220//8220 8219//8219 8221//8221 -f 8220//8220 8221//8221 8222//8222 -f 8222//8222 8221//8221 8223//8223 -f 8222//8222 8223//8223 8224//8224 -f 8224//8224 8223//8223 8225//8225 -f 8224//8224 8225//8225 8226//8226 -f 8226//8226 8225//8225 7582//7582 -f 8226//8226 7582//7582 7581//7581 -f 7598//7598 7597//7597 8227//8227 -f 8227//8227 7597//7597 8228//8228 -f 8227//8227 8228//8228 8229//8229 -f 8229//8229 8228//8228 8230//8230 -f 8229//8229 8230//8230 8231//8231 -f 8231//8231 8230//8230 8232//8232 -f 8231//8231 8232//8232 8233//8233 -f 8233//8233 8232//8232 8234//8234 -f 8235//8235 8236//8236 8237//8237 -f 8237//8237 8236//8236 8238//8238 -f 8237//8237 8238//8238 8239//8239 -f 8234//8234 8232//8232 8240//8240 -f 8240//8240 8232//8232 8241//8241 -f 8240//8240 8241//8241 8235//8235 -f 8235//8235 8241//8241 8242//8242 -f 8235//8235 8242//8242 8236//8236 -f 8239//8239 8238//8238 8243//8243 -f 8243//8243 8238//8238 8244//8244 -f 8243//8243 8244//8244 8245//8245 -f 8245//8245 8244//8244 8246//8246 -f 8246//8246 8244//8244 8247//8247 -f 8246//8246 8247//8247 8248//8248 -f 8248//8248 8247//8247 8249//8249 -f 8248//8248 8249//8249 8250//8250 -f 8250//8250 8249//8249 8251//8251 -f 8250//8250 8251//8251 8252//8252 -f 8251//8251 8253//8253 8252//8252 -f 8252//8252 8253//8253 8254//8254 -f 8252//8252 8254//8254 8255//8255 -f 8255//8255 8254//8254 8256//8256 -f 8255//8255 8256//8256 8257//8257 -f 8256//8256 8258//8258 8257//8257 -f 8257//8257 8258//8258 8259//8259 -f 8257//8257 8259//8259 8260//8260 -f 8260//8260 8259//8259 8261//8261 -f 8260//8260 8261//8261 8262//8262 -f 8262//8262 8261//8261 7608//7608 -f 8262//8262 7608//7608 7607//7607 -f 8263//8263 8264//8264 8265//8265 -f 8265//8265 8264//8264 8266//8266 -f 8265//8265 8266//8266 8267//8267 -f 8267//8267 8266//8266 8268//8268 -f 8267//8267 8268//8268 8269//8269 -f 8269//8269 8268//8268 8270//8270 -f 8269//8269 8270//8270 7640//7640 -f 7640//7640 8270//8270 8271//8271 -f 7640//7640 8271//8271 7638//7638 -f 8263//8263 8272//8272 8264//8264 -f 8264//8264 8272//8272 8273//8273 -f 8264//8264 8273//8273 8274//8274 -f 8274//8274 8273//8273 8275//8275 -f 8274//8274 8275//8275 8276//8276 -f 8276//8276 8275//8275 8277//8277 -f 8277//8277 8275//8275 8278//8278 -f 8277//8277 8278//8278 8279//8279 -f 8279//8279 8278//8278 8280//8280 -f 8279//8279 8280//8280 8281//8281 -f 8281//8281 8280//8280 8282//8282 -f 8281//8281 8282//8282 8283//8283 -f 8283//8283 8282//8282 8284//8284 -f 8283//8283 8284//8284 8285//8285 -f 8285//8285 8284//8284 8286//8286 -f 8285//8285 8286//8286 8287//8287 -f 8287//8287 8286//8286 8288//8288 -f 8287//8287 8288//8288 8289//8289 -f 8288//8288 8290//8290 8289//8289 -f 8289//8289 8290//8290 8291//8291 -f 8289//8289 8291//8291 8292//8292 -f 8292//8292 8291//8291 8293//8293 -f 8292//8292 8293//8293 8294//8294 -f 8294//8294 8293//8293 8295//8295 -f 8294//8294 8295//8295 7646//7646 -f 7646//7646 8295//8295 8296//8296 -f 7646//7646 8296//8296 7644//7644 -f 8297//8297 8298//8298 8299//8299 -f 7670//7670 7669//7669 8300//8300 -f 8300//8300 7669//7669 8301//8301 -f 8300//8300 8301//8301 8302//8302 -f 8302//8302 8301//8301 8303//8303 -f 8302//8302 8303//8303 8304//8304 -f 8304//8304 8303//8303 8305//8305 -f 8304//8304 8305//8305 8306//8306 -f 8305//8305 8307//8307 8306//8306 -f 8306//8306 8307//8307 8308//8308 -f 8306//8306 8308//8308 8309//8309 -f 8309//8309 8308//8308 8310//8310 -f 8309//8309 8310//8310 8311//8311 -f 8311//8311 8310//8310 8312//8312 -f 8311//8311 8312//8312 8298//8298 -f 8298//8298 8312//8312 8313//8313 -f 8298//8298 8313//8313 8299//8299 -f 8297//8297 8299//8299 8314//8314 -f 8314//8314 8299//8299 8315//8315 -f 8314//8314 8315//8315 8316//8316 -f 8316//8316 8315//8315 8317//8317 -f 8316//8316 8317//8317 8318//8318 -f 8318//8318 8317//8317 8319//8319 -f 8318//8318 8319//8319 8320//8320 -f 8319//8319 8321//8321 8320//8320 -f 8320//8320 8321//8321 8322//8322 -f 8320//8320 8322//8322 8323//8323 -f 8323//8323 8322//8322 8324//8324 -f 7685//7685 7684//7684 8325//8325 -f 8325//8325 7684//7684 8326//8326 -f 8325//8325 8326//8326 8327//8327 -f 8327//8327 8326//8326 8328//8328 -f 8327//8327 8328//8328 8329//8329 -f 8329//8329 8328//8328 8330//8330 -f 8329//8329 8330//8330 8324//8324 -f 8324//8324 8330//8330 8331//8331 -f 8324//8324 8331//8331 8323//8323 -f 8332//8332 8333//8333 8334//8334 -f 8334//8334 8333//8333 8335//8335 -f 8334//8334 8335//8335 8336//8336 -f 8336//8336 8335//8335 7712//7712 -f 8336//8336 7712//7712 7711//7711 -f 8334//8334 8337//8337 8332//8332 -f 8332//8332 8337//8337 8338//8338 -f 8332//8332 8338//8338 8339//8339 -f 8339//8339 8338//8338 8340//8340 -f 8339//8339 8340//8340 8341//8341 -f 8341//8341 8340//8340 8342//8342 -f 8341//8341 8342//8342 8343//8343 -f 8343//8343 8342//8342 8344//8344 -f 8343//8343 8344//8344 8345//8345 -f 8345//8345 8344//8344 8346//8346 -f 8344//8344 8347//8347 8346//8346 -f 8346//8346 8347//8347 8348//8348 -f 8346//8346 8348//8348 8349//8349 -f 8349//8349 8348//8348 8350//8350 -f 8349//8349 8350//8350 8351//8351 -f 8351//8351 8350//8350 8352//8352 -f 8351//8351 8352//8352 8353//8353 -f 8353//8353 8352//8352 8354//8354 -f 8353//8353 8354//8354 8355//8355 -f 8355//8355 8354//8354 8356//8356 -f 8355//8355 8356//8356 8357//8357 -f 8357//8357 8356//8356 8358//8358 -f 8357//8357 8358//8358 8359//8359 -f 8359//8359 8358//8358 8360//8360 -f 8359//8359 8360//8360 8361//8361 -f 8361//8361 8360//8360 8362//8362 -f 8361//8361 8362//8362 8363//8363 -f 8363//8363 8362//8362 8364//8364 -f 8363//8363 8364//8364 8365//8365 -f 8365//8365 8364//8364 8366//8366 -f 8365//8365 8366//8366 8367//8367 -f 8367//8367 8366//8366 7730//7730 -f 8367//8367 7730//7730 7729//7729 -f 7746//7746 7745//7745 8368//8368 -f 8368//8368 7745//7745 8369//8369 -f 8368//8368 8369//8369 8370//8370 -f 8370//8370 8369//8369 8371//8371 -f 8370//8370 8371//8371 8372//8372 -f 8372//8372 8371//8371 8373//8373 -f 8372//8372 8373//8373 8374//8374 -f 8374//8374 8373//8373 8375//8375 -f 8376//8376 8377//8377 8378//8378 -f 8378//8378 8377//8377 8379//8379 -f 8378//8378 8379//8379 8380//8380 -f 8375//8375 8373//8373 8381//8381 -f 8381//8381 8373//8373 8382//8382 -f 8381//8381 8382//8382 8376//8376 -f 8376//8376 8382//8382 8383//8383 -f 8376//8376 8383//8383 8377//8377 -f 8380//8380 8379//8379 8384//8384 -f 8384//8384 8379//8379 8385//8385 -f 8384//8384 8385//8385 8386//8386 -f 8386//8386 8385//8385 8387//8387 -f 8387//8387 8385//8385 8388//8388 -f 8387//8387 8388//8388 8389//8389 -f 8389//8389 8388//8388 8390//8390 -f 8389//8389 8390//8390 8391//8391 -f 8391//8391 8390//8390 8392//8392 -f 8391//8391 8392//8392 8393//8393 -f 8392//8392 8394//8394 8393//8393 -f 8393//8393 8394//8394 8395//8395 -f 8393//8393 8395//8395 8396//8396 -f 8396//8396 8395//8395 8397//8397 -f 8396//8396 8397//8397 8398//8398 -f 8397//8397 8399//8399 8398//8398 -f 8398//8398 8399//8399 8400//8400 -f 8398//8398 8400//8400 8401//8401 -f 8401//8401 8400//8400 8402//8402 -f 8401//8401 8402//8402 8403//8403 -f 8403//8403 8402//8402 7756//7756 -f 8403//8403 7756//7756 7755//7755 -f 8404//8404 8405//8405 8406//8406 -f 8406//8406 8405//8405 8407//8407 -f 8406//8406 8407//8407 8408//8408 -f 8408//8408 8407//8407 8409//8409 -f 8408//8408 8409//8409 8410//8410 -f 8410//8410 8409//8409 8411//8411 -f 8410//8410 8411//8411 7788//7788 -f 7788//7788 8411//8411 8412//8412 -f 7788//7788 8412//8412 7786//7786 -f 8404//8404 8413//8413 8405//8405 -f 8405//8405 8413//8413 8414//8414 -f 8405//8405 8414//8414 8415//8415 -f 8415//8415 8414//8414 8416//8416 -f 8415//8415 8416//8416 8417//8417 -f 8417//8417 8416//8416 8418//8418 -f 8418//8418 8416//8416 8419//8419 -f 8418//8418 8419//8419 8420//8420 -f 8420//8420 8419//8419 8421//8421 -f 8420//8420 8421//8421 8422//8422 -f 8422//8422 8421//8421 8423//8423 -f 8422//8422 8423//8423 8424//8424 -f 8424//8424 8423//8423 8425//8425 -f 8424//8424 8425//8425 8426//8426 -f 8426//8426 8425//8425 8427//8427 -f 8426//8426 8427//8427 8428//8428 -f 8428//8428 8427//8427 8429//8429 -f 8428//8428 8429//8429 8430//8430 -f 8429//8429 8431//8431 8430//8430 -f 8430//8430 8431//8431 8432//8432 -f 8430//8430 8432//8432 8433//8433 -f 8433//8433 8432//8432 8434//8434 -f 8433//8433 8434//8434 8435//8435 -f 8435//8435 8434//8434 8436//8436 -f 8435//8435 8436//8436 7794//7794 -f 7794//7794 8436//8436 8437//8437 -f 7794//7794 8437//8437 7792//7792 -f 8438//8438 8439//8439 8440//8440 -f 7818//7818 7817//7817 8441//8441 -f 8441//8441 7817//7817 8442//8442 -f 8441//8441 8442//8442 8443//8443 -f 8443//8443 8442//8442 8444//8444 -f 8443//8443 8444//8444 8445//8445 -f 8445//8445 8444//8444 8446//8446 -f 8445//8445 8446//8446 8447//8447 -f 8446//8446 8448//8448 8447//8447 -f 8447//8447 8448//8448 8449//8449 -f 8447//8447 8449//8449 8450//8450 -f 8450//8450 8449//8449 8451//8451 -f 8450//8450 8451//8451 8452//8452 -f 8452//8452 8451//8451 8453//8453 -f 8452//8452 8453//8453 8439//8439 -f 8439//8439 8453//8453 8454//8454 -f 8439//8439 8454//8454 8440//8440 -f 8438//8438 8440//8440 8455//8455 -f 8455//8455 8440//8440 8456//8456 -f 8455//8455 8456//8456 8457//8457 -f 8457//8457 8456//8456 8458//8458 -f 8457//8457 8458//8458 8459//8459 -f 8459//8459 8458//8458 8460//8460 -f 8459//8459 8460//8460 8461//8461 -f 8460//8460 8462//8462 8461//8461 -f 8461//8461 8462//8462 8463//8463 -f 8461//8461 8463//8463 8464//8464 -f 8464//8464 8463//8463 8465//8465 -f 7836//7836 7835//7835 8466//8466 -f 8466//8466 7835//7835 8467//8467 -f 8466//8466 8467//8467 8468//8468 -f 8468//8468 8467//8467 8469//8469 -f 8468//8468 8469//8469 8470//8470 -f 8470//8470 8469//8469 8471//8471 -f 8470//8470 8471//8471 8465//8465 -f 8465//8465 8471//8471 8472//8472 -f 8465//8465 8472//8472 8464//8464 -f 8473//8473 8474//8474 8475//8475 -f 8475//8475 8474//8474 8476//8476 -f 8475//8475 8476//8476 8477//8477 -f 8477//8477 8476//8476 7861//7861 -f 8477//8477 7861//7861 7860//7860 -f 8475//8475 8478//8478 8473//8473 -f 8473//8473 8478//8478 8479//8479 -f 8473//8473 8479//8479 8480//8480 -f 8480//8480 8479//8479 8481//8481 -f 8480//8480 8481//8481 8482//8482 -f 8482//8482 8481//8481 8483//8483 -f 8482//8482 8483//8483 8484//8484 -f 8484//8484 8483//8483 8485//8485 -f 8484//8484 8485//8485 8486//8486 -f 8486//8486 8485//8485 8487//8487 -f 8487//8487 8485//8485 8488//8488 -f 8487//8487 8488//8488 8489//8489 -f 8489//8489 8488//8488 8490//8490 -f 8489//8489 8490//8490 8491//8491 -f 8491//8491 8490//8490 8492//8492 -f 8491//8491 8492//8492 8493//8493 -f 8492//8492 8494//8494 8493//8493 -f 8493//8493 8494//8494 8495//8495 -f 8493//8493 8495//8495 8496//8496 -f 8496//8496 8495//8495 8497//8497 -f 7871//7871 7870//7870 8498//8498 -f 7871//7871 8498//8498 8499//8499 -f 8499//8499 8498//8498 8500//8500 -f 8499//8499 8500//8500 8501//8501 -f 8501//8501 8500//8500 8502//8502 -f 8501//8501 8502//8502 8503//8503 -f 8503//8503 8502//8502 8504//8504 -f 8503//8503 8504//8504 8505//8505 -f 8505//8505 8504//8504 8506//8506 -f 8505//8505 8506//8506 8507//8507 -f 8507//8507 8506//8506 8508//8508 -f 8507//8507 8508//8508 8497//8497 -f 8497//8497 8508//8508 8509//8509 -f 8497//8497 8509//8509 8496//8496 -f 7903//7903 7902//7902 8510//8510 -f 8510//8510 7902//7902 8511//8511 -f 8510//8510 8511//8511 8512//8512 -f 8513//8513 8514//8514 8515//8515 -f 8515//8515 8514//8514 8516//8516 -f 8511//8511 8517//8517 8512//8512 -f 8512//8512 8517//8517 8515//8515 -f 8512//8512 8515//8515 8518//8518 -f 8518//8518 8515//8515 8516//8516 -f 8519//8519 8520//8520 8521//8521 -f 8521//8521 8520//8520 8522//8522 -f 8521//8521 8522//8522 8523//8523 -f 8523//8523 8522//8522 8524//8524 -f 8523//8523 8524//8524 8513//8513 -f 8513//8513 8524//8524 8525//8525 -f 8513//8513 8525//8525 8514//8514 -f 8526//8526 8527//8527 8519//8519 -f 8519//8519 8527//8527 8528//8528 -f 8519//8519 8528//8528 8520//8520 -f 8529//8529 8530//8530 8531//8531 -f 8529//8529 8531//8531 8532//8532 -f 8532//8532 8531//8531 8533//8533 -f 8532//8532 8533//8533 8534//8534 -f 8533//8533 8535//8535 8534//8534 -f 8534//8534 8535//8535 8536//8536 -f 8534//8534 8536//8536 8537//8537 -f 8537//8537 8536//8536 8538//8538 -f 8537//8537 8538//8538 8526//8526 -f 8526//8526 8538//8538 8539//8539 -f 8526//8526 8539//8539 8527//8527 -f 7911//7911 7910//7910 8540//8540 -f 8540//8540 7910//7910 8541//8541 -f 8540//8540 8541//8541 8542//8542 -f 8542//8542 8541//8541 8543//8543 -f 8542//8542 8543//8543 8544//8544 -f 8544//8544 8543//8543 8545//8545 -f 8544//8544 8545//8545 8546//8546 -f 8546//8546 8545//8545 8547//8547 -f 8546//8546 8547//8547 8548//8548 -f 8548//8548 8547//8547 8549//8549 -f 8548//8548 8549//8549 8530//8530 -f 8530//8530 8549//8549 8550//8550 -f 8530//8530 8550//8550 8531//8531 -f 7939//7939 7941//7941 8551//8551 -f 8551//8551 7941//7941 8552//8552 -f 8551//8551 8552//8552 8553//8553 -f 8553//8553 8552//8552 8554//8554 -f 8554//8554 8552//8552 8555//8555 -f 8554//8554 8555//8555 8556//8556 -f 8556//8556 8555//8555 8557//8557 -f 8556//8556 8557//8557 8558//8558 -f 8558//8558 8557//8557 8559//8559 -f 8558//8558 8559//8559 8560//8560 -f 8560//8560 8559//8559 8561//8561 -f 8560//8560 8561//8561 8562//8562 -f 8563//8563 8564//8564 8565//8565 -f 8565//8565 8564//8564 8562//8562 -f 8565//8565 8562//8562 8566//8566 -f 8566//8566 8562//8562 8561//8561 -f 8567//8567 8568//8568 8563//8563 -f 8563//8563 8568//8568 8569//8569 -f 8563//8563 8569//8569 8564//8564 -f 8570//8570 8571//8571 8572//8572 -f 8570//8570 8572//8572 8573//8573 -f 8572//8572 8574//8574 8573//8573 -f 8573//8573 8574//8574 8575//8575 -f 8573//8573 8575//8575 8576//8576 -f 8576//8576 8575//8575 8577//8577 -f 8576//8576 8577//8577 8578//8578 -f 8578//8578 8577//8577 8579//8579 -f 8578//8578 8579//8579 8580//8580 -f 8580//8580 8579//8579 8581//8581 -f 8580//8580 8581//8581 8582//8582 -f 8582//8582 8581//8581 8583//8583 -f 8582//8582 8583//8583 8567//8567 -f 8567//8567 8583//8583 8584//8584 -f 8567//8567 8584//8584 8568//8568 -f 8571//8571 8570//8570 8585//8585 -f 8585//8585 8570//8570 8586//8586 -f 8585//8585 8586//8586 7947//7947 -f 7947//7947 8586//8586 8587//8587 -f 7947//7947 8587//8587 7945//7945 -f 7977//7977 7976//7976 8588//8588 -f 8588//8588 7976//7976 8589//8589 -f 8588//8588 8589//8589 8590//8590 -f 8590//8590 8589//8589 8591//8591 -f 8590//8590 8591//8591 8592//8592 -f 8592//8592 8591//8591 8593//8593 -f 8592//8592 8593//8593 8594//8594 -f 8593//8593 8595//8595 8594//8594 -f 8594//8594 8595//8595 8596//8596 -f 8594//8594 8596//8596 8597//8597 -f 8597//8597 8596//8596 8598//8598 -f 8597//8597 8598//8598 8599//8599 -f 8599//8599 8598//8598 8600//8600 -f 8600//8600 8598//8598 8601//8601 -f 8600//8600 8601//8601 8602//8602 -f 8602//8602 8601//8601 8603//8603 -f 8602//8602 8603//8603 8604//8604 -f 8605//8605 8606//8606 8607//8607 -f 8607//8607 8606//8606 8608//8608 -f 8607//8607 8608//8608 8604//8604 -f 8604//8604 8608//8608 8609//8609 -f 8604//8604 8609//8609 8602//8602 -f 8607//8607 8610//8610 8605//8605 -f 8605//8605 8610//8610 8611//8611 -f 8605//8605 8611//8611 8612//8612 -f 8612//8612 8611//8611 8613//8613 -f 8612//8612 8613//8613 8614//8614 -f 8614//8614 8613//8613 8615//8615 -f 8614//8614 8615//8615 8616//8616 -f 8616//8616 8615//8615 8617//8617 -f 8616//8616 8617//8617 8618//8618 -f 8618//8618 8617//8617 8619//8619 -f 8618//8618 8619//8619 8620//8620 -f 7982//7982 7981//7981 8621//8621 -f 8621//8621 7981//7981 8620//8620 -f 8621//8621 8620//8620 8622//8622 -f 8622//8622 8620//8620 8619//8619 -f 8014//8014 8013//8013 8623//8623 -f 8014//8014 8623//8623 8624//8624 -f 8624//8624 8623//8623 8625//8625 -f 8624//8624 8625//8625 8626//8626 -f 8626//8626 8625//8625 8627//8627 -f 8626//8626 8627//8627 8628//8628 -f 8627//8627 8629//8629 8628//8628 -f 8628//8628 8629//8629 8630//8630 -f 8628//8628 8630//8630 8631//8631 -f 8631//8631 8630//8630 8632//8632 -f 8631//8631 8632//8632 8633//8633 -f 8633//8633 8632//8632 8634//8634 -f 8633//8633 8634//8634 8635//8635 -f 8635//8635 8634//8634 8636//8636 -f 8634//8634 8637//8637 8636//8636 -f 8636//8636 8637//8637 8638//8638 -f 8636//8636 8638//8638 8639//8639 -f 8639//8639 8638//8638 8640//8640 -f 8639//8639 8640//8640 8641//8641 -f 8641//8641 8640//8640 8642//8642 -f 8640//8640 8643//8643 8642//8642 -f 8642//8642 8643//8643 8644//8644 -f 8642//8642 8644//8644 8645//8645 -f 8645//8645 8644//8644 8646//8646 -f 8645//8645 8646//8646 8647//8647 -f 8646//8646 8648//8648 8647//8647 -f 8647//8647 8648//8648 8649//8649 -f 8647//8647 8649//8649 8650//8650 -f 8650//8650 8649//8649 8651//8651 -f 8650//8650 8651//8651 8652//8652 -f 8652//8652 8651//8651 8653//8653 -f 8652//8652 8653//8653 8654//8654 -f 8654//8654 8653//8653 8655//8655 -f 8654//8654 8655//8655 8656//8656 -f 8656//8656 8655//8655 8037//8037 -f 8656//8656 8037//8037 8036//8036 -f 8657//8657 8658//8658 8659//8659 -f 8659//8659 8658//8658 8660//8660 -f 8659//8659 8660//8660 8661//8661 -f 8661//8661 8660//8660 8662//8662 -f 8661//8661 8662//8662 8663//8663 -f 8663//8663 8662//8662 8664//8664 -f 8663//8663 8664//8664 8049//8049 -f 8049//8049 8664//8664 8665//8665 -f 8049//8049 8665//8665 8050//8050 -f 8659//8659 8666//8666 8657//8657 -f 8657//8657 8666//8666 8667//8667 -f 8657//8657 8667//8667 8668//8668 -f 8668//8668 8667//8667 8669//8669 -f 8668//8668 8669//8669 8670//8670 -f 8670//8670 8669//8669 8671//8671 -f 8670//8670 8671//8671 8672//8672 -f 8672//8672 8671//8671 8673//8673 -f 7314//7314 7313//7313 8674//8674 -f 8674//8674 7313//7313 8675//8675 -f 8674//8674 8675//8675 8676//8676 -f 8676//8676 8675//8675 8677//8677 -f 8676//8676 8677//8677 8678//8678 -f 8678//8678 8677//8677 8679//8679 -f 8678//8678 8679//8679 8680//8680 -f 8680//8680 8679//8679 8681//8681 -f 8680//8680 8681//8681 8682//8682 -f 8682//8682 8681//8681 8683//8683 -f 8682//8682 8683//8683 8684//8684 -f 8684//8684 8683//8683 8685//8685 -f 8684//8684 8685//8685 8686//8686 -f 8686//8686 8685//8685 8687//8687 -f 8686//8686 8687//8687 8688//8688 -f 8688//8688 8687//8687 8689//8689 -f 8688//8688 8689//8689 8690//8690 -f 8690//8690 8689//8689 8673//8673 -f 8690//8690 8673//8673 8691//8691 -f 8691//8691 8673//8673 8671//8671 -f 7298//7298 8692//8692 7299//7299 -f 7299//7299 8692//8692 8693//8693 -f 7299//7299 8693//8693 7300//7300 -f 8693//8693 8694//8694 7300//7300 -f 7300//7300 8694//8694 8695//8695 -f 7300//7300 8695//8695 7301//7301 -f 7301//7301 8695//8695 8696//8696 -f 7301//7301 8696//8696 7302//7302 -f 7302//7302 8696//8696 8697//8697 -f 7302//7302 8697//8697 7305//7305 -f 7305//7305 8697//8697 8698//8698 -f 7305//7305 8698//8698 7242//7242 -f 7242//7242 8698//8698 8699//8699 -f 7242//7242 8699//8699 7243//7243 -f 7243//7243 8699//8699 8700//8700 -f 7243//7243 8700//8700 7309//7309 -f 7309//7309 8700//8700 8701//8701 -f 7309//7309 8701//8701 8702//8702 -f 8702//8702 8701//8701 7203//7203 -f 8702//8702 7203//7203 8703//8703 -f 8703//8703 7203//7203 7205//7205 -f 8703//8703 7205//7205 8704//8704 -f 8704//8704 7205//7205 7207//7207 -f 8704//8704 7207//7207 8705//8705 -f 8705//8705 7207//7207 7211//7211 -f 8705//8705 7211//7211 8706//8706 -f 8706//8706 7211//7211 7210//7210 -f 8706//8706 7210//7210 8707//8707 -f 8707//8707 7210//7210 7218//7218 -f 8707//8707 7218//7218 8708//8708 -f 8708//8708 7218//7218 7217//7217 -f 7213//7213 8709//8709 7215//7215 -f 7215//7215 8709//8709 8710//8710 -f 7215//7215 8710//8710 7217//7217 -f 7217//7217 8710//8710 8711//8711 -f 7217//7217 8711//8711 8708//8708 -f 7344//7344 7343//7343 8712//8712 -f 8712//8712 7343//7343 8713//8713 -f 8712//8712 8713//8713 8714//8714 -f 8713//8713 8715//8715 8714//8714 -f 8714//8714 8715//8715 8716//8716 -f 8714//8714 8716//8716 8717//8717 -f 8717//8717 8716//8716 8718//8718 -f 8716//8716 8719//8719 8718//8718 -f 8718//8718 8719//8719 8720//8720 -f 8718//8718 8720//8720 8721//8721 -f 8721//8721 8720//8720 8722//8722 -f 8721//8721 8722//8722 8723//8723 -f 7170//7170 7193//7193 7353//7353 -f 7353//7353 7193//7193 7356//7356 -f 586//586 7192//7192 7353//7353 -f 7353//7353 7192//7192 7171//7171 -f 7353//7353 7171//7171 7170//7170 -f 7173//7173 7179//7179 7406//7406 -f 7406//7406 7179//7179 7411//7411 -f 8724//8724 8725//8725 7401//7401 -f 7186//7186 7187//7187 7409//7409 -f 7409//7409 7187//7187 7189//7189 -f 7409//7409 7189//7189 586//586 -f 586//586 7189//7189 7191//7191 -f 586//586 7191//7191 7192//7192 -f 7179//7179 7181//7181 7411//7411 -f 7411//7411 7181//7181 7183//7183 -f 7411//7411 7183//7183 7409//7409 -f 7409//7409 7183//7183 7184//7184 -f 7409//7409 7184//7184 7186//7186 -f 8726//8726 7385//7385 8727//8727 -f 8727//8727 7385//7385 7387//7387 -f 8727//8727 7387//7387 7202//7202 -f 7202//7202 7387//7387 7200//7200 -f 8725//8725 7178//7178 7401//7401 -f 7401//7401 7178//7178 7177//7177 -f 7401//7401 7177//7177 7406//7406 -f 7406//7406 7177//7177 7174//7174 -f 7406//7406 7174//7174 7173//7173 -f 8726//8726 8728//8728 7385//7385 -f 7385//7385 8728//8728 8729//8729 -f 7385//7385 8729//8729 7391//7391 -f 7193//7193 7195//7195 7356//7356 -f 7356//7356 7195//7195 7197//7197 -f 7356//7356 7197//7197 7387//7387 -f 7387//7387 7197//7197 7198//7198 -f 7387//7387 7198//7198 7200//7200 -f 8724//8724 7401//7401 8730//8730 -f 8730//8730 7401//7401 7403//7403 -f 8730//8730 7403//7403 8731//8731 -f 8731//8731 7403//7403 8732//8732 -f 8732//8732 7403//7403 7399//7399 -f 8732//8732 7399//7399 8733//8733 -f 8729//8729 8734//8734 7391//7391 -f 7391//7391 8734//8734 8735//8735 -f 7391//7391 8735//8735 7394//7394 -f 7394//7394 8735//8735 8736//8736 -f 7394//7394 8736//8736 8737//8737 -f 598//598 8738//8738 7399//7399 -f 7399//7399 8738//8738 8739//8739 -f 7399//7399 8739//8739 8733//8733 -f 8737//8737 8740//8740 7394//7394 -f 7394//7394 8740//8740 8741//8741 -f 7394//7394 8741//8741 598//598 -f 598//598 8741//8741 8742//8742 -f 598//598 8742//8742 8738//8738 -f 7354//7354 8743//8743 7355//7355 -f 8743//8743 7354//7354 7389//7389 -f 7386//7386 7384//7384 8744//8744 -f 7395//7395 8745//8745 8746//8746 -f 7348//7348 8747//8747 7349//7349 -f 7349//7349 8747//8747 8748//8748 -f 7349//7349 8748//8748 7358//7358 -f 7358//7358 8748//8748 7359//7359 -f 7359//7359 8748//8748 8749//8749 -f 7359//7359 8749//8749 7361//7361 -f 7361//7361 8749//8749 7362//7362 -f 7362//7362 8749//8749 8750//8750 -f 7362//7362 8750//8750 7363//7363 -f 7363//7363 8750//8750 7364//7364 -f 7364//7364 8750//8750 8751//8751 -f 7364//7364 8751//8751 7352//7352 -f 7352//7352 8751//8751 8752//8752 -f 7352//7352 8752//8752 7351//7351 -f 7351//7351 8752//8752 8753//8753 -f 7351//7351 8753//8753 7414//7414 -f 7414//7414 8753//8753 8754//8754 -f 7414//7414 8754//8754 7415//7415 -f 7415//7415 8754//8754 8755//8755 -f 7415//7415 8755//8755 7416//7416 -f 7416//7416 8755//8755 8756//8756 -f 7416//7416 8756//8756 7410//7410 -f 7410//7410 8756//8756 8757//8757 -f 7410//7410 8757//8757 7412//7412 -f 7412//7412 8757//8757 8758//8758 -f 7412//7412 8758//8758 7413//7413 -f 8758//8758 8759//8759 7413//7413 -f 7413//7413 8759//8759 8760//8760 -f 7413//7413 8760//8760 7407//7407 -f 8760//8760 8761//8761 7407//7407 -f 7407//7407 8761//8761 8762//8762 -f 7407//7407 8762//8762 7408//7408 -f 7408//7408 8762//8762 8763//8763 -f 7408//7408 8763//8763 7402//7402 -f 8763//8763 8764//8764 7402//7402 -f 7402//7402 8764//8764 8765//8765 -f 7402//7402 8765//8765 7404//7404 -f 7404//7404 8765//8765 7405//7405 -f 7405//7405 8765//8765 8766//8766 -f 7405//7405 8766//8766 7400//7400 -f 7400//7400 8766//8766 8767//8767 -f 7400//7400 8767//8767 7398//7398 -f 8767//8767 8768//8768 7398//7398 -f 7398//7398 8768//8768 8769//8769 -f 7398//7398 8769//8769 7397//7397 -f 8769//8769 8770//8770 7397//7397 -f 7397//7397 8770//8770 8771//8771 -f 7397//7397 8771//8771 7396//7396 -f 7396//7396 8771//8771 8772//8772 -f 7396//7396 8772//8772 7395//7395 -f 7395//7395 8772//8772 8773//8773 -f 7395//7395 8773//8773 8745//8745 -f 8744//8744 7384//7384 8774//8774 -f 7384//7384 7383//7383 8774//8774 -f 8774//8774 7383//7383 7390//7390 -f 8774//8774 7390//7390 8775//8775 -f 8775//8775 7390//7390 7392//7392 -f 8775//8775 7392//7392 8746//8746 -f 8746//8746 7392//7392 7393//7393 -f 8746//8746 7393//7393 7395//7395 -f 7386//7386 8744//8744 7388//7388 -f 7388//7388 8744//8744 8776//8776 -f 7388//7388 8776//8776 7389//7389 -f 7389//7389 8776//8776 8777//8777 -f 7389//7389 8777//8777 8743//8743 -f 8697//8697 8696//8696 8778//8778 -f 8778//8778 8696//8696 8779//8779 -f 8733//8733 8739//8739 8780//8780 -f 8728//8728 8726//8726 8781//8781 -f 8781//8781 8726//8726 7201//7201 -f 7201//7201 8726//8726 8727//8727 -f 7201//7201 8727//8727 7202//7202 -f 8728//8728 8781//8781 8729//8729 -f 8729//8729 8781//8781 8782//8782 -f 8729//8729 8782//8782 8734//8734 -f 8734//8734 8782//8782 8783//8783 -f 8734//8734 8783//8783 8735//8735 -f 8735//8735 8783//8783 8736//8736 -f 8736//8736 8783//8783 8784//8784 -f 8736//8736 8784//8784 8737//8737 -f 8737//8737 8784//8784 8740//8740 -f 8740//8740 8784//8784 8785//8785 -f 8740//8740 8785//8785 8741//8741 -f 8741//8741 8785//8785 8786//8786 -f 8741//8741 8786//8786 8742//8742 -f 8780//8780 8739//8739 8786//8786 -f 8786//8786 8739//8739 8738//8738 -f 8786//8786 8738//8738 8742//8742 -f 8733//8733 8780//8780 8732//8732 -f 8732//8732 8780//8780 8787//8787 -f 8732//8732 8787//8787 8731//8731 -f 8731//8731 8787//8787 8788//8788 -f 8731//8731 8788//8788 8730//8730 -f 8730//8730 8788//8788 8724//8724 -f 8724//8724 8788//8788 8789//8789 -f 8724//8724 8789//8789 8725//8725 -f 8725//8725 8789//8789 7176//7176 -f 8725//8725 7176//7176 7178//7178 -f 7229//7229 7228//7228 8790//8790 -f 8790//8790 7228//7228 8791//8791 -f 8790//8790 8791//8791 8792//8792 -f 8792//8792 8791//8791 8793//8793 -f 8794//8794 8795//8795 8793//8793 -f 8793//8793 8795//8795 8796//8796 -f 8793//8793 8796//8796 8792//8792 -f 8797//8797 8692//8692 8798//8798 -f 8798//8798 8692//8692 8799//8799 -f 8798//8798 8799//8799 8800//8800 -f 8800//8800 8799//8799 8801//8801 -f 8800//8800 8801//8801 8794//8794 -f 8794//8794 8801//8801 8802//8802 -f 8794//8794 8802//8802 8795//8795 -f 8696//8696 8695//8695 8779//8779 -f 8779//8779 8695//8695 8694//8694 -f 8779//8779 8694//8694 8797//8797 -f 8797//8797 8694//8694 8693//8693 -f 8797//8797 8693//8693 8692//8692 -f 8697//8697 8778//8778 8698//8698 -f 8698//8698 8778//8778 8803//8803 -f 8698//8698 8803//8803 8699//8699 -f 8699//8699 8803//8803 8804//8804 -f 8699//8699 8804//8804 8700//8700 -f 8700//8700 8804//8804 8701//8701 -f 8701//8701 8804//8804 7204//7204 -f 8701//8701 7204//7204 7203//7203 -f 7241//7241 7204//7204 8805//8805 -f 8805//8805 7204//7204 8804//8804 -f 8805//8805 8804//8804 8806//8806 -f 8806//8806 8804//8804 8803//8803 -f 8806//8806 8803//8803 8807//8807 -f 8807//8807 8803//8803 8778//8778 -f 8807//8807 8778//8778 8808//8808 -f 8808//8808 8778//8778 8779//8779 -f 8808//8808 8779//8779 8809//8809 -f 8809//8809 8779//8779 8797//8797 -f 8809//8809 8797//8797 8810//8810 -f 8810//8810 8797//8797 8798//8798 -f 8810//8810 8798//8798 8811//8811 -f 8811//8811 8798//8798 8800//8800 -f 8811//8811 8800//8800 8812//8812 -f 8812//8812 8800//8800 8794//8794 -f 8812//8812 8794//8794 8813//8813 -f 8813//8813 8794//8794 8793//8793 -f 8813//8813 8793//8793 8814//8814 -f 8814//8814 8793//8793 8791//8791 -f 8814//8814 8791//8791 7230//7230 -f 7230//7230 8791//8791 7228//7228 -f 7201//7201 7241//7241 8781//8781 -f 8781//8781 7241//7241 8805//8805 -f 8781//8781 8805//8805 8782//8782 -f 8782//8782 8805//8805 8806//8806 -f 8782//8782 8806//8806 8783//8783 -f 8783//8783 8806//8806 8807//8807 -f 8783//8783 8807//8807 8784//8784 -f 8784//8784 8807//8807 8808//8808 -f 8784//8784 8808//8808 8785//8785 -f 8785//8785 8808//8808 8809//8809 -f 8785//8785 8809//8809 8786//8786 -f 8786//8786 8809//8809 8810//8810 -f 8786//8786 8810//8810 8780//8780 -f 8780//8780 8810//8810 8811//8811 -f 8780//8780 8811//8811 8787//8787 -f 8787//8787 8811//8811 8812//8812 -f 8787//8787 8812//8812 8788//8788 -f 8788//8788 8812//8812 8813//8813 -f 8788//8788 8813//8813 8789//8789 -f 8789//8789 8813//8813 8814//8814 -f 8789//8789 8814//8814 7176//7176 -f 7176//7176 8814//8814 7230//7230 -f 8760//8760 8759//8759 8055//8055 -f 7417//7417 7419//7419 8747//8747 -f 8747//8747 7419//7419 8748//8748 -f 7419//7419 7421//7421 8748//8748 -f 8748//8748 7421//7421 7422//7422 -f 8748//8748 7422//7422 8749//8749 -f 7422//7422 7424//7424 8749//8749 -f 8749//8749 7424//7424 7426//7426 -f 8749//8749 7426//7426 8750//8750 -f 8750//8750 7426//7426 7428//7428 -f 8750//8750 7428//7428 8751//8751 -f 8751//8751 7428//7428 7433//7433 -f 8751//8751 7433//7433 8752//8752 -f 8752//8752 7433//7433 7432//7432 -f 8752//8752 7432//7432 8753//8753 -f 8753//8753 7432//7432 7430//7430 -f 8753//8753 7430//7430 8754//8754 -f 7430//7430 8084//8084 8754//8754 -f 8754//8754 8084//8084 8083//8083 -f 8754//8754 8083//8083 8755//8755 -f 8055//8055 8759//8759 8074//8074 -f 8083//8083 8079//8079 8755//8755 -f 8755//8755 8079//8079 8077//8077 -f 8755//8755 8077//8077 8756//8756 -f 8756//8756 8077//8077 8076//8076 -f 8756//8756 8076//8076 8757//8757 -f 8757//8757 8076//8076 8074//8074 -f 8757//8757 8074//8074 8758//8758 -f 8758//8758 8074//8074 8759//8759 -f 8760//8760 8055//8055 8761//8761 -f 8761//8761 8055//8055 8058//8058 -f 8761//8761 8058//8058 8762//8762 -f 8762//8762 8058//8058 8060//8060 -f 8762//8762 8060//8060 8763//8763 -f 8763//8763 8060//8060 8062//8062 -f 8763//8763 8062//8062 8064//8064 -f 8066//8066 8765//8765 8064//8064 -f 8064//8064 8765//8765 8764//8764 -f 8064//8064 8764//8764 8763//8763 -f 8767//8767 8766//8766 8070//8070 -f 8070//8070 8766//8766 8765//8765 -f 8070//8070 8765//8765 8068//8068 -f 8068//8068 8765//8765 8066//8066 -f 8767//8767 8070//8070 8768//8768 -f 8768//8768 8070//8070 8054//8054 -f 8768//8768 8054//8054 8769//8769 -f 8769//8769 8054//8054 7372//7372 -f 8769//8769 7372//7372 8770//8770 -f 8770//8770 7372//7372 7371//7371 -f 8770//8770 7371//7371 8771//8771 -f 8771//8771 7371//7371 8772//8772 -f 8772//8772 7371//7371 7376//7376 -f 8772//8772 7376//7376 8773//8773 -f 8773//8773 7376//7376 7378//7378 -f 8773//8773 7378//7378 7380//7380 -f 8774//8774 8775//8775 7370//7370 -f 7370//7370 8775//8775 8746//8746 -f 7370//7370 8746//8746 7380//7380 -f 7380//7380 8746//8746 8745//8745 -f 7380//7380 8745//8745 8773//8773 -f 7370//7370 7368//7368 8774//8774 -f 8774//8774 7368//7368 7366//7366 -f 8774//8774 7366//7366 8744//8744 -f 8744//8744 7366//7366 7365//7365 -f 8744//8744 7365//7365 8776//8776 -f 8776//8776 7365//7365 7350//7350 -f 8776//8776 7350//7350 8777//8777 -f 8777//8777 7350//7350 7357//7357 -f 8777//8777 7357//7357 8743//8743 -f 8743//8743 7357//7357 7360//7360 -f 8743//8743 7360//7360 7355//7355 -f 8709//8709 7213//7213 8815//8815 -f 8815//8815 7213//7213 7221//7221 -f 8815//8815 7221//7221 8816//8816 -f 7221//7221 7220//7220 8816//8816 -f 8816//8816 7220//7220 7219//7219 -f 8816//8816 7219//7219 8817//8817 -f 8817//8817 7219//7219 7167//7167 -f 8817//8817 7167//7167 8818//8818 -f 8818//8818 7167//7167 7166//7166 -f 8818//8818 7166//7166 8819//8819 -f 8819//8819 7166//7166 7222//7222 -f 8819//8819 7222//7222 8820//8820 -f 8820//8820 7222//7222 7224//7224 -f 8820//8820 7224//7224 8821//8821 -f 8821//8821 7224//7224 7226//7226 -f 8821//8821 7226//7226 7276//7276 -f 7276//7276 7226//7226 7227//7227 -f 7276//7276 7227//7227 7277//7277 -f 7277//7277 7227//7227 7229//7229 -f 7277//7277 7229//7229 7280//7280 -f 7280//7280 7229//7229 8790//8790 -f 7280//7280 8790//8790 7285//7285 -f 7285//7285 8790//8790 8792//8792 -f 7285//7285 8792//8792 7286//7286 -f 7286//7286 8792//8792 8796//8796 -f 7286//7286 8796//8796 7287//7287 -f 7287//7287 8796//8796 8795//8795 -f 7287//7287 8795//8795 7290//7290 -f 7290//7290 8795//8795 8802//8802 -f 7290//7290 8802//8802 7291//7291 -f 7291//7291 8802//8802 8801//8801 -f 8692//8692 7298//7298 8799//8799 -f 8799//8799 7298//7298 7297//7297 -f 8799//8799 7297//7297 8801//8801 -f 8801//8801 7297//7297 7292//7292 -f 8801//8801 7292//7292 7291//7291 -f 8820//8820 8821//8821 8822//8822 -f 8823//8823 8824//8824 8825//8825 -f 8826//8826 8827//8827 8828//8828 -f 8829//8829 7262//7262 7261//7261 -f 8829//8829 7261//7261 8830//8830 -f 8831//8831 8832//8832 8833//8833 -f 8834//8834 8835//8835 8832//8832 -f 8836//8836 8837//8837 8835//8835 -f 8838//8838 8839//8839 8823//8823 -f 8823//8823 8839//8839 8840//8840 -f 8823//8823 8840//8840 8824//8824 -f 8824//8824 8840//8840 8841//8841 -f 8824//8824 8841//8841 8842//8842 -f 8843//8843 8844//8844 8845//8845 -f 8845//8845 8844//8844 8826//8826 -f 8846//8846 8847//8847 8843//8843 -f 7264//7264 7284//7284 8847//8847 -f 8848//8848 8825//8825 8849//8849 -f 8849//8849 8825//8825 8824//8824 -f 8849//8849 8824//8824 8836//8836 -f 8836//8836 8824//8824 8842//8842 -f 8836//8836 8842//8842 8837//8837 -f 8850//8850 8851//8851 8828//8828 -f 8852//8852 8851//8851 8853//8853 -f 8853//8853 8851//8851 8850//8850 -f 8853//8853 8850//8850 8854//8854 -f 7308//7308 7309//7309 8702//8702 -f 8830//8830 7261//7261 8855//8855 -f 8855//8855 7261//7261 7307//7307 -f 8855//8855 7307//7307 8856//8856 -f 8856//8856 7307//7307 7308//7308 -f 8856//8856 7308//7308 8857//8857 -f 8857//8857 7308//7308 8702//8702 -f 8857//8857 8702//8702 8703//8703 -f 8703//8703 8858//8858 8857//8857 -f 8857//8857 8858//8858 8859//8859 -f 8857//8857 8859//8859 8856//8856 -f 8856//8856 8859//8859 8831//8831 -f 8856//8856 8831//8831 8855//8855 -f 8855//8855 8831//8831 8833//8833 -f 8855//8855 8833//8833 8830//8830 -f 8703//8703 8704//8704 8858//8858 -f 8858//8858 8704//8704 8705//8705 -f 8858//8858 8705//8705 8706//8706 -f 8832//8832 8831//8831 8834//8834 -f 8834//8834 8831//8831 8859//8859 -f 8834//8834 8859//8859 8860//8860 -f 8860//8860 8859//8859 8858//8858 -f 8860//8860 8858//8858 8861//8861 -f 8861//8861 8858//8858 8706//8706 -f 8861//8861 8706//8706 8707//8707 -f 8835//8835 8834//8834 8836//8836 -f 8836//8836 8834//8834 8860//8860 -f 8836//8836 8860//8860 8849//8849 -f 8849//8849 8860//8860 8861//8861 -f 8849//8849 8861//8861 8848//8848 -f 8848//8848 8861//8861 8707//8707 -f 8848//8848 8707//8707 8708//8708 -f 8708//8708 8711//8711 8848//8848 -f 8848//8848 8711//8711 8862//8862 -f 8848//8848 8862//8862 8825//8825 -f 8825//8825 8862//8862 8863//8863 -f 8825//8825 8863//8863 8823//8823 -f 8823//8823 8863//8863 8864//8864 -f 8823//8823 8864//8864 8838//8838 -f 8838//8838 8864//8864 8865//8865 -f 8711//8711 8710//8710 8862//8862 -f 8862//8862 8710//8710 8854//8854 -f 8862//8862 8854//8854 8863//8863 -f 8863//8863 8854//8854 8850//8850 -f 8863//8863 8850//8850 8864//8864 -f 8864//8864 8850//8850 8828//8828 -f 8864//8864 8828//8828 8865//8865 -f 8865//8865 8828//8828 8827//8827 -f 8710//8710 8709//8709 8854//8854 -f 8854//8854 8709//8709 8815//8815 -f 8854//8854 8815//8815 8853//8853 -f 8853//8853 8815//8815 8816//8816 -f 8853//8853 8816//8816 8852//8852 -f 8852//8852 8816//8816 8817//8817 -f 8852//8852 8817//8817 8818//8818 -f 8826//8826 8828//8828 8845//8845 -f 8845//8845 8828//8828 8851//8851 -f 8845//8845 8851//8851 8866//8866 -f 8866//8866 8851//8851 8852//8852 -f 8866//8866 8852//8852 8867//8867 -f 8867//8867 8852//8852 8818//8818 -f 8867//8867 8818//8818 8819//8819 -f 8843//8843 8845//8845 8846//8846 -f 8846//8846 8845//8845 8866//8866 -f 8846//8846 8866//8866 8868//8868 -f 8868//8868 8866//8866 8867//8867 -f 8868//8868 8867//8867 8822//8822 -f 8822//8822 8867//8867 8819//8819 -f 8822//8822 8819//8819 8820//8820 -f 8847//8847 8846//8846 7264//7264 -f 7264//7264 8846//8846 8868//8868 -f 7264//7264 8868//8868 7265//7265 -f 7265//7265 8868//8868 8822//8822 -f 7265//7265 8822//8822 7275//7275 -f 7275//7275 8822//8822 8821//8821 -f 7275//7275 8821//8821 7276//7276 -f 8869//8869 8870//8870 8185//8185 -f 8185//8185 8870//8870 8187//8187 -f 8187//8187 8870//8870 8871//8871 -f 8187//8187 8871//8871 8189//8189 -f 8189//8189 8871//8871 8872//8872 -f 8189//8189 8872//8872 8190//8190 -f 8190//8190 8872//8872 8182//8182 -f 8182//8182 8872//8872 8873//8873 -f 8182//8182 8873//8873 8179//8179 -f 8179//8179 8873//8873 8874//8874 -f 8179//8179 8874//8874 8177//8177 -f 8177//8177 8874//8874 8875//8875 -f 8177//8177 8875//8875 8175//8175 -f 8175//8175 8875//8875 8173//8173 -f 8173//8173 8875//8875 8876//8876 -f 8173//8173 8876//8876 8156//8156 -f 8156//8156 8876//8876 8157//8157 -f 8157//8157 8876//8876 8877//8877 -f 8157//8157 8877//8877 8170//8170 -f 8170//8170 8877//8877 8878//8878 -f 8170//8170 8878//8878 8879//8879 -f 8880//8880 8165//8165 8879//8879 -f 8879//8879 8165//8165 8168//8168 -f 8879//8879 8168//8168 8170//8170 -f 8881//8881 7524//7524 8882//8882 -f 8882//8882 7524//7524 7522//7522 -f 8882//8882 7522//7522 8883//8883 -f 8883//8883 7522//7522 8159//8159 -f 8883//8883 8159//8159 8884//8884 -f 8884//8884 8159//8159 8161//8161 -f 8884//8884 8161//8161 8880//8880 -f 8880//8880 8161//8161 8163//8163 -f 8880//8880 8163//8163 8165//8165 -f 8885//8885 7512//7512 8886//8886 -f 8886//8886 7512//7512 7530//7530 -f 8886//8886 7530//7530 8887//8887 -f 8887//8887 7530//7530 7529//7529 -f 8887//8887 7529//7529 8888//8888 -f 8888//8888 7529//7529 7527//7527 -f 8888//8888 7527//7527 8881//8881 -f 8881//8881 7527//7527 7526//7526 -f 8881//8881 7526//7526 7524//7524 -f 8889//8889 7519//7519 8890//8890 -f 8890//8890 7519//7519 7517//7517 -f 8890//8890 7517//7517 8891//8891 -f 8891//8891 7517//7517 7515//7515 -f 8891//8891 7515//7515 8885//8885 -f 8885//8885 7515//7515 7513//7513 -f 8885//8885 7513//7513 7512//7512 -f 8892//8892 7509//7509 8893//8893 -f 8893//8893 7509//7509 7508//7508 -f 8893//8893 7508//7508 8889//8889 -f 8889//8889 7508//7508 7520//7520 -f 8889//8889 7520//7520 7519//7519 -f 7502//7502 7500//7500 8894//8894 -f 8894//8894 7500//7500 7511//7511 -f 8894//8894 7511//7511 8892//8892 -f 8892//8892 7511//7511 7510//7510 -f 8892//8892 7510//7510 7509//7509 -f 8894//8894 8895//8895 7502//7502 -f 7502//7502 8895//8895 8896//8896 -f 7502//7502 8896//8896 7504//7504 -f 7504//7504 8896//8896 8897//8897 -f 7504//7504 8897//8897 7505//7505 -f 7505//7505 8897//8897 8898//8898 -f 7505//7505 8898//8898 7495//7495 -f 7495//7495 8898//8898 8899//8899 -f 8153//8153 8899//8899 8900//8900 -f 8153//8153 7498//7498 8899//8899 -f 8899//8899 7498//7498 7497//7497 -f 8899//8899 7497//7497 7495//7495 -f 8900//8900 8901//8901 8153//8153 -f 8153//8153 8901//8901 8902//8902 -f 8153//8153 8902//8902 8151//8151 -f 8151//8151 8902//8902 8148//8148 -f 8148//8148 8902//8902 8903//8903 -f 8148//8148 8903//8903 8146//8146 -f 8146//8146 8903//8903 8904//8904 -f 8146//8146 8904//8904 8144//8144 -f 8144//8144 8904//8904 8905//8905 -f 8144//8144 8905//8905 8142//8142 -f 8142//8142 8905//8905 8140//8140 -f 8140//8140 8905//8905 8906//8906 -f 8140//8140 8906//8906 8138//8138 -f 8906//8906 8907//8907 8138//8138 -f 8138//8138 8907//8907 8908//8908 -f 8138//8138 8908//8908 8136//8136 -f 8136//8136 8908//8908 8909//8909 -f 8136//8136 8909//8909 8135//8135 -f 8135//8135 8909//8909 8910//8910 -f 8135//8135 8910//8910 8133//8133 -f 8133//8133 8910//8910 8911//8911 -f 8133//8133 8911//8911 8123//8123 -f 8123//8123 8911//8911 8912//8912 -f 8123//8123 8912//8912 8125//8125 -f 8125//8125 8912//8912 8913//8913 -f 8125//8125 8913//8913 8127//8127 -f 8127//8127 8913//8913 8914//8914 -f 8127//8127 8914//8914 8129//8129 -f 8129//8129 8914//8914 8915//8915 -f 8129//8129 8915//8915 8130//8130 -f 8130//8130 8915//8915 8916//8916 -f 8130//8130 8916//8916 7490//7490 -f 7490//7490 8916//8916 8917//8917 -f 7490//7490 8917//8917 7488//7488 -f 7488//7488 8917//8917 8918//8918 -f 7488//7488 8918//8918 7486//7486 -f 7486//7486 8918//8918 8919//8919 -f 7486//7486 8919//8919 7484//7484 -f 7484//7484 8919//8919 8920//8920 -f 7484//7484 8920//8920 7482//7482 -f 7482//7482 8920//8920 8921//8921 -f 7482//7482 8921//8921 7480//7480 -f 7480//7480 8921//8921 8922//8922 -f 7480//7480 8922//8922 7456//7456 -f 7456//7456 8922//8922 8923//8923 -f 7456//7456 8923//8923 7457//7457 -f 7457//7457 8923//8923 8924//8924 -f 7457//7457 8924//8924 7477//7477 -f 7477//7477 8924//8924 8925//8925 -f 7477//7477 8925//8925 7476//7476 -f 7476//7476 8925//8925 8926//8926 -f 7476//7476 8926//8926 7474//7474 -f 7474//7474 8926//8926 8927//8927 -f 7474//7474 8927//8927 7471//7471 -f 7471//7471 8927//8927 8928//8928 -f 8929//8929 7467//7467 8928//8928 -f 8928//8928 7467//7467 7469//7469 -f 8928//8928 7469//7469 7471//7471 -f 8930//8930 7463//7463 8929//8929 -f 8929//8929 7463//7463 7465//7465 -f 8929//8929 7465//7465 7467//7467 -f 8931//8931 7459//7459 8930//8930 -f 8930//8930 7459//7459 7461//7461 -f 8930//8930 7461//7461 7463//7463 -f 8932//8932 8119//8119 8931//8931 -f 8931//8931 8119//8119 8121//8121 -f 8931//8931 8121//8121 7459//7459 -f 8933//8933 8109//8109 8934//8934 -f 8934//8934 8109//8109 8111//8111 -f 8934//8934 8111//8111 8935//8935 -f 8935//8935 8111//8111 8114//8114 -f 8935//8935 8114//8114 8932//8932 -f 8932//8932 8114//8114 8116//8116 -f 8932//8932 8116//8116 8119//8119 -f 8936//8936 8104//8104 8937//8937 -f 8937//8937 8104//8104 8105//8105 -f 8937//8937 8105//8105 8933//8933 -f 8933//8933 8105//8105 8107//8107 -f 8933//8933 8107//8107 8109//8109 -f 8099//8099 8094//8094 8938//8938 -f 8938//8938 8094//8094 8096//8096 -f 8938//8938 8096//8096 8939//8939 -f 8939//8939 8096//8096 8098//8098 -f 8939//8939 8098//8098 8936//8936 -f 8936//8936 8098//8098 8102//8102 -f 8936//8936 8102//8102 8104//8104 -f 8099//8099 8938//8938 8940//8940 -f 8099//8099 8940//8940 8093//8093 -f 8093//8093 8940//8940 8941//8941 -f 8942//8942 7450//7450 8943//8943 -f 8943//8943 7450//7450 8086//8086 -f 8943//8943 8086//8086 8944//8944 -f 8944//8944 8086//8086 8088//8088 -f 8944//8944 8088//8088 8945//8945 -f 8945//8945 8088//8088 8090//8090 -f 8945//8945 8090//8090 8941//8941 -f 8941//8941 8090//8090 8092//8092 -f 8941//8941 8092//8092 8093//8093 -f 7437//7437 7444//7444 8946//8946 -f 8946//8946 7444//7444 7446//7446 -f 8946//8946 7446//7446 8947//8947 -f 8947//8947 7446//7446 7455//7455 -f 8947//8947 7455//7455 8948//8948 -f 8948//8948 7455//7455 7454//7454 -f 8948//8948 7454//7454 8942//8942 -f 8942//8942 7454//7454 7452//7452 -f 8942//8942 7452//7452 7450//7450 -f 8946//8946 8949//8949 7437//7437 -f 7437//7437 8949//8949 8950//8950 -f 7437//7437 8950//8950 7438//7438 -f 7438//7438 8950//8950 8951//8951 -f 7438//7438 8951//8951 7440//7440 -f 7440//7440 8951//8951 8952//8952 -f 7440//7440 8952//8952 7441//7441 -f 7441//7441 8952//8952 8953//8953 -f 7441//7441 8953//8953 7418//7418 -f 7418//7418 8953//8953 8954//8954 -f 7418//7418 8954//8954 7420//7420 -f 7420//7420 8954//8954 8955//8955 -f 7420//7420 8955//8955 7423//7423 -f 7423//7423 8955//8955 8956//8956 -f 7423//7423 8956//8956 7425//7425 -f 7425//7425 8956//8956 8957//8957 -f 7436//7436 7435//7435 8958//8958 -f 8958//8958 7435//7435 7434//7434 -f 8958//8958 7434//7434 8957//8957 -f 8957//8957 7434//7434 7427//7427 -f 8957//8957 7427//7427 7425//7425 -f 8959//8959 7429//7429 8958//8958 -f 8958//8958 7429//7429 7431//7431 -f 8958//8958 7431//7431 7436//7436 -f 8075//8075 8078//8078 8960//8960 -f 8960//8960 8078//8078 8082//8082 -f 8960//8960 8082//8082 8961//8961 -f 8961//8961 8082//8082 8081//8081 -f 8961//8961 8081//8081 8962//8962 -f 8962//8962 8081//8081 8080//8080 -f 8962//8962 8080//8080 8959//8959 -f 8959//8959 8080//8080 8085//8085 -f 8959//8959 8085//8085 7429//7429 -f 8963//8963 8073//8073 8964//8964 -f 8964//8964 8073//8073 8075//8075 -f 8964//8964 8075//8075 8960//8960 -f 8073//8073 8963//8963 8965//8965 -f 8073//8073 8965//8965 8056//8056 -f 8056//8056 8965//8965 8966//8966 -f 8056//8056 8966//8966 8057//8057 -f 8057//8057 8966//8966 8059//8059 -f 8967//8967 8061//8061 8968//8968 -f 8968//8968 8061//8061 8059//8059 -f 8968//8968 8059//8059 8966//8966 -f 8061//8061 8967//8967 8969//8969 -f 8061//8061 8969//8969 8063//8063 -f 8063//8063 8969//8969 8970//8970 -f 8063//8063 8970//8970 8065//8065 -f 8065//8065 8970//8970 8971//8971 -f 8065//8065 8971//8971 8067//8067 -f 8067//8067 8971//8971 8972//8972 -f 8067//8067 8972//8972 8069//8069 -f 8069//8069 8972//8972 8071//8071 -f 8071//8071 8972//8972 8973//8973 -f 8071//8071 8973//8973 8072//8072 -f 8072//8072 8973//8973 8974//8974 -f 8072//8072 8974//8974 8053//8053 -f 8053//8053 8974//8974 8975//8975 -f 8053//8053 8975//8975 7373//7373 -f 7373//7373 8975//8975 8976//8976 -f 7373//7373 8976//8976 7374//7374 -f 7374//7374 8976//8976 8977//8977 -f 8978//8978 7382//7382 8979//8979 -f 8979//8979 7382//7382 7381//7381 -f 8979//8979 7381//7381 8980//8980 -f 8980//8980 7381//7381 7379//7379 -f 8980//8980 7379//7379 8981//8981 -f 8981//8981 7379//7379 7377//7377 -f 8981//8981 7377//7377 8977//8977 -f 8977//8977 7377//7377 7375//7375 -f 8977//8977 7375//7375 7374//7374 -f 8982//8982 7367//7367 8978//8978 -f 8978//8978 7367//7367 7369//7369 -f 8978//8978 7369//7369 7382//7382 -f 8982//8982 8983//8983 7367//7367 -f 7367//7367 8983//8983 8747//8747 -f 7367//7367 8747//8747 7348//7348 -f 8185//8185 7536//7536 8869//8869 -f 8869//8869 7536//7536 7534//7534 -f 8869//8869 7534//7534 8984//8984 -f 8984//8984 7534//7534 7532//7532 -f 8984//8984 7532//7532 8985//8985 -f 8985//8985 7532//7532 7531//7531 -f 8985//8985 7531//7531 8986//8986 -f 8986//8986 7531//7531 7540//7540 -f 8986//8986 7540//7540 8987//8987 -f 8987//8987 7540//7540 7542//7542 -f 8987//8987 7542//7542 8988//8988 -f 7542//7542 7544//7544 8988//8988 -f 8988//8988 7544//7544 7547//7547 -f 8988//8988 7547//7547 8989//8989 -f 8989//8989 7547//7547 7549//7549 -f 8989//8989 7549//7549 8990//8990 -f 7262//7262 8829//8829 8991//8991 -f 7249//7249 7252//7252 8992//8992 -f 7296//7296 8993//8993 7253//7253 -f 7253//7253 8993//8993 8992//8992 -f 7253//7253 8992//8992 7251//7251 -f 7251//7251 8992//8992 7252//7252 -f 8847//8847 7284//7284 8994//8994 -f 7284//7284 7283//7283 8994//8994 -f 8994//8994 7283//7283 7247//7247 -f 8994//8994 7247//7247 8992//8992 -f 8992//8992 7247//7247 7246//7246 -f 8992//8992 7246//7246 7249//7249 -f 8995//8995 8865//8865 8827//8827 -f 7296//7296 7258//7258 8993//8993 -f 8993//8993 7258//7258 7257//7257 -f 8993//8993 7257//7257 8991//8991 -f 8991//8991 7257//7257 7260//7260 -f 8991//8991 7260//7260 7262//7262 -f 8827//8827 8826//8826 8995//8995 -f 8995//8995 8826//8826 8844//8844 -f 8995//8995 8844//8844 8994//8994 -f 8994//8994 8844//8844 8843//8843 -f 8994//8994 8843//8843 8847//8847 -f 8835//8835 8837//8837 8996//8996 -f 8996//8996 8837//8837 8842//8842 -f 8996//8996 8839//8839 8995//8995 -f 8995//8995 8839//8839 8838//8838 -f 8995//8995 8838//8838 8865//8865 -f 8842//8842 8841//8841 8996//8996 -f 8996//8996 8841//8841 8840//8840 -f 8996//8996 8840//8840 8839//8839 -f 8829//8829 8830//8830 8991//8991 -f 8991//8991 8830//8830 8833//8833 -f 8991//8991 8833//8833 8996//8996 -f 8996//8996 8833//8833 8832//8832 -f 8996//8996 8832//8832 8835//8835 -f 8990//8990 7568//7568 7570//7570 -f 8990//8990 7570//7570 8989//8989 -f 8989//8989 7570//7570 7572//7572 -f 8989//8989 7572//7572 8988//8988 -f 8988//8988 7572//7572 8987//8987 -f 8987//8987 7572//7572 7574//7574 -f 8987//8987 7574//7574 8986//8986 -f 8986//8986 7574//7574 7576//7576 -f 8986//8986 7576//7576 8985//8985 -f 8985//8985 7576//7576 7578//7578 -f 8985//8985 7578//7578 8984//8984 -f 7578//7578 7580//7580 8984//8984 -f 8984//8984 7580//7580 7582//7582 -f 8984//8984 7582//7582 8869//8869 -f 8869//8869 7582//7582 8225//8225 -f 8869//8869 8225//8225 8870//8870 -f 8870//8870 8225//8225 8223//8223 -f 8870//8870 8223//8223 8871//8871 -f 8871//8871 8223//8223 8221//8221 -f 8871//8871 8221//8221 8872//8872 -f 8221//8221 8219//8219 8872//8872 -f 8872//8872 8219//8219 8217//8217 -f 8872//8872 8217//8217 8873//8873 -f 8873//8873 8217//8217 8215//8215 -f 8873//8873 8215//8215 8874//8874 -f 8874//8874 8215//8215 8213//8213 -f 8874//8874 8213//8213 8875//8875 -f 8213//8213 8211//8211 8875//8875 -f 8875//8875 8211//8211 8209//8209 -f 8875//8875 8209//8209 8876//8876 -f 8209//8209 8207//8207 8876//8876 -f 8876//8876 8207//8207 8206//8206 -f 8876//8876 8206//8206 8877//8877 -f 8877//8877 8206//8206 8203//8203 -f 8877//8877 8203//8203 8878//8878 -f 8878//8878 8203//8203 8201//8201 -f 8878//8878 8201//8201 8879//8879 -f 8201//8201 8199//8199 8879//8879 -f 8879//8879 8199//8199 8197//8197 -f 8879//8879 8197//8197 8880//8880 -f 8880//8880 8197//8197 8196//8196 -f 8880//8880 8196//8196 8884//8884 -f 8884//8884 8196//8196 8193//8193 -f 8884//8884 8193//8193 8883//8883 -f 8193//8193 8195//8195 8883//8883 -f 8883//8883 8195//8195 7563//7563 -f 8883//8883 7563//7563 8882//8882 -f 8882//8882 7563//7563 7565//7565 -f 8882//8882 7565//7565 8881//8881 -f 8881//8881 7565//7565 7562//7562 -f 8881//8881 7562//7562 8888//8888 -f 8888//8888 7562//7562 7561//7561 -f 8888//8888 7561//7561 8887//8887 -f 8887//8887 7561//7561 7559//7559 -f 8887//8887 7559//7559 8886//8886 -f 8886//8886 7559//7559 7557//7557 -f 8886//8886 7557//7557 8885//8885 -f 8885//8885 7557//7557 7554//7554 -f 8885//8885 7554//7554 8891//8891 -f 8891//8891 7554//7554 7552//7552 -f 7541//7541 8896//8896 7543//7543 -f 7543//7543 8896//8896 8895//8895 -f 7543//7543 8895//8895 7545//7545 -f 7545//7545 8895//8895 8894//8894 -f 7545//7545 8894//8894 7546//7546 -f 7546//7546 8894//8894 8892//8892 -f 7546//7546 8892//8892 7548//7548 -f 7548//7548 8892//8892 8893//8893 -f 7548//7548 8893//8893 7550//7550 -f 7550//7550 8893//8893 8889//8889 -f 7550//7550 8889//8889 7552//7552 -f 7552//7552 8889//8889 8890//8890 -f 7552//7552 8890//8890 8891//8891 -f 8897//8897 8896//8896 7541//7541 -f 8897//8897 7541//7541 8898//8898 -f 8898//8898 7541//7541 7539//7539 -f 7539//7539 7538//7538 8898//8898 -f 8898//8898 7538//7538 7533//7533 -f 8898//8898 7533//7533 8899//8899 -f 7533//7533 7535//7535 8899//8899 -f 8899//8899 7535//7535 7537//7537 -f 8899//8899 7537//7537 8900//8900 -f 8900//8900 7537//7537 8184//8184 -f 8900//8900 8184//8184 8901//8901 -f 8184//8184 8186//8186 8901//8901 -f 8901//8901 8186//8186 8902//8902 -f 8186//8186 8188//8188 8902//8902 -f 8902//8902 8188//8188 8183//8183 -f 8902//8902 8183//8183 8903//8903 -f 8903//8903 8183//8183 8181//8181 -f 8903//8903 8181//8181 8904//8904 -f 8904//8904 8181//8181 8180//8180 -f 8904//8904 8180//8180 8905//8905 -f 8905//8905 8180//8180 8178//8178 -f 8905//8905 8178//8178 8906//8906 -f 8906//8906 8178//8178 8176//8176 -f 8906//8906 8176//8176 8907//8907 -f 8907//8907 8176//8176 8174//8174 -f 8907//8907 8174//8174 8908//8908 -f 8908//8908 8174//8174 8158//8158 -f 8908//8908 8158//8158 8909//8909 -f 8909//8909 8158//8158 8172//8172 -f 8909//8909 8172//8172 8910//8910 -f 8172//8172 8171//8171 8910//8910 -f 8910//8910 8171//8171 8169//8169 -f 8910//8910 8169//8169 8911//8911 -f 8911//8911 8169//8169 8167//8167 -f 8911//8911 8167//8167 8912//8912 -f 8912//8912 8167//8167 8166//8166 -f 8912//8912 8166//8166 8913//8913 -f 8913//8913 8166//8166 8164//8164 -f 8913//8913 8164//8164 8914//8914 -f 8914//8914 8164//8164 8162//8162 -f 8914//8914 8162//8162 8915//8915 -f 8915//8915 8162//8162 8160//8160 -f 8915//8915 8160//8160 8916//8916 -f 8916//8916 8160//8160 7521//7521 -f 7514//7514 8920//8920 7528//7528 -f 7528//7528 8920//8920 8919//8919 -f 7528//7528 8919//8919 7525//7525 -f 7525//7525 8919//8919 8918//8918 -f 7525//7525 8918//8918 7523//7523 -f 7523//7523 8918//8918 8917//8917 -f 7523//7523 8917//8917 7521//7521 -f 7521//7521 8917//8917 8916//8916 -f 7507//7507 8925//8925 8924//8924 -f 7507//7507 8924//8924 7518//7518 -f 7518//7518 8924//8924 8923//8923 -f 7518//7518 8923//8923 7516//7516 -f 7516//7516 8923//8923 8922//8922 -f 7516//7516 8922//8922 7514//7514 -f 7514//7514 8922//8922 8921//8921 -f 7514//7514 8921//8921 8920//8920 -f 8925//8925 7507//7507 8926//8926 -f 8926//8926 7507//7507 7506//7506 -f 8926//8926 7506//7506 8927//8927 -f 7506//7506 7499//7499 8927//8927 -f 8927//8927 7499//7499 7501//7501 -f 8927//8927 7501//7501 8928//8928 -f 8928//8928 7501//7501 7503//7503 -f 8928//8928 7503//7503 8929//8929 -f 8929//8929 7503//7503 7494//7494 -f 8929//8929 7494//7494 8930//8930 -f 7494//7494 7493//7493 8930//8930 -f 8930//8930 7493//7493 7496//7496 -f 8930//8930 7496//7496 8931//8931 -f 8152//8152 8932//8932 8154//8154 -f 8154//8154 8932//8932 8931//8931 -f 8154//8154 8931//8931 8155//8155 -f 8155//8155 8931//8931 7496//7496 -f 8152//8152 8150//8150 8932//8932 -f 8932//8932 8150//8150 8149//8149 -f 8932//8932 8149//8149 8935//8935 -f 8149//8149 8147//8147 8935//8935 -f 8935//8935 8147//8147 8145//8145 -f 8935//8935 8145//8145 8934//8934 -f 8934//8934 8145//8145 8143//8143 -f 8934//8934 8143//8143 8933//8933 -f 8933//8933 8143//8143 8141//8141 -f 8933//8933 8141//8141 8937//8937 -f 8937//8937 8141//8141 8139//8139 -f 8937//8937 8139//8139 8936//8936 -f 8936//8936 8139//8139 8137//8137 -f 8936//8936 8137//8137 8939//8939 -f 8939//8939 8137//8137 8938//8938 -f 8938//8938 8137//8137 8134//8134 -f 8134//8134 8132//8132 8938//8938 -f 8938//8938 8132//8132 8131//8131 -f 8938//8938 8131//8131 8940//8940 -f 8940//8940 8131//8131 8122//8122 -f 8940//8940 8122//8122 8941//8941 -f 8122//8122 8124//8124 8941//8941 -f 8941//8941 8124//8124 8126//8126 -f 8941//8941 8126//8126 8945//8945 -f 8945//8945 8126//8126 8128//8128 -f 8945//8945 8128//8128 8944//8944 -f 8944//8944 8128//8128 8943//8943 -f 8943//8943 8128//8128 7492//7492 -f 8943//8943 7492//7492 8942//8942 -f 8942//8942 7492//7492 7491//7491 -f 8942//8942 7491//7491 8948//8948 -f 8948//8948 7491//7491 7489//7489 -f 8948//8948 7489//7489 8947//8947 -f 7489//7489 7487//7487 8947//8947 -f 8947//8947 7487//7487 7485//7485 -f 8947//8947 7485//7485 8946//8946 -f 8946//8946 7485//7485 7483//7483 -f 8946//8946 7483//7483 8949//8949 -f 8949//8949 7483//7483 7481//7481 -f 7472//7472 8956//8956 8955//8955 -f 7472//7472 8955//8955 7473//7473 -f 7473//7473 8955//8955 8954//8954 -f 7473//7473 8954//8954 7475//7475 -f 7475//7475 8954//8954 8953//8953 -f 7475//7475 8953//8953 7478//7478 -f 7478//7478 8953//8953 8952//8952 -f 7478//7478 8952//8952 7479//7479 -f 7479//7479 8952//8952 8951//8951 -f 7479//7479 8951//8951 7458//7458 -f 7458//7458 8951//8951 8950//8950 -f 7458//7458 8950//8950 7481//7481 -f 7481//7481 8950//8950 8949//8949 -f 7472//7472 7470//7470 8956//8956 -f 8956//8956 7470//7470 7468//7468 -f 8956//8956 7468//7468 8957//8957 -f 7468//7468 7466//7466 8957//8957 -f 8957//8957 7466//7466 7464//7464 -f 8957//8957 7464//7464 8958//8958 -f 7464//7464 7462//7462 8958//8958 -f 8958//8958 7462//7462 7460//7460 -f 8958//8958 7460//7460 8959//8959 -f 8959//8959 7460//7460 8120//8120 -f 8959//8959 8120//8120 8962//8962 -f 8962//8962 8120//8120 8118//8118 -f 8962//8962 8118//8118 8961//8961 -f 8961//8961 8118//8118 8117//8117 -f 8961//8961 8117//8117 8960//8960 -f 8960//8960 8117//8117 8115//8115 -f 8960//8960 8115//8115 8964//8964 -f 8964//8964 8115//8115 8113//8113 -f 8964//8964 8113//8113 8963//8963 -f 8963//8963 8113//8113 8112//8112 -f 8963//8963 8112//8112 8110//8110 -f 8963//8963 8110//8110 8965//8965 -f 8965//8965 8110//8110 8108//8108 -f 8965//8965 8108//8108 8966//8966 -f 8966//8966 8108//8108 8106//8106 -f 8966//8966 8106//8106 8968//8968 -f 8968//8968 8106//8106 8103//8103 -f 8968//8968 8103//8103 8967//8967 -f 8967//8967 8103//8103 8097//8097 -f 8967//8967 8097//8097 8969//8969 -f 8969//8969 8097//8097 8095//8095 -f 8969//8969 8095//8095 8970//8970 -f 8970//8970 8095//8095 8101//8101 -f 8970//8970 8101//8101 8971//8971 -f 8971//8971 8101//8101 8100//8100 -f 8971//8971 8100//8100 8972//8972 -f 8972//8972 8100//8100 8091//8091 -f 8972//8972 8091//8091 8973//8973 -f 8973//8973 8091//8091 8974//8974 -f 8974//8974 8091//8091 8089//8089 -f 8974//8974 8089//8089 8087//8087 -f 8974//8974 8087//8087 8975//8975 -f 8975//8975 8087//8087 7449//7449 -f 8975//8975 7449//7449 8976//8976 -f 7449//7449 7451//7451 8976//8976 -f 8976//8976 7451//7451 7453//7453 -f 8976//8976 7453//7453 8977//8977 -f 8977//8977 7453//7453 7445//7445 -f 8977//8977 7445//7445 8981//8981 -f 8981//8981 7445//7445 8980//8980 -f 7445//7445 7447//7447 8980//8980 -f 8980//8980 7447//7447 7448//7448 -f 8980//8980 7448//7448 8979//8979 -f 8979//8979 7448//7448 7443//7443 -f 8979//8979 7443//7443 8978//8978 -f 8978//8978 7443//7443 7442//7442 -f 8978//8978 7442//7442 8982//8982 -f 8982//8982 7442//7442 7439//7439 -f 8982//8982 7439//7439 8983//8983 -f 8983//8983 7439//7439 7417//7417 -f 8983//8983 7417//7417 8747//8747 -f 8991//8991 8996//8996 8997//8997 -f 8997//8997 8996//8996 8998//8998 -f 8993//8993 8991//8991 8999//8999 -f 8999//8999 8991//8991 8997//8997 -f 8992//8992 8993//8993 9000//9000 -f 9000//9000 8993//8993 8999//8999 -f 8994//8994 8992//8992 9001//9001 -f 9001//9001 8992//8992 9000//9000 -f 8995//8995 8994//8994 9002//9002 -f 9002//9002 8994//8994 9001//9001 -f 8996//8996 8995//8995 8998//8998 -f 8998//8998 8995//8995 9002//9002 -f 9002//9002 9001//9001 8998//8998 -f 8998//8998 9001//9001 9000//9000 -f 8998//8998 9000//9000 8997//8997 -f 8997//8997 9000//9000 8999//8999 -f 9003//9003 9004//9004 8326//8326 -f 8326//8326 9004//9004 8328//8328 -f 8328//8328 9004//9004 9005//9005 -f 8328//8328 9005//9005 8330//8330 -f 8330//8330 9005//9005 9006//9006 -f 8330//8330 9006//9006 8331//8331 -f 8331//8331 9006//9006 8323//8323 -f 8323//8323 9006//9006 9007//9007 -f 8323//8323 9007//9007 8320//8320 -f 8320//8320 9007//9007 9008//9008 -f 8320//8320 9008//9008 8318//8318 -f 8318//8318 9008//9008 9009//9009 -f 8318//8318 9009//9009 8316//8316 -f 8316//8316 9009//9009 8314//8314 -f 8314//8314 9009//9009 9010//9010 -f 8314//8314 9010//9010 8297//8297 -f 8297//8297 9010//9010 8298//8298 -f 8298//8298 9010//9010 9011//9011 -f 8298//8298 9011//9011 8311//8311 -f 9011//9011 9012//9012 8311//8311 -f 8311//8311 9012//9012 9013//9013 -f 8311//8311 9013//9013 8309//8309 -f 8309//8309 9013//9013 8306//8306 -f 8306//8306 9013//9013 9014//9014 -f 8306//8306 9014//9014 8304//8304 -f 8304//8304 9014//9014 8302//8302 -f 8302//8302 9014//9014 9015//9015 -f 8302//8302 9015//9015 8300//8300 -f 8300//8300 9015//9015 9016//9016 -f 8300//8300 9016//9016 7670//7670 -f 7670//7670 9016//9016 9017//9017 -f 7670//7670 9017//9017 7672//7672 -f 7672//7672 9017//9017 9018//9018 -f 7672//7672 9018//9018 7674//7674 -f 7674//7674 9018//9018 7675//7675 -f 7675//7675 9018//9018 9019//9019 -f 7675//7675 9019//9019 7677//7677 -f 7677//7677 9019//9019 9020//9020 -f 7677//7677 9020//9020 7678//7678 -f 7678//7678 9020//9020 9021//9021 -f 7678//7678 9021//9021 7660//7660 -f 7660//7660 9021//9021 9022//9022 -f 7660//7660 9022//9022 7661//7661 -f 7661//7661 9022//9022 7663//7663 -f 7663//7663 9022//9022 9023//9023 -f 7663//7663 9023//9023 7665//7665 -f 7665//7665 9023//9023 9024//9024 -f 7665//7665 9024//9024 7667//7667 -f 7667//7667 9024//9024 9025//9025 -f 7667//7667 9025//9025 7668//7668 -f 7668//7668 9025//9025 7656//7656 -f 7656//7656 9025//9025 9026//9026 -f 7656//7656 9026//9026 7657//7657 -f 7657//7657 9026//9026 9027//9027 -f 7657//7657 9027//9027 7658//7658 -f 7658//7658 9027//9027 7659//7659 -f 7659//7659 9027//9027 9028//9028 -f 7659//7659 9028//9028 7648//7648 -f 7648//7648 9028//9028 9029//9029 -f 7648//7648 9029//9029 7650//7650 -f 7650//7650 9029//9029 9030//9030 -f 7650//7650 9030//9030 7652//7652 -f 7652//7652 9030//9030 9031//9031 -f 7652//7652 9031//9031 7653//7653 -f 7653//7653 9031//9031 9032//9032 -f 7653//7653 9032//9032 7643//7643 -f 7643//7643 9032//9032 9033//9033 -f 7643//7643 9033//9033 7645//7645 -f 7645//7645 9033//9033 7646//7646 -f 7646//7646 9033//9033 9034//9034 -f 7646//7646 9034//9034 8294//8294 -f 9034//9034 9035//9035 8294//8294 -f 8294//8294 9035//9035 9036//9036 -f 8294//8294 9036//9036 8292//8292 -f 8292//8292 9036//9036 8289//8289 -f 8289//8289 9036//9036 9037//9037 -f 8289//8289 9037//9037 8287//8287 -f 8287//8287 9037//9037 9038//9038 -f 8287//8287 9038//9038 8285//8285 -f 8285//8285 9038//9038 9039//9039 -f 8285//8285 9039//9039 8283//8283 -f 8283//8283 9039//9039 8281//8281 -f 8281//8281 9039//9039 9040//9040 -f 8281//8281 9040//9040 8279//8279 -f 9040//9040 9041//9041 8279//8279 -f 8279//8279 9041//9041 9042//9042 -f 8279//8279 9042//9042 8277//8277 -f 8277//8277 9042//9042 9043//9043 -f 8277//8277 9043//9043 8276//8276 -f 8276//8276 9043//9043 9044//9044 -f 8276//8276 9044//9044 8274//8274 -f 8274//8274 9044//9044 9045//9045 -f 8274//8274 9045//9045 8264//8264 -f 8264//8264 9045//9045 9046//9046 -f 8264//8264 9046//9046 8266//8266 -f 8266//8266 9046//9046 9047//9047 -f 8266//8266 9047//9047 8268//8268 -f 8268//8268 9047//9047 9048//9048 -f 8268//8268 9048//9048 8270//8270 -f 8270//8270 9048//9048 9049//9049 -f 8270//8270 9049//9049 8271//8271 -f 8271//8271 9049//9049 9050//9050 -f 8271//8271 9050//9050 7638//7638 -f 7638//7638 9050//9050 9051//9051 -f 7638//7638 9051//9051 7636//7636 -f 7636//7636 9051//9051 9052//9052 -f 7636//7636 9052//9052 7634//7634 -f 7634//7634 9052//9052 9053//9053 -f 7634//7634 9053//9053 7632//7632 -f 7632//7632 9053//9053 9054//9054 -f 7632//7632 9054//9054 7630//7630 -f 7630//7630 9054//9054 9055//9055 -f 7630//7630 9055//9055 7628//7628 -f 7628//7628 9055//9055 9056//9056 -f 7628//7628 9056//9056 7604//7604 -f 7604//7604 9056//9056 9057//9057 -f 7604//7604 9057//9057 7605//7605 -f 7605//7605 9057//9057 9058//9058 -f 7605//7605 9058//9058 7625//7625 -f 7625//7625 9058//9058 9059//9059 -f 7625//7625 9059//9059 7624//7624 -f 7624//7624 9059//9059 9060//9060 -f 7624//7624 9060//9060 7622//7622 -f 7622//7622 9060//9060 9061//9061 -f 7622//7622 9061//9061 7619//7619 -f 7619//7619 9061//9061 9062//9062 -f 9063//9063 7615//7615 9062//9062 -f 9062//9062 7615//7615 7617//7617 -f 9062//9062 7617//7617 7619//7619 -f 9064//9064 7611//7611 9063//9063 -f 9063//9063 7611//7611 7613//7613 -f 9063//9063 7613//7613 7615//7615 -f 9065//9065 7607//7607 9064//9064 -f 9064//9064 7607//7607 7609//7609 -f 9064//9064 7609//7609 7611//7611 -f 9066//9066 8260//8260 9065//9065 -f 9065//9065 8260//8260 8262//8262 -f 9065//9065 8262//8262 7607//7607 -f 9067//9067 8250//8250 9068//9068 -f 9068//9068 8250//8250 8252//8252 -f 9068//9068 8252//8252 9069//9069 -f 9069//9069 8252//8252 8255//8255 -f 9069//9069 8255//8255 9066//9066 -f 9066//9066 8255//8255 8257//8257 -f 9066//9066 8257//8257 8260//8260 -f 9070//9070 8245//8245 9071//9071 -f 9071//9071 8245//8245 8246//8246 -f 9071//9071 8246//8246 9067//9067 -f 9067//9067 8246//8246 8248//8248 -f 9067//9067 8248//8248 8250//8250 -f 9072//9072 8237//8237 9073//9073 -f 9073//9073 8237//8237 8239//8239 -f 9073//9073 8239//8239 9070//9070 -f 9070//9070 8239//8239 8243//8243 -f 9070//9070 8243//8243 8245//8245 -f 9074//9074 8234//8234 9075//9075 -f 9075//9075 8234//8234 8240//8240 -f 9075//9075 8240//8240 9072//9072 -f 9072//9072 8240//8240 8235//8235 -f 9072//9072 8235//8235 8237//8237 -f 9076//9076 7598//7598 9077//9077 -f 9077//9077 7598//7598 8227//8227 -f 9077//9077 8227//8227 9078//9078 -f 9078//9078 8227//8227 8229//8229 -f 9078//9078 8229//8229 9079//9079 -f 9079//9079 8229//8229 8231//8231 -f 9079//9079 8231//8231 9074//9074 -f 9074//9074 8231//8231 8233//8233 -f 9074//9074 8233//8233 8234//8234 -f 7585//7585 7592//7592 9080//9080 -f 9080//9080 7592//7592 7594//7594 -f 9080//9080 7594//7594 9081//9081 -f 9081//9081 7594//7594 7603//7603 -f 9081//9081 7603//7603 9082//9082 -f 9082//9082 7603//7603 7602//7602 -f 9082//9082 7602//7602 9076//9076 -f 9076//9076 7602//7602 7600//7600 -f 9076//9076 7600//7600 7598//7598 -f 9080//9080 9083//9083 7585//7585 -f 7585//7585 9083//9083 9084//9084 -f 7585//7585 9084//9084 7586//7586 -f 7586//7586 9084//9084 9085//9085 -f 7586//7586 9085//9085 7588//7588 -f 7588//7588 9085//9085 9086//9086 -f 7588//7588 9086//9086 7589//7589 -f 7589//7589 9086//9086 9087//9087 -f 7589//7589 9087//9087 7569//7569 -f 7569//7569 9087//9087 9088//9088 -f 7569//7569 9088//9088 7571//7571 -f 7571//7571 9088//9088 9089//9089 -f 7571//7571 9089//9089 7573//7573 -f 7573//7573 9089//9089 9090//9090 -f 7573//7573 9090//9090 7575//7575 -f 7575//7575 9090//9090 9091//9091 -f 7583//7583 7584//7584 9092//9092 -f 9092//9092 7584//7584 7579//7579 -f 9092//9092 7579//7579 9091//9091 -f 9091//9091 7579//7579 7577//7577 -f 9091//9091 7577//7577 7575//7575 -f 7583//7583 9092//9092 7581//7581 -f 7581//7581 9092//9092 9093//9093 -f 7581//7581 9093//9093 8226//8226 -f 8226//8226 9093//9093 8224//8224 -f 8224//8224 9093//9093 9094//9094 -f 8224//8224 9094//9094 8222//8222 -f 8222//8222 9094//9094 9095//9095 -f 8222//8222 9095//9095 8220//8220 -f 8220//8220 9095//9095 9096//9096 -f 8220//8220 9096//9096 8218//8218 -f 8218//8218 9096//9096 8216//8216 -f 8216//8216 9096//9096 9097//9097 -f 8216//8216 9097//9097 8214//8214 -f 9097//9097 9098//9098 8214//8214 -f 8214//8214 9098//9098 9099//9099 -f 8214//8214 9099//9099 8212//8212 -f 8212//8212 9099//9099 9100//9100 -f 8212//8212 9100//9100 8210//8210 -f 8210//8210 9100//9100 8208//8208 -f 8208//8208 9100//9100 9101//9101 -f 8208//8208 9101//9101 8205//8205 -f 9101//9101 9102//9102 8205//8205 -f 8205//8205 9102//9102 9103//9103 -f 8205//8205 9103//9103 8204//8204 -f 8204//8204 9103//9103 9104//9104 -f 8204//8204 9104//9104 8202//8202 -f 8202//8202 9104//9104 9105//9105 -f 8202//8202 9105//9105 8200//8200 -f 8200//8200 9105//9105 9106//9106 -f 9107//9107 7566//7566 9108//9108 -f 9108//9108 7566//7566 7564//7564 -f 9108//9108 7564//7564 9109//9109 -f 9109//9109 7564//7564 8194//8194 -f 9109//9109 8194//8194 9110//9110 -f 9110//9110 8194//8194 8192//8192 -f 9110//9110 8192//8192 9111//9111 -f 9111//9111 8192//8192 8191//8191 -f 9111//9111 8191//8191 9106//9106 -f 9106//9106 8191//8191 8198//8198 -f 9106//9106 8198//8198 8200//8200 -f 9112//9112 7555//7555 9113//9113 -f 9113//9113 7555//7555 7556//7556 -f 9113//9113 7556//7556 9114//9114 -f 9114//9114 7556//7556 7558//7558 -f 9114//9114 7558//7558 9115//9115 -f 9115//9115 7558//7558 7560//7560 -f 9115//9115 7560//7560 9107//9107 -f 9107//9107 7560//7560 7567//7567 -f 9107//9107 7567//7567 7566//7566 -f 9116//9116 7551//7551 9112//9112 -f 9112//9112 7551//7551 7553//7553 -f 9112//9112 7553//7553 7555//7555 -f 9116//9116 9117//9117 7551//7551 -f 7551//7551 9117//9117 8990//8990 -f 7551//7551 8990//8990 7549//7549 -f 8326//8326 7684//7684 9003//9003 -f 9003//9003 7684//7684 7682//7682 -f 9003//9003 7682//7682 9118//9118 -f 9118//9118 7682//7682 7680//7680 -f 9118//9118 7680//7680 9119//9119 -f 9119//9119 7680//7680 7679//7679 -f 9119//9119 7679//7679 9120//9120 -f 9120//9120 7679//7679 7688//7688 -f 9120//9120 7688//7688 9121//9121 -f 9121//9121 7688//7688 7690//7690 -f 9121//9121 7690//7690 9122//9122 -f 7690//7690 7692//7692 9122//9122 -f 9122//9122 7692//7692 7695//7695 -f 9122//9122 7695//7695 9123//9123 -f 9123//9123 7695//7695 7697//7697 -f 9123//9123 7697//7697 9124//9124 -f 9124//9124 7716//7716 7718//7718 -f 9124//9124 7718//7718 9123//9123 -f 9123//9123 7718//7718 7720//7720 -f 9123//9123 7720//7720 9122//9122 -f 9122//9122 7720//7720 9121//9121 -f 9121//9121 7720//7720 7722//7722 -f 9121//9121 7722//7722 9120//9120 -f 9120//9120 7722//7722 7724//7724 -f 9120//9120 7724//7724 9119//9119 -f 9119//9119 7724//7724 7726//7726 -f 9119//9119 7726//7726 9118//9118 -f 7726//7726 7728//7728 9118//9118 -f 9118//9118 7728//7728 7730//7730 -f 9118//9118 7730//7730 9003//9003 -f 9003//9003 7730//7730 8366//8366 -f 9003//9003 8366//8366 9004//9004 -f 9004//9004 8366//8366 8364//8364 -f 9004//9004 8364//8364 9005//9005 -f 9005//9005 8364//8364 8362//8362 -f 9005//9005 8362//8362 9006//9006 -f 8362//8362 8360//8360 9006//9006 -f 9006//9006 8360//8360 8358//8358 -f 9006//9006 8358//8358 9007//9007 -f 9007//9007 8358//8358 8356//8356 -f 9007//9007 8356//8356 9008//9008 -f 9008//9008 8356//8356 8354//8354 -f 9008//9008 8354//8354 9009//9009 -f 8354//8354 8352//8352 9009//9009 -f 9009//9009 8352//8352 8350//8350 -f 9009//9009 8350//8350 9010//9010 -f 8350//8350 8348//8348 9010//9010 -f 9010//9010 8348//8348 8347//8347 -f 9010//9010 8347//8347 9011//9011 -f 9011//9011 8347//8347 8344//8344 -f 9011//9011 8344//8344 9012//9012 -f 9012//9012 8344//8344 8342//8342 -f 9012//9012 8342//8342 9013//9013 -f 8342//8342 8340//8340 9013//9013 -f 9013//9013 8340//8340 8338//8338 -f 9013//9013 8338//8338 9014//9014 -f 9014//9014 8338//8338 8337//8337 -f 9014//9014 8337//8337 9015//9015 -f 9015//9015 8337//8337 8334//8334 -f 9015//9015 8334//8334 9016//9016 -f 8334//8334 8336//8336 9016//9016 -f 9016//9016 8336//8336 7711//7711 -f 9016//9016 7711//7711 9017//9017 -f 9017//9017 7711//7711 7713//7713 -f 9017//9017 7713//7713 9018//9018 -f 9018//9018 7713//7713 7710//7710 -f 9018//9018 7710//7710 9019//9019 -f 9019//9019 7710//7710 7709//7709 -f 9019//9019 7709//7709 9020//9020 -f 9020//9020 7709//7709 7707//7707 -f 9020//9020 7707//7707 9021//9021 -f 9021//9021 7707//7707 7705//7705 -f 9021//9021 7705//7705 9022//9022 -f 9022//9022 7705//7705 7702//7702 -f 9022//9022 7702//7702 9023//9023 -f 9023//9023 7702//7702 7700//7700 -f 9030//9030 9029//9029 7691//7691 -f 7691//7691 9029//9029 7693//7693 -f 7693//7693 9029//9029 9028//9028 -f 7693//7693 9028//9028 7694//7694 -f 7694//7694 9028//9028 9027//9027 -f 7694//7694 9027//9027 7696//7696 -f 7696//7696 9027//9027 9026//9026 -f 7696//7696 9026//9026 7698//7698 -f 7698//7698 9026//9026 9025//9025 -f 7698//7698 9025//9025 7700//7700 -f 7700//7700 9025//9025 9024//9024 -f 7700//7700 9024//9024 9023//9023 -f 7691//7691 7689//7689 9030//9030 -f 9030//9030 7689//7689 7687//7687 -f 9030//9030 7687//7687 9031//9031 -f 9031//9031 7687//7687 7686//7686 -f 9031//9031 7686//7686 9032//9032 -f 9032//9032 7686//7686 7681//7681 -f 9032//9032 7681//7681 9033//9033 -f 7681//7681 7683//7683 9033//9033 -f 9033//9033 7683//7683 7685//7685 -f 9033//9033 7685//7685 9034//9034 -f 9034//9034 7685//7685 8325//8325 -f 9034//9034 8325//8325 9035//9035 -f 8325//8325 8327//8327 9035//9035 -f 9035//9035 8327//8327 8329//8329 -f 9035//9035 8329//8329 9036//9036 -f 9036//9036 8329//8329 8324//8324 -f 9036//9036 8324//8324 9037//9037 -f 9037//9037 8324//8324 8322//8322 -f 9037//9037 8322//8322 9038//9038 -f 9038//9038 8322//8322 8321//8321 -f 9038//9038 8321//8321 9039//9039 -f 9039//9039 8321//8321 8319//8319 -f 9039//9039 8319//8319 9040//9040 -f 9040//9040 8319//8319 8317//8317 -f 9040//9040 8317//8317 9041//9041 -f 9041//9041 8317//8317 8315//8315 -f 9041//9041 8315//8315 9042//9042 -f 9042//9042 8315//8315 8299//8299 -f 9042//9042 8299//8299 9043//9043 -f 9043//9043 8299//8299 8313//8313 -f 9043//9043 8313//8313 9044//9044 -f 8313//8313 8312//8312 9044//9044 -f 9044//9044 8312//8312 8310//8310 -f 9044//9044 8310//8310 9045//9045 -f 9045//9045 8310//8310 8308//8308 -f 9045//9045 8308//8308 9046//9046 -f 9046//9046 8308//8308 8307//8307 -f 9046//9046 8307//8307 9047//9047 -f 9047//9047 8307//8307 8305//8305 -f 9047//9047 8305//8305 9048//9048 -f 9048//9048 8305//8305 8303//8303 -f 9048//9048 8303//8303 9049//9049 -f 9049//9049 8303//8303 8301//8301 -f 9049//9049 8301//8301 9050//9050 -f 9050//9050 8301//8301 7669//7669 -f 9050//9050 7669//7669 9051//9051 -f 9051//9051 7669//7669 7671//7671 -f 9051//9051 7671//7671 9052//9052 -f 9052//9052 7671//7671 7673//7673 -f 9052//9052 7673//7673 9053//9053 -f 9053//9053 7673//7673 7676//7676 -f 9053//9053 7676//7676 9054//9054 -f 9054//9054 7676//7676 7662//7662 -f 7655//7655 9059//9059 9058//9058 -f 7655//7655 9058//9058 7666//7666 -f 7666//7666 9058//9058 9057//9057 -f 7666//7666 9057//9057 7664//7664 -f 7664//7664 9057//9057 9056//9056 -f 7664//7664 9056//9056 7662//7662 -f 7662//7662 9056//9056 9055//9055 -f 7662//7662 9055//9055 9054//9054 -f 9059//9059 7655//7655 9060//9060 -f 9060//9060 7655//7655 7654//7654 -f 9060//9060 7654//7654 9061//9061 -f 7654//7654 7647//7647 9061//9061 -f 9061//9061 7647//7647 7649//7649 -f 9061//9061 7649//7649 9062//9062 -f 9062//9062 7649//7649 7651//7651 -f 9062//9062 7651//7651 9063//9063 -f 9063//9063 7651//7651 7642//7642 -f 9063//9063 7642//7642 9064//9064 -f 7642//7642 7641//7641 9064//9064 -f 9064//9064 7641//7641 7644//7644 -f 9064//9064 7644//7644 9065//9065 -f 8293//8293 9066//9066 8295//8295 -f 8295//8295 9066//9066 9065//9065 -f 8295//8295 9065//9065 8296//8296 -f 8296//8296 9065//9065 7644//7644 -f 8293//8293 8291//8291 9066//9066 -f 9066//9066 8291//8291 8290//8290 -f 9066//9066 8290//8290 9069//9069 -f 8290//8290 8288//8288 9069//9069 -f 9069//9069 8288//8288 8286//8286 -f 9069//9069 8286//8286 9068//9068 -f 9068//9068 8286//8286 8284//8284 -f 9068//9068 8284//8284 9067//9067 -f 9067//9067 8284//8284 8282//8282 -f 9067//9067 8282//8282 9071//9071 -f 9071//9071 8282//8282 8280//8280 -f 9071//9071 8280//8280 9070//9070 -f 9070//9070 8280//8280 8278//8278 -f 9070//9070 8278//8278 9073//9073 -f 9073//9073 8278//8278 8275//8275 -f 9073//9073 8275//8275 9072//9072 -f 8275//8275 8273//8273 9072//9072 -f 9072//9072 8273//8273 8272//8272 -f 9072//9072 8272//8272 9075//9075 -f 9075//9075 8272//8272 8263//8263 -f 9075//9075 8263//8263 9074//9074 -f 8263//8263 8265//8265 9074//9074 -f 9074//9074 8265//8265 8267//8267 -f 9074//9074 8267//8267 9079//9079 -f 9079//9079 8267//8267 8269//8269 -f 9079//9079 8269//8269 9078//9078 -f 9078//9078 8269//8269 9077//9077 -f 9077//9077 8269//8269 7640//7640 -f 9077//9077 7640//7640 9076//9076 -f 9076//9076 7640//7640 7639//7639 -f 9076//9076 7639//7639 9082//9082 -f 9082//9082 7639//7639 7637//7637 -f 9082//9082 7637//7637 9081//9081 -f 7637//7637 7635//7635 9081//9081 -f 9081//9081 7635//7635 7633//7633 -f 9081//9081 7633//7633 9080//9080 -f 9080//9080 7633//7633 7631//7631 -f 9080//9080 7631//7631 9083//9083 -f 9083//9083 7631//7631 7629//7629 -f 9083//9083 7629//7629 9084//9084 -f 9084//9084 7629//7629 7606//7606 -f 9084//9084 7606//7606 9085//9085 -f 9085//9085 7606//7606 7627//7627 -f 9085//9085 7627//7627 9086//9086 -f 9086//9086 7627//7627 7626//7626 -f 9086//9086 7626//7626 9087//9087 -f 9087//9087 7626//7626 7623//7623 -f 9087//9087 7623//7623 9088//9088 -f 9088//9088 7623//7623 7621//7621 -f 9088//9088 7621//7621 9089//9089 -f 9089//9089 7621//7621 7620//7620 -f 9089//9089 7620//7620 9090//9090 -f 7620//7620 7618//7618 9090//9090 -f 9090//9090 7618//7618 7616//7616 -f 9090//9090 7616//7616 9091//9091 -f 7616//7616 7614//7614 9091//9091 -f 9091//9091 7614//7614 7612//7612 -f 9091//9091 7612//7612 9092//9092 -f 7612//7612 7610//7610 9092//9092 -f 9092//9092 7610//7610 7608//7608 -f 9092//9092 7608//7608 9093//9093 -f 9093//9093 7608//7608 8261//8261 -f 9093//9093 8261//8261 9094//9094 -f 9094//9094 8261//8261 8259//8259 -f 9094//9094 8259//8259 9095//9095 -f 9095//9095 8259//8259 8258//8258 -f 9095//9095 8258//8258 9096//9096 -f 9096//9096 8258//8258 8256//8256 -f 9096//9096 8256//8256 9097//9097 -f 8256//8256 8254//8254 9097//9097 -f 9097//9097 8254//8254 8253//8253 -f 9097//9097 8253//8253 9098//9098 -f 9098//9098 8253//8253 8251//8251 -f 9098//9098 8251//8251 9099//9099 -f 9099//9099 8251//8251 8249//8249 -f 9099//9099 8249//8249 9100//9100 -f 9100//9100 8249//8249 8247//8247 -f 9100//9100 8247//8247 9101//9101 -f 9101//9101 8247//8247 8244//8244 -f 9101//9101 8244//8244 9102//9102 -f 9102//9102 8244//8244 8238//8238 -f 9102//9102 8238//8238 9103//9103 -f 9103//9103 8238//8238 8236//8236 -f 9103//9103 8236//8236 9104//9104 -f 9104//9104 8236//8236 8242//8242 -f 9104//9104 8242//8242 9105//9105 -f 9105//9105 8242//8242 8241//8241 -f 9105//9105 8241//8241 9106//9106 -f 9106//9106 8241//8241 8232//8232 -f 9106//9106 8232//8232 9111//9111 -f 9111//9111 8232//8232 8230//8230 -f 9111//9111 8230//8230 9110//9110 -f 9110//9110 8230//8230 8228//8228 -f 9110//9110 8228//8228 9109//9109 -f 9109//9109 8228//8228 7597//7597 -f 9109//9109 7597//7597 9108//9108 -f 7597//7597 7599//7599 9108//9108 -f 9108//9108 7599//7599 7601//7601 -f 9108//9108 7601//7601 9107//9107 -f 9107//9107 7601//7601 7593//7593 -f 9107//9107 7593//7593 9115//9115 -f 9115//9115 7593//7593 9114//9114 -f 7593//7593 7595//7595 9114//9114 -f 9114//9114 7595//7595 7596//7596 -f 9114//9114 7596//7596 9113//9113 -f 9113//9113 7596//7596 7591//7591 -f 9113//9113 7591//7591 9112//9112 -f 9112//9112 7591//7591 7590//7590 -f 9112//9112 7590//7590 9116//9116 -f 9116//9116 7590//7590 7587//7587 -f 9116//9116 7587//7587 9117//9117 -f 9117//9117 7587//7587 7568//7568 -f 9117//9117 7568//7568 8990//8990 -f 9125//9125 9126//9126 8467//8467 -f 8467//8467 9126//9126 8469//8469 -f 8469//8469 9126//9126 9127//9127 -f 8469//8469 9127//9127 8471//8471 -f 8471//8471 9127//9127 9128//9128 -f 8471//8471 9128//9128 8472//8472 -f 8472//8472 9128//9128 8464//8464 -f 8464//8464 9128//9128 9129//9129 -f 8464//8464 9129//9129 8461//8461 -f 8461//8461 9129//9129 9130//9130 -f 8461//8461 9130//9130 8459//8459 -f 8459//8459 9130//9130 9131//9131 -f 8459//8459 9131//9131 8457//8457 -f 8457//8457 9131//9131 8455//8455 -f 8455//8455 9131//9131 9132//9132 -f 8455//8455 9132//9132 8438//8438 -f 8438//8438 9132//9132 8439//8439 -f 8439//8439 9132//9132 9133//9133 -f 8439//8439 9133//9133 8452//8452 -f 9133//9133 9134//9134 8452//8452 -f 8452//8452 9134//9134 9135//9135 -f 8452//8452 9135//9135 8450//8450 -f 8450//8450 9135//9135 8447//8447 -f 8447//8447 9135//9135 9136//9136 -f 8447//8447 9136//9136 8445//8445 -f 8445//8445 9136//9136 8443//8443 -f 8443//8443 9136//9136 9137//9137 -f 8443//8443 9137//9137 8441//8441 -f 8441//8441 9137//9137 9138//9138 -f 8441//8441 9138//9138 7818//7818 -f 7818//7818 9138//9138 9139//9139 -f 7818//7818 9139//9139 7820//7820 -f 7820//7820 9139//9139 9140//9140 -f 7820//7820 9140//9140 7822//7822 -f 7822//7822 9140//9140 7823//7823 -f 7823//7823 9140//9140 9141//9141 -f 7823//7823 9141//9141 7825//7825 -f 7825//7825 9141//9141 9142//9142 -f 7825//7825 9142//9142 7826//7826 -f 7826//7826 9142//9142 9143//9143 -f 7826//7826 9143//9143 7808//7808 -f 7808//7808 9143//9143 9144//9144 -f 7808//7808 9144//9144 7809//7809 -f 7809//7809 9144//9144 7811//7811 -f 7811//7811 9144//9144 9145//9145 -f 7811//7811 9145//9145 7813//7813 -f 7813//7813 9145//9145 9146//9146 -f 7813//7813 9146//9146 7815//7815 -f 7815//7815 9146//9146 9147//9147 -f 7815//7815 9147//9147 7816//7816 -f 7816//7816 9147//9147 7804//7804 -f 7804//7804 9147//9147 9148//9148 -f 7804//7804 9148//9148 7805//7805 -f 7805//7805 9148//9148 9149//9149 -f 7805//7805 9149//9149 7806//7806 -f 7806//7806 9149//9149 7807//7807 -f 7807//7807 9149//9149 9150//9150 -f 7807//7807 9150//9150 7796//7796 -f 7796//7796 9150//9150 9151//9151 -f 7796//7796 9151//9151 7798//7798 -f 7798//7798 9151//9151 9152//9152 -f 7798//7798 9152//9152 7800//7800 -f 7800//7800 9152//9152 9153//9153 -f 7800//7800 9153//9153 7801//7801 -f 7801//7801 9153//9153 9154//9154 -f 7801//7801 9154//9154 7791//7791 -f 7791//7791 9154//9154 9155//9155 -f 7791//7791 9155//9155 7793//7793 -f 7793//7793 9155//9155 7794//7794 -f 7794//7794 9155//9155 9156//9156 -f 7794//7794 9156//9156 8435//8435 -f 9156//9156 9157//9157 8435//8435 -f 8435//8435 9157//9157 9158//9158 -f 8435//8435 9158//9158 8433//8433 -f 8433//8433 9158//9158 8430//8430 -f 8430//8430 9158//9158 9159//9159 -f 8430//8430 9159//9159 8428//8428 -f 8428//8428 9159//9159 9160//9160 -f 8428//8428 9160//9160 8426//8426 -f 8426//8426 9160//9160 9161//9161 -f 8426//8426 9161//9161 8424//8424 -f 8424//8424 9161//9161 8422//8422 -f 8422//8422 9161//9161 9162//9162 -f 8422//8422 9162//9162 8420//8420 -f 9162//9162 9163//9163 8420//8420 -f 8420//8420 9163//9163 9164//9164 -f 8420//8420 9164//9164 8418//8418 -f 8418//8418 9164//9164 9165//9165 -f 8418//8418 9165//9165 8417//8417 -f 8417//8417 9165//9165 9166//9166 -f 8417//8417 9166//9166 8415//8415 -f 8415//8415 9166//9166 9167//9167 -f 8415//8415 9167//9167 8405//8405 -f 8405//8405 9167//9167 9168//9168 -f 8405//8405 9168//9168 8407//8407 -f 8407//8407 9168//9168 9169//9169 -f 8407//8407 9169//9169 8409//8409 -f 8409//8409 9169//9169 9170//9170 -f 8409//8409 9170//9170 8411//8411 -f 8411//8411 9170//9170 9171//9171 -f 8411//8411 9171//9171 8412//8412 -f 8412//8412 9171//9171 9172//9172 -f 8412//8412 9172//9172 7786//7786 -f 7786//7786 9172//9172 9173//9173 -f 7786//7786 9173//9173 7784//7784 -f 7784//7784 9173//9173 9174//9174 -f 7784//7784 9174//9174 7782//7782 -f 7782//7782 9174//9174 9175//9175 -f 7782//7782 9175//9175 7780//7780 -f 7780//7780 9175//9175 9176//9176 -f 7780//7780 9176//9176 7778//7778 -f 7778//7778 9176//9176 9177//9177 -f 7778//7778 9177//9177 7776//7776 -f 7776//7776 9177//9177 9178//9178 -f 7776//7776 9178//9178 7752//7752 -f 7752//7752 9178//9178 9179//9179 -f 7752//7752 9179//9179 7753//7753 -f 7753//7753 9179//9179 9180//9180 -f 7753//7753 9180//9180 7773//7773 -f 7773//7773 9180//9180 9181//9181 -f 7773//7773 9181//9181 7772//7772 -f 7772//7772 9181//9181 9182//9182 -f 7772//7772 9182//9182 7770//7770 -f 7770//7770 9182//9182 9183//9183 -f 7770//7770 9183//9183 7767//7767 -f 7767//7767 9183//9183 9184//9184 -f 9185//9185 7763//7763 9184//9184 -f 9184//9184 7763//7763 7765//7765 -f 9184//9184 7765//7765 7767//7767 -f 9186//9186 7759//7759 9185//9185 -f 9185//9185 7759//7759 7761//7761 -f 9185//9185 7761//7761 7763//7763 -f 9187//9187 7755//7755 9186//9186 -f 9186//9186 7755//7755 7757//7757 -f 9186//9186 7757//7757 7759//7759 -f 9188//9188 8401//8401 9187//9187 -f 9187//9187 8401//8401 8403//8403 -f 9187//9187 8403//8403 7755//7755 -f 9189//9189 8391//8391 9190//9190 -f 9190//9190 8391//8391 8393//8393 -f 9190//9190 8393//8393 9191//9191 -f 9191//9191 8393//8393 8396//8396 -f 9191//9191 8396//8396 9188//9188 -f 9188//9188 8396//8396 8398//8398 -f 9188//9188 8398//8398 8401//8401 -f 9192//9192 8386//8386 9193//9193 -f 9193//9193 8386//8386 8387//8387 -f 9193//9193 8387//8387 9189//9189 -f 9189//9189 8387//8387 8389//8389 -f 9189//9189 8389//8389 8391//8391 -f 9194//9194 8378//8378 9195//9195 -f 9195//9195 8378//8378 8380//8380 -f 9195//9195 8380//8380 9192//9192 -f 9192//9192 8380//8380 8384//8384 -f 9192//9192 8384//8384 8386//8386 -f 9196//9196 8375//8375 9197//9197 -f 9197//9197 8375//8375 8381//8381 -f 9197//9197 8381//8381 9194//9194 -f 9194//9194 8381//8381 8376//8376 -f 9194//9194 8376//8376 8378//8378 -f 9198//9198 7746//7746 9199//9199 -f 9199//9199 7746//7746 8368//8368 -f 9199//9199 8368//8368 9200//9200 -f 9200//9200 8368//8368 8370//8370 -f 9200//9200 8370//8370 9201//9201 -f 9201//9201 8370//8370 8372//8372 -f 9201//9201 8372//8372 9196//9196 -f 9196//9196 8372//8372 8374//8374 -f 9196//9196 8374//8374 8375//8375 -f 7733//7733 7740//7740 9202//9202 -f 9202//9202 7740//7740 7742//7742 -f 9202//9202 7742//7742 9203//9203 -f 9203//9203 7742//7742 7751//7751 -f 9203//9203 7751//7751 9204//9204 -f 9204//9204 7751//7751 7750//7750 -f 9204//9204 7750//7750 9198//9198 -f 9198//9198 7750//7750 7748//7748 -f 9198//9198 7748//7748 7746//7746 -f 9202//9202 9205//9205 7733//7733 -f 7733//7733 9205//9205 9206//9206 -f 7733//7733 9206//9206 7734//7734 -f 7734//7734 9206//9206 9207//9207 -f 7734//7734 9207//9207 7736//7736 -f 7736//7736 9207//9207 9208//9208 -f 7736//7736 9208//9208 7737//7737 -f 7737//7737 9208//9208 9209//9209 -f 7737//7737 9209//9209 7717//7717 -f 7717//7717 9209//9209 9210//9210 -f 7717//7717 9210//9210 7719//7719 -f 7719//7719 9210//9210 9211//9211 -f 7719//7719 9211//9211 7721//7721 -f 7721//7721 9211//9211 9212//9212 -f 7721//7721 9212//9212 7723//7723 -f 7723//7723 9212//9212 9213//9213 -f 7731//7731 7732//7732 9214//9214 -f 9214//9214 7732//7732 7727//7727 -f 9214//9214 7727//7727 9213//9213 -f 9213//9213 7727//7727 7725//7725 -f 9213//9213 7725//7725 7723//7723 -f 7731//7731 9214//9214 7729//7729 -f 7729//7729 9214//9214 9215//9215 -f 7729//7729 9215//9215 8367//8367 -f 8367//8367 9215//9215 8365//8365 -f 8365//8365 9215//9215 9216//9216 -f 8365//8365 9216//9216 8363//8363 -f 8363//8363 9216//9216 9217//9217 -f 8363//8363 9217//9217 8361//8361 -f 8361//8361 9217//9217 9218//9218 -f 8361//8361 9218//9218 8359//8359 -f 8359//8359 9218//9218 8357//8357 -f 8357//8357 9218//9218 9219//9219 -f 8357//8357 9219//9219 8355//8355 -f 9219//9219 9220//9220 8355//8355 -f 8355//8355 9220//9220 9221//9221 -f 8355//8355 9221//9221 8353//8353 -f 8353//8353 9221//9221 9222//9222 -f 8353//8353 9222//9222 8351//8351 -f 8351//8351 9222//9222 8349//8349 -f 8349//8349 9222//9222 9223//9223 -f 8349//8349 9223//9223 8346//8346 -f 9223//9223 9224//9224 8346//8346 -f 8346//8346 9224//9224 9225//9225 -f 8346//8346 9225//9225 8345//8345 -f 8345//8345 9225//9225 9226//9226 -f 8345//8345 9226//9226 8343//8343 -f 8343//8343 9226//9226 9227//9227 -f 8343//8343 9227//9227 8341//8341 -f 8341//8341 9227//9227 9228//9228 -f 9229//9229 7714//7714 9230//9230 -f 9230//9230 7714//7714 7712//7712 -f 9230//9230 7712//7712 9231//9231 -f 9231//9231 7712//7712 8335//8335 -f 9231//9231 8335//8335 9232//9232 -f 9232//9232 8335//8335 8333//8333 -f 9232//9232 8333//8333 9233//9233 -f 9233//9233 8333//8333 8332//8332 -f 9233//9233 8332//8332 9228//9228 -f 9228//9228 8332//8332 8339//8339 -f 9228//9228 8339//8339 8341//8341 -f 9234//9234 7703//7703 9235//9235 -f 9235//9235 7703//7703 7704//7704 -f 9235//9235 7704//7704 9236//9236 -f 9236//9236 7704//7704 7706//7706 -f 9236//9236 7706//7706 9237//9237 -f 9237//9237 7706//7706 7708//7708 -f 9237//9237 7708//7708 9229//9229 -f 9229//9229 7708//7708 7715//7715 -f 9229//9229 7715//7715 7714//7714 -f 9238//9238 7699//7699 9234//9234 -f 9234//9234 7699//7699 7701//7701 -f 9234//9234 7701//7701 7703//7703 -f 9238//9238 9239//9239 7699//7699 -f 7699//7699 9239//9239 9124//9124 -f 7699//7699 9124//9124 7697//7697 -f 8467//8467 7835//7835 9125//9125 -f 9125//9125 7835//7835 7833//7833 -f 9125//9125 7833//7833 9240//9240 -f 9240//9240 7833//7833 7831//7831 -f 9240//9240 7831//7831 9241//9241 -f 9241//9241 7831//7831 7830//7830 -f 9241//9241 7830//7830 9242//9242 -f 9242//9242 7830//7830 7839//7839 -f 9242//9242 7839//7839 9243//9243 -f 9243//9243 7839//7839 7841//7841 -f 9243//9243 7841//7841 9244//9244 -f 7841//7841 7843//7843 9244//9244 -f 9244//9244 7843//7843 7846//7846 -f 9244//9244 7846//7846 9245//9245 -f 9245//9245 7846//7846 7848//7848 -f 9245//9245 7848//7848 9246//9246 -f 9246//9246 7884//7884 7886//7886 -f 9246//9246 7886//7886 9245//9245 -f 9245//9245 7886//7886 7865//7865 -f 9245//9245 7865//7865 9244//9244 -f 9244//9244 7865//7865 9243//9243 -f 9243//9243 7865//7865 7867//7867 -f 9243//9243 7867//7867 9242//9242 -f 9242//9242 7867//7867 7869//7869 -f 9242//9242 7869//7869 9241//9241 -f 9241//9241 7869//7869 7875//7875 -f 9241//9241 7875//7875 9240//9240 -f 7875//7875 7873//7873 9240//9240 -f 9240//9240 7873//7873 7871//7871 -f 9240//9240 7871//7871 9125//9125 -f 9125//9125 7871//7871 8499//8499 -f 9125//9125 8499//8499 9126//9126 -f 9126//9126 8499//8499 8501//8501 -f 9126//9126 8501//8501 9127//9127 -f 9127//9127 8501//8501 8503//8503 -f 9127//9127 8503//8503 9128//9128 -f 8503//8503 8505//8505 9128//9128 -f 9128//9128 8505//8505 8507//8507 -f 9128//9128 8507//8507 9129//9129 -f 9129//9129 8507//8507 8497//8497 -f 9129//9129 8497//8497 9130//9130 -f 9130//9130 8497//8497 8495//8495 -f 9130//9130 8495//8495 9131//9131 -f 8495//8495 8494//8494 9131//9131 -f 9131//9131 8494//8494 8492//8492 -f 9131//9131 8492//8492 9132//9132 -f 8492//8492 8490//8490 9132//9132 -f 9132//9132 8490//8490 8488//8488 -f 9132//9132 8488//8488 9133//9133 -f 9133//9133 8488//8488 8485//8485 -f 9133//9133 8485//8485 9134//9134 -f 9134//9134 8485//8485 8483//8483 -f 9134//9134 8483//8483 9135//9135 -f 8483//8483 8481//8481 9135//9135 -f 9135//9135 8481//8481 8479//8479 -f 9135//9135 8479//8479 9136//9136 -f 9136//9136 8479//8479 8478//8478 -f 9136//9136 8478//8478 9137//9137 -f 9137//9137 8478//8478 8475//8475 -f 9137//9137 8475//8475 9138//9138 -f 8475//8475 8477//8477 9138//9138 -f 9138//9138 8477//8477 7860//7860 -f 9138//9138 7860//7860 9139//9139 -f 9139//9139 7860//7860 7859//7859 -f 9139//9139 7859//7859 9140//9140 -f 9140//9140 7859//7859 7828//7828 -f 9140//9140 7828//7828 9141//9141 -f 9141//9141 7828//7828 7827//7827 -f 9141//9141 7827//7827 9142//9142 -f 9142//9142 7827//7827 7858//7858 -f 9142//9142 7858//7858 9143//9143 -f 9143//9143 7858//7858 7857//7857 -f 9143//9143 7857//7857 9144//9144 -f 9144//9144 7857//7857 7853//7853 -f 9144//9144 7853//7853 9145//9145 -f 9145//9145 7853//7853 7851//7851 -f 9152//9152 9151//9151 7842//7842 -f 7842//7842 9151//9151 7844//7844 -f 7844//7844 9151//9151 9150//9150 -f 7844//7844 9150//9150 7845//7845 -f 7845//7845 9150//9150 9149//9149 -f 7845//7845 9149//9149 7847//7847 -f 7847//7847 9149//9149 9148//9148 -f 7847//7847 9148//9148 7849//7849 -f 7849//7849 9148//9148 9147//9147 -f 7849//7849 9147//9147 7851//7851 -f 7851//7851 9147//9147 9146//9146 -f 7851//7851 9146//9146 9145//9145 -f 7842//7842 7840//7840 9152//9152 -f 9152//9152 7840//7840 7838//7838 -f 9152//9152 7838//7838 9153//9153 -f 9153//9153 7838//7838 7837//7837 -f 9153//9153 7837//7837 9154//9154 -f 9154//9154 7837//7837 7832//7832 -f 9154//9154 7832//7832 9155//9155 -f 7832//7832 7834//7834 9155//9155 -f 9155//9155 7834//7834 7836//7836 -f 9155//9155 7836//7836 9156//9156 -f 9156//9156 7836//7836 8466//8466 -f 9156//9156 8466//8466 9157//9157 -f 8466//8466 8468//8468 9157//9157 -f 9157//9157 8468//8468 8470//8470 -f 9157//9157 8470//8470 9158//9158 -f 9158//9158 8470//8470 8465//8465 -f 9158//9158 8465//8465 9159//9159 -f 9159//9159 8465//8465 8463//8463 -f 9159//9159 8463//8463 9160//9160 -f 9160//9160 8463//8463 8462//8462 -f 9160//9160 8462//8462 9161//9161 -f 9161//9161 8462//8462 8460//8460 -f 9161//9161 8460//8460 9162//9162 -f 9162//9162 8460//8460 8458//8458 -f 9162//9162 8458//8458 9163//9163 -f 9163//9163 8458//8458 8456//8456 -f 9163//9163 8456//8456 9164//9164 -f 9164//9164 8456//8456 8440//8440 -f 9164//9164 8440//8440 9165//9165 -f 9165//9165 8440//8440 8454//8454 -f 9165//9165 8454//8454 9166//9166 -f 8454//8454 8453//8453 9166//9166 -f 9166//9166 8453//8453 8451//8451 -f 9166//9166 8451//8451 9167//9167 -f 9167//9167 8451//8451 8449//8449 -f 9167//9167 8449//8449 9168//9168 -f 9168//9168 8449//8449 8448//8448 -f 9168//9168 8448//8448 9169//9169 -f 9169//9169 8448//8448 8446//8446 -f 9169//9169 8446//8446 9170//9170 -f 9170//9170 8446//8446 8444//8444 -f 9170//9170 8444//8444 9171//9171 -f 9171//9171 8444//8444 8442//8442 -f 9171//9171 8442//8442 9172//9172 -f 9172//9172 8442//8442 7817//7817 -f 9172//9172 7817//7817 9173//9173 -f 9173//9173 7817//7817 7819//7819 -f 9173//9173 7819//7819 9174//9174 -f 9174//9174 7819//7819 7821//7821 -f 9174//9174 7821//7821 9175//9175 -f 9175//9175 7821//7821 7824//7824 -f 9175//9175 7824//7824 9176//9176 -f 9176//9176 7824//7824 7810//7810 -f 7803//7803 9181//9181 9180//9180 -f 7803//7803 9180//9180 7814//7814 -f 7814//7814 9180//9180 9179//9179 -f 7814//7814 9179//9179 7812//7812 -f 7812//7812 9179//9179 9178//9178 -f 7812//7812 9178//9178 7810//7810 -f 7810//7810 9178//9178 9177//9177 -f 7810//7810 9177//9177 9176//9176 -f 9181//9181 7803//7803 9182//9182 -f 9182//9182 7803//7803 7802//7802 -f 9182//9182 7802//7802 9183//9183 -f 7802//7802 7795//7795 9183//9183 -f 9183//9183 7795//7795 7797//7797 -f 9183//9183 7797//7797 9184//9184 -f 9184//9184 7797//7797 7799//7799 -f 9184//9184 7799//7799 9185//9185 -f 9185//9185 7799//7799 7790//7790 -f 9185//9185 7790//7790 9186//9186 -f 7790//7790 7789//7789 9186//9186 -f 9186//9186 7789//7789 7792//7792 -f 9186//9186 7792//7792 9187//9187 -f 8434//8434 9188//9188 8436//8436 -f 8436//8436 9188//9188 9187//9187 -f 8436//8436 9187//9187 8437//8437 -f 8437//8437 9187//9187 7792//7792 -f 8434//8434 8432//8432 9188//9188 -f 9188//9188 8432//8432 8431//8431 -f 9188//9188 8431//8431 9191//9191 -f 8431//8431 8429//8429 9191//9191 -f 9191//9191 8429//8429 8427//8427 -f 9191//9191 8427//8427 9190//9190 -f 9190//9190 8427//8427 8425//8425 -f 9190//9190 8425//8425 9189//9189 -f 9189//9189 8425//8425 8423//8423 -f 9189//9189 8423//8423 9193//9193 -f 9193//9193 8423//8423 8421//8421 -f 9193//9193 8421//8421 9192//9192 -f 9192//9192 8421//8421 8419//8419 -f 9192//9192 8419//8419 9195//9195 -f 9195//9195 8419//8419 8416//8416 -f 9195//9195 8416//8416 9194//9194 -f 8416//8416 8414//8414 9194//9194 -f 9194//9194 8414//8414 8413//8413 -f 9194//9194 8413//8413 9197//9197 -f 9197//9197 8413//8413 8404//8404 -f 9197//9197 8404//8404 9196//9196 -f 8404//8404 8406//8406 9196//9196 -f 9196//9196 8406//8406 8408//8408 -f 9196//9196 8408//8408 9201//9201 -f 9201//9201 8408//8408 8410//8410 -f 9201//9201 8410//8410 9200//9200 -f 9200//9200 8410//8410 9199//9199 -f 9199//9199 8410//8410 7788//7788 -f 9199//9199 7788//7788 9198//9198 -f 9198//9198 7788//7788 7787//7787 -f 9198//9198 7787//7787 9204//9204 -f 9204//9204 7787//7787 7785//7785 -f 9204//9204 7785//7785 9203//9203 -f 7785//7785 7783//7783 9203//9203 -f 9203//9203 7783//7783 7781//7781 -f 9203//9203 7781//7781 9202//9202 -f 9202//9202 7781//7781 7779//7779 -f 9202//9202 7779//7779 9205//9205 -f 9205//9205 7779//7779 7777//7777 -f 9205//9205 7777//7777 9206//9206 -f 9206//9206 7777//7777 7754//7754 -f 9206//9206 7754//7754 9207//9207 -f 9207//9207 7754//7754 7775//7775 -f 9207//9207 7775//7775 9208//9208 -f 9208//9208 7775//7775 7774//7774 -f 9208//9208 7774//7774 9209//9209 -f 9209//9209 7774//7774 7771//7771 -f 9209//9209 7771//7771 9210//9210 -f 9210//9210 7771//7771 7769//7769 -f 9210//9210 7769//7769 9211//9211 -f 9211//9211 7769//7769 7768//7768 -f 9211//9211 7768//7768 9212//9212 -f 7768//7768 7766//7766 9212//9212 -f 9212//9212 7766//7766 7764//7764 -f 9212//9212 7764//7764 9213//9213 -f 7764//7764 7762//7762 9213//9213 -f 9213//9213 7762//7762 7760//7760 -f 9213//9213 7760//7760 9214//9214 -f 7760//7760 7758//7758 9214//9214 -f 9214//9214 7758//7758 7756//7756 -f 9214//9214 7756//7756 9215//9215 -f 9215//9215 7756//7756 8402//8402 -f 9215//9215 8402//8402 9216//9216 -f 9216//9216 8402//8402 8400//8400 -f 9216//9216 8400//8400 9217//9217 -f 9217//9217 8400//8400 8399//8399 -f 9217//9217 8399//8399 9218//9218 -f 9218//9218 8399//8399 8397//8397 -f 9218//9218 8397//8397 9219//9219 -f 8397//8397 8395//8395 9219//9219 -f 9219//9219 8395//8395 8394//8394 -f 9219//9219 8394//8394 9220//9220 -f 9220//9220 8394//8394 8392//8392 -f 9220//9220 8392//8392 9221//9221 -f 9221//9221 8392//8392 8390//8390 -f 9221//9221 8390//8390 9222//9222 -f 9222//9222 8390//8390 8388//8388 -f 9222//9222 8388//8388 9223//9223 -f 9223//9223 8388//8388 8385//8385 -f 9223//9223 8385//8385 9224//9224 -f 9224//9224 8385//8385 8379//8379 -f 9224//9224 8379//8379 9225//9225 -f 9225//9225 8379//8379 8377//8377 -f 9225//9225 8377//8377 9226//9226 -f 9226//9226 8377//8377 8383//8383 -f 9226//9226 8383//8383 9227//9227 -f 9227//9227 8383//8383 8382//8382 -f 9227//9227 8382//8382 9228//9228 -f 9228//9228 8382//8382 8373//8373 -f 9228//9228 8373//8373 9233//9233 -f 9233//9233 8373//8373 8371//8371 -f 9233//9233 8371//8371 9232//9232 -f 9232//9232 8371//8371 8369//8369 -f 9232//9232 8369//8369 9231//9231 -f 9231//9231 8369//8369 7745//7745 -f 9231//9231 7745//7745 9230//9230 -f 7745//7745 7747//7747 9230//9230 -f 9230//9230 7747//7747 7749//7749 -f 9230//9230 7749//7749 9229//9229 -f 9229//9229 7749//7749 7741//7741 -f 9229//9229 7741//7741 9237//9237 -f 9237//9237 7741//7741 9236//9236 -f 7741//7741 7743//7743 9236//9236 -f 9236//9236 7743//7743 7744//7744 -f 9236//9236 7744//7744 9235//9235 -f 9235//9235 7744//7744 7739//7739 -f 9235//9235 7739//7739 9234//9234 -f 9234//9234 7739//7739 7738//7738 -f 9234//9234 7738//7738 9238//9238 -f 9238//9238 7738//7738 7735//7735 -f 9238//9238 7735//7735 9239//9239 -f 9239//9239 7735//7735 7716//7716 -f 9239//9239 7716//7716 9124//9124 -f 8536//8536 8535//8535 9247//9247 -f 9248//9248 9249//9249 7983//7983 -f 7983//7983 9249//9249 9250//9250 -f 7983//7983 9250//9250 7981//7981 -f 7981//7981 9250//9250 9251//9251 -f 7981//7981 9251//9251 8620//8620 -f 8620//8620 9251//9251 9252//9252 -f 8620//8620 9252//9252 8618//8618 -f 8618//8618 9252//9252 9253//9253 -f 9254//9254 8614//8614 9253//9253 -f 9253//9253 8614//8614 8616//8616 -f 9253//9253 8616//8616 8618//8618 -f 9255//9255 8609//8609 9256//9256 -f 9256//9256 8609//8609 8608//8608 -f 9256//9256 8608//8608 9257//9257 -f 9257//9257 8608//8608 8606//8606 -f 9257//9257 8606//8606 9258//9258 -f 9258//9258 8606//8606 8605//8605 -f 9258//9258 8605//8605 9254//9254 -f 9254//9254 8605//8605 8612//8612 -f 9254//9254 8612//8612 8614//8614 -f 9259//9259 8590//8590 9260//9260 -f 9260//9260 8590//8590 8592//8592 -f 9260//9260 8592//8592 9261//9261 -f 9261//9261 8592//8592 8594//8594 -f 9261//9261 8594//8594 9262//9262 -f 9262//9262 8594//8594 8597//8597 -f 9262//9262 8597//8597 9263//9263 -f 9263//9263 8597//8597 8599//8599 -f 9263//9263 8599//8599 9264//9264 -f 9264//9264 8599//8599 8600//8600 -f 9264//9264 8600//8600 9255//9255 -f 9255//9255 8600//8600 8602//8602 -f 9255//9255 8602//8602 8609//8609 -f 7980//7980 7979//7979 9265//9265 -f 9265//9265 7979//7979 7977//7977 -f 9265//9265 7977//7977 9259//9259 -f 9259//9259 7977//7977 8588//8588 -f 9259//9259 8588//8588 8590//8590 -f 7980//7980 9265//9265 7974//7974 -f 7974//7974 9265//9265 9266//9266 -f 7974//7974 9266//9266 7975//7975 -f 9267//9267 7963//7963 9266//9266 -f 9266//9266 7963//7963 7962//7962 -f 9266//9266 7962//7962 7975//7975 -f 9268//9268 7968//7968 9269//9269 -f 9269//9269 7968//7968 7967//7967 -f 9269//9269 7967//7967 9267//9267 -f 9267//9267 7967//7967 7965//7965 -f 9267//9267 7965//7965 7963//7963 -f 7961//7961 7960//7960 9270//9270 -f 9270//9270 7960//7960 7959//7959 -f 9270//9270 7959//7959 9271//9271 -f 9271//9271 7959//7959 7958//7958 -f 9271//9271 7958//7958 9272//9272 -f 9272//9272 7958//7958 7971//7971 -f 9272//9272 7971//7971 9268//9268 -f 9268//9268 7971//7971 7970//7970 -f 9268//9268 7970//7970 7968//7968 -f 7961//7961 9270//9270 7950//7950 -f 7950//7950 9270//9270 9273//9273 -f 7950//7950 9273//9273 7951//7951 -f 7951//7951 9273//9273 9274//9274 -f 7951//7951 9274//9274 7952//7952 -f 7952//7952 9274//9274 9275//9275 -f 7952//7952 9275//9275 7954//7954 -f 7954//7954 9275//9275 9276//9276 -f 7954//7954 9276//9276 7955//7955 -f 7955//7955 9276//9276 7944//7944 -f 7944//7944 9276//9276 9277//9277 -f 7944//7944 9277//9277 7946//7946 -f 7946//7946 9277//9277 7947//7947 -f 7947//7947 9277//9277 9278//9278 -f 7947//7947 9278//9278 8585//8585 -f 8585//8585 9278//9278 8571//8571 -f 8571//8571 9278//9278 9279//9279 -f 8571//8571 9279//9279 8572//8572 -f 8572//8572 9279//9279 9280//9280 -f 8572//8572 9280//9280 8574//8574 -f 8574//8574 9280//9280 9281//9281 -f 8574//8574 9281//9281 8575//8575 -f 8575//8575 9281//9281 9282//9282 -f 8575//8575 9282//9282 8577//8577 -f 8577//8577 9282//9282 8579//8579 -f 8579//8579 9282//9282 9283//9283 -f 8579//8579 9283//9283 8581//8581 -f 8581//8581 9283//9283 9284//9284 -f 8581//8581 9284//9284 8583//8583 -f 8583//8583 9284//9284 9285//9285 -f 8583//8583 9285//9285 8584//8584 -f 8584//8584 9285//9285 8568//8568 -f 8568//8568 9285//9285 9286//9286 -f 8568//8568 9286//9286 8569//8569 -f 8569//8569 9286//9286 9287//9287 -f 8569//8569 9287//9287 8564//8564 -f 8564//8564 9287//9287 9288//9288 -f 8564//8564 9288//9288 8562//8562 -f 8562//8562 9288//9288 9289//9289 -f 8562//8562 9289//9289 8560//8560 -f 9290//9290 8556//8556 9289//9289 -f 9289//9289 8556//8556 8558//8558 -f 9289//9289 8558//8558 8560//8560 -f 9291//9291 7937//7937 9292//9292 -f 9292//9292 7937//7937 7939//7939 -f 9292//9292 7939//7939 9293//9293 -f 9293//9293 7939//7939 8551//8551 -f 9293//9293 8551//8551 9294//9294 -f 9294//9294 8551//8551 8553//8553 -f 9294//9294 8553//8553 9290//9290 -f 9290//9290 8553//8553 8554//8554 -f 9290//9290 8554//8554 8556//8556 -f 9295//9295 7928//7928 9296//9296 -f 9296//9296 7928//7928 7930//7930 -f 9296//9296 7930//7930 9297//9297 -f 9297//9297 7930//7930 7932//7932 -f 9297//9297 7932//7932 9298//9298 -f 9298//9298 7932//7932 7934//7934 -f 9298//9298 7934//7934 9291//9291 -f 9291//9291 7934//7934 7935//7935 -f 9291//9291 7935//7935 7937//7937 -f 9299//9299 7905//7905 9295//9295 -f 9295//9295 7905//7905 7904//7904 -f 9295//9295 7904//7904 7928//7928 -f 9300//9300 7923//7923 9299//9299 -f 9299//9299 7923//7923 7925//7925 -f 9299//9299 7925//7925 7905//7905 -f 9301//9301 7909//7909 9300//9300 -f 9300//9300 7909//7909 7908//7908 -f 9300//9300 7908//7908 7923//7923 -f 9302//9302 8543//8543 9303//9303 -f 9303//9303 8543//8543 8541//8541 -f 9303//9303 8541//8541 9304//9304 -f 9304//9304 8541//8541 7910//7910 -f 9304//9304 7910//7910 9305//9305 -f 9305//9305 7910//7910 7912//7912 -f 9305//9305 7912//7912 9306//9306 -f 9306//9306 7912//7912 7914//7914 -f 9306//9306 7914//7914 9307//9307 -f 9307//9307 7914//7914 7916//7916 -f 9307//9307 7916//7916 9308//9308 -f 9308//9308 7916//7916 7918//7918 -f 9308//9308 7918//7918 9301//9301 -f 9301//9301 7918//7918 7920//7920 -f 9301//9301 7920//7920 7909//7909 -f 8535//8535 8533//8533 9247//9247 -f 9247//9247 8533//8533 8531//8531 -f 9247//9247 8531//8531 9309//9309 -f 9309//9309 8531//8531 8550//8550 -f 9309//9309 8550//8550 9310//9310 -f 9310//9310 8550//8550 8549//8549 -f 9310//9310 8549//8549 9311//9311 -f 9311//9311 8549//8549 8547//8547 -f 9311//9311 8547//8547 9302//9302 -f 9302//9302 8547//8547 8545//8545 -f 9302//9302 8545//8545 8543//8543 -f 8536//8536 9247//9247 8538//8538 -f 8538//8538 9247//9247 9312//9312 -f 8538//8538 9312//9312 8539//8539 -f 8539//8539 9312//9312 8527//8527 -f 8527//8527 9312//9312 9313//9313 -f 8527//8527 9313//9313 8528//8528 -f 8528//8528 9313//9313 8520//8520 -f 8520//8520 9313//9313 9314//9314 -f 8520//8520 9314//9314 8522//8522 -f 8522//8522 9314//9314 8524//8524 -f 8524//8524 9314//9314 9315//9315 -f 8524//8524 9315//9315 8525//8525 -f 8525//8525 9315//9315 9316//9316 -f 8525//8525 9316//9316 8514//8514 -f 8514//8514 9316//9316 8516//8516 -f 8516//8516 9316//9316 9317//9317 -f 8516//8516 9317//9317 8518//8518 -f 8518//8518 9317//9317 9318//9318 -f 8518//8518 9318//9318 8512//8512 -f 8512//8512 9318//9318 9319//9319 -f 8512//8512 9319//9319 8510//8510 -f 8510//8510 9319//9319 9320//9320 -f 8510//8510 9320//9320 7903//7903 -f 7903//7903 9320//9320 7901//7901 -f 7901//7901 9320//9320 9321//9321 -f 7901//7901 9321//9321 7898//7898 -f 7898//7898 9321//9321 9322//9322 -f 7898//7898 9322//9322 7897//7897 -f 7897//7897 9322//9322 7895//7895 -f 7895//7895 9322//9322 9323//9323 -f 7895//7895 9323//9323 7893//7893 -f 9324//9324 7883//7883 9325//9325 -f 9325//9325 7883//7883 7881//7881 -f 9325//9325 7881//7881 9326//9326 -f 9326//9326 7881//7881 7879//7879 -f 9326//9326 7879//7879 9327//9327 -f 9327//9327 7879//7879 7878//7878 -f 9327//9327 7878//7878 9323//9323 -f 9323//9323 7878//7878 7891//7891 -f 9323//9323 7891//7891 7893//7893 -f 7872//7872 7874//7874 9328//9328 -f 9328//9328 7874//7874 7876//7876 -f 9328//9328 7876//7876 9329//9329 -f 9329//9329 7876//7876 7877//7877 -f 9329//9329 7877//7877 9330//9330 -f 9330//9330 7877//7877 7868//7868 -f 9330//9330 7868//7868 9331//9331 -f 9331//9331 7868//7868 7866//7866 -f 9331//9331 7866//7866 9332//9332 -f 9332//9332 7866//7866 7888//7888 -f 9332//9332 7888//7888 9333//9333 -f 9333//9333 7888//7888 7887//7887 -f 9333//9333 7887//7887 9324//9324 -f 9324//9324 7887//7887 7885//7885 -f 9324//9324 7885//7885 7883//7883 -f 7872//7872 9328//9328 7870//7870 -f 7870//7870 9328//9328 9334//9334 -f 7870//7870 9334//9334 8498//8498 -f 8498//8498 9334//9334 8500//8500 -f 8500//8500 9334//9334 9335//9335 -f 8500//8500 9335//9335 8502//8502 -f 8502//8502 9335//9335 8504//8504 -f 8504//8504 9335//9335 9336//9336 -f 8504//8504 9336//9336 8506//8506 -f 8506//8506 9336//9336 9337//9337 -f 8506//8506 9337//9337 8508//8508 -f 8508//8508 9337//9337 8509//8509 -f 8509//8509 9337//9337 9338//9338 -f 8509//8509 9338//9338 8496//8496 -f 8496//8496 9338//9338 9339//9339 -f 8496//8496 9339//9339 8493//8493 -f 8493//8493 9339//9339 9340//9340 -f 8493//8493 9340//9340 8491//8491 -f 8491//8491 9340//9340 9341//9341 -f 8491//8491 9341//9341 8489//8489 -f 8489//8489 9341//9341 8487//8487 -f 8487//8487 9341//9341 9342//9342 -f 8487//8487 9342//9342 8486//8486 -f 8486//8486 9342//9342 9343//9343 -f 8486//8486 9343//9343 8484//8484 -f 8484//8484 9343//9343 9344//9344 -f 8484//8484 9344//9344 8482//8482 -f 8482//8482 9344//9344 9345//9345 -f 8482//8482 9345//9345 8480//8480 -f 8480//8480 9345//9345 9346//9346 -f 8480//8480 9346//9346 8473//8473 -f 8473//8473 9346//9346 9347//9347 -f 8473//8473 9347//9347 8474//8474 -f 8474//8474 9347//9347 8476//8476 -f 8476//8476 9347//9347 9348//9348 -f 8476//8476 9348//9348 7861//7861 -f 7861//7861 9348//9348 9349//9349 -f 7861//7861 9349//9349 7862//7862 -f 7862//7862 9349//9349 7863//7863 -f 7863//7863 9349//9349 9350//9350 -f 7863//7863 9350//9350 7864//7864 -f 7864//7864 9350//9350 7829//7829 -f 7829//7829 9350//9350 9351//9351 -f 7829//7829 9351//9351 7856//7856 -f 7856//7856 9351//9351 7855//7855 -f 7855//7855 9351//9351 9352//9352 -f 7855//7855 9352//9352 7854//7854 -f 7854//7854 9352//9352 9353//9353 -f 7854//7854 9353//9353 7852//7852 -f 7852//7852 9353//9353 9354//9354 -f 7852//7852 9354//9354 7850//7850 -f 7850//7850 9354//9354 9246//9246 -f 7850//7850 9246//9246 7848//7848 -f 7983//7983 7985//7985 9248//9248 -f 9248//9248 7985//7985 7987//7987 -f 9248//9248 7987//7987 9355//9355 -f 9355//9355 7987//7987 7989//7989 -f 9355//9355 7989//7989 9356//9356 -f 9356//9356 7989//7989 7992//7992 -f 9356//9356 7992//7992 9357//9357 -f 9357//9357 7992//7992 7994//7994 -f 9357//9357 7994//7994 9358//9358 -f 9358//9358 7994//7994 7995//7995 -f 9358//9358 7995//7995 9359//9359 -f 7995//7995 7998//7998 9359//9359 -f 9359//9359 7998//7998 8000//8000 -f 9359//9359 8000//8000 9360//9360 -f 9360//9360 8022//8022 8025//8025 -f 9360//9360 8025//8025 9359//9359 -f 9359//9359 8025//8025 8027//8027 -f 9359//9359 8027//8027 9358//9358 -f 9358//9358 8027//8027 9357//9357 -f 9357//9357 8027//8027 8029//8029 -f 9357//9357 8029//8029 9356//9356 -f 9356//9356 8029//8029 8031//8031 -f 9356//9356 8031//8031 9355//9355 -f 9355//9355 8031//8031 8033//8033 -f 9355//9355 8033//8033 9248//9248 -f 9248//9248 8033//8033 8035//8035 -f 9248//9248 8035//8035 9249//9249 -f 9249//9249 8035//8035 8037//8037 -f 9249//9249 8037//8037 9250//9250 -f 9250//9250 8037//8037 9251//9251 -f 9251//9251 8037//8037 8655//8655 -f 9251//9251 8655//8655 9252//9252 -f 8655//8655 8653//8653 9252//9252 -f 9252//9252 8653//8653 8651//8651 -f 9252//9252 8651//8651 9253//9253 -f 8651//8651 8649//8649 9253//9253 -f 9253//9253 8649//8649 8648//8648 -f 9253//9253 8648//8648 9254//9254 -f 8648//8648 8646//8646 9254//9254 -f 9254//9254 8646//8646 8644//8644 -f 9254//9254 8644//8644 9258//9258 -f 9258//9258 8644//8644 8643//8643 -f 9258//9258 8643//8643 9257//9257 -f 9257//9257 8643//8643 8640//8640 -f 9257//9257 8640//8640 9256//9256 -f 9256//9256 8640//8640 8638//8638 -f 9256//9256 8638//8638 9255//9255 -f 9255//9255 8638//8638 8637//8637 -f 9255//9255 8637//8637 9264//9264 -f 9264//9264 8637//8637 8634//8634 -f 9264//9264 8634//8634 9263//9263 -f 9263//9263 8634//8634 8632//8632 -f 9263//9263 8632//8632 9262//9262 -f 8623//8623 9259//9259 8625//8625 -f 8625//8625 9259//9259 9260//9260 -f 8625//8625 9260//9260 8627//8627 -f 8627//8627 9260//9260 9261//9261 -f 8627//8627 9261//9261 8629//8629 -f 8629//8629 9261//9261 9262//9262 -f 8629//8629 9262//9262 8630//8630 -f 8630//8630 9262//9262 8632//8632 -f 8623//8623 8013//8013 9259//9259 -f 9259//9259 8013//8013 8012//8012 -f 9259//9259 8012//8012 9265//9265 -f 8012//8012 8016//8016 9265//9265 -f 9265//9265 8016//8016 8015//8015 -f 9265//9265 8015//8015 9266//9266 -f 8015//8015 8010//8010 9266//9266 -f 9266//9266 8010//8010 8008//8008 -f 9266//9266 8008//8008 9267//9267 -f 9267//9267 8008//8008 8005//8005 -f 9267//9267 8005//8005 9269//9269 -f 9269//9269 8005//8005 8003//8003 -f 9275//9275 9274//9274 7993//7993 -f 7993//7993 9274//9274 7996//7996 -f 7996//7996 9274//9274 9273//9273 -f 7996//7996 9273//9273 7997//7997 -f 7997//7997 9273//9273 9270//9270 -f 7997//7997 9270//9270 7999//7999 -f 7999//7999 9270//9270 9271//9271 -f 7999//7999 9271//9271 8001//8001 -f 8001//8001 9271//9271 9272//9272 -f 8001//8001 9272//9272 8003//8003 -f 8003//8003 9272//9272 9268//9268 -f 8003//8003 9268//9268 9269//9269 -f 7993//7993 7991//7991 9275//9275 -f 9275//9275 7991//7991 7990//7990 -f 9275//9275 7990//7990 9276//9276 -f 7990//7990 7988//7988 9276//9276 -f 9276//9276 7988//7988 7986//7986 -f 9276//9276 7986//7986 9277//9277 -f 7986//7986 7984//7984 9277//9277 -f 9277//9277 7984//7984 7982//7982 -f 9277//9277 7982//7982 9278//9278 -f 8598//8598 9289//9289 8601//8601 -f 8601//8601 9289//9289 9288//9288 -f 8601//8601 9288//9288 8603//8603 -f 8603//8603 9288//9288 9287//9287 -f 8603//8603 9287//9287 8604//8604 -f 8604//8604 9287//9287 9286//9286 -f 8604//8604 9286//9286 8607//8607 -f 8607//8607 9286//9286 9285//9285 -f 8607//8607 9285//9285 8610//8610 -f 8610//8610 9285//9285 9284//9284 -f 8610//8610 9284//9284 8611//8611 -f 8611//8611 9284//9284 9283//9283 -f 8611//8611 9283//9283 8613//8613 -f 8613//8613 9283//9283 9282//9282 -f 8613//8613 9282//9282 8615//8615 -f 8615//8615 9282//9282 9281//9281 -f 8615//8615 9281//9281 8617//8617 -f 8617//8617 9281//9281 9280//9280 -f 8617//8617 9280//9280 8619//8619 -f 8619//8619 9280//9280 9279//9279 -f 8619//8619 9279//9279 8622//8622 -f 8622//8622 9279//9279 9278//9278 -f 8622//8622 9278//9278 8621//8621 -f 8621//8621 9278//9278 7982//7982 -f 8598//8598 8596//8596 9289//9289 -f 9289//9289 8596//8596 8595//8595 -f 9289//9289 8595//8595 9290//9290 -f 8595//8595 8593//8593 9290//9290 -f 9290//9290 8593//8593 8591//8591 -f 9290//9290 8591//8591 9294//9294 -f 9294//9294 8591//8591 8589//8589 -f 9294//9294 8589//8589 9293//9293 -f 9293//9293 8589//8589 7976//7976 -f 9293//9293 7976//7976 9292//9292 -f 9292//9292 7976//7976 7978//7978 -f 9292//9292 7978//7978 9291//9291 -f 9291//9291 7978//7978 7973//7973 -f 9291//9291 7973//7973 9298//9298 -f 9298//9298 7973//7973 7972//7972 -f 9298//9298 7972//7972 9297//9297 -f 9297//9297 7972//7972 7964//7964 -f 9297//9297 7964//7964 9296//9296 -f 9296//9296 7964//7964 7966//7966 -f 9296//9296 7966//7966 9295//9295 -f 9295//9295 7966//7966 7969//7969 -f 9295//9295 7969//7969 9299//9299 -f 7969//7969 7957//7957 9299//9299 -f 9299//9299 7957//7957 7956//7956 -f 9299//9299 7956//7956 9300//9300 -f 9308//9308 9301//9301 7948//7948 -f 7948//7948 9301//9301 9300//9300 -f 7948//7948 9300//9300 7949//7949 -f 7949//7949 9300//9300 7956//7956 -f 9308//9308 7948//7948 9307//9307 -f 9307//9307 7948//7948 7953//7953 -f 9307//9307 7953//7953 9306//9306 -f 9306//9306 7953//7953 7943//7943 -f 9306//9306 7943//7943 9305//9305 -f 9305//9305 7943//7943 7942//7942 -f 9305//9305 7942//7942 9304//9304 -f 9304//9304 7942//7942 7945//7945 -f 9304//9304 7945//7945 9303//9303 -f 7945//7945 8587//8587 9303//9303 -f 9303//9303 8587//8587 8586//8586 -f 9303//9303 8586//8586 9302//9302 -f 9302//9302 8586//8586 8570//8570 -f 9302//9302 8570//8570 9311//9311 -f 9311//9311 8570//8570 8573//8573 -f 9311//9311 8573//8573 9310//9310 -f 9310//9310 8573//8573 8576//8576 -f 9310//9310 8576//8576 9309//9309 -f 9309//9309 8576//8576 8578//8578 -f 9309//9309 8578//8578 9247//9247 -f 8578//8578 8580//8580 9247//9247 -f 9247//9247 8580//8580 8582//8582 -f 9247//9247 8582//8582 9312//9312 -f 8582//8582 8567//8567 9312//9312 -f 9312//9312 8567//8567 8563//8563 -f 9312//9312 8563//8563 9313//9313 -f 9313//9313 8563//8563 9314//9314 -f 9314//9314 8563//8563 8565//8565 -f 9314//9314 8565//8565 9315//9315 -f 8565//8565 8566//8566 9315//9315 -f 9315//9315 8566//8566 8561//8561 -f 9315//9315 8561//8561 9316//9316 -f 9316//9316 8561//8561 8559//8559 -f 9316//9316 8559//8559 9317//9317 -f 8559//8559 8557//8557 9317//9317 -f 9317//9317 8557//8557 8555//8555 -f 9317//9317 8555//8555 9318//9318 -f 9318//9318 8555//8555 8552//8552 -f 9318//9318 8552//8552 9319//9319 -f 9319//9319 8552//8552 7941//7941 -f 9319//9319 7941//7941 9320//9320 -f 9320//9320 7941//7941 7940//7940 -f 9320//9320 7940//7940 9321//9321 -f 9321//9321 7940//7940 7938//7938 -f 9321//9321 7938//7938 9322//9322 -f 7938//7938 7936//7936 9322//9322 -f 9322//9322 7936//7936 7933//7933 -f 9322//9322 7933//7933 9323//9323 -f 9323//9323 7933//7933 7931//7931 -f 9323//9323 7931//7931 7929//7929 -f 7922//7922 9331//9331 7907//7907 -f 7907//7907 9331//9331 9332//9332 -f 7907//7907 9332//9332 7924//7924 -f 7924//7924 9332//9332 9333//9333 -f 7924//7924 9333//9333 7926//7926 -f 7926//7926 9333//9333 9324//9324 -f 7926//7926 9324//9324 7927//7927 -f 7927//7927 9324//9324 9325//9325 -f 7927//7927 9325//9325 7906//7906 -f 7906//7906 9325//9325 9326//9326 -f 7906//7906 9326//9326 7929//7929 -f 7929//7929 9326//9326 9327//9327 -f 7929//7929 9327//9327 9323//9323 -f 7922//7922 7921//7921 9331//9331 -f 9331//9331 7921//7921 7919//7919 -f 9331//9331 7919//7919 9330//9330 -f 9330//9330 7919//7919 7917//7917 -f 9330//9330 7917//7917 9329//9329 -f 9329//9329 7917//7917 7915//7915 -f 9329//9329 7915//7915 9328//9328 -f 7915//7915 7913//7913 9328//9328 -f 9328//9328 7913//7913 7911//7911 -f 9328//9328 7911//7911 9334//9334 -f 7911//7911 8540//8540 9334//9334 -f 9334//9334 8540//8540 8542//8542 -f 9334//9334 8542//8542 9335//9335 -f 8542//8542 8544//8544 9335//9335 -f 9335//9335 8544//8544 8546//8546 -f 9335//9335 8546//8546 9336//9336 -f 8546//8546 8548//8548 9336//9336 -f 9336//9336 8548//8548 8530//8530 -f 9336//9336 8530//8530 9337//9337 -f 9337//9337 8530//8530 8529//8529 -f 9337//9337 8529//8529 9338//9338 -f 9338//9338 8529//8529 8532//8532 -f 9338//9338 8532//8532 9339//9339 -f 9339//9339 8532//8532 8534//8534 -f 9339//9339 8534//8534 9340//9340 -f 8534//8534 8537//8537 9340//9340 -f 9340//9340 8537//8537 8526//8526 -f 9340//9340 8526//8526 9341//9341 -f 9341//9341 8526//8526 8519//8519 -f 9341//9341 8519//8519 9342//9342 -f 9342//9342 8519//8519 9343//9343 -f 9343//9343 8519//8519 8521//8521 -f 9343//9343 8521//8521 9344//9344 -f 8521//8521 8523//8523 9344//9344 -f 9344//9344 8523//8523 8513//8513 -f 9344//9344 8513//8513 9345//9345 -f 9345//9345 8513//8513 8515//8515 -f 9345//9345 8515//8515 9346//9346 -f 9346//9346 8515//8515 9347//9347 -f 9347//9347 8515//8515 8517//8517 -f 9347//9347 8517//8517 9348//9348 -f 8517//8517 8511//8511 9348//9348 -f 9348//9348 8511//8511 7902//7902 -f 9348//9348 7902//7902 9349//9349 -f 7902//7902 7900//7900 9349//9349 -f 9349//9349 7900//7900 7899//7899 -f 9349//9349 7899//7899 9350//9350 -f 7899//7899 7896//7896 9350//9350 -f 9350//9350 7896//7896 7894//7894 -f 9350//9350 7894//7894 9351//9351 -f 9351//9351 7894//7894 7892//7892 -f 9351//9351 7892//7892 9352//9352 -f 9352//9352 7892//7892 7890//7890 -f 9352//9352 7890//7890 9353//9353 -f 7890//7890 7889//7889 9353//9353 -f 9353//9353 7889//7889 7880//7880 -f 9353//9353 7880//7880 9354//9354 -f 7880//7880 7882//7882 9354//9354 -f 9354//9354 7882//7882 7884//7884 -f 9354//9354 7884//7884 9246//9246 -f 9361//9361 9362//9362 7346//7346 -f 7346//7346 9362//9362 7347//7347 -f 7347//7347 9362//9362 9363//9363 -f 7347//7347 9363//9363 7312//7312 -f 7312//7312 9363//9363 9364//9364 -f 7312//7312 9364//9364 7340//7340 -f 7340//7340 9364//9364 9365//9365 -f 7340//7340 9365//9365 7338//7338 -f 7338//7338 9365//9365 9366//9366 -f 7338//7338 9366//9366 7336//7336 -f 7336//7336 9366//9366 9367//9367 -f 7336//7336 9367//9367 7334//7334 -f 7334//7334 9367//9367 7332//7332 -f 7332//7332 9367//9367 9368//9368 -f 7332//7332 9368//9368 7330//7330 -f 7330//7330 9368//9368 9369//9369 -f 7330//7330 9369//9369 7327//7327 -f 7327//7327 9369//9369 9370//9370 -f 7327//7327 9370//9370 7325//7325 -f 9370//9370 9371//9371 7325//7325 -f 7325//7325 9371//9371 9372//9372 -f 7325//7325 9372//9372 7323//7323 -f 7323//7323 9372//9372 9373//9373 -f 7323//7323 9373//9373 7321//7321 -f 7321//7321 9373//9373 9374//9374 -f 7321//7321 9374//9374 7319//7319 -f 7319//7319 9374//9374 9375//9375 -f 9376//9376 7313//7313 9377//9377 -f 9377//9377 7313//7313 7315//7315 -f 9377//9377 7315//7315 9375//9375 -f 9375//9375 7315//7315 7317//7317 -f 9375//9375 7317//7317 7319//7319 -f 9378//9378 8685//8685 9379//9379 -f 9379//9379 8685//8685 8683//8683 -f 9379//9379 8683//8683 9380//9380 -f 9380//9380 8683//8683 8681//8681 -f 9380//9380 8681//8681 9381//9381 -f 9381//9381 8681//8681 8679//8679 -f 9381//9381 8679//8679 9382//9382 -f 9382//9382 8679//8679 8677//8677 -f 9382//9382 8677//8677 9376//9376 -f 9376//9376 8677//8677 8675//8675 -f 9376//9376 8675//8675 7313//7313 -f 9383//9383 8689//8689 9378//9378 -f 9378//9378 8689//8689 8687//8687 -f 9378//9378 8687//8687 8685//8685 -f 9383//9383 9384//9384 8689//8689 -f 8689//8689 9384//9384 9385//9385 -f 8689//8689 9385//9385 8673//8673 -f 8673//8673 9385//9385 9386//9386 -f 8673//8673 9386//9386 8672//8672 -f 8672//8672 9386//9386 9387//9387 -f 8672//8672 9387//9387 8670//8670 -f 8670//8670 9387//9387 9388//9388 -f 8670//8670 9388//9388 8668//8668 -f 9388//9388 9389//9389 8668//8668 -f 8668//8668 9389//9389 9390//9390 -f 8668//8668 9390//9390 8657//8657 -f 8657//8657 9390//9390 9391//9391 -f 8657//8657 9391//9391 8658//8658 -f 8658//8658 9391//9391 9392//9392 -f 8658//8658 9392//9392 8660//8660 -f 8660//8660 9392//9392 9393//9393 -f 8660//8660 9393//9393 8662//8662 -f 8662//8662 9393//9393 8664//8664 -f 9393//9393 9394//9394 8664//8664 -f 8664//8664 9394//9394 9395//9395 -f 8664//8664 9395//9395 8665//8665 -f 8665//8665 9395//9395 9396//9396 -f 8665//8665 9396//9396 8050//8050 -f 8050//8050 9396//9396 9397//9397 -f 8050//8050 9397//9397 8048//8048 -f 9397//9397 9398//9398 8048//8048 -f 8048//8048 9398//9398 9399//9399 -f 8048//8048 9399//9399 8046//8046 -f 8046//8046 9399//9399 9400//9400 -f 8046//8046 9400//9400 8044//8044 -f 8044//8044 9400//9400 9401//9401 -f 8044//8044 9401//9401 8042//8042 -f 9402//9402 8040//8040 9403//9403 -f 9403//9403 8040//8040 8042//8042 -f 9403//9403 8042//8042 9404//9404 -f 9404//9404 8042//8042 9401//9401 -f 9402//9402 9405//9405 8040//8040 -f 8040//8040 9405//9405 9406//9406 -f 8040//8040 9406//9406 8020//8020 -f 8020//8020 9406//9406 9407//9407 -f 8020//8020 9407//9407 8021//8021 -f 8021//8021 9407//9407 9408//9408 -f 8021//8021 9408//9408 8023//8023 -f 8023//8023 9408//9408 9409//9409 -f 8023//8023 9409//9409 8024//8024 -f 9409//9409 9410//9410 8024//8024 -f 8024//8024 9410//9410 9411//9411 -f 8024//8024 9411//9411 8026//8026 -f 8026//8026 9411//9411 9412//9412 -f 8026//8026 9412//9412 8028//8028 -f 8028//8028 9412//9412 9413//9413 -f 8028//8028 9413//9413 8030//8030 -f 8030//8030 9413//9413 9414//9414 -f 8030//8030 9414//9414 8032//8032 -f 8032//8032 9414//9414 8034//8034 -f 8034//8034 9414//9414 9415//9415 -f 8034//8034 9415//9415 8039//8039 -f 8039//8039 9415//9415 9416//9416 -f 8039//8039 9416//9416 8038//8038 -f 8038//8038 9416//9416 9417//9417 -f 8038//8038 9417//9417 8036//8036 -f 8036//8036 9417//9417 8656//8656 -f 8656//8656 9417//9417 9418//9418 -f 8656//8656 9418//9418 8654//8654 -f 8654//8654 9418//9418 9419//9419 -f 8654//8654 9419//9419 8652//8652 -f 8652//8652 9419//9419 9420//9420 -f 8652//8652 9420//9420 8650//8650 -f 8650//8650 9420//9420 9421//9421 -f 8650//8650 9421//9421 8647//8647 -f 9421//9421 9422//9422 8647//8647 -f 8647//8647 9422//9422 9423//9423 -f 8647//8647 9423//9423 8645//8645 -f 8645//8645 9423//9423 9424//9424 -f 8645//8645 9424//9424 8642//8642 -f 9424//9424 9425//9425 8642//8642 -f 8642//8642 9425//9425 9426//9426 -f 8642//8642 9426//9426 8641//8641 -f 8641//8641 9426//9426 9427//9427 -f 8641//8641 9427//9427 8639//8639 -f 8639//8639 9427//9427 9428//9428 -f 8639//8639 9428//9428 8636//8636 -f 8636//8636 9428//9428 9429//9429 -f 8636//8636 9429//9429 8635//8635 -f 8635//8635 9429//9429 9430//9430 -f 8635//8635 9430//9430 8633//8633 -f 9430//9430 9431//9431 8633//8633 -f 8633//8633 9431//9431 9432//9432 -f 8633//8633 9432//9432 8631//8631 -f 9432//9432 9433//9433 8631//8631 -f 8631//8631 9433//9433 9434//9434 -f 8631//8631 9434//9434 8628//8628 -f 8628//8628 9434//9434 9435//9435 -f 8628//8628 9435//9435 8626//8626 -f 9435//9435 9436//9436 8626//8626 -f 8626//8626 9436//9436 9437//9437 -f 8626//8626 9437//9437 8624//8624 -f 8624//8624 9437//9437 9438//9438 -f 8624//8624 9438//9438 8014//8014 -f 9438//9438 9439//9439 8014//8014 -f 8014//8014 9439//9439 9440//9440 -f 8014//8014 9440//9440 8018//8018 -f 8018//8018 9440//9440 9441//9441 -f 8018//8018 9441//9441 8017//8017 -f 8017//8017 9441//9441 9442//9442 -f 8017//8017 9442//9442 8011//8011 -f 8011//8011 9442//9442 9443//9443 -f 8011//8011 9443//9443 8009//8009 -f 8009//8009 9443//9443 9444//9444 -f 8009//8009 9444//9444 8007//8007 -f 8007//8007 9444//9444 9445//9445 -f 8007//8007 9445//9445 8006//8006 -f 8006//8006 9445//9445 9446//9446 -f 8006//8006 9446//9446 8004//8004 -f 9446//9446 9447//9447 8004//8004 -f 8004//8004 9447//9447 9448//9448 -f 8004//8004 9448//9448 8002//8002 -f 8002//8002 9448//9448 9360//9360 -f 8002//8002 9360//9360 8000//8000 -f 7346//7346 7344//7344 9361//9361 -f 9361//9361 7344//7344 8712//8712 -f 9361//9361 8712//8712 9449//9449 -f 9449//9449 8712//8712 9450//9450 -f 9449//9449 9450//9450 9451//9451 -f 9451//9451 9450//9450 9452//9452 -f 9451//9451 9452//9452 9453//9453 -f 9453//9453 9452//9452 9454//9454 -f 9453//9453 9454//9454 9455//9455 -f 9455//9455 9454//9454 9456//9456 -f 9455//9455 9456//9456 9457//9457 -f 9457//9457 9456//9456 9458//9458 -f 9457//9457 9458//9458 9459//9459 -f 9459//9459 9458//9458 9460//9460 -f 9459//9459 9460//9460 9461//9461 -f 9461//9461 9460//9460 9462//9462 -f 9461//9461 9462//9462 9463//9463 -f 9453//9453 9455//9455 9464//9464 -f 8019//8019 8022//8022 9360//9360 -f 9360//9360 9448//9448 8019//8019 -f 8019//8019 9448//9448 9447//9447 -f 8019//8019 9447//9447 8041//8041 -f 9447//9447 9446//9446 8041//8041 -f 8041//8041 9446//9446 9445//9445 -f 8041//8041 9445//9445 8043//8043 -f 8043//8043 9445//9445 9444//9444 -f 8043//8043 9444//9444 8045//8045 -f 8045//8045 9444//9444 9443//9443 -f 8045//8045 9443//9443 8047//8047 -f 8047//8047 9443//9443 9442//9442 -f 8047//8047 9442//9442 8052//8052 -f 8052//8052 9442//9442 9441//9441 -f 8052//8052 9441//9441 8051//8051 -f 8051//8051 9441//9441 9440//9440 -f 8051//8051 9440//9440 8049//8049 -f 8049//8049 9440//9440 9439//9439 -f 9439//9439 9438//9438 8049//8049 -f 8049//8049 9438//9438 9437//9437 -f 8049//8049 9437//9437 8663//8663 -f 8663//8663 9437//9437 9436//9436 -f 8663//8663 9436//9436 8661//8661 -f 9436//9436 9435//9435 8661//8661 -f 8661//8661 9435//9435 9434//9434 -f 8661//8661 9434//9434 8659//8659 -f 8659//8659 9434//9434 9433//9433 -f 8659//8659 9433//9433 8666//8666 -f 8666//8666 9433//9433 9432//9432 -f 8666//8666 9432//9432 8667//8667 -f 8667//8667 9432//9432 9431//9431 -f 8667//8667 9431//9431 8669//8669 -f 8669//8669 9431//9431 9430//9430 -f 8669//8669 9430//9430 8671//8671 -f 9430//9430 9429//9429 8671//8671 -f 8671//8671 9429//9429 9428//9428 -f 8671//8671 9428//9428 8691//8691 -f 8691//8691 9428//9428 9427//9427 -f 8691//8691 9427//9427 8690//8690 -f 9427//9427 9426//9426 8690//8690 -f 8690//8690 9426//9426 9425//9425 -f 8690//8690 9425//9425 8688//8688 -f 8688//8688 9425//9425 9424//9424 -f 8688//8688 9424//9424 8686//8686 -f 8686//8686 9424//9424 9423//9423 -f 8686//8686 9423//9423 8684//8684 -f 8684//8684 9423//9423 9422//9422 -f 8684//8684 9422//9422 8682//8682 -f 8682//8682 9422//9422 9421//9421 -f 8682//8682 9421//9421 8680//8680 -f 8680//8680 9421//9421 9420//9420 -f 8680//8680 9420//9420 8678//8678 -f 8678//8678 9420//9420 9419//9419 -f 8678//8678 9419//9419 8676//8676 -f 8676//8676 9419//9419 9418//9418 -f 8676//8676 9418//9418 8674//8674 -f 8674//8674 9418//9418 9417//9417 -f 8674//8674 9417//9417 7314//7314 -f 7314//7314 9417//9417 9416//9416 -f 7314//7314 9416//9416 7316//7316 -f 7316//7316 9416//9416 9415//9415 -f 7316//7316 9415//9415 7318//7318 -f 7318//7318 9415//9415 9414//9414 -f 9413//9413 7322//7322 9414//9414 -f 9414//9414 7322//7322 7320//7320 -f 9414//9414 7320//7320 7318//7318 -f 7329//7329 7328//7328 9412//9412 -f 9412//9412 7328//7328 7326//7326 -f 9412//9412 7326//7326 9413//9413 -f 9413//9413 7326//7326 7324//7324 -f 9413//9413 7324//7324 7322//7322 -f 9412//9412 9411//9411 7329//7329 -f 7329//7329 9411//9411 9410//9410 -f 7329//7329 9410//9410 7331//7331 -f 9410//9410 9409//9409 7331//7331 -f 7331//7331 9409//9409 9408//9408 -f 7331//7331 9408//9408 7333//7333 -f 7333//7333 9408//9408 9407//9407 -f 7333//7333 9407//9407 7335//7335 -f 9403//9403 7339//7339 9402//9402 -f 9402//9402 7339//7339 7337//7337 -f 9402//9402 7337//7337 9405//9405 -f 9405//9405 7337//7337 7335//7335 -f 9405//9405 7335//7335 9406//9406 -f 9406//9406 7335//7335 9407//9407 -f 9403//9403 9404//9404 7339//7339 -f 7339//7339 9404//9404 9401//9401 -f 7339//7339 9401//9401 7341//7341 -f 7341//7341 9401//9401 9400//9400 -f 7341//7341 9400//9400 7310//7310 -f 7310//7310 9400//9400 9399//9399 -f 7310//7310 9399//9399 7311//7311 -f 7311//7311 9399//9399 9398//9398 -f 7311//7311 9398//9398 7345//7345 -f 7345//7345 9398//9398 9397//9397 -f 7345//7345 9397//9397 7342//7342 -f 7342//7342 9397//9397 9396//9396 -f 7342//7342 9396//9396 7343//7343 -f 7343//7343 9396//9396 8713//8713 -f 8713//8713 9396//9396 9395//9395 -f 8713//8713 9395//9395 8715//8715 -f 8715//8715 9395//9395 9394//9394 -f 8715//8715 9394//9394 8716//8716 -f 9394//9394 9393//9393 8716//8716 -f 8716//8716 9393//9393 9392//9392 -f 8716//8716 9392//9392 8719//8719 -f 8719//8719 9392//9392 9391//9391 -f 8719//8719 9391//9391 8720//8720 -f 9391//9391 9390//9390 8720//8720 -f 8720//8720 9390//9390 9389//9389 -f 8720//8720 9389//9389 8722//8722 -f 8722//8722 9389//9389 9388//9388 -f 8722//8722 9388//9388 8723//8723 -f 8723//8723 9388//9388 9465//9465 -f 9388//9388 9387//9387 9465//9465 -f 9465//9465 9387//9387 9386//9386 -f 9465//9465 9386//9386 9466//9466 -f 9466//9466 9386//9386 9385//9385 -f 9466//9466 9385//9385 9467//9467 -f 9467//9467 9385//9385 9384//9384 -f 9467//9467 9384//9384 9468//9468 -f 9384//9384 9383//9383 9468//9468 -f 9468//9468 9383//9383 9378//9378 -f 9468//9468 9378//9378 9469//9469 -f 9469//9469 9378//9378 9470//9470 -f 9470//9470 9378//9378 9379//9379 -f 9470//9470 9379//9379 9471//9471 -f 9471//9471 9379//9379 9472//9472 -f 9472//9472 9379//9379 9380//9380 -f 9472//9472 9380//9380 9473//9473 -f 9473//9473 9380//9380 9381//9381 -f 9473//9473 9381//9381 9474//9474 -f 9474//9474 9381//9381 9382//9382 -f 9474//9474 9382//9382 9475//9475 -f 9475//9475 9382//9382 9376//9376 -f 9475//9475 9376//9376 9476//9476 -f 9476//9476 9376//9376 9477//9477 -f 9477//9477 9376//9376 9377//9377 -f 9477//9477 9377//9377 9478//9478 -f 9478//9478 9377//9377 9375//9375 -f 9478//9478 9375//9375 9479//9479 -f 9479//9479 9375//9375 9374//9374 -f 9479//9479 9374//9374 9480//9480 -f 9480//9480 9374//9374 9481//9481 -f 9481//9481 9374//9374 9373//9373 -f 9481//9481 9373//9373 9482//9482 -f 9373//9373 9372//9372 9482//9482 -f 9482//9482 9372//9372 9371//9371 -f 9482//9482 9371//9371 9483//9483 -f 9371//9371 9370//9370 9483//9483 -f 9483//9483 9370//9370 9369//9369 -f 9483//9483 9369//9369 9484//9484 -f 9484//9484 9369//9369 9368//9368 -f 9484//9484 9368//9368 9485//9485 -f 9485//9485 9368//9368 9367//9367 -f 9485//9485 9367//9367 9486//9486 -f 9486//9486 9367//9367 9487//9487 -f 9487//9487 9367//9367 9366//9366 -f 9487//9487 9366//9366 9488//9488 -f 9488//9488 9366//9366 9365//9365 -f 9488//9488 9365//9365 9489//9489 -f 9489//9489 9365//9365 9364//9364 -f 9489//9489 9364//9364 9490//9490 -f 9490//9490 9364//9364 9363//9363 -f 9490//9490 9363//9363 9491//9491 -f 9491//9491 9363//9363 9362//9362 -f 9491//9491 9362//9362 9492//9492 -f 9362//9362 9361//9361 9492//9492 -f 9492//9492 9361//9361 9449//9449 -f 9492//9492 9449//9449 9464//9464 -f 9464//9464 9449//9449 9451//9451 -f 9464//9464 9451//9451 9453//9453 -f 9450//9450 8712//8712 8714//8714 -f 9490//9490 9491//9491 9493//9493 -f 9486//9486 9487//9487 9494//9494 -f 9494//9494 9487//9487 9488//9488 -f 9494//9494 9488//9488 9493//9493 -f 9493//9493 9488//9488 9489//9489 -f 9493//9493 9489//9489 9490//9490 -f 9486//9486 9494//9494 9485//9485 -f 9485//9485 9494//9494 9495//9495 -f 9485//9485 9495//9495 9484//9484 -f 9484//9484 9495//9495 9496//9496 -f 9484//9484 9496//9496 9483//9483 -f 9483//9483 9496//9496 9497//9497 -f 9483//9483 9497//9497 9482//9482 -f 9497//9497 9498//9498 9482//9482 -f 9482//9482 9498//9498 9499//9499 -f 9482//9482 9499//9499 9481//9481 -f 9481//9481 9499//9499 9500//9500 -f 9481//9481 9500//9500 9480//9480 -f 9480//9480 9500//9500 9479//9479 -f 9479//9479 9500//9500 9501//9501 -f 9479//9479 9501//9501 9478//9478 -f 9478//9478 9501//9501 9477//9477 -f 9477//9477 9501//9501 9502//9502 -f 9477//9477 9502//9502 9476//9476 -f 9476//9476 9502//9502 9475//9475 -f 9475//9475 9502//9502 9503//9503 -f 9475//9475 9503//9503 9474//9474 -f 9470//9470 9471//9471 9504//9504 -f 9504//9504 9471//9471 9472//9472 -f 9504//9504 9472//9472 9503//9503 -f 9503//9503 9472//9472 9473//9473 -f 9503//9503 9473//9473 9474//9474 -f 9505//9505 9468//9468 9504//9504 -f 9504//9504 9468//9468 9469//9469 -f 9504//9504 9469//9469 9470//9470 -f 8717//8717 8718//8718 9458//9458 -f 9458//9458 8718//8718 8721//8721 -f 9458//9458 8721//8721 9460//9460 -f 9460//9460 8721//8721 8723//8723 -f 9460//9460 8723//8723 9462//9462 -f 9462//9462 8723//8723 9465//9465 -f 9462//9462 9465//9465 9463//9463 -f 9463//9463 9465//9465 9466//9466 -f 9463//9463 9466//9466 9505//9505 -f 9505//9505 9466//9466 9467//9467 -f 9505//9505 9467//9467 9468//9468 -f 9458//9458 9456//9456 8717//8717 -f 8717//8717 9456//9456 9454//9454 -f 8717//8717 9454//9454 8714//8714 -f 8714//8714 9454//9454 9452//9452 -f 8714//8714 9452//9452 9450//9450 -f 9492//9492 9464//9464 9455//9455 -f 9498//9498 9455//9455 9499//9499 -f 9499//9499 9455//9455 9500//9500 -f 9500//9500 9455//9455 9501//9501 -f 9501//9501 9455//9455 9457//9457 -f 9501//9501 9457//9457 9459//9459 -f 9461//9461 9463//9463 9505//9505 -f 9505//9505 9504//9504 9503//9503 -f 9459//9459 9461//9461 9501//9501 -f 9501//9501 9461//9461 9505//9505 -f 9501//9501 9505//9505 9502//9502 -f 9502//9502 9505//9505 9503//9503 -f 9495//9495 9494//9494 9496//9496 -f 9496//9496 9494//9494 9493//9493 -f 9498//9498 9497//9497 9455//9455 -f 9455//9455 9497//9497 9496//9496 -f 9455//9455 9496//9496 9492//9492 -f 9492//9492 9496//9496 9493//9493 -f 9492//9492 9493//9493 9491//9491 -f 9506//9506 9507//9507 9508//9508 -f 9508//9508 9507//9507 9509//9509 -f 9510//9510 9511//9511 9512//9512 -f 9513//9513 9514//9514 9515//9515 -f 9515//9515 9514//9514 9516//9516 -f 9516//9516 9514//9514 9517//9517 -f 9516//9516 9517//9517 9518//9518 -f 9513//9513 9515//9515 9519//9519 -f 9519//9519 9515//9515 9520//9520 -f 9519//9519 9520//9520 9521//9521 -f 9521//9521 9520//9520 9522//9522 -f 9521//9521 9522//9522 9523//9523 -f 9523//9523 9522//9522 9524//9524 -f 9524//9524 9522//9522 9525//9525 -f 9524//9524 9525//9525 9526//9526 -f 9526//9526 9525//9525 9527//9527 -f 9527//9527 9525//9525 9528//9528 -f 9527//9527 9528//9528 9529//9529 -f 9529//9529 9528//9528 9530//9530 -f 9529//9529 9530//9530 9531//9531 -f 9512//9512 9511//9511 9530//9530 -f 9530//9530 9511//9511 9532//9532 -f 9530//9530 9532//9532 9531//9531 -f 9510//9510 9512//9512 9533//9533 -f 9533//9533 9512//9512 9534//9534 -f 9533//9533 9534//9534 9535//9535 -f 9535//9535 9534//9534 9536//9536 -f 9535//9535 9536//9536 9537//9537 -f 9537//9537 9536//9536 9538//9538 -f 9538//9538 9536//9536 9539//9539 -f 9538//9538 9539//9539 9540//9540 -f 9540//9540 9539//9539 9541//9541 -f 9540//9540 9541//9541 9542//9542 -f 9543//9543 9544//9544 9545//9545 -f 9545//9545 9544//9544 9546//9546 -f 9545//9545 9546//9546 9547//9547 -f 9547//9547 9546//9546 9548//9548 -f 9549//9549 9550//9550 9548//9548 -f 9548//9548 9550//9550 9551//9551 -f 9548//9548 9551//9551 9547//9547 -f 9552//9552 9553//9553 9554//9554 -f 9554//9554 9553//9553 9555//9555 -f 9554//9554 9555//9555 9556//9556 -f 9556//9556 9555//9555 9557//9557 -f 9556//9556 9557//9557 9549//9549 -f 9549//9549 9557//9557 9558//9558 -f 9549//9549 9558//9558 9550//9550 -f 9507//9507 9559//9559 9509//9509 -f 9509//9509 9559//9559 9560//9560 -f 9509//9509 9560//9560 9552//9552 -f 9552//9552 9560//9560 9561//9561 -f 9552//9552 9561//9561 9553//9553 -f 9506//9506 9508//9508 9562//9562 -f 9562//9562 9508//9508 9563//9563 -f 9562//9562 9563//9563 9564//9564 -f 9564//9564 9563//9563 9565//9565 -f 9564//9564 9565//9565 9566//9566 -f 9566//9566 9565//9565 9567//9567 -f 9567//9567 9565//9565 9568//9568 -f 9567//9567 9568//9568 9569//9569 -f 9570//9570 9568//9568 9571//9571 -f 9571//9571 9568//9568 9565//9565 -f 9571//9571 9565//9565 9572//9572 -f 9572//9572 9565//9565 9563//9563 -f 9572//9572 9563//9563 9573//9573 -f 9573//9573 9563//9563 9508//9508 -f 9573//9573 9508//9508 9574//9574 -f 9574//9574 9508//9508 9509//9509 -f 9574//9574 9509//9509 9575//9575 -f 9575//9575 9509//9509 9552//9552 -f 9575//9575 9552//9552 9576//9576 -f 9576//9576 9552//9552 9554//9554 -f 9576//9576 9554//9554 9577//9577 -f 9577//9577 9554//9554 9556//9556 -f 9577//9577 9556//9556 9578//9578 -f 9578//9578 9556//9556 9549//9549 -f 9578//9578 9549//9549 9579//9579 -f 9579//9579 9549//9549 9548//9548 -f 9579//9579 9548//9548 9580//9580 -f 9580//9580 9548//9548 9546//9546 -f 9580//9580 9546//9546 9581//9581 -f 9581//9581 9546//9546 9544//9544 -f 9516//9516 9570//9570 9515//9515 -f 9515//9515 9570//9570 9571//9571 -f 9515//9515 9571//9571 9520//9520 -f 9520//9520 9571//9571 9572//9572 -f 9520//9520 9572//9572 9522//9522 -f 9522//9522 9572//9572 9573//9573 -f 9522//9522 9573//9573 9525//9525 -f 9525//9525 9573//9573 9574//9574 -f 9525//9525 9574//9574 9528//9528 -f 9528//9528 9574//9574 9575//9575 -f 9528//9528 9575//9575 9530//9530 -f 9530//9530 9575//9575 9576//9576 -f 9530//9530 9576//9576 9512//9512 -f 9512//9512 9576//9576 9577//9577 -f 9512//9512 9577//9577 9534//9534 -f 9534//9534 9577//9577 9578//9578 -f 9534//9534 9578//9578 9536//9536 -f 9536//9536 9578//9578 9579//9579 -f 9536//9536 9579//9579 9539//9539 -f 9539//9539 9579//9579 9580//9580 -f 9539//9539 9580//9580 9541//9541 -f 9541//9541 9580//9580 9581//9581 -f 9582//9582 9583//9583 9584//9584 -f 9585//9585 9586//9586 9587//9587 -f 9588//9588 9589//9589 9586//9586 -f 9590//9590 9591//9591 9592//9592 -f 9593//9593 9591//9591 9594//9594 -f 9594//9594 9591//9591 9590//9590 -f 9594//9594 9590//9590 9595//9595 -f 9596//9596 9597//9597 9598//9598 -f 9599//9599 9600//9600 9597//9597 -f 9601//9601 9602//9602 9600//9600 -f 9603//9603 9604//9604 9605//9605 -f 9606//9606 9595//9595 9607//9607 -f 9607//9607 9595//9595 9590//9590 -f 9607//9607 9590//9590 9608//9608 -f 9608//9608 9590//9590 9592//9592 -f 9608//9608 9592//9592 9589//9589 -f 9609//9609 9610//9610 9611//9611 -f 9612//9612 9610//9610 9613//9613 -f 9613//9613 9610//9610 9609//9609 -f 9613//9613 9609//9609 9614//9614 -f 9615//9615 9616//9616 9617//9617 -f 9603//9603 9605//9605 9618//9618 -f 9618//9618 9605//9605 9615//9615 -f 9618//9618 9615//9615 9619//9619 -f 9619//9619 9615//9615 9617//9617 -f 9619//9619 9617//9617 9620//9620 -f 9620//9620 9621//9621 9619//9619 -f 9619//9619 9621//9621 9622//9622 -f 9619//9619 9622//9622 9618//9618 -f 9618//9618 9622//9622 9585//9585 -f 9618//9618 9585//9585 9603//9603 -f 9603//9603 9585//9585 9587//9587 -f 9603//9603 9587//9587 9604//9604 -f 9604//9604 9587//9587 9623//9623 -f 9604//9604 9623//9623 9624//9624 -f 9620//9620 9625//9625 9621//9621 -f 9621//9621 9625//9625 9626//9626 -f 9621//9621 9626//9626 9627//9627 -f 9586//9586 9585//9585 9588//9588 -f 9588//9588 9585//9585 9622//9622 -f 9588//9588 9622//9622 9628//9628 -f 9628//9628 9622//9622 9621//9621 -f 9628//9628 9621//9621 9629//9629 -f 9629//9629 9621//9621 9627//9627 -f 9629//9629 9627//9627 9630//9630 -f 9589//9589 9588//9588 9608//9608 -f 9608//9608 9588//9588 9628//9628 -f 9608//9608 9628//9628 9607//9607 -f 9607//9607 9628//9628 9629//9629 -f 9607//9607 9629//9629 9606//9606 -f 9606//9606 9629//9629 9630//9630 -f 9606//9606 9630//9630 9631//9631 -f 9631//9631 9632//9632 9606//9606 -f 9606//9606 9632//9632 9633//9633 -f 9606//9606 9633//9633 9595//9595 -f 9595//9595 9633//9633 9634//9634 -f 9595//9595 9634//9634 9594//9594 -f 9594//9594 9634//9634 9635//9635 -f 9594//9594 9635//9635 9593//9593 -f 9593//9593 9635//9635 9636//9636 -f 9632//9632 9637//9637 9633//9633 -f 9633//9633 9637//9637 9614//9614 -f 9633//9633 9614//9614 9634//9634 -f 9634//9634 9614//9614 9609//9609 -f 9634//9634 9609//9609 9635//9635 -f 9635//9635 9609//9609 9611//9611 -f 9635//9635 9611//9611 9636//9636 -f 9636//9636 9611//9611 9598//9598 -f 9637//9637 9638//9638 9614//9614 -f 9614//9614 9638//9638 9639//9639 -f 9614//9614 9639//9639 9613//9613 -f 9613//9613 9639//9639 9640//9640 -f 9613//9613 9640//9640 9612//9612 -f 9612//9612 9640//9640 9641//9641 -f 9612//9612 9641//9641 9642//9642 -f 9598//9598 9611//9611 9596//9596 -f 9596//9596 9611//9611 9610//9610 -f 9596//9596 9610//9610 9643//9643 -f 9643//9643 9610//9610 9612//9612 -f 9643//9643 9612//9612 9644//9644 -f 9644//9644 9612//9612 9642//9642 -f 9644//9644 9642//9642 9645//9645 -f 9597//9597 9596//9596 9599//9599 -f 9599//9599 9596//9596 9643//9643 -f 9599//9599 9643//9643 9646//9646 -f 9646//9646 9643//9643 9644//9644 -f 9646//9646 9644//9644 9584//9584 -f 9584//9584 9644//9644 9645//9645 -f 9584//9584 9645//9645 9582//9582 -f 9600//9600 9599//9599 9601//9601 -f 9601//9601 9599//9599 9646//9646 -f 9601//9601 9646//9646 9647//9647 -f 9647//9647 9646//9646 9584//9584 -f 9647//9647 9584//9584 9648//9648 -f 9648//9648 9584//9584 9583//9583 -f 9648//9648 9583//9583 9649//9649 -f 9650//9650 9651//9651 9652//9652 -f 9653//9653 9654//9654 9655//9655 -f 9655//9655 9654//9654 9656//9656 -f 9655//9655 9656//9656 9657//9657 -f 9657//9657 9656//9656 9658//9658 -f 9657//9657 9658//9658 9659//9659 -f 9659//9659 9658//9658 9660//9660 -f 9659//9659 9660//9660 9661//9661 -f 9661//9661 9660//9660 9662//9662 -f 9661//9661 9662//9662 9663//9663 -f 9663//9663 9662//9662 9664//9664 -f 9663//9663 9664//9664 9665//9665 -f 9665//9665 9664//9664 9666//9666 -f 9665//9665 9666//9666 9667//9667 -f 9666//9666 9668//9668 9667//9667 -f 9667//9667 9668//9668 9669//9669 -f 9667//9667 9669//9669 9670//9670 -f 9670//9670 9669//9669 9671//9671 -f 9670//9670 9671//9671 9672//9672 -f 9672//9672 9671//9671 9673//9673 -f 9672//9672 9673//9673 9674//9674 -f 9674//9674 9673//9673 9675//9675 -f 9674//9674 9675//9675 9676//9676 -f 9676//9676 9675//9675 9677//9677 -f 9676//9676 9677//9677 9678//9678 -f 9678//9678 9677//9677 9679//9679 -f 9678//9678 9679//9679 9680//9680 -f 9680//9680 9679//9679 9652//9652 -f 9652//9652 9679//9679 9681//9681 -f 9652//9652 9681//9681 9650//9650 -f 9682//9682 9683//9683 9684//9684 -f 9682//9682 9684//9684 9685//9685 -f 9685//9685 9684//9684 9686//9686 -f 9685//9685 9686//9686 9651//9651 -f 9651//9651 9686//9686 9687//9687 -f 9651//9651 9687//9687 9652//9652 -f 9688//9688 9689//9689 9690//9690 -f 9691//9691 766//766 9692//9692 -f 9692//9692 766//766 9693//9693 -f 9694//9694 9695//9695 9696//9696 -f 9690//9690 9689//9689 9697//9697 -f 9689//9689 9698//9698 9697//9697 -f 9697//9697 9698//9698 9699//9699 -f 9697//9697 9699//9699 9700//9700 -f 9700//9700 9699//9699 9701//9701 -f 9700//9700 9701//9701 9695//9695 -f 9695//9695 9701//9701 9702//9702 -f 9695//9695 9702//9702 9696//9696 -f 9696//9696 9702//9702 9703//9703 -f 9696//9696 9703//9703 9693//9693 -f 9693//9693 9703//9703 9704//9704 -f 9693//9693 9704//9704 9692//9692 -f 9690//9690 9705//9705 9688//9688 -f 9688//9688 9705//9705 9706//9706 -f 9688//9688 9706//9706 9707//9707 -f 9707//9707 9706//9706 9708//9708 -f 9707//9707 9708//9708 9709//9709 -f 9709//9709 9708//9708 9710//9710 -f 9711//9711 9712//9712 9713//9713 -f 9713//9713 9714//9714 9711//9711 -f 9711//9711 9714//9714 9715//9715 -f 9711//9711 9715//9715 9716//9716 -f 9716//9716 9715//9715 9717//9717 -f 9716//9716 9717//9717 9718//9718 -f 9718//9718 9717//9717 9719//9719 -f 9718//9718 9719//9719 9720//9720 -f 9720//9720 9719//9719 9721//9721 -f 9720//9720 9721//9721 9710//9710 -f 9710//9710 9721//9721 9722//9722 -f 9710//9710 9722//9722 9709//9709 -f 9723//9723 9724//9724 9725//9725 -f 9725//9725 9724//9724 9726//9726 -f 9725//9725 9726//9726 9727//9727 -f 9727//9727 9726//9726 9728//9728 -f 9727//9727 9728//9728 9696//9696 -f 9696//9696 9728//9728 9729//9729 -f 9696//9696 9729//9729 9694//9694 -f 9723//9723 9725//9725 9730//9730 -f 9730//9730 9725//9725 9731//9731 -f 9730//9730 9731//9731 9732//9732 -f 9732//9732 9731//9731 9733//9733 -f 9733//9733 9731//9731 9734//9734 -f 9733//9733 9734//9734 9735//9735 -f 9735//9735 9734//9734 9736//9736 -f 9736//9736 9734//9734 778//778 -f 9736//9736 778//778 9737//9737 -f 9737//9737 778//778 9738//9738 -f 9738//9738 778//778 9739//9739 -f 9738//9738 9739//9739 9740//9740 -f 9741//9741 9742//9742 9743//9743 -f 9743//9743 9742//9742 9744//9744 -f 9743//9743 9744//9744 9739//9739 -f 9739//9739 9744//9744 9745//9745 -f 9739//9739 9745//9745 9740//9740 -f 9746//9746 9747//9747 9741//9741 -f 9741//9741 9747//9747 9748//9748 -f 9741//9741 9748//9748 9742//9742 -f 9749//9749 9750//9750 9751//9751 -f 9751//9751 9750//9750 9752//9752 -f 9751//9751 9752//9752 9746//9746 -f 9746//9746 9752//9752 9753//9753 -f 9746//9746 9753//9753 9747//9747 -f 9691//9691 9754//9754 766//766 -f 766//766 9754//9754 9755//9755 -f 766//766 9755//9755 9749//9749 -f 9749//9749 9755//9755 9756//9756 -f 9749//9749 9756//9756 9750//9750 -f 9757//9757 9758//9758 9759//9759 -f 9759//9759 9758//9758 9760//9760 -f 9759//9759 9760//9760 9761//9761 -f 9761//9761 9760//9760 9762//9762 -f 9762//9762 9760//9760 9763//9763 -f 9762//9762 9763//9763 9764//9764 -f 9764//9764 9763//9763 9765//9765 -f 9764//9764 9765//9765 9766//9766 -f 9766//9766 9765//9765 9767//9767 -f 9766//9766 9767//9767 9768//9768 -f 9769//9769 9770//9770 9771//9771 -f 9771//9771 9770//9770 9772//9772 -f 9771//9771 9772//9772 9773//9773 -f 9767//9767 9774//9774 9768//9768 -f 9768//9768 9774//9774 9775//9775 -f 9768//9768 9775//9775 9773//9773 -f 9773//9773 9775//9775 9776//9776 -f 9773//9773 9776//9776 9771//9771 -f 9777//9777 9778//9778 9779//9779 -f 9779//9779 9778//9778 9780//9780 -f 9779//9779 9780//9780 9757//9757 -f 9757//9757 9780//9780 9781//9781 -f 9757//9757 9781//9781 9758//9758 -f 9779//9779 9782//9782 9777//9777 -f 9777//9777 9782//9782 9783//9783 -f 9777//9777 9783//9783 9784//9784 -f 9785//9785 9786//9786 9787//9787 -f 9787//9787 9786//9786 9784//9784 -f 9787//9787 9784//9784 9788//9788 -f 9788//9788 9784//9784 9783//9783 -f 9789//9789 9790//9790 9791//9791 -f 9791//9791 9790//9790 9792//9792 -f 9791//9791 9792//9792 9793//9793 -f 9793//9793 9792//9792 9794//9794 -f 9793//9793 9794//9794 9785//9785 -f 9785//9785 9794//9794 9795//9795 -f 9785//9785 9795//9795 9786//9786 -f 9796//9796 9797//9797 9798//9798 -f 9799//9799 9800//9800 9801//9801 -f 9801//9801 9800//9800 9802//9802 -f 9801//9801 9802//9802 9803//9803 -f 9803//9803 9802//9802 9804//9804 -f 9803//9803 9804//9804 9805//9805 -f 9805//9805 9804//9804 9806//9806 -f 9805//9805 9806//9806 9807//9807 -f 9807//9807 9806//9806 9808//9808 -f 9807//9807 9808//9808 9809//9809 -f 9809//9809 9808//9808 9810//9810 -f 9809//9809 9810//9810 9811//9811 -f 9810//9810 9812//9812 9811//9811 -f 9811//9811 9812//9812 9813//9813 -f 9811//9811 9813//9813 9814//9814 -f 9814//9814 9813//9813 9815//9815 -f 9814//9814 9815//9815 9816//9816 -f 9816//9816 9815//9815 9817//9817 -f 9817//9817 9815//9815 9818//9818 -f 9817//9817 9818//9818 9797//9797 -f 9797//9797 9818//9818 9819//9819 -f 9797//9797 9819//9819 9798//9798 -f 9796//9796 9798//9798 9820//9820 -f 9820//9820 9798//9798 9821//9821 -f 9820//9820 9821//9821 9822//9822 -f 9822//9822 9821//9821 9823//9823 -f 9822//9822 9823//9823 9824//9824 -f 9824//9824 9823//9823 9825//9825 -f 9824//9824 9825//9825 9826//9826 -f 9826//9826 9825//9825 9827//9827 -f 9826//9826 9827//9827 9828//9828 -f 9828//9828 9827//9827 9829//9829 -f 9828//9828 9829//9829 9830//9830 -f 9830//9830 9829//9829 9831//9831 -f 9830//9830 9831//9831 9832//9832 -f 9833//9833 9834//9834 9835//9835 -f 9833//9833 9835//9835 9836//9836 -f 9836//9836 9835//9835 9837//9837 -f 9836//9836 9837//9837 9838//9838 -f 9839//9839 9840//9840 9841//9841 -f 9841//9841 9840//9840 9842//9842 -f 9841//9841 9842//9842 9843//9843 -f 9843//9843 9842//9842 9844//9844 -f 9843//9843 9844//9844 9834//9834 -f 9834//9834 9844//9844 9845//9845 -f 9834//9834 9845//9845 9835//9835 -f 9846//9846 9847//9847 9848//9848 -f 9848//9848 9849//9849 9846//9846 -f 9846//9846 9849//9849 9850//9850 -f 9846//9846 9850//9850 9839//9839 -f 9839//9839 9850//9850 9851//9851 -f 9839//9839 9851//9851 9840//9840 -f 9852//9852 9853//9853 9854//9854 -f 9854//9854 9853//9853 9855//9855 -f 9854//9854 9855//9855 9856//9856 -f 9856//9856 9855//9855 9857//9857 -f 9856//9856 9857//9857 9858//9858 -f 9858//9858 9857//9857 9859//9859 -f 9858//9858 9859//9859 9847//9847 -f 9847//9847 9859//9859 9860//9860 -f 9847//9847 9860//9860 9848//9848 -f 9861//9861 9862//9862 9863//9863 -f 9863//9863 9862//9862 9864//9864 -f 9863//9863 9864//9864 9865//9865 -f 9864//9864 9866//9866 9865//9865 -f 9865//9865 9866//9866 9867//9867 -f 9865//9865 9867//9867 9868//9868 -f 9868//9868 9867//9867 9869//9869 -f 9868//9868 9869//9869 9854//9854 -f 9854//9854 9869//9869 9870//9870 -f 9854//9854 9870//9870 9852//9852 -f 9871//9871 9872//9872 9873//9873 -f 9873//9873 9872//9872 9874//9874 -f 9873//9873 9874//9874 9875//9875 -f 9875//9875 9874//9874 9876//9876 -f 9875//9875 9876//9876 9877//9877 -f 9873//9873 9878//9878 9871//9871 -f 9871//9871 9878//9878 9879//9879 -f 9871//9871 9879//9879 9880//9880 -f 9880//9880 9879//9879 9881//9881 -f 9880//9880 9881//9881 9882//9882 -f 9882//9882 9881//9881 9883//9883 -f 9882//9882 9883//9883 9884//9884 -f 9883//9883 9885//9885 9884//9884 -f 9884//9884 9885//9885 9886//9886 -f 9884//9884 9886//9886 9887//9887 -f 9887//9887 9886//9886 9888//9888 -f 9887//9887 9888//9888 9889//9889 -f 9889//9889 9888//9888 9890//9890 -f 9889//9889 9890//9890 9891//9891 -f 9891//9891 9890//9890 9892//9892 -f 9891//9891 9892//9892 9893//9893 -f 9893//9893 9892//9892 9894//9894 -f 9893//9893 9894//9894 9895//9895 -f 9895//9895 9894//9894 9896//9896 -f 9896//9896 9894//9894 9897//9897 -f 9896//9896 9897//9897 9898//9898 -f 9898//9898 9897//9897 9899//9899 -f 9898//9898 9899//9899 9900//9900 -f 9900//9900 9899//9899 9901//9901 -f 9900//9900 9901//9901 9902//9902 -f 9903//9903 9904//9904 9905//9905 -f 9905//9905 9904//9904 9906//9906 -f 9905//9905 9906//9906 9902//9902 -f 9902//9902 9906//9906 9907//9907 -f 9902//9902 9907//9907 9900//9900 -f 9908//9908 9909//9909 9910//9910 -f 9910//9910 9909//9909 9911//9911 -f 9910//9910 9911//9911 9912//9912 -f 9912//9912 9911//9911 9913//9913 -f 9912//9912 9913//9913 9914//9914 -f 9914//9914 9913//9913 9915//9915 -f 9914//9914 9915//9915 9916//9916 -f 9916//9916 9915//9915 9917//9917 -f 9916//9916 9917//9917 9918//9918 -f 9918//9918 9917//9917 9919//9919 -f 9918//9918 9919//9919 9920//9920 -f 9921//9921 9922//9922 9923//9923 -f 9923//9923 9922//9922 9920//9920 -f 9923//9923 9920//9920 9924//9924 -f 9924//9924 9920//9920 9919//9919 -f 9925//9925 9926//9926 9927//9927 -f 9927//9927 9926//9926 9928//9928 -f 9927//9927 9928//9928 9908//9908 -f 9908//9908 9928//9928 9929//9929 -f 9908//9908 9929//9929 9909//9909 -f 9927//9927 9930//9930 9925//9925 -f 9925//9925 9930//9930 9931//9931 -f 9925//9925 9931//9931 9932//9932 -f 9933//9933 9934//9934 9935//9935 -f 9935//9935 9934//9934 9932//9932 -f 9935//9935 9932//9932 9936//9936 -f 9936//9936 9932//9932 9931//9931 -f 9937//9937 9938//9938 9939//9939 -f 9939//9939 9938//9938 9940//9940 -f 9939//9939 9940//9940 9941//9941 -f 9941//9941 9940//9940 9942//9942 -f 9941//9941 9942//9942 9933//9933 -f 9933//9933 9942//9942 9943//9943 -f 9933//9933 9943//9943 9934//9934 -f 9944//9944 9945//9945 9946//9946 -f 9947//9947 9948//9948 9949//9949 -f 9949//9949 9948//9948 9950//9950 -f 9949//9949 9950//9950 9951//9951 -f 9951//9951 9950//9950 9952//9952 -f 9951//9951 9952//9952 9953//9953 -f 9953//9953 9952//9952 9954//9954 -f 9953//9953 9954//9954 9955//9955 -f 9955//9955 9954//9954 9956//9956 -f 9955//9955 9956//9956 9957//9957 -f 9957//9957 9956//9956 9958//9958 -f 9957//9957 9958//9958 9959//9959 -f 9958//9958 9960//9960 9959//9959 -f 9959//9959 9960//9960 9961//9961 -f 9959//9959 9961//9961 9962//9962 -f 9962//9962 9961//9961 9963//9963 -f 9962//9962 9963//9963 9964//9964 -f 9964//9964 9963//9963 9965//9965 -f 9965//9965 9963//9963 9966//9966 -f 9965//9965 9966//9966 9945//9945 -f 9945//9945 9966//9966 9967//9967 -f 9945//9945 9967//9967 9946//9946 -f 9944//9944 9946//9946 9968//9968 -f 9968//9968 9946//9946 9969//9969 -f 9968//9968 9969//9969 9970//9970 -f 9970//9970 9969//9969 9971//9971 -f 9970//9970 9971//9971 9972//9972 -f 9972//9972 9971//9971 9973//9973 -f 9972//9972 9973//9973 9974//9974 -f 9974//9974 9973//9973 9975//9975 -f 9974//9974 9975//9975 9976//9976 -f 9976//9976 9975//9975 9977//9977 -f 9976//9976 9977//9977 9978//9978 -f 9978//9978 9977//9977 9979//9979 -f 9978//9978 9979//9979 9980//9980 -f 9981//9981 9982//9982 9983//9983 -f 9981//9981 9983//9983 9984//9984 -f 9984//9984 9983//9983 9985//9985 -f 9984//9984 9985//9985 9986//9986 -f 9987//9987 9988//9988 9989//9989 -f 9989//9989 9988//9988 9990//9990 -f 9989//9989 9990//9990 9991//9991 -f 9991//9991 9990//9990 9992//9992 -f 9991//9991 9992//9992 9982//9982 -f 9982//9982 9992//9992 9993//9993 -f 9982//9982 9993//9993 9983//9983 -f 9994//9994 9995//9995 9996//9996 -f 9996//9996 9997//9997 9994//9994 -f 9994//9994 9997//9997 9998//9998 -f 9994//9994 9998//9998 9987//9987 -f 9987//9987 9998//9998 9999//9999 -f 9987//9987 9999//9999 9988//9988 -f 10000//10000 10001//10001 10002//10002 -f 10002//10002 10001//10001 10003//10003 -f 10002//10002 10003//10003 10004//10004 -f 10004//10004 10003//10003 10005//10005 -f 10004//10004 10005//10005 10006//10006 -f 10006//10006 10005//10005 10007//10007 -f 10006//10006 10007//10007 9995//9995 -f 9995//9995 10007//10007 10008//10008 -f 9995//9995 10008//10008 9996//9996 -f 10009//10009 10010//10010 10011//10011 -f 10011//10011 10010//10010 10012//10012 -f 10011//10011 10012//10012 10013//10013 -f 10012//10012 10014//10014 10013//10013 -f 10013//10013 10014//10014 10015//10015 -f 10013//10013 10015//10015 10016//10016 -f 10016//10016 10015//10015 10017//10017 -f 10016//10016 10017//10017 10002//10002 -f 10002//10002 10017//10017 10018//10018 -f 10002//10002 10018//10018 10000//10000 -f 10019//10019 10020//10020 10021//10021 -f 10021//10021 10020//10020 10022//10022 -f 10021//10021 10022//10022 10023//10023 -f 10023//10023 10022//10022 10024//10024 -f 10023//10023 10024//10024 10025//10025 -f 10021//10021 10026//10026 10019//10019 -f 10019//10019 10026//10026 10027//10027 -f 10019//10019 10027//10027 10028//10028 -f 10028//10028 10027//10027 10029//10029 -f 10028//10028 10029//10029 10030//10030 -f 10030//10030 10029//10029 10031//10031 -f 10030//10030 10031//10031 10032//10032 -f 10031//10031 10033//10033 10032//10032 -f 10032//10032 10033//10033 10034//10034 -f 10032//10032 10034//10034 10035//10035 -f 10035//10035 10034//10034 10036//10036 -f 10035//10035 10036//10036 10037//10037 -f 10037//10037 10036//10036 10038//10038 -f 10037//10037 10038//10038 10039//10039 -f 10039//10039 10038//10038 10040//10040 -f 10039//10039 10040//10040 10041//10041 -f 10041//10041 10040//10040 10042//10042 -f 10041//10041 10042//10042 10043//10043 -f 10043//10043 10042//10042 10044//10044 -f 10044//10044 10042//10042 10045//10045 -f 10044//10044 10045//10045 10046//10046 -f 10046//10046 10045//10045 10047//10047 -f 10046//10046 10047//10047 10048//10048 -f 10048//10048 10047//10047 10049//10049 -f 10048//10048 10049//10049 10050//10050 -f 10051//10051 10052//10052 10053//10053 -f 10053//10053 10052//10052 10054//10054 -f 10053//10053 10054//10054 10050//10050 -f 10050//10050 10054//10054 10055//10055 -f 10050//10050 10055//10055 10048//10048 -f 10056//10056 10057//10057 10058//10058 -f 10058//10058 10057//10057 10059//10059 -f 10058//10058 10059//10059 10060//10060 -f 10060//10060 10059//10059 10061//10061 -f 10060//10060 10061//10061 10062//10062 -f 10062//10062 10061//10061 10063//10063 -f 10062//10062 10063//10063 10064//10064 -f 10064//10064 10063//10063 10065//10065 -f 10064//10064 10065//10065 10066//10066 -f 10066//10066 10065//10065 10067//10067 -f 10066//10066 10067//10067 10068//10068 -f 10069//10069 10070//10070 10071//10071 -f 10071//10071 10070//10070 10068//10068 -f 10071//10071 10068//10068 10072//10072 -f 10072//10072 10068//10068 10067//10067 -f 10073//10073 10074//10074 10075//10075 -f 10075//10075 10074//10074 10076//10076 -f 10075//10075 10076//10076 10056//10056 -f 10056//10056 10076//10076 10077//10077 -f 10056//10056 10077//10077 10057//10057 -f 10075//10075 10078//10078 10073//10073 -f 10073//10073 10078//10078 10079//10079 -f 10073//10073 10079//10079 10080//10080 -f 10081//10081 10082//10082 10083//10083 -f 10083//10083 10082//10082 10080//10080 -f 10083//10083 10080//10080 10084//10084 -f 10084//10084 10080//10080 10079//10079 -f 10085//10085 10086//10086 10087//10087 -f 10087//10087 10086//10086 10088//10088 -f 10087//10087 10088//10088 10089//10089 -f 10089//10089 10088//10088 10090//10090 -f 10089//10089 10090//10090 10081//10081 -f 10081//10081 10090//10090 10091//10091 -f 10081//10081 10091//10091 10082//10082 -f 10092//10092 10093//10093 10094//10094 -f 10095//10095 10096//10096 10097//10097 -f 10097//10097 10096//10096 10098//10098 -f 10097//10097 10098//10098 10099//10099 -f 10099//10099 10098//10098 10100//10100 -f 10099//10099 10100//10100 10101//10101 -f 10101//10101 10100//10100 10102//10102 -f 10101//10101 10102//10102 10103//10103 -f 10103//10103 10102//10102 10104//10104 -f 10103//10103 10104//10104 10105//10105 -f 10105//10105 10104//10104 10106//10106 -f 10105//10105 10106//10106 10107//10107 -f 10106//10106 10108//10108 10107//10107 -f 10107//10107 10108//10108 10109//10109 -f 10107//10107 10109//10109 10110//10110 -f 10110//10110 10109//10109 10111//10111 -f 10110//10110 10111//10111 10112//10112 -f 10112//10112 10111//10111 10113//10113 -f 10113//10113 10111//10111 10114//10114 -f 10113//10113 10114//10114 10093//10093 -f 10093//10093 10114//10114 10115//10115 -f 10093//10093 10115//10115 10094//10094 -f 10092//10092 10094//10094 10116//10116 -f 10116//10116 10094//10094 10117//10117 -f 10116//10116 10117//10117 10118//10118 -f 10118//10118 10117//10117 10119//10119 -f 10118//10118 10119//10119 10120//10120 -f 10120//10120 10119//10119 10121//10121 -f 10120//10120 10121//10121 10122//10122 -f 10122//10122 10121//10121 10123//10123 -f 10122//10122 10123//10123 10124//10124 -f 10124//10124 10123//10123 10125//10125 -f 10124//10124 10125//10125 10126//10126 -f 10126//10126 10125//10125 10127//10127 -f 10126//10126 10127//10127 10128//10128 -f 10129//10129 10130//10130 10131//10131 -f 10129//10129 10131//10131 10132//10132 -f 10132//10132 10131//10131 10133//10133 -f 10132//10132 10133//10133 10134//10134 -f 10135//10135 10136//10136 10137//10137 -f 10137//10137 10136//10136 10138//10138 -f 10137//10137 10138//10138 10139//10139 -f 10139//10139 10138//10138 10140//10140 -f 10139//10139 10140//10140 10130//10130 -f 10130//10130 10140//10140 10141//10141 -f 10130//10130 10141//10141 10131//10131 -f 10142//10142 10143//10143 10144//10144 -f 10144//10144 10145//10145 10142//10142 -f 10142//10142 10145//10145 10146//10146 -f 10142//10142 10146//10146 10135//10135 -f 10135//10135 10146//10146 10147//10147 -f 10135//10135 10147//10147 10136//10136 -f 10148//10148 10149//10149 10150//10150 -f 10150//10150 10149//10149 10151//10151 -f 10150//10150 10151//10151 10152//10152 -f 10152//10152 10151//10151 10153//10153 -f 10152//10152 10153//10153 10154//10154 -f 10154//10154 10153//10153 10155//10155 -f 10154//10154 10155//10155 10143//10143 -f 10143//10143 10155//10155 10156//10156 -f 10143//10143 10156//10156 10144//10144 -f 10157//10157 10158//10158 10159//10159 -f 10159//10159 10158//10158 10160//10160 -f 10159//10159 10160//10160 10161//10161 -f 10160//10160 10162//10162 10161//10161 -f 10161//10161 10162//10162 10163//10163 -f 10161//10161 10163//10163 10164//10164 -f 10164//10164 10163//10163 10165//10165 -f 10164//10164 10165//10165 10150//10150 -f 10150//10150 10165//10165 10166//10166 -f 10150//10150 10166//10166 10148//10148 -f 10167//10167 10168//10168 10169//10169 -f 10170//10170 10171//10171 10172//10172 -f 10172//10172 10171//10171 10173//10173 -f 10172//10172 10173//10173 10174//10174 -f 10174//10174 10173//10173 10175//10175 -f 10174//10174 10175//10175 10176//10176 -f 10172//10172 10177//10177 10170//10170 -f 10170//10170 10177//10177 10178//10178 -f 10170//10170 10178//10178 10179//10179 -f 10179//10179 10178//10178 10180//10180 -f 10179//10179 10180//10180 10181//10181 -f 10181//10181 10180//10180 10182//10182 -f 10181//10181 10182//10182 10183//10183 -f 10182//10182 10184//10184 10183//10183 -f 10183//10183 10184//10184 10185//10185 -f 10183//10183 10185//10185 10186//10186 -f 10186//10186 10185//10185 10187//10187 -f 10186//10186 10187//10187 10188//10188 -f 10188//10188 10187//10187 10189//10189 -f 10188//10188 10189//10189 10190//10190 -f 10190//10190 10189//10189 10191//10191 -f 10190//10190 10191//10191 10192//10192 -f 10192//10192 10191//10191 10193//10193 -f 10192//10192 10193//10193 10194//10194 -f 10194//10194 10193//10193 10195//10195 -f 10195//10195 10193//10193 10196//10196 -f 10196//10196 10193//10193 10197//10197 -f 10196//10196 10197//10197 10169//10169 -f 10169//10169 10197//10197 10198//10198 -f 10169//10169 10198//10198 10167//10167 -f 10199//10199 10200//10200 10201//10201 -f 10201//10201 10202//10202 10199//10199 -f 10199//10199 10202//10202 10203//10203 -f 10199//10199 10203//10203 10168//10168 -f 10168//10168 10203//10203 10204//10204 -f 10168//10168 10204//10204 10169//10169 -f 10205//10205 10206//10206 10207//10207 -f 10207//10207 10206//10206 10208//10208 -f 10207//10207 10208//10208 10209//10209 -f 10210//10210 10211//10211 10212//10212 -f 10212//10212 10211//10211 10213//10213 -f 10212//10212 10213//10213 10214//10214 -f 10214//10214 10213//10213 10215//10215 -f 10214//10214 10215//10215 10216//10216 -f 10216//10216 10215//10215 10209//10209 -f 10216//10216 10209//10209 10217//10217 -f 10217//10217 10209//10209 10208//10208 -f 10218//10218 10219//10219 10220//10220 -f 10220//10220 10219//10219 10221//10221 -f 10220//10220 10221//10221 10222//10222 -f 10222//10222 10221//10221 10223//10223 -f 10222//10222 10223//10223 10224//10224 -f 10224//10224 10223//10223 10225//10225 -f 10224//10224 10225//10225 10226//10226 -f 10226//10226 10225//10225 10227//10227 -f 10226//10226 10227//10227 10205//10205 -f 10205//10205 10227//10227 10228//10228 -f 10205//10205 10228//10228 10206//10206 -f 10220//10220 10229//10229 10218//10218 -f 10218//10218 10229//10229 10230//10230 -f 10218//10218 10230//10230 10231//10231 -f 10231//10231 10230//10230 10232//10232 -f 10231//10231 10232//10232 10233//10233 -f 10233//10233 10232//10232 10234//10234 -f 10233//10233 10234//10234 10235//10235 -f 10235//10235 10234//10234 10236//10236 -f 10235//10235 10236//10236 10237//10237 -f 10237//10237 10236//10236 10238//10238 -f 10236//10236 10239//10239 10238//10238 -f 10238//10238 10239//10239 10240//10240 -f 10238//10238 10240//10240 10241//10241 -f 10241//10241 10240//10240 10242//10242 -f 10241//10241 10242//10242 10243//10243 -f 10244//10244 10245//10245 10246//10246 -f 10247//10247 10248//10248 10249//10249 -f 10250//10250 10251//10251 10252//10252 -f 10252//10252 10251//10251 10253//10253 -f 10252//10252 10253//10253 10254//10254 -f 10254//10254 10253//10253 10255//10255 -f 10254//10254 10255//10255 10256//10256 -f 10256//10256 10255//10255 10257//10257 -f 10256//10256 10257//10257 10258//10258 -f 10258//10258 10257//10257 10259//10259 -f 10258//10258 10259//10259 10260//10260 -f 10260//10260 10259//10259 10261//10261 -f 10260//10260 10261//10261 10249//10249 -f 10249//10249 10261//10261 10262//10262 -f 10249//10249 10262//10262 10247//10247 -f 10248//10248 10247//10247 10263//10263 -f 10263//10263 10247//10247 10264//10264 -f 10263//10263 10264//10264 10265//10265 -f 10265//10265 10264//10264 10266//10266 -f 10265//10265 10266//10266 10245//10245 -f 10245//10245 10266//10266 10267//10267 -f 10245//10245 10267//10267 10246//10246 -f 10244//10244 10246//10246 10268//10268 -f 10268//10268 10246//10246 10269//10269 -f 10268//10268 10269//10269 10270//10270 -f 10270//10270 10269//10269 10271//10271 -f 10270//10270 10271//10271 10272//10272 -f 10272//10272 10271//10271 10273//10273 -f 10272//10272 10273//10273 10274//10274 -f 10274//10274 10273//10273 10275//10275 -f 10275//10275 10273//10273 10276//10276 -f 10275//10275 10276//10276 10277//10277 -f 10277//10277 10276//10276 10278//10278 -f 10277//10277 10278//10278 10279//10279 -f 10279//10279 10278//10278 10280//10280 -f 10279//10279 10280//10280 10281//10281 -f 10282//10282 10283//10283 10284//10284 -f 10282//10282 10284//10284 10285//10285 -f 10285//10285 10284//10284 10286//10286 -f 10285//10285 10286//10286 10287//10287 -f 10288//10288 10289//10289 10290//10290 -f 10290//10290 10291//10291 10288//10288 -f 10288//10288 10291//10291 10292//10292 -f 10288//10288 10292//10292 10293//10293 -f 10293//10293 10292//10292 10294//10294 -f 10293//10293 10294//10294 10283//10283 -f 10283//10283 10294//10294 10295//10295 -f 10283//10283 10295//10295 10284//10284 -f 10296//10296 10297//10297 10298//10298 -f 10298//10298 10299//10299 10296//10296 -f 10296//10296 10299//10299 10300//10300 -f 10296//10296 10300//10300 10289//10289 -f 10289//10289 10300//10300 10301//10301 -f 10289//10289 10301//10301 10290//10290 -f 10302//10302 10303//10303 10304//10304 -f 10304//10304 10303//10303 10305//10305 -f 10304//10304 10305//10305 10306//10306 -f 10305//10305 10307//10307 10306//10306 -f 10306//10306 10307//10307 10308//10308 -f 10306//10306 10308//10308 10309//10309 -f 10309//10309 10308//10308 10310//10310 -f 10309//10309 10310//10310 10297//10297 -f 10297//10297 10310//10310 10311//10311 -f 10297//10297 10311//10311 10298//10298 -f 10312//10312 10313//10313 10314//10314 -f 10312//10312 10314//10314 10304//10304 -f 10304//10304 10314//10314 10315//10315 -f 10304//10304 10315//10315 10302//10302 -f 10316//10316 10317//10317 10318//10318 -f 10318//10318 10317//10317 10319//10319 -f 10318//10318 10319//10319 10313//10313 -f 10313//10313 10319//10319 10320//10320 -f 10313//10313 10320//10320 10314//10314 -f 10321//10321 10322//10322 10323//10323 -f 10323//10323 10322//10322 10324//10324 -f 10323//10323 10324//10324 10325//10325 -f 10325//10325 10324//10324 10326//10326 -f 10325//10325 10326//10326 10327//10327 -f 10327//10327 10326//10326 10328//10328 -f 10327//10327 10328//10328 10329//10329 -f 10328//10328 10330//10330 10329//10329 -f 10329//10329 10330//10330 10331//10331 -f 10329//10329 10331//10331 10332//10332 -f 10332//10332 10331//10331 10333//10333 -f 10332//10332 10333//10333 10334//10334 -f 10334//10334 10333//10333 10335//10335 -f 10333//10333 10336//10336 10335//10335 -f 10335//10335 10336//10336 10337//10337 -f 10335//10335 10337//10337 10338//10338 -f 10338//10338 10337//10337 10339//10339 -f 10338//10338 10339//10339 10340//10340 -f 10340//10340 10339//10339 10341//10341 -f 10340//10340 10341//10341 10342//10342 -f 10342//10342 10341//10341 10343//10343 -f 10342//10342 10343//10343 10344//10344 -f 10344//10344 10343//10343 10345//10345 -f 10344//10344 10345//10345 10346//10346 -f 10346//10346 10345//10345 10347//10347 -f 10347//10347 10345//10345 10348//10348 -f 10347//10347 10348//10348 10349//10349 -f 10349//10349 10348//10348 10350//10350 -f 10349//10349 10350//10350 10351//10351 -f 10352//10352 10353//10353 10354//10354 -f 10350//10350 10355//10355 10351//10351 -f 10351//10351 10355//10355 10356//10356 -f 10351//10351 10356//10356 10357//10357 -f 10357//10357 10356//10356 10352//10352 -f 10357//10357 10352//10352 10358//10358 -f 10358//10358 10352//10352 10354//10354 -f 10359//10359 10360//10360 10361//10361 -f 10359//10359 10361//10361 10362//10362 -f 10361//10361 10363//10363 10362//10362 -f 10362//10362 10363//10363 10364//10364 -f 10362//10362 10364//10364 10365//10365 -f 10365//10365 10364//10364 10366//10366 -f 10365//10365 10366//10366 10367//10367 -f 10367//10367 10366//10366 10368//10368 -f 10367//10367 10368//10368 10369//10369 -f 10369//10369 10368//10368 10370//10370 -f 10369//10369 10370//10370 10371//10371 -f 10371//10371 10370//10370 10372//10372 -f 10371//10371 10372//10372 10373//10373 -f 10373//10373 10372//10372 10374//10374 -f 10373//10373 10374//10374 10375//10375 -f 10376//10376 10377//10377 10378//10378 -f 10378//10378 10377//10377 10375//10375 -f 10378//10378 10375//10375 10379//10379 -f 10379//10379 10375//10375 10374//10374 -f 10360//10360 10359//10359 10380//10380 -f 10380//10380 10359//10359 10381//10381 -f 10380//10380 10381//10381 10382//10382 -f 10382//10382 10381//10381 10383//10383 -f 10382//10382 10383//10383 10384//10384 -f 10384//10384 10383//10383 10385//10385 -f 10384//10384 10385//10385 10386//10386 -f 10386//10386 10385//10385 10387//10387 -f 10386//10386 10387//10387 10388//10388 -f 10389//10389 10390//10390 10391//10391 -f 10391//10391 10390//10390 10388//10388 -f 10391//10391 10388//10388 10392//10392 -f 10392//10392 10388//10388 10387//10387 -f 9713//9713 9712//9712 10393//10393 -f 10393//10393 9712//9712 10394//10394 -f 10395//10395 10396//10396 10397//10397 -f 10395//10395 10397//10397 10398//10398 -f 10398//10398 10397//10397 10399//10399 -f 10398//10398 10399//10399 10400//10400 -f 10400//10400 10399//10399 10401//10401 -f 10400//10400 10401//10401 10402//10402 -f 10402//10402 10401//10401 10403//10403 -f 10402//10402 10403//10403 10404//10404 -f 10404//10404 10403//10403 10405//10405 -f 10404//10404 10405//10405 10406//10406 -f 10406//10406 10405//10405 10407//10407 -f 10406//10406 10407//10407 10408//10408 -f 10408//10408 10407//10407 10409//10409 -f 10408//10408 10409//10409 10410//10410 -f 10410//10410 10409//10409 10411//10411 -f 10410//10410 10411//10411 10394//10394 -f 10394//10394 10411//10411 10412//10412 -f 10394//10394 10412//10412 10393//10393 -f 10396//10396 10395//10395 10413//10413 -f 10413//10413 10395//10395 10414//10414 -f 10413//10413 10414//10414 10415//10415 -f 10414//10414 10416//10416 10415//10415 -f 10415//10415 10416//10416 10417//10417 -f 10415//10415 10417//10417 10418//10418 -f 10418//10418 10417//10417 10419//10419 -f 10420//10420 10421//10421 10419//10419 -f 10419//10419 10421//10421 10422//10422 -f 10419//10419 10422//10422 10418//10418 -f 10419//10419 10423//10423 10420//10420 -f 10420//10420 10423//10423 10424//10424 -f 10420//10420 10424//10424 10425//10425 -f 10425//10425 10424//10424 9770//9770 -f 10425//10425 9770//9770 9769//9769 -f 9790//9790 9789//9789 10426//10426 -f 10426//10426 9789//9789 10427//10427 -f 10426//10426 10427//10427 10428//10428 -f 10428//10428 10427//10427 10429//10429 -f 10428//10428 10429//10429 10430//10430 -f 10430//10430 10429//10429 10431//10431 -f 10430//10430 10431//10431 10432//10432 -f 10432//10432 10431//10431 10433//10433 -f 10434//10434 10435//10435 10436//10436 -f 10436//10436 10435//10435 10437//10437 -f 10436//10436 10437//10437 10438//10438 -f 10433//10433 10431//10431 10439//10439 -f 10439//10439 10431//10431 10440//10440 -f 10439//10439 10440//10440 10434//10434 -f 10434//10434 10440//10440 10441//10441 -f 10434//10434 10441//10441 10435//10435 -f 10438//10438 10437//10437 10442//10442 -f 10442//10442 10437//10437 10443//10443 -f 10442//10442 10443//10443 10444//10444 -f 10444//10444 10443//10443 10445//10445 -f 10445//10445 10443//10443 10446//10446 -f 10445//10445 10446//10446 10447//10447 -f 10447//10447 10446//10446 10448//10448 -f 10447//10447 10448//10448 10449//10449 -f 10449//10449 10448//10448 10450//10450 -f 10449//10449 10450//10450 10451//10451 -f 10450//10450 10452//10452 10451//10451 -f 10451//10451 10452//10452 10453//10453 -f 10451//10451 10453//10453 10454//10454 -f 10454//10454 10453//10453 10455//10455 -f 10454//10454 10455//10455 10456//10456 -f 10455//10455 10457//10457 10456//10456 -f 10456//10456 10457//10457 10458//10458 -f 10456//10456 10458//10458 10459//10459 -f 10459//10459 10458//10458 10460//10460 -f 10459//10459 10460//10460 10461//10461 -f 10461//10461 10460//10460 9800//9800 -f 10461//10461 9800//9800 9799//9799 -f 10462//10462 10463//10463 10464//10464 -f 10464//10464 10463//10463 10465//10465 -f 10464//10464 10465//10465 10466//10466 -f 10466//10466 10465//10465 10467//10467 -f 10466//10466 10467//10467 10468//10468 -f 10468//10468 10467//10467 10469//10469 -f 10468//10468 10469//10469 9832//9832 -f 9832//9832 10469//10469 10470//10470 -f 9832//9832 10470//10470 9830//9830 -f 10462//10462 10471//10471 10463//10463 -f 10463//10463 10471//10471 10472//10472 -f 10463//10463 10472//10472 10473//10473 -f 10473//10473 10472//10472 10474//10474 -f 10473//10473 10474//10474 10475//10475 -f 10475//10475 10474//10474 10476//10476 -f 10476//10476 10474//10474 10477//10477 -f 10476//10476 10477//10477 10478//10478 -f 10478//10478 10477//10477 10479//10479 -f 10478//10478 10479//10479 10480//10480 -f 10480//10480 10479//10479 10481//10481 -f 10480//10480 10481//10481 10482//10482 -f 10482//10482 10481//10481 10483//10483 -f 10482//10482 10483//10483 10484//10484 -f 10484//10484 10483//10483 10485//10485 -f 10484//10484 10485//10485 10486//10486 -f 10486//10486 10485//10485 10487//10487 -f 10486//10486 10487//10487 10488//10488 -f 10487//10487 10489//10489 10488//10488 -f 10488//10488 10489//10489 10490//10490 -f 10488//10488 10490//10490 10491//10491 -f 10491//10491 10490//10490 10492//10492 -f 10491//10491 10492//10492 10493//10493 -f 10493//10493 10492//10492 10494//10494 -f 10493//10493 10494//10494 9838//9838 -f 9838//9838 10494//10494 10495//10495 -f 9838//9838 10495//10495 9836//9836 -f 10496//10496 10497//10497 10498//10498 -f 9862//9862 9861//9861 10499//10499 -f 10499//10499 9861//9861 10500//10500 -f 10499//10499 10500//10500 10501//10501 -f 10501//10501 10500//10500 10502//10502 -f 10501//10501 10502//10502 10503//10503 -f 10503//10503 10502//10502 10504//10504 -f 10503//10503 10504//10504 10505//10505 -f 10504//10504 10506//10506 10505//10505 -f 10505//10505 10506//10506 10507//10507 -f 10505//10505 10507//10507 10508//10508 -f 10508//10508 10507//10507 10509//10509 -f 10508//10508 10509//10509 10510//10510 -f 10510//10510 10509//10509 10511//10511 -f 10510//10510 10511//10511 10497//10497 -f 10497//10497 10511//10511 10512//10512 -f 10497//10497 10512//10512 10498//10498 -f 10496//10496 10498//10498 10513//10513 -f 10513//10513 10498//10498 10514//10514 -f 10513//10513 10514//10514 10515//10515 -f 10515//10515 10514//10514 10516//10516 -f 10515//10515 10516//10516 10517//10517 -f 10517//10517 10516//10516 10518//10518 -f 10517//10517 10518//10518 10519//10519 -f 10518//10518 10520//10520 10519//10519 -f 10519//10519 10520//10520 10521//10521 -f 10519//10519 10521//10521 10522//10522 -f 10522//10522 10521//10521 10523//10523 -f 9877//9877 9876//9876 10524//10524 -f 10524//10524 9876//9876 10525//10525 -f 10524//10524 10525//10525 10526//10526 -f 10526//10526 10525//10525 10527//10527 -f 10526//10526 10527//10527 10528//10528 -f 10528//10528 10527//10527 10529//10529 -f 10528//10528 10529//10529 10523//10523 -f 10523//10523 10529//10529 10530//10530 -f 10523//10523 10530//10530 10522//10522 -f 10531//10531 10532//10532 10533//10533 -f 10533//10533 10532//10532 10534//10534 -f 10533//10533 10534//10534 10535//10535 -f 10535//10535 10534//10534 9904//9904 -f 10535//10535 9904//9904 9903//9903 -f 10533//10533 10536//10536 10531//10531 -f 10531//10531 10536//10536 10537//10537 -f 10531//10531 10537//10537 10538//10538 -f 10538//10538 10537//10537 10539//10539 -f 10538//10538 10539//10539 10540//10540 -f 10540//10540 10539//10539 10541//10541 -f 10540//10540 10541//10541 10542//10542 -f 10542//10542 10541//10541 10543//10543 -f 10542//10542 10543//10543 10544//10544 -f 10544//10544 10543//10543 10545//10545 -f 10543//10543 10546//10546 10545//10545 -f 10545//10545 10546//10546 10547//10547 -f 10545//10545 10547//10547 10548//10548 -f 10548//10548 10547//10547 10549//10549 -f 10548//10548 10549//10549 10550//10550 -f 10550//10550 10549//10549 10551//10551 -f 10550//10550 10551//10551 10552//10552 -f 10552//10552 10551//10551 10553//10553 -f 10552//10552 10553//10553 10554//10554 -f 10554//10554 10553//10553 10555//10555 -f 10554//10554 10555//10555 10556//10556 -f 10556//10556 10555//10555 10557//10557 -f 10556//10556 10557//10557 10558//10558 -f 10558//10558 10557//10557 10559//10559 -f 10558//10558 10559//10559 10560//10560 -f 10560//10560 10559//10559 10561//10561 -f 10560//10560 10561//10561 10562//10562 -f 10562//10562 10561//10561 10563//10563 -f 10562//10562 10563//10563 10564//10564 -f 10564//10564 10563//10563 10565//10565 -f 10564//10564 10565//10565 10566//10566 -f 10566//10566 10565//10565 9922//9922 -f 10566//10566 9922//9922 9921//9921 -f 9938//9938 9937//9937 10567//10567 -f 10567//10567 9937//9937 10568//10568 -f 10567//10567 10568//10568 10569//10569 -f 10569//10569 10568//10568 10570//10570 -f 10569//10569 10570//10570 10571//10571 -f 10571//10571 10570//10570 10572//10572 -f 10571//10571 10572//10572 10573//10573 -f 10573//10573 10572//10572 10574//10574 -f 10575//10575 10576//10576 10577//10577 -f 10577//10577 10576//10576 10578//10578 -f 10577//10577 10578//10578 10579//10579 -f 10574//10574 10572//10572 10580//10580 -f 10580//10580 10572//10572 10581//10581 -f 10580//10580 10581//10581 10575//10575 -f 10575//10575 10581//10581 10582//10582 -f 10575//10575 10582//10582 10576//10576 -f 10579//10579 10578//10578 10583//10583 -f 10583//10583 10578//10578 10584//10584 -f 10583//10583 10584//10584 10585//10585 -f 10585//10585 10584//10584 10586//10586 -f 10586//10586 10584//10584 10587//10587 -f 10586//10586 10587//10587 10588//10588 -f 10588//10588 10587//10587 10589//10589 -f 10588//10588 10589//10589 10590//10590 -f 10590//10590 10589//10589 10591//10591 -f 10590//10590 10591//10591 10592//10592 -f 10591//10591 10593//10593 10592//10592 -f 10592//10592 10593//10593 10594//10594 -f 10592//10592 10594//10594 10595//10595 -f 10595//10595 10594//10594 10596//10596 -f 10595//10595 10596//10596 10597//10597 -f 10596//10596 10598//10598 10597//10597 -f 10597//10597 10598//10598 10599//10599 -f 10597//10597 10599//10599 10600//10600 -f 10600//10600 10599//10599 10601//10601 -f 10600//10600 10601//10601 10602//10602 -f 10602//10602 10601//10601 9948//9948 -f 10602//10602 9948//9948 9947//9947 -f 10603//10603 10604//10604 10605//10605 -f 10605//10605 10604//10604 10606//10606 -f 10605//10605 10606//10606 10607//10607 -f 10607//10607 10606//10606 10608//10608 -f 10607//10607 10608//10608 10609//10609 -f 10609//10609 10608//10608 10610//10610 -f 10609//10609 10610//10610 9980//9980 -f 9980//9980 10610//10610 10611//10611 -f 9980//9980 10611//10611 9978//9978 -f 10603//10603 10612//10612 10604//10604 -f 10604//10604 10612//10612 10613//10613 -f 10604//10604 10613//10613 10614//10614 -f 10614//10614 10613//10613 10615//10615 -f 10614//10614 10615//10615 10616//10616 -f 10616//10616 10615//10615 10617//10617 -f 10617//10617 10615//10615 10618//10618 -f 10617//10617 10618//10618 10619//10619 -f 10619//10619 10618//10618 10620//10620 -f 10619//10619 10620//10620 10621//10621 -f 10621//10621 10620//10620 10622//10622 -f 10621//10621 10622//10622 10623//10623 -f 10623//10623 10622//10622 10624//10624 -f 10623//10623 10624//10624 10625//10625 -f 10625//10625 10624//10624 10626//10626 -f 10625//10625 10626//10626 10627//10627 -f 10627//10627 10626//10626 10628//10628 -f 10627//10627 10628//10628 10629//10629 -f 10628//10628 10630//10630 10629//10629 -f 10629//10629 10630//10630 10631//10631 -f 10629//10629 10631//10631 10632//10632 -f 10632//10632 10631//10631 10633//10633 -f 10632//10632 10633//10633 10634//10634 -f 10634//10634 10633//10633 10635//10635 -f 10634//10634 10635//10635 9986//9986 -f 9986//9986 10635//10635 10636//10636 -f 9986//9986 10636//10636 9984//9984 -f 10637//10637 10638//10638 10639//10639 -f 10010//10010 10009//10009 10640//10640 -f 10640//10640 10009//10009 10641//10641 -f 10640//10640 10641//10641 10642//10642 -f 10642//10642 10641//10641 10643//10643 -f 10642//10642 10643//10643 10644//10644 -f 10644//10644 10643//10643 10645//10645 -f 10644//10644 10645//10645 10646//10646 -f 10645//10645 10647//10647 10646//10646 -f 10646//10646 10647//10647 10648//10648 -f 10646//10646 10648//10648 10649//10649 -f 10649//10649 10648//10648 10650//10650 -f 10649//10649 10650//10650 10651//10651 -f 10651//10651 10650//10650 10652//10652 -f 10651//10651 10652//10652 10638//10638 -f 10638//10638 10652//10652 10653//10653 -f 10638//10638 10653//10653 10639//10639 -f 10637//10637 10639//10639 10654//10654 -f 10654//10654 10639//10639 10655//10655 -f 10654//10654 10655//10655 10656//10656 -f 10656//10656 10655//10655 10657//10657 -f 10656//10656 10657//10657 10658//10658 -f 10658//10658 10657//10657 10659//10659 -f 10658//10658 10659//10659 10660//10660 -f 10659//10659 10661//10661 10660//10660 -f 10660//10660 10661//10661 10662//10662 -f 10660//10660 10662//10662 10663//10663 -f 10663//10663 10662//10662 10664//10664 -f 10025//10025 10024//10024 10665//10665 -f 10665//10665 10024//10024 10666//10666 -f 10665//10665 10666//10666 10667//10667 -f 10667//10667 10666//10666 10668//10668 -f 10667//10667 10668//10668 10669//10669 -f 10669//10669 10668//10668 10670//10670 -f 10669//10669 10670//10670 10664//10664 -f 10664//10664 10670//10670 10671//10671 -f 10664//10664 10671//10671 10663//10663 -f 10672//10672 10673//10673 10674//10674 -f 10674//10674 10673//10673 10675//10675 -f 10674//10674 10675//10675 10676//10676 -f 10676//10676 10675//10675 10052//10052 -f 10676//10676 10052//10052 10051//10051 -f 10674//10674 10677//10677 10672//10672 -f 10672//10672 10677//10677 10678//10678 -f 10672//10672 10678//10678 10679//10679 -f 10679//10679 10678//10678 10680//10680 -f 10679//10679 10680//10680 10681//10681 -f 10681//10681 10680//10680 10682//10682 -f 10681//10681 10682//10682 10683//10683 -f 10683//10683 10682//10682 10684//10684 -f 10683//10683 10684//10684 10685//10685 -f 10685//10685 10684//10684 10686//10686 -f 10684//10684 10687//10687 10686//10686 -f 10686//10686 10687//10687 10688//10688 -f 10686//10686 10688//10688 10689//10689 -f 10689//10689 10688//10688 10690//10690 -f 10689//10689 10690//10690 10691//10691 -f 10691//10691 10690//10690 10692//10692 -f 10691//10691 10692//10692 10693//10693 -f 10693//10693 10692//10692 10694//10694 -f 10693//10693 10694//10694 10695//10695 -f 10695//10695 10694//10694 10696//10696 -f 10695//10695 10696//10696 10697//10697 -f 10697//10697 10696//10696 10698//10698 -f 10697//10697 10698//10698 10699//10699 -f 10699//10699 10698//10698 10700//10700 -f 10699//10699 10700//10700 10701//10701 -f 10701//10701 10700//10700 10702//10702 -f 10701//10701 10702//10702 10703//10703 -f 10703//10703 10702//10702 10704//10704 -f 10703//10703 10704//10704 10705//10705 -f 10705//10705 10704//10704 10706//10706 -f 10705//10705 10706//10706 10707//10707 -f 10707//10707 10706//10706 10070//10070 -f 10707//10707 10070//10070 10069//10069 -f 10086//10086 10085//10085 10708//10708 -f 10708//10708 10085//10085 10709//10709 -f 10708//10708 10709//10709 10710//10710 -f 10710//10710 10709//10709 10711//10711 -f 10710//10710 10711//10711 10712//10712 -f 10712//10712 10711//10711 10713//10713 -f 10712//10712 10713//10713 10714//10714 -f 10714//10714 10713//10713 10715//10715 -f 10716//10716 10717//10717 10718//10718 -f 10718//10718 10717//10717 10719//10719 -f 10718//10718 10719//10719 10720//10720 -f 10715//10715 10713//10713 10721//10721 -f 10721//10721 10713//10713 10722//10722 -f 10721//10721 10722//10722 10716//10716 -f 10716//10716 10722//10722 10723//10723 -f 10716//10716 10723//10723 10717//10717 -f 10720//10720 10719//10719 10724//10724 -f 10724//10724 10719//10719 10725//10725 -f 10724//10724 10725//10725 10726//10726 -f 10726//10726 10725//10725 10727//10727 -f 10727//10727 10725//10725 10728//10728 -f 10727//10727 10728//10728 10729//10729 -f 10729//10729 10728//10728 10730//10730 -f 10729//10729 10730//10730 10731//10731 -f 10731//10731 10730//10730 10732//10732 -f 10731//10731 10732//10732 10733//10733 -f 10732//10732 10734//10734 10733//10733 -f 10733//10733 10734//10734 10735//10735 -f 10733//10733 10735//10735 10736//10736 -f 10736//10736 10735//10735 10737//10737 -f 10736//10736 10737//10737 10738//10738 -f 10737//10737 10739//10739 10738//10738 -f 10738//10738 10739//10739 10740//10740 -f 10738//10738 10740//10740 10741//10741 -f 10741//10741 10740//10740 10742//10742 -f 10741//10741 10742//10742 10743//10743 -f 10743//10743 10742//10742 10096//10096 -f 10743//10743 10096//10096 10095//10095 -f 10744//10744 10745//10745 10746//10746 -f 10746//10746 10745//10745 10747//10747 -f 10746//10746 10747//10747 10748//10748 -f 10748//10748 10747//10747 10749//10749 -f 10748//10748 10749//10749 10750//10750 -f 10750//10750 10749//10749 10751//10751 -f 10750//10750 10751//10751 10128//10128 -f 10128//10128 10751//10751 10752//10752 -f 10128//10128 10752//10752 10126//10126 -f 10744//10744 10753//10753 10745//10745 -f 10745//10745 10753//10753 10754//10754 -f 10745//10745 10754//10754 10755//10755 -f 10755//10755 10754//10754 10756//10756 -f 10755//10755 10756//10756 10757//10757 -f 10757//10757 10756//10756 10758//10758 -f 10758//10758 10756//10756 10759//10759 -f 10758//10758 10759//10759 10760//10760 -f 10760//10760 10759//10759 10761//10761 -f 10760//10760 10761//10761 10762//10762 -f 10762//10762 10761//10761 10763//10763 -f 10762//10762 10763//10763 10764//10764 -f 10764//10764 10763//10763 10765//10765 -f 10764//10764 10765//10765 10766//10766 -f 10766//10766 10765//10765 10767//10767 -f 10766//10766 10767//10767 10768//10768 -f 10768//10768 10767//10767 10769//10769 -f 10768//10768 10769//10769 10770//10770 -f 10769//10769 10771//10771 10770//10770 -f 10770//10770 10771//10771 10772//10772 -f 10770//10770 10772//10772 10773//10773 -f 10773//10773 10772//10772 10774//10774 -f 10773//10773 10774//10774 10775//10775 -f 10775//10775 10774//10774 10776//10776 -f 10775//10775 10776//10776 10134//10134 -f 10134//10134 10776//10776 10777//10777 -f 10134//10134 10777//10777 10132//10132 -f 10778//10778 10779//10779 10780//10780 -f 10158//10158 10157//10157 10781//10781 -f 10781//10781 10157//10157 10782//10782 -f 10781//10781 10782//10782 10783//10783 -f 10783//10783 10782//10782 10784//10784 -f 10783//10783 10784//10784 10785//10785 -f 10785//10785 10784//10784 10786//10786 -f 10785//10785 10786//10786 10787//10787 -f 10786//10786 10788//10788 10787//10787 -f 10787//10787 10788//10788 10789//10789 -f 10787//10787 10789//10789 10790//10790 -f 10790//10790 10789//10789 10791//10791 -f 10790//10790 10791//10791 10792//10792 -f 10792//10792 10791//10791 10793//10793 -f 10792//10792 10793//10793 10779//10779 -f 10779//10779 10793//10793 10794//10794 -f 10779//10779 10794//10794 10780//10780 -f 10778//10778 10780//10780 10795//10795 -f 10795//10795 10780//10780 10796//10796 -f 10795//10795 10796//10796 10797//10797 -f 10797//10797 10796//10796 10798//10798 -f 10797//10797 10798//10798 10799//10799 -f 10799//10799 10798//10798 10800//10800 -f 10799//10799 10800//10800 10801//10801 -f 10800//10800 10802//10802 10801//10801 -f 10801//10801 10802//10802 10803//10803 -f 10801//10801 10803//10803 10804//10804 -f 10804//10804 10803//10803 10805//10805 -f 10176//10176 10175//10175 10806//10806 -f 10806//10806 10175//10175 10807//10807 -f 10806//10806 10807//10807 10808//10808 -f 10808//10808 10807//10807 10809//10809 -f 10808//10808 10809//10809 10810//10810 -f 10810//10810 10809//10809 10811//10811 -f 10810//10810 10811//10811 10805//10805 -f 10805//10805 10811//10811 10812//10812 -f 10805//10805 10812//10812 10804//10804 -f 10813//10813 10814//10814 10815//10815 -f 10815//10815 10814//10814 10816//10816 -f 10815//10815 10816//10816 10817//10817 -f 10817//10817 10816//10816 10201//10201 -f 10817//10817 10201//10201 10200//10200 -f 10815//10815 10818//10818 10813//10813 -f 10813//10813 10818//10818 10819//10819 -f 10813//10813 10819//10819 10820//10820 -f 10820//10820 10819//10819 10821//10821 -f 10820//10820 10821//10821 10822//10822 -f 10822//10822 10821//10821 10823//10823 -f 10822//10822 10823//10823 10824//10824 -f 10824//10824 10823//10823 10825//10825 -f 10824//10824 10825//10825 10826//10826 -f 10826//10826 10825//10825 10827//10827 -f 10827//10827 10825//10825 10828//10828 -f 10827//10827 10828//10828 10829//10829 -f 10829//10829 10828//10828 10830//10830 -f 10829//10829 10830//10830 10831//10831 -f 10831//10831 10830//10830 10832//10832 -f 10831//10831 10832//10832 10833//10833 -f 10832//10832 10834//10834 10833//10833 -f 10833//10833 10834//10834 10835//10835 -f 10833//10833 10835//10835 10836//10836 -f 10836//10836 10835//10835 10837//10837 -f 10211//10211 10210//10210 10838//10838 -f 10211//10211 10838//10838 10839//10839 -f 10839//10839 10838//10838 10840//10840 -f 10839//10839 10840//10840 10841//10841 -f 10841//10841 10840//10840 10842//10842 -f 10841//10841 10842//10842 10843//10843 -f 10843//10843 10842//10842 10844//10844 -f 10843//10843 10844//10844 10845//10845 -f 10845//10845 10844//10844 10846//10846 -f 10845//10845 10846//10846 10847//10847 -f 10847//10847 10846//10846 10848//10848 -f 10847//10847 10848//10848 10837//10837 -f 10837//10837 10848//10848 10849//10849 -f 10837//10837 10849//10849 10836//10836 -f 10243//10243 10242//10242 10850//10850 -f 10850//10850 10242//10242 10851//10851 -f 10850//10850 10851//10851 10852//10852 -f 10853//10853 10854//10854 10855//10855 -f 10855//10855 10854//10854 10856//10856 -f 10851//10851 10857//10857 10852//10852 -f 10852//10852 10857//10857 10855//10855 -f 10852//10852 10855//10855 10858//10858 -f 10858//10858 10855//10855 10856//10856 -f 10859//10859 10860//10860 10861//10861 -f 10861//10861 10860//10860 10862//10862 -f 10861//10861 10862//10862 10863//10863 -f 10863//10863 10862//10862 10864//10864 -f 10863//10863 10864//10864 10853//10853 -f 10853//10853 10864//10864 10865//10865 -f 10853//10853 10865//10865 10854//10854 -f 10866//10866 10867//10867 10859//10859 -f 10859//10859 10867//10867 10868//10868 -f 10859//10859 10868//10868 10860//10860 -f 10869//10869 10870//10870 10871//10871 -f 10869//10869 10871//10871 10872//10872 -f 10872//10872 10871//10871 10873//10873 -f 10872//10872 10873//10873 10874//10874 -f 10873//10873 10875//10875 10874//10874 -f 10874//10874 10875//10875 10876//10876 -f 10874//10874 10876//10876 10877//10877 -f 10877//10877 10876//10876 10878//10878 -f 10877//10877 10878//10878 10866//10866 -f 10866//10866 10878//10878 10879//10879 -f 10866//10866 10879//10879 10867//10867 -f 10251//10251 10250//10250 10880//10880 -f 10880//10880 10250//10250 10881//10881 -f 10880//10880 10881//10881 10882//10882 -f 10882//10882 10881//10881 10883//10883 -f 10882//10882 10883//10883 10884//10884 -f 10884//10884 10883//10883 10885//10885 -f 10884//10884 10885//10885 10886//10886 -f 10886//10886 10885//10885 10887//10887 -f 10886//10886 10887//10887 10888//10888 -f 10888//10888 10887//10887 10889//10889 -f 10888//10888 10889//10889 10870//10870 -f 10870//10870 10889//10889 10890//10890 -f 10870//10870 10890//10890 10871//10871 -f 10279//10279 10281//10281 10891//10891 -f 10891//10891 10281//10281 10892//10892 -f 10891//10891 10892//10892 10893//10893 -f 10893//10893 10892//10892 10894//10894 -f 10894//10894 10892//10892 10895//10895 -f 10894//10894 10895//10895 10896//10896 -f 10896//10896 10895//10895 10897//10897 -f 10896//10896 10897//10897 10898//10898 -f 10898//10898 10897//10897 10899//10899 -f 10898//10898 10899//10899 10900//10900 -f 10900//10900 10899//10899 10901//10901 -f 10900//10900 10901//10901 10902//10902 -f 10903//10903 10904//10904 10905//10905 -f 10905//10905 10904//10904 10902//10902 -f 10905//10905 10902//10902 10906//10906 -f 10906//10906 10902//10902 10901//10901 -f 10907//10907 10908//10908 10903//10903 -f 10903//10903 10908//10908 10909//10909 -f 10903//10903 10909//10909 10904//10904 -f 10910//10910 10911//10911 10912//10912 -f 10910//10910 10912//10912 10913//10913 -f 10912//10912 10914//10914 10913//10913 -f 10913//10913 10914//10914 10915//10915 -f 10913//10913 10915//10915 10916//10916 -f 10916//10916 10915//10915 10917//10917 -f 10916//10916 10917//10917 10918//10918 -f 10918//10918 10917//10917 10919//10919 -f 10918//10918 10919//10919 10920//10920 -f 10920//10920 10919//10919 10921//10921 -f 10920//10920 10921//10921 10922//10922 -f 10922//10922 10921//10921 10923//10923 -f 10922//10922 10923//10923 10907//10907 -f 10907//10907 10923//10923 10924//10924 -f 10907//10907 10924//10924 10908//10908 -f 10911//10911 10910//10910 10925//10925 -f 10925//10925 10910//10910 10926//10926 -f 10925//10925 10926//10926 10287//10287 -f 10287//10287 10926//10926 10927//10927 -f 10287//10287 10927//10927 10285//10285 -f 10317//10317 10316//10316 10928//10928 -f 10928//10928 10316//10316 10929//10929 -f 10928//10928 10929//10929 10930//10930 -f 10930//10930 10929//10929 10931//10931 -f 10930//10930 10931//10931 10932//10932 -f 10932//10932 10931//10931 10933//10933 -f 10932//10932 10933//10933 10934//10934 -f 10933//10933 10935//10935 10934//10934 -f 10934//10934 10935//10935 10936//10936 -f 10934//10934 10936//10936 10937//10937 -f 10937//10937 10936//10936 10938//10938 -f 10937//10937 10938//10938 10939//10939 -f 10939//10939 10938//10938 10940//10940 -f 10940//10940 10938//10938 10941//10941 -f 10940//10940 10941//10941 10942//10942 -f 10942//10942 10941//10941 10943//10943 -f 10942//10942 10943//10943 10944//10944 -f 10945//10945 10946//10946 10947//10947 -f 10947//10947 10946//10946 10948//10948 -f 10947//10947 10948//10948 10944//10944 -f 10944//10944 10948//10948 10949//10949 -f 10944//10944 10949//10949 10942//10942 -f 10947//10947 10950//10950 10945//10945 -f 10945//10945 10950//10950 10951//10951 -f 10945//10945 10951//10951 10952//10952 -f 10952//10952 10951//10951 10953//10953 -f 10952//10952 10953//10953 10954//10954 -f 10954//10954 10953//10953 10955//10955 -f 10954//10954 10955//10955 10956//10956 -f 10956//10956 10955//10955 10957//10957 -f 10956//10956 10957//10957 10958//10958 -f 10958//10958 10957//10957 10959//10959 -f 10958//10958 10959//10959 10960//10960 -f 10322//10322 10321//10321 10961//10961 -f 10961//10961 10321//10321 10960//10960 -f 10961//10961 10960//10960 10962//10962 -f 10962//10962 10960//10960 10959//10959 -f 10354//10354 10353//10353 10963//10963 -f 10354//10354 10963//10963 10964//10964 -f 10964//10964 10963//10963 10965//10965 -f 10964//10964 10965//10965 10966//10966 -f 10966//10966 10965//10965 10967//10967 -f 10966//10966 10967//10967 10968//10968 -f 10967//10967 10969//10969 10968//10968 -f 10968//10968 10969//10969 10970//10970 -f 10968//10968 10970//10970 10971//10971 -f 10971//10971 10970//10970 10972//10972 -f 10971//10971 10972//10972 10973//10973 -f 10973//10973 10972//10972 10974//10974 -f 10973//10973 10974//10974 10975//10975 -f 10975//10975 10974//10974 10976//10976 -f 10974//10974 10977//10977 10976//10976 -f 10976//10976 10977//10977 10978//10978 -f 10976//10976 10978//10978 10979//10979 -f 10979//10979 10978//10978 10980//10980 -f 10979//10979 10980//10980 10981//10981 -f 10981//10981 10980//10980 10982//10982 -f 10980//10980 10983//10983 10982//10982 -f 10982//10982 10983//10983 10984//10984 -f 10982//10982 10984//10984 10985//10985 -f 10985//10985 10984//10984 10986//10986 -f 10985//10985 10986//10986 10987//10987 -f 10986//10986 10988//10988 10987//10987 -f 10987//10987 10988//10988 10989//10989 -f 10987//10987 10989//10989 10990//10990 -f 10990//10990 10989//10989 10991//10991 -f 10990//10990 10991//10991 10992//10992 -f 10992//10992 10991//10991 10993//10993 -f 10992//10992 10993//10993 10994//10994 -f 10994//10994 10993//10993 10995//10995 -f 10994//10994 10995//10995 10996//10996 -f 10996//10996 10995//10995 10377//10377 -f 10996//10996 10377//10377 10376//10376 -f 10997//10997 10998//10998 10999//10999 -f 10999//10999 10998//10998 11000//11000 -f 10999//10999 11000//11000 11001//11001 -f 11001//11001 11000//11000 11002//11002 -f 11001//11001 11002//11002 11003//11003 -f 11003//11003 11002//11002 11004//11004 -f 11003//11003 11004//11004 10389//10389 -f 10389//10389 11004//11004 11005//11005 -f 10389//10389 11005//11005 10390//10390 -f 10999//10999 11006//11006 10997//10997 -f 10997//10997 11006//11006 11007//11007 -f 10997//10997 11007//11007 11008//11008 -f 11008//11008 11007//11007 11009//11009 -f 11008//11008 11009//11009 11010//11010 -f 11010//11010 11009//11009 11011//11011 -f 11010//11010 11011//11011 11012//11012 -f 11012//11012 11011//11011 11013//11013 -f 9654//9654 9653//9653 11014//11014 -f 11014//11014 9653//9653 11015//11015 -f 11014//11014 11015//11015 11016//11016 -f 11016//11016 11015//11015 11017//11017 -f 11016//11016 11017//11017 11018//11018 -f 11018//11018 11017//11017 11019//11019 -f 11018//11018 11019//11019 11020//11020 -f 11020//11020 11019//11019 11021//11021 -f 11020//11020 11021//11021 11022//11022 -f 11022//11022 11021//11021 11023//11023 -f 11022//11022 11023//11023 11024//11024 -f 11024//11024 11023//11023 11025//11025 -f 11024//11024 11025//11025 11026//11026 -f 11026//11026 11025//11025 11027//11027 -f 11026//11026 11027//11027 11028//11028 -f 11028//11028 11027//11027 11029//11029 -f 11028//11028 11029//11029 11030//11030 -f 11030//11030 11029//11029 11013//11013 -f 11030//11030 11013//11013 11031//11031 -f 11031//11031 11013//11013 11011//11011 -f 9638//9638 11032//11032 9639//9639 -f 9639//9639 11032//11032 11033//11033 -f 9639//9639 11033//11033 9640//9640 -f 11033//11033 11034//11034 9640//9640 -f 9640//9640 11034//11034 11035//11035 -f 9640//9640 11035//11035 9641//9641 -f 9641//9641 11035//11035 11036//11036 -f 9641//9641 11036//11036 9642//9642 -f 9642//9642 11036//11036 11037//11037 -f 9642//9642 11037//11037 9645//9645 -f 9645//9645 11037//11037 11038//11038 -f 9645//9645 11038//11038 9582//9582 -f 9582//9582 11038//11038 11039//11039 -f 9582//9582 11039//11039 9583//9583 -f 9583//9583 11039//11039 11040//11040 -f 9583//9583 11040//11040 9649//9649 -f 9649//9649 11040//11040 11041//11041 -f 9649//9649 11041//11041 11042//11042 -f 11042//11042 11041//11041 9543//9543 -f 11042//11042 9543//9543 11043//11043 -f 11043//11043 9543//9543 9545//9545 -f 11043//11043 9545//9545 11044//11044 -f 11044//11044 9545//9545 9547//9547 -f 11044//11044 9547//9547 11045//11045 -f 11045//11045 9547//9547 9551//9551 -f 11045//11045 9551//9551 11046//11046 -f 11046//11046 9551//9551 9550//9550 -f 11046//11046 9550//9550 11047//11047 -f 11047//11047 9550//9550 9558//9558 -f 11047//11047 9558//9558 11048//11048 -f 11048//11048 9558//9558 9557//9557 -f 9553//9553 11049//11049 9555//9555 -f 9555//9555 11049//11049 11050//11050 -f 9555//9555 11050//11050 9557//9557 -f 9557//9557 11050//11050 11051//11051 -f 9557//9557 11051//11051 11048//11048 -f 9684//9684 9683//9683 11052//11052 -f 11052//11052 9683//9683 11053//11053 -f 11052//11052 11053//11053 11054//11054 -f 11053//11053 11055//11055 11054//11054 -f 11054//11054 11055//11055 11056//11056 -f 11054//11054 11056//11056 11057//11057 -f 11057//11057 11056//11056 11058//11058 -f 11056//11056 11059//11059 11058//11058 -f 11058//11058 11059//11059 11060//11060 -f 11058//11058 11060//11060 11061//11061 -f 11061//11061 11060//11060 11062//11062 -f 11061//11061 11062//11062 11063//11063 -f 9524//9524 9526//9526 9749//9749 -f 9526//9526 9527//9527 9749//9749 -f 9749//9749 9527//9527 9529//9529 -f 9749//9749 9529//9529 766//766 -f 9524//9524 9749//9749 9523//9523 -f 9523//9523 9749//9749 9751//9751 -f 9523//9523 9751//9751 9521//9521 -f 9521//9521 9751//9751 9519//9519 -f 9519//9519 9751//9751 9746//9746 -f 9519//9519 9746//9746 9513//9513 -f 11064//11064 11065//11065 9741//9741 -f 11066//11066 11067//11067 9725//9725 -f 9725//9725 11067//11067 9731//9731 -f 9538//9538 9540//9540 9727//9727 -f 11065//11065 9518//9518 9741//9741 -f 9741//9741 9518//9518 9517//9517 -f 9741//9741 9517//9517 9746//9746 -f 9746//9746 9517//9517 9514//9514 -f 9746//9746 9514//9514 9513//9513 -f 9540//9540 9542//9542 9727//9727 -f 9727//9727 9542//9542 11068//11068 -f 9727//9727 11068//11068 9725//9725 -f 9725//9725 11068//11068 11069//11069 -f 9725//9725 11069//11069 11066//11066 -f 11064//11064 9741//9741 11070//11070 -f 11070//11070 9741//9741 9743//9743 -f 11070//11070 9743//9743 11071//11071 -f 11071//11071 9743//9743 11072//11072 -f 11072//11072 9743//9743 9739//9739 -f 11072//11072 9739//9739 11073//11073 -f 9538//9538 9727//9727 9537//9537 -f 9537//9537 9727//9727 9696//9696 -f 9537//9537 9696//9696 9535//9535 -f 9535//9535 9696//9696 9533//9533 -f 9533//9533 9696//9696 9693//9693 -f 9533//9533 9693//9693 9510//9510 -f 9529//9529 9531//9531 766//766 -f 766//766 9531//9531 9532//9532 -f 766//766 9532//9532 9693//9693 -f 9693//9693 9532//9532 9511//9511 -f 9693//9693 9511//9511 9510//9510 -f 778//778 11074//11074 9739//9739 -f 9739//9739 11074//11074 11075//11075 -f 9739//9739 11075//11075 11073//11073 -f 11067//11067 11076//11076 9731//9731 -f 9731//9731 11076//11076 11077//11077 -f 9731//9731 11077//11077 9734//9734 -f 9734//9734 11077//11077 11078//11078 -f 9734//9734 11078//11078 11079//11079 -f 11079//11079 11080//11080 9734//9734 -f 9734//9734 11080//11080 11081//11081 -f 9734//9734 11081//11081 778//778 -f 778//778 11081//11081 11082//11082 -f 778//778 11082//11082 11074//11074 -f 9694//9694 11083//11083 9695//9695 -f 11083//11083 9694//9694 9729//9729 -f 9726//9726 9724//9724 11084//11084 -f 9735//9735 11085//11085 11086//11086 -f 9688//9688 11087//11087 9689//9689 -f 9689//9689 11087//11087 11088//11088 -f 9689//9689 11088//11088 9698//9698 -f 9698//9698 11088//11088 9699//9699 -f 9699//9699 11088//11088 11089//11089 -f 9699//9699 11089//11089 9701//9701 -f 9701//9701 11089//11089 9702//9702 -f 9702//9702 11089//11089 11090//11090 -f 9702//9702 11090//11090 9703//9703 -f 9703//9703 11090//11090 9704//9704 -f 9704//9704 11090//11090 11091//11091 -f 9704//9704 11091//11091 9692//9692 -f 9692//9692 11091//11091 11092//11092 -f 9692//9692 11092//11092 9691//9691 -f 9691//9691 11092//11092 11093//11093 -f 9691//9691 11093//11093 9754//9754 -f 9754//9754 11093//11093 11094//11094 -f 9754//9754 11094//11094 9755//9755 -f 9755//9755 11094//11094 11095//11095 -f 9755//9755 11095//11095 9756//9756 -f 9756//9756 11095//11095 11096//11096 -f 9756//9756 11096//11096 9750//9750 -f 9750//9750 11096//11096 11097//11097 -f 9750//9750 11097//11097 9752//9752 -f 9752//9752 11097//11097 11098//11098 -f 9752//9752 11098//11098 9753//9753 -f 11098//11098 11099//11099 9753//9753 -f 9753//9753 11099//11099 11100//11100 -f 9753//9753 11100//11100 9747//9747 -f 11100//11100 11101//11101 9747//9747 -f 9747//9747 11101//11101 11102//11102 -f 9747//9747 11102//11102 9748//9748 -f 9748//9748 11102//11102 11103//11103 -f 9748//9748 11103//11103 9742//9742 -f 11103//11103 11104//11104 9742//9742 -f 9742//9742 11104//11104 11105//11105 -f 9742//9742 11105//11105 9744//9744 -f 9744//9744 11105//11105 9745//9745 -f 9745//9745 11105//11105 11106//11106 -f 9745//9745 11106//11106 9740//9740 -f 9740//9740 11106//11106 11107//11107 -f 9740//9740 11107//11107 9738//9738 -f 11107//11107 11108//11108 9738//9738 -f 9738//9738 11108//11108 11109//11109 -f 9738//9738 11109//11109 9737//9737 -f 11109//11109 11110//11110 9737//9737 -f 9737//9737 11110//11110 11111//11111 -f 9737//9737 11111//11111 9736//9736 -f 9736//9736 11111//11111 11112//11112 -f 9736//9736 11112//11112 9735//9735 -f 9735//9735 11112//11112 11113//11113 -f 9735//9735 11113//11113 11085//11085 -f 11084//11084 9724//9724 11114//11114 -f 9724//9724 9723//9723 11114//11114 -f 11114//11114 9723//9723 9730//9730 -f 11114//11114 9730//9730 11115//11115 -f 11115//11115 9730//9730 9732//9732 -f 11115//11115 9732//9732 11086//11086 -f 11086//11086 9732//9732 9733//9733 -f 11086//11086 9733//9733 9735//9735 -f 9726//9726 11084//11084 9728//9728 -f 9728//9728 11084//11084 11116//11116 -f 9728//9728 11116//11116 9729//9729 -f 9729//9729 11116//11116 11117//11117 -f 9729//9729 11117//11117 11083//11083 -f 11037//11037 11036//11036 11118//11118 -f 11118//11118 11036//11036 11119//11119 -f 11073//11073 11075//11075 11120//11120 -f 11066//11066 11069//11069 11121//11121 -f 11121//11121 11069//11069 9541//9541 -f 9541//9541 11069//11069 11068//11068 -f 9541//9541 11068//11068 9542//9542 -f 11066//11066 11121//11121 11067//11067 -f 11067//11067 11121//11121 11122//11122 -f 11067//11067 11122//11122 11076//11076 -f 11076//11076 11122//11122 11123//11123 -f 11076//11076 11123//11123 11077//11077 -f 11077//11077 11123//11123 11078//11078 -f 11078//11078 11123//11123 11124//11124 -f 11078//11078 11124//11124 11079//11079 -f 11079//11079 11124//11124 11080//11080 -f 11080//11080 11124//11124 11125//11125 -f 11080//11080 11125//11125 11081//11081 -f 11081//11081 11125//11125 11126//11126 -f 11081//11081 11126//11126 11082//11082 -f 11120//11120 11075//11075 11126//11126 -f 11126//11126 11075//11075 11074//11074 -f 11126//11126 11074//11074 11082//11082 -f 11073//11073 11120//11120 11072//11072 -f 11072//11072 11120//11120 11127//11127 -f 11072//11072 11127//11127 11071//11071 -f 11071//11071 11127//11127 11128//11128 -f 11071//11071 11128//11128 11070//11070 -f 11070//11070 11128//11128 11064//11064 -f 11064//11064 11128//11128 11129//11129 -f 11064//11064 11129//11129 11065//11065 -f 11065//11065 11129//11129 9516//9516 -f 11065//11065 9516//9516 9518//9518 -f 9569//9569 9568//9568 11130//11130 -f 11130//11130 9568//9568 11131//11131 -f 11130//11130 11131//11131 11132//11132 -f 11132//11132 11131//11131 11133//11133 -f 11134//11134 11135//11135 11133//11133 -f 11133//11133 11135//11135 11136//11136 -f 11133//11133 11136//11136 11132//11132 -f 11137//11137 11032//11032 11138//11138 -f 11138//11138 11032//11032 11139//11139 -f 11138//11138 11139//11139 11140//11140 -f 11140//11140 11139//11139 11141//11141 -f 11140//11140 11141//11141 11134//11134 -f 11134//11134 11141//11141 11142//11142 -f 11134//11134 11142//11142 11135//11135 -f 11036//11036 11035//11035 11119//11119 -f 11119//11119 11035//11035 11034//11034 -f 11119//11119 11034//11034 11137//11137 -f 11137//11137 11034//11034 11033//11033 -f 11137//11137 11033//11033 11032//11032 -f 11037//11037 11118//11118 11038//11038 -f 11038//11038 11118//11118 11143//11143 -f 11038//11038 11143//11143 11039//11039 -f 11039//11039 11143//11143 11144//11144 -f 11039//11039 11144//11144 11040//11040 -f 11040//11040 11144//11144 11041//11041 -f 11041//11041 11144//11144 9544//9544 -f 11041//11041 9544//9544 9543//9543 -f 9581//9581 9544//9544 11145//11145 -f 11145//11145 9544//9544 11144//11144 -f 11145//11145 11144//11144 11146//11146 -f 11146//11146 11144//11144 11143//11143 -f 11146//11146 11143//11143 11147//11147 -f 11147//11147 11143//11143 11118//11118 -f 11147//11147 11118//11118 11148//11148 -f 11148//11148 11118//11118 11119//11119 -f 11148//11148 11119//11119 11149//11149 -f 11149//11149 11119//11119 11137//11137 -f 11149//11149 11137//11137 11150//11150 -f 11150//11150 11137//11137 11138//11138 -f 11150//11150 11138//11138 11151//11151 -f 11151//11151 11138//11138 11140//11140 -f 11151//11151 11140//11140 11152//11152 -f 11152//11152 11140//11140 11134//11134 -f 11152//11152 11134//11134 11153//11153 -f 11153//11153 11134//11134 11133//11133 -f 11153//11153 11133//11133 11154//11154 -f 11154//11154 11133//11133 11131//11131 -f 11154//11154 11131//11131 9570//9570 -f 9570//9570 11131//11131 9568//9568 -f 9541//9541 9581//9581 11121//11121 -f 11121//11121 9581//9581 11145//11145 -f 11121//11121 11145//11145 11122//11122 -f 11122//11122 11145//11145 11146//11146 -f 11122//11122 11146//11146 11123//11123 -f 11123//11123 11146//11146 11147//11147 -f 11123//11123 11147//11147 11124//11124 -f 11124//11124 11147//11147 11148//11148 -f 11124//11124 11148//11148 11125//11125 -f 11125//11125 11148//11148 11149//11149 -f 11125//11125 11149//11149 11126//11126 -f 11126//11126 11149//11149 11150//11150 -f 11126//11126 11150//11150 11120//11120 -f 11120//11120 11150//11150 11151//11151 -f 11120//11120 11151//11151 11127//11127 -f 11127//11127 11151//11151 11152//11152 -f 11127//11127 11152//11152 11128//11128 -f 11128//11128 11152//11152 11153//11153 -f 11128//11128 11153//11153 11129//11129 -f 11129//11129 11153//11153 11154//11154 -f 11129//11129 11154//11154 9516//9516 -f 9516//9516 11154//11154 9570//9570 -f 11100//11100 11099//11099 10395//10395 -f 9757//9757 9759//9759 11087//11087 -f 11087//11087 9759//9759 11088//11088 -f 9759//9759 9761//9761 11088//11088 -f 11088//11088 9761//9761 9762//9762 -f 11088//11088 9762//9762 11089//11089 -f 9762//9762 9764//9764 11089//11089 -f 11089//11089 9764//9764 9766//9766 -f 11089//11089 9766//9766 11090//11090 -f 11090//11090 9766//9766 9768//9768 -f 11090//11090 9768//9768 11091//11091 -f 11091//11091 9768//9768 9773//9773 -f 11091//11091 9773//9773 11092//11092 -f 11092//11092 9773//9773 9772//9772 -f 11092//11092 9772//9772 11093//11093 -f 11093//11093 9772//9772 9770//9770 -f 11093//11093 9770//9770 11094//11094 -f 9770//9770 10424//10424 11094//11094 -f 11094//11094 10424//10424 10423//10423 -f 11094//11094 10423//10423 11095//11095 -f 10395//10395 11099//11099 10414//10414 -f 10423//10423 10419//10419 11095//11095 -f 11095//11095 10419//10419 10417//10417 -f 11095//11095 10417//10417 11096//11096 -f 11096//11096 10417//10417 10416//10416 -f 11096//11096 10416//10416 11097//11097 -f 11097//11097 10416//10416 10414//10414 -f 11097//11097 10414//10414 11098//11098 -f 11098//11098 10414//10414 11099//11099 -f 11100//11100 10395//10395 11101//11101 -f 11101//11101 10395//10395 10398//10398 -f 11101//11101 10398//10398 11102//11102 -f 11102//11102 10398//10398 10400//10400 -f 11102//11102 10400//10400 11103//11103 -f 11103//11103 10400//10400 10402//10402 -f 11103//11103 10402//10402 10404//10404 -f 10406//10406 11105//11105 10404//10404 -f 10404//10404 11105//11105 11104//11104 -f 10404//10404 11104//11104 11103//11103 -f 11107//11107 11106//11106 10410//10410 -f 10410//10410 11106//11106 11105//11105 -f 10410//10410 11105//11105 10408//10408 -f 10408//10408 11105//11105 10406//10406 -f 11107//11107 10410//10410 11108//11108 -f 11108//11108 10410//10410 10394//10394 -f 11108//11108 10394//10394 11109//11109 -f 11109//11109 10394//10394 9712//9712 -f 11109//11109 9712//9712 11110//11110 -f 11110//11110 9712//9712 9711//9711 -f 11110//11110 9711//9711 11111//11111 -f 11111//11111 9711//9711 11112//11112 -f 11112//11112 9711//9711 9716//9716 -f 11112//11112 9716//9716 11113//11113 -f 11113//11113 9716//9716 9718//9718 -f 11113//11113 9718//9718 9720//9720 -f 11114//11114 11115//11115 9710//9710 -f 9710//9710 11115//11115 11086//11086 -f 9710//9710 11086//11086 9720//9720 -f 9720//9720 11086//11086 11085//11085 -f 9720//9720 11085//11085 11113//11113 -f 9710//9710 9708//9708 11114//11114 -f 11114//11114 9708//9708 9706//9706 -f 11114//11114 9706//9706 11084//11084 -f 11084//11084 9706//9706 9705//9705 -f 11084//11084 9705//9705 11116//11116 -f 11116//11116 9705//9705 9690//9690 -f 11116//11116 9690//9690 11117//11117 -f 11117//11117 9690//9690 9697//9697 -f 11117//11117 9697//9697 11083//11083 -f 11083//11083 9697//9697 9700//9700 -f 11083//11083 9700//9700 9695//9695 -f 11049//11049 9553//9553 11155//11155 -f 11155//11155 9553//9553 9561//9561 -f 11155//11155 9561//9561 11156//11156 -f 9561//9561 9560//9560 11156//11156 -f 11156//11156 9560//9560 9559//9559 -f 11156//11156 9559//9559 11157//11157 -f 11157//11157 9559//9559 9507//9507 -f 11157//11157 9507//9507 11158//11158 -f 11158//11158 9507//9507 9506//9506 -f 11158//11158 9506//9506 11159//11159 -f 11159//11159 9506//9506 9562//9562 -f 11159//11159 9562//9562 11160//11160 -f 11160//11160 9562//9562 9564//9564 -f 11160//11160 9564//9564 11161//11161 -f 11161//11161 9564//9564 9566//9566 -f 11161//11161 9566//9566 9616//9616 -f 9616//9616 9566//9566 9567//9567 -f 9616//9616 9567//9567 9617//9617 -f 9617//9617 9567//9567 9569//9569 -f 9617//9617 9569//9569 9620//9620 -f 9620//9620 9569//9569 11130//11130 -f 9620//9620 11130//11130 9625//9625 -f 9625//9625 11130//11130 11132//11132 -f 9625//9625 11132//11132 9626//9626 -f 9626//9626 11132//11132 11136//11136 -f 9626//9626 11136//11136 9627//9627 -f 9627//9627 11136//11136 11135//11135 -f 9627//9627 11135//11135 9630//9630 -f 9630//9630 11135//11135 11142//11142 -f 9630//9630 11142//11142 9631//9631 -f 9631//9631 11142//11142 11141//11141 -f 11032//11032 9638//9638 11139//11139 -f 11139//11139 9638//9638 9637//9637 -f 11139//11139 9637//9637 11141//11141 -f 11141//11141 9637//9637 9632//9632 -f 11141//11141 9632//9632 9631//9631 -f 11160//11160 11161//11161 11162//11162 -f 11163//11163 11164//11164 11165//11165 -f 11166//11166 11167//11167 11168//11168 -f 11169//11169 9602//9602 9601//9601 -f 11169//11169 9601//9601 11170//11170 -f 11171//11171 11172//11172 11173//11173 -f 11174//11174 11175//11175 11172//11172 -f 11176//11176 11177//11177 11175//11175 -f 11178//11178 11179//11179 11163//11163 -f 11163//11163 11179//11179 11180//11180 -f 11163//11163 11180//11180 11164//11164 -f 11164//11164 11180//11180 11181//11181 -f 11164//11164 11181//11181 11182//11182 -f 11183//11183 11184//11184 11185//11185 -f 11185//11185 11184//11184 11166//11166 -f 11186//11186 11187//11187 11183//11183 -f 9604//9604 9624//9624 11187//11187 -f 11188//11188 11165//11165 11189//11189 -f 11189//11189 11165//11165 11164//11164 -f 11189//11189 11164//11164 11176//11176 -f 11176//11176 11164//11164 11182//11182 -f 11176//11176 11182//11182 11177//11177 -f 11190//11190 11191//11191 11168//11168 -f 11192//11192 11191//11191 11193//11193 -f 11193//11193 11191//11191 11190//11190 -f 11193//11193 11190//11190 11194//11194 -f 9648//9648 9649//9649 11042//11042 -f 11170//11170 9601//9601 11195//11195 -f 11195//11195 9601//9601 9647//9647 -f 11195//11195 9647//9647 11196//11196 -f 11196//11196 9647//9647 9648//9648 -f 11196//11196 9648//9648 11197//11197 -f 11197//11197 9648//9648 11042//11042 -f 11197//11197 11042//11042 11043//11043 -f 11043//11043 11198//11198 11197//11197 -f 11197//11197 11198//11198 11199//11199 -f 11197//11197 11199//11199 11196//11196 -f 11196//11196 11199//11199 11171//11171 -f 11196//11196 11171//11171 11195//11195 -f 11195//11195 11171//11171 11173//11173 -f 11195//11195 11173//11173 11170//11170 -f 11043//11043 11044//11044 11198//11198 -f 11198//11198 11044//11044 11045//11045 -f 11198//11198 11045//11045 11046//11046 -f 11172//11172 11171//11171 11174//11174 -f 11174//11174 11171//11171 11199//11199 -f 11174//11174 11199//11199 11200//11200 -f 11200//11200 11199//11199 11198//11198 -f 11200//11200 11198//11198 11201//11201 -f 11201//11201 11198//11198 11046//11046 -f 11201//11201 11046//11046 11047//11047 -f 11175//11175 11174//11174 11176//11176 -f 11176//11176 11174//11174 11200//11200 -f 11176//11176 11200//11200 11189//11189 -f 11189//11189 11200//11200 11201//11201 -f 11189//11189 11201//11201 11188//11188 -f 11188//11188 11201//11201 11047//11047 -f 11188//11188 11047//11047 11048//11048 -f 11048//11048 11051//11051 11188//11188 -f 11188//11188 11051//11051 11202//11202 -f 11188//11188 11202//11202 11165//11165 -f 11165//11165 11202//11202 11203//11203 -f 11165//11165 11203//11203 11163//11163 -f 11163//11163 11203//11203 11204//11204 -f 11163//11163 11204//11204 11178//11178 -f 11178//11178 11204//11204 11205//11205 -f 11051//11051 11050//11050 11202//11202 -f 11202//11202 11050//11050 11194//11194 -f 11202//11202 11194//11194 11203//11203 -f 11203//11203 11194//11194 11190//11190 -f 11203//11203 11190//11190 11204//11204 -f 11204//11204 11190//11190 11168//11168 -f 11204//11204 11168//11168 11205//11205 -f 11205//11205 11168//11168 11167//11167 -f 11050//11050 11049//11049 11194//11194 -f 11194//11194 11049//11049 11155//11155 -f 11194//11194 11155//11155 11193//11193 -f 11193//11193 11155//11155 11156//11156 -f 11193//11193 11156//11156 11192//11192 -f 11192//11192 11156//11156 11157//11157 -f 11192//11192 11157//11157 11158//11158 -f 11166//11166 11168//11168 11185//11185 -f 11185//11185 11168//11168 11191//11191 -f 11185//11185 11191//11191 11206//11206 -f 11206//11206 11191//11191 11192//11192 -f 11206//11206 11192//11192 11207//11207 -f 11207//11207 11192//11192 11158//11158 -f 11207//11207 11158//11158 11159//11159 -f 11183//11183 11185//11185 11186//11186 -f 11186//11186 11185//11185 11206//11206 -f 11186//11186 11206//11206 11208//11208 -f 11208//11208 11206//11206 11207//11207 -f 11208//11208 11207//11207 11162//11162 -f 11162//11162 11207//11207 11159//11159 -f 11162//11162 11159//11159 11160//11160 -f 11187//11187 11186//11186 9604//9604 -f 9604//9604 11186//11186 11208//11208 -f 9604//9604 11208//11208 9605//9605 -f 9605//9605 11208//11208 11162//11162 -f 9605//9605 11162//11162 9615//9615 -f 9615//9615 11162//11162 11161//11161 -f 9615//9615 11161//11161 9616//9616 -f 11209//11209 11210//11210 10525//10525 -f 10525//10525 11210//11210 10527//10527 -f 10527//10527 11210//11210 11211//11211 -f 10527//10527 11211//11211 10529//10529 -f 10529//10529 11211//11211 11212//11212 -f 10529//10529 11212//11212 10530//10530 -f 10530//10530 11212//11212 10522//10522 -f 10522//10522 11212//11212 11213//11213 -f 10522//10522 11213//11213 10519//10519 -f 10519//10519 11213//11213 11214//11214 -f 10519//10519 11214//11214 10517//10517 -f 10517//10517 11214//11214 11215//11215 -f 10517//10517 11215//11215 10515//10515 -f 10515//10515 11215//11215 10513//10513 -f 10513//10513 11215//11215 11216//11216 -f 10513//10513 11216//11216 10496//10496 -f 10496//10496 11216//11216 10497//10497 -f 10497//10497 11216//11216 11217//11217 -f 10497//10497 11217//11217 10510//10510 -f 10510//10510 11217//11217 11218//11218 -f 10510//10510 11218//11218 11219//11219 -f 11220//11220 10505//10505 11219//11219 -f 11219//11219 10505//10505 10508//10508 -f 11219//11219 10508//10508 10510//10510 -f 11221//11221 9864//9864 11222//11222 -f 11222//11222 9864//9864 9862//9862 -f 11222//11222 9862//9862 11223//11223 -f 11223//11223 9862//9862 10499//10499 -f 11223//11223 10499//10499 11224//11224 -f 11224//11224 10499//10499 10501//10501 -f 11224//11224 10501//10501 11220//11220 -f 11220//11220 10501//10501 10503//10503 -f 11220//11220 10503//10503 10505//10505 -f 11225//11225 9852//9852 11226//11226 -f 11226//11226 9852//9852 9870//9870 -f 11226//11226 9870//9870 11227//11227 -f 11227//11227 9870//9870 9869//9869 -f 11227//11227 9869//9869 11228//11228 -f 11228//11228 9869//9869 9867//9867 -f 11228//11228 9867//9867 11221//11221 -f 11221//11221 9867//9867 9866//9866 -f 11221//11221 9866//9866 9864//9864 -f 11229//11229 9859//9859 11230//11230 -f 11230//11230 9859//9859 9857//9857 -f 11230//11230 9857//9857 11231//11231 -f 11231//11231 9857//9857 9855//9855 -f 11231//11231 9855//9855 11225//11225 -f 11225//11225 9855//9855 9853//9853 -f 11225//11225 9853//9853 9852//9852 -f 11232//11232 9849//9849 11233//11233 -f 11233//11233 9849//9849 9848//9848 -f 11233//11233 9848//9848 11229//11229 -f 11229//11229 9848//9848 9860//9860 -f 11229//11229 9860//9860 9859//9859 -f 9842//9842 9840//9840 11234//11234 -f 11234//11234 9840//9840 9851//9851 -f 11234//11234 9851//9851 11232//11232 -f 11232//11232 9851//9851 9850//9850 -f 11232//11232 9850//9850 9849//9849 -f 11234//11234 11235//11235 9842//9842 -f 9842//9842 11235//11235 11236//11236 -f 9842//9842 11236//11236 9844//9844 -f 9844//9844 11236//11236 11237//11237 -f 9844//9844 11237//11237 9845//9845 -f 9845//9845 11237//11237 11238//11238 -f 9845//9845 11238//11238 9835//9835 -f 9835//9835 11238//11238 11239//11239 -f 10493//10493 11239//11239 11240//11240 -f 10493//10493 9838//9838 11239//11239 -f 11239//11239 9838//9838 9837//9837 -f 11239//11239 9837//9837 9835//9835 -f 11240//11240 11241//11241 10493//10493 -f 10493//10493 11241//11241 11242//11242 -f 10493//10493 11242//11242 10491//10491 -f 10491//10491 11242//11242 10488//10488 -f 10488//10488 11242//11242 11243//11243 -f 10488//10488 11243//11243 10486//10486 -f 10486//10486 11243//11243 11244//11244 -f 10486//10486 11244//11244 10484//10484 -f 10484//10484 11244//11244 11245//11245 -f 10484//10484 11245//11245 10482//10482 -f 10482//10482 11245//11245 10480//10480 -f 10480//10480 11245//11245 11246//11246 -f 10480//10480 11246//11246 10478//10478 -f 11246//11246 11247//11247 10478//10478 -f 10478//10478 11247//11247 11248//11248 -f 10478//10478 11248//11248 10476//10476 -f 10476//10476 11248//11248 11249//11249 -f 10476//10476 11249//11249 10475//10475 -f 10475//10475 11249//11249 11250//11250 -f 10475//10475 11250//11250 10473//10473 -f 10473//10473 11250//11250 11251//11251 -f 10473//10473 11251//11251 10463//10463 -f 10463//10463 11251//11251 11252//11252 -f 10463//10463 11252//11252 10465//10465 -f 10465//10465 11252//11252 11253//11253 -f 10465//10465 11253//11253 10467//10467 -f 10467//10467 11253//11253 11254//11254 -f 10467//10467 11254//11254 10469//10469 -f 10469//10469 11254//11254 11255//11255 -f 10469//10469 11255//11255 10470//10470 -f 10470//10470 11255//11255 11256//11256 -f 10470//10470 11256//11256 9830//9830 -f 9830//9830 11256//11256 11257//11257 -f 9830//9830 11257//11257 9828//9828 -f 9828//9828 11257//11257 11258//11258 -f 9828//9828 11258//11258 9826//9826 -f 9826//9826 11258//11258 11259//11259 -f 9826//9826 11259//11259 9824//9824 -f 9824//9824 11259//11259 11260//11260 -f 9824//9824 11260//11260 9822//9822 -f 9822//9822 11260//11260 11261//11261 -f 9822//9822 11261//11261 9820//9820 -f 9820//9820 11261//11261 11262//11262 -f 9820//9820 11262//11262 9796//9796 -f 9796//9796 11262//11262 11263//11263 -f 9796//9796 11263//11263 9797//9797 -f 9797//9797 11263//11263 11264//11264 -f 9797//9797 11264//11264 9817//9817 -f 9817//9817 11264//11264 11265//11265 -f 9817//9817 11265//11265 9816//9816 -f 9816//9816 11265//11265 11266//11266 -f 9816//9816 11266//11266 9814//9814 -f 9814//9814 11266//11266 11267//11267 -f 9814//9814 11267//11267 9811//9811 -f 9811//9811 11267//11267 11268//11268 -f 11269//11269 9807//9807 11268//11268 -f 11268//11268 9807//9807 9809//9809 -f 11268//11268 9809//9809 9811//9811 -f 11270//11270 9803//9803 11269//11269 -f 11269//11269 9803//9803 9805//9805 -f 11269//11269 9805//9805 9807//9807 -f 11271//11271 9799//9799 11270//11270 -f 11270//11270 9799//9799 9801//9801 -f 11270//11270 9801//9801 9803//9803 -f 11272//11272 10459//10459 11271//11271 -f 11271//11271 10459//10459 10461//10461 -f 11271//11271 10461//10461 9799//9799 -f 11273//11273 10449//10449 11274//11274 -f 11274//11274 10449//10449 10451//10451 -f 11274//11274 10451//10451 11275//11275 -f 11275//11275 10451//10451 10454//10454 -f 11275//11275 10454//10454 11272//11272 -f 11272//11272 10454//10454 10456//10456 -f 11272//11272 10456//10456 10459//10459 -f 11276//11276 10444//10444 11277//11277 -f 11277//11277 10444//10444 10445//10445 -f 11277//11277 10445//10445 11273//11273 -f 11273//11273 10445//10445 10447//10447 -f 11273//11273 10447//10447 10449//10449 -f 10439//10439 10434//10434 11278//11278 -f 11278//11278 10434//10434 10436//10436 -f 11278//11278 10436//10436 11279//11279 -f 11279//11279 10436//10436 10438//10438 -f 11279//11279 10438//10438 11276//11276 -f 11276//11276 10438//10438 10442//10442 -f 11276//11276 10442//10442 10444//10444 -f 10439//10439 11278//11278 11280//11280 -f 10439//10439 11280//11280 10433//10433 -f 10433//10433 11280//11280 11281//11281 -f 11282//11282 9790//9790 11283//11283 -f 11283//11283 9790//9790 10426//10426 -f 11283//11283 10426//10426 11284//11284 -f 11284//11284 10426//10426 10428//10428 -f 11284//11284 10428//10428 11285//11285 -f 11285//11285 10428//10428 10430//10430 -f 11285//11285 10430//10430 11281//11281 -f 11281//11281 10430//10430 10432//10432 -f 11281//11281 10432//10432 10433//10433 -f 9777//9777 9784//9784 11286//11286 -f 11286//11286 9784//9784 9786//9786 -f 11286//11286 9786//9786 11287//11287 -f 11287//11287 9786//9786 9795//9795 -f 11287//11287 9795//9795 11288//11288 -f 11288//11288 9795//9795 9794//9794 -f 11288//11288 9794//9794 11282//11282 -f 11282//11282 9794//9794 9792//9792 -f 11282//11282 9792//9792 9790//9790 -f 11286//11286 11289//11289 9777//9777 -f 9777//9777 11289//11289 11290//11290 -f 9777//9777 11290//11290 9778//9778 -f 9778//9778 11290//11290 11291//11291 -f 9778//9778 11291//11291 9780//9780 -f 9780//9780 11291//11291 11292//11292 -f 9780//9780 11292//11292 9781//9781 -f 9781//9781 11292//11292 11293//11293 -f 9781//9781 11293//11293 9758//9758 -f 9758//9758 11293//11293 11294//11294 -f 9758//9758 11294//11294 9760//9760 -f 9760//9760 11294//11294 11295//11295 -f 9760//9760 11295//11295 9763//9763 -f 9763//9763 11295//11295 11296//11296 -f 9763//9763 11296//11296 9765//9765 -f 9765//9765 11296//11296 11297//11297 -f 9776//9776 9775//9775 11298//11298 -f 11298//11298 9775//9775 9774//9774 -f 11298//11298 9774//9774 11297//11297 -f 11297//11297 9774//9774 9767//9767 -f 11297//11297 9767//9767 9765//9765 -f 11299//11299 9769//9769 11298//11298 -f 11298//11298 9769//9769 9771//9771 -f 11298//11298 9771//9771 9776//9776 -f 10415//10415 10418//10418 11300//11300 -f 11300//11300 10418//10418 10422//10422 -f 11300//11300 10422//10422 11301//11301 -f 11301//11301 10422//10422 10421//10421 -f 11301//11301 10421//10421 11302//11302 -f 11302//11302 10421//10421 10420//10420 -f 11302//11302 10420//10420 11299//11299 -f 11299//11299 10420//10420 10425//10425 -f 11299//11299 10425//10425 9769//9769 -f 11303//11303 10413//10413 11304//11304 -f 11304//11304 10413//10413 10415//10415 -f 11304//11304 10415//10415 11300//11300 -f 10413//10413 11303//11303 11305//11305 -f 10413//10413 11305//11305 10396//10396 -f 10396//10396 11305//11305 11306//11306 -f 10396//10396 11306//11306 10397//10397 -f 10397//10397 11306//11306 10399//10399 -f 11307//11307 10401//10401 11308//11308 -f 11308//11308 10401//10401 10399//10399 -f 11308//11308 10399//10399 11306//11306 -f 10401//10401 11307//11307 11309//11309 -f 10401//10401 11309//11309 10403//10403 -f 10403//10403 11309//11309 11310//11310 -f 10403//10403 11310//11310 10405//10405 -f 10405//10405 11310//11310 11311//11311 -f 10405//10405 11311//11311 10407//10407 -f 10407//10407 11311//11311 11312//11312 -f 10407//10407 11312//11312 10409//10409 -f 10409//10409 11312//11312 10411//10411 -f 10411//10411 11312//11312 11313//11313 -f 10411//10411 11313//11313 10412//10412 -f 10412//10412 11313//11313 11314//11314 -f 10412//10412 11314//11314 10393//10393 -f 10393//10393 11314//11314 11315//11315 -f 10393//10393 11315//11315 9713//9713 -f 9713//9713 11315//11315 11316//11316 -f 9713//9713 11316//11316 9714//9714 -f 9714//9714 11316//11316 11317//11317 -f 11318//11318 9722//9722 11319//11319 -f 11319//11319 9722//9722 9721//9721 -f 11319//11319 9721//9721 11320//11320 -f 11320//11320 9721//9721 9719//9719 -f 11320//11320 9719//9719 11321//11321 -f 11321//11321 9719//9719 9717//9717 -f 11321//11321 9717//9717 11317//11317 -f 11317//11317 9717//9717 9715//9715 -f 11317//11317 9715//9715 9714//9714 -f 11322//11322 9707//9707 11318//11318 -f 11318//11318 9707//9707 9709//9709 -f 11318//11318 9709//9709 9722//9722 -f 11322//11322 11323//11323 9707//9707 -f 9707//9707 11323//11323 11087//11087 -f 9707//9707 11087//11087 9688//9688 -f 10525//10525 9876//9876 11209//11209 -f 11209//11209 9876//9876 9874//9874 -f 11209//11209 9874//9874 11324//11324 -f 11324//11324 9874//9874 9872//9872 -f 11324//11324 9872//9872 11325//11325 -f 11325//11325 9872//9872 9871//9871 -f 11325//11325 9871//9871 11326//11326 -f 11326//11326 9871//9871 9880//9880 -f 11326//11326 9880//9880 11327//11327 -f 11327//11327 9880//9880 9882//9882 -f 11327//11327 9882//9882 11328//11328 -f 9882//9882 9884//9884 11328//11328 -f 11328//11328 9884//9884 9887//9887 -f 11328//11328 9887//9887 11329//11329 -f 11329//11329 9887//9887 9889//9889 -f 11329//11329 9889//9889 11330//11330 -f 9602//9602 11169//11169 11331//11331 -f 9636//9636 11332//11332 9593//9593 -f 9593//9593 11332//11332 11333//11333 -f 9593//9593 11333//11333 9591//9591 -f 11334//11334 9587//9587 11333//11333 -f 11333//11333 9587//9587 9586//9586 -f 9586//9586 9589//9589 11333//11333 -f 11333//11333 9589//9589 9592//9592 -f 11333//11333 9592//9592 9591//9591 -f 11187//11187 9624//9624 11334//11334 -f 11334//11334 9624//9624 9623//9623 -f 11334//11334 9623//9623 9587//9587 -f 11335//11335 11205//11205 11167//11167 -f 9636//9636 9598//9598 11332//11332 -f 11332//11332 9598//9598 9597//9597 -f 11332//11332 9597//9597 11331//11331 -f 11331//11331 9597//9597 9600//9600 -f 11331//11331 9600//9600 9602//9602 -f 11167//11167 11166//11166 11335//11335 -f 11335//11335 11166//11166 11184//11184 -f 11335//11335 11184//11184 11334//11334 -f 11334//11334 11184//11184 11183//11183 -f 11334//11334 11183//11183 11187//11187 -f 11175//11175 11177//11177 11336//11336 -f 11336//11336 11177//11177 11182//11182 -f 11336//11336 11179//11179 11335//11335 -f 11335//11335 11179//11179 11178//11178 -f 11335//11335 11178//11178 11205//11205 -f 11182//11182 11181//11181 11336//11336 -f 11336//11336 11181//11181 11180//11180 -f 11336//11336 11180//11180 11179//11179 -f 11169//11169 11170//11170 11331//11331 -f 11331//11331 11170//11170 11173//11173 -f 11331//11331 11173//11173 11336//11336 -f 11336//11336 11173//11173 11172//11172 -f 11336//11336 11172//11172 11175//11175 -f 11330//11330 9908//9908 9910//9910 -f 11330//11330 9910//9910 11329//11329 -f 11329//11329 9910//9910 9912//9912 -f 11329//11329 9912//9912 11328//11328 -f 11328//11328 9912//9912 11327//11327 -f 11327//11327 9912//9912 9914//9914 -f 11327//11327 9914//9914 11326//11326 -f 11326//11326 9914//9914 9916//9916 -f 11326//11326 9916//9916 11325//11325 -f 11325//11325 9916//9916 9918//9918 -f 11325//11325 9918//9918 11324//11324 -f 9918//9918 9920//9920 11324//11324 -f 11324//11324 9920//9920 9922//9922 -f 11324//11324 9922//9922 11209//11209 -f 11209//11209 9922//9922 10565//10565 -f 11209//11209 10565//10565 11210//11210 -f 11210//11210 10565//10565 10563//10563 -f 11210//11210 10563//10563 11211//11211 -f 11211//11211 10563//10563 10561//10561 -f 11211//11211 10561//10561 11212//11212 -f 10561//10561 10559//10559 11212//11212 -f 11212//11212 10559//10559 10557//10557 -f 11212//11212 10557//10557 11213//11213 -f 11213//11213 10557//10557 10555//10555 -f 11213//11213 10555//10555 11214//11214 -f 11214//11214 10555//10555 10553//10553 -f 11214//11214 10553//10553 11215//11215 -f 10553//10553 10551//10551 11215//11215 -f 11215//11215 10551//10551 10549//10549 -f 11215//11215 10549//10549 11216//11216 -f 10549//10549 10547//10547 11216//11216 -f 11216//11216 10547//10547 10546//10546 -f 11216//11216 10546//10546 11217//11217 -f 11217//11217 10546//10546 10543//10543 -f 11217//11217 10543//10543 11218//11218 -f 11218//11218 10543//10543 10541//10541 -f 11218//11218 10541//10541 11219//11219 -f 10541//10541 10539//10539 11219//11219 -f 11219//11219 10539//10539 10537//10537 -f 11219//11219 10537//10537 11220//11220 -f 11220//11220 10537//10537 10536//10536 -f 11220//11220 10536//10536 11224//11224 -f 11224//11224 10536//10536 10533//10533 -f 11224//11224 10533//10533 11223//11223 -f 10533//10533 10535//10535 11223//11223 -f 11223//11223 10535//10535 9903//9903 -f 11223//11223 9903//9903 11222//11222 -f 11222//11222 9903//9903 9905//9905 -f 11222//11222 9905//9905 11221//11221 -f 11221//11221 9905//9905 9902//9902 -f 11221//11221 9902//9902 11228//11228 -f 11228//11228 9902//9902 9901//9901 -f 11228//11228 9901//9901 11227//11227 -f 11227//11227 9901//9901 9899//9899 -f 11227//11227 9899//9899 11226//11226 -f 11226//11226 9899//9899 9897//9897 -f 11226//11226 9897//9897 11225//11225 -f 11225//11225 9897//9897 9894//9894 -f 11225//11225 9894//9894 11231//11231 -f 11231//11231 9894//9894 9892//9892 -f 9881//9881 11236//11236 9883//9883 -f 9883//9883 11236//11236 11235//11235 -f 9883//9883 11235//11235 9885//9885 -f 9885//9885 11235//11235 11234//11234 -f 9885//9885 11234//11234 9886//9886 -f 9886//9886 11234//11234 11232//11232 -f 9886//9886 11232//11232 9888//9888 -f 9888//9888 11232//11232 11233//11233 -f 9888//9888 11233//11233 9890//9890 -f 9890//9890 11233//11233 11229//11229 -f 9890//9890 11229//11229 9892//9892 -f 9892//9892 11229//11229 11230//11230 -f 9892//9892 11230//11230 11231//11231 -f 11237//11237 11236//11236 9881//9881 -f 11237//11237 9881//9881 11238//11238 -f 11238//11238 9881//9881 9879//9879 -f 9879//9879 9878//9878 11238//11238 -f 11238//11238 9878//9878 9873//9873 -f 11238//11238 9873//9873 11239//11239 -f 9873//9873 9875//9875 11239//11239 -f 11239//11239 9875//9875 9877//9877 -f 11239//11239 9877//9877 11240//11240 -f 11240//11240 9877//9877 10524//10524 -f 11240//11240 10524//10524 11241//11241 -f 10524//10524 10526//10526 11241//11241 -f 11241//11241 10526//10526 11242//11242 -f 10526//10526 10528//10528 11242//11242 -f 11242//11242 10528//10528 10523//10523 -f 11242//11242 10523//10523 11243//11243 -f 11243//11243 10523//10523 10521//10521 -f 11243//11243 10521//10521 11244//11244 -f 11244//11244 10521//10521 10520//10520 -f 11244//11244 10520//10520 11245//11245 -f 11245//11245 10520//10520 10518//10518 -f 11245//11245 10518//10518 11246//11246 -f 11246//11246 10518//10518 10516//10516 -f 11246//11246 10516//10516 11247//11247 -f 11247//11247 10516//10516 10514//10514 -f 11247//11247 10514//10514 11248//11248 -f 11248//11248 10514//10514 10498//10498 -f 11248//11248 10498//10498 11249//11249 -f 11249//11249 10498//10498 10512//10512 -f 11249//11249 10512//10512 11250//11250 -f 10512//10512 10511//10511 11250//11250 -f 11250//11250 10511//10511 10509//10509 -f 11250//11250 10509//10509 11251//11251 -f 11251//11251 10509//10509 10507//10507 -f 11251//11251 10507//10507 11252//11252 -f 11252//11252 10507//10507 10506//10506 -f 11252//11252 10506//10506 11253//11253 -f 11253//11253 10506//10506 10504//10504 -f 11253//11253 10504//10504 11254//11254 -f 11254//11254 10504//10504 10502//10502 -f 11254//11254 10502//10502 11255//11255 -f 11255//11255 10502//10502 10500//10500 -f 11255//11255 10500//10500 11256//11256 -f 11256//11256 10500//10500 9861//9861 -f 9854//9854 11260//11260 9868//9868 -f 9868//9868 11260//11260 11259//11259 -f 9868//9868 11259//11259 9865//9865 -f 9865//9865 11259//11259 11258//11258 -f 9865//9865 11258//11258 9863//9863 -f 9863//9863 11258//11258 11257//11257 -f 9863//9863 11257//11257 9861//9861 -f 9861//9861 11257//11257 11256//11256 -f 9847//9847 11265//11265 11264//11264 -f 9847//9847 11264//11264 9858//9858 -f 9858//9858 11264//11264 11263//11263 -f 9858//9858 11263//11263 9856//9856 -f 9856//9856 11263//11263 11262//11262 -f 9856//9856 11262//11262 9854//9854 -f 9854//9854 11262//11262 11261//11261 -f 9854//9854 11261//11261 11260//11260 -f 11265//11265 9847//9847 11266//11266 -f 11266//11266 9847//9847 9846//9846 -f 11266//11266 9846//9846 11267//11267 -f 9846//9846 9839//9839 11267//11267 -f 11267//11267 9839//9839 9841//9841 -f 11267//11267 9841//9841 11268//11268 -f 11268//11268 9841//9841 9843//9843 -f 11268//11268 9843//9843 11269//11269 -f 11269//11269 9843//9843 9834//9834 -f 11269//11269 9834//9834 11270//11270 -f 9834//9834 9833//9833 11270//11270 -f 11270//11270 9833//9833 9836//9836 -f 11270//11270 9836//9836 11271//11271 -f 10492//10492 11272//11272 10494//10494 -f 10494//10494 11272//11272 11271//11271 -f 10494//10494 11271//11271 10495//10495 -f 10495//10495 11271//11271 9836//9836 -f 10492//10492 10490//10490 11272//11272 -f 11272//11272 10490//10490 10489//10489 -f 11272//11272 10489//10489 11275//11275 -f 10489//10489 10487//10487 11275//11275 -f 11275//11275 10487//10487 10485//10485 -f 11275//11275 10485//10485 11274//11274 -f 11274//11274 10485//10485 10483//10483 -f 11274//11274 10483//10483 11273//11273 -f 11273//11273 10483//10483 10481//10481 -f 11273//11273 10481//10481 11277//11277 -f 11277//11277 10481//10481 10479//10479 -f 11277//11277 10479//10479 11276//11276 -f 11276//11276 10479//10479 10477//10477 -f 11276//11276 10477//10477 11279//11279 -f 11279//11279 10477//10477 11278//11278 -f 11278//11278 10477//10477 10474//10474 -f 10474//10474 10472//10472 11278//11278 -f 11278//11278 10472//10472 10471//10471 -f 11278//11278 10471//10471 11280//11280 -f 11280//11280 10471//10471 10462//10462 -f 11280//11280 10462//10462 11281//11281 -f 10462//10462 10464//10464 11281//11281 -f 11281//11281 10464//10464 10466//10466 -f 11281//11281 10466//10466 11285//11285 -f 11285//11285 10466//10466 10468//10468 -f 11285//11285 10468//10468 11284//11284 -f 11284//11284 10468//10468 11283//11283 -f 11283//11283 10468//10468 9832//9832 -f 11283//11283 9832//9832 11282//11282 -f 11282//11282 9832//9832 9831//9831 -f 11282//11282 9831//9831 11288//11288 -f 11288//11288 9831//9831 9829//9829 -f 11288//11288 9829//9829 11287//11287 -f 9829//9829 9827//9827 11287//11287 -f 11287//11287 9827//9827 9825//9825 -f 11287//11287 9825//9825 11286//11286 -f 11286//11286 9825//9825 9823//9823 -f 11286//11286 9823//9823 11289//11289 -f 11289//11289 9823//9823 9821//9821 -f 9812//9812 11296//11296 11295//11295 -f 9812//9812 11295//11295 9813//9813 -f 9813//9813 11295//11295 11294//11294 -f 9813//9813 11294//11294 9815//9815 -f 9815//9815 11294//11294 11293//11293 -f 9815//9815 11293//11293 9818//9818 -f 9818//9818 11293//11293 11292//11292 -f 9818//9818 11292//11292 9819//9819 -f 9819//9819 11292//11292 11291//11291 -f 9819//9819 11291//11291 9798//9798 -f 9798//9798 11291//11291 11290//11290 -f 9798//9798 11290//11290 9821//9821 -f 9821//9821 11290//11290 11289//11289 -f 9812//9812 9810//9810 11296//11296 -f 11296//11296 9810//9810 9808//9808 -f 11296//11296 9808//9808 11297//11297 -f 9808//9808 9806//9806 11297//11297 -f 11297//11297 9806//9806 9804//9804 -f 11297//11297 9804//9804 11298//11298 -f 9804//9804 9802//9802 11298//11298 -f 11298//11298 9802//9802 9800//9800 -f 11298//11298 9800//9800 11299//11299 -f 11299//11299 9800//9800 10460//10460 -f 11299//11299 10460//10460 11302//11302 -f 11302//11302 10460//10460 10458//10458 -f 11302//11302 10458//10458 11301//11301 -f 11301//11301 10458//10458 10457//10457 -f 11301//11301 10457//10457 11300//11300 -f 11300//11300 10457//10457 10455//10455 -f 11300//11300 10455//10455 11304//11304 -f 11304//11304 10455//10455 10453//10453 -f 11304//11304 10453//10453 11303//11303 -f 11303//11303 10453//10453 10452//10452 -f 11303//11303 10452//10452 10450//10450 -f 11303//11303 10450//10450 11305//11305 -f 11305//11305 10450//10450 10448//10448 -f 11305//11305 10448//10448 11306//11306 -f 11306//11306 10448//10448 10446//10446 -f 11306//11306 10446//10446 11308//11308 -f 11308//11308 10446//10446 10443//10443 -f 11308//11308 10443//10443 11307//11307 -f 11307//11307 10443//10443 10437//10437 -f 11307//11307 10437//10437 11309//11309 -f 11309//11309 10437//10437 10435//10435 -f 11309//11309 10435//10435 11310//11310 -f 11310//11310 10435//10435 10441//10441 -f 11310//11310 10441//10441 11311//11311 -f 11311//11311 10441//10441 10440//10440 -f 11311//11311 10440//10440 11312//11312 -f 11312//11312 10440//10440 10431//10431 -f 11312//11312 10431//10431 11313//11313 -f 11313//11313 10431//10431 11314//11314 -f 11314//11314 10431//10431 10429//10429 -f 11314//11314 10429//10429 10427//10427 -f 11314//11314 10427//10427 11315//11315 -f 11315//11315 10427//10427 9789//9789 -f 11315//11315 9789//9789 11316//11316 -f 9789//9789 9791//9791 11316//11316 -f 11316//11316 9791//9791 9793//9793 -f 11316//11316 9793//9793 11317//11317 -f 11317//11317 9793//9793 9785//9785 -f 11317//11317 9785//9785 11321//11321 -f 11321//11321 9785//9785 11320//11320 -f 9785//9785 9787//9787 11320//11320 -f 11320//11320 9787//9787 9788//9788 -f 11320//11320 9788//9788 11319//11319 -f 11319//11319 9788//9788 9783//9783 -f 11319//11319 9783//9783 11318//11318 -f 11318//11318 9783//9783 9782//9782 -f 11318//11318 9782//9782 11322//11322 -f 11322//11322 9782//9782 9779//9779 -f 11322//11322 9779//9779 11323//11323 -f 11323//11323 9779//9779 9757//9757 -f 11323//11323 9757//9757 11087//11087 -f 11331//11331 11336//11336 11337//11337 -f 11337//11337 11336//11336 11338//11338 -f 11332//11332 11331//11331 11339//11339 -f 11339//11339 11331//11331 11337//11337 -f 11333//11333 11332//11332 11340//11340 -f 11340//11340 11332//11332 11339//11339 -f 11334//11334 11333//11333 11341//11341 -f 11341//11341 11333//11333 11340//11340 -f 11335//11335 11334//11334 11342//11342 -f 11342//11342 11334//11334 11341//11341 -f 11336//11336 11335//11335 11338//11338 -f 11338//11338 11335//11335 11342//11342 -f 11342//11342 11341//11341 11338//11338 -f 11338//11338 11341//11341 11340//11340 -f 11338//11338 11340//11340 11337//11337 -f 11337//11337 11340//11340 11339//11339 -f 11343//11343 11344//11344 10666//10666 -f 10666//10666 11344//11344 10668//10668 -f 10668//10668 11344//11344 11345//11345 -f 10668//10668 11345//11345 10670//10670 -f 10670//10670 11345//11345 11346//11346 -f 10670//10670 11346//11346 10671//10671 -f 10671//10671 11346//11346 10663//10663 -f 10663//10663 11346//11346 11347//11347 -f 10663//10663 11347//11347 10660//10660 -f 10660//10660 11347//11347 11348//11348 -f 10660//10660 11348//11348 10658//10658 -f 10658//10658 11348//11348 11349//11349 -f 10658//10658 11349//11349 10656//10656 -f 10656//10656 11349//11349 10654//10654 -f 10654//10654 11349//11349 11350//11350 -f 10654//10654 11350//11350 10637//10637 -f 10637//10637 11350//11350 10638//10638 -f 10638//10638 11350//11350 11351//11351 -f 10638//10638 11351//11351 10651//10651 -f 11351//11351 11352//11352 10651//10651 -f 10651//10651 11352//11352 11353//11353 -f 10651//10651 11353//11353 10649//10649 -f 10649//10649 11353//11353 10646//10646 -f 10646//10646 11353//11353 11354//11354 -f 10646//10646 11354//11354 10644//10644 -f 10644//10644 11354//11354 10642//10642 -f 10642//10642 11354//11354 11355//11355 -f 10642//10642 11355//11355 10640//10640 -f 10640//10640 11355//11355 11356//11356 -f 10640//10640 11356//11356 10010//10010 -f 10010//10010 11356//11356 11357//11357 -f 10010//10010 11357//11357 10012//10012 -f 10012//10012 11357//11357 11358//11358 -f 10012//10012 11358//11358 10014//10014 -f 10014//10014 11358//11358 10015//10015 -f 10015//10015 11358//11358 11359//11359 -f 10015//10015 11359//11359 10017//10017 -f 10017//10017 11359//11359 11360//11360 -f 10017//10017 11360//11360 10018//10018 -f 10018//10018 11360//11360 11361//11361 -f 10018//10018 11361//11361 10000//10000 -f 10000//10000 11361//11361 11362//11362 -f 10000//10000 11362//11362 10001//10001 -f 10001//10001 11362//11362 10003//10003 -f 10003//10003 11362//11362 11363//11363 -f 10003//10003 11363//11363 10005//10005 -f 10005//10005 11363//11363 11364//11364 -f 10005//10005 11364//11364 10007//10007 -f 10007//10007 11364//11364 11365//11365 -f 10007//10007 11365//11365 10008//10008 -f 10008//10008 11365//11365 9996//9996 -f 9996//9996 11365//11365 11366//11366 -f 9996//9996 11366//11366 9997//9997 -f 9997//9997 11366//11366 11367//11367 -f 9997//9997 11367//11367 9998//9998 -f 9998//9998 11367//11367 9999//9999 -f 9999//9999 11367//11367 11368//11368 -f 9999//9999 11368//11368 9988//9988 -f 9988//9988 11368//11368 11369//11369 -f 9988//9988 11369//11369 9990//9990 -f 9990//9990 11369//11369 11370//11370 -f 9990//9990 11370//11370 9992//9992 -f 9992//9992 11370//11370 11371//11371 -f 9992//9992 11371//11371 9993//9993 -f 9993//9993 11371//11371 11372//11372 -f 9993//9993 11372//11372 9983//9983 -f 9983//9983 11372//11372 11373//11373 -f 9983//9983 11373//11373 9985//9985 -f 9985//9985 11373//11373 9986//9986 -f 9986//9986 11373//11373 11374//11374 -f 9986//9986 11374//11374 10634//10634 -f 11374//11374 11375//11375 10634//10634 -f 10634//10634 11375//11375 11376//11376 -f 10634//10634 11376//11376 10632//10632 -f 10632//10632 11376//11376 10629//10629 -f 10629//10629 11376//11376 11377//11377 -f 10629//10629 11377//11377 10627//10627 -f 10627//10627 11377//11377 11378//11378 -f 10627//10627 11378//11378 10625//10625 -f 10625//10625 11378//11378 11379//11379 -f 10625//10625 11379//11379 10623//10623 -f 10623//10623 11379//11379 10621//10621 -f 10621//10621 11379//11379 11380//11380 -f 10621//10621 11380//11380 10619//10619 -f 11380//11380 11381//11381 10619//10619 -f 10619//10619 11381//11381 11382//11382 -f 10619//10619 11382//11382 10617//10617 -f 10617//10617 11382//11382 11383//11383 -f 10617//10617 11383//11383 10616//10616 -f 10616//10616 11383//11383 11384//11384 -f 10616//10616 11384//11384 10614//10614 -f 10614//10614 11384//11384 11385//11385 -f 10614//10614 11385//11385 10604//10604 -f 10604//10604 11385//11385 11386//11386 -f 10604//10604 11386//11386 10606//10606 -f 10606//10606 11386//11386 11387//11387 -f 10606//10606 11387//11387 10608//10608 -f 10608//10608 11387//11387 11388//11388 -f 10608//10608 11388//11388 10610//10610 -f 10610//10610 11388//11388 11389//11389 -f 10610//10610 11389//11389 10611//10611 -f 10611//10611 11389//11389 11390//11390 -f 10611//10611 11390//11390 9978//9978 -f 9978//9978 11390//11390 11391//11391 -f 9978//9978 11391//11391 9976//9976 -f 9976//9976 11391//11391 11392//11392 -f 9976//9976 11392//11392 9974//9974 -f 9974//9974 11392//11392 11393//11393 -f 9974//9974 11393//11393 9972//9972 -f 9972//9972 11393//11393 11394//11394 -f 9972//9972 11394//11394 9970//9970 -f 9970//9970 11394//11394 11395//11395 -f 9970//9970 11395//11395 9968//9968 -f 9968//9968 11395//11395 11396//11396 -f 9968//9968 11396//11396 9944//9944 -f 9944//9944 11396//11396 11397//11397 -f 9944//9944 11397//11397 9945//9945 -f 9945//9945 11397//11397 11398//11398 -f 9945//9945 11398//11398 9965//9965 -f 9965//9965 11398//11398 11399//11399 -f 9965//9965 11399//11399 9964//9964 -f 9964//9964 11399//11399 11400//11400 -f 9964//9964 11400//11400 9962//9962 -f 9962//9962 11400//11400 11401//11401 -f 9962//9962 11401//11401 9959//9959 -f 9959//9959 11401//11401 11402//11402 -f 11403//11403 9955//9955 11402//11402 -f 11402//11402 9955//9955 9957//9957 -f 11402//11402 9957//9957 9959//9959 -f 11404//11404 9951//9951 11403//11403 -f 11403//11403 9951//9951 9953//9953 -f 11403//11403 9953//9953 9955//9955 -f 11405//11405 9947//9947 11404//11404 -f 11404//11404 9947//9947 9949//9949 -f 11404//11404 9949//9949 9951//9951 -f 11406//11406 10600//10600 11405//11405 -f 11405//11405 10600//10600 10602//10602 -f 11405//11405 10602//10602 9947//9947 -f 11407//11407 10590//10590 11408//11408 -f 11408//11408 10590//10590 10592//10592 -f 11408//11408 10592//10592 11409//11409 -f 11409//11409 10592//10592 10595//10595 -f 11409//11409 10595//10595 11406//11406 -f 11406//11406 10595//10595 10597//10597 -f 11406//11406 10597//10597 10600//10600 -f 11410//11410 10585//10585 11411//11411 -f 11411//11411 10585//10585 10586//10586 -f 11411//11411 10586//10586 11407//11407 -f 11407//11407 10586//10586 10588//10588 -f 11407//11407 10588//10588 10590//10590 -f 11412//11412 10577//10577 11413//11413 -f 11413//11413 10577//10577 10579//10579 -f 11413//11413 10579//10579 11410//11410 -f 11410//11410 10579//10579 10583//10583 -f 11410//11410 10583//10583 10585//10585 -f 11414//11414 10574//10574 11415//11415 -f 11415//11415 10574//10574 10580//10580 -f 11415//11415 10580//10580 11412//11412 -f 11412//11412 10580//10580 10575//10575 -f 11412//11412 10575//10575 10577//10577 -f 11416//11416 9938//9938 11417//11417 -f 11417//11417 9938//9938 10567//10567 -f 11417//11417 10567//10567 11418//11418 -f 11418//11418 10567//10567 10569//10569 -f 11418//11418 10569//10569 11419//11419 -f 11419//11419 10569//10569 10571//10571 -f 11419//11419 10571//10571 11414//11414 -f 11414//11414 10571//10571 10573//10573 -f 11414//11414 10573//10573 10574//10574 -f 9925//9925 9932//9932 11420//11420 -f 11420//11420 9932//9932 9934//9934 -f 11420//11420 9934//9934 11421//11421 -f 11421//11421 9934//9934 9943//9943 -f 11421//11421 9943//9943 11422//11422 -f 11422//11422 9943//9943 9942//9942 -f 11422//11422 9942//9942 11416//11416 -f 11416//11416 9942//9942 9940//9940 -f 11416//11416 9940//9940 9938//9938 -f 11420//11420 11423//11423 9925//9925 -f 9925//9925 11423//11423 11424//11424 -f 9925//9925 11424//11424 9926//9926 -f 9926//9926 11424//11424 11425//11425 -f 9926//9926 11425//11425 9928//9928 -f 9928//9928 11425//11425 11426//11426 -f 9928//9928 11426//11426 9929//9929 -f 9929//9929 11426//11426 11427//11427 -f 9929//9929 11427//11427 9909//9909 -f 9909//9909 11427//11427 11428//11428 -f 9909//9909 11428//11428 9911//9911 -f 9911//9911 11428//11428 11429//11429 -f 9911//9911 11429//11429 9913//9913 -f 9913//9913 11429//11429 11430//11430 -f 9913//9913 11430//11430 9915//9915 -f 9915//9915 11430//11430 11431//11431 -f 9923//9923 9924//9924 11432//11432 -f 11432//11432 9924//9924 9919//9919 -f 11432//11432 9919//9919 11431//11431 -f 11431//11431 9919//9919 9917//9917 -f 11431//11431 9917//9917 9915//9915 -f 9923//9923 11432//11432 9921//9921 -f 9921//9921 11432//11432 11433//11433 -f 9921//9921 11433//11433 10566//10566 -f 10566//10566 11433//11433 10564//10564 -f 10564//10564 11433//11433 11434//11434 -f 10564//10564 11434//11434 10562//10562 -f 10562//10562 11434//11434 11435//11435 -f 10562//10562 11435//11435 10560//10560 -f 10560//10560 11435//11435 11436//11436 -f 10560//10560 11436//11436 10558//10558 -f 10558//10558 11436//11436 10556//10556 -f 10556//10556 11436//11436 11437//11437 -f 10556//10556 11437//11437 10554//10554 -f 11437//11437 11438//11438 10554//10554 -f 10554//10554 11438//11438 11439//11439 -f 10554//10554 11439//11439 10552//10552 -f 10552//10552 11439//11439 11440//11440 -f 10552//10552 11440//11440 10550//10550 -f 10550//10550 11440//11440 10548//10548 -f 10548//10548 11440//11440 11441//11441 -f 10548//10548 11441//11441 10545//10545 -f 11441//11441 11442//11442 10545//10545 -f 10545//10545 11442//11442 11443//11443 -f 10545//10545 11443//11443 10544//10544 -f 10544//10544 11443//11443 11444//11444 -f 10544//10544 11444//11444 10542//10542 -f 10542//10542 11444//11444 11445//11445 -f 10542//10542 11445//11445 10540//10540 -f 10540//10540 11445//11445 11446//11446 -f 11447//11447 9906//9906 11448//11448 -f 11448//11448 9906//9906 9904//9904 -f 11448//11448 9904//9904 11449//11449 -f 11449//11449 9904//9904 10534//10534 -f 11449//11449 10534//10534 11450//11450 -f 11450//11450 10534//10534 10532//10532 -f 11450//11450 10532//10532 11451//11451 -f 11451//11451 10532//10532 10531//10531 -f 11451//11451 10531//10531 11446//11446 -f 11446//11446 10531//10531 10538//10538 -f 11446//11446 10538//10538 10540//10540 -f 11452//11452 9895//9895 11453//11453 -f 11453//11453 9895//9895 9896//9896 -f 11453//11453 9896//9896 11454//11454 -f 11454//11454 9896//9896 9898//9898 -f 11454//11454 9898//9898 11455//11455 -f 11455//11455 9898//9898 9900//9900 -f 11455//11455 9900//9900 11447//11447 -f 11447//11447 9900//9900 9907//9907 -f 11447//11447 9907//9907 9906//9906 -f 11456//11456 9891//9891 11452//11452 -f 11452//11452 9891//9891 9893//9893 -f 11452//11452 9893//9893 9895//9895 -f 11456//11456 11457//11457 9891//9891 -f 9891//9891 11457//11457 11330//11330 -f 9891//9891 11330//11330 9889//9889 -f 10666//10666 10024//10024 11343//11343 -f 11343//11343 10024//10024 10022//10022 -f 11343//11343 10022//10022 11458//11458 -f 11458//11458 10022//10022 10020//10020 -f 11458//11458 10020//10020 11459//11459 -f 11459//11459 10020//10020 10019//10019 -f 11459//11459 10019//10019 11460//11460 -f 11460//11460 10019//10019 10028//10028 -f 11460//11460 10028//10028 11461//11461 -f 11461//11461 10028//10028 10030//10030 -f 11461//11461 10030//10030 11462//11462 -f 10030//10030 10032//10032 11462//11462 -f 11462//11462 10032//10032 10035//10035 -f 11462//11462 10035//10035 11463//11463 -f 11463//11463 10035//10035 10037//10037 -f 11463//11463 10037//10037 11464//11464 -f 11464//11464 10056//10056 10058//10058 -f 11464//11464 10058//10058 11463//11463 -f 11463//11463 10058//10058 10060//10060 -f 11463//11463 10060//10060 11462//11462 -f 11462//11462 10060//10060 11461//11461 -f 11461//11461 10060//10060 10062//10062 -f 11461//11461 10062//10062 11460//11460 -f 11460//11460 10062//10062 10064//10064 -f 11460//11460 10064//10064 11459//11459 -f 11459//11459 10064//10064 10066//10066 -f 11459//11459 10066//10066 11458//11458 -f 10066//10066 10068//10068 11458//11458 -f 11458//11458 10068//10068 10070//10070 -f 11458//11458 10070//10070 11343//11343 -f 11343//11343 10070//10070 10706//10706 -f 11343//11343 10706//10706 11344//11344 -f 11344//11344 10706//10706 10704//10704 -f 11344//11344 10704//10704 11345//11345 -f 11345//11345 10704//10704 10702//10702 -f 11345//11345 10702//10702 11346//11346 -f 10702//10702 10700//10700 11346//11346 -f 11346//11346 10700//10700 10698//10698 -f 11346//11346 10698//10698 11347//11347 -f 11347//11347 10698//10698 10696//10696 -f 11347//11347 10696//10696 11348//11348 -f 11348//11348 10696//10696 10694//10694 -f 11348//11348 10694//10694 11349//11349 -f 10694//10694 10692//10692 11349//11349 -f 11349//11349 10692//10692 10690//10690 -f 11349//11349 10690//10690 11350//11350 -f 10690//10690 10688//10688 11350//11350 -f 11350//11350 10688//10688 10687//10687 -f 11350//11350 10687//10687 11351//11351 -f 11351//11351 10687//10687 10684//10684 -f 11351//11351 10684//10684 11352//11352 -f 11352//11352 10684//10684 10682//10682 -f 11352//11352 10682//10682 11353//11353 -f 10682//10682 10680//10680 11353//11353 -f 11353//11353 10680//10680 10678//10678 -f 11353//11353 10678//10678 11354//11354 -f 11354//11354 10678//10678 10677//10677 -f 11354//11354 10677//10677 11355//11355 -f 11355//11355 10677//10677 10674//10674 -f 11355//11355 10674//10674 11356//11356 -f 10674//10674 10676//10676 11356//11356 -f 11356//11356 10676//10676 10051//10051 -f 11356//11356 10051//10051 11357//11357 -f 11357//11357 10051//10051 10053//10053 -f 11357//11357 10053//10053 11358//11358 -f 11358//11358 10053//10053 10050//10050 -f 11358//11358 10050//10050 11359//11359 -f 11359//11359 10050//10050 10049//10049 -f 11359//11359 10049//10049 11360//11360 -f 11360//11360 10049//10049 10047//10047 -f 11360//11360 10047//10047 11361//11361 -f 11361//11361 10047//10047 10045//10045 -f 11361//11361 10045//10045 11362//11362 -f 11362//11362 10045//10045 10042//10042 -f 11362//11362 10042//10042 11363//11363 -f 11363//11363 10042//10042 10040//10040 -f 11370//11370 11369//11369 10031//10031 -f 10031//10031 11369//11369 10033//10033 -f 10033//10033 11369//11369 11368//11368 -f 10033//10033 11368//11368 10034//10034 -f 10034//10034 11368//11368 11367//11367 -f 10034//10034 11367//11367 10036//10036 -f 10036//10036 11367//11367 11366//11366 -f 10036//10036 11366//11366 10038//10038 -f 10038//10038 11366//11366 11365//11365 -f 10038//10038 11365//11365 10040//10040 -f 10040//10040 11365//11365 11364//11364 -f 10040//10040 11364//11364 11363//11363 -f 10031//10031 10029//10029 11370//11370 -f 11370//11370 10029//10029 10027//10027 -f 11370//11370 10027//10027 11371//11371 -f 11371//11371 10027//10027 10026//10026 -f 11371//11371 10026//10026 11372//11372 -f 11372//11372 10026//10026 10021//10021 -f 11372//11372 10021//10021 11373//11373 -f 10021//10021 10023//10023 11373//11373 -f 11373//11373 10023//10023 10025//10025 -f 11373//11373 10025//10025 11374//11374 -f 11374//11374 10025//10025 10665//10665 -f 11374//11374 10665//10665 11375//11375 -f 10665//10665 10667//10667 11375//11375 -f 11375//11375 10667//10667 10669//10669 -f 11375//11375 10669//10669 11376//11376 -f 11376//11376 10669//10669 10664//10664 -f 11376//11376 10664//10664 11377//11377 -f 11377//11377 10664//10664 10662//10662 -f 11377//11377 10662//10662 11378//11378 -f 11378//11378 10662//10662 10661//10661 -f 11378//11378 10661//10661 11379//11379 -f 11379//11379 10661//10661 10659//10659 -f 11379//11379 10659//10659 11380//11380 -f 11380//11380 10659//10659 10657//10657 -f 11380//11380 10657//10657 11381//11381 -f 11381//11381 10657//10657 10655//10655 -f 11381//11381 10655//10655 11382//11382 -f 11382//11382 10655//10655 10639//10639 -f 11382//11382 10639//10639 11383//11383 -f 11383//11383 10639//10639 10653//10653 -f 11383//11383 10653//10653 11384//11384 -f 10653//10653 10652//10652 11384//11384 -f 11384//11384 10652//10652 10650//10650 -f 11384//11384 10650//10650 11385//11385 -f 11385//11385 10650//10650 10648//10648 -f 11385//11385 10648//10648 11386//11386 -f 11386//11386 10648//10648 10647//10647 -f 11386//11386 10647//10647 11387//11387 -f 11387//11387 10647//10647 10645//10645 -f 11387//11387 10645//10645 11388//11388 -f 11388//11388 10645//10645 10643//10643 -f 11388//11388 10643//10643 11389//11389 -f 11389//11389 10643//10643 10641//10641 -f 11389//11389 10641//10641 11390//11390 -f 11390//11390 10641//10641 10009//10009 -f 11390//11390 10009//10009 11391//11391 -f 11391//11391 10009//10009 10011//10011 -f 11391//11391 10011//10011 11392//11392 -f 11392//11392 10011//10011 10013//10013 -f 11392//11392 10013//10013 11393//11393 -f 11393//11393 10013//10013 10016//10016 -f 11393//11393 10016//10016 11394//11394 -f 11394//11394 10016//10016 10002//10002 -f 9995//9995 11399//11399 11398//11398 -f 9995//9995 11398//11398 10006//10006 -f 10006//10006 11398//11398 11397//11397 -f 10006//10006 11397//11397 10004//10004 -f 10004//10004 11397//11397 11396//11396 -f 10004//10004 11396//11396 10002//10002 -f 10002//10002 11396//11396 11395//11395 -f 10002//10002 11395//11395 11394//11394 -f 11399//11399 9995//9995 11400//11400 -f 11400//11400 9995//9995 9994//9994 -f 11400//11400 9994//9994 11401//11401 -f 9994//9994 9987//9987 11401//11401 -f 11401//11401 9987//9987 9989//9989 -f 11401//11401 9989//9989 11402//11402 -f 11402//11402 9989//9989 9991//9991 -f 11402//11402 9991//9991 11403//11403 -f 11403//11403 9991//9991 9982//9982 -f 11403//11403 9982//9982 11404//11404 -f 9982//9982 9981//9981 11404//11404 -f 11404//11404 9981//9981 9984//9984 -f 11404//11404 9984//9984 11405//11405 -f 10633//10633 11406//11406 10635//10635 -f 10635//10635 11406//11406 11405//11405 -f 10635//10635 11405//11405 10636//10636 -f 10636//10636 11405//11405 9984//9984 -f 10633//10633 10631//10631 11406//11406 -f 11406//11406 10631//10631 10630//10630 -f 11406//11406 10630//10630 11409//11409 -f 10630//10630 10628//10628 11409//11409 -f 11409//11409 10628//10628 10626//10626 -f 11409//11409 10626//10626 11408//11408 -f 11408//11408 10626//10626 10624//10624 -f 11408//11408 10624//10624 11407//11407 -f 11407//11407 10624//10624 10622//10622 -f 11407//11407 10622//10622 11411//11411 -f 11411//11411 10622//10622 10620//10620 -f 11411//11411 10620//10620 11410//11410 -f 11410//11410 10620//10620 10618//10618 -f 11410//11410 10618//10618 11413//11413 -f 11413//11413 10618//10618 10615//10615 -f 11413//11413 10615//10615 11412//11412 -f 10615//10615 10613//10613 11412//11412 -f 11412//11412 10613//10613 10612//10612 -f 11412//11412 10612//10612 11415//11415 -f 11415//11415 10612//10612 10603//10603 -f 11415//11415 10603//10603 11414//11414 -f 10603//10603 10605//10605 11414//11414 -f 11414//11414 10605//10605 10607//10607 -f 11414//11414 10607//10607 11419//11419 -f 11419//11419 10607//10607 10609//10609 -f 11419//11419 10609//10609 11418//11418 -f 11418//11418 10609//10609 11417//11417 -f 11417//11417 10609//10609 9980//9980 -f 11417//11417 9980//9980 11416//11416 -f 11416//11416 9980//9980 9979//9979 -f 11416//11416 9979//9979 11422//11422 -f 11422//11422 9979//9979 9977//9977 -f 11422//11422 9977//9977 11421//11421 -f 9977//9977 9975//9975 11421//11421 -f 11421//11421 9975//9975 9973//9973 -f 11421//11421 9973//9973 11420//11420 -f 11420//11420 9973//9973 9971//9971 -f 11420//11420 9971//9971 11423//11423 -f 11423//11423 9971//9971 9969//9969 -f 11423//11423 9969//9969 11424//11424 -f 11424//11424 9969//9969 9946//9946 -f 11424//11424 9946//9946 11425//11425 -f 11425//11425 9946//9946 9967//9967 -f 11425//11425 9967//9967 11426//11426 -f 11426//11426 9967//9967 9966//9966 -f 11426//11426 9966//9966 11427//11427 -f 11427//11427 9966//9966 9963//9963 -f 11427//11427 9963//9963 11428//11428 -f 11428//11428 9963//9963 9961//9961 -f 11428//11428 9961//9961 11429//11429 -f 11429//11429 9961//9961 9960//9960 -f 11429//11429 9960//9960 11430//11430 -f 9960//9960 9958//9958 11430//11430 -f 11430//11430 9958//9958 9956//9956 -f 11430//11430 9956//9956 11431//11431 -f 9956//9956 9954//9954 11431//11431 -f 11431//11431 9954//9954 9952//9952 -f 11431//11431 9952//9952 11432//11432 -f 9952//9952 9950//9950 11432//11432 -f 11432//11432 9950//9950 9948//9948 -f 11432//11432 9948//9948 11433//11433 -f 11433//11433 9948//9948 10601//10601 -f 11433//11433 10601//10601 11434//11434 -f 11434//11434 10601//10601 10599//10599 -f 11434//11434 10599//10599 11435//11435 -f 11435//11435 10599//10599 10598//10598 -f 11435//11435 10598//10598 11436//11436 -f 11436//11436 10598//10598 10596//10596 -f 11436//11436 10596//10596 11437//11437 -f 10596//10596 10594//10594 11437//11437 -f 11437//11437 10594//10594 10593//10593 -f 11437//11437 10593//10593 11438//11438 -f 11438//11438 10593//10593 10591//10591 -f 11438//11438 10591//10591 11439//11439 -f 11439//11439 10591//10591 10589//10589 -f 11439//11439 10589//10589 11440//11440 -f 11440//11440 10589//10589 10587//10587 -f 11440//11440 10587//10587 11441//11441 -f 11441//11441 10587//10587 10584//10584 -f 11441//11441 10584//10584 11442//11442 -f 11442//11442 10584//10584 10578//10578 -f 11442//11442 10578//10578 11443//11443 -f 11443//11443 10578//10578 10576//10576 -f 11443//11443 10576//10576 11444//11444 -f 11444//11444 10576//10576 10582//10582 -f 11444//11444 10582//10582 11445//11445 -f 11445//11445 10582//10582 10581//10581 -f 11445//11445 10581//10581 11446//11446 -f 11446//11446 10581//10581 10572//10572 -f 11446//11446 10572//10572 11451//11451 -f 11451//11451 10572//10572 10570//10570 -f 11451//11451 10570//10570 11450//11450 -f 11450//11450 10570//10570 10568//10568 -f 11450//11450 10568//10568 11449//11449 -f 11449//11449 10568//10568 9937//9937 -f 11449//11449 9937//9937 11448//11448 -f 9937//9937 9939//9939 11448//11448 -f 11448//11448 9939//9939 9941//9941 -f 11448//11448 9941//9941 11447//11447 -f 11447//11447 9941//9941 9933//9933 -f 11447//11447 9933//9933 11455//11455 -f 11455//11455 9933//9933 11454//11454 -f 9933//9933 9935//9935 11454//11454 -f 11454//11454 9935//9935 9936//9936 -f 11454//11454 9936//9936 11453//11453 -f 11453//11453 9936//9936 9931//9931 -f 11453//11453 9931//9931 11452//11452 -f 11452//11452 9931//9931 9930//9930 -f 11452//11452 9930//9930 11456//11456 -f 11456//11456 9930//9930 9927//9927 -f 11456//11456 9927//9927 11457//11457 -f 11457//11457 9927//9927 9908//9908 -f 11457//11457 9908//9908 11330//11330 -f 11465//11465 11466//11466 10807//10807 -f 10807//10807 11466//11466 10809//10809 -f 10809//10809 11466//11466 11467//11467 -f 10809//10809 11467//11467 10811//10811 -f 10811//10811 11467//11467 11468//11468 -f 10811//10811 11468//11468 10812//10812 -f 10812//10812 11468//11468 10804//10804 -f 10804//10804 11468//11468 11469//11469 -f 10804//10804 11469//11469 10801//10801 -f 10801//10801 11469//11469 11470//11470 -f 10801//10801 11470//11470 10799//10799 -f 10799//10799 11470//11470 11471//11471 -f 10799//10799 11471//11471 10797//10797 -f 10797//10797 11471//11471 10795//10795 -f 10795//10795 11471//11471 11472//11472 -f 10795//10795 11472//11472 10778//10778 -f 10778//10778 11472//11472 10779//10779 -f 10779//10779 11472//11472 11473//11473 -f 10779//10779 11473//11473 10792//10792 -f 11473//11473 11474//11474 10792//10792 -f 10792//10792 11474//11474 11475//11475 -f 10792//10792 11475//11475 10790//10790 -f 10790//10790 11475//11475 10787//10787 -f 10787//10787 11475//11475 11476//11476 -f 10787//10787 11476//11476 10785//10785 -f 10785//10785 11476//11476 10783//10783 -f 10783//10783 11476//11476 11477//11477 -f 10783//10783 11477//11477 10781//10781 -f 10781//10781 11477//11477 11478//11478 -f 10781//10781 11478//11478 10158//10158 -f 10158//10158 11478//11478 11479//11479 -f 10158//10158 11479//11479 10160//10160 -f 10160//10160 11479//11479 11480//11480 -f 10160//10160 11480//11480 10162//10162 -f 10162//10162 11480//11480 10163//10163 -f 10163//10163 11480//11480 11481//11481 -f 10163//10163 11481//11481 10165//10165 -f 10165//10165 11481//11481 11482//11482 -f 10165//10165 11482//11482 10166//10166 -f 10166//10166 11482//11482 11483//11483 -f 10166//10166 11483//11483 10148//10148 -f 10148//10148 11483//11483 11484//11484 -f 10148//10148 11484//11484 10149//10149 -f 10149//10149 11484//11484 10151//10151 -f 10151//10151 11484//11484 11485//11485 -f 10151//10151 11485//11485 10153//10153 -f 10153//10153 11485//11485 11486//11486 -f 10153//10153 11486//11486 10155//10155 -f 10155//10155 11486//11486 11487//11487 -f 10155//10155 11487//11487 10156//10156 -f 10156//10156 11487//11487 10144//10144 -f 10144//10144 11487//11487 11488//11488 -f 10144//10144 11488//11488 10145//10145 -f 10145//10145 11488//11488 11489//11489 -f 10145//10145 11489//11489 10146//10146 -f 10146//10146 11489//11489 10147//10147 -f 10147//10147 11489//11489 11490//11490 -f 10147//10147 11490//11490 10136//10136 -f 10136//10136 11490//11490 11491//11491 -f 10136//10136 11491//11491 10138//10138 -f 10138//10138 11491//11491 11492//11492 -f 10138//10138 11492//11492 10140//10140 -f 10140//10140 11492//11492 11493//11493 -f 10140//10140 11493//11493 10141//10141 -f 10141//10141 11493//11493 11494//11494 -f 10141//10141 11494//11494 10131//10131 -f 10131//10131 11494//11494 11495//11495 -f 10131//10131 11495//11495 10133//10133 -f 10133//10133 11495//11495 10134//10134 -f 10134//10134 11495//11495 11496//11496 -f 10134//10134 11496//11496 10775//10775 -f 11496//11496 11497//11497 10775//10775 -f 10775//10775 11497//11497 11498//11498 -f 10775//10775 11498//11498 10773//10773 -f 10773//10773 11498//11498 10770//10770 -f 10770//10770 11498//11498 11499//11499 -f 10770//10770 11499//11499 10768//10768 -f 10768//10768 11499//11499 11500//11500 -f 10768//10768 11500//11500 10766//10766 -f 10766//10766 11500//11500 11501//11501 -f 10766//10766 11501//11501 10764//10764 -f 10764//10764 11501//11501 10762//10762 -f 10762//10762 11501//11501 11502//11502 -f 10762//10762 11502//11502 10760//10760 -f 11502//11502 11503//11503 10760//10760 -f 10760//10760 11503//11503 11504//11504 -f 10760//10760 11504//11504 10758//10758 -f 10758//10758 11504//11504 11505//11505 -f 10758//10758 11505//11505 10757//10757 -f 10757//10757 11505//11505 11506//11506 -f 10757//10757 11506//11506 10755//10755 -f 10755//10755 11506//11506 11507//11507 -f 10755//10755 11507//11507 10745//10745 -f 10745//10745 11507//11507 11508//11508 -f 10745//10745 11508//11508 10747//10747 -f 10747//10747 11508//11508 11509//11509 -f 10747//10747 11509//11509 10749//10749 -f 10749//10749 11509//11509 11510//11510 -f 10749//10749 11510//11510 10751//10751 -f 10751//10751 11510//11510 11511//11511 -f 10751//10751 11511//11511 10752//10752 -f 10752//10752 11511//11511 11512//11512 -f 10752//10752 11512//11512 10126//10126 -f 10126//10126 11512//11512 11513//11513 -f 10126//10126 11513//11513 10124//10124 -f 10124//10124 11513//11513 11514//11514 -f 10124//10124 11514//11514 10122//10122 -f 10122//10122 11514//11514 11515//11515 -f 10122//10122 11515//11515 10120//10120 -f 10120//10120 11515//11515 11516//11516 -f 10120//10120 11516//11516 10118//10118 -f 10118//10118 11516//11516 11517//11517 -f 10118//10118 11517//11517 10116//10116 -f 10116//10116 11517//11517 11518//11518 -f 10116//10116 11518//11518 10092//10092 -f 10092//10092 11518//11518 11519//11519 -f 10092//10092 11519//11519 10093//10093 -f 10093//10093 11519//11519 11520//11520 -f 10093//10093 11520//11520 10113//10113 -f 10113//10113 11520//11520 11521//11521 -f 10113//10113 11521//11521 10112//10112 -f 10112//10112 11521//11521 11522//11522 -f 10112//10112 11522//11522 10110//10110 -f 10110//10110 11522//11522 11523//11523 -f 10110//10110 11523//11523 10107//10107 -f 10107//10107 11523//11523 11524//11524 -f 11525//11525 10103//10103 11524//11524 -f 11524//11524 10103//10103 10105//10105 -f 11524//11524 10105//10105 10107//10107 -f 11526//11526 10099//10099 11525//11525 -f 11525//11525 10099//10099 10101//10101 -f 11525//11525 10101//10101 10103//10103 -f 11527//11527 10095//10095 11526//11526 -f 11526//11526 10095//10095 10097//10097 -f 11526//11526 10097//10097 10099//10099 -f 11528//11528 10741//10741 11527//11527 -f 11527//11527 10741//10741 10743//10743 -f 11527//11527 10743//10743 10095//10095 -f 11529//11529 10731//10731 11530//11530 -f 11530//11530 10731//10731 10733//10733 -f 11530//11530 10733//10733 11531//11531 -f 11531//11531 10733//10733 10736//10736 -f 11531//11531 10736//10736 11528//11528 -f 11528//11528 10736//10736 10738//10738 -f 11528//11528 10738//10738 10741//10741 -f 11532//11532 10726//10726 11533//11533 -f 11533//11533 10726//10726 10727//10727 -f 11533//11533 10727//10727 11529//11529 -f 11529//11529 10727//10727 10729//10729 -f 11529//11529 10729//10729 10731//10731 -f 11534//11534 10718//10718 11535//11535 -f 11535//11535 10718//10718 10720//10720 -f 11535//11535 10720//10720 11532//11532 -f 11532//11532 10720//10720 10724//10724 -f 11532//11532 10724//10724 10726//10726 -f 11536//11536 10715//10715 11537//11537 -f 11537//11537 10715//10715 10721//10721 -f 11537//11537 10721//10721 11534//11534 -f 11534//11534 10721//10721 10716//10716 -f 11534//11534 10716//10716 10718//10718 -f 11538//11538 10086//10086 11539//11539 -f 11539//11539 10086//10086 10708//10708 -f 11539//11539 10708//10708 11540//11540 -f 11540//11540 10708//10708 10710//10710 -f 11540//11540 10710//10710 11541//11541 -f 11541//11541 10710//10710 10712//10712 -f 11541//11541 10712//10712 11536//11536 -f 11536//11536 10712//10712 10714//10714 -f 11536//11536 10714//10714 10715//10715 -f 10073//10073 10080//10080 11542//11542 -f 11542//11542 10080//10080 10082//10082 -f 11542//11542 10082//10082 11543//11543 -f 11543//11543 10082//10082 10091//10091 -f 11543//11543 10091//10091 11544//11544 -f 11544//11544 10091//10091 10090//10090 -f 11544//11544 10090//10090 11538//11538 -f 11538//11538 10090//10090 10088//10088 -f 11538//11538 10088//10088 10086//10086 -f 11542//11542 11545//11545 10073//10073 -f 10073//10073 11545//11545 11546//11546 -f 10073//10073 11546//11546 10074//10074 -f 10074//10074 11546//11546 11547//11547 -f 10074//10074 11547//11547 10076//10076 -f 10076//10076 11547//11547 11548//11548 -f 10076//10076 11548//11548 10077//10077 -f 10077//10077 11548//11548 11549//11549 -f 10077//10077 11549//11549 10057//10057 -f 10057//10057 11549//11549 11550//11550 -f 10057//10057 11550//11550 10059//10059 -f 10059//10059 11550//11550 11551//11551 -f 10059//10059 11551//11551 10061//10061 -f 10061//10061 11551//11551 11552//11552 -f 10061//10061 11552//11552 10063//10063 -f 10063//10063 11552//11552 11553//11553 -f 10071//10071 10072//10072 11554//11554 -f 11554//11554 10072//10072 10067//10067 -f 11554//11554 10067//10067 11553//11553 -f 11553//11553 10067//10067 10065//10065 -f 11553//11553 10065//10065 10063//10063 -f 10071//10071 11554//11554 10069//10069 -f 10069//10069 11554//11554 11555//11555 -f 10069//10069 11555//11555 10707//10707 -f 10707//10707 11555//11555 10705//10705 -f 10705//10705 11555//11555 11556//11556 -f 10705//10705 11556//11556 10703//10703 -f 10703//10703 11556//11556 11557//11557 -f 10703//10703 11557//11557 10701//10701 -f 10701//10701 11557//11557 11558//11558 -f 10701//10701 11558//11558 10699//10699 -f 10699//10699 11558//11558 10697//10697 -f 10697//10697 11558//11558 11559//11559 -f 10697//10697 11559//11559 10695//10695 -f 11559//11559 11560//11560 10695//10695 -f 10695//10695 11560//11560 11561//11561 -f 10695//10695 11561//11561 10693//10693 -f 10693//10693 11561//11561 11562//11562 -f 10693//10693 11562//11562 10691//10691 -f 10691//10691 11562//11562 10689//10689 -f 10689//10689 11562//11562 11563//11563 -f 10689//10689 11563//11563 10686//10686 -f 11563//11563 11564//11564 10686//10686 -f 10686//10686 11564//11564 11565//11565 -f 10686//10686 11565//11565 10685//10685 -f 10685//10685 11565//11565 11566//11566 -f 10685//10685 11566//11566 10683//10683 -f 10683//10683 11566//11566 11567//11567 -f 10683//10683 11567//11567 10681//10681 -f 10681//10681 11567//11567 11568//11568 -f 11569//11569 10054//10054 11570//11570 -f 11570//11570 10054//10054 10052//10052 -f 11570//11570 10052//10052 11571//11571 -f 11571//11571 10052//10052 10675//10675 -f 11571//11571 10675//10675 11572//11572 -f 11572//11572 10675//10675 10673//10673 -f 11572//11572 10673//10673 11573//11573 -f 11573//11573 10673//10673 10672//10672 -f 11573//11573 10672//10672 11568//11568 -f 11568//11568 10672//10672 10679//10679 -f 11568//11568 10679//10679 10681//10681 -f 11574//11574 10043//10043 11575//11575 -f 11575//11575 10043//10043 10044//10044 -f 11575//11575 10044//10044 11576//11576 -f 11576//11576 10044//10044 10046//10046 -f 11576//11576 10046//10046 11577//11577 -f 11577//11577 10046//10046 10048//10048 -f 11577//11577 10048//10048 11569//11569 -f 11569//11569 10048//10048 10055//10055 -f 11569//11569 10055//10055 10054//10054 -f 11578//11578 10039//10039 11574//11574 -f 11574//11574 10039//10039 10041//10041 -f 11574//11574 10041//10041 10043//10043 -f 11578//11578 11579//11579 10039//10039 -f 10039//10039 11579//11579 11464//11464 -f 10039//10039 11464//11464 10037//10037 -f 10807//10807 10175//10175 11465//11465 -f 11465//11465 10175//10175 10173//10173 -f 11465//11465 10173//10173 11580//11580 -f 11580//11580 10173//10173 10171//10171 -f 11580//11580 10171//10171 11581//11581 -f 11581//11581 10171//10171 10170//10170 -f 11581//11581 10170//10170 11582//11582 -f 11582//11582 10170//10170 10179//10179 -f 11582//11582 10179//10179 11583//11583 -f 11583//11583 10179//10179 10181//10181 -f 11583//11583 10181//10181 11584//11584 -f 10181//10181 10183//10183 11584//11584 -f 11584//11584 10183//10183 10186//10186 -f 11584//11584 10186//10186 11585//11585 -f 11585//11585 10186//10186 10188//10188 -f 11585//11585 10188//10188 11586//11586 -f 11586//11586 10224//10224 10226//10226 -f 11586//11586 10226//10226 11585//11585 -f 11585//11585 10226//10226 10205//10205 -f 11585//11585 10205//10205 11584//11584 -f 11584//11584 10205//10205 11583//11583 -f 11583//11583 10205//10205 10207//10207 -f 11583//11583 10207//10207 11582//11582 -f 11582//11582 10207//10207 10209//10209 -f 11582//11582 10209//10209 11581//11581 -f 11581//11581 10209//10209 10215//10215 -f 11581//11581 10215//10215 11580//11580 -f 10215//10215 10213//10213 11580//11580 -f 11580//11580 10213//10213 10211//10211 -f 11580//11580 10211//10211 11465//11465 -f 11465//11465 10211//10211 10839//10839 -f 11465//11465 10839//10839 11466//11466 -f 11466//11466 10839//10839 10841//10841 -f 11466//11466 10841//10841 11467//11467 -f 11467//11467 10841//10841 10843//10843 -f 11467//11467 10843//10843 11468//11468 -f 10843//10843 10845//10845 11468//11468 -f 11468//11468 10845//10845 10847//10847 -f 11468//11468 10847//10847 11469//11469 -f 11469//11469 10847//10847 10837//10837 -f 11469//11469 10837//10837 11470//11470 -f 11470//11470 10837//10837 10835//10835 -f 11470//11470 10835//10835 11471//11471 -f 10835//10835 10834//10834 11471//11471 -f 11471//11471 10834//10834 10832//10832 -f 11471//11471 10832//10832 11472//11472 -f 10832//10832 10830//10830 11472//11472 -f 11472//11472 10830//10830 10828//10828 -f 11472//11472 10828//10828 11473//11473 -f 11473//11473 10828//10828 10825//10825 -f 11473//11473 10825//10825 11474//11474 -f 11474//11474 10825//10825 10823//10823 -f 11474//11474 10823//10823 11475//11475 -f 10823//10823 10821//10821 11475//11475 -f 11475//11475 10821//10821 10819//10819 -f 11475//11475 10819//10819 11476//11476 -f 11476//11476 10819//10819 10818//10818 -f 11476//11476 10818//10818 11477//11477 -f 11477//11477 10818//10818 10815//10815 -f 11477//11477 10815//10815 11478//11478 -f 10815//10815 10817//10817 11478//11478 -f 11478//11478 10817//10817 10200//10200 -f 11478//11478 10200//10200 11479//11479 -f 11479//11479 10200//10200 10199//10199 -f 11479//11479 10199//10199 11480//11480 -f 11480//11480 10199//10199 10168//10168 -f 11480//11480 10168//10168 11481//11481 -f 11481//11481 10168//10168 10167//10167 -f 11481//11481 10167//10167 11482//11482 -f 11482//11482 10167//10167 10198//10198 -f 11482//11482 10198//10198 11483//11483 -f 11483//11483 10198//10198 10197//10197 -f 11483//11483 10197//10197 11484//11484 -f 11484//11484 10197//10197 10193//10193 -f 11484//11484 10193//10193 11485//11485 -f 11485//11485 10193//10193 10191//10191 -f 11492//11492 11491//11491 10182//10182 -f 10182//10182 11491//11491 10184//10184 -f 10184//10184 11491//11491 11490//11490 -f 10184//10184 11490//11490 10185//10185 -f 10185//10185 11490//11490 11489//11489 -f 10185//10185 11489//11489 10187//10187 -f 10187//10187 11489//11489 11488//11488 -f 10187//10187 11488//11488 10189//10189 -f 10189//10189 11488//11488 11487//11487 -f 10189//10189 11487//11487 10191//10191 -f 10191//10191 11487//11487 11486//11486 -f 10191//10191 11486//11486 11485//11485 -f 10182//10182 10180//10180 11492//11492 -f 11492//11492 10180//10180 10178//10178 -f 11492//11492 10178//10178 11493//11493 -f 11493//11493 10178//10178 10177//10177 -f 11493//11493 10177//10177 11494//11494 -f 11494//11494 10177//10177 10172//10172 -f 11494//11494 10172//10172 11495//11495 -f 10172//10172 10174//10174 11495//11495 -f 11495//11495 10174//10174 10176//10176 -f 11495//11495 10176//10176 11496//11496 -f 11496//11496 10176//10176 10806//10806 -f 11496//11496 10806//10806 11497//11497 -f 10806//10806 10808//10808 11497//11497 -f 11497//11497 10808//10808 10810//10810 -f 11497//11497 10810//10810 11498//11498 -f 11498//11498 10810//10810 10805//10805 -f 11498//11498 10805//10805 11499//11499 -f 11499//11499 10805//10805 10803//10803 -f 11499//11499 10803//10803 11500//11500 -f 11500//11500 10803//10803 10802//10802 -f 11500//11500 10802//10802 11501//11501 -f 11501//11501 10802//10802 10800//10800 -f 11501//11501 10800//10800 11502//11502 -f 11502//11502 10800//10800 10798//10798 -f 11502//11502 10798//10798 11503//11503 -f 11503//11503 10798//10798 10796//10796 -f 11503//11503 10796//10796 11504//11504 -f 11504//11504 10796//10796 10780//10780 -f 11504//11504 10780//10780 11505//11505 -f 11505//11505 10780//10780 10794//10794 -f 11505//11505 10794//10794 11506//11506 -f 10794//10794 10793//10793 11506//11506 -f 11506//11506 10793//10793 10791//10791 -f 11506//11506 10791//10791 11507//11507 -f 11507//11507 10791//10791 10789//10789 -f 11507//11507 10789//10789 11508//11508 -f 11508//11508 10789//10789 10788//10788 -f 11508//11508 10788//10788 11509//11509 -f 11509//11509 10788//10788 10786//10786 -f 11509//11509 10786//10786 11510//11510 -f 11510//11510 10786//10786 10784//10784 -f 11510//11510 10784//10784 11511//11511 -f 11511//11511 10784//10784 10782//10782 -f 11511//11511 10782//10782 11512//11512 -f 11512//11512 10782//10782 10157//10157 -f 11512//11512 10157//10157 11513//11513 -f 11513//11513 10157//10157 10159//10159 -f 11513//11513 10159//10159 11514//11514 -f 11514//11514 10159//10159 10161//10161 -f 11514//11514 10161//10161 11515//11515 -f 11515//11515 10161//10161 10164//10164 -f 11515//11515 10164//10164 11516//11516 -f 11516//11516 10164//10164 10150//10150 -f 10143//10143 11521//11521 11520//11520 -f 10143//10143 11520//11520 10154//10154 -f 10154//10154 11520//11520 11519//11519 -f 10154//10154 11519//11519 10152//10152 -f 10152//10152 11519//11519 11518//11518 -f 10152//10152 11518//11518 10150//10150 -f 10150//10150 11518//11518 11517//11517 -f 10150//10150 11517//11517 11516//11516 -f 11521//11521 10143//10143 11522//11522 -f 11522//11522 10143//10143 10142//10142 -f 11522//11522 10142//10142 11523//11523 -f 10142//10142 10135//10135 11523//11523 -f 11523//11523 10135//10135 10137//10137 -f 11523//11523 10137//10137 11524//11524 -f 11524//11524 10137//10137 10139//10139 -f 11524//11524 10139//10139 11525//11525 -f 11525//11525 10139//10139 10130//10130 -f 11525//11525 10130//10130 11526//11526 -f 10130//10130 10129//10129 11526//11526 -f 11526//11526 10129//10129 10132//10132 -f 11526//11526 10132//10132 11527//11527 -f 10774//10774 11528//11528 10776//10776 -f 10776//10776 11528//11528 11527//11527 -f 10776//10776 11527//11527 10777//10777 -f 10777//10777 11527//11527 10132//10132 -f 10774//10774 10772//10772 11528//11528 -f 11528//11528 10772//10772 10771//10771 -f 11528//11528 10771//10771 11531//11531 -f 10771//10771 10769//10769 11531//11531 -f 11531//11531 10769//10769 10767//10767 -f 11531//11531 10767//10767 11530//11530 -f 11530//11530 10767//10767 10765//10765 -f 11530//11530 10765//10765 11529//11529 -f 11529//11529 10765//10765 10763//10763 -f 11529//11529 10763//10763 11533//11533 -f 11533//11533 10763//10763 10761//10761 -f 11533//11533 10761//10761 11532//11532 -f 11532//11532 10761//10761 10759//10759 -f 11532//11532 10759//10759 11535//11535 -f 11535//11535 10759//10759 10756//10756 -f 11535//11535 10756//10756 11534//11534 -f 10756//10756 10754//10754 11534//11534 -f 11534//11534 10754//10754 10753//10753 -f 11534//11534 10753//10753 11537//11537 -f 11537//11537 10753//10753 10744//10744 -f 11537//11537 10744//10744 11536//11536 -f 10744//10744 10746//10746 11536//11536 -f 11536//11536 10746//10746 10748//10748 -f 11536//11536 10748//10748 11541//11541 -f 11541//11541 10748//10748 10750//10750 -f 11541//11541 10750//10750 11540//11540 -f 11540//11540 10750//10750 11539//11539 -f 11539//11539 10750//10750 10128//10128 -f 11539//11539 10128//10128 11538//11538 -f 11538//11538 10128//10128 10127//10127 -f 11538//11538 10127//10127 11544//11544 -f 11544//11544 10127//10127 10125//10125 -f 11544//11544 10125//10125 11543//11543 -f 10125//10125 10123//10123 11543//11543 -f 11543//11543 10123//10123 10121//10121 -f 11543//11543 10121//10121 11542//11542 -f 11542//11542 10121//10121 10119//10119 -f 11542//11542 10119//10119 11545//11545 -f 11545//11545 10119//10119 10117//10117 -f 11545//11545 10117//10117 11546//11546 -f 11546//11546 10117//10117 10094//10094 -f 11546//11546 10094//10094 11547//11547 -f 11547//11547 10094//10094 10115//10115 -f 11547//11547 10115//10115 11548//11548 -f 11548//11548 10115//10115 10114//10114 -f 11548//11548 10114//10114 11549//11549 -f 11549//11549 10114//10114 10111//10111 -f 11549//11549 10111//10111 11550//11550 -f 11550//11550 10111//10111 10109//10109 -f 11550//11550 10109//10109 11551//11551 -f 11551//11551 10109//10109 10108//10108 -f 11551//11551 10108//10108 11552//11552 -f 10108//10108 10106//10106 11552//11552 -f 11552//11552 10106//10106 10104//10104 -f 11552//11552 10104//10104 11553//11553 -f 10104//10104 10102//10102 11553//11553 -f 11553//11553 10102//10102 10100//10100 -f 11553//11553 10100//10100 11554//11554 -f 10100//10100 10098//10098 11554//11554 -f 11554//11554 10098//10098 10096//10096 -f 11554//11554 10096//10096 11555//11555 -f 11555//11555 10096//10096 10742//10742 -f 11555//11555 10742//10742 11556//11556 -f 11556//11556 10742//10742 10740//10740 -f 11556//11556 10740//10740 11557//11557 -f 11557//11557 10740//10740 10739//10739 -f 11557//11557 10739//10739 11558//11558 -f 11558//11558 10739//10739 10737//10737 -f 11558//11558 10737//10737 11559//11559 -f 10737//10737 10735//10735 11559//11559 -f 11559//11559 10735//10735 10734//10734 -f 11559//11559 10734//10734 11560//11560 -f 11560//11560 10734//10734 10732//10732 -f 11560//11560 10732//10732 11561//11561 -f 11561//11561 10732//10732 10730//10730 -f 11561//11561 10730//10730 11562//11562 -f 11562//11562 10730//10730 10728//10728 -f 11562//11562 10728//10728 11563//11563 -f 11563//11563 10728//10728 10725//10725 -f 11563//11563 10725//10725 11564//11564 -f 11564//11564 10725//10725 10719//10719 -f 11564//11564 10719//10719 11565//11565 -f 11565//11565 10719//10719 10717//10717 -f 11565//11565 10717//10717 11566//11566 -f 11566//11566 10717//10717 10723//10723 -f 11566//11566 10723//10723 11567//11567 -f 11567//11567 10723//10723 10722//10722 -f 11567//11567 10722//10722 11568//11568 -f 11568//11568 10722//10722 10713//10713 -f 11568//11568 10713//10713 11573//11573 -f 11573//11573 10713//10713 10711//10711 -f 11573//11573 10711//10711 11572//11572 -f 11572//11572 10711//10711 10709//10709 -f 11572//11572 10709//10709 11571//11571 -f 11571//11571 10709//10709 10085//10085 -f 11571//11571 10085//10085 11570//11570 -f 10085//10085 10087//10087 11570//11570 -f 11570//11570 10087//10087 10089//10089 -f 11570//11570 10089//10089 11569//11569 -f 11569//11569 10089//10089 10081//10081 -f 11569//11569 10081//10081 11577//11577 -f 11577//11577 10081//10081 11576//11576 -f 10081//10081 10083//10083 11576//11576 -f 11576//11576 10083//10083 10084//10084 -f 11576//11576 10084//10084 11575//11575 -f 11575//11575 10084//10084 10079//10079 -f 11575//11575 10079//10079 11574//11574 -f 11574//11574 10079//10079 10078//10078 -f 11574//11574 10078//10078 11578//11578 -f 11578//11578 10078//10078 10075//10075 -f 11578//11578 10075//10075 11579//11579 -f 11579//11579 10075//10075 10056//10056 -f 11579//11579 10056//10056 11464//11464 -f 10876//10876 10875//10875 11587//11587 -f 11588//11588 11589//11589 10323//10323 -f 10323//10323 11589//11589 11590//11590 -f 10323//10323 11590//11590 10321//10321 -f 10321//10321 11590//11590 11591//11591 -f 10321//10321 11591//11591 10960//10960 -f 10960//10960 11591//11591 11592//11592 -f 10960//10960 11592//11592 10958//10958 -f 10958//10958 11592//11592 11593//11593 -f 11594//11594 10954//10954 11593//11593 -f 11593//11593 10954//10954 10956//10956 -f 11593//11593 10956//10956 10958//10958 -f 11595//11595 10949//10949 11596//11596 -f 11596//11596 10949//10949 10948//10948 -f 11596//11596 10948//10948 11597//11597 -f 11597//11597 10948//10948 10946//10946 -f 11597//11597 10946//10946 11598//11598 -f 11598//11598 10946//10946 10945//10945 -f 11598//11598 10945//10945 11594//11594 -f 11594//11594 10945//10945 10952//10952 -f 11594//11594 10952//10952 10954//10954 -f 11599//11599 10930//10930 11600//11600 -f 11600//11600 10930//10930 10932//10932 -f 11600//11600 10932//10932 11601//11601 -f 11601//11601 10932//10932 10934//10934 -f 11601//11601 10934//10934 11602//11602 -f 11602//11602 10934//10934 10937//10937 -f 11602//11602 10937//10937 11603//11603 -f 11603//11603 10937//10937 10939//10939 -f 11603//11603 10939//10939 11604//11604 -f 11604//11604 10939//10939 10940//10940 -f 11604//11604 10940//10940 11595//11595 -f 11595//11595 10940//10940 10942//10942 -f 11595//11595 10942//10942 10949//10949 -f 10320//10320 10319//10319 11605//11605 -f 11605//11605 10319//10319 10317//10317 -f 11605//11605 10317//10317 11599//11599 -f 11599//11599 10317//10317 10928//10928 -f 11599//11599 10928//10928 10930//10930 -f 10320//10320 11605//11605 10314//10314 -f 10314//10314 11605//11605 11606//11606 -f 10314//10314 11606//11606 10315//10315 -f 11607//11607 10303//10303 11606//11606 -f 11606//11606 10303//10303 10302//10302 -f 11606//11606 10302//10302 10315//10315 -f 11608//11608 10308//10308 11609//11609 -f 11609//11609 10308//10308 10307//10307 -f 11609//11609 10307//10307 11607//11607 -f 11607//11607 10307//10307 10305//10305 -f 11607//11607 10305//10305 10303//10303 -f 10301//10301 10300//10300 11610//11610 -f 11610//11610 10300//10300 10299//10299 -f 11610//11610 10299//10299 11611//11611 -f 11611//11611 10299//10299 10298//10298 -f 11611//11611 10298//10298 11612//11612 -f 11612//11612 10298//10298 10311//10311 -f 11612//11612 10311//10311 11608//11608 -f 11608//11608 10311//10311 10310//10310 -f 11608//11608 10310//10310 10308//10308 -f 10301//10301 11610//11610 10290//10290 -f 10290//10290 11610//11610 11613//11613 -f 10290//10290 11613//11613 10291//10291 -f 10291//10291 11613//11613 11614//11614 -f 10291//10291 11614//11614 10292//10292 -f 10292//10292 11614//11614 11615//11615 -f 10292//10292 11615//11615 10294//10294 -f 10294//10294 11615//11615 11616//11616 -f 10294//10294 11616//11616 10295//10295 -f 10295//10295 11616//11616 10284//10284 -f 10284//10284 11616//11616 11617//11617 -f 10284//10284 11617//11617 10286//10286 -f 10286//10286 11617//11617 10287//10287 -f 10287//10287 11617//11617 11618//11618 -f 10287//10287 11618//11618 10925//10925 -f 10925//10925 11618//11618 10911//10911 -f 10911//10911 11618//11618 11619//11619 -f 10911//10911 11619//11619 10912//10912 -f 10912//10912 11619//11619 11620//11620 -f 10912//10912 11620//11620 10914//10914 -f 10914//10914 11620//11620 11621//11621 -f 10914//10914 11621//11621 10915//10915 -f 10915//10915 11621//11621 11622//11622 -f 10915//10915 11622//11622 10917//10917 -f 10917//10917 11622//11622 10919//10919 -f 10919//10919 11622//11622 11623//11623 -f 10919//10919 11623//11623 10921//10921 -f 10921//10921 11623//11623 11624//11624 -f 10921//10921 11624//11624 10923//10923 -f 10923//10923 11624//11624 11625//11625 -f 10923//10923 11625//11625 10924//10924 -f 10924//10924 11625//11625 10908//10908 -f 10908//10908 11625//11625 11626//11626 -f 10908//10908 11626//11626 10909//10909 -f 10909//10909 11626//11626 11627//11627 -f 10909//10909 11627//11627 10904//10904 -f 10904//10904 11627//11627 11628//11628 -f 10904//10904 11628//11628 10902//10902 -f 10902//10902 11628//11628 11629//11629 -f 10902//10902 11629//11629 10900//10900 -f 11630//11630 10896//10896 11629//11629 -f 11629//11629 10896//10896 10898//10898 -f 11629//11629 10898//10898 10900//10900 -f 11631//11631 10277//10277 11632//11632 -f 11632//11632 10277//10277 10279//10279 -f 11632//11632 10279//10279 11633//11633 -f 11633//11633 10279//10279 10891//10891 -f 11633//11633 10891//10891 11634//11634 -f 11634//11634 10891//10891 10893//10893 -f 11634//11634 10893//10893 11630//11630 -f 11630//11630 10893//10893 10894//10894 -f 11630//11630 10894//10894 10896//10896 -f 11635//11635 10268//10268 11636//11636 -f 11636//11636 10268//10268 10270//10270 -f 11636//11636 10270//10270 11637//11637 -f 11637//11637 10270//10270 10272//10272 -f 11637//11637 10272//10272 11638//11638 -f 11638//11638 10272//10272 10274//10274 -f 11638//11638 10274//10274 11631//11631 -f 11631//11631 10274//10274 10275//10275 -f 11631//11631 10275//10275 10277//10277 -f 11639//11639 10245//10245 11635//11635 -f 11635//11635 10245//10245 10244//10244 -f 11635//11635 10244//10244 10268//10268 -f 11640//11640 10263//10263 11639//11639 -f 11639//11639 10263//10263 10265//10265 -f 11639//11639 10265//10265 10245//10245 -f 11641//11641 10249//10249 11640//11640 -f 11640//11640 10249//10249 10248//10248 -f 11640//11640 10248//10248 10263//10263 -f 11642//11642 10883//10883 11643//11643 -f 11643//11643 10883//10883 10881//10881 -f 11643//11643 10881//10881 11644//11644 -f 11644//11644 10881//10881 10250//10250 -f 11644//11644 10250//10250 11645//11645 -f 11645//11645 10250//10250 10252//10252 -f 11645//11645 10252//10252 11646//11646 -f 11646//11646 10252//10252 10254//10254 -f 11646//11646 10254//10254 11647//11647 -f 11647//11647 10254//10254 10256//10256 -f 11647//11647 10256//10256 11648//11648 -f 11648//11648 10256//10256 10258//10258 -f 11648//11648 10258//10258 11641//11641 -f 11641//11641 10258//10258 10260//10260 -f 11641//11641 10260//10260 10249//10249 -f 10875//10875 10873//10873 11587//11587 -f 11587//11587 10873//10873 10871//10871 -f 11587//11587 10871//10871 11649//11649 -f 11649//11649 10871//10871 10890//10890 -f 11649//11649 10890//10890 11650//11650 -f 11650//11650 10890//10890 10889//10889 -f 11650//11650 10889//10889 11651//11651 -f 11651//11651 10889//10889 10887//10887 -f 11651//11651 10887//10887 11642//11642 -f 11642//11642 10887//10887 10885//10885 -f 11642//11642 10885//10885 10883//10883 -f 10876//10876 11587//11587 10878//10878 -f 10878//10878 11587//11587 11652//11652 -f 10878//10878 11652//11652 10879//10879 -f 10879//10879 11652//11652 10867//10867 -f 10867//10867 11652//11652 11653//11653 -f 10867//10867 11653//11653 10868//10868 -f 10868//10868 11653//11653 10860//10860 -f 10860//10860 11653//11653 11654//11654 -f 10860//10860 11654//11654 10862//10862 -f 10862//10862 11654//11654 10864//10864 -f 10864//10864 11654//11654 11655//11655 -f 10864//10864 11655//11655 10865//10865 -f 10865//10865 11655//11655 11656//11656 -f 10865//10865 11656//11656 10854//10854 -f 10854//10854 11656//11656 10856//10856 -f 10856//10856 11656//11656 11657//11657 -f 10856//10856 11657//11657 10858//10858 -f 10858//10858 11657//11657 11658//11658 -f 10858//10858 11658//11658 10852//10852 -f 10852//10852 11658//11658 11659//11659 -f 10852//10852 11659//11659 10850//10850 -f 10850//10850 11659//11659 11660//11660 -f 10850//10850 11660//11660 10243//10243 -f 10243//10243 11660//11660 10241//10241 -f 10241//10241 11660//11660 11661//11661 -f 10241//10241 11661//11661 10238//10238 -f 10238//10238 11661//11661 11662//11662 -f 10238//10238 11662//11662 10237//10237 -f 10237//10237 11662//11662 10235//10235 -f 10235//10235 11662//11662 11663//11663 -f 10235//10235 11663//11663 10233//10233 -f 11664//11664 10223//10223 11665//11665 -f 11665//11665 10223//10223 10221//10221 -f 11665//11665 10221//10221 11666//11666 -f 11666//11666 10221//10221 10219//10219 -f 11666//11666 10219//10219 11667//11667 -f 11667//11667 10219//10219 10218//10218 -f 11667//11667 10218//10218 11663//11663 -f 11663//11663 10218//10218 10231//10231 -f 11663//11663 10231//10231 10233//10233 -f 10212//10212 10214//10214 11668//11668 -f 11668//11668 10214//10214 10216//10216 -f 11668//11668 10216//10216 11669//11669 -f 11669//11669 10216//10216 10217//10217 -f 11669//11669 10217//10217 11670//11670 -f 11670//11670 10217//10217 10208//10208 -f 11670//11670 10208//10208 11671//11671 -f 11671//11671 10208//10208 10206//10206 -f 11671//11671 10206//10206 11672//11672 -f 11672//11672 10206//10206 10228//10228 -f 11672//11672 10228//10228 11673//11673 -f 11673//11673 10228//10228 10227//10227 -f 11673//11673 10227//10227 11664//11664 -f 11664//11664 10227//10227 10225//10225 -f 11664//11664 10225//10225 10223//10223 -f 10212//10212 11668//11668 10210//10210 -f 10210//10210 11668//11668 11674//11674 -f 10210//10210 11674//11674 10838//10838 -f 10838//10838 11674//11674 10840//10840 -f 10840//10840 11674//11674 11675//11675 -f 10840//10840 11675//11675 10842//10842 -f 10842//10842 11675//11675 10844//10844 -f 10844//10844 11675//11675 11676//11676 -f 10844//10844 11676//11676 10846//10846 -f 10846//10846 11676//11676 11677//11677 -f 10846//10846 11677//11677 10848//10848 -f 10848//10848 11677//11677 10849//10849 -f 10849//10849 11677//11677 11678//11678 -f 10849//10849 11678//11678 10836//10836 -f 10836//10836 11678//11678 11679//11679 -f 10836//10836 11679//11679 10833//10833 -f 10833//10833 11679//11679 11680//11680 -f 10833//10833 11680//11680 10831//10831 -f 10831//10831 11680//11680 11681//11681 -f 10831//10831 11681//11681 10829//10829 -f 10829//10829 11681//11681 10827//10827 -f 10827//10827 11681//11681 11682//11682 -f 10827//10827 11682//11682 10826//10826 -f 10826//10826 11682//11682 11683//11683 -f 10826//10826 11683//11683 10824//10824 -f 10824//10824 11683//11683 11684//11684 -f 10824//10824 11684//11684 10822//10822 -f 10822//10822 11684//11684 11685//11685 -f 10822//10822 11685//11685 10820//10820 -f 10820//10820 11685//11685 11686//11686 -f 10820//10820 11686//11686 10813//10813 -f 10813//10813 11686//11686 11687//11687 -f 10813//10813 11687//11687 10814//10814 -f 10814//10814 11687//11687 10816//10816 -f 10816//10816 11687//11687 11688//11688 -f 10816//10816 11688//11688 10201//10201 -f 10201//10201 11688//11688 11689//11689 -f 10201//10201 11689//11689 10202//10202 -f 10202//10202 11689//11689 10203//10203 -f 10203//10203 11689//11689 11690//11690 -f 10203//10203 11690//11690 10204//10204 -f 10204//10204 11690//11690 10169//10169 -f 10169//10169 11690//11690 11691//11691 -f 10169//10169 11691//11691 10196//10196 -f 10196//10196 11691//11691 10195//10195 -f 10195//10195 11691//11691 11692//11692 -f 10195//10195 11692//11692 10194//10194 -f 10194//10194 11692//11692 11693//11693 -f 10194//10194 11693//11693 10192//10192 -f 10192//10192 11693//11693 11694//11694 -f 10192//10192 11694//11694 10190//10190 -f 10190//10190 11694//11694 11586//11586 -f 10190//10190 11586//11586 10188//10188 -f 10323//10323 10325//10325 11588//11588 -f 11588//11588 10325//10325 10327//10327 -f 11588//11588 10327//10327 11695//11695 -f 11695//11695 10327//10327 10329//10329 -f 11695//11695 10329//10329 11696//11696 -f 11696//11696 10329//10329 10332//10332 -f 11696//11696 10332//10332 11697//11697 -f 11697//11697 10332//10332 10334//10334 -f 11697//11697 10334//10334 11698//11698 -f 11698//11698 10334//10334 10335//10335 -f 11698//11698 10335//10335 11699//11699 -f 10335//10335 10338//10338 11699//11699 -f 11699//11699 10338//10338 10340//10340 -f 11699//11699 10340//10340 11700//11700 -f 11700//11700 10362//10362 10365//10365 -f 11700//11700 10365//10365 11699//11699 -f 11699//11699 10365//10365 10367//10367 -f 11699//11699 10367//10367 11698//11698 -f 11698//11698 10367//10367 11697//11697 -f 11697//11697 10367//10367 10369//10369 -f 11697//11697 10369//10369 11696//11696 -f 11696//11696 10369//10369 10371//10371 -f 11696//11696 10371//10371 11695//11695 -f 11695//11695 10371//10371 10373//10373 -f 11695//11695 10373//10373 11588//11588 -f 11588//11588 10373//10373 10375//10375 -f 11588//11588 10375//10375 11589//11589 -f 11589//11589 10375//10375 10377//10377 -f 11589//11589 10377//10377 11590//11590 -f 11590//11590 10377//10377 11591//11591 -f 11591//11591 10377//10377 10995//10995 -f 11591//11591 10995//10995 11592//11592 -f 10995//10995 10993//10993 11592//11592 -f 11592//11592 10993//10993 10991//10991 -f 11592//11592 10991//10991 11593//11593 -f 10991//10991 10989//10989 11593//11593 -f 11593//11593 10989//10989 10988//10988 -f 11593//11593 10988//10988 11594//11594 -f 10988//10988 10986//10986 11594//11594 -f 11594//11594 10986//10986 10984//10984 -f 11594//11594 10984//10984 11598//11598 -f 11598//11598 10984//10984 10983//10983 -f 11598//11598 10983//10983 11597//11597 -f 11597//11597 10983//10983 10980//10980 -f 11597//11597 10980//10980 11596//11596 -f 11596//11596 10980//10980 10978//10978 -f 11596//11596 10978//10978 11595//11595 -f 11595//11595 10978//10978 10977//10977 -f 11595//11595 10977//10977 11604//11604 -f 11604//11604 10977//10977 10974//10974 -f 11604//11604 10974//10974 11603//11603 -f 11603//11603 10974//10974 10972//10972 -f 11603//11603 10972//10972 11602//11602 -f 10963//10963 11599//11599 10965//10965 -f 10965//10965 11599//11599 11600//11600 -f 10965//10965 11600//11600 10967//10967 -f 10967//10967 11600//11600 11601//11601 -f 10967//10967 11601//11601 10969//10969 -f 10969//10969 11601//11601 11602//11602 -f 10969//10969 11602//11602 10970//10970 -f 10970//10970 11602//11602 10972//10972 -f 10963//10963 10353//10353 11599//11599 -f 11599//11599 10353//10353 10352//10352 -f 11599//11599 10352//10352 11605//11605 -f 10352//10352 10356//10356 11605//11605 -f 11605//11605 10356//10356 10355//10355 -f 11605//11605 10355//10355 11606//11606 -f 10355//10355 10350//10350 11606//11606 -f 11606//11606 10350//10350 10348//10348 -f 11606//11606 10348//10348 11607//11607 -f 11607//11607 10348//10348 10345//10345 -f 11607//11607 10345//10345 11609//11609 -f 11609//11609 10345//10345 10343//10343 -f 11615//11615 11614//11614 10333//10333 -f 10333//10333 11614//11614 10336//10336 -f 10336//10336 11614//11614 11613//11613 -f 10336//10336 11613//11613 10337//10337 -f 10337//10337 11613//11613 11610//11610 -f 10337//10337 11610//11610 10339//10339 -f 10339//10339 11610//11610 11611//11611 -f 10339//10339 11611//11611 10341//10341 -f 10341//10341 11611//11611 11612//11612 -f 10341//10341 11612//11612 10343//10343 -f 10343//10343 11612//11612 11608//11608 -f 10343//10343 11608//11608 11609//11609 -f 10333//10333 10331//10331 11615//11615 -f 11615//11615 10331//10331 10330//10330 -f 11615//11615 10330//10330 11616//11616 -f 10330//10330 10328//10328 11616//11616 -f 11616//11616 10328//10328 10326//10326 -f 11616//11616 10326//10326 11617//11617 -f 10326//10326 10324//10324 11617//11617 -f 11617//11617 10324//10324 10322//10322 -f 11617//11617 10322//10322 11618//11618 -f 10938//10938 11629//11629 10941//10941 -f 10941//10941 11629//11629 11628//11628 -f 10941//10941 11628//11628 10943//10943 -f 10943//10943 11628//11628 11627//11627 -f 10943//10943 11627//11627 10944//10944 -f 10944//10944 11627//11627 11626//11626 -f 10944//10944 11626//11626 10947//10947 -f 10947//10947 11626//11626 11625//11625 -f 10947//10947 11625//11625 10950//10950 -f 10950//10950 11625//11625 11624//11624 -f 10950//10950 11624//11624 10951//10951 -f 10951//10951 11624//11624 11623//11623 -f 10951//10951 11623//11623 10953//10953 -f 10953//10953 11623//11623 11622//11622 -f 10953//10953 11622//11622 10955//10955 -f 10955//10955 11622//11622 11621//11621 -f 10955//10955 11621//11621 10957//10957 -f 10957//10957 11621//11621 11620//11620 -f 10957//10957 11620//11620 10959//10959 -f 10959//10959 11620//11620 11619//11619 -f 10959//10959 11619//11619 10962//10962 -f 10962//10962 11619//11619 11618//11618 -f 10962//10962 11618//11618 10961//10961 -f 10961//10961 11618//11618 10322//10322 -f 10938//10938 10936//10936 11629//11629 -f 11629//11629 10936//10936 10935//10935 -f 11629//11629 10935//10935 11630//11630 -f 10935//10935 10933//10933 11630//11630 -f 11630//11630 10933//10933 10931//10931 -f 11630//11630 10931//10931 11634//11634 -f 11634//11634 10931//10931 10929//10929 -f 11634//11634 10929//10929 11633//11633 -f 11633//11633 10929//10929 10316//10316 -f 11633//11633 10316//10316 11632//11632 -f 11632//11632 10316//10316 10318//10318 -f 11632//11632 10318//10318 11631//11631 -f 11631//11631 10318//10318 10313//10313 -f 11631//11631 10313//10313 11638//11638 -f 11638//11638 10313//10313 10312//10312 -f 11638//11638 10312//10312 11637//11637 -f 11637//11637 10312//10312 10304//10304 -f 11637//11637 10304//10304 11636//11636 -f 11636//11636 10304//10304 10306//10306 -f 11636//11636 10306//10306 11635//11635 -f 11635//11635 10306//10306 10309//10309 -f 11635//11635 10309//10309 11639//11639 -f 10309//10309 10297//10297 11639//11639 -f 11639//11639 10297//10297 10296//10296 -f 11639//11639 10296//10296 11640//11640 -f 11648//11648 11641//11641 10288//10288 -f 10288//10288 11641//11641 11640//11640 -f 10288//10288 11640//11640 10289//10289 -f 10289//10289 11640//11640 10296//10296 -f 11648//11648 10288//10288 11647//11647 -f 11647//11647 10288//10288 10293//10293 -f 11647//11647 10293//10293 11646//11646 -f 11646//11646 10293//10293 10283//10283 -f 11646//11646 10283//10283 11645//11645 -f 11645//11645 10283//10283 10282//10282 -f 11645//11645 10282//10282 11644//11644 -f 11644//11644 10282//10282 10285//10285 -f 11644//11644 10285//10285 11643//11643 -f 10285//10285 10927//10927 11643//11643 -f 11643//11643 10927//10927 10926//10926 -f 11643//11643 10926//10926 11642//11642 -f 11642//11642 10926//10926 10910//10910 -f 11642//11642 10910//10910 11651//11651 -f 11651//11651 10910//10910 10913//10913 -f 11651//11651 10913//10913 11650//11650 -f 11650//11650 10913//10913 10916//10916 -f 11650//11650 10916//10916 11649//11649 -f 11649//11649 10916//10916 10918//10918 -f 11649//11649 10918//10918 11587//11587 -f 10918//10918 10920//10920 11587//11587 -f 11587//11587 10920//10920 10922//10922 -f 11587//11587 10922//10922 11652//11652 -f 10922//10922 10907//10907 11652//11652 -f 11652//11652 10907//10907 10903//10903 -f 11652//11652 10903//10903 11653//11653 -f 11653//11653 10903//10903 11654//11654 -f 11654//11654 10903//10903 10905//10905 -f 11654//11654 10905//10905 11655//11655 -f 10905//10905 10906//10906 11655//11655 -f 11655//11655 10906//10906 10901//10901 -f 11655//11655 10901//10901 11656//11656 -f 11656//11656 10901//10901 10899//10899 -f 11656//11656 10899//10899 11657//11657 -f 10899//10899 10897//10897 11657//11657 -f 11657//11657 10897//10897 10895//10895 -f 11657//11657 10895//10895 11658//11658 -f 11658//11658 10895//10895 10892//10892 -f 11658//11658 10892//10892 11659//11659 -f 11659//11659 10892//10892 10281//10281 -f 11659//11659 10281//10281 11660//11660 -f 11660//11660 10281//10281 10280//10280 -f 11660//11660 10280//10280 11661//11661 -f 11661//11661 10280//10280 10278//10278 -f 11661//11661 10278//10278 11662//11662 -f 10278//10278 10276//10276 11662//11662 -f 11662//11662 10276//10276 10273//10273 -f 11662//11662 10273//10273 11663//11663 -f 11663//11663 10273//10273 10271//10271 -f 11663//11663 10271//10271 10269//10269 -f 10262//10262 11671//11671 10247//10247 -f 10247//10247 11671//11671 11672//11672 -f 10247//10247 11672//11672 10264//10264 -f 10264//10264 11672//11672 11673//11673 -f 10264//10264 11673//11673 10266//10266 -f 10266//10266 11673//11673 11664//11664 -f 10266//10266 11664//11664 10267//10267 -f 10267//10267 11664//11664 11665//11665 -f 10267//10267 11665//11665 10246//10246 -f 10246//10246 11665//11665 11666//11666 -f 10246//10246 11666//11666 10269//10269 -f 10269//10269 11666//11666 11667//11667 -f 10269//10269 11667//11667 11663//11663 -f 10262//10262 10261//10261 11671//11671 -f 11671//11671 10261//10261 10259//10259 -f 11671//11671 10259//10259 11670//11670 -f 11670//11670 10259//10259 10257//10257 -f 11670//11670 10257//10257 11669//11669 -f 11669//11669 10257//10257 10255//10255 -f 11669//11669 10255//10255 11668//11668 -f 10255//10255 10253//10253 11668//11668 -f 11668//11668 10253//10253 10251//10251 -f 11668//11668 10251//10251 11674//11674 -f 10251//10251 10880//10880 11674//11674 -f 11674//11674 10880//10880 10882//10882 -f 11674//11674 10882//10882 11675//11675 -f 10882//10882 10884//10884 11675//11675 -f 11675//11675 10884//10884 10886//10886 -f 11675//11675 10886//10886 11676//11676 -f 10886//10886 10888//10888 11676//11676 -f 11676//11676 10888//10888 10870//10870 -f 11676//11676 10870//10870 11677//11677 -f 11677//11677 10870//10870 10869//10869 -f 11677//11677 10869//10869 11678//11678 -f 11678//11678 10869//10869 10872//10872 -f 11678//11678 10872//10872 11679//11679 -f 11679//11679 10872//10872 10874//10874 -f 11679//11679 10874//10874 11680//11680 -f 10874//10874 10877//10877 11680//11680 -f 11680//11680 10877//10877 10866//10866 -f 11680//11680 10866//10866 11681//11681 -f 11681//11681 10866//10866 10859//10859 -f 11681//11681 10859//10859 11682//11682 -f 11682//11682 10859//10859 11683//11683 -f 11683//11683 10859//10859 10861//10861 -f 11683//11683 10861//10861 11684//11684 -f 10861//10861 10863//10863 11684//11684 -f 11684//11684 10863//10863 10853//10853 -f 11684//11684 10853//10853 11685//11685 -f 11685//11685 10853//10853 10855//10855 -f 11685//11685 10855//10855 11686//11686 -f 11686//11686 10855//10855 11687//11687 -f 11687//11687 10855//10855 10857//10857 -f 11687//11687 10857//10857 11688//11688 -f 10857//10857 10851//10851 11688//11688 -f 11688//11688 10851//10851 10242//10242 -f 11688//11688 10242//10242 11689//11689 -f 10242//10242 10240//10240 11689//11689 -f 11689//11689 10240//10240 10239//10239 -f 11689//11689 10239//10239 11690//11690 -f 10239//10239 10236//10236 11690//11690 -f 11690//11690 10236//10236 10234//10234 -f 11690//11690 10234//10234 11691//11691 -f 11691//11691 10234//10234 10232//10232 -f 11691//11691 10232//10232 11692//11692 -f 11692//11692 10232//10232 10230//10230 -f 11692//11692 10230//10230 11693//11693 -f 10230//10230 10229//10229 11693//11693 -f 11693//11693 10229//10229 10220//10220 -f 11693//11693 10220//10220 11694//11694 -f 10220//10220 10222//10222 11694//11694 -f 11694//11694 10222//10222 10224//10224 -f 11694//11694 10224//10224 11586//11586 -f 11701//11701 11702//11702 9686//9686 -f 9686//9686 11702//11702 9687//9687 -f 9687//9687 11702//11702 11703//11703 -f 9687//9687 11703//11703 9652//9652 -f 9652//9652 11703//11703 11704//11704 -f 9652//9652 11704//11704 9680//9680 -f 9680//9680 11704//11704 11705//11705 -f 9680//9680 11705//11705 9678//9678 -f 9678//9678 11705//11705 11706//11706 -f 9678//9678 11706//11706 9676//9676 -f 9676//9676 11706//11706 11707//11707 -f 9676//9676 11707//11707 9674//9674 -f 9674//9674 11707//11707 9672//9672 -f 9672//9672 11707//11707 11708//11708 -f 9672//9672 11708//11708 9670//9670 -f 9670//9670 11708//11708 11709//11709 -f 9670//9670 11709//11709 9667//9667 -f 9667//9667 11709//11709 11710//11710 -f 9667//9667 11710//11710 9665//9665 -f 11710//11710 11711//11711 9665//9665 -f 9665//9665 11711//11711 11712//11712 -f 9665//9665 11712//11712 9663//9663 -f 9663//9663 11712//11712 11713//11713 -f 9663//9663 11713//11713 9661//9661 -f 9661//9661 11713//11713 11714//11714 -f 9661//9661 11714//11714 9659//9659 -f 9659//9659 11714//11714 11715//11715 -f 11716//11716 9653//9653 11717//11717 -f 11717//11717 9653//9653 9655//9655 -f 11717//11717 9655//9655 11715//11715 -f 11715//11715 9655//9655 9657//9657 -f 11715//11715 9657//9657 9659//9659 -f 11718//11718 11025//11025 11719//11719 -f 11719//11719 11025//11025 11023//11023 -f 11719//11719 11023//11023 11720//11720 -f 11720//11720 11023//11023 11021//11021 -f 11720//11720 11021//11021 11721//11721 -f 11721//11721 11021//11021 11019//11019 -f 11721//11721 11019//11019 11722//11722 -f 11722//11722 11019//11019 11017//11017 -f 11722//11722 11017//11017 11716//11716 -f 11716//11716 11017//11017 11015//11015 -f 11716//11716 11015//11015 9653//9653 -f 11723//11723 11029//11029 11718//11718 -f 11718//11718 11029//11029 11027//11027 -f 11718//11718 11027//11027 11025//11025 -f 11723//11723 11724//11724 11029//11029 -f 11029//11029 11724//11724 11725//11725 -f 11029//11029 11725//11725 11013//11013 -f 11013//11013 11725//11725 11726//11726 -f 11013//11013 11726//11726 11012//11012 -f 11012//11012 11726//11726 11727//11727 -f 11012//11012 11727//11727 11010//11010 -f 11010//11010 11727//11727 11728//11728 -f 11010//11010 11728//11728 11008//11008 -f 11728//11728 11729//11729 11008//11008 -f 11008//11008 11729//11729 11730//11730 -f 11008//11008 11730//11730 10997//10997 -f 10997//10997 11730//11730 11731//11731 -f 10997//10997 11731//11731 10998//10998 -f 10998//10998 11731//11731 11732//11732 -f 10998//10998 11732//11732 11000//11000 -f 11000//11000 11732//11732 11733//11733 -f 11000//11000 11733//11733 11002//11002 -f 11002//11002 11733//11733 11004//11004 -f 11733//11733 11734//11734 11004//11004 -f 11004//11004 11734//11734 11735//11735 -f 11004//11004 11735//11735 11005//11005 -f 11005//11005 11735//11735 11736//11736 -f 11005//11005 11736//11736 10390//10390 -f 10390//10390 11736//11736 11737//11737 -f 10390//10390 11737//11737 10388//10388 -f 11737//11737 11738//11738 10388//10388 -f 10388//10388 11738//11738 11739//11739 -f 10388//10388 11739//11739 10386//10386 -f 10386//10386 11739//11739 11740//11740 -f 10386//10386 11740//11740 10384//10384 -f 10384//10384 11740//11740 11741//11741 -f 10384//10384 11741//11741 10382//10382 -f 11742//11742 10380//10380 11743//11743 -f 11743//11743 10380//10380 10382//10382 -f 11743//11743 10382//10382 11744//11744 -f 11744//11744 10382//10382 11741//11741 -f 11742//11742 11745//11745 10380//10380 -f 10380//10380 11745//11745 11746//11746 -f 10380//10380 11746//11746 10360//10360 -f 10360//10360 11746//11746 11747//11747 -f 10360//10360 11747//11747 10361//10361 -f 10361//10361 11747//11747 11748//11748 -f 10361//10361 11748//11748 10363//10363 -f 10363//10363 11748//11748 11749//11749 -f 10363//10363 11749//11749 10364//10364 -f 11749//11749 11750//11750 10364//10364 -f 10364//10364 11750//11750 11751//11751 -f 10364//10364 11751//11751 10366//10366 -f 10366//10366 11751//11751 11752//11752 -f 10366//10366 11752//11752 10368//10368 -f 10368//10368 11752//11752 11753//11753 -f 10368//10368 11753//11753 10370//10370 -f 10370//10370 11753//11753 11754//11754 -f 10370//10370 11754//11754 10372//10372 -f 10372//10372 11754//11754 10374//10374 -f 10374//10374 11754//11754 11755//11755 -f 10374//10374 11755//11755 10379//10379 -f 10379//10379 11755//11755 11756//11756 -f 10379//10379 11756//11756 10378//10378 -f 10378//10378 11756//11756 11757//11757 -f 10378//10378 11757//11757 10376//10376 -f 10376//10376 11757//11757 10996//10996 -f 10996//10996 11757//11757 11758//11758 -f 10996//10996 11758//11758 10994//10994 -f 10994//10994 11758//11758 11759//11759 -f 10994//10994 11759//11759 10992//10992 -f 10992//10992 11759//11759 11760//11760 -f 10992//10992 11760//11760 10990//10990 -f 10990//10990 11760//11760 11761//11761 -f 10990//10990 11761//11761 10987//10987 -f 11761//11761 11762//11762 10987//10987 -f 10987//10987 11762//11762 11763//11763 -f 10987//10987 11763//11763 10985//10985 -f 10985//10985 11763//11763 11764//11764 -f 10985//10985 11764//11764 10982//10982 -f 11764//11764 11765//11765 10982//10982 -f 10982//10982 11765//11765 11766//11766 -f 10982//10982 11766//11766 10981//10981 -f 10981//10981 11766//11766 11767//11767 -f 10981//10981 11767//11767 10979//10979 -f 10979//10979 11767//11767 11768//11768 -f 10979//10979 11768//11768 10976//10976 -f 10976//10976 11768//11768 11769//11769 -f 10976//10976 11769//11769 10975//10975 -f 10975//10975 11769//11769 11770//11770 -f 10975//10975 11770//11770 10973//10973 -f 11770//11770 11771//11771 10973//10973 -f 10973//10973 11771//11771 11772//11772 -f 10973//10973 11772//11772 10971//10971 -f 11772//11772 11773//11773 10971//10971 -f 10971//10971 11773//11773 11774//11774 -f 10971//10971 11774//11774 10968//10968 -f 10968//10968 11774//11774 11775//11775 -f 10968//10968 11775//11775 10966//10966 -f 11775//11775 11776//11776 10966//10966 -f 10966//10966 11776//11776 11777//11777 -f 10966//10966 11777//11777 10964//10964 -f 10964//10964 11777//11777 11778//11778 -f 10964//10964 11778//11778 10354//10354 -f 11778//11778 11779//11779 10354//10354 -f 10354//10354 11779//11779 11780//11780 -f 10354//10354 11780//11780 10358//10358 -f 10358//10358 11780//11780 11781//11781 -f 10358//10358 11781//11781 10357//10357 -f 10357//10357 11781//11781 11782//11782 -f 10357//10357 11782//11782 10351//10351 -f 10351//10351 11782//11782 11783//11783 -f 10351//10351 11783//11783 10349//10349 -f 10349//10349 11783//11783 11784//11784 -f 10349//10349 11784//11784 10347//10347 -f 10347//10347 11784//11784 11785//11785 -f 10347//10347 11785//11785 10346//10346 -f 10346//10346 11785//11785 11786//11786 -f 10346//10346 11786//11786 10344//10344 -f 11786//11786 11787//11787 10344//10344 -f 10344//10344 11787//11787 11788//11788 -f 10344//10344 11788//11788 10342//10342 -f 10342//10342 11788//11788 11700//11700 -f 10342//10342 11700//11700 10340//10340 -f 9686//9686 9684//9684 11701//11701 -f 11701//11701 9684//9684 11052//11052 -f 11701//11701 11052//11052 11789//11789 -f 11789//11789 11052//11052 11790//11790 -f 11789//11789 11790//11790 11791//11791 -f 11791//11791 11790//11790 11792//11792 -f 11791//11791 11792//11792 11793//11793 -f 11793//11793 11792//11792 11794//11794 -f 11793//11793 11794//11794 11795//11795 -f 11795//11795 11794//11794 11796//11796 -f 11795//11795 11796//11796 11797//11797 -f 11797//11797 11796//11796 11798//11798 -f 11797//11797 11798//11798 11799//11799 -f 11799//11799 11798//11798 11800//11800 -f 11799//11799 11800//11800 11801//11801 -f 11801//11801 11800//11800 11802//11802 -f 11801//11801 11802//11802 11803//11803 -f 11793//11793 11795//11795 11804//11804 -f 10359//10359 10362//10362 11700//11700 -f 11700//11700 11788//11788 10359//10359 -f 10359//10359 11788//11788 11787//11787 -f 10359//10359 11787//11787 10381//10381 -f 11787//11787 11786//11786 10381//10381 -f 10381//10381 11786//11786 11785//11785 -f 10381//10381 11785//11785 10383//10383 -f 10383//10383 11785//11785 11784//11784 -f 10383//10383 11784//11784 10385//10385 -f 10385//10385 11784//11784 11783//11783 -f 10385//10385 11783//11783 10387//10387 -f 10387//10387 11783//11783 11782//11782 -f 10387//10387 11782//11782 10392//10392 -f 10392//10392 11782//11782 11781//11781 -f 10392//10392 11781//11781 10391//10391 -f 10391//10391 11781//11781 11780//11780 -f 10391//10391 11780//11780 10389//10389 -f 10389//10389 11780//11780 11779//11779 -f 11779//11779 11778//11778 10389//10389 -f 10389//10389 11778//11778 11777//11777 -f 10389//10389 11777//11777 11003//11003 -f 11003//11003 11777//11777 11776//11776 -f 11003//11003 11776//11776 11001//11001 -f 11776//11776 11775//11775 11001//11001 -f 11001//11001 11775//11775 11774//11774 -f 11001//11001 11774//11774 10999//10999 -f 10999//10999 11774//11774 11773//11773 -f 10999//10999 11773//11773 11006//11006 -f 11006//11006 11773//11773 11772//11772 -f 11006//11006 11772//11772 11007//11007 -f 11007//11007 11772//11772 11771//11771 -f 11007//11007 11771//11771 11009//11009 -f 11009//11009 11771//11771 11770//11770 -f 11009//11009 11770//11770 11011//11011 -f 11770//11770 11769//11769 11011//11011 -f 11011//11011 11769//11769 11768//11768 -f 11011//11011 11768//11768 11031//11031 -f 11031//11031 11768//11768 11767//11767 -f 11031//11031 11767//11767 11030//11030 -f 11767//11767 11766//11766 11030//11030 -f 11030//11030 11766//11766 11765//11765 -f 11030//11030 11765//11765 11028//11028 -f 11028//11028 11765//11765 11764//11764 -f 11028//11028 11764//11764 11026//11026 -f 11026//11026 11764//11764 11763//11763 -f 11026//11026 11763//11763 11024//11024 -f 11024//11024 11763//11763 11762//11762 -f 11024//11024 11762//11762 11022//11022 -f 11022//11022 11762//11762 11761//11761 -f 11022//11022 11761//11761 11020//11020 -f 11020//11020 11761//11761 11760//11760 -f 11020//11020 11760//11760 11018//11018 -f 11018//11018 11760//11760 11759//11759 -f 11018//11018 11759//11759 11016//11016 -f 11016//11016 11759//11759 11758//11758 -f 11016//11016 11758//11758 11014//11014 -f 11014//11014 11758//11758 11757//11757 -f 11014//11014 11757//11757 9654//9654 -f 9654//9654 11757//11757 11756//11756 -f 9654//9654 11756//11756 9656//9656 -f 9656//9656 11756//11756 11755//11755 -f 9656//9656 11755//11755 9658//9658 -f 9658//9658 11755//11755 11754//11754 -f 11753//11753 9662//9662 11754//11754 -f 11754//11754 9662//9662 9660//9660 -f 11754//11754 9660//9660 9658//9658 -f 9669//9669 9668//9668 11752//11752 -f 11752//11752 9668//9668 9666//9666 -f 11752//11752 9666//9666 11753//11753 -f 11753//11753 9666//9666 9664//9664 -f 11753//11753 9664//9664 9662//9662 -f 11752//11752 11751//11751 9669//9669 -f 9669//9669 11751//11751 11750//11750 -f 9669//9669 11750//11750 9671//9671 -f 11750//11750 11749//11749 9671//9671 -f 9671//9671 11749//11749 11748//11748 -f 9671//9671 11748//11748 9673//9673 -f 9673//9673 11748//11748 11747//11747 -f 9673//9673 11747//11747 9675//9675 -f 11743//11743 9679//9679 11742//11742 -f 11742//11742 9679//9679 9677//9677 -f 11742//11742 9677//9677 11745//11745 -f 11745//11745 9677//9677 9675//9675 -f 11745//11745 9675//9675 11746//11746 -f 11746//11746 9675//9675 11747//11747 -f 11743//11743 11744//11744 9679//9679 -f 9679//9679 11744//11744 11741//11741 -f 9679//9679 11741//11741 9681//9681 -f 9681//9681 11741//11741 11740//11740 -f 9681//9681 11740//11740 9650//9650 -f 9650//9650 11740//11740 11739//11739 -f 9650//9650 11739//11739 9651//9651 -f 9651//9651 11739//11739 11738//11738 -f 9651//9651 11738//11738 9685//9685 -f 9685//9685 11738//11738 11737//11737 -f 9685//9685 11737//11737 9682//9682 -f 9682//9682 11737//11737 11736//11736 -f 9682//9682 11736//11736 9683//9683 -f 9683//9683 11736//11736 11053//11053 -f 11053//11053 11736//11736 11735//11735 -f 11053//11053 11735//11735 11055//11055 -f 11055//11055 11735//11735 11734//11734 -f 11055//11055 11734//11734 11056//11056 -f 11734//11734 11733//11733 11056//11056 -f 11056//11056 11733//11733 11732//11732 -f 11056//11056 11732//11732 11059//11059 -f 11059//11059 11732//11732 11731//11731 -f 11059//11059 11731//11731 11060//11060 -f 11731//11731 11730//11730 11060//11060 -f 11060//11060 11730//11730 11729//11729 -f 11060//11060 11729//11729 11062//11062 -f 11062//11062 11729//11729 11728//11728 -f 11062//11062 11728//11728 11063//11063 -f 11063//11063 11728//11728 11805//11805 -f 11728//11728 11727//11727 11805//11805 -f 11805//11805 11727//11727 11726//11726 -f 11805//11805 11726//11726 11806//11806 -f 11806//11806 11726//11726 11725//11725 -f 11806//11806 11725//11725 11807//11807 -f 11807//11807 11725//11725 11724//11724 -f 11807//11807 11724//11724 11808//11808 -f 11724//11724 11723//11723 11808//11808 -f 11808//11808 11723//11723 11718//11718 -f 11808//11808 11718//11718 11809//11809 -f 11809//11809 11718//11718 11810//11810 -f 11810//11810 11718//11718 11719//11719 -f 11810//11810 11719//11719 11811//11811 -f 11811//11811 11719//11719 11812//11812 -f 11812//11812 11719//11719 11720//11720 -f 11812//11812 11720//11720 11813//11813 -f 11813//11813 11720//11720 11721//11721 -f 11813//11813 11721//11721 11814//11814 -f 11814//11814 11721//11721 11722//11722 -f 11814//11814 11722//11722 11815//11815 -f 11815//11815 11722//11722 11716//11716 -f 11815//11815 11716//11716 11816//11816 -f 11816//11816 11716//11716 11817//11817 -f 11817//11817 11716//11716 11717//11717 -f 11817//11817 11717//11717 11818//11818 -f 11818//11818 11717//11717 11715//11715 -f 11818//11818 11715//11715 11819//11819 -f 11819//11819 11715//11715 11714//11714 -f 11819//11819 11714//11714 11820//11820 -f 11820//11820 11714//11714 11821//11821 -f 11821//11821 11714//11714 11713//11713 -f 11821//11821 11713//11713 11822//11822 -f 11713//11713 11712//11712 11822//11822 -f 11822//11822 11712//11712 11711//11711 -f 11822//11822 11711//11711 11823//11823 -f 11711//11711 11710//11710 11823//11823 -f 11823//11823 11710//11710 11709//11709 -f 11823//11823 11709//11709 11824//11824 -f 11824//11824 11709//11709 11708//11708 -f 11824//11824 11708//11708 11825//11825 -f 11825//11825 11708//11708 11707//11707 -f 11825//11825 11707//11707 11826//11826 -f 11826//11826 11707//11707 11827//11827 -f 11827//11827 11707//11707 11706//11706 -f 11827//11827 11706//11706 11828//11828 -f 11828//11828 11706//11706 11705//11705 -f 11828//11828 11705//11705 11829//11829 -f 11829//11829 11705//11705 11704//11704 -f 11829//11829 11704//11704 11830//11830 -f 11830//11830 11704//11704 11703//11703 -f 11830//11830 11703//11703 11831//11831 -f 11831//11831 11703//11703 11702//11702 -f 11831//11831 11702//11702 11832//11832 -f 11702//11702 11701//11701 11832//11832 -f 11832//11832 11701//11701 11789//11789 -f 11832//11832 11789//11789 11804//11804 -f 11804//11804 11789//11789 11791//11791 -f 11804//11804 11791//11791 11793//11793 -f 11790//11790 11052//11052 11054//11054 -f 11830//11830 11831//11831 11833//11833 -f 11826//11826 11827//11827 11834//11834 -f 11834//11834 11827//11827 11828//11828 -f 11834//11834 11828//11828 11833//11833 -f 11833//11833 11828//11828 11829//11829 -f 11833//11833 11829//11829 11830//11830 -f 11826//11826 11834//11834 11825//11825 -f 11825//11825 11834//11834 11835//11835 -f 11825//11825 11835//11835 11824//11824 -f 11824//11824 11835//11835 11836//11836 -f 11824//11824 11836//11836 11823//11823 -f 11823//11823 11836//11836 11837//11837 -f 11823//11823 11837//11837 11822//11822 -f 11837//11837 11838//11838 11822//11822 -f 11822//11822 11838//11838 11839//11839 -f 11822//11822 11839//11839 11821//11821 -f 11821//11821 11839//11839 11840//11840 -f 11821//11821 11840//11840 11820//11820 -f 11820//11820 11840//11840 11819//11819 -f 11819//11819 11840//11840 11841//11841 -f 11819//11819 11841//11841 11818//11818 -f 11818//11818 11841//11841 11817//11817 -f 11817//11817 11841//11841 11842//11842 -f 11817//11817 11842//11842 11816//11816 -f 11816//11816 11842//11842 11815//11815 -f 11815//11815 11842//11842 11843//11843 -f 11815//11815 11843//11843 11814//11814 -f 11810//11810 11811//11811 11844//11844 -f 11844//11844 11811//11811 11812//11812 -f 11844//11844 11812//11812 11843//11843 -f 11843//11843 11812//11812 11813//11813 -f 11843//11843 11813//11813 11814//11814 -f 11845//11845 11808//11808 11844//11844 -f 11844//11844 11808//11808 11809//11809 -f 11844//11844 11809//11809 11810//11810 -f 11057//11057 11058//11058 11798//11798 -f 11798//11798 11058//11058 11061//11061 -f 11798//11798 11061//11061 11800//11800 -f 11800//11800 11061//11061 11063//11063 -f 11800//11800 11063//11063 11802//11802 -f 11802//11802 11063//11063 11805//11805 -f 11802//11802 11805//11805 11803//11803 -f 11803//11803 11805//11805 11806//11806 -f 11803//11803 11806//11806 11845//11845 -f 11845//11845 11806//11806 11807//11807 -f 11845//11845 11807//11807 11808//11808 -f 11798//11798 11796//11796 11057//11057 -f 11057//11057 11796//11796 11794//11794 -f 11057//11057 11794//11794 11054//11054 -f 11054//11054 11794//11794 11792//11792 -f 11054//11054 11792//11792 11790//11790 -f 11832//11832 11804//11804 11795//11795 -f 11838//11838 11795//11795 11839//11839 -f 11839//11839 11795//11795 11840//11840 -f 11840//11840 11795//11795 11841//11841 -f 11841//11841 11795//11795 11797//11797 -f 11841//11841 11797//11797 11799//11799 -f 11801//11801 11803//11803 11845//11845 -f 11845//11845 11844//11844 11843//11843 -f 11799//11799 11801//11801 11841//11841 -f 11841//11841 11801//11801 11845//11845 -f 11841//11841 11845//11845 11842//11842 -f 11842//11842 11845//11845 11843//11843 -f 11835//11835 11834//11834 11836//11836 -f 11836//11836 11834//11834 11833//11833 -f 11838//11838 11837//11837 11795//11795 -f 11795//11795 11837//11837 11836//11836 -f 11795//11795 11836//11836 11832//11832 -f 11832//11832 11836//11836 11833//11833 -f 11832//11832 11833//11833 11831//11831 -f 11846//11846 11847//11847 11848//11848 -f 11848//11848 11847//11847 11849//11849 -f 11850//11850 11851//11851 11852//11852 -f 11853//11853 11854//11854 11855//11855 -f 11855//11855 11854//11854 11856//11856 -f 11856//11856 11854//11854 11857//11857 -f 11856//11856 11857//11857 11858//11858 -f 11853//11853 11855//11855 11859//11859 -f 11859//11859 11855//11855 11860//11860 -f 11859//11859 11860//11860 11861//11861 -f 11861//11861 11860//11860 11862//11862 -f 11861//11861 11862//11862 11863//11863 -f 11863//11863 11862//11862 11864//11864 -f 11864//11864 11862//11862 11865//11865 -f 11864//11864 11865//11865 11866//11866 -f 11866//11866 11865//11865 11867//11867 -f 11867//11867 11865//11865 11868//11868 -f 11867//11867 11868//11868 11869//11869 -f 11869//11869 11868//11868 11870//11870 -f 11869//11869 11870//11870 11871//11871 -f 11852//11852 11851//11851 11870//11870 -f 11870//11870 11851//11851 11872//11872 -f 11870//11870 11872//11872 11871//11871 -f 11850//11850 11852//11852 11873//11873 -f 11873//11873 11852//11852 11874//11874 -f 11873//11873 11874//11874 11875//11875 -f 11875//11875 11874//11874 11876//11876 -f 11875//11875 11876//11876 11877//11877 -f 11877//11877 11876//11876 11878//11878 -f 11878//11878 11876//11876 11879//11879 -f 11878//11878 11879//11879 11880//11880 -f 11880//11880 11879//11879 11881//11881 -f 11880//11880 11881//11881 11882//11882 -f 11883//11883 11884//11884 11885//11885 -f 11885//11885 11884//11884 11886//11886 -f 11885//11885 11886//11886 11887//11887 -f 11887//11887 11886//11886 11888//11888 -f 11889//11889 11890//11890 11888//11888 -f 11888//11888 11890//11890 11891//11891 -f 11888//11888 11891//11891 11887//11887 -f 11892//11892 11893//11893 11894//11894 -f 11894//11894 11893//11893 11895//11895 -f 11894//11894 11895//11895 11896//11896 -f 11896//11896 11895//11895 11897//11897 -f 11896//11896 11897//11897 11889//11889 -f 11889//11889 11897//11897 11898//11898 -f 11889//11889 11898//11898 11890//11890 -f 11847//11847 11899//11899 11849//11849 -f 11849//11849 11899//11899 11900//11900 -f 11849//11849 11900//11900 11892//11892 -f 11892//11892 11900//11900 11901//11901 -f 11892//11892 11901//11901 11893//11893 -f 11846//11846 11848//11848 11902//11902 -f 11902//11902 11848//11848 11903//11903 -f 11902//11902 11903//11903 11904//11904 -f 11904//11904 11903//11903 11905//11905 -f 11904//11904 11905//11905 11906//11906 -f 11906//11906 11905//11905 11907//11907 -f 11907//11907 11905//11905 11908//11908 -f 11907//11907 11908//11908 11909//11909 -f 11910//11910 11908//11908 11911//11911 -f 11911//11911 11908//11908 11905//11905 -f 11911//11911 11905//11905 11912//11912 -f 11912//11912 11905//11905 11903//11903 -f 11912//11912 11903//11903 11913//11913 -f 11913//11913 11903//11903 11848//11848 -f 11913//11913 11848//11848 11914//11914 -f 11914//11914 11848//11848 11849//11849 -f 11914//11914 11849//11849 11915//11915 -f 11915//11915 11849//11849 11892//11892 -f 11915//11915 11892//11892 11916//11916 -f 11916//11916 11892//11892 11894//11894 -f 11916//11916 11894//11894 11917//11917 -f 11917//11917 11894//11894 11896//11896 -f 11917//11917 11896//11896 11918//11918 -f 11918//11918 11896//11896 11889//11889 -f 11918//11918 11889//11889 11919//11919 -f 11919//11919 11889//11889 11888//11888 -f 11919//11919 11888//11888 11920//11920 -f 11920//11920 11888//11888 11886//11886 -f 11920//11920 11886//11886 11921//11921 -f 11921//11921 11886//11886 11884//11884 -f 11856//11856 11910//11910 11855//11855 -f 11855//11855 11910//11910 11911//11911 -f 11855//11855 11911//11911 11860//11860 -f 11860//11860 11911//11911 11912//11912 -f 11860//11860 11912//11912 11862//11862 -f 11862//11862 11912//11912 11913//11913 -f 11862//11862 11913//11913 11865//11865 -f 11865//11865 11913//11913 11914//11914 -f 11865//11865 11914//11914 11868//11868 -f 11868//11868 11914//11914 11915//11915 -f 11868//11868 11915//11915 11870//11870 -f 11870//11870 11915//11915 11916//11916 -f 11870//11870 11916//11916 11852//11852 -f 11852//11852 11916//11916 11917//11917 -f 11852//11852 11917//11917 11874//11874 -f 11874//11874 11917//11917 11918//11918 -f 11874//11874 11918//11918 11876//11876 -f 11876//11876 11918//11918 11919//11919 -f 11876//11876 11919//11919 11879//11879 -f 11879//11879 11919//11919 11920//11920 -f 11879//11879 11920//11920 11881//11881 -f 11881//11881 11920//11920 11921//11921 -f 11922//11922 11923//11923 11924//11924 -f 11925//11925 11926//11926 11927//11927 -f 11928//11928 11929//11929 11926//11926 -f 11930//11930 11931//11931 11932//11932 -f 11933//11933 11931//11931 11934//11934 -f 11934//11934 11931//11931 11930//11930 -f 11934//11934 11930//11930 11935//11935 -f 11936//11936 11937//11937 11938//11938 -f 11939//11939 11940//11940 11937//11937 -f 11941//11941 11942//11942 11940//11940 -f 11943//11943 11944//11944 11945//11945 -f 11946//11946 11935//11935 11947//11947 -f 11947//11947 11935//11935 11930//11930 -f 11947//11947 11930//11930 11948//11948 -f 11948//11948 11930//11930 11932//11932 -f 11948//11948 11932//11932 11929//11929 -f 11949//11949 11950//11950 11951//11951 -f 11952//11952 11950//11950 11953//11953 -f 11953//11953 11950//11950 11949//11949 -f 11953//11953 11949//11949 11954//11954 -f 11955//11955 11956//11956 11957//11957 -f 11943//11943 11945//11945 11958//11958 -f 11958//11958 11945//11945 11955//11955 -f 11958//11958 11955//11955 11959//11959 -f 11959//11959 11955//11955 11957//11957 -f 11959//11959 11957//11957 11960//11960 -f 11960//11960 11961//11961 11959//11959 -f 11959//11959 11961//11961 11962//11962 -f 11959//11959 11962//11962 11958//11958 -f 11958//11958 11962//11962 11925//11925 -f 11958//11958 11925//11925 11943//11943 -f 11943//11943 11925//11925 11927//11927 -f 11943//11943 11927//11927 11944//11944 -f 11944//11944 11927//11927 11963//11963 -f 11944//11944 11963//11963 11964//11964 -f 11960//11960 11965//11965 11961//11961 -f 11961//11961 11965//11965 11966//11966 -f 11961//11961 11966//11966 11967//11967 -f 11926//11926 11925//11925 11928//11928 -f 11928//11928 11925//11925 11962//11962 -f 11928//11928 11962//11962 11968//11968 -f 11968//11968 11962//11962 11961//11961 -f 11968//11968 11961//11961 11969//11969 -f 11969//11969 11961//11961 11967//11967 -f 11969//11969 11967//11967 11970//11970 -f 11929//11929 11928//11928 11948//11948 -f 11948//11948 11928//11928 11968//11968 -f 11948//11948 11968//11968 11947//11947 -f 11947//11947 11968//11968 11969//11969 -f 11947//11947 11969//11969 11946//11946 -f 11946//11946 11969//11969 11970//11970 -f 11946//11946 11970//11970 11971//11971 -f 11971//11971 11972//11972 11946//11946 -f 11946//11946 11972//11972 11973//11973 -f 11946//11946 11973//11973 11935//11935 -f 11935//11935 11973//11973 11974//11974 -f 11935//11935 11974//11974 11934//11934 -f 11934//11934 11974//11974 11975//11975 -f 11934//11934 11975//11975 11933//11933 -f 11933//11933 11975//11975 11976//11976 -f 11972//11972 11977//11977 11973//11973 -f 11973//11973 11977//11977 11954//11954 -f 11973//11973 11954//11954 11974//11974 -f 11974//11974 11954//11954 11949//11949 -f 11974//11974 11949//11949 11975//11975 -f 11975//11975 11949//11949 11951//11951 -f 11975//11975 11951//11951 11976//11976 -f 11976//11976 11951//11951 11938//11938 -f 11977//11977 11978//11978 11954//11954 -f 11954//11954 11978//11978 11979//11979 -f 11954//11954 11979//11979 11953//11953 -f 11953//11953 11979//11979 11980//11980 -f 11953//11953 11980//11980 11952//11952 -f 11952//11952 11980//11980 11981//11981 -f 11952//11952 11981//11981 11982//11982 -f 11938//11938 11951//11951 11936//11936 -f 11936//11936 11951//11951 11950//11950 -f 11936//11936 11950//11950 11983//11983 -f 11983//11983 11950//11950 11952//11952 -f 11983//11983 11952//11952 11984//11984 -f 11984//11984 11952//11952 11982//11982 -f 11984//11984 11982//11982 11985//11985 -f 11937//11937 11936//11936 11939//11939 -f 11939//11939 11936//11936 11983//11983 -f 11939//11939 11983//11983 11986//11986 -f 11986//11986 11983//11983 11984//11984 -f 11986//11986 11984//11984 11924//11924 -f 11924//11924 11984//11984 11985//11985 -f 11924//11924 11985//11985 11922//11922 -f 11940//11940 11939//11939 11941//11941 -f 11941//11941 11939//11939 11986//11986 -f 11941//11941 11986//11986 11987//11987 -f 11987//11987 11986//11986 11924//11924 -f 11987//11987 11924//11924 11988//11988 -f 11988//11988 11924//11924 11923//11923 -f 11988//11988 11923//11923 11989//11989 -f 11990//11990 11991//11991 11992//11992 -f 11993//11993 11994//11994 11995//11995 -f 11995//11995 11994//11994 11996//11996 -f 11995//11995 11996//11996 11997//11997 -f 11997//11997 11996//11996 11998//11998 -f 11997//11997 11998//11998 11999//11999 -f 11999//11999 11998//11998 12000//12000 -f 11999//11999 12000//12000 12001//12001 -f 12001//12001 12000//12000 12002//12002 -f 12001//12001 12002//12002 12003//12003 -f 12003//12003 12002//12002 12004//12004 -f 12003//12003 12004//12004 12005//12005 -f 12005//12005 12004//12004 12006//12006 -f 12005//12005 12006//12006 12007//12007 -f 12006//12006 12008//12008 12007//12007 -f 12007//12007 12008//12008 12009//12009 -f 12007//12007 12009//12009 12010//12010 -f 12010//12010 12009//12009 12011//12011 -f 12010//12010 12011//12011 12012//12012 -f 12012//12012 12011//12011 12013//12013 -f 12012//12012 12013//12013 12014//12014 -f 12014//12014 12013//12013 12015//12015 -f 12014//12014 12015//12015 12016//12016 -f 12016//12016 12015//12015 12017//12017 -f 12016//12016 12017//12017 12018//12018 -f 12018//12018 12017//12017 12019//12019 -f 12018//12018 12019//12019 12020//12020 -f 12020//12020 12019//12019 11992//11992 -f 11992//11992 12019//12019 12021//12021 -f 11992//11992 12021//12021 11990//11990 -f 12022//12022 12023//12023 12024//12024 -f 12022//12022 12024//12024 12025//12025 -f 12025//12025 12024//12024 12026//12026 -f 12025//12025 12026//12026 11991//11991 -f 11991//11991 12026//12026 12027//12027 -f 11991//11991 12027//12027 11992//11992 -f 12028//12028 12029//12029 12030//12030 -f 12031//12031 850//850 12032//12032 -f 12032//12032 850//850 12033//12033 -f 12034//12034 12035//12035 12036//12036 -f 12030//12030 12029//12029 12037//12037 -f 12029//12029 12038//12038 12037//12037 -f 12037//12037 12038//12038 12039//12039 -f 12037//12037 12039//12039 12040//12040 -f 12040//12040 12039//12039 12041//12041 -f 12040//12040 12041//12041 12035//12035 -f 12035//12035 12041//12041 12042//12042 -f 12035//12035 12042//12042 12036//12036 -f 12036//12036 12042//12042 12043//12043 -f 12036//12036 12043//12043 12033//12033 -f 12033//12033 12043//12043 12044//12044 -f 12033//12033 12044//12044 12032//12032 -f 12030//12030 12045//12045 12028//12028 -f 12028//12028 12045//12045 12046//12046 -f 12028//12028 12046//12046 12047//12047 -f 12047//12047 12046//12046 12048//12048 -f 12047//12047 12048//12048 12049//12049 -f 12049//12049 12048//12048 12050//12050 -f 12051//12051 12052//12052 12053//12053 -f 12053//12053 12054//12054 12051//12051 -f 12051//12051 12054//12054 12055//12055 -f 12051//12051 12055//12055 12056//12056 -f 12056//12056 12055//12055 12057//12057 -f 12056//12056 12057//12057 12058//12058 -f 12058//12058 12057//12057 12059//12059 -f 12058//12058 12059//12059 12060//12060 -f 12060//12060 12059//12059 12061//12061 -f 12060//12060 12061//12061 12050//12050 -f 12050//12050 12061//12061 12062//12062 -f 12050//12050 12062//12062 12049//12049 -f 12063//12063 12064//12064 12065//12065 -f 12065//12065 12064//12064 12066//12066 -f 12065//12065 12066//12066 12067//12067 -f 12067//12067 12066//12066 12068//12068 -f 12067//12067 12068//12068 12036//12036 -f 12036//12036 12068//12068 12069//12069 -f 12036//12036 12069//12069 12034//12034 -f 12063//12063 12065//12065 12070//12070 -f 12070//12070 12065//12065 12071//12071 -f 12070//12070 12071//12071 12072//12072 -f 12072//12072 12071//12071 12073//12073 -f 12073//12073 12071//12071 12074//12074 -f 12073//12073 12074//12074 12075//12075 -f 12075//12075 12074//12074 12076//12076 -f 12076//12076 12074//12074 862//862 -f 12076//12076 862//862 12077//12077 -f 12077//12077 862//862 12078//12078 -f 12078//12078 862//862 12079//12079 -f 12078//12078 12079//12079 12080//12080 -f 12081//12081 12082//12082 12083//12083 -f 12083//12083 12082//12082 12084//12084 -f 12083//12083 12084//12084 12079//12079 -f 12079//12079 12084//12084 12085//12085 -f 12079//12079 12085//12085 12080//12080 -f 12086//12086 12087//12087 12081//12081 -f 12081//12081 12087//12087 12088//12088 -f 12081//12081 12088//12088 12082//12082 -f 12089//12089 12090//12090 12091//12091 -f 12091//12091 12090//12090 12092//12092 -f 12091//12091 12092//12092 12086//12086 -f 12086//12086 12092//12092 12093//12093 -f 12086//12086 12093//12093 12087//12087 -f 12031//12031 12094//12094 850//850 -f 850//850 12094//12094 12095//12095 -f 850//850 12095//12095 12089//12089 -f 12089//12089 12095//12095 12096//12096 -f 12089//12089 12096//12096 12090//12090 -f 12097//12097 12098//12098 12099//12099 -f 12099//12099 12098//12098 12100//12100 -f 12099//12099 12100//12100 12101//12101 -f 12101//12101 12100//12100 12102//12102 -f 12102//12102 12100//12100 12103//12103 -f 12102//12102 12103//12103 12104//12104 -f 12104//12104 12103//12103 12105//12105 -f 12104//12104 12105//12105 12106//12106 -f 12106//12106 12105//12105 12107//12107 -f 12106//12106 12107//12107 12108//12108 -f 12109//12109 12110//12110 12111//12111 -f 12111//12111 12110//12110 12112//12112 -f 12111//12111 12112//12112 12113//12113 -f 12107//12107 12114//12114 12108//12108 -f 12108//12108 12114//12114 12115//12115 -f 12108//12108 12115//12115 12113//12113 -f 12113//12113 12115//12115 12116//12116 -f 12113//12113 12116//12116 12111//12111 -f 12117//12117 12118//12118 12119//12119 -f 12119//12119 12118//12118 12120//12120 -f 12119//12119 12120//12120 12097//12097 -f 12097//12097 12120//12120 12121//12121 -f 12097//12097 12121//12121 12098//12098 -f 12119//12119 12122//12122 12117//12117 -f 12117//12117 12122//12122 12123//12123 -f 12117//12117 12123//12123 12124//12124 -f 12125//12125 12126//12126 12127//12127 -f 12127//12127 12126//12126 12124//12124 -f 12127//12127 12124//12124 12128//12128 -f 12128//12128 12124//12124 12123//12123 -f 12129//12129 12130//12130 12131//12131 -f 12131//12131 12130//12130 12132//12132 -f 12131//12131 12132//12132 12133//12133 -f 12133//12133 12132//12132 12134//12134 -f 12133//12133 12134//12134 12125//12125 -f 12125//12125 12134//12134 12135//12135 -f 12125//12125 12135//12135 12126//12126 -f 12136//12136 12137//12137 12138//12138 -f 12139//12139 12140//12140 12141//12141 -f 12141//12141 12140//12140 12142//12142 -f 12141//12141 12142//12142 12143//12143 -f 12143//12143 12142//12142 12144//12144 -f 12143//12143 12144//12144 12145//12145 -f 12145//12145 12144//12144 12146//12146 -f 12145//12145 12146//12146 12147//12147 -f 12147//12147 12146//12146 12148//12148 -f 12147//12147 12148//12148 12149//12149 -f 12149//12149 12148//12148 12150//12150 -f 12149//12149 12150//12150 12151//12151 -f 12150//12150 12152//12152 12151//12151 -f 12151//12151 12152//12152 12153//12153 -f 12151//12151 12153//12153 12154//12154 -f 12154//12154 12153//12153 12155//12155 -f 12154//12154 12155//12155 12156//12156 -f 12156//12156 12155//12155 12157//12157 -f 12157//12157 12155//12155 12158//12158 -f 12157//12157 12158//12158 12137//12137 -f 12137//12137 12158//12158 12159//12159 -f 12137//12137 12159//12159 12138//12138 -f 12136//12136 12138//12138 12160//12160 -f 12160//12160 12138//12138 12161//12161 -f 12160//12160 12161//12161 12162//12162 -f 12162//12162 12161//12161 12163//12163 -f 12162//12162 12163//12163 12164//12164 -f 12164//12164 12163//12163 12165//12165 -f 12164//12164 12165//12165 12166//12166 -f 12166//12166 12165//12165 12167//12167 -f 12166//12166 12167//12167 12168//12168 -f 12168//12168 12167//12167 12169//12169 -f 12168//12168 12169//12169 12170//12170 -f 12170//12170 12169//12169 12171//12171 -f 12170//12170 12171//12171 12172//12172 -f 12173//12173 12174//12174 12175//12175 -f 12173//12173 12175//12175 12176//12176 -f 12176//12176 12175//12175 12177//12177 -f 12176//12176 12177//12177 12178//12178 -f 12179//12179 12180//12180 12181//12181 -f 12181//12181 12180//12180 12182//12182 -f 12181//12181 12182//12182 12183//12183 -f 12183//12183 12182//12182 12184//12184 -f 12183//12183 12184//12184 12174//12174 -f 12174//12174 12184//12184 12185//12185 -f 12174//12174 12185//12185 12175//12175 -f 12186//12186 12187//12187 12188//12188 -f 12188//12188 12189//12189 12186//12186 -f 12186//12186 12189//12189 12190//12190 -f 12186//12186 12190//12190 12179//12179 -f 12179//12179 12190//12190 12191//12191 -f 12179//12179 12191//12191 12180//12180 -f 12192//12192 12193//12193 12194//12194 -f 12194//12194 12193//12193 12195//12195 -f 12194//12194 12195//12195 12196//12196 -f 12196//12196 12195//12195 12197//12197 -f 12196//12196 12197//12197 12198//12198 -f 12198//12198 12197//12197 12199//12199 -f 12198//12198 12199//12199 12187//12187 -f 12187//12187 12199//12199 12200//12200 -f 12187//12187 12200//12200 12188//12188 -f 12201//12201 12202//12202 12203//12203 -f 12203//12203 12202//12202 12204//12204 -f 12203//12203 12204//12204 12205//12205 -f 12204//12204 12206//12206 12205//12205 -f 12205//12205 12206//12206 12207//12207 -f 12205//12205 12207//12207 12208//12208 -f 12208//12208 12207//12207 12209//12209 -f 12208//12208 12209//12209 12194//12194 -f 12194//12194 12209//12209 12210//12210 -f 12194//12194 12210//12210 12192//12192 -f 12211//12211 12212//12212 12213//12213 -f 12213//12213 12212//12212 12214//12214 -f 12213//12213 12214//12214 12215//12215 -f 12215//12215 12214//12214 12216//12216 -f 12215//12215 12216//12216 12217//12217 -f 12213//12213 12218//12218 12211//12211 -f 12211//12211 12218//12218 12219//12219 -f 12211//12211 12219//12219 12220//12220 -f 12220//12220 12219//12219 12221//12221 -f 12220//12220 12221//12221 12222//12222 -f 12222//12222 12221//12221 12223//12223 -f 12222//12222 12223//12223 12224//12224 -f 12223//12223 12225//12225 12224//12224 -f 12224//12224 12225//12225 12226//12226 -f 12224//12224 12226//12226 12227//12227 -f 12227//12227 12226//12226 12228//12228 -f 12227//12227 12228//12228 12229//12229 -f 12229//12229 12228//12228 12230//12230 -f 12229//12229 12230//12230 12231//12231 -f 12231//12231 12230//12230 12232//12232 -f 12231//12231 12232//12232 12233//12233 -f 12233//12233 12232//12232 12234//12234 -f 12233//12233 12234//12234 12235//12235 -f 12235//12235 12234//12234 12236//12236 -f 12236//12236 12234//12234 12237//12237 -f 12236//12236 12237//12237 12238//12238 -f 12238//12238 12237//12237 12239//12239 -f 12238//12238 12239//12239 12240//12240 -f 12240//12240 12239//12239 12241//12241 -f 12240//12240 12241//12241 12242//12242 -f 12243//12243 12244//12244 12245//12245 -f 12245//12245 12244//12244 12246//12246 -f 12245//12245 12246//12246 12242//12242 -f 12242//12242 12246//12246 12247//12247 -f 12242//12242 12247//12247 12240//12240 -f 12248//12248 12249//12249 12250//12250 -f 12250//12250 12249//12249 12251//12251 -f 12250//12250 12251//12251 12252//12252 -f 12252//12252 12251//12251 12253//12253 -f 12252//12252 12253//12253 12254//12254 -f 12254//12254 12253//12253 12255//12255 -f 12254//12254 12255//12255 12256//12256 -f 12256//12256 12255//12255 12257//12257 -f 12256//12256 12257//12257 12258//12258 -f 12258//12258 12257//12257 12259//12259 -f 12258//12258 12259//12259 12260//12260 -f 12261//12261 12262//12262 12263//12263 -f 12263//12263 12262//12262 12260//12260 -f 12263//12263 12260//12260 12264//12264 -f 12264//12264 12260//12260 12259//12259 -f 12265//12265 12266//12266 12267//12267 -f 12267//12267 12266//12266 12268//12268 -f 12267//12267 12268//12268 12248//12248 -f 12248//12248 12268//12268 12269//12269 -f 12248//12248 12269//12269 12249//12249 -f 12267//12267 12270//12270 12265//12265 -f 12265//12265 12270//12270 12271//12271 -f 12265//12265 12271//12271 12272//12272 -f 12273//12273 12274//12274 12275//12275 -f 12275//12275 12274//12274 12272//12272 -f 12275//12275 12272//12272 12276//12276 -f 12276//12276 12272//12272 12271//12271 -f 12277//12277 12278//12278 12279//12279 -f 12279//12279 12278//12278 12280//12280 -f 12279//12279 12280//12280 12281//12281 -f 12281//12281 12280//12280 12282//12282 -f 12281//12281 12282//12282 12273//12273 -f 12273//12273 12282//12282 12283//12283 -f 12273//12273 12283//12283 12274//12274 -f 12284//12284 12285//12285 12286//12286 -f 12287//12287 12288//12288 12289//12289 -f 12289//12289 12288//12288 12290//12290 -f 12289//12289 12290//12290 12291//12291 -f 12291//12291 12290//12290 12292//12292 -f 12291//12291 12292//12292 12293//12293 -f 12293//12293 12292//12292 12294//12294 -f 12293//12293 12294//12294 12295//12295 -f 12295//12295 12294//12294 12296//12296 -f 12295//12295 12296//12296 12297//12297 -f 12297//12297 12296//12296 12298//12298 -f 12297//12297 12298//12298 12299//12299 -f 12298//12298 12300//12300 12299//12299 -f 12299//12299 12300//12300 12301//12301 -f 12299//12299 12301//12301 12302//12302 -f 12302//12302 12301//12301 12303//12303 -f 12302//12302 12303//12303 12304//12304 -f 12304//12304 12303//12303 12305//12305 -f 12305//12305 12303//12303 12306//12306 -f 12305//12305 12306//12306 12285//12285 -f 12285//12285 12306//12306 12307//12307 -f 12285//12285 12307//12307 12286//12286 -f 12284//12284 12286//12286 12308//12308 -f 12308//12308 12286//12286 12309//12309 -f 12308//12308 12309//12309 12310//12310 -f 12310//12310 12309//12309 12311//12311 -f 12310//12310 12311//12311 12312//12312 -f 12312//12312 12311//12311 12313//12313 -f 12312//12312 12313//12313 12314//12314 -f 12314//12314 12313//12313 12315//12315 -f 12314//12314 12315//12315 12316//12316 -f 12316//12316 12315//12315 12317//12317 -f 12316//12316 12317//12317 12318//12318 -f 12318//12318 12317//12317 12319//12319 -f 12318//12318 12319//12319 12320//12320 -f 12321//12321 12322//12322 12323//12323 -f 12321//12321 12323//12323 12324//12324 -f 12324//12324 12323//12323 12325//12325 -f 12324//12324 12325//12325 12326//12326 -f 12327//12327 12328//12328 12329//12329 -f 12329//12329 12328//12328 12330//12330 -f 12329//12329 12330//12330 12331//12331 -f 12331//12331 12330//12330 12332//12332 -f 12331//12331 12332//12332 12322//12322 -f 12322//12322 12332//12332 12333//12333 -f 12322//12322 12333//12333 12323//12323 -f 12334//12334 12335//12335 12336//12336 -f 12336//12336 12337//12337 12334//12334 -f 12334//12334 12337//12337 12338//12338 -f 12334//12334 12338//12338 12327//12327 -f 12327//12327 12338//12338 12339//12339 -f 12327//12327 12339//12339 12328//12328 -f 12340//12340 12341//12341 12342//12342 -f 12342//12342 12341//12341 12343//12343 -f 12342//12342 12343//12343 12344//12344 -f 12344//12344 12343//12343 12345//12345 -f 12344//12344 12345//12345 12346//12346 -f 12346//12346 12345//12345 12347//12347 -f 12346//12346 12347//12347 12335//12335 -f 12335//12335 12347//12347 12348//12348 -f 12335//12335 12348//12348 12336//12336 -f 12349//12349 12350//12350 12351//12351 -f 12351//12351 12350//12350 12352//12352 -f 12351//12351 12352//12352 12353//12353 -f 12352//12352 12354//12354 12353//12353 -f 12353//12353 12354//12354 12355//12355 -f 12353//12353 12355//12355 12356//12356 -f 12356//12356 12355//12355 12357//12357 -f 12356//12356 12357//12357 12342//12342 -f 12342//12342 12357//12357 12358//12358 -f 12342//12342 12358//12358 12340//12340 -f 12359//12359 12360//12360 12361//12361 -f 12361//12361 12360//12360 12362//12362 -f 12361//12361 12362//12362 12363//12363 -f 12363//12363 12362//12362 12364//12364 -f 12363//12363 12364//12364 12365//12365 -f 12361//12361 12366//12366 12359//12359 -f 12359//12359 12366//12366 12367//12367 -f 12359//12359 12367//12367 12368//12368 -f 12368//12368 12367//12367 12369//12369 -f 12368//12368 12369//12369 12370//12370 -f 12370//12370 12369//12369 12371//12371 -f 12370//12370 12371//12371 12372//12372 -f 12371//12371 12373//12373 12372//12372 -f 12372//12372 12373//12373 12374//12374 -f 12372//12372 12374//12374 12375//12375 -f 12375//12375 12374//12374 12376//12376 -f 12375//12375 12376//12376 12377//12377 -f 12377//12377 12376//12376 12378//12378 -f 12377//12377 12378//12378 12379//12379 -f 12379//12379 12378//12378 12380//12380 -f 12379//12379 12380//12380 12381//12381 -f 12381//12381 12380//12380 12382//12382 -f 12381//12381 12382//12382 12383//12383 -f 12383//12383 12382//12382 12384//12384 -f 12384//12384 12382//12382 12385//12385 -f 12384//12384 12385//12385 12386//12386 -f 12386//12386 12385//12385 12387//12387 -f 12386//12386 12387//12387 12388//12388 -f 12388//12388 12387//12387 12389//12389 -f 12388//12388 12389//12389 12390//12390 -f 12391//12391 12392//12392 12393//12393 -f 12393//12393 12392//12392 12394//12394 -f 12393//12393 12394//12394 12390//12390 -f 12390//12390 12394//12394 12395//12395 -f 12390//12390 12395//12395 12388//12388 -f 12396//12396 12397//12397 12398//12398 -f 12398//12398 12397//12397 12399//12399 -f 12398//12398 12399//12399 12400//12400 -f 12400//12400 12399//12399 12401//12401 -f 12400//12400 12401//12401 12402//12402 -f 12402//12402 12401//12401 12403//12403 -f 12402//12402 12403//12403 12404//12404 -f 12404//12404 12403//12403 12405//12405 -f 12404//12404 12405//12405 12406//12406 -f 12406//12406 12405//12405 12407//12407 -f 12406//12406 12407//12407 12408//12408 -f 12409//12409 12410//12410 12411//12411 -f 12411//12411 12410//12410 12408//12408 -f 12411//12411 12408//12408 12412//12412 -f 12412//12412 12408//12408 12407//12407 -f 12413//12413 12414//12414 12415//12415 -f 12415//12415 12414//12414 12416//12416 -f 12415//12415 12416//12416 12396//12396 -f 12396//12396 12416//12416 12417//12417 -f 12396//12396 12417//12417 12397//12397 -f 12415//12415 12418//12418 12413//12413 -f 12413//12413 12418//12418 12419//12419 -f 12413//12413 12419//12419 12420//12420 -f 12421//12421 12422//12422 12423//12423 -f 12423//12423 12422//12422 12420//12420 -f 12423//12423 12420//12420 12424//12424 -f 12424//12424 12420//12420 12419//12419 -f 12425//12425 12426//12426 12427//12427 -f 12427//12427 12426//12426 12428//12428 -f 12427//12427 12428//12428 12429//12429 -f 12429//12429 12428//12428 12430//12430 -f 12429//12429 12430//12430 12421//12421 -f 12421//12421 12430//12430 12431//12431 -f 12421//12421 12431//12431 12422//12422 -f 12432//12432 12433//12433 12434//12434 -f 12435//12435 12436//12436 12437//12437 -f 12437//12437 12436//12436 12438//12438 -f 12437//12437 12438//12438 12439//12439 -f 12439//12439 12438//12438 12440//12440 -f 12439//12439 12440//12440 12441//12441 -f 12441//12441 12440//12440 12442//12442 -f 12441//12441 12442//12442 12443//12443 -f 12443//12443 12442//12442 12444//12444 -f 12443//12443 12444//12444 12445//12445 -f 12445//12445 12444//12444 12446//12446 -f 12445//12445 12446//12446 12447//12447 -f 12446//12446 12448//12448 12447//12447 -f 12447//12447 12448//12448 12449//12449 -f 12447//12447 12449//12449 12450//12450 -f 12450//12450 12449//12449 12451//12451 -f 12450//12450 12451//12451 12452//12452 -f 12452//12452 12451//12451 12453//12453 -f 12453//12453 12451//12451 12454//12454 -f 12453//12453 12454//12454 12433//12433 -f 12433//12433 12454//12454 12455//12455 -f 12433//12433 12455//12455 12434//12434 -f 12432//12432 12434//12434 12456//12456 -f 12456//12456 12434//12434 12457//12457 -f 12456//12456 12457//12457 12458//12458 -f 12458//12458 12457//12457 12459//12459 -f 12458//12458 12459//12459 12460//12460 -f 12460//12460 12459//12459 12461//12461 -f 12460//12460 12461//12461 12462//12462 -f 12462//12462 12461//12461 12463//12463 -f 12462//12462 12463//12463 12464//12464 -f 12464//12464 12463//12463 12465//12465 -f 12464//12464 12465//12465 12466//12466 -f 12466//12466 12465//12465 12467//12467 -f 12466//12466 12467//12467 12468//12468 -f 12469//12469 12470//12470 12471//12471 -f 12469//12469 12471//12471 12472//12472 -f 12472//12472 12471//12471 12473//12473 -f 12472//12472 12473//12473 12474//12474 -f 12475//12475 12476//12476 12477//12477 -f 12477//12477 12476//12476 12478//12478 -f 12477//12477 12478//12478 12479//12479 -f 12479//12479 12478//12478 12480//12480 -f 12479//12479 12480//12480 12470//12470 -f 12470//12470 12480//12480 12481//12481 -f 12470//12470 12481//12481 12471//12471 -f 12482//12482 12483//12483 12484//12484 -f 12484//12484 12485//12485 12482//12482 -f 12482//12482 12485//12485 12486//12486 -f 12482//12482 12486//12486 12475//12475 -f 12475//12475 12486//12486 12487//12487 -f 12475//12475 12487//12487 12476//12476 -f 12488//12488 12489//12489 12490//12490 -f 12490//12490 12489//12489 12491//12491 -f 12490//12490 12491//12491 12492//12492 -f 12492//12492 12491//12491 12493//12493 -f 12492//12492 12493//12493 12494//12494 -f 12494//12494 12493//12493 12495//12495 -f 12494//12494 12495//12495 12483//12483 -f 12483//12483 12495//12495 12496//12496 -f 12483//12483 12496//12496 12484//12484 -f 12497//12497 12498//12498 12499//12499 -f 12499//12499 12498//12498 12500//12500 -f 12499//12499 12500//12500 12501//12501 -f 12500//12500 12502//12502 12501//12501 -f 12501//12501 12502//12502 12503//12503 -f 12501//12501 12503//12503 12504//12504 -f 12504//12504 12503//12503 12505//12505 -f 12504//12504 12505//12505 12490//12490 -f 12490//12490 12505//12505 12506//12506 -f 12490//12490 12506//12506 12488//12488 -f 12507//12507 12508//12508 12509//12509 -f 12510//12510 12511//12511 12512//12512 -f 12512//12512 12511//12511 12513//12513 -f 12512//12512 12513//12513 12514//12514 -f 12514//12514 12513//12513 12515//12515 -f 12514//12514 12515//12515 12516//12516 -f 12512//12512 12517//12517 12510//12510 -f 12510//12510 12517//12517 12518//12518 -f 12510//12510 12518//12518 12519//12519 -f 12519//12519 12518//12518 12520//12520 -f 12519//12519 12520//12520 12521//12521 -f 12521//12521 12520//12520 12522//12522 -f 12521//12521 12522//12522 12523//12523 -f 12522//12522 12524//12524 12523//12523 -f 12523//12523 12524//12524 12525//12525 -f 12523//12523 12525//12525 12526//12526 -f 12526//12526 12525//12525 12527//12527 -f 12526//12526 12527//12527 12528//12528 -f 12528//12528 12527//12527 12529//12529 -f 12528//12528 12529//12529 12530//12530 -f 12530//12530 12529//12529 12531//12531 -f 12530//12530 12531//12531 12532//12532 -f 12532//12532 12531//12531 12533//12533 -f 12532//12532 12533//12533 12534//12534 -f 12534//12534 12533//12533 12535//12535 -f 12535//12535 12533//12533 12536//12536 -f 12536//12536 12533//12533 12537//12537 -f 12536//12536 12537//12537 12509//12509 -f 12509//12509 12537//12537 12538//12538 -f 12509//12509 12538//12538 12507//12507 -f 12539//12539 12540//12540 12541//12541 -f 12541//12541 12542//12542 12539//12539 -f 12539//12539 12542//12542 12543//12543 -f 12539//12539 12543//12543 12508//12508 -f 12508//12508 12543//12543 12544//12544 -f 12508//12508 12544//12544 12509//12509 -f 12545//12545 12546//12546 12547//12547 -f 12547//12547 12546//12546 12548//12548 -f 12547//12547 12548//12548 12549//12549 -f 12550//12550 12551//12551 12552//12552 -f 12552//12552 12551//12551 12553//12553 -f 12552//12552 12553//12553 12554//12554 -f 12554//12554 12553//12553 12555//12555 -f 12554//12554 12555//12555 12556//12556 -f 12556//12556 12555//12555 12549//12549 -f 12556//12556 12549//12549 12557//12557 -f 12557//12557 12549//12549 12548//12548 -f 12558//12558 12559//12559 12560//12560 -f 12560//12560 12559//12559 12561//12561 -f 12560//12560 12561//12561 12562//12562 -f 12562//12562 12561//12561 12563//12563 -f 12562//12562 12563//12563 12564//12564 -f 12564//12564 12563//12563 12565//12565 -f 12564//12564 12565//12565 12566//12566 -f 12566//12566 12565//12565 12567//12567 -f 12566//12566 12567//12567 12545//12545 -f 12545//12545 12567//12567 12568//12568 -f 12545//12545 12568//12568 12546//12546 -f 12560//12560 12569//12569 12558//12558 -f 12558//12558 12569//12569 12570//12570 -f 12558//12558 12570//12570 12571//12571 -f 12571//12571 12570//12570 12572//12572 -f 12571//12571 12572//12572 12573//12573 -f 12573//12573 12572//12572 12574//12574 -f 12573//12573 12574//12574 12575//12575 -f 12575//12575 12574//12574 12576//12576 -f 12575//12575 12576//12576 12577//12577 -f 12577//12577 12576//12576 12578//12578 -f 12576//12576 12579//12579 12578//12578 -f 12578//12578 12579//12579 12580//12580 -f 12578//12578 12580//12580 12581//12581 -f 12581//12581 12580//12580 12582//12582 -f 12581//12581 12582//12582 12583//12583 -f 12584//12584 12585//12585 12586//12586 -f 12587//12587 12588//12588 12589//12589 -f 12590//12590 12591//12591 12592//12592 -f 12592//12592 12591//12591 12593//12593 -f 12592//12592 12593//12593 12594//12594 -f 12594//12594 12593//12593 12595//12595 -f 12594//12594 12595//12595 12596//12596 -f 12596//12596 12595//12595 12597//12597 -f 12596//12596 12597//12597 12598//12598 -f 12598//12598 12597//12597 12599//12599 -f 12598//12598 12599//12599 12600//12600 -f 12600//12600 12599//12599 12601//12601 -f 12600//12600 12601//12601 12589//12589 -f 12589//12589 12601//12601 12602//12602 -f 12589//12589 12602//12602 12587//12587 -f 12588//12588 12587//12587 12603//12603 -f 12603//12603 12587//12587 12604//12604 -f 12603//12603 12604//12604 12605//12605 -f 12605//12605 12604//12604 12606//12606 -f 12605//12605 12606//12606 12585//12585 -f 12585//12585 12606//12606 12607//12607 -f 12585//12585 12607//12607 12586//12586 -f 12584//12584 12586//12586 12608//12608 -f 12608//12608 12586//12586 12609//12609 -f 12608//12608 12609//12609 12610//12610 -f 12610//12610 12609//12609 12611//12611 -f 12610//12610 12611//12611 12612//12612 -f 12612//12612 12611//12611 12613//12613 -f 12612//12612 12613//12613 12614//12614 -f 12614//12614 12613//12613 12615//12615 -f 12615//12615 12613//12613 12616//12616 -f 12615//12615 12616//12616 12617//12617 -f 12617//12617 12616//12616 12618//12618 -f 12617//12617 12618//12618 12619//12619 -f 12619//12619 12618//12618 12620//12620 -f 12619//12619 12620//12620 12621//12621 -f 12622//12622 12623//12623 12624//12624 -f 12622//12622 12624//12624 12625//12625 -f 12625//12625 12624//12624 12626//12626 -f 12625//12625 12626//12626 12627//12627 -f 12628//12628 12629//12629 12630//12630 -f 12630//12630 12631//12631 12628//12628 -f 12628//12628 12631//12631 12632//12632 -f 12628//12628 12632//12632 12633//12633 -f 12633//12633 12632//12632 12634//12634 -f 12633//12633 12634//12634 12623//12623 -f 12623//12623 12634//12634 12635//12635 -f 12623//12623 12635//12635 12624//12624 -f 12636//12636 12637//12637 12638//12638 -f 12638//12638 12639//12639 12636//12636 -f 12636//12636 12639//12639 12640//12640 -f 12636//12636 12640//12640 12629//12629 -f 12629//12629 12640//12640 12641//12641 -f 12629//12629 12641//12641 12630//12630 -f 12642//12642 12643//12643 12644//12644 -f 12644//12644 12643//12643 12645//12645 -f 12644//12644 12645//12645 12646//12646 -f 12645//12645 12647//12647 12646//12646 -f 12646//12646 12647//12647 12648//12648 -f 12646//12646 12648//12648 12649//12649 -f 12649//12649 12648//12648 12650//12650 -f 12649//12649 12650//12650 12637//12637 -f 12637//12637 12650//12650 12651//12651 -f 12637//12637 12651//12651 12638//12638 -f 12652//12652 12653//12653 12654//12654 -f 12652//12652 12654//12654 12644//12644 -f 12644//12644 12654//12654 12655//12655 -f 12644//12644 12655//12655 12642//12642 -f 12656//12656 12657//12657 12658//12658 -f 12658//12658 12657//12657 12659//12659 -f 12658//12658 12659//12659 12653//12653 -f 12653//12653 12659//12659 12660//12660 -f 12653//12653 12660//12660 12654//12654 -f 12661//12661 12662//12662 12663//12663 -f 12663//12663 12662//12662 12664//12664 -f 12663//12663 12664//12664 12665//12665 -f 12665//12665 12664//12664 12666//12666 -f 12665//12665 12666//12666 12667//12667 -f 12667//12667 12666//12666 12668//12668 -f 12667//12667 12668//12668 12669//12669 -f 12668//12668 12670//12670 12669//12669 -f 12669//12669 12670//12670 12671//12671 -f 12669//12669 12671//12671 12672//12672 -f 12672//12672 12671//12671 12673//12673 -f 12672//12672 12673//12673 12674//12674 -f 12674//12674 12673//12673 12675//12675 -f 12673//12673 12676//12676 12675//12675 -f 12675//12675 12676//12676 12677//12677 -f 12675//12675 12677//12677 12678//12678 -f 12678//12678 12677//12677 12679//12679 -f 12678//12678 12679//12679 12680//12680 -f 12680//12680 12679//12679 12681//12681 -f 12680//12680 12681//12681 12682//12682 -f 12682//12682 12681//12681 12683//12683 -f 12682//12682 12683//12683 12684//12684 -f 12684//12684 12683//12683 12685//12685 -f 12684//12684 12685//12685 12686//12686 -f 12686//12686 12685//12685 12687//12687 -f 12687//12687 12685//12685 12688//12688 -f 12687//12687 12688//12688 12689//12689 -f 12689//12689 12688//12688 12690//12690 -f 12689//12689 12690//12690 12691//12691 -f 12692//12692 12693//12693 12694//12694 -f 12690//12690 12695//12695 12691//12691 -f 12691//12691 12695//12695 12696//12696 -f 12691//12691 12696//12696 12697//12697 -f 12697//12697 12696//12696 12692//12692 -f 12697//12697 12692//12692 12698//12698 -f 12698//12698 12692//12692 12694//12694 -f 12699//12699 12700//12700 12701//12701 -f 12699//12699 12701//12701 12702//12702 -f 12701//12701 12703//12703 12702//12702 -f 12702//12702 12703//12703 12704//12704 -f 12702//12702 12704//12704 12705//12705 -f 12705//12705 12704//12704 12706//12706 -f 12705//12705 12706//12706 12707//12707 -f 12707//12707 12706//12706 12708//12708 -f 12707//12707 12708//12708 12709//12709 -f 12709//12709 12708//12708 12710//12710 -f 12709//12709 12710//12710 12711//12711 -f 12711//12711 12710//12710 12712//12712 -f 12711//12711 12712//12712 12713//12713 -f 12713//12713 12712//12712 12714//12714 -f 12713//12713 12714//12714 12715//12715 -f 12716//12716 12717//12717 12718//12718 -f 12718//12718 12717//12717 12715//12715 -f 12718//12718 12715//12715 12719//12719 -f 12719//12719 12715//12715 12714//12714 -f 12700//12700 12699//12699 12720//12720 -f 12720//12720 12699//12699 12721//12721 -f 12720//12720 12721//12721 12722//12722 -f 12722//12722 12721//12721 12723//12723 -f 12722//12722 12723//12723 12724//12724 -f 12724//12724 12723//12723 12725//12725 -f 12724//12724 12725//12725 12726//12726 -f 12726//12726 12725//12725 12727//12727 -f 12726//12726 12727//12727 12728//12728 -f 12729//12729 12730//12730 12731//12731 -f 12731//12731 12730//12730 12728//12728 -f 12731//12731 12728//12728 12732//12732 -f 12732//12732 12728//12728 12727//12727 -f 12053//12053 12052//12052 12733//12733 -f 12733//12733 12052//12052 12734//12734 -f 12735//12735 12736//12736 12737//12737 -f 12735//12735 12737//12737 12738//12738 -f 12738//12738 12737//12737 12739//12739 -f 12738//12738 12739//12739 12740//12740 -f 12740//12740 12739//12739 12741//12741 -f 12740//12740 12741//12741 12742//12742 -f 12742//12742 12741//12741 12743//12743 -f 12742//12742 12743//12743 12744//12744 -f 12744//12744 12743//12743 12745//12745 -f 12744//12744 12745//12745 12746//12746 -f 12746//12746 12745//12745 12747//12747 -f 12746//12746 12747//12747 12748//12748 -f 12748//12748 12747//12747 12749//12749 -f 12748//12748 12749//12749 12750//12750 -f 12750//12750 12749//12749 12751//12751 -f 12750//12750 12751//12751 12734//12734 -f 12734//12734 12751//12751 12752//12752 -f 12734//12734 12752//12752 12733//12733 -f 12736//12736 12735//12735 12753//12753 -f 12753//12753 12735//12735 12754//12754 -f 12753//12753 12754//12754 12755//12755 -f 12754//12754 12756//12756 12755//12755 -f 12755//12755 12756//12756 12757//12757 -f 12755//12755 12757//12757 12758//12758 -f 12758//12758 12757//12757 12759//12759 -f 12760//12760 12761//12761 12759//12759 -f 12759//12759 12761//12761 12762//12762 -f 12759//12759 12762//12762 12758//12758 -f 12759//12759 12763//12763 12760//12760 -f 12760//12760 12763//12763 12764//12764 -f 12760//12760 12764//12764 12765//12765 -f 12765//12765 12764//12764 12110//12110 -f 12765//12765 12110//12110 12109//12109 -f 12130//12130 12129//12129 12766//12766 -f 12766//12766 12129//12129 12767//12767 -f 12766//12766 12767//12767 12768//12768 -f 12768//12768 12767//12767 12769//12769 -f 12768//12768 12769//12769 12770//12770 -f 12770//12770 12769//12769 12771//12771 -f 12770//12770 12771//12771 12772//12772 -f 12772//12772 12771//12771 12773//12773 -f 12774//12774 12775//12775 12776//12776 -f 12776//12776 12775//12775 12777//12777 -f 12776//12776 12777//12777 12778//12778 -f 12773//12773 12771//12771 12779//12779 -f 12779//12779 12771//12771 12780//12780 -f 12779//12779 12780//12780 12774//12774 -f 12774//12774 12780//12780 12781//12781 -f 12774//12774 12781//12781 12775//12775 -f 12778//12778 12777//12777 12782//12782 -f 12782//12782 12777//12777 12783//12783 -f 12782//12782 12783//12783 12784//12784 -f 12784//12784 12783//12783 12785//12785 -f 12785//12785 12783//12783 12786//12786 -f 12785//12785 12786//12786 12787//12787 -f 12787//12787 12786//12786 12788//12788 -f 12787//12787 12788//12788 12789//12789 -f 12789//12789 12788//12788 12790//12790 -f 12789//12789 12790//12790 12791//12791 -f 12790//12790 12792//12792 12791//12791 -f 12791//12791 12792//12792 12793//12793 -f 12791//12791 12793//12793 12794//12794 -f 12794//12794 12793//12793 12795//12795 -f 12794//12794 12795//12795 12796//12796 -f 12795//12795 12797//12797 12796//12796 -f 12796//12796 12797//12797 12798//12798 -f 12796//12796 12798//12798 12799//12799 -f 12799//12799 12798//12798 12800//12800 -f 12799//12799 12800//12800 12801//12801 -f 12801//12801 12800//12800 12140//12140 -f 12801//12801 12140//12140 12139//12139 -f 12802//12802 12803//12803 12804//12804 -f 12804//12804 12803//12803 12805//12805 -f 12804//12804 12805//12805 12806//12806 -f 12806//12806 12805//12805 12807//12807 -f 12806//12806 12807//12807 12808//12808 -f 12808//12808 12807//12807 12809//12809 -f 12808//12808 12809//12809 12172//12172 -f 12172//12172 12809//12809 12810//12810 -f 12172//12172 12810//12810 12170//12170 -f 12802//12802 12811//12811 12803//12803 -f 12803//12803 12811//12811 12812//12812 -f 12803//12803 12812//12812 12813//12813 -f 12813//12813 12812//12812 12814//12814 -f 12813//12813 12814//12814 12815//12815 -f 12815//12815 12814//12814 12816//12816 -f 12816//12816 12814//12814 12817//12817 -f 12816//12816 12817//12817 12818//12818 -f 12818//12818 12817//12817 12819//12819 -f 12818//12818 12819//12819 12820//12820 -f 12820//12820 12819//12819 12821//12821 -f 12820//12820 12821//12821 12822//12822 -f 12822//12822 12821//12821 12823//12823 -f 12822//12822 12823//12823 12824//12824 -f 12824//12824 12823//12823 12825//12825 -f 12824//12824 12825//12825 12826//12826 -f 12826//12826 12825//12825 12827//12827 -f 12826//12826 12827//12827 12828//12828 -f 12827//12827 12829//12829 12828//12828 -f 12828//12828 12829//12829 12830//12830 -f 12828//12828 12830//12830 12831//12831 -f 12831//12831 12830//12830 12832//12832 -f 12831//12831 12832//12832 12833//12833 -f 12833//12833 12832//12832 12834//12834 -f 12833//12833 12834//12834 12178//12178 -f 12178//12178 12834//12834 12835//12835 -f 12178//12178 12835//12835 12176//12176 -f 12836//12836 12837//12837 12838//12838 -f 12202//12202 12201//12201 12839//12839 -f 12839//12839 12201//12201 12840//12840 -f 12839//12839 12840//12840 12841//12841 -f 12841//12841 12840//12840 12842//12842 -f 12841//12841 12842//12842 12843//12843 -f 12843//12843 12842//12842 12844//12844 -f 12843//12843 12844//12844 12845//12845 -f 12844//12844 12846//12846 12845//12845 -f 12845//12845 12846//12846 12847//12847 -f 12845//12845 12847//12847 12848//12848 -f 12848//12848 12847//12847 12849//12849 -f 12848//12848 12849//12849 12850//12850 -f 12850//12850 12849//12849 12851//12851 -f 12850//12850 12851//12851 12837//12837 -f 12837//12837 12851//12851 12852//12852 -f 12837//12837 12852//12852 12838//12838 -f 12836//12836 12838//12838 12853//12853 -f 12853//12853 12838//12838 12854//12854 -f 12853//12853 12854//12854 12855//12855 -f 12855//12855 12854//12854 12856//12856 -f 12855//12855 12856//12856 12857//12857 -f 12857//12857 12856//12856 12858//12858 -f 12857//12857 12858//12858 12859//12859 -f 12858//12858 12860//12860 12859//12859 -f 12859//12859 12860//12860 12861//12861 -f 12859//12859 12861//12861 12862//12862 -f 12862//12862 12861//12861 12863//12863 -f 12217//12217 12216//12216 12864//12864 -f 12864//12864 12216//12216 12865//12865 -f 12864//12864 12865//12865 12866//12866 -f 12866//12866 12865//12865 12867//12867 -f 12866//12866 12867//12867 12868//12868 -f 12868//12868 12867//12867 12869//12869 -f 12868//12868 12869//12869 12863//12863 -f 12863//12863 12869//12869 12870//12870 -f 12863//12863 12870//12870 12862//12862 -f 12871//12871 12872//12872 12873//12873 -f 12873//12873 12872//12872 12874//12874 -f 12873//12873 12874//12874 12875//12875 -f 12875//12875 12874//12874 12244//12244 -f 12875//12875 12244//12244 12243//12243 -f 12873//12873 12876//12876 12871//12871 -f 12871//12871 12876//12876 12877//12877 -f 12871//12871 12877//12877 12878//12878 -f 12878//12878 12877//12877 12879//12879 -f 12878//12878 12879//12879 12880//12880 -f 12880//12880 12879//12879 12881//12881 -f 12880//12880 12881//12881 12882//12882 -f 12882//12882 12881//12881 12883//12883 -f 12882//12882 12883//12883 12884//12884 -f 12884//12884 12883//12883 12885//12885 -f 12883//12883 12886//12886 12885//12885 -f 12885//12885 12886//12886 12887//12887 -f 12885//12885 12887//12887 12888//12888 -f 12888//12888 12887//12887 12889//12889 -f 12888//12888 12889//12889 12890//12890 -f 12890//12890 12889//12889 12891//12891 -f 12890//12890 12891//12891 12892//12892 -f 12892//12892 12891//12891 12893//12893 -f 12892//12892 12893//12893 12894//12894 -f 12894//12894 12893//12893 12895//12895 -f 12894//12894 12895//12895 12896//12896 -f 12896//12896 12895//12895 12897//12897 -f 12896//12896 12897//12897 12898//12898 -f 12898//12898 12897//12897 12899//12899 -f 12898//12898 12899//12899 12900//12900 -f 12900//12900 12899//12899 12901//12901 -f 12900//12900 12901//12901 12902//12902 -f 12902//12902 12901//12901 12903//12903 -f 12902//12902 12903//12903 12904//12904 -f 12904//12904 12903//12903 12905//12905 -f 12904//12904 12905//12905 12906//12906 -f 12906//12906 12905//12905 12262//12262 -f 12906//12906 12262//12262 12261//12261 -f 12278//12278 12277//12277 12907//12907 -f 12907//12907 12277//12277 12908//12908 -f 12907//12907 12908//12908 12909//12909 -f 12909//12909 12908//12908 12910//12910 -f 12909//12909 12910//12910 12911//12911 -f 12911//12911 12910//12910 12912//12912 -f 12911//12911 12912//12912 12913//12913 -f 12913//12913 12912//12912 12914//12914 -f 12915//12915 12916//12916 12917//12917 -f 12917//12917 12916//12916 12918//12918 -f 12917//12917 12918//12918 12919//12919 -f 12914//12914 12912//12912 12920//12920 -f 12920//12920 12912//12912 12921//12921 -f 12920//12920 12921//12921 12915//12915 -f 12915//12915 12921//12921 12922//12922 -f 12915//12915 12922//12922 12916//12916 -f 12919//12919 12918//12918 12923//12923 -f 12923//12923 12918//12918 12924//12924 -f 12923//12923 12924//12924 12925//12925 -f 12925//12925 12924//12924 12926//12926 -f 12926//12926 12924//12924 12927//12927 -f 12926//12926 12927//12927 12928//12928 -f 12928//12928 12927//12927 12929//12929 -f 12928//12928 12929//12929 12930//12930 -f 12930//12930 12929//12929 12931//12931 -f 12930//12930 12931//12931 12932//12932 -f 12931//12931 12933//12933 12932//12932 -f 12932//12932 12933//12933 12934//12934 -f 12932//12932 12934//12934 12935//12935 -f 12935//12935 12934//12934 12936//12936 -f 12935//12935 12936//12936 12937//12937 -f 12936//12936 12938//12938 12937//12937 -f 12937//12937 12938//12938 12939//12939 -f 12937//12937 12939//12939 12940//12940 -f 12940//12940 12939//12939 12941//12941 -f 12940//12940 12941//12941 12942//12942 -f 12942//12942 12941//12941 12288//12288 -f 12942//12942 12288//12288 12287//12287 -f 12943//12943 12944//12944 12945//12945 -f 12945//12945 12944//12944 12946//12946 -f 12945//12945 12946//12946 12947//12947 -f 12947//12947 12946//12946 12948//12948 -f 12947//12947 12948//12948 12949//12949 -f 12949//12949 12948//12948 12950//12950 -f 12949//12949 12950//12950 12320//12320 -f 12320//12320 12950//12950 12951//12951 -f 12320//12320 12951//12951 12318//12318 -f 12943//12943 12952//12952 12944//12944 -f 12944//12944 12952//12952 12953//12953 -f 12944//12944 12953//12953 12954//12954 -f 12954//12954 12953//12953 12955//12955 -f 12954//12954 12955//12955 12956//12956 -f 12956//12956 12955//12955 12957//12957 -f 12957//12957 12955//12955 12958//12958 -f 12957//12957 12958//12958 12959//12959 -f 12959//12959 12958//12958 12960//12960 -f 12959//12959 12960//12960 12961//12961 -f 12961//12961 12960//12960 12962//12962 -f 12961//12961 12962//12962 12963//12963 -f 12963//12963 12962//12962 12964//12964 -f 12963//12963 12964//12964 12965//12965 -f 12965//12965 12964//12964 12966//12966 -f 12965//12965 12966//12966 12967//12967 -f 12967//12967 12966//12966 12968//12968 -f 12967//12967 12968//12968 12969//12969 -f 12968//12968 12970//12970 12969//12969 -f 12969//12969 12970//12970 12971//12971 -f 12969//12969 12971//12971 12972//12972 -f 12972//12972 12971//12971 12973//12973 -f 12972//12972 12973//12973 12974//12974 -f 12974//12974 12973//12973 12975//12975 -f 12974//12974 12975//12975 12326//12326 -f 12326//12326 12975//12975 12976//12976 -f 12326//12326 12976//12976 12324//12324 -f 12977//12977 12978//12978 12979//12979 -f 12350//12350 12349//12349 12980//12980 -f 12980//12980 12349//12349 12981//12981 -f 12980//12980 12981//12981 12982//12982 -f 12982//12982 12981//12981 12983//12983 -f 12982//12982 12983//12983 12984//12984 -f 12984//12984 12983//12983 12985//12985 -f 12984//12984 12985//12985 12986//12986 -f 12985//12985 12987//12987 12986//12986 -f 12986//12986 12987//12987 12988//12988 -f 12986//12986 12988//12988 12989//12989 -f 12989//12989 12988//12988 12990//12990 -f 12989//12989 12990//12990 12991//12991 -f 12991//12991 12990//12990 12992//12992 -f 12991//12991 12992//12992 12978//12978 -f 12978//12978 12992//12992 12993//12993 -f 12978//12978 12993//12993 12979//12979 -f 12977//12977 12979//12979 12994//12994 -f 12994//12994 12979//12979 12995//12995 -f 12994//12994 12995//12995 12996//12996 -f 12996//12996 12995//12995 12997//12997 -f 12996//12996 12997//12997 12998//12998 -f 12998//12998 12997//12997 12999//12999 -f 12998//12998 12999//12999 13000//13000 -f 12999//12999 13001//13001 13000//13000 -f 13000//13000 13001//13001 13002//13002 -f 13000//13000 13002//13002 13003//13003 -f 13003//13003 13002//13002 13004//13004 -f 12365//12365 12364//12364 13005//13005 -f 13005//13005 12364//12364 13006//13006 -f 13005//13005 13006//13006 13007//13007 -f 13007//13007 13006//13006 13008//13008 -f 13007//13007 13008//13008 13009//13009 -f 13009//13009 13008//13008 13010//13010 -f 13009//13009 13010//13010 13004//13004 -f 13004//13004 13010//13010 13011//13011 -f 13004//13004 13011//13011 13003//13003 -f 13012//13012 13013//13013 13014//13014 -f 13014//13014 13013//13013 13015//13015 -f 13014//13014 13015//13015 13016//13016 -f 13016//13016 13015//13015 12392//12392 -f 13016//13016 12392//12392 12391//12391 -f 13014//13014 13017//13017 13012//13012 -f 13012//13012 13017//13017 13018//13018 -f 13012//13012 13018//13018 13019//13019 -f 13019//13019 13018//13018 13020//13020 -f 13019//13019 13020//13020 13021//13021 -f 13021//13021 13020//13020 13022//13022 -f 13021//13021 13022//13022 13023//13023 -f 13023//13023 13022//13022 13024//13024 -f 13023//13023 13024//13024 13025//13025 -f 13025//13025 13024//13024 13026//13026 -f 13024//13024 13027//13027 13026//13026 -f 13026//13026 13027//13027 13028//13028 -f 13026//13026 13028//13028 13029//13029 -f 13029//13029 13028//13028 13030//13030 -f 13029//13029 13030//13030 13031//13031 -f 13031//13031 13030//13030 13032//13032 -f 13031//13031 13032//13032 13033//13033 -f 13033//13033 13032//13032 13034//13034 -f 13033//13033 13034//13034 13035//13035 -f 13035//13035 13034//13034 13036//13036 -f 13035//13035 13036//13036 13037//13037 -f 13037//13037 13036//13036 13038//13038 -f 13037//13037 13038//13038 13039//13039 -f 13039//13039 13038//13038 13040//13040 -f 13039//13039 13040//13040 13041//13041 -f 13041//13041 13040//13040 13042//13042 -f 13041//13041 13042//13042 13043//13043 -f 13043//13043 13042//13042 13044//13044 -f 13043//13043 13044//13044 13045//13045 -f 13045//13045 13044//13044 13046//13046 -f 13045//13045 13046//13046 13047//13047 -f 13047//13047 13046//13046 12410//12410 -f 13047//13047 12410//12410 12409//12409 -f 12426//12426 12425//12425 13048//13048 -f 13048//13048 12425//12425 13049//13049 -f 13048//13048 13049//13049 13050//13050 -f 13050//13050 13049//13049 13051//13051 -f 13050//13050 13051//13051 13052//13052 -f 13052//13052 13051//13051 13053//13053 -f 13052//13052 13053//13053 13054//13054 -f 13054//13054 13053//13053 13055//13055 -f 13056//13056 13057//13057 13058//13058 -f 13058//13058 13057//13057 13059//13059 -f 13058//13058 13059//13059 13060//13060 -f 13055//13055 13053//13053 13061//13061 -f 13061//13061 13053//13053 13062//13062 -f 13061//13061 13062//13062 13056//13056 -f 13056//13056 13062//13062 13063//13063 -f 13056//13056 13063//13063 13057//13057 -f 13060//13060 13059//13059 13064//13064 -f 13064//13064 13059//13059 13065//13065 -f 13064//13064 13065//13065 13066//13066 -f 13066//13066 13065//13065 13067//13067 -f 13067//13067 13065//13065 13068//13068 -f 13067//13067 13068//13068 13069//13069 -f 13069//13069 13068//13068 13070//13070 -f 13069//13069 13070//13070 13071//13071 -f 13071//13071 13070//13070 13072//13072 -f 13071//13071 13072//13072 13073//13073 -f 13072//13072 13074//13074 13073//13073 -f 13073//13073 13074//13074 13075//13075 -f 13073//13073 13075//13075 13076//13076 -f 13076//13076 13075//13075 13077//13077 -f 13076//13076 13077//13077 13078//13078 -f 13077//13077 13079//13079 13078//13078 -f 13078//13078 13079//13079 13080//13080 -f 13078//13078 13080//13080 13081//13081 -f 13081//13081 13080//13080 13082//13082 -f 13081//13081 13082//13082 13083//13083 -f 13083//13083 13082//13082 12436//12436 -f 13083//13083 12436//12436 12435//12435 -f 13084//13084 13085//13085 13086//13086 -f 13086//13086 13085//13085 13087//13087 -f 13086//13086 13087//13087 13088//13088 -f 13088//13088 13087//13087 13089//13089 -f 13088//13088 13089//13089 13090//13090 -f 13090//13090 13089//13089 13091//13091 -f 13090//13090 13091//13091 12468//12468 -f 12468//12468 13091//13091 13092//13092 -f 12468//12468 13092//13092 12466//12466 -f 13084//13084 13093//13093 13085//13085 -f 13085//13085 13093//13093 13094//13094 -f 13085//13085 13094//13094 13095//13095 -f 13095//13095 13094//13094 13096//13096 -f 13095//13095 13096//13096 13097//13097 -f 13097//13097 13096//13096 13098//13098 -f 13098//13098 13096//13096 13099//13099 -f 13098//13098 13099//13099 13100//13100 -f 13100//13100 13099//13099 13101//13101 -f 13100//13100 13101//13101 13102//13102 -f 13102//13102 13101//13101 13103//13103 -f 13102//13102 13103//13103 13104//13104 -f 13104//13104 13103//13103 13105//13105 -f 13104//13104 13105//13105 13106//13106 -f 13106//13106 13105//13105 13107//13107 -f 13106//13106 13107//13107 13108//13108 -f 13108//13108 13107//13107 13109//13109 -f 13108//13108 13109//13109 13110//13110 -f 13109//13109 13111//13111 13110//13110 -f 13110//13110 13111//13111 13112//13112 -f 13110//13110 13112//13112 13113//13113 -f 13113//13113 13112//13112 13114//13114 -f 13113//13113 13114//13114 13115//13115 -f 13115//13115 13114//13114 13116//13116 -f 13115//13115 13116//13116 12474//12474 -f 12474//12474 13116//13116 13117//13117 -f 12474//12474 13117//13117 12472//12472 -f 13118//13118 13119//13119 13120//13120 -f 12498//12498 12497//12497 13121//13121 -f 13121//13121 12497//12497 13122//13122 -f 13121//13121 13122//13122 13123//13123 -f 13123//13123 13122//13122 13124//13124 -f 13123//13123 13124//13124 13125//13125 -f 13125//13125 13124//13124 13126//13126 -f 13125//13125 13126//13126 13127//13127 -f 13126//13126 13128//13128 13127//13127 -f 13127//13127 13128//13128 13129//13129 -f 13127//13127 13129//13129 13130//13130 -f 13130//13130 13129//13129 13131//13131 -f 13130//13130 13131//13131 13132//13132 -f 13132//13132 13131//13131 13133//13133 -f 13132//13132 13133//13133 13119//13119 -f 13119//13119 13133//13133 13134//13134 -f 13119//13119 13134//13134 13120//13120 -f 13118//13118 13120//13120 13135//13135 -f 13135//13135 13120//13120 13136//13136 -f 13135//13135 13136//13136 13137//13137 -f 13137//13137 13136//13136 13138//13138 -f 13137//13137 13138//13138 13139//13139 -f 13139//13139 13138//13138 13140//13140 -f 13139//13139 13140//13140 13141//13141 -f 13140//13140 13142//13142 13141//13141 -f 13141//13141 13142//13142 13143//13143 -f 13141//13141 13143//13143 13144//13144 -f 13144//13144 13143//13143 13145//13145 -f 12516//12516 12515//12515 13146//13146 -f 13146//13146 12515//12515 13147//13147 -f 13146//13146 13147//13147 13148//13148 -f 13148//13148 13147//13147 13149//13149 -f 13148//13148 13149//13149 13150//13150 -f 13150//13150 13149//13149 13151//13151 -f 13150//13150 13151//13151 13145//13145 -f 13145//13145 13151//13151 13152//13152 -f 13145//13145 13152//13152 13144//13144 -f 13153//13153 13154//13154 13155//13155 -f 13155//13155 13154//13154 13156//13156 -f 13155//13155 13156//13156 13157//13157 -f 13157//13157 13156//13156 12541//12541 -f 13157//13157 12541//12541 12540//12540 -f 13155//13155 13158//13158 13153//13153 -f 13153//13153 13158//13158 13159//13159 -f 13153//13153 13159//13159 13160//13160 -f 13160//13160 13159//13159 13161//13161 -f 13160//13160 13161//13161 13162//13162 -f 13162//13162 13161//13161 13163//13163 -f 13162//13162 13163//13163 13164//13164 -f 13164//13164 13163//13163 13165//13165 -f 13164//13164 13165//13165 13166//13166 -f 13166//13166 13165//13165 13167//13167 -f 13167//13167 13165//13165 13168//13168 -f 13167//13167 13168//13168 13169//13169 -f 13169//13169 13168//13168 13170//13170 -f 13169//13169 13170//13170 13171//13171 -f 13171//13171 13170//13170 13172//13172 -f 13171//13171 13172//13172 13173//13173 -f 13172//13172 13174//13174 13173//13173 -f 13173//13173 13174//13174 13175//13175 -f 13173//13173 13175//13175 13176//13176 -f 13176//13176 13175//13175 13177//13177 -f 12551//12551 12550//12550 13178//13178 -f 12551//12551 13178//13178 13179//13179 -f 13179//13179 13178//13178 13180//13180 -f 13179//13179 13180//13180 13181//13181 -f 13181//13181 13180//13180 13182//13182 -f 13181//13181 13182//13182 13183//13183 -f 13183//13183 13182//13182 13184//13184 -f 13183//13183 13184//13184 13185//13185 -f 13185//13185 13184//13184 13186//13186 -f 13185//13185 13186//13186 13187//13187 -f 13187//13187 13186//13186 13188//13188 -f 13187//13187 13188//13188 13177//13177 -f 13177//13177 13188//13188 13189//13189 -f 13177//13177 13189//13189 13176//13176 -f 12583//12583 12582//12582 13190//13190 -f 13190//13190 12582//12582 13191//13191 -f 13190//13190 13191//13191 13192//13192 -f 13193//13193 13194//13194 13195//13195 -f 13195//13195 13194//13194 13196//13196 -f 13191//13191 13197//13197 13192//13192 -f 13192//13192 13197//13197 13195//13195 -f 13192//13192 13195//13195 13198//13198 -f 13198//13198 13195//13195 13196//13196 -f 13199//13199 13200//13200 13201//13201 -f 13201//13201 13200//13200 13202//13202 -f 13201//13201 13202//13202 13203//13203 -f 13203//13203 13202//13202 13204//13204 -f 13203//13203 13204//13204 13193//13193 -f 13193//13193 13204//13204 13205//13205 -f 13193//13193 13205//13205 13194//13194 -f 13206//13206 13207//13207 13199//13199 -f 13199//13199 13207//13207 13208//13208 -f 13199//13199 13208//13208 13200//13200 -f 13209//13209 13210//13210 13211//13211 -f 13209//13209 13211//13211 13212//13212 -f 13212//13212 13211//13211 13213//13213 -f 13212//13212 13213//13213 13214//13214 -f 13213//13213 13215//13215 13214//13214 -f 13214//13214 13215//13215 13216//13216 -f 13214//13214 13216//13216 13217//13217 -f 13217//13217 13216//13216 13218//13218 -f 13217//13217 13218//13218 13206//13206 -f 13206//13206 13218//13218 13219//13219 -f 13206//13206 13219//13219 13207//13207 -f 12591//12591 12590//12590 13220//13220 -f 13220//13220 12590//12590 13221//13221 -f 13220//13220 13221//13221 13222//13222 -f 13222//13222 13221//13221 13223//13223 -f 13222//13222 13223//13223 13224//13224 -f 13224//13224 13223//13223 13225//13225 -f 13224//13224 13225//13225 13226//13226 -f 13226//13226 13225//13225 13227//13227 -f 13226//13226 13227//13227 13228//13228 -f 13228//13228 13227//13227 13229//13229 -f 13228//13228 13229//13229 13210//13210 -f 13210//13210 13229//13229 13230//13230 -f 13210//13210 13230//13230 13211//13211 -f 12619//12619 12621//12621 13231//13231 -f 13231//13231 12621//12621 13232//13232 -f 13231//13231 13232//13232 13233//13233 -f 13233//13233 13232//13232 13234//13234 -f 13234//13234 13232//13232 13235//13235 -f 13234//13234 13235//13235 13236//13236 -f 13236//13236 13235//13235 13237//13237 -f 13236//13236 13237//13237 13238//13238 -f 13238//13238 13237//13237 13239//13239 -f 13238//13238 13239//13239 13240//13240 -f 13240//13240 13239//13239 13241//13241 -f 13240//13240 13241//13241 13242//13242 -f 13243//13243 13244//13244 13245//13245 -f 13245//13245 13244//13244 13242//13242 -f 13245//13245 13242//13242 13246//13246 -f 13246//13246 13242//13242 13241//13241 -f 13247//13247 13248//13248 13243//13243 -f 13243//13243 13248//13248 13249//13249 -f 13243//13243 13249//13249 13244//13244 -f 13250//13250 13251//13251 13252//13252 -f 13250//13250 13252//13252 13253//13253 -f 13252//13252 13254//13254 13253//13253 -f 13253//13253 13254//13254 13255//13255 -f 13253//13253 13255//13255 13256//13256 -f 13256//13256 13255//13255 13257//13257 -f 13256//13256 13257//13257 13258//13258 -f 13258//13258 13257//13257 13259//13259 -f 13258//13258 13259//13259 13260//13260 -f 13260//13260 13259//13259 13261//13261 -f 13260//13260 13261//13261 13262//13262 -f 13262//13262 13261//13261 13263//13263 -f 13262//13262 13263//13263 13247//13247 -f 13247//13247 13263//13263 13264//13264 -f 13247//13247 13264//13264 13248//13248 -f 13251//13251 13250//13250 13265//13265 -f 13265//13265 13250//13250 13266//13266 -f 13265//13265 13266//13266 12627//12627 -f 12627//12627 13266//13266 13267//13267 -f 12627//12627 13267//13267 12625//12625 -f 12657//12657 12656//12656 13268//13268 -f 13268//13268 12656//12656 13269//13269 -f 13268//13268 13269//13269 13270//13270 -f 13270//13270 13269//13269 13271//13271 -f 13270//13270 13271//13271 13272//13272 -f 13272//13272 13271//13271 13273//13273 -f 13272//13272 13273//13273 13274//13274 -f 13273//13273 13275//13275 13274//13274 -f 13274//13274 13275//13275 13276//13276 -f 13274//13274 13276//13276 13277//13277 -f 13277//13277 13276//13276 13278//13278 -f 13277//13277 13278//13278 13279//13279 -f 13279//13279 13278//13278 13280//13280 -f 13280//13280 13278//13278 13281//13281 -f 13280//13280 13281//13281 13282//13282 -f 13282//13282 13281//13281 13283//13283 -f 13282//13282 13283//13283 13284//13284 -f 13285//13285 13286//13286 13287//13287 -f 13287//13287 13286//13286 13288//13288 -f 13287//13287 13288//13288 13284//13284 -f 13284//13284 13288//13288 13289//13289 -f 13284//13284 13289//13289 13282//13282 -f 13287//13287 13290//13290 13285//13285 -f 13285//13285 13290//13290 13291//13291 -f 13285//13285 13291//13291 13292//13292 -f 13292//13292 13291//13291 13293//13293 -f 13292//13292 13293//13293 13294//13294 -f 13294//13294 13293//13293 13295//13295 -f 13294//13294 13295//13295 13296//13296 -f 13296//13296 13295//13295 13297//13297 -f 13296//13296 13297//13297 13298//13298 -f 13298//13298 13297//13297 13299//13299 -f 13298//13298 13299//13299 13300//13300 -f 12662//12662 12661//12661 13301//13301 -f 13301//13301 12661//12661 13300//13300 -f 13301//13301 13300//13300 13302//13302 -f 13302//13302 13300//13300 13299//13299 -f 12694//12694 12693//12693 13303//13303 -f 12694//12694 13303//13303 13304//13304 -f 13304//13304 13303//13303 13305//13305 -f 13304//13304 13305//13305 13306//13306 -f 13306//13306 13305//13305 13307//13307 -f 13306//13306 13307//13307 13308//13308 -f 13307//13307 13309//13309 13308//13308 -f 13308//13308 13309//13309 13310//13310 -f 13308//13308 13310//13310 13311//13311 -f 13311//13311 13310//13310 13312//13312 -f 13311//13311 13312//13312 13313//13313 -f 13313//13313 13312//13312 13314//13314 -f 13313//13313 13314//13314 13315//13315 -f 13315//13315 13314//13314 13316//13316 -f 13314//13314 13317//13317 13316//13316 -f 13316//13316 13317//13317 13318//13318 -f 13316//13316 13318//13318 13319//13319 -f 13319//13319 13318//13318 13320//13320 -f 13319//13319 13320//13320 13321//13321 -f 13321//13321 13320//13320 13322//13322 -f 13320//13320 13323//13323 13322//13322 -f 13322//13322 13323//13323 13324//13324 -f 13322//13322 13324//13324 13325//13325 -f 13325//13325 13324//13324 13326//13326 -f 13325//13325 13326//13326 13327//13327 -f 13326//13326 13328//13328 13327//13327 -f 13327//13327 13328//13328 13329//13329 -f 13327//13327 13329//13329 13330//13330 -f 13330//13330 13329//13329 13331//13331 -f 13330//13330 13331//13331 13332//13332 -f 13332//13332 13331//13331 13333//13333 -f 13332//13332 13333//13333 13334//13334 -f 13334//13334 13333//13333 13335//13335 -f 13334//13334 13335//13335 13336//13336 -f 13336//13336 13335//13335 12717//12717 -f 13336//13336 12717//12717 12716//12716 -f 13337//13337 13338//13338 13339//13339 -f 13339//13339 13338//13338 13340//13340 -f 13339//13339 13340//13340 13341//13341 -f 13341//13341 13340//13340 13342//13342 -f 13341//13341 13342//13342 13343//13343 -f 13343//13343 13342//13342 13344//13344 -f 13343//13343 13344//13344 12729//12729 -f 12729//12729 13344//13344 13345//13345 -f 12729//12729 13345//13345 12730//12730 -f 13339//13339 13346//13346 13337//13337 -f 13337//13337 13346//13346 13347//13347 -f 13337//13337 13347//13347 13348//13348 -f 13348//13348 13347//13347 13349//13349 -f 13348//13348 13349//13349 13350//13350 -f 13350//13350 13349//13349 13351//13351 -f 13350//13350 13351//13351 13352//13352 -f 13352//13352 13351//13351 13353//13353 -f 11994//11994 11993//11993 13354//13354 -f 13354//13354 11993//11993 13355//13355 -f 13354//13354 13355//13355 13356//13356 -f 13356//13356 13355//13355 13357//13357 -f 13356//13356 13357//13357 13358//13358 -f 13358//13358 13357//13357 13359//13359 -f 13358//13358 13359//13359 13360//13360 -f 13360//13360 13359//13359 13361//13361 -f 13360//13360 13361//13361 13362//13362 -f 13362//13362 13361//13361 13363//13363 -f 13362//13362 13363//13363 13364//13364 -f 13364//13364 13363//13363 13365//13365 -f 13364//13364 13365//13365 13366//13366 -f 13366//13366 13365//13365 13367//13367 -f 13366//13366 13367//13367 13368//13368 -f 13368//13368 13367//13367 13369//13369 -f 13368//13368 13369//13369 13370//13370 -f 13370//13370 13369//13369 13353//13353 -f 13370//13370 13353//13353 13371//13371 -f 13371//13371 13353//13353 13351//13351 -f 11978//11978 13372//13372 11979//11979 -f 11979//11979 13372//13372 13373//13373 -f 11979//11979 13373//13373 11980//11980 -f 13373//13373 13374//13374 11980//11980 -f 11980//11980 13374//13374 13375//13375 -f 11980//11980 13375//13375 11981//11981 -f 11981//11981 13375//13375 13376//13376 -f 11981//11981 13376//13376 11982//11982 -f 11982//11982 13376//13376 13377//13377 -f 11982//11982 13377//13377 11985//11985 -f 11985//11985 13377//13377 13378//13378 -f 11985//11985 13378//13378 11922//11922 -f 11922//11922 13378//13378 13379//13379 -f 11922//11922 13379//13379 11923//11923 -f 11923//11923 13379//13379 13380//13380 -f 11923//11923 13380//13380 11989//11989 -f 11989//11989 13380//13380 13381//13381 -f 11989//11989 13381//13381 13382//13382 -f 13382//13382 13381//13381 11883//11883 -f 13382//13382 11883//11883 13383//13383 -f 13383//13383 11883//11883 11885//11885 -f 13383//13383 11885//11885 13384//13384 -f 13384//13384 11885//11885 11887//11887 -f 13384//13384 11887//11887 13385//13385 -f 13385//13385 11887//11887 11891//11891 -f 13385//13385 11891//11891 13386//13386 -f 13386//13386 11891//11891 11890//11890 -f 13386//13386 11890//11890 13387//13387 -f 13387//13387 11890//11890 11898//11898 -f 13387//13387 11898//11898 13388//13388 -f 13388//13388 11898//11898 11897//11897 -f 11893//11893 13389//13389 11895//11895 -f 11895//11895 13389//13389 13390//13390 -f 11895//11895 13390//13390 11897//11897 -f 11897//11897 13390//13390 13391//13391 -f 11897//11897 13391//13391 13388//13388 -f 12024//12024 12023//12023 13392//13392 -f 13392//13392 12023//12023 13393//13393 -f 13392//13392 13393//13393 13394//13394 -f 13393//13393 13395//13395 13394//13394 -f 13394//13394 13395//13395 13396//13396 -f 13394//13394 13396//13396 13397//13397 -f 13397//13397 13396//13396 13398//13398 -f 13396//13396 13399//13399 13398//13398 -f 13398//13398 13399//13399 13400//13400 -f 13398//13398 13400//13400 13401//13401 -f 13401//13401 13400//13400 13402//13402 -f 13401//13401 13402//13402 13403//13403 -f 13404//13404 13405//13405 12081//12081 -f 13406//13406 13407//13407 12065//12065 -f 12065//12065 13407//13407 12071//12071 -f 11878//11878 11880//11880 12067//12067 -f 11853//11853 11859//11859 12086//12086 -f 12086//12086 11859//11859 12091//12091 -f 13405//13405 11858//11858 12081//12081 -f 12081//12081 11858//11858 11857//11857 -f 12081//12081 11857//11857 12086//12086 -f 12086//12086 11857//11857 11854//11854 -f 12086//12086 11854//11854 11853//11853 -f 11880//11880 11882//11882 12067//12067 -f 12067//12067 11882//11882 13408//13408 -f 12067//12067 13408//13408 12065//12065 -f 12065//12065 13408//13408 13409//13409 -f 12065//12065 13409//13409 13406//13406 -f 11866//11866 11867//11867 12089//12089 -f 12089//12089 11867//11867 11869//11869 -f 12089//12089 11869//11869 850//850 -f 11859//11859 11861//11861 12091//12091 -f 12091//12091 11861//11861 11863//11863 -f 12091//12091 11863//11863 12089//12089 -f 12089//12089 11863//11863 11864//11864 -f 12089//12089 11864//11864 11866//11866 -f 13404//13404 12081//12081 13410//13410 -f 13410//13410 12081//12081 12083//12083 -f 13410//13410 12083//12083 13411//13411 -f 13411//13411 12083//12083 13412//13412 -f 13412//13412 12083//12083 12079//12079 -f 13412//13412 12079//12079 13413//13413 -f 11878//11878 12067//12067 11877//11877 -f 11877//11877 12067//12067 12036//12036 -f 11877//11877 12036//12036 11875//11875 -f 11875//11875 12036//12036 11873//11873 -f 11873//11873 12036//12036 12033//12033 -f 11873//11873 12033//12033 11850//11850 -f 11869//11869 11871//11871 850//850 -f 850//850 11871//11871 11872//11872 -f 850//850 11872//11872 12033//12033 -f 12033//12033 11872//11872 11851//11851 -f 12033//12033 11851//11851 11850//11850 -f 862//862 13414//13414 12079//12079 -f 12079//12079 13414//13414 13415//13415 -f 12079//12079 13415//13415 13413//13413 -f 13407//13407 13416//13416 12071//12071 -f 12071//12071 13416//13416 13417//13417 -f 12071//12071 13417//13417 12074//12074 -f 12074//12074 13417//13417 13418//13418 -f 12074//12074 13418//13418 13419//13419 -f 13419//13419 13420//13420 12074//12074 -f 12074//12074 13420//13420 13421//13421 -f 12074//12074 13421//13421 862//862 -f 862//862 13421//13421 13422//13422 -f 862//862 13422//13422 13414//13414 -f 12034//12034 13423//13423 12035//12035 -f 13423//13423 12034//12034 12069//12069 -f 12066//12066 12064//12064 13424//13424 -f 12075//12075 13425//13425 13426//13426 -f 12028//12028 13427//13427 12029//12029 -f 12029//12029 13427//13427 13428//13428 -f 12029//12029 13428//13428 12038//12038 -f 12038//12038 13428//13428 12039//12039 -f 12039//12039 13428//13428 13429//13429 -f 12039//12039 13429//13429 12041//12041 -f 12041//12041 13429//13429 12042//12042 -f 12042//12042 13429//13429 13430//13430 -f 12042//12042 13430//13430 12043//12043 -f 12043//12043 13430//13430 12044//12044 -f 12044//12044 13430//13430 13431//13431 -f 12044//12044 13431//13431 12032//12032 -f 12032//12032 13431//13431 13432//13432 -f 12032//12032 13432//13432 12031//12031 -f 12031//12031 13432//13432 13433//13433 -f 12031//12031 13433//13433 12094//12094 -f 12094//12094 13433//13433 13434//13434 -f 12094//12094 13434//13434 12095//12095 -f 12095//12095 13434//13434 13435//13435 -f 12095//12095 13435//13435 12096//12096 -f 12096//12096 13435//13435 13436//13436 -f 12096//12096 13436//13436 12090//12090 -f 12090//12090 13436//13436 13437//13437 -f 12090//12090 13437//13437 12092//12092 -f 12092//12092 13437//13437 13438//13438 -f 12092//12092 13438//13438 12093//12093 -f 13438//13438 13439//13439 12093//12093 -f 12093//12093 13439//13439 13440//13440 -f 12093//12093 13440//13440 12087//12087 -f 13440//13440 13441//13441 12087//12087 -f 12087//12087 13441//13441 13442//13442 -f 12087//12087 13442//13442 12088//12088 -f 12088//12088 13442//13442 13443//13443 -f 12088//12088 13443//13443 12082//12082 -f 13443//13443 13444//13444 12082//12082 -f 12082//12082 13444//13444 13445//13445 -f 12082//12082 13445//13445 12084//12084 -f 12084//12084 13445//13445 12085//12085 -f 12085//12085 13445//13445 13446//13446 -f 12085//12085 13446//13446 12080//12080 -f 12080//12080 13446//13446 13447//13447 -f 12080//12080 13447//13447 12078//12078 -f 13447//13447 13448//13448 12078//12078 -f 12078//12078 13448//13448 13449//13449 -f 12078//12078 13449//13449 12077//12077 -f 13449//13449 13450//13450 12077//12077 -f 12077//12077 13450//13450 13451//13451 -f 12077//12077 13451//13451 12076//12076 -f 12076//12076 13451//13451 13452//13452 -f 12076//12076 13452//13452 12075//12075 -f 12075//12075 13452//13452 13453//13453 -f 12075//12075 13453//13453 13425//13425 -f 13424//13424 12064//12064 13454//13454 -f 12064//12064 12063//12063 13454//13454 -f 13454//13454 12063//12063 12070//12070 -f 13454//13454 12070//12070 13455//13455 -f 13455//13455 12070//12070 12072//12072 -f 13455//13455 12072//12072 13426//13426 -f 13426//13426 12072//12072 12073//12073 -f 13426//13426 12073//12073 12075//12075 -f 12066//12066 13424//13424 12068//12068 -f 12068//12068 13424//13424 13456//13456 -f 12068//12068 13456//13456 12069//12069 -f 12069//12069 13456//13456 13457//13457 -f 12069//12069 13457//13457 13423//13423 -f 13377//13377 13376//13376 13458//13458 -f 13458//13458 13376//13376 13459//13459 -f 13413//13413 13415//13415 13460//13460 -f 13406//13406 13409//13409 13461//13461 -f 13461//13461 13409//13409 11881//11881 -f 11881//11881 13409//13409 13408//13408 -f 11881//11881 13408//13408 11882//11882 -f 13406//13406 13461//13461 13407//13407 -f 13407//13407 13461//13461 13462//13462 -f 13407//13407 13462//13462 13416//13416 -f 13416//13416 13462//13462 13463//13463 -f 13416//13416 13463//13463 13417//13417 -f 13417//13417 13463//13463 13418//13418 -f 13418//13418 13463//13463 13464//13464 -f 13418//13418 13464//13464 13419//13419 -f 13419//13419 13464//13464 13420//13420 -f 13420//13420 13464//13464 13465//13465 -f 13420//13420 13465//13465 13421//13421 -f 13421//13421 13465//13465 13466//13466 -f 13421//13421 13466//13466 13422//13422 -f 13460//13460 13415//13415 13466//13466 -f 13466//13466 13415//13415 13414//13414 -f 13466//13466 13414//13414 13422//13422 -f 13413//13413 13460//13460 13412//13412 -f 13412//13412 13460//13460 13467//13467 -f 13412//13412 13467//13467 13411//13411 -f 13411//13411 13467//13467 13468//13468 -f 13411//13411 13468//13468 13410//13410 -f 13410//13410 13468//13468 13404//13404 -f 13404//13404 13468//13468 13469//13469 -f 13404//13404 13469//13469 13405//13405 -f 13405//13405 13469//13469 11856//11856 -f 13405//13405 11856//11856 11858//11858 -f 11909//11909 11908//11908 13470//13470 -f 13470//13470 11908//11908 13471//13471 -f 13470//13470 13471//13471 13472//13472 -f 13472//13472 13471//13471 13473//13473 -f 13474//13474 13475//13475 13473//13473 -f 13473//13473 13475//13475 13476//13476 -f 13473//13473 13476//13476 13472//13472 -f 13477//13477 13372//13372 13478//13478 -f 13478//13478 13372//13372 13479//13479 -f 13478//13478 13479//13479 13480//13480 -f 13480//13480 13479//13479 13481//13481 -f 13480//13480 13481//13481 13474//13474 -f 13474//13474 13481//13481 13482//13482 -f 13474//13474 13482//13482 13475//13475 -f 13376//13376 13375//13375 13459//13459 -f 13459//13459 13375//13375 13374//13374 -f 13459//13459 13374//13374 13477//13477 -f 13477//13477 13374//13374 13373//13373 -f 13477//13477 13373//13373 13372//13372 -f 13377//13377 13458//13458 13378//13378 -f 13378//13378 13458//13458 13483//13483 -f 13378//13378 13483//13483 13379//13379 -f 13379//13379 13483//13483 13484//13484 -f 13379//13379 13484//13484 13380//13380 -f 13380//13380 13484//13484 13381//13381 -f 13381//13381 13484//13484 11884//11884 -f 13381//13381 11884//11884 11883//11883 -f 11921//11921 11884//11884 13485//13485 -f 13485//13485 11884//11884 13484//13484 -f 13485//13485 13484//13484 13486//13486 -f 13486//13486 13484//13484 13483//13483 -f 13486//13486 13483//13483 13487//13487 -f 13487//13487 13483//13483 13458//13458 -f 13487//13487 13458//13458 13488//13488 -f 13488//13488 13458//13458 13459//13459 -f 13488//13488 13459//13459 13489//13489 -f 13489//13489 13459//13459 13477//13477 -f 13489//13489 13477//13477 13490//13490 -f 13490//13490 13477//13477 13478//13478 -f 13490//13490 13478//13478 13491//13491 -f 13491//13491 13478//13478 13480//13480 -f 13491//13491 13480//13480 13492//13492 -f 13492//13492 13480//13480 13474//13474 -f 13492//13492 13474//13474 13493//13493 -f 13493//13493 13474//13474 13473//13473 -f 13493//13493 13473//13473 13494//13494 -f 13494//13494 13473//13473 13471//13471 -f 13494//13494 13471//13471 11910//11910 -f 11910//11910 13471//13471 11908//11908 -f 11881//11881 11921//11921 13461//13461 -f 13461//13461 11921//11921 13485//13485 -f 13461//13461 13485//13485 13462//13462 -f 13462//13462 13485//13485 13486//13486 -f 13462//13462 13486//13486 13463//13463 -f 13463//13463 13486//13486 13487//13487 -f 13463//13463 13487//13487 13464//13464 -f 13464//13464 13487//13487 13488//13488 -f 13464//13464 13488//13488 13465//13465 -f 13465//13465 13488//13488 13489//13489 -f 13465//13465 13489//13489 13466//13466 -f 13466//13466 13489//13489 13490//13490 -f 13466//13466 13490//13490 13460//13460 -f 13460//13460 13490//13490 13491//13491 -f 13460//13460 13491//13491 13467//13467 -f 13467//13467 13491//13491 13492//13492 -f 13467//13467 13492//13492 13468//13468 -f 13468//13468 13492//13492 13493//13493 -f 13468//13468 13493//13493 13469//13469 -f 13469//13469 13493//13493 13494//13494 -f 13469//13469 13494//13494 11856//11856 -f 11856//11856 13494//13494 11910//11910 -f 13440//13440 13439//13439 12735//12735 -f 12097//12097 12099//12099 13427//13427 -f 13427//13427 12099//12099 13428//13428 -f 12099//12099 12101//12101 13428//13428 -f 13428//13428 12101//12101 12102//12102 -f 13428//13428 12102//12102 13429//13429 -f 12102//12102 12104//12104 13429//13429 -f 13429//13429 12104//12104 12106//12106 -f 13429//13429 12106//12106 13430//13430 -f 13430//13430 12106//12106 12108//12108 -f 13430//13430 12108//12108 13431//13431 -f 13431//13431 12108//12108 12113//12113 -f 13431//13431 12113//12113 13432//13432 -f 13432//13432 12113//12113 12112//12112 -f 13432//13432 12112//12112 13433//13433 -f 13433//13433 12112//12112 12110//12110 -f 13433//13433 12110//12110 13434//13434 -f 12110//12110 12764//12764 13434//13434 -f 13434//13434 12764//12764 12763//12763 -f 13434//13434 12763//12763 13435//13435 -f 12735//12735 13439//13439 12754//12754 -f 12763//12763 12759//12759 13435//13435 -f 13435//13435 12759//12759 12757//12757 -f 13435//13435 12757//12757 13436//13436 -f 13436//13436 12757//12757 12756//12756 -f 13436//13436 12756//12756 13437//13437 -f 13437//13437 12756//12756 12754//12754 -f 13437//13437 12754//12754 13438//13438 -f 13438//13438 12754//12754 13439//13439 -f 13440//13440 12735//12735 13441//13441 -f 13441//13441 12735//12735 12738//12738 -f 13441//13441 12738//12738 13442//13442 -f 13442//13442 12738//12738 12740//12740 -f 13442//13442 12740//12740 13443//13443 -f 13443//13443 12740//12740 12742//12742 -f 13443//13443 12742//12742 12744//12744 -f 12746//12746 13445//13445 12744//12744 -f 12744//12744 13445//13445 13444//13444 -f 12744//12744 13444//13444 13443//13443 -f 13447//13447 13446//13446 12750//12750 -f 12750//12750 13446//13446 13445//13445 -f 12750//12750 13445//13445 12748//12748 -f 12748//12748 13445//13445 12746//12746 -f 13447//13447 12750//12750 13448//13448 -f 13448//13448 12750//12750 12734//12734 -f 13448//13448 12734//12734 13449//13449 -f 13449//13449 12734//12734 12052//12052 -f 13449//13449 12052//12052 13450//13450 -f 13450//13450 12052//12052 12051//12051 -f 13450//13450 12051//12051 13451//13451 -f 13451//13451 12051//12051 13452//13452 -f 13452//13452 12051//12051 12056//12056 -f 13452//13452 12056//12056 13453//13453 -f 13453//13453 12056//12056 12058//12058 -f 13453//13453 12058//12058 12060//12060 -f 13454//13454 13455//13455 12050//12050 -f 12050//12050 13455//13455 13426//13426 -f 12050//12050 13426//13426 12060//12060 -f 12060//12060 13426//13426 13425//13425 -f 12060//12060 13425//13425 13453//13453 -f 12050//12050 12048//12048 13454//13454 -f 13454//13454 12048//12048 12046//12046 -f 13454//13454 12046//12046 13424//13424 -f 13424//13424 12046//12046 12045//12045 -f 13424//13424 12045//12045 13456//13456 -f 13456//13456 12045//12045 12030//12030 -f 13456//13456 12030//12030 13457//13457 -f 13457//13457 12030//12030 12037//12037 -f 13457//13457 12037//12037 13423//13423 -f 13423//13423 12037//12037 12040//12040 -f 13423//13423 12040//12040 12035//12035 -f 13389//13389 11893//11893 13495//13495 -f 13495//13495 11893//11893 11901//11901 -f 13495//13495 11901//11901 13496//13496 -f 11901//11901 11900//11900 13496//13496 -f 13496//13496 11900//11900 11899//11899 -f 13496//13496 11899//11899 13497//13497 -f 13497//13497 11899//11899 11847//11847 -f 13497//13497 11847//11847 13498//13498 -f 13498//13498 11847//11847 11846//11846 -f 13498//13498 11846//11846 13499//13499 -f 13499//13499 11846//11846 11902//11902 -f 13499//13499 11902//11902 13500//13500 -f 13500//13500 11902//11902 11904//11904 -f 13500//13500 11904//11904 13501//13501 -f 13501//13501 11904//11904 11906//11906 -f 13501//13501 11906//11906 11956//11956 -f 11956//11956 11906//11906 11907//11907 -f 11956//11956 11907//11907 11957//11957 -f 11957//11957 11907//11907 11909//11909 -f 11957//11957 11909//11909 11960//11960 -f 11960//11960 11909//11909 13470//13470 -f 11960//11960 13470//13470 11965//11965 -f 11965//11965 13470//13470 13472//13472 -f 11965//11965 13472//13472 11966//11966 -f 11966//11966 13472//13472 13476//13476 -f 11966//11966 13476//13476 11967//11967 -f 11967//11967 13476//13476 13475//13475 -f 11967//11967 13475//13475 11970//11970 -f 11970//11970 13475//13475 13482//13482 -f 11970//11970 13482//13482 11971//11971 -f 11971//11971 13482//13482 13481//13481 -f 13372//13372 11978//11978 13479//13479 -f 13479//13479 11978//11978 11977//11977 -f 13479//13479 11977//11977 13481//13481 -f 13481//13481 11977//11977 11972//11972 -f 13481//13481 11972//11972 11971//11971 -f 13500//13500 13501//13501 13502//13502 -f 13503//13503 13504//13504 13505//13505 -f 13506//13506 13507//13507 13508//13508 -f 13509//13509 11942//11942 11941//11941 -f 13509//13509 11941//11941 13510//13510 -f 13511//13511 13512//13512 13513//13513 -f 13514//13514 13515//13515 13512//13512 -f 13516//13516 13517//13517 13515//13515 -f 13518//13518 13519//13519 13503//13503 -f 13503//13503 13519//13519 13520//13520 -f 13503//13503 13520//13520 13504//13504 -f 13504//13504 13520//13520 13521//13521 -f 13504//13504 13521//13521 13522//13522 -f 13523//13523 13524//13524 13525//13525 -f 13525//13525 13524//13524 13506//13506 -f 13526//13526 13527//13527 13523//13523 -f 11944//11944 11964//11964 13527//13527 -f 13528//13528 13505//13505 13529//13529 -f 13529//13529 13505//13505 13504//13504 -f 13529//13529 13504//13504 13516//13516 -f 13516//13516 13504//13504 13522//13522 -f 13516//13516 13522//13522 13517//13517 -f 13530//13530 13531//13531 13508//13508 -f 13532//13532 13531//13531 13533//13533 -f 13533//13533 13531//13531 13530//13530 -f 13533//13533 13530//13530 13534//13534 -f 11988//11988 11989//11989 13382//13382 -f 13510//13510 11941//11941 13535//13535 -f 13535//13535 11941//11941 11987//11987 -f 13535//13535 11987//11987 13536//13536 -f 13536//13536 11987//11987 11988//11988 -f 13536//13536 11988//11988 13537//13537 -f 13537//13537 11988//11988 13382//13382 -f 13537//13537 13382//13382 13383//13383 -f 13383//13383 13538//13538 13537//13537 -f 13537//13537 13538//13538 13539//13539 -f 13537//13537 13539//13539 13536//13536 -f 13536//13536 13539//13539 13511//13511 -f 13536//13536 13511//13511 13535//13535 -f 13535//13535 13511//13511 13513//13513 -f 13535//13535 13513//13513 13510//13510 -f 13383//13383 13384//13384 13538//13538 -f 13538//13538 13384//13384 13385//13385 -f 13538//13538 13385//13385 13386//13386 -f 13512//13512 13511//13511 13514//13514 -f 13514//13514 13511//13511 13539//13539 -f 13514//13514 13539//13539 13540//13540 -f 13540//13540 13539//13539 13538//13538 -f 13540//13540 13538//13538 13541//13541 -f 13541//13541 13538//13538 13386//13386 -f 13541//13541 13386//13386 13387//13387 -f 13515//13515 13514//13514 13516//13516 -f 13516//13516 13514//13514 13540//13540 -f 13516//13516 13540//13540 13529//13529 -f 13529//13529 13540//13540 13541//13541 -f 13529//13529 13541//13541 13528//13528 -f 13528//13528 13541//13541 13387//13387 -f 13528//13528 13387//13387 13388//13388 -f 13388//13388 13391//13391 13528//13528 -f 13528//13528 13391//13391 13542//13542 -f 13528//13528 13542//13542 13505//13505 -f 13505//13505 13542//13542 13543//13543 -f 13505//13505 13543//13543 13503//13503 -f 13503//13503 13543//13543 13544//13544 -f 13503//13503 13544//13544 13518//13518 -f 13518//13518 13544//13544 13545//13545 -f 13391//13391 13390//13390 13542//13542 -f 13542//13542 13390//13390 13534//13534 -f 13542//13542 13534//13534 13543//13543 -f 13543//13543 13534//13534 13530//13530 -f 13543//13543 13530//13530 13544//13544 -f 13544//13544 13530//13530 13508//13508 -f 13544//13544 13508//13508 13545//13545 -f 13545//13545 13508//13508 13507//13507 -f 13390//13390 13389//13389 13534//13534 -f 13534//13534 13389//13389 13495//13495 -f 13534//13534 13495//13495 13533//13533 -f 13533//13533 13495//13495 13496//13496 -f 13533//13533 13496//13496 13532//13532 -f 13532//13532 13496//13496 13497//13497 -f 13532//13532 13497//13497 13498//13498 -f 13506//13506 13508//13508 13525//13525 -f 13525//13525 13508//13508 13531//13531 -f 13525//13525 13531//13531 13546//13546 -f 13546//13546 13531//13531 13532//13532 -f 13546//13546 13532//13532 13547//13547 -f 13547//13547 13532//13532 13498//13498 -f 13547//13547 13498//13498 13499//13499 -f 13523//13523 13525//13525 13526//13526 -f 13526//13526 13525//13525 13546//13546 -f 13526//13526 13546//13546 13548//13548 -f 13548//13548 13546//13546 13547//13547 -f 13548//13548 13547//13547 13502//13502 -f 13502//13502 13547//13547 13499//13499 -f 13502//13502 13499//13499 13500//13500 -f 13527//13527 13526//13526 11944//11944 -f 11944//11944 13526//13526 13548//13548 -f 11944//11944 13548//13548 11945//11945 -f 11945//11945 13548//13548 13502//13502 -f 11945//11945 13502//13502 11955//11955 -f 11955//11955 13502//13502 13501//13501 -f 11955//11955 13501//13501 11956//11956 -f 13549//13549 13550//13550 12865//12865 -f 12865//12865 13550//13550 12867//12867 -f 12867//12867 13550//13550 13551//13551 -f 12867//12867 13551//13551 12869//12869 -f 12869//12869 13551//13551 13552//13552 -f 12869//12869 13552//13552 12870//12870 -f 12870//12870 13552//13552 12862//12862 -f 12862//12862 13552//13552 13553//13553 -f 12862//12862 13553//13553 12859//12859 -f 12859//12859 13553//13553 13554//13554 -f 12859//12859 13554//13554 12857//12857 -f 12857//12857 13554//13554 13555//13555 -f 12857//12857 13555//13555 12855//12855 -f 12855//12855 13555//13555 12853//12853 -f 12853//12853 13555//13555 13556//13556 -f 12853//12853 13556//13556 12836//12836 -f 12836//12836 13556//13556 12837//12837 -f 12837//12837 13556//13556 13557//13557 -f 12837//12837 13557//13557 12850//12850 -f 12850//12850 13557//13557 13558//13558 -f 12850//12850 13558//13558 13559//13559 -f 13560//13560 12845//12845 13559//13559 -f 13559//13559 12845//12845 12848//12848 -f 13559//13559 12848//12848 12850//12850 -f 13561//13561 12204//12204 13562//13562 -f 13562//13562 12204//12204 12202//12202 -f 13562//13562 12202//12202 13563//13563 -f 13563//13563 12202//12202 12839//12839 -f 13563//13563 12839//12839 13564//13564 -f 13564//13564 12839//12839 12841//12841 -f 13564//13564 12841//12841 13560//13560 -f 13560//13560 12841//12841 12843//12843 -f 13560//13560 12843//12843 12845//12845 -f 13565//13565 12192//12192 13566//13566 -f 13566//13566 12192//12192 12210//12210 -f 13566//13566 12210//12210 13567//13567 -f 13567//13567 12210//12210 12209//12209 -f 13567//13567 12209//12209 13568//13568 -f 13568//13568 12209//12209 12207//12207 -f 13568//13568 12207//12207 13561//13561 -f 13561//13561 12207//12207 12206//12206 -f 13561//13561 12206//12206 12204//12204 -f 13569//13569 12199//12199 13570//13570 -f 13570//13570 12199//12199 12197//12197 -f 13570//13570 12197//12197 13571//13571 -f 13571//13571 12197//12197 12195//12195 -f 13571//13571 12195//12195 13565//13565 -f 13565//13565 12195//12195 12193//12193 -f 13565//13565 12193//12193 12192//12192 -f 13572//13572 12189//12189 13573//13573 -f 13573//13573 12189//12189 12188//12188 -f 13573//13573 12188//12188 13569//13569 -f 13569//13569 12188//12188 12200//12200 -f 13569//13569 12200//12200 12199//12199 -f 12182//12182 12180//12180 13574//13574 -f 13574//13574 12180//12180 12191//12191 -f 13574//13574 12191//12191 13572//13572 -f 13572//13572 12191//12191 12190//12190 -f 13572//13572 12190//12190 12189//12189 -f 13574//13574 13575//13575 12182//12182 -f 12182//12182 13575//13575 13576//13576 -f 12182//12182 13576//13576 12184//12184 -f 12184//12184 13576//13576 13577//13577 -f 12184//12184 13577//13577 12185//12185 -f 12185//12185 13577//13577 13578//13578 -f 12185//12185 13578//13578 12175//12175 -f 12175//12175 13578//13578 13579//13579 -f 12833//12833 13579//13579 13580//13580 -f 12833//12833 12178//12178 13579//13579 -f 13579//13579 12178//12178 12177//12177 -f 13579//13579 12177//12177 12175//12175 -f 13580//13580 13581//13581 12833//12833 -f 12833//12833 13581//13581 13582//13582 -f 12833//12833 13582//13582 12831//12831 -f 12831//12831 13582//13582 12828//12828 -f 12828//12828 13582//13582 13583//13583 -f 12828//12828 13583//13583 12826//12826 -f 12826//12826 13583//13583 13584//13584 -f 12826//12826 13584//13584 12824//12824 -f 12824//12824 13584//13584 13585//13585 -f 12824//12824 13585//13585 12822//12822 -f 12822//12822 13585//13585 12820//12820 -f 12820//12820 13585//13585 13586//13586 -f 12820//12820 13586//13586 12818//12818 -f 13586//13586 13587//13587 12818//12818 -f 12818//12818 13587//13587 13588//13588 -f 12818//12818 13588//13588 12816//12816 -f 12816//12816 13588//13588 13589//13589 -f 12816//12816 13589//13589 12815//12815 -f 12815//12815 13589//13589 13590//13590 -f 12815//12815 13590//13590 12813//12813 -f 12813//12813 13590//13590 13591//13591 -f 12813//12813 13591//13591 12803//12803 -f 12803//12803 13591//13591 13592//13592 -f 12803//12803 13592//13592 12805//12805 -f 12805//12805 13592//13592 13593//13593 -f 12805//12805 13593//13593 12807//12807 -f 12807//12807 13593//13593 13594//13594 -f 12807//12807 13594//13594 12809//12809 -f 12809//12809 13594//13594 13595//13595 -f 12809//12809 13595//13595 12810//12810 -f 12810//12810 13595//13595 13596//13596 -f 12810//12810 13596//13596 12170//12170 -f 12170//12170 13596//13596 13597//13597 -f 12170//12170 13597//13597 12168//12168 -f 12168//12168 13597//13597 13598//13598 -f 12168//12168 13598//13598 12166//12166 -f 12166//12166 13598//13598 13599//13599 -f 12166//12166 13599//13599 12164//12164 -f 12164//12164 13599//13599 13600//13600 -f 12164//12164 13600//13600 12162//12162 -f 12162//12162 13600//13600 13601//13601 -f 12162//12162 13601//13601 12160//12160 -f 12160//12160 13601//13601 13602//13602 -f 12160//12160 13602//13602 12136//12136 -f 12136//12136 13602//13602 13603//13603 -f 12136//12136 13603//13603 12137//12137 -f 12137//12137 13603//13603 13604//13604 -f 12137//12137 13604//13604 12157//12157 -f 12157//12157 13604//13604 13605//13605 -f 12157//12157 13605//13605 12156//12156 -f 12156//12156 13605//13605 13606//13606 -f 12156//12156 13606//13606 12154//12154 -f 12154//12154 13606//13606 13607//13607 -f 12154//12154 13607//13607 12151//12151 -f 12151//12151 13607//13607 13608//13608 -f 13609//13609 12147//12147 13608//13608 -f 13608//13608 12147//12147 12149//12149 -f 13608//13608 12149//12149 12151//12151 -f 13610//13610 12143//12143 13609//13609 -f 13609//13609 12143//12143 12145//12145 -f 13609//13609 12145//12145 12147//12147 -f 13611//13611 12139//12139 13610//13610 -f 13610//13610 12139//12139 12141//12141 -f 13610//13610 12141//12141 12143//12143 -f 13612//13612 12799//12799 13611//13611 -f 13611//13611 12799//12799 12801//12801 -f 13611//13611 12801//12801 12139//12139 -f 13613//13613 12789//12789 13614//13614 -f 13614//13614 12789//12789 12791//12791 -f 13614//13614 12791//12791 13615//13615 -f 13615//13615 12791//12791 12794//12794 -f 13615//13615 12794//12794 13612//13612 -f 13612//13612 12794//12794 12796//12796 -f 13612//13612 12796//12796 12799//12799 -f 13616//13616 12784//12784 13617//13617 -f 13617//13617 12784//12784 12785//12785 -f 13617//13617 12785//12785 13613//13613 -f 13613//13613 12785//12785 12787//12787 -f 13613//13613 12787//12787 12789//12789 -f 12779//12779 12774//12774 13618//13618 -f 13618//13618 12774//12774 12776//12776 -f 13618//13618 12776//12776 13619//13619 -f 13619//13619 12776//12776 12778//12778 -f 13619//13619 12778//12778 13616//13616 -f 13616//13616 12778//12778 12782//12782 -f 13616//13616 12782//12782 12784//12784 -f 12779//12779 13618//13618 13620//13620 -f 12779//12779 13620//13620 12773//12773 -f 12773//12773 13620//13620 13621//13621 -f 13622//13622 12130//12130 13623//13623 -f 13623//13623 12130//12130 12766//12766 -f 13623//13623 12766//12766 13624//13624 -f 13624//13624 12766//12766 12768//12768 -f 13624//13624 12768//12768 13625//13625 -f 13625//13625 12768//12768 12770//12770 -f 13625//13625 12770//12770 13621//13621 -f 13621//13621 12770//12770 12772//12772 -f 13621//13621 12772//12772 12773//12773 -f 12117//12117 12124//12124 13626//13626 -f 13626//13626 12124//12124 12126//12126 -f 13626//13626 12126//12126 13627//13627 -f 13627//13627 12126//12126 12135//12135 -f 13627//13627 12135//12135 13628//13628 -f 13628//13628 12135//12135 12134//12134 -f 13628//13628 12134//12134 13622//13622 -f 13622//13622 12134//12134 12132//12132 -f 13622//13622 12132//12132 12130//12130 -f 13626//13626 13629//13629 12117//12117 -f 12117//12117 13629//13629 13630//13630 -f 12117//12117 13630//13630 12118//12118 -f 12118//12118 13630//13630 13631//13631 -f 12118//12118 13631//13631 12120//12120 -f 12120//12120 13631//13631 13632//13632 -f 12120//12120 13632//13632 12121//12121 -f 12121//12121 13632//13632 13633//13633 -f 12121//12121 13633//13633 12098//12098 -f 12098//12098 13633//13633 13634//13634 -f 12098//12098 13634//13634 12100//12100 -f 12100//12100 13634//13634 13635//13635 -f 12100//12100 13635//13635 12103//12103 -f 12103//12103 13635//13635 13636//13636 -f 12103//12103 13636//13636 12105//12105 -f 12105//12105 13636//13636 13637//13637 -f 12116//12116 12115//12115 13638//13638 -f 13638//13638 12115//12115 12114//12114 -f 13638//13638 12114//12114 13637//13637 -f 13637//13637 12114//12114 12107//12107 -f 13637//13637 12107//12107 12105//12105 -f 13639//13639 12109//12109 13638//13638 -f 13638//13638 12109//12109 12111//12111 -f 13638//13638 12111//12111 12116//12116 -f 12755//12755 12758//12758 13640//13640 -f 13640//13640 12758//12758 12762//12762 -f 13640//13640 12762//12762 13641//13641 -f 13641//13641 12762//12762 12761//12761 -f 13641//13641 12761//12761 13642//13642 -f 13642//13642 12761//12761 12760//12760 -f 13642//13642 12760//12760 13639//13639 -f 13639//13639 12760//12760 12765//12765 -f 13639//13639 12765//12765 12109//12109 -f 13643//13643 12753//12753 13644//13644 -f 13644//13644 12753//12753 12755//12755 -f 13644//13644 12755//12755 13640//13640 -f 12753//12753 13643//13643 13645//13645 -f 12753//12753 13645//13645 12736//12736 -f 12736//12736 13645//13645 13646//13646 -f 12736//12736 13646//13646 12737//12737 -f 12737//12737 13646//13646 12739//12739 -f 13647//13647 12741//12741 13648//13648 -f 13648//13648 12741//12741 12739//12739 -f 13648//13648 12739//12739 13646//13646 -f 12741//12741 13647//13647 13649//13649 -f 12741//12741 13649//13649 12743//12743 -f 12743//12743 13649//13649 13650//13650 -f 12743//12743 13650//13650 12745//12745 -f 12745//12745 13650//13650 13651//13651 -f 12745//12745 13651//13651 12747//12747 -f 12747//12747 13651//13651 13652//13652 -f 12747//12747 13652//13652 12749//12749 -f 12749//12749 13652//13652 12751//12751 -f 12751//12751 13652//13652 13653//13653 -f 12751//12751 13653//13653 12752//12752 -f 12752//12752 13653//13653 13654//13654 -f 12752//12752 13654//13654 12733//12733 -f 12733//12733 13654//13654 13655//13655 -f 12733//12733 13655//13655 12053//12053 -f 12053//12053 13655//13655 13656//13656 -f 12053//12053 13656//13656 12054//12054 -f 12054//12054 13656//13656 13657//13657 -f 13658//13658 12062//12062 13659//13659 -f 13659//13659 12062//12062 12061//12061 -f 13659//13659 12061//12061 13660//13660 -f 13660//13660 12061//12061 12059//12059 -f 13660//13660 12059//12059 13661//13661 -f 13661//13661 12059//12059 12057//12057 -f 13661//13661 12057//12057 13657//13657 -f 13657//13657 12057//12057 12055//12055 -f 13657//13657 12055//12055 12054//12054 -f 13662//13662 12047//12047 13658//13658 -f 13658//13658 12047//12047 12049//12049 -f 13658//13658 12049//12049 12062//12062 -f 13662//13662 13663//13663 12047//12047 -f 12047//12047 13663//13663 13427//13427 -f 12047//12047 13427//13427 12028//12028 -f 12865//12865 12216//12216 13549//13549 -f 13549//13549 12216//12216 12214//12214 -f 13549//13549 12214//12214 13664//13664 -f 13664//13664 12214//12214 12212//12212 -f 13664//13664 12212//12212 13665//13665 -f 13665//13665 12212//12212 12211//12211 -f 13665//13665 12211//12211 13666//13666 -f 13666//13666 12211//12211 12220//12220 -f 13666//13666 12220//12220 13667//13667 -f 13667//13667 12220//12220 12222//12222 -f 13667//13667 12222//12222 13668//13668 -f 12222//12222 12224//12224 13668//13668 -f 13668//13668 12224//12224 12227//12227 -f 13668//13668 12227//12227 13669//13669 -f 13669//13669 12227//12227 12229//12229 -f 13669//13669 12229//12229 13670//13670 -f 11942//11942 13509//13509 13671//13671 -f 11929//11929 11932//11932 13672//13672 -f 11976//11976 13673//13673 11933//11933 -f 11933//11933 13673//13673 13672//13672 -f 11933//11933 13672//13672 11931//11931 -f 11931//11931 13672//13672 11932//11932 -f 13527//13527 11964//11964 13674//13674 -f 11964//11964 11963//11963 13674//13674 -f 13674//13674 11963//11963 11927//11927 -f 13674//13674 11927//11927 13672//13672 -f 13672//13672 11927//11927 11926//11926 -f 13672//13672 11926//11926 11929//11929 -f 13675//13675 13545//13545 13507//13507 -f 11976//11976 11938//11938 13673//13673 -f 13673//13673 11938//11938 11937//11937 -f 13673//13673 11937//11937 13671//13671 -f 13671//13671 11937//11937 11940//11940 -f 13671//13671 11940//11940 11942//11942 -f 13507//13507 13506//13506 13675//13675 -f 13675//13675 13506//13506 13524//13524 -f 13675//13675 13524//13524 13674//13674 -f 13674//13674 13524//13524 13523//13523 -f 13674//13674 13523//13523 13527//13527 -f 13515//13515 13517//13517 13676//13676 -f 13676//13676 13517//13517 13522//13522 -f 13676//13676 13519//13519 13675//13675 -f 13675//13675 13519//13519 13518//13518 -f 13675//13675 13518//13518 13545//13545 -f 13522//13522 13521//13521 13676//13676 -f 13676//13676 13521//13521 13520//13520 -f 13676//13676 13520//13520 13519//13519 -f 13509//13509 13510//13510 13671//13671 -f 13671//13671 13510//13510 13513//13513 -f 13671//13671 13513//13513 13676//13676 -f 13676//13676 13513//13513 13512//13512 -f 13676//13676 13512//13512 13515//13515 -f 13670//13670 12248//12248 12250//12250 -f 13670//13670 12250//12250 13669//13669 -f 13669//13669 12250//12250 12252//12252 -f 13669//13669 12252//12252 13668//13668 -f 13668//13668 12252//12252 13667//13667 -f 13667//13667 12252//12252 12254//12254 -f 13667//13667 12254//12254 13666//13666 -f 13666//13666 12254//12254 12256//12256 -f 13666//13666 12256//12256 13665//13665 -f 13665//13665 12256//12256 12258//12258 -f 13665//13665 12258//12258 13664//13664 -f 12258//12258 12260//12260 13664//13664 -f 13664//13664 12260//12260 12262//12262 -f 13664//13664 12262//12262 13549//13549 -f 13549//13549 12262//12262 12905//12905 -f 13549//13549 12905//12905 13550//13550 -f 13550//13550 12905//12905 12903//12903 -f 13550//13550 12903//12903 13551//13551 -f 13551//13551 12903//12903 12901//12901 -f 13551//13551 12901//12901 13552//13552 -f 12901//12901 12899//12899 13552//13552 -f 13552//13552 12899//12899 12897//12897 -f 13552//13552 12897//12897 13553//13553 -f 13553//13553 12897//12897 12895//12895 -f 13553//13553 12895//12895 13554//13554 -f 13554//13554 12895//12895 12893//12893 -f 13554//13554 12893//12893 13555//13555 -f 12893//12893 12891//12891 13555//13555 -f 13555//13555 12891//12891 12889//12889 -f 13555//13555 12889//12889 13556//13556 -f 12889//12889 12887//12887 13556//13556 -f 13556//13556 12887//12887 12886//12886 -f 13556//13556 12886//12886 13557//13557 -f 13557//13557 12886//12886 12883//12883 -f 13557//13557 12883//12883 13558//13558 -f 13558//13558 12883//12883 12881//12881 -f 13558//13558 12881//12881 13559//13559 -f 12881//12881 12879//12879 13559//13559 -f 13559//13559 12879//12879 12877//12877 -f 13559//13559 12877//12877 13560//13560 -f 13560//13560 12877//12877 12876//12876 -f 13560//13560 12876//12876 13564//13564 -f 13564//13564 12876//12876 12873//12873 -f 13564//13564 12873//12873 13563//13563 -f 12873//12873 12875//12875 13563//13563 -f 13563//13563 12875//12875 12243//12243 -f 13563//13563 12243//12243 13562//13562 -f 13562//13562 12243//12243 12245//12245 -f 13562//13562 12245//12245 13561//13561 -f 13561//13561 12245//12245 12242//12242 -f 13561//13561 12242//12242 13568//13568 -f 13568//13568 12242//12242 12241//12241 -f 13568//13568 12241//12241 13567//13567 -f 13567//13567 12241//12241 12239//12239 -f 13567//13567 12239//12239 13566//13566 -f 13566//13566 12239//12239 12237//12237 -f 13566//13566 12237//12237 13565//13565 -f 13565//13565 12237//12237 12234//12234 -f 13565//13565 12234//12234 13571//13571 -f 13571//13571 12234//12234 12232//12232 -f 12221//12221 13576//13576 12223//12223 -f 12223//12223 13576//13576 13575//13575 -f 12223//12223 13575//13575 12225//12225 -f 12225//12225 13575//13575 13574//13574 -f 12225//12225 13574//13574 12226//12226 -f 12226//12226 13574//13574 13572//13572 -f 12226//12226 13572//13572 12228//12228 -f 12228//12228 13572//13572 13573//13573 -f 12228//12228 13573//13573 12230//12230 -f 12230//12230 13573//13573 13569//13569 -f 12230//12230 13569//13569 12232//12232 -f 12232//12232 13569//13569 13570//13570 -f 12232//12232 13570//13570 13571//13571 -f 13577//13577 13576//13576 12221//12221 -f 13577//13577 12221//12221 13578//13578 -f 13578//13578 12221//12221 12219//12219 -f 12219//12219 12218//12218 13578//13578 -f 13578//13578 12218//12218 12213//12213 -f 13578//13578 12213//12213 13579//13579 -f 12213//12213 12215//12215 13579//13579 -f 13579//13579 12215//12215 12217//12217 -f 13579//13579 12217//12217 13580//13580 -f 13580//13580 12217//12217 12864//12864 -f 13580//13580 12864//12864 13581//13581 -f 12864//12864 12866//12866 13581//13581 -f 13581//13581 12866//12866 13582//13582 -f 12866//12866 12868//12868 13582//13582 -f 13582//13582 12868//12868 12863//12863 -f 13582//13582 12863//12863 13583//13583 -f 13583//13583 12863//12863 12861//12861 -f 13583//13583 12861//12861 13584//13584 -f 13584//13584 12861//12861 12860//12860 -f 13584//13584 12860//12860 13585//13585 -f 13585//13585 12860//12860 12858//12858 -f 13585//13585 12858//12858 13586//13586 -f 13586//13586 12858//12858 12856//12856 -f 13586//13586 12856//12856 13587//13587 -f 13587//13587 12856//12856 12854//12854 -f 13587//13587 12854//12854 13588//13588 -f 13588//13588 12854//12854 12838//12838 -f 13588//13588 12838//12838 13589//13589 -f 13589//13589 12838//12838 12852//12852 -f 13589//13589 12852//12852 13590//13590 -f 12852//12852 12851//12851 13590//13590 -f 13590//13590 12851//12851 12849//12849 -f 13590//13590 12849//12849 13591//13591 -f 13591//13591 12849//12849 12847//12847 -f 13591//13591 12847//12847 13592//13592 -f 13592//13592 12847//12847 12846//12846 -f 13592//13592 12846//12846 13593//13593 -f 13593//13593 12846//12846 12844//12844 -f 13593//13593 12844//12844 13594//13594 -f 13594//13594 12844//12844 12842//12842 -f 13594//13594 12842//12842 13595//13595 -f 13595//13595 12842//12842 12840//12840 -f 13595//13595 12840//12840 13596//13596 -f 13596//13596 12840//12840 12201//12201 -f 12194//12194 13600//13600 12208//12208 -f 12208//12208 13600//13600 13599//13599 -f 12208//12208 13599//13599 12205//12205 -f 12205//12205 13599//13599 13598//13598 -f 12205//12205 13598//13598 12203//12203 -f 12203//12203 13598//13598 13597//13597 -f 12203//12203 13597//13597 12201//12201 -f 12201//12201 13597//13597 13596//13596 -f 12187//12187 13605//13605 13604//13604 -f 12187//12187 13604//13604 12198//12198 -f 12198//12198 13604//13604 13603//13603 -f 12198//12198 13603//13603 12196//12196 -f 12196//12196 13603//13603 13602//13602 -f 12196//12196 13602//13602 12194//12194 -f 12194//12194 13602//13602 13601//13601 -f 12194//12194 13601//13601 13600//13600 -f 13605//13605 12187//12187 13606//13606 -f 13606//13606 12187//12187 12186//12186 -f 13606//13606 12186//12186 13607//13607 -f 12186//12186 12179//12179 13607//13607 -f 13607//13607 12179//12179 12181//12181 -f 13607//13607 12181//12181 13608//13608 -f 13608//13608 12181//12181 12183//12183 -f 13608//13608 12183//12183 13609//13609 -f 13609//13609 12183//12183 12174//12174 -f 13609//13609 12174//12174 13610//13610 -f 12174//12174 12173//12173 13610//13610 -f 13610//13610 12173//12173 12176//12176 -f 13610//13610 12176//12176 13611//13611 -f 12832//12832 13612//13612 12834//12834 -f 12834//12834 13612//13612 13611//13611 -f 12834//12834 13611//13611 12835//12835 -f 12835//12835 13611//13611 12176//12176 -f 12832//12832 12830//12830 13612//13612 -f 13612//13612 12830//12830 12829//12829 -f 13612//13612 12829//12829 13615//13615 -f 12829//12829 12827//12827 13615//13615 -f 13615//13615 12827//12827 12825//12825 -f 13615//13615 12825//12825 13614//13614 -f 13614//13614 12825//12825 12823//12823 -f 13614//13614 12823//12823 13613//13613 -f 13613//13613 12823//12823 12821//12821 -f 13613//13613 12821//12821 13617//13617 -f 13617//13617 12821//12821 12819//12819 -f 13617//13617 12819//12819 13616//13616 -f 13616//13616 12819//12819 12817//12817 -f 13616//13616 12817//12817 13619//13619 -f 13619//13619 12817//12817 13618//13618 -f 13618//13618 12817//12817 12814//12814 -f 12814//12814 12812//12812 13618//13618 -f 13618//13618 12812//12812 12811//12811 -f 13618//13618 12811//12811 13620//13620 -f 13620//13620 12811//12811 12802//12802 -f 13620//13620 12802//12802 13621//13621 -f 12802//12802 12804//12804 13621//13621 -f 13621//13621 12804//12804 12806//12806 -f 13621//13621 12806//12806 13625//13625 -f 13625//13625 12806//12806 12808//12808 -f 13625//13625 12808//12808 13624//13624 -f 13624//13624 12808//12808 13623//13623 -f 13623//13623 12808//12808 12172//12172 -f 13623//13623 12172//12172 13622//13622 -f 13622//13622 12172//12172 12171//12171 -f 13622//13622 12171//12171 13628//13628 -f 13628//13628 12171//12171 12169//12169 -f 13628//13628 12169//12169 13627//13627 -f 12169//12169 12167//12167 13627//13627 -f 13627//13627 12167//12167 12165//12165 -f 13627//13627 12165//12165 13626//13626 -f 13626//13626 12165//12165 12163//12163 -f 13626//13626 12163//12163 13629//13629 -f 13629//13629 12163//12163 12161//12161 -f 12152//12152 13636//13636 13635//13635 -f 12152//12152 13635//13635 12153//12153 -f 12153//12153 13635//13635 13634//13634 -f 12153//12153 13634//13634 12155//12155 -f 12155//12155 13634//13634 13633//13633 -f 12155//12155 13633//13633 12158//12158 -f 12158//12158 13633//13633 13632//13632 -f 12158//12158 13632//13632 12159//12159 -f 12159//12159 13632//13632 13631//13631 -f 12159//12159 13631//13631 12138//12138 -f 12138//12138 13631//13631 13630//13630 -f 12138//12138 13630//13630 12161//12161 -f 12161//12161 13630//13630 13629//13629 -f 12152//12152 12150//12150 13636//13636 -f 13636//13636 12150//12150 12148//12148 -f 13636//13636 12148//12148 13637//13637 -f 12148//12148 12146//12146 13637//13637 -f 13637//13637 12146//12146 12144//12144 -f 13637//13637 12144//12144 13638//13638 -f 12144//12144 12142//12142 13638//13638 -f 13638//13638 12142//12142 12140//12140 -f 13638//13638 12140//12140 13639//13639 -f 13639//13639 12140//12140 12800//12800 -f 13639//13639 12800//12800 13642//13642 -f 13642//13642 12800//12800 12798//12798 -f 13642//13642 12798//12798 13641//13641 -f 13641//13641 12798//12798 12797//12797 -f 13641//13641 12797//12797 13640//13640 -f 13640//13640 12797//12797 12795//12795 -f 13640//13640 12795//12795 13644//13644 -f 13644//13644 12795//12795 12793//12793 -f 13644//13644 12793//12793 13643//13643 -f 13643//13643 12793//12793 12792//12792 -f 13643//13643 12792//12792 12790//12790 -f 13643//13643 12790//12790 13645//13645 -f 13645//13645 12790//12790 12788//12788 -f 13645//13645 12788//12788 13646//13646 -f 13646//13646 12788//12788 12786//12786 -f 13646//13646 12786//12786 13648//13648 -f 13648//13648 12786//12786 12783//12783 -f 13648//13648 12783//12783 13647//13647 -f 13647//13647 12783//12783 12777//12777 -f 13647//13647 12777//12777 13649//13649 -f 13649//13649 12777//12777 12775//12775 -f 13649//13649 12775//12775 13650//13650 -f 13650//13650 12775//12775 12781//12781 -f 13650//13650 12781//12781 13651//13651 -f 13651//13651 12781//12781 12780//12780 -f 13651//13651 12780//12780 13652//13652 -f 13652//13652 12780//12780 12771//12771 -f 13652//13652 12771//12771 13653//13653 -f 13653//13653 12771//12771 13654//13654 -f 13654//13654 12771//12771 12769//12769 -f 13654//13654 12769//12769 12767//12767 -f 13654//13654 12767//12767 13655//13655 -f 13655//13655 12767//12767 12129//12129 -f 13655//13655 12129//12129 13656//13656 -f 12129//12129 12131//12131 13656//13656 -f 13656//13656 12131//12131 12133//12133 -f 13656//13656 12133//12133 13657//13657 -f 13657//13657 12133//12133 12125//12125 -f 13657//13657 12125//12125 13661//13661 -f 13661//13661 12125//12125 13660//13660 -f 12125//12125 12127//12127 13660//13660 -f 13660//13660 12127//12127 12128//12128 -f 13660//13660 12128//12128 13659//13659 -f 13659//13659 12128//12128 12123//12123 -f 13659//13659 12123//12123 13658//13658 -f 13658//13658 12123//12123 12122//12122 -f 13658//13658 12122//12122 13662//13662 -f 13662//13662 12122//12122 12119//12119 -f 13662//13662 12119//12119 13663//13663 -f 13663//13663 12119//12119 12097//12097 -f 13663//13663 12097//12097 13427//13427 -f 13671//13671 13676//13676 13677//13677 -f 13677//13677 13676//13676 13678//13678 -f 13673//13673 13671//13671 13679//13679 -f 13679//13679 13671//13671 13677//13677 -f 13672//13672 13673//13673 13680//13680 -f 13680//13680 13673//13673 13679//13679 -f 13674//13674 13672//13672 13681//13681 -f 13681//13681 13672//13672 13680//13680 -f 13675//13675 13674//13674 13682//13682 -f 13682//13682 13674//13674 13681//13681 -f 13676//13676 13675//13675 13678//13678 -f 13678//13678 13675//13675 13682//13682 -f 13682//13682 13681//13681 13678//13678 -f 13678//13678 13681//13681 13680//13680 -f 13678//13678 13680//13680 13677//13677 -f 13677//13677 13680//13680 13679//13679 -f 13683//13683 13684//13684 13006//13006 -f 13006//13006 13684//13684 13008//13008 -f 13008//13008 13684//13684 13685//13685 -f 13008//13008 13685//13685 13010//13010 -f 13010//13010 13685//13685 13686//13686 -f 13010//13010 13686//13686 13011//13011 -f 13011//13011 13686//13686 13003//13003 -f 13003//13003 13686//13686 13687//13687 -f 13003//13003 13687//13687 13000//13000 -f 13000//13000 13687//13687 13688//13688 -f 13000//13000 13688//13688 12998//12998 -f 12998//12998 13688//13688 13689//13689 -f 12998//12998 13689//13689 12996//12996 -f 12996//12996 13689//13689 12994//12994 -f 12994//12994 13689//13689 13690//13690 -f 12994//12994 13690//13690 12977//12977 -f 12977//12977 13690//13690 12978//12978 -f 12978//12978 13690//13690 13691//13691 -f 12978//12978 13691//13691 12991//12991 -f 13691//13691 13692//13692 12991//12991 -f 12991//12991 13692//13692 13693//13693 -f 12991//12991 13693//13693 12989//12989 -f 12989//12989 13693//13693 12986//12986 -f 12986//12986 13693//13693 13694//13694 -f 12986//12986 13694//13694 12984//12984 -f 12984//12984 13694//13694 12982//12982 -f 12982//12982 13694//13694 13695//13695 -f 12982//12982 13695//13695 12980//12980 -f 12980//12980 13695//13695 13696//13696 -f 12980//12980 13696//13696 12350//12350 -f 12350//12350 13696//13696 13697//13697 -f 12350//12350 13697//13697 12352//12352 -f 12352//12352 13697//13697 13698//13698 -f 12352//12352 13698//13698 12354//12354 -f 12354//12354 13698//13698 12355//12355 -f 12355//12355 13698//13698 13699//13699 -f 12355//12355 13699//13699 12357//12357 -f 12357//12357 13699//13699 13700//13700 -f 12357//12357 13700//13700 12358//12358 -f 12358//12358 13700//13700 13701//13701 -f 12358//12358 13701//13701 12340//12340 -f 12340//12340 13701//13701 13702//13702 -f 12340//12340 13702//13702 12341//12341 -f 12341//12341 13702//13702 12343//12343 -f 12343//12343 13702//13702 13703//13703 -f 12343//12343 13703//13703 12345//12345 -f 12345//12345 13703//13703 13704//13704 -f 12345//12345 13704//13704 12347//12347 -f 12347//12347 13704//13704 13705//13705 -f 12347//12347 13705//13705 12348//12348 -f 12348//12348 13705//13705 12336//12336 -f 12336//12336 13705//13705 13706//13706 -f 12336//12336 13706//13706 12337//12337 -f 12337//12337 13706//13706 13707//13707 -f 12337//12337 13707//13707 12338//12338 -f 12338//12338 13707//13707 12339//12339 -f 12339//12339 13707//13707 13708//13708 -f 12339//12339 13708//13708 12328//12328 -f 12328//12328 13708//13708 13709//13709 -f 12328//12328 13709//13709 12330//12330 -f 12330//12330 13709//13709 13710//13710 -f 12330//12330 13710//13710 12332//12332 -f 12332//12332 13710//13710 13711//13711 -f 12332//12332 13711//13711 12333//12333 -f 12333//12333 13711//13711 13712//13712 -f 12333//12333 13712//13712 12323//12323 -f 12323//12323 13712//13712 13713//13713 -f 12323//12323 13713//13713 12325//12325 -f 12325//12325 13713//13713 12326//12326 -f 12326//12326 13713//13713 13714//13714 -f 12326//12326 13714//13714 12974//12974 -f 13714//13714 13715//13715 12974//12974 -f 12974//12974 13715//13715 13716//13716 -f 12974//12974 13716//13716 12972//12972 -f 12972//12972 13716//13716 12969//12969 -f 12969//12969 13716//13716 13717//13717 -f 12969//12969 13717//13717 12967//12967 -f 12967//12967 13717//13717 13718//13718 -f 12967//12967 13718//13718 12965//12965 -f 12965//12965 13718//13718 13719//13719 -f 12965//12965 13719//13719 12963//12963 -f 12963//12963 13719//13719 12961//12961 -f 12961//12961 13719//13719 13720//13720 -f 12961//12961 13720//13720 12959//12959 -f 13720//13720 13721//13721 12959//12959 -f 12959//12959 13721//13721 13722//13722 -f 12959//12959 13722//13722 12957//12957 -f 12957//12957 13722//13722 13723//13723 -f 12957//12957 13723//13723 12956//12956 -f 12956//12956 13723//13723 13724//13724 -f 12956//12956 13724//13724 12954//12954 -f 12954//12954 13724//13724 13725//13725 -f 12954//12954 13725//13725 12944//12944 -f 12944//12944 13725//13725 13726//13726 -f 12944//12944 13726//13726 12946//12946 -f 12946//12946 13726//13726 13727//13727 -f 12946//12946 13727//13727 12948//12948 -f 12948//12948 13727//13727 13728//13728 -f 12948//12948 13728//13728 12950//12950 -f 12950//12950 13728//13728 13729//13729 -f 12950//12950 13729//13729 12951//12951 -f 12951//12951 13729//13729 13730//13730 -f 12951//12951 13730//13730 12318//12318 -f 12318//12318 13730//13730 13731//13731 -f 12318//12318 13731//13731 12316//12316 -f 12316//12316 13731//13731 13732//13732 -f 12316//12316 13732//13732 12314//12314 -f 12314//12314 13732//13732 13733//13733 -f 12314//12314 13733//13733 12312//12312 -f 12312//12312 13733//13733 13734//13734 -f 12312//12312 13734//13734 12310//12310 -f 12310//12310 13734//13734 13735//13735 -f 12310//12310 13735//13735 12308//12308 -f 12308//12308 13735//13735 13736//13736 -f 12308//12308 13736//13736 12284//12284 -f 12284//12284 13736//13736 13737//13737 -f 12284//12284 13737//13737 12285//12285 -f 12285//12285 13737//13737 13738//13738 -f 12285//12285 13738//13738 12305//12305 -f 12305//12305 13738//13738 13739//13739 -f 12305//12305 13739//13739 12304//12304 -f 12304//12304 13739//13739 13740//13740 -f 12304//12304 13740//13740 12302//12302 -f 12302//12302 13740//13740 13741//13741 -f 12302//12302 13741//13741 12299//12299 -f 12299//12299 13741//13741 13742//13742 -f 13743//13743 12295//12295 13742//13742 -f 13742//13742 12295//12295 12297//12297 -f 13742//13742 12297//12297 12299//12299 -f 13744//13744 12291//12291 13743//13743 -f 13743//13743 12291//12291 12293//12293 -f 13743//13743 12293//12293 12295//12295 -f 13745//13745 12287//12287 13744//13744 -f 13744//13744 12287//12287 12289//12289 -f 13744//13744 12289//12289 12291//12291 -f 13746//13746 12940//12940 13745//13745 -f 13745//13745 12940//12940 12942//12942 -f 13745//13745 12942//12942 12287//12287 -f 13747//13747 12930//12930 13748//13748 -f 13748//13748 12930//12930 12932//12932 -f 13748//13748 12932//12932 13749//13749 -f 13749//13749 12932//12932 12935//12935 -f 13749//13749 12935//12935 13746//13746 -f 13746//13746 12935//12935 12937//12937 -f 13746//13746 12937//12937 12940//12940 -f 13750//13750 12925//12925 13751//13751 -f 13751//13751 12925//12925 12926//12926 -f 13751//13751 12926//12926 13747//13747 -f 13747//13747 12926//12926 12928//12928 -f 13747//13747 12928//12928 12930//12930 -f 13752//13752 12917//12917 13753//13753 -f 13753//13753 12917//12917 12919//12919 -f 13753//13753 12919//12919 13750//13750 -f 13750//13750 12919//12919 12923//12923 -f 13750//13750 12923//12923 12925//12925 -f 13754//13754 12914//12914 13755//13755 -f 13755//13755 12914//12914 12920//12920 -f 13755//13755 12920//12920 13752//13752 -f 13752//13752 12920//12920 12915//12915 -f 13752//13752 12915//12915 12917//12917 -f 13756//13756 12278//12278 13757//13757 -f 13757//13757 12278//12278 12907//12907 -f 13757//13757 12907//12907 13758//13758 -f 13758//13758 12907//12907 12909//12909 -f 13758//13758 12909//12909 13759//13759 -f 13759//13759 12909//12909 12911//12911 -f 13759//13759 12911//12911 13754//13754 -f 13754//13754 12911//12911 12913//12913 -f 13754//13754 12913//12913 12914//12914 -f 12265//12265 12272//12272 13760//13760 -f 13760//13760 12272//12272 12274//12274 -f 13760//13760 12274//12274 13761//13761 -f 13761//13761 12274//12274 12283//12283 -f 13761//13761 12283//12283 13762//13762 -f 13762//13762 12283//12283 12282//12282 -f 13762//13762 12282//12282 13756//13756 -f 13756//13756 12282//12282 12280//12280 -f 13756//13756 12280//12280 12278//12278 -f 13760//13760 13763//13763 12265//12265 -f 12265//12265 13763//13763 13764//13764 -f 12265//12265 13764//13764 12266//12266 -f 12266//12266 13764//13764 13765//13765 -f 12266//12266 13765//13765 12268//12268 -f 12268//12268 13765//13765 13766//13766 -f 12268//12268 13766//13766 12269//12269 -f 12269//12269 13766//13766 13767//13767 -f 12269//12269 13767//13767 12249//12249 -f 12249//12249 13767//13767 13768//13768 -f 12249//12249 13768//13768 12251//12251 -f 12251//12251 13768//13768 13769//13769 -f 12251//12251 13769//13769 12253//12253 -f 12253//12253 13769//13769 13770//13770 -f 12253//12253 13770//13770 12255//12255 -f 12255//12255 13770//13770 13771//13771 -f 12263//12263 12264//12264 13772//13772 -f 13772//13772 12264//12264 12259//12259 -f 13772//13772 12259//12259 13771//13771 -f 13771//13771 12259//12259 12257//12257 -f 13771//13771 12257//12257 12255//12255 -f 12263//12263 13772//13772 12261//12261 -f 12261//12261 13772//13772 13773//13773 -f 12261//12261 13773//13773 12906//12906 -f 12906//12906 13773//13773 12904//12904 -f 12904//12904 13773//13773 13774//13774 -f 12904//12904 13774//13774 12902//12902 -f 12902//12902 13774//13774 13775//13775 -f 12902//12902 13775//13775 12900//12900 -f 12900//12900 13775//13775 13776//13776 -f 12900//12900 13776//13776 12898//12898 -f 12898//12898 13776//13776 12896//12896 -f 12896//12896 13776//13776 13777//13777 -f 12896//12896 13777//13777 12894//12894 -f 13777//13777 13778//13778 12894//12894 -f 12894//12894 13778//13778 13779//13779 -f 12894//12894 13779//13779 12892//12892 -f 12892//12892 13779//13779 13780//13780 -f 12892//12892 13780//13780 12890//12890 -f 12890//12890 13780//13780 12888//12888 -f 12888//12888 13780//13780 13781//13781 -f 12888//12888 13781//13781 12885//12885 -f 13781//13781 13782//13782 12885//12885 -f 12885//12885 13782//13782 13783//13783 -f 12885//12885 13783//13783 12884//12884 -f 12884//12884 13783//13783 13784//13784 -f 12884//12884 13784//13784 12882//12882 -f 12882//12882 13784//13784 13785//13785 -f 12882//12882 13785//13785 12880//12880 -f 12880//12880 13785//13785 13786//13786 -f 13787//13787 12246//12246 13788//13788 -f 13788//13788 12246//12246 12244//12244 -f 13788//13788 12244//12244 13789//13789 -f 13789//13789 12244//12244 12874//12874 -f 13789//13789 12874//12874 13790//13790 -f 13790//13790 12874//12874 12872//12872 -f 13790//13790 12872//12872 13791//13791 -f 13791//13791 12872//12872 12871//12871 -f 13791//13791 12871//12871 13786//13786 -f 13786//13786 12871//12871 12878//12878 -f 13786//13786 12878//12878 12880//12880 -f 13792//13792 12235//12235 13793//13793 -f 13793//13793 12235//12235 12236//12236 -f 13793//13793 12236//12236 13794//13794 -f 13794//13794 12236//12236 12238//12238 -f 13794//13794 12238//12238 13795//13795 -f 13795//13795 12238//12238 12240//12240 -f 13795//13795 12240//12240 13787//13787 -f 13787//13787 12240//12240 12247//12247 -f 13787//13787 12247//12247 12246//12246 -f 13796//13796 12231//12231 13792//13792 -f 13792//13792 12231//12231 12233//12233 -f 13792//13792 12233//12233 12235//12235 -f 13796//13796 13797//13797 12231//12231 -f 12231//12231 13797//13797 13670//13670 -f 12231//12231 13670//13670 12229//12229 -f 13006//13006 12364//12364 13683//13683 -f 13683//13683 12364//12364 12362//12362 -f 13683//13683 12362//12362 13798//13798 -f 13798//13798 12362//12362 12360//12360 -f 13798//13798 12360//12360 13799//13799 -f 13799//13799 12360//12360 12359//12359 -f 13799//13799 12359//12359 13800//13800 -f 13800//13800 12359//12359 12368//12368 -f 13800//13800 12368//12368 13801//13801 -f 13801//13801 12368//12368 12370//12370 -f 13801//13801 12370//12370 13802//13802 -f 12370//12370 12372//12372 13802//13802 -f 13802//13802 12372//12372 12375//12375 -f 13802//13802 12375//12375 13803//13803 -f 13803//13803 12375//12375 12377//12377 -f 13803//13803 12377//12377 13804//13804 -f 13804//13804 12396//12396 12398//12398 -f 13804//13804 12398//12398 13803//13803 -f 13803//13803 12398//12398 12400//12400 -f 13803//13803 12400//12400 13802//13802 -f 13802//13802 12400//12400 13801//13801 -f 13801//13801 12400//12400 12402//12402 -f 13801//13801 12402//12402 13800//13800 -f 13800//13800 12402//12402 12404//12404 -f 13800//13800 12404//12404 13799//13799 -f 13799//13799 12404//12404 12406//12406 -f 13799//13799 12406//12406 13798//13798 -f 12406//12406 12408//12408 13798//13798 -f 13798//13798 12408//12408 12410//12410 -f 13798//13798 12410//12410 13683//13683 -f 13683//13683 12410//12410 13046//13046 -f 13683//13683 13046//13046 13684//13684 -f 13684//13684 13046//13046 13044//13044 -f 13684//13684 13044//13044 13685//13685 -f 13685//13685 13044//13044 13042//13042 -f 13685//13685 13042//13042 13686//13686 -f 13042//13042 13040//13040 13686//13686 -f 13686//13686 13040//13040 13038//13038 -f 13686//13686 13038//13038 13687//13687 -f 13687//13687 13038//13038 13036//13036 -f 13687//13687 13036//13036 13688//13688 -f 13688//13688 13036//13036 13034//13034 -f 13688//13688 13034//13034 13689//13689 -f 13034//13034 13032//13032 13689//13689 -f 13689//13689 13032//13032 13030//13030 -f 13689//13689 13030//13030 13690//13690 -f 13030//13030 13028//13028 13690//13690 -f 13690//13690 13028//13028 13027//13027 -f 13690//13690 13027//13027 13691//13691 -f 13691//13691 13027//13027 13024//13024 -f 13691//13691 13024//13024 13692//13692 -f 13692//13692 13024//13024 13022//13022 -f 13692//13692 13022//13022 13693//13693 -f 13022//13022 13020//13020 13693//13693 -f 13693//13693 13020//13020 13018//13018 -f 13693//13693 13018//13018 13694//13694 -f 13694//13694 13018//13018 13017//13017 -f 13694//13694 13017//13017 13695//13695 -f 13695//13695 13017//13017 13014//13014 -f 13695//13695 13014//13014 13696//13696 -f 13014//13014 13016//13016 13696//13696 -f 13696//13696 13016//13016 12391//12391 -f 13696//13696 12391//12391 13697//13697 -f 13697//13697 12391//12391 12393//12393 -f 13697//13697 12393//12393 13698//13698 -f 13698//13698 12393//12393 12390//12390 -f 13698//13698 12390//12390 13699//13699 -f 13699//13699 12390//12390 12389//12389 -f 13699//13699 12389//12389 13700//13700 -f 13700//13700 12389//12389 12387//12387 -f 13700//13700 12387//12387 13701//13701 -f 13701//13701 12387//12387 12385//12385 -f 13701//13701 12385//12385 13702//13702 -f 13702//13702 12385//12385 12382//12382 -f 13702//13702 12382//12382 13703//13703 -f 13703//13703 12382//12382 12380//12380 -f 13710//13710 13709//13709 12371//12371 -f 12371//12371 13709//13709 12373//12373 -f 12373//12373 13709//13709 13708//13708 -f 12373//12373 13708//13708 12374//12374 -f 12374//12374 13708//13708 13707//13707 -f 12374//12374 13707//13707 12376//12376 -f 12376//12376 13707//13707 13706//13706 -f 12376//12376 13706//13706 12378//12378 -f 12378//12378 13706//13706 13705//13705 -f 12378//12378 13705//13705 12380//12380 -f 12380//12380 13705//13705 13704//13704 -f 12380//12380 13704//13704 13703//13703 -f 12371//12371 12369//12369 13710//13710 -f 13710//13710 12369//12369 12367//12367 -f 13710//13710 12367//12367 13711//13711 -f 13711//13711 12367//12367 12366//12366 -f 13711//13711 12366//12366 13712//13712 -f 13712//13712 12366//12366 12361//12361 -f 13712//13712 12361//12361 13713//13713 -f 12361//12361 12363//12363 13713//13713 -f 13713//13713 12363//12363 12365//12365 -f 13713//13713 12365//12365 13714//13714 -f 13714//13714 12365//12365 13005//13005 -f 13714//13714 13005//13005 13715//13715 -f 13005//13005 13007//13007 13715//13715 -f 13715//13715 13007//13007 13009//13009 -f 13715//13715 13009//13009 13716//13716 -f 13716//13716 13009//13009 13004//13004 -f 13716//13716 13004//13004 13717//13717 -f 13717//13717 13004//13004 13002//13002 -f 13717//13717 13002//13002 13718//13718 -f 13718//13718 13002//13002 13001//13001 -f 13718//13718 13001//13001 13719//13719 -f 13719//13719 13001//13001 12999//12999 -f 13719//13719 12999//12999 13720//13720 -f 13720//13720 12999//12999 12997//12997 -f 13720//13720 12997//12997 13721//13721 -f 13721//13721 12997//12997 12995//12995 -f 13721//13721 12995//12995 13722//13722 -f 13722//13722 12995//12995 12979//12979 -f 13722//13722 12979//12979 13723//13723 -f 13723//13723 12979//12979 12993//12993 -f 13723//13723 12993//12993 13724//13724 -f 12993//12993 12992//12992 13724//13724 -f 13724//13724 12992//12992 12990//12990 -f 13724//13724 12990//12990 13725//13725 -f 13725//13725 12990//12990 12988//12988 -f 13725//13725 12988//12988 13726//13726 -f 13726//13726 12988//12988 12987//12987 -f 13726//13726 12987//12987 13727//13727 -f 13727//13727 12987//12987 12985//12985 -f 13727//13727 12985//12985 13728//13728 -f 13728//13728 12985//12985 12983//12983 -f 13728//13728 12983//12983 13729//13729 -f 13729//13729 12983//12983 12981//12981 -f 13729//13729 12981//12981 13730//13730 -f 13730//13730 12981//12981 12349//12349 -f 13730//13730 12349//12349 13731//13731 -f 13731//13731 12349//12349 12351//12351 -f 13731//13731 12351//12351 13732//13732 -f 13732//13732 12351//12351 12353//12353 -f 13732//13732 12353//12353 13733//13733 -f 13733//13733 12353//12353 12356//12356 -f 13733//13733 12356//12356 13734//13734 -f 13734//13734 12356//12356 12342//12342 -f 12335//12335 13739//13739 13738//13738 -f 12335//12335 13738//13738 12346//12346 -f 12346//12346 13738//13738 13737//13737 -f 12346//12346 13737//13737 12344//12344 -f 12344//12344 13737//13737 13736//13736 -f 12344//12344 13736//13736 12342//12342 -f 12342//12342 13736//13736 13735//13735 -f 12342//12342 13735//13735 13734//13734 -f 13739//13739 12335//12335 13740//13740 -f 13740//13740 12335//12335 12334//12334 -f 13740//13740 12334//12334 13741//13741 -f 12334//12334 12327//12327 13741//13741 -f 13741//13741 12327//12327 12329//12329 -f 13741//13741 12329//12329 13742//13742 -f 13742//13742 12329//12329 12331//12331 -f 13742//13742 12331//12331 13743//13743 -f 13743//13743 12331//12331 12322//12322 -f 13743//13743 12322//12322 13744//13744 -f 12322//12322 12321//12321 13744//13744 -f 13744//13744 12321//12321 12324//12324 -f 13744//13744 12324//12324 13745//13745 -f 12973//12973 13746//13746 12975//12975 -f 12975//12975 13746//13746 13745//13745 -f 12975//12975 13745//13745 12976//12976 -f 12976//12976 13745//13745 12324//12324 -f 12973//12973 12971//12971 13746//13746 -f 13746//13746 12971//12971 12970//12970 -f 13746//13746 12970//12970 13749//13749 -f 12970//12970 12968//12968 13749//13749 -f 13749//13749 12968//12968 12966//12966 -f 13749//13749 12966//12966 13748//13748 -f 13748//13748 12966//12966 12964//12964 -f 13748//13748 12964//12964 13747//13747 -f 13747//13747 12964//12964 12962//12962 -f 13747//13747 12962//12962 13751//13751 -f 13751//13751 12962//12962 12960//12960 -f 13751//13751 12960//12960 13750//13750 -f 13750//13750 12960//12960 12958//12958 -f 13750//13750 12958//12958 13753//13753 -f 13753//13753 12958//12958 12955//12955 -f 13753//13753 12955//12955 13752//13752 -f 12955//12955 12953//12953 13752//13752 -f 13752//13752 12953//12953 12952//12952 -f 13752//13752 12952//12952 13755//13755 -f 13755//13755 12952//12952 12943//12943 -f 13755//13755 12943//12943 13754//13754 -f 12943//12943 12945//12945 13754//13754 -f 13754//13754 12945//12945 12947//12947 -f 13754//13754 12947//12947 13759//13759 -f 13759//13759 12947//12947 12949//12949 -f 13759//13759 12949//12949 13758//13758 -f 13758//13758 12949//12949 13757//13757 -f 13757//13757 12949//12949 12320//12320 -f 13757//13757 12320//12320 13756//13756 -f 13756//13756 12320//12320 12319//12319 -f 13756//13756 12319//12319 13762//13762 -f 13762//13762 12319//12319 12317//12317 -f 13762//13762 12317//12317 13761//13761 -f 12317//12317 12315//12315 13761//13761 -f 13761//13761 12315//12315 12313//12313 -f 13761//13761 12313//12313 13760//13760 -f 13760//13760 12313//12313 12311//12311 -f 13760//13760 12311//12311 13763//13763 -f 13763//13763 12311//12311 12309//12309 -f 13763//13763 12309//12309 13764//13764 -f 13764//13764 12309//12309 12286//12286 -f 13764//13764 12286//12286 13765//13765 -f 13765//13765 12286//12286 12307//12307 -f 13765//13765 12307//12307 13766//13766 -f 13766//13766 12307//12307 12306//12306 -f 13766//13766 12306//12306 13767//13767 -f 13767//13767 12306//12306 12303//12303 -f 13767//13767 12303//12303 13768//13768 -f 13768//13768 12303//12303 12301//12301 -f 13768//13768 12301//12301 13769//13769 -f 13769//13769 12301//12301 12300//12300 -f 13769//13769 12300//12300 13770//13770 -f 12300//12300 12298//12298 13770//13770 -f 13770//13770 12298//12298 12296//12296 -f 13770//13770 12296//12296 13771//13771 -f 12296//12296 12294//12294 13771//13771 -f 13771//13771 12294//12294 12292//12292 -f 13771//13771 12292//12292 13772//13772 -f 12292//12292 12290//12290 13772//13772 -f 13772//13772 12290//12290 12288//12288 -f 13772//13772 12288//12288 13773//13773 -f 13773//13773 12288//12288 12941//12941 -f 13773//13773 12941//12941 13774//13774 -f 13774//13774 12941//12941 12939//12939 -f 13774//13774 12939//12939 13775//13775 -f 13775//13775 12939//12939 12938//12938 -f 13775//13775 12938//12938 13776//13776 -f 13776//13776 12938//12938 12936//12936 -f 13776//13776 12936//12936 13777//13777 -f 12936//12936 12934//12934 13777//13777 -f 13777//13777 12934//12934 12933//12933 -f 13777//13777 12933//12933 13778//13778 -f 13778//13778 12933//12933 12931//12931 -f 13778//13778 12931//12931 13779//13779 -f 13779//13779 12931//12931 12929//12929 -f 13779//13779 12929//12929 13780//13780 -f 13780//13780 12929//12929 12927//12927 -f 13780//13780 12927//12927 13781//13781 -f 13781//13781 12927//12927 12924//12924 -f 13781//13781 12924//12924 13782//13782 -f 13782//13782 12924//12924 12918//12918 -f 13782//13782 12918//12918 13783//13783 -f 13783//13783 12918//12918 12916//12916 -f 13783//13783 12916//12916 13784//13784 -f 13784//13784 12916//12916 12922//12922 -f 13784//13784 12922//12922 13785//13785 -f 13785//13785 12922//12922 12921//12921 -f 13785//13785 12921//12921 13786//13786 -f 13786//13786 12921//12921 12912//12912 -f 13786//13786 12912//12912 13791//13791 -f 13791//13791 12912//12912 12910//12910 -f 13791//13791 12910//12910 13790//13790 -f 13790//13790 12910//12910 12908//12908 -f 13790//13790 12908//12908 13789//13789 -f 13789//13789 12908//12908 12277//12277 -f 13789//13789 12277//12277 13788//13788 -f 12277//12277 12279//12279 13788//13788 -f 13788//13788 12279//12279 12281//12281 -f 13788//13788 12281//12281 13787//13787 -f 13787//13787 12281//12281 12273//12273 -f 13787//13787 12273//12273 13795//13795 -f 13795//13795 12273//12273 13794//13794 -f 12273//12273 12275//12275 13794//13794 -f 13794//13794 12275//12275 12276//12276 -f 13794//13794 12276//12276 13793//13793 -f 13793//13793 12276//12276 12271//12271 -f 13793//13793 12271//12271 13792//13792 -f 13792//13792 12271//12271 12270//12270 -f 13792//13792 12270//12270 13796//13796 -f 13796//13796 12270//12270 12267//12267 -f 13796//13796 12267//12267 13797//13797 -f 13797//13797 12267//12267 12248//12248 -f 13797//13797 12248//12248 13670//13670 -f 13805//13805 13806//13806 13147//13147 -f 13147//13147 13806//13806 13149//13149 -f 13149//13149 13806//13806 13807//13807 -f 13149//13149 13807//13807 13151//13151 -f 13151//13151 13807//13807 13808//13808 -f 13151//13151 13808//13808 13152//13152 -f 13152//13152 13808//13808 13144//13144 -f 13144//13144 13808//13808 13809//13809 -f 13144//13144 13809//13809 13141//13141 -f 13141//13141 13809//13809 13810//13810 -f 13141//13141 13810//13810 13139//13139 -f 13139//13139 13810//13810 13811//13811 -f 13139//13139 13811//13811 13137//13137 -f 13137//13137 13811//13811 13135//13135 -f 13135//13135 13811//13811 13812//13812 -f 13135//13135 13812//13812 13118//13118 -f 13118//13118 13812//13812 13119//13119 -f 13119//13119 13812//13812 13813//13813 -f 13119//13119 13813//13813 13132//13132 -f 13813//13813 13814//13814 13132//13132 -f 13132//13132 13814//13814 13815//13815 -f 13132//13132 13815//13815 13130//13130 -f 13130//13130 13815//13815 13127//13127 -f 13127//13127 13815//13815 13816//13816 -f 13127//13127 13816//13816 13125//13125 -f 13125//13125 13816//13816 13123//13123 -f 13123//13123 13816//13816 13817//13817 -f 13123//13123 13817//13817 13121//13121 -f 13121//13121 13817//13817 13818//13818 -f 13121//13121 13818//13818 12498//12498 -f 12498//12498 13818//13818 13819//13819 -f 12498//12498 13819//13819 12500//12500 -f 12500//12500 13819//13819 13820//13820 -f 12500//12500 13820//13820 12502//12502 -f 12502//12502 13820//13820 12503//12503 -f 12503//12503 13820//13820 13821//13821 -f 12503//12503 13821//13821 12505//12505 -f 12505//12505 13821//13821 13822//13822 -f 12505//12505 13822//13822 12506//12506 -f 12506//12506 13822//13822 13823//13823 -f 12506//12506 13823//13823 12488//12488 -f 12488//12488 13823//13823 13824//13824 -f 12488//12488 13824//13824 12489//12489 -f 12489//12489 13824//13824 12491//12491 -f 12491//12491 13824//13824 13825//13825 -f 12491//12491 13825//13825 12493//12493 -f 12493//12493 13825//13825 13826//13826 -f 12493//12493 13826//13826 12495//12495 -f 12495//12495 13826//13826 13827//13827 -f 12495//12495 13827//13827 12496//12496 -f 12496//12496 13827//13827 12484//12484 -f 12484//12484 13827//13827 13828//13828 -f 12484//12484 13828//13828 12485//12485 -f 12485//12485 13828//13828 13829//13829 -f 12485//12485 13829//13829 12486//12486 -f 12486//12486 13829//13829 12487//12487 -f 12487//12487 13829//13829 13830//13830 -f 12487//12487 13830//13830 12476//12476 -f 12476//12476 13830//13830 13831//13831 -f 12476//12476 13831//13831 12478//12478 -f 12478//12478 13831//13831 13832//13832 -f 12478//12478 13832//13832 12480//12480 -f 12480//12480 13832//13832 13833//13833 -f 12480//12480 13833//13833 12481//12481 -f 12481//12481 13833//13833 13834//13834 -f 12481//12481 13834//13834 12471//12471 -f 12471//12471 13834//13834 13835//13835 -f 12471//12471 13835//13835 12473//12473 -f 12473//12473 13835//13835 12474//12474 -f 12474//12474 13835//13835 13836//13836 -f 12474//12474 13836//13836 13115//13115 -f 13836//13836 13837//13837 13115//13115 -f 13115//13115 13837//13837 13838//13838 -f 13115//13115 13838//13838 13113//13113 -f 13113//13113 13838//13838 13110//13110 -f 13110//13110 13838//13838 13839//13839 -f 13110//13110 13839//13839 13108//13108 -f 13108//13108 13839//13839 13840//13840 -f 13108//13108 13840//13840 13106//13106 -f 13106//13106 13840//13840 13841//13841 -f 13106//13106 13841//13841 13104//13104 -f 13104//13104 13841//13841 13102//13102 -f 13102//13102 13841//13841 13842//13842 -f 13102//13102 13842//13842 13100//13100 -f 13842//13842 13843//13843 13100//13100 -f 13100//13100 13843//13843 13844//13844 -f 13100//13100 13844//13844 13098//13098 -f 13098//13098 13844//13844 13845//13845 -f 13098//13098 13845//13845 13097//13097 -f 13097//13097 13845//13845 13846//13846 -f 13097//13097 13846//13846 13095//13095 -f 13095//13095 13846//13846 13847//13847 -f 13095//13095 13847//13847 13085//13085 -f 13085//13085 13847//13847 13848//13848 -f 13085//13085 13848//13848 13087//13087 -f 13087//13087 13848//13848 13849//13849 -f 13087//13087 13849//13849 13089//13089 -f 13089//13089 13849//13849 13850//13850 -f 13089//13089 13850//13850 13091//13091 -f 13091//13091 13850//13850 13851//13851 -f 13091//13091 13851//13851 13092//13092 -f 13092//13092 13851//13851 13852//13852 -f 13092//13092 13852//13852 12466//12466 -f 12466//12466 13852//13852 13853//13853 -f 12466//12466 13853//13853 12464//12464 -f 12464//12464 13853//13853 13854//13854 -f 12464//12464 13854//13854 12462//12462 -f 12462//12462 13854//13854 13855//13855 -f 12462//12462 13855//13855 12460//12460 -f 12460//12460 13855//13855 13856//13856 -f 12460//12460 13856//13856 12458//12458 -f 12458//12458 13856//13856 13857//13857 -f 12458//12458 13857//13857 12456//12456 -f 12456//12456 13857//13857 13858//13858 -f 12456//12456 13858//13858 12432//12432 -f 12432//12432 13858//13858 13859//13859 -f 12432//12432 13859//13859 12433//12433 -f 12433//12433 13859//13859 13860//13860 -f 12433//12433 13860//13860 12453//12453 -f 12453//12453 13860//13860 13861//13861 -f 12453//12453 13861//13861 12452//12452 -f 12452//12452 13861//13861 13862//13862 -f 12452//12452 13862//13862 12450//12450 -f 12450//12450 13862//13862 13863//13863 -f 12450//12450 13863//13863 12447//12447 -f 12447//12447 13863//13863 13864//13864 -f 13865//13865 12443//12443 13864//13864 -f 13864//13864 12443//12443 12445//12445 -f 13864//13864 12445//12445 12447//12447 -f 13866//13866 12439//12439 13865//13865 -f 13865//13865 12439//12439 12441//12441 -f 13865//13865 12441//12441 12443//12443 -f 13867//13867 12435//12435 13866//13866 -f 13866//13866 12435//12435 12437//12437 -f 13866//13866 12437//12437 12439//12439 -f 13868//13868 13081//13081 13867//13867 -f 13867//13867 13081//13081 13083//13083 -f 13867//13867 13083//13083 12435//12435 -f 13869//13869 13071//13071 13870//13870 -f 13870//13870 13071//13071 13073//13073 -f 13870//13870 13073//13073 13871//13871 -f 13871//13871 13073//13073 13076//13076 -f 13871//13871 13076//13076 13868//13868 -f 13868//13868 13076//13076 13078//13078 -f 13868//13868 13078//13078 13081//13081 -f 13872//13872 13066//13066 13873//13873 -f 13873//13873 13066//13066 13067//13067 -f 13873//13873 13067//13067 13869//13869 -f 13869//13869 13067//13067 13069//13069 -f 13869//13869 13069//13069 13071//13071 -f 13874//13874 13058//13058 13875//13875 -f 13875//13875 13058//13058 13060//13060 -f 13875//13875 13060//13060 13872//13872 -f 13872//13872 13060//13060 13064//13064 -f 13872//13872 13064//13064 13066//13066 -f 13876//13876 13055//13055 13877//13877 -f 13877//13877 13055//13055 13061//13061 -f 13877//13877 13061//13061 13874//13874 -f 13874//13874 13061//13061 13056//13056 -f 13874//13874 13056//13056 13058//13058 -f 13878//13878 12426//12426 13879//13879 -f 13879//13879 12426//12426 13048//13048 -f 13879//13879 13048//13048 13880//13880 -f 13880//13880 13048//13048 13050//13050 -f 13880//13880 13050//13050 13881//13881 -f 13881//13881 13050//13050 13052//13052 -f 13881//13881 13052//13052 13876//13876 -f 13876//13876 13052//13052 13054//13054 -f 13876//13876 13054//13054 13055//13055 -f 12413//12413 12420//12420 13882//13882 -f 13882//13882 12420//12420 12422//12422 -f 13882//13882 12422//12422 13883//13883 -f 13883//13883 12422//12422 12431//12431 -f 13883//13883 12431//12431 13884//13884 -f 13884//13884 12431//12431 12430//12430 -f 13884//13884 12430//12430 13878//13878 -f 13878//13878 12430//12430 12428//12428 -f 13878//13878 12428//12428 12426//12426 -f 13882//13882 13885//13885 12413//12413 -f 12413//12413 13885//13885 13886//13886 -f 12413//12413 13886//13886 12414//12414 -f 12414//12414 13886//13886 13887//13887 -f 12414//12414 13887//13887 12416//12416 -f 12416//12416 13887//13887 13888//13888 -f 12416//12416 13888//13888 12417//12417 -f 12417//12417 13888//13888 13889//13889 -f 12417//12417 13889//13889 12397//12397 -f 12397//12397 13889//13889 13890//13890 -f 12397//12397 13890//13890 12399//12399 -f 12399//12399 13890//13890 13891//13891 -f 12399//12399 13891//13891 12401//12401 -f 12401//12401 13891//13891 13892//13892 -f 12401//12401 13892//13892 12403//12403 -f 12403//12403 13892//13892 13893//13893 -f 12411//12411 12412//12412 13894//13894 -f 13894//13894 12412//12412 12407//12407 -f 13894//13894 12407//12407 13893//13893 -f 13893//13893 12407//12407 12405//12405 -f 13893//13893 12405//12405 12403//12403 -f 12411//12411 13894//13894 12409//12409 -f 12409//12409 13894//13894 13895//13895 -f 12409//12409 13895//13895 13047//13047 -f 13047//13047 13895//13895 13045//13045 -f 13045//13045 13895//13895 13896//13896 -f 13045//13045 13896//13896 13043//13043 -f 13043//13043 13896//13896 13897//13897 -f 13043//13043 13897//13897 13041//13041 -f 13041//13041 13897//13897 13898//13898 -f 13041//13041 13898//13898 13039//13039 -f 13039//13039 13898//13898 13037//13037 -f 13037//13037 13898//13898 13899//13899 -f 13037//13037 13899//13899 13035//13035 -f 13899//13899 13900//13900 13035//13035 -f 13035//13035 13900//13900 13901//13901 -f 13035//13035 13901//13901 13033//13033 -f 13033//13033 13901//13901 13902//13902 -f 13033//13033 13902//13902 13031//13031 -f 13031//13031 13902//13902 13029//13029 -f 13029//13029 13902//13902 13903//13903 -f 13029//13029 13903//13903 13026//13026 -f 13903//13903 13904//13904 13026//13026 -f 13026//13026 13904//13904 13905//13905 -f 13026//13026 13905//13905 13025//13025 -f 13025//13025 13905//13905 13906//13906 -f 13025//13025 13906//13906 13023//13023 -f 13023//13023 13906//13906 13907//13907 -f 13023//13023 13907//13907 13021//13021 -f 13021//13021 13907//13907 13908//13908 -f 13909//13909 12394//12394 13910//13910 -f 13910//13910 12394//12394 12392//12392 -f 13910//13910 12392//12392 13911//13911 -f 13911//13911 12392//12392 13015//13015 -f 13911//13911 13015//13015 13912//13912 -f 13912//13912 13015//13015 13013//13013 -f 13912//13912 13013//13013 13913//13913 -f 13913//13913 13013//13013 13012//13012 -f 13913//13913 13012//13012 13908//13908 -f 13908//13908 13012//13012 13019//13019 -f 13908//13908 13019//13019 13021//13021 -f 13914//13914 12383//12383 13915//13915 -f 13915//13915 12383//12383 12384//12384 -f 13915//13915 12384//12384 13916//13916 -f 13916//13916 12384//12384 12386//12386 -f 13916//13916 12386//12386 13917//13917 -f 13917//13917 12386//12386 12388//12388 -f 13917//13917 12388//12388 13909//13909 -f 13909//13909 12388//12388 12395//12395 -f 13909//13909 12395//12395 12394//12394 -f 13918//13918 12379//12379 13914//13914 -f 13914//13914 12379//12379 12381//12381 -f 13914//13914 12381//12381 12383//12383 -f 13918//13918 13919//13919 12379//12379 -f 12379//12379 13919//13919 13804//13804 -f 12379//12379 13804//13804 12377//12377 -f 13147//13147 12515//12515 13805//13805 -f 13805//13805 12515//12515 12513//12513 -f 13805//13805 12513//12513 13920//13920 -f 13920//13920 12513//12513 12511//12511 -f 13920//13920 12511//12511 13921//13921 -f 13921//13921 12511//12511 12510//12510 -f 13921//13921 12510//12510 13922//13922 -f 13922//13922 12510//12510 12519//12519 -f 13922//13922 12519//12519 13923//13923 -f 13923//13923 12519//12519 12521//12521 -f 13923//13923 12521//12521 13924//13924 -f 12521//12521 12523//12523 13924//13924 -f 13924//13924 12523//12523 12526//12526 -f 13924//13924 12526//12526 13925//13925 -f 13925//13925 12526//12526 12528//12528 -f 13925//13925 12528//12528 13926//13926 -f 13926//13926 12564//12564 12566//12566 -f 13926//13926 12566//12566 13925//13925 -f 13925//13925 12566//12566 12545//12545 -f 13925//13925 12545//12545 13924//13924 -f 13924//13924 12545//12545 13923//13923 -f 13923//13923 12545//12545 12547//12547 -f 13923//13923 12547//12547 13922//13922 -f 13922//13922 12547//12547 12549//12549 -f 13922//13922 12549//12549 13921//13921 -f 13921//13921 12549//12549 12555//12555 -f 13921//13921 12555//12555 13920//13920 -f 12555//12555 12553//12553 13920//13920 -f 13920//13920 12553//12553 12551//12551 -f 13920//13920 12551//12551 13805//13805 -f 13805//13805 12551//12551 13179//13179 -f 13805//13805 13179//13179 13806//13806 -f 13806//13806 13179//13179 13181//13181 -f 13806//13806 13181//13181 13807//13807 -f 13807//13807 13181//13181 13183//13183 -f 13807//13807 13183//13183 13808//13808 -f 13183//13183 13185//13185 13808//13808 -f 13808//13808 13185//13185 13187//13187 -f 13808//13808 13187//13187 13809//13809 -f 13809//13809 13187//13187 13177//13177 -f 13809//13809 13177//13177 13810//13810 -f 13810//13810 13177//13177 13175//13175 -f 13810//13810 13175//13175 13811//13811 -f 13175//13175 13174//13174 13811//13811 -f 13811//13811 13174//13174 13172//13172 -f 13811//13811 13172//13172 13812//13812 -f 13172//13172 13170//13170 13812//13812 -f 13812//13812 13170//13170 13168//13168 -f 13812//13812 13168//13168 13813//13813 -f 13813//13813 13168//13168 13165//13165 -f 13813//13813 13165//13165 13814//13814 -f 13814//13814 13165//13165 13163//13163 -f 13814//13814 13163//13163 13815//13815 -f 13163//13163 13161//13161 13815//13815 -f 13815//13815 13161//13161 13159//13159 -f 13815//13815 13159//13159 13816//13816 -f 13816//13816 13159//13159 13158//13158 -f 13816//13816 13158//13158 13817//13817 -f 13817//13817 13158//13158 13155//13155 -f 13817//13817 13155//13155 13818//13818 -f 13155//13155 13157//13157 13818//13818 -f 13818//13818 13157//13157 12540//12540 -f 13818//13818 12540//12540 13819//13819 -f 13819//13819 12540//12540 12539//12539 -f 13819//13819 12539//12539 13820//13820 -f 13820//13820 12539//12539 12508//12508 -f 13820//13820 12508//12508 13821//13821 -f 13821//13821 12508//12508 12507//12507 -f 13821//13821 12507//12507 13822//13822 -f 13822//13822 12507//12507 12538//12538 -f 13822//13822 12538//12538 13823//13823 -f 13823//13823 12538//12538 12537//12537 -f 13823//13823 12537//12537 13824//13824 -f 13824//13824 12537//12537 12533//12533 -f 13824//13824 12533//12533 13825//13825 -f 13825//13825 12533//12533 12531//12531 -f 13832//13832 13831//13831 12522//12522 -f 12522//12522 13831//13831 12524//12524 -f 12524//12524 13831//13831 13830//13830 -f 12524//12524 13830//13830 12525//12525 -f 12525//12525 13830//13830 13829//13829 -f 12525//12525 13829//13829 12527//12527 -f 12527//12527 13829//13829 13828//13828 -f 12527//12527 13828//13828 12529//12529 -f 12529//12529 13828//13828 13827//13827 -f 12529//12529 13827//13827 12531//12531 -f 12531//12531 13827//13827 13826//13826 -f 12531//12531 13826//13826 13825//13825 -f 12522//12522 12520//12520 13832//13832 -f 13832//13832 12520//12520 12518//12518 -f 13832//13832 12518//12518 13833//13833 -f 13833//13833 12518//12518 12517//12517 -f 13833//13833 12517//12517 13834//13834 -f 13834//13834 12517//12517 12512//12512 -f 13834//13834 12512//12512 13835//13835 -f 12512//12512 12514//12514 13835//13835 -f 13835//13835 12514//12514 12516//12516 -f 13835//13835 12516//12516 13836//13836 -f 13836//13836 12516//12516 13146//13146 -f 13836//13836 13146//13146 13837//13837 -f 13146//13146 13148//13148 13837//13837 -f 13837//13837 13148//13148 13150//13150 -f 13837//13837 13150//13150 13838//13838 -f 13838//13838 13150//13150 13145//13145 -f 13838//13838 13145//13145 13839//13839 -f 13839//13839 13145//13145 13143//13143 -f 13839//13839 13143//13143 13840//13840 -f 13840//13840 13143//13143 13142//13142 -f 13840//13840 13142//13142 13841//13841 -f 13841//13841 13142//13142 13140//13140 -f 13841//13841 13140//13140 13842//13842 -f 13842//13842 13140//13140 13138//13138 -f 13842//13842 13138//13138 13843//13843 -f 13843//13843 13138//13138 13136//13136 -f 13843//13843 13136//13136 13844//13844 -f 13844//13844 13136//13136 13120//13120 -f 13844//13844 13120//13120 13845//13845 -f 13845//13845 13120//13120 13134//13134 -f 13845//13845 13134//13134 13846//13846 -f 13134//13134 13133//13133 13846//13846 -f 13846//13846 13133//13133 13131//13131 -f 13846//13846 13131//13131 13847//13847 -f 13847//13847 13131//13131 13129//13129 -f 13847//13847 13129//13129 13848//13848 -f 13848//13848 13129//13129 13128//13128 -f 13848//13848 13128//13128 13849//13849 -f 13849//13849 13128//13128 13126//13126 -f 13849//13849 13126//13126 13850//13850 -f 13850//13850 13126//13126 13124//13124 -f 13850//13850 13124//13124 13851//13851 -f 13851//13851 13124//13124 13122//13122 -f 13851//13851 13122//13122 13852//13852 -f 13852//13852 13122//13122 12497//12497 -f 13852//13852 12497//12497 13853//13853 -f 13853//13853 12497//12497 12499//12499 -f 13853//13853 12499//12499 13854//13854 -f 13854//13854 12499//12499 12501//12501 -f 13854//13854 12501//12501 13855//13855 -f 13855//13855 12501//12501 12504//12504 -f 13855//13855 12504//12504 13856//13856 -f 13856//13856 12504//12504 12490//12490 -f 12483//12483 13861//13861 13860//13860 -f 12483//12483 13860//13860 12494//12494 -f 12494//12494 13860//13860 13859//13859 -f 12494//12494 13859//13859 12492//12492 -f 12492//12492 13859//13859 13858//13858 -f 12492//12492 13858//13858 12490//12490 -f 12490//12490 13858//13858 13857//13857 -f 12490//12490 13857//13857 13856//13856 -f 13861//13861 12483//12483 13862//13862 -f 13862//13862 12483//12483 12482//12482 -f 13862//13862 12482//12482 13863//13863 -f 12482//12482 12475//12475 13863//13863 -f 13863//13863 12475//12475 12477//12477 -f 13863//13863 12477//12477 13864//13864 -f 13864//13864 12477//12477 12479//12479 -f 13864//13864 12479//12479 13865//13865 -f 13865//13865 12479//12479 12470//12470 -f 13865//13865 12470//12470 13866//13866 -f 12470//12470 12469//12469 13866//13866 -f 13866//13866 12469//12469 12472//12472 -f 13866//13866 12472//12472 13867//13867 -f 13114//13114 13868//13868 13116//13116 -f 13116//13116 13868//13868 13867//13867 -f 13116//13116 13867//13867 13117//13117 -f 13117//13117 13867//13867 12472//12472 -f 13114//13114 13112//13112 13868//13868 -f 13868//13868 13112//13112 13111//13111 -f 13868//13868 13111//13111 13871//13871 -f 13111//13111 13109//13109 13871//13871 -f 13871//13871 13109//13109 13107//13107 -f 13871//13871 13107//13107 13870//13870 -f 13870//13870 13107//13107 13105//13105 -f 13870//13870 13105//13105 13869//13869 -f 13869//13869 13105//13105 13103//13103 -f 13869//13869 13103//13103 13873//13873 -f 13873//13873 13103//13103 13101//13101 -f 13873//13873 13101//13101 13872//13872 -f 13872//13872 13101//13101 13099//13099 -f 13872//13872 13099//13099 13875//13875 -f 13875//13875 13099//13099 13096//13096 -f 13875//13875 13096//13096 13874//13874 -f 13096//13096 13094//13094 13874//13874 -f 13874//13874 13094//13094 13093//13093 -f 13874//13874 13093//13093 13877//13877 -f 13877//13877 13093//13093 13084//13084 -f 13877//13877 13084//13084 13876//13876 -f 13084//13084 13086//13086 13876//13876 -f 13876//13876 13086//13086 13088//13088 -f 13876//13876 13088//13088 13881//13881 -f 13881//13881 13088//13088 13090//13090 -f 13881//13881 13090//13090 13880//13880 -f 13880//13880 13090//13090 13879//13879 -f 13879//13879 13090//13090 12468//12468 -f 13879//13879 12468//12468 13878//13878 -f 13878//13878 12468//12468 12467//12467 -f 13878//13878 12467//12467 13884//13884 -f 13884//13884 12467//12467 12465//12465 -f 13884//13884 12465//12465 13883//13883 -f 12465//12465 12463//12463 13883//13883 -f 13883//13883 12463//12463 12461//12461 -f 13883//13883 12461//12461 13882//13882 -f 13882//13882 12461//12461 12459//12459 -f 13882//13882 12459//12459 13885//13885 -f 13885//13885 12459//12459 12457//12457 -f 13885//13885 12457//12457 13886//13886 -f 13886//13886 12457//12457 12434//12434 -f 13886//13886 12434//12434 13887//13887 -f 13887//13887 12434//12434 12455//12455 -f 13887//13887 12455//12455 13888//13888 -f 13888//13888 12455//12455 12454//12454 -f 13888//13888 12454//12454 13889//13889 -f 13889//13889 12454//12454 12451//12451 -f 13889//13889 12451//12451 13890//13890 -f 13890//13890 12451//12451 12449//12449 -f 13890//13890 12449//12449 13891//13891 -f 13891//13891 12449//12449 12448//12448 -f 13891//13891 12448//12448 13892//13892 -f 12448//12448 12446//12446 13892//13892 -f 13892//13892 12446//12446 12444//12444 -f 13892//13892 12444//12444 13893//13893 -f 12444//12444 12442//12442 13893//13893 -f 13893//13893 12442//12442 12440//12440 -f 13893//13893 12440//12440 13894//13894 -f 12440//12440 12438//12438 13894//13894 -f 13894//13894 12438//12438 12436//12436 -f 13894//13894 12436//12436 13895//13895 -f 13895//13895 12436//12436 13082//13082 -f 13895//13895 13082//13082 13896//13896 -f 13896//13896 13082//13082 13080//13080 -f 13896//13896 13080//13080 13897//13897 -f 13897//13897 13080//13080 13079//13079 -f 13897//13897 13079//13079 13898//13898 -f 13898//13898 13079//13079 13077//13077 -f 13898//13898 13077//13077 13899//13899 -f 13077//13077 13075//13075 13899//13899 -f 13899//13899 13075//13075 13074//13074 -f 13899//13899 13074//13074 13900//13900 -f 13900//13900 13074//13074 13072//13072 -f 13900//13900 13072//13072 13901//13901 -f 13901//13901 13072//13072 13070//13070 -f 13901//13901 13070//13070 13902//13902 -f 13902//13902 13070//13070 13068//13068 -f 13902//13902 13068//13068 13903//13903 -f 13903//13903 13068//13068 13065//13065 -f 13903//13903 13065//13065 13904//13904 -f 13904//13904 13065//13065 13059//13059 -f 13904//13904 13059//13059 13905//13905 -f 13905//13905 13059//13059 13057//13057 -f 13905//13905 13057//13057 13906//13906 -f 13906//13906 13057//13057 13063//13063 -f 13906//13906 13063//13063 13907//13907 -f 13907//13907 13063//13063 13062//13062 -f 13907//13907 13062//13062 13908//13908 -f 13908//13908 13062//13062 13053//13053 -f 13908//13908 13053//13053 13913//13913 -f 13913//13913 13053//13053 13051//13051 -f 13913//13913 13051//13051 13912//13912 -f 13912//13912 13051//13051 13049//13049 -f 13912//13912 13049//13049 13911//13911 -f 13911//13911 13049//13049 12425//12425 -f 13911//13911 12425//12425 13910//13910 -f 12425//12425 12427//12427 13910//13910 -f 13910//13910 12427//12427 12429//12429 -f 13910//13910 12429//12429 13909//13909 -f 13909//13909 12429//12429 12421//12421 -f 13909//13909 12421//12421 13917//13917 -f 13917//13917 12421//12421 13916//13916 -f 12421//12421 12423//12423 13916//13916 -f 13916//13916 12423//12423 12424//12424 -f 13916//13916 12424//12424 13915//13915 -f 13915//13915 12424//12424 12419//12419 -f 13915//13915 12419//12419 13914//13914 -f 13914//13914 12419//12419 12418//12418 -f 13914//13914 12418//12418 13918//13918 -f 13918//13918 12418//12418 12415//12415 -f 13918//13918 12415//12415 13919//13919 -f 13919//13919 12415//12415 12396//12396 -f 13919//13919 12396//12396 13804//13804 -f 13216//13216 13215//13215 13927//13927 -f 13928//13928 13929//13929 12663//12663 -f 12663//12663 13929//13929 13930//13930 -f 12663//12663 13930//13930 12661//12661 -f 12661//12661 13930//13930 13931//13931 -f 12661//12661 13931//13931 13300//13300 -f 13300//13300 13931//13931 13932//13932 -f 13300//13300 13932//13932 13298//13298 -f 13298//13298 13932//13932 13933//13933 -f 13934//13934 13294//13294 13933//13933 -f 13933//13933 13294//13294 13296//13296 -f 13933//13933 13296//13296 13298//13298 -f 13935//13935 13289//13289 13936//13936 -f 13936//13936 13289//13289 13288//13288 -f 13936//13936 13288//13288 13937//13937 -f 13937//13937 13288//13288 13286//13286 -f 13937//13937 13286//13286 13938//13938 -f 13938//13938 13286//13286 13285//13285 -f 13938//13938 13285//13285 13934//13934 -f 13934//13934 13285//13285 13292//13292 -f 13934//13934 13292//13292 13294//13294 -f 13939//13939 13270//13270 13940//13940 -f 13940//13940 13270//13270 13272//13272 -f 13940//13940 13272//13272 13941//13941 -f 13941//13941 13272//13272 13274//13274 -f 13941//13941 13274//13274 13942//13942 -f 13942//13942 13274//13274 13277//13277 -f 13942//13942 13277//13277 13943//13943 -f 13943//13943 13277//13277 13279//13279 -f 13943//13943 13279//13279 13944//13944 -f 13944//13944 13279//13279 13280//13280 -f 13944//13944 13280//13280 13935//13935 -f 13935//13935 13280//13280 13282//13282 -f 13935//13935 13282//13282 13289//13289 -f 12660//12660 12659//12659 13945//13945 -f 13945//13945 12659//12659 12657//12657 -f 13945//13945 12657//12657 13939//13939 -f 13939//13939 12657//12657 13268//13268 -f 13939//13939 13268//13268 13270//13270 -f 12660//12660 13945//13945 12654//12654 -f 12654//12654 13945//13945 13946//13946 -f 12654//12654 13946//13946 12655//12655 -f 13947//13947 12643//12643 13946//13946 -f 13946//13946 12643//12643 12642//12642 -f 13946//13946 12642//12642 12655//12655 -f 13948//13948 12648//12648 13949//13949 -f 13949//13949 12648//12648 12647//12647 -f 13949//13949 12647//12647 13947//13947 -f 13947//13947 12647//12647 12645//12645 -f 13947//13947 12645//12645 12643//12643 -f 12641//12641 12640//12640 13950//13950 -f 13950//13950 12640//12640 12639//12639 -f 13950//13950 12639//12639 13951//13951 -f 13951//13951 12639//12639 12638//12638 -f 13951//13951 12638//12638 13952//13952 -f 13952//13952 12638//12638 12651//12651 -f 13952//13952 12651//12651 13948//13948 -f 13948//13948 12651//12651 12650//12650 -f 13948//13948 12650//12650 12648//12648 -f 12641//12641 13950//13950 12630//12630 -f 12630//12630 13950//13950 13953//13953 -f 12630//12630 13953//13953 12631//12631 -f 12631//12631 13953//13953 13954//13954 -f 12631//12631 13954//13954 12632//12632 -f 12632//12632 13954//13954 13955//13955 -f 12632//12632 13955//13955 12634//12634 -f 12634//12634 13955//13955 13956//13956 -f 12634//12634 13956//13956 12635//12635 -f 12635//12635 13956//13956 12624//12624 -f 12624//12624 13956//13956 13957//13957 -f 12624//12624 13957//13957 12626//12626 -f 12626//12626 13957//13957 12627//12627 -f 12627//12627 13957//13957 13958//13958 -f 12627//12627 13958//13958 13265//13265 -f 13265//13265 13958//13958 13251//13251 -f 13251//13251 13958//13958 13959//13959 -f 13251//13251 13959//13959 13252//13252 -f 13252//13252 13959//13959 13960//13960 -f 13252//13252 13960//13960 13254//13254 -f 13254//13254 13960//13960 13961//13961 -f 13254//13254 13961//13961 13255//13255 -f 13255//13255 13961//13961 13962//13962 -f 13255//13255 13962//13962 13257//13257 -f 13257//13257 13962//13962 13259//13259 -f 13259//13259 13962//13962 13963//13963 -f 13259//13259 13963//13963 13261//13261 -f 13261//13261 13963//13963 13964//13964 -f 13261//13261 13964//13964 13263//13263 -f 13263//13263 13964//13964 13965//13965 -f 13263//13263 13965//13965 13264//13264 -f 13264//13264 13965//13965 13248//13248 -f 13248//13248 13965//13965 13966//13966 -f 13248//13248 13966//13966 13249//13249 -f 13249//13249 13966//13966 13967//13967 -f 13249//13249 13967//13967 13244//13244 -f 13244//13244 13967//13967 13968//13968 -f 13244//13244 13968//13968 13242//13242 -f 13242//13242 13968//13968 13969//13969 -f 13242//13242 13969//13969 13240//13240 -f 13970//13970 13236//13236 13969//13969 -f 13969//13969 13236//13236 13238//13238 -f 13969//13969 13238//13238 13240//13240 -f 13971//13971 12617//12617 13972//13972 -f 13972//13972 12617//12617 12619//12619 -f 13972//13972 12619//12619 13973//13973 -f 13973//13973 12619//12619 13231//13231 -f 13973//13973 13231//13231 13974//13974 -f 13974//13974 13231//13231 13233//13233 -f 13974//13974 13233//13233 13970//13970 -f 13970//13970 13233//13233 13234//13234 -f 13970//13970 13234//13234 13236//13236 -f 13975//13975 12608//12608 13976//13976 -f 13976//13976 12608//12608 12610//12610 -f 13976//13976 12610//12610 13977//13977 -f 13977//13977 12610//12610 12612//12612 -f 13977//13977 12612//12612 13978//13978 -f 13978//13978 12612//12612 12614//12614 -f 13978//13978 12614//12614 13971//13971 -f 13971//13971 12614//12614 12615//12615 -f 13971//13971 12615//12615 12617//12617 -f 13979//13979 12585//12585 13975//13975 -f 13975//13975 12585//12585 12584//12584 -f 13975//13975 12584//12584 12608//12608 -f 13980//13980 12603//12603 13979//13979 -f 13979//13979 12603//12603 12605//12605 -f 13979//13979 12605//12605 12585//12585 -f 13981//13981 12589//12589 13980//13980 -f 13980//13980 12589//12589 12588//12588 -f 13980//13980 12588//12588 12603//12603 -f 13982//13982 13223//13223 13983//13983 -f 13983//13983 13223//13223 13221//13221 -f 13983//13983 13221//13221 13984//13984 -f 13984//13984 13221//13221 12590//12590 -f 13984//13984 12590//12590 13985//13985 -f 13985//13985 12590//12590 12592//12592 -f 13985//13985 12592//12592 13986//13986 -f 13986//13986 12592//12592 12594//12594 -f 13986//13986 12594//12594 13987//13987 -f 13987//13987 12594//12594 12596//12596 -f 13987//13987 12596//12596 13988//13988 -f 13988//13988 12596//12596 12598//12598 -f 13988//13988 12598//12598 13981//13981 -f 13981//13981 12598//12598 12600//12600 -f 13981//13981 12600//12600 12589//12589 -f 13215//13215 13213//13213 13927//13927 -f 13927//13927 13213//13213 13211//13211 -f 13927//13927 13211//13211 13989//13989 -f 13989//13989 13211//13211 13230//13230 -f 13989//13989 13230//13230 13990//13990 -f 13990//13990 13230//13230 13229//13229 -f 13990//13990 13229//13229 13991//13991 -f 13991//13991 13229//13229 13227//13227 -f 13991//13991 13227//13227 13982//13982 -f 13982//13982 13227//13227 13225//13225 -f 13982//13982 13225//13225 13223//13223 -f 13216//13216 13927//13927 13218//13218 -f 13218//13218 13927//13927 13992//13992 -f 13218//13218 13992//13992 13219//13219 -f 13219//13219 13992//13992 13207//13207 -f 13207//13207 13992//13992 13993//13993 -f 13207//13207 13993//13993 13208//13208 -f 13208//13208 13993//13993 13200//13200 -f 13200//13200 13993//13993 13994//13994 -f 13200//13200 13994//13994 13202//13202 -f 13202//13202 13994//13994 13204//13204 -f 13204//13204 13994//13994 13995//13995 -f 13204//13204 13995//13995 13205//13205 -f 13205//13205 13995//13995 13996//13996 -f 13205//13205 13996//13996 13194//13194 -f 13194//13194 13996//13996 13196//13196 -f 13196//13196 13996//13996 13997//13997 -f 13196//13196 13997//13997 13198//13198 -f 13198//13198 13997//13997 13998//13998 -f 13198//13198 13998//13998 13192//13192 -f 13192//13192 13998//13998 13999//13999 -f 13192//13192 13999//13999 13190//13190 -f 13190//13190 13999//13999 14000//14000 -f 13190//13190 14000//14000 12583//12583 -f 12583//12583 14000//14000 12581//12581 -f 12581//12581 14000//14000 14001//14001 -f 12581//12581 14001//14001 12578//12578 -f 12578//12578 14001//14001 14002//14002 -f 12578//12578 14002//14002 12577//12577 -f 12577//12577 14002//14002 12575//12575 -f 12575//12575 14002//14002 14003//14003 -f 12575//12575 14003//14003 12573//12573 -f 14004//14004 12563//12563 14005//14005 -f 14005//14005 12563//12563 12561//12561 -f 14005//14005 12561//12561 14006//14006 -f 14006//14006 12561//12561 12559//12559 -f 14006//14006 12559//12559 14007//14007 -f 14007//14007 12559//12559 12558//12558 -f 14007//14007 12558//12558 14003//14003 -f 14003//14003 12558//12558 12571//12571 -f 14003//14003 12571//12571 12573//12573 -f 12552//12552 12554//12554 14008//14008 -f 14008//14008 12554//12554 12556//12556 -f 14008//14008 12556//12556 14009//14009 -f 14009//14009 12556//12556 12557//12557 -f 14009//14009 12557//12557 14010//14010 -f 14010//14010 12557//12557 12548//12548 -f 14010//14010 12548//12548 14011//14011 -f 14011//14011 12548//12548 12546//12546 -f 14011//14011 12546//12546 14012//14012 -f 14012//14012 12546//12546 12568//12568 -f 14012//14012 12568//12568 14013//14013 -f 14013//14013 12568//12568 12567//12567 -f 14013//14013 12567//12567 14004//14004 -f 14004//14004 12567//12567 12565//12565 -f 14004//14004 12565//12565 12563//12563 -f 12552//12552 14008//14008 12550//12550 -f 12550//12550 14008//14008 14014//14014 -f 12550//12550 14014//14014 13178//13178 -f 13178//13178 14014//14014 13180//13180 -f 13180//13180 14014//14014 14015//14015 -f 13180//13180 14015//14015 13182//13182 -f 13182//13182 14015//14015 13184//13184 -f 13184//13184 14015//14015 14016//14016 -f 13184//13184 14016//14016 13186//13186 -f 13186//13186 14016//14016 14017//14017 -f 13186//13186 14017//14017 13188//13188 -f 13188//13188 14017//14017 13189//13189 -f 13189//13189 14017//14017 14018//14018 -f 13189//13189 14018//14018 13176//13176 -f 13176//13176 14018//14018 14019//14019 -f 13176//13176 14019//14019 13173//13173 -f 13173//13173 14019//14019 14020//14020 -f 13173//13173 14020//14020 13171//13171 -f 13171//13171 14020//14020 14021//14021 -f 13171//13171 14021//14021 13169//13169 -f 13169//13169 14021//14021 13167//13167 -f 13167//13167 14021//14021 14022//14022 -f 13167//13167 14022//14022 13166//13166 -f 13166//13166 14022//14022 14023//14023 -f 13166//13166 14023//14023 13164//13164 -f 13164//13164 14023//14023 14024//14024 -f 13164//13164 14024//14024 13162//13162 -f 13162//13162 14024//14024 14025//14025 -f 13162//13162 14025//14025 13160//13160 -f 13160//13160 14025//14025 14026//14026 -f 13160//13160 14026//14026 13153//13153 -f 13153//13153 14026//14026 14027//14027 -f 13153//13153 14027//14027 13154//13154 -f 13154//13154 14027//14027 13156//13156 -f 13156//13156 14027//14027 14028//14028 -f 13156//13156 14028//14028 12541//12541 -f 12541//12541 14028//14028 14029//14029 -f 12541//12541 14029//14029 12542//12542 -f 12542//12542 14029//14029 12543//12543 -f 12543//12543 14029//14029 14030//14030 -f 12543//12543 14030//14030 12544//12544 -f 12544//12544 14030//14030 12509//12509 -f 12509//12509 14030//14030 14031//14031 -f 12509//12509 14031//14031 12536//12536 -f 12536//12536 14031//14031 12535//12535 -f 12535//12535 14031//14031 14032//14032 -f 12535//12535 14032//14032 12534//12534 -f 12534//12534 14032//14032 14033//14033 -f 12534//12534 14033//14033 12532//12532 -f 12532//12532 14033//14033 14034//14034 -f 12532//12532 14034//14034 12530//12530 -f 12530//12530 14034//14034 13926//13926 -f 12530//12530 13926//13926 12528//12528 -f 12663//12663 12665//12665 13928//13928 -f 13928//13928 12665//12665 12667//12667 -f 13928//13928 12667//12667 14035//14035 -f 14035//14035 12667//12667 12669//12669 -f 14035//14035 12669//12669 14036//14036 -f 14036//14036 12669//12669 12672//12672 -f 14036//14036 12672//12672 14037//14037 -f 14037//14037 12672//12672 12674//12674 -f 14037//14037 12674//12674 14038//14038 -f 14038//14038 12674//12674 12675//12675 -f 14038//14038 12675//12675 14039//14039 -f 12675//12675 12678//12678 14039//14039 -f 14039//14039 12678//12678 12680//12680 -f 14039//14039 12680//12680 14040//14040 -f 14040//14040 12702//12702 12705//12705 -f 14040//14040 12705//12705 14039//14039 -f 14039//14039 12705//12705 12707//12707 -f 14039//14039 12707//12707 14038//14038 -f 14038//14038 12707//12707 14037//14037 -f 14037//14037 12707//12707 12709//12709 -f 14037//14037 12709//12709 14036//14036 -f 14036//14036 12709//12709 12711//12711 -f 14036//14036 12711//12711 14035//14035 -f 14035//14035 12711//12711 12713//12713 -f 14035//14035 12713//12713 13928//13928 -f 13928//13928 12713//12713 12715//12715 -f 13928//13928 12715//12715 13929//13929 -f 13929//13929 12715//12715 12717//12717 -f 13929//13929 12717//12717 13930//13930 -f 13930//13930 12717//12717 13931//13931 -f 13931//13931 12717//12717 13335//13335 -f 13931//13931 13335//13335 13932//13932 -f 13335//13335 13333//13333 13932//13932 -f 13932//13932 13333//13333 13331//13331 -f 13932//13932 13331//13331 13933//13933 -f 13331//13331 13329//13329 13933//13933 -f 13933//13933 13329//13329 13328//13328 -f 13933//13933 13328//13328 13934//13934 -f 13328//13328 13326//13326 13934//13934 -f 13934//13934 13326//13326 13324//13324 -f 13934//13934 13324//13324 13938//13938 -f 13938//13938 13324//13324 13323//13323 -f 13938//13938 13323//13323 13937//13937 -f 13937//13937 13323//13323 13320//13320 -f 13937//13937 13320//13320 13936//13936 -f 13936//13936 13320//13320 13318//13318 -f 13936//13936 13318//13318 13935//13935 -f 13935//13935 13318//13318 13317//13317 -f 13935//13935 13317//13317 13944//13944 -f 13944//13944 13317//13317 13314//13314 -f 13944//13944 13314//13314 13943//13943 -f 13943//13943 13314//13314 13312//13312 -f 13943//13943 13312//13312 13942//13942 -f 13303//13303 13939//13939 13305//13305 -f 13305//13305 13939//13939 13940//13940 -f 13305//13305 13940//13940 13307//13307 -f 13307//13307 13940//13940 13941//13941 -f 13307//13307 13941//13941 13309//13309 -f 13309//13309 13941//13941 13942//13942 -f 13309//13309 13942//13942 13310//13310 -f 13310//13310 13942//13942 13312//13312 -f 13303//13303 12693//12693 13939//13939 -f 13939//13939 12693//12693 12692//12692 -f 13939//13939 12692//12692 13945//13945 -f 12692//12692 12696//12696 13945//13945 -f 13945//13945 12696//12696 12695//12695 -f 13945//13945 12695//12695 13946//13946 -f 12695//12695 12690//12690 13946//13946 -f 13946//13946 12690//12690 12688//12688 -f 13946//13946 12688//12688 13947//13947 -f 13947//13947 12688//12688 12685//12685 -f 13947//13947 12685//12685 13949//13949 -f 13949//13949 12685//12685 12683//12683 -f 13955//13955 13954//13954 12673//12673 -f 12673//12673 13954//13954 12676//12676 -f 12676//12676 13954//13954 13953//13953 -f 12676//12676 13953//13953 12677//12677 -f 12677//12677 13953//13953 13950//13950 -f 12677//12677 13950//13950 12679//12679 -f 12679//12679 13950//13950 13951//13951 -f 12679//12679 13951//13951 12681//12681 -f 12681//12681 13951//13951 13952//13952 -f 12681//12681 13952//13952 12683//12683 -f 12683//12683 13952//13952 13948//13948 -f 12683//12683 13948//13948 13949//13949 -f 12673//12673 12671//12671 13955//13955 -f 13955//13955 12671//12671 12670//12670 -f 13955//13955 12670//12670 13956//13956 -f 12670//12670 12668//12668 13956//13956 -f 13956//13956 12668//12668 12666//12666 -f 13956//13956 12666//12666 13957//13957 -f 12666//12666 12664//12664 13957//13957 -f 13957//13957 12664//12664 12662//12662 -f 13957//13957 12662//12662 13958//13958 -f 13278//13278 13969//13969 13281//13281 -f 13281//13281 13969//13969 13968//13968 -f 13281//13281 13968//13968 13283//13283 -f 13283//13283 13968//13968 13967//13967 -f 13283//13283 13967//13967 13284//13284 -f 13284//13284 13967//13967 13966//13966 -f 13284//13284 13966//13966 13287//13287 -f 13287//13287 13966//13966 13965//13965 -f 13287//13287 13965//13965 13290//13290 -f 13290//13290 13965//13965 13964//13964 -f 13290//13290 13964//13964 13291//13291 -f 13291//13291 13964//13964 13963//13963 -f 13291//13291 13963//13963 13293//13293 -f 13293//13293 13963//13963 13962//13962 -f 13293//13293 13962//13962 13295//13295 -f 13295//13295 13962//13962 13961//13961 -f 13295//13295 13961//13961 13297//13297 -f 13297//13297 13961//13961 13960//13960 -f 13297//13297 13960//13960 13299//13299 -f 13299//13299 13960//13960 13959//13959 -f 13299//13299 13959//13959 13302//13302 -f 13302//13302 13959//13959 13958//13958 -f 13302//13302 13958//13958 13301//13301 -f 13301//13301 13958//13958 12662//12662 -f 13278//13278 13276//13276 13969//13969 -f 13969//13969 13276//13276 13275//13275 -f 13969//13969 13275//13275 13970//13970 -f 13275//13275 13273//13273 13970//13970 -f 13970//13970 13273//13273 13271//13271 -f 13970//13970 13271//13271 13974//13974 -f 13974//13974 13271//13271 13269//13269 -f 13974//13974 13269//13269 13973//13973 -f 13973//13973 13269//13269 12656//12656 -f 13973//13973 12656//12656 13972//13972 -f 13972//13972 12656//12656 12658//12658 -f 13972//13972 12658//12658 13971//13971 -f 13971//13971 12658//12658 12653//12653 -f 13971//13971 12653//12653 13978//13978 -f 13978//13978 12653//12653 12652//12652 -f 13978//13978 12652//12652 13977//13977 -f 13977//13977 12652//12652 12644//12644 -f 13977//13977 12644//12644 13976//13976 -f 13976//13976 12644//12644 12646//12646 -f 13976//13976 12646//12646 13975//13975 -f 13975//13975 12646//12646 12649//12649 -f 13975//13975 12649//12649 13979//13979 -f 12649//12649 12637//12637 13979//13979 -f 13979//13979 12637//12637 12636//12636 -f 13979//13979 12636//12636 13980//13980 -f 13988//13988 13981//13981 12628//12628 -f 12628//12628 13981//13981 13980//13980 -f 12628//12628 13980//13980 12629//12629 -f 12629//12629 13980//13980 12636//12636 -f 13988//13988 12628//12628 13987//13987 -f 13987//13987 12628//12628 12633//12633 -f 13987//13987 12633//12633 13986//13986 -f 13986//13986 12633//12633 12623//12623 -f 13986//13986 12623//12623 13985//13985 -f 13985//13985 12623//12623 12622//12622 -f 13985//13985 12622//12622 13984//13984 -f 13984//13984 12622//12622 12625//12625 -f 13984//13984 12625//12625 13983//13983 -f 12625//12625 13267//13267 13983//13983 -f 13983//13983 13267//13267 13266//13266 -f 13983//13983 13266//13266 13982//13982 -f 13982//13982 13266//13266 13250//13250 -f 13982//13982 13250//13250 13991//13991 -f 13991//13991 13250//13250 13253//13253 -f 13991//13991 13253//13253 13990//13990 -f 13990//13990 13253//13253 13256//13256 -f 13990//13990 13256//13256 13989//13989 -f 13989//13989 13256//13256 13258//13258 -f 13989//13989 13258//13258 13927//13927 -f 13258//13258 13260//13260 13927//13927 -f 13927//13927 13260//13260 13262//13262 -f 13927//13927 13262//13262 13992//13992 -f 13262//13262 13247//13247 13992//13992 -f 13992//13992 13247//13247 13243//13243 -f 13992//13992 13243//13243 13993//13993 -f 13993//13993 13243//13243 13994//13994 -f 13994//13994 13243//13243 13245//13245 -f 13994//13994 13245//13245 13995//13995 -f 13245//13245 13246//13246 13995//13995 -f 13995//13995 13246//13246 13241//13241 -f 13995//13995 13241//13241 13996//13996 -f 13996//13996 13241//13241 13239//13239 -f 13996//13996 13239//13239 13997//13997 -f 13239//13239 13237//13237 13997//13997 -f 13997//13997 13237//13237 13235//13235 -f 13997//13997 13235//13235 13998//13998 -f 13998//13998 13235//13235 13232//13232 -f 13998//13998 13232//13232 13999//13999 -f 13999//13999 13232//13232 12621//12621 -f 13999//13999 12621//12621 14000//14000 -f 14000//14000 12621//12621 12620//12620 -f 14000//14000 12620//12620 14001//14001 -f 14001//14001 12620//12620 12618//12618 -f 14001//14001 12618//12618 14002//14002 -f 12618//12618 12616//12616 14002//14002 -f 14002//14002 12616//12616 12613//12613 -f 14002//14002 12613//12613 14003//14003 -f 14003//14003 12613//12613 12611//12611 -f 14003//14003 12611//12611 12609//12609 -f 12602//12602 14011//14011 12587//12587 -f 12587//12587 14011//14011 14012//14012 -f 12587//12587 14012//14012 12604//12604 -f 12604//12604 14012//14012 14013//14013 -f 12604//12604 14013//14013 12606//12606 -f 12606//12606 14013//14013 14004//14004 -f 12606//12606 14004//14004 12607//12607 -f 12607//12607 14004//14004 14005//14005 -f 12607//12607 14005//14005 12586//12586 -f 12586//12586 14005//14005 14006//14006 -f 12586//12586 14006//14006 12609//12609 -f 12609//12609 14006//14006 14007//14007 -f 12609//12609 14007//14007 14003//14003 -f 12602//12602 12601//12601 14011//14011 -f 14011//14011 12601//12601 12599//12599 -f 14011//14011 12599//12599 14010//14010 -f 14010//14010 12599//12599 12597//12597 -f 14010//14010 12597//12597 14009//14009 -f 14009//14009 12597//12597 12595//12595 -f 14009//14009 12595//12595 14008//14008 -f 12595//12595 12593//12593 14008//14008 -f 14008//14008 12593//12593 12591//12591 -f 14008//14008 12591//12591 14014//14014 -f 12591//12591 13220//13220 14014//14014 -f 14014//14014 13220//13220 13222//13222 -f 14014//14014 13222//13222 14015//14015 -f 13222//13222 13224//13224 14015//14015 -f 14015//14015 13224//13224 13226//13226 -f 14015//14015 13226//13226 14016//14016 -f 13226//13226 13228//13228 14016//14016 -f 14016//14016 13228//13228 13210//13210 -f 14016//14016 13210//13210 14017//14017 -f 14017//14017 13210//13210 13209//13209 -f 14017//14017 13209//13209 14018//14018 -f 14018//14018 13209//13209 13212//13212 -f 14018//14018 13212//13212 14019//14019 -f 14019//14019 13212//13212 13214//13214 -f 14019//14019 13214//13214 14020//14020 -f 13214//13214 13217//13217 14020//14020 -f 14020//14020 13217//13217 13206//13206 -f 14020//14020 13206//13206 14021//14021 -f 14021//14021 13206//13206 13199//13199 -f 14021//14021 13199//13199 14022//14022 -f 14022//14022 13199//13199 14023//14023 -f 14023//14023 13199//13199 13201//13201 -f 14023//14023 13201//13201 14024//14024 -f 13201//13201 13203//13203 14024//14024 -f 14024//14024 13203//13203 13193//13193 -f 14024//14024 13193//13193 14025//14025 -f 14025//14025 13193//13193 13195//13195 -f 14025//14025 13195//13195 14026//14026 -f 14026//14026 13195//13195 14027//14027 -f 14027//14027 13195//13195 13197//13197 -f 14027//14027 13197//13197 14028//14028 -f 13197//13197 13191//13191 14028//14028 -f 14028//14028 13191//13191 12582//12582 -f 14028//14028 12582//12582 14029//14029 -f 12582//12582 12580//12580 14029//14029 -f 14029//14029 12580//12580 12579//12579 -f 14029//14029 12579//12579 14030//14030 -f 12579//12579 12576//12576 14030//14030 -f 14030//14030 12576//12576 12574//12574 -f 14030//14030 12574//12574 14031//14031 -f 14031//14031 12574//12574 12572//12572 -f 14031//14031 12572//12572 14032//14032 -f 14032//14032 12572//12572 12570//12570 -f 14032//14032 12570//12570 14033//14033 -f 12570//12570 12569//12569 14033//14033 -f 14033//14033 12569//12569 12560//12560 -f 14033//14033 12560//12560 14034//14034 -f 12560//12560 12562//12562 14034//14034 -f 14034//14034 12562//12562 12564//12564 -f 14034//14034 12564//12564 13926//13926 -f 14041//14041 14042//14042 12026//12026 -f 12026//12026 14042//14042 12027//12027 -f 12027//12027 14042//14042 14043//14043 -f 12027//12027 14043//14043 11992//11992 -f 11992//11992 14043//14043 14044//14044 -f 11992//11992 14044//14044 12020//12020 -f 12020//12020 14044//14044 14045//14045 -f 12020//12020 14045//14045 12018//12018 -f 12018//12018 14045//14045 14046//14046 -f 12018//12018 14046//14046 12016//12016 -f 12016//12016 14046//14046 14047//14047 -f 12016//12016 14047//14047 12014//12014 -f 12014//12014 14047//14047 12012//12012 -f 12012//12012 14047//14047 14048//14048 -f 12012//12012 14048//14048 12010//12010 -f 12010//12010 14048//14048 14049//14049 -f 12010//12010 14049//14049 12007//12007 -f 12007//12007 14049//14049 14050//14050 -f 12007//12007 14050//14050 12005//12005 -f 14050//14050 14051//14051 12005//12005 -f 12005//12005 14051//14051 14052//14052 -f 12005//12005 14052//14052 12003//12003 -f 12003//12003 14052//14052 14053//14053 -f 12003//12003 14053//14053 12001//12001 -f 12001//12001 14053//14053 14054//14054 -f 12001//12001 14054//14054 11999//11999 -f 11999//11999 14054//14054 14055//14055 -f 14056//14056 11993//11993 14057//14057 -f 14057//14057 11993//11993 11995//11995 -f 14057//14057 11995//11995 14055//14055 -f 14055//14055 11995//11995 11997//11997 -f 14055//14055 11997//11997 11999//11999 -f 14058//14058 13365//13365 14059//14059 -f 14059//14059 13365//13365 13363//13363 -f 14059//14059 13363//13363 14060//14060 -f 14060//14060 13363//13363 13361//13361 -f 14060//14060 13361//13361 14061//14061 -f 14061//14061 13361//13361 13359//13359 -f 14061//14061 13359//13359 14062//14062 -f 14062//14062 13359//13359 13357//13357 -f 14062//14062 13357//13357 14056//14056 -f 14056//14056 13357//13357 13355//13355 -f 14056//14056 13355//13355 11993//11993 -f 14063//14063 13369//13369 14058//14058 -f 14058//14058 13369//13369 13367//13367 -f 14058//14058 13367//13367 13365//13365 -f 14063//14063 14064//14064 13369//13369 -f 13369//13369 14064//14064 14065//14065 -f 13369//13369 14065//14065 13353//13353 -f 13353//13353 14065//14065 14066//14066 -f 13353//13353 14066//14066 13352//13352 -f 13352//13352 14066//14066 14067//14067 -f 13352//13352 14067//14067 13350//13350 -f 13350//13350 14067//14067 14068//14068 -f 13350//13350 14068//14068 13348//13348 -f 14068//14068 14069//14069 13348//13348 -f 13348//13348 14069//14069 14070//14070 -f 13348//13348 14070//14070 13337//13337 -f 13337//13337 14070//14070 14071//14071 -f 13337//13337 14071//14071 13338//13338 -f 13338//13338 14071//14071 14072//14072 -f 13338//13338 14072//14072 13340//13340 -f 13340//13340 14072//14072 14073//14073 -f 13340//13340 14073//14073 13342//13342 -f 13342//13342 14073//14073 13344//13344 -f 14073//14073 14074//14074 13344//13344 -f 13344//13344 14074//14074 14075//14075 -f 13344//13344 14075//14075 13345//13345 -f 13345//13345 14075//14075 14076//14076 -f 13345//13345 14076//14076 12730//12730 -f 12730//12730 14076//14076 14077//14077 -f 12730//12730 14077//14077 12728//12728 -f 14077//14077 14078//14078 12728//12728 -f 12728//12728 14078//14078 14079//14079 -f 12728//12728 14079//14079 12726//12726 -f 12726//12726 14079//14079 14080//14080 -f 12726//12726 14080//14080 12724//12724 -f 12724//12724 14080//14080 14081//14081 -f 12724//12724 14081//14081 12722//12722 -f 14082//14082 12720//12720 14083//14083 -f 14083//14083 12720//12720 12722//12722 -f 14083//14083 12722//12722 14084//14084 -f 14084//14084 12722//12722 14081//14081 -f 14082//14082 14085//14085 12720//12720 -f 12720//12720 14085//14085 14086//14086 -f 12720//12720 14086//14086 12700//12700 -f 12700//12700 14086//14086 14087//14087 -f 12700//12700 14087//14087 12701//12701 -f 12701//12701 14087//14087 14088//14088 -f 12701//12701 14088//14088 12703//12703 -f 12703//12703 14088//14088 14089//14089 -f 12703//12703 14089//14089 12704//12704 -f 14089//14089 14090//14090 12704//12704 -f 12704//12704 14090//14090 14091//14091 -f 12704//12704 14091//14091 12706//12706 -f 12706//12706 14091//14091 14092//14092 -f 12706//12706 14092//14092 12708//12708 -f 12708//12708 14092//14092 14093//14093 -f 12708//12708 14093//14093 12710//12710 -f 12710//12710 14093//14093 14094//14094 -f 12710//12710 14094//14094 12712//12712 -f 12712//12712 14094//14094 12714//12714 -f 12714//12714 14094//14094 14095//14095 -f 12714//12714 14095//14095 12719//12719 -f 12719//12719 14095//14095 14096//14096 -f 12719//12719 14096//14096 12718//12718 -f 12718//12718 14096//14096 14097//14097 -f 12718//12718 14097//14097 12716//12716 -f 12716//12716 14097//14097 13336//13336 -f 13336//13336 14097//14097 14098//14098 -f 13336//13336 14098//14098 13334//13334 -f 13334//13334 14098//14098 14099//14099 -f 13334//13334 14099//14099 13332//13332 -f 13332//13332 14099//14099 14100//14100 -f 13332//13332 14100//14100 13330//13330 -f 13330//13330 14100//14100 14101//14101 -f 13330//13330 14101//14101 13327//13327 -f 14101//14101 14102//14102 13327//13327 -f 13327//13327 14102//14102 14103//14103 -f 13327//13327 14103//14103 13325//13325 -f 13325//13325 14103//14103 14104//14104 -f 13325//13325 14104//14104 13322//13322 -f 14104//14104 14105//14105 13322//13322 -f 13322//13322 14105//14105 14106//14106 -f 13322//13322 14106//14106 13321//13321 -f 13321//13321 14106//14106 14107//14107 -f 13321//13321 14107//14107 13319//13319 -f 13319//13319 14107//14107 14108//14108 -f 13319//13319 14108//14108 13316//13316 -f 13316//13316 14108//14108 14109//14109 -f 13316//13316 14109//14109 13315//13315 -f 13315//13315 14109//14109 14110//14110 -f 13315//13315 14110//14110 13313//13313 -f 14110//14110 14111//14111 13313//13313 -f 13313//13313 14111//14111 14112//14112 -f 13313//13313 14112//14112 13311//13311 -f 14112//14112 14113//14113 13311//13311 -f 13311//13311 14113//14113 14114//14114 -f 13311//13311 14114//14114 13308//13308 -f 13308//13308 14114//14114 14115//14115 -f 13308//13308 14115//14115 13306//13306 -f 14115//14115 14116//14116 13306//13306 -f 13306//13306 14116//14116 14117//14117 -f 13306//13306 14117//14117 13304//13304 -f 13304//13304 14117//14117 14118//14118 -f 13304//13304 14118//14118 12694//12694 -f 14118//14118 14119//14119 12694//12694 -f 12694//12694 14119//14119 14120//14120 -f 12694//12694 14120//14120 12698//12698 -f 12698//12698 14120//14120 14121//14121 -f 12698//12698 14121//14121 12697//12697 -f 12697//12697 14121//14121 14122//14122 -f 12697//12697 14122//14122 12691//12691 -f 12691//12691 14122//14122 14123//14123 -f 12691//12691 14123//14123 12689//12689 -f 12689//12689 14123//14123 14124//14124 -f 12689//12689 14124//14124 12687//12687 -f 12687//12687 14124//14124 14125//14125 -f 12687//12687 14125//14125 12686//12686 -f 12686//12686 14125//14125 14126//14126 -f 12686//12686 14126//14126 12684//12684 -f 14126//14126 14127//14127 12684//12684 -f 12684//12684 14127//14127 14128//14128 -f 12684//12684 14128//14128 12682//12682 -f 12682//12682 14128//14128 14040//14040 -f 12682//12682 14040//14040 12680//12680 -f 12026//12026 12024//12024 14041//14041 -f 14041//14041 12024//12024 13392//13392 -f 14041//14041 13392//13392 14129//14129 -f 14129//14129 13392//13392 14130//14130 -f 14129//14129 14130//14130 14131//14131 -f 14131//14131 14130//14130 14132//14132 -f 14131//14131 14132//14132 14133//14133 -f 14133//14133 14132//14132 14134//14134 -f 14133//14133 14134//14134 14135//14135 -f 14135//14135 14134//14134 14136//14136 -f 14135//14135 14136//14136 14137//14137 -f 14137//14137 14136//14136 14138//14138 -f 14137//14137 14138//14138 14139//14139 -f 14139//14139 14138//14138 14140//14140 -f 14139//14139 14140//14140 14141//14141 -f 14141//14141 14140//14140 14142//14142 -f 14141//14141 14142//14142 14143//14143 -f 14133//14133 14135//14135 14144//14144 -f 12699//12699 12702//12702 14040//14040 -f 14040//14040 14128//14128 12699//12699 -f 12699//12699 14128//14128 14127//14127 -f 12699//12699 14127//14127 12721//12721 -f 14127//14127 14126//14126 12721//12721 -f 12721//12721 14126//14126 14125//14125 -f 12721//12721 14125//14125 12723//12723 -f 12723//12723 14125//14125 14124//14124 -f 12723//12723 14124//14124 12725//12725 -f 12725//12725 14124//14124 14123//14123 -f 12725//12725 14123//14123 12727//12727 -f 12727//12727 14123//14123 14122//14122 -f 12727//12727 14122//14122 12732//12732 -f 12732//12732 14122//14122 14121//14121 -f 12732//12732 14121//14121 12731//12731 -f 12731//12731 14121//14121 14120//14120 -f 12731//12731 14120//14120 12729//12729 -f 12729//12729 14120//14120 14119//14119 -f 14119//14119 14118//14118 12729//12729 -f 12729//12729 14118//14118 14117//14117 -f 12729//12729 14117//14117 13343//13343 -f 13343//13343 14117//14117 14116//14116 -f 13343//13343 14116//14116 13341//13341 -f 14116//14116 14115//14115 13341//13341 -f 13341//13341 14115//14115 14114//14114 -f 13341//13341 14114//14114 13339//13339 -f 13339//13339 14114//14114 14113//14113 -f 13339//13339 14113//14113 13346//13346 -f 13346//13346 14113//14113 14112//14112 -f 13346//13346 14112//14112 13347//13347 -f 13347//13347 14112//14112 14111//14111 -f 13347//13347 14111//14111 13349//13349 -f 13349//13349 14111//14111 14110//14110 -f 13349//13349 14110//14110 13351//13351 -f 14110//14110 14109//14109 13351//13351 -f 13351//13351 14109//14109 14108//14108 -f 13351//13351 14108//14108 13371//13371 -f 13371//13371 14108//14108 14107//14107 -f 13371//13371 14107//14107 13370//13370 -f 14107//14107 14106//14106 13370//13370 -f 13370//13370 14106//14106 14105//14105 -f 13370//13370 14105//14105 13368//13368 -f 13368//13368 14105//14105 14104//14104 -f 13368//13368 14104//14104 13366//13366 -f 13366//13366 14104//14104 14103//14103 -f 13366//13366 14103//14103 13364//13364 -f 13364//13364 14103//14103 14102//14102 -f 13364//13364 14102//14102 13362//13362 -f 13362//13362 14102//14102 14101//14101 -f 13362//13362 14101//14101 13360//13360 -f 13360//13360 14101//14101 14100//14100 -f 13360//13360 14100//14100 13358//13358 -f 13358//13358 14100//14100 14099//14099 -f 13358//13358 14099//14099 13356//13356 -f 13356//13356 14099//14099 14098//14098 -f 13356//13356 14098//14098 13354//13354 -f 13354//13354 14098//14098 14097//14097 -f 13354//13354 14097//14097 11994//11994 -f 11994//11994 14097//14097 14096//14096 -f 11994//11994 14096//14096 11996//11996 -f 11996//11996 14096//14096 14095//14095 -f 11996//11996 14095//14095 11998//11998 -f 11998//11998 14095//14095 14094//14094 -f 14093//14093 12002//12002 14094//14094 -f 14094//14094 12002//12002 12000//12000 -f 14094//14094 12000//12000 11998//11998 -f 12009//12009 12008//12008 14092//14092 -f 14092//14092 12008//12008 12006//12006 -f 14092//14092 12006//12006 14093//14093 -f 14093//14093 12006//12006 12004//12004 -f 14093//14093 12004//12004 12002//12002 -f 14092//14092 14091//14091 12009//12009 -f 12009//12009 14091//14091 14090//14090 -f 12009//12009 14090//14090 12011//12011 -f 14090//14090 14089//14089 12011//12011 -f 12011//12011 14089//14089 14088//14088 -f 12011//12011 14088//14088 12013//12013 -f 12013//12013 14088//14088 14087//14087 -f 12013//12013 14087//14087 12015//12015 -f 14083//14083 12019//12019 14082//14082 -f 14082//14082 12019//12019 12017//12017 -f 14082//14082 12017//12017 14085//14085 -f 14085//14085 12017//12017 12015//12015 -f 14085//14085 12015//12015 14086//14086 -f 14086//14086 12015//12015 14087//14087 -f 14083//14083 14084//14084 12019//12019 -f 12019//12019 14084//14084 14081//14081 -f 12019//12019 14081//14081 12021//12021 -f 12021//12021 14081//14081 14080//14080 -f 12021//12021 14080//14080 11990//11990 -f 11990//11990 14080//14080 14079//14079 -f 11990//11990 14079//14079 11991//11991 -f 11991//11991 14079//14079 14078//14078 -f 11991//11991 14078//14078 12025//12025 -f 12025//12025 14078//14078 14077//14077 -f 12025//12025 14077//14077 12022//12022 -f 12022//12022 14077//14077 14076//14076 -f 12022//12022 14076//14076 12023//12023 -f 12023//12023 14076//14076 13393//13393 -f 13393//13393 14076//14076 14075//14075 -f 13393//13393 14075//14075 13395//13395 -f 13395//13395 14075//14075 14074//14074 -f 13395//13395 14074//14074 13396//13396 -f 14074//14074 14073//14073 13396//13396 -f 13396//13396 14073//14073 14072//14072 -f 13396//13396 14072//14072 13399//13399 -f 13399//13399 14072//14072 14071//14071 -f 13399//13399 14071//14071 13400//13400 -f 14071//14071 14070//14070 13400//13400 -f 13400//13400 14070//14070 14069//14069 -f 13400//13400 14069//14069 13402//13402 -f 13402//13402 14069//14069 14068//14068 -f 13402//13402 14068//14068 13403//13403 -f 13403//13403 14068//14068 14145//14145 -f 14068//14068 14067//14067 14145//14145 -f 14145//14145 14067//14067 14066//14066 -f 14145//14145 14066//14066 14146//14146 -f 14146//14146 14066//14066 14065//14065 -f 14146//14146 14065//14065 14147//14147 -f 14147//14147 14065//14065 14064//14064 -f 14147//14147 14064//14064 14148//14148 -f 14064//14064 14063//14063 14148//14148 -f 14148//14148 14063//14063 14058//14058 -f 14148//14148 14058//14058 14149//14149 -f 14149//14149 14058//14058 14150//14150 -f 14150//14150 14058//14058 14059//14059 -f 14150//14150 14059//14059 14151//14151 -f 14151//14151 14059//14059 14152//14152 -f 14152//14152 14059//14059 14060//14060 -f 14152//14152 14060//14060 14153//14153 -f 14153//14153 14060//14060 14061//14061 -f 14153//14153 14061//14061 14154//14154 -f 14154//14154 14061//14061 14062//14062 -f 14154//14154 14062//14062 14155//14155 -f 14155//14155 14062//14062 14056//14056 -f 14155//14155 14056//14056 14156//14156 -f 14156//14156 14056//14056 14157//14157 -f 14157//14157 14056//14056 14057//14057 -f 14157//14157 14057//14057 14158//14158 -f 14158//14158 14057//14057 14055//14055 -f 14158//14158 14055//14055 14159//14159 -f 14159//14159 14055//14055 14054//14054 -f 14159//14159 14054//14054 14160//14160 -f 14160//14160 14054//14054 14161//14161 -f 14161//14161 14054//14054 14053//14053 -f 14161//14161 14053//14053 14162//14162 -f 14053//14053 14052//14052 14162//14162 -f 14162//14162 14052//14052 14051//14051 -f 14162//14162 14051//14051 14163//14163 -f 14051//14051 14050//14050 14163//14163 -f 14163//14163 14050//14050 14049//14049 -f 14163//14163 14049//14049 14164//14164 -f 14164//14164 14049//14049 14048//14048 -f 14164//14164 14048//14048 14165//14165 -f 14165//14165 14048//14048 14047//14047 -f 14165//14165 14047//14047 14166//14166 -f 14166//14166 14047//14047 14167//14167 -f 14167//14167 14047//14047 14046//14046 -f 14167//14167 14046//14046 14168//14168 -f 14168//14168 14046//14046 14045//14045 -f 14168//14168 14045//14045 14169//14169 -f 14169//14169 14045//14045 14044//14044 -f 14169//14169 14044//14044 14170//14170 -f 14170//14170 14044//14044 14043//14043 -f 14170//14170 14043//14043 14171//14171 -f 14171//14171 14043//14043 14042//14042 -f 14171//14171 14042//14042 14172//14172 -f 14042//14042 14041//14041 14172//14172 -f 14172//14172 14041//14041 14129//14129 -f 14172//14172 14129//14129 14144//14144 -f 14144//14144 14129//14129 14131//14131 -f 14144//14144 14131//14131 14133//14133 -f 14130//14130 13392//13392 13394//13394 -f 14170//14170 14171//14171 14173//14173 -f 14166//14166 14167//14167 14174//14174 -f 14174//14174 14167//14167 14168//14168 -f 14174//14174 14168//14168 14173//14173 -f 14173//14173 14168//14168 14169//14169 -f 14173//14173 14169//14169 14170//14170 -f 14166//14166 14174//14174 14165//14165 -f 14165//14165 14174//14174 14175//14175 -f 14165//14165 14175//14175 14164//14164 -f 14164//14164 14175//14175 14176//14176 -f 14164//14164 14176//14176 14163//14163 -f 14163//14163 14176//14176 14177//14177 -f 14163//14163 14177//14177 14162//14162 -f 14177//14177 14178//14178 14162//14162 -f 14162//14162 14178//14178 14179//14179 -f 14162//14162 14179//14179 14161//14161 -f 14161//14161 14179//14179 14180//14180 -f 14161//14161 14180//14180 14160//14160 -f 14160//14160 14180//14180 14159//14159 -f 14159//14159 14180//14180 14181//14181 -f 14159//14159 14181//14181 14158//14158 -f 14158//14158 14181//14181 14157//14157 -f 14157//14157 14181//14181 14182//14182 -f 14157//14157 14182//14182 14156//14156 -f 14156//14156 14182//14182 14155//14155 -f 14155//14155 14182//14182 14183//14183 -f 14155//14155 14183//14183 14154//14154 -f 14150//14150 14151//14151 14184//14184 -f 14184//14184 14151//14151 14152//14152 -f 14184//14184 14152//14152 14183//14183 -f 14183//14183 14152//14152 14153//14153 -f 14183//14183 14153//14153 14154//14154 -f 14185//14185 14148//14148 14184//14184 -f 14184//14184 14148//14148 14149//14149 -f 14184//14184 14149//14149 14150//14150 -f 13397//13397 13398//13398 14138//14138 -f 14138//14138 13398//13398 13401//13401 -f 14138//14138 13401//13401 14140//14140 -f 14140//14140 13401//13401 13403//13403 -f 14140//14140 13403//13403 14142//14142 -f 14142//14142 13403//13403 14145//14145 -f 14142//14142 14145//14145 14143//14143 -f 14143//14143 14145//14145 14146//14146 -f 14143//14143 14146//14146 14185//14185 -f 14185//14185 14146//14146 14147//14147 -f 14185//14185 14147//14147 14148//14148 -f 14138//14138 14136//14136 13397//13397 -f 13397//13397 14136//14136 14134//14134 -f 13397//13397 14134//14134 13394//13394 -f 13394//13394 14134//14134 14132//14132 -f 13394//13394 14132//14132 14130//14130 -f 14172//14172 14144//14144 14135//14135 -f 14178//14178 14135//14135 14179//14179 -f 14179//14179 14135//14135 14180//14180 -f 14180//14180 14135//14135 14181//14181 -f 14181//14181 14135//14135 14137//14137 -f 14181//14181 14137//14137 14139//14139 -f 14141//14141 14143//14143 14185//14185 -f 14185//14185 14184//14184 14183//14183 -f 14139//14139 14141//14141 14181//14181 -f 14181//14181 14141//14141 14185//14185 -f 14181//14181 14185//14185 14182//14182 -f 14182//14182 14185//14185 14183//14183 -f 14175//14175 14174//14174 14176//14176 -f 14176//14176 14174//14174 14173//14173 -f 14178//14178 14177//14177 14135//14135 -f 14135//14135 14177//14177 14176//14176 -f 14135//14135 14176//14176 14172//14172 -f 14172//14172 14176//14176 14173//14173 -f 14172//14172 14173//14173 14171//14171 -f 14186//14186 14187//14187 14188//14188 -f 14188//14188 14187//14187 14189//14189 -f 14188//14188 14189//14189 14190//14190 -f 14190//14190 14189//14189 14191//14191 -f 14190//14190 14191//14191 14192//14192 -f 14192//14192 14191//14191 14193//14193 -f 14192//14192 14193//14193 14194//14194 -f 14194//14194 14193//14193 14195//14195 -f 14194//14194 14195//14195 14196//14196 -f 14196//14196 14195//14195 14197//14197 -f 14196//14196 14197//14197 14198//14198 -f 14198//14198 14197//14197 14199//14199 -f 14198//14198 14199//14199 14200//14200 -f 14200//14200 14199//14199 14201//14201 -f 14200//14200 14201//14201 14202//14202 -f 14202//14202 14201//14201 14203//14203 -f 14202//14202 14203//14203 14204//14204 -f 14204//14204 14203//14203 14205//14205 -f 14204//14204 14205//14205 14206//14206 -f 14206//14206 14205//14205 14207//14207 -f 14206//14206 14207//14207 14208//14208 -f 14208//14208 14207//14207 14209//14209 -f 14208//14208 14209//14209 14210//14210 -f 14210//14210 14209//14209 14211//14211 -f 14210//14210 14211//14211 14212//14212 -f 14212//14212 14211//14211 14213//14213 -f 14212//14212 14213//14213 14214//14214 -f 14214//14214 14213//14213 14215//14215 -f 14216//14216 14217//14217 14218//14218 -f 14216//14216 14218//14218 14219//14219 -f 14219//14219 14218//14218 14220//14220 -f 14219//14219 14220//14220 14221//14221 -f 14221//14221 14220//14220 14222//14222 -f 14221//14221 14222//14222 14223//14223 -f 14223//14223 14222//14222 14224//14224 -f 14223//14223 14224//14224 14225//14225 -f 14225//14225 14224//14224 14226//14226 -f 14225//14225 14226//14226 14227//14227 -f 14227//14227 14226//14226 14228//14228 -f 14227//14227 14228//14228 14229//14229 -f 14229//14229 14228//14228 14230//14230 -f 14229//14229 14230//14230 14231//14231 -f 14231//14231 14230//14230 14232//14232 -f 14231//14231 14232//14232 14233//14233 -f 14233//14233 14232//14232 14234//14234 -f 14233//14233 14234//14234 14235//14235 -f 14235//14235 14234//14234 14236//14236 -f 14235//14235 14236//14236 14237//14237 -f 14237//14237 14236//14236 14238//14238 -f 14237//14237 14238//14238 14239//14239 -f 14239//14239 14238//14238 14240//14240 -f 14239//14239 14240//14240 14241//14241 -f 14241//14241 14240//14240 14242//14242 -f 14241//14241 14242//14242 14243//14243 -f 14243//14243 14242//14242 14244//14244 -f 14243//14243 14244//14244 14245//14245 -f 14245//14245 14244//14244 14246//14246 -f 14245//14245 14246//14246 14247//14247 -f 14247//14247 14246//14246 14248//14248 -f 14247//14247 14248//14248 14249//14249 -f 14249//14249 14248//14248 14250//14250 -f 14249//14249 14250//14250 14251//14251 -f 14251//14251 14250//14250 14252//14252 -f 14251//14251 14252//14252 14253//14253 -f 14253//14253 14252//14252 14254//14254 -f 14253//14253 14254//14254 14255//14255 -f 14256//14256 14257//14257 14258//14258 -f 14256//14256 14258//14258 14259//14259 -f 14259//14259 14258//14258 14260//14260 -f 14259//14259 14260//14260 14261//14261 -f 14261//14261 14260//14260 14262//14262 -f 14261//14261 14262//14262 14263//14263 -f 14263//14263 14262//14262 14264//14264 -f 14263//14263 14264//14264 14265//14265 -f 14265//14265 14264//14264 14266//14266 -f 14265//14265 14266//14266 14267//14267 -f 14267//14267 14266//14266 14268//14268 -f 14267//14267 14268//14268 14269//14269 -f 14269//14269 14268//14268 14270//14270 -f 14269//14269 14270//14270 14271//14271 -f 14271//14271 14270//14270 14272//14272 -f 14271//14271 14272//14272 14273//14273 -f 14273//14273 14272//14272 14274//14274 -f 14273//14273 14274//14274 14275//14275 -f 14275//14275 14274//14274 14276//14276 -f 14275//14275 14276//14276 14277//14277 -f 14277//14277 14276//14276 14278//14278 -f 14277//14277 14278//14278 14279//14279 -f 14279//14279 14278//14278 14280//14280 -f 14279//14279 14280//14280 14281//14281 -f 14281//14281 14280//14280 14282//14282 -f 14281//14281 14282//14282 14283//14283 -f 14283//14283 14282//14282 14284//14284 -f 14283//14283 14284//14284 14285//14285 -f 14285//14285 14284//14284 14286//14286 -f 14285//14285 14286//14286 14287//14287 -f 14287//14287 14286//14286 14288//14288 -f 14287//14287 14288//14288 14289//14289 -f 14289//14289 14288//14288 14290//14290 -f 14289//14289 14290//14290 14291//14291 -f 14291//14291 14290//14290 14292//14292 -f 14291//14291 14292//14292 14293//14293 -f 14293//14293 14292//14292 14294//14294 -f 14293//14293 14294//14294 14295//14295 -f 14296//14296 14297//14297 14298//14298 -f 14296//14296 14298//14298 14299//14299 -f 14299//14299 14298//14298 14300//14300 -f 14299//14299 14300//14300 14301//14301 -f 14301//14301 14300//14300 14302//14302 -f 14301//14301 14302//14302 14303//14303 -f 14303//14303 14302//14302 14304//14304 -f 14303//14303 14304//14304 14305//14305 -f 14305//14305 14304//14304 14306//14306 -f 14305//14305 14306//14306 14307//14307 -f 14307//14307 14306//14306 14308//14308 -f 14307//14307 14308//14308 14309//14309 -f 14309//14309 14308//14308 14310//14310 -f 14309//14309 14310//14310 14311//14311 -f 14311//14311 14310//14310 14312//14312 -f 14311//14311 14312//14312 14313//14313 -f 14313//14313 14312//14312 14314//14314 -f 14313//14313 14314//14314 14315//14315 -f 14315//14315 14314//14314 14316//14316 -f 14315//14315 14316//14316 14317//14317 -f 14317//14317 14316//14316 14318//14318 -f 14317//14317 14318//14318 14319//14319 -f 14319//14319 14318//14318 14320//14320 -f 14319//14319 14320//14320 14321//14321 -f 14321//14321 14320//14320 14322//14322 -f 14321//14321 14322//14322 14323//14323 -f 14323//14323 14322//14322 14324//14324 -f 14323//14323 14324//14324 14325//14325 -f 14325//14325 14324//14324 14326//14326 -f 14325//14325 14326//14326 14327//14327 -f 14327//14327 14326//14326 14328//14328 -f 14327//14327 14328//14328 14329//14329 -f 14329//14329 14328//14328 14330//14330 -f 14329//14329 14330//14330 14331//14331 -f 14214//14214 14215//14215 14332//14332 -f 14332//14332 14215//14215 14333//14333 -f 14332//14332 14333//14333 14334//14334 -f 14334//14334 14333//14333 14335//14335 -f 14334//14334 14335//14335 14336//14336 -f 14336//14336 14335//14335 14337//14337 -f 14336//14336 14337//14337 14338//14338 -f 14338//14338 14337//14337 14339//14339 -f 14338//14338 14339//14339 14340//14340 -f 14340//14340 14339//14339 14341//14341 -f 14340//14340 14341//14341 14342//14342 -f 14342//14342 14341//14341 14343//14343 -f 14342//14342 14343//14343 14344//14344 -f 14344//14344 14343//14343 14345//14345 -f 14344//14344 14345//14345 14346//14346 -f 14346//14346 14345//14345 14347//14347 -f 14346//14346 14347//14347 14348//14348 -f 14348//14348 14347//14347 14349//14349 -f 14348//14348 14349//14349 14350//14350 -f 14350//14350 14349//14349 14351//14351 -f 14350//14350 14351//14351 14352//14352 -f 14352//14352 14351//14351 14353//14353 -f 14352//14352 14353//14353 14354//14354 -f 14354//14354 14353//14353 14355//14355 -f 14354//14354 14355//14355 14356//14356 -f 14356//14356 14355//14355 14357//14357 -f 14356//14356 14357//14357 14186//14186 -f 14186//14186 14357//14357 14187//14187 -f 14334//14334 14220//14220 14332//14332 -f 14332//14332 14220//14220 14218//14218 -f 14332//14332 14218//14218 14214//14214 -f 14214//14214 14218//14218 14217//14217 -f 14214//14214 14217//14217 14212//14212 -f 14196//14196 14358//14358 14194//14194 -f 14194//14194 14358//14358 14359//14359 -f 14194//14194 14359//14359 14192//14192 -f 14192//14192 14359//14359 14360//14360 -f 14192//14192 14360//14360 14190//14190 -f 14340//14340 14228//14228 14338//14338 -f 14338//14338 14228//14228 14226//14226 -f 14338//14338 14226//14226 14336//14336 -f 14336//14336 14226//14226 14224//14224 -f 14336//14336 14224//14224 14334//14334 -f 14334//14334 14224//14224 14222//14222 -f 14334//14334 14222//14222 14220//14220 -f 14360//14360 14361//14361 14190//14190 -f 14190//14190 14361//14361 14362//14362 -f 14190//14190 14362//14362 14188//14188 -f 14188//14188 14362//14362 14363//14363 -f 14188//14188 14363//14363 14186//14186 -f 14186//14186 14363//14363 14254//14254 -f 14186//14186 14254//14254 14356//14356 -f 14200//14200 14364//14364 14198//14198 -f 14198//14198 14364//14364 14365//14365 -f 14198//14198 14365//14365 14196//14196 -f 14196//14196 14365//14365 14366//14366 -f 14196//14196 14366//14366 14358//14358 -f 14217//14217 14367//14367 14212//14212 -f 14212//14212 14367//14367 14368//14368 -f 14212//14212 14368//14368 14210//14210 -f 14210//14210 14368//14368 14369//14369 -f 14210//14210 14369//14369 14208//14208 -f 14208//14208 14369//14369 14370//14370 -f 14208//14208 14370//14370 14206//14206 -f 14344//14344 14234//14234 14342//14342 -f 14342//14342 14234//14234 14232//14232 -f 14342//14342 14232//14232 14340//14340 -f 14340//14340 14232//14232 14230//14230 -f 14340//14340 14230//14230 14228//14228 -f 14370//14370 14371//14371 14206//14206 -f 14206//14206 14371//14371 14372//14372 -f 14206//14206 14372//14372 14204//14204 -f 14204//14204 14372//14372 14373//14373 -f 14204//14204 14373//14373 14202//14202 -f 14202//14202 14373//14373 14374//14374 -f 14202//14202 14374//14374 14200//14200 -f 14200//14200 14374//14374 14375//14375 -f 14200//14200 14375//14375 14364//14364 -f 14254//14254 14252//14252 14356//14356 -f 14356//14356 14252//14252 14250//14250 -f 14356//14356 14250//14250 14354//14354 -f 14354//14354 14250//14250 14248//14248 -f 14354//14354 14248//14248 14352//14352 -f 14352//14352 14248//14248 14246//14246 -f 14352//14352 14246//14246 14350//14350 -f 14246//14246 14244//14244 14350//14350 -f 14350//14350 14244//14244 14242//14242 -f 14350//14350 14242//14242 14348//14348 -f 14348//14348 14242//14242 14240//14240 -f 14348//14348 14240//14240 14346//14346 -f 14346//14346 14240//14240 14238//14238 -f 14346//14346 14238//14238 14344//14344 -f 14344//14344 14238//14238 14236//14236 -f 14344//14344 14236//14236 14234//14234 -f 14333//14333 14261//14261 14335//14335 -f 14335//14335 14261//14261 14263//14263 -f 14335//14335 14263//14263 14337//14337 -f 14337//14337 14263//14263 14265//14265 -f 14337//14337 14265//14265 14339//14339 -f 14265//14265 14267//14267 14339//14339 -f 14339//14339 14267//14267 14269//14269 -f 14339//14339 14269//14269 14341//14341 -f 14341//14341 14269//14269 14271//14271 -f 14341//14341 14271//14271 14343//14343 -f 14189//14189 14376//14376 14191//14191 -f 14191//14191 14376//14376 14377//14377 -f 14191//14191 14377//14377 14193//14193 -f 14193//14193 14377//14377 14378//14378 -f 14193//14193 14378//14378 14195//14195 -f 14211//14211 14379//14379 14213//14213 -f 14213//14213 14379//14379 14380//14380 -f 14213//14213 14380//14380 14215//14215 -f 14215//14215 14380//14380 14256//14256 -f 14215//14215 14256//14256 14333//14333 -f 14333//14333 14256//14256 14259//14259 -f 14333//14333 14259//14259 14261//14261 -f 14205//14205 14381//14381 14207//14207 -f 14207//14207 14381//14381 14382//14382 -f 14207//14207 14382//14382 14209//14209 -f 14209//14209 14382//14382 14383//14383 -f 14209//14209 14383//14383 14211//14211 -f 14211//14211 14383//14383 14384//14384 -f 14211//14211 14384//14384 14379//14379 -f 14199//14199 14385//14385 14201//14201 -f 14201//14201 14385//14385 14386//14386 -f 14201//14201 14386//14386 14203//14203 -f 14203//14203 14386//14386 14387//14387 -f 14203//14203 14387//14387 14205//14205 -f 14205//14205 14387//14387 14388//14388 -f 14205//14205 14388//14388 14381//14381 -f 14378//14378 14389//14389 14195//14195 -f 14195//14195 14389//14389 14390//14390 -f 14195//14195 14390//14390 14197//14197 -f 14197//14197 14390//14390 14391//14391 -f 14197//14197 14391//14391 14199//14199 -f 14199//14199 14391//14391 14392//14392 -f 14199//14199 14392//14392 14385//14385 -f 14355//14355 14291//14291 14357//14357 -f 14357//14357 14291//14291 14293//14293 -f 14357//14357 14293//14293 14187//14187 -f 14187//14187 14293//14293 14295//14295 -f 14187//14187 14295//14295 14189//14189 -f 14189//14189 14295//14295 14393//14393 -f 14189//14189 14393//14393 14376//14376 -f 14349//14349 14283//14283 14351//14351 -f 14351//14351 14283//14283 14285//14285 -f 14351//14351 14285//14285 14353//14353 -f 14353//14353 14285//14285 14287//14287 -f 14353//14353 14287//14287 14355//14355 -f 14355//14355 14287//14287 14289//14289 -f 14355//14355 14289//14289 14291//14291 -f 14271//14271 14273//14273 14343//14343 -f 14343//14343 14273//14273 14275//14275 -f 14343//14343 14275//14275 14345//14345 -f 14345//14345 14275//14275 14277//14277 -f 14345//14345 14277//14277 14347//14347 -f 14347//14347 14277//14277 14279//14279 -f 14347//14347 14279//14279 14349//14349 -f 14349//14349 14279//14279 14281//14281 -f 14349//14349 14281//14281 14283//14283 -f 14255//14255 14254//14254 14363//14363 -f 14255//14255 14363//14363 14394//14394 -f 14394//14394 14363//14363 14362//14362 -f 14394//14394 14362//14362 14395//14395 -f 14395//14395 14362//14362 14361//14361 -f 14395//14395 14361//14361 14396//14396 -f 14396//14396 14361//14361 14360//14360 -f 14396//14396 14360//14360 14397//14397 -f 14397//14397 14360//14360 14359//14359 -f 14397//14397 14359//14359 14398//14398 -f 14398//14398 14359//14359 14358//14358 -f 14398//14398 14358//14358 14399//14399 -f 14399//14399 14358//14358 14366//14366 -f 14399//14399 14366//14366 14400//14400 -f 14400//14400 14366//14366 14365//14365 -f 14400//14400 14365//14365 14401//14401 -f 14401//14401 14365//14365 14364//14364 -f 14401//14401 14364//14364 14402//14402 -f 14402//14402 14364//14364 14375//14375 -f 14402//14402 14375//14375 14403//14403 -f 14403//14403 14375//14375 14374//14374 -f 14403//14403 14374//14374 14404//14404 -f 14404//14404 14374//14374 14373//14373 -f 14404//14404 14373//14373 14405//14405 -f 14405//14405 14373//14373 14372//14372 -f 14405//14405 14372//14372 14406//14406 -f 14406//14406 14372//14372 14371//14371 -f 14406//14406 14371//14371 14407//14407 -f 14407//14407 14371//14371 14370//14370 -f 14407//14407 14370//14370 14408//14408 -f 14408//14408 14370//14370 14369//14369 -f 14408//14408 14369//14369 14409//14409 -f 14409//14409 14369//14369 14368//14368 -f 14409//14409 14368//14368 14410//14410 -f 14410//14410 14368//14368 14367//14367 -f 14410//14410 14367//14367 14411//14411 -f 14411//14411 14367//14367 14217//14217 -f 14411//14411 14217//14217 14216//14216 -f 14295//14295 14294//14294 14412//14412 -f 14295//14295 14412//14412 14393//14393 -f 14393//14393 14412//14412 14413//14413 -f 14393//14393 14413//14413 14376//14376 -f 14376//14376 14413//14413 14414//14414 -f 14376//14376 14414//14414 14377//14377 -f 14377//14377 14414//14414 14415//14415 -f 14377//14377 14415//14415 14378//14378 -f 14378//14378 14415//14415 14416//14416 -f 14378//14378 14416//14416 14389//14389 -f 14389//14389 14416//14416 14417//14417 -f 14389//14389 14417//14417 14390//14390 -f 14390//14390 14417//14417 14418//14418 -f 14390//14390 14418//14418 14391//14391 -f 14391//14391 14418//14418 14419//14419 -f 14391//14391 14419//14419 14392//14392 -f 14392//14392 14419//14419 14420//14420 -f 14392//14392 14420//14420 14385//14385 -f 14385//14385 14420//14420 14421//14421 -f 14385//14385 14421//14421 14386//14386 -f 14386//14386 14421//14421 14422//14422 -f 14386//14386 14422//14422 14387//14387 -f 14387//14387 14422//14422 14423//14423 -f 14387//14387 14423//14423 14388//14388 -f 14388//14388 14423//14423 14424//14424 -f 14388//14388 14424//14424 14381//14381 -f 14381//14381 14424//14424 14425//14425 -f 14381//14381 14425//14425 14382//14382 -f 14382//14382 14425//14425 14426//14426 -f 14382//14382 14426//14426 14383//14383 -f 14383//14383 14426//14426 14427//14427 -f 14383//14383 14427//14427 14384//14384 -f 14384//14384 14427//14427 14428//14428 -f 14384//14384 14428//14428 14379//14379 -f 14379//14379 14428//14428 14429//14429 -f 14379//14379 14429//14429 14380//14380 -f 14380//14380 14429//14429 14257//14257 -f 14380//14380 14257//14257 14256//14256 -f 14430//14430 14408//14408 14431//14431 -f 14431//14431 14408//14408 14409//14409 -f 14431//14431 14409//14409 14432//14432 -f 14432//14432 14409//14409 14410//14410 -f 14432//14432 14410//14410 14433//14433 -f 14433//14433 14410//14410 14411//14411 -f 14433//14433 14411//14411 14297//14297 -f 14297//14297 14411//14411 14216//14216 -f 14297//14297 14216//14216 14298//14298 -f 14298//14298 14216//14216 14219//14219 -f 14298//14298 14219//14219 14300//14300 -f 14300//14300 14219//14219 14221//14221 -f 14300//14300 14221//14221 14302//14302 -f 14302//14302 14221//14221 14223//14223 -f 14302//14302 14223//14223 14304//14304 -f 14322//14322 14247//14247 14324//14324 -f 14324//14324 14247//14247 14249//14249 -f 14324//14324 14249//14249 14326//14326 -f 14326//14326 14249//14249 14251//14251 -f 14326//14326 14251//14251 14328//14328 -f 14328//14328 14251//14251 14253//14253 -f 14328//14328 14253//14253 14330//14330 -f 14330//14330 14253//14253 14255//14255 -f 14330//14330 14255//14255 14434//14434 -f 14434//14434 14255//14255 14394//14394 -f 14434//14434 14394//14394 14435//14435 -f 14435//14435 14394//14394 14395//14395 -f 14435//14435 14395//14395 14436//14436 -f 14436//14436 14395//14395 14396//14396 -f 14436//14436 14396//14396 14437//14437 -f 14223//14223 14225//14225 14304//14304 -f 14304//14304 14225//14225 14227//14227 -f 14304//14304 14227//14227 14306//14306 -f 14306//14306 14227//14227 14229//14229 -f 14306//14306 14229//14229 14308//14308 -f 14308//14308 14229//14229 14231//14231 -f 14308//14308 14231//14231 14310//14310 -f 14310//14310 14231//14231 14233//14233 -f 14310//14310 14233//14233 14312//14312 -f 14312//14312 14233//14233 14235//14235 -f 14312//14312 14235//14235 14314//14314 -f 14314//14314 14235//14235 14237//14237 -f 14314//14314 14237//14237 14316//14316 -f 14316//14316 14237//14237 14239//14239 -f 14316//14316 14239//14239 14318//14318 -f 14318//14318 14239//14239 14241//14241 -f 14318//14318 14241//14241 14320//14320 -f 14320//14320 14241//14241 14243//14243 -f 14320//14320 14243//14243 14322//14322 -f 14322//14322 14243//14243 14245//14245 -f 14322//14322 14245//14245 14247//14247 -f 14396//14396 14397//14397 14437//14437 -f 14437//14437 14397//14397 14398//14398 -f 14437//14437 14398//14398 14438//14438 -f 14438//14438 14398//14398 14399//14399 -f 14438//14438 14399//14399 14439//14439 -f 14439//14439 14399//14399 14400//14400 -f 14439//14439 14400//14400 14440//14440 -f 14440//14440 14400//14400 14401//14401 -f 14440//14440 14401//14401 14441//14441 -f 14441//14441 14401//14401 14402//14402 -f 14441//14441 14402//14402 14442//14442 -f 14442//14442 14402//14402 14403//14403 -f 14442//14442 14403//14403 14443//14443 -f 14443//14443 14403//14403 14404//14404 -f 14443//14443 14404//14404 14444//14444 -f 14444//14444 14404//14404 14405//14405 -f 14444//14444 14405//14405 14445//14445 -f 14445//14445 14405//14405 14406//14406 -f 14445//14445 14406//14406 14430//14430 -f 14430//14430 14406//14406 14407//14407 -f 14430//14430 14407//14407 14408//14408 -f 14446//14446 14415//14415 14447//14447 -f 14447//14447 14415//14415 14414//14414 -f 14447//14447 14414//14414 14448//14448 -f 14448//14448 14414//14414 14413//14413 -f 14448//14448 14413//14413 14449//14449 -f 14449//14449 14413//14413 14412//14412 -f 14449//14449 14412//14412 14331//14331 -f 14331//14331 14412//14412 14294//14294 -f 14331//14331 14294//14294 14329//14329 -f 14329//14329 14294//14294 14292//14292 -f 14329//14329 14292//14292 14327//14327 -f 14327//14327 14292//14292 14290//14290 -f 14327//14327 14290//14290 14325//14325 -f 14325//14325 14290//14290 14288//14288 -f 14325//14325 14288//14288 14323//14323 -f 14305//14305 14264//14264 14303//14303 -f 14303//14303 14264//14264 14262//14262 -f 14303//14303 14262//14262 14301//14301 -f 14301//14301 14262//14262 14260//14260 -f 14301//14301 14260//14260 14299//14299 -f 14299//14299 14260//14260 14258//14258 -f 14299//14299 14258//14258 14296//14296 -f 14296//14296 14258//14258 14257//14257 -f 14296//14296 14257//14257 14450//14450 -f 14450//14450 14257//14257 14429//14429 -f 14450//14450 14429//14429 14451//14451 -f 14451//14451 14429//14429 14428//14428 -f 14451//14451 14428//14428 14452//14452 -f 14452//14452 14428//14428 14427//14427 -f 14452//14452 14427//14427 14453//14453 -f 14288//14288 14286//14286 14323//14323 -f 14323//14323 14286//14286 14284//14284 -f 14323//14323 14284//14284 14321//14321 -f 14321//14321 14284//14284 14282//14282 -f 14321//14321 14282//14282 14319//14319 -f 14319//14319 14282//14282 14280//14280 -f 14319//14319 14280//14280 14317//14317 -f 14317//14317 14280//14280 14278//14278 -f 14317//14317 14278//14278 14315//14315 -f 14315//14315 14278//14278 14276//14276 -f 14315//14315 14276//14276 14313//14313 -f 14313//14313 14276//14276 14274//14274 -f 14313//14313 14274//14274 14311//14311 -f 14311//14311 14274//14274 14272//14272 -f 14311//14311 14272//14272 14309//14309 -f 14309//14309 14272//14272 14270//14270 -f 14309//14309 14270//14270 14307//14307 -f 14307//14307 14270//14270 14268//14268 -f 14307//14307 14268//14268 14305//14305 -f 14305//14305 14268//14268 14266//14266 -f 14305//14305 14266//14266 14264//14264 -f 14427//14427 14426//14426 14453//14453 -f 14453//14453 14426//14426 14425//14425 -f 14453//14453 14425//14425 14454//14454 -f 14454//14454 14425//14425 14424//14424 -f 14454//14454 14424//14424 14455//14455 -f 14455//14455 14424//14424 14423//14423 -f 14455//14455 14423//14423 14456//14456 -f 14456//14456 14423//14423 14422//14422 -f 14456//14456 14422//14422 14457//14457 -f 14457//14457 14422//14422 14421//14421 -f 14457//14457 14421//14421 14458//14458 -f 14458//14458 14421//14421 14420//14420 -f 14458//14458 14420//14420 14459//14459 -f 14459//14459 14420//14420 14419//14419 -f 14459//14459 14419//14419 14460//14460 -f 14460//14460 14419//14419 14418//14418 -f 14460//14460 14418//14418 14461//14461 -f 14461//14461 14418//14418 14417//14417 -f 14461//14461 14417//14417 14446//14446 -f 14446//14446 14417//14417 14416//14416 -f 14446//14446 14416//14416 14415//14415 -f 14331//14331 14330//14330 14434//14434 -f 14331//14331 14434//14434 14449//14449 -f 14449//14449 14434//14434 14435//14435 -f 14449//14449 14435//14435 14448//14448 -f 14448//14448 14435//14435 14436//14436 -f 14448//14448 14436//14436 14447//14447 -f 14447//14447 14436//14436 14437//14437 -f 14447//14447 14437//14437 14446//14446 -f 14446//14446 14437//14437 14438//14438 -f 14446//14446 14438//14438 14461//14461 -f 14461//14461 14438//14438 14439//14439 -f 14461//14461 14439//14439 14460//14460 -f 14460//14460 14439//14439 14440//14440 -f 14460//14460 14440//14440 14459//14459 -f 14459//14459 14440//14440 14441//14441 -f 14459//14459 14441//14441 14458//14458 -f 14458//14458 14441//14441 14442//14442 -f 14458//14458 14442//14442 14457//14457 -f 14457//14457 14442//14442 14443//14443 -f 14457//14457 14443//14443 14456//14456 -f 14456//14456 14443//14443 14444//14444 -f 14456//14456 14444//14444 14455//14455 -f 14455//14455 14444//14444 14445//14445 -f 14455//14455 14445//14445 14454//14454 -f 14454//14454 14445//14445 14430//14430 -f 14454//14454 14430//14430 14453//14453 -f 14453//14453 14430//14430 14431//14431 -f 14453//14453 14431//14431 14452//14452 -f 14452//14452 14431//14431 14432//14432 -f 14452//14452 14432//14432 14451//14451 -f 14451//14451 14432//14432 14433//14433 -f 14451//14451 14433//14433 14450//14450 -f 14450//14450 14433//14433 14297//14297 -f 14450//14450 14297//14297 14296//14296 -f 14462//14462 14463//14463 14464//14464 -f 14464//14464 14463//14463 14465//14465 -f 14464//14464 14465//14465 14466//14466 -f 14466//14466 14465//14465 14467//14467 -f 14466//14466 14467//14467 14468//14468 -f 14468//14468 14467//14467 14469//14469 -f 14468//14468 14469//14469 14470//14470 -f 14470//14470 14469//14469 14471//14471 -f 14470//14470 14471//14471 14472//14472 -f 14472//14472 14471//14471 14473//14473 -f 14472//14472 14473//14473 14474//14474 -f 14474//14474 14473//14473 14475//14475 -f 14474//14474 14475//14475 14476//14476 -f 14476//14476 14475//14475 14477//14477 -f 14476//14476 14477//14477 14478//14478 -f 14478//14478 14477//14477 14479//14479 -f 14478//14478 14479//14479 14480//14480 -f 14480//14480 14479//14479 14481//14481 -f 14480//14480 14481//14481 14482//14482 -f 14482//14482 14481//14481 14483//14483 -f 14482//14482 14483//14483 14484//14484 -f 14484//14484 14483//14483 14485//14485 -f 14484//14484 14485//14485 14486//14486 -f 14486//14486 14485//14485 14487//14487 -f 14486//14486 14487//14487 14488//14488 -f 14488//14488 14487//14487 14489//14489 -f 14488//14488 14489//14489 14490//14490 -f 14490//14490 14489//14489 14491//14491 -f 14492//14492 14493//14493 14494//14494 -f 14492//14492 14494//14494 14495//14495 -f 14495//14495 14494//14494 14496//14496 -f 14495//14495 14496//14496 14497//14497 -f 14497//14497 14496//14496 14498//14498 -f 14497//14497 14498//14498 14499//14499 -f 14499//14499 14498//14498 14500//14500 -f 14499//14499 14500//14500 14501//14501 -f 14501//14501 14500//14500 14502//14502 -f 14501//14501 14502//14502 14503//14503 -f 14503//14503 14502//14502 14504//14504 -f 14503//14503 14504//14504 14505//14505 -f 14505//14505 14504//14504 14506//14506 -f 14505//14505 14506//14506 14507//14507 -f 14507//14507 14506//14506 14508//14508 -f 14507//14507 14508//14508 14509//14509 -f 14509//14509 14508//14508 14510//14510 -f 14509//14509 14510//14510 14511//14511 -f 14511//14511 14510//14510 14512//14512 -f 14511//14511 14512//14512 14513//14513 -f 14513//14513 14512//14512 14514//14514 -f 14513//14513 14514//14514 14515//14515 -f 14515//14515 14514//14514 14516//14516 -f 14515//14515 14516//14516 14517//14517 -f 14517//14517 14516//14516 14518//14518 -f 14517//14517 14518//14518 14519//14519 -f 14519//14519 14518//14518 14520//14520 -f 14519//14519 14520//14520 14521//14521 -f 14521//14521 14520//14520 14522//14522 -f 14521//14521 14522//14522 14523//14523 -f 14523//14523 14522//14522 14524//14524 -f 14523//14523 14524//14524 14525//14525 -f 14525//14525 14524//14524 14526//14526 -f 14525//14525 14526//14526 14527//14527 -f 14527//14527 14526//14526 14528//14528 -f 14527//14527 14528//14528 14529//14529 -f 14529//14529 14528//14528 14530//14530 -f 14529//14529 14530//14530 14531//14531 -f 14532//14532 14533//14533 14534//14534 -f 14532//14532 14534//14534 14535//14535 -f 14535//14535 14534//14534 14536//14536 -f 14535//14535 14536//14536 14537//14537 -f 14537//14537 14536//14536 14538//14538 -f 14537//14537 14538//14538 14539//14539 -f 14539//14539 14538//14538 14540//14540 -f 14539//14539 14540//14540 14541//14541 -f 14541//14541 14540//14540 14542//14542 -f 14541//14541 14542//14542 14543//14543 -f 14543//14543 14542//14542 14544//14544 -f 14543//14543 14544//14544 14545//14545 -f 14545//14545 14544//14544 14546//14546 -f 14545//14545 14546//14546 14547//14547 -f 14547//14547 14546//14546 14548//14548 -f 14547//14547 14548//14548 14549//14549 -f 14549//14549 14548//14548 14550//14550 -f 14549//14549 14550//14550 14551//14551 -f 14551//14551 14550//14550 14552//14552 -f 14551//14551 14552//14552 14553//14553 -f 14553//14553 14552//14552 14554//14554 -f 14553//14553 14554//14554 14555//14555 -f 14555//14555 14554//14554 14556//14556 -f 14555//14555 14556//14556 14557//14557 -f 14557//14557 14556//14556 14558//14558 -f 14557//14557 14558//14558 14559//14559 -f 14559//14559 14558//14558 14560//14560 -f 14559//14559 14560//14560 14561//14561 -f 14561//14561 14560//14560 14562//14562 -f 14561//14561 14562//14562 14563//14563 -f 14563//14563 14562//14562 14564//14564 -f 14563//14563 14564//14564 14565//14565 -f 14565//14565 14564//14564 14566//14566 -f 14565//14565 14566//14566 14567//14567 -f 14567//14567 14566//14566 14568//14568 -f 14567//14567 14568//14568 14569//14569 -f 14569//14569 14568//14568 14570//14570 -f 14569//14569 14570//14570 14571//14571 -f 14572//14572 14573//14573 14574//14574 -f 14572//14572 14574//14574 14575//14575 -f 14575//14575 14574//14574 14576//14576 -f 14575//14575 14576//14576 14577//14577 -f 14577//14577 14576//14576 14578//14578 -f 14577//14577 14578//14578 14579//14579 -f 14579//14579 14578//14578 14580//14580 -f 14579//14579 14580//14580 14581//14581 -f 14581//14581 14580//14580 14582//14582 -f 14581//14581 14582//14582 14583//14583 -f 14583//14583 14582//14582 14584//14584 -f 14583//14583 14584//14584 14585//14585 -f 14585//14585 14584//14584 14586//14586 -f 14585//14585 14586//14586 14587//14587 -f 14587//14587 14586//14586 14588//14588 -f 14587//14587 14588//14588 14589//14589 -f 14589//14589 14588//14588 14590//14590 -f 14589//14589 14590//14590 14591//14591 -f 14591//14591 14590//14590 14592//14592 -f 14591//14591 14592//14592 14593//14593 -f 14593//14593 14592//14592 14594//14594 -f 14593//14593 14594//14594 14595//14595 -f 14595//14595 14594//14594 14596//14596 -f 14595//14595 14596//14596 14597//14597 -f 14597//14597 14596//14596 14598//14598 -f 14597//14597 14598//14598 14599//14599 -f 14599//14599 14598//14598 14600//14600 -f 14599//14599 14600//14600 14601//14601 -f 14601//14601 14600//14600 14602//14602 -f 14601//14601 14602//14602 14603//14603 -f 14603//14603 14602//14602 14604//14604 -f 14603//14603 14604//14604 14605//14605 -f 14605//14605 14604//14604 14606//14606 -f 14605//14605 14606//14606 14607//14607 -f 14490//14490 14491//14491 14608//14608 -f 14608//14608 14491//14491 14609//14609 -f 14608//14608 14609//14609 14610//14610 -f 14610//14610 14609//14609 14611//14611 -f 14610//14610 14611//14611 14612//14612 -f 14612//14612 14611//14611 14613//14613 -f 14612//14612 14613//14613 14614//14614 -f 14614//14614 14613//14613 14615//14615 -f 14614//14614 14615//14615 14616//14616 -f 14616//14616 14615//14615 14617//14617 -f 14616//14616 14617//14617 14618//14618 -f 14618//14618 14617//14617 14619//14619 -f 14618//14618 14619//14619 14620//14620 -f 14620//14620 14619//14619 14621//14621 -f 14620//14620 14621//14621 14622//14622 -f 14622//14622 14621//14621 14623//14623 -f 14622//14622 14623//14623 14624//14624 -f 14624//14624 14623//14623 14625//14625 -f 14624//14624 14625//14625 14626//14626 -f 14626//14626 14625//14625 14627//14627 -f 14626//14626 14627//14627 14628//14628 -f 14628//14628 14627//14627 14629//14629 -f 14628//14628 14629//14629 14630//14630 -f 14630//14630 14629//14629 14631//14631 -f 14630//14630 14631//14631 14632//14632 -f 14632//14632 14631//14631 14633//14633 -f 14632//14632 14633//14633 14462//14462 -f 14462//14462 14633//14633 14463//14463 -f 14610//14610 14496//14496 14608//14608 -f 14608//14608 14496//14496 14494//14494 -f 14608//14608 14494//14494 14490//14490 -f 14490//14490 14494//14494 14493//14493 -f 14490//14490 14493//14493 14488//14488 -f 14466//14466 14634//14634 14464//14464 -f 14464//14464 14634//14634 14635//14635 -f 14464//14464 14635//14635 14462//14462 -f 14462//14462 14635//14635 14530//14530 -f 14462//14462 14530//14530 14632//14632 -f 14472//14472 14636//14636 14470//14470 -f 14470//14470 14636//14636 14637//14637 -f 14470//14470 14637//14637 14468//14468 -f 14468//14468 14637//14637 14638//14638 -f 14468//14468 14638//14638 14466//14466 -f 14466//14466 14638//14638 14639//14639 -f 14466//14466 14639//14639 14634//14634 -f 14476//14476 14640//14640 14474//14474 -f 14474//14474 14640//14640 14641//14641 -f 14474//14474 14641//14641 14472//14472 -f 14472//14472 14641//14641 14642//14642 -f 14472//14472 14642//14642 14636//14636 -f 14616//14616 14504//14504 14614//14614 -f 14614//14614 14504//14504 14502//14502 -f 14614//14614 14502//14502 14612//14612 -f 14612//14612 14502//14502 14500//14500 -f 14612//14612 14500//14500 14610//14610 -f 14610//14610 14500//14500 14498//14498 -f 14610//14610 14498//14498 14496//14496 -f 14620//14620 14510//14510 14618//14618 -f 14618//14618 14510//14510 14508//14508 -f 14618//14618 14508//14508 14616//14616 -f 14616//14616 14508//14508 14506//14506 -f 14616//14616 14506//14506 14504//14504 -f 14530//14530 14528//14528 14632//14632 -f 14632//14632 14528//14528 14526//14526 -f 14632//14632 14526//14526 14630//14630 -f 14630//14630 14526//14526 14524//14524 -f 14630//14630 14524//14524 14628//14628 -f 14628//14628 14524//14524 14522//14522 -f 14628//14628 14522//14522 14626//14626 -f 14522//14522 14520//14520 14626//14626 -f 14626//14626 14520//14520 14518//14518 -f 14626//14626 14518//14518 14624//14624 -f 14624//14624 14518//14518 14516//14516 -f 14624//14624 14516//14516 14622//14622 -f 14622//14622 14516//14516 14514//14514 -f 14622//14622 14514//14514 14620//14620 -f 14620//14620 14514//14514 14512//14512 -f 14620//14620 14512//14512 14510//14510 -f 14482//14482 14643//14643 14480//14480 -f 14480//14480 14643//14643 14644//14644 -f 14480//14480 14644//14644 14478//14478 -f 14478//14478 14644//14644 14645//14645 -f 14478//14478 14645//14645 14476//14476 -f 14476//14476 14645//14645 14646//14646 -f 14476//14476 14646//14646 14640//14640 -f 14493//14493 14647//14647 14488//14488 -f 14488//14488 14647//14647 14648//14648 -f 14488//14488 14648//14648 14486//14486 -f 14486//14486 14648//14648 14649//14649 -f 14486//14486 14649//14649 14484//14484 -f 14484//14484 14649//14649 14650//14650 -f 14484//14484 14650//14650 14482//14482 -f 14482//14482 14650//14650 14651//14651 -f 14482//14482 14651//14651 14643//14643 -f 14609//14609 14537//14537 14611//14611 -f 14611//14611 14537//14537 14539//14539 -f 14611//14611 14539//14539 14613//14613 -f 14613//14613 14539//14539 14541//14541 -f 14613//14613 14541//14541 14615//14615 -f 14631//14631 14567//14567 14633//14633 -f 14633//14633 14567//14567 14569//14569 -f 14633//14633 14569//14569 14463//14463 -f 14463//14463 14569//14569 14571//14571 -f 14463//14463 14571//14571 14465//14465 -f 14619//14619 14551//14551 14621//14621 -f 14621//14621 14551//14551 14553//14553 -f 14621//14621 14553//14553 14623//14623 -f 14623//14623 14553//14553 14555//14555 -f 14623//14623 14555//14555 14625//14625 -f 14471//14471 14652//14652 14473//14473 -f 14473//14473 14652//14652 14653//14653 -f 14473//14473 14653//14653 14475//14475 -f 14571//14571 14654//14654 14465//14465 -f 14465//14465 14654//14654 14655//14655 -f 14465//14465 14655//14655 14467//14467 -f 14467//14467 14655//14655 14656//14656 -f 14467//14467 14656//14656 14469//14469 -f 14469//14469 14656//14656 14657//14657 -f 14469//14469 14657//14657 14471//14471 -f 14471//14471 14657//14657 14658//14658 -f 14471//14471 14658//14658 14652//14652 -f 14555//14555 14557//14557 14625//14625 -f 14625//14625 14557//14557 14559//14559 -f 14625//14625 14559//14559 14627//14627 -f 14627//14627 14559//14559 14561//14561 -f 14627//14627 14561//14561 14629//14629 -f 14629//14629 14561//14561 14563//14563 -f 14629//14629 14563//14563 14631//14631 -f 14631//14631 14563//14563 14565//14565 -f 14631//14631 14565//14565 14567//14567 -f 14541//14541 14543//14543 14615//14615 -f 14615//14615 14543//14543 14545//14545 -f 14615//14615 14545//14545 14617//14617 -f 14617//14617 14545//14545 14547//14547 -f 14617//14617 14547//14547 14619//14619 -f 14619//14619 14547//14547 14549//14549 -f 14619//14619 14549//14549 14551//14551 -f 14653//14653 14659//14659 14475//14475 -f 14475//14475 14659//14659 14660//14660 -f 14475//14475 14660//14660 14477//14477 -f 14477//14477 14660//14660 14661//14661 -f 14477//14477 14661//14661 14479//14479 -f 14479//14479 14661//14661 14662//14662 -f 14479//14479 14662//14662 14481//14481 -f 14487//14487 14663//14663 14489//14489 -f 14489//14489 14663//14663 14664//14664 -f 14489//14489 14664//14664 14491//14491 -f 14491//14491 14664//14664 14532//14532 -f 14491//14491 14532//14532 14609//14609 -f 14609//14609 14532//14532 14535//14535 -f 14609//14609 14535//14535 14537//14537 -f 14662//14662 14665//14665 14481//14481 -f 14481//14481 14665//14665 14666//14666 -f 14481//14481 14666//14666 14483//14483 -f 14483//14483 14666//14666 14667//14667 -f 14483//14483 14667//14667 14485//14485 -f 14485//14485 14667//14667 14668//14668 -f 14485//14485 14668//14668 14487//14487 -f 14487//14487 14668//14668 14669//14669 -f 14487//14487 14669//14669 14663//14663 -f 14531//14531 14530//14530 14635//14635 -f 14531//14531 14635//14635 14670//14670 -f 14670//14670 14635//14635 14634//14634 -f 14670//14670 14634//14634 14671//14671 -f 14671//14671 14634//14634 14639//14639 -f 14671//14671 14639//14639 14672//14672 -f 14672//14672 14639//14639 14638//14638 -f 14672//14672 14638//14638 14673//14673 -f 14673//14673 14638//14638 14637//14637 -f 14673//14673 14637//14637 14674//14674 -f 14674//14674 14637//14637 14636//14636 -f 14674//14674 14636//14636 14675//14675 -f 14675//14675 14636//14636 14642//14642 -f 14675//14675 14642//14642 14676//14676 -f 14676//14676 14642//14642 14641//14641 -f 14676//14676 14641//14641 14677//14677 -f 14677//14677 14641//14641 14640//14640 -f 14677//14677 14640//14640 14678//14678 -f 14678//14678 14640//14640 14646//14646 -f 14678//14678 14646//14646 14679//14679 -f 14679//14679 14646//14646 14645//14645 -f 14679//14679 14645//14645 14680//14680 -f 14680//14680 14645//14645 14644//14644 -f 14680//14680 14644//14644 14681//14681 -f 14681//14681 14644//14644 14643//14643 -f 14681//14681 14643//14643 14682//14682 -f 14682//14682 14643//14643 14651//14651 -f 14682//14682 14651//14651 14683//14683 -f 14683//14683 14651//14651 14650//14650 -f 14683//14683 14650//14650 14684//14684 -f 14684//14684 14650//14650 14649//14649 -f 14684//14684 14649//14649 14685//14685 -f 14685//14685 14649//14649 14648//14648 -f 14685//14685 14648//14648 14686//14686 -f 14686//14686 14648//14648 14647//14647 -f 14686//14686 14647//14647 14687//14687 -f 14687//14687 14647//14647 14493//14493 -f 14687//14687 14493//14493 14492//14492 -f 14571//14571 14570//14570 14688//14688 -f 14571//14571 14688//14688 14654//14654 -f 14654//14654 14688//14688 14689//14689 -f 14654//14654 14689//14689 14655//14655 -f 14655//14655 14689//14689 14690//14690 -f 14655//14655 14690//14690 14656//14656 -f 14656//14656 14690//14690 14691//14691 -f 14656//14656 14691//14691 14657//14657 -f 14657//14657 14691//14691 14692//14692 -f 14657//14657 14692//14692 14658//14658 -f 14658//14658 14692//14692 14693//14693 -f 14658//14658 14693//14693 14652//14652 -f 14652//14652 14693//14693 14694//14694 -f 14652//14652 14694//14694 14653//14653 -f 14653//14653 14694//14694 14695//14695 -f 14653//14653 14695//14695 14659//14659 -f 14659//14659 14695//14695 14696//14696 -f 14659//14659 14696//14696 14660//14660 -f 14660//14660 14696//14696 14697//14697 -f 14660//14660 14697//14697 14661//14661 -f 14661//14661 14697//14697 14698//14698 -f 14661//14661 14698//14698 14662//14662 -f 14662//14662 14698//14698 14699//14699 -f 14662//14662 14699//14699 14665//14665 -f 14665//14665 14699//14699 14700//14700 -f 14665//14665 14700//14700 14666//14666 -f 14666//14666 14700//14700 14701//14701 -f 14666//14666 14701//14701 14667//14667 -f 14667//14667 14701//14701 14702//14702 -f 14667//14667 14702//14702 14668//14668 -f 14668//14668 14702//14702 14703//14703 -f 14668//14668 14703//14703 14669//14669 -f 14669//14669 14703//14703 14704//14704 -f 14669//14669 14704//14704 14663//14663 -f 14663//14663 14704//14704 14705//14705 -f 14663//14663 14705//14705 14664//14664 -f 14664//14664 14705//14705 14533//14533 -f 14664//14664 14533//14533 14532//14532 -f 14706//14706 14684//14684 14707//14707 -f 14707//14707 14684//14684 14685//14685 -f 14707//14707 14685//14685 14708//14708 -f 14708//14708 14685//14685 14686//14686 -f 14708//14708 14686//14686 14709//14709 -f 14709//14709 14686//14686 14687//14687 -f 14709//14709 14687//14687 14573//14573 -f 14573//14573 14687//14687 14492//14492 -f 14573//14573 14492//14492 14574//14574 -f 14574//14574 14492//14492 14495//14495 -f 14574//14574 14495//14495 14576//14576 -f 14576//14576 14495//14495 14497//14497 -f 14576//14576 14497//14497 14578//14578 -f 14578//14578 14497//14497 14499//14499 -f 14578//14578 14499//14499 14580//14580 -f 14710//14710 14674//14674 14711//14711 -f 14711//14711 14674//14674 14675//14675 -f 14711//14711 14675//14675 14712//14712 -f 14712//14712 14675//14675 14676//14676 -f 14712//14712 14676//14676 14713//14713 -f 14713//14713 14676//14676 14677//14677 -f 14713//14713 14677//14677 14714//14714 -f 14714//14714 14677//14677 14678//14678 -f 14714//14714 14678//14678 14715//14715 -f 14715//14715 14678//14678 14679//14679 -f 14715//14715 14679//14679 14716//14716 -f 14716//14716 14679//14679 14680//14680 -f 14716//14716 14680//14680 14717//14717 -f 14717//14717 14680//14680 14681//14681 -f 14717//14717 14681//14681 14718//14718 -f 14718//14718 14681//14681 14682//14682 -f 14718//14718 14682//14682 14706//14706 -f 14706//14706 14682//14682 14683//14683 -f 14706//14706 14683//14683 14684//14684 -f 14598//14598 14523//14523 14600//14600 -f 14600//14600 14523//14523 14525//14525 -f 14600//14600 14525//14525 14602//14602 -f 14602//14602 14525//14525 14527//14527 -f 14602//14602 14527//14527 14604//14604 -f 14604//14604 14527//14527 14529//14529 -f 14604//14604 14529//14529 14606//14606 -f 14606//14606 14529//14529 14531//14531 -f 14606//14606 14531//14531 14719//14719 -f 14719//14719 14531//14531 14670//14670 -f 14719//14719 14670//14670 14720//14720 -f 14720//14720 14670//14670 14671//14671 -f 14720//14720 14671//14671 14721//14721 -f 14721//14721 14671//14671 14672//14672 -f 14721//14721 14672//14672 14710//14710 -f 14710//14710 14672//14672 14673//14673 -f 14710//14710 14673//14673 14674//14674 -f 14499//14499 14501//14501 14580//14580 -f 14580//14580 14501//14501 14503//14503 -f 14580//14580 14503//14503 14582//14582 -f 14582//14582 14503//14503 14505//14505 -f 14582//14582 14505//14505 14584//14584 -f 14584//14584 14505//14505 14507//14507 -f 14584//14584 14507//14507 14586//14586 -f 14586//14586 14507//14507 14509//14509 -f 14586//14586 14509//14509 14588//14588 -f 14588//14588 14509//14509 14511//14511 -f 14588//14588 14511//14511 14590//14590 -f 14590//14590 14511//14511 14513//14513 -f 14590//14590 14513//14513 14592//14592 -f 14592//14592 14513//14513 14515//14515 -f 14592//14592 14515//14515 14594//14594 -f 14594//14594 14515//14515 14517//14517 -f 14594//14594 14517//14517 14596//14596 -f 14596//14596 14517//14517 14519//14519 -f 14596//14596 14519//14519 14598//14598 -f 14598//14598 14519//14519 14521//14521 -f 14598//14598 14521//14521 14523//14523 -f 14722//14722 14691//14691 14723//14723 -f 14723//14723 14691//14691 14690//14690 -f 14723//14723 14690//14690 14724//14724 -f 14724//14724 14690//14690 14689//14689 -f 14724//14724 14689//14689 14725//14725 -f 14725//14725 14689//14689 14688//14688 -f 14725//14725 14688//14688 14607//14607 -f 14607//14607 14688//14688 14570//14570 -f 14607//14607 14570//14570 14605//14605 -f 14605//14605 14570//14570 14568//14568 -f 14605//14605 14568//14568 14603//14603 -f 14603//14603 14568//14568 14566//14566 -f 14603//14603 14566//14566 14601//14601 -f 14601//14601 14566//14566 14564//14564 -f 14601//14601 14564//14564 14599//14599 -f 14726//14726 14701//14701 14727//14727 -f 14727//14727 14701//14701 14700//14700 -f 14727//14727 14700//14700 14728//14728 -f 14728//14728 14700//14700 14699//14699 -f 14728//14728 14699//14699 14729//14729 -f 14729//14729 14699//14699 14698//14698 -f 14729//14729 14698//14698 14730//14730 -f 14730//14730 14698//14698 14697//14697 -f 14730//14730 14697//14697 14731//14731 -f 14731//14731 14697//14697 14696//14696 -f 14731//14731 14696//14696 14732//14732 -f 14732//14732 14696//14696 14695//14695 -f 14732//14732 14695//14695 14733//14733 -f 14733//14733 14695//14695 14694//14694 -f 14733//14733 14694//14694 14734//14734 -f 14734//14734 14694//14694 14693//14693 -f 14734//14734 14693//14693 14722//14722 -f 14722//14722 14693//14693 14692//14692 -f 14722//14722 14692//14692 14691//14691 -f 14581//14581 14540//14540 14579//14579 -f 14579//14579 14540//14540 14538//14538 -f 14579//14579 14538//14538 14577//14577 -f 14577//14577 14538//14538 14536//14536 -f 14577//14577 14536//14536 14575//14575 -f 14575//14575 14536//14536 14534//14534 -f 14575//14575 14534//14534 14572//14572 -f 14572//14572 14534//14534 14533//14533 -f 14572//14572 14533//14533 14735//14735 -f 14735//14735 14533//14533 14705//14705 -f 14735//14735 14705//14705 14736//14736 -f 14736//14736 14705//14705 14704//14704 -f 14736//14736 14704//14704 14737//14737 -f 14737//14737 14704//14704 14703//14703 -f 14737//14737 14703//14703 14726//14726 -f 14726//14726 14703//14703 14702//14702 -f 14726//14726 14702//14702 14701//14701 -f 14564//14564 14562//14562 14599//14599 -f 14599//14599 14562//14562 14560//14560 -f 14599//14599 14560//14560 14597//14597 -f 14597//14597 14560//14560 14558//14558 -f 14597//14597 14558//14558 14595//14595 -f 14595//14595 14558//14558 14556//14556 -f 14595//14595 14556//14556 14593//14593 -f 14593//14593 14556//14556 14554//14554 -f 14593//14593 14554//14554 14591//14591 -f 14591//14591 14554//14554 14552//14552 -f 14591//14591 14552//14552 14589//14589 -f 14589//14589 14552//14552 14550//14550 -f 14589//14589 14550//14550 14587//14587 -f 14587//14587 14550//14550 14548//14548 -f 14587//14587 14548//14548 14585//14585 -f 14585//14585 14548//14548 14546//14546 -f 14585//14585 14546//14546 14583//14583 -f 14583//14583 14546//14546 14544//14544 -f 14583//14583 14544//14544 14581//14581 -f 14581//14581 14544//14544 14542//14542 -f 14581//14581 14542//14542 14540//14540 -f 14607//14607 14606//14606 14719//14719 -f 14607//14607 14719//14719 14725//14725 -f 14725//14725 14719//14719 14720//14720 -f 14725//14725 14720//14720 14724//14724 -f 14724//14724 14720//14720 14721//14721 -f 14724//14724 14721//14721 14723//14723 -f 14723//14723 14721//14721 14710//14710 -f 14723//14723 14710//14710 14722//14722 -f 14722//14722 14710//14710 14711//14711 -f 14722//14722 14711//14711 14734//14734 -f 14734//14734 14711//14711 14712//14712 -f 14734//14734 14712//14712 14733//14733 -f 14733//14733 14712//14712 14713//14713 -f 14733//14733 14713//14713 14732//14732 -f 14732//14732 14713//14713 14714//14714 -f 14732//14732 14714//14714 14731//14731 -f 14731//14731 14714//14714 14715//14715 -f 14731//14731 14715//14715 14730//14730 -f 14730//14730 14715//14715 14716//14716 -f 14730//14730 14716//14716 14729//14729 -f 14729//14729 14716//14716 14717//14717 -f 14729//14729 14717//14717 14728//14728 -f 14728//14728 14717//14717 14718//14718 -f 14728//14728 14718//14718 14727//14727 -f 14727//14727 14718//14718 14706//14706 -f 14727//14727 14706//14706 14726//14726 -f 14726//14726 14706//14706 14707//14707 -f 14726//14726 14707//14707 14737//14737 -f 14737//14737 14707//14707 14708//14708 -f 14737//14737 14708//14708 14736//14736 -f 14736//14736 14708//14708 14709//14709 -f 14736//14736 14709//14709 14735//14735 -f 14735//14735 14709//14709 14573//14573 -f 14735//14735 14573//14573 14572//14572 -f 14738//14738 14739//14739 14740//14740 -f 14740//14740 14739//14739 14741//14741 -f 14740//14740 14741//14741 14742//14742 -f 14742//14742 14741//14741 14743//14743 -f 14742//14742 14743//14743 14744//14744 -f 14744//14744 14743//14743 14745//14745 -f 14744//14744 14745//14745 14746//14746 -f 14746//14746 14745//14745 14747//14747 -f 14746//14746 14747//14747 14748//14748 -f 14748//14748 14747//14747 14749//14749 -f 14748//14748 14749//14749 14750//14750 -f 14750//14750 14749//14749 14751//14751 -f 14750//14750 14751//14751 14752//14752 -f 14752//14752 14751//14751 14753//14753 -f 14752//14752 14753//14753 14754//14754 -f 14754//14754 14753//14753 14755//14755 -f 14754//14754 14755//14755 14756//14756 -f 14756//14756 14755//14755 14757//14757 -f 14756//14756 14757//14757 14758//14758 -f 14758//14758 14757//14757 14759//14759 -f 14758//14758 14759//14759 14760//14760 -f 14760//14760 14759//14759 14761//14761 -f 14760//14760 14761//14761 14762//14762 -f 14762//14762 14761//14761 14763//14763 -f 14762//14762 14763//14763 14764//14764 -f 14764//14764 14763//14763 14765//14765 -f 14764//14764 14765//14765 14766//14766 -f 14766//14766 14765//14765 14767//14767 -f 14768//14768 962//962 14769//14769 -f 14768//14768 14769//14769 14770//14770 -f 14770//14770 14769//14769 14771//14771 -f 14770//14770 14771//14771 14772//14772 -f 14772//14772 14771//14771 14773//14773 -f 14772//14772 14773//14773 14774//14774 -f 14774//14774 14773//14773 14775//14775 -f 14774//14774 14775//14775 14776//14776 -f 14776//14776 14775//14775 14777//14777 -f 14776//14776 14777//14777 14778//14778 -f 14778//14778 14777//14777 14779//14779 -f 14778//14778 14779//14779 14780//14780 -f 14780//14780 14779//14779 14781//14781 -f 14780//14780 14781//14781 14782//14782 -f 14782//14782 14781//14781 14783//14783 -f 14782//14782 14783//14783 14784//14784 -f 14784//14784 14783//14783 14785//14785 -f 14784//14784 14785//14785 14786//14786 -f 14786//14786 14785//14785 14787//14787 -f 14786//14786 14787//14787 14788//14788 -f 14788//14788 14787//14787 14789//14789 -f 14788//14788 14789//14789 14790//14790 -f 14790//14790 14789//14789 14791//14791 -f 14790//14790 14791//14791 14792//14792 -f 14792//14792 14791//14791 14793//14793 -f 14792//14792 14793//14793 14794//14794 -f 14794//14794 14793//14793 14795//14795 -f 14794//14794 14795//14795 14796//14796 -f 14796//14796 14795//14795 14797//14797 -f 14796//14796 14797//14797 14798//14798 -f 14798//14798 14797//14797 14799//14799 -f 14798//14798 14799//14799 14800//14800 -f 14800//14800 14799//14799 14801//14801 -f 14800//14800 14801//14801 14802//14802 -f 14802//14802 14801//14801 14803//14803 -f 14802//14802 14803//14803 14804//14804 -f 14804//14804 14803//14803 974//974 -f 14804//14804 974//974 14805//14805 -f 961//961 14806//14806 14807//14807 -f 961//961 14807//14807 14808//14808 -f 14808//14808 14807//14807 14809//14809 -f 14808//14808 14809//14809 14810//14810 -f 14810//14810 14809//14809 14811//14811 -f 14810//14810 14811//14811 14812//14812 -f 14812//14812 14811//14811 14813//14813 -f 14812//14812 14813//14813 14814//14814 -f 14814//14814 14813//14813 14815//14815 -f 14814//14814 14815//14815 14816//14816 -f 14816//14816 14815//14815 14817//14817 -f 14816//14816 14817//14817 14818//14818 -f 14818//14818 14817//14817 14819//14819 -f 14818//14818 14819//14819 14820//14820 -f 14820//14820 14819//14819 14821//14821 -f 14820//14820 14821//14821 14822//14822 -f 14822//14822 14821//14821 14823//14823 -f 14822//14822 14823//14823 14824//14824 -f 14824//14824 14823//14823 14825//14825 -f 14824//14824 14825//14825 14826//14826 -f 14826//14826 14825//14825 14827//14827 -f 14826//14826 14827//14827 14828//14828 -f 14828//14828 14827//14827 14829//14829 -f 14828//14828 14829//14829 14830//14830 -f 14830//14830 14829//14829 14831//14831 -f 14830//14830 14831//14831 14832//14832 -f 14832//14832 14831//14831 14833//14833 -f 14832//14832 14833//14833 14834//14834 -f 14834//14834 14833//14833 14835//14835 -f 14834//14834 14835//14835 14836//14836 -f 14836//14836 14835//14835 14837//14837 -f 14836//14836 14837//14837 14838//14838 -f 14838//14838 14837//14837 14839//14839 -f 14838//14838 14839//14839 14840//14840 -f 14840//14840 14839//14839 14841//14841 -f 14840//14840 14841//14841 14842//14842 -f 14842//14842 14841//14841 14843//14843 -f 14842//14842 14843//14843 973//973 -f 14844//14844 14845//14845 14846//14846 -f 14844//14844 14846//14846 14847//14847 -f 14847//14847 14846//14846 14848//14848 -f 14847//14847 14848//14848 14849//14849 -f 14849//14849 14848//14848 14850//14850 -f 14849//14849 14850//14850 14851//14851 -f 14851//14851 14850//14850 14852//14852 -f 14851//14851 14852//14852 14853//14853 -f 14853//14853 14852//14852 14854//14854 -f 14853//14853 14854//14854 14855//14855 -f 14855//14855 14854//14854 14856//14856 -f 14855//14855 14856//14856 14857//14857 -f 14857//14857 14856//14856 14858//14858 -f 14857//14857 14858//14858 14859//14859 -f 14859//14859 14858//14858 14860//14860 -f 14859//14859 14860//14860 14861//14861 -f 14861//14861 14860//14860 14862//14862 -f 14861//14861 14862//14862 14863//14863 -f 14863//14863 14862//14862 14864//14864 -f 14863//14863 14864//14864 14865//14865 -f 14865//14865 14864//14864 14866//14866 -f 14865//14865 14866//14866 14867//14867 -f 14867//14867 14866//14866 14868//14868 -f 14867//14867 14868//14868 14869//14869 -f 14869//14869 14868//14868 14870//14870 -f 14869//14869 14870//14870 14871//14871 -f 14871//14871 14870//14870 14872//14872 -f 14871//14871 14872//14872 14873//14873 -f 14873//14873 14872//14872 14874//14874 -f 14873//14873 14874//14874 14875//14875 -f 14875//14875 14874//14874 14876//14876 -f 14875//14875 14876//14876 14877//14877 -f 14877//14877 14876//14876 14878//14878 -f 14877//14877 14878//14878 14879//14879 -f 14766//14766 14767//14767 14880//14880 -f 14880//14880 14767//14767 14881//14881 -f 14880//14880 14881//14881 14882//14882 -f 14882//14882 14881//14881 14883//14883 -f 14882//14882 14883//14883 14884//14884 -f 14884//14884 14883//14883 14885//14885 -f 14884//14884 14885//14885 14886//14886 -f 14886//14886 14885//14885 14887//14887 -f 14886//14886 14887//14887 14888//14888 -f 14888//14888 14887//14887 14889//14889 -f 14888//14888 14889//14889 14890//14890 -f 14890//14890 14889//14889 14891//14891 -f 14890//14890 14891//14891 14892//14892 -f 14892//14892 14891//14891 14893//14893 -f 14892//14892 14893//14893 14894//14894 -f 14894//14894 14893//14893 14895//14895 -f 14894//14894 14895//14895 14896//14896 -f 14896//14896 14895//14895 14897//14897 -f 14896//14896 14897//14897 14898//14898 -f 14898//14898 14897//14897 14899//14899 -f 14898//14898 14899//14899 14900//14900 -f 14900//14900 14899//14899 14901//14901 -f 14900//14900 14901//14901 14902//14902 -f 14902//14902 14901//14901 14903//14903 -f 14902//14902 14903//14903 14904//14904 -f 14904//14904 14903//14903 14905//14905 -f 14904//14904 14905//14905 14738//14738 -f 14738//14738 14905//14905 14739//14739 -f 14742//14742 14906//14906 14740//14740 -f 14740//14740 14906//14906 14907//14907 -f 14740//14740 14907//14907 14738//14738 -f 14738//14738 14907//14907 974//974 -f 14738//14738 974//974 14904//14904 -f 14882//14882 14771//14771 14880//14880 -f 14880//14880 14771//14771 14769//14769 -f 14880//14880 14769//14769 14766//14766 -f 14766//14766 14769//14769 962//962 -f 14766//14766 962//962 14764//14764 -f 14888//14888 14779//14779 14886//14886 -f 14886//14886 14779//14779 14777//14777 -f 14886//14886 14777//14777 14884//14884 -f 14884//14884 14777//14777 14775//14775 -f 14884//14884 14775//14775 14882//14882 -f 14882//14882 14775//14775 14773//14773 -f 14882//14882 14773//14773 14771//14771 -f 14894//14894 14787//14787 14892//14892 -f 14892//14892 14787//14787 14785//14785 -f 14892//14892 14785//14785 14890//14890 -f 14890//14890 14785//14785 14783//14783 -f 14890//14890 14783//14783 14888//14888 -f 14888//14888 14783//14783 14781//14781 -f 14888//14888 14781//14781 14779//14779 -f 974//974 14803//14803 14904//14904 -f 14904//14904 14803//14803 14801//14801 -f 14904//14904 14801//14801 14902//14902 -f 14902//14902 14801//14801 14799//14799 -f 14902//14902 14799//14799 14900//14900 -f 14900//14900 14799//14799 14797//14797 -f 14900//14900 14797//14797 14898//14898 -f 14748//14748 14908//14908 14746//14746 -f 14746//14746 14908//14908 14909//14909 -f 14746//14746 14909//14909 14744//14744 -f 14744//14744 14909//14909 14910//14910 -f 14744//14744 14910//14910 14742//14742 -f 14742//14742 14910//14910 14911//14911 -f 14742//14742 14911//14911 14906//14906 -f 14797//14797 14795//14795 14898//14898 -f 14898//14898 14795//14795 14793//14793 -f 14898//14898 14793//14793 14896//14896 -f 14896//14896 14793//14793 14791//14791 -f 14896//14896 14791//14791 14894//14894 -f 14894//14894 14791//14791 14789//14789 -f 14894//14894 14789//14789 14787//14787 -f 14754//14754 14912//14912 14752//14752 -f 14752//14752 14912//14912 14913//14913 -f 14752//14752 14913//14913 14750//14750 -f 14750//14750 14913//14913 14914//14914 -f 14750//14750 14914//14914 14748//14748 -f 14748//14748 14914//14914 14915//14915 -f 14748//14748 14915//14915 14908//14908 -f 962//962 14916//14916 14764//14764 -f 14764//14764 14916//14916 14917//14917 -f 14764//14764 14917//14917 14762//14762 -f 14762//14762 14917//14917 14918//14918 -f 14762//14762 14918//14918 14760//14760 -f 14760//14760 14918//14918 14919//14919 -f 14760//14760 14919//14919 14758//14758 -f 14919//14919 14920//14920 14758//14758 -f 14758//14758 14920//14920 14921//14921 -f 14758//14758 14921//14921 14756//14756 -f 14756//14756 14921//14921 14922//14922 -f 14756//14756 14922//14922 14754//14754 -f 14754//14754 14922//14922 14923//14923 -f 14754//14754 14923//14923 14912//14912 -f 14763//14763 14924//14924 14765//14765 -f 14765//14765 14924//14924 14925//14925 -f 14765//14765 14925//14925 14767//14767 -f 14767//14767 14925//14925 961//961 -f 14767//14767 961//961 14881//14881 -f 14757//14757 14926//14926 14759//14759 -f 14759//14759 14926//14926 14927//14927 -f 14759//14759 14927//14927 14761//14761 -f 14761//14761 14927//14927 14928//14928 -f 14761//14761 14928//14928 14763//14763 -f 14763//14763 14928//14928 14929//14929 -f 14763//14763 14929//14929 14924//14924 -f 14751//14751 14930//14930 14753//14753 -f 14753//14753 14930//14930 14931//14931 -f 14753//14753 14931//14931 14755//14755 -f 14755//14755 14931//14931 14932//14932 -f 14755//14755 14932//14932 14757//14757 -f 14757//14757 14932//14932 14933//14933 -f 14757//14757 14933//14933 14926//14926 -f 14747//14747 14934//14934 14749//14749 -f 14749//14749 14934//14934 14935//14935 -f 14749//14749 14935//14935 14751//14751 -f 14751//14751 14935//14935 14936//14936 -f 14751//14751 14936//14936 14930//14930 -f 14903//14903 14840//14840 14905//14905 -f 14905//14905 14840//14840 14842//14842 -f 14905//14905 14842//14842 14739//14739 -f 14739//14739 14842//14842 973//973 -f 14739//14739 973//973 14741//14741 -f 961//961 14808//14808 14881//14881 -f 14881//14881 14808//14808 14810//14810 -f 14881//14881 14810//14810 14883//14883 -f 14883//14883 14810//14810 14812//14812 -f 14883//14883 14812//14812 14885//14885 -f 14885//14885 14812//14812 14814//14814 -f 14885//14885 14814//14814 14887//14887 -f 973//973 14937//14937 14741//14741 -f 14741//14741 14937//14937 14938//14938 -f 14741//14741 14938//14938 14743//14743 -f 14743//14743 14938//14938 14939//14939 -f 14743//14743 14939//14939 14745//14745 -f 14745//14745 14939//14939 14940//14940 -f 14745//14745 14940//14940 14747//14747 -f 14747//14747 14940//14940 14941//14941 -f 14747//14747 14941//14941 14934//14934 -f 14897//14897 14832//14832 14899//14899 -f 14899//14899 14832//14832 14834//14834 -f 14899//14899 14834//14834 14901//14901 -f 14901//14901 14834//14834 14836//14836 -f 14901//14901 14836//14836 14903//14903 -f 14903//14903 14836//14836 14838//14838 -f 14903//14903 14838//14838 14840//14840 -f 14891//14891 14824//14824 14893//14893 -f 14893//14893 14824//14824 14826//14826 -f 14893//14893 14826//14826 14895//14895 -f 14895//14895 14826//14826 14828//14828 -f 14895//14895 14828//14828 14897//14897 -f 14897//14897 14828//14828 14830//14830 -f 14897//14897 14830//14830 14832//14832 -f 14814//14814 14816//14816 14887//14887 -f 14887//14887 14816//14816 14818//14818 -f 14887//14887 14818//14818 14889//14889 -f 14889//14889 14818//14818 14820//14820 -f 14889//14889 14820//14820 14891//14891 -f 14891//14891 14820//14820 14822//14822 -f 14891//14891 14822//14822 14824//14824 -f 14805//14805 974//974 14907//14907 -f 14805//14805 14907//14907 14942//14942 -f 14942//14942 14907//14907 14906//14906 -f 14942//14942 14906//14906 14943//14943 -f 14943//14943 14906//14906 14911//14911 -f 14943//14943 14911//14911 14944//14944 -f 14944//14944 14911//14911 14910//14910 -f 14944//14944 14910//14910 14945//14945 -f 14945//14945 14910//14910 14909//14909 -f 14945//14945 14909//14909 14946//14946 -f 14946//14946 14909//14909 14908//14908 -f 14946//14946 14908//14908 14947//14947 -f 14947//14947 14908//14908 14915//14915 -f 14947//14947 14915//14915 14948//14948 -f 14948//14948 14915//14915 14914//14914 -f 14948//14948 14914//14914 14949//14949 -f 14949//14949 14914//14914 14913//14913 -f 14949//14949 14913//14913 14950//14950 -f 14950//14950 14913//14913 14912//14912 -f 14950//14950 14912//14912 14951//14951 -f 14951//14951 14912//14912 14923//14923 -f 14951//14951 14923//14923 14952//14952 -f 14952//14952 14923//14923 14922//14922 -f 14952//14952 14922//14922 14953//14953 -f 14953//14953 14922//14922 14921//14921 -f 14953//14953 14921//14921 14954//14954 -f 14954//14954 14921//14921 14920//14920 -f 14954//14954 14920//14920 14955//14955 -f 14955//14955 14920//14920 14919//14919 -f 14955//14955 14919//14919 14956//14956 -f 14956//14956 14919//14919 14918//14918 -f 14956//14956 14918//14918 14957//14957 -f 14957//14957 14918//14918 14917//14917 -f 14957//14957 14917//14917 14958//14958 -f 14958//14958 14917//14917 14916//14916 -f 14958//14958 14916//14916 14959//14959 -f 14959//14959 14916//14916 962//962 -f 14959//14959 962//962 14768//14768 -f 973//973 14843//14843 14960//14960 -f 973//973 14960//14960 14937//14937 -f 14937//14937 14960//14960 14961//14961 -f 14937//14937 14961//14961 14938//14938 -f 14938//14938 14961//14961 14962//14962 -f 14938//14938 14962//14962 14939//14939 -f 14939//14939 14962//14962 14963//14963 -f 14939//14939 14963//14963 14940//14940 -f 14940//14940 14963//14963 14964//14964 -f 14940//14940 14964//14964 14941//14941 -f 14941//14941 14964//14964 14965//14965 -f 14941//14941 14965//14965 14934//14934 -f 14934//14934 14965//14965 14966//14966 -f 14934//14934 14966//14966 14935//14935 -f 14935//14935 14966//14966 14967//14967 -f 14935//14935 14967//14967 14936//14936 -f 14936//14936 14967//14967 14968//14968 -f 14936//14936 14968//14968 14930//14930 -f 14930//14930 14968//14968 14969//14969 -f 14930//14930 14969//14969 14931//14931 -f 14931//14931 14969//14969 14970//14970 -f 14931//14931 14970//14970 14932//14932 -f 14932//14932 14970//14970 14971//14971 -f 14932//14932 14971//14971 14933//14933 -f 14933//14933 14971//14971 14972//14972 -f 14933//14933 14972//14972 14926//14926 -f 14926//14926 14972//14972 14973//14973 -f 14926//14926 14973//14973 14927//14927 -f 14927//14927 14973//14973 14974//14974 -f 14927//14927 14974//14974 14928//14928 -f 14928//14928 14974//14974 14975//14975 -f 14928//14928 14975//14975 14929//14929 -f 14929//14929 14975//14975 14976//14976 -f 14929//14929 14976//14976 14924//14924 -f 14924//14924 14976//14976 14977//14977 -f 14924//14924 14977//14977 14925//14925 -f 14925//14925 14977//14977 14806//14806 -f 14925//14925 14806//14806 961//961 -f 14978//14978 14956//14956 14979//14979 -f 14979//14979 14956//14956 14957//14957 -f 14979//14979 14957//14957 14980//14980 -f 14980//14980 14957//14957 14958//14958 -f 14980//14980 14958//14958 14981//14981 -f 14981//14981 14958//14958 14959//14959 -f 14981//14981 14959//14959 14845//14845 -f 14845//14845 14959//14959 14768//14768 -f 14845//14845 14768//14768 14846//14846 -f 14846//14846 14768//14768 14770//14770 -f 14846//14846 14770//14770 14848//14848 -f 14848//14848 14770//14770 14772//14772 -f 14848//14848 14772//14772 14850//14850 -f 14850//14850 14772//14772 14774//14774 -f 14850//14850 14774//14774 14852//14852 -f 14870//14870 14798//14798 14872//14872 -f 14872//14872 14798//14798 14800//14800 -f 14872//14872 14800//14800 14874//14874 -f 14874//14874 14800//14800 14802//14802 -f 14874//14874 14802//14802 14876//14876 -f 14876//14876 14802//14802 14804//14804 -f 14876//14876 14804//14804 14878//14878 -f 14878//14878 14804//14804 14805//14805 -f 14878//14878 14805//14805 14982//14982 -f 14982//14982 14805//14805 14942//14942 -f 14982//14982 14942//14942 14983//14983 -f 14983//14983 14942//14942 14943//14943 -f 14983//14983 14943//14943 14984//14984 -f 14984//14984 14943//14943 14944//14944 -f 14984//14984 14944//14944 14985//14985 -f 14944//14944 14945//14945 14985//14985 -f 14985//14985 14945//14945 14946//14946 -f 14985//14985 14946//14946 14986//14986 -f 14986//14986 14946//14946 14947//14947 -f 14986//14986 14947//14947 14987//14987 -f 14987//14987 14947//14947 14948//14948 -f 14987//14987 14948//14948 14988//14988 -f 14988//14988 14948//14948 14949//14949 -f 14988//14988 14949//14949 14989//14989 -f 14989//14989 14949//14949 14950//14950 -f 14989//14989 14950//14950 14990//14990 -f 14990//14990 14950//14950 14951//14951 -f 14990//14990 14951//14951 14991//14991 -f 14991//14991 14951//14951 14952//14952 -f 14991//14991 14952//14952 14992//14992 -f 14992//14992 14952//14952 14953//14953 -f 14992//14992 14953//14953 14993//14993 -f 14993//14993 14953//14953 14954//14954 -f 14993//14993 14954//14954 14978//14978 -f 14978//14978 14954//14954 14955//14955 -f 14978//14978 14955//14955 14956//14956 -f 14774//14774 14776//14776 14852//14852 -f 14852//14852 14776//14776 14778//14778 -f 14852//14852 14778//14778 14854//14854 -f 14854//14854 14778//14778 14780//14780 -f 14854//14854 14780//14780 14856//14856 -f 14856//14856 14780//14780 14782//14782 -f 14856//14856 14782//14782 14858//14858 -f 14858//14858 14782//14782 14784//14784 -f 14858//14858 14784//14784 14860//14860 -f 14860//14860 14784//14784 14786//14786 -f 14860//14860 14786//14786 14862//14862 -f 14862//14862 14786//14786 14788//14788 -f 14862//14862 14788//14788 14864//14864 -f 14864//14864 14788//14788 14790//14790 -f 14864//14864 14790//14790 14866//14866 -f 14866//14866 14790//14790 14792//14792 -f 14866//14866 14792//14792 14868//14868 -f 14868//14868 14792//14792 14794//14794 -f 14868//14868 14794//14794 14870//14870 -f 14870//14870 14794//14794 14796//14796 -f 14870//14870 14796//14796 14798//14798 -f 14994//14994 14963//14963 14995//14995 -f 14995//14995 14963//14963 14962//14962 -f 14995//14995 14962//14962 14996//14996 -f 14996//14996 14962//14962 14961//14961 -f 14996//14996 14961//14961 14997//14997 -f 14997//14997 14961//14961 14960//14960 -f 14997//14997 14960//14960 14879//14879 -f 14879//14879 14960//14960 14843//14843 -f 14879//14879 14843//14843 14877//14877 -f 14877//14877 14843//14843 14841//14841 -f 14877//14877 14841//14841 14875//14875 -f 14875//14875 14841//14841 14839//14839 -f 14875//14875 14839//14839 14873//14873 -f 14873//14873 14839//14839 14837//14837 -f 14873//14873 14837//14837 14871//14871 -f 14998//14998 14973//14973 14999//14999 -f 14999//14999 14973//14973 14972//14972 -f 14999//14999 14972//14972 15000//15000 -f 15000//15000 14972//14972 14971//14971 -f 15000//15000 14971//14971 15001//15001 -f 15001//15001 14971//14971 14970//14970 -f 15001//15001 14970//14970 15002//15002 -f 15002//15002 14970//14970 14969//14969 -f 15002//15002 14969//14969 15003//15003 -f 15003//15003 14969//14969 14968//14968 -f 15003//15003 14968//14968 15004//15004 -f 15004//15004 14968//14968 14967//14967 -f 15004//15004 14967//14967 15005//15005 -f 15005//15005 14967//14967 14966//14966 -f 15005//15005 14966//14966 15006//15006 -f 15006//15006 14966//14966 14965//14965 -f 15006//15006 14965//14965 14994//14994 -f 14994//14994 14965//14965 14964//14964 -f 14994//14994 14964//14964 14963//14963 -f 14853//14853 14813//14813 14851//14851 -f 14851//14851 14813//14813 14811//14811 -f 14851//14851 14811//14811 14849//14849 -f 14849//14849 14811//14811 14809//14809 -f 14849//14849 14809//14809 14847//14847 -f 14847//14847 14809//14809 14807//14807 -f 14847//14847 14807//14807 14844//14844 -f 14844//14844 14807//14807 14806//14806 -f 14844//14844 14806//14806 15007//15007 -f 15007//15007 14806//14806 14977//14977 -f 15007//15007 14977//14977 15008//15008 -f 15008//15008 14977//14977 14976//14976 -f 15008//15008 14976//14976 15009//15009 -f 15009//15009 14976//14976 14975//14975 -f 15009//15009 14975//14975 14998//14998 -f 14998//14998 14975//14975 14974//14974 -f 14998//14998 14974//14974 14973//14973 -f 14837//14837 14835//14835 14871//14871 -f 14871//14871 14835//14835 14833//14833 -f 14871//14871 14833//14833 14869//14869 -f 14869//14869 14833//14833 14831//14831 -f 14869//14869 14831//14831 14867//14867 -f 14867//14867 14831//14831 14829//14829 -f 14867//14867 14829//14829 14865//14865 -f 14865//14865 14829//14829 14827//14827 -f 14865//14865 14827//14827 14863//14863 -f 14863//14863 14827//14827 14825//14825 -f 14863//14863 14825//14825 14861//14861 -f 14861//14861 14825//14825 14823//14823 -f 14861//14861 14823//14823 14859//14859 -f 14859//14859 14823//14823 14821//14821 -f 14859//14859 14821//14821 14857//14857 -f 14857//14857 14821//14821 14819//14819 -f 14857//14857 14819//14819 14855//14855 -f 14855//14855 14819//14819 14817//14817 -f 14855//14855 14817//14817 14853//14853 -f 14853//14853 14817//14817 14815//14815 -f 14853//14853 14815//14815 14813//14813 -f 14879//14879 14878//14878 14982//14982 -f 14879//14879 14982//14982 14997//14997 -f 14997//14997 14982//14982 14983//14983 -f 14997//14997 14983//14983 14996//14996 -f 14996//14996 14983//14983 14984//14984 -f 14996//14996 14984//14984 14995//14995 -f 14995//14995 14984//14984 14985//14985 -f 14995//14995 14985//14985 14994//14994 -f 14994//14994 14985//14985 14986//14986 -f 14994//14994 14986//14986 15006//15006 -f 15006//15006 14986//14986 14987//14987 -f 15006//15006 14987//14987 15005//15005 -f 15005//15005 14987//14987 14988//14988 -f 15005//15005 14988//14988 15004//15004 -f 15004//15004 14988//14988 14989//14989 -f 15004//15004 14989//14989 15003//15003 -f 15003//15003 14989//14989 14990//14990 -f 15003//15003 14990//14990 15002//15002 -f 15002//15002 14990//14990 14991//14991 -f 15002//15002 14991//14991 15001//15001 -f 15001//15001 14991//14991 14992//14992 -f 15001//15001 14992//14992 15000//15000 -f 15000//15000 14992//14992 14993//14993 -f 15000//15000 14993//14993 14999//14999 -f 14999//14999 14993//14993 14978//14978 -f 14999//14999 14978//14978 14998//14998 -f 14998//14998 14978//14978 14979//14979 -f 14998//14998 14979//14979 15009//15009 -f 15009//15009 14979//14979 14980//14980 -f 15009//15009 14980//14980 15008//15008 -f 15008//15008 14980//14980 14981//14981 -f 15008//15008 14981//14981 15007//15007 -f 15007//15007 14981//14981 14845//14845 -f 15007//15007 14845//14845 14844//14844 -f 15010//15010 15011//15011 15012//15012 -f 15012//15012 15011//15011 15013//15013 -f 15012//15012 15013//15013 15014//15014 -f 15014//15014 15013//15013 15015//15015 -f 15014//15014 15015//15015 15016//15016 -f 15016//15016 15015//15015 15017//15017 -f 15016//15016 15017//15017 15018//15018 -f 15018//15018 15017//15017 15019//15019 -f 15018//15018 15019//15019 15020//15020 -f 15020//15020 15019//15019 15021//15021 -f 15020//15020 15021//15021 15022//15022 -f 15022//15022 15021//15021 15023//15023 -f 15022//15022 15023//15023 15024//15024 -f 15024//15024 15023//15023 15025//15025 -f 15024//15024 15025//15025 15026//15026 -f 15026//15026 15025//15025 15027//15027 -f 15026//15026 15027//15027 15028//15028 -f 15028//15028 15027//15027 15029//15029 -f 15028//15028 15029//15029 15030//15030 -f 15030//15030 15029//15029 15031//15031 -f 15030//15030 15031//15031 15032//15032 -f 15032//15032 15031//15031 15033//15033 -f 15032//15032 15033//15033 15034//15034 -f 15034//15034 15033//15033 15035//15035 -f 15034//15034 15035//15035 15036//15036 -f 15036//15036 15035//15035 15037//15037 -f 15036//15036 15037//15037 15038//15038 -f 15038//15038 15037//15037 15039//15039 -f 15040//15040 15041//15041 15042//15042 -f 15040//15040 15042//15042 15043//15043 -f 15043//15043 15042//15042 15044//15044 -f 15043//15043 15044//15044 15045//15045 -f 15045//15045 15044//15044 15046//15046 -f 15045//15045 15046//15046 15047//15047 -f 15047//15047 15046//15046 15048//15048 -f 15047//15047 15048//15048 15049//15049 -f 15049//15049 15048//15048 15050//15050 -f 15049//15049 15050//15050 15051//15051 -f 15051//15051 15050//15050 15052//15052 -f 15051//15051 15052//15052 15053//15053 -f 15053//15053 15052//15052 15054//15054 -f 15053//15053 15054//15054 15055//15055 -f 15055//15055 15054//15054 15056//15056 -f 15055//15055 15056//15056 15057//15057 -f 15057//15057 15056//15056 15058//15058 -f 15057//15057 15058//15058 15059//15059 -f 15059//15059 15058//15058 15060//15060 -f 15059//15059 15060//15060 15061//15061 -f 15061//15061 15060//15060 15062//15062 -f 15061//15061 15062//15062 15063//15063 -f 15063//15063 15062//15062 15064//15064 -f 15063//15063 15064//15064 15065//15065 -f 15065//15065 15064//15064 15066//15066 -f 15065//15065 15066//15066 15067//15067 -f 15067//15067 15066//15066 15068//15068 -f 15067//15067 15068//15068 15069//15069 -f 15069//15069 15068//15068 15070//15070 -f 15069//15069 15070//15070 15071//15071 -f 15071//15071 15070//15070 15072//15072 -f 15071//15071 15072//15072 15073//15073 -f 15073//15073 15072//15072 15074//15074 -f 15073//15073 15074//15074 15075//15075 -f 15075//15075 15074//15074 15076//15076 -f 15075//15075 15076//15076 15077//15077 -f 15077//15077 15076//15076 15078//15078 -f 15077//15077 15078//15078 15079//15079 -f 15080//15080 15081//15081 15082//15082 -f 15080//15080 15082//15082 15083//15083 -f 15083//15083 15082//15082 15084//15084 -f 15083//15083 15084//15084 15085//15085 -f 15085//15085 15084//15084 15086//15086 -f 15085//15085 15086//15086 15087//15087 -f 15087//15087 15086//15086 15088//15088 -f 15087//15087 15088//15088 15089//15089 -f 15089//15089 15088//15088 15090//15090 -f 15089//15089 15090//15090 15091//15091 -f 15091//15091 15090//15090 15092//15092 -f 15091//15091 15092//15092 15093//15093 -f 15093//15093 15092//15092 15094//15094 -f 15093//15093 15094//15094 15095//15095 -f 15095//15095 15094//15094 15096//15096 -f 15095//15095 15096//15096 15097//15097 -f 15097//15097 15096//15096 15098//15098 -f 15097//15097 15098//15098 15099//15099 -f 15099//15099 15098//15098 15100//15100 -f 15099//15099 15100//15100 15101//15101 -f 15101//15101 15100//15100 15102//15102 -f 15101//15101 15102//15102 15103//15103 -f 15103//15103 15102//15102 15104//15104 -f 15103//15103 15104//15104 15105//15105 -f 15105//15105 15104//15104 15106//15106 -f 15105//15105 15106//15106 15107//15107 -f 15107//15107 15106//15106 15108//15108 -f 15107//15107 15108//15108 15109//15109 -f 15109//15109 15108//15108 15110//15110 -f 15109//15109 15110//15110 15111//15111 -f 15111//15111 15110//15110 15112//15112 -f 15111//15111 15112//15112 15113//15113 -f 15113//15113 15112//15112 15114//15114 -f 15113//15113 15114//15114 15115//15115 -f 15115//15115 15114//15114 15116//15116 -f 15115//15115 15116//15116 15117//15117 -f 15117//15117 15116//15116 15118//15118 -f 15117//15117 15118//15118 15119//15119 -f 15120//15120 15121//15121 15122//15122 -f 15120//15120 15122//15122 15123//15123 -f 15123//15123 15122//15122 15124//15124 -f 15123//15123 15124//15124 15125//15125 -f 15125//15125 15124//15124 15126//15126 -f 15125//15125 15126//15126 15127//15127 -f 15127//15127 15126//15126 15128//15128 -f 15127//15127 15128//15128 15129//15129 -f 15129//15129 15128//15128 15130//15130 -f 15129//15129 15130//15130 15131//15131 -f 15131//15131 15130//15130 15132//15132 -f 15131//15131 15132//15132 15133//15133 -f 15133//15133 15132//15132 15134//15134 -f 15133//15133 15134//15134 15135//15135 -f 15135//15135 15134//15134 15136//15136 -f 15135//15135 15136//15136 15137//15137 -f 15137//15137 15136//15136 15138//15138 -f 15137//15137 15138//15138 15139//15139 -f 15139//15139 15138//15138 15140//15140 -f 15139//15139 15140//15140 15141//15141 -f 15141//15141 15140//15140 15142//15142 -f 15141//15141 15142//15142 15143//15143 -f 15143//15143 15142//15142 15144//15144 -f 15143//15143 15144//15144 15145//15145 -f 15145//15145 15144//15144 15146//15146 -f 15145//15145 15146//15146 15147//15147 -f 15147//15147 15146//15146 15148//15148 -f 15147//15147 15148//15148 15149//15149 -f 15149//15149 15148//15148 15150//15150 -f 15149//15149 15150//15150 15151//15151 -f 15151//15151 15150//15150 15152//15152 -f 15151//15151 15152//15152 15153//15153 -f 15153//15153 15152//15152 15154//15154 -f 15153//15153 15154//15154 15155//15155 -f 15038//15038 15039//15039 15156//15156 -f 15156//15156 15039//15039 15157//15157 -f 15156//15156 15157//15157 15158//15158 -f 15158//15158 15157//15157 15159//15159 -f 15158//15158 15159//15159 15160//15160 -f 15160//15160 15159//15159 15161//15161 -f 15160//15160 15161//15161 15162//15162 -f 15162//15162 15161//15161 15163//15163 -f 15162//15162 15163//15163 15164//15164 -f 15164//15164 15163//15163 15165//15165 -f 15164//15164 15165//15165 15166//15166 -f 15166//15166 15165//15165 15167//15167 -f 15166//15166 15167//15167 15168//15168 -f 15168//15168 15167//15167 15169//15169 -f 15168//15168 15169//15169 15170//15170 -f 15170//15170 15169//15169 15171//15171 -f 15170//15170 15171//15171 15172//15172 -f 15172//15172 15171//15171 15173//15173 -f 15172//15172 15173//15173 15174//15174 -f 15174//15174 15173//15173 15175//15175 -f 15174//15174 15175//15175 15176//15176 -f 15176//15176 15175//15175 15177//15177 -f 15176//15176 15177//15177 15178//15178 -f 15178//15178 15177//15177 15179//15179 -f 15178//15178 15179//15179 15180//15180 -f 15180//15180 15179//15179 15181//15181 -f 15180//15180 15181//15181 15010//15010 -f 15010//15010 15181//15181 15011//15011 -f 15158//15158 15044//15044 15156//15156 -f 15156//15156 15044//15044 15042//15042 -f 15156//15156 15042//15042 15038//15038 -f 15038//15038 15042//15042 15041//15041 -f 15038//15038 15041//15041 15036//15036 -f 15020//15020 15182//15182 15018//15018 -f 15018//15018 15182//15182 15183//15183 -f 15018//15018 15183//15183 15016//15016 -f 15016//15016 15183//15183 15184//15184 -f 15016//15016 15184//15184 15014//15014 -f 15164//15164 15052//15052 15162//15162 -f 15162//15162 15052//15052 15050//15050 -f 15162//15162 15050//15050 15160//15160 -f 15160//15160 15050//15050 15048//15048 -f 15160//15160 15048//15048 15158//15158 -f 15158//15158 15048//15048 15046//15046 -f 15158//15158 15046//15046 15044//15044 -f 15184//15184 15185//15185 15014//15014 -f 15014//15014 15185//15185 15186//15186 -f 15014//15014 15186//15186 15012//15012 -f 15012//15012 15186//15186 15187//15187 -f 15012//15012 15187//15187 15010//15010 -f 15010//15010 15187//15187 15078//15078 -f 15010//15010 15078//15078 15180//15180 -f 15026//15026 15188//15188 15024//15024 -f 15024//15024 15188//15188 15189//15189 -f 15024//15024 15189//15189 15022//15022 -f 15022//15022 15189//15189 15190//15190 -f 15022//15022 15190//15190 15020//15020 -f 15020//15020 15190//15190 15191//15191 -f 15020//15020 15191//15191 15182//15182 -f 15041//15041 15192//15192 15036//15036 -f 15036//15036 15192//15192 15193//15193 -f 15036//15036 15193//15193 15034//15034 -f 15034//15034 15193//15193 15194//15194 -f 15034//15034 15194//15194 15032//15032 -f 15032//15032 15194//15194 15195//15195 -f 15032//15032 15195//15195 15030//15030 -f 15170//15170 15060//15060 15168//15168 -f 15168//15168 15060//15060 15058//15058 -f 15168//15168 15058//15058 15166//15166 -f 15166//15166 15058//15058 15056//15056 -f 15166//15166 15056//15056 15164//15164 -f 15164//15164 15056//15056 15054//15054 -f 15164//15164 15054//15054 15052//15052 -f 15195//15195 15196//15196 15030//15030 -f 15030//15030 15196//15196 15197//15197 -f 15030//15030 15197//15197 15028//15028 -f 15028//15028 15197//15197 15198//15198 -f 15028//15028 15198//15198 15026//15026 -f 15026//15026 15198//15198 15199//15199 -f 15026//15026 15199//15199 15188//15188 -f 15078//15078 15076//15076 15180//15180 -f 15180//15180 15076//15076 15074//15074 -f 15180//15180 15074//15074 15178//15178 -f 15178//15178 15074//15074 15072//15072 -f 15178//15178 15072//15072 15176//15176 -f 15176//15176 15072//15072 15070//15070 -f 15176//15176 15070//15070 15174//15174 -f 15070//15070 15068//15068 15174//15174 -f 15174//15174 15068//15068 15066//15066 -f 15174//15174 15066//15066 15172//15172 -f 15172//15172 15066//15066 15064//15064 -f 15172//15172 15064//15064 15170//15170 -f 15170//15170 15064//15064 15062//15062 -f 15170//15170 15062//15062 15060//15060 -f 15157//15157 15085//15085 15159//15159 -f 15159//15159 15085//15085 15087//15087 -f 15159//15159 15087//15087 15161//15161 -f 15161//15161 15087//15087 15089//15089 -f 15161//15161 15089//15089 15163//15163 -f 15013//15013 15200//15200 15015//15015 -f 15015//15015 15200//15200 15201//15201 -f 15015//15015 15201//15201 15017//15017 -f 15017//15017 15201//15201 15202//15202 -f 15017//15017 15202//15202 15019//15019 -f 15089//15089 15091//15091 15163//15163 -f 15163//15163 15091//15091 15093//15093 -f 15163//15163 15093//15093 15165//15165 -f 15165//15165 15093//15093 15095//15095 -f 15165//15165 15095//15095 15167//15167 -f 15167//15167 15095//15095 15097//15097 -f 15167//15167 15097//15097 15169//15169 -f 15202//15202 15203//15203 15019//15019 -f 15019//15019 15203//15203 15204//15204 -f 15019//15019 15204//15204 15021//15021 -f 15021//15021 15204//15204 15205//15205 -f 15021//15021 15205//15205 15023//15023 -f 15023//15023 15205//15205 15206//15206 -f 15023//15023 15206//15206 15025//15025 -f 15035//15035 15207//15207 15037//15037 -f 15037//15037 15207//15207 15208//15208 -f 15037//15037 15208//15208 15039//15039 -f 15039//15039 15208//15208 15080//15080 -f 15039//15039 15080//15080 15157//15157 -f 15157//15157 15080//15080 15083//15083 -f 15157//15157 15083//15083 15085//15085 -f 15179//15179 15115//15115 15181//15181 -f 15181//15181 15115//15115 15117//15117 -f 15181//15181 15117//15117 15011//15011 -f 15011//15011 15117//15117 15119//15119 -f 15011//15011 15119//15119 15013//15013 -f 15013//15013 15119//15119 15209//15209 -f 15013//15013 15209//15209 15200//15200 -f 15029//15029 15210//15210 15031//15031 -f 15031//15031 15210//15210 15211//15211 -f 15031//15031 15211//15211 15033//15033 -f 15033//15033 15211//15211 15212//15212 -f 15033//15033 15212//15212 15035//15035 -f 15035//15035 15212//15212 15213//15213 -f 15035//15035 15213//15213 15207//15207 -f 15173//15173 15107//15107 15175//15175 -f 15175//15175 15107//15107 15109//15109 -f 15175//15175 15109//15109 15177//15177 -f 15177//15177 15109//15109 15111//15111 -f 15177//15177 15111//15111 15179//15179 -f 15179//15179 15111//15111 15113//15113 -f 15179//15179 15113//15113 15115//15115 -f 15097//15097 15099//15099 15169//15169 -f 15169//15169 15099//15099 15101//15101 -f 15169//15169 15101//15101 15171//15171 -f 15171//15171 15101//15101 15103//15103 -f 15171//15171 15103//15103 15173//15173 -f 15173//15173 15103//15103 15105//15105 -f 15173//15173 15105//15105 15107//15107 -f 15206//15206 15214//15214 15025//15025 -f 15025//15025 15214//15214 15215//15215 -f 15025//15025 15215//15215 15027//15027 -f 15027//15027 15215//15215 15216//15216 -f 15027//15027 15216//15216 15029//15029 -f 15029//15029 15216//15216 15217//15217 -f 15029//15029 15217//15217 15210//15210 -f 15079//15079 15078//15078 15187//15187 -f 15079//15079 15187//15187 15218//15218 -f 15218//15218 15187//15187 15186//15186 -f 15218//15218 15186//15186 15219//15219 -f 15219//15219 15186//15186 15185//15185 -f 15219//15219 15185//15185 15220//15220 -f 15220//15220 15185//15185 15184//15184 -f 15220//15220 15184//15184 15221//15221 -f 15221//15221 15184//15184 15183//15183 -f 15221//15221 15183//15183 15222//15222 -f 15222//15222 15183//15183 15182//15182 -f 15222//15222 15182//15182 15223//15223 -f 15223//15223 15182//15182 15191//15191 -f 15223//15223 15191//15191 15224//15224 -f 15224//15224 15191//15191 15190//15190 -f 15224//15224 15190//15190 15225//15225 -f 15225//15225 15190//15190 15189//15189 -f 15225//15225 15189//15189 15226//15226 -f 15226//15226 15189//15189 15188//15188 -f 15226//15226 15188//15188 15227//15227 -f 15227//15227 15188//15188 15199//15199 -f 15227//15227 15199//15199 15228//15228 -f 15228//15228 15199//15199 15198//15198 -f 15228//15228 15198//15198 15229//15229 -f 15229//15229 15198//15198 15197//15197 -f 15229//15229 15197//15197 15230//15230 -f 15230//15230 15197//15197 15196//15196 -f 15230//15230 15196//15196 15231//15231 -f 15231//15231 15196//15196 15195//15195 -f 15231//15231 15195//15195 15232//15232 -f 15232//15232 15195//15195 15194//15194 -f 15232//15232 15194//15194 15233//15233 -f 15233//15233 15194//15194 15193//15193 -f 15233//15233 15193//15193 15234//15234 -f 15234//15234 15193//15193 15192//15192 -f 15234//15234 15192//15192 15235//15235 -f 15235//15235 15192//15192 15041//15041 -f 15235//15235 15041//15041 15040//15040 -f 15119//15119 15118//15118 15236//15236 -f 15119//15119 15236//15236 15209//15209 -f 15209//15209 15236//15236 15237//15237 -f 15209//15209 15237//15237 15200//15200 -f 15200//15200 15237//15237 15238//15238 -f 15200//15200 15238//15238 15201//15201 -f 15201//15201 15238//15238 15239//15239 -f 15201//15201 15239//15239 15202//15202 -f 15202//15202 15239//15239 15240//15240 -f 15202//15202 15240//15240 15203//15203 -f 15203//15203 15240//15240 15241//15241 -f 15203//15203 15241//15241 15204//15204 -f 15204//15204 15241//15241 15242//15242 -f 15204//15204 15242//15242 15205//15205 -f 15205//15205 15242//15242 15243//15243 -f 15205//15205 15243//15243 15206//15206 -f 15206//15206 15243//15243 15244//15244 -f 15206//15206 15244//15244 15214//15214 -f 15214//15214 15244//15244 15245//15245 -f 15214//15214 15245//15245 15215//15215 -f 15215//15215 15245//15245 15246//15246 -f 15215//15215 15246//15246 15216//15216 -f 15216//15216 15246//15246 15247//15247 -f 15216//15216 15247//15247 15217//15217 -f 15217//15217 15247//15247 15248//15248 -f 15217//15217 15248//15248 15210//15210 -f 15210//15210 15248//15248 15249//15249 -f 15210//15210 15249//15249 15211//15211 -f 15211//15211 15249//15249 15250//15250 -f 15211//15211 15250//15250 15212//15212 -f 15212//15212 15250//15250 15251//15251 -f 15212//15212 15251//15251 15213//15213 -f 15213//15213 15251//15251 15252//15252 -f 15213//15213 15252//15252 15207//15207 -f 15207//15207 15252//15252 15253//15253 -f 15207//15207 15253//15253 15208//15208 -f 15208//15208 15253//15253 15081//15081 -f 15208//15208 15081//15081 15080//15080 -f 15254//15254 15232//15232 15255//15255 -f 15255//15255 15232//15232 15233//15233 -f 15255//15255 15233//15233 15256//15256 -f 15256//15256 15233//15233 15234//15234 -f 15256//15256 15234//15234 15257//15257 -f 15257//15257 15234//15234 15235//15235 -f 15257//15257 15235//15235 15121//15121 -f 15121//15121 15235//15235 15040//15040 -f 15121//15121 15040//15040 15122//15122 -f 15122//15122 15040//15040 15043//15043 -f 15122//15122 15043//15043 15124//15124 -f 15124//15124 15043//15043 15045//15045 -f 15124//15124 15045//15045 15126//15126 -f 15126//15126 15045//15045 15047//15047 -f 15126//15126 15047//15047 15128//15128 -f 15146//15146 15071//15071 15148//15148 -f 15148//15148 15071//15071 15073//15073 -f 15148//15148 15073//15073 15150//15150 -f 15150//15150 15073//15073 15075//15075 -f 15150//15150 15075//15075 15152//15152 -f 15152//15152 15075//15075 15077//15077 -f 15152//15152 15077//15077 15154//15154 -f 15154//15154 15077//15077 15079//15079 -f 15154//15154 15079//15079 15258//15258 -f 15258//15258 15079//15079 15218//15218 -f 15258//15258 15218//15218 15259//15259 -f 15259//15259 15218//15218 15219//15219 -f 15259//15259 15219//15219 15260//15260 -f 15260//15260 15219//15219 15220//15220 -f 15260//15260 15220//15220 15261//15261 -f 15047//15047 15049//15049 15128//15128 -f 15128//15128 15049//15049 15051//15051 -f 15128//15128 15051//15051 15130//15130 -f 15130//15130 15051//15051 15053//15053 -f 15130//15130 15053//15053 15132//15132 -f 15132//15132 15053//15053 15055//15055 -f 15132//15132 15055//15055 15134//15134 -f 15134//15134 15055//15055 15057//15057 -f 15134//15134 15057//15057 15136//15136 -f 15136//15136 15057//15057 15059//15059 -f 15136//15136 15059//15059 15138//15138 -f 15138//15138 15059//15059 15061//15061 -f 15138//15138 15061//15061 15140//15140 -f 15140//15140 15061//15061 15063//15063 -f 15140//15140 15063//15063 15142//15142 -f 15142//15142 15063//15063 15065//15065 -f 15142//15142 15065//15065 15144//15144 -f 15144//15144 15065//15065 15067//15067 -f 15144//15144 15067//15067 15146//15146 -f 15146//15146 15067//15067 15069//15069 -f 15146//15146 15069//15069 15071//15071 -f 15220//15220 15221//15221 15261//15261 -f 15261//15261 15221//15221 15222//15222 -f 15261//15261 15222//15222 15262//15262 -f 15262//15262 15222//15222 15223//15223 -f 15262//15262 15223//15223 15263//15263 -f 15263//15263 15223//15223 15224//15224 -f 15263//15263 15224//15224 15264//15264 -f 15264//15264 15224//15224 15225//15225 -f 15264//15264 15225//15225 15265//15265 -f 15265//15265 15225//15225 15226//15226 -f 15265//15265 15226//15226 15266//15266 -f 15266//15266 15226//15226 15227//15227 -f 15266//15266 15227//15227 15267//15267 -f 15267//15267 15227//15227 15228//15228 -f 15267//15267 15228//15228 15268//15268 -f 15268//15268 15228//15228 15229//15229 -f 15268//15268 15229//15229 15269//15269 -f 15269//15269 15229//15229 15230//15230 -f 15269//15269 15230//15230 15254//15254 -f 15254//15254 15230//15230 15231//15231 -f 15254//15254 15231//15231 15232//15232 -f 15147//15147 15108//15108 15145//15145 -f 15145//15145 15108//15108 15106//15106 -f 15145//15145 15106//15106 15143//15143 -f 15143//15143 15106//15106 15104//15104 -f 15143//15143 15104//15104 15141//15141 -f 15141//15141 15104//15104 15102//15102 -f 15141//15141 15102//15102 15139//15139 -f 15139//15139 15102//15102 15100//15100 -f 15139//15139 15100//15100 15137//15137 -f 15137//15137 15100//15100 15098//15098 -f 15137//15137 15098//15098 15135//15135 -f 15135//15135 15098//15098 15096//15096 -f 15135//15135 15096//15096 15133//15133 -f 15133//15133 15096//15096 15094//15094 -f 15133//15133 15094//15094 15131//15131 -f 15131//15131 15094//15094 15092//15092 -f 15131//15131 15092//15092 15129//15129 -f 15270//15270 15239//15239 15271//15271 -f 15271//15271 15239//15239 15238//15238 -f 15271//15271 15238//15238 15272//15272 -f 15272//15272 15238//15238 15237//15237 -f 15272//15272 15237//15237 15273//15273 -f 15273//15273 15237//15237 15236//15236 -f 15273//15273 15236//15236 15155//15155 -f 15155//15155 15236//15236 15118//15118 -f 15155//15155 15118//15118 15153//15153 -f 15153//15153 15118//15118 15116//15116 -f 15153//15153 15116//15116 15151//15151 -f 15151//15151 15116//15116 15114//15114 -f 15151//15151 15114//15114 15149//15149 -f 15149//15149 15114//15114 15112//15112 -f 15149//15149 15112//15112 15147//15147 -f 15147//15147 15112//15112 15110//15110 -f 15147//15147 15110//15110 15108//15108 -f 15092//15092 15090//15090 15129//15129 -f 15129//15129 15090//15090 15088//15088 -f 15129//15129 15088//15088 15127//15127 -f 15127//15127 15088//15088 15086//15086 -f 15127//15127 15086//15086 15125//15125 -f 15125//15125 15086//15086 15084//15084 -f 15125//15125 15084//15084 15123//15123 -f 15123//15123 15084//15084 15082//15082 -f 15123//15123 15082//15082 15120//15120 -f 15120//15120 15082//15082 15081//15081 -f 15120//15120 15081//15081 15274//15274 -f 15274//15274 15081//15081 15253//15253 -f 15274//15274 15253//15253 15275//15275 -f 15275//15275 15253//15253 15252//15252 -f 15275//15275 15252//15252 15276//15276 -f 15276//15276 15252//15252 15251//15251 -f 15276//15276 15251//15251 15277//15277 -f 15251//15251 15250//15250 15277//15277 -f 15277//15277 15250//15250 15249//15249 -f 15277//15277 15249//15249 15278//15278 -f 15278//15278 15249//15249 15248//15248 -f 15278//15278 15248//15248 15279//15279 -f 15279//15279 15248//15248 15247//15247 -f 15279//15279 15247//15247 15280//15280 -f 15280//15280 15247//15247 15246//15246 -f 15280//15280 15246//15246 15281//15281 -f 15281//15281 15246//15246 15245//15245 -f 15281//15281 15245//15245 15282//15282 -f 15282//15282 15245//15245 15244//15244 -f 15282//15282 15244//15244 15283//15283 -f 15283//15283 15244//15244 15243//15243 -f 15283//15283 15243//15243 15284//15284 -f 15284//15284 15243//15243 15242//15242 -f 15284//15284 15242//15242 15285//15285 -f 15285//15285 15242//15242 15241//15241 -f 15285//15285 15241//15241 15270//15270 -f 15270//15270 15241//15241 15240//15240 -f 15270//15270 15240//15240 15239//15239 -f 15155//15155 15154//15154 15258//15258 -f 15155//15155 15258//15258 15273//15273 -f 15273//15273 15258//15258 15259//15259 -f 15273//15273 15259//15259 15272//15272 -f 15272//15272 15259//15259 15260//15260 -f 15272//15272 15260//15260 15271//15271 -f 15271//15271 15260//15260 15261//15261 -f 15271//15271 15261//15261 15270//15270 -f 15270//15270 15261//15261 15262//15262 -f 15270//15270 15262//15262 15285//15285 -f 15285//15285 15262//15262 15263//15263 -f 15285//15285 15263//15263 15284//15284 -f 15284//15284 15263//15263 15264//15264 -f 15284//15284 15264//15264 15283//15283 -f 15283//15283 15264//15264 15265//15265 -f 15283//15283 15265//15265 15282//15282 -f 15282//15282 15265//15265 15266//15266 -f 15282//15282 15266//15266 15281//15281 -f 15281//15281 15266//15266 15267//15267 -f 15281//15281 15267//15267 15280//15280 -f 15280//15280 15267//15267 15268//15268 -f 15280//15280 15268//15268 15279//15279 -f 15279//15279 15268//15268 15269//15269 -f 15279//15279 15269//15269 15278//15278 -f 15278//15278 15269//15269 15254//15254 -f 15278//15278 15254//15254 15277//15277 -f 15277//15277 15254//15254 15255//15255 -f 15277//15277 15255//15255 15276//15276 -f 15276//15276 15255//15255 15256//15256 -f 15276//15276 15256//15256 15275//15275 -f 15275//15275 15256//15256 15257//15257 -f 15275//15275 15257//15257 15274//15274 -f 15274//15274 15257//15257 15121//15121 -f 15274//15274 15121//15121 15120//15120 -f 15286//15286 15287//15287 15288//15288 -f 15288//15288 15287//15287 15289//15289 -f 15288//15288 15289//15289 15290//15290 -f 15290//15290 15289//15289 15291//15291 -f 15290//15290 15291//15291 15292//15292 -f 15292//15292 15291//15291 15293//15293 -f 15292//15292 15293//15293 15294//15294 -f 15294//15294 15293//15293 15295//15295 -f 15294//15294 15295//15295 15296//15296 -f 15296//15296 15295//15295 15297//15297 -f 15296//15296 15297//15297 15298//15298 -f 15298//15298 15297//15297 15299//15299 -f 15298//15298 15299//15299 15300//15300 -f 15300//15300 15299//15299 15301//15301 -f 15300//15300 15301//15301 15302//15302 -f 15302//15302 15301//15301 15303//15303 -f 15302//15302 15303//15303 15304//15304 -f 15304//15304 15303//15303 15305//15305 -f 15304//15304 15305//15305 15306//15306 -f 15306//15306 15305//15305 15307//15307 -f 15306//15306 15307//15307 15308//15308 -f 15308//15308 15307//15307 15309//15309 -f 15308//15308 15309//15309 15310//15310 -f 15310//15310 15309//15309 15311//15311 -f 15310//15310 15311//15311 15312//15312 -f 15312//15312 15311//15311 15313//15313 -f 15312//15312 15313//15313 15314//15314 -f 15314//15314 15313//15313 15315//15315 -f 15316//15316 990//990 15317//15317 -f 15316//15316 15317//15317 15318//15318 -f 15318//15318 15317//15317 15319//15319 -f 15318//15318 15319//15319 15320//15320 -f 15320//15320 15319//15319 15321//15321 -f 15320//15320 15321//15321 15322//15322 -f 15322//15322 15321//15321 15323//15323 -f 15322//15322 15323//15323 15324//15324 -f 15324//15324 15323//15323 15325//15325 -f 15324//15324 15325//15325 15326//15326 -f 15326//15326 15325//15325 15327//15327 -f 15326//15326 15327//15327 15328//15328 -f 15328//15328 15327//15327 15329//15329 -f 15328//15328 15329//15329 15330//15330 -f 15330//15330 15329//15329 15331//15331 -f 15330//15330 15331//15331 15332//15332 -f 15332//15332 15331//15331 15333//15333 -f 15332//15332 15333//15333 15334//15334 -f 15334//15334 15333//15333 15335//15335 -f 15334//15334 15335//15335 15336//15336 -f 15336//15336 15335//15335 15337//15337 -f 15336//15336 15337//15337 15338//15338 -f 15338//15338 15337//15337 15339//15339 -f 15338//15338 15339//15339 15340//15340 -f 15340//15340 15339//15339 15341//15341 -f 15340//15340 15341//15341 15342//15342 -f 15342//15342 15341//15341 15343//15343 -f 15342//15342 15343//15343 15344//15344 -f 15344//15344 15343//15343 15345//15345 -f 15344//15344 15345//15345 15346//15346 -f 15346//15346 15345//15345 15347//15347 -f 15346//15346 15347//15347 15348//15348 -f 15348//15348 15347//15347 15349//15349 -f 15348//15348 15349//15349 15350//15350 -f 15350//15350 15349//15349 15351//15351 -f 15350//15350 15351//15351 15352//15352 -f 15352//15352 15351//15351 1002//1002 -f 15352//15352 1002//1002 15353//15353 -f 989//989 15354//15354 15355//15355 -f 989//989 15355//15355 15356//15356 -f 15356//15356 15355//15355 15357//15357 -f 15356//15356 15357//15357 15358//15358 -f 15358//15358 15357//15357 15359//15359 -f 15358//15358 15359//15359 15360//15360 -f 15360//15360 15359//15359 15361//15361 -f 15360//15360 15361//15361 15362//15362 -f 15362//15362 15361//15361 15363//15363 -f 15362//15362 15363//15363 15364//15364 -f 15364//15364 15363//15363 15365//15365 -f 15364//15364 15365//15365 15366//15366 -f 15366//15366 15365//15365 15367//15367 -f 15366//15366 15367//15367 15368//15368 -f 15368//15368 15367//15367 15369//15369 -f 15368//15368 15369//15369 15370//15370 -f 15370//15370 15369//15369 15371//15371 -f 15370//15370 15371//15371 15372//15372 -f 15372//15372 15371//15371 15373//15373 -f 15372//15372 15373//15373 15374//15374 -f 15374//15374 15373//15373 15375//15375 -f 15374//15374 15375//15375 15376//15376 -f 15376//15376 15375//15375 15377//15377 -f 15376//15376 15377//15377 15378//15378 -f 15378//15378 15377//15377 15379//15379 -f 15378//15378 15379//15379 15380//15380 -f 15380//15380 15379//15379 15381//15381 -f 15380//15380 15381//15381 15382//15382 -f 15382//15382 15381//15381 15383//15383 -f 15382//15382 15383//15383 15384//15384 -f 15384//15384 15383//15383 15385//15385 -f 15384//15384 15385//15385 15386//15386 -f 15386//15386 15385//15385 15387//15387 -f 15386//15386 15387//15387 15388//15388 -f 15388//15388 15387//15387 15389//15389 -f 15388//15388 15389//15389 15390//15390 -f 15390//15390 15389//15389 15391//15391 -f 15390//15390 15391//15391 1001//1001 -f 15392//15392 15393//15393 15394//15394 -f 15392//15392 15394//15394 15395//15395 -f 15395//15395 15394//15394 15396//15396 -f 15395//15395 15396//15396 15397//15397 -f 15397//15397 15396//15396 15398//15398 -f 15397//15397 15398//15398 15399//15399 -f 15399//15399 15398//15398 15400//15400 -f 15399//15399 15400//15400 15401//15401 -f 15401//15401 15400//15400 15402//15402 -f 15401//15401 15402//15402 15403//15403 -f 15403//15403 15402//15402 15404//15404 -f 15403//15403 15404//15404 15405//15405 -f 15405//15405 15404//15404 15406//15406 -f 15405//15405 15406//15406 15407//15407 -f 15407//15407 15406//15406 15408//15408 -f 15407//15407 15408//15408 15409//15409 -f 15409//15409 15408//15408 15410//15410 -f 15409//15409 15410//15410 15411//15411 -f 15411//15411 15410//15410 15412//15412 -f 15411//15411 15412//15412 15413//15413 -f 15413//15413 15412//15412 15414//15414 -f 15413//15413 15414//15414 15415//15415 -f 15415//15415 15414//15414 15416//15416 -f 15415//15415 15416//15416 15417//15417 -f 15417//15417 15416//15416 15418//15418 -f 15417//15417 15418//15418 15419//15419 -f 15419//15419 15418//15418 15420//15420 -f 15419//15419 15420//15420 15421//15421 -f 15421//15421 15420//15420 15422//15422 -f 15421//15421 15422//15422 15423//15423 -f 15423//15423 15422//15422 15424//15424 -f 15423//15423 15424//15424 15425//15425 -f 15425//15425 15424//15424 15426//15426 -f 15425//15425 15426//15426 15427//15427 -f 15314//15314 15315//15315 15428//15428 -f 15428//15428 15315//15315 15429//15429 -f 15428//15428 15429//15429 15430//15430 -f 15430//15430 15429//15429 15431//15431 -f 15430//15430 15431//15431 15432//15432 -f 15432//15432 15431//15431 15433//15433 -f 15432//15432 15433//15433 15434//15434 -f 15434//15434 15433//15433 15435//15435 -f 15434//15434 15435//15435 15436//15436 -f 15436//15436 15435//15435 15437//15437 -f 15436//15436 15437//15437 15438//15438 -f 15438//15438 15437//15437 15439//15439 -f 15438//15438 15439//15439 15440//15440 -f 15440//15440 15439//15439 15441//15441 -f 15440//15440 15441//15441 15442//15442 -f 15442//15442 15441//15441 15443//15443 -f 15442//15442 15443//15443 15444//15444 -f 15444//15444 15443//15443 15445//15445 -f 15444//15444 15445//15445 15446//15446 -f 15446//15446 15445//15445 15447//15447 -f 15446//15446 15447//15447 15448//15448 -f 15448//15448 15447//15447 15449//15449 -f 15448//15448 15449//15449 15450//15450 -f 15450//15450 15449//15449 15451//15451 -f 15450//15450 15451//15451 15452//15452 -f 15452//15452 15451//15451 15453//15453 -f 15452//15452 15453//15453 15286//15286 -f 15286//15286 15453//15453 15287//15287 -f 15290//15290 15454//15454 15288//15288 -f 15288//15288 15454//15454 15455//15455 -f 15288//15288 15455//15455 15286//15286 -f 15286//15286 15455//15455 1002//1002 -f 15286//15286 1002//1002 15452//15452 -f 15296//15296 15456//15456 15294//15294 -f 15294//15294 15456//15456 15457//15457 -f 15294//15294 15457//15457 15292//15292 -f 15292//15292 15457//15457 15458//15458 -f 15292//15292 15458//15458 15290//15290 -f 15290//15290 15458//15458 15459//15459 -f 15290//15290 15459//15459 15454//15454 -f 15430//15430 15319//15319 15428//15428 -f 15428//15428 15319//15319 15317//15317 -f 15428//15428 15317//15317 15314//15314 -f 15314//15314 15317//15317 990//990 -f 15314//15314 990//990 15312//15312 -f 15436//15436 15327//15327 15434//15434 -f 15434//15434 15327//15327 15325//15325 -f 15434//15434 15325//15325 15432//15432 -f 15432//15432 15325//15325 15323//15323 -f 15432//15432 15323//15323 15430//15430 -f 15430//15430 15323//15323 15321//15321 -f 15430//15430 15321//15321 15319//15319 -f 15446//15446 15341//15341 15444//15444 -f 15444//15444 15341//15341 15339//15339 -f 15444//15444 15339//15339 15442//15442 -f 15339//15339 15337//15337 15442//15442 -f 15442//15442 15337//15337 15335//15335 -f 15442//15442 15335//15335 15440//15440 -f 15440//15440 15335//15335 15333//15333 -f 15440//15440 15333//15333 15438//15438 -f 15438//15438 15333//15333 15331//15331 -f 15438//15438 15331//15331 15436//15436 -f 15436//15436 15331//15331 15329//15329 -f 15436//15436 15329//15329 15327//15327 -f 1002//1002 15351//15351 15452//15452 -f 15452//15452 15351//15351 15349//15349 -f 15452//15452 15349//15349 15450//15450 -f 15450//15450 15349//15349 15347//15347 -f 15450//15450 15347//15347 15448//15448 -f 15448//15448 15347//15347 15345//15345 -f 15448//15448 15345//15345 15446//15446 -f 15446//15446 15345//15345 15343//15343 -f 15446//15446 15343//15343 15341//15341 -f 15306//15306 15460//15460 15304//15304 -f 15304//15304 15460//15460 15461//15461 -f 15304//15304 15461//15461 15302//15302 -f 15461//15461 15462//15462 15302//15302 -f 15302//15302 15462//15462 15463//15463 -f 15302//15302 15463//15463 15300//15300 -f 15300//15300 15463//15463 15464//15464 -f 15300//15300 15464//15464 15298//15298 -f 15298//15298 15464//15464 15465//15465 -f 15298//15298 15465//15465 15296//15296 -f 15296//15296 15465//15465 15466//15466 -f 15296//15296 15466//15466 15456//15456 -f 990//990 15467//15467 15312//15312 -f 15312//15312 15467//15467 15468//15468 -f 15312//15312 15468//15468 15310//15310 -f 15310//15310 15468//15468 15469//15469 -f 15310//15310 15469//15469 15308//15308 -f 15308//15308 15469//15469 15470//15470 -f 15308//15308 15470//15470 15306//15306 -f 15306//15306 15470//15470 15471//15471 -f 15306//15306 15471//15471 15460//15460 -f 15295//15295 15472//15472 15297//15297 -f 15297//15297 15472//15472 15473//15473 -f 15297//15297 15473//15473 15299//15299 -f 15311//15311 15474//15474 15313//15313 -f 15313//15313 15474//15474 15475//15475 -f 15313//15313 15475//15475 15315//15315 -f 15315//15315 15475//15475 989//989 -f 15315//15315 989//989 15429//15429 -f 15305//15305 15476//15476 15307//15307 -f 15307//15307 15476//15476 15477//15477 -f 15307//15307 15477//15477 15309//15309 -f 15309//15309 15477//15477 15478//15478 -f 15309//15309 15478//15478 15311//15311 -f 15311//15311 15478//15478 15479//15479 -f 15311//15311 15479//15479 15474//15474 -f 989//989 15356//15356 15429//15429 -f 15429//15429 15356//15356 15358//15358 -f 15429//15429 15358//15358 15431//15431 -f 15431//15431 15358//15358 15360//15360 -f 15431//15431 15360//15360 15433//15433 -f 15433//15433 15360//15360 15362//15362 -f 15433//15433 15362//15362 15435//15435 -f 15473//15473 15480//15480 15299//15299 -f 15299//15299 15480//15480 15481//15481 -f 15299//15299 15481//15481 15301//15301 -f 15301//15301 15481//15481 15482//15482 -f 15301//15301 15482//15482 15303//15303 -f 15303//15303 15482//15482 15483//15483 -f 15303//15303 15483//15483 15305//15305 -f 15305//15305 15483//15483 15484//15484 -f 15305//15305 15484//15484 15476//15476 -f 15289//15289 15485//15485 15291//15291 -f 15291//15291 15485//15485 15486//15486 -f 15291//15291 15486//15486 15293//15293 -f 15293//15293 15486//15486 15487//15487 -f 15293//15293 15487//15487 15295//15295 -f 15295//15295 15487//15487 15488//15488 -f 15295//15295 15488//15488 15472//15472 -f 15445//15445 15380//15380 15447//15447 -f 15447//15447 15380//15380 15382//15382 -f 15447//15447 15382//15382 15449//15449 -f 15449//15449 15382//15382 15384//15384 -f 15449//15449 15384//15384 15451//15451 -f 15362//15362 15364//15364 15435//15435 -f 15435//15435 15364//15364 15366//15366 -f 15435//15435 15366//15366 15437//15437 -f 15437//15437 15366//15366 15368//15368 -f 15437//15437 15368//15368 15439//15439 -f 15384//15384 15386//15386 15451//15451 -f 15451//15451 15386//15386 15388//15388 -f 15451//15451 15388//15388 15453//15453 -f 15453//15453 15388//15388 15390//15390 -f 15453//15453 15390//15390 15287//15287 -f 15287//15287 15390//15390 1001//1001 -f 15287//15287 1001//1001 15289//15289 -f 15289//15289 1001//1001 15489//15489 -f 15289//15289 15489//15489 15485//15485 -f 15368//15368 15370//15370 15439//15439 -f 15439//15439 15370//15370 15372//15372 -f 15439//15439 15372//15372 15441//15441 -f 15441//15441 15372//15372 15374//15374 -f 15441//15441 15374//15374 15443//15443 -f 15443//15443 15374//15374 15376//15376 -f 15443//15443 15376//15376 15445//15445 -f 15445//15445 15376//15376 15378//15378 -f 15445//15445 15378//15378 15380//15380 -f 15353//15353 1002//1002 15455//15455 -f 15353//15353 15455//15455 15490//15490 -f 15490//15490 15455//15455 15454//15454 -f 15490//15490 15454//15454 15491//15491 -f 15491//15491 15454//15454 15459//15459 -f 15491//15491 15459//15459 15492//15492 -f 15492//15492 15459//15459 15458//15458 -f 15492//15492 15458//15458 15493//15493 -f 15493//15493 15458//15458 15457//15457 -f 15493//15493 15457//15457 15494//15494 -f 15494//15494 15457//15457 15456//15456 -f 15494//15494 15456//15456 15495//15495 -f 15495//15495 15456//15456 15466//15466 -f 15495//15495 15466//15466 15496//15496 -f 15496//15496 15466//15466 15465//15465 -f 15496//15496 15465//15465 15497//15497 -f 15497//15497 15465//15465 15464//15464 -f 15497//15497 15464//15464 15498//15498 -f 15498//15498 15464//15464 15463//15463 -f 15498//15498 15463//15463 15499//15499 -f 15499//15499 15463//15463 15462//15462 -f 15499//15499 15462//15462 15500//15500 -f 15500//15500 15462//15462 15461//15461 -f 15500//15500 15461//15461 15501//15501 -f 15501//15501 15461//15461 15460//15460 -f 15501//15501 15460//15460 15502//15502 -f 15502//15502 15460//15460 15471//15471 -f 15502//15502 15471//15471 15503//15503 -f 15503//15503 15471//15471 15470//15470 -f 15503//15503 15470//15470 15504//15504 -f 15504//15504 15470//15470 15469//15469 -f 15504//15504 15469//15469 15505//15505 -f 15505//15505 15469//15469 15468//15468 -f 15505//15505 15468//15468 15506//15506 -f 15506//15506 15468//15468 15467//15467 -f 15506//15506 15467//15467 15507//15507 -f 15507//15507 15467//15467 990//990 -f 15507//15507 990//990 15316//15316 -f 1001//1001 15391//15391 15508//15508 -f 1001//1001 15508//15508 15489//15489 -f 15489//15489 15508//15508 15509//15509 -f 15489//15489 15509//15509 15485//15485 -f 15485//15485 15509//15509 15510//15510 -f 15485//15485 15510//15510 15486//15486 -f 15486//15486 15510//15510 15511//15511 -f 15486//15486 15511//15511 15487//15487 -f 15487//15487 15511//15511 15512//15512 -f 15487//15487 15512//15512 15488//15488 -f 15488//15488 15512//15512 15513//15513 -f 15488//15488 15513//15513 15472//15472 -f 15472//15472 15513//15513 15514//15514 -f 15472//15472 15514//15514 15473//15473 -f 15473//15473 15514//15514 15515//15515 -f 15473//15473 15515//15515 15480//15480 -f 15480//15480 15515//15515 15516//15516 -f 15480//15480 15516//15516 15481//15481 -f 15481//15481 15516//15516 15517//15517 -f 15481//15481 15517//15517 15482//15482 -f 15482//15482 15517//15517 15518//15518 -f 15482//15482 15518//15518 15483//15483 -f 15483//15483 15518//15518 15519//15519 -f 15483//15483 15519//15519 15484//15484 -f 15484//15484 15519//15519 15520//15520 -f 15484//15484 15520//15520 15476//15476 -f 15476//15476 15520//15520 15521//15521 -f 15476//15476 15521//15521 15477//15477 -f 15477//15477 15521//15521 15522//15522 -f 15477//15477 15522//15522 15478//15478 -f 15478//15478 15522//15522 15523//15523 -f 15478//15478 15523//15523 15479//15479 -f 15479//15479 15523//15523 15524//15524 -f 15479//15479 15524//15524 15474//15474 -f 15474//15474 15524//15524 15525//15525 -f 15474//15474 15525//15525 15475//15475 -f 15475//15475 15525//15525 15354//15354 -f 15475//15475 15354//15354 989//989 -f 15526//15526 15494//15494 15527//15527 -f 15527//15527 15494//15494 15495//15495 -f 15527//15527 15495//15495 15528//15528 -f 15528//15528 15495//15495 15496//15496 -f 15528//15528 15496//15496 15529//15529 -f 15529//15529 15496//15496 15497//15497 -f 15529//15529 15497//15497 15530//15530 -f 15530//15530 15497//15497 15498//15498 -f 15530//15530 15498//15498 15531//15531 -f 15531//15531 15498//15498 15499//15499 -f 15531//15531 15499//15499 15532//15532 -f 15532//15532 15499//15499 15500//15500 -f 15532//15532 15500//15500 15533//15533 -f 15533//15533 15500//15500 15501//15501 -f 15533//15533 15501//15501 15534//15534 -f 15534//15534 15501//15501 15502//15502 -f 15534//15534 15502//15502 15535//15535 -f 15418//15418 15346//15346 15420//15420 -f 15420//15420 15346//15346 15348//15348 -f 15420//15420 15348//15348 15422//15422 -f 15422//15422 15348//15348 15350//15350 -f 15422//15422 15350//15350 15424//15424 -f 15424//15424 15350//15350 15352//15352 -f 15424//15424 15352//15352 15426//15426 -f 15426//15426 15352//15352 15353//15353 -f 15426//15426 15353//15353 15536//15536 -f 15536//15536 15353//15353 15490//15490 -f 15536//15536 15490//15490 15537//15537 -f 15537//15537 15490//15490 15491//15491 -f 15537//15537 15491//15491 15538//15538 -f 15538//15538 15491//15491 15492//15492 -f 15538//15538 15492//15492 15526//15526 -f 15526//15526 15492//15492 15493//15493 -f 15526//15526 15493//15493 15494//15494 -f 15502//15502 15503//15503 15535//15535 -f 15535//15535 15503//15503 15504//15504 -f 15535//15535 15504//15504 15539//15539 -f 15539//15539 15504//15504 15505//15505 -f 15539//15539 15505//15505 15540//15540 -f 15540//15540 15505//15505 15506//15506 -f 15540//15540 15506//15506 15541//15541 -f 15541//15541 15506//15506 15507//15507 -f 15541//15541 15507//15507 15393//15393 -f 15393//15393 15507//15507 15316//15316 -f 15393//15393 15316//15316 15394//15394 -f 15394//15394 15316//15316 15318//15318 -f 15394//15394 15318//15318 15396//15396 -f 15396//15396 15318//15318 15320//15320 -f 15396//15396 15320//15320 15398//15398 -f 15398//15398 15320//15320 15322//15322 -f 15398//15398 15322//15322 15400//15400 -f 15322//15322 15324//15324 15400//15400 -f 15400//15400 15324//15324 15326//15326 -f 15400//15400 15326//15326 15402//15402 -f 15402//15402 15326//15326 15328//15328 -f 15402//15402 15328//15328 15404//15404 -f 15404//15404 15328//15328 15330//15330 -f 15404//15404 15330//15330 15406//15406 -f 15406//15406 15330//15330 15332//15332 -f 15406//15406 15332//15332 15408//15408 -f 15408//15408 15332//15332 15334//15334 -f 15408//15408 15334//15334 15410//15410 -f 15410//15410 15334//15334 15336//15336 -f 15410//15410 15336//15336 15412//15412 -f 15412//15412 15336//15336 15338//15338 -f 15412//15412 15338//15338 15414//15414 -f 15414//15414 15338//15338 15340//15340 -f 15414//15414 15340//15340 15416//15416 -f 15416//15416 15340//15340 15342//15342 -f 15416//15416 15342//15342 15418//15418 -f 15418//15418 15342//15342 15344//15344 -f 15418//15418 15344//15344 15346//15346 -f 15401//15401 15361//15361 15399//15399 -f 15399//15399 15361//15361 15359//15359 -f 15399//15399 15359//15359 15397//15397 -f 15397//15397 15359//15359 15357//15357 -f 15397//15397 15357//15357 15395//15395 -f 15395//15395 15357//15357 15355//15355 -f 15395//15395 15355//15355 15392//15392 -f 15392//15392 15355//15355 15354//15354 -f 15392//15392 15354//15354 15542//15542 -f 15542//15542 15354//15354 15525//15525 -f 15542//15542 15525//15525 15543//15543 -f 15543//15543 15525//15525 15524//15524 -f 15543//15543 15524//15524 15544//15544 -f 15544//15544 15524//15524 15523//15523 -f 15544//15544 15523//15523 15545//15545 -f 15546//15546 15511//15511 15547//15547 -f 15547//15547 15511//15511 15510//15510 -f 15547//15547 15510//15510 15548//15548 -f 15548//15548 15510//15510 15509//15509 -f 15548//15548 15509//15509 15549//15549 -f 15549//15549 15509//15509 15508//15508 -f 15549//15549 15508//15508 15427//15427 -f 15427//15427 15508//15508 15391//15391 -f 15427//15427 15391//15391 15425//15425 -f 15425//15425 15391//15391 15389//15389 -f 15425//15425 15389//15389 15423//15423 -f 15423//15423 15389//15389 15387//15387 -f 15423//15423 15387//15387 15421//15421 -f 15421//15421 15387//15387 15385//15385 -f 15421//15421 15385//15385 15419//15419 -f 15523//15523 15522//15522 15545//15545 -f 15545//15545 15522//15522 15521//15521 -f 15545//15545 15521//15521 15550//15550 -f 15550//15550 15521//15521 15520//15520 -f 15550//15550 15520//15520 15551//15551 -f 15551//15551 15520//15520 15519//15519 -f 15551//15551 15519//15519 15552//15552 -f 15552//15552 15519//15519 15518//15518 -f 15552//15552 15518//15518 15553//15553 -f 15553//15553 15518//15518 15517//15517 -f 15553//15553 15517//15517 15554//15554 -f 15554//15554 15517//15517 15516//15516 -f 15554//15554 15516//15516 15555//15555 -f 15555//15555 15516//15516 15515//15515 -f 15555//15555 15515//15515 15556//15556 -f 15556//15556 15515//15515 15514//15514 -f 15556//15556 15514//15514 15557//15557 -f 15557//15557 15514//15514 15513//15513 -f 15557//15557 15513//15513 15546//15546 -f 15546//15546 15513//15513 15512//15512 -f 15546//15546 15512//15512 15511//15511 -f 15385//15385 15383//15383 15419//15419 -f 15419//15419 15383//15383 15381//15381 -f 15419//15419 15381//15381 15417//15417 -f 15417//15417 15381//15381 15379//15379 -f 15417//15417 15379//15379 15415//15415 -f 15415//15415 15379//15379 15377//15377 -f 15415//15415 15377//15377 15413//15413 -f 15413//15413 15377//15377 15375//15375 -f 15413//15413 15375//15375 15411//15411 -f 15411//15411 15375//15375 15373//15373 -f 15411//15411 15373//15373 15409//15409 -f 15409//15409 15373//15373 15371//15371 -f 15409//15409 15371//15371 15407//15407 -f 15407//15407 15371//15371 15369//15369 -f 15407//15407 15369//15369 15405//15405 -f 15405//15405 15369//15369 15367//15367 -f 15405//15405 15367//15367 15403//15403 -f 15403//15403 15367//15367 15365//15365 -f 15403//15403 15365//15365 15401//15401 -f 15401//15401 15365//15365 15363//15363 -f 15401//15401 15363//15363 15361//15361 -f 15427//15427 15426//15426 15536//15536 -f 15427//15427 15536//15536 15549//15549 -f 15549//15549 15536//15536 15537//15537 -f 15549//15549 15537//15537 15548//15548 -f 15548//15548 15537//15537 15538//15538 -f 15548//15548 15538//15538 15547//15547 -f 15547//15547 15538//15538 15526//15526 -f 15547//15547 15526//15526 15546//15546 -f 15546//15546 15526//15526 15527//15527 -f 15546//15546 15527//15527 15557//15557 -f 15557//15557 15527//15527 15528//15528 -f 15557//15557 15528//15528 15556//15556 -f 15556//15556 15528//15528 15529//15529 -f 15556//15556 15529//15529 15555//15555 -f 15555//15555 15529//15529 15530//15530 -f 15555//15555 15530//15530 15554//15554 -f 15554//15554 15530//15530 15531//15531 -f 15554//15554 15531//15531 15553//15553 -f 15553//15553 15531//15531 15532//15532 -f 15553//15553 15532//15532 15552//15552 -f 15552//15552 15532//15532 15533//15533 -f 15552//15552 15533//15533 15551//15551 -f 15551//15551 15533//15533 15534//15534 -f 15551//15551 15534//15534 15550//15550 -f 15550//15550 15534//15534 15535//15535 -f 15550//15550 15535//15535 15545//15545 -f 15545//15545 15535//15535 15539//15539 -f 15545//15545 15539//15539 15544//15544 -f 15544//15544 15539//15539 15540//15540 -f 15544//15544 15540//15540 15543//15543 -f 15543//15543 15540//15540 15541//15541 -f 15543//15543 15541//15541 15542//15542 -f 15542//15542 15541//15541 15393//15393 -f 15542//15542 15393//15393 15392//15392 -f 15558//15558 15559//15559 15560//15560 -f 15560//15560 15559//15559 15561//15561 -f 15560//15560 15561//15561 15562//15562 -f 15562//15562 15561//15561 15563//15563 -f 15562//15562 15563//15563 15564//15564 -f 15564//15564 15563//15563 15565//15565 -f 15564//15564 15565//15565 15566//15566 -f 15566//15566 15565//15565 15567//15567 -f 15566//15566 15567//15567 15568//15568 -f 15568//15568 15567//15567 15569//15569 -f 15568//15568 15569//15569 15570//15570 -f 15570//15570 15569//15569 15571//15571 -f 15570//15570 15571//15571 15572//15572 -f 15572//15572 15571//15571 15573//15573 -f 15572//15572 15573//15573 15574//15574 -f 15574//15574 15573//15573 15575//15575 -f 15574//15574 15575//15575 15576//15576 -f 15576//15576 15575//15575 15577//15577 -f 15576//15576 15577//15577 15578//15578 -f 15578//15578 15577//15577 15579//15579 -f 15578//15578 15579//15579 15580//15580 -f 15580//15580 15579//15579 15581//15581 -f 15580//15580 15581//15581 15582//15582 -f 15582//15582 15581//15581 15583//15583 -f 15582//15582 15583//15583 15584//15584 -f 15584//15584 15583//15583 15585//15585 -f 15584//15584 15585//15585 15586//15586 -f 15586//15586 15585//15585 15587//15587 -f 15588//15588 15589//15589 15590//15590 -f 15588//15588 15590//15590 15591//15591 -f 15591//15591 15590//15590 15592//15592 -f 15591//15591 15592//15592 15593//15593 -f 15593//15593 15592//15592 15594//15594 -f 15593//15593 15594//15594 15595//15595 -f 15595//15595 15594//15594 15596//15596 -f 15595//15595 15596//15596 15597//15597 -f 15597//15597 15596//15596 15598//15598 -f 15597//15597 15598//15598 15599//15599 -f 15599//15599 15598//15598 15600//15600 -f 15599//15599 15600//15600 15601//15601 -f 15601//15601 15600//15600 15602//15602 -f 15601//15601 15602//15602 15603//15603 -f 15603//15603 15602//15602 15604//15604 -f 15603//15603 15604//15604 15605//15605 -f 15605//15605 15604//15604 15606//15606 -f 15605//15605 15606//15606 15607//15607 -f 15607//15607 15606//15606 15608//15608 -f 15607//15607 15608//15608 15609//15609 -f 15609//15609 15608//15608 15610//15610 -f 15609//15609 15610//15610 15611//15611 -f 15611//15611 15610//15610 15612//15612 -f 15611//15611 15612//15612 15613//15613 -f 15613//15613 15612//15612 15614//15614 -f 15613//15613 15614//15614 15615//15615 -f 15615//15615 15614//15614 15616//15616 -f 15615//15615 15616//15616 15617//15617 -f 15617//15617 15616//15616 15618//15618 -f 15617//15617 15618//15618 15619//15619 -f 15619//15619 15618//15618 15620//15620 -f 15619//15619 15620//15620 15621//15621 -f 15621//15621 15620//15620 15622//15622 -f 15621//15621 15622//15622 15623//15623 -f 15623//15623 15622//15622 15624//15624 -f 15623//15623 15624//15624 15625//15625 -f 15625//15625 15624//15624 15626//15626 -f 15625//15625 15626//15626 15627//15627 -f 15628//15628 15629//15629 15630//15630 -f 15628//15628 15630//15630 15631//15631 -f 15631//15631 15630//15630 15632//15632 -f 15631//15631 15632//15632 15633//15633 -f 15633//15633 15632//15632 15634//15634 -f 15633//15633 15634//15634 15635//15635 -f 15635//15635 15634//15634 15636//15636 -f 15635//15635 15636//15636 15637//15637 -f 15637//15637 15636//15636 15638//15638 -f 15637//15637 15638//15638 15639//15639 -f 15639//15639 15638//15638 15640//15640 -f 15639//15639 15640//15640 15641//15641 -f 15641//15641 15640//15640 15642//15642 -f 15641//15641 15642//15642 15643//15643 -f 15643//15643 15642//15642 15644//15644 -f 15643//15643 15644//15644 15645//15645 -f 15645//15645 15644//15644 15646//15646 -f 15645//15645 15646//15646 15647//15647 -f 15647//15647 15646//15646 15648//15648 -f 15647//15647 15648//15648 15649//15649 -f 15649//15649 15648//15648 15650//15650 -f 15649//15649 15650//15650 15651//15651 -f 15651//15651 15650//15650 15652//15652 -f 15651//15651 15652//15652 15653//15653 -f 15653//15653 15652//15652 15654//15654 -f 15653//15653 15654//15654 15655//15655 -f 15655//15655 15654//15654 15656//15656 -f 15655//15655 15656//15656 15657//15657 -f 15657//15657 15656//15656 15658//15658 -f 15657//15657 15658//15658 15659//15659 -f 15659//15659 15658//15658 15660//15660 -f 15659//15659 15660//15660 15661//15661 -f 15661//15661 15660//15660 15662//15662 -f 15661//15661 15662//15662 15663//15663 -f 15663//15663 15662//15662 15664//15664 -f 15663//15663 15664//15664 15665//15665 -f 15665//15665 15664//15664 15666//15666 -f 15665//15665 15666//15666 15667//15667 -f 15668//15668 15669//15669 15670//15670 -f 15668//15668 15670//15670 15671//15671 -f 15671//15671 15670//15670 15672//15672 -f 15671//15671 15672//15672 15673//15673 -f 15673//15673 15672//15672 15674//15674 -f 15673//15673 15674//15674 15675//15675 -f 15675//15675 15674//15674 15676//15676 -f 15675//15675 15676//15676 15677//15677 -f 15677//15677 15676//15676 15678//15678 -f 15677//15677 15678//15678 15679//15679 -f 15679//15679 15678//15678 15680//15680 -f 15679//15679 15680//15680 15681//15681 -f 15681//15681 15680//15680 15682//15682 -f 15681//15681 15682//15682 15683//15683 -f 15683//15683 15682//15682 15684//15684 -f 15683//15683 15684//15684 15685//15685 -f 15685//15685 15684//15684 15686//15686 -f 15685//15685 15686//15686 15687//15687 -f 15687//15687 15686//15686 15688//15688 -f 15687//15687 15688//15688 15689//15689 -f 15689//15689 15688//15688 15690//15690 -f 15689//15689 15690//15690 15691//15691 -f 15691//15691 15690//15690 15692//15692 -f 15691//15691 15692//15692 15693//15693 -f 15693//15693 15692//15692 15694//15694 -f 15693//15693 15694//15694 15695//15695 -f 15695//15695 15694//15694 15696//15696 -f 15695//15695 15696//15696 15697//15697 -f 15697//15697 15696//15696 15698//15698 -f 15697//15697 15698//15698 15699//15699 -f 15699//15699 15698//15698 15700//15700 -f 15699//15699 15700//15700 15701//15701 -f 15701//15701 15700//15700 15702//15702 -f 15701//15701 15702//15702 15703//15703 -f 15586//15586 15587//15587 15704//15704 -f 15704//15704 15587//15587 15705//15705 -f 15704//15704 15705//15705 15706//15706 -f 15706//15706 15705//15705 15707//15707 -f 15706//15706 15707//15707 15708//15708 -f 15708//15708 15707//15707 15709//15709 -f 15708//15708 15709//15709 15710//15710 -f 15710//15710 15709//15709 15711//15711 -f 15710//15710 15711//15711 15712//15712 -f 15712//15712 15711//15711 15713//15713 -f 15712//15712 15713//15713 15714//15714 -f 15714//15714 15713//15713 15715//15715 -f 15714//15714 15715//15715 15716//15716 -f 15716//15716 15715//15715 15717//15717 -f 15716//15716 15717//15717 15718//15718 -f 15718//15718 15717//15717 15719//15719 -f 15718//15718 15719//15719 15720//15720 -f 15720//15720 15719//15719 15721//15721 -f 15720//15720 15721//15721 15722//15722 -f 15722//15722 15721//15721 15723//15723 -f 15722//15722 15723//15723 15724//15724 -f 15724//15724 15723//15723 15725//15725 -f 15724//15724 15725//15725 15726//15726 -f 15726//15726 15725//15725 15727//15727 -f 15726//15726 15727//15727 15728//15728 -f 15728//15728 15727//15727 15729//15729 -f 15728//15728 15729//15729 15558//15558 -f 15558//15558 15729//15729 15559//15559 -f 15562//15562 15730//15730 15560//15560 -f 15560//15560 15730//15730 15731//15731 -f 15560//15560 15731//15731 15558//15558 -f 15558//15558 15731//15731 15626//15626 -f 15558//15558 15626//15626 15728//15728 -f 15568//15568 15732//15732 15566//15566 -f 15566//15566 15732//15732 15733//15733 -f 15566//15566 15733//15733 15564//15564 -f 15564//15564 15733//15733 15734//15734 -f 15564//15564 15734//15734 15562//15562 -f 15562//15562 15734//15734 15735//15735 -f 15562//15562 15735//15735 15730//15730 -f 15574//15574 15736//15736 15572//15572 -f 15572//15572 15736//15736 15737//15737 -f 15572//15572 15737//15737 15570//15570 -f 15570//15570 15737//15737 15738//15738 -f 15570//15570 15738//15738 15568//15568 -f 15568//15568 15738//15738 15739//15739 -f 15568//15568 15739//15739 15732//15732 -f 15706//15706 15592//15592 15704//15704 -f 15704//15704 15592//15592 15590//15590 -f 15704//15704 15590//15590 15586//15586 -f 15586//15586 15590//15590 15589//15589 -f 15586//15586 15589//15589 15584//15584 -f 15712//15712 15600//15600 15710//15710 -f 15710//15710 15600//15600 15598//15598 -f 15710//15710 15598//15598 15708//15708 -f 15708//15708 15598//15598 15596//15596 -f 15708//15708 15596//15596 15706//15706 -f 15706//15706 15596//15596 15594//15594 -f 15706//15706 15594//15594 15592//15592 -f 15718//15718 15608//15608 15716//15716 -f 15716//15716 15608//15608 15606//15606 -f 15716//15716 15606//15606 15714//15714 -f 15714//15714 15606//15606 15604//15604 -f 15714//15714 15604//15604 15712//15712 -f 15712//15712 15604//15604 15602//15602 -f 15712//15712 15602//15602 15600//15600 -f 15722//15722 15614//15614 15720//15720 -f 15720//15720 15614//15614 15612//15612 -f 15720//15720 15612//15612 15718//15718 -f 15718//15718 15612//15612 15610//15610 -f 15718//15718 15610//15610 15608//15608 -f 15626//15626 15624//15624 15728//15728 -f 15728//15728 15624//15624 15622//15622 -f 15728//15728 15622//15622 15726//15726 -f 15726//15726 15622//15622 15620//15620 -f 15726//15726 15620//15620 15724//15724 -f 15724//15724 15620//15620 15618//15618 -f 15724//15724 15618//15618 15722//15722 -f 15722//15722 15618//15618 15616//15616 -f 15722//15722 15616//15616 15614//15614 -f 15578//15578 15740//15740 15576//15576 -f 15576//15576 15740//15740 15741//15741 -f 15576//15576 15741//15741 15574//15574 -f 15574//15574 15741//15741 15742//15742 -f 15574//15574 15742//15742 15736//15736 -f 15589//15589 15743//15743 15584//15584 -f 15584//15584 15743//15743 15744//15744 -f 15584//15584 15744//15744 15582//15582 -f 15582//15582 15744//15744 15745//15745 -f 15582//15582 15745//15745 15580//15580 -f 15580//15580 15745//15745 15746//15746 -f 15580//15580 15746//15746 15578//15578 -f 15578//15578 15746//15746 15747//15747 -f 15578//15578 15747//15747 15740//15740 -f 15705//15705 15633//15633 15707//15707 -f 15707//15707 15633//15633 15635//15635 -f 15707//15707 15635//15635 15709//15709 -f 15709//15709 15635//15635 15637//15637 -f 15709//15709 15637//15637 15711//15711 -f 15573//15573 15748//15748 15575//15575 -f 15575//15575 15748//15748 15749//15749 -f 15575//15575 15749//15749 15577//15577 -f 15567//15567 15750//15750 15569//15569 -f 15569//15569 15750//15750 15751//15751 -f 15569//15569 15751//15751 15571//15571 -f 15571//15571 15751//15751 15752//15752 -f 15571//15571 15752//15752 15573//15573 -f 15573//15573 15752//15752 15753//15753 -f 15573//15573 15753//15753 15748//15748 -f 15561//15561 15754//15754 15563//15563 -f 15563//15563 15754//15754 15755//15755 -f 15563//15563 15755//15755 15565//15565 -f 15565//15565 15755//15755 15756//15756 -f 15565//15565 15756//15756 15567//15567 -f 15567//15567 15756//15756 15757//15757 -f 15567//15567 15757//15757 15750//15750 -f 15583//15583 15758//15758 15585//15585 -f 15585//15585 15758//15758 15759//15759 -f 15585//15585 15759//15759 15587//15587 -f 15587//15587 15759//15759 15628//15628 -f 15587//15587 15628//15628 15705//15705 -f 15705//15705 15628//15628 15631//15631 -f 15705//15705 15631//15631 15633//15633 -f 15749//15749 15760//15760 15577//15577 -f 15577//15577 15760//15760 15761//15761 -f 15577//15577 15761//15761 15579//15579 -f 15579//15579 15761//15761 15762//15762 -f 15579//15579 15762//15762 15581//15581 -f 15581//15581 15762//15762 15763//15763 -f 15581//15581 15763//15763 15583//15583 -f 15583//15583 15763//15763 15764//15764 -f 15583//15583 15764//15764 15758//15758 -f 15721//15721 15655//15655 15723//15723 -f 15723//15723 15655//15655 15657//15657 -f 15723//15723 15657//15657 15725//15725 -f 15725//15725 15657//15657 15659//15659 -f 15725//15725 15659//15659 15727//15727 -f 15659//15659 15661//15661 15727//15727 -f 15727//15727 15661//15661 15663//15663 -f 15727//15727 15663//15663 15729//15729 -f 15729//15729 15663//15663 15665//15665 -f 15729//15729 15665//15665 15559//15559 -f 15559//15559 15665//15665 15667//15667 -f 15559//15559 15667//15667 15561//15561 -f 15561//15561 15667//15667 15765//15765 -f 15561//15561 15765//15765 15754//15754 -f 15717//15717 15649//15649 15719//15719 -f 15719//15719 15649//15649 15651//15651 -f 15719//15719 15651//15651 15721//15721 -f 15721//15721 15651//15651 15653//15653 -f 15721//15721 15653//15653 15655//15655 -f 15637//15637 15639//15639 15711//15711 -f 15711//15711 15639//15639 15641//15641 -f 15711//15711 15641//15641 15713//15713 -f 15713//15713 15641//15641 15643//15643 -f 15713//15713 15643//15643 15715//15715 -f 15715//15715 15643//15643 15645//15645 -f 15715//15715 15645//15645 15717//15717 -f 15717//15717 15645//15645 15647//15647 -f 15717//15717 15647//15647 15649//15649 -f 15627//15627 15626//15626 15731//15731 -f 15627//15627 15731//15731 15766//15766 -f 15766//15766 15731//15731 15730//15730 -f 15766//15766 15730//15730 15767//15767 -f 15767//15767 15730//15730 15735//15735 -f 15767//15767 15735//15735 15768//15768 -f 15768//15768 15735//15735 15734//15734 -f 15768//15768 15734//15734 15769//15769 -f 15769//15769 15734//15734 15733//15733 -f 15769//15769 15733//15733 15770//15770 -f 15770//15770 15733//15733 15732//15732 -f 15770//15770 15732//15732 15771//15771 -f 15771//15771 15732//15732 15739//15739 -f 15771//15771 15739//15739 15772//15772 -f 15772//15772 15739//15739 15738//15738 -f 15772//15772 15738//15738 15773//15773 -f 15773//15773 15738//15738 15737//15737 -f 15773//15773 15737//15737 15774//15774 -f 15774//15774 15737//15737 15736//15736 -f 15774//15774 15736//15736 15775//15775 -f 15775//15775 15736//15736 15742//15742 -f 15775//15775 15742//15742 15776//15776 -f 15776//15776 15742//15742 15741//15741 -f 15776//15776 15741//15741 15777//15777 -f 15777//15777 15741//15741 15740//15740 -f 15777//15777 15740//15740 15778//15778 -f 15778//15778 15740//15740 15747//15747 -f 15778//15778 15747//15747 15779//15779 -f 15779//15779 15747//15747 15746//15746 -f 15779//15779 15746//15746 15780//15780 -f 15780//15780 15746//15746 15745//15745 -f 15780//15780 15745//15745 15781//15781 -f 15781//15781 15745//15745 15744//15744 -f 15781//15781 15744//15744 15782//15782 -f 15782//15782 15744//15744 15743//15743 -f 15782//15782 15743//15743 15783//15783 -f 15783//15783 15743//15743 15589//15589 -f 15783//15783 15589//15589 15588//15588 -f 15667//15667 15666//15666 15784//15784 -f 15667//15667 15784//15784 15765//15765 -f 15765//15765 15784//15784 15785//15785 -f 15765//15765 15785//15785 15754//15754 -f 15754//15754 15785//15785 15786//15786 -f 15754//15754 15786//15786 15755//15755 -f 15755//15755 15786//15786 15787//15787 -f 15755//15755 15787//15787 15756//15756 -f 15756//15756 15787//15787 15788//15788 -f 15756//15756 15788//15788 15757//15757 -f 15757//15757 15788//15788 15789//15789 -f 15757//15757 15789//15789 15750//15750 -f 15750//15750 15789//15789 15790//15790 -f 15750//15750 15790//15790 15751//15751 -f 15751//15751 15790//15790 15791//15791 -f 15751//15751 15791//15791 15752//15752 -f 15752//15752 15791//15791 15792//15792 -f 15752//15752 15792//15792 15753//15753 -f 15753//15753 15792//15792 15793//15793 -f 15753//15753 15793//15793 15748//15748 -f 15748//15748 15793//15793 15794//15794 -f 15748//15748 15794//15794 15749//15749 -f 15749//15749 15794//15794 15795//15795 -f 15749//15749 15795//15795 15760//15760 -f 15760//15760 15795//15795 15796//15796 -f 15760//15760 15796//15796 15761//15761 -f 15761//15761 15796//15796 15797//15797 -f 15761//15761 15797//15797 15762//15762 -f 15762//15762 15797//15797 15798//15798 -f 15762//15762 15798//15798 15763//15763 -f 15763//15763 15798//15798 15799//15799 -f 15763//15763 15799//15799 15764//15764 -f 15764//15764 15799//15799 15800//15800 -f 15764//15764 15800//15800 15758//15758 -f 15758//15758 15800//15800 15801//15801 -f 15758//15758 15801//15801 15759//15759 -f 15759//15759 15801//15801 15629//15629 -f 15759//15759 15629//15629 15628//15628 -f 15802//15802 15780//15780 15803//15803 -f 15803//15803 15780//15780 15781//15781 -f 15803//15803 15781//15781 15804//15804 -f 15804//15804 15781//15781 15782//15782 -f 15804//15804 15782//15782 15805//15805 -f 15805//15805 15782//15782 15783//15783 -f 15805//15805 15783//15783 15669//15669 -f 15669//15669 15783//15783 15588//15588 -f 15669//15669 15588//15588 15670//15670 -f 15670//15670 15588//15588 15591//15591 -f 15670//15670 15591//15591 15672//15672 -f 15672//15672 15591//15591 15593//15593 -f 15672//15672 15593//15593 15674//15674 -f 15674//15674 15593//15593 15595//15595 -f 15674//15674 15595//15595 15676//15676 -f 15806//15806 15770//15770 15807//15807 -f 15807//15807 15770//15770 15771//15771 -f 15807//15807 15771//15771 15808//15808 -f 15808//15808 15771//15771 15772//15772 -f 15808//15808 15772//15772 15809//15809 -f 15809//15809 15772//15772 15773//15773 -f 15809//15809 15773//15773 15810//15810 -f 15810//15810 15773//15773 15774//15774 -f 15810//15810 15774//15774 15811//15811 -f 15811//15811 15774//15774 15775//15775 -f 15811//15811 15775//15775 15812//15812 -f 15812//15812 15775//15775 15776//15776 -f 15812//15812 15776//15776 15813//15813 -f 15813//15813 15776//15776 15777//15777 -f 15813//15813 15777//15777 15814//15814 -f 15814//15814 15777//15777 15778//15778 -f 15814//15814 15778//15778 15802//15802 -f 15802//15802 15778//15778 15779//15779 -f 15802//15802 15779//15779 15780//15780 -f 15694//15694 15619//15619 15696//15696 -f 15696//15696 15619//15619 15621//15621 -f 15696//15696 15621//15621 15698//15698 -f 15698//15698 15621//15621 15623//15623 -f 15698//15698 15623//15623 15700//15700 -f 15700//15700 15623//15623 15625//15625 -f 15700//15700 15625//15625 15702//15702 -f 15702//15702 15625//15625 15627//15627 -f 15702//15702 15627//15627 15815//15815 -f 15815//15815 15627//15627 15766//15766 -f 15815//15815 15766//15766 15816//15816 -f 15816//15816 15766//15766 15767//15767 -f 15816//15816 15767//15767 15817//15817 -f 15817//15817 15767//15767 15768//15768 -f 15817//15817 15768//15768 15806//15806 -f 15806//15806 15768//15768 15769//15769 -f 15806//15806 15769//15769 15770//15770 -f 15595//15595 15597//15597 15676//15676 -f 15676//15676 15597//15597 15599//15599 -f 15676//15676 15599//15599 15678//15678 -f 15678//15678 15599//15599 15601//15601 -f 15678//15678 15601//15601 15680//15680 -f 15680//15680 15601//15601 15603//15603 -f 15680//15680 15603//15603 15682//15682 -f 15682//15682 15603//15603 15605//15605 -f 15682//15682 15605//15605 15684//15684 -f 15684//15684 15605//15605 15607//15607 -f 15684//15684 15607//15607 15686//15686 -f 15686//15686 15607//15607 15609//15609 -f 15686//15686 15609//15609 15688//15688 -f 15688//15688 15609//15609 15611//15611 -f 15688//15688 15611//15611 15690//15690 -f 15690//15690 15611//15611 15613//15613 -f 15690//15690 15613//15613 15692//15692 -f 15692//15692 15613//15613 15615//15615 -f 15692//15692 15615//15615 15694//15694 -f 15694//15694 15615//15615 15617//15617 -f 15694//15694 15617//15617 15619//15619 -f 15818//15818 15797//15797 15819//15819 -f 15819//15819 15797//15797 15796//15796 -f 15819//15819 15796//15796 15820//15820 -f 15820//15820 15796//15796 15795//15795 -f 15820//15820 15795//15795 15821//15821 -f 15821//15821 15795//15795 15794//15794 -f 15821//15821 15794//15794 15822//15822 -f 15822//15822 15794//15794 15793//15793 -f 15822//15822 15793//15793 15823//15823 -f 15823//15823 15793//15793 15792//15792 -f 15823//15823 15792//15792 15824//15824 -f 15824//15824 15792//15792 15791//15791 -f 15824//15824 15791//15791 15825//15825 -f 15825//15825 15791//15791 15790//15790 -f 15825//15825 15790//15790 15826//15826 -f 15826//15826 15790//15790 15789//15789 -f 15826//15826 15789//15789 15827//15827 -f 15677//15677 15636//15636 15675//15675 -f 15675//15675 15636//15636 15634//15634 -f 15675//15675 15634//15634 15673//15673 -f 15673//15673 15634//15634 15632//15632 -f 15673//15673 15632//15632 15671//15671 -f 15671//15671 15632//15632 15630//15630 -f 15671//15671 15630//15630 15668//15668 -f 15668//15668 15630//15630 15629//15629 -f 15668//15668 15629//15629 15828//15828 -f 15828//15828 15629//15629 15801//15801 -f 15828//15828 15801//15801 15829//15829 -f 15829//15829 15801//15801 15800//15800 -f 15829//15829 15800//15800 15830//15830 -f 15830//15830 15800//15800 15799//15799 -f 15830//15830 15799//15799 15818//15818 -f 15818//15818 15799//15799 15798//15798 -f 15818//15818 15798//15798 15797//15797 -f 15695//15695 15656//15656 15693//15693 -f 15693//15693 15656//15656 15654//15654 -f 15693//15693 15654//15654 15691//15691 -f 15691//15691 15654//15654 15652//15652 -f 15691//15691 15652//15652 15689//15689 -f 15689//15689 15652//15652 15650//15650 -f 15689//15689 15650//15650 15687//15687 -f 15687//15687 15650//15650 15648//15648 -f 15687//15687 15648//15648 15685//15685 -f 15685//15685 15648//15648 15646//15646 -f 15685//15685 15646//15646 15683//15683 -f 15683//15683 15646//15646 15644//15644 -f 15683//15683 15644//15644 15681//15681 -f 15681//15681 15644//15644 15642//15642 -f 15681//15681 15642//15642 15679//15679 -f 15679//15679 15642//15642 15640//15640 -f 15679//15679 15640//15640 15677//15677 -f 15677//15677 15640//15640 15638//15638 -f 15677//15677 15638//15638 15636//15636 -f 15789//15789 15788//15788 15827//15827 -f 15827//15827 15788//15788 15787//15787 -f 15827//15827 15787//15787 15831//15831 -f 15831//15831 15787//15787 15786//15786 -f 15831//15831 15786//15786 15832//15832 -f 15832//15832 15786//15786 15785//15785 -f 15832//15832 15785//15785 15833//15833 -f 15833//15833 15785//15785 15784//15784 -f 15833//15833 15784//15784 15703//15703 -f 15703//15703 15784//15784 15666//15666 -f 15703//15703 15666//15666 15701//15701 -f 15701//15701 15666//15666 15664//15664 -f 15701//15701 15664//15664 15699//15699 -f 15699//15699 15664//15664 15662//15662 -f 15699//15699 15662//15662 15697//15697 -f 15697//15697 15662//15662 15660//15660 -f 15697//15697 15660//15660 15695//15695 -f 15695//15695 15660//15660 15658//15658 -f 15695//15695 15658//15658 15656//15656 -f 15703//15703 15702//15702 15815//15815 -f 15703//15703 15815//15815 15833//15833 -f 15833//15833 15815//15815 15816//15816 -f 15833//15833 15816//15816 15832//15832 -f 15832//15832 15816//15816 15817//15817 -f 15832//15832 15817//15817 15831//15831 -f 15831//15831 15817//15817 15806//15806 -f 15831//15831 15806//15806 15827//15827 -f 15827//15827 15806//15806 15807//15807 -f 15827//15827 15807//15807 15826//15826 -f 15826//15826 15807//15807 15808//15808 -f 15826//15826 15808//15808 15825//15825 -f 15825//15825 15808//15808 15809//15809 -f 15825//15825 15809//15809 15824//15824 -f 15824//15824 15809//15809 15810//15810 -f 15824//15824 15810//15810 15823//15823 -f 15823//15823 15810//15810 15811//15811 -f 15823//15823 15811//15811 15822//15822 -f 15822//15822 15811//15811 15812//15812 -f 15822//15822 15812//15812 15821//15821 -f 15821//15821 15812//15812 15813//15813 -f 15821//15821 15813//15813 15820//15820 -f 15820//15820 15813//15813 15814//15814 -f 15820//15820 15814//15814 15819//15819 -f 15819//15819 15814//15814 15802//15802 -f 15819//15819 15802//15802 15818//15818 -f 15818//15818 15802//15802 15803//15803 -f 15818//15818 15803//15803 15830//15830 -f 15830//15830 15803//15803 15804//15804 -f 15830//15830 15804//15804 15829//15829 -f 15829//15829 15804//15804 15805//15805 -f 15829//15829 15805//15805 15828//15828 -f 15828//15828 15805//15805 15669//15669 -f 15828//15828 15669//15669 15668//15668 -f 15834//15834 15835//15835 15836//15836 -f 15836//15836 15835//15835 15837//15837 -f 15836//15836 15837//15837 15838//15838 -f 15838//15838 15837//15837 15839//15839 -f 15838//15838 15839//15839 15840//15840 -f 15840//15840 15839//15839 15841//15841 -f 15840//15840 15841//15841 15842//15842 -f 15842//15842 15841//15841 15843//15843 -f 15842//15842 15843//15843 15844//15844 -f 15844//15844 15843//15843 15845//15845 -f 15844//15844 15845//15845 15846//15846 -f 15846//15846 15845//15845 15847//15847 -f 15846//15846 15847//15847 15848//15848 -f 15848//15848 15847//15847 15849//15849 -f 15848//15848 15849//15849 15850//15850 -f 15850//15850 15849//15849 15851//15851 -f 15850//15850 15851//15851 15852//15852 -f 15852//15852 15851//15851 15853//15853 -f 15852//15852 15853//15853 15854//15854 -f 15854//15854 15853//15853 15855//15855 -f 15854//15854 15855//15855 15856//15856 -f 15856//15856 15855//15855 15857//15857 -f 15856//15856 15857//15857 15858//15858 -f 15858//15858 15857//15857 15859//15859 -f 15858//15858 15859//15859 15860//15860 -f 15860//15860 15859//15859 15861//15861 -f 15860//15860 15861//15861 15862//15862 -f 15862//15862 15861//15861 15863//15863 -f 15864//15864 15865//15865 15866//15866 -f 15864//15864 15866//15866 15867//15867 -f 15867//15867 15866//15866 15868//15868 -f 15867//15867 15868//15868 15869//15869 -f 15869//15869 15868//15868 15870//15870 -f 15869//15869 15870//15870 15871//15871 -f 15871//15871 15870//15870 15872//15872 -f 15871//15871 15872//15872 15873//15873 -f 15873//15873 15872//15872 15874//15874 -f 15873//15873 15874//15874 15875//15875 -f 15875//15875 15874//15874 15876//15876 -f 15875//15875 15876//15876 15877//15877 -f 15877//15877 15876//15876 15878//15878 -f 15877//15877 15878//15878 15879//15879 -f 15879//15879 15878//15878 15880//15880 -f 15879//15879 15880//15880 15881//15881 -f 15881//15881 15880//15880 15882//15882 -f 15881//15881 15882//15882 15883//15883 -f 15883//15883 15882//15882 15884//15884 -f 15883//15883 15884//15884 15885//15885 -f 15885//15885 15884//15884 15886//15886 -f 15885//15885 15886//15886 15887//15887 -f 15887//15887 15886//15886 15888//15888 -f 15887//15887 15888//15888 15889//15889 -f 15889//15889 15888//15888 15890//15890 -f 15889//15889 15890//15890 15891//15891 -f 15891//15891 15890//15890 15892//15892 -f 15891//15891 15892//15892 15893//15893 -f 15893//15893 15892//15892 15894//15894 -f 15893//15893 15894//15894 15895//15895 -f 15895//15895 15894//15894 15896//15896 -f 15895//15895 15896//15896 15897//15897 -f 15897//15897 15896//15896 15898//15898 -f 15897//15897 15898//15898 15899//15899 -f 15899//15899 15898//15898 15900//15900 -f 15899//15899 15900//15900 15901//15901 -f 15901//15901 15900//15900 15902//15902 -f 15901//15901 15902//15902 15903//15903 -f 15904//15904 15905//15905 15906//15906 -f 15904//15904 15906//15906 15907//15907 -f 15907//15907 15906//15906 15908//15908 -f 15907//15907 15908//15908 15909//15909 -f 15909//15909 15908//15908 15910//15910 -f 15909//15909 15910//15910 15911//15911 -f 15911//15911 15910//15910 15912//15912 -f 15911//15911 15912//15912 15913//15913 -f 15913//15913 15912//15912 15914//15914 -f 15913//15913 15914//15914 15915//15915 -f 15915//15915 15914//15914 15916//15916 -f 15915//15915 15916//15916 15917//15917 -f 15917//15917 15916//15916 15918//15918 -f 15917//15917 15918//15918 15919//15919 -f 15919//15919 15918//15918 15920//15920 -f 15919//15919 15920//15920 15921//15921 -f 15921//15921 15920//15920 15922//15922 -f 15921//15921 15922//15922 15923//15923 -f 15923//15923 15922//15922 15924//15924 -f 15923//15923 15924//15924 15925//15925 -f 15925//15925 15924//15924 15926//15926 -f 15925//15925 15926//15926 15927//15927 -f 15927//15927 15926//15926 15928//15928 -f 15927//15927 15928//15928 15929//15929 -f 15929//15929 15928//15928 15930//15930 -f 15929//15929 15930//15930 15931//15931 -f 15931//15931 15930//15930 15932//15932 -f 15931//15931 15932//15932 15933//15933 -f 15933//15933 15932//15932 15934//15934 -f 15933//15933 15934//15934 15935//15935 -f 15935//15935 15934//15934 15936//15936 -f 15935//15935 15936//15936 15937//15937 -f 15937//15937 15936//15936 15938//15938 -f 15937//15937 15938//15938 15939//15939 -f 15939//15939 15938//15938 15940//15940 -f 15939//15939 15940//15940 15941//15941 -f 15941//15941 15940//15940 15942//15942 -f 15941//15941 15942//15942 15943//15943 -f 15944//15944 15945//15945 15946//15946 -f 15944//15944 15946//15946 15947//15947 -f 15947//15947 15946//15946 15948//15948 -f 15947//15947 15948//15948 15949//15949 -f 15949//15949 15948//15948 15950//15950 -f 15949//15949 15950//15950 15951//15951 -f 15951//15951 15950//15950 15952//15952 -f 15951//15951 15952//15952 15953//15953 -f 15953//15953 15952//15952 15954//15954 -f 15953//15953 15954//15954 15955//15955 -f 15955//15955 15954//15954 15956//15956 -f 15955//15955 15956//15956 15957//15957 -f 15957//15957 15956//15956 15958//15958 -f 15957//15957 15958//15958 15959//15959 -f 15959//15959 15958//15958 15960//15960 -f 15959//15959 15960//15960 15961//15961 -f 15961//15961 15960//15960 15962//15962 -f 15961//15961 15962//15962 15963//15963 -f 15963//15963 15962//15962 15964//15964 -f 15963//15963 15964//15964 15965//15965 -f 15965//15965 15964//15964 15966//15966 -f 15965//15965 15966//15966 15967//15967 -f 15967//15967 15966//15966 15968//15968 -f 15967//15967 15968//15968 15969//15969 -f 15969//15969 15968//15968 15970//15970 -f 15969//15969 15970//15970 15971//15971 -f 15971//15971 15970//15970 15972//15972 -f 15971//15971 15972//15972 15973//15973 -f 15973//15973 15972//15972 15974//15974 -f 15973//15973 15974//15974 15975//15975 -f 15975//15975 15974//15974 15976//15976 -f 15975//15975 15976//15976 15977//15977 -f 15977//15977 15976//15976 15978//15978 -f 15977//15977 15978//15978 15979//15979 -f 15862//15862 15863//15863 15980//15980 -f 15980//15980 15863//15863 15981//15981 -f 15980//15980 15981//15981 15982//15982 -f 15982//15982 15981//15981 15983//15983 -f 15982//15982 15983//15983 15984//15984 -f 15984//15984 15983//15983 15985//15985 -f 15984//15984 15985//15985 15986//15986 -f 15986//15986 15985//15985 15987//15987 -f 15986//15986 15987//15987 15988//15988 -f 15988//15988 15987//15987 15989//15989 -f 15988//15988 15989//15989 15990//15990 -f 15990//15990 15989//15989 15991//15991 -f 15990//15990 15991//15991 15992//15992 -f 15992//15992 15991//15991 15993//15993 -f 15992//15992 15993//15993 15994//15994 -f 15994//15994 15993//15993 15995//15995 -f 15994//15994 15995//15995 15996//15996 -f 15996//15996 15995//15995 15997//15997 -f 15996//15996 15997//15997 15998//15998 -f 15998//15998 15997//15997 15999//15999 -f 15998//15998 15999//15999 16000//16000 -f 16000//16000 15999//15999 16001//16001 -f 16000//16000 16001//16001 16002//16002 -f 16002//16002 16001//16001 16003//16003 -f 16002//16002 16003//16003 16004//16004 -f 16004//16004 16003//16003 16005//16005 -f 16004//16004 16005//16005 15834//15834 -f 15834//15834 16005//16005 15835//15835 -f 15844//15844 16006//16006 15842//15842 -f 15842//15842 16006//16006 16007//16007 -f 15842//15842 16007//16007 15840//15840 -f 15840//15840 16007//16007 16008//16008 -f 15840//15840 16008//16008 15838//15838 -f 15848//15848 16009//16009 15846//15846 -f 15846//15846 16009//16009 16010//16010 -f 15846//15846 16010//16010 15844//15844 -f 15844//15844 16010//16010 16011//16011 -f 15844//15844 16011//16011 16006//16006 -f 15988//15988 15876//15876 15986//15986 -f 15986//15986 15876//15876 15874//15874 -f 15986//15986 15874//15874 15984//15984 -f 15984//15984 15874//15874 15872//15872 -f 15984//15984 15872//15872 15982//15982 -f 15872//15872 15870//15870 15982//15982 -f 15982//15982 15870//15870 15868//15868 -f 15982//15982 15868//15868 15980//15980 -f 15980//15980 15868//15868 15866//15866 -f 15980//15980 15866//15866 15862//15862 -f 15862//15862 15866//15866 15865//15865 -f 15862//15862 15865//15865 15860//15860 -f 15992//15992 15882//15882 15990//15990 -f 15990//15990 15882//15882 15880//15880 -f 15990//15990 15880//15880 15988//15988 -f 15988//15988 15880//15880 15878//15878 -f 15988//15988 15878//15878 15876//15876 -f 15854//15854 16012//16012 15852//15852 -f 15852//15852 16012//16012 16013//16013 -f 15852//15852 16013//16013 15850//15850 -f 15850//15850 16013//16013 16014//16014 -f 15850//15850 16014//16014 15848//15848 -f 15848//15848 16014//16014 16015//16015 -f 15848//15848 16015//16015 16009//16009 -f 16008//16008 16016//16016 15838//15838 -f 15838//15838 16016//16016 16017//16017 -f 15838//15838 16017//16017 15836//15836 -f 15836//15836 16017//16017 16018//16018 -f 15836//15836 16018//16018 15834//15834 -f 15834//15834 16018//16018 15902//15902 -f 15834//15834 15902//15902 16004//16004 -f 15865//15865 16019//16019 15860//15860 -f 15860//15860 16019//16019 16020//16020 -f 15860//15860 16020//16020 15858//15858 -f 15858//15858 16020//16020 16021//16021 -f 15858//15858 16021//16021 15856//15856 -f 15856//15856 16021//16021 16022//16022 -f 15856//15856 16022//16022 15854//15854 -f 15854//15854 16022//16022 16023//16023 -f 15854//15854 16023//16023 16012//16012 -f 15998//15998 15890//15890 15996//15996 -f 15996//15996 15890//15890 15888//15888 -f 15996//15996 15888//15888 15994//15994 -f 15994//15994 15888//15888 15886//15886 -f 15994//15994 15886//15886 15992//15992 -f 15992//15992 15886//15886 15884//15884 -f 15992//15992 15884//15884 15882//15882 -f 15902//15902 15900//15900 16004//16004 -f 16004//16004 15900//15900 15898//15898 -f 16004//16004 15898//15898 16002//16002 -f 16002//16002 15898//15898 15896//15896 -f 16002//16002 15896//15896 16000//16000 -f 16000//16000 15896//15896 15894//15894 -f 16000//16000 15894//15894 15998//15998 -f 15998//15998 15894//15894 15892//15892 -f 15998//15998 15892//15892 15890//15890 -f 15981//15981 15909//15909 15983//15983 -f 15983//15983 15909//15909 15911//15911 -f 15983//15983 15911//15911 15985//15985 -f 15985//15985 15911//15911 15913//15913 -f 15985//15985 15913//15913 15987//15987 -f 15913//15913 15915//15915 15987//15987 -f 15987//15987 15915//15915 15917//15917 -f 15987//15987 15917//15917 15989//15989 -f 15989//15989 15917//15917 15919//15919 -f 15989//15989 15919//15919 15991//15991 -f 15843//15843 16024//16024 15845//15845 -f 15845//15845 16024//16024 16025//16025 -f 15845//15845 16025//16025 15847//15847 -f 15837//15837 16026//16026 15839//15839 -f 15839//15839 16026//16026 16027//16027 -f 15839//15839 16027//16027 15841//15841 -f 15841//15841 16027//16027 16028//16028 -f 15841//15841 16028//16028 15843//15843 -f 15843//15843 16028//16028 16029//16029 -f 15843//15843 16029//16029 16024//16024 -f 16003//16003 15939//15939 16005//16005 -f 16005//16005 15939//15939 15941//15941 -f 16005//16005 15941//15941 15835//15835 -f 15835//15835 15941//15941 15943//15943 -f 15835//15835 15943//15943 15837//15837 -f 15837//15837 15943//15943 16030//16030 -f 15837//15837 16030//16030 16026//16026 -f 15997//15997 15931//15931 15999//15999 -f 15999//15999 15931//15931 15933//15933 -f 15999//15999 15933//15933 16001//16001 -f 16001//16001 15933//15933 15935//15935 -f 16001//16001 15935//15935 16003//16003 -f 16003//16003 15935//15935 15937//15937 -f 16003//16003 15937//15937 15939//15939 -f 15919//15919 15921//15921 15991//15991 -f 15991//15991 15921//15921 15923//15923 -f 15991//15991 15923//15923 15993//15993 -f 15993//15993 15923//15923 15925//15925 -f 15993//15993 15925//15925 15995//15995 -f 15995//15995 15925//15925 15927//15927 -f 15995//15995 15927//15927 15997//15997 -f 15997//15997 15927//15927 15929//15929 -f 15997//15997 15929//15929 15931//15931 -f 15859//15859 16031//16031 15861//15861 -f 15861//15861 16031//16031 16032//16032 -f 15861//15861 16032//16032 15863//15863 -f 15863//15863 16032//16032 15904//15904 -f 15863//15863 15904//15904 15981//15981 -f 15981//15981 15904//15904 15907//15907 -f 15981//15981 15907//15907 15909//15909 -f 15853//15853 16033//16033 15855//15855 -f 15855//15855 16033//16033 16034//16034 -f 15855//15855 16034//16034 15857//15857 -f 15857//15857 16034//16034 16035//16035 -f 15857//15857 16035//16035 15859//15859 -f 15859//15859 16035//16035 16036//16036 -f 15859//15859 16036//16036 16031//16031 -f 16025//16025 16037//16037 15847//15847 -f 15847//15847 16037//16037 16038//16038 -f 15847//15847 16038//16038 15849//15849 -f 15849//15849 16038//16038 16039//16039 -f 15849//15849 16039//16039 15851//15851 -f 15851//15851 16039//16039 16040//16040 -f 15851//15851 16040//16040 15853//15853 -f 15853//15853 16040//16040 16041//16041 -f 15853//15853 16041//16041 16033//16033 -f 15903//15903 15902//15902 16018//16018 -f 15903//15903 16018//16018 16042//16042 -f 16042//16042 16018//16018 16017//16017 -f 16042//16042 16017//16017 16043//16043 -f 16043//16043 16017//16017 16016//16016 -f 16043//16043 16016//16016 16044//16044 -f 16044//16044 16016//16016 16008//16008 -f 16044//16044 16008//16008 16045//16045 -f 16045//16045 16008//16008 16007//16007 -f 16045//16045 16007//16007 16046//16046 -f 16046//16046 16007//16007 16006//16006 -f 16046//16046 16006//16006 16047//16047 -f 16047//16047 16006//16006 16011//16011 -f 16047//16047 16011//16011 16048//16048 -f 16048//16048 16011//16011 16010//16010 -f 16048//16048 16010//16010 16049//16049 -f 16049//16049 16010//16010 16009//16009 -f 16049//16049 16009//16009 16050//16050 -f 16050//16050 16009//16009 16015//16015 -f 16050//16050 16015//16015 16051//16051 -f 16051//16051 16015//16015 16014//16014 -f 16051//16051 16014//16014 16052//16052 -f 16052//16052 16014//16014 16013//16013 -f 16052//16052 16013//16013 16053//16053 -f 16053//16053 16013//16013 16012//16012 -f 16053//16053 16012//16012 16054//16054 -f 16054//16054 16012//16012 16023//16023 -f 16054//16054 16023//16023 16055//16055 -f 16055//16055 16023//16023 16022//16022 -f 16055//16055 16022//16022 16056//16056 -f 16056//16056 16022//16022 16021//16021 -f 16056//16056 16021//16021 16057//16057 -f 16057//16057 16021//16021 16020//16020 -f 16057//16057 16020//16020 16058//16058 -f 16058//16058 16020//16020 16019//16019 -f 16058//16058 16019//16019 16059//16059 -f 16059//16059 16019//16019 15865//15865 -f 16059//16059 15865//15865 15864//15864 -f 15943//15943 15942//15942 16060//16060 -f 15943//15943 16060//16060 16030//16030 -f 16030//16030 16060//16060 16061//16061 -f 16030//16030 16061//16061 16026//16026 -f 16026//16026 16061//16061 16062//16062 -f 16026//16026 16062//16062 16027//16027 -f 16027//16027 16062//16062 16063//16063 -f 16027//16027 16063//16063 16028//16028 -f 16028//16028 16063//16063 16064//16064 -f 16028//16028 16064//16064 16029//16029 -f 16029//16029 16064//16064 16065//16065 -f 16029//16029 16065//16065 16024//16024 -f 16024//16024 16065//16065 16066//16066 -f 16024//16024 16066//16066 16025//16025 -f 16025//16025 16066//16066 16067//16067 -f 16025//16025 16067//16067 16037//16037 -f 16037//16037 16067//16067 16068//16068 -f 16037//16037 16068//16068 16038//16038 -f 16038//16038 16068//16068 16069//16069 -f 16038//16038 16069//16069 16039//16039 -f 16039//16039 16069//16069 16070//16070 -f 16039//16039 16070//16070 16040//16040 -f 16040//16040 16070//16070 16071//16071 -f 16040//16040 16071//16071 16041//16041 -f 16041//16041 16071//16071 16072//16072 -f 16041//16041 16072//16072 16033//16033 -f 16033//16033 16072//16072 16073//16073 -f 16033//16033 16073//16073 16034//16034 -f 16034//16034 16073//16073 16074//16074 -f 16034//16034 16074//16074 16035//16035 -f 16035//16035 16074//16074 16075//16075 -f 16035//16035 16075//16075 16036//16036 -f 16036//16036 16075//16075 16076//16076 -f 16036//16036 16076//16076 16031//16031 -f 16031//16031 16076//16076 16077//16077 -f 16031//16031 16077//16077 16032//16032 -f 16032//16032 16077//16077 15905//15905 -f 16032//16032 15905//15905 15904//15904 -f 16078//16078 16056//16056 16079//16079 -f 16079//16079 16056//16056 16057//16057 -f 16079//16079 16057//16057 16080//16080 -f 16080//16080 16057//16057 16058//16058 -f 16080//16080 16058//16058 16081//16081 -f 16081//16081 16058//16058 16059//16059 -f 16081//16081 16059//16059 15945//15945 -f 15945//15945 16059//16059 15864//15864 -f 15945//15945 15864//15864 15946//15946 -f 15946//15946 15864//15864 15867//15867 -f 15946//15946 15867//15867 15948//15948 -f 15948//15948 15867//15867 15869//15869 -f 15948//15948 15869//15869 15950//15950 -f 15950//15950 15869//15869 15871//15871 -f 15950//15950 15871//15871 15952//15952 -f 15970//15970 15895//15895 15972//15972 -f 15972//15972 15895//15895 15897//15897 -f 15972//15972 15897//15897 15974//15974 -f 15974//15974 15897//15897 15899//15899 -f 15974//15974 15899//15899 15976//15976 -f 15976//15976 15899//15899 15901//15901 -f 15976//15976 15901//15901 15978//15978 -f 15978//15978 15901//15901 15903//15903 -f 15978//15978 15903//15903 16082//16082 -f 16082//16082 15903//15903 16042//16042 -f 16082//16082 16042//16042 16083//16083 -f 16083//16083 16042//16042 16043//16043 -f 16083//16083 16043//16043 16084//16084 -f 16084//16084 16043//16043 16044//16044 -f 16084//16084 16044//16044 16085//16085 -f 16044//16044 16045//16045 16085//16085 -f 16085//16085 16045//16045 16046//16046 -f 16085//16085 16046//16046 16086//16086 -f 16086//16086 16046//16046 16047//16047 -f 16086//16086 16047//16047 16087//16087 -f 16087//16087 16047//16047 16048//16048 -f 16087//16087 16048//16048 16088//16088 -f 16088//16088 16048//16048 16049//16049 -f 16088//16088 16049//16049 16089//16089 -f 16089//16089 16049//16049 16050//16050 -f 16089//16089 16050//16050 16090//16090 -f 16090//16090 16050//16050 16051//16051 -f 16090//16090 16051//16051 16091//16091 -f 16091//16091 16051//16051 16052//16052 -f 16091//16091 16052//16052 16092//16092 -f 16092//16092 16052//16052 16053//16053 -f 16092//16092 16053//16053 16093//16093 -f 16093//16093 16053//16053 16054//16054 -f 16093//16093 16054//16054 16078//16078 -f 16078//16078 16054//16054 16055//16055 -f 16078//16078 16055//16055 16056//16056 -f 15871//15871 15873//15873 15952//15952 -f 15952//15952 15873//15873 15875//15875 -f 15952//15952 15875//15875 15954//15954 -f 15954//15954 15875//15875 15877//15877 -f 15954//15954 15877//15877 15956//15956 -f 15956//15956 15877//15877 15879//15879 -f 15956//15956 15879//15879 15958//15958 -f 15958//15958 15879//15879 15881//15881 -f 15958//15958 15881//15881 15960//15960 -f 15960//15960 15881//15881 15883//15883 -f 15960//15960 15883//15883 15962//15962 -f 15962//15962 15883//15883 15885//15885 -f 15962//15962 15885//15885 15964//15964 -f 15964//15964 15885//15885 15887//15887 -f 15964//15964 15887//15887 15966//15966 -f 15966//15966 15887//15887 15889//15889 -f 15966//15966 15889//15889 15968//15968 -f 15968//15968 15889//15889 15891//15891 -f 15968//15968 15891//15891 15970//15970 -f 15970//15970 15891//15891 15893//15893 -f 15970//15970 15893//15893 15895//15895 -f 16094//16094 16063//16063 16095//16095 -f 16095//16095 16063//16063 16062//16062 -f 16095//16095 16062//16062 16096//16096 -f 16096//16096 16062//16062 16061//16061 -f 16096//16096 16061//16061 16097//16097 -f 16097//16097 16061//16061 16060//16060 -f 16097//16097 16060//16060 15979//15979 -f 15979//15979 16060//16060 15942//15942 -f 15979//15979 15942//15942 15977//15977 -f 15977//15977 15942//15942 15940//15940 -f 15977//15977 15940//15940 15975//15975 -f 15975//15975 15940//15940 15938//15938 -f 15975//15975 15938//15938 15973//15973 -f 15973//15973 15938//15938 15936//15936 -f 15973//15973 15936//15936 15971//15971 -f 16098//16098 16073//16073 16099//16099 -f 16099//16099 16073//16073 16072//16072 -f 16099//16099 16072//16072 16100//16100 -f 16100//16100 16072//16072 16071//16071 -f 16100//16100 16071//16071 16101//16101 -f 16101//16101 16071//16071 16070//16070 -f 16101//16101 16070//16070 16102//16102 -f 16102//16102 16070//16070 16069//16069 -f 16102//16102 16069//16069 16103//16103 -f 16103//16103 16069//16069 16068//16068 -f 16103//16103 16068//16068 16104//16104 -f 16104//16104 16068//16068 16067//16067 -f 16104//16104 16067//16067 16105//16105 -f 16105//16105 16067//16067 16066//16066 -f 16105//16105 16066//16066 16106//16106 -f 16106//16106 16066//16066 16065//16065 -f 16106//16106 16065//16065 16094//16094 -f 16094//16094 16065//16065 16064//16064 -f 16094//16094 16064//16064 16063//16063 -f 15953//15953 15912//15912 15951//15951 -f 15951//15951 15912//15912 15910//15910 -f 15951//15951 15910//15910 15949//15949 -f 15949//15949 15910//15910 15908//15908 -f 15949//15949 15908//15908 15947//15947 -f 15947//15947 15908//15908 15906//15906 -f 15947//15947 15906//15906 15944//15944 -f 15944//15944 15906//15906 15905//15905 -f 15944//15944 15905//15905 16107//16107 -f 16107//16107 15905//15905 16077//16077 -f 16107//16107 16077//16077 16108//16108 -f 16108//16108 16077//16077 16076//16076 -f 16108//16108 16076//16076 16109//16109 -f 16109//16109 16076//16076 16075//16075 -f 16109//16109 16075//16075 16098//16098 -f 16098//16098 16075//16075 16074//16074 -f 16098//16098 16074//16074 16073//16073 -f 15936//15936 15934//15934 15971//15971 -f 15971//15971 15934//15934 15932//15932 -f 15971//15971 15932//15932 15969//15969 -f 15969//15969 15932//15932 15930//15930 -f 15969//15969 15930//15930 15967//15967 -f 15967//15967 15930//15930 15928//15928 -f 15967//15967 15928//15928 15965//15965 -f 15965//15965 15928//15928 15926//15926 -f 15965//15965 15926//15926 15963//15963 -f 15963//15963 15926//15926 15924//15924 -f 15963//15963 15924//15924 15961//15961 -f 15961//15961 15924//15924 15922//15922 -f 15961//15961 15922//15922 15959//15959 -f 15959//15959 15922//15922 15920//15920 -f 15959//15959 15920//15920 15957//15957 -f 15957//15957 15920//15920 15918//15918 -f 15957//15957 15918//15918 15955//15955 -f 15955//15955 15918//15918 15916//15916 -f 15955//15955 15916//15916 15953//15953 -f 15953//15953 15916//15916 15914//15914 -f 15953//15953 15914//15914 15912//15912 -f 15979//15979 15978//15978 16082//16082 -f 15979//15979 16082//16082 16097//16097 -f 16097//16097 16082//16082 16083//16083 -f 16097//16097 16083//16083 16096//16096 -f 16096//16096 16083//16083 16084//16084 -f 16096//16096 16084//16084 16095//16095 -f 16095//16095 16084//16084 16085//16085 -f 16095//16095 16085//16085 16094//16094 -f 16094//16094 16085//16085 16086//16086 -f 16094//16094 16086//16086 16106//16106 -f 16106//16106 16086//16086 16087//16087 -f 16106//16106 16087//16087 16105//16105 -f 16105//16105 16087//16087 16088//16088 -f 16105//16105 16088//16088 16104//16104 -f 16104//16104 16088//16088 16089//16089 -f 16104//16104 16089//16089 16103//16103 -f 16103//16103 16089//16089 16090//16090 -f 16103//16103 16090//16090 16102//16102 -f 16102//16102 16090//16090 16091//16091 -f 16102//16102 16091//16091 16101//16101 -f 16101//16101 16091//16091 16092//16092 -f 16101//16101 16092//16092 16100//16100 -f 16100//16100 16092//16092 16093//16093 -f 16100//16100 16093//16093 16099//16099 -f 16099//16099 16093//16093 16078//16078 -f 16099//16099 16078//16078 16098//16098 -f 16098//16098 16078//16078 16079//16079 -f 16098//16098 16079//16079 16109//16109 -f 16109//16109 16079//16079 16080//16080 -f 16109//16109 16080//16080 16108//16108 -f 16108//16108 16080//16080 16081//16081 -f 16108//16108 16081//16081 16107//16107 -f 16107//16107 16081//16081 15945//15945 -f 16107//16107 15945//15945 15944//15944 -f 16110//16110 16111//16111 16112//16112 -f 16112//16112 16111//16111 16113//16113 -f 16112//16112 16113//16113 16114//16114 -f 16114//16114 16113//16113 16115//16115 -f 16114//16114 16115//16115 16116//16116 -f 16116//16116 16115//16115 16117//16117 -f 16116//16116 16117//16117 16118//16118 -f 16118//16118 16117//16117 16119//16119 -f 16118//16118 16119//16119 16120//16120 -f 16120//16120 16119//16119 16121//16121 -f 16120//16120 16121//16121 16122//16122 -f 16122//16122 16121//16121 16123//16123 -f 16122//16122 16123//16123 16124//16124 -f 16124//16124 16123//16123 16125//16125 -f 16124//16124 16125//16125 16126//16126 -f 16126//16126 16125//16125 16127//16127 -f 16126//16126 16127//16127 16128//16128 -f 16128//16128 16127//16127 16129//16129 -f 16128//16128 16129//16129 16130//16130 -f 16130//16130 16129//16129 16131//16131 -f 16130//16130 16131//16131 16132//16132 -f 16132//16132 16131//16131 16133//16133 -f 16132//16132 16133//16133 16134//16134 -f 16134//16134 16133//16133 16135//16135 -f 16134//16134 16135//16135 16136//16136 -f 16136//16136 16135//16135 16137//16137 -f 16136//16136 16137//16137 16138//16138 -f 16138//16138 16137//16137 16139//16139 -f 16140//16140 16141//16141 16142//16142 -f 16140//16140 16142//16142 16143//16143 -f 16143//16143 16142//16142 16144//16144 -f 16143//16143 16144//16144 16145//16145 -f 16145//16145 16144//16144 16146//16146 -f 16145//16145 16146//16146 16147//16147 -f 16147//16147 16146//16146 16148//16148 -f 16147//16147 16148//16148 16149//16149 -f 16149//16149 16148//16148 16150//16150 -f 16149//16149 16150//16150 16151//16151 -f 16151//16151 16150//16150 16152//16152 -f 16151//16151 16152//16152 16153//16153 -f 16153//16153 16152//16152 16154//16154 -f 16153//16153 16154//16154 16155//16155 -f 16155//16155 16154//16154 16156//16156 -f 16155//16155 16156//16156 16157//16157 -f 16157//16157 16156//16156 16158//16158 -f 16157//16157 16158//16158 16159//16159 -f 16159//16159 16158//16158 16160//16160 -f 16159//16159 16160//16160 16161//16161 -f 16161//16161 16160//16160 16162//16162 -f 16161//16161 16162//16162 16163//16163 -f 16163//16163 16162//16162 16164//16164 -f 16163//16163 16164//16164 16165//16165 -f 16165//16165 16164//16164 16166//16166 -f 16165//16165 16166//16166 16167//16167 -f 16167//16167 16166//16166 16168//16168 -f 16167//16167 16168//16168 16169//16169 -f 16169//16169 16168//16168 16170//16170 -f 16169//16169 16170//16170 16171//16171 -f 16171//16171 16170//16170 16172//16172 -f 16171//16171 16172//16172 16173//16173 -f 16173//16173 16172//16172 16174//16174 -f 16173//16173 16174//16174 16175//16175 -f 16175//16175 16174//16174 16176//16176 -f 16175//16175 16176//16176 16177//16177 -f 16177//16177 16176//16176 16178//16178 -f 16177//16177 16178//16178 16179//16179 -f 16180//16180 16181//16181 16182//16182 -f 16180//16180 16182//16182 16183//16183 -f 16183//16183 16182//16182 16184//16184 -f 16183//16183 16184//16184 16185//16185 -f 16185//16185 16184//16184 16186//16186 -f 16185//16185 16186//16186 16187//16187 -f 16187//16187 16186//16186 16188//16188 -f 16187//16187 16188//16188 16189//16189 -f 16189//16189 16188//16188 16190//16190 -f 16189//16189 16190//16190 16191//16191 -f 16191//16191 16190//16190 16192//16192 -f 16191//16191 16192//16192 16193//16193 -f 16193//16193 16192//16192 16194//16194 -f 16193//16193 16194//16194 16195//16195 -f 16195//16195 16194//16194 16196//16196 -f 16195//16195 16196//16196 16197//16197 -f 16197//16197 16196//16196 16198//16198 -f 16197//16197 16198//16198 16199//16199 -f 16199//16199 16198//16198 16200//16200 -f 16199//16199 16200//16200 16201//16201 -f 16201//16201 16200//16200 16202//16202 -f 16201//16201 16202//16202 16203//16203 -f 16203//16203 16202//16202 16204//16204 -f 16203//16203 16204//16204 16205//16205 -f 16205//16205 16204//16204 16206//16206 -f 16205//16205 16206//16206 16207//16207 -f 16207//16207 16206//16206 16208//16208 -f 16207//16207 16208//16208 16209//16209 -f 16209//16209 16208//16208 16210//16210 -f 16209//16209 16210//16210 16211//16211 -f 16211//16211 16210//16210 16212//16212 -f 16211//16211 16212//16212 16213//16213 -f 16213//16213 16212//16212 16214//16214 -f 16213//16213 16214//16214 16215//16215 -f 16215//16215 16214//16214 16216//16216 -f 16215//16215 16216//16216 16217//16217 -f 16217//16217 16216//16216 16218//16218 -f 16217//16217 16218//16218 16219//16219 -f 16220//16220 16221//16221 16222//16222 -f 16220//16220 16222//16222 16223//16223 -f 16223//16223 16222//16222 16224//16224 -f 16223//16223 16224//16224 16225//16225 -f 16225//16225 16224//16224 16226//16226 -f 16225//16225 16226//16226 16227//16227 -f 16227//16227 16226//16226 16228//16228 -f 16227//16227 16228//16228 16229//16229 -f 16229//16229 16228//16228 16230//16230 -f 16229//16229 16230//16230 16231//16231 -f 16231//16231 16230//16230 16232//16232 -f 16231//16231 16232//16232 16233//16233 -f 16233//16233 16232//16232 16234//16234 -f 16233//16233 16234//16234 16235//16235 -f 16235//16235 16234//16234 16236//16236 -f 16235//16235 16236//16236 16237//16237 -f 16237//16237 16236//16236 16238//16238 -f 16237//16237 16238//16238 16239//16239 -f 16239//16239 16238//16238 16240//16240 -f 16239//16239 16240//16240 16241//16241 -f 16241//16241 16240//16240 16242//16242 -f 16241//16241 16242//16242 16243//16243 -f 16243//16243 16242//16242 16244//16244 -f 16243//16243 16244//16244 16245//16245 -f 16245//16245 16244//16244 16246//16246 -f 16245//16245 16246//16246 16247//16247 -f 16247//16247 16246//16246 16248//16248 -f 16247//16247 16248//16248 16249//16249 -f 16249//16249 16248//16248 16250//16250 -f 16249//16249 16250//16250 16251//16251 -f 16251//16251 16250//16250 16252//16252 -f 16251//16251 16252//16252 16253//16253 -f 16253//16253 16252//16252 16254//16254 -f 16253//16253 16254//16254 16255//16255 -f 16138//16138 16139//16139 16256//16256 -f 16256//16256 16139//16139 16257//16257 -f 16256//16256 16257//16257 16258//16258 -f 16258//16258 16257//16257 16259//16259 -f 16258//16258 16259//16259 16260//16260 -f 16260//16260 16259//16259 16261//16261 -f 16260//16260 16261//16261 16262//16262 -f 16262//16262 16261//16261 16263//16263 -f 16262//16262 16263//16263 16264//16264 -f 16264//16264 16263//16263 16265//16265 -f 16264//16264 16265//16265 16266//16266 -f 16266//16266 16265//16265 16267//16267 -f 16266//16266 16267//16267 16268//16268 -f 16268//16268 16267//16267 16269//16269 -f 16268//16268 16269//16269 16270//16270 -f 16270//16270 16269//16269 16271//16271 -f 16270//16270 16271//16271 16272//16272 -f 16272//16272 16271//16271 16273//16273 -f 16272//16272 16273//16273 16274//16274 -f 16274//16274 16273//16273 16275//16275 -f 16274//16274 16275//16275 16276//16276 -f 16276//16276 16275//16275 16277//16277 -f 16276//16276 16277//16277 16278//16278 -f 16278//16278 16277//16277 16279//16279 -f 16278//16278 16279//16279 16280//16280 -f 16280//16280 16279//16279 16281//16281 -f 16280//16280 16281//16281 16110//16110 -f 16110//16110 16281//16281 16111//16111 -f 16120//16120 16282//16282 16118//16118 -f 16118//16118 16282//16282 16283//16283 -f 16118//16118 16283//16283 16116//16116 -f 16116//16116 16283//16283 16284//16284 -f 16116//16116 16284//16284 16114//16114 -f 16124//16124 16285//16285 16122//16122 -f 16122//16122 16285//16285 16286//16286 -f 16122//16122 16286//16286 16120//16120 -f 16120//16120 16286//16286 16287//16287 -f 16120//16120 16287//16287 16282//16282 -f 16258//16258 16144//16144 16256//16256 -f 16256//16256 16144//16144 16142//16142 -f 16256//16256 16142//16142 16138//16138 -f 16138//16138 16142//16142 16141//16141 -f 16138//16138 16141//16141 16136//16136 -f 16264//16264 16152//16152 16262//16262 -f 16262//16262 16152//16152 16150//16150 -f 16262//16262 16150//16150 16260//16260 -f 16260//16260 16150//16150 16148//16148 -f 16260//16260 16148//16148 16258//16258 -f 16258//16258 16148//16148 16146//16146 -f 16258//16258 16146//16146 16144//16144 -f 16268//16268 16158//16158 16266//16266 -f 16266//16266 16158//16158 16156//16156 -f 16266//16266 16156//16156 16264//16264 -f 16264//16264 16156//16156 16154//16154 -f 16264//16264 16154//16154 16152//16152 -f 16130//16130 16288//16288 16128//16128 -f 16128//16128 16288//16288 16289//16289 -f 16128//16128 16289//16289 16126//16126 -f 16126//16126 16289//16289 16290//16290 -f 16126//16126 16290//16290 16124//16124 -f 16124//16124 16290//16290 16291//16291 -f 16124//16124 16291//16291 16285//16285 -f 16284//16284 16292//16292 16114//16114 -f 16114//16114 16292//16292 16293//16293 -f 16114//16114 16293//16293 16112//16112 -f 16112//16112 16293//16293 16294//16294 -f 16112//16112 16294//16294 16110//16110 -f 16110//16110 16294//16294 16178//16178 -f 16110//16110 16178//16178 16280//16280 -f 16141//16141 16295//16295 16136//16136 -f 16136//16136 16295//16295 16296//16296 -f 16136//16136 16296//16296 16134//16134 -f 16134//16134 16296//16296 16297//16297 -f 16134//16134 16297//16297 16132//16132 -f 16132//16132 16297//16297 16298//16298 -f 16132//16132 16298//16298 16130//16130 -f 16130//16130 16298//16298 16299//16299 -f 16130//16130 16299//16299 16288//16288 -f 16274//16274 16166//16166 16272//16272 -f 16272//16272 16166//16166 16164//16164 -f 16272//16272 16164//16164 16270//16270 -f 16270//16270 16164//16164 16162//16162 -f 16270//16270 16162//16162 16268//16268 -f 16268//16268 16162//16162 16160//16160 -f 16268//16268 16160//16160 16158//16158 -f 16178//16178 16176//16176 16280//16280 -f 16280//16280 16176//16176 16174//16174 -f 16280//16280 16174//16174 16278//16278 -f 16278//16278 16174//16174 16172//16172 -f 16278//16278 16172//16172 16276//16276 -f 16276//16276 16172//16172 16170//16170 -f 16276//16276 16170//16170 16274//16274 -f 16274//16274 16170//16170 16168//16168 -f 16274//16274 16168//16168 16166//16166 -f 16257//16257 16185//16185 16259//16259 -f 16259//16259 16185//16185 16187//16187 -f 16259//16259 16187//16187 16261//16261 -f 16261//16261 16187//16187 16189//16189 -f 16261//16261 16189//16189 16263//16263 -f 16189//16189 16191//16191 16263//16263 -f 16263//16263 16191//16191 16193//16193 -f 16263//16263 16193//16193 16265//16265 -f 16265//16265 16193//16193 16195//16195 -f 16265//16265 16195//16195 16267//16267 -f 16119//16119 16300//16300 16121//16121 -f 16121//16121 16300//16300 16301//16301 -f 16121//16121 16301//16301 16123//16123 -f 16113//16113 16302//16302 16115//16115 -f 16115//16115 16302//16302 16303//16303 -f 16115//16115 16303//16303 16117//16117 -f 16117//16117 16303//16303 16304//16304 -f 16117//16117 16304//16304 16119//16119 -f 16119//16119 16304//16304 16305//16305 -f 16119//16119 16305//16305 16300//16300 -f 16279//16279 16215//16215 16281//16281 -f 16281//16281 16215//16215 16217//16217 -f 16281//16281 16217//16217 16111//16111 -f 16111//16111 16217//16217 16219//16219 -f 16111//16111 16219//16219 16113//16113 -f 16113//16113 16219//16219 16306//16306 -f 16113//16113 16306//16306 16302//16302 -f 16273//16273 16207//16207 16275//16275 -f 16275//16275 16207//16207 16209//16209 -f 16275//16275 16209//16209 16277//16277 -f 16277//16277 16209//16209 16211//16211 -f 16277//16277 16211//16211 16279//16279 -f 16279//16279 16211//16211 16213//16213 -f 16279//16279 16213//16213 16215//16215 -f 16195//16195 16197//16197 16267//16267 -f 16267//16267 16197//16197 16199//16199 -f 16267//16267 16199//16199 16269//16269 -f 16269//16269 16199//16199 16201//16201 -f 16269//16269 16201//16201 16271//16271 -f 16271//16271 16201//16201 16203//16203 -f 16271//16271 16203//16203 16273//16273 -f 16273//16273 16203//16203 16205//16205 -f 16273//16273 16205//16205 16207//16207 -f 16135//16135 16307//16307 16137//16137 -f 16137//16137 16307//16307 16308//16308 -f 16137//16137 16308//16308 16139//16139 -f 16139//16139 16308//16308 16180//16180 -f 16139//16139 16180//16180 16257//16257 -f 16257//16257 16180//16180 16183//16183 -f 16257//16257 16183//16183 16185//16185 -f 16129//16129 16309//16309 16131//16131 -f 16131//16131 16309//16309 16310//16310 -f 16131//16131 16310//16310 16133//16133 -f 16133//16133 16310//16310 16311//16311 -f 16133//16133 16311//16311 16135//16135 -f 16135//16135 16311//16311 16312//16312 -f 16135//16135 16312//16312 16307//16307 -f 16301//16301 16313//16313 16123//16123 -f 16123//16123 16313//16313 16314//16314 -f 16123//16123 16314//16314 16125//16125 -f 16125//16125 16314//16314 16315//16315 -f 16125//16125 16315//16315 16127//16127 -f 16127//16127 16315//16315 16316//16316 -f 16127//16127 16316//16316 16129//16129 -f 16129//16129 16316//16316 16317//16317 -f 16129//16129 16317//16317 16309//16309 -f 16179//16179 16178//16178 16294//16294 -f 16179//16179 16294//16294 16318//16318 -f 16318//16318 16294//16294 16293//16293 -f 16318//16318 16293//16293 16319//16319 -f 16319//16319 16293//16293 16292//16292 -f 16319//16319 16292//16292 16320//16320 -f 16320//16320 16292//16292 16284//16284 -f 16320//16320 16284//16284 16321//16321 -f 16321//16321 16284//16284 16283//16283 -f 16321//16321 16283//16283 16322//16322 -f 16322//16322 16283//16283 16282//16282 -f 16322//16322 16282//16282 16323//16323 -f 16323//16323 16282//16282 16287//16287 -f 16323//16323 16287//16287 16324//16324 -f 16324//16324 16287//16287 16286//16286 -f 16324//16324 16286//16286 16325//16325 -f 16325//16325 16286//16286 16285//16285 -f 16325//16325 16285//16285 16326//16326 -f 16326//16326 16285//16285 16291//16291 -f 16326//16326 16291//16291 16327//16327 -f 16327//16327 16291//16291 16290//16290 -f 16327//16327 16290//16290 16328//16328 -f 16328//16328 16290//16290 16289//16289 -f 16328//16328 16289//16289 16329//16329 -f 16329//16329 16289//16289 16288//16288 -f 16329//16329 16288//16288 16330//16330 -f 16330//16330 16288//16288 16299//16299 -f 16330//16330 16299//16299 16331//16331 -f 16331//16331 16299//16299 16298//16298 -f 16331//16331 16298//16298 16332//16332 -f 16332//16332 16298//16298 16297//16297 -f 16332//16332 16297//16297 16333//16333 -f 16333//16333 16297//16297 16296//16296 -f 16333//16333 16296//16296 16334//16334 -f 16334//16334 16296//16296 16295//16295 -f 16334//16334 16295//16295 16335//16335 -f 16335//16335 16295//16295 16141//16141 -f 16335//16335 16141//16141 16140//16140 -f 16219//16219 16218//16218 16336//16336 -f 16219//16219 16336//16336 16306//16306 -f 16306//16306 16336//16336 16337//16337 -f 16306//16306 16337//16337 16302//16302 -f 16302//16302 16337//16337 16338//16338 -f 16302//16302 16338//16338 16303//16303 -f 16303//16303 16338//16338 16339//16339 -f 16303//16303 16339//16339 16304//16304 -f 16304//16304 16339//16339 16340//16340 -f 16304//16304 16340//16340 16305//16305 -f 16305//16305 16340//16340 16341//16341 -f 16305//16305 16341//16341 16300//16300 -f 16300//16300 16341//16341 16342//16342 -f 16300//16300 16342//16342 16301//16301 -f 16301//16301 16342//16342 16343//16343 -f 16301//16301 16343//16343 16313//16313 -f 16313//16313 16343//16343 16344//16344 -f 16313//16313 16344//16344 16314//16314 -f 16314//16314 16344//16344 16345//16345 -f 16314//16314 16345//16345 16315//16315 -f 16315//16315 16345//16345 16346//16346 -f 16315//16315 16346//16346 16316//16316 -f 16316//16316 16346//16346 16347//16347 -f 16316//16316 16347//16347 16317//16317 -f 16317//16317 16347//16347 16348//16348 -f 16317//16317 16348//16348 16309//16309 -f 16309//16309 16348//16348 16349//16349 -f 16309//16309 16349//16349 16310//16310 -f 16310//16310 16349//16349 16350//16350 -f 16310//16310 16350//16350 16311//16311 -f 16311//16311 16350//16350 16351//16351 -f 16311//16311 16351//16351 16312//16312 -f 16312//16312 16351//16351 16352//16352 -f 16312//16312 16352//16352 16307//16307 -f 16307//16307 16352//16352 16353//16353 -f 16307//16307 16353//16353 16308//16308 -f 16308//16308 16353//16353 16181//16181 -f 16308//16308 16181//16181 16180//16180 -f 16354//16354 16332//16332 16355//16355 -f 16355//16355 16332//16332 16333//16333 -f 16355//16355 16333//16333 16356//16356 -f 16356//16356 16333//16333 16334//16334 -f 16356//16356 16334//16334 16357//16357 -f 16357//16357 16334//16334 16335//16335 -f 16357//16357 16335//16335 16221//16221 -f 16221//16221 16335//16335 16140//16140 -f 16221//16221 16140//16140 16222//16222 -f 16222//16222 16140//16140 16143//16143 -f 16222//16222 16143//16143 16224//16224 -f 16224//16224 16143//16143 16145//16145 -f 16224//16224 16145//16145 16226//16226 -f 16226//16226 16145//16145 16147//16147 -f 16226//16226 16147//16147 16228//16228 -f 16246//16246 16171//16171 16248//16248 -f 16248//16248 16171//16171 16173//16173 -f 16248//16248 16173//16173 16250//16250 -f 16250//16250 16173//16173 16175//16175 -f 16250//16250 16175//16175 16252//16252 -f 16252//16252 16175//16175 16177//16177 -f 16252//16252 16177//16177 16254//16254 -f 16254//16254 16177//16177 16179//16179 -f 16254//16254 16179//16179 16358//16358 -f 16358//16358 16179//16179 16318//16318 -f 16358//16358 16318//16318 16359//16359 -f 16359//16359 16318//16318 16319//16319 -f 16359//16359 16319//16319 16360//16360 -f 16360//16360 16319//16319 16320//16320 -f 16360//16360 16320//16320 16361//16361 -f 16320//16320 16321//16321 16361//16361 -f 16361//16361 16321//16321 16322//16322 -f 16361//16361 16322//16322 16362//16362 -f 16362//16362 16322//16322 16323//16323 -f 16362//16362 16323//16323 16363//16363 -f 16363//16363 16323//16323 16324//16324 -f 16363//16363 16324//16324 16364//16364 -f 16364//16364 16324//16324 16325//16325 -f 16364//16364 16325//16325 16365//16365 -f 16365//16365 16325//16325 16326//16326 -f 16365//16365 16326//16326 16366//16366 -f 16366//16366 16326//16326 16327//16327 -f 16366//16366 16327//16327 16367//16367 -f 16367//16367 16327//16327 16328//16328 -f 16367//16367 16328//16328 16368//16368 -f 16368//16368 16328//16328 16329//16329 -f 16368//16368 16329//16329 16369//16369 -f 16369//16369 16329//16329 16330//16330 -f 16369//16369 16330//16330 16354//16354 -f 16354//16354 16330//16330 16331//16331 -f 16354//16354 16331//16331 16332//16332 -f 16147//16147 16149//16149 16228//16228 -f 16228//16228 16149//16149 16151//16151 -f 16228//16228 16151//16151 16230//16230 -f 16230//16230 16151//16151 16153//16153 -f 16230//16230 16153//16153 16232//16232 -f 16232//16232 16153//16153 16155//16155 -f 16232//16232 16155//16155 16234//16234 -f 16234//16234 16155//16155 16157//16157 -f 16234//16234 16157//16157 16236//16236 -f 16236//16236 16157//16157 16159//16159 -f 16236//16236 16159//16159 16238//16238 -f 16238//16238 16159//16159 16161//16161 -f 16238//16238 16161//16161 16240//16240 -f 16240//16240 16161//16161 16163//16163 -f 16240//16240 16163//16163 16242//16242 -f 16242//16242 16163//16163 16165//16165 -f 16242//16242 16165//16165 16244//16244 -f 16244//16244 16165//16165 16167//16167 -f 16244//16244 16167//16167 16246//16246 -f 16246//16246 16167//16167 16169//16169 -f 16246//16246 16169//16169 16171//16171 -f 16247//16247 16208//16208 16245//16245 -f 16245//16245 16208//16208 16206//16206 -f 16245//16245 16206//16206 16243//16243 -f 16243//16243 16206//16206 16204//16204 -f 16243//16243 16204//16204 16241//16241 -f 16241//16241 16204//16204 16202//16202 -f 16241//16241 16202//16202 16239//16239 -f 16239//16239 16202//16202 16200//16200 -f 16239//16239 16200//16200 16237//16237 -f 16237//16237 16200//16200 16198//16198 -f 16237//16237 16198//16198 16235//16235 -f 16235//16235 16198//16198 16196//16196 -f 16235//16235 16196//16196 16233//16233 -f 16233//16233 16196//16196 16194//16194 -f 16233//16233 16194//16194 16231//16231 -f 16231//16231 16194//16194 16192//16192 -f 16231//16231 16192//16192 16229//16229 -f 16370//16370 16339//16339 16371//16371 -f 16371//16371 16339//16339 16338//16338 -f 16371//16371 16338//16338 16372//16372 -f 16372//16372 16338//16338 16337//16337 -f 16372//16372 16337//16337 16373//16373 -f 16373//16373 16337//16337 16336//16336 -f 16373//16373 16336//16336 16255//16255 -f 16255//16255 16336//16336 16218//16218 -f 16255//16255 16218//16218 16253//16253 -f 16253//16253 16218//16218 16216//16216 -f 16253//16253 16216//16216 16251//16251 -f 16251//16251 16216//16216 16214//16214 -f 16251//16251 16214//16214 16249//16249 -f 16249//16249 16214//16214 16212//16212 -f 16249//16249 16212//16212 16247//16247 -f 16247//16247 16212//16212 16210//16210 -f 16247//16247 16210//16210 16208//16208 -f 16374//16374 16349//16349 16375//16375 -f 16375//16375 16349//16349 16348//16348 -f 16375//16375 16348//16348 16376//16376 -f 16376//16376 16348//16348 16347//16347 -f 16376//16376 16347//16347 16377//16377 -f 16377//16377 16347//16347 16346//16346 -f 16377//16377 16346//16346 16378//16378 -f 16378//16378 16346//16346 16345//16345 -f 16378//16378 16345//16345 16379//16379 -f 16379//16379 16345//16345 16344//16344 -f 16379//16379 16344//16344 16380//16380 -f 16380//16380 16344//16344 16343//16343 -f 16380//16380 16343//16343 16381//16381 -f 16381//16381 16343//16343 16342//16342 -f 16381//16381 16342//16342 16382//16382 -f 16382//16382 16342//16342 16341//16341 -f 16382//16382 16341//16341 16370//16370 -f 16370//16370 16341//16341 16340//16340 -f 16370//16370 16340//16340 16339//16339 -f 16192//16192 16190//16190 16229//16229 -f 16229//16229 16190//16190 16188//16188 -f 16229//16229 16188//16188 16227//16227 -f 16227//16227 16188//16188 16186//16186 -f 16227//16227 16186//16186 16225//16225 -f 16225//16225 16186//16186 16184//16184 -f 16225//16225 16184//16184 16223//16223 -f 16223//16223 16184//16184 16182//16182 -f 16223//16223 16182//16182 16220//16220 -f 16220//16220 16182//16182 16181//16181 -f 16220//16220 16181//16181 16383//16383 -f 16383//16383 16181//16181 16353//16353 -f 16383//16383 16353//16353 16384//16384 -f 16384//16384 16353//16353 16352//16352 -f 16384//16384 16352//16352 16385//16385 -f 16385//16385 16352//16352 16351//16351 -f 16385//16385 16351//16351 16374//16374 -f 16374//16374 16351//16351 16350//16350 -f 16374//16374 16350//16350 16349//16349 -f 16255//16255 16254//16254 16358//16358 -f 16255//16255 16358//16358 16373//16373 -f 16373//16373 16358//16358 16359//16359 -f 16373//16373 16359//16359 16372//16372 -f 16372//16372 16359//16359 16360//16360 -f 16372//16372 16360//16360 16371//16371 -f 16371//16371 16360//16360 16361//16361 -f 16371//16371 16361//16361 16370//16370 -f 16370//16370 16361//16361 16362//16362 -f 16370//16370 16362//16362 16382//16382 -f 16382//16382 16362//16362 16363//16363 -f 16382//16382 16363//16363 16381//16381 -f 16381//16381 16363//16363 16364//16364 -f 16381//16381 16364//16364 16380//16380 -f 16380//16380 16364//16364 16365//16365 -f 16380//16380 16365//16365 16379//16379 -f 16379//16379 16365//16365 16366//16366 -f 16379//16379 16366//16366 16378//16378 -f 16378//16378 16366//16366 16367//16367 -f 16378//16378 16367//16367 16377//16377 -f 16377//16377 16367//16367 16368//16368 -f 16377//16377 16368//16368 16376//16376 -f 16376//16376 16368//16368 16369//16369 -f 16376//16376 16369//16369 16375//16375 -f 16375//16375 16369//16369 16354//16354 -f 16375//16375 16354//16354 16374//16374 -f 16374//16374 16354//16354 16355//16355 -f 16374//16374 16355//16355 16385//16385 -f 16385//16385 16355//16355 16356//16356 -f 16385//16385 16356//16356 16384//16384 -f 16384//16384 16356//16356 16357//16357 -f 16384//16384 16357//16357 16383//16383 -f 16383//16383 16357//16357 16221//16221 -f 16383//16383 16221//16221 16220//16220 -f 16386//16386 16387//16387 16388//16388 -f 16388//16388 16387//16387 16389//16389 -f 16388//16388 16389//16389 16390//16390 -f 16390//16390 16389//16389 16391//16391 -f 16390//16390 16391//16391 16392//16392 -f 16392//16392 16391//16391 16393//16393 -f 16392//16392 16393//16393 16394//16394 -f 16394//16394 16393//16393 16395//16395 -f 16394//16394 16395//16395 16396//16396 -f 16396//16396 16395//16395 16397//16397 -f 16396//16396 16397//16397 16398//16398 -f 16398//16398 16397//16397 16399//16399 -f 16398//16398 16399//16399 16400//16400 -f 16400//16400 16399//16399 16401//16401 -f 16400//16400 16401//16401 16402//16402 -f 16402//16402 16401//16401 16403//16403 -f 16402//16402 16403//16403 16404//16404 -f 16404//16404 16403//16403 16405//16405 -f 16404//16404 16405//16405 16406//16406 -f 16406//16406 16405//16405 16407//16407 -f 16406//16406 16407//16407 16408//16408 -f 16408//16408 16407//16407 16409//16409 -f 16408//16408 16409//16409 16410//16410 -f 16410//16410 16409//16409 16411//16411 -f 16410//16410 16411//16411 16412//16412 -f 16412//16412 16411//16411 16413//16413 -f 16412//16412 16413//16413 16414//16414 -f 16414//16414 16413//16413 16415//16415 -f 16416//16416 1099//1099 16417//16417 -f 16416//16416 16417//16417 16418//16418 -f 16418//16418 16417//16417 16419//16419 -f 16418//16418 16419//16419 16420//16420 -f 16420//16420 16419//16419 16421//16421 -f 16420//16420 16421//16421 16422//16422 -f 16422//16422 16421//16421 16423//16423 -f 16422//16422 16423//16423 16424//16424 -f 16424//16424 16423//16423 16425//16425 -f 16424//16424 16425//16425 16426//16426 -f 16426//16426 16425//16425 16427//16427 -f 16426//16426 16427//16427 16428//16428 -f 16428//16428 16427//16427 16429//16429 -f 16428//16428 16429//16429 16430//16430 -f 16430//16430 16429//16429 16431//16431 -f 16430//16430 16431//16431 16432//16432 -f 16432//16432 16431//16431 16433//16433 -f 16432//16432 16433//16433 16434//16434 -f 16434//16434 16433//16433 16435//16435 -f 16434//16434 16435//16435 16436//16436 -f 16436//16436 16435//16435 16437//16437 -f 16436//16436 16437//16437 16438//16438 -f 16438//16438 16437//16437 16439//16439 -f 16438//16438 16439//16439 16440//16440 -f 16440//16440 16439//16439 16441//16441 -f 16440//16440 16441//16441 16442//16442 -f 16442//16442 16441//16441 16443//16443 -f 16442//16442 16443//16443 16444//16444 -f 16444//16444 16443//16443 16445//16445 -f 16444//16444 16445//16445 16446//16446 -f 16446//16446 16445//16445 16447//16447 -f 16446//16446 16447//16447 16448//16448 -f 16448//16448 16447//16447 16449//16449 -f 16448//16448 16449//16449 16450//16450 -f 16450//16450 16449//16449 16451//16451 -f 16450//16450 16451//16451 16452//16452 -f 16452//16452 16451//16451 1087//1087 -f 16452//16452 1087//1087 16453//16453 -f 1100//1100 16454//16454 16455//16455 -f 1100//1100 16455//16455 16456//16456 -f 16456//16456 16455//16455 16457//16457 -f 16456//16456 16457//16457 16458//16458 -f 16458//16458 16457//16457 16459//16459 -f 16458//16458 16459//16459 16460//16460 -f 16460//16460 16459//16459 16461//16461 -f 16460//16460 16461//16461 16462//16462 -f 16462//16462 16461//16461 16463//16463 -f 16462//16462 16463//16463 16464//16464 -f 16464//16464 16463//16463 16465//16465 -f 16464//16464 16465//16465 16466//16466 -f 16466//16466 16465//16465 16467//16467 -f 16466//16466 16467//16467 16468//16468 -f 16468//16468 16467//16467 16469//16469 -f 16468//16468 16469//16469 16470//16470 -f 16470//16470 16469//16469 16471//16471 -f 16470//16470 16471//16471 16472//16472 -f 16472//16472 16471//16471 16473//16473 -f 16472//16472 16473//16473 16474//16474 -f 16474//16474 16473//16473 16475//16475 -f 16474//16474 16475//16475 16476//16476 -f 16476//16476 16475//16475 16477//16477 -f 16476//16476 16477//16477 16478//16478 -f 16478//16478 16477//16477 16479//16479 -f 16478//16478 16479//16479 16480//16480 -f 16480//16480 16479//16479 16481//16481 -f 16480//16480 16481//16481 16482//16482 -f 16482//16482 16481//16481 16483//16483 -f 16482//16482 16483//16483 16484//16484 -f 16484//16484 16483//16483 16485//16485 -f 16484//16484 16485//16485 16486//16486 -f 16486//16486 16485//16485 16487//16487 -f 16486//16486 16487//16487 16488//16488 -f 16488//16488 16487//16487 16489//16489 -f 16488//16488 16489//16489 16490//16490 -f 16490//16490 16489//16489 16491//16491 -f 16490//16490 16491//16491 1088//1088 -f 16492//16492 16493//16493 16494//16494 -f 16492//16492 16494//16494 16495//16495 -f 16495//16495 16494//16494 16496//16496 -f 16495//16495 16496//16496 16497//16497 -f 16497//16497 16496//16496 16498//16498 -f 16497//16497 16498//16498 16499//16499 -f 16499//16499 16498//16498 16500//16500 -f 16499//16499 16500//16500 16501//16501 -f 16501//16501 16500//16500 16502//16502 -f 16501//16501 16502//16502 16503//16503 -f 16503//16503 16502//16502 16504//16504 -f 16503//16503 16504//16504 16505//16505 -f 16505//16505 16504//16504 16506//16506 -f 16505//16505 16506//16506 16507//16507 -f 16507//16507 16506//16506 16508//16508 -f 16507//16507 16508//16508 16509//16509 -f 16509//16509 16508//16508 16510//16510 -f 16509//16509 16510//16510 16511//16511 -f 16511//16511 16510//16510 16512//16512 -f 16511//16511 16512//16512 16513//16513 -f 16513//16513 16512//16512 16514//16514 -f 16513//16513 16514//16514 16515//16515 -f 16515//16515 16514//16514 16516//16516 -f 16515//16515 16516//16516 16517//16517 -f 16517//16517 16516//16516 16518//16518 -f 16517//16517 16518//16518 16519//16519 -f 16519//16519 16518//16518 16520//16520 -f 16519//16519 16520//16520 16521//16521 -f 16521//16521 16520//16520 16522//16522 -f 16521//16521 16522//16522 16523//16523 -f 16523//16523 16522//16522 16524//16524 -f 16523//16523 16524//16524 16525//16525 -f 16525//16525 16524//16524 16526//16526 -f 16525//16525 16526//16526 16527//16527 -f 16414//16414 16415//16415 16528//16528 -f 16528//16528 16415//16415 16529//16529 -f 16528//16528 16529//16529 16530//16530 -f 16530//16530 16529//16529 16531//16531 -f 16530//16530 16531//16531 16532//16532 -f 16532//16532 16531//16531 16533//16533 -f 16532//16532 16533//16533 16534//16534 -f 16534//16534 16533//16533 16535//16535 -f 16534//16534 16535//16535 16536//16536 -f 16536//16536 16535//16535 16537//16537 -f 16536//16536 16537//16537 16538//16538 -f 16538//16538 16537//16537 16539//16539 -f 16538//16538 16539//16539 16540//16540 -f 16540//16540 16539//16539 16541//16541 -f 16540//16540 16541//16541 16542//16542 -f 16542//16542 16541//16541 16543//16543 -f 16542//16542 16543//16543 16544//16544 -f 16544//16544 16543//16543 16545//16545 -f 16544//16544 16545//16545 16546//16546 -f 16546//16546 16545//16545 16547//16547 -f 16546//16546 16547//16547 16548//16548 -f 16548//16548 16547//16547 16549//16549 -f 16548//16548 16549//16549 16550//16550 -f 16550//16550 16549//16549 16551//16551 -f 16550//16550 16551//16551 16552//16552 -f 16552//16552 16551//16551 16553//16553 -f 16552//16552 16553//16553 16386//16386 -f 16386//16386 16553//16553 16387//16387 -f 16390//16390 16554//16554 16388//16388 -f 16388//16388 16554//16554 16555//16555 -f 16388//16388 16555//16555 16386//16386 -f 16386//16386 16555//16555 1087//1087 -f 16386//16386 1087//1087 16552//16552 -f 16396//16396 16556//16556 16394//16394 -f 16394//16394 16556//16556 16557//16557 -f 16394//16394 16557//16557 16392//16392 -f 16392//16392 16557//16557 16558//16558 -f 16392//16392 16558//16558 16390//16390 -f 16390//16390 16558//16558 16559//16559 -f 16390//16390 16559//16559 16554//16554 -f 16402//16402 16560//16560 16400//16400 -f 16400//16400 16560//16560 16561//16561 -f 16400//16400 16561//16561 16398//16398 -f 16398//16398 16561//16561 16562//16562 -f 16398//16398 16562//16562 16396//16396 -f 16396//16396 16562//16562 16563//16563 -f 16396//16396 16563//16563 16556//16556 -f 16530//16530 16419//16419 16528//16528 -f 16528//16528 16419//16419 16417//16417 -f 16528//16528 16417//16417 16414//16414 -f 16414//16414 16417//16417 1099//1099 -f 16414//16414 1099//1099 16412//16412 -f 16546//16546 16441//16441 16544//16544 -f 16544//16544 16441//16441 16439//16439 -f 16544//16544 16439//16439 16542//16542 -f 16542//16542 16439//16439 16437//16437 -f 16542//16542 16437//16437 16540//16540 -f 1087//1087 16451//16451 16552//16552 -f 16552//16552 16451//16451 16449//16449 -f 16552//16552 16449//16449 16550//16550 -f 16550//16550 16449//16449 16447//16447 -f 16550//16550 16447//16447 16548//16548 -f 16548//16548 16447//16447 16445//16445 -f 16548//16548 16445//16445 16546//16546 -f 16546//16546 16445//16445 16443//16443 -f 16546//16546 16443//16443 16441//16441 -f 16406//16406 16564//16564 16404//16404 -f 16404//16404 16564//16564 16565//16565 -f 16404//16404 16565//16565 16402//16402 -f 16402//16402 16565//16565 16566//16566 -f 16402//16402 16566//16566 16560//16560 -f 16536//16536 16427//16427 16534//16534 -f 16534//16534 16427//16427 16425//16425 -f 16534//16534 16425//16425 16532//16532 -f 16532//16532 16425//16425 16423//16423 -f 16532//16532 16423//16423 16530//16530 -f 16530//16530 16423//16423 16421//16421 -f 16530//16530 16421//16421 16419//16419 -f 16437//16437 16435//16435 16540//16540 -f 16540//16540 16435//16435 16433//16433 -f 16540//16540 16433//16433 16538//16538 -f 16538//16538 16433//16433 16431//16431 -f 16538//16538 16431//16431 16536//16536 -f 16536//16536 16431//16431 16429//16429 -f 16536//16536 16429//16429 16427//16427 -f 1099//1099 16567//16567 16412//16412 -f 16412//16412 16567//16567 16568//16568 -f 16412//16412 16568//16568 16410//16410 -f 16410//16410 16568//16568 16569//16569 -f 16410//16410 16569//16569 16408//16408 -f 16408//16408 16569//16569 16570//16570 -f 16408//16408 16570//16570 16406//16406 -f 16406//16406 16570//16570 16571//16571 -f 16406//16406 16571//16571 16564//16564 -f 16411//16411 16572//16572 16413//16413 -f 16413//16413 16572//16572 16573//16573 -f 16413//16413 16573//16573 16415//16415 -f 16415//16415 16573//16573 1100//1100 -f 16415//16415 1100//1100 16529//16529 -f 16395//16395 16574//16574 16397//16397 -f 16397//16397 16574//16574 16575//16575 -f 16397//16397 16575//16575 16399//16399 -f 16399//16399 16575//16575 16576//16576 -f 16399//16399 16576//16576 16401//16401 -f 16539//16539 16472//16472 16541//16541 -f 16541//16541 16472//16472 16474//16474 -f 16541//16541 16474//16474 16543//16543 -f 16543//16543 16474//16474 16476//16476 -f 16543//16543 16476//16476 16545//16545 -f 16405//16405 16577//16577 16407//16407 -f 16407//16407 16577//16577 16578//16578 -f 16407//16407 16578//16578 16409//16409 -f 16409//16409 16578//16578 16579//16579 -f 16409//16409 16579//16579 16411//16411 -f 16411//16411 16579//16579 16580//16580 -f 16411//16411 16580//16580 16572//16572 -f 16576//16576 16581//16581 16401//16401 -f 16401//16401 16581//16581 16582//16582 -f 16401//16401 16582//16582 16403//16403 -f 16403//16403 16582//16582 16583//16583 -f 16403//16403 16583//16583 16405//16405 -f 16405//16405 16583//16583 16584//16584 -f 16405//16405 16584//16584 16577//16577 -f 16389//16389 16585//16585 16391//16391 -f 16391//16391 16585//16585 16586//16586 -f 16391//16391 16586//16586 16393//16393 -f 16393//16393 16586//16586 16587//16587 -f 16393//16393 16587//16587 16395//16395 -f 16395//16395 16587//16587 16588//16588 -f 16395//16395 16588//16588 16574//16574 -f 16551//16551 16488//16488 16553//16553 -f 16553//16553 16488//16488 16490//16490 -f 16553//16553 16490//16490 16387//16387 -f 16387//16387 16490//16490 1088//1088 -f 16387//16387 1088//1088 16389//16389 -f 16389//16389 1088//1088 16589//16589 -f 16389//16389 16589//16589 16585//16585 -f 16476//16476 16478//16478 16545//16545 -f 16545//16545 16478//16478 16480//16480 -f 16545//16545 16480//16480 16547//16547 -f 16547//16547 16480//16480 16482//16482 -f 16547//16547 16482//16482 16549//16549 -f 16549//16549 16482//16482 16484//16484 -f 16549//16549 16484//16484 16551//16551 -f 16551//16551 16484//16484 16486//16486 -f 16551//16551 16486//16486 16488//16488 -f 16535//16535 16466//16466 16537//16537 -f 16537//16537 16466//16466 16468//16468 -f 16537//16537 16468//16468 16539//16539 -f 16539//16539 16468//16468 16470//16470 -f 16539//16539 16470//16470 16472//16472 -f 1100//1100 16456//16456 16529//16529 -f 16529//16529 16456//16456 16458//16458 -f 16529//16529 16458//16458 16531//16531 -f 16531//16531 16458//16458 16460//16460 -f 16531//16531 16460//16460 16533//16533 -f 16533//16533 16460//16460 16462//16462 -f 16533//16533 16462//16462 16535//16535 -f 16535//16535 16462//16462 16464//16464 -f 16535//16535 16464//16464 16466//16466 -f 16453//16453 1087//1087 16555//16555 -f 16453//16453 16555//16555 16590//16590 -f 16590//16590 16555//16555 16554//16554 -f 16590//16590 16554//16554 16591//16591 -f 16591//16591 16554//16554 16559//16559 -f 16591//16591 16559//16559 16592//16592 -f 16592//16592 16559//16559 16558//16558 -f 16592//16592 16558//16558 16593//16593 -f 16593//16593 16558//16558 16557//16557 -f 16593//16593 16557//16557 16594//16594 -f 16594//16594 16557//16557 16556//16556 -f 16594//16594 16556//16556 16595//16595 -f 16595//16595 16556//16556 16563//16563 -f 16595//16595 16563//16563 16596//16596 -f 16596//16596 16563//16563 16562//16562 -f 16596//16596 16562//16562 16597//16597 -f 16597//16597 16562//16562 16561//16561 -f 16597//16597 16561//16561 16598//16598 -f 16598//16598 16561//16561 16560//16560 -f 16598//16598 16560//16560 16599//16599 -f 16599//16599 16560//16560 16566//16566 -f 16599//16599 16566//16566 16600//16600 -f 16600//16600 16566//16566 16565//16565 -f 16600//16600 16565//16565 16601//16601 -f 16601//16601 16565//16565 16564//16564 -f 16601//16601 16564//16564 16602//16602 -f 16602//16602 16564//16564 16571//16571 -f 16602//16602 16571//16571 16603//16603 -f 16603//16603 16571//16571 16570//16570 -f 16603//16603 16570//16570 16604//16604 -f 16604//16604 16570//16570 16569//16569 -f 16604//16604 16569//16569 16605//16605 -f 16605//16605 16569//16569 16568//16568 -f 16605//16605 16568//16568 16606//16606 -f 16606//16606 16568//16568 16567//16567 -f 16606//16606 16567//16567 16607//16607 -f 16607//16607 16567//16567 1099//1099 -f 16607//16607 1099//1099 16416//16416 -f 1088//1088 16491//16491 16608//16608 -f 1088//1088 16608//16608 16589//16589 -f 16589//16589 16608//16608 16609//16609 -f 16589//16589 16609//16609 16585//16585 -f 16585//16585 16609//16609 16610//16610 -f 16585//16585 16610//16610 16586//16586 -f 16586//16586 16610//16610 16611//16611 -f 16586//16586 16611//16611 16587//16587 -f 16587//16587 16611//16611 16612//16612 -f 16587//16587 16612//16612 16588//16588 -f 16588//16588 16612//16612 16613//16613 -f 16588//16588 16613//16613 16574//16574 -f 16574//16574 16613//16613 16614//16614 -f 16574//16574 16614//16614 16575//16575 -f 16575//16575 16614//16614 16615//16615 -f 16575//16575 16615//16615 16576//16576 -f 16576//16576 16615//16615 16616//16616 -f 16576//16576 16616//16616 16581//16581 -f 16581//16581 16616//16616 16617//16617 -f 16581//16581 16617//16617 16582//16582 -f 16582//16582 16617//16617 16618//16618 -f 16582//16582 16618//16618 16583//16583 -f 16583//16583 16618//16618 16619//16619 -f 16583//16583 16619//16619 16584//16584 -f 16584//16584 16619//16619 16620//16620 -f 16584//16584 16620//16620 16577//16577 -f 16577//16577 16620//16620 16621//16621 -f 16577//16577 16621//16621 16578//16578 -f 16578//16578 16621//16621 16622//16622 -f 16578//16578 16622//16622 16579//16579 -f 16579//16579 16622//16622 16623//16623 -f 16579//16579 16623//16623 16580//16580 -f 16580//16580 16623//16623 16624//16624 -f 16580//16580 16624//16624 16572//16572 -f 16572//16572 16624//16624 16625//16625 -f 16572//16572 16625//16625 16573//16573 -f 16573//16573 16625//16625 16454//16454 -f 16573//16573 16454//16454 1100//1100 -f 16518//16518 16446//16446 16520//16520 -f 16520//16520 16446//16446 16448//16448 -f 16520//16520 16448//16448 16522//16522 -f 16522//16522 16448//16448 16450//16450 -f 16522//16522 16450//16450 16524//16524 -f 16524//16524 16450//16450 16452//16452 -f 16524//16524 16452//16452 16526//16526 -f 16526//16526 16452//16452 16453//16453 -f 16526//16526 16453//16453 16626//16626 -f 16626//16626 16453//16453 16590//16590 -f 16626//16626 16590//16590 16627//16627 -f 16627//16627 16590//16590 16591//16591 -f 16627//16627 16591//16591 16628//16628 -f 16628//16628 16591//16591 16592//16592 -f 16628//16628 16592//16592 16629//16629 -f 16630//16630 16604//16604 16631//16631 -f 16631//16631 16604//16604 16605//16605 -f 16631//16631 16605//16605 16632//16632 -f 16632//16632 16605//16605 16606//16606 -f 16632//16632 16606//16606 16633//16633 -f 16633//16633 16606//16606 16607//16607 -f 16633//16633 16607//16607 16493//16493 -f 16493//16493 16607//16607 16416//16416 -f 16493//16493 16416//16416 16494//16494 -f 16494//16494 16416//16416 16418//16418 -f 16494//16494 16418//16418 16496//16496 -f 16496//16496 16418//16418 16420//16420 -f 16496//16496 16420//16420 16498//16498 -f 16498//16498 16420//16420 16422//16422 -f 16498//16498 16422//16422 16500//16500 -f 16592//16592 16593//16593 16629//16629 -f 16629//16629 16593//16593 16594//16594 -f 16629//16629 16594//16594 16634//16634 -f 16634//16634 16594//16594 16595//16595 -f 16634//16634 16595//16595 16635//16635 -f 16635//16635 16595//16595 16596//16596 -f 16635//16635 16596//16596 16636//16636 -f 16636//16636 16596//16596 16597//16597 -f 16636//16636 16597//16597 16637//16637 -f 16637//16637 16597//16597 16598//16598 -f 16637//16637 16598//16598 16638//16638 -f 16638//16638 16598//16598 16599//16599 -f 16638//16638 16599//16599 16639//16639 -f 16639//16639 16599//16599 16600//16600 -f 16639//16639 16600//16600 16640//16640 -f 16640//16640 16600//16600 16601//16601 -f 16640//16640 16601//16601 16641//16641 -f 16641//16641 16601//16601 16602//16602 -f 16641//16641 16602//16602 16630//16630 -f 16630//16630 16602//16602 16603//16603 -f 16630//16630 16603//16603 16604//16604 -f 16422//16422 16424//16424 16500//16500 -f 16500//16500 16424//16424 16426//16426 -f 16500//16500 16426//16426 16502//16502 -f 16502//16502 16426//16426 16428//16428 -f 16502//16502 16428//16428 16504//16504 -f 16504//16504 16428//16428 16430//16430 -f 16504//16504 16430//16430 16506//16506 -f 16506//16506 16430//16430 16432//16432 -f 16506//16506 16432//16432 16508//16508 -f 16508//16508 16432//16432 16434//16434 -f 16508//16508 16434//16434 16510//16510 -f 16510//16510 16434//16434 16436//16436 -f 16510//16510 16436//16436 16512//16512 -f 16512//16512 16436//16436 16438//16438 -f 16512//16512 16438//16438 16514//16514 -f 16514//16514 16438//16438 16440//16440 -f 16514//16514 16440//16440 16516//16516 -f 16516//16516 16440//16440 16442//16442 -f 16516//16516 16442//16442 16518//16518 -f 16518//16518 16442//16442 16444//16444 -f 16518//16518 16444//16444 16446//16446 -f 16642//16642 16611//16611 16643//16643 -f 16643//16643 16611//16611 16610//16610 -f 16643//16643 16610//16610 16644//16644 -f 16644//16644 16610//16610 16609//16609 -f 16644//16644 16609//16609 16645//16645 -f 16645//16645 16609//16609 16608//16608 -f 16645//16645 16608//16608 16527//16527 -f 16527//16527 16608//16608 16491//16491 -f 16527//16527 16491//16491 16525//16525 -f 16525//16525 16491//16491 16489//16489 -f 16525//16525 16489//16489 16523//16523 -f 16523//16523 16489//16489 16487//16487 -f 16523//16523 16487//16487 16521//16521 -f 16521//16521 16487//16487 16485//16485 -f 16521//16521 16485//16485 16519//16519 -f 16501//16501 16461//16461 16499//16499 -f 16499//16499 16461//16461 16459//16459 -f 16499//16499 16459//16459 16497//16497 -f 16497//16497 16459//16459 16457//16457 -f 16497//16497 16457//16457 16495//16495 -f 16495//16495 16457//16457 16455//16455 -f 16495//16495 16455//16455 16492//16492 -f 16492//16492 16455//16455 16454//16454 -f 16492//16492 16454//16454 16646//16646 -f 16646//16646 16454//16454 16625//16625 -f 16646//16646 16625//16625 16647//16647 -f 16647//16647 16625//16625 16624//16624 -f 16647//16647 16624//16624 16648//16648 -f 16648//16648 16624//16624 16623//16623 -f 16648//16648 16623//16623 16649//16649 -f 16623//16623 16622//16622 16649//16649 -f 16649//16649 16622//16622 16621//16621 -f 16649//16649 16621//16621 16650//16650 -f 16650//16650 16621//16621 16620//16620 -f 16650//16650 16620//16620 16651//16651 -f 16651//16651 16620//16620 16619//16619 -f 16651//16651 16619//16619 16652//16652 -f 16652//16652 16619//16619 16618//16618 -f 16652//16652 16618//16618 16653//16653 -f 16653//16653 16618//16618 16617//16617 -f 16653//16653 16617//16617 16654//16654 -f 16654//16654 16617//16617 16616//16616 -f 16654//16654 16616//16616 16655//16655 -f 16655//16655 16616//16616 16615//16615 -f 16655//16655 16615//16615 16656//16656 -f 16656//16656 16615//16615 16614//16614 -f 16656//16656 16614//16614 16657//16657 -f 16657//16657 16614//16614 16613//16613 -f 16657//16657 16613//16613 16642//16642 -f 16642//16642 16613//16613 16612//16612 -f 16642//16642 16612//16612 16611//16611 -f 16485//16485 16483//16483 16519//16519 -f 16519//16519 16483//16483 16481//16481 -f 16519//16519 16481//16481 16517//16517 -f 16517//16517 16481//16481 16479//16479 -f 16517//16517 16479//16479 16515//16515 -f 16515//16515 16479//16479 16477//16477 -f 16515//16515 16477//16477 16513//16513 -f 16513//16513 16477//16477 16475//16475 -f 16513//16513 16475//16475 16511//16511 -f 16511//16511 16475//16475 16473//16473 -f 16511//16511 16473//16473 16509//16509 -f 16509//16509 16473//16473 16471//16471 -f 16509//16509 16471//16471 16507//16507 -f 16507//16507 16471//16471 16469//16469 -f 16507//16507 16469//16469 16505//16505 -f 16505//16505 16469//16469 16467//16467 -f 16505//16505 16467//16467 16503//16503 -f 16503//16503 16467//16467 16465//16465 -f 16503//16503 16465//16465 16501//16501 -f 16501//16501 16465//16465 16463//16463 -f 16501//16501 16463//16463 16461//16461 -f 16527//16527 16526//16526 16626//16626 -f 16527//16527 16626//16626 16645//16645 -f 16645//16645 16626//16626 16627//16627 -f 16645//16645 16627//16627 16644//16644 -f 16644//16644 16627//16627 16628//16628 -f 16644//16644 16628//16628 16643//16643 -f 16643//16643 16628//16628 16629//16629 -f 16643//16643 16629//16629 16642//16642 -f 16642//16642 16629//16629 16634//16634 -f 16642//16642 16634//16634 16657//16657 -f 16657//16657 16634//16634 16635//16635 -f 16657//16657 16635//16635 16656//16656 -f 16656//16656 16635//16635 16636//16636 -f 16656//16656 16636//16636 16655//16655 -f 16655//16655 16636//16636 16637//16637 -f 16655//16655 16637//16637 16654//16654 -f 16654//16654 16637//16637 16638//16638 -f 16654//16654 16638//16638 16653//16653 -f 16653//16653 16638//16638 16639//16639 -f 16653//16653 16639//16639 16652//16652 -f 16652//16652 16639//16639 16640//16640 -f 16652//16652 16640//16640 16651//16651 -f 16651//16651 16640//16640 16641//16641 -f 16651//16651 16641//16641 16650//16650 -f 16650//16650 16641//16641 16630//16630 -f 16650//16650 16630//16630 16649//16649 -f 16649//16649 16630//16630 16631//16631 -f 16649//16649 16631//16631 16648//16648 -f 16648//16648 16631//16631 16632//16632 -f 16648//16648 16632//16632 16647//16647 -f 16647//16647 16632//16632 16633//16633 -f 16647//16647 16633//16633 16646//16646 -f 16646//16646 16633//16633 16493//16493 -f 16646//16646 16493//16493 16492//16492 -f 16658//16658 16659//16659 16660//16660 -f 16660//16660 16659//16659 16661//16661 -f 16660//16660 16661//16661 16662//16662 -f 16662//16662 16661//16661 16663//16663 -f 16662//16662 16663//16663 16664//16664 -f 16664//16664 16663//16663 16665//16665 -f 16664//16664 16665//16665 16666//16666 -f 16666//16666 16665//16665 16667//16667 -f 16666//16666 16667//16667 16668//16668 -f 16668//16668 16667//16667 16669//16669 -f 16668//16668 16669//16669 16670//16670 -f 16670//16670 16669//16669 16671//16671 -f 16670//16670 16671//16671 16672//16672 -f 16672//16672 16671//16671 16673//16673 -f 16672//16672 16673//16673 16674//16674 -f 16674//16674 16673//16673 16675//16675 -f 16674//16674 16675//16675 16676//16676 -f 16676//16676 16675//16675 16677//16677 -f 16676//16676 16677//16677 16678//16678 -f 16678//16678 16677//16677 16679//16679 -f 16678//16678 16679//16679 16680//16680 -f 16680//16680 16679//16679 16681//16681 -f 16680//16680 16681//16681 16682//16682 -f 16682//16682 16681//16681 16683//16683 -f 16682//16682 16683//16683 16684//16684 -f 16684//16684 16683//16683 16685//16685 -f 16684//16684 16685//16685 16686//16686 -f 16686//16686 16685//16685 16687//16687 -f 16688//16688 16689//16689 16690//16690 -f 16688//16688 16690//16690 16691//16691 -f 16691//16691 16690//16690 16692//16692 -f 16691//16691 16692//16692 16693//16693 -f 16693//16693 16692//16692 16694//16694 -f 16693//16693 16694//16694 16695//16695 -f 16695//16695 16694//16694 16696//16696 -f 16695//16695 16696//16696 16697//16697 -f 16697//16697 16696//16696 16698//16698 -f 16697//16697 16698//16698 16699//16699 -f 16699//16699 16698//16698 16700//16700 -f 16699//16699 16700//16700 16701//16701 -f 16701//16701 16700//16700 16702//16702 -f 16701//16701 16702//16702 16703//16703 -f 16703//16703 16702//16702 16704//16704 -f 16703//16703 16704//16704 16705//16705 -f 16705//16705 16704//16704 16706//16706 -f 16705//16705 16706//16706 16707//16707 -f 16707//16707 16706//16706 16708//16708 -f 16707//16707 16708//16708 16709//16709 -f 16709//16709 16708//16708 16710//16710 -f 16709//16709 16710//16710 16711//16711 -f 16711//16711 16710//16710 16712//16712 -f 16711//16711 16712//16712 16713//16713 -f 16713//16713 16712//16712 16714//16714 -f 16713//16713 16714//16714 16715//16715 -f 16715//16715 16714//16714 16716//16716 -f 16715//16715 16716//16716 16717//16717 -f 16717//16717 16716//16716 16718//16718 -f 16717//16717 16718//16718 16719//16719 -f 16719//16719 16718//16718 16720//16720 -f 16719//16719 16720//16720 16721//16721 -f 16721//16721 16720//16720 16722//16722 -f 16721//16721 16722//16722 16723//16723 -f 16723//16723 16722//16722 16724//16724 -f 16723//16723 16724//16724 16725//16725 -f 16725//16725 16724//16724 16726//16726 -f 16725//16725 16726//16726 16727//16727 -f 16728//16728 16729//16729 16730//16730 -f 16728//16728 16730//16730 16731//16731 -f 16731//16731 16730//16730 16732//16732 -f 16731//16731 16732//16732 16733//16733 -f 16733//16733 16732//16732 16734//16734 -f 16733//16733 16734//16734 16735//16735 -f 16735//16735 16734//16734 16736//16736 -f 16735//16735 16736//16736 16737//16737 -f 16737//16737 16736//16736 16738//16738 -f 16737//16737 16738//16738 16739//16739 -f 16739//16739 16738//16738 16740//16740 -f 16739//16739 16740//16740 16741//16741 -f 16741//16741 16740//16740 16742//16742 -f 16741//16741 16742//16742 16743//16743 -f 16743//16743 16742//16742 16744//16744 -f 16743//16743 16744//16744 16745//16745 -f 16745//16745 16744//16744 16746//16746 -f 16745//16745 16746//16746 16747//16747 -f 16747//16747 16746//16746 16748//16748 -f 16747//16747 16748//16748 16749//16749 -f 16749//16749 16748//16748 16750//16750 -f 16749//16749 16750//16750 16751//16751 -f 16751//16751 16750//16750 16752//16752 -f 16751//16751 16752//16752 16753//16753 -f 16753//16753 16752//16752 16754//16754 -f 16753//16753 16754//16754 16755//16755 -f 16755//16755 16754//16754 16756//16756 -f 16755//16755 16756//16756 16757//16757 -f 16757//16757 16756//16756 16758//16758 -f 16757//16757 16758//16758 16759//16759 -f 16759//16759 16758//16758 16760//16760 -f 16759//16759 16760//16760 16761//16761 -f 16761//16761 16760//16760 16762//16762 -f 16761//16761 16762//16762 16763//16763 -f 16763//16763 16762//16762 16764//16764 -f 16763//16763 16764//16764 16765//16765 -f 16765//16765 16764//16764 16766//16766 -f 16765//16765 16766//16766 16767//16767 -f 16768//16768 16769//16769 16770//16770 -f 16768//16768 16770//16770 16771//16771 -f 16771//16771 16770//16770 16772//16772 -f 16771//16771 16772//16772 16773//16773 -f 16773//16773 16772//16772 16774//16774 -f 16773//16773 16774//16774 16775//16775 -f 16775//16775 16774//16774 16776//16776 -f 16775//16775 16776//16776 16777//16777 -f 16777//16777 16776//16776 16778//16778 -f 16777//16777 16778//16778 16779//16779 -f 16779//16779 16778//16778 16780//16780 -f 16779//16779 16780//16780 16781//16781 -f 16781//16781 16780//16780 16782//16782 -f 16781//16781 16782//16782 16783//16783 -f 16783//16783 16782//16782 16784//16784 -f 16783//16783 16784//16784 16785//16785 -f 16785//16785 16784//16784 16786//16786 -f 16785//16785 16786//16786 16787//16787 -f 16787//16787 16786//16786 16788//16788 -f 16787//16787 16788//16788 16789//16789 -f 16789//16789 16788//16788 16790//16790 -f 16789//16789 16790//16790 16791//16791 -f 16791//16791 16790//16790 16792//16792 -f 16791//16791 16792//16792 16793//16793 -f 16793//16793 16792//16792 16794//16794 -f 16793//16793 16794//16794 16795//16795 -f 16795//16795 16794//16794 16796//16796 -f 16795//16795 16796//16796 16797//16797 -f 16797//16797 16796//16796 16798//16798 -f 16797//16797 16798//16798 16799//16799 -f 16799//16799 16798//16798 16800//16800 -f 16799//16799 16800//16800 16801//16801 -f 16801//16801 16800//16800 16802//16802 -f 16801//16801 16802//16802 16803//16803 -f 16686//16686 16687//16687 16804//16804 -f 16804//16804 16687//16687 16805//16805 -f 16804//16804 16805//16805 16806//16806 -f 16806//16806 16805//16805 16807//16807 -f 16806//16806 16807//16807 16808//16808 -f 16808//16808 16807//16807 16809//16809 -f 16808//16808 16809//16809 16810//16810 -f 16810//16810 16809//16809 16811//16811 -f 16810//16810 16811//16811 16812//16812 -f 16812//16812 16811//16811 16813//16813 -f 16812//16812 16813//16813 16814//16814 -f 16814//16814 16813//16813 16815//16815 -f 16814//16814 16815//16815 16816//16816 -f 16816//16816 16815//16815 16817//16817 -f 16816//16816 16817//16817 16818//16818 -f 16818//16818 16817//16817 16819//16819 -f 16818//16818 16819//16819 16820//16820 -f 16820//16820 16819//16819 16821//16821 -f 16820//16820 16821//16821 16822//16822 -f 16822//16822 16821//16821 16823//16823 -f 16822//16822 16823//16823 16824//16824 -f 16824//16824 16823//16823 16825//16825 -f 16824//16824 16825//16825 16826//16826 -f 16826//16826 16825//16825 16827//16827 -f 16826//16826 16827//16827 16828//16828 -f 16828//16828 16827//16827 16829//16829 -f 16828//16828 16829//16829 16658//16658 -f 16658//16658 16829//16829 16659//16659 -f 16662//16662 16830//16830 16660//16660 -f 16660//16660 16830//16830 16831//16831 -f 16660//16660 16831//16831 16658//16658 -f 16658//16658 16831//16831 16726//16726 -f 16658//16658 16726//16726 16828//16828 -f 16668//16668 16832//16832 16666//16666 -f 16666//16666 16832//16832 16833//16833 -f 16666//16666 16833//16833 16664//16664 -f 16664//16664 16833//16833 16834//16834 -f 16664//16664 16834//16834 16662//16662 -f 16662//16662 16834//16834 16835//16835 -f 16662//16662 16835//16835 16830//16830 -f 16674//16674 16836//16836 16672//16672 -f 16672//16672 16836//16836 16837//16837 -f 16672//16672 16837//16837 16670//16670 -f 16670//16670 16837//16837 16838//16838 -f 16670//16670 16838//16838 16668//16668 -f 16668//16668 16838//16838 16839//16839 -f 16668//16668 16839//16839 16832//16832 -f 16806//16806 16692//16692 16804//16804 -f 16804//16804 16692//16692 16690//16690 -f 16804//16804 16690//16690 16686//16686 -f 16686//16686 16690//16690 16689//16689 -f 16686//16686 16689//16689 16684//16684 -f 16812//16812 16700//16700 16810//16810 -f 16810//16810 16700//16700 16698//16698 -f 16810//16810 16698//16698 16808//16808 -f 16808//16808 16698//16698 16696//16696 -f 16808//16808 16696//16696 16806//16806 -f 16806//16806 16696//16696 16694//16694 -f 16806//16806 16694//16694 16692//16692 -f 16818//16818 16708//16708 16816//16816 -f 16816//16816 16708//16708 16706//16706 -f 16816//16816 16706//16706 16814//16814 -f 16814//16814 16706//16706 16704//16704 -f 16814//16814 16704//16704 16812//16812 -f 16812//16812 16704//16704 16702//16702 -f 16812//16812 16702//16702 16700//16700 -f 16822//16822 16714//16714 16820//16820 -f 16820//16820 16714//16714 16712//16712 -f 16820//16820 16712//16712 16818//16818 -f 16818//16818 16712//16712 16710//16710 -f 16818//16818 16710//16710 16708//16708 -f 16726//16726 16724//16724 16828//16828 -f 16828//16828 16724//16724 16722//16722 -f 16828//16828 16722//16722 16826//16826 -f 16826//16826 16722//16722 16720//16720 -f 16826//16826 16720//16720 16824//16824 -f 16824//16824 16720//16720 16718//16718 -f 16824//16824 16718//16718 16822//16822 -f 16822//16822 16718//16718 16716//16716 -f 16822//16822 16716//16716 16714//16714 -f 16678//16678 16840//16840 16676//16676 -f 16676//16676 16840//16840 16841//16841 -f 16676//16676 16841//16841 16674//16674 -f 16674//16674 16841//16841 16842//16842 -f 16674//16674 16842//16842 16836//16836 -f 16689//16689 16843//16843 16684//16684 -f 16684//16684 16843//16843 16844//16844 -f 16684//16684 16844//16844 16682//16682 -f 16682//16682 16844//16844 16845//16845 -f 16682//16682 16845//16845 16680//16680 -f 16680//16680 16845//16845 16846//16846 -f 16680//16680 16846//16846 16678//16678 -f 16678//16678 16846//16846 16847//16847 -f 16678//16678 16847//16847 16840//16840 -f 16805//16805 16733//16733 16807//16807 -f 16807//16807 16733//16733 16735//16735 -f 16807//16807 16735//16735 16809//16809 -f 16809//16809 16735//16735 16737//16737 -f 16809//16809 16737//16737 16811//16811 -f 16673//16673 16848//16848 16675//16675 -f 16675//16675 16848//16848 16849//16849 -f 16675//16675 16849//16849 16677//16677 -f 16667//16667 16850//16850 16669//16669 -f 16669//16669 16850//16850 16851//16851 -f 16669//16669 16851//16851 16671//16671 -f 16671//16671 16851//16851 16852//16852 -f 16671//16671 16852//16852 16673//16673 -f 16673//16673 16852//16852 16853//16853 -f 16673//16673 16853//16853 16848//16848 -f 16821//16821 16755//16755 16823//16823 -f 16823//16823 16755//16755 16757//16757 -f 16823//16823 16757//16757 16825//16825 -f 16825//16825 16757//16757 16759//16759 -f 16825//16825 16759//16759 16827//16827 -f 16683//16683 16854//16854 16685//16685 -f 16685//16685 16854//16854 16855//16855 -f 16685//16685 16855//16855 16687//16687 -f 16687//16687 16855//16855 16728//16728 -f 16687//16687 16728//16728 16805//16805 -f 16805//16805 16728//16728 16731//16731 -f 16805//16805 16731//16731 16733//16733 -f 16849//16849 16856//16856 16677//16677 -f 16677//16677 16856//16856 16857//16857 -f 16677//16677 16857//16857 16679//16679 -f 16679//16679 16857//16857 16858//16858 -f 16679//16679 16858//16858 16681//16681 -f 16681//16681 16858//16858 16859//16859 -f 16681//16681 16859//16859 16683//16683 -f 16683//16683 16859//16859 16860//16860 -f 16683//16683 16860//16860 16854//16854 -f 16661//16661 16861//16861 16663//16663 -f 16663//16663 16861//16861 16862//16862 -f 16663//16663 16862//16862 16665//16665 -f 16665//16665 16862//16862 16863//16863 -f 16665//16665 16863//16863 16667//16667 -f 16667//16667 16863//16863 16864//16864 -f 16667//16667 16864//16864 16850//16850 -f 16759//16759 16761//16761 16827//16827 -f 16827//16827 16761//16761 16763//16763 -f 16827//16827 16763//16763 16829//16829 -f 16829//16829 16763//16763 16765//16765 -f 16829//16829 16765//16765 16659//16659 -f 16659//16659 16765//16765 16767//16767 -f 16659//16659 16767//16767 16661//16661 -f 16661//16661 16767//16767 16865//16865 -f 16661//16661 16865//16865 16861//16861 -f 16817//16817 16749//16749 16819//16819 -f 16819//16819 16749//16749 16751//16751 -f 16819//16819 16751//16751 16821//16821 -f 16821//16821 16751//16751 16753//16753 -f 16821//16821 16753//16753 16755//16755 -f 16737//16737 16739//16739 16811//16811 -f 16811//16811 16739//16739 16741//16741 -f 16811//16811 16741//16741 16813//16813 -f 16813//16813 16741//16741 16743//16743 -f 16813//16813 16743//16743 16815//16815 -f 16815//16815 16743//16743 16745//16745 -f 16815//16815 16745//16745 16817//16817 -f 16817//16817 16745//16745 16747//16747 -f 16817//16817 16747//16747 16749//16749 -f 16727//16727 16726//16726 16831//16831 -f 16727//16727 16831//16831 16866//16866 -f 16866//16866 16831//16831 16830//16830 -f 16866//16866 16830//16830 16867//16867 -f 16867//16867 16830//16830 16835//16835 -f 16867//16867 16835//16835 16868//16868 -f 16868//16868 16835//16835 16834//16834 -f 16868//16868 16834//16834 16869//16869 -f 16869//16869 16834//16834 16833//16833 -f 16869//16869 16833//16833 16870//16870 -f 16870//16870 16833//16833 16832//16832 -f 16870//16870 16832//16832 16871//16871 -f 16871//16871 16832//16832 16839//16839 -f 16871//16871 16839//16839 16872//16872 -f 16872//16872 16839//16839 16838//16838 -f 16872//16872 16838//16838 16873//16873 -f 16873//16873 16838//16838 16837//16837 -f 16873//16873 16837//16837 16874//16874 -f 16874//16874 16837//16837 16836//16836 -f 16874//16874 16836//16836 16875//16875 -f 16875//16875 16836//16836 16842//16842 -f 16875//16875 16842//16842 16876//16876 -f 16876//16876 16842//16842 16841//16841 -f 16876//16876 16841//16841 16877//16877 -f 16877//16877 16841//16841 16840//16840 -f 16877//16877 16840//16840 16878//16878 -f 16878//16878 16840//16840 16847//16847 -f 16878//16878 16847//16847 16879//16879 -f 16879//16879 16847//16847 16846//16846 -f 16879//16879 16846//16846 16880//16880 -f 16880//16880 16846//16846 16845//16845 -f 16880//16880 16845//16845 16881//16881 -f 16881//16881 16845//16845 16844//16844 -f 16881//16881 16844//16844 16882//16882 -f 16882//16882 16844//16844 16843//16843 -f 16882//16882 16843//16843 16883//16883 -f 16883//16883 16843//16843 16689//16689 -f 16883//16883 16689//16689 16688//16688 -f 16767//16767 16766//16766 16884//16884 -f 16767//16767 16884//16884 16865//16865 -f 16865//16865 16884//16884 16885//16885 -f 16865//16865 16885//16885 16861//16861 -f 16861//16861 16885//16885 16886//16886 -f 16861//16861 16886//16886 16862//16862 -f 16862//16862 16886//16886 16887//16887 -f 16862//16862 16887//16887 16863//16863 -f 16863//16863 16887//16887 16888//16888 -f 16863//16863 16888//16888 16864//16864 -f 16864//16864 16888//16888 16889//16889 -f 16864//16864 16889//16889 16850//16850 -f 16850//16850 16889//16889 16890//16890 -f 16850//16850 16890//16890 16851//16851 -f 16851//16851 16890//16890 16891//16891 -f 16851//16851 16891//16891 16852//16852 -f 16852//16852 16891//16891 16892//16892 -f 16852//16852 16892//16892 16853//16853 -f 16853//16853 16892//16892 16893//16893 -f 16853//16853 16893//16893 16848//16848 -f 16848//16848 16893//16893 16894//16894 -f 16848//16848 16894//16894 16849//16849 -f 16849//16849 16894//16894 16895//16895 -f 16849//16849 16895//16895 16856//16856 -f 16856//16856 16895//16895 16896//16896 -f 16856//16856 16896//16896 16857//16857 -f 16857//16857 16896//16896 16897//16897 -f 16857//16857 16897//16897 16858//16858 -f 16858//16858 16897//16897 16898//16898 -f 16858//16858 16898//16898 16859//16859 -f 16859//16859 16898//16898 16899//16899 -f 16859//16859 16899//16899 16860//16860 -f 16860//16860 16899//16899 16900//16900 -f 16860//16860 16900//16900 16854//16854 -f 16854//16854 16900//16900 16901//16901 -f 16854//16854 16901//16901 16855//16855 -f 16855//16855 16901//16901 16729//16729 -f 16855//16855 16729//16729 16728//16728 -f 16794//16794 16719//16719 16796//16796 -f 16796//16796 16719//16719 16721//16721 -f 16796//16796 16721//16721 16798//16798 -f 16798//16798 16721//16721 16723//16723 -f 16798//16798 16723//16723 16800//16800 -f 16800//16800 16723//16723 16725//16725 -f 16800//16800 16725//16725 16802//16802 -f 16802//16802 16725//16725 16727//16727 -f 16802//16802 16727//16727 16902//16902 -f 16902//16902 16727//16727 16866//16866 -f 16902//16902 16866//16866 16903//16903 -f 16903//16903 16866//16866 16867//16867 -f 16903//16903 16867//16867 16904//16904 -f 16904//16904 16867//16867 16868//16868 -f 16904//16904 16868//16868 16905//16905 -f 16906//16906 16880//16880 16907//16907 -f 16907//16907 16880//16880 16881//16881 -f 16907//16907 16881//16881 16908//16908 -f 16908//16908 16881//16881 16882//16882 -f 16908//16908 16882//16882 16909//16909 -f 16909//16909 16882//16882 16883//16883 -f 16909//16909 16883//16883 16769//16769 -f 16769//16769 16883//16883 16688//16688 -f 16769//16769 16688//16688 16770//16770 -f 16770//16770 16688//16688 16691//16691 -f 16770//16770 16691//16691 16772//16772 -f 16772//16772 16691//16691 16693//16693 -f 16772//16772 16693//16693 16774//16774 -f 16774//16774 16693//16693 16695//16695 -f 16774//16774 16695//16695 16776//16776 -f 16868//16868 16869//16869 16905//16905 -f 16905//16905 16869//16869 16870//16870 -f 16905//16905 16870//16870 16910//16910 -f 16910//16910 16870//16870 16871//16871 -f 16910//16910 16871//16871 16911//16911 -f 16911//16911 16871//16871 16872//16872 -f 16911//16911 16872//16872 16912//16912 -f 16912//16912 16872//16872 16873//16873 -f 16912//16912 16873//16873 16913//16913 -f 16913//16913 16873//16873 16874//16874 -f 16913//16913 16874//16874 16914//16914 -f 16914//16914 16874//16874 16875//16875 -f 16914//16914 16875//16875 16915//16915 -f 16915//16915 16875//16875 16876//16876 -f 16915//16915 16876//16876 16916//16916 -f 16916//16916 16876//16876 16877//16877 -f 16916//16916 16877//16877 16917//16917 -f 16917//16917 16877//16877 16878//16878 -f 16917//16917 16878//16878 16906//16906 -f 16906//16906 16878//16878 16879//16879 -f 16906//16906 16879//16879 16880//16880 -f 16695//16695 16697//16697 16776//16776 -f 16776//16776 16697//16697 16699//16699 -f 16776//16776 16699//16699 16778//16778 -f 16778//16778 16699//16699 16701//16701 -f 16778//16778 16701//16701 16780//16780 -f 16780//16780 16701//16701 16703//16703 -f 16780//16780 16703//16703 16782//16782 -f 16782//16782 16703//16703 16705//16705 -f 16782//16782 16705//16705 16784//16784 -f 16784//16784 16705//16705 16707//16707 -f 16784//16784 16707//16707 16786//16786 -f 16786//16786 16707//16707 16709//16709 -f 16786//16786 16709//16709 16788//16788 -f 16788//16788 16709//16709 16711//16711 -f 16788//16788 16711//16711 16790//16790 -f 16790//16790 16711//16711 16713//16713 -f 16790//16790 16713//16713 16792//16792 -f 16792//16792 16713//16713 16715//16715 -f 16792//16792 16715//16715 16794//16794 -f 16794//16794 16715//16715 16717//16717 -f 16794//16794 16717//16717 16719//16719 -f 16795//16795 16756//16756 16793//16793 -f 16793//16793 16756//16756 16754//16754 -f 16793//16793 16754//16754 16791//16791 -f 16791//16791 16754//16754 16752//16752 -f 16791//16791 16752//16752 16789//16789 -f 16789//16789 16752//16752 16750//16750 -f 16789//16789 16750//16750 16787//16787 -f 16787//16787 16750//16750 16748//16748 -f 16787//16787 16748//16748 16785//16785 -f 16785//16785 16748//16748 16746//16746 -f 16785//16785 16746//16746 16783//16783 -f 16783//16783 16746//16746 16744//16744 -f 16783//16783 16744//16744 16781//16781 -f 16781//16781 16744//16744 16742//16742 -f 16781//16781 16742//16742 16779//16779 -f 16779//16779 16742//16742 16740//16740 -f 16779//16779 16740//16740 16777//16777 -f 16918//16918 16897//16897 16919//16919 -f 16919//16919 16897//16897 16896//16896 -f 16919//16919 16896//16896 16920//16920 -f 16920//16920 16896//16896 16895//16895 -f 16920//16920 16895//16895 16921//16921 -f 16921//16921 16895//16895 16894//16894 -f 16921//16921 16894//16894 16922//16922 -f 16922//16922 16894//16894 16893//16893 -f 16922//16922 16893//16893 16923//16923 -f 16923//16923 16893//16893 16892//16892 -f 16923//16923 16892//16892 16924//16924 -f 16924//16924 16892//16892 16891//16891 -f 16924//16924 16891//16891 16925//16925 -f 16925//16925 16891//16891 16890//16890 -f 16925//16925 16890//16890 16926//16926 -f 16926//16926 16890//16890 16889//16889 -f 16926//16926 16889//16889 16927//16927 -f 16740//16740 16738//16738 16777//16777 -f 16777//16777 16738//16738 16736//16736 -f 16777//16777 16736//16736 16775//16775 -f 16775//16775 16736//16736 16734//16734 -f 16775//16775 16734//16734 16773//16773 -f 16773//16773 16734//16734 16732//16732 -f 16773//16773 16732//16732 16771//16771 -f 16771//16771 16732//16732 16730//16730 -f 16771//16771 16730//16730 16768//16768 -f 16768//16768 16730//16730 16729//16729 -f 16768//16768 16729//16729 16928//16928 -f 16928//16928 16729//16729 16901//16901 -f 16928//16928 16901//16901 16929//16929 -f 16929//16929 16901//16901 16900//16900 -f 16929//16929 16900//16900 16930//16930 -f 16930//16930 16900//16900 16899//16899 -f 16930//16930 16899//16899 16918//16918 -f 16918//16918 16899//16899 16898//16898 -f 16918//16918 16898//16898 16897//16897 -f 16889//16889 16888//16888 16927//16927 -f 16927//16927 16888//16888 16887//16887 -f 16927//16927 16887//16887 16931//16931 -f 16931//16931 16887//16887 16886//16886 -f 16931//16931 16886//16886 16932//16932 -f 16932//16932 16886//16886 16885//16885 -f 16932//16932 16885//16885 16933//16933 -f 16933//16933 16885//16885 16884//16884 -f 16933//16933 16884//16884 16803//16803 -f 16803//16803 16884//16884 16766//16766 -f 16803//16803 16766//16766 16801//16801 -f 16801//16801 16766//16766 16764//16764 -f 16801//16801 16764//16764 16799//16799 -f 16799//16799 16764//16764 16762//16762 -f 16799//16799 16762//16762 16797//16797 -f 16797//16797 16762//16762 16760//16760 -f 16797//16797 16760//16760 16795//16795 -f 16795//16795 16760//16760 16758//16758 -f 16795//16795 16758//16758 16756//16756 -f 16803//16803 16802//16802 16902//16902 -f 16803//16803 16902//16902 16933//16933 -f 16933//16933 16902//16902 16903//16903 -f 16933//16933 16903//16903 16932//16932 -f 16932//16932 16903//16903 16904//16904 -f 16932//16932 16904//16904 16931//16931 -f 16931//16931 16904//16904 16905//16905 -f 16931//16931 16905//16905 16927//16927 -f 16927//16927 16905//16905 16910//16910 -f 16927//16927 16910//16910 16926//16926 -f 16926//16926 16910//16910 16911//16911 -f 16926//16926 16911//16911 16925//16925 -f 16925//16925 16911//16911 16912//16912 -f 16925//16925 16912//16912 16924//16924 -f 16924//16924 16912//16912 16913//16913 -f 16924//16924 16913//16913 16923//16923 -f 16923//16923 16913//16913 16914//16914 -f 16923//16923 16914//16914 16922//16922 -f 16922//16922 16914//16914 16915//16915 -f 16922//16922 16915//16915 16921//16921 -f 16921//16921 16915//16915 16916//16916 -f 16921//16921 16916//16916 16920//16920 -f 16920//16920 16916//16916 16917//16917 -f 16920//16920 16917//16917 16919//16919 -f 16919//16919 16917//16917 16906//16906 -f 16919//16919 16906//16906 16918//16918 -f 16918//16918 16906//16906 16907//16907 -f 16918//16918 16907//16907 16930//16930 -f 16930//16930 16907//16907 16908//16908 -f 16930//16930 16908//16908 16929//16929 -f 16929//16929 16908//16908 16909//16909 -f 16929//16929 16909//16909 16928//16928 -f 16928//16928 16909//16909 16769//16769 -f 16928//16928 16769//16769 16768//16768 -f 16934//16934 16935//16935 16936//16936 -f 16936//16936 16935//16935 16937//16937 -f 16936//16936 16937//16937 16938//16938 -f 16938//16938 16937//16937 16939//16939 -f 16938//16938 16939//16939 16940//16940 -f 16940//16940 16939//16939 16941//16941 -f 16940//16940 16941//16941 16942//16942 -f 16942//16942 16941//16941 16943//16943 -f 16942//16942 16943//16943 16944//16944 -f 16944//16944 16943//16943 16945//16945 -f 16944//16944 16945//16945 16946//16946 -f 16946//16946 16945//16945 16947//16947 -f 16946//16946 16947//16947 16948//16948 -f 16948//16948 16947//16947 16949//16949 -f 16948//16948 16949//16949 16950//16950 -f 16950//16950 16949//16949 16951//16951 -f 16950//16950 16951//16951 16952//16952 -f 16952//16952 16951//16951 16953//16953 -f 16952//16952 16953//16953 16954//16954 -f 16954//16954 16953//16953 16955//16955 -f 16954//16954 16955//16955 16956//16956 -f 16956//16956 16955//16955 16957//16957 -f 16956//16956 16957//16957 16958//16958 -f 16958//16958 16957//16957 16959//16959 -f 16958//16958 16959//16959 16960//16960 -f 16960//16960 16959//16959 16961//16961 -f 16960//16960 16961//16961 16962//16962 -f 16962//16962 16961//16961 16963//16963 -f 16964//16964 16965//16965 16966//16966 -f 16964//16964 16966//16966 16967//16967 -f 16967//16967 16966//16966 16968//16968 -f 16967//16967 16968//16968 16969//16969 -f 16969//16969 16968//16968 16970//16970 -f 16969//16969 16970//16970 16971//16971 -f 16971//16971 16970//16970 16972//16972 -f 16971//16971 16972//16972 16973//16973 -f 16973//16973 16972//16972 16974//16974 -f 16973//16973 16974//16974 16975//16975 -f 16975//16975 16974//16974 16976//16976 -f 16975//16975 16976//16976 16977//16977 -f 16977//16977 16976//16976 16978//16978 -f 16977//16977 16978//16978 16979//16979 -f 16979//16979 16978//16978 16980//16980 -f 16979//16979 16980//16980 16981//16981 -f 16981//16981 16980//16980 16982//16982 -f 16981//16981 16982//16982 16983//16983 -f 16983//16983 16982//16982 16984//16984 -f 16983//16983 16984//16984 16985//16985 -f 16985//16985 16984//16984 16986//16986 -f 16985//16985 16986//16986 16987//16987 -f 16987//16987 16986//16986 16988//16988 -f 16987//16987 16988//16988 16989//16989 -f 16989//16989 16988//16988 16990//16990 -f 16989//16989 16990//16990 16991//16991 -f 16991//16991 16990//16990 16992//16992 -f 16991//16991 16992//16992 16993//16993 -f 16993//16993 16992//16992 16994//16994 -f 16993//16993 16994//16994 16995//16995 -f 16995//16995 16994//16994 16996//16996 -f 16995//16995 16996//16996 16997//16997 -f 16997//16997 16996//16996 16998//16998 -f 16997//16997 16998//16998 16999//16999 -f 16999//16999 16998//16998 17000//17000 -f 16999//16999 17000//17000 17001//17001 -f 17001//17001 17000//17000 17002//17002 -f 17001//17001 17002//17002 17003//17003 -f 17004//17004 17005//17005 17006//17006 -f 17004//17004 17006//17006 17007//17007 -f 17007//17007 17006//17006 17008//17008 -f 17007//17007 17008//17008 17009//17009 -f 17009//17009 17008//17008 17010//17010 -f 17009//17009 17010//17010 17011//17011 -f 17011//17011 17010//17010 17012//17012 -f 17011//17011 17012//17012 17013//17013 -f 17013//17013 17012//17012 17014//17014 -f 17013//17013 17014//17014 17015//17015 -f 17015//17015 17014//17014 17016//17016 -f 17015//17015 17016//17016 17017//17017 -f 17017//17017 17016//17016 17018//17018 -f 17017//17017 17018//17018 17019//17019 -f 17019//17019 17018//17018 17020//17020 -f 17019//17019 17020//17020 17021//17021 -f 17021//17021 17020//17020 17022//17022 -f 17021//17021 17022//17022 17023//17023 -f 17023//17023 17022//17022 17024//17024 -f 17023//17023 17024//17024 17025//17025 -f 17025//17025 17024//17024 17026//17026 -f 17025//17025 17026//17026 17027//17027 -f 17027//17027 17026//17026 17028//17028 -f 17027//17027 17028//17028 17029//17029 -f 17029//17029 17028//17028 17030//17030 -f 17029//17029 17030//17030 17031//17031 -f 17031//17031 17030//17030 17032//17032 -f 17031//17031 17032//17032 17033//17033 -f 17033//17033 17032//17032 17034//17034 -f 17033//17033 17034//17034 17035//17035 -f 17035//17035 17034//17034 17036//17036 -f 17035//17035 17036//17036 17037//17037 -f 17037//17037 17036//17036 17038//17038 -f 17037//17037 17038//17038 17039//17039 -f 17039//17039 17038//17038 17040//17040 -f 17039//17039 17040//17040 17041//17041 -f 17041//17041 17040//17040 17042//17042 -f 17041//17041 17042//17042 17043//17043 -f 17044//17044 17045//17045 17046//17046 -f 17044//17044 17046//17046 17047//17047 -f 17047//17047 17046//17046 17048//17048 -f 17047//17047 17048//17048 17049//17049 -f 17049//17049 17048//17048 17050//17050 -f 17049//17049 17050//17050 17051//17051 -f 17051//17051 17050//17050 17052//17052 -f 17051//17051 17052//17052 17053//17053 -f 17053//17053 17052//17052 17054//17054 -f 17053//17053 17054//17054 17055//17055 -f 17055//17055 17054//17054 17056//17056 -f 17055//17055 17056//17056 17057//17057 -f 17057//17057 17056//17056 17058//17058 -f 17057//17057 17058//17058 17059//17059 -f 17059//17059 17058//17058 17060//17060 -f 17059//17059 17060//17060 17061//17061 -f 17061//17061 17060//17060 17062//17062 -f 17061//17061 17062//17062 17063//17063 -f 17063//17063 17062//17062 17064//17064 -f 17063//17063 17064//17064 17065//17065 -f 17065//17065 17064//17064 17066//17066 -f 17065//17065 17066//17066 17067//17067 -f 17067//17067 17066//17066 17068//17068 -f 17067//17067 17068//17068 17069//17069 -f 17069//17069 17068//17068 17070//17070 -f 17069//17069 17070//17070 17071//17071 -f 17071//17071 17070//17070 17072//17072 -f 17071//17071 17072//17072 17073//17073 -f 17073//17073 17072//17072 17074//17074 -f 17073//17073 17074//17074 17075//17075 -f 17075//17075 17074//17074 17076//17076 -f 17075//17075 17076//17076 17077//17077 -f 17077//17077 17076//17076 17078//17078 -f 17077//17077 17078//17078 17079//17079 -f 16962//16962 16963//16963 17080//17080 -f 17080//17080 16963//16963 17081//17081 -f 17080//17080 17081//17081 17082//17082 -f 17082//17082 17081//17081 17083//17083 -f 17082//17082 17083//17083 17084//17084 -f 17084//17084 17083//17083 17085//17085 -f 17084//17084 17085//17085 17086//17086 -f 17086//17086 17085//17085 17087//17087 -f 17086//17086 17087//17087 17088//17088 -f 17088//17088 17087//17087 17089//17089 -f 17088//17088 17089//17089 17090//17090 -f 17090//17090 17089//17089 17091//17091 -f 17090//17090 17091//17091 17092//17092 -f 17092//17092 17091//17091 17093//17093 -f 17092//17092 17093//17093 17094//17094 -f 17094//17094 17093//17093 17095//17095 -f 17094//17094 17095//17095 17096//17096 -f 17096//17096 17095//17095 17097//17097 -f 17096//17096 17097//17097 17098//17098 -f 17098//17098 17097//17097 17099//17099 -f 17098//17098 17099//17099 17100//17100 -f 17100//17100 17099//17099 17101//17101 -f 17100//17100 17101//17101 17102//17102 -f 17102//17102 17101//17101 17103//17103 -f 17102//17102 17103//17103 17104//17104 -f 17104//17104 17103//17103 17105//17105 -f 17104//17104 17105//17105 16934//16934 -f 16934//16934 17105//17105 16935//16935 -f 17082//17082 16968//16968 17080//17080 -f 17080//17080 16968//16968 16966//16966 -f 17080//17080 16966//16966 16962//16962 -f 16962//16962 16966//16966 16965//16965 -f 16962//16962 16965//16965 16960//16960 -f 16938//16938 17106//17106 16936//16936 -f 16936//16936 17106//17106 17107//17107 -f 16936//16936 17107//17107 16934//16934 -f 16934//16934 17107//17107 17002//17002 -f 16934//16934 17002//17002 17104//17104 -f 17088//17088 16976//16976 17086//17086 -f 17086//17086 16976//16976 16974//16974 -f 17086//17086 16974//16974 17084//17084 -f 17084//17084 16974//16974 16972//16972 -f 17084//17084 16972//16972 17082//17082 -f 17082//17082 16972//16972 16970//16970 -f 17082//17082 16970//16970 16968//16968 -f 17002//17002 17000//17000 17104//17104 -f 17104//17104 17000//17000 16998//16998 -f 17104//17104 16998//16998 17102//17102 -f 17102//17102 16998//16998 16996//16996 -f 17102//17102 16996//16996 17100//17100 -f 17100//17100 16996//16996 16994//16994 -f 17100//17100 16994//16994 17098//17098 -f 16944//16944 17108//17108 16942//16942 -f 16942//16942 17108//17108 17109//17109 -f 16942//16942 17109//17109 16940//16940 -f 16940//16940 17109//17109 17110//17110 -f 16940//16940 17110//17110 16938//16938 -f 16938//16938 17110//17110 17111//17111 -f 16938//16938 17111//17111 17106//17106 -f 16948//16948 17112//17112 16946//16946 -f 16946//16946 17112//17112 17113//17113 -f 16946//16946 17113//17113 16944//16944 -f 16944//16944 17113//17113 17114//17114 -f 16944//16944 17114//17114 17108//17108 -f 17094//17094 16984//16984 17092//17092 -f 17092//17092 16984//16984 16982//16982 -f 17092//17092 16982//16982 17090//17090 -f 17090//17090 16982//16982 16980//16980 -f 17090//17090 16980//16980 17088//17088 -f 17088//17088 16980//16980 16978//16978 -f 17088//17088 16978//16978 16976//16976 -f 16994//16994 16992//16992 17098//17098 -f 17098//17098 16992//16992 16990//16990 -f 17098//17098 16990//16990 17096//17096 -f 17096//17096 16990//16990 16988//16988 -f 17096//17096 16988//16988 17094//17094 -f 17094//17094 16988//16988 16986//16986 -f 17094//17094 16986//16986 16984//16984 -f 16965//16965 17115//17115 16960//16960 -f 16960//16960 17115//17115 17116//17116 -f 16960//16960 17116//17116 16958//16958 -f 16958//16958 17116//17116 17117//17117 -f 16958//16958 17117//17117 16956//16956 -f 16956//16956 17117//17117 17118//17118 -f 16956//16956 17118//17118 16954//16954 -f 17118//17118 17119//17119 16954//16954 -f 16954//16954 17119//17119 17120//17120 -f 16954//16954 17120//17120 16952//16952 -f 16952//16952 17120//17120 17121//17121 -f 16952//16952 17121//17121 16950//16950 -f 16950//16950 17121//17121 17122//17122 -f 16950//16950 17122//17122 16948//16948 -f 16948//16948 17122//17122 17123//17123 -f 16948//16948 17123//17123 17112//17112 -f 17081//17081 17009//17009 17083//17083 -f 17083//17083 17009//17009 17011//17011 -f 17083//17083 17011//17011 17085//17085 -f 17085//17085 17011//17011 17013//17013 -f 17085//17085 17013//17013 17087//17087 -f 17103//17103 17039//17039 17105//17105 -f 17105//17105 17039//17039 17041//17041 -f 17105//17105 17041//17041 16935//16935 -f 16935//16935 17041//17041 17043//17043 -f 16935//16935 17043//17043 16937//16937 -f 17097//17097 17031//17031 17099//17099 -f 17099//17099 17031//17031 17033//17033 -f 17099//17099 17033//17033 17101//17101 -f 17101//17101 17033//17033 17035//17035 -f 17101//17101 17035//17035 17103//17103 -f 17103//17103 17035//17035 17037//17037 -f 17103//17103 17037//17037 17039//17039 -f 17013//17013 17015//17015 17087//17087 -f 17087//17087 17015//17015 17017//17017 -f 17087//17087 17017//17017 17089//17089 -f 17089//17089 17017//17017 17019//17019 -f 17089//17089 17019//17019 17091//17091 -f 17091//17091 17019//17019 17021//17021 -f 17091//17091 17021//17021 17093//17093 -f 17043//17043 17124//17124 16937//16937 -f 16937//16937 17124//17124 17125//17125 -f 16937//16937 17125//17125 16939//16939 -f 16939//16939 17125//17125 17126//17126 -f 16939//16939 17126//17126 16941//16941 -f 16941//16941 17126//17126 17127//17127 -f 16941//16941 17127//17127 16943//16943 -f 17021//17021 17023//17023 17093//17093 -f 17093//17093 17023//17023 17025//17025 -f 17093//17093 17025//17025 17095//17095 -f 17095//17095 17025//17025 17027//17027 -f 17095//17095 17027//17027 17097//17097 -f 17097//17097 17027//17027 17029//17029 -f 17097//17097 17029//17029 17031//17031 -f 16959//16959 17128//17128 16961//16961 -f 16961//16961 17128//17128 17129//17129 -f 16961//16961 17129//17129 16963//16963 -f 16963//16963 17129//17129 17004//17004 -f 16963//16963 17004//17004 17081//17081 -f 17081//17081 17004//17004 17007//17007 -f 17081//17081 17007//17007 17009//17009 -f 17127//17127 17130//17130 16943//16943 -f 16943//16943 17130//17130 17131//17131 -f 16943//16943 17131//17131 16945//16945 -f 16945//16945 17131//17131 17132//17132 -f 16945//16945 17132//17132 16947//16947 -f 16953//16953 17133//17133 16955//16955 -f 16955//16955 17133//17133 17134//17134 -f 16955//16955 17134//17134 16957//16957 -f 16957//16957 17134//17134 17135//17135 -f 16957//16957 17135//17135 16959//16959 -f 16959//16959 17135//17135 17136//17136 -f 16959//16959 17136//17136 17128//17128 -f 17132//17132 17137//17137 16947//16947 -f 16947//16947 17137//17137 17138//17138 -f 16947//16947 17138//17138 16949//16949 -f 16949//16949 17138//17138 17139//17139 -f 16949//16949 17139//17139 16951//16951 -f 16951//16951 17139//17139 17140//17140 -f 16951//16951 17140//17140 16953//16953 -f 16953//16953 17140//17140 17141//17141 -f 16953//16953 17141//17141 17133//17133 -f 17003//17003 17002//17002 17107//17107 -f 17003//17003 17107//17107 17142//17142 -f 17142//17142 17107//17107 17106//17106 -f 17142//17142 17106//17106 17143//17143 -f 17143//17143 17106//17106 17111//17111 -f 17143//17143 17111//17111 17144//17144 -f 17144//17144 17111//17111 17110//17110 -f 17144//17144 17110//17110 17145//17145 -f 17145//17145 17110//17110 17109//17109 -f 17145//17145 17109//17109 17146//17146 -f 17146//17146 17109//17109 17108//17108 -f 17146//17146 17108//17108 17147//17147 -f 17147//17147 17108//17108 17114//17114 -f 17147//17147 17114//17114 17148//17148 -f 17148//17148 17114//17114 17113//17113 -f 17148//17148 17113//17113 17149//17149 -f 17149//17149 17113//17113 17112//17112 -f 17149//17149 17112//17112 17150//17150 -f 17150//17150 17112//17112 17123//17123 -f 17150//17150 17123//17123 17151//17151 -f 17151//17151 17123//17123 17122//17122 -f 17151//17151 17122//17122 17152//17152 -f 17152//17152 17122//17122 17121//17121 -f 17152//17152 17121//17121 17153//17153 -f 17153//17153 17121//17121 17120//17120 -f 17153//17153 17120//17120 17154//17154 -f 17154//17154 17120//17120 17119//17119 -f 17154//17154 17119//17119 17155//17155 -f 17155//17155 17119//17119 17118//17118 -f 17155//17155 17118//17118 17156//17156 -f 17156//17156 17118//17118 17117//17117 -f 17156//17156 17117//17117 17157//17157 -f 17157//17157 17117//17117 17116//17116 -f 17157//17157 17116//17116 17158//17158 -f 17158//17158 17116//17116 17115//17115 -f 17158//17158 17115//17115 17159//17159 -f 17159//17159 17115//17115 16965//16965 -f 17159//17159 16965//16965 16964//16964 -f 17043//17043 17042//17042 17160//17160 -f 17043//17043 17160//17160 17124//17124 -f 17124//17124 17160//17160 17161//17161 -f 17124//17124 17161//17161 17125//17125 -f 17125//17125 17161//17161 17162//17162 -f 17125//17125 17162//17162 17126//17126 -f 17126//17126 17162//17162 17163//17163 -f 17126//17126 17163//17163 17127//17127 -f 17127//17127 17163//17163 17164//17164 -f 17127//17127 17164//17164 17130//17130 -f 17130//17130 17164//17164 17165//17165 -f 17130//17130 17165//17165 17131//17131 -f 17131//17131 17165//17165 17166//17166 -f 17131//17131 17166//17166 17132//17132 -f 17132//17132 17166//17166 17167//17167 -f 17132//17132 17167//17167 17137//17137 -f 17137//17137 17167//17167 17168//17168 -f 17137//17137 17168//17168 17138//17138 -f 17138//17138 17168//17168 17169//17169 -f 17138//17138 17169//17169 17139//17139 -f 17139//17139 17169//17169 17170//17170 -f 17139//17139 17170//17170 17140//17140 -f 17140//17140 17170//17170 17171//17171 -f 17140//17140 17171//17171 17141//17141 -f 17141//17141 17171//17171 17172//17172 -f 17141//17141 17172//17172 17133//17133 -f 17133//17133 17172//17172 17173//17173 -f 17133//17133 17173//17173 17134//17134 -f 17134//17134 17173//17173 17174//17174 -f 17134//17134 17174//17174 17135//17135 -f 17135//17135 17174//17174 17175//17175 -f 17135//17135 17175//17175 17136//17136 -f 17136//17136 17175//17175 17176//17176 -f 17136//17136 17176//17176 17128//17128 -f 17128//17128 17176//17176 17177//17177 -f 17128//17128 17177//17177 17129//17129 -f 17129//17129 17177//17177 17005//17005 -f 17129//17129 17005//17005 17004//17004 -f 17178//17178 17146//17146 17179//17179 -f 17179//17179 17146//17146 17147//17147 -f 17179//17179 17147//17147 17180//17180 -f 17180//17180 17147//17147 17148//17148 -f 17180//17180 17148//17148 17181//17181 -f 17181//17181 17148//17148 17149//17149 -f 17181//17181 17149//17149 17182//17182 -f 17182//17182 17149//17149 17150//17150 -f 17182//17182 17150//17150 17183//17183 -f 17183//17183 17150//17150 17151//17151 -f 17183//17183 17151//17151 17184//17184 -f 17184//17184 17151//17151 17152//17152 -f 17184//17184 17152//17152 17185//17185 -f 17185//17185 17152//17152 17153//17153 -f 17185//17185 17153//17153 17186//17186 -f 17186//17186 17153//17153 17154//17154 -f 17186//17186 17154//17154 17187//17187 -f 17154//17154 17155//17155 17187//17187 -f 17187//17187 17155//17155 17156//17156 -f 17187//17187 17156//17156 17188//17188 -f 17188//17188 17156//17156 17157//17157 -f 17188//17188 17157//17157 17189//17189 -f 17189//17189 17157//17157 17158//17158 -f 17189//17189 17158//17158 17190//17190 -f 17190//17190 17158//17158 17159//17159 -f 17190//17190 17159//17159 17045//17045 -f 17045//17045 17159//17159 16964//16964 -f 17045//17045 16964//16964 17046//17046 -f 17046//17046 16964//16964 16967//16967 -f 17046//17046 16967//16967 17048//17048 -f 17048//17048 16967//16967 16969//16969 -f 17048//17048 16969//16969 17050//17050 -f 17050//17050 16969//16969 16971//16971 -f 17050//17050 16971//16971 17052//17052 -f 17070//17070 16995//16995 17072//17072 -f 17072//17072 16995//16995 16997//16997 -f 17072//17072 16997//16997 17074//17074 -f 17074//17074 16997//16997 16999//16999 -f 17074//17074 16999//16999 17076//17076 -f 17076//17076 16999//16999 17001//17001 -f 17076//17076 17001//17001 17078//17078 -f 17078//17078 17001//17001 17003//17003 -f 17078//17078 17003//17003 17191//17191 -f 17191//17191 17003//17003 17142//17142 -f 17191//17191 17142//17142 17192//17192 -f 17192//17192 17142//17142 17143//17143 -f 17192//17192 17143//17143 17193//17193 -f 17193//17193 17143//17143 17144//17144 -f 17193//17193 17144//17144 17178//17178 -f 17178//17178 17144//17144 17145//17145 -f 17178//17178 17145//17145 17146//17146 -f 16971//16971 16973//16973 17052//17052 -f 17052//17052 16973//16973 16975//16975 -f 17052//17052 16975//16975 17054//17054 -f 17054//17054 16975//16975 16977//16977 -f 17054//17054 16977//16977 17056//17056 -f 17056//17056 16977//16977 16979//16979 -f 17056//17056 16979//16979 17058//17058 -f 17058//17058 16979//16979 16981//16981 -f 17058//17058 16981//16981 17060//17060 -f 17060//17060 16981//16981 16983//16983 -f 17060//17060 16983//16983 17062//17062 -f 17062//17062 16983//16983 16985//16985 -f 17062//17062 16985//16985 17064//17064 -f 17064//17064 16985//16985 16987//16987 -f 17064//17064 16987//16987 17066//17066 -f 17066//17066 16987//16987 16989//16989 -f 17066//17066 16989//16989 17068//17068 -f 17068//17068 16989//16989 16991//16991 -f 17068//17068 16991//16991 17070//17070 -f 17070//17070 16991//16991 16993//16993 -f 17070//17070 16993//16993 16995//16995 -f 17194//17194 17173//17173 17195//17195 -f 17195//17195 17173//17173 17172//17172 -f 17195//17195 17172//17172 17196//17196 -f 17196//17196 17172//17172 17171//17171 -f 17196//17196 17171//17171 17197//17197 -f 17197//17197 17171//17171 17170//17170 -f 17197//17197 17170//17170 17198//17198 -f 17198//17198 17170//17170 17169//17169 -f 17198//17198 17169//17169 17199//17199 -f 17199//17199 17169//17169 17168//17168 -f 17199//17199 17168//17168 17200//17200 -f 17200//17200 17168//17168 17167//17167 -f 17200//17200 17167//17167 17201//17201 -f 17201//17201 17167//17167 17166//17166 -f 17201//17201 17166//17166 17202//17202 -f 17202//17202 17166//17166 17165//17165 -f 17202//17202 17165//17165 17203//17203 -f 17053//17053 17012//17012 17051//17051 -f 17051//17051 17012//17012 17010//17010 -f 17051//17051 17010//17010 17049//17049 -f 17049//17049 17010//17010 17008//17008 -f 17049//17049 17008//17008 17047//17047 -f 17047//17047 17008//17008 17006//17006 -f 17047//17047 17006//17006 17044//17044 -f 17044//17044 17006//17006 17005//17005 -f 17044//17044 17005//17005 17204//17204 -f 17204//17204 17005//17005 17177//17177 -f 17204//17204 17177//17177 17205//17205 -f 17205//17205 17177//17177 17176//17176 -f 17205//17205 17176//17176 17206//17206 -f 17206//17206 17176//17176 17175//17175 -f 17206//17206 17175//17175 17194//17194 -f 17194//17194 17175//17175 17174//17174 -f 17194//17194 17174//17174 17173//17173 -f 17071//17071 17032//17032 17069//17069 -f 17069//17069 17032//17032 17030//17030 -f 17069//17069 17030//17030 17067//17067 -f 17067//17067 17030//17030 17028//17028 -f 17067//17067 17028//17028 17065//17065 -f 17065//17065 17028//17028 17026//17026 -f 17065//17065 17026//17026 17063//17063 -f 17063//17063 17026//17026 17024//17024 -f 17063//17063 17024//17024 17061//17061 -f 17061//17061 17024//17024 17022//17022 -f 17061//17061 17022//17022 17059//17059 -f 17059//17059 17022//17022 17020//17020 -f 17059//17059 17020//17020 17057//17057 -f 17057//17057 17020//17020 17018//17018 -f 17057//17057 17018//17018 17055//17055 -f 17055//17055 17018//17018 17016//17016 -f 17055//17055 17016//17016 17053//17053 -f 17053//17053 17016//17016 17014//17014 -f 17053//17053 17014//17014 17012//17012 -f 17165//17165 17164//17164 17203//17203 -f 17203//17203 17164//17164 17163//17163 -f 17203//17203 17163//17163 17207//17207 -f 17207//17207 17163//17163 17162//17162 -f 17207//17207 17162//17162 17208//17208 -f 17208//17208 17162//17162 17161//17161 -f 17208//17208 17161//17161 17209//17209 -f 17209//17209 17161//17161 17160//17160 -f 17209//17209 17160//17160 17079//17079 -f 17079//17079 17160//17160 17042//17042 -f 17079//17079 17042//17042 17077//17077 -f 17077//17077 17042//17042 17040//17040 -f 17077//17077 17040//17040 17075//17075 -f 17075//17075 17040//17040 17038//17038 -f 17075//17075 17038//17038 17073//17073 -f 17073//17073 17038//17038 17036//17036 -f 17073//17073 17036//17036 17071//17071 -f 17071//17071 17036//17036 17034//17034 -f 17071//17071 17034//17034 17032//17032 -f 17079//17079 17078//17078 17191//17191 -f 17079//17079 17191//17191 17209//17209 -f 17209//17209 17191//17191 17192//17192 -f 17209//17209 17192//17192 17208//17208 -f 17208//17208 17192//17192 17193//17193 -f 17208//17208 17193//17193 17207//17207 -f 17207//17207 17193//17193 17178//17178 -f 17207//17207 17178//17178 17203//17203 -f 17203//17203 17178//17178 17179//17179 -f 17203//17203 17179//17179 17202//17202 -f 17202//17202 17179//17179 17180//17180 -f 17202//17202 17180//17180 17201//17201 -f 17201//17201 17180//17180 17181//17181 -f 17201//17201 17181//17181 17200//17200 -f 17200//17200 17181//17181 17182//17182 -f 17200//17200 17182//17182 17199//17199 -f 17199//17199 17182//17182 17183//17183 -f 17199//17199 17183//17183 17198//17198 -f 17198//17198 17183//17183 17184//17184 -f 17198//17198 17184//17184 17197//17197 -f 17197//17197 17184//17184 17185//17185 -f 17197//17197 17185//17185 17196//17196 -f 17196//17196 17185//17185 17186//17186 -f 17196//17196 17186//17186 17195//17195 -f 17195//17195 17186//17186 17187//17187 -f 17195//17195 17187//17187 17194//17194 -f 17194//17194 17187//17187 17188//17188 -f 17194//17194 17188//17188 17206//17206 -f 17206//17206 17188//17188 17189//17189 -f 17206//17206 17189//17189 17205//17205 -f 17205//17205 17189//17189 17190//17190 -f 17205//17205 17190//17190 17204//17204 -f 17204//17204 17190//17190 17045//17045 -f 17204//17204 17045//17045 17044//17044 -f 17210//17210 17211//17211 17212//17212 -f 17212//17212 17211//17211 17213//17213 -f 17212//17212 17213//17213 17214//17214 -f 17214//17214 17213//17213 17215//17215 -f 17214//17214 17215//17215 17216//17216 -f 17216//17216 17215//17215 17217//17217 -f 17216//17216 17217//17217 17218//17218 -f 17218//17218 17217//17217 17219//17219 -f 17218//17218 17219//17219 17220//17220 -f 17220//17220 17219//17219 17221//17221 -f 17220//17220 17221//17221 17222//17222 -f 17222//17222 17221//17221 17223//17223 -f 17222//17222 17223//17223 17224//17224 -f 17224//17224 17223//17223 17225//17225 -f 17224//17224 17225//17225 17226//17226 -f 17226//17226 17225//17225 17227//17227 -f 17226//17226 17227//17227 17228//17228 -f 17228//17228 17227//17227 17229//17229 -f 17228//17228 17229//17229 17230//17230 -f 17230//17230 17229//17229 17231//17231 -f 17230//17230 17231//17231 17232//17232 -f 17232//17232 17231//17231 17233//17233 -f 17232//17232 17233//17233 17234//17234 -f 17234//17234 17233//17233 17235//17235 -f 17234//17234 17235//17235 17236//17236 -f 17236//17236 17235//17235 17237//17237 -f 17236//17236 17237//17237 17238//17238 -f 17238//17238 17237//17237 17239//17239 -f 17240//17240 1127//1127 17241//17241 -f 17240//17240 17241//17241 17242//17242 -f 17242//17242 17241//17241 17243//17243 -f 17242//17242 17243//17243 17244//17244 -f 17244//17244 17243//17243 17245//17245 -f 17244//17244 17245//17245 17246//17246 -f 17246//17246 17245//17245 17247//17247 -f 17246//17246 17247//17247 17248//17248 -f 17248//17248 17247//17247 17249//17249 -f 17248//17248 17249//17249 17250//17250 -f 17250//17250 17249//17249 17251//17251 -f 17250//17250 17251//17251 17252//17252 -f 17252//17252 17251//17251 17253//17253 -f 17252//17252 17253//17253 17254//17254 -f 17254//17254 17253//17253 17255//17255 -f 17254//17254 17255//17255 17256//17256 -f 17256//17256 17255//17255 17257//17257 -f 17256//17256 17257//17257 17258//17258 -f 17258//17258 17257//17257 17259//17259 -f 17258//17258 17259//17259 17260//17260 -f 17260//17260 17259//17259 17261//17261 -f 17260//17260 17261//17261 17262//17262 -f 17262//17262 17261//17261 17263//17263 -f 17262//17262 17263//17263 17264//17264 -f 17264//17264 17263//17263 17265//17265 -f 17264//17264 17265//17265 17266//17266 -f 17266//17266 17265//17265 17267//17267 -f 17266//17266 17267//17267 17268//17268 -f 17268//17268 17267//17267 17269//17269 -f 17268//17268 17269//17269 17270//17270 -f 17270//17270 17269//17269 17271//17271 -f 17270//17270 17271//17271 17272//17272 -f 17272//17272 17271//17271 17273//17273 -f 17272//17272 17273//17273 17274//17274 -f 17274//17274 17273//17273 17275//17275 -f 17274//17274 17275//17275 17276//17276 -f 17276//17276 17275//17275 1115//1115 -f 17276//17276 1115//1115 17277//17277 -f 1128//1128 17278//17278 17279//17279 -f 1128//1128 17279//17279 17280//17280 -f 17280//17280 17279//17279 17281//17281 -f 17280//17280 17281//17281 17282//17282 -f 17282//17282 17281//17281 17283//17283 -f 17282//17282 17283//17283 17284//17284 -f 17284//17284 17283//17283 17285//17285 -f 17284//17284 17285//17285 17286//17286 -f 17286//17286 17285//17285 17287//17287 -f 17286//17286 17287//17287 17288//17288 -f 17288//17288 17287//17287 17289//17289 -f 17288//17288 17289//17289 17290//17290 -f 17290//17290 17289//17289 17291//17291 -f 17290//17290 17291//17291 17292//17292 -f 17292//17292 17291//17291 17293//17293 -f 17292//17292 17293//17293 17294//17294 -f 17294//17294 17293//17293 17295//17295 -f 17294//17294 17295//17295 17296//17296 -f 17296//17296 17295//17295 17297//17297 -f 17296//17296 17297//17297 17298//17298 -f 17298//17298 17297//17297 17299//17299 -f 17298//17298 17299//17299 17300//17300 -f 17300//17300 17299//17299 17301//17301 -f 17300//17300 17301//17301 17302//17302 -f 17302//17302 17301//17301 17303//17303 -f 17302//17302 17303//17303 17304//17304 -f 17304//17304 17303//17303 17305//17305 -f 17304//17304 17305//17305 17306//17306 -f 17306//17306 17305//17305 17307//17307 -f 17306//17306 17307//17307 17308//17308 -f 17308//17308 17307//17307 17309//17309 -f 17308//17308 17309//17309 17310//17310 -f 17310//17310 17309//17309 17311//17311 -f 17310//17310 17311//17311 17312//17312 -f 17312//17312 17311//17311 17313//17313 -f 17312//17312 17313//17313 17314//17314 -f 17314//17314 17313//17313 17315//17315 -f 17314//17314 17315//17315 1116//1116 -f 17316//17316 17317//17317 17318//17318 -f 17316//17316 17318//17318 17319//17319 -f 17319//17319 17318//17318 17320//17320 -f 17319//17319 17320//17320 17321//17321 -f 17321//17321 17320//17320 17322//17322 -f 17321//17321 17322//17322 17323//17323 -f 17323//17323 17322//17322 17324//17324 -f 17323//17323 17324//17324 17325//17325 -f 17325//17325 17324//17324 17326//17326 -f 17325//17325 17326//17326 17327//17327 -f 17327//17327 17326//17326 17328//17328 -f 17327//17327 17328//17328 17329//17329 -f 17329//17329 17328//17328 17330//17330 -f 17329//17329 17330//17330 17331//17331 -f 17331//17331 17330//17330 17332//17332 -f 17331//17331 17332//17332 17333//17333 -f 17333//17333 17332//17332 17334//17334 -f 17333//17333 17334//17334 17335//17335 -f 17335//17335 17334//17334 17336//17336 -f 17335//17335 17336//17336 17337//17337 -f 17337//17337 17336//17336 17338//17338 -f 17337//17337 17338//17338 17339//17339 -f 17339//17339 17338//17338 17340//17340 -f 17339//17339 17340//17340 17341//17341 -f 17341//17341 17340//17340 17342//17342 -f 17341//17341 17342//17342 17343//17343 -f 17343//17343 17342//17342 17344//17344 -f 17343//17343 17344//17344 17345//17345 -f 17345//17345 17344//17344 17346//17346 -f 17345//17345 17346//17346 17347//17347 -f 17347//17347 17346//17346 17348//17348 -f 17347//17347 17348//17348 17349//17349 -f 17349//17349 17348//17348 17350//17350 -f 17349//17349 17350//17350 17351//17351 -f 17238//17238 17239//17239 17352//17352 -f 17352//17352 17239//17239 17353//17353 -f 17352//17352 17353//17353 17354//17354 -f 17354//17354 17353//17353 17355//17355 -f 17354//17354 17355//17355 17356//17356 -f 17356//17356 17355//17355 17357//17357 -f 17356//17356 17357//17357 17358//17358 -f 17358//17358 17357//17357 17359//17359 -f 17358//17358 17359//17359 17360//17360 -f 17360//17360 17359//17359 17361//17361 -f 17360//17360 17361//17361 17362//17362 -f 17362//17362 17361//17361 17363//17363 -f 17362//17362 17363//17363 17364//17364 -f 17364//17364 17363//17363 17365//17365 -f 17364//17364 17365//17365 17366//17366 -f 17366//17366 17365//17365 17367//17367 -f 17366//17366 17367//17367 17368//17368 -f 17368//17368 17367//17367 17369//17369 -f 17368//17368 17369//17369 17370//17370 -f 17370//17370 17369//17369 17371//17371 -f 17370//17370 17371//17371 17372//17372 -f 17372//17372 17371//17371 17373//17373 -f 17372//17372 17373//17373 17374//17374 -f 17374//17374 17373//17373 17375//17375 -f 17374//17374 17375//17375 17376//17376 -f 17376//17376 17375//17375 17377//17377 -f 17376//17376 17377//17377 17210//17210 -f 17210//17210 17377//17377 17211//17211 -f 17214//17214 17378//17378 17212//17212 -f 17212//17212 17378//17378 17379//17379 -f 17212//17212 17379//17379 17210//17210 -f 17210//17210 17379//17379 1115//1115 -f 17210//17210 1115//1115 17376//17376 -f 17226//17226 17380//17380 17224//17224 -f 17224//17224 17380//17380 17381//17381 -f 17224//17224 17381//17381 17222//17222 -f 17222//17222 17381//17381 17382//17382 -f 17222//17222 17382//17382 17220//17220 -f 17366//17366 17259//17259 17364//17364 -f 17364//17364 17259//17259 17257//17257 -f 17364//17364 17257//17257 17362//17362 -f 17362//17362 17257//17257 17255//17255 -f 17362//17362 17255//17255 17360//17360 -f 1115//1115 17275//17275 17376//17376 -f 17376//17376 17275//17275 17273//17273 -f 17376//17376 17273//17273 17374//17374 -f 17374//17374 17273//17273 17271//17271 -f 17374//17374 17271//17271 17372//17372 -f 17372//17372 17271//17271 17269//17269 -f 17372//17372 17269//17269 17370//17370 -f 17382//17382 17383//17383 17220//17220 -f 17220//17220 17383//17383 17384//17384 -f 17220//17220 17384//17384 17218//17218 -f 17218//17218 17384//17384 17385//17385 -f 17218//17218 17385//17385 17216//17216 -f 17216//17216 17385//17385 17386//17386 -f 17216//17216 17386//17386 17214//17214 -f 17214//17214 17386//17386 17387//17387 -f 17214//17214 17387//17387 17378//17378 -f 17269//17269 17267//17267 17370//17370 -f 17370//17370 17267//17267 17265//17265 -f 17370//17370 17265//17265 17368//17368 -f 17368//17368 17265//17265 17263//17263 -f 17368//17368 17263//17263 17366//17366 -f 17366//17366 17263//17263 17261//17261 -f 17366//17366 17261//17261 17259//17259 -f 17230//17230 17388//17388 17228//17228 -f 17228//17228 17388//17388 17389//17389 -f 17228//17228 17389//17389 17226//17226 -f 17226//17226 17389//17389 17390//17390 -f 17226//17226 17390//17390 17380//17380 -f 17236//17236 17391//17391 17234//17234 -f 17234//17234 17391//17391 17392//17392 -f 17234//17234 17392//17392 17232//17232 -f 17232//17232 17392//17392 17393//17393 -f 17232//17232 17393//17393 17230//17230 -f 17230//17230 17393//17393 17394//17394 -f 17230//17230 17394//17394 17388//17388 -f 17354//17354 17243//17243 17352//17352 -f 17352//17352 17243//17243 17241//17241 -f 17352//17352 17241//17241 17238//17238 -f 17238//17238 17241//17241 1127//1127 -f 17238//17238 1127//1127 17236//17236 -f 17236//17236 1127//1127 17395//17395 -f 17236//17236 17395//17395 17391//17391 -f 17255//17255 17253//17253 17360//17360 -f 17360//17360 17253//17253 17251//17251 -f 17360//17360 17251//17251 17358//17358 -f 17358//17358 17251//17251 17249//17249 -f 17358//17358 17249//17249 17356//17356 -f 17356//17356 17249//17249 17247//17247 -f 17356//17356 17247//17247 17354//17354 -f 17354//17354 17247//17247 17245//17245 -f 17354//17354 17245//17245 17243//17243 -f 17235//17235 17396//17396 17237//17237 -f 17237//17237 17396//17396 17397//17397 -f 17237//17237 17397//17397 17239//17239 -f 17239//17239 17397//17397 1128//1128 -f 17239//17239 1128//1128 17353//17353 -f 17223//17223 17398//17398 17225//17225 -f 17225//17225 17398//17398 17399//17399 -f 17225//17225 17399//17399 17227//17227 -f 17227//17227 17399//17399 17400//17400 -f 17227//17227 17400//17400 17229//17229 -f 17400//17400 17401//17401 17229//17229 -f 17229//17229 17401//17401 17402//17402 -f 17229//17229 17402//17402 17231//17231 -f 17231//17231 17402//17402 17403//17403 -f 17231//17231 17403//17403 17233//17233 -f 17233//17233 17403//17403 17404//17404 -f 17233//17233 17404//17404 17235//17235 -f 17235//17235 17404//17404 17405//17405 -f 17235//17235 17405//17405 17396//17396 -f 17375//17375 17312//17312 17377//17377 -f 17377//17377 17312//17312 17314//17314 -f 17377//17377 17314//17314 17211//17211 -f 17211//17211 17314//17314 1116//1116 -f 17211//17211 1116//1116 17213//17213 -f 17219//17219 17406//17406 17221//17221 -f 17221//17221 17406//17406 17407//17407 -f 17221//17221 17407//17407 17223//17223 -f 17223//17223 17407//17407 17408//17408 -f 17223//17223 17408//17408 17398//17398 -f 1116//1116 17409//17409 17213//17213 -f 17213//17213 17409//17409 17410//17410 -f 17213//17213 17410//17410 17215//17215 -f 17215//17215 17410//17410 17411//17411 -f 17215//17215 17411//17411 17217//17217 -f 17217//17217 17411//17411 17412//17412 -f 17217//17217 17412//17412 17219//17219 -f 17219//17219 17412//17412 17413//17413 -f 17219//17219 17413//17413 17406//17406 -f 17369//17369 17304//17304 17371//17371 -f 17371//17371 17304//17304 17306//17306 -f 17371//17371 17306//17306 17373//17373 -f 17373//17373 17306//17306 17308//17308 -f 17373//17373 17308//17308 17375//17375 -f 17375//17375 17308//17308 17310//17310 -f 17375//17375 17310//17310 17312//17312 -f 17363//17363 17296//17296 17365//17365 -f 17365//17365 17296//17296 17298//17298 -f 17365//17365 17298//17298 17367//17367 -f 17367//17367 17298//17298 17300//17300 -f 17367//17367 17300//17300 17369//17369 -f 17369//17369 17300//17300 17302//17302 -f 17369//17369 17302//17302 17304//17304 -f 1128//1128 17280//17280 17353//17353 -f 17353//17353 17280//17280 17282//17282 -f 17353//17353 17282//17282 17355//17355 -f 17355//17355 17282//17282 17284//17284 -f 17355//17355 17284//17284 17357//17357 -f 17357//17357 17284//17284 17286//17286 -f 17357//17357 17286//17286 17359//17359 -f 17286//17286 17288//17288 17359//17359 -f 17359//17359 17288//17288 17290//17290 -f 17359//17359 17290//17290 17361//17361 -f 17361//17361 17290//17290 17292//17292 -f 17361//17361 17292//17292 17363//17363 -f 17363//17363 17292//17292 17294//17294 -f 17363//17363 17294//17294 17296//17296 -f 17277//17277 1115//1115 17379//17379 -f 17277//17277 17379//17379 17414//17414 -f 17414//17414 17379//17379 17378//17378 -f 17414//17414 17378//17378 17415//17415 -f 17415//17415 17378//17378 17387//17387 -f 17415//17415 17387//17387 17416//17416 -f 17416//17416 17387//17387 17386//17386 -f 17416//17416 17386//17386 17417//17417 -f 17417//17417 17386//17386 17385//17385 -f 17417//17417 17385//17385 17418//17418 -f 17418//17418 17385//17385 17384//17384 -f 17418//17418 17384//17384 17419//17419 -f 17419//17419 17384//17384 17383//17383 -f 17419//17419 17383//17383 17420//17420 -f 17420//17420 17383//17383 17382//17382 -f 17420//17420 17382//17382 17421//17421 -f 17421//17421 17382//17382 17381//17381 -f 17421//17421 17381//17381 17422//17422 -f 17422//17422 17381//17381 17380//17380 -f 17422//17422 17380//17380 17423//17423 -f 17423//17423 17380//17380 17390//17390 -f 17423//17423 17390//17390 17424//17424 -f 17424//17424 17390//17390 17389//17389 -f 17424//17424 17389//17389 17425//17425 -f 17425//17425 17389//17389 17388//17388 -f 17425//17425 17388//17388 17426//17426 -f 17426//17426 17388//17388 17394//17394 -f 17426//17426 17394//17394 17427//17427 -f 17427//17427 17394//17394 17393//17393 -f 17427//17427 17393//17393 17428//17428 -f 17428//17428 17393//17393 17392//17392 -f 17428//17428 17392//17392 17429//17429 -f 17429//17429 17392//17392 17391//17391 -f 17429//17429 17391//17391 17430//17430 -f 17430//17430 17391//17391 17395//17395 -f 17430//17430 17395//17395 17431//17431 -f 17431//17431 17395//17395 1127//1127 -f 17431//17431 1127//1127 17240//17240 -f 1116//1116 17315//17315 17432//17432 -f 1116//1116 17432//17432 17409//17409 -f 17409//17409 17432//17432 17433//17433 -f 17409//17409 17433//17433 17410//17410 -f 17410//17410 17433//17433 17434//17434 -f 17410//17410 17434//17434 17411//17411 -f 17411//17411 17434//17434 17435//17435 -f 17411//17411 17435//17435 17412//17412 -f 17412//17412 17435//17435 17436//17436 -f 17412//17412 17436//17436 17413//17413 -f 17413//17413 17436//17436 17437//17437 -f 17413//17413 17437//17437 17406//17406 -f 17406//17406 17437//17437 17438//17438 -f 17406//17406 17438//17438 17407//17407 -f 17407//17407 17438//17438 17439//17439 -f 17407//17407 17439//17439 17408//17408 -f 17408//17408 17439//17439 17440//17440 -f 17408//17408 17440//17440 17398//17398 -f 17398//17398 17440//17440 17441//17441 -f 17398//17398 17441//17441 17399//17399 -f 17399//17399 17441//17441 17442//17442 -f 17399//17399 17442//17442 17400//17400 -f 17400//17400 17442//17442 17443//17443 -f 17400//17400 17443//17443 17401//17401 -f 17401//17401 17443//17443 17444//17444 -f 17401//17401 17444//17444 17402//17402 -f 17402//17402 17444//17444 17445//17445 -f 17402//17402 17445//17445 17403//17403 -f 17403//17403 17445//17445 17446//17446 -f 17403//17403 17446//17446 17404//17404 -f 17404//17404 17446//17446 17447//17447 -f 17404//17404 17447//17447 17405//17405 -f 17405//17405 17447//17447 17448//17448 -f 17405//17405 17448//17448 17396//17396 -f 17396//17396 17448//17448 17449//17449 -f 17396//17396 17449//17449 17397//17397 -f 17397//17397 17449//17449 17278//17278 -f 17397//17397 17278//17278 1128//1128 -f 17450//17450 17428//17428 17451//17451 -f 17451//17451 17428//17428 17429//17429 -f 17451//17451 17429//17429 17452//17452 -f 17452//17452 17429//17429 17430//17430 -f 17452//17452 17430//17430 17453//17453 -f 17453//17453 17430//17430 17431//17431 -f 17453//17453 17431//17431 17317//17317 -f 17317//17317 17431//17431 17240//17240 -f 17317//17317 17240//17240 17318//17318 -f 17318//17318 17240//17240 17242//17242 -f 17318//17318 17242//17242 17320//17320 -f 17320//17320 17242//17242 17244//17244 -f 17320//17320 17244//17244 17322//17322 -f 17322//17322 17244//17244 17246//17246 -f 17322//17322 17246//17246 17324//17324 -f 17246//17246 17248//17248 17324//17324 -f 17324//17324 17248//17248 17250//17250 -f 17324//17324 17250//17250 17326//17326 -f 17326//17326 17250//17250 17252//17252 -f 17326//17326 17252//17252 17328//17328 -f 17328//17328 17252//17252 17254//17254 -f 17328//17328 17254//17254 17330//17330 -f 17330//17330 17254//17254 17256//17256 -f 17330//17330 17256//17256 17332//17332 -f 17332//17332 17256//17256 17258//17258 -f 17332//17332 17258//17258 17334//17334 -f 17334//17334 17258//17258 17260//17260 -f 17334//17334 17260//17260 17336//17336 -f 17336//17336 17260//17260 17262//17262 -f 17336//17336 17262//17262 17338//17338 -f 17338//17338 17262//17262 17264//17264 -f 17338//17338 17264//17264 17340//17340 -f 17340//17340 17264//17264 17266//17266 -f 17340//17340 17266//17266 17342//17342 -f 17454//17454 17418//17418 17455//17455 -f 17455//17455 17418//17418 17419//17419 -f 17455//17455 17419//17419 17456//17456 -f 17456//17456 17419//17419 17420//17420 -f 17456//17456 17420//17420 17457//17457 -f 17457//17457 17420//17420 17421//17421 -f 17457//17457 17421//17421 17458//17458 -f 17458//17458 17421//17421 17422//17422 -f 17458//17458 17422//17422 17459//17459 -f 17459//17459 17422//17422 17423//17423 -f 17459//17459 17423//17423 17460//17460 -f 17460//17460 17423//17423 17424//17424 -f 17460//17460 17424//17424 17461//17461 -f 17461//17461 17424//17424 17425//17425 -f 17461//17461 17425//17425 17462//17462 -f 17462//17462 17425//17425 17426//17426 -f 17462//17462 17426//17426 17450//17450 -f 17450//17450 17426//17426 17427//17427 -f 17450//17450 17427//17427 17428//17428 -f 17266//17266 17268//17268 17342//17342 -f 17342//17342 17268//17268 17270//17270 -f 17342//17342 17270//17270 17344//17344 -f 17344//17344 17270//17270 17272//17272 -f 17344//17344 17272//17272 17346//17346 -f 17346//17346 17272//17272 17274//17274 -f 17346//17346 17274//17274 17348//17348 -f 17348//17348 17274//17274 17276//17276 -f 17348//17348 17276//17276 17350//17350 -f 17350//17350 17276//17276 17277//17277 -f 17350//17350 17277//17277 17463//17463 -f 17463//17463 17277//17277 17414//17414 -f 17463//17463 17414//17414 17464//17464 -f 17464//17464 17414//17414 17415//17415 -f 17464//17464 17415//17415 17465//17465 -f 17465//17465 17415//17415 17416//17416 -f 17465//17465 17416//17416 17454//17454 -f 17454//17454 17416//17416 17417//17417 -f 17454//17454 17417//17417 17418//17418 -f 17466//17466 17445//17445 17467//17467 -f 17467//17467 17445//17445 17444//17444 -f 17467//17467 17444//17444 17468//17468 -f 17468//17468 17444//17444 17443//17443 -f 17468//17468 17443//17443 17469//17469 -f 17469//17469 17443//17443 17442//17442 -f 17469//17469 17442//17442 17470//17470 -f 17470//17470 17442//17442 17441//17441 -f 17470//17470 17441//17441 17471//17471 -f 17471//17471 17441//17441 17440//17440 -f 17471//17471 17440//17440 17472//17472 -f 17472//17472 17440//17440 17439//17439 -f 17472//17472 17439//17439 17473//17473 -f 17473//17473 17439//17439 17438//17438 -f 17473//17473 17438//17438 17474//17474 -f 17474//17474 17438//17438 17437//17437 -f 17474//17474 17437//17437 17475//17475 -f 17343//17343 17305//17305 17341//17341 -f 17341//17341 17305//17305 17303//17303 -f 17341//17341 17303//17303 17339//17339 -f 17339//17339 17303//17303 17301//17301 -f 17339//17339 17301//17301 17337//17337 -f 17337//17337 17301//17301 17299//17299 -f 17337//17337 17299//17299 17335//17335 -f 17335//17335 17299//17299 17297//17297 -f 17335//17335 17297//17297 17333//17333 -f 17333//17333 17297//17297 17295//17295 -f 17333//17333 17295//17295 17331//17331 -f 17331//17331 17295//17295 17293//17293 -f 17331//17331 17293//17293 17329//17329 -f 17329//17329 17293//17293 17291//17291 -f 17329//17329 17291//17291 17327//17327 -f 17327//17327 17291//17291 17289//17289 -f 17327//17327 17289//17289 17325//17325 -f 17437//17437 17436//17436 17475//17475 -f 17475//17475 17436//17436 17435//17435 -f 17475//17475 17435//17435 17476//17476 -f 17476//17476 17435//17435 17434//17434 -f 17476//17476 17434//17434 17477//17477 -f 17477//17477 17434//17434 17433//17433 -f 17477//17477 17433//17433 17478//17478 -f 17478//17478 17433//17433 17432//17432 -f 17478//17478 17432//17432 17351//17351 -f 17351//17351 17432//17432 17315//17315 -f 17351//17351 17315//17315 17349//17349 -f 17349//17349 17315//17315 17313//17313 -f 17349//17349 17313//17313 17347//17347 -f 17347//17347 17313//17313 17311//17311 -f 17347//17347 17311//17311 17345//17345 -f 17345//17345 17311//17311 17309//17309 -f 17345//17345 17309//17309 17343//17343 -f 17343//17343 17309//17309 17307//17307 -f 17343//17343 17307//17307 17305//17305 -f 17289//17289 17287//17287 17325//17325 -f 17325//17325 17287//17287 17285//17285 -f 17325//17325 17285//17285 17323//17323 -f 17323//17323 17285//17285 17283//17283 -f 17323//17323 17283//17283 17321//17321 -f 17321//17321 17283//17283 17281//17281 -f 17321//17321 17281//17281 17319//17319 -f 17319//17319 17281//17281 17279//17279 -f 17319//17319 17279//17279 17316//17316 -f 17316//17316 17279//17279 17278//17278 -f 17316//17316 17278//17278 17479//17479 -f 17479//17479 17278//17278 17449//17449 -f 17479//17479 17449//17449 17480//17480 -f 17480//17480 17449//17449 17448//17448 -f 17480//17480 17448//17448 17481//17481 -f 17481//17481 17448//17448 17447//17447 -f 17481//17481 17447//17447 17466//17466 -f 17466//17466 17447//17447 17446//17446 -f 17466//17466 17446//17446 17445//17445 -f 17351//17351 17350//17350 17463//17463 -f 17351//17351 17463//17463 17478//17478 -f 17478//17478 17463//17463 17464//17464 -f 17478//17478 17464//17464 17477//17477 -f 17477//17477 17464//17464 17465//17465 -f 17477//17477 17465//17465 17476//17476 -f 17476//17476 17465//17465 17454//17454 -f 17476//17476 17454//17454 17475//17475 -f 17475//17475 17454//17454 17455//17455 -f 17475//17475 17455//17455 17474//17474 -f 17474//17474 17455//17455 17456//17456 -f 17474//17474 17456//17456 17473//17473 -f 17473//17473 17456//17456 17457//17457 -f 17473//17473 17457//17457 17472//17472 -f 17472//17472 17457//17457 17458//17458 -f 17472//17472 17458//17458 17471//17471 -f 17471//17471 17458//17458 17459//17459 -f 17471//17471 17459//17459 17470//17470 -f 17470//17470 17459//17459 17460//17460 -f 17470//17470 17460//17460 17469//17469 -f 17469//17469 17460//17460 17461//17461 -f 17469//17469 17461//17461 17468//17468 -f 17468//17468 17461//17461 17462//17462 -f 17468//17468 17462//17462 17467//17467 -f 17467//17467 17462//17462 17450//17450 -f 17467//17467 17450//17450 17466//17466 -f 17466//17466 17450//17450 17451//17451 -f 17466//17466 17451//17451 17481//17481 -f 17481//17481 17451//17451 17452//17452 -f 17481//17481 17452//17452 17480//17480 -f 17480//17480 17452//17452 17453//17453 -f 17480//17480 17453//17453 17479//17479 -f 17479//17479 17453//17453 17317//17317 -f 17479//17479 17317//17317 17316//17316 -f 17482//17482 17483//17483 17484//17484 -f 17484//17484 17483//17483 17485//17485 -f 17484//17484 17485//17485 17486//17486 -f 17486//17486 17485//17485 17487//17487 -f 17486//17486 17487//17487 17488//17488 -f 17488//17488 17487//17487 17489//17489 -f 17488//17488 17489//17489 17490//17490 -f 17490//17490 17489//17489 17491//17491 -f 17490//17490 17491//17491 17492//17492 -f 17492//17492 17491//17491 17493//17493 -f 17492//17492 17493//17493 17494//17494 -f 17494//17494 17493//17493 17495//17495 -f 17494//17494 17495//17495 17496//17496 -f 17496//17496 17495//17495 17497//17497 -f 17496//17496 17497//17497 17498//17498 -f 17498//17498 17497//17497 17499//17499 -f 17498//17498 17499//17499 17500//17500 -f 17500//17500 17499//17499 17501//17501 -f 17500//17500 17501//17501 17502//17502 -f 17502//17502 17501//17501 17503//17503 -f 17502//17502 17503//17503 17504//17504 -f 17504//17504 17503//17503 17505//17505 -f 17504//17504 17505//17505 17506//17506 -f 17506//17506 17505//17505 17507//17507 -f 17506//17506 17507//17507 17508//17508 -f 17508//17508 17507//17507 17509//17509 -f 17508//17508 17509//17509 17510//17510 -f 17510//17510 17509//17509 17511//17511 -f 17512//17512 17513//17513 17514//17514 -f 17512//17512 17514//17514 17515//17515 -f 17515//17515 17514//17514 17516//17516 -f 17515//17515 17516//17516 17517//17517 -f 17517//17517 17516//17516 17518//17518 -f 17517//17517 17518//17518 17519//17519 -f 17519//17519 17518//17518 17520//17520 -f 17519//17519 17520//17520 17521//17521 -f 17521//17521 17520//17520 17522//17522 -f 17521//17521 17522//17522 17523//17523 -f 17523//17523 17522//17522 17524//17524 -f 17523//17523 17524//17524 17525//17525 -f 17525//17525 17524//17524 17526//17526 -f 17525//17525 17526//17526 17527//17527 -f 17527//17527 17526//17526 17528//17528 -f 17527//17527 17528//17528 17529//17529 -f 17529//17529 17528//17528 17530//17530 -f 17529//17529 17530//17530 17531//17531 -f 17531//17531 17530//17530 17532//17532 -f 17531//17531 17532//17532 17533//17533 -f 17533//17533 17532//17532 17534//17534 -f 17533//17533 17534//17534 17535//17535 -f 17535//17535 17534//17534 17536//17536 -f 17535//17535 17536//17536 17537//17537 -f 17537//17537 17536//17536 17538//17538 -f 17537//17537 17538//17538 17539//17539 -f 17539//17539 17538//17538 17540//17540 -f 17539//17539 17540//17540 17541//17541 -f 17541//17541 17540//17540 17542//17542 -f 17541//17541 17542//17542 17543//17543 -f 17543//17543 17542//17542 17544//17544 -f 17543//17543 17544//17544 17545//17545 -f 17545//17545 17544//17544 17546//17546 -f 17545//17545 17546//17546 17547//17547 -f 17547//17547 17546//17546 17548//17548 -f 17547//17547 17548//17548 17549//17549 -f 17549//17549 17548//17548 17550//17550 -f 17549//17549 17550//17550 17551//17551 -f 17552//17552 17553//17553 17554//17554 -f 17552//17552 17554//17554 17555//17555 -f 17555//17555 17554//17554 17556//17556 -f 17555//17555 17556//17556 17557//17557 -f 17557//17557 17556//17556 17558//17558 -f 17557//17557 17558//17558 17559//17559 -f 17559//17559 17558//17558 17560//17560 -f 17559//17559 17560//17560 17561//17561 -f 17561//17561 17560//17560 17562//17562 -f 17561//17561 17562//17562 17563//17563 -f 17563//17563 17562//17562 17564//17564 -f 17563//17563 17564//17564 17565//17565 -f 17565//17565 17564//17564 17566//17566 -f 17565//17565 17566//17566 17567//17567 -f 17567//17567 17566//17566 17568//17568 -f 17567//17567 17568//17568 17569//17569 -f 17569//17569 17568//17568 17570//17570 -f 17569//17569 17570//17570 17571//17571 -f 17571//17571 17570//17570 17572//17572 -f 17571//17571 17572//17572 17573//17573 -f 17573//17573 17572//17572 17574//17574 -f 17573//17573 17574//17574 17575//17575 -f 17575//17575 17574//17574 17576//17576 -f 17575//17575 17576//17576 17577//17577 -f 17577//17577 17576//17576 17578//17578 -f 17577//17577 17578//17578 17579//17579 -f 17579//17579 17578//17578 17580//17580 -f 17579//17579 17580//17580 17581//17581 -f 17581//17581 17580//17580 17582//17582 -f 17581//17581 17582//17582 17583//17583 -f 17583//17583 17582//17582 17584//17584 -f 17583//17583 17584//17584 17585//17585 -f 17585//17585 17584//17584 17586//17586 -f 17585//17585 17586//17586 17587//17587 -f 17587//17587 17586//17586 17588//17588 -f 17587//17587 17588//17588 17589//17589 -f 17589//17589 17588//17588 17590//17590 -f 17589//17589 17590//17590 17591//17591 -f 17592//17592 17593//17593 17594//17594 -f 17592//17592 17594//17594 17595//17595 -f 17595//17595 17594//17594 17596//17596 -f 17595//17595 17596//17596 17597//17597 -f 17597//17597 17596//17596 17598//17598 -f 17597//17597 17598//17598 17599//17599 -f 17599//17599 17598//17598 17600//17600 -f 17599//17599 17600//17600 17601//17601 -f 17601//17601 17600//17600 17602//17602 -f 17601//17601 17602//17602 17603//17603 -f 17603//17603 17602//17602 17604//17604 -f 17603//17603 17604//17604 17605//17605 -f 17605//17605 17604//17604 17606//17606 -f 17605//17605 17606//17606 17607//17607 -f 17607//17607 17606//17606 17608//17608 -f 17607//17607 17608//17608 17609//17609 -f 17609//17609 17608//17608 17610//17610 -f 17609//17609 17610//17610 17611//17611 -f 17611//17611 17610//17610 17612//17612 -f 17611//17611 17612//17612 17613//17613 -f 17613//17613 17612//17612 17614//17614 -f 17613//17613 17614//17614 17615//17615 -f 17615//17615 17614//17614 17616//17616 -f 17615//17615 17616//17616 17617//17617 -f 17617//17617 17616//17616 17618//17618 -f 17617//17617 17618//17618 17619//17619 -f 17619//17619 17618//17618 17620//17620 -f 17619//17619 17620//17620 17621//17621 -f 17621//17621 17620//17620 17622//17622 -f 17621//17621 17622//17622 17623//17623 -f 17623//17623 17622//17622 17624//17624 -f 17623//17623 17624//17624 17625//17625 -f 17625//17625 17624//17624 17626//17626 -f 17625//17625 17626//17626 17627//17627 -f 17510//17510 17511//17511 17628//17628 -f 17628//17628 17511//17511 17629//17629 -f 17628//17628 17629//17629 17630//17630 -f 17630//17630 17629//17629 17631//17631 -f 17630//17630 17631//17631 17632//17632 -f 17632//17632 17631//17631 17633//17633 -f 17632//17632 17633//17633 17634//17634 -f 17634//17634 17633//17633 17635//17635 -f 17634//17634 17635//17635 17636//17636 -f 17636//17636 17635//17635 17637//17637 -f 17636//17636 17637//17637 17638//17638 -f 17638//17638 17637//17637 17639//17639 -f 17638//17638 17639//17639 17640//17640 -f 17640//17640 17639//17639 17641//17641 -f 17640//17640 17641//17641 17642//17642 -f 17642//17642 17641//17641 17643//17643 -f 17642//17642 17643//17643 17644//17644 -f 17644//17644 17643//17643 17645//17645 -f 17644//17644 17645//17645 17646//17646 -f 17646//17646 17645//17645 17647//17647 -f 17646//17646 17647//17647 17648//17648 -f 17648//17648 17647//17647 17649//17649 -f 17648//17648 17649//17649 17650//17650 -f 17650//17650 17649//17649 17651//17651 -f 17650//17650 17651//17651 17652//17652 -f 17652//17652 17651//17651 17653//17653 -f 17652//17652 17653//17653 17482//17482 -f 17482//17482 17653//17653 17483//17483 -f 17492//17492 17654//17654 17490//17490 -f 17490//17490 17654//17654 17655//17655 -f 17490//17490 17655//17655 17488//17488 -f 17488//17488 17655//17655 17656//17656 -f 17488//17488 17656//17656 17486//17486 -f 17496//17496 17657//17657 17494//17494 -f 17494//17494 17657//17657 17658//17658 -f 17494//17494 17658//17658 17492//17492 -f 17492//17492 17658//17658 17659//17659 -f 17492//17492 17659//17659 17654//17654 -f 17636//17636 17524//17524 17634//17634 -f 17634//17634 17524//17524 17522//17522 -f 17634//17634 17522//17522 17632//17632 -f 17632//17632 17522//17522 17520//17520 -f 17632//17632 17520//17520 17630//17630 -f 17520//17520 17518//17518 17630//17630 -f 17630//17630 17518//17518 17516//17516 -f 17630//17630 17516//17516 17628//17628 -f 17628//17628 17516//17516 17514//17514 -f 17628//17628 17514//17514 17510//17510 -f 17510//17510 17514//17514 17513//17513 -f 17510//17510 17513//17513 17508//17508 -f 17640//17640 17530//17530 17638//17638 -f 17638//17638 17530//17530 17528//17528 -f 17638//17638 17528//17528 17636//17636 -f 17636//17636 17528//17528 17526//17526 -f 17636//17636 17526//17526 17524//17524 -f 17502//17502 17660//17660 17500//17500 -f 17500//17500 17660//17660 17661//17661 -f 17500//17500 17661//17661 17498//17498 -f 17498//17498 17661//17661 17662//17662 -f 17498//17498 17662//17662 17496//17496 -f 17496//17496 17662//17662 17663//17663 -f 17496//17496 17663//17663 17657//17657 -f 17656//17656 17664//17664 17486//17486 -f 17486//17486 17664//17664 17665//17665 -f 17486//17486 17665//17665 17484//17484 -f 17484//17484 17665//17665 17666//17666 -f 17484//17484 17666//17666 17482//17482 -f 17482//17482 17666//17666 17550//17550 -f 17482//17482 17550//17550 17652//17652 -f 17513//17513 17667//17667 17508//17508 -f 17508//17508 17667//17667 17668//17668 -f 17508//17508 17668//17668 17506//17506 -f 17506//17506 17668//17668 17669//17669 -f 17506//17506 17669//17669 17504//17504 -f 17504//17504 17669//17669 17670//17670 -f 17504//17504 17670//17670 17502//17502 -f 17502//17502 17670//17670 17671//17671 -f 17502//17502 17671//17671 17660//17660 -f 17646//17646 17538//17538 17644//17644 -f 17644//17644 17538//17538 17536//17536 -f 17644//17644 17536//17536 17642//17642 -f 17642//17642 17536//17536 17534//17534 -f 17642//17642 17534//17534 17640//17640 -f 17640//17640 17534//17534 17532//17532 -f 17640//17640 17532//17532 17530//17530 -f 17550//17550 17548//17548 17652//17652 -f 17652//17652 17548//17548 17546//17546 -f 17652//17652 17546//17546 17650//17650 -f 17650//17650 17546//17546 17544//17544 -f 17650//17650 17544//17544 17648//17648 -f 17648//17648 17544//17544 17542//17542 -f 17648//17648 17542//17542 17646//17646 -f 17646//17646 17542//17542 17540//17540 -f 17646//17646 17540//17540 17538//17538 -f 17629//17629 17557//17557 17631//17631 -f 17631//17631 17557//17557 17559//17559 -f 17631//17631 17559//17559 17633//17633 -f 17633//17633 17559//17559 17561//17561 -f 17633//17633 17561//17561 17635//17635 -f 17561//17561 17563//17563 17635//17635 -f 17635//17635 17563//17563 17565//17565 -f 17635//17635 17565//17565 17637//17637 -f 17637//17637 17565//17565 17567//17567 -f 17637//17637 17567//17567 17639//17639 -f 17491//17491 17672//17672 17493//17493 -f 17493//17493 17672//17672 17673//17673 -f 17493//17493 17673//17673 17495//17495 -f 17485//17485 17674//17674 17487//17487 -f 17487//17487 17674//17674 17675//17675 -f 17487//17487 17675//17675 17489//17489 -f 17489//17489 17675//17675 17676//17676 -f 17489//17489 17676//17676 17491//17491 -f 17491//17491 17676//17676 17677//17677 -f 17491//17491 17677//17677 17672//17672 -f 17651//17651 17587//17587 17653//17653 -f 17653//17653 17587//17587 17589//17589 -f 17653//17653 17589//17589 17483//17483 -f 17483//17483 17589//17589 17591//17591 -f 17483//17483 17591//17591 17485//17485 -f 17485//17485 17591//17591 17678//17678 -f 17485//17485 17678//17678 17674//17674 -f 17645//17645 17579//17579 17647//17647 -f 17647//17647 17579//17579 17581//17581 -f 17647//17647 17581//17581 17649//17649 -f 17649//17649 17581//17581 17583//17583 -f 17649//17649 17583//17583 17651//17651 -f 17651//17651 17583//17583 17585//17585 -f 17651//17651 17585//17585 17587//17587 -f 17567//17567 17569//17569 17639//17639 -f 17639//17639 17569//17569 17571//17571 -f 17639//17639 17571//17571 17641//17641 -f 17641//17641 17571//17571 17573//17573 -f 17641//17641 17573//17573 17643//17643 -f 17643//17643 17573//17573 17575//17575 -f 17643//17643 17575//17575 17645//17645 -f 17645//17645 17575//17575 17577//17577 -f 17645//17645 17577//17577 17579//17579 -f 17507//17507 17679//17679 17509//17509 -f 17509//17509 17679//17679 17680//17680 -f 17509//17509 17680//17680 17511//17511 -f 17511//17511 17680//17680 17552//17552 -f 17511//17511 17552//17552 17629//17629 -f 17629//17629 17552//17552 17555//17555 -f 17629//17629 17555//17555 17557//17557 -f 17501//17501 17681//17681 17503//17503 -f 17503//17503 17681//17681 17682//17682 -f 17503//17503 17682//17682 17505//17505 -f 17505//17505 17682//17682 17683//17683 -f 17505//17505 17683//17683 17507//17507 -f 17507//17507 17683//17683 17684//17684 -f 17507//17507 17684//17684 17679//17679 -f 17673//17673 17685//17685 17495//17495 -f 17495//17495 17685//17685 17686//17686 -f 17495//17495 17686//17686 17497//17497 -f 17497//17497 17686//17686 17687//17687 -f 17497//17497 17687//17687 17499//17499 -f 17499//17499 17687//17687 17688//17688 -f 17499//17499 17688//17688 17501//17501 -f 17501//17501 17688//17688 17689//17689 -f 17501//17501 17689//17689 17681//17681 -f 17551//17551 17550//17550 17666//17666 -f 17551//17551 17666//17666 17690//17690 -f 17690//17690 17666//17666 17665//17665 -f 17690//17690 17665//17665 17691//17691 -f 17691//17691 17665//17665 17664//17664 -f 17691//17691 17664//17664 17692//17692 -f 17692//17692 17664//17664 17656//17656 -f 17692//17692 17656//17656 17693//17693 -f 17693//17693 17656//17656 17655//17655 -f 17693//17693 17655//17655 17694//17694 -f 17694//17694 17655//17655 17654//17654 -f 17694//17694 17654//17654 17695//17695 -f 17695//17695 17654//17654 17659//17659 -f 17695//17695 17659//17659 17696//17696 -f 17696//17696 17659//17659 17658//17658 -f 17696//17696 17658//17658 17697//17697 -f 17697//17697 17658//17658 17657//17657 -f 17697//17697 17657//17657 17698//17698 -f 17698//17698 17657//17657 17663//17663 -f 17698//17698 17663//17663 17699//17699 -f 17699//17699 17663//17663 17662//17662 -f 17699//17699 17662//17662 17700//17700 -f 17700//17700 17662//17662 17661//17661 -f 17700//17700 17661//17661 17701//17701 -f 17701//17701 17661//17661 17660//17660 -f 17701//17701 17660//17660 17702//17702 -f 17702//17702 17660//17660 17671//17671 -f 17702//17702 17671//17671 17703//17703 -f 17703//17703 17671//17671 17670//17670 -f 17703//17703 17670//17670 17704//17704 -f 17704//17704 17670//17670 17669//17669 -f 17704//17704 17669//17669 17705//17705 -f 17705//17705 17669//17669 17668//17668 -f 17705//17705 17668//17668 17706//17706 -f 17706//17706 17668//17668 17667//17667 -f 17706//17706 17667//17667 17707//17707 -f 17707//17707 17667//17667 17513//17513 -f 17707//17707 17513//17513 17512//17512 -f 17591//17591 17590//17590 17708//17708 -f 17591//17591 17708//17708 17678//17678 -f 17678//17678 17708//17708 17709//17709 -f 17678//17678 17709//17709 17674//17674 -f 17674//17674 17709//17709 17710//17710 -f 17674//17674 17710//17710 17675//17675 -f 17675//17675 17710//17710 17711//17711 -f 17675//17675 17711//17711 17676//17676 -f 17676//17676 17711//17711 17712//17712 -f 17676//17676 17712//17712 17677//17677 -f 17677//17677 17712//17712 17713//17713 -f 17677//17677 17713//17713 17672//17672 -f 17672//17672 17713//17713 17714//17714 -f 17672//17672 17714//17714 17673//17673 -f 17673//17673 17714//17714 17715//17715 -f 17673//17673 17715//17715 17685//17685 -f 17685//17685 17715//17715 17716//17716 -f 17685//17685 17716//17716 17686//17686 -f 17686//17686 17716//17716 17717//17717 -f 17686//17686 17717//17717 17687//17687 -f 17687//17687 17717//17717 17718//17718 -f 17687//17687 17718//17718 17688//17688 -f 17688//17688 17718//17718 17719//17719 -f 17688//17688 17719//17719 17689//17689 -f 17689//17689 17719//17719 17720//17720 -f 17689//17689 17720//17720 17681//17681 -f 17681//17681 17720//17720 17721//17721 -f 17681//17681 17721//17721 17682//17682 -f 17682//17682 17721//17721 17722//17722 -f 17682//17682 17722//17722 17683//17683 -f 17683//17683 17722//17722 17723//17723 -f 17683//17683 17723//17723 17684//17684 -f 17684//17684 17723//17723 17724//17724 -f 17684//17684 17724//17724 17679//17679 -f 17679//17679 17724//17724 17725//17725 -f 17679//17679 17725//17725 17680//17680 -f 17680//17680 17725//17725 17553//17553 -f 17680//17680 17553//17553 17552//17552 -f 17726//17726 17704//17704 17727//17727 -f 17727//17727 17704//17704 17705//17705 -f 17727//17727 17705//17705 17728//17728 -f 17728//17728 17705//17705 17706//17706 -f 17728//17728 17706//17706 17729//17729 -f 17729//17729 17706//17706 17707//17707 -f 17729//17729 17707//17707 17593//17593 -f 17593//17593 17707//17707 17512//17512 -f 17593//17593 17512//17512 17594//17594 -f 17594//17594 17512//17512 17515//17515 -f 17594//17594 17515//17515 17596//17596 -f 17596//17596 17515//17515 17517//17517 -f 17596//17596 17517//17517 17598//17598 -f 17598//17598 17517//17517 17519//17519 -f 17598//17598 17519//17519 17600//17600 -f 17618//17618 17543//17543 17620//17620 -f 17620//17620 17543//17543 17545//17545 -f 17620//17620 17545//17545 17622//17622 -f 17622//17622 17545//17545 17547//17547 -f 17622//17622 17547//17547 17624//17624 -f 17624//17624 17547//17547 17549//17549 -f 17624//17624 17549//17549 17626//17626 -f 17626//17626 17549//17549 17551//17551 -f 17626//17626 17551//17551 17730//17730 -f 17730//17730 17551//17551 17690//17690 -f 17730//17730 17690//17690 17731//17731 -f 17731//17731 17690//17690 17691//17691 -f 17731//17731 17691//17691 17732//17732 -f 17732//17732 17691//17691 17692//17692 -f 17732//17732 17692//17692 17733//17733 -f 17692//17692 17693//17693 17733//17733 -f 17733//17733 17693//17693 17694//17694 -f 17733//17733 17694//17694 17734//17734 -f 17734//17734 17694//17694 17695//17695 -f 17734//17734 17695//17695 17735//17735 -f 17735//17735 17695//17695 17696//17696 -f 17735//17735 17696//17696 17736//17736 -f 17736//17736 17696//17696 17697//17697 -f 17736//17736 17697//17697 17737//17737 -f 17737//17737 17697//17697 17698//17698 -f 17737//17737 17698//17698 17738//17738 -f 17738//17738 17698//17698 17699//17699 -f 17738//17738 17699//17699 17739//17739 -f 17739//17739 17699//17699 17700//17700 -f 17739//17739 17700//17700 17740//17740 -f 17740//17740 17700//17700 17701//17701 -f 17740//17740 17701//17701 17741//17741 -f 17741//17741 17701//17701 17702//17702 -f 17741//17741 17702//17702 17726//17726 -f 17726//17726 17702//17702 17703//17703 -f 17726//17726 17703//17703 17704//17704 -f 17519//17519 17521//17521 17600//17600 -f 17600//17600 17521//17521 17523//17523 -f 17600//17600 17523//17523 17602//17602 -f 17602//17602 17523//17523 17525//17525 -f 17602//17602 17525//17525 17604//17604 -f 17604//17604 17525//17525 17527//17527 -f 17604//17604 17527//17527 17606//17606 -f 17606//17606 17527//17527 17529//17529 -f 17606//17606 17529//17529 17608//17608 -f 17608//17608 17529//17529 17531//17531 -f 17608//17608 17531//17531 17610//17610 -f 17610//17610 17531//17531 17533//17533 -f 17610//17610 17533//17533 17612//17612 -f 17612//17612 17533//17533 17535//17535 -f 17612//17612 17535//17535 17614//17614 -f 17614//17614 17535//17535 17537//17537 -f 17614//17614 17537//17537 17616//17616 -f 17616//17616 17537//17537 17539//17539 -f 17616//17616 17539//17539 17618//17618 -f 17618//17618 17539//17539 17541//17541 -f 17618//17618 17541//17541 17543//17543 -f 17742//17742 17711//17711 17743//17743 -f 17743//17743 17711//17711 17710//17710 -f 17743//17743 17710//17710 17744//17744 -f 17744//17744 17710//17710 17709//17709 -f 17744//17744 17709//17709 17745//17745 -f 17745//17745 17709//17709 17708//17708 -f 17745//17745 17708//17708 17627//17627 -f 17627//17627 17708//17708 17590//17590 -f 17627//17627 17590//17590 17625//17625 -f 17625//17625 17590//17590 17588//17588 -f 17625//17625 17588//17588 17623//17623 -f 17623//17623 17588//17588 17586//17586 -f 17623//17623 17586//17586 17621//17621 -f 17621//17621 17586//17586 17584//17584 -f 17621//17621 17584//17584 17619//17619 -f 17746//17746 17721//17721 17747//17747 -f 17747//17747 17721//17721 17720//17720 -f 17747//17747 17720//17720 17748//17748 -f 17748//17748 17720//17720 17719//17719 -f 17748//17748 17719//17719 17749//17749 -f 17749//17749 17719//17719 17718//17718 -f 17749//17749 17718//17718 17750//17750 -f 17750//17750 17718//17718 17717//17717 -f 17750//17750 17717//17717 17751//17751 -f 17751//17751 17717//17717 17716//17716 -f 17751//17751 17716//17716 17752//17752 -f 17752//17752 17716//17716 17715//17715 -f 17752//17752 17715//17715 17753//17753 -f 17753//17753 17715//17715 17714//17714 -f 17753//17753 17714//17714 17754//17754 -f 17754//17754 17714//17714 17713//17713 -f 17754//17754 17713//17713 17742//17742 -f 17742//17742 17713//17713 17712//17712 -f 17742//17742 17712//17712 17711//17711 -f 17601//17601 17560//17560 17599//17599 -f 17599//17599 17560//17560 17558//17558 -f 17599//17599 17558//17558 17597//17597 -f 17597//17597 17558//17558 17556//17556 -f 17597//17597 17556//17556 17595//17595 -f 17595//17595 17556//17556 17554//17554 -f 17595//17595 17554//17554 17592//17592 -f 17592//17592 17554//17554 17553//17553 -f 17592//17592 17553//17553 17755//17755 -f 17755//17755 17553//17553 17725//17725 -f 17755//17755 17725//17725 17756//17756 -f 17756//17756 17725//17725 17724//17724 -f 17756//17756 17724//17724 17757//17757 -f 17757//17757 17724//17724 17723//17723 -f 17757//17757 17723//17723 17746//17746 -f 17746//17746 17723//17723 17722//17722 -f 17746//17746 17722//17722 17721//17721 -f 17584//17584 17582//17582 17619//17619 -f 17619//17619 17582//17582 17580//17580 -f 17619//17619 17580//17580 17617//17617 -f 17617//17617 17580//17580 17578//17578 -f 17617//17617 17578//17578 17615//17615 -f 17615//17615 17578//17578 17576//17576 -f 17615//17615 17576//17576 17613//17613 -f 17613//17613 17576//17576 17574//17574 -f 17613//17613 17574//17574 17611//17611 -f 17611//17611 17574//17574 17572//17572 -f 17611//17611 17572//17572 17609//17609 -f 17609//17609 17572//17572 17570//17570 -f 17609//17609 17570//17570 17607//17607 -f 17607//17607 17570//17570 17568//17568 -f 17607//17607 17568//17568 17605//17605 -f 17605//17605 17568//17568 17566//17566 -f 17605//17605 17566//17566 17603//17603 -f 17603//17603 17566//17566 17564//17564 -f 17603//17603 17564//17564 17601//17601 -f 17601//17601 17564//17564 17562//17562 -f 17601//17601 17562//17562 17560//17560 -f 17627//17627 17626//17626 17730//17730 -f 17627//17627 17730//17730 17745//17745 -f 17745//17745 17730//17730 17731//17731 -f 17745//17745 17731//17731 17744//17744 -f 17744//17744 17731//17731 17732//17732 -f 17744//17744 17732//17732 17743//17743 -f 17743//17743 17732//17732 17733//17733 -f 17743//17743 17733//17733 17742//17742 -f 17742//17742 17733//17733 17734//17734 -f 17742//17742 17734//17734 17754//17754 -f 17754//17754 17734//17734 17735//17735 -f 17754//17754 17735//17735 17753//17753 -f 17753//17753 17735//17735 17736//17736 -f 17753//17753 17736//17736 17752//17752 -f 17752//17752 17736//17736 17737//17737 -f 17752//17752 17737//17737 17751//17751 -f 17751//17751 17737//17737 17738//17738 -f 17751//17751 17738//17738 17750//17750 -f 17750//17750 17738//17738 17739//17739 -f 17750//17750 17739//17739 17749//17749 -f 17749//17749 17739//17739 17740//17740 -f 17749//17749 17740//17740 17748//17748 -f 17748//17748 17740//17740 17741//17741 -f 17748//17748 17741//17741 17747//17747 -f 17747//17747 17741//17741 17726//17726 -f 17747//17747 17726//17726 17746//17746 -f 17746//17746 17726//17726 17727//17727 -f 17746//17746 17727//17727 17757//17757 -f 17757//17757 17727//17727 17728//17728 -f 17757//17757 17728//17728 17756//17756 -f 17756//17756 17728//17728 17729//17729 -f 17756//17756 17729//17729 17755//17755 -f 17755//17755 17729//17729 17593//17593 -f 17755//17755 17593//17593 17592//17592 -f 17758//17758 17759//17759 17760//17760 -f 17760//17760 17759//17759 17761//17761 -f 17760//17760 17761//17761 17762//17762 -f 17762//17762 17761//17761 17763//17763 -f 17762//17762 17763//17763 17764//17764 -f 17764//17764 17763//17763 17765//17765 -f 17764//17764 17765//17765 17766//17766 -f 17766//17766 17765//17765 17767//17767 -f 17766//17766 17767//17767 17768//17768 -f 17768//17768 17767//17767 17769//17769 -f 17768//17768 17769//17769 17770//17770 -f 17770//17770 17769//17769 17771//17771 -f 17770//17770 17771//17771 17772//17772 -f 17772//17772 17771//17771 17773//17773 -f 17772//17772 17773//17773 17774//17774 -f 17774//17774 17773//17773 17775//17775 -f 17774//17774 17775//17775 17776//17776 -f 17776//17776 17775//17775 17777//17777 -f 17776//17776 17777//17777 17778//17778 -f 17778//17778 17777//17777 17779//17779 -f 17778//17778 17779//17779 17780//17780 -f 17780//17780 17779//17779 17781//17781 -f 17780//17780 17781//17781 17782//17782 -f 17782//17782 17781//17781 17783//17783 -f 17782//17782 17783//17783 17784//17784 -f 17784//17784 17783//17783 17785//17785 -f 17784//17784 17785//17785 17786//17786 -f 17786//17786 17785//17785 17787//17787 -f 17788//17788 1043//1043 17789//17789 -f 17788//17788 17789//17789 17790//17790 -f 17790//17790 17789//17789 17791//17791 -f 17790//17790 17791//17791 17792//17792 -f 17792//17792 17791//17791 17793//17793 -f 17792//17792 17793//17793 17794//17794 -f 17794//17794 17793//17793 17795//17795 -f 17794//17794 17795//17795 17796//17796 -f 17796//17796 17795//17795 17797//17797 -f 17796//17796 17797//17797 17798//17798 -f 17798//17798 17797//17797 17799//17799 -f 17798//17798 17799//17799 17800//17800 -f 17800//17800 17799//17799 17801//17801 -f 17800//17800 17801//17801 17802//17802 -f 17802//17802 17801//17801 17803//17803 -f 17802//17802 17803//17803 17804//17804 -f 17804//17804 17803//17803 17805//17805 -f 17804//17804 17805//17805 17806//17806 -f 17806//17806 17805//17805 17807//17807 -f 17806//17806 17807//17807 17808//17808 -f 17808//17808 17807//17807 17809//17809 -f 17808//17808 17809//17809 17810//17810 -f 17810//17810 17809//17809 17811//17811 -f 17810//17810 17811//17811 17812//17812 -f 17812//17812 17811//17811 17813//17813 -f 17812//17812 17813//17813 17814//17814 -f 17814//17814 17813//17813 17815//17815 -f 17814//17814 17815//17815 17816//17816 -f 17816//17816 17815//17815 17817//17817 -f 17816//17816 17817//17817 17818//17818 -f 17818//17818 17817//17817 17819//17819 -f 17818//17818 17819//17819 17820//17820 -f 17820//17820 17819//17819 17821//17821 -f 17820//17820 17821//17821 17822//17822 -f 17822//17822 17821//17821 17823//17823 -f 17822//17822 17823//17823 17824//17824 -f 17824//17824 17823//17823 1031//1031 -f 17824//17824 1031//1031 17825//17825 -f 1044//1044 17826//17826 17827//17827 -f 1044//1044 17827//17827 17828//17828 -f 17828//17828 17827//17827 17829//17829 -f 17828//17828 17829//17829 17830//17830 -f 17830//17830 17829//17829 17831//17831 -f 17830//17830 17831//17831 17832//17832 -f 17832//17832 17831//17831 17833//17833 -f 17832//17832 17833//17833 17834//17834 -f 17834//17834 17833//17833 17835//17835 -f 17834//17834 17835//17835 17836//17836 -f 17836//17836 17835//17835 17837//17837 -f 17836//17836 17837//17837 17838//17838 -f 17838//17838 17837//17837 17839//17839 -f 17838//17838 17839//17839 17840//17840 -f 17840//17840 17839//17839 17841//17841 -f 17840//17840 17841//17841 17842//17842 -f 17842//17842 17841//17841 17843//17843 -f 17842//17842 17843//17843 17844//17844 -f 17844//17844 17843//17843 17845//17845 -f 17844//17844 17845//17845 17846//17846 -f 17846//17846 17845//17845 17847//17847 -f 17846//17846 17847//17847 17848//17848 -f 17848//17848 17847//17847 17849//17849 -f 17848//17848 17849//17849 17850//17850 -f 17850//17850 17849//17849 17851//17851 -f 17850//17850 17851//17851 17852//17852 -f 17852//17852 17851//17851 17853//17853 -f 17852//17852 17853//17853 17854//17854 -f 17854//17854 17853//17853 17855//17855 -f 17854//17854 17855//17855 17856//17856 -f 17856//17856 17855//17855 17857//17857 -f 17856//17856 17857//17857 17858//17858 -f 17858//17858 17857//17857 17859//17859 -f 17858//17858 17859//17859 17860//17860 -f 17860//17860 17859//17859 17861//17861 -f 17860//17860 17861//17861 17862//17862 -f 17862//17862 17861//17861 17863//17863 -f 17862//17862 17863//17863 1032//1032 -f 17864//17864 17865//17865 17866//17866 -f 17864//17864 17866//17866 17867//17867 -f 17867//17867 17866//17866 17868//17868 -f 17867//17867 17868//17868 17869//17869 -f 17869//17869 17868//17868 17870//17870 -f 17869//17869 17870//17870 17871//17871 -f 17871//17871 17870//17870 17872//17872 -f 17871//17871 17872//17872 17873//17873 -f 17873//17873 17872//17872 17874//17874 -f 17873//17873 17874//17874 17875//17875 -f 17875//17875 17874//17874 17876//17876 -f 17875//17875 17876//17876 17877//17877 -f 17877//17877 17876//17876 17878//17878 -f 17877//17877 17878//17878 17879//17879 -f 17879//17879 17878//17878 17880//17880 -f 17879//17879 17880//17880 17881//17881 -f 17881//17881 17880//17880 17882//17882 -f 17881//17881 17882//17882 17883//17883 -f 17883//17883 17882//17882 17884//17884 -f 17883//17883 17884//17884 17885//17885 -f 17885//17885 17884//17884 17886//17886 -f 17885//17885 17886//17886 17887//17887 -f 17887//17887 17886//17886 17888//17888 -f 17887//17887 17888//17888 17889//17889 -f 17889//17889 17888//17888 17890//17890 -f 17889//17889 17890//17890 17891//17891 -f 17891//17891 17890//17890 17892//17892 -f 17891//17891 17892//17892 17893//17893 -f 17893//17893 17892//17892 17894//17894 -f 17893//17893 17894//17894 17895//17895 -f 17895//17895 17894//17894 17896//17896 -f 17895//17895 17896//17896 17897//17897 -f 17897//17897 17896//17896 17898//17898 -f 17897//17897 17898//17898 17899//17899 -f 17786//17786 17787//17787 17900//17900 -f 17900//17900 17787//17787 17901//17901 -f 17900//17900 17901//17901 17902//17902 -f 17902//17902 17901//17901 17903//17903 -f 17902//17902 17903//17903 17904//17904 -f 17904//17904 17903//17903 17905//17905 -f 17904//17904 17905//17905 17906//17906 -f 17906//17906 17905//17905 17907//17907 -f 17906//17906 17907//17907 17908//17908 -f 17908//17908 17907//17907 17909//17909 -f 17908//17908 17909//17909 17910//17910 -f 17910//17910 17909//17909 17911//17911 -f 17910//17910 17911//17911 17912//17912 -f 17912//17912 17911//17911 17913//17913 -f 17912//17912 17913//17913 17914//17914 -f 17914//17914 17913//17913 17915//17915 -f 17914//17914 17915//17915 17916//17916 -f 17916//17916 17915//17915 17917//17917 -f 17916//17916 17917//17917 17918//17918 -f 17918//17918 17917//17917 17919//17919 -f 17918//17918 17919//17919 17920//17920 -f 17920//17920 17919//17919 17921//17921 -f 17920//17920 17921//17921 17922//17922 -f 17922//17922 17921//17921 17923//17923 -f 17922//17922 17923//17923 17924//17924 -f 17924//17924 17923//17923 17925//17925 -f 17924//17924 17925//17925 17758//17758 -f 17758//17758 17925//17925 17759//17759 -f 17762//17762 17926//17926 17760//17760 -f 17760//17760 17926//17926 17927//17927 -f 17760//17760 17927//17927 17758//17758 -f 17758//17758 17927//17927 1031//1031 -f 17758//17758 1031//1031 17924//17924 -f 17774//17774 17928//17928 17772//17772 -f 17772//17772 17928//17928 17929//17929 -f 17772//17772 17929//17929 17770//17770 -f 17770//17770 17929//17929 17930//17930 -f 17770//17770 17930//17930 17768//17768 -f 17914//17914 17807//17807 17912//17912 -f 17912//17912 17807//17807 17805//17805 -f 17912//17912 17805//17805 17910//17910 -f 17910//17910 17805//17805 17803//17803 -f 17910//17910 17803//17803 17908//17908 -f 1031//1031 17823//17823 17924//17924 -f 17924//17924 17823//17823 17821//17821 -f 17924//17924 17821//17821 17922//17922 -f 17922//17922 17821//17821 17819//17819 -f 17922//17922 17819//17819 17920//17920 -f 17920//17920 17819//17819 17817//17817 -f 17920//17920 17817//17817 17918//17918 -f 17930//17930 17931//17931 17768//17768 -f 17768//17768 17931//17931 17932//17932 -f 17768//17768 17932//17932 17766//17766 -f 17766//17766 17932//17932 17933//17933 -f 17766//17766 17933//17933 17764//17764 -f 17764//17764 17933//17933 17934//17934 -f 17764//17764 17934//17934 17762//17762 -f 17762//17762 17934//17934 17935//17935 -f 17762//17762 17935//17935 17926//17926 -f 17817//17817 17815//17815 17918//17918 -f 17918//17918 17815//17815 17813//17813 -f 17918//17918 17813//17813 17916//17916 -f 17916//17916 17813//17813 17811//17811 -f 17916//17916 17811//17811 17914//17914 -f 17914//17914 17811//17811 17809//17809 -f 17914//17914 17809//17809 17807//17807 -f 17778//17778 17936//17936 17776//17776 -f 17776//17776 17936//17936 17937//17937 -f 17776//17776 17937//17937 17774//17774 -f 17774//17774 17937//17937 17938//17938 -f 17774//17774 17938//17938 17928//17928 -f 17784//17784 17939//17939 17782//17782 -f 17782//17782 17939//17939 17940//17940 -f 17782//17782 17940//17940 17780//17780 -f 17780//17780 17940//17940 17941//17941 -f 17780//17780 17941//17941 17778//17778 -f 17778//17778 17941//17941 17942//17942 -f 17778//17778 17942//17942 17936//17936 -f 17902//17902 17791//17791 17900//17900 -f 17900//17900 17791//17791 17789//17789 -f 17900//17900 17789//17789 17786//17786 -f 17786//17786 17789//17789 1043//1043 -f 17786//17786 1043//1043 17784//17784 -f 17784//17784 1043//1043 17943//17943 -f 17784//17784 17943//17943 17939//17939 -f 17803//17803 17801//17801 17908//17908 -f 17908//17908 17801//17801 17799//17799 -f 17908//17908 17799//17799 17906//17906 -f 17906//17906 17799//17799 17797//17797 -f 17906//17906 17797//17797 17904//17904 -f 17904//17904 17797//17797 17795//17795 -f 17904//17904 17795//17795 17902//17902 -f 17902//17902 17795//17795 17793//17793 -f 17902//17902 17793//17793 17791//17791 -f 17783//17783 17944//17944 17785//17785 -f 17785//17785 17944//17944 17945//17945 -f 17785//17785 17945//17945 17787//17787 -f 17787//17787 17945//17945 1044//1044 -f 17787//17787 1044//1044 17901//17901 -f 17771//17771 17946//17946 17773//17773 -f 17773//17773 17946//17946 17947//17947 -f 17773//17773 17947//17947 17775//17775 -f 17775//17775 17947//17947 17948//17948 -f 17775//17775 17948//17948 17777//17777 -f 17948//17948 17949//17949 17777//17777 -f 17777//17777 17949//17949 17950//17950 -f 17777//17777 17950//17950 17779//17779 -f 17779//17779 17950//17950 17951//17951 -f 17779//17779 17951//17951 17781//17781 -f 17781//17781 17951//17951 17952//17952 -f 17781//17781 17952//17952 17783//17783 -f 17783//17783 17952//17952 17953//17953 -f 17783//17783 17953//17953 17944//17944 -f 17923//17923 17860//17860 17925//17925 -f 17925//17925 17860//17860 17862//17862 -f 17925//17925 17862//17862 17759//17759 -f 17759//17759 17862//17862 1032//1032 -f 17759//17759 1032//1032 17761//17761 -f 17767//17767 17954//17954 17769//17769 -f 17769//17769 17954//17954 17955//17955 -f 17769//17769 17955//17955 17771//17771 -f 17771//17771 17955//17955 17956//17956 -f 17771//17771 17956//17956 17946//17946 -f 1032//1032 17957//17957 17761//17761 -f 17761//17761 17957//17957 17958//17958 -f 17761//17761 17958//17958 17763//17763 -f 17763//17763 17958//17958 17959//17959 -f 17763//17763 17959//17959 17765//17765 -f 17765//17765 17959//17959 17960//17960 -f 17765//17765 17960//17960 17767//17767 -f 17767//17767 17960//17960 17961//17961 -f 17767//17767 17961//17961 17954//17954 -f 17917//17917 17852//17852 17919//17919 -f 17919//17919 17852//17852 17854//17854 -f 17919//17919 17854//17854 17921//17921 -f 17921//17921 17854//17854 17856//17856 -f 17921//17921 17856//17856 17923//17923 -f 17923//17923 17856//17856 17858//17858 -f 17923//17923 17858//17858 17860//17860 -f 17911//17911 17844//17844 17913//17913 -f 17913//17913 17844//17844 17846//17846 -f 17913//17913 17846//17846 17915//17915 -f 17915//17915 17846//17846 17848//17848 -f 17915//17915 17848//17848 17917//17917 -f 17917//17917 17848//17848 17850//17850 -f 17917//17917 17850//17850 17852//17852 -f 1044//1044 17828//17828 17901//17901 -f 17901//17901 17828//17828 17830//17830 -f 17901//17901 17830//17830 17903//17903 -f 17903//17903 17830//17830 17832//17832 -f 17903//17903 17832//17832 17905//17905 -f 17905//17905 17832//17832 17834//17834 -f 17905//17905 17834//17834 17907//17907 -f 17834//17834 17836//17836 17907//17907 -f 17907//17907 17836//17836 17838//17838 -f 17907//17907 17838//17838 17909//17909 -f 17909//17909 17838//17838 17840//17840 -f 17909//17909 17840//17840 17911//17911 -f 17911//17911 17840//17840 17842//17842 -f 17911//17911 17842//17842 17844//17844 -f 17825//17825 1031//1031 17927//17927 -f 17825//17825 17927//17927 17962//17962 -f 17962//17962 17927//17927 17926//17926 -f 17962//17962 17926//17926 17963//17963 -f 17963//17963 17926//17926 17935//17935 -f 17963//17963 17935//17935 17964//17964 -f 17964//17964 17935//17935 17934//17934 -f 17964//17964 17934//17934 17965//17965 -f 17965//17965 17934//17934 17933//17933 -f 17965//17965 17933//17933 17966//17966 -f 17966//17966 17933//17933 17932//17932 -f 17966//17966 17932//17932 17967//17967 -f 17967//17967 17932//17932 17931//17931 -f 17967//17967 17931//17931 17968//17968 -f 17968//17968 17931//17931 17930//17930 -f 17968//17968 17930//17930 17969//17969 -f 17969//17969 17930//17930 17929//17929 -f 17969//17969 17929//17929 17970//17970 -f 17970//17970 17929//17929 17928//17928 -f 17970//17970 17928//17928 17971//17971 -f 17971//17971 17928//17928 17938//17938 -f 17971//17971 17938//17938 17972//17972 -f 17972//17972 17938//17938 17937//17937 -f 17972//17972 17937//17937 17973//17973 -f 17973//17973 17937//17937 17936//17936 -f 17973//17973 17936//17936 17974//17974 -f 17974//17974 17936//17936 17942//17942 -f 17974//17974 17942//17942 17975//17975 -f 17975//17975 17942//17942 17941//17941 -f 17975//17975 17941//17941 17976//17976 -f 17976//17976 17941//17941 17940//17940 -f 17976//17976 17940//17940 17977//17977 -f 17977//17977 17940//17940 17939//17939 -f 17977//17977 17939//17939 17978//17978 -f 17978//17978 17939//17939 17943//17943 -f 17978//17978 17943//17943 17979//17979 -f 17979//17979 17943//17943 1043//1043 -f 17979//17979 1043//1043 17788//17788 -f 1032//1032 17863//17863 17980//17980 -f 1032//1032 17980//17980 17957//17957 -f 17957//17957 17980//17980 17981//17981 -f 17957//17957 17981//17981 17958//17958 -f 17958//17958 17981//17981 17982//17982 -f 17958//17958 17982//17982 17959//17959 -f 17959//17959 17982//17982 17983//17983 -f 17959//17959 17983//17983 17960//17960 -f 17960//17960 17983//17983 17984//17984 -f 17960//17960 17984//17984 17961//17961 -f 17961//17961 17984//17984 17985//17985 -f 17961//17961 17985//17985 17954//17954 -f 17954//17954 17985//17985 17986//17986 -f 17954//17954 17986//17986 17955//17955 -f 17955//17955 17986//17986 17987//17987 -f 17955//17955 17987//17987 17956//17956 -f 17956//17956 17987//17987 17988//17988 -f 17956//17956 17988//17988 17946//17946 -f 17946//17946 17988//17988 17989//17989 -f 17946//17946 17989//17989 17947//17947 -f 17947//17947 17989//17989 17990//17990 -f 17947//17947 17990//17990 17948//17948 -f 17948//17948 17990//17990 17991//17991 -f 17948//17948 17991//17991 17949//17949 -f 17949//17949 17991//17991 17992//17992 -f 17949//17949 17992//17992 17950//17950 -f 17950//17950 17992//17992 17993//17993 -f 17950//17950 17993//17993 17951//17951 -f 17951//17951 17993//17993 17994//17994 -f 17951//17951 17994//17994 17952//17952 -f 17952//17952 17994//17994 17995//17995 -f 17952//17952 17995//17995 17953//17953 -f 17953//17953 17995//17995 17996//17996 -f 17953//17953 17996//17996 17944//17944 -f 17944//17944 17996//17996 17997//17997 -f 17944//17944 17997//17997 17945//17945 -f 17945//17945 17997//17997 17826//17826 -f 17945//17945 17826//17826 1044//1044 -f 17998//17998 17976//17976 17999//17999 -f 17999//17999 17976//17976 17977//17977 -f 17999//17999 17977//17977 18000//18000 -f 18000//18000 17977//17977 17978//17978 -f 18000//18000 17978//17978 18001//18001 -f 18001//18001 17978//17978 17979//17979 -f 18001//18001 17979//17979 17865//17865 -f 17865//17865 17979//17979 17788//17788 -f 17865//17865 17788//17788 17866//17866 -f 17866//17866 17788//17788 17790//17790 -f 17866//17866 17790//17790 17868//17868 -f 17868//17868 17790//17790 17792//17792 -f 17868//17868 17792//17792 17870//17870 -f 17870//17870 17792//17792 17794//17794 -f 17870//17870 17794//17794 17872//17872 -f 17794//17794 17796//17796 17872//17872 -f 17872//17872 17796//17796 17798//17798 -f 17872//17872 17798//17798 17874//17874 -f 17874//17874 17798//17798 17800//17800 -f 17874//17874 17800//17800 17876//17876 -f 17876//17876 17800//17800 17802//17802 -f 17876//17876 17802//17802 17878//17878 -f 17878//17878 17802//17802 17804//17804 -f 17878//17878 17804//17804 17880//17880 -f 17880//17880 17804//17804 17806//17806 -f 17880//17880 17806//17806 17882//17882 -f 17882//17882 17806//17806 17808//17808 -f 17882//17882 17808//17808 17884//17884 -f 17884//17884 17808//17808 17810//17810 -f 17884//17884 17810//17810 17886//17886 -f 17886//17886 17810//17810 17812//17812 -f 17886//17886 17812//17812 17888//17888 -f 17888//17888 17812//17812 17814//17814 -f 17888//17888 17814//17814 17890//17890 -f 18002//18002 17966//17966 18003//18003 -f 18003//18003 17966//17966 17967//17967 -f 18003//18003 17967//17967 18004//18004 -f 18004//18004 17967//17967 17968//17968 -f 18004//18004 17968//17968 18005//18005 -f 18005//18005 17968//17968 17969//17969 -f 18005//18005 17969//17969 18006//18006 -f 18006//18006 17969//17969 17970//17970 -f 18006//18006 17970//17970 18007//18007 -f 18007//18007 17970//17970 17971//17971 -f 18007//18007 17971//17971 18008//18008 -f 18008//18008 17971//17971 17972//17972 -f 18008//18008 17972//17972 18009//18009 -f 18009//18009 17972//17972 17973//17973 -f 18009//18009 17973//17973 18010//18010 -f 18010//18010 17973//17973 17974//17974 -f 18010//18010 17974//17974 17998//17998 -f 17998//17998 17974//17974 17975//17975 -f 17998//17998 17975//17975 17976//17976 -f 17814//17814 17816//17816 17890//17890 -f 17890//17890 17816//17816 17818//17818 -f 17890//17890 17818//17818 17892//17892 -f 17892//17892 17818//17818 17820//17820 -f 17892//17892 17820//17820 17894//17894 -f 17894//17894 17820//17820 17822//17822 -f 17894//17894 17822//17822 17896//17896 -f 17896//17896 17822//17822 17824//17824 -f 17896//17896 17824//17824 17898//17898 -f 17898//17898 17824//17824 17825//17825 -f 17898//17898 17825//17825 18011//18011 -f 18011//18011 17825//17825 17962//17962 -f 18011//18011 17962//17962 18012//18012 -f 18012//18012 17962//17962 17963//17963 -f 18012//18012 17963//17963 18013//18013 -f 18013//18013 17963//17963 17964//17964 -f 18013//18013 17964//17964 18002//18002 -f 18002//18002 17964//17964 17965//17965 -f 18002//18002 17965//17965 17966//17966 -f 18014//18014 17993//17993 18015//18015 -f 18015//18015 17993//17993 17992//17992 -f 18015//18015 17992//17992 18016//18016 -f 18016//18016 17992//17992 17991//17991 -f 18016//18016 17991//17991 18017//18017 -f 18017//18017 17991//17991 17990//17990 -f 18017//18017 17990//17990 18018//18018 -f 18018//18018 17990//17990 17989//17989 -f 18018//18018 17989//17989 18019//18019 -f 18019//18019 17989//17989 17988//17988 -f 18019//18019 17988//17988 18020//18020 -f 18020//18020 17988//17988 17987//17987 -f 18020//18020 17987//17987 18021//18021 -f 18021//18021 17987//17987 17986//17986 -f 18021//18021 17986//17986 18022//18022 -f 18022//18022 17986//17986 17985//17985 -f 18022//18022 17985//17985 18023//18023 -f 17891//17891 17853//17853 17889//17889 -f 17889//17889 17853//17853 17851//17851 -f 17889//17889 17851//17851 17887//17887 -f 17887//17887 17851//17851 17849//17849 -f 17887//17887 17849//17849 17885//17885 -f 17885//17885 17849//17849 17847//17847 -f 17885//17885 17847//17847 17883//17883 -f 17883//17883 17847//17847 17845//17845 -f 17883//17883 17845//17845 17881//17881 -f 17881//17881 17845//17845 17843//17843 -f 17881//17881 17843//17843 17879//17879 -f 17879//17879 17843//17843 17841//17841 -f 17879//17879 17841//17841 17877//17877 -f 17877//17877 17841//17841 17839//17839 -f 17877//17877 17839//17839 17875//17875 -f 17875//17875 17839//17839 17837//17837 -f 17875//17875 17837//17837 17873//17873 -f 17985//17985 17984//17984 18023//18023 -f 18023//18023 17984//17984 17983//17983 -f 18023//18023 17983//17983 18024//18024 -f 18024//18024 17983//17983 17982//17982 -f 18024//18024 17982//17982 18025//18025 -f 18025//18025 17982//17982 17981//17981 -f 18025//18025 17981//17981 18026//18026 -f 18026//18026 17981//17981 17980//17980 -f 18026//18026 17980//17980 17899//17899 -f 17899//17899 17980//17980 17863//17863 -f 17899//17899 17863//17863 17897//17897 -f 17897//17897 17863//17863 17861//17861 -f 17897//17897 17861//17861 17895//17895 -f 17895//17895 17861//17861 17859//17859 -f 17895//17895 17859//17859 17893//17893 -f 17893//17893 17859//17859 17857//17857 -f 17893//17893 17857//17857 17891//17891 -f 17891//17891 17857//17857 17855//17855 -f 17891//17891 17855//17855 17853//17853 -f 17837//17837 17835//17835 17873//17873 -f 17873//17873 17835//17835 17833//17833 -f 17873//17873 17833//17833 17871//17871 -f 17871//17871 17833//17833 17831//17831 -f 17871//17871 17831//17831 17869//17869 -f 17869//17869 17831//17831 17829//17829 -f 17869//17869 17829//17829 17867//17867 -f 17867//17867 17829//17829 17827//17827 -f 17867//17867 17827//17827 17864//17864 -f 17864//17864 17827//17827 17826//17826 -f 17864//17864 17826//17826 18027//18027 -f 18027//18027 17826//17826 17997//17997 -f 18027//18027 17997//17997 18028//18028 -f 18028//18028 17997//17997 17996//17996 -f 18028//18028 17996//17996 18029//18029 -f 18029//18029 17996//17996 17995//17995 -f 18029//18029 17995//17995 18014//18014 -f 18014//18014 17995//17995 17994//17994 -f 18014//18014 17994//17994 17993//17993 -f 17899//17899 17898//17898 18011//18011 -f 17899//17899 18011//18011 18026//18026 -f 18026//18026 18011//18011 18012//18012 -f 18026//18026 18012//18012 18025//18025 -f 18025//18025 18012//18012 18013//18013 -f 18025//18025 18013//18013 18024//18024 -f 18024//18024 18013//18013 18002//18002 -f 18024//18024 18002//18002 18023//18023 -f 18023//18023 18002//18002 18003//18003 -f 18023//18023 18003//18003 18022//18022 -f 18022//18022 18003//18003 18004//18004 -f 18022//18022 18004//18004 18021//18021 -f 18021//18021 18004//18004 18005//18005 -f 18021//18021 18005//18005 18020//18020 -f 18020//18020 18005//18005 18006//18006 -f 18020//18020 18006//18006 18019//18019 -f 18019//18019 18006//18006 18007//18007 -f 18019//18019 18007//18007 18018//18018 -f 18018//18018 18007//18007 18008//18008 -f 18018//18018 18008//18008 18017//18017 -f 18017//18017 18008//18008 18009//18009 -f 18017//18017 18009//18009 18016//18016 -f 18016//18016 18009//18009 18010//18010 -f 18016//18016 18010//18010 18015//18015 -f 18015//18015 18010//18010 17998//17998 -f 18015//18015 17998//17998 18014//18014 -f 18014//18014 17998//17998 17999//17999 -f 18014//18014 17999//17999 18029//18029 -f 18029//18029 17999//17999 18000//18000 -f 18029//18029 18000//18000 18028//18028 -f 18028//18028 18000//18000 18001//18001 -f 18028//18028 18001//18001 18027//18027 -f 18027//18027 18001//18001 17865//17865 -f 18027//18027 17865//17865 17864//17864 -f 18030//18030 18031//18031 18032//18032 -f 18032//18032 18031//18031 18033//18033 -f 18032//18032 18033//18033 18034//18034 -f 18034//18034 18033//18033 18035//18035 -f 18034//18034 18035//18035 18036//18036 -f 18036//18036 18035//18035 18037//18037 -f 18036//18036 18037//18037 18038//18038 -f 18038//18038 18037//18037 18039//18039 -f 18038//18038 18039//18039 18040//18040 -f 18040//18040 18039//18039 18041//18041 -f 18040//18040 18041//18041 18042//18042 -f 18042//18042 18041//18041 18043//18043 -f 18042//18042 18043//18043 18044//18044 -f 18044//18044 18043//18043 18045//18045 -f 18044//18044 18045//18045 18046//18046 -f 18046//18046 18045//18045 18047//18047 -f 18046//18046 18047//18047 18048//18048 -f 18048//18048 18047//18047 18049//18049 -f 18048//18048 18049//18049 18050//18050 -f 18050//18050 18049//18049 18051//18051 -f 18050//18050 18051//18051 18052//18052 -f 18052//18052 18051//18051 18053//18053 -f 18052//18052 18053//18053 18054//18054 -f 18054//18054 18053//18053 18055//18055 -f 18054//18054 18055//18055 18056//18056 -f 18056//18056 18055//18055 18057//18057 -f 18056//18056 18057//18057 18058//18058 -f 18058//18058 18057//18057 18059//18059 -f 18060//18060 18061//18061 18062//18062 -f 18060//18060 18062//18062 18063//18063 -f 18063//18063 18062//18062 18064//18064 -f 18063//18063 18064//18064 18065//18065 -f 18065//18065 18064//18064 18066//18066 -f 18065//18065 18066//18066 18067//18067 -f 18067//18067 18066//18066 18068//18068 -f 18067//18067 18068//18068 18069//18069 -f 18069//18069 18068//18068 18070//18070 -f 18069//18069 18070//18070 18071//18071 -f 18071//18071 18070//18070 18072//18072 -f 18071//18071 18072//18072 18073//18073 -f 18073//18073 18072//18072 18074//18074 -f 18073//18073 18074//18074 18075//18075 -f 18075//18075 18074//18074 18076//18076 -f 18075//18075 18076//18076 18077//18077 -f 18077//18077 18076//18076 18078//18078 -f 18077//18077 18078//18078 18079//18079 -f 18079//18079 18078//18078 18080//18080 -f 18079//18079 18080//18080 18081//18081 -f 18081//18081 18080//18080 18082//18082 -f 18081//18081 18082//18082 18083//18083 -f 18083//18083 18082//18082 18084//18084 -f 18083//18083 18084//18084 18085//18085 -f 18085//18085 18084//18084 18086//18086 -f 18085//18085 18086//18086 18087//18087 -f 18087//18087 18086//18086 18088//18088 -f 18087//18087 18088//18088 18089//18089 -f 18089//18089 18088//18088 18090//18090 -f 18089//18089 18090//18090 18091//18091 -f 18091//18091 18090//18090 18092//18092 -f 18091//18091 18092//18092 18093//18093 -f 18093//18093 18092//18092 18094//18094 -f 18093//18093 18094//18094 18095//18095 -f 18095//18095 18094//18094 18096//18096 -f 18095//18095 18096//18096 18097//18097 -f 18097//18097 18096//18096 18098//18098 -f 18097//18097 18098//18098 18099//18099 -f 18100//18100 18101//18101 18102//18102 -f 18100//18100 18102//18102 18103//18103 -f 18103//18103 18102//18102 18104//18104 -f 18103//18103 18104//18104 18105//18105 -f 18105//18105 18104//18104 18106//18106 -f 18105//18105 18106//18106 18107//18107 -f 18107//18107 18106//18106 18108//18108 -f 18107//18107 18108//18108 18109//18109 -f 18109//18109 18108//18108 18110//18110 -f 18109//18109 18110//18110 18111//18111 -f 18111//18111 18110//18110 18112//18112 -f 18111//18111 18112//18112 18113//18113 -f 18113//18113 18112//18112 18114//18114 -f 18113//18113 18114//18114 18115//18115 -f 18115//18115 18114//18114 18116//18116 -f 18115//18115 18116//18116 18117//18117 -f 18117//18117 18116//18116 18118//18118 -f 18117//18117 18118//18118 18119//18119 -f 18119//18119 18118//18118 18120//18120 -f 18119//18119 18120//18120 18121//18121 -f 18121//18121 18120//18120 18122//18122 -f 18121//18121 18122//18122 18123//18123 -f 18123//18123 18122//18122 18124//18124 -f 18123//18123 18124//18124 18125//18125 -f 18125//18125 18124//18124 18126//18126 -f 18125//18125 18126//18126 18127//18127 -f 18127//18127 18126//18126 18128//18128 -f 18127//18127 18128//18128 18129//18129 -f 18129//18129 18128//18128 18130//18130 -f 18129//18129 18130//18130 18131//18131 -f 18131//18131 18130//18130 18132//18132 -f 18131//18131 18132//18132 18133//18133 -f 18133//18133 18132//18132 18134//18134 -f 18133//18133 18134//18134 18135//18135 -f 18135//18135 18134//18134 18136//18136 -f 18135//18135 18136//18136 18137//18137 -f 18137//18137 18136//18136 18138//18138 -f 18137//18137 18138//18138 18139//18139 -f 18140//18140 18141//18141 18142//18142 -f 18140//18140 18142//18142 18143//18143 -f 18143//18143 18142//18142 18144//18144 -f 18143//18143 18144//18144 18145//18145 -f 18145//18145 18144//18144 18146//18146 -f 18145//18145 18146//18146 18147//18147 -f 18147//18147 18146//18146 18148//18148 -f 18147//18147 18148//18148 18149//18149 -f 18149//18149 18148//18148 18150//18150 -f 18149//18149 18150//18150 18151//18151 -f 18151//18151 18150//18150 18152//18152 -f 18151//18151 18152//18152 18153//18153 -f 18153//18153 18152//18152 18154//18154 -f 18153//18153 18154//18154 18155//18155 -f 18155//18155 18154//18154 18156//18156 -f 18155//18155 18156//18156 18157//18157 -f 18157//18157 18156//18156 18158//18158 -f 18157//18157 18158//18158 18159//18159 -f 18159//18159 18158//18158 18160//18160 -f 18159//18159 18160//18160 18161//18161 -f 18161//18161 18160//18160 18162//18162 -f 18161//18161 18162//18162 18163//18163 -f 18163//18163 18162//18162 18164//18164 -f 18163//18163 18164//18164 18165//18165 -f 18165//18165 18164//18164 18166//18166 -f 18165//18165 18166//18166 18167//18167 -f 18167//18167 18166//18166 18168//18168 -f 18167//18167 18168//18168 18169//18169 -f 18169//18169 18168//18168 18170//18170 -f 18169//18169 18170//18170 18171//18171 -f 18171//18171 18170//18170 18172//18172 -f 18171//18171 18172//18172 18173//18173 -f 18173//18173 18172//18172 18174//18174 -f 18173//18173 18174//18174 18175//18175 -f 18058//18058 18059//18059 18176//18176 -f 18176//18176 18059//18059 18177//18177 -f 18176//18176 18177//18177 18178//18178 -f 18178//18178 18177//18177 18179//18179 -f 18178//18178 18179//18179 18180//18180 -f 18180//18180 18179//18179 18181//18181 -f 18180//18180 18181//18181 18182//18182 -f 18182//18182 18181//18181 18183//18183 -f 18182//18182 18183//18183 18184//18184 -f 18184//18184 18183//18183 18185//18185 -f 18184//18184 18185//18185 18186//18186 -f 18186//18186 18185//18185 18187//18187 -f 18186//18186 18187//18187 18188//18188 -f 18188//18188 18187//18187 18189//18189 -f 18188//18188 18189//18189 18190//18190 -f 18190//18190 18189//18189 18191//18191 -f 18190//18190 18191//18191 18192//18192 -f 18192//18192 18191//18191 18193//18193 -f 18192//18192 18193//18193 18194//18194 -f 18194//18194 18193//18193 18195//18195 -f 18194//18194 18195//18195 18196//18196 -f 18196//18196 18195//18195 18197//18197 -f 18196//18196 18197//18197 18198//18198 -f 18198//18198 18197//18197 18199//18199 -f 18198//18198 18199//18199 18200//18200 -f 18200//18200 18199//18199 18201//18201 -f 18200//18200 18201//18201 18030//18030 -f 18030//18030 18201//18201 18031//18031 -f 18046//18046 18202//18202 18044//18044 -f 18044//18044 18202//18202 18203//18203 -f 18044//18044 18203//18203 18042//18042 -f 18042//18042 18203//18203 18204//18204 -f 18042//18042 18204//18204 18040//18040 -f 18178//18178 18064//18064 18176//18176 -f 18176//18176 18064//18064 18062//18062 -f 18176//18176 18062//18062 18058//18058 -f 18058//18058 18062//18062 18061//18061 -f 18058//18058 18061//18061 18056//18056 -f 18184//18184 18072//18072 18182//18182 -f 18182//18182 18072//18072 18070//18070 -f 18182//18182 18070//18070 18180//18180 -f 18180//18180 18070//18070 18068//18068 -f 18180//18180 18068//18068 18178//18178 -f 18178//18178 18068//18068 18066//18066 -f 18178//18178 18066//18066 18064//18064 -f 18194//18194 18086//18086 18192//18192 -f 18192//18192 18086//18086 18084//18084 -f 18192//18192 18084//18084 18190//18190 -f 18190//18190 18084//18084 18082//18082 -f 18190//18190 18082//18082 18188//18188 -f 18200//18200 18094//18094 18198//18198 -f 18198//18198 18094//18094 18092//18092 -f 18198//18198 18092//18092 18196//18196 -f 18196//18196 18092//18092 18090//18090 -f 18196//18196 18090//18090 18194//18194 -f 18194//18194 18090//18090 18088//18088 -f 18194//18194 18088//18088 18086//18086 -f 18034//18034 18205//18205 18032//18032 -f 18032//18032 18205//18205 18206//18206 -f 18032//18032 18206//18206 18030//18030 -f 18030//18030 18206//18206 18098//18098 -f 18030//18030 18098//18098 18200//18200 -f 18200//18200 18098//18098 18096//18096 -f 18200//18200 18096//18096 18094//18094 -f 18204//18204 18207//18207 18040//18040 -f 18040//18040 18207//18207 18208//18208 -f 18040//18040 18208//18208 18038//18038 -f 18038//18038 18208//18208 18209//18209 -f 18038//18038 18209//18209 18036//18036 -f 18036//18036 18209//18209 18210//18210 -f 18036//18036 18210//18210 18034//18034 -f 18034//18034 18210//18210 18211//18211 -f 18034//18034 18211//18211 18205//18205 -f 18082//18082 18080//18080 18188//18188 -f 18188//18188 18080//18080 18078//18078 -f 18188//18188 18078//18078 18186//18186 -f 18186//18186 18078//18078 18076//18076 -f 18186//18186 18076//18076 18184//18184 -f 18184//18184 18076//18076 18074//18074 -f 18184//18184 18074//18074 18072//18072 -f 18061//18061 18212//18212 18056//18056 -f 18056//18056 18212//18212 18213//18213 -f 18056//18056 18213//18213 18054//18054 -f 18054//18054 18213//18213 18214//18214 -f 18054//18054 18214//18214 18052//18052 -f 18052//18052 18214//18214 18215//18215 -f 18052//18052 18215//18215 18050//18050 -f 18215//18215 18216//18216 18050//18050 -f 18050//18050 18216//18216 18217//18217 -f 18050//18050 18217//18217 18048//18048 -f 18048//18048 18217//18217 18218//18218 -f 18048//18048 18218//18218 18046//18046 -f 18046//18046 18218//18218 18219//18219 -f 18046//18046 18219//18219 18202//18202 -f 18187//18187 18119//18119 18189//18189 -f 18189//18189 18119//18119 18121//18121 -f 18189//18189 18121//18121 18191//18191 -f 18191//18191 18121//18121 18123//18123 -f 18191//18191 18123//18123 18193//18193 -f 18183//18183 18113//18113 18185//18185 -f 18185//18185 18113//18113 18115//18115 -f 18185//18185 18115//18115 18187//18187 -f 18187//18187 18115//18115 18117//18117 -f 18187//18187 18117//18117 18119//18119 -f 18177//18177 18105//18105 18179//18179 -f 18179//18179 18105//18105 18107//18107 -f 18179//18179 18107//18107 18181//18181 -f 18181//18181 18107//18107 18109//18109 -f 18181//18181 18109//18109 18183//18183 -f 18183//18183 18109//18109 18111//18111 -f 18183//18183 18111//18111 18113//18113 -f 18055//18055 18220//18220 18057//18057 -f 18057//18057 18220//18220 18221//18221 -f 18057//18057 18221//18221 18059//18059 -f 18059//18059 18221//18221 18100//18100 -f 18059//18059 18100//18100 18177//18177 -f 18177//18177 18100//18100 18103//18103 -f 18177//18177 18103//18103 18105//18105 -f 18123//18123 18125//18125 18193//18193 -f 18193//18193 18125//18125 18127//18127 -f 18193//18193 18127//18127 18195//18195 -f 18195//18195 18127//18127 18129//18129 -f 18195//18195 18129//18129 18197//18197 -f 18197//18197 18129//18129 18131//18131 -f 18197//18197 18131//18131 18199//18199 -f 18131//18131 18133//18133 18199//18199 -f 18199//18199 18133//18133 18135//18135 -f 18199//18199 18135//18135 18201//18201 -f 18201//18201 18135//18135 18137//18137 -f 18201//18201 18137//18137 18031//18031 -f 18031//18031 18137//18137 18139//18139 -f 18031//18031 18139//18139 18033//18033 -f 18049//18049 18222//18222 18051//18051 -f 18051//18051 18222//18222 18223//18223 -f 18051//18051 18223//18223 18053//18053 -f 18053//18053 18223//18223 18224//18224 -f 18053//18053 18224//18224 18055//18055 -f 18055//18055 18224//18224 18225//18225 -f 18055//18055 18225//18225 18220//18220 -f 18045//18045 18226//18226 18047//18047 -f 18047//18047 18226//18226 18227//18227 -f 18047//18047 18227//18227 18049//18049 -f 18049//18049 18227//18227 18228//18228 -f 18049//18049 18228//18228 18222//18222 -f 18039//18039 18229//18229 18041//18041 -f 18041//18041 18229//18229 18230//18230 -f 18041//18041 18230//18230 18043//18043 -f 18043//18043 18230//18230 18231//18231 -f 18043//18043 18231//18231 18045//18045 -f 18045//18045 18231//18231 18232//18232 -f 18045//18045 18232//18232 18226//18226 -f 18139//18139 18233//18233 18033//18033 -f 18033//18033 18233//18233 18234//18234 -f 18033//18033 18234//18234 18035//18035 -f 18035//18035 18234//18234 18235//18235 -f 18035//18035 18235//18235 18037//18037 -f 18037//18037 18235//18235 18236//18236 -f 18037//18037 18236//18236 18039//18039 -f 18039//18039 18236//18236 18237//18237 -f 18039//18039 18237//18237 18229//18229 -f 18099//18099 18098//18098 18206//18206 -f 18099//18099 18206//18206 18238//18238 -f 18238//18238 18206//18206 18205//18205 -f 18238//18238 18205//18205 18239//18239 -f 18239//18239 18205//18205 18211//18211 -f 18239//18239 18211//18211 18240//18240 -f 18240//18240 18211//18211 18210//18210 -f 18240//18240 18210//18210 18241//18241 -f 18241//18241 18210//18210 18209//18209 -f 18241//18241 18209//18209 18242//18242 -f 18242//18242 18209//18209 18208//18208 -f 18242//18242 18208//18208 18243//18243 -f 18243//18243 18208//18208 18207//18207 -f 18243//18243 18207//18207 18244//18244 -f 18244//18244 18207//18207 18204//18204 -f 18244//18244 18204//18204 18245//18245 -f 18245//18245 18204//18204 18203//18203 -f 18245//18245 18203//18203 18246//18246 -f 18246//18246 18203//18203 18202//18202 -f 18246//18246 18202//18202 18247//18247 -f 18247//18247 18202//18202 18219//18219 -f 18247//18247 18219//18219 18248//18248 -f 18248//18248 18219//18219 18218//18218 -f 18248//18248 18218//18218 18249//18249 -f 18249//18249 18218//18218 18217//18217 -f 18249//18249 18217//18217 18250//18250 -f 18250//18250 18217//18217 18216//18216 -f 18250//18250 18216//18216 18251//18251 -f 18251//18251 18216//18216 18215//18215 -f 18251//18251 18215//18215 18252//18252 -f 18252//18252 18215//18215 18214//18214 -f 18252//18252 18214//18214 18253//18253 -f 18253//18253 18214//18214 18213//18213 -f 18253//18253 18213//18213 18254//18254 -f 18254//18254 18213//18213 18212//18212 -f 18254//18254 18212//18212 18255//18255 -f 18255//18255 18212//18212 18061//18061 -f 18255//18255 18061//18061 18060//18060 -f 18139//18139 18138//18138 18256//18256 -f 18139//18139 18256//18256 18233//18233 -f 18233//18233 18256//18256 18257//18257 -f 18233//18233 18257//18257 18234//18234 -f 18234//18234 18257//18257 18258//18258 -f 18234//18234 18258//18258 18235//18235 -f 18235//18235 18258//18258 18259//18259 -f 18235//18235 18259//18259 18236//18236 -f 18236//18236 18259//18259 18260//18260 -f 18236//18236 18260//18260 18237//18237 -f 18237//18237 18260//18260 18261//18261 -f 18237//18237 18261//18261 18229//18229 -f 18229//18229 18261//18261 18262//18262 -f 18229//18229 18262//18262 18230//18230 -f 18230//18230 18262//18262 18263//18263 -f 18230//18230 18263//18263 18231//18231 -f 18231//18231 18263//18263 18264//18264 -f 18231//18231 18264//18264 18232//18232 -f 18232//18232 18264//18264 18265//18265 -f 18232//18232 18265//18265 18226//18226 -f 18226//18226 18265//18265 18266//18266 -f 18226//18226 18266//18266 18227//18227 -f 18227//18227 18266//18266 18267//18267 -f 18227//18227 18267//18267 18228//18228 -f 18228//18228 18267//18267 18268//18268 -f 18228//18228 18268//18268 18222//18222 -f 18222//18222 18268//18268 18269//18269 -f 18222//18222 18269//18269 18223//18223 -f 18223//18223 18269//18269 18270//18270 -f 18223//18223 18270//18270 18224//18224 -f 18224//18224 18270//18270 18271//18271 -f 18224//18224 18271//18271 18225//18225 -f 18225//18225 18271//18271 18272//18272 -f 18225//18225 18272//18272 18220//18220 -f 18220//18220 18272//18272 18273//18273 -f 18220//18220 18273//18273 18221//18221 -f 18221//18221 18273//18273 18101//18101 -f 18221//18221 18101//18101 18100//18100 -f 18274//18274 18252//18252 18275//18275 -f 18275//18275 18252//18252 18253//18253 -f 18275//18275 18253//18253 18276//18276 -f 18276//18276 18253//18253 18254//18254 -f 18276//18276 18254//18254 18277//18277 -f 18277//18277 18254//18254 18255//18255 -f 18277//18277 18255//18255 18141//18141 -f 18141//18141 18255//18255 18060//18060 -f 18141//18141 18060//18060 18142//18142 -f 18142//18142 18060//18060 18063//18063 -f 18142//18142 18063//18063 18144//18144 -f 18144//18144 18063//18063 18065//18065 -f 18144//18144 18065//18065 18146//18146 -f 18146//18146 18065//18065 18067//18067 -f 18146//18146 18067//18067 18148//18148 -f 18067//18067 18069//18069 18148//18148 -f 18148//18148 18069//18069 18071//18071 -f 18148//18148 18071//18071 18150//18150 -f 18150//18150 18071//18071 18073//18073 -f 18150//18150 18073//18073 18152//18152 -f 18152//18152 18073//18073 18075//18075 -f 18152//18152 18075//18075 18154//18154 -f 18154//18154 18075//18075 18077//18077 -f 18154//18154 18077//18077 18156//18156 -f 18156//18156 18077//18077 18079//18079 -f 18156//18156 18079//18079 18158//18158 -f 18158//18158 18079//18079 18081//18081 -f 18158//18158 18081//18081 18160//18160 -f 18160//18160 18081//18081 18083//18083 -f 18160//18160 18083//18083 18162//18162 -f 18162//18162 18083//18083 18085//18085 -f 18162//18162 18085//18085 18164//18164 -f 18164//18164 18085//18085 18087//18087 -f 18164//18164 18087//18087 18166//18166 -f 18087//18087 18089//18089 18166//18166 -f 18166//18166 18089//18089 18091//18091 -f 18166//18166 18091//18091 18168//18168 -f 18168//18168 18091//18091 18093//18093 -f 18168//18168 18093//18093 18170//18170 -f 18170//18170 18093//18093 18095//18095 -f 18170//18170 18095//18095 18172//18172 -f 18172//18172 18095//18095 18097//18097 -f 18172//18172 18097//18097 18174//18174 -f 18174//18174 18097//18097 18099//18099 -f 18174//18174 18099//18099 18278//18278 -f 18278//18278 18099//18099 18238//18238 -f 18278//18278 18238//18238 18279//18279 -f 18279//18279 18238//18238 18239//18239 -f 18279//18279 18239//18239 18280//18280 -f 18280//18280 18239//18239 18240//18240 -f 18280//18280 18240//18240 18281//18281 -f 18240//18240 18241//18241 18281//18281 -f 18281//18281 18241//18241 18242//18242 -f 18281//18281 18242//18242 18282//18282 -f 18282//18282 18242//18242 18243//18243 -f 18282//18282 18243//18243 18283//18283 -f 18283//18283 18243//18243 18244//18244 -f 18283//18283 18244//18244 18284//18284 -f 18284//18284 18244//18244 18245//18245 -f 18284//18284 18245//18245 18285//18285 -f 18285//18285 18245//18245 18246//18246 -f 18285//18285 18246//18246 18286//18286 -f 18286//18286 18246//18246 18247//18247 -f 18286//18286 18247//18247 18287//18287 -f 18287//18287 18247//18247 18248//18248 -f 18287//18287 18248//18248 18288//18288 -f 18288//18288 18248//18248 18249//18249 -f 18288//18288 18249//18249 18289//18289 -f 18289//18289 18249//18249 18250//18250 -f 18289//18289 18250//18250 18274//18274 -f 18274//18274 18250//18250 18251//18251 -f 18274//18274 18251//18251 18252//18252 -f 18290//18290 18259//18259 18291//18291 -f 18291//18291 18259//18259 18258//18258 -f 18291//18291 18258//18258 18292//18292 -f 18292//18292 18258//18258 18257//18257 -f 18292//18292 18257//18257 18293//18293 -f 18293//18293 18257//18257 18256//18256 -f 18293//18293 18256//18256 18175//18175 -f 18175//18175 18256//18256 18138//18138 -f 18175//18175 18138//18138 18173//18173 -f 18173//18173 18138//18138 18136//18136 -f 18173//18173 18136//18136 18171//18171 -f 18171//18171 18136//18136 18134//18134 -f 18171//18171 18134//18134 18169//18169 -f 18169//18169 18134//18134 18132//18132 -f 18169//18169 18132//18132 18167//18167 -f 18132//18132 18130//18130 18167//18167 -f 18167//18167 18130//18130 18128//18128 -f 18167//18167 18128//18128 18165//18165 -f 18165//18165 18128//18128 18126//18126 -f 18165//18165 18126//18126 18163//18163 -f 18163//18163 18126//18126 18124//18124 -f 18163//18163 18124//18124 18161//18161 -f 18161//18161 18124//18124 18122//18122 -f 18161//18161 18122//18122 18159//18159 -f 18159//18159 18122//18122 18120//18120 -f 18159//18159 18120//18120 18157//18157 -f 18157//18157 18120//18120 18118//18118 -f 18157//18157 18118//18118 18155//18155 -f 18155//18155 18118//18118 18116//18116 -f 18155//18155 18116//18116 18153//18153 -f 18153//18153 18116//18116 18114//18114 -f 18153//18153 18114//18114 18151//18151 -f 18151//18151 18114//18114 18112//18112 -f 18151//18151 18112//18112 18149//18149 -f 18294//18294 18269//18269 18295//18295 -f 18295//18295 18269//18269 18268//18268 -f 18295//18295 18268//18268 18296//18296 -f 18296//18296 18268//18268 18267//18267 -f 18296//18296 18267//18267 18297//18297 -f 18297//18297 18267//18267 18266//18266 -f 18297//18297 18266//18266 18298//18298 -f 18298//18298 18266//18266 18265//18265 -f 18298//18298 18265//18265 18299//18299 -f 18299//18299 18265//18265 18264//18264 -f 18299//18299 18264//18264 18300//18300 -f 18300//18300 18264//18264 18263//18263 -f 18300//18300 18263//18263 18301//18301 -f 18301//18301 18263//18263 18262//18262 -f 18301//18301 18262//18262 18302//18302 -f 18302//18302 18262//18262 18261//18261 -f 18302//18302 18261//18261 18290//18290 -f 18290//18290 18261//18261 18260//18260 -f 18290//18290 18260//18260 18259//18259 -f 18112//18112 18110//18110 18149//18149 -f 18149//18149 18110//18110 18108//18108 -f 18149//18149 18108//18108 18147//18147 -f 18147//18147 18108//18108 18106//18106 -f 18147//18147 18106//18106 18145//18145 -f 18145//18145 18106//18106 18104//18104 -f 18145//18145 18104//18104 18143//18143 -f 18143//18143 18104//18104 18102//18102 -f 18143//18143 18102//18102 18140//18140 -f 18140//18140 18102//18102 18101//18101 -f 18140//18140 18101//18101 18303//18303 -f 18303//18303 18101//18101 18273//18273 -f 18303//18303 18273//18273 18304//18304 -f 18304//18304 18273//18273 18272//18272 -f 18304//18304 18272//18272 18305//18305 -f 18305//18305 18272//18272 18271//18271 -f 18305//18305 18271//18271 18294//18294 -f 18294//18294 18271//18271 18270//18270 -f 18294//18294 18270//18270 18269//18269 -f 18175//18175 18174//18174 18278//18278 -f 18175//18175 18278//18278 18293//18293 -f 18293//18293 18278//18278 18279//18279 -f 18293//18293 18279//18279 18292//18292 -f 18292//18292 18279//18279 18280//18280 -f 18292//18292 18280//18280 18291//18291 -f 18291//18291 18280//18280 18281//18281 -f 18291//18291 18281//18281 18290//18290 -f 18290//18290 18281//18281 18282//18282 -f 18290//18290 18282//18282 18302//18302 -f 18302//18302 18282//18282 18283//18283 -f 18302//18302 18283//18283 18301//18301 -f 18301//18301 18283//18283 18284//18284 -f 18301//18301 18284//18284 18300//18300 -f 18300//18300 18284//18284 18285//18285 -f 18300//18300 18285//18285 18299//18299 -f 18299//18299 18285//18285 18286//18286 -f 18299//18299 18286//18286 18298//18298 -f 18298//18298 18286//18286 18287//18287 -f 18298//18298 18287//18287 18297//18297 -f 18297//18297 18287//18287 18288//18288 -f 18297//18297 18288//18288 18296//18296 -f 18296//18296 18288//18288 18289//18289 -f 18296//18296 18289//18289 18295//18295 -f 18295//18295 18289//18289 18274//18274 -f 18295//18295 18274//18274 18294//18294 -f 18294//18294 18274//18274 18275//18275 -f 18294//18294 18275//18275 18305//18305 -f 18305//18305 18275//18275 18276//18276 -f 18305//18305 18276//18276 18304//18304 -f 18304//18304 18276//18276 18277//18277 -f 18304//18304 18277//18277 18303//18303 -f 18303//18303 18277//18277 18141//18141 -f 18303//18303 18141//18141 18140//18140 -f 18306//18306 18307//18307 18308//18308 -f 18308//18308 18307//18307 18309//18309 -f 18308//18308 18309//18309 18310//18310 -f 18310//18310 18309//18309 18311//18311 -f 18310//18310 18311//18311 18312//18312 -f 18312//18312 18311//18311 18313//18313 -f 18312//18312 18313//18313 18314//18314 -f 18314//18314 18313//18313 18315//18315 -f 18314//18314 18315//18315 18316//18316 -f 18316//18316 18315//18315 18317//18317 -f 18316//18316 18317//18317 18318//18318 -f 18318//18318 18317//18317 18319//18319 -f 18318//18318 18319//18319 18320//18320 -f 18320//18320 18319//18319 18321//18321 -f 18320//18320 18321//18321 18322//18322 -f 18322//18322 18321//18321 18323//18323 -f 18322//18322 18323//18323 18324//18324 -f 18324//18324 18323//18323 18325//18325 -f 18324//18324 18325//18325 18326//18326 -f 18326//18326 18325//18325 18327//18327 -f 18326//18326 18327//18327 18328//18328 -f 18328//18328 18327//18327 18329//18329 -f 18328//18328 18329//18329 18330//18330 -f 18330//18330 18329//18329 18331//18331 -f 18330//18330 18331//18331 18332//18332 -f 18332//18332 18331//18331 18333//18333 -f 18332//18332 18333//18333 18334//18334 -f 18334//18334 18333//18333 18335//18335 -f 18336//18336 1057//1057 18337//18337 -f 18336//18336 18337//18337 18338//18338 -f 18338//18338 18337//18337 18339//18339 -f 18338//18338 18339//18339 18340//18340 -f 18340//18340 18339//18339 18341//18341 -f 18340//18340 18341//18341 18342//18342 -f 18342//18342 18341//18341 18343//18343 -f 18342//18342 18343//18343 18344//18344 -f 18344//18344 18343//18343 18345//18345 -f 18344//18344 18345//18345 18346//18346 -f 18346//18346 18345//18345 18347//18347 -f 18346//18346 18347//18347 18348//18348 -f 18348//18348 18347//18347 18349//18349 -f 18348//18348 18349//18349 18350//18350 -f 18350//18350 18349//18349 18351//18351 -f 18350//18350 18351//18351 18352//18352 -f 18352//18352 18351//18351 18353//18353 -f 18352//18352 18353//18353 18354//18354 -f 18354//18354 18353//18353 18355//18355 -f 18354//18354 18355//18355 18356//18356 -f 18356//18356 18355//18355 18357//18357 -f 18356//18356 18357//18357 18358//18358 -f 18358//18358 18357//18357 18359//18359 -f 18358//18358 18359//18359 18360//18360 -f 18360//18360 18359//18359 18361//18361 -f 18360//18360 18361//18361 18362//18362 -f 18362//18362 18361//18361 18363//18363 -f 18362//18362 18363//18363 18364//18364 -f 18364//18364 18363//18363 18365//18365 -f 18364//18364 18365//18365 18366//18366 -f 18366//18366 18365//18365 18367//18367 -f 18366//18366 18367//18367 18368//18368 -f 18368//18368 18367//18367 18369//18369 -f 18368//18368 18369//18369 18370//18370 -f 18370//18370 18369//18369 18371//18371 -f 18370//18370 18371//18371 18372//18372 -f 18372//18372 18371//18371 1045//1045 -f 18372//18372 1045//1045 18373//18373 -f 1058//1058 18374//18374 18375//18375 -f 1058//1058 18375//18375 18376//18376 -f 18376//18376 18375//18375 18377//18377 -f 18376//18376 18377//18377 18378//18378 -f 18378//18378 18377//18377 18379//18379 -f 18378//18378 18379//18379 18380//18380 -f 18380//18380 18379//18379 18381//18381 -f 18380//18380 18381//18381 18382//18382 -f 18382//18382 18381//18381 18383//18383 -f 18382//18382 18383//18383 18384//18384 -f 18384//18384 18383//18383 18385//18385 -f 18384//18384 18385//18385 18386//18386 -f 18386//18386 18385//18385 18387//18387 -f 18386//18386 18387//18387 18388//18388 -f 18388//18388 18387//18387 18389//18389 -f 18388//18388 18389//18389 18390//18390 -f 18390//18390 18389//18389 18391//18391 -f 18390//18390 18391//18391 18392//18392 -f 18392//18392 18391//18391 18393//18393 -f 18392//18392 18393//18393 18394//18394 -f 18394//18394 18393//18393 18395//18395 -f 18394//18394 18395//18395 18396//18396 -f 18396//18396 18395//18395 18397//18397 -f 18396//18396 18397//18397 18398//18398 -f 18398//18398 18397//18397 18399//18399 -f 18398//18398 18399//18399 18400//18400 -f 18400//18400 18399//18399 18401//18401 -f 18400//18400 18401//18401 18402//18402 -f 18402//18402 18401//18401 18403//18403 -f 18402//18402 18403//18403 18404//18404 -f 18404//18404 18403//18403 18405//18405 -f 18404//18404 18405//18405 18406//18406 -f 18406//18406 18405//18405 18407//18407 -f 18406//18406 18407//18407 18408//18408 -f 18408//18408 18407//18407 18409//18409 -f 18408//18408 18409//18409 18410//18410 -f 18410//18410 18409//18409 18411//18411 -f 18410//18410 18411//18411 1046//1046 -f 18412//18412 18413//18413 18414//18414 -f 18412//18412 18414//18414 18415//18415 -f 18415//18415 18414//18414 18416//18416 -f 18415//18415 18416//18416 18417//18417 -f 18417//18417 18416//18416 18418//18418 -f 18417//18417 18418//18418 18419//18419 -f 18419//18419 18418//18418 18420//18420 -f 18419//18419 18420//18420 18421//18421 -f 18421//18421 18420//18420 18422//18422 -f 18421//18421 18422//18422 18423//18423 -f 18423//18423 18422//18422 18424//18424 -f 18423//18423 18424//18424 18425//18425 -f 18425//18425 18424//18424 18426//18426 -f 18425//18425 18426//18426 18427//18427 -f 18427//18427 18426//18426 18428//18428 -f 18427//18427 18428//18428 18429//18429 -f 18429//18429 18428//18428 18430//18430 -f 18429//18429 18430//18430 18431//18431 -f 18431//18431 18430//18430 18432//18432 -f 18431//18431 18432//18432 18433//18433 -f 18433//18433 18432//18432 18434//18434 -f 18433//18433 18434//18434 18435//18435 -f 18435//18435 18434//18434 18436//18436 -f 18435//18435 18436//18436 18437//18437 -f 18437//18437 18436//18436 18438//18438 -f 18437//18437 18438//18438 18439//18439 -f 18439//18439 18438//18438 18440//18440 -f 18439//18439 18440//18440 18441//18441 -f 18441//18441 18440//18440 18442//18442 -f 18441//18441 18442//18442 18443//18443 -f 18443//18443 18442//18442 18444//18444 -f 18443//18443 18444//18444 18445//18445 -f 18445//18445 18444//18444 18446//18446 -f 18445//18445 18446//18446 18447//18447 -f 18334//18334 18335//18335 18448//18448 -f 18448//18448 18335//18335 18449//18449 -f 18448//18448 18449//18449 18450//18450 -f 18450//18450 18449//18449 18451//18451 -f 18450//18450 18451//18451 18452//18452 -f 18452//18452 18451//18451 18453//18453 -f 18452//18452 18453//18453 18454//18454 -f 18454//18454 18453//18453 18455//18455 -f 18454//18454 18455//18455 18456//18456 -f 18456//18456 18455//18455 18457//18457 -f 18456//18456 18457//18457 18458//18458 -f 18458//18458 18457//18457 18459//18459 -f 18458//18458 18459//18459 18460//18460 -f 18460//18460 18459//18459 18461//18461 -f 18460//18460 18461//18461 18462//18462 -f 18462//18462 18461//18461 18463//18463 -f 18462//18462 18463//18463 18464//18464 -f 18464//18464 18463//18463 18465//18465 -f 18464//18464 18465//18465 18466//18466 -f 18466//18466 18465//18465 18467//18467 -f 18466//18466 18467//18467 18468//18468 -f 18468//18468 18467//18467 18469//18469 -f 18468//18468 18469//18469 18470//18470 -f 18470//18470 18469//18469 18471//18471 -f 18470//18470 18471//18471 18472//18472 -f 18472//18472 18471//18471 18473//18473 -f 18472//18472 18473//18473 18306//18306 -f 18306//18306 18473//18473 18307//18307 -f 18322//18322 18474//18474 18320//18320 -f 18320//18320 18474//18474 18475//18475 -f 18320//18320 18475//18475 18318//18318 -f 18318//18318 18475//18475 18476//18476 -f 18318//18318 18476//18476 18316//18316 -f 18310//18310 18477//18477 18308//18308 -f 18308//18308 18477//18477 18478//18478 -f 18308//18308 18478//18478 18306//18306 -f 18306//18306 18478//18478 1045//1045 -f 18306//18306 1045//1045 18472//18472 -f 18476//18476 18479//18479 18316//18316 -f 18316//18316 18479//18479 18480//18480 -f 18316//18316 18480//18480 18314//18314 -f 18314//18314 18480//18480 18481//18481 -f 18314//18314 18481//18481 18312//18312 -f 18312//18312 18481//18481 18482//18482 -f 18312//18312 18482//18482 18310//18310 -f 18310//18310 18482//18482 18483//18483 -f 18310//18310 18483//18483 18477//18477 -f 18462//18462 18355//18355 18460//18460 -f 18460//18460 18355//18355 18353//18353 -f 18460//18460 18353//18353 18458//18458 -f 18458//18458 18353//18353 18351//18351 -f 18458//18458 18351//18351 18456//18456 -f 18326//18326 18484//18484 18324//18324 -f 18324//18324 18484//18484 18485//18485 -f 18324//18324 18485//18485 18322//18322 -f 18322//18322 18485//18485 18486//18486 -f 18322//18322 18486//18486 18474//18474 -f 18332//18332 18487//18487 18330//18330 -f 18330//18330 18487//18487 18488//18488 -f 18330//18330 18488//18488 18328//18328 -f 18328//18328 18488//18488 18489//18489 -f 18328//18328 18489//18489 18326//18326 -f 18326//18326 18489//18489 18490//18490 -f 18326//18326 18490//18490 18484//18484 -f 18450//18450 18339//18339 18448//18448 -f 18448//18448 18339//18339 18337//18337 -f 18448//18448 18337//18337 18334//18334 -f 18334//18334 18337//18337 1057//1057 -f 18334//18334 1057//1057 18332//18332 -f 18332//18332 1057//1057 18491//18491 -f 18332//18332 18491//18491 18487//18487 -f 18351//18351 18349//18349 18456//18456 -f 18456//18456 18349//18349 18347//18347 -f 18456//18456 18347//18347 18454//18454 -f 18454//18454 18347//18347 18345//18345 -f 18454//18454 18345//18345 18452//18452 -f 18452//18452 18345//18345 18343//18343 -f 18452//18452 18343//18343 18450//18450 -f 18450//18450 18343//18343 18341//18341 -f 18450//18450 18341//18341 18339//18339 -f 18466//18466 18361//18361 18464//18464 -f 18464//18464 18361//18361 18359//18359 -f 18464//18464 18359//18359 18462//18462 -f 18462//18462 18359//18359 18357//18357 -f 18462//18462 18357//18357 18355//18355 -f 1045//1045 18371//18371 18472//18472 -f 18472//18472 18371//18371 18369//18369 -f 18472//18472 18369//18369 18470//18470 -f 18470//18470 18369//18369 18367//18367 -f 18470//18470 18367//18367 18468//18468 -f 18468//18468 18367//18367 18365//18365 -f 18468//18468 18365//18365 18466//18466 -f 18466//18466 18365//18365 18363//18363 -f 18466//18466 18363//18363 18361//18361 -f 18331//18331 18492//18492 18333//18333 -f 18333//18333 18492//18492 18493//18493 -f 18333//18333 18493//18493 18335//18335 -f 18335//18335 18493//18493 1058//1058 -f 18335//18335 1058//1058 18449//18449 -f 18325//18325 18494//18494 18327//18327 -f 18327//18327 18494//18494 18495//18495 -f 18327//18327 18495//18495 18329//18329 -f 18329//18329 18495//18495 18496//18496 -f 18329//18329 18496//18496 18331//18331 -f 18331//18331 18496//18496 18497//18497 -f 18331//18331 18497//18497 18492//18492 -f 18319//18319 18498//18498 18321//18321 -f 18321//18321 18498//18498 18499//18499 -f 18321//18321 18499//18499 18323//18323 -f 18323//18323 18499//18499 18500//18500 -f 18323//18323 18500//18500 18325//18325 -f 18325//18325 18500//18500 18501//18501 -f 18325//18325 18501//18501 18494//18494 -f 18315//18315 18502//18502 18317//18317 -f 18317//18317 18502//18502 18503//18503 -f 18317//18317 18503//18503 18319//18319 -f 18319//18319 18503//18503 18504//18504 -f 18319//18319 18504//18504 18498//18498 -f 18459//18459 18392//18392 18461//18461 -f 18461//18461 18392//18392 18394//18394 -f 18461//18461 18394//18394 18463//18463 -f 18463//18463 18394//18394 18396//18396 -f 18463//18463 18396//18396 18465//18465 -f 18471//18471 18408//18408 18473//18473 -f 18473//18473 18408//18408 18410//18410 -f 18473//18473 18410//18410 18307//18307 -f 18307//18307 18410//18410 1046//1046 -f 18307//18307 1046//1046 18309//18309 -f 18396//18396 18398//18398 18465//18465 -f 18465//18465 18398//18398 18400//18400 -f 18465//18465 18400//18400 18467//18467 -f 18467//18467 18400//18400 18402//18402 -f 18467//18467 18402//18402 18469//18469 -f 18469//18469 18402//18402 18404//18404 -f 18469//18469 18404//18404 18471//18471 -f 18471//18471 18404//18404 18406//18406 -f 18471//18471 18406//18406 18408//18408 -f 18455//18455 18386//18386 18457//18457 -f 18457//18457 18386//18386 18388//18388 -f 18457//18457 18388//18388 18459//18459 -f 18459//18459 18388//18388 18390//18390 -f 18459//18459 18390//18390 18392//18392 -f 1058//1058 18376//18376 18449//18449 -f 18449//18449 18376//18376 18378//18378 -f 18449//18449 18378//18378 18451//18451 -f 18451//18451 18378//18378 18380//18380 -f 18451//18451 18380//18380 18453//18453 -f 18453//18453 18380//18380 18382//18382 -f 18453//18453 18382//18382 18455//18455 -f 18455//18455 18382//18382 18384//18384 -f 18455//18455 18384//18384 18386//18386 -f 1046//1046 18505//18505 18309//18309 -f 18309//18309 18505//18505 18506//18506 -f 18309//18309 18506//18506 18311//18311 -f 18311//18311 18506//18506 18507//18507 -f 18311//18311 18507//18507 18313//18313 -f 18313//18313 18507//18507 18508//18508 -f 18313//18313 18508//18508 18315//18315 -f 18315//18315 18508//18508 18509//18509 -f 18315//18315 18509//18509 18502//18502 -f 18373//18373 1045//1045 18478//18478 -f 18373//18373 18478//18478 18510//18510 -f 18510//18510 18478//18478 18477//18477 -f 18510//18510 18477//18477 18511//18511 -f 18511//18511 18477//18477 18483//18483 -f 18511//18511 18483//18483 18512//18512 -f 18512//18512 18483//18483 18482//18482 -f 18512//18512 18482//18482 18513//18513 -f 18513//18513 18482//18482 18481//18481 -f 18513//18513 18481//18481 18514//18514 -f 18514//18514 18481//18481 18480//18480 -f 18514//18514 18480//18480 18515//18515 -f 18515//18515 18480//18480 18479//18479 -f 18515//18515 18479//18479 18516//18516 -f 18516//18516 18479//18479 18476//18476 -f 18516//18516 18476//18476 18517//18517 -f 18517//18517 18476//18476 18475//18475 -f 18517//18517 18475//18475 18518//18518 -f 18518//18518 18475//18475 18474//18474 -f 18518//18518 18474//18474 18519//18519 -f 18519//18519 18474//18474 18486//18486 -f 18519//18519 18486//18486 18520//18520 -f 18520//18520 18486//18486 18485//18485 -f 18520//18520 18485//18485 18521//18521 -f 18521//18521 18485//18485 18484//18484 -f 18521//18521 18484//18484 18522//18522 -f 18522//18522 18484//18484 18490//18490 -f 18522//18522 18490//18490 18523//18523 -f 18523//18523 18490//18490 18489//18489 -f 18523//18523 18489//18489 18524//18524 -f 18524//18524 18489//18489 18488//18488 -f 18524//18524 18488//18488 18525//18525 -f 18525//18525 18488//18488 18487//18487 -f 18525//18525 18487//18487 18526//18526 -f 18526//18526 18487//18487 18491//18491 -f 18526//18526 18491//18491 18527//18527 -f 18527//18527 18491//18491 1057//1057 -f 18527//18527 1057//1057 18336//18336 -f 1046//1046 18411//18411 18528//18528 -f 1046//1046 18528//18528 18505//18505 -f 18505//18505 18528//18528 18529//18529 -f 18505//18505 18529//18529 18506//18506 -f 18506//18506 18529//18529 18530//18530 -f 18506//18506 18530//18530 18507//18507 -f 18507//18507 18530//18530 18531//18531 -f 18507//18507 18531//18531 18508//18508 -f 18508//18508 18531//18531 18532//18532 -f 18508//18508 18532//18532 18509//18509 -f 18509//18509 18532//18532 18533//18533 -f 18509//18509 18533//18533 18502//18502 -f 18502//18502 18533//18533 18534//18534 -f 18502//18502 18534//18534 18503//18503 -f 18503//18503 18534//18534 18535//18535 -f 18503//18503 18535//18535 18504//18504 -f 18504//18504 18535//18535 18536//18536 -f 18504//18504 18536//18536 18498//18498 -f 18498//18498 18536//18536 18537//18537 -f 18498//18498 18537//18537 18499//18499 -f 18499//18499 18537//18537 18538//18538 -f 18499//18499 18538//18538 18500//18500 -f 18500//18500 18538//18538 18539//18539 -f 18500//18500 18539//18539 18501//18501 -f 18501//18501 18539//18539 18540//18540 -f 18501//18501 18540//18540 18494//18494 -f 18494//18494 18540//18540 18541//18541 -f 18494//18494 18541//18541 18495//18495 -f 18495//18495 18541//18541 18542//18542 -f 18495//18495 18542//18542 18496//18496 -f 18496//18496 18542//18542 18543//18543 -f 18496//18496 18543//18543 18497//18497 -f 18497//18497 18543//18543 18544//18544 -f 18497//18497 18544//18544 18492//18492 -f 18492//18492 18544//18544 18545//18545 -f 18492//18492 18545//18545 18493//18493 -f 18493//18493 18545//18545 18374//18374 -f 18493//18493 18374//18374 1058//1058 -f 18546//18546 18524//18524 18547//18547 -f 18547//18547 18524//18524 18525//18525 -f 18547//18547 18525//18525 18548//18548 -f 18548//18548 18525//18525 18526//18526 -f 18548//18548 18526//18526 18549//18549 -f 18549//18549 18526//18526 18527//18527 -f 18549//18549 18527//18527 18413//18413 -f 18413//18413 18527//18527 18336//18336 -f 18413//18413 18336//18336 18414//18414 -f 18414//18414 18336//18336 18338//18338 -f 18414//18414 18338//18338 18416//18416 -f 18416//18416 18338//18338 18340//18340 -f 18416//18416 18340//18340 18418//18418 -f 18418//18418 18340//18340 18342//18342 -f 18418//18418 18342//18342 18420//18420 -f 18550//18550 18514//18514 18551//18551 -f 18551//18551 18514//18514 18515//18515 -f 18551//18551 18515//18515 18552//18552 -f 18552//18552 18515//18515 18516//18516 -f 18552//18552 18516//18516 18553//18553 -f 18553//18553 18516//18516 18517//18517 -f 18553//18553 18517//18517 18554//18554 -f 18554//18554 18517//18517 18518//18518 -f 18554//18554 18518//18518 18555//18555 -f 18555//18555 18518//18518 18519//18519 -f 18555//18555 18519//18519 18556//18556 -f 18556//18556 18519//18519 18520//18520 -f 18556//18556 18520//18520 18557//18557 -f 18557//18557 18520//18520 18521//18521 -f 18557//18557 18521//18521 18558//18558 -f 18558//18558 18521//18521 18522//18522 -f 18558//18558 18522//18522 18546//18546 -f 18546//18546 18522//18522 18523//18523 -f 18546//18546 18523//18523 18524//18524 -f 18438//18438 18366//18366 18440//18440 -f 18440//18440 18366//18366 18368//18368 -f 18440//18440 18368//18368 18442//18442 -f 18442//18442 18368//18368 18370//18370 -f 18442//18442 18370//18370 18444//18444 -f 18444//18444 18370//18370 18372//18372 -f 18444//18444 18372//18372 18446//18446 -f 18446//18446 18372//18372 18373//18373 -f 18446//18446 18373//18373 18559//18559 -f 18559//18559 18373//18373 18510//18510 -f 18559//18559 18510//18510 18560//18560 -f 18560//18560 18510//18510 18511//18511 -f 18560//18560 18511//18511 18561//18561 -f 18561//18561 18511//18511 18512//18512 -f 18561//18561 18512//18512 18550//18550 -f 18550//18550 18512//18512 18513//18513 -f 18550//18550 18513//18513 18514//18514 -f 18342//18342 18344//18344 18420//18420 -f 18420//18420 18344//18344 18346//18346 -f 18420//18420 18346//18346 18422//18422 -f 18422//18422 18346//18346 18348//18348 -f 18422//18422 18348//18348 18424//18424 -f 18424//18424 18348//18348 18350//18350 -f 18424//18424 18350//18350 18426//18426 -f 18426//18426 18350//18350 18352//18352 -f 18426//18426 18352//18352 18428//18428 -f 18428//18428 18352//18352 18354//18354 -f 18428//18428 18354//18354 18430//18430 -f 18430//18430 18354//18354 18356//18356 -f 18430//18430 18356//18356 18432//18432 -f 18432//18432 18356//18356 18358//18358 -f 18432//18432 18358//18358 18434//18434 -f 18434//18434 18358//18358 18360//18360 -f 18434//18434 18360//18360 18436//18436 -f 18436//18436 18360//18360 18362//18362 -f 18436//18436 18362//18362 18438//18438 -f 18438//18438 18362//18362 18364//18364 -f 18438//18438 18364//18364 18366//18366 -f 18562//18562 18531//18531 18563//18563 -f 18563//18563 18531//18531 18530//18530 -f 18563//18563 18530//18530 18564//18564 -f 18564//18564 18530//18530 18529//18529 -f 18564//18564 18529//18529 18565//18565 -f 18565//18565 18529//18529 18528//18528 -f 18565//18565 18528//18528 18447//18447 -f 18447//18447 18528//18528 18411//18411 -f 18447//18447 18411//18411 18445//18445 -f 18445//18445 18411//18411 18409//18409 -f 18445//18445 18409//18409 18443//18443 -f 18443//18443 18409//18409 18407//18407 -f 18443//18443 18407//18407 18441//18441 -f 18441//18441 18407//18407 18405//18405 -f 18441//18441 18405//18405 18439//18439 -f 18566//18566 18541//18541 18567//18567 -f 18567//18567 18541//18541 18540//18540 -f 18567//18567 18540//18540 18568//18568 -f 18568//18568 18540//18540 18539//18539 -f 18568//18568 18539//18539 18569//18569 -f 18569//18569 18539//18539 18538//18538 -f 18569//18569 18538//18538 18570//18570 -f 18570//18570 18538//18538 18537//18537 -f 18570//18570 18537//18537 18571//18571 -f 18571//18571 18537//18537 18536//18536 -f 18571//18571 18536//18536 18572//18572 -f 18572//18572 18536//18536 18535//18535 -f 18572//18572 18535//18535 18573//18573 -f 18573//18573 18535//18535 18534//18534 -f 18573//18573 18534//18534 18574//18574 -f 18574//18574 18534//18534 18533//18533 -f 18574//18574 18533//18533 18562//18562 -f 18562//18562 18533//18533 18532//18532 -f 18562//18562 18532//18532 18531//18531 -f 18421//18421 18381//18381 18419//18419 -f 18419//18419 18381//18381 18379//18379 -f 18419//18419 18379//18379 18417//18417 -f 18417//18417 18379//18379 18377//18377 -f 18417//18417 18377//18377 18415//18415 -f 18415//18415 18377//18377 18375//18375 -f 18415//18415 18375//18375 18412//18412 -f 18412//18412 18375//18375 18374//18374 -f 18412//18412 18374//18374 18575//18575 -f 18575//18575 18374//18374 18545//18545 -f 18575//18575 18545//18545 18576//18576 -f 18576//18576 18545//18545 18544//18544 -f 18576//18576 18544//18544 18577//18577 -f 18577//18577 18544//18544 18543//18543 -f 18577//18577 18543//18543 18566//18566 -f 18566//18566 18543//18543 18542//18542 -f 18566//18566 18542//18542 18541//18541 -f 18405//18405 18403//18403 18439//18439 -f 18439//18439 18403//18403 18401//18401 -f 18439//18439 18401//18401 18437//18437 -f 18437//18437 18401//18401 18399//18399 -f 18437//18437 18399//18399 18435//18435 -f 18435//18435 18399//18399 18397//18397 -f 18435//18435 18397//18397 18433//18433 -f 18433//18433 18397//18397 18395//18395 -f 18433//18433 18395//18395 18431//18431 -f 18431//18431 18395//18395 18393//18393 -f 18431//18431 18393//18393 18429//18429 -f 18429//18429 18393//18393 18391//18391 -f 18429//18429 18391//18391 18427//18427 -f 18427//18427 18391//18391 18389//18389 -f 18427//18427 18389//18389 18425//18425 -f 18425//18425 18389//18389 18387//18387 -f 18425//18425 18387//18387 18423//18423 -f 18423//18423 18387//18387 18385//18385 -f 18423//18423 18385//18385 18421//18421 -f 18421//18421 18385//18385 18383//18383 -f 18421//18421 18383//18383 18381//18381 -f 18447//18447 18446//18446 18559//18559 -f 18447//18447 18559//18559 18565//18565 -f 18565//18565 18559//18559 18560//18560 -f 18565//18565 18560//18560 18564//18564 -f 18564//18564 18560//18560 18561//18561 -f 18564//18564 18561//18561 18563//18563 -f 18563//18563 18561//18561 18550//18550 -f 18563//18563 18550//18550 18562//18562 -f 18562//18562 18550//18550 18551//18551 -f 18562//18562 18551//18551 18574//18574 -f 18574//18574 18551//18551 18552//18552 -f 18574//18574 18552//18552 18573//18573 -f 18573//18573 18552//18552 18553//18553 -f 18573//18573 18553//18553 18572//18572 -f 18572//18572 18553//18553 18554//18554 -f 18572//18572 18554//18554 18571//18571 -f 18571//18571 18554//18554 18555//18555 -f 18571//18571 18555//18555 18570//18570 -f 18570//18570 18555//18555 18556//18556 -f 18570//18570 18556//18556 18569//18569 -f 18569//18569 18556//18556 18557//18557 -f 18569//18569 18557//18557 18568//18568 -f 18568//18568 18557//18557 18558//18558 -f 18568//18568 18558//18558 18567//18567 -f 18567//18567 18558//18558 18546//18546 -f 18567//18567 18546//18546 18566//18566 -f 18566//18566 18546//18546 18547//18547 -f 18566//18566 18547//18547 18577//18577 -f 18577//18577 18547//18547 18548//18548 -f 18577//18577 18548//18548 18576//18576 -f 18576//18576 18548//18548 18549//18549 -f 18576//18576 18549//18549 18575//18575 -f 18575//18575 18549//18549 18413//18413 -f 18575//18575 18413//18413 18412//18412 -f 18578//18578 18579//18579 18580//18580 -f 18580//18580 18579//18579 18581//18581 -f 18580//18580 18581//18581 18582//18582 -f 18582//18582 18581//18581 18583//18583 -f 18582//18582 18583//18583 18584//18584 -f 18584//18584 18583//18583 18585//18585 -f 18584//18584 18585//18585 18586//18586 -f 18586//18586 18585//18585 18587//18587 -f 18586//18586 18587//18587 18588//18588 -f 18588//18588 18587//18587 18589//18589 -f 18588//18588 18589//18589 18590//18590 -f 18590//18590 18589//18589 18591//18591 -f 18590//18590 18591//18591 18592//18592 -f 18592//18592 18591//18591 18593//18593 -f 18592//18592 18593//18593 18594//18594 -f 18594//18594 18593//18593 18595//18595 -f 18594//18594 18595//18595 18596//18596 -f 18596//18596 18595//18595 18597//18597 -f 18596//18596 18597//18597 18598//18598 -f 18598//18598 18597//18597 18599//18599 -f 18598//18598 18599//18599 18600//18600 -f 18600//18600 18599//18599 18601//18601 -f 18600//18600 18601//18601 18602//18602 -f 18602//18602 18601//18601 18603//18603 -f 18602//18602 18603//18603 18604//18604 -f 18604//18604 18603//18603 18605//18605 -f 18604//18604 18605//18605 18606//18606 -f 18606//18606 18605//18605 18607//18607 -f 18608//18608 1188//1188 18609//18609 -f 18608//18608 18609//18609 18610//18610 -f 18610//18610 18609//18609 18611//18611 -f 18610//18610 18611//18611 18612//18612 -f 18612//18612 18611//18611 18613//18613 -f 18612//18612 18613//18613 18614//18614 -f 18614//18614 18613//18613 18615//18615 -f 18614//18614 18615//18615 18616//18616 -f 18616//18616 18615//18615 18617//18617 -f 18616//18616 18617//18617 18618//18618 -f 18618//18618 18617//18617 18619//18619 -f 18618//18618 18619//18619 18620//18620 -f 18620//18620 18619//18619 18621//18621 -f 18620//18620 18621//18621 18622//18622 -f 18622//18622 18621//18621 18623//18623 -f 18622//18622 18623//18623 18624//18624 -f 18624//18624 18623//18623 18625//18625 -f 18624//18624 18625//18625 18626//18626 -f 18626//18626 18625//18625 18627//18627 -f 18626//18626 18627//18627 18628//18628 -f 18628//18628 18627//18627 18629//18629 -f 18628//18628 18629//18629 18630//18630 -f 18630//18630 18629//18629 18631//18631 -f 18630//18630 18631//18631 18632//18632 -f 18632//18632 18631//18631 18633//18633 -f 18632//18632 18633//18633 18634//18634 -f 18634//18634 18633//18633 18635//18635 -f 18634//18634 18635//18635 18636//18636 -f 18636//18636 18635//18635 18637//18637 -f 18636//18636 18637//18637 18638//18638 -f 18638//18638 18637//18637 18639//18639 -f 18638//18638 18639//18639 18640//18640 -f 18640//18640 18639//18639 18641//18641 -f 18640//18640 18641//18641 18642//18642 -f 18642//18642 18641//18641 18643//18643 -f 18642//18642 18643//18643 18644//18644 -f 18644//18644 18643//18643 1202//1202 -f 18644//18644 1202//1202 18645//18645 -f 1187//1187 18646//18646 18647//18647 -f 1187//1187 18647//18647 18648//18648 -f 18648//18648 18647//18647 18649//18649 -f 18648//18648 18649//18649 18650//18650 -f 18650//18650 18649//18649 18651//18651 -f 18650//18650 18651//18651 18652//18652 -f 18652//18652 18651//18651 18653//18653 -f 18652//18652 18653//18653 18654//18654 -f 18654//18654 18653//18653 18655//18655 -f 18654//18654 18655//18655 18656//18656 -f 18656//18656 18655//18655 18657//18657 -f 18656//18656 18657//18657 18658//18658 -f 18658//18658 18657//18657 18659//18659 -f 18658//18658 18659//18659 18660//18660 -f 18660//18660 18659//18659 18661//18661 -f 18660//18660 18661//18661 18662//18662 -f 18662//18662 18661//18661 18663//18663 -f 18662//18662 18663//18663 18664//18664 -f 18664//18664 18663//18663 18665//18665 -f 18664//18664 18665//18665 18666//18666 -f 18666//18666 18665//18665 18667//18667 -f 18666//18666 18667//18667 18668//18668 -f 18668//18668 18667//18667 18669//18669 -f 18668//18668 18669//18669 18670//18670 -f 18670//18670 18669//18669 18671//18671 -f 18670//18670 18671//18671 18672//18672 -f 18672//18672 18671//18671 18673//18673 -f 18672//18672 18673//18673 18674//18674 -f 18674//18674 18673//18673 18675//18675 -f 18674//18674 18675//18675 18676//18676 -f 18676//18676 18675//18675 18677//18677 -f 18676//18676 18677//18677 18678//18678 -f 18678//18678 18677//18677 18679//18679 -f 18678//18678 18679//18679 18680//18680 -f 18680//18680 18679//18679 18681//18681 -f 18680//18680 18681//18681 18682//18682 -f 18682//18682 18681//18681 18683//18683 -f 18682//18682 18683//18683 1201//1201 -f 18684//18684 18685//18685 18686//18686 -f 18684//18684 18686//18686 18687//18687 -f 18687//18687 18686//18686 18688//18688 -f 18687//18687 18688//18688 18689//18689 -f 18689//18689 18688//18688 18690//18690 -f 18689//18689 18690//18690 18691//18691 -f 18691//18691 18690//18690 18692//18692 -f 18691//18691 18692//18692 18693//18693 -f 18693//18693 18692//18692 18694//18694 -f 18693//18693 18694//18694 18695//18695 -f 18695//18695 18694//18694 18696//18696 -f 18695//18695 18696//18696 18697//18697 -f 18697//18697 18696//18696 18698//18698 -f 18697//18697 18698//18698 18699//18699 -f 18699//18699 18698//18698 18700//18700 -f 18699//18699 18700//18700 18701//18701 -f 18701//18701 18700//18700 18702//18702 -f 18701//18701 18702//18702 18703//18703 -f 18703//18703 18702//18702 18704//18704 -f 18703//18703 18704//18704 18705//18705 -f 18705//18705 18704//18704 18706//18706 -f 18705//18705 18706//18706 18707//18707 -f 18707//18707 18706//18706 18708//18708 -f 18707//18707 18708//18708 18709//18709 -f 18709//18709 18708//18708 18710//18710 -f 18709//18709 18710//18710 18711//18711 -f 18711//18711 18710//18710 18712//18712 -f 18711//18711 18712//18712 18713//18713 -f 18713//18713 18712//18712 18714//18714 -f 18713//18713 18714//18714 18715//18715 -f 18715//18715 18714//18714 18716//18716 -f 18715//18715 18716//18716 18717//18717 -f 18717//18717 18716//18716 18718//18718 -f 18717//18717 18718//18718 18719//18719 -f 18603//18603 18720//18720 18605//18605 -f 18605//18605 18720//18720 18721//18721 -f 18605//18605 18721//18721 18607//18607 -f 18607//18607 18721//18721 1202//1202 -f 18607//18607 1202//1202 18722//18722 -f 18597//18597 18723//18723 18599//18599 -f 18599//18599 18723//18723 18724//18724 -f 18599//18599 18724//18724 18601//18601 -f 18601//18601 18724//18724 18725//18725 -f 18601//18601 18725//18725 18603//18603 -f 18603//18603 18725//18725 18726//18726 -f 18603//18603 18726//18726 18720//18720 -f 18591//18591 18727//18727 18593//18593 -f 18593//18593 18727//18727 18728//18728 -f 18593//18593 18728//18728 18595//18595 -f 18595//18595 18728//18728 18729//18729 -f 18595//18595 18729//18729 18597//18597 -f 18597//18597 18729//18729 18730//18730 -f 18597//18597 18730//18730 18723//18723 -f 18731//18731 18611//18611 18732//18732 -f 18732//18732 18611//18611 18609//18609 -f 18732//18732 18609//18609 18579//18579 -f 18579//18579 18609//18609 1188//1188 -f 18579//18579 1188//1188 18581//18581 -f 1202//1202 18643//18643 18722//18722 -f 18722//18722 18643//18643 18641//18641 -f 18722//18722 18641//18641 18733//18733 -f 18733//18733 18641//18641 18639//18639 -f 18733//18733 18639//18639 18734//18734 -f 18734//18734 18639//18639 18637//18637 -f 18734//18734 18637//18637 18735//18735 -f 1188//1188 18736//18736 18581//18581 -f 18581//18581 18736//18736 18737//18737 -f 18581//18581 18737//18737 18583//18583 -f 18583//18583 18737//18737 18738//18738 -f 18583//18583 18738//18738 18585//18585 -f 18585//18585 18738//18738 18739//18739 -f 18585//18585 18739//18739 18587//18587 -f 18740//18740 18619//18619 18741//18741 -f 18741//18741 18619//18619 18617//18617 -f 18741//18741 18617//18617 18742//18742 -f 18742//18742 18617//18617 18615//18615 -f 18742//18742 18615//18615 18731//18731 -f 18731//18731 18615//18615 18613//18613 -f 18731//18731 18613//18613 18611//18611 -f 18739//18739 18743//18743 18587//18587 -f 18587//18587 18743//18743 18744//18744 -f 18587//18587 18744//18744 18589//18589 -f 18589//18589 18744//18744 18745//18745 -f 18589//18589 18745//18745 18591//18591 -f 18591//18591 18745//18745 18746//18746 -f 18591//18591 18746//18746 18727//18727 -f 18747//18747 18627//18627 18748//18748 -f 18748//18748 18627//18627 18625//18625 -f 18748//18748 18625//18625 18749//18749 -f 18749//18749 18625//18625 18623//18623 -f 18749//18749 18623//18623 18740//18740 -f 18740//18740 18623//18623 18621//18621 -f 18740//18740 18621//18621 18619//18619 -f 18637//18637 18635//18635 18735//18735 -f 18735//18735 18635//18635 18633//18633 -f 18735//18735 18633//18633 18750//18750 -f 18750//18750 18633//18633 18631//18631 -f 18750//18750 18631//18631 18747//18747 -f 18747//18747 18631//18631 18629//18629 -f 18747//18747 18629//18629 18627//18627 -f 18606//18606 18607//18607 18751//18751 -f 18751//18751 18607//18607 18722//18722 -f 18751//18751 18722//18722 18752//18752 -f 18752//18752 18722//18722 18733//18733 -f 18752//18752 18733//18733 18753//18753 -f 18753//18753 18733//18733 18734//18734 -f 18753//18753 18734//18734 18754//18754 -f 18754//18754 18734//18734 18735//18735 -f 18754//18754 18735//18735 18755//18755 -f 18755//18755 18735//18735 18750//18750 -f 18755//18755 18750//18750 18756//18756 -f 18756//18756 18750//18750 18747//18747 -f 18756//18756 18747//18747 18757//18757 -f 18757//18757 18747//18747 18748//18748 -f 18757//18757 18748//18748 18758//18758 -f 18758//18758 18748//18748 18749//18749 -f 18758//18758 18749//18749 18759//18759 -f 18759//18759 18749//18749 18740//18740 -f 18759//18759 18740//18740 18760//18760 -f 18760//18760 18740//18740 18741//18741 -f 18760//18760 18741//18741 18761//18761 -f 18761//18761 18741//18741 18742//18742 -f 18761//18761 18742//18742 18762//18762 -f 18762//18762 18742//18742 18731//18731 -f 18762//18762 18731//18731 18763//18763 -f 18763//18763 18731//18731 18732//18732 -f 18763//18763 18732//18732 18578//18578 -f 18578//18578 18732//18732 18579//18579 -f 18645//18645 1202//1202 18721//18721 -f 18645//18645 18721//18721 18764//18764 -f 18764//18764 18721//18721 18720//18720 -f 18764//18764 18720//18720 18765//18765 -f 18765//18765 18720//18720 18726//18726 -f 18765//18765 18726//18726 18766//18766 -f 18766//18766 18726//18726 18725//18725 -f 18766//18766 18725//18725 18767//18767 -f 18767//18767 18725//18725 18724//18724 -f 18767//18767 18724//18724 18768//18768 -f 18768//18768 18724//18724 18723//18723 -f 18768//18768 18723//18723 18769//18769 -f 18769//18769 18723//18723 18730//18730 -f 18769//18769 18730//18730 18770//18770 -f 18770//18770 18730//18730 18729//18729 -f 18770//18770 18729//18729 18771//18771 -f 18771//18771 18729//18729 18728//18728 -f 18771//18771 18728//18728 18772//18772 -f 18772//18772 18728//18728 18727//18727 -f 18772//18772 18727//18727 18773//18773 -f 18773//18773 18727//18727 18746//18746 -f 18773//18773 18746//18746 18774//18774 -f 18774//18774 18746//18746 18745//18745 -f 18774//18774 18745//18745 18775//18775 -f 18775//18775 18745//18745 18744//18744 -f 18775//18775 18744//18744 18776//18776 -f 18776//18776 18744//18744 18743//18743 -f 18776//18776 18743//18743 18777//18777 -f 18777//18777 18743//18743 18739//18739 -f 18777//18777 18739//18739 18778//18778 -f 18778//18778 18739//18739 18738//18738 -f 18778//18778 18738//18738 18779//18779 -f 18779//18779 18738//18738 18737//18737 -f 18779//18779 18737//18737 18780//18780 -f 18780//18780 18737//18737 18736//18736 -f 18780//18780 18736//18736 18781//18781 -f 18781//18781 18736//18736 1188//1188 -f 18781//18781 1188//1188 18608//18608 -f 18604//18604 18782//18782 18602//18602 -f 18602//18602 18782//18782 18783//18783 -f 18602//18602 18783//18783 18600//18600 -f 18600//18600 18783//18783 18784//18784 -f 18600//18600 18784//18784 18598//18598 -f 18752//18752 18680//18680 18751//18751 -f 18751//18751 18680//18680 18682//18682 -f 18751//18751 18682//18682 18606//18606 -f 18606//18606 18682//18682 1201//1201 -f 18606//18606 1201//1201 18604//18604 -f 18604//18604 1201//1201 18785//18785 -f 18604//18604 18785//18785 18782//18782 -f 18582//18582 18786//18786 18580//18580 -f 18580//18580 18786//18786 18787//18787 -f 18580//18580 18787//18787 18578//18578 -f 18578//18578 18787//18787 1187//1187 -f 18578//18578 1187//1187 18763//18763 -f 18784//18784 18788//18788 18598//18598 -f 18598//18598 18788//18788 18789//18789 -f 18598//18598 18789//18789 18596//18596 -f 18596//18596 18789//18789 18790//18790 -f 18596//18596 18790//18790 18594//18594 -f 18755//18755 18672//18672 18754//18754 -f 18754//18754 18672//18672 18674//18674 -f 18754//18754 18674//18674 18753//18753 -f 18753//18753 18674//18674 18676//18676 -f 18753//18753 18676//18676 18752//18752 -f 18752//18752 18676//18676 18678//18678 -f 18752//18752 18678//18678 18680//18680 -f 1187//1187 18648//18648 18763//18763 -f 18763//18763 18648//18648 18650//18650 -f 18763//18763 18650//18650 18762//18762 -f 18762//18762 18650//18650 18652//18652 -f 18762//18762 18652//18652 18761//18761 -f 18761//18761 18652//18652 18654//18654 -f 18761//18761 18654//18654 18760//18760 -f 18588//18588 18791//18791 18586//18586 -f 18586//18586 18791//18791 18792//18792 -f 18586//18586 18792//18792 18584//18584 -f 18584//18584 18792//18792 18793//18793 -f 18584//18584 18793//18793 18582//18582 -f 18582//18582 18793//18793 18794//18794 -f 18582//18582 18794//18794 18786//18786 -f 18790//18790 18795//18795 18594//18594 -f 18594//18594 18795//18795 18796//18796 -f 18594//18594 18796//18796 18592//18592 -f 18592//18592 18796//18796 18797//18797 -f 18592//18592 18797//18797 18590//18590 -f 18590//18590 18797//18797 18798//18798 -f 18590//18590 18798//18798 18588//18588 -f 18588//18588 18798//18798 18799//18799 -f 18588//18588 18799//18799 18791//18791 -f 18758//18758 18664//18664 18757//18757 -f 18757//18757 18664//18664 18666//18666 -f 18757//18757 18666//18666 18756//18756 -f 18756//18756 18666//18666 18668//18668 -f 18756//18756 18668//18668 18755//18755 -f 18755//18755 18668//18668 18670//18670 -f 18755//18755 18670//18670 18672//18672 -f 18654//18654 18656//18656 18760//18760 -f 18760//18760 18656//18656 18658//18658 -f 18760//18760 18658//18658 18759//18759 -f 18759//18759 18658//18658 18660//18660 -f 18759//18759 18660//18660 18758//18758 -f 18758//18758 18660//18660 18662//18662 -f 18758//18758 18662//18662 18664//18664 -f 18800//18800 18777//18777 18801//18801 -f 18801//18801 18777//18777 18778//18778 -f 18801//18801 18778//18778 18802//18802 -f 18802//18802 18778//18778 18779//18779 -f 18802//18802 18779//18779 18803//18803 -f 18803//18803 18779//18779 18780//18780 -f 18803//18803 18780//18780 18804//18804 -f 18804//18804 18780//18780 18781//18781 -f 18804//18804 18781//18781 18685//18685 -f 18685//18685 18781//18781 18608//18608 -f 18685//18685 18608//18608 18686//18686 -f 18686//18686 18608//18608 18610//18610 -f 18686//18686 18610//18610 18688//18688 -f 18688//18688 18610//18610 18612//18612 -f 18688//18688 18612//18612 18690//18690 -f 18690//18690 18612//18612 18614//18614 -f 18690//18690 18614//18614 18692//18692 -f 18708//18708 18636//18636 18710//18710 -f 18710//18710 18636//18636 18638//18638 -f 18710//18710 18638//18638 18712//18712 -f 18712//18712 18638//18638 18640//18640 -f 18712//18712 18640//18640 18714//18714 -f 18714//18714 18640//18640 18642//18642 -f 18714//18714 18642//18642 18716//18716 -f 18716//18716 18642//18642 18644//18644 -f 18716//18716 18644//18644 18718//18718 -f 18718//18718 18644//18644 18645//18645 -f 18718//18718 18645//18645 18805//18805 -f 18805//18805 18645//18645 18764//18764 -f 18805//18805 18764//18764 18806//18806 -f 18806//18806 18764//18764 18765//18765 -f 18806//18806 18765//18765 18807//18807 -f 18807//18807 18765//18765 18766//18766 -f 18807//18807 18766//18766 18808//18808 -f 18766//18766 18767//18767 18808//18808 -f 18808//18808 18767//18767 18768//18768 -f 18808//18808 18768//18768 18809//18809 -f 18809//18809 18768//18768 18769//18769 -f 18809//18809 18769//18769 18810//18810 -f 18810//18810 18769//18769 18770//18770 -f 18810//18810 18770//18770 18811//18811 -f 18811//18811 18770//18770 18771//18771 -f 18811//18811 18771//18771 18812//18812 -f 18812//18812 18771//18771 18772//18772 -f 18812//18812 18772//18772 18813//18813 -f 18813//18813 18772//18772 18773//18773 -f 18813//18813 18773//18773 18814//18814 -f 18814//18814 18773//18773 18774//18774 -f 18814//18814 18774//18774 18815//18815 -f 18815//18815 18774//18774 18775//18775 -f 18815//18815 18775//18775 18800//18800 -f 18800//18800 18775//18775 18776//18776 -f 18800//18800 18776//18776 18777//18777 -f 18614//18614 18616//18616 18692//18692 -f 18692//18692 18616//18616 18618//18618 -f 18692//18692 18618//18618 18694//18694 -f 18694//18694 18618//18618 18620//18620 -f 18694//18694 18620//18620 18696//18696 -f 18696//18696 18620//18620 18622//18622 -f 18696//18696 18622//18622 18698//18698 -f 18698//18698 18622//18622 18624//18624 -f 18698//18698 18624//18624 18700//18700 -f 18700//18700 18624//18624 18626//18626 -f 18700//18700 18626//18626 18702//18702 -f 18702//18702 18626//18626 18628//18628 -f 18702//18702 18628//18628 18704//18704 -f 18704//18704 18628//18628 18630//18630 -f 18704//18704 18630//18630 18706//18706 -f 18706//18706 18630//18630 18632//18632 -f 18706//18706 18632//18632 18708//18708 -f 18708//18708 18632//18632 18634//18634 -f 18708//18708 18634//18634 18636//18636 -f 1201//1201 18683//18683 18816//18816 -f 1201//1201 18816//18816 18785//18785 -f 18785//18785 18816//18816 18817//18817 -f 18785//18785 18817//18817 18782//18782 -f 18782//18782 18817//18817 18818//18818 -f 18782//18782 18818//18818 18783//18783 -f 18783//18783 18818//18818 18819//18819 -f 18783//18783 18819//18819 18784//18784 -f 18784//18784 18819//18819 18820//18820 -f 18784//18784 18820//18820 18788//18788 -f 18788//18788 18820//18820 18821//18821 -f 18788//18788 18821//18821 18789//18789 -f 18789//18789 18821//18821 18822//18822 -f 18789//18789 18822//18822 18790//18790 -f 18790//18790 18822//18822 18823//18823 -f 18790//18790 18823//18823 18795//18795 -f 18795//18795 18823//18823 18824//18824 -f 18795//18795 18824//18824 18796//18796 -f 18796//18796 18824//18824 18825//18825 -f 18796//18796 18825//18825 18797//18797 -f 18797//18797 18825//18825 18826//18826 -f 18797//18797 18826//18826 18798//18798 -f 18798//18798 18826//18826 18827//18827 -f 18798//18798 18827//18827 18799//18799 -f 18799//18799 18827//18827 18828//18828 -f 18799//18799 18828//18828 18791//18791 -f 18791//18791 18828//18828 18829//18829 -f 18791//18791 18829//18829 18792//18792 -f 18792//18792 18829//18829 18830//18830 -f 18792//18792 18830//18830 18793//18793 -f 18793//18793 18830//18830 18831//18831 -f 18793//18793 18831//18831 18794//18794 -f 18794//18794 18831//18831 18832//18832 -f 18794//18794 18832//18832 18786//18786 -f 18786//18786 18832//18832 18833//18833 -f 18786//18786 18833//18833 18787//18787 -f 18787//18787 18833//18833 18646//18646 -f 18787//18787 18646//18646 1187//1187 -f 18719//18719 18718//18718 18805//18805 -f 18719//18719 18805//18805 18834//18834 -f 18834//18834 18805//18805 18806//18806 -f 18834//18834 18806//18806 18835//18835 -f 18835//18835 18806//18806 18807//18807 -f 18835//18835 18807//18807 18836//18836 -f 18836//18836 18807//18807 18808//18808 -f 18836//18836 18808//18808 18837//18837 -f 18837//18837 18808//18808 18809//18809 -f 18837//18837 18809//18809 18838//18838 -f 18838//18838 18809//18809 18810//18810 -f 18838//18838 18810//18810 18839//18839 -f 18839//18839 18810//18810 18811//18811 -f 18839//18839 18811//18811 18840//18840 -f 18840//18840 18811//18811 18812//18812 -f 18840//18840 18812//18812 18841//18841 -f 18841//18841 18812//18812 18813//18813 -f 18841//18841 18813//18813 18842//18842 -f 18842//18842 18813//18813 18814//18814 -f 18842//18842 18814//18814 18843//18843 -f 18843//18843 18814//18814 18815//18815 -f 18843//18843 18815//18815 18844//18844 -f 18844//18844 18815//18815 18800//18800 -f 18844//18844 18800//18800 18845//18845 -f 18845//18845 18800//18800 18801//18801 -f 18845//18845 18801//18801 18846//18846 -f 18846//18846 18801//18801 18802//18802 -f 18846//18846 18802//18802 18847//18847 -f 18847//18847 18802//18802 18803//18803 -f 18847//18847 18803//18803 18848//18848 -f 18848//18848 18803//18803 18804//18804 -f 18848//18848 18804//18804 18849//18849 -f 18849//18849 18804//18804 18685//18685 -f 18849//18849 18685//18685 18684//18684 -f 18838//18838 18820//18820 18837//18837 -f 18837//18837 18820//18820 18819//18819 -f 18837//18837 18819//18819 18836//18836 -f 18836//18836 18819//18819 18818//18818 -f 18836//18836 18818//18818 18835//18835 -f 18835//18835 18818//18818 18817//18817 -f 18835//18835 18817//18817 18834//18834 -f 18834//18834 18817//18817 18816//18816 -f 18834//18834 18816//18816 18719//18719 -f 18719//18719 18816//18816 18683//18683 -f 18719//18719 18683//18683 18717//18717 -f 18717//18717 18683//18683 18681//18681 -f 18717//18717 18681//18681 18715//18715 -f 18715//18715 18681//18681 18679//18679 -f 18715//18715 18679//18679 18713//18713 -f 18713//18713 18679//18679 18677//18677 -f 18713//18713 18677//18677 18711//18711 -f 18846//18846 18829//18829 18845//18845 -f 18845//18845 18829//18829 18828//18828 -f 18845//18845 18828//18828 18844//18844 -f 18844//18844 18828//18828 18827//18827 -f 18844//18844 18827//18827 18843//18843 -f 18843//18843 18827//18827 18826//18826 -f 18843//18843 18826//18826 18842//18842 -f 18842//18842 18826//18826 18825//18825 -f 18842//18842 18825//18825 18841//18841 -f 18841//18841 18825//18825 18824//18824 -f 18841//18841 18824//18824 18840//18840 -f 18840//18840 18824//18824 18823//18823 -f 18840//18840 18823//18823 18839//18839 -f 18839//18839 18823//18823 18822//18822 -f 18839//18839 18822//18822 18838//18838 -f 18838//18838 18822//18822 18821//18821 -f 18838//18838 18821//18821 18820//18820 -f 18695//18695 18655//18655 18693//18693 -f 18693//18693 18655//18655 18653//18653 -f 18693//18693 18653//18653 18691//18691 -f 18691//18691 18653//18653 18651//18651 -f 18691//18691 18651//18651 18689//18689 -f 18689//18689 18651//18651 18649//18649 -f 18689//18689 18649//18649 18687//18687 -f 18687//18687 18649//18649 18647//18647 -f 18687//18687 18647//18647 18684//18684 -f 18684//18684 18647//18647 18646//18646 -f 18684//18684 18646//18646 18849//18849 -f 18849//18849 18646//18646 18833//18833 -f 18849//18849 18833//18833 18848//18848 -f 18848//18848 18833//18833 18832//18832 -f 18848//18848 18832//18832 18847//18847 -f 18847//18847 18832//18832 18831//18831 -f 18847//18847 18831//18831 18846//18846 -f 18846//18846 18831//18831 18830//18830 -f 18846//18846 18830//18830 18829//18829 -f 18677//18677 18675//18675 18711//18711 -f 18711//18711 18675//18675 18673//18673 -f 18711//18711 18673//18673 18709//18709 -f 18709//18709 18673//18673 18671//18671 -f 18709//18709 18671//18671 18707//18707 -f 18707//18707 18671//18671 18669//18669 -f 18707//18707 18669//18669 18705//18705 -f 18705//18705 18669//18669 18667//18667 -f 18705//18705 18667//18667 18703//18703 -f 18703//18703 18667//18667 18665//18665 -f 18703//18703 18665//18665 18701//18701 -f 18701//18701 18665//18665 18663//18663 -f 18701//18701 18663//18663 18699//18699 -f 18699//18699 18663//18663 18661//18661 -f 18699//18699 18661//18661 18697//18697 -f 18697//18697 18661//18661 18659//18659 -f 18697//18697 18659//18659 18695//18695 -f 18695//18695 18659//18659 18657//18657 -f 18695//18695 18657//18657 18655//18655 -f 18850//18850 18851//18851 18852//18852 -f 18852//18852 18851//18851 18853//18853 -f 18852//18852 18853//18853 18854//18854 -f 18854//18854 18853//18853 18855//18855 -f 18854//18854 18855//18855 18856//18856 -f 18856//18856 18855//18855 18857//18857 -f 18856//18856 18857//18857 18858//18858 -f 18858//18858 18857//18857 18859//18859 -f 18858//18858 18859//18859 18860//18860 -f 18860//18860 18859//18859 18861//18861 -f 18860//18860 18861//18861 18862//18862 -f 18862//18862 18861//18861 18863//18863 -f 18862//18862 18863//18863 18864//18864 -f 18864//18864 18863//18863 18865//18865 -f 18864//18864 18865//18865 18866//18866 -f 18866//18866 18865//18865 18867//18867 -f 18866//18866 18867//18867 18868//18868 -f 18868//18868 18867//18867 18869//18869 -f 18868//18868 18869//18869 18870//18870 -f 18870//18870 18869//18869 18871//18871 -f 18870//18870 18871//18871 18872//18872 -f 18872//18872 18871//18871 18873//18873 -f 18872//18872 18873//18873 18874//18874 -f 18874//18874 18873//18873 18875//18875 -f 18874//18874 18875//18875 18876//18876 -f 18876//18876 18875//18875 18877//18877 -f 18876//18876 18877//18877 18878//18878 -f 18878//18878 18877//18877 18879//18879 -f 18880//18880 1185//1185 18881//18881 -f 18880//18880 18881//18881 18882//18882 -f 18882//18882 18881//18881 18883//18883 -f 18882//18882 18883//18883 18884//18884 -f 18884//18884 18883//18883 18885//18885 -f 18884//18884 18885//18885 18886//18886 -f 18886//18886 18885//18885 18887//18887 -f 18886//18886 18887//18887 18888//18888 -f 18888//18888 18887//18887 18889//18889 -f 18888//18888 18889//18889 18890//18890 -f 18890//18890 18889//18889 18891//18891 -f 18890//18890 18891//18891 18892//18892 -f 18892//18892 18891//18891 18893//18893 -f 18892//18892 18893//18893 18894//18894 -f 18894//18894 18893//18893 18895//18895 -f 18894//18894 18895//18895 18896//18896 -f 18896//18896 18895//18895 18897//18897 -f 18896//18896 18897//18897 18898//18898 -f 18898//18898 18897//18897 18899//18899 -f 18898//18898 18899//18899 18900//18900 -f 18900//18900 18899//18899 18901//18901 -f 18900//18900 18901//18901 18902//18902 -f 18902//18902 18901//18901 18903//18903 -f 18902//18902 18903//18903 18904//18904 -f 18904//18904 18903//18903 18905//18905 -f 18904//18904 18905//18905 18906//18906 -f 18906//18906 18905//18905 18907//18907 -f 18906//18906 18907//18907 18908//18908 -f 18908//18908 18907//18907 18909//18909 -f 18908//18908 18909//18909 18910//18910 -f 18910//18910 18909//18909 18911//18911 -f 18910//18910 18911//18911 18912//18912 -f 18912//18912 18911//18911 18913//18913 -f 18912//18912 18913//18913 18914//18914 -f 18914//18914 18913//18913 18915//18915 -f 18914//18914 18915//18915 18916//18916 -f 18916//18916 18915//18915 1171//1171 -f 18916//18916 1171//1171 18917//18917 -f 1186//1186 18918//18918 18919//18919 -f 1186//1186 18919//18919 18920//18920 -f 18920//18920 18919//18919 18921//18921 -f 18920//18920 18921//18921 18922//18922 -f 18922//18922 18921//18921 18923//18923 -f 18922//18922 18923//18923 18924//18924 -f 18924//18924 18923//18923 18925//18925 -f 18924//18924 18925//18925 18926//18926 -f 18926//18926 18925//18925 18927//18927 -f 18926//18926 18927//18927 18928//18928 -f 18928//18928 18927//18927 18929//18929 -f 18928//18928 18929//18929 18930//18930 -f 18930//18930 18929//18929 18931//18931 -f 18930//18930 18931//18931 18932//18932 -f 18932//18932 18931//18931 18933//18933 -f 18932//18932 18933//18933 18934//18934 -f 18934//18934 18933//18933 18935//18935 -f 18934//18934 18935//18935 18936//18936 -f 18936//18936 18935//18935 18937//18937 -f 18936//18936 18937//18937 18938//18938 -f 18938//18938 18937//18937 18939//18939 -f 18938//18938 18939//18939 18940//18940 -f 18940//18940 18939//18939 18941//18941 -f 18940//18940 18941//18941 18942//18942 -f 18942//18942 18941//18941 18943//18943 -f 18942//18942 18943//18943 18944//18944 -f 18944//18944 18943//18943 18945//18945 -f 18944//18944 18945//18945 18946//18946 -f 18946//18946 18945//18945 18947//18947 -f 18946//18946 18947//18947 18948//18948 -f 18948//18948 18947//18947 18949//18949 -f 18948//18948 18949//18949 18950//18950 -f 18950//18950 18949//18949 18951//18951 -f 18950//18950 18951//18951 18952//18952 -f 18952//18952 18951//18951 18953//18953 -f 18952//18952 18953//18953 18954//18954 -f 18954//18954 18953//18953 18955//18955 -f 18954//18954 18955//18955 1172//1172 -f 18956//18956 18957//18957 18958//18958 -f 18956//18956 18958//18958 18959//18959 -f 18959//18959 18958//18958 18960//18960 -f 18959//18959 18960//18960 18961//18961 -f 18961//18961 18960//18960 18962//18962 -f 18961//18961 18962//18962 18963//18963 -f 18963//18963 18962//18962 18964//18964 -f 18963//18963 18964//18964 18965//18965 -f 18965//18965 18964//18964 18966//18966 -f 18965//18965 18966//18966 18967//18967 -f 18967//18967 18966//18966 18968//18968 -f 18967//18967 18968//18968 18969//18969 -f 18969//18969 18968//18968 18970//18970 -f 18969//18969 18970//18970 18971//18971 -f 18971//18971 18970//18970 18972//18972 -f 18971//18971 18972//18972 18973//18973 -f 18973//18973 18972//18972 18974//18974 -f 18973//18973 18974//18974 18975//18975 -f 18975//18975 18974//18974 18976//18976 -f 18975//18975 18976//18976 18977//18977 -f 18977//18977 18976//18976 18978//18978 -f 18977//18977 18978//18978 18979//18979 -f 18979//18979 18978//18978 18980//18980 -f 18979//18979 18980//18980 18981//18981 -f 18981//18981 18980//18980 18982//18982 -f 18981//18981 18982//18982 18983//18983 -f 18983//18983 18982//18982 18984//18984 -f 18983//18983 18984//18984 18985//18985 -f 18985//18985 18984//18984 18986//18986 -f 18985//18985 18986//18986 18987//18987 -f 18987//18987 18986//18986 18988//18988 -f 18987//18987 18988//18988 18989//18989 -f 18989//18989 18988//18988 18990//18990 -f 18989//18989 18990//18990 18991//18991 -f 18875//18875 18992//18992 18877//18877 -f 18877//18877 18992//18992 18993//18993 -f 18877//18877 18993//18993 18879//18879 -f 18879//18879 18993//18993 1171//1171 -f 18879//18879 1171//1171 18994//18994 -f 18995//18995 18883//18883 18996//18996 -f 18996//18996 18883//18883 18881//18881 -f 18996//18996 18881//18881 18851//18851 -f 18851//18851 18881//18881 1185//1185 -f 18851//18851 1185//1185 18853//18853 -f 18869//18869 18997//18997 18871//18871 -f 18871//18871 18997//18997 18998//18998 -f 18871//18871 18998//18998 18873//18873 -f 18873//18873 18998//18998 18999//18999 -f 18873//18873 18999//18999 18875//18875 -f 18875//18875 18999//18999 19000//19000 -f 18875//18875 19000//19000 18992//18992 -f 18863//18863 19001//19001 18865//18865 -f 18865//18865 19001//19001 19002//19002 -f 18865//18865 19002//19002 18867//18867 -f 18867//18867 19002//19002 19003//19003 -f 18867//18867 19003//19003 18869//18869 -f 18869//18869 19003//19003 19004//19004 -f 18869//18869 19004//19004 18997//18997 -f 19005//19005 18891//18891 19006//19006 -f 19006//19006 18891//18891 18889//18889 -f 19006//19006 18889//18889 19007//19007 -f 19007//19007 18889//18889 18887//18887 -f 19007//19007 18887//18887 18995//18995 -f 18995//18995 18887//18887 18885//18885 -f 18995//18995 18885//18885 18883//18883 -f 19008//19008 18899//18899 19009//19009 -f 19009//19009 18899//18899 18897//18897 -f 19009//19009 18897//18897 19010//19010 -f 19010//19010 18897//18897 18895//18895 -f 19010//19010 18895//18895 19005//19005 -f 19005//19005 18895//18895 18893//18893 -f 19005//19005 18893//18893 18891//18891 -f 18859//18859 19011//19011 18861//18861 -f 18861//18861 19011//19011 19012//19012 -f 18861//18861 19012//19012 18863//18863 -f 18863//18863 19012//19012 19013//19013 -f 18863//18863 19013//19013 19001//19001 -f 1185//1185 19014//19014 18853//18853 -f 18853//18853 19014//19014 19015//19015 -f 18853//18853 19015//19015 18855//18855 -f 18855//18855 19015//19015 19016//19016 -f 18855//18855 19016//19016 18857//18857 -f 18857//18857 19016//19016 19017//19017 -f 18857//18857 19017//19017 18859//18859 -f 18859//18859 19017//19017 19018//19018 -f 18859//18859 19018//19018 19011//19011 -f 19019//19019 18905//18905 19020//19020 -f 19020//19020 18905//18905 18903//18903 -f 19020//19020 18903//18903 19008//19008 -f 19008//19008 18903//18903 18901//18901 -f 19008//19008 18901//18901 18899//18899 -f 1171//1171 18915//18915 18994//18994 -f 18994//18994 18915//18915 18913//18913 -f 18994//18994 18913//18913 19021//19021 -f 19021//19021 18913//18913 18911//18911 -f 19021//19021 18911//18911 19022//19022 -f 19022//19022 18911//18911 18909//18909 -f 19022//19022 18909//18909 19019//19019 -f 19019//19019 18909//18909 18907//18907 -f 19019//19019 18907//18907 18905//18905 -f 18878//18878 18879//18879 19023//19023 -f 19023//19023 18879//18879 18994//18994 -f 19023//19023 18994//18994 19024//19024 -f 19024//19024 18994//18994 19021//19021 -f 19024//19024 19021//19021 19025//19025 -f 19025//19025 19021//19021 19022//19022 -f 19025//19025 19022//19022 19026//19026 -f 19026//19026 19022//19022 19019//19019 -f 19026//19026 19019//19019 19027//19027 -f 19027//19027 19019//19019 19020//19020 -f 19027//19027 19020//19020 19028//19028 -f 19028//19028 19020//19020 19008//19008 -f 19028//19028 19008//19008 19029//19029 -f 19029//19029 19008//19008 19009//19009 -f 19029//19029 19009//19009 19030//19030 -f 19030//19030 19009//19009 19010//19010 -f 19030//19030 19010//19010 19031//19031 -f 19031//19031 19010//19010 19005//19005 -f 19031//19031 19005//19005 19032//19032 -f 19032//19032 19005//19005 19006//19006 -f 19032//19032 19006//19006 19033//19033 -f 19033//19033 19006//19006 19007//19007 -f 19033//19033 19007//19007 19034//19034 -f 19034//19034 19007//19007 18995//18995 -f 19034//19034 18995//18995 19035//19035 -f 19035//19035 18995//18995 18996//18996 -f 19035//19035 18996//18996 18850//18850 -f 18850//18850 18996//18996 18851//18851 -f 18917//18917 1171//1171 18993//18993 -f 18917//18917 18993//18993 19036//19036 -f 19036//19036 18993//18993 18992//18992 -f 19036//19036 18992//18992 19037//19037 -f 19037//19037 18992//18992 19000//19000 -f 19037//19037 19000//19000 19038//19038 -f 19038//19038 19000//19000 18999//18999 -f 19038//19038 18999//18999 19039//19039 -f 19039//19039 18999//18999 18998//18998 -f 19039//19039 18998//18998 19040//19040 -f 19040//19040 18998//18998 18997//18997 -f 19040//19040 18997//18997 19041//19041 -f 19041//19041 18997//18997 19004//19004 -f 19041//19041 19004//19004 19042//19042 -f 19042//19042 19004//19004 19003//19003 -f 19042//19042 19003//19003 19043//19043 -f 19043//19043 19003//19003 19002//19002 -f 19043//19043 19002//19002 19044//19044 -f 19044//19044 19002//19002 19001//19001 -f 19044//19044 19001//19001 19045//19045 -f 19045//19045 19001//19001 19013//19013 -f 19045//19045 19013//19013 19046//19046 -f 19046//19046 19013//19013 19012//19012 -f 19046//19046 19012//19012 19047//19047 -f 19047//19047 19012//19012 19011//19011 -f 19047//19047 19011//19011 19048//19048 -f 19048//19048 19011//19011 19018//19018 -f 19048//19048 19018//19018 19049//19049 -f 19049//19049 19018//19018 19017//19017 -f 19049//19049 19017//19017 19050//19050 -f 19050//19050 19017//19017 19016//19016 -f 19050//19050 19016//19016 19051//19051 -f 19051//19051 19016//19016 19015//19015 -f 19051//19051 19015//19015 19052//19052 -f 19052//19052 19015//19015 19014//19014 -f 19052//19052 19014//19014 19053//19053 -f 19053//19053 19014//19014 1185//1185 -f 19053//19053 1185//1185 18880//18880 -f 19035//19035 18922//18922 19034//19034 -f 19034//19034 18922//18922 18924//18924 -f 19034//19034 18924//18924 19033//19033 -f 19033//19033 18924//18924 18926//18926 -f 19033//19033 18926//18926 19032//19032 -f 18876//18876 19054//19054 18874//18874 -f 18874//18874 19054//19054 19055//19055 -f 18874//18874 19055//19055 18872//18872 -f 18872//18872 19055//19055 19056//19056 -f 18872//18872 19056//19056 18870//18870 -f 19030//19030 18936//18936 19029//19029 -f 19029//19029 18936//18936 18938//18938 -f 19029//19029 18938//18938 19028//19028 -f 19028//19028 18938//18938 18940//18940 -f 19028//19028 18940//18940 19027//19027 -f 18866//18866 19057//19057 18864//18864 -f 18864//18864 19057//19057 19058//19058 -f 18864//18864 19058//19058 18862//18862 -f 18862//18862 19058//19058 19059//19059 -f 18862//18862 19059//19059 18860//18860 -f 19024//19024 18952//18952 19023//19023 -f 19023//19023 18952//18952 18954//18954 -f 19023//19023 18954//18954 18878//18878 -f 18878//18878 18954//18954 1172//1172 -f 18878//18878 1172//1172 18876//18876 -f 18876//18876 1172//1172 19060//19060 -f 18876//18876 19060//19060 19054//19054 -f 18940//18940 18942//18942 19027//19027 -f 19027//19027 18942//18942 18944//18944 -f 19027//19027 18944//18944 19026//19026 -f 19026//19026 18944//18944 18946//18946 -f 19026//19026 18946//18946 19025//19025 -f 19025//19025 18946//18946 18948//18948 -f 19025//19025 18948//18948 19024//19024 -f 19024//19024 18948//18948 18950//18950 -f 19024//19024 18950//18950 18952//18952 -f 18926//18926 18928//18928 19032//19032 -f 19032//19032 18928//18928 18930//18930 -f 19032//19032 18930//18930 19031//19031 -f 19031//19031 18930//18930 18932//18932 -f 19031//19031 18932//18932 19030//19030 -f 19030//19030 18932//18932 18934//18934 -f 19030//19030 18934//18934 18936//18936 -f 18854//18854 19061//19061 18852//18852 -f 18852//18852 19061//19061 19062//19062 -f 18852//18852 19062//19062 18850//18850 -f 18850//18850 19062//19062 1186//1186 -f 18850//18850 1186//1186 19035//19035 -f 19035//19035 1186//1186 18920//18920 -f 19035//19035 18920//18920 18922//18922 -f 19059//19059 19063//19063 18860//18860 -f 18860//18860 19063//19063 19064//19064 -f 18860//18860 19064//19064 18858//18858 -f 18858//18858 19064//19064 19065//19065 -f 18858//18858 19065//19065 18856//18856 -f 18856//18856 19065//19065 19066//19066 -f 18856//18856 19066//19066 18854//18854 -f 18854//18854 19066//19066 19067//19067 -f 18854//18854 19067//19067 19061//19061 -f 19056//19056 19068//19068 18870//18870 -f 18870//18870 19068//19068 19069//19069 -f 18870//18870 19069//19069 18868//18868 -f 18868//18868 19069//19069 19070//19070 -f 18868//18868 19070//19070 18866//18866 -f 18866//18866 19070//19070 19071//19071 -f 18866//18866 19071//19071 19057//19057 -f 18980//18980 18908//18908 18982//18982 -f 18982//18982 18908//18908 18910//18910 -f 18982//18982 18910//18910 18984//18984 -f 18984//18984 18910//18910 18912//18912 -f 18984//18984 18912//18912 18986//18986 -f 18986//18986 18912//18912 18914//18914 -f 18986//18986 18914//18914 18988//18988 -f 18988//18988 18914//18914 18916//18916 -f 18988//18988 18916//18916 18990//18990 -f 18990//18990 18916//18916 18917//18917 -f 18990//18990 18917//18917 19072//19072 -f 19072//19072 18917//18917 19036//19036 -f 19072//19072 19036//19036 19073//19073 -f 19073//19073 19036//19036 19037//19037 -f 19073//19073 19037//19037 19074//19074 -f 19074//19074 19037//19037 19038//19038 -f 19074//19074 19038//19038 19075//19075 -f 19038//19038 19039//19039 19075//19075 -f 19075//19075 19039//19039 19040//19040 -f 19075//19075 19040//19040 19076//19076 -f 19076//19076 19040//19040 19041//19041 -f 19076//19076 19041//19041 19077//19077 -f 19077//19077 19041//19041 19042//19042 -f 19077//19077 19042//19042 19078//19078 -f 19078//19078 19042//19042 19043//19043 -f 19078//19078 19043//19043 19079//19079 -f 19079//19079 19043//19043 19044//19044 -f 19079//19079 19044//19044 19080//19080 -f 19080//19080 19044//19044 19045//19045 -f 19080//19080 19045//19045 19081//19081 -f 19081//19081 19045//19045 19046//19046 -f 19081//19081 19046//19046 19082//19082 -f 19082//19082 19046//19046 19047//19047 -f 19082//19082 19047//19047 19083//19083 -f 19047//19047 19048//19048 19083//19083 -f 19083//19083 19048//19048 19049//19049 -f 19083//19083 19049//19049 19084//19084 -f 19084//19084 19049//19049 19050//19050 -f 19084//19084 19050//19050 19085//19085 -f 19085//19085 19050//19050 19051//19051 -f 19085//19085 19051//19051 19086//19086 -f 19086//19086 19051//19051 19052//19052 -f 19086//19086 19052//19052 19087//19087 -f 19087//19087 19052//19052 19053//19053 -f 19087//19087 19053//19053 18957//18957 -f 18957//18957 19053//19053 18880//18880 -f 18957//18957 18880//18880 18958//18958 -f 18958//18958 18880//18880 18882//18882 -f 18958//18958 18882//18882 18960//18960 -f 18960//18960 18882//18882 18884//18884 -f 18960//18960 18884//18884 18962//18962 -f 18962//18962 18884//18884 18886//18886 -f 18962//18962 18886//18886 18964//18964 -f 18886//18886 18888//18888 18964//18964 -f 18964//18964 18888//18888 18890//18890 -f 18964//18964 18890//18890 18966//18966 -f 18966//18966 18890//18890 18892//18892 -f 18966//18966 18892//18892 18968//18968 -f 18968//18968 18892//18892 18894//18894 -f 18968//18968 18894//18894 18970//18970 -f 18970//18970 18894//18894 18896//18896 -f 18970//18970 18896//18896 18972//18972 -f 18972//18972 18896//18896 18898//18898 -f 18972//18972 18898//18898 18974//18974 -f 18974//18974 18898//18898 18900//18900 -f 18974//18974 18900//18900 18976//18976 -f 18976//18976 18900//18900 18902//18902 -f 18976//18976 18902//18902 18978//18978 -f 18978//18978 18902//18902 18904//18904 -f 18978//18978 18904//18904 18980//18980 -f 18980//18980 18904//18904 18906//18906 -f 18980//18980 18906//18906 18908//18908 -f 1172//1172 18955//18955 19088//19088 -f 1172//1172 19088//19088 19060//19060 -f 19060//19060 19088//19088 19089//19089 -f 19060//19060 19089//19089 19054//19054 -f 19054//19054 19089//19089 19090//19090 -f 19054//19054 19090//19090 19055//19055 -f 19055//19055 19090//19090 19091//19091 -f 19055//19055 19091//19091 19056//19056 -f 19056//19056 19091//19091 19092//19092 -f 19056//19056 19092//19092 19068//19068 -f 19068//19068 19092//19092 19093//19093 -f 19068//19068 19093//19093 19069//19069 -f 19069//19069 19093//19093 19094//19094 -f 19069//19069 19094//19094 19070//19070 -f 19070//19070 19094//19094 19095//19095 -f 19070//19070 19095//19095 19071//19071 -f 19071//19071 19095//19095 19096//19096 -f 19071//19071 19096//19096 19057//19057 -f 19057//19057 19096//19096 19097//19097 -f 19057//19057 19097//19097 19058//19058 -f 19058//19058 19097//19097 19098//19098 -f 19058//19058 19098//19098 19059//19059 -f 19059//19059 19098//19098 19099//19099 -f 19059//19059 19099//19099 19063//19063 -f 19063//19063 19099//19099 19100//19100 -f 19063//19063 19100//19100 19064//19064 -f 19064//19064 19100//19100 19101//19101 -f 19064//19064 19101//19101 19065//19065 -f 19065//19065 19101//19101 19102//19102 -f 19065//19065 19102//19102 19066//19066 -f 19066//19066 19102//19102 19103//19103 -f 19066//19066 19103//19103 19067//19067 -f 19067//19067 19103//19103 19104//19104 -f 19067//19067 19104//19104 19061//19061 -f 19061//19061 19104//19104 19105//19105 -f 19061//19061 19105//19105 19062//19062 -f 19062//19062 19105//19105 18918//18918 -f 19062//19062 18918//18918 1186//1186 -f 18991//18991 18990//18990 19072//19072 -f 18991//18991 19072//19072 19106//19106 -f 19106//19106 19072//19072 19073//19073 -f 19106//19106 19073//19073 19107//19107 -f 19107//19107 19073//19073 19074//19074 -f 19107//19107 19074//19074 19108//19108 -f 19108//19108 19074//19074 19075//19075 -f 19108//19108 19075//19075 19109//19109 -f 19109//19109 19075//19075 19076//19076 -f 19109//19109 19076//19076 19110//19110 -f 19110//19110 19076//19076 19077//19077 -f 19110//19110 19077//19077 19111//19111 -f 19111//19111 19077//19077 19078//19078 -f 19111//19111 19078//19078 19112//19112 -f 19112//19112 19078//19078 19079//19079 -f 19112//19112 19079//19079 19113//19113 -f 19113//19113 19079//19079 19080//19080 -f 19113//19113 19080//19080 19114//19114 -f 19114//19114 19080//19080 19081//19081 -f 19114//19114 19081//19081 19115//19115 -f 19115//19115 19081//19081 19082//19082 -f 19115//19115 19082//19082 19116//19116 -f 19116//19116 19082//19082 19083//19083 -f 19116//19116 19083//19083 19117//19117 -f 19117//19117 19083//19083 19084//19084 -f 19117//19117 19084//19084 19118//19118 -f 19118//19118 19084//19084 19085//19085 -f 19118//19118 19085//19085 19119//19119 -f 19119//19119 19085//19085 19086//19086 -f 19119//19119 19086//19086 19120//19120 -f 19120//19120 19086//19086 19087//19087 -f 19120//19120 19087//19087 19121//19121 -f 19121//19121 19087//19087 18957//18957 -f 19121//19121 18957//18957 18956//18956 -f 19110//19110 19092//19092 19109//19109 -f 19109//19109 19092//19092 19091//19091 -f 19109//19109 19091//19091 19108//19108 -f 19108//19108 19091//19091 19090//19090 -f 19108//19108 19090//19090 19107//19107 -f 19107//19107 19090//19090 19089//19089 -f 19107//19107 19089//19089 19106//19106 -f 19106//19106 19089//19089 19088//19088 -f 19106//19106 19088//19088 18991//18991 -f 18991//18991 19088//19088 18955//18955 -f 18991//18991 18955//18955 18989//18989 -f 18989//18989 18955//18955 18953//18953 -f 18989//18989 18953//18953 18987//18987 -f 18987//18987 18953//18953 18951//18951 -f 18987//18987 18951//18951 18985//18985 -f 18985//18985 18951//18951 18949//18949 -f 18985//18985 18949//18949 18983//18983 -f 18949//18949 18947//18947 18983//18983 -f 18983//18983 18947//18947 18945//18945 -f 18983//18983 18945//18945 18981//18981 -f 18981//18981 18945//18945 18943//18943 -f 18981//18981 18943//18943 18979//18979 -f 18979//18979 18943//18943 18941//18941 -f 18979//18979 18941//18941 18977//18977 -f 18977//18977 18941//18941 18939//18939 -f 18977//18977 18939//18939 18975//18975 -f 18975//18975 18939//18939 18937//18937 -f 18975//18975 18937//18937 18973//18973 -f 18973//18973 18937//18937 18935//18935 -f 18973//18973 18935//18935 18971//18971 -f 18971//18971 18935//18935 18933//18933 -f 18971//18971 18933//18933 18969//18969 -f 18969//18969 18933//18933 18931//18931 -f 18969//18969 18931//18931 18967//18967 -f 18931//18931 18929//18929 18967//18967 -f 18967//18967 18929//18929 18927//18927 -f 18967//18967 18927//18927 18965//18965 -f 18965//18965 18927//18927 18925//18925 -f 18965//18965 18925//18925 18963//18963 -f 18963//18963 18925//18925 18923//18923 -f 18963//18963 18923//18923 18961//18961 -f 18961//18961 18923//18923 18921//18921 -f 18961//18961 18921//18921 18959//18959 -f 18959//18959 18921//18921 18919//18919 -f 18959//18959 18919//18919 18956//18956 -f 18956//18956 18919//18919 18918//18918 -f 18956//18956 18918//18918 19121//19121 -f 19121//19121 18918//18918 19105//19105 -f 19121//19121 19105//19105 19120//19120 -f 19120//19120 19105//19105 19104//19104 -f 19120//19120 19104//19104 19119//19119 -f 19119//19119 19104//19104 19103//19103 -f 19119//19119 19103//19103 19118//19118 -f 19103//19103 19102//19102 19118//19118 -f 19118//19118 19102//19102 19101//19101 -f 19118//19118 19101//19101 19117//19117 -f 19117//19117 19101//19101 19100//19100 -f 19117//19117 19100//19100 19116//19116 -f 19116//19116 19100//19100 19099//19099 -f 19116//19116 19099//19099 19115//19115 -f 19115//19115 19099//19099 19098//19098 -f 19115//19115 19098//19098 19114//19114 -f 19114//19114 19098//19098 19097//19097 -f 19114//19114 19097//19097 19113//19113 -f 19113//19113 19097//19097 19096//19096 -f 19113//19113 19096//19096 19112//19112 -f 19112//19112 19096//19096 19095//19095 -f 19112//19112 19095//19095 19111//19111 -f 19111//19111 19095//19095 19094//19094 -f 19111//19111 19094//19094 19110//19110 -f 19110//19110 19094//19094 19093//19093 -f 19110//19110 19093//19093 19092//19092 -f 19122//19122 19123//19123 19124//19124 -f 19122//19122 19124//19124 19125//19125 -f 19125//19125 19124//19124 19126//19126 -f 19125//19125 19126//19126 19127//19127 -f 19127//19127 19126//19126 19128//19128 -f 19127//19127 19128//19128 19129//19129 -f 19129//19129 19128//19128 19130//19130 -f 19129//19129 19130//19130 19131//19131 -f 19131//19131 19130//19130 19132//19132 -f 19131//19131 19132//19132 19133//19133 -f 19133//19133 19132//19132 19134//19134 -f 19133//19133 19134//19134 19135//19135 -f 19135//19135 19134//19134 19136//19136 -f 19135//19135 19136//19136 19137//19137 -f 19137//19137 19136//19136 19138//19138 -f 19137//19137 19138//19138 19139//19139 -f 19139//19139 19138//19138 19140//19140 -f 19139//19139 19140//19140 19141//19141 -f 19141//19141 19140//19140 19142//19142 -f 19141//19141 19142//19142 19143//19143 -f 19143//19143 19142//19142 19144//19144 -f 19143//19143 19144//19144 19145//19145 -f 19145//19145 19144//19144 19146//19146 -f 19145//19145 19146//19146 19147//19147 -f 19147//19147 19146//19146 19148//19148 -f 19147//19147 19148//19148 19149//19149 -f 19149//19149 19148//19148 19150//19150 -f 19149//19149 19150//19150 19151//19151 -f 19151//19151 19150//19150 19152//19152 -f 19151//19151 19152//19152 19153//19153 -f 19153//19153 19152//19152 19154//19154 -f 19153//19153 19154//19154 19155//19155 -f 19156//19156 19157//19157 19158//19158 -f 19156//19156 19158//19158 19159//19159 -f 19159//19159 19158//19158 19160//19160 -f 19159//19159 19160//19160 19161//19161 -f 19161//19161 19160//19160 19162//19162 -f 19161//19161 19162//19162 19163//19163 -f 19163//19163 19162//19162 19164//19164 -f 19163//19163 19164//19164 19165//19165 -f 19165//19165 19164//19164 19166//19166 -f 19165//19165 19166//19166 19167//19167 -f 19167//19167 19166//19166 19168//19168 -f 19167//19167 19168//19168 19169//19169 -f 19169//19169 19168//19168 19170//19170 -f 19169//19169 19170//19170 19171//19171 -f 19171//19171 19170//19170 19172//19172 -f 19171//19171 19172//19172 19173//19173 -f 19173//19173 19172//19172 19174//19174 -f 19173//19173 19174//19174 19175//19175 -f 19175//19175 19174//19174 19176//19176 -f 19175//19175 19176//19176 19177//19177 -f 19177//19177 19176//19176 19178//19178 -f 19177//19177 19178//19178 19179//19179 -f 19179//19179 19178//19178 19180//19180 -f 19179//19179 19180//19180 19181//19181 -f 19181//19181 19180//19180 19182//19182 -f 19181//19181 19182//19182 19183//19183 -f 19183//19183 19182//19182 19184//19184 -f 19183//19183 19184//19184 19185//19185 -f 19185//19185 19184//19184 19186//19186 -f 19185//19185 19186//19186 19187//19187 -f 19188//19188 19189//19189 19190//19190 -f 19190//19190 19189//19189 19191//19191 -f 19190//19190 19191//19191 19192//19192 -f 19192//19192 19191//19191 19193//19193 -f 19193//19193 19191//19191 19194//19194 -f 19194//19194 19191//19191 19195//19195 -f 19194//19194 19195//19195 19196//19196 -f 19197//19197 19198//19198 19195//19195 -f 19195//19195 19198//19198 19199//19199 -f 19195//19195 19199//19199 19196//19196 -f 19197//19197 19195//19195 19200//19200 -f 19200//19200 19195//19195 19201//19201 -f 19200//19200 19201//19201 19202//19202 -f 19203//19203 19204//19204 19205//19205 -f 19205//19205 19204//19204 19206//19206 -f 19205//19205 19206//19206 19201//19201 -f 19201//19201 19206//19206 19207//19207 -f 19201//19201 19207//19207 19202//19202 -f 19208//19208 19209//19209 19210//19210 -f 19210//19210 19209//19209 19211//19211 -f 19210//19210 19211//19211 19205//19205 -f 19205//19205 19211//19211 19212//19212 -f 19205//19205 19212//19212 19203//19203 -f 19213//19213 19214//19214 19215//19215 -f 19215//19215 19214//19214 19216//19216 -f 19215//19215 19216//19216 19210//19210 -f 19210//19210 19216//19216 19217//19217 -f 19210//19210 19217//19217 19208//19208 -f 19213//19213 19215//19215 19218//19218 -f 19218//19218 19215//19215 19219//19219 -f 19218//19218 19219//19219 19220//19220 -f 19221//19221 19222//19222 19223//19223 -f 19223//19223 19222//19222 19224//19224 -f 19223//19223 19224//19224 19219//19219 -f 19219//19219 19224//19224 19225//19225 -f 19219//19219 19225//19225 19220//19220 -f 19221//19221 19223//19223 19226//19226 -f 19226//19226 19223//19223 19227//19227 -f 19226//19226 19227//19227 19228//19228 -f 19229//19229 19230//19230 19231//19231 -f 19231//19231 19232//19232 19229//19229 -f 19229//19229 19232//19232 19233//19233 -f 19229//19229 19233//19233 19227//19227 -f 19227//19227 19233//19233 19234//19234 -f 19227//19227 19234//19234 19228//19228 -f 19235//19235 19236//19236 19237//19237 -f 19237//19237 19236//19236 19238//19238 -f 19237//19237 19238//19238 19239//19239 -f 19239//19239 19238//19238 19240//19240 -f 19239//19239 19240//19240 19241//19241 -f 19240//19240 19242//19242 19241//19241 -f 19241//19241 19242//19242 19243//19243 -f 19241//19241 19243//19243 19244//19244 -f 19244//19244 19243//19243 19245//19245 -f 19244//19244 19245//19245 19246//19246 -f 19246//19246 19245//19245 19247//19247 -f 19246//19246 19247//19247 19248//19248 -f 19248//19248 19247//19247 19249//19249 -f 19248//19248 19249//19249 19250//19250 -f 19250//19250 19249//19249 19251//19251 -f 19250//19250 19251//19251 19252//19252 -f 19252//19252 19251//19251 19253//19253 -f 19252//19252 19253//19253 19254//19254 -f 19254//19254 19253//19253 19255//19255 -f 19254//19254 19255//19255 19256//19256 -f 19256//19256 19255//19255 19257//19257 -f 19256//19256 19257//19257 19258//19258 -f 19257//19257 19259//19259 19258//19258 -f 19258//19258 19259//19259 19260//19260 -f 19258//19258 19260//19260 19261//19261 -f 19261//19261 19260//19260 19262//19262 -f 19261//19261 19262//19262 19263//19263 -f 19262//19262 19264//19264 19263//19263 -f 19263//19263 19264//19264 19265//19265 -f 19263//19263 19265//19265 19266//19266 -f 19266//19266 19265//19265 19267//19267 -f 19266//19266 19267//19267 19268//19268 -f 19268//19268 19267//19267 19269//19269 -f 19268//19268 19269//19269 19270//19270 -f 19270//19270 19269//19269 19271//19271 -f 19270//19270 19271//19271 19272//19272 -f 19272//19272 19271//19271 19273//19273 -f 19274//19274 19275//19275 19276//19276 -f 19276//19276 19275//19275 19277//19277 -f 19276//19276 19277//19277 19278//19278 -f 19278//19278 19277//19277 19279//19279 -f 19278//19278 19279//19279 19280//19280 -f 19280//19280 19279//19279 19281//19281 -f 19280//19280 19281//19281 19282//19282 -f 19282//19282 19281//19281 19283//19283 -f 19282//19282 19283//19283 19273//19273 -f 19273//19273 19283//19283 19284//19284 -f 19273//19273 19284//19284 19272//19272 -f 19285//19285 19286//19286 19287//19287 -f 19287//19287 19286//19286 19288//19288 -f 19287//19287 19288//19288 19289//19289 -f 19289//19289 19288//19288 19290//19290 -f 19289//19289 19290//19290 19291//19291 -f 19291//19291 19290//19290 19292//19292 -f 19291//19291 19292//19292 19293//19293 -f 19293//19293 19292//19292 19294//19294 -f 19293//19293 19294//19294 19295//19295 -f 19295//19295 19294//19294 19296//19296 -f 19295//19295 19296//19296 19274//19274 -f 19274//19274 19296//19296 19297//19297 -f 19274//19274 19297//19297 19275//19275 -f 19298//19298 19299//19299 19300//19300 -f 19300//19300 19301//19301 19298//19298 -f 19298//19298 19301//19301 19302//19302 -f 19298//19298 19302//19302 19285//19285 -f 19285//19285 19302//19302 19303//19303 -f 19285//19285 19303//19303 19286//19286 -f 19304//19304 19305//19305 19306//19306 -f 19306//19306 19305//19305 19307//19307 -f 19306//19306 19307//19307 19308//19308 -f 19309//19309 19310//19310 19311//19311 -f 19307//19307 19312//19312 19308//19308 -f 19308//19308 19312//19312 19313//19313 -f 19308//19308 19313//19313 19314//19314 -f 19314//19314 19313//19313 19315//19315 -f 19314//19314 19315//19315 19316//19316 -f 19316//19316 19315//19315 19317//19317 -f 19316//19316 19317//19317 19310//19310 -f 19310//19310 19317//19317 19318//19318 -f 19310//19310 19318//19318 19311//19311 -f 19309//19309 19311//19311 19319//19319 -f 19319//19319 19311//19311 19320//19320 -f 19319//19319 19320//19320 19321//19321 -f 19321//19321 19320//19320 19322//19322 -f 19321//19321 19322//19322 19323//19323 -f 19323//19323 19322//19322 19324//19324 -f 19323//19323 19324//19324 19325//19325 -f 19325//19325 19324//19324 19326//19326 -f 19326//19326 19324//19324 19327//19327 -f 19326//19326 19327//19327 19328//19328 -f 19328//19328 19327//19327 19329//19329 -f 19328//19328 19329//19329 19330//19330 -f 19330//19330 19329//19329 19331//19331 -f 19330//19330 19331//19331 19332//19332 -f 19332//19332 19331//19331 19333//19333 -f 19332//19332 19333//19333 19334//19334 -f 19334//19334 19333//19333 19335//19335 -f 19334//19334 19335//19335 19336//19336 -f 19336//19336 19335//19335 19337//19337 -f 19336//19336 19337//19337 19338//19338 -f 19338//19338 19337//19337 19339//19339 -f 19338//19338 19339//19339 19340//19340 -f 19339//19339 19341//19341 19340//19340 -f 19340//19340 19341//19341 19342//19342 -f 19340//19340 19342//19342 19343//19343 -f 19343//19343 19342//19342 19344//19344 -f 19343//19343 19344//19344 19345//19345 -f 19345//19345 19344//19344 19346//19346 -f 19345//19345 19346//19346 19347//19347 -f 19347//19347 19346//19346 19348//19348 -f 19347//19347 19348//19348 19349//19349 -f 19349//19349 19348//19348 19350//19350 -f 19349//19349 19350//19350 19351//19351 -f 19350//19350 19352//19352 19351//19351 -f 19351//19351 19352//19352 19353//19353 -f 19351//19351 19353//19353 19354//19354 -f 19354//19354 19353//19353 19355//19355 -f 19354//19354 19355//19355 19356//19356 -f 19356//19356 19355//19355 19357//19357 -f 19356//19356 19357//19357 19358//19358 -f 19358//19358 19357//19357 19359//19359 -f 19358//19358 19359//19359 19360//19360 -f 19360//19360 19359//19359 19361//19361 -f 19362//19362 19363//19363 19364//19364 -f 19364//19364 19363//19363 19365//19365 -f 19364//19364 19365//19365 19366//19366 -f 19366//19366 19365//19365 19361//19361 -f 19366//19366 19361//19361 19359//19359 -f 19367//19367 19368//19368 19369//19369 -f 19369//19369 19368//19368 19363//19363 -f 19369//19369 19363//19363 19370//19370 -f 19370//19370 19363//19363 19362//19362 -f 19371//19371 19372//19372 19373//19373 -f 19373//19373 19372//19372 19374//19374 -f 19373//19373 19374//19374 19375//19375 -f 19375//19375 19374//19374 19376//19376 -f 19375//19375 19376//19376 19377//19377 -f 19376//19376 19378//19378 19377//19377 -f 19377//19377 19378//19378 19379//19379 -f 19377//19377 19379//19379 19380//19380 -f 19380//19380 19379//19379 19381//19381 -f 19379//19379 19382//19382 19381//19381 -f 19381//19381 19382//19382 19383//19383 -f 19381//19381 19383//19383 19384//19384 -f 19384//19384 19383//19383 19385//19385 -f 19384//19384 19385//19385 19386//19386 -f 19385//19385 19387//19387 19386//19386 -f 19386//19386 19387//19387 19388//19388 -f 19386//19386 19388//19388 19389//19389 -f 19389//19389 19388//19388 19390//19390 -f 19389//19389 19390//19390 19391//19391 -f 19391//19391 19390//19390 19392//19392 -f 19391//19391 19392//19392 19393//19393 -f 19393//19393 19392//19392 19394//19394 -f 19393//19393 19394//19394 19395//19395 -f 19395//19395 19394//19394 19396//19396 -f 19395//19395 19396//19396 19397//19397 -f 19397//19397 19396//19396 19398//19398 -f 19397//19397 19398//19398 19399//19399 -f 19399//19399 19398//19398 19400//19400 -f 19399//19399 19400//19400 19401//19401 -f 19401//19401 19400//19400 19402//19402 -f 19401//19401 19402//19402 19403//19403 -f 19403//19403 19402//19402 19404//19404 -f 19403//19403 19404//19404 19405//19405 -f 19405//19405 19404//19404 19406//19406 -f 19405//19405 19406//19406 19407//19407 -f 19407//19407 19406//19406 19408//19408 -f 19407//19407 19408//19408 19409//19409 -f 19409//19409 19408//19408 19410//19410 -f 19409//19409 19410//19410 19411//19411 -f 19411//19411 19410//19410 19412//19412 -f 19411//19411 19412//19412 19413//19413 -f 19413//19413 19412//19412 19414//19414 -f 19413//19413 19414//19414 19415//19415 -f 19415//19415 19414//19414 19416//19416 -f 19415//19415 19416//19416 19417//19417 -f 19417//19417 19416//19416 19418//19418 -f 19417//19417 19418//19418 19419//19419 -f 19419//19419 19418//19418 19420//19420 -f 19420//19420 19418//19418 19421//19421 -f 19420//19420 19421//19421 19422//19422 -f 19421//19421 19423//19423 19422//19422 -f 19422//19422 19423//19423 19424//19424 -f 19422//19422 19424//19424 19425//19425 -f 19425//19425 19424//19424 19426//19426 -f 19425//19425 19426//19426 19427//19427 -f 19427//19427 19426//19426 19428//19428 -f 19427//19427 19428//19428 19429//19429 -f 19429//19429 19428//19428 19430//19430 -f 19431//19431 19432//19432 19433//19433 -f 19433//19433 19432//19432 19434//19434 -f 19433//19433 19434//19434 19430//19430 -f 19430//19430 19434//19434 19435//19435 -f 19430//19430 19435//19435 19429//19429 -f 19436//19436 19437//19437 19438//19438 -f 19438//19438 19437//19437 19439//19439 -f 19439//19439 19437//19437 19440//19440 -f 19439//19439 19440//19440 19441//19441 -f 19441//19441 19440//19440 19442//19442 -f 19441//19441 19442//19442 19443//19443 -f 19443//19443 19442//19442 19444//19444 -f 19444//19444 19442//19442 19445//19445 -f 19444//19444 19445//19445 19446//19446 -f 19446//19446 19445//19445 19447//19447 -f 19446//19446 19447//19447 19448//19448 -f 19448//19448 19447//19447 19449//19449 -f 19448//19448 19449//19449 19450//19450 -f 19450//19450 19449//19449 19451//19451 -f 19450//19450 19451//19451 19452//19452 -f 19452//19452 19451//19451 19453//19453 -f 19452//19452 19453//19453 19454//19454 -f 19454//19454 19453//19453 19455//19455 -f 19454//19454 19455//19455 19456//19456 -f 19456//19456 19455//19455 19457//19457 -f 19456//19456 19457//19457 19458//19458 -f 19458//19458 19457//19457 19459//19459 -f 19458//19458 19459//19459 19460//19460 -f 19460//19460 19459//19459 19461//19461 -f 19460//19460 19461//19461 19462//19462 -f 19462//19462 19461//19461 19463//19463 -f 19462//19462 19463//19463 19464//19464 -f 19464//19464 19463//19463 19465//19465 -f 19464//19464 19465//19465 19466//19466 -f 19466//19466 19465//19465 19467//19467 -f 19466//19466 19467//19467 19468//19468 -f 19468//19468 19467//19467 19469//19469 -f 19468//19468 19469//19469 19470//19470 -f 19470//19470 19469//19469 19471//19471 -f 19470//19470 19471//19471 19472//19472 -f 19472//19472 19471//19471 19473//19473 -f 19472//19472 19473//19473 19474//19474 -f 19474//19474 19473//19473 19475//19475 -f 19474//19474 19475//19475 19476//19476 -f 19475//19475 19477//19477 19476//19476 -f 19476//19476 19477//19477 19478//19478 -f 19476//19476 19478//19478 19479//19479 -f 19479//19479 19478//19478 19480//19480 -f 19479//19479 19480//19480 19481//19481 -f 19482//19482 19483//19483 19484//19484 -f 19484//19484 19483//19483 19485//19485 -f 19484//19484 19485//19485 19486//19486 -f 19486//19486 19485//19485 19481//19481 -f 19486//19486 19481//19481 19487//19487 -f 19487//19487 19481//19481 19480//19480 -f 19438//19438 19488//19488 19436//19436 -f 19436//19436 19488//19488 19489//19489 -f 19436//19436 19489//19489 19490//19490 -f 19490//19490 19489//19489 19491//19491 -f 19489//19489 19492//19492 19491//19491 -f 19491//19491 19492//19492 19493//19493 -f 19491//19491 19493//19493 19494//19494 -f 19494//19494 19493//19493 19495//19495 -f 19493//19493 19496//19496 19495//19495 -f 19495//19495 19496//19496 19497//19497 -f 19495//19495 19497//19497 19498//19498 -f 19498//19498 19497//19497 19499//19499 -f 19498//19498 19499//19499 19500//19500 -f 19500//19500 19499//19499 19501//19501 -f 19500//19500 19501//19501 19502//19502 -f 19502//19502 19501//19501 19503//19503 -f 19502//19502 19503//19503 19504//19504 -f 19504//19504 19503//19503 19505//19505 -f 19506//19506 19507//19507 19508//19508 -f 19508//19508 19507//19507 19509//19509 -f 19509//19509 19507//19507 19510//19510 -f 19509//19509 19510//19510 19511//19511 -f 19511//19511 19510//19510 19512//19512 -f 19511//19511 19512//19512 19513//19513 -f 19506//19506 19508//19508 19514//19514 -f 19514//19514 19508//19508 19515//19515 -f 19514//19514 19515//19515 19516//19516 -f 19516//19516 19515//19515 19517//19517 -f 19516//19516 19517//19517 19518//19518 -f 19518//19518 19517//19517 19519//19519 -f 19518//19518 19519//19519 19520//19520 -f 19520//19520 19519//19519 19521//19521 -f 19520//19520 19521//19521 19522//19522 -f 19522//19522 19521//19521 19523//19523 -f 19522//19522 19523//19523 19524//19524 -f 19524//19524 19523//19523 19525//19525 -f 19525//19525 19523//19523 19526//19526 -f 19525//19525 19526//19526 19527//19527 -f 19527//19527 19526//19526 19528//19528 -f 19527//19527 19528//19528 19529//19529 -f 19529//19529 19528//19528 19530//19530 -f 19529//19529 19530//19530 19531//19531 -f 19531//19531 19530//19530 19532//19532 -f 19531//19531 19532//19532 19533//19533 -f 19533//19533 19532//19532 19534//19534 -f 19533//19533 19534//19534 19535//19535 -f 19535//19535 19534//19534 19536//19536 -f 19535//19535 19536//19536 19537//19537 -f 19537//19537 19536//19536 19538//19538 -f 19537//19537 19538//19538 19539//19539 -f 19539//19539 19538//19538 19540//19540 -f 19539//19539 19540//19540 19541//19541 -f 19542//19542 19543//19543 19544//19544 -f 19541//19541 19540//19540 19545//19545 -f 19545//19545 19540//19540 19546//19546 -f 19545//19545 19546//19546 19547//19547 -f 19547//19547 19546//19546 19548//19548 -f 19547//19547 19548//19548 19543//19543 -f 19543//19543 19548//19548 19549//19549 -f 19543//19543 19549//19549 19544//19544 -f 19542//19542 19544//19544 19550//19550 -f 19550//19550 19544//19544 19551//19551 -f 19550//19550 19551//19551 19552//19552 -f 19552//19552 19551//19551 19553//19553 -f 19552//19552 19553//19553 19554//19554 -f 19553//19553 19555//19555 19554//19554 -f 19554//19554 19555//19555 19556//19556 -f 19554//19554 19556//19556 19557//19557 -f 19557//19557 19556//19556 19558//19558 -f 19557//19557 19558//19558 19559//19559 -f 19559//19559 19558//19558 19560//19560 -f 19559//19559 19560//19560 19561//19561 -f 19561//19561 19560//19560 19562//19562 -f 19561//19561 19562//19562 19563//19563 -f 19563//19563 19562//19562 19564//19564 -f 19563//19563 19564//19564 19565//19565 -f 19566//19566 19567//19567 19568//19568 -f 19568//19568 19567//19567 19569//19569 -f 19568//19568 19569//19569 19570//19570 -f 19570//19570 19569//19569 19571//19571 -f 19570//19570 19571//19571 19565//19565 -f 19565//19565 19571//19571 19572//19572 -f 19565//19565 19572//19572 19563//19563 -f 19573//19573 19574//19574 19575//19575 -f 19575//19575 19574//19574 19576//19576 -f 19575//19575 19576//19576 19566//19566 -f 19566//19566 19576//19576 19577//19577 -f 19566//19566 19577//19577 19567//19567 -f 19578//19578 19579//19579 19580//19580 -f 19581//19581 19582//19582 19583//19583 -f 19583//19583 19582//19582 19584//19584 -f 19583//19583 19584//19584 19585//19585 -f 19585//19585 19584//19584 19586//19586 -f 19585//19585 19586//19586 19587//19587 -f 19583//19583 19588//19588 19581//19581 -f 19581//19581 19588//19588 19589//19589 -f 19581//19581 19589//19589 19590//19590 -f 19590//19590 19589//19589 19591//19591 -f 19590//19590 19591//19591 19592//19592 -f 19592//19592 19591//19591 19593//19593 -f 19592//19592 19593//19593 19594//19594 -f 19594//19594 19593//19593 19595//19595 -f 19594//19594 19595//19595 19596//19596 -f 19596//19596 19595//19595 19597//19597 -f 19596//19596 19597//19597 19598//19598 -f 19597//19597 19599//19599 19598//19598 -f 19598//19598 19599//19599 19600//19600 -f 19598//19598 19600//19600 19601//19601 -f 19601//19601 19600//19600 19602//19602 -f 19601//19601 19602//19602 19603//19603 -f 19603//19603 19602//19602 19604//19604 -f 19603//19603 19604//19604 19605//19605 -f 19604//19604 19606//19606 19605//19605 -f 19605//19605 19606//19606 19607//19607 -f 19605//19605 19607//19607 19608//19608 -f 19608//19608 19607//19607 19609//19609 -f 19608//19608 19609//19609 19610//19610 -f 19610//19610 19609//19609 19611//19611 -f 19610//19610 19611//19611 19612//19612 -f 19612//19612 19611//19611 19613//19613 -f 19612//19612 19613//19613 19614//19614 -f 19613//19613 19615//19615 19614//19614 -f 19614//19614 19615//19615 19616//19616 -f 19614//19614 19616//19616 19617//19617 -f 19617//19617 19616//19616 19618//19618 -f 19617//19617 19618//19618 19619//19619 -f 19619//19619 19618//19618 19620//19620 -f 19618//19618 19621//19621 19620//19620 -f 19620//19620 19621//19621 19622//19622 -f 19620//19620 19622//19622 19623//19623 -f 19623//19623 19622//19622 19624//19624 -f 19623//19623 19624//19624 19625//19625 -f 19625//19625 19624//19624 19626//19626 -f 19625//19625 19626//19626 19627//19627 -f 19627//19627 19626//19626 19628//19628 -f 19627//19627 19628//19628 19629//19629 -f 19629//19629 19628//19628 19630//19630 -f 19629//19629 19630//19630 19631//19631 -f 19630//19630 19632//19632 19631//19631 -f 19631//19631 19632//19632 19633//19633 -f 19631//19631 19633//19633 19634//19634 -f 19634//19634 19633//19633 19635//19635 -f 19634//19634 19635//19635 19636//19636 -f 19636//19636 19635//19635 19637//19637 -f 19636//19636 19637//19637 19638//19638 -f 19638//19638 19637//19637 19639//19639 -f 19638//19638 19639//19639 19640//19640 -f 19640//19640 19639//19639 19641//19641 -f 19640//19640 19641//19641 19642//19642 -f 19642//19642 19641//19641 19643//19643 -f 19642//19642 19643//19643 19579//19579 -f 19579//19579 19643//19643 19644//19644 -f 19579//19579 19644//19644 19580//19580 -f 19578//19578 19580//19580 19645//19645 -f 19645//19645 19580//19580 19646//19646 -f 19645//19645 19646//19646 19647//19647 -f 19648//19648 19649//19649 19650//19650 -f 19650//19650 19649//19649 19651//19651 -f 19650//19650 19651//19651 19652//19652 -f 19652//19652 19651//19651 19653//19653 -f 19652//19652 19653//19653 19654//19654 -f 19654//19654 19653//19653 19655//19655 -f 19654//19654 19655//19655 19656//19656 -f 19656//19656 19655//19655 19657//19657 -f 19656//19656 19657//19657 19658//19658 -f 19658//19658 19657//19657 19659//19659 -f 19658//19658 19659//19659 19660//19660 -f 19660//19660 19659//19659 19661//19661 -f 19660//19660 19661//19661 19662//19662 -f 19662//19662 19661//19661 19663//19663 -f 19662//19662 19663//19663 19664//19664 -f 19664//19664 19663//19663 19665//19665 -f 19664//19664 19665//19665 19666//19666 -f 19666//19666 19665//19665 19667//19667 -f 19666//19666 19667//19667 19668//19668 -f 19668//19668 19667//19667 19669//19669 -f 19668//19668 19669//19669 19670//19670 -f 19670//19670 19669//19669 19671//19671 -f 19670//19670 19671//19671 19672//19672 -f 19671//19671 19673//19673 19672//19672 -f 19672//19672 19673//19673 19674//19674 -f 19672//19672 19674//19674 19675//19675 -f 19675//19675 19674//19674 19676//19676 -f 19675//19675 19676//19676 19677//19677 -f 19677//19677 19676//19676 19678//19678 -f 19677//19677 19678//19678 19679//19679 -f 19679//19679 19678//19678 19680//19680 -f 19679//19679 19680//19680 19681//19681 -f 19681//19681 19680//19680 19682//19682 -f 19681//19681 19682//19682 19683//19683 -f 19683//19683 19682//19682 19684//19684 -f 19682//19682 19685//19685 19684//19684 -f 19684//19684 19685//19685 19686//19686 -f 19684//19684 19686//19686 19687//19687 -f 19687//19687 19686//19686 19688//19688 -f 19687//19687 19688//19688 19689//19689 -f 19689//19689 19688//19688 19690//19690 -f 19689//19689 19690//19690 19691//19691 -f 19691//19691 19690//19690 19692//19692 -f 19691//19691 19692//19692 19693//19693 -f 19693//19693 19692//19692 19694//19694 -f 19693//19693 19694//19694 19695//19695 -f 19695//19695 19694//19694 19696//19696 -f 19695//19695 19696//19696 19697//19697 -f 19697//19697 19696//19696 19698//19698 -f 19697//19697 19698//19698 19699//19699 -f 19699//19699 19698//19698 19700//19700 -f 19699//19699 19700//19700 19701//19701 -f 19701//19701 19700//19700 19702//19702 -f 19701//19701 19702//19702 19703//19703 -f 19703//19703 19702//19702 19704//19704 -f 19703//19703 19704//19704 19705//19705 -f 19705//19705 19704//19704 19706//19706 -f 19707//19707 19708//19708 19709//19709 -f 19709//19709 19708//19708 19710//19710 -f 19709//19709 19710//19710 19706//19706 -f 19706//19706 19710//19710 19711//19711 -f 19706//19706 19711//19711 19705//19705 -f 19712//19712 19713//19713 19714//19714 -f 19715//19715 19716//19716 19717//19717 -f 19717//19717 19716//19716 19718//19718 -f 19717//19717 19718//19718 19719//19719 -f 19719//19719 19718//19718 19720//19720 -f 19719//19719 19720//19720 19721//19721 -f 19721//19721 19720//19720 19722//19722 -f 19721//19721 19722//19722 19723//19723 -f 19723//19723 19722//19722 19724//19724 -f 19723//19723 19724//19724 19725//19725 -f 19726//19726 19727//19727 19728//19728 -f 19728//19728 19727//19727 19729//19729 -f 19728//19728 19729//19729 19725//19725 -f 19725//19725 19729//19729 19730//19730 -f 19725//19725 19730//19730 19723//19723 -f 19731//19731 19732//19732 19733//19733 -f 19733//19733 19732//19732 19734//19734 -f 19728//19728 19735//19735 19726//19726 -f 19726//19726 19735//19735 19736//19736 -f 19726//19726 19736//19736 19737//19737 -f 19737//19737 19736//19736 19738//19738 -f 19737//19737 19738//19738 19739//19739 -f 19739//19739 19738//19738 19740//19740 -f 19739//19739 19740//19740 19731//19731 -f 19731//19731 19740//19740 19741//19741 -f 19731//19731 19741//19741 19732//19732 -f 19742//19742 19743//19743 19744//19744 -f 19744//19744 19743//19743 19745//19745 -f 19744//19744 19745//19745 19734//19734 -f 19734//19734 19745//19745 19746//19746 -f 19734//19734 19746//19746 19733//19733 -f 19747//19747 19748//19748 19749//19749 -f 19749//19749 19748//19748 19750//19750 -f 19749//19749 19750//19750 19742//19742 -f 19742//19742 19750//19750 19751//19751 -f 19742//19742 19751//19751 19743//19743 -f 19714//19714 19713//19713 19752//19752 -f 19752//19752 19713//19713 19753//19753 -f 19752//19752 19753//19753 19747//19747 -f 19747//19747 19753//19753 19754//19754 -f 19747//19747 19754//19754 19748//19748 -f 19714//19714 19755//19755 19712//19712 -f 19712//19712 19755//19755 19756//19756 -f 19712//19712 19756//19756 19757//19757 -f 19757//19757 19756//19756 19758//19758 -f 19757//19757 19758//19758 19759//19759 -f 19759//19759 19758//19758 19760//19760 -f 19759//19759 19760//19760 19761//19761 -f 19761//19761 19760//19760 19762//19762 -f 19761//19761 19762//19762 19763//19763 -f 19762//19762 19764//19764 19763//19763 -f 19763//19763 19764//19764 19765//19765 -f 19765//19765 19764//19764 19766//19766 -f 19765//19765 19766//19766 19767//19767 -f 19766//19766 19768//19768 19767//19767 -f 19767//19767 19768//19768 19769//19769 -f 19767//19767 19769//19769 19770//19770 -f 19770//19770 19769//19769 19771//19771 -f 19770//19770 19771//19771 19772//19772 -f 19772//19772 19771//19771 19773//19773 -f 19773//19773 19771//19771 19774//19774 -f 19773//19773 19774//19774 19775//19775 -f 19774//19774 19776//19776 19775//19775 -f 19775//19775 19776//19776 19777//19777 -f 19775//19775 19777//19777 19778//19778 -f 19778//19778 19777//19777 19779//19779 -f 19778//19778 19779//19779 19780//19780 -f 19779//19779 19781//19781 19780//19780 -f 19780//19780 19781//19781 19782//19782 -f 19780//19780 19782//19782 19783//19783 -f 19783//19783 19782//19782 19784//19784 -f 19783//19783 19784//19784 19785//19785 -f 19785//19785 19784//19784 19786//19786 -f 19787//19787 19788//19788 19789//19789 -f 19789//19789 19788//19788 19790//19790 -f 19789//19789 19790//19790 19791//19791 -f 19791//19791 19790//19790 19792//19792 -f 19791//19791 19792//19792 19793//19793 -f 19794//19794 19795//19795 19796//19796 -f 19796//19796 19797//19797 19794//19794 -f 19794//19794 19797//19797 19798//19798 -f 19794//19794 19798//19798 19799//19799 -f 19792//19792 19800//19800 19793//19793 -f 19793//19793 19800//19800 19801//19801 -f 19793//19793 19801//19801 19802//19802 -f 19802//19802 19801//19801 19803//19803 -f 19802//19802 19803//19803 19804//19804 -f 19804//19804 19803//19803 19805//19805 -f 19804//19804 19805//19805 19806//19806 -f 19806//19806 19805//19805 19807//19807 -f 19806//19806 19807//19807 19808//19808 -f 19808//19808 19807//19807 19809//19809 -f 19808//19808 19809//19809 19810//19810 -f 19810//19810 19809//19809 19811//19811 -f 19810//19810 19811//19811 19812//19812 -f 19812//19812 19811//19811 19813//19813 -f 19812//19812 19813//19813 19795//19795 -f 19795//19795 19813//19813 19814//19814 -f 19795//19795 19814//19814 19796//19796 -f 19798//19798 19815//19815 19799//19799 -f 19799//19799 19815//19815 19816//19816 -f 19799//19799 19816//19816 19817//19817 -f 19817//19817 19816//19816 19818//19818 -f 19817//19817 19818//19818 19819//19819 -f 19819//19819 19818//19818 19820//19820 -f 19819//19819 19820//19820 19821//19821 -f 19821//19821 19820//19820 19822//19822 -f 19821//19821 19822//19822 19823//19823 -f 19823//19823 19822//19822 19824//19824 -f 19823//19823 19824//19824 19825//19825 -f 19824//19824 19826//19826 19825//19825 -f 19825//19825 19826//19826 19827//19827 -f 19825//19825 19827//19827 19828//19828 -f 19828//19828 19827//19827 19829//19829 -f 19828//19828 19829//19829 19830//19830 -f 19830//19830 19829//19829 19831//19831 -f 19830//19830 19831//19831 19832//19832 -f 19832//19832 19831//19831 19833//19833 -f 19833//19833 19831//19831 19834//19834 -f 19833//19833 19834//19834 19835//19835 -f 19836//19836 19837//19837 19838//19838 -f 19838//19838 19837//19837 19839//19839 -f 19838//19838 19839//19839 19840//19840 -f 19840//19840 19839//19839 19841//19841 -f 19840//19840 19841//19841 19842//19842 -f 19842//19842 19841//19841 19843//19843 -f 19842//19842 19843//19843 19844//19844 -f 19844//19844 19843//19843 19845//19845 -f 19844//19844 19845//19845 19846//19846 -f 19846//19846 19845//19845 19847//19847 -f 19846//19846 19847//19847 19848//19848 -f 19848//19848 19847//19847 19849//19849 -f 19848//19848 19849//19849 19850//19850 -f 19850//19850 19849//19849 19835//19835 -f 19850//19850 19835//19835 19851//19851 -f 19851//19851 19835//19835 19834//19834 -f 19852//19852 19853//19853 19854//19854 -f 19854//19854 19853//19853 19855//19855 -f 19854//19854 19855//19855 19856//19856 -f 19856//19856 19855//19855 19857//19857 -f 19856//19856 19857//19857 19836//19836 -f 19836//19836 19857//19857 19858//19858 -f 19836//19836 19858//19858 19837//19837 -f 19859//19859 19860//19860 19861//19861 -f 19861//19861 19860//19860 19862//19862 -f 19861//19861 19862//19862 19852//19852 -f 19852//19852 19862//19862 19863//19863 -f 19852//19852 19863//19863 19853//19853 -f 19864//19864 19865//19865 19866//19866 -f 19866//19866 19865//19865 19867//19867 -f 19866//19866 19867//19867 19868//19868 -f 19867//19867 19869//19869 19868//19868 -f 19868//19868 19869//19869 19870//19870 -f 19868//19868 19870//19870 19871//19871 -f 19871//19871 19870//19870 19872//19872 -f 19871//19871 19872//19872 19873//19873 -f 19873//19873 19872//19872 19874//19874 -f 19873//19873 19874//19874 19875//19875 -f 19875//19875 19874//19874 19876//19876 -f 19875//19875 19876//19876 19877//19877 -f 19876//19876 19878//19878 19877//19877 -f 19877//19877 19878//19878 19879//19879 -f 19877//19877 19879//19879 19880//19880 -f 19880//19880 19879//19879 19881//19881 -f 19880//19880 19881//19881 19882//19882 -f 19882//19882 19881//19881 19883//19883 -f 19882//19882 19883//19883 19884//19884 -f 19884//19884 19883//19883 19885//19885 -f 19884//19884 19885//19885 19886//19886 -f 19885//19885 19887//19887 19886//19886 -f 19886//19886 19887//19887 19888//19888 -f 19886//19886 19888//19888 19889//19889 -f 19889//19889 19888//19888 19890//19890 -f 19889//19889 19890//19890 19891//19891 -f 19891//19891 19890//19890 19892//19892 -f 19891//19891 19892//19892 19893//19893 -f 19893//19893 19892//19892 19894//19894 -f 19893//19893 19894//19894 19895//19895 -f 19895//19895 19894//19894 19896//19896 -f 19895//19895 19896//19896 19897//19897 -f 19897//19897 19896//19896 19898//19898 -f 19897//19897 19898//19898 19899//19899 -f 19899//19899 19898//19898 19900//19900 -f 19899//19899 19900//19900 19901//19901 -f 19900//19900 19902//19902 19901//19901 -f 19901//19901 19902//19902 19903//19903 -f 19901//19901 19903//19903 19904//19904 -f 19904//19904 19903//19903 19905//19905 -f 19904//19904 19905//19905 19906//19906 -f 19906//19906 19905//19905 19907//19907 -f 19906//19906 19907//19907 19908//19908 -f 19908//19908 19907//19907 19909//19909 -f 19908//19908 19909//19909 19910//19910 -f 19910//19910 19909//19909 19911//19911 -f 19910//19910 19911//19911 19912//19912 -f 19911//19911 19913//19913 19912//19912 -f 19912//19912 19913//19913 19914//19914 -f 19912//19912 19914//19914 19915//19915 -f 19915//19915 19914//19914 19916//19916 -f 19915//19915 19916//19916 19917//19917 -f 19917//19917 19916//19916 19918//19918 -f 19916//19916 19919//19919 19918//19918 -f 19918//19918 19919//19919 19920//19920 -f 19918//19918 19920//19920 19921//19921 -f 19921//19921 19920//19920 19922//19922 -f 19921//19921 19922//19922 19923//19923 -f 19923//19923 19922//19922 19924//19924 -f 19923//19923 19924//19924 19925//19925 -f 19924//19924 19926//19926 19925//19925 -f 19925//19925 19926//19926 19927//19927 -f 19925//19925 19927//19927 19928//19928 -f 19928//19928 19927//19927 19929//19929 -f 19928//19928 19929//19929 19930//19930 -f 19930//19930 19929//19929 19931//19931 -f 19932//19932 19933//19933 19934//19934 -f 19934//19934 19933//19933 19935//19935 -f 19934//19934 19935//19935 19936//19936 -f 19935//19935 19937//19937 19936//19936 -f 19936//19936 19937//19937 19938//19938 -f 19936//19936 19938//19938 19939//19939 -f 19939//19939 19938//19938 19940//19940 -f 19939//19939 19940//19940 19941//19941 -f 19941//19941 19940//19940 19942//19942 -f 19941//19941 19942//19942 19943//19943 -f 19943//19943 19942//19942 19944//19944 -f 19943//19943 19944//19944 19945//19945 -f 19946//19946 19947//19947 19948//19948 -f 19948//19948 19947//19947 19949//19949 -f 19948//19948 19949//19949 19950//19950 -f 19950//19950 19949//19949 19951//19951 -f 19950//19950 19951//19951 19952//19952 -f 19952//19952 19951//19951 19953//19953 -f 19952//19952 19953//19953 19954//19954 -f 19954//19954 19953//19953 19955//19955 -f 19954//19954 19955//19955 19956//19956 -f 19956//19956 19955//19955 19957//19957 -f 19956//19956 19957//19957 19958//19958 -f 19958//19958 19957//19957 19959//19959 -f 19958//19958 19959//19959 19960//19960 -f 19960//19960 19959//19959 19961//19961 -f 19960//19960 19961//19961 19962//19962 -f 19962//19962 19961//19961 19963//19963 -f 19962//19962 19963//19963 19945//19945 -f 19945//19945 19963//19963 19964//19964 -f 19945//19945 19964//19964 19943//19943 -f 19965//19965 19966//19966 19967//19967 -f 19967//19967 19966//19966 19968//19968 -f 19967//19967 19968//19968 19969//19969 -f 19969//19969 19968//19968 19970//19970 -f 19969//19969 19970//19970 19946//19946 -f 19946//19946 19970//19970 19971//19971 -f 19946//19946 19971//19971 19947//19947 -f 19972//19972 19973//19973 19974//19974 -f 19974//19974 19973//19973 19975//19975 -f 19974//19974 19975//19975 19965//19965 -f 19965//19965 19975//19975 19976//19976 -f 19965//19965 19976//19976 19966//19966 -f 19977//19977 19978//19978 19979//19979 -f 19979//19979 19980//19980 19977//19977 -f 19977//19977 19980//19980 19981//19981 -f 19977//19977 19981//19981 19982//19982 -f 19982//19982 19981//19981 19983//19983 -f 19982//19982 19983//19983 19984//19984 -f 19984//19984 19983//19983 19985//19985 -f 19984//19984 19985//19985 19986//19986 -f 19986//19986 19985//19985 19987//19987 -f 19986//19986 19987//19987 19988//19988 -f 19988//19988 19987//19987 19989//19989 -f 19988//19988 19989//19989 19990//19990 -f 19990//19990 19989//19989 19991//19991 -f 19990//19990 19991//19991 19932//19932 -f 19932//19932 19991//19991 19992//19992 -f 19932//19932 19992//19992 19933//19933 -f 19993//19993 19994//19994 19995//19995 -f 19978//19978 19996//19996 19979//19979 -f 19979//19979 19996//19996 19993//19993 -f 19979//19979 19993//19993 19997//19997 -f 19997//19997 19993//19993 19995//19995 -f 19998//19998 19999//19999 20000//20000 -f 20001//20001 20002//20002 20003//20003 -f 20003//20003 20002//20002 20004//20004 -f 20003//20003 20004//20004 20005//20005 -f 20005//20005 20004//20004 20006//20006 -f 20005//20005 20006//20006 20000//20000 -f 20000//20000 20006//20006 20007//20007 -f 20000//20000 20007//20007 19998//19998 -f 19999//19999 19998//19998 20008//20008 -f 20008//20008 19998//19998 20009//20009 -f 20008//20008 20009//20009 20010//20010 -f 20010//20010 20009//20009 20011//20011 -f 20010//20010 20011//20011 20012//20012 -f 20013//20013 20014//20014 20015//20015 -f 20011//20011 20016//20016 20012//20012 -f 20012//20012 20016//20016 20017//20017 -f 20012//20012 20017//20017 20018//20018 -f 20018//20018 20017//20017 20019//20019 -f 20018//20018 20019//20019 20020//20020 -f 20020//20020 20019//20019 20021//20021 -f 20020//20020 20021//20021 20022//20022 -f 20022//20022 20021//20021 20023//20023 -f 20022//20022 20023//20023 20024//20024 -f 20024//20024 20023//20023 20025//20025 -f 20024//20024 20025//20025 20014//20014 -f 20014//20014 20025//20025 20026//20026 -f 20014//20014 20026//20026 20015//20015 -f 20013//20013 20015//20015 20027//20027 -f 20027//20027 20015//20015 20028//20028 -f 20027//20027 20028//20028 20029//20029 -f 20029//20029 20028//20028 20030//20030 -f 20029//20029 20030//20030 20031//20031 -f 20031//20031 20030//20030 20032//20032 -f 20031//20031 20032//20032 20033//20033 -f 20033//20033 20032//20032 20034//20034 -f 20033//20033 20034//20034 20035//20035 -f 20034//20034 20036//20036 20035//20035 -f 20035//20035 20036//20036 20037//20037 -f 20035//20035 20037//20037 20038//20038 -f 20038//20038 20037//20037 20039//20039 -f 20038//20038 20039//20039 20040//20040 -f 20040//20040 20039//20039 20041//20041 -f 20040//20040 20041//20041 20042//20042 -f 20042//20042 20041//20041 20043//20043 -f 20042//20042 20043//20043 20044//20044 -f 20044//20044 20043//20043 20045//20045 -f 20044//20044 20045//20045 20046//20046 -f 20046//20046 20045//20045 20047//20047 -f 20048//20048 20049//20049 20050//20050 -f 20050//20050 20049//20049 20051//20051 -f 20050//20050 20051//20051 20052//20052 -f 20052//20052 20051//20051 20053//20053 -f 20052//20052 20053//20053 20047//20047 -f 20047//20047 20053//20053 20054//20054 -f 20047//20047 20054//20054 20046//20046 -f 20055//20055 20056//20056 20048//20048 -f 20048//20048 20056//20056 20057//20057 -f 20048//20048 20057//20057 20049//20049 -f 20058//20058 20059//20059 20060//20060 -f 20048//20048 20061//20061 20055//20055 -f 20055//20055 20061//20061 20058//20058 -f 20055//20055 20058//20058 20062//20062 -f 20062//20062 20058//20058 20060//20060 -f 20063//20063 20064//20064 20065//20065 -f 20066//20066 20067//20067 20068//20068 -f 20068//20068 20067//20067 20069//20069 -f 20068//20068 20069//20069 20070//20070 -f 20070//20070 20069//20069 20071//20071 -f 20070//20070 20071//20071 20065//20065 -f 20065//20065 20071//20071 20072//20072 -f 20065//20065 20072//20072 20063//20063 -f 20064//20064 20063//20063 20073//20073 -f 20073//20073 20063//20063 20074//20074 -f 20073//20073 20074//20074 20075//20075 -f 20075//20075 20074//20074 20076//20076 -f 20075//20075 20076//20076 20077//20077 -f 20077//20077 20076//20076 20078//20078 -f 20077//20077 20078//20078 20079//20079 -f 20079//20079 20078//20078 20080//20080 -f 20079//20079 20080//20080 20081//20081 -f 20080//20080 20082//20082 20081//20081 -f 20081//20081 20082//20082 20083//20083 -f 20081//20081 20083//20083 20084//20084 -f 20084//20084 20083//20083 20085//20085 -f 20084//20084 20085//20085 20086//20086 -f 20086//20086 20085//20085 20087//20087 -f 20086//20086 20087//20087 20088//20088 -f 20087//20087 20089//20089 20088//20088 -f 20088//20088 20089//20089 20090//20090 -f 20088//20088 20090//20090 20091//20091 -f 20091//20091 20090//20090 20092//20092 -f 20091//20091 20092//20092 20093//20093 -f 20093//20093 20092//20092 20094//20094 -f 20093//20093 20094//20094 20095//20095 -f 20095//20095 20094//20094 20096//20096 -f 20095//20095 20096//20096 20097//20097 -f 20097//20097 20096//20096 20098//20098 -f 20097//20097 20098//20098 20099//20099 -f 20099//20099 20098//20098 20100//20100 -f 20099//20099 20100//20100 20101//20101 -f 20101//20101 20100//20100 20102//20102 -f 20101//20101 20102//20102 20103//20103 -f 20103//20103 20102//20102 20104//20104 -f 20105//20105 20106//20106 20107//20107 -f 20107//20107 20106//20106 20108//20108 -f 20107//20107 20108//20108 20109//20109 -f 20109//20109 20108//20108 20110//20110 -f 20109//20109 20110//20110 20111//20111 -f 20111//20111 20110//20110 20112//20112 -f 20111//20111 20112//20112 20113//20113 -f 20113//20113 20112//20112 20114//20114 -f 20113//20113 20114//20114 20115//20115 -f 20115//20115 20114//20114 20116//20116 -f 20115//20115 20116//20116 20117//20117 -f 20117//20117 20116//20116 20118//20118 -f 20117//20117 20118//20118 20119//20119 -f 20119//20119 20118//20118 20120//20120 -f 20119//20119 20120//20120 20104//20104 -f 20104//20104 20120//20120 20121//20121 -f 20104//20104 20121//20121 20103//20103 -f 20122//20122 20123//20123 20124//20124 -f 20107//20107 20125//20125 20105//20105 -f 20105//20105 20125//20125 20122//20122 -f 20105//20105 20122//20122 20126//20126 -f 20126//20126 20122//20122 20124//20124 -f 20127//20127 20128//20128 20129//20129 -f 20127//20127 20129//20129 20130//20130 -f 20129//20129 20131//20131 20130//20130 -f 20130//20130 20131//20131 20132//20132 -f 20130//20130 20132//20132 20133//20133 -f 20133//20133 20132//20132 20134//20134 -f 20133//20133 20134//20134 20135//20135 -f 20135//20135 20134//20134 20136//20136 -f 20135//20135 20136//20136 20137//20137 -f 20137//20137 20136//20136 20138//20138 -f 20137//20137 20138//20138 20139//20139 -f 20139//20139 20138//20138 20140//20140 -f 20139//20139 20140//20140 20141//20141 -f 20141//20141 20140//20140 20142//20142 -f 20141//20141 20142//20142 20143//20143 -f 20143//20143 20142//20142 20144//20144 -f 20143//20143 20144//20144 20145//20145 -f 20145//20145 20144//20144 20146//20146 -f 20145//20145 20146//20146 20147//20147 -f 20128//20128 20127//20127 20148//20148 -f 20148//20148 20127//20127 20149//20149 -f 20148//20148 20149//20149 20150//20150 -f 20150//20150 20149//20149 20151//20151 -f 20150//20150 20151//20151 20152//20152 -f 20152//20152 20151//20151 20153//20153 -f 20153//20153 20151//20151 20154//20154 -f 20153//20153 20154//20154 20155//20155 -f 20154//20154 20156//20156 20155//20155 -f 20155//20155 20156//20156 20157//20157 -f 20155//20155 20157//20157 20158//20158 -f 20158//20158 20157//20157 20159//20159 -f 20158//20158 20159//20159 20160//20160 -f 20160//20160 20159//20159 20161//20161 -f 20160//20160 20161//20161 20162//20162 -f 20162//20162 20161//20161 20163//20163 -f 20162//20162 20163//20163 20164//20164 -f 20163//20163 20165//20165 20164//20164 -f 20164//20164 20165//20165 20166//20166 -f 20164//20164 20166//20166 20167//20167 -f 20167//20167 20166//20166 20168//20168 -f 20167//20167 20168//20168 20169//20169 -f 20169//20169 20168//20168 20170//20170 -f 20169//20169 20170//20170 20171//20171 -f 20171//20171 20170//20170 20172//20172 -f 20171//20171 20172//20172 20173//20173 -f 20173//20173 20172//20172 20174//20174 -f 20173//20173 20174//20174 20175//20175 -f 20175//20175 20174//20174 20176//20176 -f 20175//20175 20176//20176 20177//20177 -f 20177//20177 20176//20176 20178//20178 -f 20177//20177 20178//20178 20179//20179 -f 20179//20179 20178//20178 20180//20180 -f 20179//20179 20180//20180 20181//20181 -f 20181//20181 20180//20180 20182//20182 -f 20181//20181 20182//20182 20183//20183 -f 20183//20183 20182//20182 20184//20184 -f 20184//20184 20185//20185 20183//20183 -f 20183//20183 20185//20185 20186//20186 -f 20183//20183 20186//20186 20187//20187 -f 20187//20187 20186//20186 20188//20188 -f 20187//20187 20188//20188 20189//20189 -f 20189//20189 20188//20188 20190//20190 -f 20189//20189 20190//20190 20191//20191 -f 20191//20191 20190//20190 20192//20192 -f 20191//20191 20192//20192 20193//20193 -f 20193//20193 20192//20192 20194//20194 -f 20193//20193 20194//20194 20195//20195 -f 20196//20196 20197//20197 20198//20198 -f 20198//20198 20197//20197 20199//20199 -f 20198//20198 20199//20199 20200//20200 -f 20199//20199 20201//20201 20200//20200 -f 20200//20200 20201//20201 20202//20202 -f 20200//20200 20202//20202 20203//20203 -f 20203//20203 20202//20202 20204//20204 -f 20203//20203 20204//20204 20205//20205 -f 20205//20205 20204//20204 20206//20206 -f 20205//20205 20206//20206 20207//20207 -f 20207//20207 20206//20206 20208//20208 -f 20207//20207 20208//20208 20209//20209 -f 20209//20209 20208//20208 20210//20210 -f 20209//20209 20210//20210 20211//20211 -f 20212//20212 20213//20213 20214//20214 -f 20214//20214 20213//20213 20215//20215 -f 20214//20214 20215//20215 20216//20216 -f 20216//20216 20215//20215 20217//20217 -f 20216//20216 20217//20217 20218//20218 -f 20218//20218 20217//20217 20219//20219 -f 20218//20218 20219//20219 20211//20211 -f 20211//20211 20219//20219 20220//20220 -f 20211//20211 20220//20220 20209//20209 -f 20214//20214 20221//20221 20212//20212 -f 20212//20212 20221//20221 20222//20222 -f 20212//20212 20222//20222 20223//20223 -f 20222//20222 20224//20224 20223//20223 -f 20223//20223 20224//20224 20225//20225 -f 20223//20223 20225//20225 20226//20226 -f 20226//20226 20225//20225 20227//20227 -f 20226//20226 20227//20227 20228//20228 -f 20228//20228 20227//20227 20229//20229 -f 20230//20230 20231//20231 20232//20232 -f 20232//20232 20233//20233 20230//20230 -f 20230//20230 20233//20233 20234//20234 -f 20230//20230 20234//20234 20235//20235 -f 20235//20235 20234//20234 20236//20236 -f 20235//20235 20236//20236 20237//20237 -f 20237//20237 20236//20236 20238//20238 -f 20237//20237 20238//20238 20239//20239 -f 20239//20239 20238//20238 20240//20240 -f 20239//20239 20240//20240 20241//20241 -f 20241//20241 20240//20240 20242//20242 -f 20241//20241 20242//20242 20243//20243 -f 20243//20243 20242//20242 20244//20244 -f 20243//20243 20244//20244 20245//20245 -f 20245//20245 20244//20244 20246//20246 -f 20245//20245 20246//20246 20247//20247 -f 20247//20247 20246//20246 20248//20248 -f 20247//20247 20248//20248 20249//20249 -f 20249//20249 20248//20248 20250//20250 -f 20249//20249 20250//20250 20251//20251 -f 20251//20251 20250//20250 20252//20252 -f 20251//20251 20252//20252 20253//20253 -f 20253//20253 20252//20252 20254//20254 -f 20253//20253 20254//20254 20229//20229 -f 20229//20229 20254//20254 20255//20255 -f 20229//20229 20255//20255 20228//20228 -f 20256//20256 20257//20257 20258//20258 -f 20258//20258 20257//20257 20259//20259 -f 20258//20258 20259//20259 20231//20231 -f 20231//20231 20259//20259 20260//20260 -f 20231//20231 20260//20260 20232//20232 -f 20258//20258 20261//20261 20256//20256 -f 20256//20256 20261//20261 20262//20262 -f 20256//20256 20262//20262 20263//20263 -f 20264//20264 20265//20265 20266//20266 -f 20266//20266 20265//20265 20267//20267 -f 20266//20266 20267//20267 20268//20268 -f 20268//20268 20267//20267 20269//20269 -f 20268//20268 20269//20269 20270//20270 -f 20270//20270 20269//20269 20271//20271 -f 20270//20270 20271//20271 20272//20272 -f 20272//20272 20271//20271 20273//20273 -f 20272//20272 20273//20273 20274//20274 -f 20274//20274 20273//20273 20275//20275 -f 20274//20274 20275//20275 20276//20276 -f 20276//20276 20275//20275 20277//20277 -f 20277//20277 20275//20275 20278//20278 -f 20277//20277 20278//20278 20279//20279 -f 20279//20279 20278//20278 20280//20280 -f 20279//20279 20280//20280 20281//20281 -f 20281//20281 20280//20280 20282//20282 -f 20281//20281 20282//20282 20283//20283 -f 20283//20283 20282//20282 20284//20284 -f 20283//20283 20284//20284 20285//20285 -f 20285//20285 20284//20284 20286//20286 -f 20285//20285 20286//20286 20287//20287 -f 20287//20287 20286//20286 20288//20288 -f 20288//20288 20286//20286 20289//20289 -f 20288//20288 20289//20289 20290//20290 -f 20289//20289 20291//20291 20290//20290 -f 20290//20290 20291//20291 20292//20292 -f 20290//20290 20292//20292 20293//20293 -f 20293//20293 20292//20292 20294//20294 -f 20293//20293 20294//20294 20295//20295 -f 20295//20295 20294//20294 20296//20296 -f 20295//20295 20296//20296 20297//20297 -f 20297//20297 20296//20296 20298//20298 -f 20297//20297 20298//20298 20299//20299 -f 20299//20299 20298//20298 20300//20300 -f 20299//20299 20300//20300 20301//20301 -f 20301//20301 20300//20300 20302//20302 -f 20301//20301 20302//20302 20303//20303 -f 20303//20303 20302//20302 20304//20304 -f 20303//20303 20304//20304 20305//20305 -f 20305//20305 20304//20304 20306//20306 -f 20305//20305 20306//20306 20307//20307 -f 20307//20307 20306//20306 20308//20308 -f 20307//20307 20308//20308 20309//20309 -f 20309//20309 20308//20308 20310//20310 -f 20309//20309 20310//20310 20311//20311 -f 20310//20310 20312//20312 20311//20311 -f 20311//20311 20312//20312 20313//20313 -f 20311//20311 20313//20313 20314//20314 -f 20314//20314 20313//20313 20315//20315 -f 20314//20314 20315//20315 20316//20316 -f 20316//20316 20315//20315 20317//20317 -f 20315//20315 20318//20318 20317//20317 -f 20317//20317 20318//20318 20319//20319 -f 20317//20317 20319//20319 20320//20320 -f 20319//20319 20321//20321 20320//20320 -f 20320//20320 20321//20321 20322//20322 -f 20320//20320 20322//20322 20323//20323 -f 20322//20322 20324//20324 20323//20323 -f 20323//20323 20324//20324 20325//20325 -f 20326//20326 20327//20327 20328//20328 -f 20328//20328 20327//20327 20325//20325 -f 20328//20328 20325//20325 20329//20329 -f 20329//20329 20325//20325 20324//20324 -f 20326//20326 20330//20330 20327//20327 -f 20327//20327 20330//20330 20331//20331 -f 20327//20327 20331//20331 20332//20332 -f 20333//20333 20334//20334 20335//20335 -f 20335//20335 20334//20334 20336//20336 -f 20335//20335 20336//20336 20337//20337 -f 20337//20337 20336//20336 20338//20338 -f 20333//20333 20339//20339 20334//20334 -f 20334//20334 20339//20339 20340//20340 -f 20334//20334 20340//20340 20341//20341 -f 20341//20341 20340//20340 20342//20342 -f 20341//20341 20342//20342 20343//20343 -f 20343//20343 20342//20342 20344//20344 -f 20343//20343 20344//20344 20345//20345 -f 20345//20345 20344//20344 20346//20346 -f 20345//20345 20346//20346 20347//20347 -f 20347//20347 20346//20346 20348//20348 -f 20347//20347 20348//20348 20349//20349 -f 20349//20349 20348//20348 20350//20350 -f 20349//20349 20350//20350 20351//20351 -f 20351//20351 20350//20350 20352//20352 -f 20351//20351 20352//20352 20353//20353 -f 20353//20353 20352//20352 20354//20354 -f 20353//20353 20354//20354 20355//20355 -f 20355//20355 20354//20354 20356//20356 -f 20355//20355 20356//20356 20357//20357 -f 20357//20357 20356//20356 20358//20358 -f 20357//20357 20358//20358 20359//20359 -f 20359//20359 20358//20358 20360//20360 -f 20359//20359 20360//20360 20361//20361 -f 20361//20361 20360//20360 20362//20362 -f 20361//20361 20362//20362 20363//20363 -f 20363//20363 20362//20362 20364//20364 -f 20363//20363 20364//20364 20365//20365 -f 20365//20365 20364//20364 20366//20366 -f 20365//20365 20366//20366 20367//20367 -f 20367//20367 20366//20366 20368//20368 -f 20367//20367 20368//20368 20369//20369 -f 20369//20369 20368//20368 20370//20370 -f 20369//20369 20370//20370 20371//20371 -f 20371//20371 20370//20370 20372//20372 -f 20371//20371 20372//20372 20373//20373 -f 20373//20373 20372//20372 20374//20374 -f 20373//20373 20374//20374 20375//20375 -f 20375//20375 20374//20374 20376//20376 -f 20376//20376 20374//20374 20377//20377 -f 20376//20376 20377//20377 20378//20378 -f 20378//20378 20377//20377 20379//20379 -f 20378//20378 20379//20379 20380//20380 -f 20380//20380 20379//20379 20381//20381 -f 20380//20380 20381//20381 20382//20382 -f 20382//20382 20381//20381 20383//20383 -f 20382//20382 20383//20383 20384//20384 -f 20384//20384 20383//20383 20385//20385 -f 20384//20384 20385//20385 20386//20386 -f 20386//20386 20385//20385 20387//20387 -f 20386//20386 20387//20387 20388//20388 -f 20387//20387 20389//20389 20388//20388 -f 20388//20388 20389//20389 20390//20390 -f 20388//20388 20390//20390 20391//20391 -f 20391//20391 20390//20390 20392//20392 -f 20391//20391 20392//20392 20393//20393 -f 20393//20393 20392//20392 20394//20394 -f 20393//20393 20394//20394 20395//20395 -f 20395//20395 20394//20394 20396//20396 -f 20397//20397 20398//20398 20399//20399 -f 20399//20399 20398//20398 20396//20396 -f 20399//20399 20396//20396 20400//20400 -f 20400//20400 20396//20396 20394//20394 -f 20401//20401 20402//20402 20403//20403 -f 20401//20401 20403//20403 20404//20404 -f 20404//20404 20403//20403 20405//20405 -f 20404//20404 20405//20405 20406//20406 -f 20406//20406 20405//20405 20407//20407 -f 20406//20406 20407//20407 20408//20408 -f 20408//20408 20407//20407 20409//20409 -f 20408//20408 20409//20409 20410//20410 -f 20410//20410 20409//20409 20411//20411 -f 20410//20410 20411//20411 20412//20412 -f 20412//20412 20411//20411 20413//20413 -f 20412//20412 20413//20413 20414//20414 -f 20414//20414 20413//20413 20415//20415 -f 20414//20414 20415//20415 20416//20416 -f 20416//20416 20415//20415 20417//20417 -f 20416//20416 20417//20417 20418//20418 -f 20418//20418 20417//20417 20419//20419 -f 20418//20418 20419//20419 20420//20420 -f 20420//20420 20419//20419 20421//20421 -f 20420//20420 20421//20421 20422//20422 -f 20422//20422 20421//20421 20423//20423 -f 20422//20422 20423//20423 20424//20424 -f 20424//20424 20423//20423 20425//20425 -f 20424//20424 20425//20425 20426//20426 -f 20426//20426 20425//20425 20427//20427 -f 20426//20426 20427//20427 20428//20428 -f 20428//20428 20427//20427 20429//20429 -f 20428//20428 20429//20429 20430//20430 -f 20430//20430 20429//20429 20431//20431 -f 20430//20430 20431//20431 20432//20432 -f 20431//20431 20433//20433 20432//20432 -f 20432//20432 20433//20433 20434//20434 -f 20432//20432 20434//20434 20435//20435 -f 20435//20435 20434//20434 20436//20436 -f 20435//20435 20436//20436 20437//20437 -f 20437//20437 20436//20436 20438//20438 -f 20437//20437 20438//20438 20439//20439 -f 20439//20439 20438//20438 20440//20440 -f 20439//20439 20440//20440 20441//20441 -f 20441//20441 20440//20440 20442//20442 -f 20441//20441 20442//20442 20443//20443 -f 20443//20443 20442//20442 20444//20444 -f 20443//20443 20444//20444 20445//20445 -f 20445//20445 20444//20444 20446//20446 -f 20445//20445 20446//20446 20447//20447 -f 20447//20447 20446//20446 20448//20448 -f 20447//20447 20448//20448 20449//20449 -f 20449//20449 20448//20448 20450//20450 -f 20449//20449 20450//20450 20451//20451 -f 20451//20451 20450//20450 20452//20452 -f 20451//20451 20452//20452 20453//20453 -f 20453//20453 20452//20452 20454//20454 -f 20453//20453 20454//20454 20455//20455 -f 20455//20455 20454//20454 20456//20456 -f 20455//20455 20456//20456 20457//20457 -f 20458//20458 20459//20459 20460//20460 -f 20460//20460 20461//20461 20458//20458 -f 20458//20458 20461//20461 20462//20462 -f 20458//20458 20462//20462 20463//20463 -f 20463//20463 20462//20462 20464//20464 -f 20463//20463 20464//20464 20457//20457 -f 20457//20457 20464//20464 20465//20465 -f 20457//20457 20465//20465 20455//20455 -f 20466//20466 20467//20467 20468//20468 -f 20468//20468 20467//20467 20469//20469 -f 20468//20468 20469//20469 20470//20470 -f 20470//20470 20469//20469 20471//20471 -f 20470//20470 20471//20471 20472//20472 -f 20473//20473 20474//20474 20475//20475 -f 20472//20472 20471//20471 20475//20475 -f 20475//20475 20471//20471 20476//20476 -f 20475//20475 20476//20476 20473//20473 -f 20474//20474 20473//20473 20477//20477 -f 20477//20477 20473//20473 20478//20478 -f 20477//20477 20478//20478 20479//20479 -f 20478//20478 20480//20480 20479//20479 -f 20479//20479 20480//20480 20481//20481 -f 20479//20479 20481//20481 20482//20482 -f 20482//20482 20481//20481 20483//20483 -f 20482//20482 20483//20483 20484//20484 -f 20484//20484 20483//20483 20485//20485 -f 20484//20484 20485//20485 20486//20486 -f 20486//20486 20485//20485 20487//20487 -f 20486//20486 20487//20487 20488//20488 -f 20488//20488 20487//20487 20489//20489 -f 20488//20488 20489//20489 20490//20490 -f 20490//20490 20489//20489 20491//20491 -f 20490//20490 20491//20491 20492//20492 -f 20492//20492 20491//20491 20493//20493 -f 20492//20492 20493//20493 20494//20494 -f 20494//20494 20493//20493 20495//20495 -f 20495//20495 20493//20493 20496//20496 -f 20495//20495 20496//20496 20497//20497 -f 20497//20497 20496//20496 20498//20498 -f 20497//20497 20498//20498 20499//20499 -f 20498//20498 20500//20500 20499//20499 -f 20499//20499 20500//20500 20501//20501 -f 20499//20499 20501//20501 20502//20502 -f 20502//20502 20501//20501 20503//20503 -f 20502//20502 20503//20503 20504//20504 -f 20504//20504 20503//20503 20505//20505 -f 20504//20504 20505//20505 20506//20506 -f 20506//20506 20505//20505 20507//20507 -f 20506//20506 20507//20507 20508//20508 -f 20508//20508 20507//20507 20509//20509 -f 20508//20508 20509//20509 20510//20510 -f 20510//20510 20509//20509 20511//20511 -f 20512//20512 20513//20513 20514//20514 -f 20514//20514 20513//20513 20515//20515 -f 20514//20514 20515//20515 20516//20516 -f 20514//20514 20517//20517 20512//20512 -f 20512//20512 20517//20517 20518//20518 -f 20512//20512 20518//20518 20519//20519 -f 20519//20519 20518//20518 20520//20520 -f 20519//20519 20520//20520 20521//20521 -f 20521//20521 20520//20520 20522//20522 -f 20521//20521 20522//20522 20523//20523 -f 20523//20523 20522//20522 20524//20524 -f 20523//20523 20524//20524 20525//20525 -f 20525//20525 20524//20524 20526//20526 -f 20525//20525 20526//20526 20511//20511 -f 20511//20511 20526//20526 20527//20527 -f 20511//20511 20527//20527 20510//20510 -f 20516//20516 20515//20515 20528//20528 -f 20528//20528 20515//20515 20529//20529 -f 20528//20528 20529//20529 20530//20530 -f 20531//20531 20532//20532 20533//20533 -f 20531//20531 20533//20533 20534//20534 -f 20534//20534 20533//20533 20535//20535 -f 20534//20534 20535//20535 20536//20536 -f 20535//20535 20537//20537 20536//20536 -f 20536//20536 20537//20537 20538//20538 -f 20536//20536 20538//20538 20539//20539 -f 20539//20539 20538//20538 20540//20540 -f 20539//20539 20540//20540 20541//20541 -f 20541//20541 20540//20540 20542//20542 -f 20541//20541 20542//20542 20543//20543 -f 20543//20543 20542//20542 20544//20544 -f 20544//20544 20542//20542 20545//20545 -f 20544//20544 20545//20545 20546//20546 -f 20546//20546 20545//20545 20547//20547 -f 20546//20546 20547//20547 20548//20548 -f 20548//20548 20547//20547 20549//20549 -f 20548//20548 20549//20549 20550//20550 -f 20550//20550 20549//20549 20551//20551 -f 20550//20550 20551//20551 20552//20552 -f 20552//20552 20551//20551 20553//20553 -f 20552//20552 20553//20553 20554//20554 -f 20554//20554 20553//20553 20555//20555 -f 20554//20554 20555//20555 20556//20556 -f 20556//20556 20555//20555 20557//20557 -f 20556//20556 20557//20557 20558//20558 -f 20558//20558 20557//20557 20559//20559 -f 20558//20558 20559//20559 20560//20560 -f 20560//20560 20559//20559 20561//20561 -f 20560//20560 20561//20561 20562//20562 -f 20562//20562 20561//20561 20563//20563 -f 20562//20562 20563//20563 20564//20564 -f 20564//20564 20563//20563 20565//20565 -f 20564//20564 20565//20565 20566//20566 -f 20566//20566 20565//20565 20567//20567 -f 20566//20566 20567//20567 20568//20568 -f 20568//20568 20567//20567 20569//20569 -f 20569//20569 20567//20567 20570//20570 -f 20569//20569 20570//20570 20571//20571 -f 20571//20571 20570//20570 20572//20572 -f 20571//20571 20572//20572 20573//20573 -f 20573//20573 20572//20572 20574//20574 -f 20573//20573 20574//20574 20575//20575 -f 20575//20575 20574//20574 20576//20576 -f 20576//20576 20574//20574 20577//20577 -f 20576//20576 20577//20577 20578//20578 -f 20578//20578 20577//20577 20579//20579 -f 20578//20578 20579//20579 20580//20580 -f 20580//20580 20579//20579 20581//20581 -f 20580//20580 20581//20581 20582//20582 -f 20582//20582 20581//20581 20583//20583 -f 20582//20582 20583//20583 20584//20584 -f 20584//20584 20583//20583 20585//20585 -f 20585//20585 20583//20583 20586//20586 -f 20585//20585 20586//20586 20587//20587 -f 20587//20587 20586//20586 20588//20588 -f 20587//20587 20588//20588 20589//20589 -f 20589//20589 20588//20588 20590//20590 -f 20589//20589 20590//20590 20591//20591 -f 20591//20591 20590//20590 20592//20592 -f 20591//20591 20592//20592 20593//20593 -f 20593//20593 20592//20592 20594//20594 -f 20594//20594 20592//20592 20595//20595 -f 20594//20594 20595//20595 20596//20596 -f 20596//20596 20595//20595 20597//20597 -f 20596//20596 20597//20597 20598//20598 -f 20598//20598 20597//20597 20599//20599 -f 20598//20598 20599//20599 20600//20600 -f 20601//20601 20602//20602 20603//20603 -f 20603//20603 20602//20602 20604//20604 -f 20603//20603 20604//20604 20605//20605 -f 20604//20604 20606//20606 20605//20605 -f 20605//20605 20606//20606 20607//20607 -f 20605//20605 20607//20607 20608//20608 -f 20608//20608 20607//20607 20609//20609 -f 20608//20608 20609//20609 20610//20610 -f 20610//20610 20609//20609 20611//20611 -f 20610//20610 20611//20611 20612//20612 -f 20612//20612 20611//20611 20613//20613 -f 20612//20612 20613//20613 20614//20614 -f 20614//20614 20613//20613 20615//20615 -f 20614//20614 20615//20615 20616//20616 -f 20616//20616 20615//20615 20617//20617 -f 20616//20616 20617//20617 20618//20618 -f 20617//20617 20619//20619 20618//20618 -f 20618//20618 20619//20619 20620//20620 -f 20618//20618 20620//20620 20621//20621 -f 20621//20621 20620//20620 20622//20622 -f 20621//20621 20622//20622 20623//20623 -f 20623//20623 20622//20622 20624//20624 -f 20623//20623 20624//20624 20625//20625 -f 20625//20625 20624//20624 20626//20626 -f 20625//20625 20626//20626 20627//20627 -f 20627//20627 20626//20626 20628//20628 -f 20627//20627 20628//20628 20629//20629 -f 20628//20628 20630//20630 20629//20629 -f 20629//20629 20630//20630 20631//20631 -f 20629//20629 20631//20631 20632//20632 -f 20632//20632 20631//20631 20633//20633 -f 20632//20632 20633//20633 20634//20634 -f 20634//20634 20633//20633 20635//20635 -f 20634//20634 20635//20635 20636//20636 -f 20637//20637 20638//20638 20639//20639 -f 20639//20639 20638//20638 20640//20640 -f 20639//20639 20640//20640 20641//20641 -f 20635//20635 20642//20642 20636//20636 -f 20636//20636 20642//20642 20643//20643 -f 20636//20636 20643//20643 20644//20644 -f 20644//20644 20643//20643 20641//20641 -f 20644//20644 20641//20641 20645//20645 -f 20645//20645 20641//20641 20640//20640 -f 20639//20639 20646//20646 20637//20637 -f 20637//20637 20646//20646 20647//20647 -f 20637//20637 20647//20647 20648//20648 -f 20648//20648 20647//20647 20649//20649 -f 20648//20648 20649//20649 20650//20650 -f 20650//20650 20649//20649 20651//20651 -f 20650//20650 20651//20651 20652//20652 -f 20652//20652 20651//20651 20653//20653 -f 20654//20654 20655//20655 20656//20656 -f 20651//20651 20657//20657 20653//20653 -f 20653//20653 20657//20657 20654//20654 -f 20653//20653 20654//20654 20658//20658 -f 20658//20658 20654//20654 20656//20656 -f 20659//20659 20660//20660 20661//20661 -f 20661//20661 20660//20660 20662//20662 -f 20661//20661 20662//20662 20655//20655 -f 20655//20655 20662//20662 20663//20663 -f 20655//20655 20663//20663 20656//20656 -f 20661//20661 20664//20664 20659//20659 -f 20659//20659 20664//20664 20665//20665 -f 20659//20659 20665//20665 20666//20666 -f 20666//20666 20665//20665 20667//20667 -f 20666//20666 20667//20667 20668//20668 -f 20668//20668 20667//20667 20669//20669 -f 20668//20668 20669//20669 20670//20670 -f 20671//20671 20672//20672 20673//20673 -f 20674//20674 20675//20675 20676//20676 -f 20676//20676 20675//20675 20677//20677 -f 20676//20676 20677//20677 20678//20678 -f 20678//20678 20677//20677 20679//20679 -f 20678//20678 20679//20679 20680//20680 -f 20680//20680 20679//20679 20681//20681 -f 20680//20680 20681//20681 20682//20682 -f 20682//20682 20681//20681 20683//20683 -f 20682//20682 20683//20683 20684//20684 -f 20684//20684 20683//20683 20685//20685 -f 20684//20684 20685//20685 20686//20686 -f 20674//20674 20687//20687 20675//20675 -f 20675//20675 20687//20687 20688//20688 -f 20675//20675 20688//20688 20689//20689 -f 20689//20689 20688//20688 20690//20690 -f 20689//20689 20690//20690 20691//20691 -f 20691//20691 20690//20690 20692//20692 -f 20691//20691 20692//20692 20672//20672 -f 20672//20672 20692//20692 20693//20693 -f 20672//20672 20693//20693 20673//20673 -f 20673//20673 20694//20694 20671//20671 -f 20671//20671 20694//20694 20695//20695 -f 20671//20671 20695//20695 20696//20696 -f 20696//20696 20695//20695 20697//20697 -f 20696//20696 20697//20697 20698//20698 -f 20698//20698 20697//20697 20699//20699 -f 20698//20698 20699//20699 20700//20700 -f 20700//20700 20699//20699 20701//20701 -f 20700//20700 20701//20701 20702//20702 -f 20702//20702 20701//20701 20703//20703 -f 20702//20702 20703//20703 20704//20704 -f 20704//20704 20703//20703 20705//20705 -f 20704//20704 20705//20705 20706//20706 -f 20706//20706 20705//20705 20707//20707 -f 20706//20706 20707//20707 20708//20708 -f 20708//20708 20707//20707 20709//20709 -f 20708//20708 20709//20709 20710//20710 -f 20710//20710 20709//20709 20711//20711 -f 20711//20711 20709//20709 20712//20712 -f 20711//20711 20712//20712 20713//20713 -f 20713//20713 20712//20712 20714//20714 -f 20713//20713 20714//20714 20715//20715 -f 20715//20715 20714//20714 20716//20716 -f 20716//20716 20714//20714 20717//20717 -f 20716//20716 20717//20717 20718//20718 -f 20718//20718 20717//20717 20719//20719 -f 20718//20718 20719//20719 20720//20720 -f 20720//20720 20719//20719 20721//20721 -f 20720//20720 20721//20721 20722//20722 -f 20722//20722 20721//20721 20723//20723 -f 20722//20722 20723//20723 20724//20724 -f 20724//20724 20723//20723 20725//20725 -f 20724//20724 20725//20725 20726//20726 -f 20725//20725 20727//20727 20726//20726 -f 20726//20726 20727//20727 20728//20728 -f 20726//20726 20728//20728 20729//20729 -f 20729//20729 20728//20728 20730//20730 -f 20729//20729 20730//20730 20731//20731 -f 20732//20732 20733//20733 20734//20734 -f 20734//20734 20733//20733 20731//20731 -f 20734//20734 20731//20731 20735//20735 -f 20735//20735 20731//20731 20730//20730 -f 20732//20732 20736//20736 20733//20733 -f 20733//20733 20736//20736 20737//20737 -f 20733//20733 20737//20737 20738//20738 -f 20738//20738 20737//20737 20739//20739 -f 20738//20738 20739//20739 20740//20740 -f 20741//20741 20742//20742 20743//20743 -f 20743//20743 20742//20742 20740//20740 -f 20743//20743 20740//20740 20744//20744 -f 20744//20744 20740//20740 20739//20739 -f 20745//20745 20746//20746 20747//20747 -f 20747//20747 20746//20746 20748//20748 -f 20747//20747 20748//20748 20749//20749 -f 20749//20749 20748//20748 20750//20750 -f 20749//20749 20750//20750 20751//20751 -f 20745//20745 20752//20752 20746//20746 -f 20746//20746 20752//20752 20753//20753 -f 20746//20746 20753//20753 20754//20754 -f 20754//20754 20753//20753 20755//20755 -f 20754//20754 20755//20755 20756//20756 -f 20757//20757 20758//20758 20759//20759 -f 20759//20759 20758//20758 20760//20760 -f 20759//20759 20760//20760 20761//20761 -f 20755//20755 20762//20762 20756//20756 -f 20756//20756 20762//20762 20763//20763 -f 20756//20756 20763//20763 20757//20757 -f 20757//20757 20763//20763 20764//20764 -f 20757//20757 20764//20764 20758//20758 -f 20760//20760 20765//20765 20761//20761 -f 20761//20761 20765//20765 20766//20766 -f 20761//20761 20766//20766 20767//20767 -f 20767//20767 20766//20766 20768//20768 -f 20767//20767 20768//20768 20769//20769 -f 20769//20769 20768//20768 20770//20770 -f 20769//20769 20770//20770 20771//20771 -f 20771//20771 20770//20770 20772//20772 -f 20773//20773 20774//20774 20775//20775 -f 20775//20775 20774//20774 20776//20776 -f 20775//20775 20776//20776 20777//20777 -f 20777//20777 20776//20776 20778//20778 -f 20777//20777 20778//20778 20772//20772 -f 20772//20772 20778//20778 20779//20779 -f 20772//20772 20779//20779 20771//20771 -f 20780//20780 20781//20781 20782//20782 -f 20782//20782 20781//20781 20783//20783 -f 20782//20782 20783//20783 20784//20784 -f 20784//20784 20783//20783 20785//20785 -f 20784//20784 20785//20785 20786//20786 -f 20785//20785 20787//20787 20786//20786 -f 20786//20786 20787//20787 20788//20788 -f 20786//20786 20788//20788 20789//20789 -f 20789//20789 20788//20788 20790//20790 -f 20789//20789 20790//20790 20791//20791 -f 20791//20791 20790//20790 20792//20792 -f 20791//20791 20792//20792 20773//20773 -f 20773//20773 20792//20792 20793//20793 -f 20773//20773 20793//20793 20774//20774 -f 20782//20782 20794//20794 20780//20780 -f 20780//20780 20794//20794 20795//20795 -f 20780//20780 20795//20795 20796//20796 -f 20796//20796 20795//20795 20797//20797 -f 20796//20796 20797//20797 20798//20798 -f 20797//20797 20799//20799 20798//20798 -f 20798//20798 20799//20799 20800//20800 -f 20798//20798 20800//20800 20801//20801 -f 20800//20800 20802//20802 20801//20801 -f 20801//20801 20802//20802 20803//20803 -f 20801//20801 20803//20803 20804//20804 -f 20804//20804 20803//20803 20805//20805 -f 20804//20804 20805//20805 20806//20806 -f 20805//20805 20807//20807 20806//20806 -f 20806//20806 20807//20807 20808//20808 -f 20806//20806 20808//20808 20809//20809 -f 20808//20808 20810//20810 20809//20809 -f 20809//20809 20810//20810 20811//20811 -f 20809//20809 20811//20811 20812//20812 -f 20812//20812 20811//20811 20813//20813 -f 20814//20814 20815//20815 20816//20816 -f 20816//20816 20815//20815 20817//20817 -f 20816//20816 20817//20817 20813//20813 -f 20813//20813 20817//20817 20818//20818 -f 20813//20813 20818//20818 20812//20812 -f 20819//20819 20820//20820 20821//20821 -f 20821//20821 20820//20820 20822//20822 -f 20822//20822 20823//20823 20821//20821 -f 20821//20821 20823//20823 20824//20824 -f 20821//20821 20824//20824 20825//20825 -f 20824//20824 20826//20826 20825//20825 -f 20825//20825 20826//20826 20827//20827 -f 20825//20825 20827//20827 20828//20828 -f 20828//20828 20827//20827 20829//20829 -f 20828//20828 20829//20829 20830//20830 -f 20829//20829 20831//20831 20830//20830 -f 20830//20830 20831//20831 20832//20832 -f 20830//20830 20832//20832 20833//20833 -f 20833//20833 20832//20832 20834//20834 -f 20833//20833 20834//20834 20835//20835 -f 20835//20835 20834//20834 20836//20836 -f 20836//20836 20834//20834 20837//20837 -f 20836//20836 20837//20837 20838//20838 -f 20838//20838 20837//20837 20839//20839 -f 20838//20838 20839//20839 20840//20840 -f 20840//20840 20839//20839 20841//20841 -f 20840//20840 20841//20841 20842//20842 -f 20842//20842 20841//20841 20843//20843 -f 20843//20843 20841//20841 20844//20844 -f 20843//20843 20844//20844 20845//20845 -f 20845//20845 20844//20844 20846//20846 -f 20845//20845 20846//20846 20847//20847 -f 20847//20847 20846//20846 20848//20848 -f 20847//20847 20848//20848 20849//20849 -f 20849//20849 20848//20848 20850//20850 -f 20849//20849 20850//20850 20851//20851 -f 20851//20851 20850//20850 20852//20852 -f 20851//20851 20852//20852 20853//20853 -f 20853//20853 20852//20852 20854//20854 -f 20853//20853 20854//20854 20855//20855 -f 20855//20855 20854//20854 20856//20856 -f 20855//20855 20856//20856 20857//20857 -f 20856//20856 20858//20858 20857//20857 -f 20857//20857 20858//20858 20859//20859 -f 20857//20857 20859//20859 20860//20860 -f 20860//20860 20859//20859 20861//20861 -f 20860//20860 20861//20861 20862//20862 -f 20861//20861 20863//20863 20862//20862 -f 20862//20862 20863//20863 20864//20864 -f 20862//20862 20864//20864 20865//20865 -f 20864//20864 20866//20866 20865//20865 -f 20865//20865 20866//20866 20867//20867 -f 20867//20867 20866//20866 20868//20868 -f 20867//20867 20868//20868 20869//20869 -f 20868//20868 20870//20870 20869//20869 -f 20869//20869 20870//20870 20871//20871 -f 20869//20869 20871//20871 20872//20872 -f 20872//20872 20871//20871 20873//20873 -f 20872//20872 20873//20873 20874//20874 -f 20874//20874 20873//20873 20875//20875 -f 20874//20874 20875//20875 20876//20876 -f 20876//20876 20875//20875 20877//20877 -f 20876//20876 20877//20877 20878//20878 -f 20879//20879 20880//20880 20881//20881 -f 20881//20881 20880//20880 20878//20878 -f 20881//20881 20878//20878 20882//20882 -f 20882//20882 20878//20878 20877//20877 -f 20883//20883 20884//20884 20885//20885 -f 20885//20885 20884//20884 20886//20886 -f 20885//20885 20886//20886 20879//20879 -f 20879//20879 20886//20886 20887//20887 -f 20879//20879 20887//20887 20880//20880 -f 19300//19300 19299//19299 20888//20888 -f 20888//20888 19299//19299 20889//20889 -f 20888//20888 20889//20889 20890//20890 -f 20890//20890 20889//20889 20891//20891 -f 20891//20891 20889//20889 20892//20892 -f 20891//20891 20892//20892 20893//20893 -f 20893//20893 20892//20892 20894//20894 -f 20893//20893 20894//20894 20895//20895 -f 20895//20895 20894//20894 20896//20896 -f 20895//20895 20896//20896 20897//20897 -f 20897//20897 20896//20896 20898//20898 -f 20897//20897 20898//20898 20899//20899 -f 20899//20899 20898//20898 20900//20900 -f 20899//20899 20900//20900 20901//20901 -f 20901//20901 20900//20900 20902//20902 -f 20901//20901 20902//20902 20903//20903 -f 20903//20903 20902//20902 20904//20904 -f 20903//20903 20904//20904 20905//20905 -f 20905//20905 20904//20904 20906//20906 -f 20905//20905 20906//20906 20907//20907 -f 20907//20907 20906//20906 20908//20908 -f 20907//20907 20908//20908 20909//20909 -f 20909//20909 20908//20908 20910//20910 -f 20909//20909 20910//20910 20911//20911 -f 20911//20911 20910//20910 20912//20912 -f 20911//20911 20912//20912 20913//20913 -f 20913//20913 20912//20912 20914//20914 -f 20913//20913 20914//20914 20915//20915 -f 20915//20915 20914//20914 20916//20916 -f 20916//20916 20914//20914 20917//20917 -f 20916//20916 20917//20917 20918//20918 -f 20918//20918 20917//20917 20919//20919 -f 20918//20918 20919//20919 20920//20920 -f 20920//20920 20919//20919 20921//20921 -f 20920//20920 20921//20921 20922//20922 -f 20922//20922 20921//20921 20923//20923 -f 20922//20922 20923//20923 20924//20924 -f 20924//20924 20923//20923 20925//20925 -f 20924//20924 20925//20925 20926//20926 -f 20926//20926 20925//20925 20927//20927 -f 20926//20926 20927//20927 20928//20928 -f 20928//20928 20927//20927 20929//20929 -f 20928//20928 20929//20929 20930//20930 -f 20929//20929 20931//20931 20930//20930 -f 20930//20930 20931//20931 20932//20932 -f 20930//20930 20932//20932 20933//20933 -f 20933//20933 20932//20932 20934//20934 -f 20933//20933 20934//20934 20935//20935 -f 20935//20935 20934//20934 20936//20936 -f 20935//20935 20936//20936 20937//20937 -f 20937//20937 20936//20936 20938//20938 -f 20937//20937 20938//20938 20939//20939 -f 20940//20940 20941//20941 20938//20938 -f 20938//20938 20941//20941 20942//20942 -f 20938//20938 20942//20942 20939//20939 -f 20943//20943 19189//19189 19188//19188 -f 19188//19188 20944//20944 20943//20943 -f 20943//20943 20944//20944 20945//20945 -f 20943//20943 20945//20945 20941//20941 -f 20941//20941 20945//20945 20946//20946 -f 20941//20941 20946//20946 20942//20942 -f 20947//20947 19368//19368 19367//19367 -f 19367//19367 20948//20948 20947//20947 -f 20947//20947 20948//20948 20949//20949 -f 20947//20947 20949//20949 20950//20950 -f 20949//20949 20951//20951 20950//20950 -f 20950//20950 20951//20951 20952//20952 -f 20950//20950 20952//20952 20953//20953 -f 20953//20953 20952//20952 20954//20954 -f 20953//20953 20954//20954 20955//20955 -f 20955//20955 20954//20954 20956//20956 -f 20955//20955 20956//20956 20957//20957 -f 20957//20957 20956//20956 20958//20958 -f 20957//20957 20958//20958 20959//20959 -f 20959//20959 20958//20958 20960//20960 -f 20959//20959 20960//20960 20961//20961 -f 20962//20962 20963//20963 20964//20964 -f 20964//20964 20963//20963 20965//20965 -f 20964//20964 20965//20965 20966//20966 -f 20961//20961 20960//20960 20967//20967 -f 20967//20967 20960//20960 20968//20968 -f 20967//20967 20968//20968 20969//20969 -f 20969//20969 20968//20968 20970//20970 -f 20969//20969 20970//20970 20971//20971 -f 20971//20971 20970//20970 20972//20972 -f 20971//20971 20972//20972 20962//20962 -f 20962//20962 20972//20972 20973//20973 -f 20962//20962 20973//20973 20963//20963 -f 20966//20966 20965//20965 20974//20974 -f 20974//20974 20965//20965 20975//20975 -f 20974//20974 20975//20975 20976//20976 -f 20976//20976 20975//20975 20977//20977 -f 20976//20976 20977//20977 20978//20978 -f 20978//20978 20977//20977 20979//20979 -f 20978//20978 20979//20979 20980//20980 -f 20981//20981 20982//20982 20983//20983 -f 20981//20981 20983//20983 20984//20984 -f 20984//20984 20983//20983 20985//20985 -f 20984//20984 20985//20985 20986//20986 -f 20979//20979 20987//20987 20980//20980 -f 20980//20980 20987//20987 20988//20988 -f 20980//20980 20988//20988 20989//20989 -f 20989//20989 20988//20988 20990//20990 -f 20989//20989 20990//20990 20991//20991 -f 20991//20991 20990//20990 20992//20992 -f 20991//20991 20992//20992 20993//20993 -f 20993//20993 20992//20992 20994//20994 -f 20993//20993 20994//20994 20995//20995 -f 20995//20995 20994//20994 20986//20986 -f 20995//20995 20986//20986 20996//20996 -f 20996//20996 20986//20986 20985//20985 -f 20982//20982 20981//20981 20997//20997 -f 20997//20997 20981//20981 20998//20998 -f 20997//20997 20998//20998 20999//20999 -f 20999//20999 20998//20998 21000//21000 -f 21000//21000 20998//20998 21001//21001 -f 21000//21000 21001//21001 21002//21002 -f 21002//21002 21001//21001 21003//21003 -f 21002//21002 21003//21003 21004//21004 -f 21004//21004 21003//21003 21005//21005 -f 21005//21005 21003//21003 21006//21006 -f 21005//21005 21006//21006 21007//21007 -f 21006//21006 21008//21008 21007//21007 -f 21007//21007 21008//21008 21009//21009 -f 21007//21007 21009//21009 21010//21010 -f 21010//21010 21009//21009 21011//21011 -f 21010//21010 21011//21011 21012//21012 -f 21012//21012 21011//21011 21013//21013 -f 21012//21012 21013//21013 21014//21014 -f 21014//21014 21013//21013 21015//21015 -f 19236//19236 19235//19235 21016//21016 -f 21016//21016 19235//19235 21017//21017 -f 21016//21016 21017//21017 21015//21015 -f 21015//21015 21017//21017 21018//21018 -f 21015//21015 21018//21018 21014//21014 -f 19432//19432 19431//19431 21019//21019 -f 21019//21019 19431//19431 21020//21020 -f 21019//21019 21020//21020 21021//21021 -f 21022//21022 21023//21023 21024//21024 -f 21024//21024 21023//21023 21025//21025 -f 21024//21024 21025//21025 21026//21026 -f 21020//21020 21027//21027 21021//21021 -f 21021//21021 21027//21027 21028//21028 -f 21021//21021 21028//21028 21029//21029 -f 21029//21029 21028//21028 21030//21030 -f 21029//21029 21030//21030 21031//21031 -f 21031//21031 21030//21030 21032//21032 -f 21031//21031 21032//21032 21022//21022 -f 21022//21022 21032//21032 21033//21033 -f 21022//21022 21033//21033 21023//21023 -f 21034//21034 21035//21035 21036//21036 -f 21036//21036 21035//21035 21037//21037 -f 21025//21025 21038//21038 21026//21026 -f 21026//21026 21038//21038 21039//21039 -f 21026//21026 21039//21039 21040//21040 -f 21040//21040 21039//21039 21041//21041 -f 21040//21040 21041//21041 21034//21034 -f 21034//21034 21041//21041 21042//21042 -f 21034//21034 21042//21042 21035//21035 -f 21043//21043 21044//21044 21045//21045 -f 21043//21043 21045//21045 21046//21046 -f 21045//21045 21047//21047 21046//21046 -f 21046//21046 21047//21047 21048//21048 -f 21046//21046 21048//21048 21049//21049 -f 21049//21049 21048//21048 21050//21050 -f 21049//21049 21050//21050 21051//21051 -f 21051//21051 21050//21050 21052//21052 -f 21051//21051 21052//21052 21053//21053 -f 21053//21053 21052//21052 21054//21054 -f 21053//21053 21054//21054 21037//21037 -f 21037//21037 21054//21054 21055//21055 -f 21037//21037 21055//21055 21036//21036 -f 21044//21044 21043//21043 21056//21056 -f 21056//21056 21043//21043 21057//21057 -f 21056//21056 21057//21057 21058//21058 -f 21057//21057 21059//21059 21058//21058 -f 21058//21058 21059//21059 21060//21060 -f 21058//21058 21060//21060 21061//21061 -f 21061//21061 21060//21060 21062//21062 -f 21061//21061 21062//21062 21063//21063 -f 21062//21062 21064//21064 21063//21063 -f 21063//21063 21064//21064 21065//21065 -f 21063//21063 21065//21065 21066//21066 -f 21065//21065 21067//21067 21066//21066 -f 21066//21066 21067//21067 21068//21068 -f 21066//21066 21068//21068 21069//21069 -f 21069//21069 21068//21068 21070//21070 -f 21069//21069 21070//21070 21071//21071 -f 21070//21070 21072//21072 21071//21071 -f 21071//21071 21072//21072 21073//21073 -f 21071//21071 21073//21073 21074//21074 -f 21074//21074 21073//21073 21075//21075 -f 21074//21074 21075//21075 21076//21076 -f 21076//21076 21075//21075 21077//21077 -f 21076//21076 21077//21077 21078//21078 -f 21078//21078 21077//21077 21079//21079 -f 21078//21078 21079//21079 21080//21080 -f 21080//21080 21079//21079 21081//21081 -f 21080//21080 21081//21081 21082//21082 -f 21082//21082 21081//21081 21083//21083 -f 21082//21082 21083//21083 21084//21084 -f 21084//21084 21083//21083 21085//21085 -f 21084//21084 21085//21085 21086//21086 -f 21086//21086 21085//21085 21087//21087 -f 21086//21086 21087//21087 19304//19304 -f 19304//19304 21087//21087 19305//19305 -f 21088//21088 19504//19504 19505//19505 -f 19505//19505 21089//21089 21088//21088 -f 21088//21088 21089//21089 21090//21090 -f 21088//21088 21090//21090 21091//21091 -f 21091//21091 21090//21090 21092//21092 -f 21091//21091 21092//21092 21093//21093 -f 21093//21093 21092//21092 21094//21094 -f 21093//21093 21094//21094 21095//21095 -f 21095//21095 21094//21094 21096//21096 -f 21097//21097 21098//21098 21099//21099 -f 21099//21099 21098//21098 21100//21100 -f 21099//21099 21100//21100 21101//21101 -f 21101//21101 21100//21100 21102//21102 -f 21100//21100 21103//21103 21102//21102 -f 21102//21102 21103//21103 21104//21104 -f 21102//21102 21104//21104 21096//21096 -f 21096//21096 21104//21104 21095//21095 -f 21097//21097 21099//21099 21105//21105 -f 21105//21105 21099//21099 21106//21106 -f 21105//21105 21106//21106 21107//21107 -f 21108//21108 21109//21109 21110//21110 -f 21108//21108 21110//21110 21111//21111 -f 21106//21106 21112//21112 21107//21107 -f 21107//21107 21112//21112 21113//21113 -f 21107//21107 21113//21113 21114//21114 -f 21114//21114 21113//21113 21115//21115 -f 21114//21114 21115//21115 21116//21116 -f 21116//21116 21115//21115 21117//21117 -f 21116//21116 21117//21117 21118//21118 -f 21118//21118 21117//21117 21119//21119 -f 21118//21118 21119//21119 21120//21120 -f 21120//21120 21119//21119 21121//21121 -f 21120//21120 21121//21121 21109//21109 -f 21109//21109 21121//21121 21122//21122 -f 21109//21109 21122//21122 21110//21110 -f 21123//21123 21124//21124 21125//21125 -f 21110//21110 21126//21126 21111//21111 -f 21111//21111 21126//21126 21127//21127 -f 21111//21111 21127//21127 21128//21128 -f 21128//21128 21127//21127 21129//21129 -f 21128//21128 21129//21129 21130//21130 -f 21130//21130 21129//21129 21123//21123 -f 21130//21130 21123//21123 21131//21131 -f 21131//21131 21123//21123 21125//21125 -f 21132//21132 21133//21133 21134//21134 -f 21134//21134 21133//21133 21135//21135 -f 21134//21134 21135//21135 21136//21136 -f 21136//21136 21135//21135 21137//21137 -f 21136//21136 21137//21137 21138//21138 -f 21138//21138 21137//21137 21139//21139 -f 21138//21138 21139//21139 21140//21140 -f 21140//21140 21139//21139 21141//21141 -f 21140//21140 21141//21141 21124//21124 -f 21124//21124 21141//21141 21142//21142 -f 21124//21124 21142//21142 21125//21125 -f 21143//21143 21144//21144 21145//21145 -f 21145//21145 21144//21144 21146//21146 -f 21145//21145 21146//21146 21147//21147 -f 21147//21147 21146//21146 21148//21148 -f 21147//21147 21148//21148 21149//21149 -f 21149//21149 21148//21148 21150//21150 -f 21149//21149 21150//21150 21132//21132 -f 21132//21132 21150//21150 21151//21151 -f 21132//21132 21151//21151 21133//21133 -f 19372//19372 19371//19371 21152//21152 -f 21152//21152 19371//19371 21153//21153 -f 21152//21152 21153//21153 21143//21143 -f 21143//21143 21153//21153 21154//21154 -f 21143//21143 21154//21154 21144//21144 -f 21155//21155 21156//21156 21157//21157 -f 19574//19574 19573//19573 21158//21158 -f 21158//21158 19573//19573 21159//21159 -f 21158//21158 21159//21159 21160//21160 -f 21160//21160 21159//21159 21161//21161 -f 21160//21160 21161//21161 21162//21162 -f 21162//21162 21161//21161 21163//21163 -f 21162//21162 21163//21163 21164//21164 -f 21163//21163 21165//21165 21164//21164 -f 21164//21164 21165//21165 21166//21166 -f 21164//21164 21166//21166 21167//21167 -f 21167//21167 21166//21166 21168//21168 -f 21167//21167 21168//21168 21169//21169 -f 21169//21169 21168//21168 21170//21170 -f 21169//21169 21170//21170 21171//21171 -f 21171//21171 21170//21170 21172//21172 -f 21171//21171 21172//21172 21173//21173 -f 21173//21173 21172//21172 21174//21174 -f 21173//21173 21174//21174 21175//21175 -f 21174//21174 21176//21176 21175//21175 -f 21175//21175 21176//21176 21177//21177 -f 21175//21175 21177//21177 21178//21178 -f 21178//21178 21177//21177 21179//21179 -f 21178//21178 21179//21179 21180//21180 -f 21180//21180 21179//21179 21181//21181 -f 21180//21180 21181//21181 21182//21182 -f 21182//21182 21181//21181 21183//21183 -f 21182//21182 21183//21183 21184//21184 -f 21184//21184 21183//21183 21185//21185 -f 21184//21184 21185//21185 21186//21186 -f 21186//21186 21185//21185 21187//21187 -f 21186//21186 21187//21187 21188//21188 -f 21188//21188 21187//21187 21189//21189 -f 21188//21188 21189//21189 21190//21190 -f 21190//21190 21189//21189 21191//21191 -f 21190//21190 21191//21191 21192//21192 -f 21192//21192 21191//21191 21193//21193 -f 21192//21192 21193//21193 21194//21194 -f 21194//21194 21193//21193 21195//21195 -f 21194//21194 21195//21195 21196//21196 -f 21196//21196 21195//21195 21197//21197 -f 21196//21196 21197//21197 21198//21198 -f 21198//21198 21197//21197 21199//21199 -f 21198//21198 21199//21199 21200//21200 -f 21200//21200 21199//21199 21201//21201 -f 21200//21200 21201//21201 21202//21202 -f 21202//21202 21201//21201 21203//21203 -f 21202//21202 21203//21203 21204//21204 -f 21204//21204 21203//21203 21205//21205 -f 21204//21204 21205//21205 21206//21206 -f 21206//21206 21205//21205 21207//21207 -f 21206//21206 21207//21207 21156//21156 -f 21156//21156 21207//21207 21208//21208 -f 21156//21156 21208//21208 21157//21157 -f 21155//21155 21157//21157 21209//21209 -f 21209//21209 21157//21157 21210//21210 -f 21209//21209 21210//21210 21211//21211 -f 19483//19483 19482//19482 21212//21212 -f 21212//21212 19482//19482 21211//21211 -f 21212//21212 21211//21211 21213//21213 -f 21213//21213 21211//21211 21210//21210 -f 19645//19645 19647//19647 21214//21214 -f 21214//21214 19647//19647 21215//21215 -f 21214//21214 21215//21215 21216//21216 -f 21216//21216 21215//21215 21217//21217 -f 21217//21217 21215//21215 21218//21218 -f 21217//21217 21218//21218 21219//21219 -f 21218//21218 21220//21220 21219//21219 -f 21219//21219 21220//21220 21221//21221 -f 21219//21219 21221//21221 21222//21222 -f 21222//21222 21221//21221 21223//21223 -f 21221//21221 21224//21224 21223//21223 -f 21223//21223 21224//21224 21225//21225 -f 21223//21223 21225//21225 21226//21226 -f 21226//21226 21225//21225 21227//21227 -f 21226//21226 21227//21227 21228//21228 -f 21228//21228 21227//21227 21229//21229 -f 21228//21228 21229//21229 21230//21230 -f 21230//21230 21229//21229 21231//21231 -f 21230//21230 21231//21231 21232//21232 -f 21232//21232 21231//21231 21233//21233 -f 21232//21232 21233//21233 21234//21234 -f 21234//21234 21233//21233 21235//21235 -f 21234//21234 21235//21235 21236//21236 -f 21236//21236 21235//21235 21237//21237 -f 21236//21236 21237//21237 21238//21238 -f 21238//21238 21237//21237 21239//21239 -f 21238//21238 21239//21239 21240//21240 -f 21240//21240 21239//21239 21241//21241 -f 21240//21240 21241//21241 21242//21242 -f 21242//21242 21241//21241 21243//21243 -f 21242//21242 21243//21243 21244//21244 -f 21244//21244 21243//21243 21245//21245 -f 21244//21244 21245//21245 21246//21246 -f 21246//21246 21245//21245 21247//21247 -f 21246//21246 21247//21247 21248//21248 -f 21248//21248 21247//21247 21249//21249 -f 21248//21248 21249//21249 21250//21250 -f 21250//21250 21249//21249 21251//21251 -f 21250//21250 21251//21251 21252//21252 -f 21252//21252 21251//21251 21253//21253 -f 21252//21252 21253//21253 21254//21254 -f 21254//21254 21253//21253 21255//21255 -f 21254//21254 21255//21255 21256//21256 -f 21256//21256 21255//21255 21257//21257 -f 21256//21256 21257//21257 21258//21258 -f 21258//21258 21257//21257 21259//21259 -f 21258//21258 21259//21259 21260//21260 -f 21260//21260 21259//21259 21261//21261 -f 21260//21260 21261//21261 21262//21262 -f 21262//21262 21261//21261 21263//21263 -f 21262//21262 21263//21263 21264//21264 -f 21263//21263 21265//21265 21264//21264 -f 21264//21264 21265//21265 21266//21266 -f 21264//21264 21266//21266 21267//21267 -f 21267//21267 21266//21266 21268//21268 -f 21266//21266 21269//21269 21268//21268 -f 21268//21268 21269//21269 21270//21270 -f 21268//21268 21270//21270 21271//21271 -f 21271//21271 21270//21270 21272//21272 -f 21271//21271 21272//21272 19513//19513 -f 19513//19513 21272//21272 19511//19511 -f 19708//19708 19707//19707 21273//21273 -f 21273//21273 19707//19707 21274//21274 -f 21274//21274 21275//21275 21273//21273 -f 21273//21273 21275//21275 21276//21276 -f 21273//21273 21276//21276 21277//21277 -f 21277//21277 21276//21276 21278//21278 -f 21277//21277 21278//21278 21279//21279 -f 21278//21278 21280//21280 21279//21279 -f 21279//21279 21280//21280 21281//21281 -f 21279//21279 21281//21281 21282//21282 -f 21279//21279 21282//21282 21283//21283 -f 21283//21283 21282//21282 21284//21284 -f 21283//21283 21284//21284 21285//21285 -f 21285//21285 21284//21284 21286//21286 -f 21285//21285 21286//21286 21287//21287 -f 21287//21287 21286//21286 21288//21288 -f 21287//21287 21288//21288 21289//21289 -f 21289//21289 21288//21288 21290//21290 -f 21289//21289 21290//21290 21291//21291 -f 21291//21291 21290//21290 21292//21292 -f 21292//21292 21290//21290 21293//21293 -f 21292//21292 21293//21293 21294//21294 -f 21294//21294 21293//21293 21295//21295 -f 21294//21294 21295//21295 21296//21296 -f 21296//21296 21295//21295 21297//21297 -f 21296//21296 21297//21297 21298//21298 -f 21299//21299 21300//21300 21301//21301 -f 21301//21301 21300//21300 21302//21302 -f 21297//21297 21303//21303 21298//21298 -f 21298//21298 21303//21303 21304//21304 -f 21298//21298 21304//21304 21305//21305 -f 21305//21305 21304//21304 21306//21306 -f 21305//21305 21306//21306 21307//21307 -f 21307//21307 21306//21306 21308//21308 -f 21307//21307 21308//21308 21309//21309 -f 21309//21309 21308//21308 21310//21310 -f 21309//21309 21310//21310 21311//21311 -f 21311//21311 21310//21310 21312//21312 -f 21311//21311 21312//21312 21313//21313 -f 21313//21313 21312//21312 21314//21314 -f 21313//21313 21314//21314 21315//21315 -f 21315//21315 21314//21314 21316//21316 -f 21315//21315 21316//21316 21317//21317 -f 21317//21317 21316//21316 21318//21318 -f 21317//21317 21318//21318 21319//21319 -f 21319//21319 21318//21318 21320//21320 -f 21319//21319 21320//21320 21321//21321 -f 21321//21321 21320//21320 21322//21322 -f 21321//21321 21322//21322 21323//21323 -f 21323//21323 21322//21322 21324//21324 -f 21323//21323 21324//21324 21325//21325 -f 21325//21325 21324//21324 21326//21326 -f 21325//21325 21326//21326 21327//21327 -f 21327//21327 21326//21326 21328//21328 -f 21327//21327 21328//21328 21329//21329 -f 21329//21329 21328//21328 21330//21330 -f 21329//21329 21330//21330 21331//21331 -f 21331//21331 21330//21330 21332//21332 -f 21331//21331 21332//21332 21333//21333 -f 21333//21333 21332//21332 21334//21334 -f 21333//21333 21334//21334 21299//21299 -f 21299//21299 21334//21334 21335//21335 -f 21299//21299 21335//21335 21300//21300 -f 19587//19587 19586//19586 21336//21336 -f 21336//21336 19586//19586 21337//21337 -f 21336//21336 21337//21337 21302//21302 -f 21302//21302 21337//21337 21338//21338 -f 21302//21302 21338//21338 21301//21301 -f 21339//21339 21340//21340 21341//21341 -f 21341//21341 21340//21340 21342//21342 -f 21343//21343 19785//19785 19786//19786 -f 19786//19786 21344//21344 21343//21343 -f 21343//21343 21344//21344 21345//21345 -f 21343//21343 21345//21345 21346//21346 -f 21346//21346 21345//21345 21347//21347 -f 21346//21346 21347//21347 21348//21348 -f 21348//21348 21347//21347 21349//21349 -f 21348//21348 21349//21349 21350//21350 -f 21350//21350 21349//21349 21351//21351 -f 21350//21350 21351//21351 21352//21352 -f 21352//21352 21351//21351 21353//21353 -f 21354//21354 21355//21355 21356//21356 -f 21356//21356 21355//21355 21357//21357 -f 21356//21356 21357//21357 21358//21358 -f 21358//21358 21357//21357 21359//21359 -f 21358//21358 21359//21359 21360//21360 -f 21359//21359 21361//21361 21360//21360 -f 21360//21360 21361//21361 21362//21362 -f 21360//21360 21362//21362 21363//21363 -f 21363//21363 21362//21362 21364//21364 -f 21363//21363 21364//21364 21365//21365 -f 21365//21365 21364//21364 21366//21366 -f 21365//21365 21366//21366 21367//21367 -f 21367//21367 21366//21366 21368//21368 -f 21367//21367 21368//21368 21353//21353 -f 21353//21353 21368//21368 21352//21352 -f 21369//21369 21370//21370 21371//21371 -f 21356//21356 21372//21372 21354//21354 -f 21354//21354 21372//21372 21373//21373 -f 21354//21354 21373//21373 21374//21374 -f 21374//21374 21373//21373 21375//21375 -f 21374//21374 21375//21375 21376//21376 -f 21376//21376 21375//21375 21377//21377 -f 21376//21376 21377//21377 21378//21378 -f 21378//21378 21377//21377 21379//21379 -f 21378//21378 21379//21379 21380//21380 -f 21380//21380 21379//21379 21381//21381 -f 21380//21380 21381//21381 21371//21371 -f 21371//21371 21381//21381 21382//21382 -f 21371//21371 21382//21382 21369//21369 -f 21342//21342 21340//21340 21383//21383 -f 21383//21383 21340//21340 21384//21384 -f 21383//21383 21384//21384 21385//21385 -f 21385//21385 21384//21384 21386//21386 -f 21385//21385 21386//21386 21387//21387 -f 21387//21387 21386//21386 21388//21388 -f 21387//21387 21388//21388 21389//21389 -f 21389//21389 21388//21388 21390//21390 -f 21389//21389 21390//21390 21391//21391 -f 21391//21391 21390//21390 21392//21392 -f 21391//21391 21392//21392 21370//21370 -f 21370//21370 21392//21392 21393//21393 -f 21370//21370 21393//21393 21371//21371 -f 21339//21339 21341//21341 21394//21394 -f 21394//21394 21341//21341 21395//21395 -f 21394//21394 21395//21395 21396//21396 -f 21395//21395 21397//21397 21396//21396 -f 21396//21396 21397//21397 21398//21398 -f 21396//21396 21398//21398 21399//21399 -f 21399//21399 21398//21398 21400//21400 -f 21399//21399 21400//21400 21401//21401 -f 21401//21401 21400//21400 21402//21402 -f 21400//21400 21403//21403 21402//21402 -f 21402//21402 21403//21403 21404//21404 -f 21402//21402 21404//21404 21405//21405 -f 21405//21405 21404//21404 21406//21406 -f 21405//21405 21406//21406 19648//19648 -f 19648//19648 21406//21406 19649//19649 -f 19860//19860 19859//19859 21407//21407 -f 21407//21407 19859//19859 21408//21408 -f 21407//21407 21408//21408 21409//21409 -f 21409//21409 21408//21408 21410//21410 -f 21410//21410 21408//21408 21411//21411 -f 21410//21410 21411//21411 21412//21412 -f 21411//21411 21413//21413 21412//21412 -f 21412//21412 21413//21413 21414//21414 -f 21412//21412 21414//21414 21415//21415 -f 21415//21415 21414//21414 21416//21416 -f 21415//21415 21416//21416 21417//21417 -f 21417//21417 21416//21416 21418//21418 -f 21417//21417 21418//21418 21419//21419 -f 21419//21419 21418//21418 21420//21420 -f 21419//21419 21420//21420 21421//21421 -f 21421//21421 21420//21420 21422//21422 -f 21421//21421 21422//21422 21423//21423 -f 21423//21423 21422//21422 21424//21424 -f 21423//21423 21424//21424 21425//21425 -f 21425//21425 21424//21424 21426//21426 -f 21426//21426 21424//21424 21427//21427 -f 21426//21426 21427//21427 21428//21428 -f 21428//21428 21427//21427 21429//21429 -f 21428//21428 21429//21429 21430//21430 -f 21430//21430 21429//21429 21431//21431 -f 21430//21430 21431//21431 21432//21432 -f 21432//21432 21431//21431 21433//21433 -f 21432//21432 21433//21433 21434//21434 -f 21434//21434 21433//21433 21435//21435 -f 21434//21434 21435//21435 21436//21436 -f 21435//21435 21437//21437 21436//21436 -f 21436//21436 21437//21437 21438//21438 -f 21436//21436 21438//21438 21439//21439 -f 21439//21439 21438//21438 21440//21440 -f 21439//21439 21440//21440 21441//21441 -f 21440//21440 21442//21442 21441//21441 -f 21441//21441 21442//21442 21443//21443 -f 21441//21441 21443//21443 21444//21444 -f 21445//21445 21446//21446 21447//21447 -f 21443//21443 21448//21448 21444//21444 -f 21444//21444 21448//21448 21449//21449 -f 21444//21444 21449//21449 21450//21450 -f 21450//21450 21449//21449 21451//21451 -f 21450//21450 21451//21451 21452//21452 -f 21452//21452 21451//21451 21453//21453 -f 21452//21452 21453//21453 21454//21454 -f 21454//21454 21453//21453 21455//21455 -f 21454//21454 21455//21455 21446//21446 -f 21446//21446 21455//21455 21456//21456 -f 21446//21446 21456//21456 21447//21447 -f 21447//21447 21457//21457 21445//21445 -f 21445//21445 21457//21457 21458//21458 -f 21445//21445 21458//21458 21459//21459 -f 21459//21459 21458//21458 21460//21460 -f 21458//21458 21461//21461 21460//21460 -f 21460//21460 21461//21461 21462//21462 -f 21460//21460 21462//21462 21463//21463 -f 21463//21463 21462//21462 21464//21464 -f 21463//21463 21464//21464 21465//21465 -f 21465//21465 21464//21464 21466//21466 -f 21465//21465 21466//21466 21467//21467 -f 21467//21467 21466//21466 21468//21468 -f 21467//21467 21468//21468 21469//21469 -f 21469//21469 21468//21468 21470//21470 -f 21469//21469 21470//21470 21471//21471 -f 21471//21471 21470//21470 21472//21472 -f 21471//21471 21472//21472 19715//19715 -f 19715//19715 21472//21472 19716//19716 -f 19930//19930 19931//19931 21473//21473 -f 21473//21473 19931//19931 21474//21474 -f 21473//21473 21474//21474 21475//21475 -f 21475//21475 21474//21474 21476//21476 -f 21475//21475 21476//21476 21477//21477 -f 21477//21477 21476//21476 21478//21478 -f 21477//21477 21478//21478 21479//21479 -f 21480//21480 21481//21481 21482//21482 -f 21482//21482 21481//21481 21483//21483 -f 21482//21482 21483//21483 21484//21484 -f 21484//21484 21483//21483 21485//21485 -f 21484//21484 21485//21485 21479//21479 -f 21479//21479 21485//21485 21486//21486 -f 21479//21479 21486//21486 21477//21477 -f 21487//21487 21488//21488 21480//21480 -f 21480//21480 21488//21488 21489//21489 -f 21480//21480 21489//21489 21481//21481 -f 21490//21490 21491//21491 21492//21492 -f 21492//21492 21491//21491 21493//21493 -f 21492//21492 21493//21493 21494//21494 -f 21494//21494 21493//21493 21495//21495 -f 21494//21494 21495//21495 21496//21496 -f 21496//21496 21495//21495 21497//21497 -f 21496//21496 21497//21497 21498//21498 -f 21498//21498 21497//21497 21499//21499 -f 21498//21498 21499//21499 21500//21500 -f 21500//21500 21499//21499 21501//21501 -f 21500//21500 21501//21501 21502//21502 -f 21502//21502 21501//21501 21503//21503 -f 21502//21502 21503//21503 21504//21504 -f 21504//21504 21503//21503 21505//21505 -f 21504//21504 21505//21505 21506//21506 -f 21506//21506 21505//21505 21507//21507 -f 21506//21506 21507//21507 21508//21508 -f 21508//21508 21507//21507 21509//21509 -f 21508//21508 21509//21509 21510//21510 -f 21510//21510 21509//21509 21511//21511 -f 21510//21510 21511//21511 21487//21487 -f 21487//21487 21511//21511 21512//21512 -f 21487//21487 21512//21512 21488//21488 -f 21492//21492 21513//21513 21490//21490 -f 21490//21490 21513//21513 21514//21514 -f 21490//21490 21514//21514 21515//21515 -f 21515//21515 21514//21514 21516//21516 -f 21515//21515 21516//21516 21517//21517 -f 21517//21517 21516//21516 21518//21518 -f 21517//21517 21518//21518 21519//21519 -f 21519//21519 21518//21518 21520//21520 -f 21519//21519 21520//21520 21521//21521 -f 21521//21521 21520//21520 21522//21522 -f 21521//21521 21522//21522 21523//21523 -f 21523//21523 21522//21522 21524//21524 -f 21523//21523 21524//21524 21525//21525 -f 21525//21525 21524//21524 21526//21526 -f 21526//21526 21524//21524 21527//21527 -f 21526//21526 21527//21527 21528//21528 -f 21528//21528 21527//21527 21529//21529 -f 21528//21528 21529//21529 21530//21530 -f 21530//21530 21529//21529 21531//21531 -f 21531//21531 21529//21529 21532//21532 -f 21531//21531 21532//21532 21533//21533 -f 21534//21534 19788//19788 19787//19787 -f 19787//19787 21535//21535 21534//21534 -f 21534//21534 21535//21535 21536//21536 -f 21534//21534 21536//21536 21537//21537 -f 21537//21537 21536//21536 21538//21538 -f 21537//21537 21538//21538 21533//21533 -f 21533//21533 21538//21538 21539//21539 -f 21533//21533 21539//21539 21531//21531 -f 21540//21540 21541//21541 21542//21542 -f 21543//21543 19995//19995 19994//19994 -f 21543//21543 19994//19994 21544//21544 -f 21544//21544 19994//19994 21545//21545 -f 21544//21544 21545//21545 21546//21546 -f 21545//21545 21547//21547 21546//21546 -f 21546//21546 21547//21547 21548//21548 -f 21546//21546 21548//21548 21549//21549 -f 21549//21549 21548//21548 21550//21550 -f 21549//21549 21550//21550 21551//21551 -f 21551//21551 21550//21550 21552//21552 -f 21551//21551 21552//21552 21553//21553 -f 21553//21553 21552//21552 21554//21554 -f 21553//21553 21554//21554 21555//21555 -f 21555//21555 21554//21554 21556//21556 -f 21555//21555 21556//21556 21541//21541 -f 21541//21541 21556//21556 21557//21557 -f 21541//21541 21557//21557 21542//21542 -f 21540//21540 21542//21542 21558//21558 -f 21558//21558 21542//21542 21559//21559 -f 21558//21558 21559//21559 21560//21560 -f 21560//21560 21559//21559 21561//21561 -f 21560//21560 21561//21561 21562//21562 -f 21561//21561 21563//21563 21562//21562 -f 21562//21562 21563//21563 21564//21564 -f 21562//21562 21564//21564 21565//21565 -f 21565//21565 21564//21564 21566//21566 -f 21565//21565 21566//21566 21567//21567 -f 21566//21566 21568//21568 21567//21567 -f 21567//21567 21568//21568 21569//21569 -f 21567//21567 21569//21569 21570//21570 -f 21570//21570 21569//21569 21571//21571 -f 21570//21570 21571//21571 21572//21572 -f 21572//21572 21571//21571 21573//21573 -f 21572//21572 21573//21573 21574//21574 -f 21574//21574 21573//21573 21575//21575 -f 21574//21574 21575//21575 21576//21576 -f 21576//21576 21575//21575 21577//21577 -f 21577//21577 21575//21575 21578//21578 -f 21577//21577 21578//21578 21579//21579 -f 21579//21579 21578//21578 21580//21580 -f 21579//21579 21580//21580 21581//21581 -f 21581//21581 21580//21580 21582//21582 -f 21581//21581 21582//21582 21583//21583 -f 21583//21583 21582//21582 21584//21584 -f 21583//21583 21584//21584 21585//21585 -f 21585//21585 21584//21584 21586//21586 -f 21586//21586 21584//21584 21587//21587 -f 21586//21586 21587//21587 21588//21588 -f 21588//21588 21587//21587 21589//21589 -f 21588//21588 21589//21589 21590//21590 -f 21590//21590 21589//21589 21591//21591 -f 21590//21590 21591//21591 21592//21592 -f 21592//21592 21591//21591 21593//21593 -f 21593//21593 21591//21591 21594//21594 -f 21593//21593 21594//21594 21595//21595 -f 19865//19865 19864//19864 21596//21596 -f 21596//21596 19864//19864 21597//21597 -f 21596//21596 21597//21597 21598//21598 -f 21598//21598 21597//21597 21599//21599 -f 21598//21598 21599//21599 21600//21600 -f 21600//21600 21599//21599 21601//21601 -f 21600//21600 21601//21601 21602//21602 -f 21602//21602 21601//21601 21603//21603 -f 21602//21602 21603//21603 21604//21604 -f 21604//21604 21603//21603 21605//21605 -f 21604//21604 21605//21605 21606//21606 -f 21606//21606 21605//21605 21607//21607 -f 21606//21606 21607//21607 21608//21608 -f 21608//21608 21607//21607 21595//21595 -f 21608//21608 21595//21595 21609//21609 -f 21609//21609 21595//21595 21594//21594 -f 20060//20060 20059//20059 21610//21610 -f 21610//21610 20059//20059 21611//21611 -f 21610//21610 21611//21611 21612//21612 -f 21612//21612 21611//21611 21613//21613 -f 21612//21612 21613//21613 21614//21614 -f 21614//21614 21613//21613 21615//21615 -f 21614//21614 21615//21615 21616//21616 -f 21616//21616 21615//21615 21617//21617 -f 21616//21616 21617//21617 21618//21618 -f 21618//21618 21617//21617 21619//21619 -f 21618//21618 21619//21619 21620//21620 -f 21620//21620 21619//21619 21621//21621 -f 21620//21620 21621//21621 21622//21622 -f 21622//21622 21621//21621 21623//21623 -f 21622//21622 21623//21623 21624//21624 -f 21624//21624 21623//21623 21625//21625 -f 21624//21624 21625//21625 21626//21626 -f 21626//21626 21625//21625 21627//21627 -f 21626//21626 21627//21627 21628//21628 -f 21628//21628 21627//21627 21629//21629 -f 21628//21628 21629//21629 21630//21630 -f 21630//21630 21629//21629 21631//21631 -f 21630//21630 21631//21631 21632//21632 -f 21632//21632 21631//21631 21633//21633 -f 21633//21633 21631//21631 21634//21634 -f 21633//21633 21634//21634 21635//21635 -f 21634//21634 21636//21636 21635//21635 -f 21635//21635 21636//21636 21637//21637 -f 21635//21635 21637//21637 21638//21638 -f 21638//21638 21637//21637 21639//21639 -f 21638//21638 21639//21639 21640//21640 -f 21640//21640 21639//21639 21641//21641 -f 21640//21640 21641//21641 21642//21642 -f 21642//21642 21641//21641 21643//21643 -f 21642//21642 21643//21643 21644//21644 -f 21643//21643 21645//21645 21644//21644 -f 21644//21644 21645//21645 21646//21646 -f 21644//21644 21646//21646 21647//21647 -f 21647//21647 21646//21646 21648//21648 -f 21647//21647 21648//21648 21649//21649 -f 21649//21649 21648//21648 21650//21650 -f 21649//21649 21650//21650 21651//21651 -f 21651//21651 21650//21650 21652//21652 -f 21651//21651 21652//21652 21653//21653 -f 21653//21653 21652//21652 21654//21654 -f 21653//21653 21654//21654 21655//21655 -f 21655//21655 21654//21654 21656//21656 -f 21655//21655 21656//21656 21657//21657 -f 21657//21657 21656//21656 21658//21658 -f 21657//21657 21658//21658 21659//21659 -f 21658//21658 21660//21660 21659//21659 -f 21659//21659 21660//21660 21661//21661 -f 21659//21659 21661//21661 21662//21662 -f 21662//21662 21661//21661 21663//21663 -f 21662//21662 21663//21663 21664//21664 -f 21664//21664 21663//21663 21665//21665 -f 21664//21664 21665//21665 21666//21666 -f 21666//21666 21665//21665 21667//21667 -f 21666//21666 21667//21667 21668//21668 -f 21668//21668 21667//21667 21669//21669 -f 21668//21668 21669//21669 21670//21670 -f 21670//21670 21669//21669 21671//21671 -f 21670//21670 21671//21671 21672//21672 -f 21672//21672 21671//21671 21673//21673 -f 21672//21672 21673//21673 19972//19972 -f 19972//19972 21673//21673 21674//21674 -f 19972//19972 21674//21674 19973//19973 -f 21675//21675 21676//21676 21677//21677 -f 20124//20124 20123//20123 21678//21678 -f 21678//21678 20123//20123 21679//21679 -f 21678//21678 21679//21679 21680//21680 -f 21680//21680 21679//21679 21681//21681 -f 21680//21680 21681//21681 21677//21677 -f 21677//21677 21681//21681 21682//21682 -f 21677//21677 21682//21682 21675//21675 -f 21676//21676 21675//21675 21683//21683 -f 21683//21683 21675//21675 21684//21684 -f 21683//21683 21684//21684 21685//21685 -f 21685//21685 21684//21684 21686//21686 -f 21685//21685 21686//21686 21687//21687 -f 21687//21687 21686//21686 21688//21688 -f 21687//21687 21688//21688 21689//21689 -f 21689//21689 21688//21688 21690//21690 -f 21689//21689 21690//21690 21691//21691 -f 21691//21691 21690//21690 21692//21692 -f 21691//21691 21692//21692 21693//21693 -f 21693//21693 21692//21692 21694//21694 -f 21693//21693 21694//21694 21695//21695 -f 21695//21695 21694//21694 21696//21696 -f 21695//21695 21696//21696 21697//21697 -f 21697//21697 21696//21696 21698//21698 -f 21697//21697 21698//21698 21699//21699 -f 21699//21699 21698//21698 21700//21700 -f 21699//21699 21700//21700 21701//21701 -f 21701//21701 21700//21700 21702//21702 -f 21701//21701 21702//21702 21703//21703 -f 21703//21703 21702//21702 21704//21704 -f 21703//21703 21704//21704 21705//21705 -f 21705//21705 21704//21704 21706//21706 -f 21705//21705 21706//21706 21707//21707 -f 21707//21707 21706//21706 21708//21708 -f 21707//21707 21708//21708 21709//21709 -f 21708//21708 21710//21710 21709//21709 -f 21709//21709 21710//21710 21711//21711 -f 21709//21709 21711//21711 21712//21712 -f 21712//21712 21711//21711 21713//21713 -f 21712//21712 21713//21713 21714//21714 -f 21714//21714 21713//21713 21715//21715 -f 21714//21714 21715//21715 21716//21716 -f 21717//21717 21718//21718 21719//21719 -f 21715//21715 21720//21720 21716//21716 -f 21716//21716 21720//21720 21721//21721 -f 21716//21716 21721//21721 21722//21722 -f 21722//21722 21721//21721 21723//21723 -f 21722//21722 21723//21723 21724//21724 -f 21724//21724 21723//21723 21725//21725 -f 21724//21724 21725//21725 21726//21726 -f 21726//21726 21725//21725 21727//21727 -f 21726//21726 21727//21727 21728//21728 -f 21728//21728 21727//21727 21729//21729 -f 21728//21728 21729//21729 21730//21730 -f 21730//21730 21729//21729 21717//21717 -f 21730//21730 21717//21717 21731//21731 -f 21731//21731 21717//21717 21719//21719 -f 20002//20002 20001//20001 21732//21732 -f 21732//21732 20001//20001 21733//21733 -f 21732//21732 21733//21733 21718//21718 -f 21718//21718 21733//21733 21734//21734 -f 21718//21718 21734//21734 21719//21719 -f 21735//21735 20195//20195 20194//20194 -f 20194//20194 21736//21736 21735//21735 -f 21735//21735 21736//21736 21737//21737 -f 21735//21735 21737//21737 21738//21738 -f 21738//21738 21737//21737 21739//21739 -f 21738//21738 21739//21739 21740//21740 -f 21740//21740 21739//21739 21741//21741 -f 21740//21740 21741//21741 21742//21742 -f 21743//21743 21744//21744 21745//21745 -f 21745//21745 21744//21744 21746//21746 -f 21745//21745 21746//21746 21747//21747 -f 21747//21747 21746//21746 21748//21748 -f 21747//21747 21748//21748 21749//21749 -f 21749//21749 21748//21748 21750//21750 -f 21749//21749 21750//21750 21751//21751 -f 21751//21751 21750//21750 21752//21752 -f 21751//21751 21752//21752 21753//21753 -f 21753//21753 21752//21752 21754//21754 -f 21753//21753 21754//21754 21755//21755 -f 21755//21755 21754//21754 21756//21756 -f 21755//21755 21756//21756 21742//21742 -f 21742//21742 21756//21756 21757//21757 -f 21742//21742 21757//21757 21740//21740 -f 21743//21743 21745//21745 21758//21758 -f 21758//21758 21745//21745 21759//21759 -f 21758//21758 21759//21759 21760//21760 -f 21760//21760 21759//21759 21761//21761 -f 21760//21760 21761//21761 21762//21762 -f 21762//21762 21761//21761 21763//21763 -f 21762//21762 21763//21763 21764//21764 -f 21764//21764 21763//21763 21765//21765 -f 21764//21764 21765//21765 21766//21766 -f 21766//21766 21765//21765 21767//21767 -f 21766//21766 21767//21767 21768//21768 -f 21768//21768 21767//21767 21769//21769 -f 21768//21768 21769//21769 21770//21770 -f 21770//21770 21769//21769 21771//21771 -f 21770//21770 21771//21771 21772//21772 -f 21772//21772 21771//21771 21773//21773 -f 21772//21772 21773//21773 21774//21774 -f 21774//21774 21773//21773 21775//21775 -f 21774//21774 21775//21775 21776//21776 -f 21776//21776 21775//21775 21777//21777 -f 21776//21776 21777//21777 21778//21778 -f 21778//21778 21777//21777 21779//21779 -f 21778//21778 21779//21779 21780//21780 -f 21780//21780 21779//21779 21781//21781 -f 21780//21780 21781//21781 21782//21782 -f 21782//21782 21781//21781 21783//21783 -f 21782//21782 21783//21783 21784//21784 -f 21784//21784 21783//21783 21785//21785 -f 21785//21785 21783//21783 21786//21786 -f 21785//21785 21786//21786 21787//21787 -f 21787//21787 21786//21786 21788//21788 -f 21787//21787 21788//21788 21789//21789 -f 20067//20067 20066//20066 21790//21790 -f 21790//21790 20066//20066 21791//21791 -f 21790//21790 21791//21791 21792//21792 -f 21792//21792 21791//21791 21793//21793 -f 21792//21792 21793//21793 21789//21789 -f 21789//21789 21793//21793 21794//21794 -f 21789//21789 21794//21794 21787//21787 -f 20263//20263 20262//20262 21795//21795 -f 21795//21795 20262//20262 21796//21796 -f 21795//21795 21796//21796 21797//21797 -f 21797//21797 21796//21796 21798//21798 -f 21797//21797 21798//21798 21799//21799 -f 21799//21799 21798//21798 21800//21800 -f 21799//21799 21800//21800 21801//21801 -f 21801//21801 21800//21800 21802//21802 -f 21801//21801 21802//21802 21803//21803 -f 21803//21803 21802//21802 21804//21804 -f 21803//21803 21804//21804 21805//21805 -f 21805//21805 21804//21804 21806//21806 -f 21805//21805 21806//21806 21807//21807 -f 21807//21807 21806//21806 21808//21808 -f 21807//21807 21808//21808 21809//21809 -f 21809//21809 21808//21808 21810//21810 -f 21809//21809 21810//21810 21811//21811 -f 21811//21811 21810//21810 21812//21812 -f 21811//21811 21812//21812 21813//21813 -f 21813//21813 21812//21812 21814//21814 -f 21813//21813 21814//21814 21815//21815 -f 21814//21814 21816//21816 21815//21815 -f 21815//21815 21816//21816 21817//21817 -f 21815//21815 21817//21817 21818//21818 -f 21818//21818 21817//21817 21819//21819 -f 21818//21818 21819//21819 21820//21820 -f 21820//21820 21819//21819 21821//21821 -f 21820//21820 21821//21821 21822//21822 -f 21822//21822 21821//21821 21823//21823 -f 21822//21822 21823//21823 21824//21824 -f 21824//21824 21823//21823 21825//21825 -f 21824//21824 21825//21825 21826//21826 -f 21826//21826 21825//21825 21827//21827 -f 21826//21826 21827//21827 21828//21828 -f 21827//21827 21829//21829 21828//21828 -f 21828//21828 21829//21829 21830//21830 -f 21828//21828 21830//21830 21831//21831 -f 21831//21831 21830//21830 21832//21832 -f 21831//21831 21832//21832 21833//21833 -f 21832//21832 21834//21834 21833//21833 -f 21833//21833 21834//21834 21835//21835 -f 21833//21833 21835//21835 21836//21836 -f 21836//21836 21835//21835 21837//21837 -f 21836//21836 21837//21837 21838//21838 -f 21838//21838 21837//21837 21839//21839 -f 21838//21838 21839//21839 21840//21840 -f 21840//21840 21839//21839 21841//21841 -f 21841//21841 21839//21839 21842//21842 -f 21841//21841 21842//21842 21843//21843 -f 21843//21843 21842//21842 21844//21844 -f 21843//21843 21844//21844 21845//21845 -f 21845//21845 21844//21844 21846//21846 -f 21845//21845 21846//21846 21847//21847 -f 21848//21848 21849//21849 21850//21850 -f 21848//21848 21850//21850 21851//21851 -f 21846//21846 21852//21852 21847//21847 -f 21847//21847 21852//21852 21853//21853 -f 21847//21847 21853//21853 21854//21854 -f 21854//21854 21853//21853 21851//21851 -f 21854//21854 21851//21851 21855//21855 -f 21855//21855 21851//21851 21850//21850 -f 21849//21849 21848//21848 21856//21856 -f 21856//21856 21848//21848 21857//21857 -f 21856//21856 21857//21857 20147//20147 -f 20147//20147 21857//21857 21858//21858 -f 20147//20147 21858//21858 20145//20145 -f 20332//20332 20331//20331 21859//21859 -f 21859//21859 20331//20331 21860//21860 -f 21859//21859 21860//21860 21861//21861 -f 21861//21861 21860//21860 21862//21862 -f 21861//21861 21862//21862 21863//21863 -f 21864//21864 21865//21865 21866//21866 -f 21866//21866 21865//21865 21867//21867 -f 21862//21862 21868//21868 21863//21863 -f 21863//21863 21868//21868 21869//21869 -f 21863//21863 21869//21869 21870//21870 -f 21870//21870 21869//21869 21871//21871 -f 21870//21870 21871//21871 21872//21872 -f 21872//21872 21871//21871 21867//21867 -f 21872//21872 21867//21867 21873//21873 -f 21873//21873 21867//21867 21865//21865 -f 21866//21866 21874//21874 21864//21864 -f 21864//21864 21874//21874 21875//21875 -f 21864//21864 21875//21875 21876//21876 -f 21876//21876 21875//21875 21877//21877 -f 21876//21876 21877//21877 21878//21878 -f 21878//21878 21877//21877 21879//21879 -f 21878//21878 21879//21879 21880//21880 -f 21880//21880 21879//21879 21881//21881 -f 21880//21880 21881//21881 21882//21882 -f 21882//21882 21881//21881 21883//21883 -f 21882//21882 21883//21883 21884//21884 -f 21884//21884 21883//21883 21885//21885 -f 21885//21885 21883//21883 21886//21886 -f 21885//21885 21886//21886 21887//21887 -f 21887//21887 21886//21886 21888//21888 -f 21887//21887 21888//21888 21889//21889 -f 21889//21889 21888//21888 21890//21890 -f 21889//21889 21890//21890 21891//21891 -f 21891//21891 21890//21890 21892//21892 -f 21891//21891 21892//21892 21893//21893 -f 21893//21893 21892//21892 21894//21894 -f 21893//21893 21894//21894 21895//21895 -f 21895//21895 21894//21894 21896//21896 -f 21895//21895 21896//21896 21897//21897 -f 21897//21897 21896//21896 21898//21898 -f 21898//21898 21896//21896 21899//21899 -f 21898//21898 21899//21899 21900//21900 -f 21900//21900 21899//21899 21901//21901 -f 21901//21901 21899//21899 21902//21902 -f 21901//21901 21902//21902 21903//21903 -f 21903//21903 21902//21902 21904//21904 -f 21903//21903 21904//21904 21905//21905 -f 21905//21905 21904//21904 21906//21906 -f 21905//21905 21906//21906 21907//21907 -f 21907//21907 21906//21906 21908//21908 -f 21907//21907 21908//21908 21909//21909 -f 21909//21909 21908//21908 21910//21910 -f 21909//21909 21910//21910 21911//21911 -f 21911//21911 21910//21910 21912//21912 -f 21911//21911 21912//21912 21913//21913 -f 21912//21912 21914//21914 21913//21913 -f 21913//21913 21914//21914 21915//21915 -f 21913//21913 21915//21915 21916//21916 -f 21916//21916 21915//21915 21917//21917 -f 21916//21916 21917//21917 21918//21918 -f 21918//21918 21917//21917 21919//21919 -f 21918//21918 21919//21919 21920//21920 -f 21920//21920 21919//21919 21921//21921 -f 21920//21920 21921//21921 20196//20196 -f 20196//20196 21921//21921 20197//20197 -f 20398//20398 20397//20397 21922//21922 -f 21922//21922 20397//20397 21923//21923 -f 21922//21922 21923//21923 21924//21924 -f 21924//21924 21923//21923 21925//21925 -f 21924//21924 21925//21925 21926//21926 -f 21926//21926 21925//21925 21927//21927 -f 21925//21925 21928//21928 21927//21927 -f 21927//21927 21928//21928 21929//21929 -f 21927//21927 21929//21929 21930//21930 -f 21929//21929 21931//21931 21930//21930 -f 21930//21930 21931//21931 21932//21932 -f 21930//21930 21932//21932 21933//21933 -f 21933//21933 21932//21932 21934//21934 -f 21933//21933 21934//21934 21935//21935 -f 21935//21935 21934//21934 21936//21936 -f 21935//21935 21936//21936 21937//21937 -f 21936//21936 21938//21938 21937//21937 -f 21937//21937 21938//21938 21939//21939 -f 21937//21937 21939//21939 21940//21940 -f 21940//21940 21939//21939 21941//21941 -f 21940//21940 21941//21941 21942//21942 -f 21941//21941 21943//21943 21942//21942 -f 21942//21942 21943//21943 21944//21944 -f 21942//21942 21944//21944 21945//21945 -f 21945//21945 21944//21944 21946//21946 -f 21945//21945 21946//21946 21947//21947 -f 21947//21947 21946//21946 21948//21948 -f 21947//21947 21948//21948 21949//21949 -f 21949//21949 21948//21948 21950//21950 -f 21949//21949 21950//21950 21951//21951 -f 21951//21951 21950//21950 21952//21952 -f 21951//21951 21952//21952 21953//21953 -f 21953//21953 21952//21952 21954//21954 -f 21953//21953 21954//21954 21955//21955 -f 21955//21955 21954//21954 21956//21956 -f 21955//21955 21956//21956 21957//21957 -f 21957//21957 21956//21956 21958//21958 -f 21957//21957 21958//21958 21959//21959 -f 21959//21959 21958//21958 21960//21960 -f 21959//21959 21960//21960 21961//21961 -f 21962//21962 21963//21963 21964//21964 -f 21961//21961 21960//21960 21965//21965 -f 21965//21965 21960//21960 21966//21966 -f 21965//21965 21966//21966 21967//21967 -f 21967//21967 21966//21966 21968//21968 -f 21967//21967 21968//21968 21969//21969 -f 21969//21969 21968//21968 21970//21970 -f 21969//21969 21970//21970 21963//21963 -f 21963//21963 21970//21970 21971//21971 -f 21963//21963 21971//21971 21964//21964 -f 21964//21964 21972//21972 21962//21962 -f 21962//21962 21972//21972 21973//21973 -f 21962//21962 21973//21973 21974//21974 -f 21974//21974 21973//21973 21975//21975 -f 21974//21974 21975//21975 21976//21976 -f 21976//21976 21975//21975 21977//21977 -f 21976//21976 21977//21977 21978//21978 -f 21978//21978 21977//21977 21979//21979 -f 21978//21978 21979//21979 21980//21980 -f 21980//21980 21979//21979 21981//21981 -f 21980//21980 21981//21981 21982//21982 -f 21982//21982 21981//21981 21983//21983 -f 21982//21982 21983//21983 21984//21984 -f 21984//21984 21983//21983 21985//21985 -f 21984//21984 21985//21985 20264//20264 -f 20264//20264 21985//21985 20265//20265 -f 21986//21986 21987//21987 21988//21988 -f 20460//20460 20459//20459 21987//21987 -f 21987//21987 20459//20459 21989//21989 -f 21987//21987 21989//21989 21988//21988 -f 21988//21988 21990//21990 21986//21986 -f 21986//21986 21990//21990 21991//21991 -f 21986//21986 21991//21991 21992//21992 -f 21992//21992 21991//21991 21993//21993 -f 21992//21992 21993//21993 21994//21994 -f 21992//21992 21994//21994 21995//21995 -f 21995//21995 21994//21994 21996//21996 -f 21994//21994 21997//21997 21996//21996 -f 21996//21996 21997//21997 21998//21998 -f 21996//21996 21998//21998 21999//21999 -f 21999//21999 21998//21998 22000//22000 -f 21999//21999 22000//22000 22001//22001 -f 22001//22001 22000//22000 22002//22002 -f 22001//22001 22002//22002 22003//22003 -f 22003//22003 22002//22002 22004//22004 -f 22004//22004 22002//22002 22005//22005 -f 22004//22004 22005//22005 22006//22006 -f 22005//22005 22007//22007 22006//22006 -f 22006//22006 22007//22007 22008//22008 -f 22006//22006 22008//22008 22009//22009 -f 22009//22009 22008//22008 22010//22010 -f 22009//22009 22010//22010 22011//22011 -f 22011//22011 22010//22010 22012//22012 -f 22011//22011 22012//22012 22013//22013 -f 22013//22013 22012//22012 22014//22014 -f 22013//22013 22014//22014 22015//22015 -f 22015//22015 22014//22014 22016//22016 -f 22015//22015 22016//22016 22017//22017 -f 22017//22017 22016//22016 22018//22018 -f 22017//22017 22018//22018 22019//22019 -f 22019//22019 22018//22018 22020//22020 -f 22019//22019 22020//22020 22021//22021 -f 22021//22021 22020//22020 22022//22022 -f 22021//22021 22022//22022 22023//22023 -f 22023//22023 22022//22022 22024//22024 -f 22023//22023 22024//22024 22025//22025 -f 22025//22025 22024//22024 22026//22026 -f 22025//22025 22026//22026 22027//22027 -f 22027//22027 22026//22026 22028//22028 -f 22027//22027 22028//22028 22029//22029 -f 22029//22029 22028//22028 22030//22030 -f 22029//22029 22030//22030 22031//22031 -f 22030//22030 22032//22032 22031//22031 -f 22031//22031 22032//22032 22033//22033 -f 22031//22031 22033//22033 22034//22034 -f 22034//22034 22033//22033 22035//22035 -f 22034//22034 22035//22035 22036//22036 -f 22036//22036 22035//22035 22037//22037 -f 22036//22036 22037//22037 22038//22038 -f 22038//22038 22037//22037 22039//22039 -f 22038//22038 22039//22039 22040//22040 -f 22040//22040 22039//22039 22041//22041 -f 22040//22040 22041//22041 22042//22042 -f 22042//22042 22041//22041 22043//22043 -f 22042//22042 22043//22043 22044//22044 -f 22044//22044 22043//22043 22045//22045 -f 22044//22044 22045//22045 22046//22046 -f 22046//22046 22045//22045 22047//22047 -f 22046//22046 22047//22047 22048//22048 -f 22048//22048 22047//22047 22049//22049 -f 22048//22048 22049//22049 22050//22050 -f 22050//22050 22049//22049 22051//22051 -f 22050//22050 22051//22051 20338//20338 -f 20338//20338 22051//22051 20337//20337 -f 22052//22052 22053//22053 22054//22054 -f 20528//20528 20530//20530 22055//22055 -f 22055//22055 20530//20530 22056//22056 -f 22055//22055 22056//22056 22057//22057 -f 22057//22057 22056//22056 22058//22058 -f 22057//22057 22058//22058 22054//22054 -f 22054//22054 22058//22058 22059//22059 -f 22054//22054 22059//22059 22052//22052 -f 22053//22053 22052//22052 22060//22060 -f 22060//22060 22052//22052 22061//22061 -f 22060//22060 22061//22061 22062//22062 -f 22062//22062 22061//22061 22063//22063 -f 22062//22062 22063//22063 22064//22064 -f 22064//22064 22063//22063 22065//22065 -f 22064//22064 22065//22065 22066//22066 -f 22066//22066 22065//22065 22067//22067 -f 22066//22066 22067//22067 22068//22068 -f 22068//22068 22067//22067 22069//22069 -f 22068//22068 22069//22069 22070//22070 -f 22070//22070 22069//22069 22071//22071 -f 22070//22070 22071//22071 22072//22072 -f 22072//22072 22071//22071 22073//22073 -f 22072//22072 22073//22073 22074//22074 -f 22073//22073 22075//22075 22074//22074 -f 22074//22074 22075//22075 22076//22076 -f 22074//22074 22076//22076 22077//22077 -f 22077//22077 22076//22076 22078//22078 -f 22077//22077 22078//22078 22079//22079 -f 22079//22079 22078//22078 22080//22080 -f 22081//22081 22082//22082 22083//22083 -f 22083//22083 22082//22082 22084//22084 -f 22083//22083 22084//22084 22085//22085 -f 22085//22085 22084//22084 22086//22086 -f 22085//22085 22086//22086 22087//22087 -f 22087//22087 22086//22086 22088//22088 -f 22087//22087 22088//22088 22080//22080 -f 22080//22080 22088//22088 22089//22089 -f 22080//22080 22089//22089 22079//22079 -f 22083//22083 22090//22090 22081//22081 -f 22081//22081 22090//22090 22091//22091 -f 22081//22081 22091//22091 22092//22092 -f 22092//22092 22091//22091 22093//22093 -f 22092//22092 22093//22093 22094//22094 -f 22094//22094 22093//22093 22095//22095 -f 22094//22094 22095//22095 22096//22096 -f 22096//22096 22095//22095 22097//22097 -f 22096//22096 22097//22097 22098//22098 -f 22098//22098 22097//22097 22099//22099 -f 22098//22098 22099//22099 22100//22100 -f 22100//22100 22099//22099 22101//22101 -f 22100//22100 22101//22101 22102//22102 -f 22102//22102 22101//22101 22103//22103 -f 22103//22103 22101//22101 22104//22104 -f 22103//22103 22104//22104 22105//22105 -f 22105//22105 22104//22104 22106//22106 -f 22105//22105 22106//22106 22107//22107 -f 20402//20402 20401//20401 22108//22108 -f 22108//22108 20401//20401 22109//22109 -f 22108//22108 22109//22109 22110//22110 -f 22110//22110 22109//22109 22111//22111 -f 22110//22110 22111//22111 22107//22107 -f 22107//22107 22111//22111 22112//22112 -f 22107//22107 22112//22112 22105//22105 -f 20600//20600 20599//20599 22113//22113 -f 22113//22113 20599//20599 22114//22114 -f 22113//22113 22114//22114 22115//22115 -f 22115//22115 22114//22114 22116//22116 -f 22115//22115 22116//22116 22117//22117 -f 22117//22117 22116//22116 22118//22118 -f 22116//22116 22119//22119 22118//22118 -f 22118//22118 22119//22119 22120//22120 -f 22118//22118 22120//22120 22121//22121 -f 22121//22121 22120//22120 22122//22122 -f 22121//22121 22122//22122 22123//22123 -f 22123//22123 22122//22122 22124//22124 -f 22123//22123 22124//22124 22125//22125 -f 22125//22125 22124//22124 22126//22126 -f 22125//22125 22126//22126 22127//22127 -f 22127//22127 22126//22126 22128//22128 -f 22127//22127 22128//22128 22129//22129 -f 22129//22129 22128//22128 22130//22130 -f 22129//22129 22130//22130 22131//22131 -f 22131//22131 22130//22130 22132//22132 -f 22131//22131 22132//22132 22133//22133 -f 22133//22133 22132//22132 22134//22134 -f 22134//22134 22132//22132 22135//22135 -f 22134//22134 22135//22135 22136//22136 -f 22136//22136 22135//22135 22137//22137 -f 22136//22136 22137//22137 22138//22138 -f 22138//22138 22137//22137 22139//22139 -f 22138//22138 22139//22139 22140//22140 -f 22140//22140 22139//22139 22141//22141 -f 22140//22140 22141//22141 22142//22142 -f 22142//22142 22141//22141 22143//22143 -f 22142//22142 22143//22143 22144//22144 -f 22144//22144 22143//22143 22145//22145 -f 22144//22144 22145//22145 22146//22146 -f 22146//22146 22145//22145 22147//22147 -f 22146//22146 22147//22147 22148//22148 -f 22148//22148 22147//22147 22149//22149 -f 22148//22148 22149//22149 22150//22150 -f 22150//22150 22149//22149 22151//22151 -f 22150//22150 22151//22151 22152//22152 -f 22152//22152 22151//22151 22153//22153 -f 22152//22152 22153//22153 22154//22154 -f 22154//22154 22153//22153 22155//22155 -f 22154//22154 22155//22155 22156//22156 -f 22156//22156 22155//22155 22157//22157 -f 22156//22156 22157//22157 22158//22158 -f 22158//22158 22157//22157 22159//22159 -f 22158//22158 22159//22159 22160//22160 -f 22160//22160 22159//22159 22161//22161 -f 22160//22160 22161//22161 22162//22162 -f 22162//22162 22161//22161 22163//22163 -f 22162//22162 22163//22163 22164//22164 -f 22164//22164 22163//22163 22165//22165 -f 22164//22164 22165//22165 22166//22166 -f 20467//20467 20466//20466 22167//22167 -f 22167//22167 20466//20466 22168//22168 -f 22167//22167 22168//22168 22169//22169 -f 22169//22169 22168//22168 22170//22170 -f 22169//22169 22170//22170 22166//22166 -f 22166//22166 22170//22170 22171//22171 -f 22166//22166 22171//22171 22164//22164 -f 20668//20668 20670//20670 22172//22172 -f 22172//22172 20670//20670 22173//22173 -f 22172//22172 22173//22173 22174//22174 -f 22173//22173 22175//22175 22174//22174 -f 22174//22174 22175//22175 22176//22176 -f 22174//22174 22176//22176 22177//22177 -f 22177//22177 22176//22176 22178//22178 -f 22177//22177 22178//22178 22179//22179 -f 22179//22179 22178//22178 22180//22180 -f 22179//22179 22180//22180 22181//22181 -f 22181//22181 22180//22180 22182//22182 -f 22181//22181 22182//22182 22183//22183 -f 22183//22183 22182//22182 22184//22184 -f 22183//22183 22184//22184 22185//22185 -f 22185//22185 22184//22184 22186//22186 -f 22185//22185 22186//22186 22187//22187 -f 22187//22187 22186//22186 22188//22188 -f 22187//22187 22188//22188 22189//22189 -f 22189//22189 22188//22188 22190//22190 -f 22189//22189 22190//22190 22191//22191 -f 22191//22191 22190//22190 22192//22192 -f 22191//22191 22192//22192 22193//22193 -f 22193//22193 22192//22192 22194//22194 -f 22193//22193 22194//22194 22195//22195 -f 22194//22194 22196//22196 22195//22195 -f 22195//22195 22196//22196 22197//22197 -f 22195//22195 22197//22197 22198//22198 -f 22198//22198 22197//22197 22199//22199 -f 22198//22198 22199//22199 22200//22200 -f 22201//22201 22202//22202 22203//22203 -f 22203//22203 22202//22202 22204//22204 -f 22203//22203 22204//22204 22205//22205 -f 22205//22205 22204//22204 22206//22206 -f 22205//22205 22206//22206 22207//22207 -f 22207//22207 22206//22206 22208//22208 -f 22207//22207 22208//22208 22209//22209 -f 22209//22209 22208//22208 22210//22210 -f 22209//22209 22210//22210 22211//22211 -f 22211//22211 22210//22210 22212//22212 -f 22211//22211 22212//22212 22213//22213 -f 22213//22213 22212//22212 22214//22214 -f 22213//22213 22214//22214 22215//22215 -f 22215//22215 22214//22214 22216//22216 -f 22215//22215 22216//22216 22217//22217 -f 22217//22217 22216//22216 22218//22218 -f 22217//22217 22218//22218 22219//22219 -f 22219//22219 22218//22218 22220//22220 -f 22219//22219 22220//22220 22221//22221 -f 22221//22221 22220//22220 22222//22222 -f 22221//22221 22222//22222 22223//22223 -f 22223//22223 22222//22222 22200//22200 -f 22223//22223 22200//22200 22224//22224 -f 22224//22224 22200//22200 22199//22199 -f 20532//20532 22225//22225 20533//20533 -f 20533//20533 22225//22225 22226//22226 -f 20533//20533 22226//22226 22227//22227 -f 22227//22227 22226//22226 22228//22228 -f 22227//22227 22228//22228 22229//22229 -f 22229//22229 22228//22228 22230//22230 -f 22229//22229 22230//22230 22231//22231 -f 22231//22231 22230//22230 22232//22232 -f 22231//22231 22232//22232 22201//22201 -f 22201//22201 22232//22232 22233//22233 -f 22201//22201 22233//22233 22202//22202 -f 22234//22234 20602//20602 20601//20601 -f 22235//22235 22236//22236 22237//22237 -f 20742//20742 20741//20741 22238//22238 -f 22238//22238 20741//20741 22239//22239 -f 22238//22238 22239//22239 22240//22240 -f 22240//22240 22239//22239 22241//22241 -f 22240//22240 22241//22241 22242//22242 -f 22242//22242 22241//22241 22243//22243 -f 22243//22243 22241//22241 22244//22244 -f 22243//22243 22244//22244 22245//22245 -f 22245//22245 22244//22244 22246//22246 -f 22245//22245 22246//22246 22247//22247 -f 22247//22247 22246//22246 22248//22248 -f 22248//22248 22246//22246 22249//22249 -f 22248//22248 22249//22249 22250//22250 -f 22250//22250 22249//22249 22251//22251 -f 22250//22250 22251//22251 22252//22252 -f 22252//22252 22251//22251 22253//22253 -f 22252//22252 22253//22253 22254//22254 -f 22254//22254 22253//22253 22255//22255 -f 22255//22255 22253//22253 22256//22256 -f 22255//22255 22256//22256 22257//22257 -f 22257//22257 22256//22256 22258//22258 -f 22257//22257 22258//22258 22259//22259 -f 22258//22258 22260//22260 22259//22259 -f 22259//22259 22260//22260 22261//22261 -f 22259//22259 22261//22261 22262//22262 -f 22262//22262 22261//22261 22263//22263 -f 22261//22261 22264//22264 22263//22263 -f 22263//22263 22264//22264 22265//22265 -f 22263//22263 22265//22265 22266//22266 -f 22266//22266 22265//22265 22267//22267 -f 22266//22266 22267//22267 22268//22268 -f 22268//22268 22267//22267 22269//22269 -f 22268//22268 22269//22269 22270//22270 -f 22270//22270 22269//22269 22271//22271 -f 22270//22270 22271//22271 22272//22272 -f 22272//22272 22271//22271 22273//22273 -f 22272//22272 22273//22273 22274//22274 -f 22235//22235 22237//22237 22275//22275 -f 22275//22275 22237//22237 22276//22276 -f 22275//22275 22276//22276 22277//22277 -f 22277//22277 22276//22276 22278//22278 -f 22277//22277 22278//22278 22274//22274 -f 22274//22274 22278//22278 22279//22279 -f 22274//22274 22279//22279 22272//22272 -f 22280//22280 22281//22281 22282//22282 -f 22282//22282 22281//22281 22283//22283 -f 22282//22282 22283//22283 22284//22284 -f 22284//22284 22283//22283 22285//22285 -f 22284//22284 22285//22285 22236//22236 -f 22236//22236 22285//22285 22286//22286 -f 22236//22236 22286//22286 22237//22237 -f 22234//22234 20601//20601 22287//22287 -f 22287//22287 20601//20601 22288//22288 -f 22287//22287 22288//22288 22289//22289 -f 22289//22289 22288//22288 22290//22290 -f 22289//22289 22290//22290 22291//22291 -f 22291//22291 22290//22290 22292//22292 -f 22291//22291 22292//22292 22293//22293 -f 22293//22293 22292//22292 22294//22294 -f 22293//22293 22294//22294 22295//22295 -f 22295//22295 22294//22294 22296//22296 -f 22295//22295 22296//22296 22297//22297 -f 22297//22297 22296//22296 22298//22298 -f 22297//22297 22298//22298 22299//22299 -f 22299//22299 22298//22298 22300//22300 -f 22299//22299 22300//22300 22280//22280 -f 22280//22280 22300//22300 22301//22301 -f 22280//22280 22301//22301 22281//22281 -f 22302//22302 20815//20815 22303//22303 -f 22303//22303 20815//20815 20814//20814 -f 22302//22302 22303//22303 22304//22304 -f 22304//22304 22303//22303 22305//22305 -f 22304//22304 22305//22305 22306//22306 -f 22306//22306 22305//22305 22307//22307 -f 22306//22306 22307//22307 22308//22308 -f 22309//22309 22310//22310 22311//22311 -f 22311//22311 22310//22310 22312//22312 -f 22311//22311 22312//22312 22313//22313 -f 22313//22313 22312//22312 22314//22314 -f 22313//22313 22314//22314 22315//22315 -f 22315//22315 22314//22314 22316//22316 -f 22315//22315 22316//22316 22317//22317 -f 22317//22317 22316//22316 22318//22318 -f 22317//22317 22318//22318 22319//22319 -f 22319//22319 22318//22318 22320//22320 -f 22319//22319 22320//22320 22321//22321 -f 22321//22321 22320//22320 22322//22322 -f 22321//22321 22322//22322 22308//22308 -f 22308//22308 22322//22322 22323//22323 -f 22308//22308 22323//22323 22306//22306 -f 22324//22324 22325//22325 22326//22326 -f 22326//22326 22325//22325 22327//22327 -f 22326//22326 22327//22327 22328//22328 -f 22327//22327 22329//22329 22328//22328 -f 22328//22328 22329//22329 22330//22330 -f 22328//22328 22330//22330 22331//22331 -f 22331//22331 22330//22330 22332//22332 -f 22331//22331 22332//22332 22333//22333 -f 22333//22333 22332//22332 22334//22334 -f 22333//22333 22334//22334 22309//22309 -f 22309//22309 22334//22334 22335//22335 -f 22309//22309 22335//22335 22310//22310 -f 22336//22336 22337//22337 22338//22338 -f 22338//22338 22337//22337 22339//22339 -f 22338//22338 22339//22339 22340//22340 -f 22338//22338 22341//22341 22336//22336 -f 22336//22336 22341//22341 22342//22342 -f 22336//22336 22342//22342 22324//22324 -f 22324//22324 22342//22342 22343//22343 -f 22324//22324 22343//22343 22325//22325 -f 22340//22340 22339//22339 22344//22344 -f 22344//22344 22339//22339 22345//22345 -f 22344//22344 22345//22345 22346//22346 -f 22345//22345 22347//22347 22346//22346 -f 22346//22346 22347//22347 22348//22348 -f 22346//22346 22348//22348 22349//22349 -f 22349//22349 22348//22348 22350//22350 -f 22348//22348 22351//22351 22350//22350 -f 22350//22350 22351//22351 22352//22352 -f 22350//22350 22352//22352 22353//22353 -f 22353//22353 22352//22352 22354//22354 -f 22353//22353 22354//22354 22355//22355 -f 22355//22355 22354//22354 22356//22356 -f 22355//22355 22356//22356 22357//22357 -f 22357//22357 22356//22356 22358//22358 -f 22357//22357 22358//22358 20686//20686 -f 20686//20686 22358//22358 20684//20684 -f 20884//20884 20883//20883 22359//22359 -f 22359//22359 20883//20883 22360//22360 -f 22359//22359 22360//22360 22361//22361 -f 22361//22361 22360//22360 22362//22362 -f 22361//22361 22362//22362 22363//22363 -f 22363//22363 22362//22362 22364//22364 -f 22363//22363 22364//22364 22365//22365 -f 22365//22365 22364//22364 22366//22366 -f 22365//22365 22366//22366 22367//22367 -f 22367//22367 22366//22366 22368//22368 -f 22367//22367 22368//22368 22369//22369 -f 22369//22369 22368//22368 22370//22370 -f 22369//22369 22370//22370 22371//22371 -f 22371//22371 22370//22370 22372//22372 -f 22373//22373 22374//22374 22375//22375 -f 22373//22373 22375//22375 22376//22376 -f 22376//22376 22375//22375 22377//22377 -f 22376//22376 22377//22377 22378//22378 -f 22377//22377 22379//22379 22378//22378 -f 22378//22378 22379//22379 22380//22380 -f 22378//22378 22380//22380 22372//22372 -f 22372//22372 22380//22380 22381//22381 -f 22372//22372 22381//22381 22371//22371 -f 22374//22374 22373//22373 22382//22382 -f 22382//22382 22373//22373 22383//22383 -f 22382//22382 22383//22383 22384//22384 -f 22384//22384 22383//22383 22385//22385 -f 22384//22384 22385//22385 22386//22386 -f 22386//22386 22385//22385 22387//22387 -f 22386//22386 22387//22387 22388//22388 -f 22388//22388 22387//22387 22389//22389 -f 22389//22389 22387//22387 22390//22390 -f 22389//22389 22390//22390 22391//22391 -f 22391//22391 22390//22390 22392//22392 -f 22391//22391 22392//22392 22393//22393 -f 22394//22394 22395//22395 22396//22396 -f 22396//22396 22395//22395 22397//22397 -f 22396//22396 22397//22397 22398//22398 -f 22398//22398 22397//22397 22399//22399 -f 22398//22398 22399//22399 22400//22400 -f 22400//22400 22399//22399 22401//22401 -f 22400//22400 22401//22401 22402//22402 -f 22402//22402 22401//22401 22403//22403 -f 22402//22402 22403//22403 22404//22404 -f 22404//22404 22403//22403 22405//22405 -f 22404//22404 22405//22405 22406//22406 -f 22406//22406 22405//22405 22407//22407 -f 22406//22406 22407//22407 22393//22393 -f 22393//22393 22407//22407 22408//22408 -f 22393//22393 22408//22408 22391//22391 -f 22409//22409 22410//22410 22411//22411 -f 22411//22411 22410//22410 22412//22412 -f 22411//22411 22412//22412 22413//22413 -f 22413//22413 22412//22412 22414//22414 -f 22413//22413 22414//22414 22394//22394 -f 22394//22394 22414//22414 22415//22415 -f 22394//22394 22415//22415 22395//22395 -f 20751//20751 20750//20750 22416//22416 -f 22416//22416 20750//20750 22417//22417 -f 22416//22416 22417//22417 22409//22409 -f 22409//22409 22417//22417 22418//22418 -f 22409//22409 22418//22418 22410//22410 -f 22419//22419 22420//22420 22421//22421 -f 22421//22421 22420//22420 22422//22422 -f 22421//22421 22422//22422 22423//22423 -f 22423//22423 22422//22422 22424//22424 -f 22423//22423 22424//22424 22425//22425 -f 22425//22425 22424//22424 22426//22426 -f 22425//22425 22426//22426 22427//22427 -f 22427//22427 22426//22426 22428//22428 -f 22427//22427 22428//22428 22429//22429 -f 22429//22429 22428//22428 22430//22430 -f 22429//22429 22430//22430 22431//22431 -f 22431//22431 22430//22430 22432//22432 -f 22431//22431 22432//22432 20819//20819 -f 20819//20819 22432//22432 20820//20820 -f 22419//22419 22421//22421 22433//22433 -f 22433//22433 22421//22421 22434//22434 -f 22433//22433 22434//22434 22435//22435 -f 22436//22436 22437//22437 22434//22434 -f 22434//22434 22437//22437 22438//22438 -f 22434//22434 22438//22438 22435//22435 -f 22436//22436 22434//22434 22439//22439 -f 22439//22439 22434//22434 22440//22440 -f 22439//22439 22440//22440 22441//22441 -f 22442//22442 22443//22443 22440//22440 -f 22440//22440 22443//22443 22444//22444 -f 22440//22440 22444//22444 22441//22441 -f 19155//19155 19154//19154 22445//22445 -f 19155//19155 22445//22445 22446//22446 -f 22446//22446 22445//22445 22447//22447 -f 22446//22446 22447//22447 22448//22448 -f 22448//22448 22447//22447 22449//22449 -f 22448//22448 22449//22449 22450//22450 -f 22450//22450 22449//22449 22451//22451 -f 22450//22450 22451//22451 22452//22452 -f 22452//22452 22451//22451 22453//22453 -f 22452//22452 22453//22453 22454//22454 -f 22454//22454 22453//22453 22455//22455 -f 22454//22454 22455//22455 22456//22456 -f 22456//22456 22455//22455 22457//22457 -f 22456//22456 22457//22457 22458//22458 -f 22458//22458 22457//22457 22459//22459 -f 22458//22458 22459//22459 22460//22460 -f 22460//22460 22459//22459 22461//22461 -f 22460//22460 22461//22461 22462//22462 -f 22462//22462 22461//22461 22463//22463 -f 22462//22462 22463//22463 22464//22464 -f 22464//22464 22463//22463 22465//22465 -f 22464//22464 22465//22465 22466//22466 -f 22466//22466 22465//22465 22467//22467 -f 22466//22466 22467//22467 22468//22468 -f 22468//22468 22467//22467 22469//22469 -f 22468//22468 22469//22469 22470//22470 -f 22470//22470 22469//22469 22471//22471 -f 22470//22470 22471//22471 22472//22472 -f 22472//22472 22471//22471 22473//22473 -f 22472//22472 22473//22473 22474//22474 -f 22474//22474 22473//22473 19123//19123 -f 22474//22474 19123//19123 19122//19122 -f 22475//22475 22459//22459 22476//22476 -f 22476//22476 22459//22459 22457//22457 -f 22476//22476 22457//22457 22477//22477 -f 22477//22477 22457//22457 22455//22455 -f 22477//22477 22455//22455 22478//22478 -f 22478//22478 22455//22455 22453//22453 -f 22478//22478 22453//22453 22479//22479 -f 22479//22479 22453//22453 22451//22451 -f 22479//22479 22451//22451 22480//22480 -f 22480//22480 22451//22451 22449//22449 -f 22480//22480 22449//22449 22481//22481 -f 22481//22481 22449//22449 22447//22447 -f 22481//22481 22447//22447 22482//22482 -f 22482//22482 22447//22447 22445//22445 -f 22482//22482 22445//22445 19187//19187 -f 19187//19187 22445//22445 19154//19154 -f 19187//19187 19154//19154 19185//19185 -f 19185//19185 19154//19154 19152//19152 -f 19185//19185 19152//19152 19183//19183 -f 19183//19183 19152//19152 19150//19150 -f 19183//19183 19150//19150 19181//19181 -f 19181//19181 19150//19150 19148//19148 -f 19181//19181 19148//19148 19179//19179 -f 19179//19179 19148//19148 19146//19146 -f 19179//19179 19146//19146 19177//19177 -f 19177//19177 19146//19146 19144//19144 -f 19177//19177 19144//19144 19175//19175 -f 19175//19175 19144//19144 19142//19142 -f 19175//19175 19142//19142 19173//19173 -f 19173//19173 19142//19142 19140//19140 -f 19173//19173 19140//19140 19171//19171 -f 19140//19140 19138//19138 19171//19171 -f 19171//19171 19138//19138 19136//19136 -f 19171//19171 19136//19136 19169//19169 -f 19169//19169 19136//19136 19134//19134 -f 19169//19169 19134//19134 19167//19167 -f 19167//19167 19134//19134 19132//19132 -f 19167//19167 19132//19132 19165//19165 -f 19165//19165 19132//19132 19130//19130 -f 19165//19165 19130//19130 19163//19163 -f 19163//19163 19130//19130 19128//19128 -f 19163//19163 19128//19128 19161//19161 -f 19161//19161 19128//19128 19126//19126 -f 19161//19161 19126//19126 19159//19159 -f 19159//19159 19126//19126 19124//19124 -f 19159//19159 19124//19124 19156//19156 -f 19156//19156 19124//19124 19123//19123 -f 19156//19156 19123//19123 22483//22483 -f 22483//22483 19123//19123 22473//22473 -f 22483//22483 22473//22473 22484//22484 -f 22484//22484 22473//22473 22471//22471 -f 22484//22484 22471//22471 22485//22485 -f 22485//22485 22471//22471 22469//22469 -f 22485//22485 22469//22469 22486//22486 -f 22486//22486 22469//22469 22467//22467 -f 22486//22486 22467//22467 22487//22487 -f 22487//22487 22467//22467 22465//22465 -f 22487//22487 22465//22465 22488//22488 -f 22488//22488 22465//22465 22463//22463 -f 22488//22488 22463//22463 22475//22475 -f 22475//22475 22463//22463 22461//22461 -f 22475//22475 22461//22461 22459//22459 -f 19187//19187 19186//19186 22489//22489 -f 19187//19187 22489//22489 22482//22482 -f 22482//22482 22489//22489 22490//22490 -f 22482//22482 22490//22490 22481//22481 -f 22481//22481 22490//22490 22491//22491 -f 22481//22481 22491//22491 22480//22480 -f 22480//22480 22491//22491 22492//22492 -f 22480//22480 22492//22492 22479//22479 -f 22479//22479 22492//22492 22493//22493 -f 22479//22479 22493//22493 22478//22478 -f 22478//22478 22493//22493 22494//22494 -f 22478//22478 22494//22494 22477//22477 -f 22477//22477 22494//22494 22495//22495 -f 22477//22477 22495//22495 22476//22476 -f 22476//22476 22495//22495 22496//22496 -f 22476//22476 22496//22496 22475//22475 -f 22475//22475 22496//22496 22497//22497 -f 22475//22475 22497//22497 22488//22488 -f 22488//22488 22497//22497 22498//22498 -f 22488//22488 22498//22498 22487//22487 -f 22487//22487 22498//22498 22499//22499 -f 22487//22487 22499//22499 22486//22486 -f 22486//22486 22499//22499 22500//22500 -f 22486//22486 22500//22500 22485//22485 -f 22485//22485 22500//22500 22501//22501 -f 22485//22485 22501//22501 22484//22484 -f 22484//22484 22501//22501 22502//22502 -f 22484//22484 22502//22502 22483//22483 -f 22483//22483 22502//22502 19157//19157 -f 22483//22483 19157//19157 19156//19156 -f 22503//22503 22504//22504 22505//22505 -f 22506//22506 22507//22507 22508//22508 -f 22509//22509 19170//19170 19168//19168 -f 22510//22510 22511//22511 22512//22512 -f 19170//19170 22509//22509 19172//19172 -f 22513//22513 22514//22514 22515//22515 -f 22505//22505 22516//22516 22517//22517 -f 22518//22518 22519//22519 22520//22520 -f 22521//22521 22522//22522 22523//22523 -f 22524//22524 22500//22500 22499//22499 -f 22512//22512 22525//22525 22526//22526 -f 22520//22520 22527//22527 22528//22528 -f 22491//22491 22490//22490 22529//22529 -f 22529//22529 22490//22490 22489//22489 -f 22530//22530 22494//22494 22493//22493 -f 22523//22523 22531//22531 22532//22532 -f 22500//22500 22524//22524 22501//22501 -f 19162//19162 19160//19160 22533//22533 -f 22533//22533 19160//19160 19158//19158 -f 22509//22509 22534//22534 19172//19172 -f 19172//19172 22534//22534 22503//22503 -f 19172//19172 22503//22503 19174//19174 -f 19174//19174 22503//22503 22505//22505 -f 19174//19174 22505//22505 19176//19176 -f 19176//19176 22505//22505 22517//22517 -f 19176//19176 22517//22517 19178//19178 -f 22518//22518 19182//19182 19180//19180 -f 22517//22517 22535//22535 19178//19178 -f 19178//19178 22535//22535 22536//22536 -f 19178//19178 22536//22536 19180//19180 -f 19180//19180 22536//22536 22537//22537 -f 19180//19180 22537//22537 22518//22518 -f 19182//19182 22518//22518 19184//19184 -f 19184//19184 22518//22518 22520//22520 -f 19184//19184 22520//22520 19186//19186 -f 19186//19186 22520//22520 22528//22528 -f 19186//19186 22528//22528 22489//22489 -f 22489//22489 22528//22528 22538//22538 -f 22489//22489 22538//22538 22529//22529 -f 22530//22530 22539//22539 22494//22494 -f 22494//22494 22539//22539 22540//22540 -f 22494//22494 22540//22540 22495//22495 -f 22495//22495 22540//22540 22496//22496 -f 22540//22540 22541//22541 22496//22496 -f 22496//22496 22541//22541 22521//22521 -f 22496//22496 22521//22521 22497//22497 -f 22497//22497 22521//22521 22523//22523 -f 22497//22497 22523//22523 22498//22498 -f 22498//22498 22523//22523 22532//22532 -f 22498//22498 22532//22532 22499//22499 -f 22499//22499 22532//22532 22542//22542 -f 22499//22499 22542//22542 22524//22524 -f 22524//22524 22543//22543 22501//22501 -f 22501//22501 22543//22543 22513//22513 -f 22501//22501 22513//22513 22502//22502 -f 22502//22502 22513//22513 22515//22515 -f 22502//22502 22515//22515 19157//19157 -f 22515//22515 22544//22544 19157//19157 -f 19157//19157 22544//22544 22545//22545 -f 19157//19157 22545//22545 19158//19158 -f 19158//19158 22545//22545 22546//22546 -f 19158//19158 22546//22546 22533//22533 -f 22533//22533 22547//22547 19162//19162 -f 19162//19162 22547//22547 22510//22510 -f 19162//19162 22510//22510 19164//19164 -f 19164//19164 22510//22510 22512//22512 -f 19164//19164 22512//22512 19166//19166 -f 19166//19166 22512//22512 22526//22526 -f 19166//19166 22526//22526 19168//19168 -f 19168//19168 22526//22526 22548//22548 -f 19168//19168 22548//22548 22509//22509 -f 22529//22529 22549//22549 22491//22491 -f 22491//22491 22549//22549 22506//22506 -f 22491//22491 22506//22506 22492//22492 -f 22492//22492 22506//22506 22508//22508 -f 22492//22492 22508//22508 22493//22493 -f 22493//22493 22508//22508 22550//22550 -f 22493//22493 22550//22550 22530//22530 -f 22551//22551 22552//22552 22553//22553 -f 22553//22553 22552//22552 22531//22531 -f 22553//22553 22531//22531 22554//22554 -f 22554//22554 22531//22531 22523//22523 -f 22555//22555 22551//22551 22556//22556 -f 22556//22556 22551//22551 22553//22553 -f 22556//22556 22553//22553 22554//22554 -f 22557//22557 22558//22558 22559//22559 -f 22559//22559 22560//22560 22557//22557 -f 22557//22557 22560//22560 22561//22561 -f 22557//22557 22561//22561 22562//22562 -f 22562//22562 22442//22442 22557//22557 -f 22557//22557 22442//22442 22440//22440 -f 22557//22557 22440//22440 22563//22563 -f 22563//22563 22440//22440 22434//22434 -f 22563//22563 22434//22434 22564//22564 -f 22565//22565 22566//22566 22567//22567 -f 22568//22568 22569//22569 22570//22570 -f 22570//22570 22569//22569 22571//22571 -f 22571//22571 22572//22572 22573//22573 -f 22558//22558 22574//22574 22575//22575 -f 22576//22576 22577//22577 22578//22578 -f 22579//22579 22580//22580 22581//22581 -f 22581//22581 22580//22580 22582//22582 -f 22579//22579 22583//22583 22580//22580 -f 22580//22580 22583//22583 22584//22584 -f 22580//22580 22584//22584 22585//22585 -f 22585//22585 22584//22584 22586//22586 -f 22585//22585 22586//22586 22587//22587 -f 22586//22586 22588//22588 22587//22587 -f 22587//22587 22588//22588 22589//22589 -f 22587//22587 22589//22589 22590//22590 -f 22590//22590 22589//22589 22591//22591 -f 22590//22590 22591//22591 22592//22592 -f 22593//22593 22423//22423 22594//22594 -f 22594//22594 22423//22423 22595//22595 -f 22596//22596 22421//22421 22597//22597 -f 22597//22597 22421//22421 22423//22423 -f 22597//22597 22423//22423 22598//22598 -f 22598//22598 22423//22423 22593//22593 -f 22596//22596 22599//22599 22421//22421 -f 22421//22421 22599//22599 22600//22600 -f 22421//22421 22600//22600 22434//22434 -f 22434//22434 22600//22600 22601//22601 -f 22434//22434 22601//22601 22564//22564 -f 22602//22602 22603//22603 22557//22557 -f 22557//22557 22603//22603 22570//22570 -f 22557//22557 22570//22570 22558//22558 -f 22558//22558 22570//22570 22571//22571 -f 22558//22558 22571//22571 22574//22574 -f 22574//22574 22571//22571 22573//22573 -f 22604//22604 22605//22605 22606//22606 -f 22606//22606 22605//22605 22607//22607 -f 22606//22606 22607//22607 22608//22608 -f 22607//22607 22609//22609 22608//22608 -f 22608//22608 22609//22609 22610//22610 -f 22608//22608 22610//22610 22611//22611 -f 22611//22611 22610//22610 22612//22612 -f 22611//22611 22612//22612 22613//22613 -f 22577//22577 22576//22576 22614//22614 -f 22614//22614 22576//22576 22615//22615 -f 22614//22614 22615//22615 22566//22566 -f 22566//22566 22615//22615 22616//22616 -f 22566//22566 22616//22616 22567//22567 -f 22565//22565 22567//22567 22617//22617 -f 22617//22617 22567//22567 22618//22618 -f 22617//22617 22618//22618 22582//22582 -f 22582//22582 22618//22618 22619//22619 -f 22582//22582 22619//22619 22581//22581 -f 22591//22591 22620//22620 22592//22592 -f 22592//22592 22620//22620 22621//22621 -f 22592//22592 22621//22621 22622//22622 -f 22622//22622 22621//22621 22623//22623 -f 22622//22622 22623//22623 22595//22595 -f 22595//22595 22623//22623 22624//22624 -f 22595//22595 22624//22624 22594//22594 -f 22575//22575 22625//22625 22558//22558 -f 22558//22558 22625//22625 22626//22626 -f 22558//22558 22626//22626 22627//22627 -f 22627//22627 22626//22626 22628//22628 -f 22627//22627 22628//22628 22629//22629 -f 22629//22629 22628//22628 22630//22630 -f 22629//22629 22630//22630 22631//22631 -f 22631//22631 22630//22630 22632//22632 -f 22631//22631 22632//22632 22633//22633 -f 22633//22633 22632//22632 22634//22634 -f 22633//22633 22634//22634 22635//22635 -f 22635//22635 22634//22634 22636//22636 -f 22635//22635 22636//22636 22637//22637 -f 22637//22637 22636//22636 22638//22638 -f 22637//22637 22638//22638 22604//22604 -f 22604//22604 22638//22638 22639//22639 -f 22604//22604 22639//22639 22605//22605 -f 22612//22612 22640//22640 22613//22613 -f 22613//22613 22640//22640 22641//22641 -f 22613//22613 22641//22641 22642//22642 -f 22642//22642 22641//22641 22643//22643 -f 22642//22642 22643//22643 22644//22644 -f 22644//22644 22643//22643 22645//22645 -f 22644//22644 22645//22645 22646//22646 -f 22646//22646 22645//22645 22647//22647 -f 22646//22646 22647//22647 22648//22648 -f 22648//22648 22647//22647 22649//22649 -f 22648//22648 22649//22649 22650//22650 -f 22650//22650 22649//22649 22651//22651 -f 22650//22650 22651//22651 22652//22652 -f 22652//22652 22651//22651 22653//22653 -f 22652//22652 22653//22653 22654//22654 -f 22654//22654 22653//22653 22552//22552 -f 22654//22654 22552//22552 22655//22655 -f 22655//22655 22552//22552 22551//22551 -f 22655//22655 22551//22551 22656//22656 -f 22656//22656 22551//22551 22555//22555 -f 22656//22656 22555//22555 22657//22657 -f 22657//22657 22555//22555 22658//22658 -f 22657//22657 22658//22658 22659//22659 -f 22659//22659 22658//22658 22660//22660 -f 22659//22659 22660//22660 22661//22661 -f 22661//22661 22660//22660 22662//22662 -f 22661//22661 22662//22662 22663//22663 -f 22663//22663 22662//22662 22664//22664 -f 22663//22663 22664//22664 22665//22665 -f 22664//22664 22666//22666 22665//22665 -f 22665//22665 22666//22666 22667//22667 -f 22665//22665 22667//22667 22668//22668 -f 22668//22668 22667//22667 22669//22669 -f 22668//22668 22669//22669 22578//22578 -f 22578//22578 22669//22669 22670//22670 -f 22578//22578 22670//22670 22576//22576 -f 22671//22671 22532//22532 22672//22672 -f 22672//22672 22532//22532 22531//22531 -f 22672//22672 22531//22531 22653//22653 -f 22653//22653 22531//22531 22552//22552 -f 22554//22554 22523//22523 22556//22556 -f 22556//22556 22523//22523 22522//22522 -f 22556//22556 22522//22522 22555//22555 -f 22555//22555 22522//22522 22658//22658 -f 22654//22654 22673//22673 22652//22652 -f 22652//22652 22673//22673 22674//22674 -f 22675//22675 20844//20844 20841//20841 -f 22676//22676 22392//22392 22390//22390 -f 22677//22677 20770//20770 20768//20768 -f 22678//22678 22313//22313 22315//22315 -f 22679//22679 22337//22337 22336//22336 -f 22680//22680 20712//20712 20709//20709 -f 22258//22258 22256//22256 22681//22681 -f 22681//22681 22256//22256 22682//22682 -f 22682//22682 22256//22256 22683//22683 -f 22683//22683 22256//22256 22253//22253 -f 22683//22683 22253//22253 22684//22684 -f 22253//22253 22251//22251 22684//22684 -f 22684//22684 22251//22251 22249//22249 -f 22684//22684 22249//22249 22685//22685 -f 22685//22685 22249//22249 22246//22246 -f 22685//22685 22246//22246 22686//22686 -f 22686//22686 22246//22246 22244//22244 -f 22686//22686 22244//22244 22687//22687 -f 22687//22687 22244//22244 22241//22241 -f 22687//22687 22241//22241 22688//22688 -f 22688//22688 22241//22241 22239//22239 -f 22688//22688 22239//22239 22689//22689 -f 22689//22689 22239//22239 20741//20741 -f 22689//22689 20741//20741 22690//22690 -f 22690//22690 20741//20741 20743//20743 -f 22690//22690 20743//20743 22691//22691 -f 22691//22691 20743//20743 22692//22692 -f 20743//20743 20744//20744 22692//22692 -f 22692//22692 20744//20744 20739//20739 -f 22692//22692 20739//20739 22693//22693 -f 22693//22693 20739//20739 20737//20737 -f 22693//22693 20737//20737 22694//22694 -f 20737//20737 20736//20736 22694//22694 -f 22694//22694 20736//20736 20732//20732 -f 22694//22694 20732//20732 22695//22695 -f 22695//22695 20732//20732 20734//20734 -f 22695//22695 20734//20734 22696//22696 -f 20734//20734 20735//20735 22696//22696 -f 22696//22696 20735//20735 20730//20730 -f 22696//22696 20730//20730 22697//22697 -f 22697//22697 20730//20730 20728//20728 -f 20728//20728 20727//20727 22697//22697 -f 22697//22697 20727//20727 20725//20725 -f 22697//22697 20725//20725 22698//22698 -f 22698//22698 20725//20725 20723//20723 -f 22698//22698 20723//20723 22699//22699 -f 22699//22699 20723//20723 20721//20721 -f 20721//20721 20719//20719 22699//22699 -f 22699//22699 20719//20719 20717//20717 -f 22699//22699 20717//20717 22700//22700 -f 22700//22700 20717//20717 22680//22680 -f 22680//22680 20717//20717 20714//20714 -f 22680//22680 20714//20714 20712//20712 -f 20707//20707 22701//22701 20709//20709 -f 20709//20709 22701//22701 22702//22702 -f 20709//20709 22702//22702 22680//22680 -f 20707//20707 20705//20705 22701//22701 -f 22701//22701 20705//20705 20703//20703 -f 22701//22701 20703//20703 22703//22703 -f 22703//22703 20703//20703 20701//20701 -f 22703//22703 20701//20701 22704//22704 -f 20701//20701 20699//20699 22704//22704 -f 22704//22704 20699//20699 20697//20697 -f 22704//22704 20697//20697 22705//22705 -f 22705//22705 20697//20697 20695//20695 -f 22705//22705 20695//20695 22706//22706 -f 20693//20693 22707//22707 20673//20673 -f 20673//20673 22707//22707 22706//22706 -f 20673//20673 22706//22706 20694//20694 -f 20694//20694 22706//22706 20695//20695 -f 20693//20693 20692//20692 22707//22707 -f 22707//22707 20692//20692 20690//20690 -f 22707//22707 20690//20690 22708//22708 -f 22708//22708 20690//20690 20688//20688 -f 22708//22708 20688//20688 22709//22709 -f 20688//20688 20687//20687 22709//22709 -f 22709//22709 20687//20687 20674//20674 -f 22709//22709 20674//20674 22710//22710 -f 22710//22710 20674//20674 20676//20676 -f 22710//22710 20676//20676 22711//22711 -f 22711//22711 20676//20676 20678//20678 -f 22711//22711 20678//20678 22712//22712 -f 22712//22712 20678//20678 20680//20680 -f 20680//20680 20682//20682 22712//22712 -f 22712//22712 20682//20682 20684//20684 -f 22712//22712 20684//20684 22713//22713 -f 22713//22713 20684//20684 22358//22358 -f 22713//22713 22358//22358 22714//22714 -f 22714//22714 22358//22358 22356//22356 -f 22714//22714 22356//22356 22715//22715 -f 22715//22715 22356//22356 22354//22354 -f 22715//22715 22354//22354 22716//22716 -f 22716//22716 22354//22354 22352//22352 -f 22716//22716 22352//22352 22717//22717 -f 22717//22717 22352//22352 22351//22351 -f 22717//22717 22351//22351 22718//22718 -f 22718//22718 22351//22351 22348//22348 -f 22348//22348 22347//22347 22718//22718 -f 22718//22718 22347//22347 22345//22345 -f 22718//22718 22345//22345 22719//22719 -f 22719//22719 22345//22345 22679//22679 -f 22679//22679 22345//22345 22339//22339 -f 22679//22679 22339//22339 22337//22337 -f 22324//22324 22720//22720 22336//22336 -f 22336//22336 22720//22720 22721//22721 -f 22336//22336 22721//22721 22679//22679 -f 22324//22324 22326//22326 22720//22720 -f 22720//22720 22326//22326 22328//22328 -f 22720//22720 22328//22328 22722//22722 -f 22722//22722 22328//22328 22723//22723 -f 22328//22328 22331//22331 22723//22723 -f 22723//22723 22331//22331 22333//22333 -f 22723//22723 22333//22333 22724//22724 -f 22724//22724 22333//22333 22309//22309 -f 22724//22724 22309//22309 22725//22725 -f 22725//22725 22309//22309 22678//22678 -f 22678//22678 22309//22309 22311//22311 -f 22678//22678 22311//22311 22313//22313 -f 22317//22317 22726//22726 22315//22315 -f 22315//22315 22726//22726 22727//22727 -f 22315//22315 22727//22727 22678//22678 -f 22317//22317 22319//22319 22726//22726 -f 22726//22726 22319//22319 22321//22321 -f 22726//22726 22321//22321 22728//22728 -f 22728//22728 22321//22321 22308//22308 -f 22728//22728 22308//22308 22729//22729 -f 22308//22308 22307//22307 22729//22729 -f 22729//22729 22307//22307 22305//22305 -f 22729//22729 22305//22305 22730//22730 -f 22730//22730 22305//22305 22303//22303 -f 22730//22730 22303//22303 22731//22731 -f 22731//22731 22303//22303 20814//20814 -f 22731//22731 20814//20814 22732//22732 -f 20814//20814 20816//20816 22732//22732 -f 22732//22732 20816//20816 20813//20813 -f 22732//22732 20813//20813 22733//22733 -f 22733//22733 20813//20813 22734//22734 -f 22734//22734 20813//20813 20811//20811 -f 22734//22734 20811//20811 22735//22735 -f 22735//22735 20811//20811 20810//20810 -f 22735//22735 20810//20810 22736//22736 -f 20810//20810 20808//20808 22736//22736 -f 22736//22736 20808//20808 20807//20807 -f 22736//22736 20807//20807 22737//22737 -f 22737//22737 20807//20807 20805//20805 -f 22737//22737 20805//20805 22738//22738 -f 20805//20805 20803//20803 22738//22738 -f 22738//22738 20803//20803 20802//20802 -f 22738//22738 20802//20802 22739//22739 -f 22739//22739 20802//20802 20800//20800 -f 20800//20800 20799//20799 22739//22739 -f 22739//22739 20799//20799 20797//20797 -f 22739//22739 20797//20797 22740//22740 -f 22740//22740 20797//20797 20795//20795 -f 20795//20795 20794//20794 22740//22740 -f 22740//22740 20794//20794 20782//20782 -f 22740//22740 20782//20782 22741//22741 -f 22741//22741 20782//20782 20784//20784 -f 22741//22741 20784//20784 22742//22742 -f 22742//22742 20784//20784 20786//20786 -f 20786//20786 20789//20789 22742//22742 -f 22742//22742 20789//20789 20791//20791 -f 22742//22742 20791//20791 22743//22743 -f 22743//22743 20791//20791 22744//22744 -f 20791//20791 20773//20773 22744//22744 -f 22744//22744 20773//20773 20775//20775 -f 22744//22744 20775//20775 22745//22745 -f 22745//22745 20775//20775 20777//20777 -f 22745//22745 20777//20777 22746//22746 -f 22746//22746 20777//20777 22677//22677 -f 22677//22677 20777//20777 20772//20772 -f 22677//22677 20772//20772 20770//20770 -f 20766//20766 22747//22747 20768//20768 -f 20768//20768 22747//22747 22748//22748 -f 20768//20768 22748//22748 22677//22677 -f 20766//20766 20765//20765 22747//22747 -f 22747//22747 20765//20765 20760//20760 -f 22747//22747 20760//20760 22749//22749 -f 22749//22749 20760//20760 20758//20758 -f 20762//20762 22750//22750 20763//20763 -f 20763//20763 22750//22750 22749//22749 -f 20763//20763 22749//22749 20764//20764 -f 20764//20764 22749//22749 20758//20758 -f 20752//20752 22751//22751 20753//20753 -f 20753//20753 22751//22751 22750//22750 -f 20753//20753 22750//22750 20755//20755 -f 20755//20755 22750//22750 20762//20762 -f 20752//20752 20745//20745 22751//22751 -f 22751//22751 20745//20745 20747//20747 -f 22751//22751 20747//20747 22752//22752 -f 20747//20747 20749//20749 22752//22752 -f 22752//22752 20749//20749 20751//20751 -f 22752//22752 20751//20751 22753//22753 -f 20751//20751 22416//22416 22753//22753 -f 22753//22753 22416//22416 22409//22409 -f 22753//22753 22409//22409 22754//22754 -f 22754//22754 22409//22409 22411//22411 -f 22754//22754 22411//22411 22755//22755 -f 22755//22755 22411//22411 22413//22413 -f 22755//22755 22413//22413 22756//22756 -f 22413//22413 22394//22394 22756//22756 -f 22756//22756 22394//22394 22396//22396 -f 22756//22756 22396//22396 22757//22757 -f 22757//22757 22396//22396 22398//22398 -f 22757//22757 22398//22398 22758//22758 -f 22398//22398 22400//22400 22758//22758 -f 22758//22758 22400//22400 22402//22402 -f 22758//22758 22402//22402 22759//22759 -f 22759//22759 22402//22402 22404//22404 -f 22759//22759 22404//22404 22760//22760 -f 22760//22760 22404//22404 22406//22406 -f 22760//22760 22406//22406 22676//22676 -f 22676//22676 22406//22406 22393//22393 -f 22676//22676 22393//22393 22392//22392 -f 22387//22387 22761//22761 22390//22390 -f 22390//22390 22761//22761 22762//22762 -f 22390//22390 22762//22762 22676//22676 -f 22387//22387 22385//22385 22761//22761 -f 22761//22761 22385//22385 22383//22383 -f 22761//22761 22383//22383 22763//22763 -f 22763//22763 22383//22383 22764//22764 -f 22764//22764 22383//22383 22373//22373 -f 22764//22764 22373//22373 22765//22765 -f 22765//22765 22373//22373 22376//22376 -f 22765//22765 22376//22376 22378//22378 -f 22372//22372 22766//22766 22378//22378 -f 22378//22378 22766//22766 22767//22767 -f 22378//22378 22767//22767 22765//22765 -f 22372//22372 22370//22370 22766//22766 -f 22766//22766 22370//22370 22368//22368 -f 22766//22766 22368//22368 22768//22768 -f 22768//22768 22368//22368 22769//22769 -f 22769//22769 22368//22368 22366//22366 -f 22769//22769 22366//22366 22770//22770 -f 22366//22366 22364//22364 22770//22770 -f 22770//22770 22364//22364 22362//22362 -f 22770//22770 22362//22362 22771//22771 -f 22771//22771 22362//22362 22772//22772 -f 22772//22772 22362//22362 22360//22360 -f 22772//22772 22360//22360 22773//22773 -f 22773//22773 22360//22360 20883//20883 -f 22773//22773 20883//20883 22774//22774 -f 20883//20883 20885//20885 22774//22774 -f 22774//22774 20885//20885 20879//20879 -f 22774//22774 20879//20879 22775//22775 -f 22775//22775 20879//20879 22776//22776 -f 22776//22776 20879//20879 20881//20881 -f 22776//22776 20881//20881 22777//22777 -f 22777//22777 20881//20881 20882//20882 -f 22777//22777 20882//20882 22778//22778 -f 22778//22778 20882//20882 20877//20877 -f 22778//22778 20877//20877 22779//22779 -f 22779//22779 20877//20877 20875//20875 -f 22779//22779 20875//20875 22780//22780 -f 22780//22780 20875//20875 20873//20873 -f 22780//22780 20873//20873 22781//22781 -f 22781//22781 20873//20873 20871//20871 -f 22781//22781 20871//20871 22782//22782 -f 22782//22782 20871//20871 20870//20870 -f 22782//22782 20870//20870 22783//22783 -f 22783//22783 20870//20870 20868//20868 -f 22783//22783 20868//20868 22784//22784 -f 22784//22784 20868//20868 20866//20866 -f 22784//22784 20866//20866 22785//22785 -f 22785//22785 20866//20866 20864//20864 -f 20864//20864 20863//20863 22785//22785 -f 22785//22785 20863//20863 20861//20861 -f 22785//22785 20861//20861 22786//22786 -f 22786//22786 20861//20861 20859//20859 -f 20859//20859 20858//20858 22786//22786 -f 22786//22786 20858//20858 20856//20856 -f 22786//22786 20856//20856 22787//22787 -f 22787//22787 20856//20856 20854//20854 -f 22787//22787 20854//20854 22788//22788 -f 22788//22788 20854//20854 20852//20852 -f 20852//20852 20850//20850 22788//22788 -f 22788//22788 20850//20850 20848//20848 -f 22788//22788 20848//20848 22789//22789 -f 22789//22789 20848//20848 22675//22675 -f 22675//22675 20848//20848 20846//20846 -f 22675//22675 20846//20846 20844//20844 -f 20839//20839 22790//22790 20841//20841 -f 20841//20841 22790//22790 22791//22791 -f 20841//20841 22791//22791 22675//22675 -f 20839//20839 20837//20837 22790//22790 -f 22790//22790 20837//20837 20834//20834 -f 22790//22790 20834//20834 22792//22792 -f 22792//22792 20834//20834 22793//22793 -f 20834//20834 20832//20832 22793//22793 -f 22793//22793 20832//20832 20831//20831 -f 22793//22793 20831//20831 22794//22794 -f 22794//22794 20831//20831 20829//20829 -f 22794//22794 20829//20829 22795//22795 -f 20829//20829 20827//20827 22795//22795 -f 22795//22795 20827//20827 20826//20826 -f 22795//22795 20826//20826 22796//22796 -f 22796//22796 20826//20826 20824//20824 -f 20824//20824 20823//20823 22796//22796 -f 22796//22796 20823//20823 20822//20822 -f 22796//22796 20822//20822 22797//22797 -f 20822//20822 20820//20820 22797//22797 -f 22797//22797 20820//20820 22432//22432 -f 22797//22797 22432//22432 22798//22798 -f 22798//22798 22432//22432 22430//22430 -f 22798//22798 22430//22430 22799//22799 -f 22799//22799 22430//22430 22428//22428 -f 22426//22426 22800//22800 22428//22428 -f 22428//22428 22800//22800 22801//22801 -f 22428//22428 22801//22801 22799//22799 -f 22426//22426 22424//22424 22800//22800 -f 22800//22800 22424//22424 22422//22422 -f 22800//22800 22422//22422 22802//22802 -f 22802//22802 22422//22422 22420//22420 -f 22802//22802 22420//22420 22803//22803 -f 22803//22803 22420//22420 22419//22419 -f 22803//22803 22419//22419 22804//22804 -f 22804//22804 22419//22419 22433//22433 -f 22433//22433 22435//22435 22804//22804 -f 22804//22804 22435//22435 22438//22438 -f 22804//22804 22438//22438 22805//22805 -f 22438//22438 22437//22437 22805//22805 -f 22805//22805 22437//22437 22436//22436 -f 22805//22805 22436//22436 22806//22806 -f 22806//22806 22436//22436 22439//22439 -f 22439//22439 22441//22441 22806//22806 -f 22806//22806 22441//22441 22444//22444 -f 22806//22806 22444//22444 22807//22807 -f 22444//22444 22443//22443 22807//22807 -f 22807//22807 22443//22443 22442//22442 -f 22807//22807 22442//22442 22808//22808 -f 22559//22559 22809//22809 22560//22560 -f 22560//22560 22809//22809 22810//22810 -f 22560//22560 22810//22810 22561//22561 -f 22561//22561 22810//22810 22808//22808 -f 22561//22561 22808//22808 22562//22562 -f 22562//22562 22808//22808 22442//22442 -f 22811//22811 22812//22812 22558//22558 -f 22558//22558 22812//22812 22813//22813 -f 22558//22558 22813//22813 22559//22559 -f 22559//22559 22813//22813 22814//22814 -f 22559//22559 22814//22814 22809//22809 -f 22558//22558 22627//22627 22811//22811 -f 22811//22811 22627//22627 22629//22629 -f 22811//22811 22629//22629 22815//22815 -f 22815//22815 22629//22629 22631//22631 -f 22815//22815 22631//22631 22816//22816 -f 22631//22631 22633//22633 22816//22816 -f 22816//22816 22633//22633 22635//22635 -f 22816//22816 22635//22635 22817//22817 -f 22635//22635 22637//22637 22817//22817 -f 22817//22817 22637//22637 22604//22604 -f 22817//22817 22604//22604 22818//22818 -f 22604//22604 22606//22606 22818//22818 -f 22818//22818 22606//22606 22608//22608 -f 22818//22818 22608//22608 22819//22819 -f 22819//22819 22608//22608 22611//22611 -f 22819//22819 22611//22611 22820//22820 -f 22820//22820 22611//22611 22613//22613 -f 22820//22820 22613//22613 22821//22821 -f 22821//22821 22613//22613 22642//22642 -f 22821//22821 22642//22642 22822//22822 -f 22822//22822 22642//22642 22644//22644 -f 22822//22822 22644//22644 22823//22823 -f 22644//22644 22646//22646 22823//22823 -f 22823//22823 22646//22646 22648//22648 -f 22823//22823 22648//22648 22674//22674 -f 22674//22674 22648//22648 22650//22650 -f 22674//22674 22650//22650 22652//22652 -f 22578//22578 20849//20849 22668//22668 -f 22668//22668 20849//20849 22665//22665 -f 20876//20876 22823//22823 20874//20874 -f 22369//22369 22811//22811 22815//22815 -f 22403//22403 22401//22401 22804//22804 -f 22804//22804 22401//22401 22803//22803 -f 20790//20790 22787//22787 20792//20792 -f 22310//22310 22335//22335 22764//22764 -f 22259//22259 22262//22262 22678//22678 -f 20623//20623 20625//20625 22704//22704 -f 20668//20668 22691//22691 20666//20666 -f 20666//20666 22691//22691 22692//22692 -f 20666//20666 22692//22692 20659//20659 -f 20659//20659 22692//22692 22693//22693 -f 20659//20659 22693//22693 20660//20660 -f 20660//20660 22693//22693 20662//20662 -f 20662//20662 22693//22693 22694//22694 -f 20662//20662 22694//22694 20663//20663 -f 22694//22694 22695//22695 20663//20663 -f 20663//20663 22695//22695 22696//22696 -f 20663//20663 22696//22696 20656//20656 -f 20656//20656 22696//22696 20658//20658 -f 20658//20658 22696//22696 22697//22697 -f 20658//20658 22697//22697 20653//20653 -f 20653//20653 22697//22697 20652//20652 -f 20652//20652 22697//22697 22698//22698 -f 20652//20652 22698//22698 20650//20650 -f 22699//22699 20637//20637 22698//22698 -f 22698//22698 20637//20637 20648//20648 -f 22698//22698 20648//20648 20650//20650 -f 20645//20645 20640//20640 22699//22699 -f 22699//22699 20640//20640 20638//20638 -f 22699//22699 20638//20638 20637//20637 -f 22699//22699 22700//22700 20645//20645 -f 20645//20645 22700//22700 22680//22680 -f 20645//20645 22680//22680 20644//20644 -f 22701//22701 20632//20632 22702//22702 -f 22702//22702 20632//20632 20634//20634 -f 22702//22702 20634//20634 22680//22680 -f 22680//22680 20634//20634 20636//20636 -f 22680//22680 20636//20636 20644//20644 -f 22704//22704 20625//20625 22703//22703 -f 22703//22703 20625//20625 20627//20627 -f 22703//22703 20627//20627 22701//22701 -f 22701//22701 20627//20627 20629//20629 -f 22701//22701 20629//20629 20632//20632 -f 20623//20623 22704//22704 20621//20621 -f 20621//20621 22704//22704 22705//22705 -f 20621//20621 22705//22705 20618//20618 -f 20618//20618 22705//22705 20616//20616 -f 20616//20616 22705//22705 22706//22706 -f 20616//20616 22706//22706 20614//20614 -f 22706//22706 22707//22707 20614//20614 -f 20614//20614 22707//22707 22708//22708 -f 20614//20614 22708//22708 20612//20612 -f 20612//20612 22708//22708 20610//20610 -f 20610//20610 22708//22708 22709//22709 -f 20610//20610 22709//22709 20608//20608 -f 20608//20608 22709//22709 22710//22710 -f 20608//20608 22710//22710 20605//20605 -f 22714//22714 20601//20601 22713//22713 -f 22713//22713 20601//20601 20603//20603 -f 22713//22713 20603//20603 22712//22712 -f 22712//22712 20603//20603 20605//20605 -f 22712//22712 20605//20605 22711//22711 -f 22711//22711 20605//20605 22710//22710 -f 22296//22296 22294//22294 22716//22716 -f 22716//22716 22294//22294 22292//22292 -f 22716//22716 22292//22292 22715//22715 -f 22715//22715 22292//22292 22290//22290 -f 22715//22715 22290//22290 22714//22714 -f 22714//22714 22290//22290 22288//22288 -f 22714//22714 22288//22288 20601//20601 -f 22296//22296 22716//22716 22298//22298 -f 22298//22298 22716//22716 22717//22717 -f 22298//22298 22717//22717 22300//22300 -f 22300//22300 22717//22717 22718//22718 -f 22300//22300 22718//22718 22301//22301 -f 22237//22237 22286//22286 22679//22679 -f 22679//22679 22286//22286 22285//22285 -f 22679//22679 22285//22285 22719//22719 -f 22719//22719 22285//22285 22283//22283 -f 22719//22719 22283//22283 22718//22718 -f 22718//22718 22283//22283 22281//22281 -f 22718//22718 22281//22281 22301//22301 -f 22237//22237 22679//22679 22276//22276 -f 22276//22276 22679//22679 22721//22721 -f 22276//22276 22721//22721 22278//22278 -f 22278//22278 22721//22721 22720//22720 -f 22278//22278 22720//22720 22279//22279 -f 22678//22678 22262//22262 22725//22725 -f 22725//22725 22262//22262 22263//22263 -f 22725//22725 22263//22263 22724//22724 -f 22724//22724 22263//22263 22266//22266 -f 22724//22724 22266//22266 22723//22723 -f 22723//22723 22266//22266 22268//22268 -f 22723//22723 22268//22268 22722//22722 -f 22722//22722 22268//22268 22270//22270 -f 22722//22722 22270//22270 22720//22720 -f 22720//22720 22270//22270 22272//22272 -f 22720//22720 22272//22272 22279//22279 -f 22259//22259 22678//22678 22257//22257 -f 22257//22257 22678//22678 22727//22727 -f 22257//22257 22727//22727 22255//22255 -f 22247//22247 22248//22248 22728//22728 -f 22728//22728 22248//22248 22250//22250 -f 22728//22728 22250//22250 22726//22726 -f 22726//22726 22250//22250 22252//22252 -f 22726//22726 22252//22252 22727//22727 -f 22727//22727 22252//22252 22254//22254 -f 22727//22727 22254//22254 22255//22255 -f 22247//22247 22728//22728 22245//22245 -f 22245//22245 22728//22728 22729//22729 -f 22245//22245 22729//22729 22243//22243 -f 22243//22243 22729//22729 22730//22730 -f 22243//22243 22730//22730 22242//22242 -f 22242//22242 22730//22730 22240//22240 -f 22240//22240 22730//22730 22731//22731 -f 22240//22240 22731//22731 22238//22238 -f 22732//22732 20740//20740 22731//22731 -f 22731//22731 20740//20740 20742//20742 -f 22731//22731 20742//20742 22238//22238 -f 20731//20731 20733//20733 22735//22735 -f 22735//22735 20733//20733 20738//20738 -f 22735//22735 20738//20738 22734//22734 -f 22734//22734 20738//20738 20740//20740 -f 22734//22734 20740//20740 22733//22733 -f 22733//22733 20740//20740 22732//22732 -f 22735//22735 22736//22736 20731//20731 -f 20731//20731 22736//22736 22737//22737 -f 20731//20731 22737//22737 20729//20729 -f 20729//20729 22737//22737 20726//20726 -f 20726//20726 22737//22737 22738//22738 -f 20726//20726 22738//22738 20724//20724 -f 20720//20720 20722//20722 22740//22740 -f 22740//22740 20722//20722 20724//20724 -f 22740//22740 20724//20724 22739//22739 -f 22739//22739 20724//20724 22738//22738 -f 20720//20720 22740//22740 20718//20718 -f 20718//20718 22740//22740 22741//22741 -f 20718//20718 22741//22741 20716//20716 -f 20716//20716 22741//22741 22742//22742 -f 20716//20716 22742//22742 20715//20715 -f 22744//22744 20710//20710 22743//22743 -f 22743//22743 20710//20710 20711//20711 -f 22743//22743 20711//20711 22742//22742 -f 22742//22742 20711//20711 20713//20713 -f 22742//22742 20713//20713 20715//20715 -f 20704//20704 20706//20706 22744//22744 -f 22744//22744 20706//20706 20708//20708 -f 22744//22744 20708//20708 20710//20710 -f 22744//22744 22745//22745 20704//20704 -f 20704//20704 22745//22745 22746//22746 -f 20704//20704 22746//22746 20702//20702 -f 20702//20702 22746//22746 20700//20700 -f 20700//20700 22746//22746 22677//22677 -f 20700//20700 22677//22677 20698//20698 -f 20698//20698 22677//22677 20696//20696 -f 20696//20696 22677//22677 22748//22748 -f 20696//20696 22748//22748 20671//20671 -f 22751//22751 20679//20679 22750//22750 -f 22750//22750 20679//20679 20677//20677 -f 22750//22750 20677//20677 22749//22749 -f 20677//20677 20675//20675 22749//22749 -f 22749//22749 20675//20675 20689//20689 -f 22749//22749 20689//20689 22747//22747 -f 22747//22747 20689//20689 20691//20691 -f 22747//22747 20691//20691 22748//22748 -f 22748//22748 20691//20691 20672//20672 -f 22748//22748 20672//20672 20671//20671 -f 22752//22752 20683//20683 22751//22751 -f 22751//22751 20683//20683 20681//20681 -f 22751//22751 20681//20681 20679//20679 -f 22357//22357 20686//20686 22752//22752 -f 22752//22752 20686//20686 20685//20685 -f 22752//22752 20685//20685 20683//20683 -f 22757//22757 22350//22350 22756//22756 -f 22756//22756 22350//22350 22353//22353 -f 22756//22756 22353//22353 22755//22755 -f 22755//22755 22353//22353 22355//22355 -f 22755//22755 22355//22355 22754//22754 -f 22754//22754 22355//22355 22357//22357 -f 22754//22754 22357//22357 22753//22753 -f 22753//22753 22357//22357 22752//22752 -f 22344//22344 22346//22346 22757//22757 -f 22757//22757 22346//22346 22349//22349 -f 22757//22757 22349//22349 22350//22350 -f 22757//22757 22758//22758 22344//22344 -f 22344//22344 22758//22758 22759//22759 -f 22344//22344 22759//22759 22340//22340 -f 22325//22325 22343//22343 22676//22676 -f 22676//22676 22343//22343 22342//22342 -f 22676//22676 22342//22342 22760//22760 -f 22760//22760 22342//22342 22341//22341 -f 22760//22760 22341//22341 22759//22759 -f 22759//22759 22341//22341 22338//22338 -f 22759//22759 22338//22338 22340//22340 -f 22325//22325 22676//22676 22327//22327 -f 22327//22327 22676//22676 22762//22762 -f 22327//22327 22762//22762 22329//22329 -f 22329//22329 22762//22762 22761//22761 -f 22329//22329 22761//22761 22330//22330 -f 22764//22764 22335//22335 22763//22763 -f 22763//22763 22335//22335 22334//22334 -f 22763//22763 22334//22334 22761//22761 -f 22761//22761 22334//22334 22332//22332 -f 22761//22761 22332//22332 22330//22330 -f 22310//22310 22764//22764 22312//22312 -f 22312//22312 22764//22764 22765//22765 -f 22312//22312 22765//22765 22314//22314 -f 22314//22314 22765//22765 22767//22767 -f 22314//22314 22767//22767 22316//22316 -f 22316//22316 22767//22767 22318//22318 -f 22318//22318 22767//22767 22766//22766 -f 22318//22318 22766//22766 22320//22320 -f 22320//22320 22766//22766 22322//22322 -f 22322//22322 22766//22766 22768//22768 -f 22322//22322 22768//22768 22323//22323 -f 22323//22323 22768//22768 22769//22769 -f 22323//22323 22769//22769 22306//22306 -f 22306//22306 22769//22769 22770//22770 -f 22306//22306 22770//22770 22304//22304 -f 22770//22770 22771//22771 22304//22304 -f 22304//22304 22771//22771 22772//22772 -f 22304//22304 22772//22772 22302//22302 -f 22302//22302 22772//22772 22773//22773 -f 22302//22302 22773//22773 20815//20815 -f 20815//20815 22773//22773 22774//22774 -f 20815//20815 22774//22774 20817//20817 -f 20817//20817 22774//22774 22775//22775 -f 20817//20817 22775//22775 20818//20818 -f 20818//20818 22775//22775 22776//22776 -f 20818//20818 22776//22776 20812//20812 -f 20812//20812 22776//22776 22777//22777 -f 20812//20812 22777//22777 20809//20809 -f 20809//20809 22777//22777 22778//22778 -f 20809//20809 22778//22778 20806//20806 -f 20806//20806 22778//22778 22779//22779 -f 20806//20806 22779//22779 22780//22780 -f 20798//20798 20801//20801 22780//22780 -f 22780//22780 20801//20801 20804//20804 -f 22780//22780 20804//20804 20806//20806 -f 22780//22780 22781//22781 20798//20798 -f 20798//20798 22781//22781 22782//22782 -f 20798//20798 22782//22782 20796//20796 -f 20796//20796 22782//22782 22783//22783 -f 20796//20796 22783//22783 20780//20780 -f 20780//20780 22783//22783 22784//22784 -f 20780//20780 22784//22784 20781//20781 -f 20781//20781 22784//22784 22785//22785 -f 20781//20781 22785//22785 20783//20783 -f 20783//20783 22785//22785 20785//20785 -f 20785//20785 22785//22785 22786//22786 -f 20785//20785 22786//22786 20787//20787 -f 22787//22787 20790//20790 22786//22786 -f 22786//22786 20790//20790 20788//20788 -f 22786//22786 20788//20788 20787//20787 -f 20792//20792 22787//22787 20793//20793 -f 20793//20793 22787//22787 22788//22788 -f 20793//20793 22788//22788 20774//20774 -f 20774//20774 22788//22788 22789//22789 -f 20774//20774 22789//22789 20776//20776 -f 20767//20767 20769//20769 22791//22791 -f 22791//22791 20769//20769 20771//20771 -f 22791//22791 20771//20771 22675//22675 -f 22675//22675 20771//20771 20779//20779 -f 22675//22675 20779//20779 22789//22789 -f 22789//22789 20779//20779 20778//20778 -f 22789//22789 20778//20778 20776//20776 -f 20767//20767 22791//22791 20761//20761 -f 20761//20761 22791//22791 22790//22790 -f 20761//20761 22790//22790 20759//20759 -f 20759//20759 22790//22790 22792//22792 -f 20759//20759 22792//22792 20757//20757 -f 20757//20757 22792//22792 20756//20756 -f 20756//20756 22792//22792 22793//22793 -f 20756//20756 22793//22793 20754//20754 -f 20754//20754 22793//22793 22794//22794 -f 20754//20754 22794//22794 20746//20746 -f 22797//22797 20748//20748 22796//22796 -f 22796//22796 20748//20748 20746//20746 -f 22796//22796 20746//20746 22795//22795 -f 22795//22795 20746//20746 22794//22794 -f 22418//22418 22417//22417 22797//22797 -f 22797//22797 22417//22417 20750//20750 -f 22797//22797 20750//20750 20748//20748 -f 22414//22414 22412//22412 22801//22801 -f 22801//22801 22412//22412 22410//22410 -f 22801//22801 22410//22410 22799//22799 -f 22799//22799 22410//22410 22418//22418 -f 22799//22799 22418//22418 22798//22798 -f 22798//22798 22418//22418 22797//22797 -f 22414//22414 22801//22801 22415//22415 -f 22415//22415 22801//22801 22800//22800 -f 22415//22415 22800//22800 22395//22395 -f 22395//22395 22800//22800 22802//22802 -f 22395//22395 22802//22802 22397//22397 -f 22803//22803 22401//22401 22802//22802 -f 22802//22802 22401//22401 22399//22399 -f 22802//22802 22399//22399 22397//22397 -f 22806//22806 22408//22408 22805//22805 -f 22805//22805 22408//22408 22407//22407 -f 22805//22805 22407//22407 22804//22804 -f 22804//22804 22407//22407 22405//22405 -f 22804//22804 22405//22405 22403//22403 -f 22382//22382 22384//22384 22810//22810 -f 22810//22810 22384//22384 22386//22386 -f 22810//22810 22386//22386 22808//22808 -f 22808//22808 22386//22386 22388//22388 -f 22808//22808 22388//22388 22807//22807 -f 22807//22807 22388//22388 22389//22389 -f 22807//22807 22389//22389 22806//22806 -f 22806//22806 22389//22389 22391//22391 -f 22806//22806 22391//22391 22408//22408 -f 22382//22382 22810//22810 22374//22374 -f 22374//22374 22810//22810 22809//22809 -f 22374//22374 22809//22809 22375//22375 -f 22814//22814 22379//22379 22809//22809 -f 22809//22809 22379//22379 22377//22377 -f 22809//22809 22377//22377 22375//22375 -f 22811//22811 22369//22369 22812//22812 -f 22812//22812 22369//22369 22371//22371 -f 22812//22812 22371//22371 22813//22813 -f 22813//22813 22371//22371 22381//22381 -f 22813//22813 22381//22381 22814//22814 -f 22814//22814 22381//22381 22380//22380 -f 22814//22814 22380//22380 22379//22379 -f 22361//22361 22363//22363 22816//22816 -f 22816//22816 22363//22363 22365//22365 -f 22816//22816 22365//22365 22815//22815 -f 22815//22815 22365//22365 22367//22367 -f 22815//22815 22367//22367 22369//22369 -f 22819//22819 22359//22359 22818//22818 -f 22818//22818 22359//22359 22361//22361 -f 22818//22818 22361//22361 22817//22817 -f 22817//22817 22361//22361 22816//22816 -f 22821//22821 20887//20887 22820//22820 -f 22820//22820 20887//20887 20886//20886 -f 22820//22820 20886//20886 22819//22819 -f 22819//22819 20886//20886 20884//20884 -f 22819//22819 20884//20884 22359//22359 -f 22823//22823 20876//20876 22822//22822 -f 22822//22822 20876//20876 20878//20878 -f 22822//22822 20878//20878 22821//22821 -f 22821//22821 20878//20878 20880//20880 -f 22821//22821 20880//20880 20887//20887 -f 22674//22674 20869//20869 22823//22823 -f 22823//22823 20869//20869 20872//20872 -f 22823//22823 20872//20872 20874//20874 -f 22674//22674 22673//22673 20869//20869 -f 20869//20869 22673//22673 22654//22654 -f 20869//20869 22654//22654 20867//20867 -f 20867//20867 22654//22654 20865//20865 -f 20865//20865 22654//22654 22655//22655 -f 20865//20865 22655//22655 20862//20862 -f 22655//22655 22656//22656 20862//20862 -f 20862//20862 22656//22656 22657//22657 -f 20862//20862 22657//22657 20860//20860 -f 20860//20860 22657//22657 22659//22659 -f 20860//20860 22659//22659 20857//20857 -f 20857//20857 22659//22659 20855//20855 -f 22659//22659 22661//22661 20855//20855 -f 20855//20855 22661//22661 22663//22663 -f 20855//20855 22663//22663 20853//20853 -f 20853//20853 22663//22663 22665//22665 -f 20853//20853 22665//22665 20851//20851 -f 20851//20851 22665//22665 20849//20849 -f 20840//20840 20842//20842 22614//22614 -f 22614//22614 20842//20842 20843//20843 -f 22614//22614 20843//20843 22577//22577 -f 22577//22577 20843//20843 20845//20845 -f 22577//22577 20845//20845 22578//22578 -f 22578//22578 20845//20845 20847//20847 -f 22578//22578 20847//20847 20849//20849 -f 22614//22614 22566//22566 20840//20840 -f 20840//20840 22566//22566 22565//22565 -f 20840//20840 22565//22565 20838//20838 -f 20838//20838 22565//22565 22617//22617 -f 20838//20838 22617//22617 20836//20836 -f 22177//22177 22687//22687 22174//22174 -f 22174//22174 22687//22687 22688//22688 -f 22174//22174 22688//22688 22172//22172 -f 22172//22172 22688//22688 22689//22689 -f 22172//22172 22689//22689 20668//20668 -f 20668//20668 22689//22689 22690//22690 -f 20668//20668 22690//22690 22691//22691 -f 22179//22179 22685//22685 22177//22177 -f 22177//22177 22685//22685 22686//22686 -f 22177//22177 22686//22686 22687//22687 -f 22179//22179 22181//22181 22685//22685 -f 22685//22685 22181//22181 22183//22183 -f 22685//22685 22183//22183 22684//22684 -f 22684//22684 22183//22183 22683//22683 -f 22183//22183 22185//22185 22683//22683 -f 22683//22683 22185//22185 22187//22187 -f 22683//22683 22187//22187 22682//22682 -f 22682//22682 22187//22187 22189//22189 -f 22682//22682 22189//22189 22681//22681 -f 22595//22595 22429//22429 22622//22622 -f 22622//22622 22429//22429 22431//22431 -f 22622//22622 22431//22431 22592//22592 -f 22592//22592 22431//22431 20819//20819 -f 22592//22592 20819//20819 22590//22590 -f 22590//22590 20819//20819 22587//22587 -f 22423//22423 22425//22425 22595//22595 -f 22595//22595 22425//22425 22427//22427 -f 22595//22595 22427//22427 22429//22429 -f 20819//20819 20821//20821 22587//22587 -f 22587//22587 20821//20821 20825//20825 -f 22587//22587 20825//20825 22585//22585 -f 22585//22585 20825//20825 20828//20828 -f 22585//22585 20828//20828 22580//22580 -f 22580//22580 20828//20828 20830//20830 -f 20830//20830 20833//20833 22580//22580 -f 22580//22580 20833//20833 20835//20835 -f 22580//22580 20835//20835 22582//22582 -f 22582//22582 20835//20835 20836//20836 -f 22582//22582 20836//20836 22617//22617 -f 22671//22671 22672//22672 22824//22824 -f 22824//22824 22672//22672 22653//22653 -f 22824//22824 22653//22653 22651//22651 -f 22647//22647 22645//22645 22825//22825 -f 22825//22825 22645//22645 22826//22826 -f 22825//22825 22826//22826 22827//22827 -f 22641//22641 22640//22640 22828//22828 -f 22828//22828 22640//22640 22829//22829 -f 22828//22828 22829//22829 22830//22830 -f 22610//22610 22609//22609 22831//22831 -f 22831//22831 22609//22609 22832//22832 -f 22831//22831 22832//22832 22833//22833 -f 22605//22605 22639//22639 22834//22834 -f 22834//22834 22639//22639 22835//22835 -f 22834//22834 22835//22835 22836//22836 -f 22636//22636 22634//22634 22837//22837 -f 22837//22837 22634//22634 22838//22838 -f 22837//22837 22838//22838 22839//22839 -f 22630//22630 22628//22628 22840//22840 -f 22840//22840 22628//22628 22841//22841 -f 22840//22840 22841//22841 22842//22842 -f 22625//22625 22575//22575 22843//22843 -f 22843//22843 22575//22575 22844//22844 -f 22843//22843 22844//22844 22845//22845 -f 22573//22573 22572//22572 22846//22846 -f 22846//22846 22572//22572 22847//22847 -f 22846//22846 22847//22847 22848//22848 -f 22569//22569 22568//22568 22849//22849 -f 22849//22849 22568//22568 22850//22850 -f 22849//22849 22850//22850 22851//22851 -f 22603//22603 22602//22602 22852//22852 -f 22852//22852 22602//22602 22853//22853 -f 22852//22852 22853//22853 22854//22854 -f 22563//22563 22564//22564 22855//22855 -f 22855//22855 22564//22564 22856//22856 -f 22855//22855 22856//22856 22857//22857 -f 22600//22600 22599//22599 22858//22858 -f 22858//22858 22599//22599 22859//22859 -f 22858//22858 22859//22859 22860//22860 -f 22597//22597 22598//22598 22861//22861 -f 22861//22861 22598//22598 22862//22862 -f 22861//22861 22862//22862 22863//22863 -f 22594//22594 22624//22624 22864//22864 -f 22864//22864 22624//22624 22865//22865 -f 22864//22864 22865//22865 22866//22866 -f 22621//22621 22620//22620 22867//22867 -f 22867//22867 22620//22620 22868//22868 -f 22867//22867 22868//22868 22869//22869 -f 22589//22589 22588//22588 22870//22870 -f 22870//22870 22588//22588 22871//22871 -f 22870//22870 22871//22871 22872//22872 -f 22584//22584 22583//22583 22873//22873 -f 22873//22873 22583//22583 22874//22874 -f 22873//22873 22874//22874 22875//22875 -f 22581//22581 22619//22619 22876//22876 -f 22876//22876 22619//22619 22877//22877 -f 22876//22876 22877//22877 22878//22878 -f 22567//22567 22616//22616 22879//22879 -f 22879//22879 22616//22616 22880//22880 -f 22879//22879 22880//22880 22881//22881 -f 22576//22576 22670//22670 22882//22882 -f 22882//22882 22670//22670 22883//22883 -f 22882//22882 22883//22883 22884//22884 -f 22667//22667 22666//22666 22885//22885 -f 22885//22885 22666//22666 22886//22886 -f 22885//22885 22886//22886 22887//22887 -f 22662//22662 22660//22660 22888//22888 -f 22888//22888 22660//22660 22889//22889 -f 22888//22888 22889//22889 22890//22890 -f 22651//22651 22649//22649 22824//22824 -f 22824//22824 22649//22649 22542//22542 -f 22824//22824 22542//22542 22671//22671 -f 22671//22671 22542//22542 22532//22532 -f 22660//22660 22658//22658 22889//22889 -f 22889//22889 22658//22658 22522//22522 -f 22889//22889 22522//22522 22890//22890 -f 22890//22890 22522//22522 22521//22521 -f 19231//19231 19230//19230 22891//22891 -f 22891//22891 19230//19230 22892//22892 -f 22891//22891 22892//22892 22893//22893 -f 22893//22893 22892//22892 22894//22894 -f 22894//22894 22892//22892 22895//22895 -f 22894//22894 22895//22895 22896//22896 -f 22897//22897 22898//22898 22899//22899 -f 22899//22899 22898//22898 22900//22900 -f 22899//22899 22900//22900 22895//22895 -f 22895//22895 22900//22900 22901//22901 -f 22895//22895 22901//22901 22896//22896 -f 22897//22897 22899//22899 22902//22902 -f 22902//22902 22899//22899 22903//22903 -f 22902//22902 22903//22903 22904//22904 -f 22905//22905 22906//22906 22907//22907 -f 22907//22907 22906//22906 22908//22908 -f 22907//22907 22908//22908 22903//22903 -f 22903//22903 22908//22908 22909//22909 -f 22903//22903 22909//22909 22904//22904 -f 22905//22905 22907//22907 22910//22910 -f 22910//22910 22907//22907 22911//22911 -f 22910//22910 22911//22911 22912//22912 -f 22913//22913 22914//22914 22915//22915 -f 22915//22915 22914//22914 22916//22916 -f 22915//22915 22916//22916 22911//22911 -f 22911//22911 22916//22916 22917//22917 -f 22911//22911 22917//22917 22912//22912 -f 20940//20940 22918//22918 22919//22919 -f 22919//22919 22918//22918 22920//22920 -f 22919//22919 22920//22920 22915//22915 -f 22915//22915 22920//22920 22921//22921 -f 22915//22915 22921//22921 22913//22913 -f 22827//22827 22524//22524 22825//22825 -f 22825//22825 22524//22524 22542//22542 -f 22825//22825 22542//22542 22647//22647 -f 22647//22647 22542//22542 22649//22649 -f 22890//22890 22521//22521 22888//22888 -f 22888//22888 22521//22521 22541//22541 -f 22888//22888 22541//22541 22662//22662 -f 22662//22662 22541//22541 22664//22664 -f 22922//22922 22273//22273 22271//22271 -f 22923//22923 22184//22184 22182//22182 -f 22924//22924 20540//20540 20538//20538 -f 22925//22925 20574//20574 20572//20572 -f 22926//22926 20588//20588 22927//22927 -f 22928//22928 22929//22929 22161//22161 -f 22161//22161 22929//22929 22163//22163 -f 22930//22930 20476//20476 20471//20471 -f 22931//22931 20487//20487 20485//20485 -f 22932//22932 22059//22059 22058//22058 -f 22933//22933 20413//20413 20411//20411 -f 22934//22934 20427//20427 20425//20425 -f 22934//22934 20425//20425 22935//22935 -f 22935//22935 20425//20425 20423//20423 -f 22935//22935 20423//20423 22936//22936 -f 22936//22936 20423//20423 20421//20421 -f 22936//22936 20421//20421 22937//22937 -f 22937//22937 20421//20421 20419//20419 -f 22937//22937 20419//20419 22938//22938 -f 22938//22938 20419//20419 20417//20417 -f 22938//22938 20417//20417 22933//22933 -f 22933//22933 20417//20417 20415//20415 -f 22933//22933 20415//20415 20413//20413 -f 22099//22099 22939//22939 22101//22101 -f 22101//22101 22939//22939 22940//22940 -f 22101//22101 22940//22940 22104//22104 -f 22104//22104 22940//22940 22941//22941 -f 22104//22104 22941//22941 22106//22106 -f 22106//22106 22941//22941 22942//22942 -f 22106//22106 22942//22942 22107//22107 -f 22107//22107 22942//22942 22943//22943 -f 22107//22107 22943//22943 22110//22110 -f 22110//22110 22943//22943 22944//22944 -f 22110//22110 22944//22944 22108//22108 -f 22108//22108 22944//22944 22945//22945 -f 22108//22108 22945//22945 20402//20402 -f 20402//20402 22945//22945 22946//22946 -f 20402//20402 22946//22946 20403//20403 -f 20403//20403 22946//22946 22947//22947 -f 20403//20403 22947//22947 20405//20405 -f 20405//20405 22947//22947 22948//22948 -f 20405//20405 22948//22948 20407//20407 -f 20407//20407 22948//22948 22949//22949 -f 20407//20407 22949//22949 20409//20409 -f 20409//20409 22949//22949 22950//22950 -f 20409//20409 22950//22950 20411//20411 -f 20411//20411 22950//22950 22951//22951 -f 20411//20411 22951//22951 22933//22933 -f 22099//22099 22097//22097 22939//22939 -f 22939//22939 22097//22097 22095//22095 -f 22939//22939 22095//22095 22952//22952 -f 22952//22952 22095//22095 22953//22953 -f 22953//22953 22095//22095 22093//22093 -f 22953//22953 22093//22093 22954//22954 -f 22093//22093 22091//22091 22954//22954 -f 22954//22954 22091//22091 22090//22090 -f 22954//22954 22090//22090 22955//22955 -f 22955//22955 22090//22090 22083//22083 -f 22955//22955 22083//22083 22956//22956 -f 22956//22956 22083//22083 22085//22085 -f 22956//22956 22085//22085 22957//22957 -f 22085//22085 22087//22087 22957//22957 -f 22957//22957 22087//22087 22080//22080 -f 22957//22957 22080//22080 22958//22958 -f 22080//22080 22078//22078 22958//22958 -f 22958//22958 22078//22078 22076//22076 -f 22958//22958 22076//22076 22959//22959 -f 22959//22959 22076//22076 22075//22075 -f 22959//22959 22075//22075 22960//22960 -f 22960//22960 22075//22075 22073//22073 -f 22960//22960 22073//22073 22961//22961 -f 22961//22961 22073//22073 22071//22071 -f 22961//22961 22071//22071 22962//22962 -f 22071//22071 22069//22069 22962//22962 -f 22962//22962 22069//22069 22067//22067 -f 22962//22962 22067//22067 22963//22963 -f 22963//22963 22067//22067 22964//22964 -f 22067//22067 22065//22065 22964//22964 -f 22964//22964 22065//22065 22063//22063 -f 22964//22964 22063//22063 22965//22965 -f 22965//22965 22063//22063 22061//22061 -f 22965//22965 22061//22061 22966//22966 -f 22966//22966 22061//22061 22967//22967 -f 22967//22967 22061//22061 22932//22932 -f 22932//22932 22061//22061 22052//22052 -f 22932//22932 22052//22052 22059//22059 -f 20513//20513 22968//22968 20515//20515 -f 20515//20515 22968//22968 22969//22969 -f 20515//20515 22969//22969 20529//20529 -f 20529//20529 22969//22969 22970//22970 -f 20529//20529 22970//22970 20530//20530 -f 20530//20530 22970//22970 22971//22971 -f 20530//20530 22971//22971 22056//22056 -f 22056//22056 22971//22971 22972//22972 -f 22056//22056 22972//22972 22058//22058 -f 22058//22058 22972//22972 22973//22973 -f 22058//22058 22973//22973 22932//22932 -f 20519//20519 22974//22974 20512//20512 -f 20512//20512 22974//22974 22975//22975 -f 20512//20512 22975//22975 20513//20513 -f 20513//20513 22975//22975 22976//22976 -f 20513//20513 22976//22976 22968//22968 -f 20511//20511 22977//22977 20525//20525 -f 20525//20525 22977//22977 22978//22978 -f 20525//20525 22978//22978 20523//20523 -f 20523//20523 22978//22978 22979//22979 -f 20523//20523 22979//22979 20521//20521 -f 20521//20521 22979//22979 22980//22980 -f 20521//20521 22980//22980 20519//20519 -f 20519//20519 22980//22980 22981//22981 -f 20519//20519 22981//22981 22974//22974 -f 20503//20503 22982//22982 20505//20505 -f 20505//20505 22982//22982 22983//22983 -f 20505//20505 22983//22983 20507//20507 -f 20507//20507 22983//22983 22984//22984 -f 20507//20507 22984//22984 20509//20509 -f 20509//20509 22984//22984 22985//22985 -f 20509//20509 22985//22985 20511//20511 -f 20511//20511 22985//22985 22986//22986 -f 20511//20511 22986//22986 22977//22977 -f 20503//20503 20501//20501 22982//22982 -f 22982//22982 20501//20501 20500//20500 -f 22982//22982 20500//20500 22987//22987 -f 22987//22987 20500//20500 20498//20498 -f 22987//22987 20498//20498 22988//22988 -f 22988//22988 20498//20498 20496//20496 -f 22988//22988 20496//20496 22989//22989 -f 22989//22989 20496//20496 20493//20493 -f 22989//22989 20493//20493 22990//22990 -f 22990//22990 20493//20493 20491//20491 -f 22990//22990 20491//20491 22931//22931 -f 22931//22931 20491//20491 20489//20489 -f 22931//22931 20489//20489 20487//20487 -f 20483//20483 22991//22991 20485//20485 -f 20485//20485 22991//22991 22992//22992 -f 20485//20485 22992//22992 22931//22931 -f 20478//20478 22993//22993 20480//20480 -f 20480//20480 22993//22993 22991//22991 -f 20480//20480 22991//22991 20481//20481 -f 20481//20481 22991//22991 20483//20483 -f 20476//20476 22930//22930 20473//20473 -f 20473//20473 22930//22930 22994//22994 -f 20473//20473 22994//22994 20478//20478 -f 20478//20478 22994//22994 22995//22995 -f 20478//20478 22995//22995 22993//22993 -f 22169//22169 22996//22996 22167//22167 -f 22167//22167 22996//22996 22997//22997 -f 22167//22167 22997//22997 20467//20467 -f 20467//20467 22997//22997 22998//22998 -f 20467//20467 22998//22998 20469//20469 -f 20469//20469 22998//22998 22999//22999 -f 20469//20469 22999//22999 20471//20471 -f 20471//20471 22999//22999 23000//23000 -f 20471//20471 23000//23000 22930//22930 -f 22163//22163 22929//22929 22165//22165 -f 22165//22165 22929//22929 23001//23001 -f 22165//22165 23001//23001 22166//22166 -f 22166//22166 23001//23001 23002//23002 -f 22166//22166 23002//23002 22169//22169 -f 22169//22169 23002//23002 23003//23003 -f 22169//22169 23003//23003 22996//22996 -f 22928//22928 22161//22161 23004//23004 -f 23004//23004 22161//22161 22159//22159 -f 23004//23004 22159//22159 23005//23005 -f 22159//22159 22157//22157 23005//23005 -f 23005//23005 22157//22157 22155//22155 -f 23005//23005 22155//22155 23006//23006 -f 23006//23006 22155//22155 22153//22153 -f 23006//23006 22153//22153 23007//23007 -f 23007//23007 22153//22153 22151//22151 -f 23007//23007 22151//22151 23008//23008 -f 23008//23008 22151//22151 22149//22149 -f 22147//22147 23009//23009 22149//22149 -f 22149//22149 23009//23009 23010//23010 -f 22149//22149 23010//23010 23008//23008 -f 22147//22147 22145//22145 23009//23009 -f 23009//23009 22145//22145 22143//22143 -f 23009//23009 22143//22143 23011//23011 -f 23011//23011 22143//22143 23012//23012 -f 22143//22143 22141//22141 23012//23012 -f 23012//23012 22141//22141 22139//22139 -f 23012//23012 22139//22139 23013//23013 -f 23013//23013 22139//22139 22137//22137 -f 23013//23013 22137//22137 23014//23014 -f 23014//23014 22137//22137 23015//23015 -f 22137//22137 22135//22135 23015//23015 -f 23015//23015 22135//22135 22132//22132 -f 23015//23015 22132//22132 23016//23016 -f 23016//23016 22132//22132 22130//22130 -f 23016//23016 22130//22130 23017//23017 -f 23017//23017 22130//22130 23018//23018 -f 23018//23018 22130//22130 22128//22128 -f 23018//23018 22128//22128 23019//23019 -f 22128//22128 22126//22126 23019//23019 -f 23019//23019 22126//22126 22124//22124 -f 23019//23019 22124//22124 23020//23020 -f 23020//23020 22124//22124 22122//22122 -f 20592//20592 23021//23021 20595//20595 -f 20595//20595 23021//23021 23022//23022 -f 20595//20595 23022//23022 20597//20597 -f 20597//20597 23022//23022 23023//23023 -f 20597//20597 23023//23023 20599//20599 -f 20599//20599 23023//23023 23024//23024 -f 20599//20599 23024//23024 22114//22114 -f 22114//22114 23024//23024 23025//23025 -f 22114//22114 23025//23025 22116//22116 -f 22116//22116 23025//23025 23026//23026 -f 22116//22116 23026//23026 22119//22119 -f 22119//22119 23026//23026 23027//23027 -f 22119//22119 23027//23027 22120//22120 -f 22120//22120 23027//23027 23028//23028 -f 22120//22120 23028//23028 22122//22122 -f 22122//22122 23028//23028 23029//23029 -f 22122//22122 23029//23029 23020//23020 -f 20588//20588 22926//22926 20590//20590 -f 20590//20590 22926//22926 23030//23030 -f 20590//20590 23030//23030 20592//20592 -f 20592//20592 23030//23030 23031//23031 -f 20592//20592 23031//23031 23021//23021 -f 20588//20588 20586//20586 22927//22927 -f 22927//22927 20586//20586 20583//20583 -f 22927//22927 20583//20583 23032//23032 -f 20583//20583 20581//20581 23032//23032 -f 23032//23032 20581//20581 20579//20579 -f 23032//23032 20579//20579 23033//23033 -f 23033//23033 20579//20579 22925//22925 -f 22925//22925 20579//20579 20577//20577 -f 22925//22925 20577//20577 20574//20574 -f 23034//23034 23035//23035 20565//20565 -f 20565//20565 23035//23035 23036//23036 -f 20565//20565 23036//23036 20567//20567 -f 20567//20567 23036//23036 23037//23037 -f 20567//20567 23037//23037 20570//20570 -f 20570//20570 23037//23037 23038//23038 -f 20570//20570 23038//23038 20572//20572 -f 20572//20572 23038//23038 23039//23039 -f 20572//20572 23039//23039 22925//22925 -f 20565//20565 20563//20563 23034//23034 -f 23034//23034 20563//20563 20561//20561 -f 23034//23034 20561//20561 23040//23040 -f 23040//23040 20561//20561 20559//20559 -f 23040//23040 20559//20559 23041//23041 -f 23041//23041 20559//20559 20557//20557 -f 23041//23041 20557//20557 23042//23042 -f 23042//23042 20557//20557 20555//20555 -f 23042//23042 20555//20555 23043//23043 -f 23043//23043 20555//20555 20553//20553 -f 23043//23043 20553//20553 23044//23044 -f 23044//23044 20553//20553 20551//20551 -f 23044//23044 20551//20551 23045//23045 -f 23045//23045 20551//20551 23046//23046 -f 23046//23046 20551//20551 20549//20549 -f 23046//23046 20549//20549 23047//23047 -f 20549//20549 20547//20547 23047//23047 -f 23047//23047 20547//20547 20545//20545 -f 23047//23047 20545//20545 23048//23048 -f 23048//23048 20545//20545 22924//22924 -f 22924//22924 20545//20545 20542//20542 -f 22924//22924 20542//20542 20540//20540 -f 20537//20537 23049//23049 20538//20538 -f 20538//20538 23049//23049 23050//23050 -f 20538//20538 23050//23050 22924//22924 -f 23051//23051 23052//23052 22229//22229 -f 22229//22229 23052//23052 23053//23053 -f 22229//22229 23053//23053 22227//22227 -f 22227//22227 23053//23053 23054//23054 -f 22227//22227 23054//23054 20533//20533 -f 20533//20533 23054//23054 23049//23049 -f 20533//20533 23049//23049 20535//20535 -f 20535//20535 23049//23049 20537//20537 -f 22229//22229 22231//22231 23051//23051 -f 23051//23051 22231//22231 22201//22201 -f 23051//23051 22201//22201 23055//23055 -f 23055//23055 22201//22201 22203//22203 -f 23055//23055 22203//22203 23056//23056 -f 23056//23056 22203//22203 22205//22205 -f 23056//23056 22205//22205 23057//23057 -f 23057//23057 22205//22205 22207//22207 -f 23057//23057 22207//22207 23058//23058 -f 23058//23058 22207//22207 23059//23059 -f 22207//22207 22209//22209 23059//23059 -f 23059//23059 22209//22209 22211//22211 -f 23059//23059 22211//22211 23060//23060 -f 23060//23060 22211//22211 23061//23061 -f 23061//23061 22211//22211 22213//22213 -f 23061//23061 22213//22213 23062//23062 -f 22213//22213 22215//22215 23062//23062 -f 23062//23062 22215//22215 22217//22217 -f 23062//23062 22217//22217 23063//23063 -f 23063//23063 22217//22217 22219//22219 -f 23063//23063 22219//22219 23064//23064 -f 23064//23064 22219//22219 22221//22221 -f 23064//23064 22221//22221 23065//23065 -f 23065//23065 22221//22221 22223//22223 -f 23065//23065 22223//22223 23066//23066 -f 23066//23066 22223//22223 22224//22224 -f 23066//23066 22224//22224 22199//22199 -f 22199//22199 22197//22197 23066//23066 -f 23066//23066 22197//22197 22196//22196 -f 23066//23066 22196//22196 23067//23067 -f 23067//23067 22196//22196 22194//22194 -f 23067//23067 22194//22194 23068//23068 -f 23068//23068 22194//22194 23069//23069 -f 22194//22194 22192//22192 23069//23069 -f 23069//23069 22192//22192 22190//22190 -f 23069//23069 22190//22190 23070//23070 -f 23070//23070 22190//22190 22188//22188 -f 23070//23070 22188//22188 22923//22923 -f 22923//22923 22188//22188 22186//22186 -f 22923//22923 22186//22186 22184//22184 -f 22180//22180 23071//23071 22182//22182 -f 22182//22182 23071//23071 23072//23072 -f 22182//22182 23072//23072 22923//22923 -f 22180//22180 22178//22178 23071//23071 -f 23071//23071 22178//22178 22176//22176 -f 23071//23071 22176//22176 23073//23073 -f 23073//23073 22176//22176 23074//23074 -f 23074//23074 22176//22176 22175//22175 -f 23074//23074 22175//22175 23075//23075 -f 23075//23075 22175//22175 22173//22173 -f 23075//23075 22173//22173 23076//23076 -f 23076//23076 22173//22173 20670//20670 -f 23076//23076 20670//20670 23077//23077 -f 20670//20670 20669//20669 23077//23077 -f 23077//23077 20669//20669 20667//20667 -f 23077//23077 20667//20667 23078//23078 -f 23078//23078 20667//20667 20665//20665 -f 23078//23078 20665//20665 23079//23079 -f 23079//23079 20665//20665 20664//20664 -f 23079//23079 20664//20664 23080//23080 -f 23080//23080 20664//20664 20661//20661 -f 23080//23080 20661//20661 23081//23081 -f 23081//23081 20661//20661 20655//20655 -f 23081//23081 20655//20655 23082//23082 -f 23082//23082 20655//20655 20654//20654 -f 23082//23082 20654//20654 23083//23083 -f 23083//23083 20654//20654 20657//20657 -f 23083//23083 20657//20657 23084//23084 -f 20657//20657 20651//20651 23084//23084 -f 23084//23084 20651//20651 20649//20649 -f 23084//23084 20649//20649 23085//23085 -f 23085//23085 20649//20649 20647//20647 -f 20647//20647 20646//20646 23085//23085 -f 23085//23085 20646//20646 20639//20639 -f 23085//23085 20639//20639 23086//23086 -f 23086//23086 20639//20639 20641//20641 -f 23086//23086 20641//20641 23087//23087 -f 23087//23087 20641//20641 20643//20643 -f 20633//20633 23088//23088 20635//20635 -f 20635//20635 23088//23088 23087//23087 -f 20635//20635 23087//23087 20642//20642 -f 20642//20642 23087//23087 20643//20643 -f 20631//20631 23089//23089 20633//20633 -f 20633//20633 23089//23089 23090//23090 -f 20633//20633 23090//23090 23088//23088 -f 20631//20631 20630//20630 23089//23089 -f 23089//23089 20630//20630 20628//20628 -f 23089//23089 20628//20628 23091//23091 -f 23091//23091 20628//20628 20626//20626 -f 23091//23091 20626//20626 23092//23092 -f 23092//23092 20626//20626 20624//20624 -f 20624//20624 20622//20622 23092//23092 -f 23092//23092 20622//20622 20620//20620 -f 23092//23092 20620//20620 23093//23093 -f 23093//23093 20620//20620 20619//20619 -f 23093//23093 20619//20619 23094//23094 -f 23094//23094 20619//20619 20617//20617 -f 20617//20617 20615//20615 23094//23094 -f 23094//23094 20615//20615 20613//20613 -f 23094//23094 20613//20613 23095//23095 -f 23095//23095 20613//20613 20611//20611 -f 23095//23095 20611//20611 23096//23096 -f 23096//23096 20611//20611 20609//20609 -f 23096//23096 20609//20609 23097//23097 -f 20604//20604 23098//23098 20606//20606 -f 20606//20606 23098//23098 23097//23097 -f 20606//20606 23097//23097 20607//20607 -f 20607//20607 23097//23097 20609//20609 -f 20602//20602 23099//23099 20604//20604 -f 20604//20604 23099//23099 23100//23100 -f 20604//20604 23100//23100 23098//23098 -f 20602//20602 22234//22234 23099//23099 -f 23099//23099 22234//22234 22287//22287 -f 23099//23099 22287//22287 23101//23101 -f 22297//22297 23102//23102 22295//22295 -f 22295//22295 23102//23102 23103//23103 -f 22295//22295 23103//23103 22293//22293 -f 22293//22293 23103//23103 23104//23104 -f 22293//22293 23104//23104 22291//22291 -f 22291//22291 23104//23104 23101//23101 -f 22291//22291 23101//23101 22289//22289 -f 22289//22289 23101//23101 22287//22287 -f 22297//22297 22299//22299 23102//23102 -f 23102//23102 22299//22299 22280//22280 -f 23102//23102 22280//22280 23105//23105 -f 23105//23105 22280//22280 22282//22282 -f 23105//23105 22282//22282 23106//23106 -f 23106//23106 22282//22282 23107//23107 -f 23107//23107 22282//22282 22284//22284 -f 23107//23107 22284//22284 23108//23108 -f 22284//22284 22236//22236 23108//23108 -f 23108//23108 22236//22236 22235//22235 -f 23108//23108 22235//22235 23109//23109 -f 23109//23109 22235//22235 22275//22275 -f 23109//23109 22275//22275 23110//23110 -f 23110//23110 22275//22275 22277//22277 -f 23110//23110 22277//22277 23111//23111 -f 23111//23111 22277//22277 22922//22922 -f 22922//22922 22277//22277 22274//22274 -f 22922//22922 22274//22274 22273//22273 -f 22261//22261 23112//23112 22264//22264 -f 22264//22264 23112//23112 23113//23113 -f 22264//22264 23113//23113 22265//22265 -f 22265//22265 23113//23113 23114//23114 -f 22265//22265 23114//23114 22267//22267 -f 22267//22267 23114//23114 23115//23115 -f 22267//22267 23115//23115 22269//22269 -f 22269//22269 23115//23115 23116//23116 -f 22269//22269 23116//23116 22271//22271 -f 22271//22271 23116//23116 23117//23117 -f 22271//22271 23117//23117 22922//22922 -f 22261//22261 22260//22260 23112//23112 -f 23112//23112 22260//22260 22258//22258 -f 23112//23112 22258//22258 22681//22681 -f 22645//22645 22643//22643 22826//22826 -f 22826//22826 22643//22643 22543//22543 -f 22826//22826 22543//22543 22827//22827 -f 22827//22827 22543//22543 22524//22524 -f 22666//22666 22664//22664 22886//22886 -f 22886//22886 22664//22664 22541//22541 -f 22886//22886 22541//22541 22887//22887 -f 22887//22887 22541//22541 22540//22540 -f 22954//22954 22955//22955 22025//22025 -f 22970//22970 22969//22969 20460//20460 -f 22974//22974 22981//22981 20465//20465 -f 22990//22990 20426//20426 20428//20428 -f 22930//22930 23000//23000 20408//20408 -f 22088//22088 23011//23011 22089//22089 -f 22089//22089 23011//23011 22079//22079 -f 23039//23039 20504//20504 20506//20506 -f 20504//20504 23039//23039 23038//23038 -f 23082//23082 20587//20587 20589//20589 -f 20568//20568 23090//23090 20566//20566 -f 20566//20566 23090//23090 20564//20564 -f 23112//23112 22681//22681 22189//22189 -f 22189//22189 22191//22191 23112//23112 -f 23112//23112 22191//22191 22193//22193 -f 23112//23112 22193//22193 23113//23113 -f 23113//23113 22193//22193 22195//22195 -f 23113//23113 22195//22195 23114//23114 -f 23114//23114 22195//22195 23115//23115 -f 23115//23115 22195//22195 22198//22198 -f 23115//23115 22198//22198 23116//23116 -f 22198//22198 22200//22200 23116//23116 -f 23116//23116 22200//22200 22222//22222 -f 23116//23116 22222//22222 23117//23117 -f 23117//23117 22222//22222 22922//22922 -f 22922//22922 22222//22222 22220//22220 -f 22922//22922 22220//22220 23111//23111 -f 22220//22220 22218//22218 23111//23111 -f 23111//23111 22218//22218 22216//22216 -f 23111//23111 22216//22216 23110//23110 -f 23110//23110 22216//22216 22214//22214 -f 23110//23110 22214//22214 23109//23109 -f 23109//23109 22214//22214 23108//23108 -f 23108//23108 22214//22214 22212//22212 -f 23108//23108 22212//22212 23107//23107 -f 22232//22232 23104//23104 22233//22233 -f 22233//22233 23104//23104 23103//23103 -f 22233//22233 23103//23103 22202//22202 -f 22202//22202 23103//23103 23102//23102 -f 22202//22202 23102//23102 22204//22204 -f 22204//22204 23102//23102 23105//23105 -f 22204//22204 23105//23105 22206//22206 -f 22206//22206 23105//23105 23106//23106 -f 22206//22206 23106//23106 22208//22208 -f 22208//22208 23106//23106 23107//23107 -f 22208//22208 23107//23107 22210//22210 -f 22210//22210 23107//23107 22212//22212 -f 22232//22232 22230//22230 23104//23104 -f 23104//23104 22230//22230 22228//22228 -f 23104//23104 22228//22228 23101//23101 -f 23101//23101 22228//22228 22226//22226 -f 23101//23101 22226//22226 23099//23099 -f 22226//22226 22225//22225 23099//23099 -f 23099//23099 22225//22225 20532//20532 -f 23099//23099 20532//20532 23100//23100 -f 20532//20532 20531//20531 23100//23100 -f 23100//23100 20531//20531 20534//20534 -f 23100//23100 20534//20534 23098//23098 -f 23098//23098 20534//20534 20536//20536 -f 23098//23098 20536//20536 20539//20539 -f 20541//20541 23096//23096 20539//20539 -f 20539//20539 23096//23096 23097//23097 -f 20539//20539 23097//23097 23098//23098 -f 20541//20541 20543//20543 23096//23096 -f 23096//23096 20543//20543 20544//20544 -f 23096//23096 20544//20544 23095//23095 -f 23095//23095 20544//20544 20546//20546 -f 23095//23095 20546//20546 23094//23094 -f 23094//23094 20546//20546 20548//20548 -f 20548//20548 20550//20550 23094//23094 -f 23094//23094 20550//20550 20552//20552 -f 23094//23094 20552//20552 23093//23093 -f 23093//23093 20552//20552 20554//20554 -f 23093//23093 20554//20554 23092//23092 -f 23092//23092 20554//20554 20556//20556 -f 23092//23092 20556//20556 23091//23091 -f 20556//20556 20558//20558 23091//23091 -f 23091//23091 20558//20558 20560//20560 -f 23091//23091 20560//20560 23089//23089 -f 23089//23089 20560//20560 23090//23090 -f 23090//23090 20560//20560 20562//20562 -f 23090//23090 20562//20562 20564//20564 -f 20569//20569 23087//23087 20568//20568 -f 20568//20568 23087//23087 23088//23088 -f 20568//20568 23088//23088 23090//23090 -f 20569//20569 20571//20571 23087//23087 -f 23087//23087 20571//20571 20573//20573 -f 23087//23087 20573//20573 23086//23086 -f 23086//23086 20573//20573 20575//20575 -f 23086//23086 20575//20575 23085//23085 -f 23085//23085 20575//20575 20576//20576 -f 20576//20576 20578//20578 23085//23085 -f 23085//23085 20578//20578 20580//20580 -f 23085//23085 20580//20580 23084//23084 -f 23084//23084 20580//20580 20582//20582 -f 23084//23084 20582//20582 23083//23083 -f 23083//23083 20582//20582 20584//20584 -f 23083//23083 20584//20584 23082//23082 -f 23082//23082 20584//20584 20585//20585 -f 23082//23082 20585//20585 20587//20587 -f 20591//20591 23080//23080 20589//20589 -f 20589//20589 23080//23080 23081//23081 -f 20589//20589 23081//23081 23082//23082 -f 20591//20591 20593//20593 23080//23080 -f 23080//23080 20593//20593 20594//20594 -f 23080//23080 20594//20594 23079//23079 -f 23079//23079 20594//20594 20596//20596 -f 23079//23079 20596//20596 23078//23078 -f 23078//23078 20596//20596 20598//20598 -f 23078//23078 20598//20598 23077//23077 -f 23077//23077 20598//20598 23076//23076 -f 23076//23076 20598//20598 20600//20600 -f 23076//23076 20600//20600 23075//23075 -f 20600//20600 22113//22113 23075//23075 -f 23075//23075 22113//22113 22115//22115 -f 23075//23075 22115//22115 23074//23074 -f 23074//23074 22115//22115 22117//22117 -f 23074//23074 22117//22117 23073//23073 -f 23073//23073 22117//22117 22118//22118 -f 23073//23073 22118//22118 23071//23071 -f 23071//23071 22118//22118 22121//22121 -f 23071//23071 22121//22121 23072//23072 -f 23072//23072 22121//22121 22123//22123 -f 23072//23072 22123//22123 22923//22923 -f 22123//22123 22125//22125 22923//22923 -f 22923//22923 22125//22125 22127//22127 -f 22923//22923 22127//22127 23070//23070 -f 22127//22127 22129//22129 23070//23070 -f 23070//23070 22129//22129 22131//22131 -f 23070//23070 22131//22131 23069//23069 -f 23069//23069 22131//22131 22133//22133 -f 23069//23069 22133//22133 23068//23068 -f 23068//23068 22133//22133 22134//22134 -f 22134//22134 22136//22136 23068//23068 -f 23068//23068 22136//22136 22138//22138 -f 23068//23068 22138//22138 23067//23067 -f 23067//23067 22138//22138 23066//23066 -f 22138//22138 22140//22140 23066//23066 -f 23066//23066 22140//22140 22142//22142 -f 23066//23066 22142//22142 23065//23065 -f 23065//23065 22142//22142 22144//22144 -f 23065//23065 22144//22144 23064//23064 -f 23064//23064 22144//22144 23063//23063 -f 23063//23063 22144//22144 22146//22146 -f 23063//23063 22146//22146 23062//23062 -f 22146//22146 22148//22148 23062//23062 -f 23062//23062 22148//22148 22150//22150 -f 23062//23062 22150//22150 23061//23061 -f 23061//23061 22150//22150 22152//22152 -f 23061//23061 22152//22152 23060//23060 -f 22152//22152 22154//22154 23060//23060 -f 23060//23060 22154//22154 22156//22156 -f 23060//23060 22156//22156 23059//23059 -f 23059//23059 22156//22156 23058//23058 -f 23058//23058 22156//22156 22158//22158 -f 23058//23058 22158//22158 23057//23057 -f 22158//22158 22160//22160 23057//23057 -f 23057//23057 22160//22160 22162//22162 -f 23057//23057 22162//22162 23056//23056 -f 22164//22164 23051//23051 22162//22162 -f 22162//22162 23051//23051 23055//23055 -f 22162//22162 23055//23055 23056//23056 -f 23053//23053 23052//23052 22170//22170 -f 22170//22170 23052//23052 23051//23051 -f 22170//22170 23051//23051 22171//22171 -f 22171//22171 23051//23051 22164//22164 -f 22170//22170 22168//22168 23053//23053 -f 23053//23053 22168//22168 20466//20466 -f 23053//23053 20466//20466 23054//23054 -f 23054//23054 20466//20466 20468//20468 -f 23054//23054 20468//20468 23049//23049 -f 23049//23049 20468//20468 20470//20470 -f 23049//23049 20470//20470 23050//23050 -f 23050//23050 20470//20470 20472//20472 -f 23050//23050 20472//20472 22924//22924 -f 20472//20472 20475//20475 22924//22924 -f 22924//22924 20475//20475 20474//20474 -f 22924//22924 20474//20474 23048//23048 -f 23048//23048 20474//20474 20477//20477 -f 23048//23048 20477//20477 23047//23047 -f 23047//23047 20477//20477 20479//20479 -f 23047//23047 20479//20479 23046//23046 -f 23046//23046 20479//20479 20482//20482 -f 23046//23046 20482//20482 23045//23045 -f 23045//23045 20482//20482 20484//20484 -f 20486//20486 23043//23043 20484//20484 -f 20484//20484 23043//23043 23044//23044 -f 20484//20484 23044//23044 23045//23045 -f 20488//20488 23041//23041 20486//20486 -f 20486//20486 23041//23041 23042//23042 -f 20486//20486 23042//23042 23043//23043 -f 20488//20488 20490//20490 23041//23041 -f 23041//23041 20490//20490 20492//20492 -f 23041//23041 20492//20492 23040//23040 -f 23040//23040 20492//20492 20494//20494 -f 23040//23040 20494//20494 23034//23034 -f 23034//23034 20494//20494 20495//20495 -f 23034//23034 20495//20495 23035//23035 -f 23035//23035 20495//20495 20497//20497 -f 23035//23035 20497//20497 23036//23036 -f 23036//23036 20497//20497 23037//23037 -f 23037//23037 20497//20497 20499//20499 -f 23037//23037 20499//20499 23038//23038 -f 23038//23038 20499//20499 20502//20502 -f 23038//23038 20502//20502 20504//20504 -f 20508//20508 23033//23033 20506//20506 -f 20506//20506 23033//23033 22925//22925 -f 20506//20506 22925//22925 23039//23039 -f 20508//20508 20510//20510 23033//23033 -f 23033//23033 20510//20510 20527//20527 -f 23033//23033 20527//20527 23032//23032 -f 23032//23032 20527//20527 20526//20526 -f 23032//23032 20526//20526 22927//22927 -f 22927//22927 20526//20526 20524//20524 -f 20524//20524 20522//20522 22927//22927 -f 22927//22927 20522//20522 20520//20520 -f 22927//22927 20520//20520 22926//22926 -f 22926//22926 20520//20520 23030//23030 -f 23030//23030 20520//20520 20518//20518 -f 23030//23030 20518//20518 23031//23031 -f 23023//23023 23022//23022 20516//20516 -f 20516//20516 23022//23022 23021//23021 -f 20516//20516 23021//23021 20514//20514 -f 20514//20514 23021//23021 23031//23031 -f 20514//20514 23031//23031 20517//20517 -f 20517//20517 23031//23031 20518//20518 -f 20516//20516 20528//20528 23023//23023 -f 23023//23023 20528//20528 22055//22055 -f 23023//23023 22055//22055 23024//23024 -f 23024//23024 22055//22055 23025//23025 -f 23025//23025 22055//22055 22057//22057 -f 23025//23025 22057//22057 23026//23026 -f 23026//23026 22057//22057 23027//23027 -f 23027//23027 22057//22057 22054//22054 -f 23027//23027 22054//22054 23028//23028 -f 23028//23028 22054//22054 22053//22053 -f 23028//23028 22053//22053 23029//23029 -f 23029//23029 22053//22053 22060//22060 -f 23029//23029 22060//22060 23020//23020 -f 23020//23020 22060//22060 22062//22062 -f 23020//23020 22062//22062 23019//23019 -f 23019//23019 22062//22062 23018//23018 -f 23018//23018 22062//22062 22064//22064 -f 23018//23018 22064//22064 23017//23017 -f 23017//23017 22064//22064 22066//22066 -f 23017//23017 22066//22066 23016//23016 -f 23016//23016 22066//22066 22068//22068 -f 23016//23016 22068//22068 23015//23015 -f 23015//23015 22068//22068 22070//22070 -f 23015//23015 22070//22070 22072//22072 -f 22079//22079 23011//23011 22077//22077 -f 22077//22077 23011//23011 23012//23012 -f 22077//22077 23012//23012 22074//22074 -f 22074//22074 23012//23012 23013//23013 -f 22074//22074 23013//23013 22072//22072 -f 22072//22072 23013//23013 23014//23014 -f 22072//22072 23014//23014 23015//23015 -f 22086//22086 23010//23010 22088//22088 -f 22088//22088 23010//23010 23009//23009 -f 22088//22088 23009//23009 23011//23011 -f 22081//22081 23008//23008 22082//22082 -f 22082//22082 23008//23008 23010//23010 -f 22082//22082 23010//23010 22084//22084 -f 22084//22084 23010//23010 22086//22086 -f 22092//22092 23006//23006 22081//22081 -f 22081//22081 23006//23006 23007//23007 -f 22081//22081 23007//23007 23008//23008 -f 22092//22092 22094//22094 23006//23006 -f 23006//23006 22094//22094 22096//22096 -f 23006//23006 22096//22096 23005//23005 -f 23005//23005 22096//22096 23004//23004 -f 23004//23004 22096//22096 22098//22098 -f 23004//23004 22098//22098 22928//22928 -f 22098//22098 22100//22100 22928//22928 -f 22928//22928 22100//22100 22102//22102 -f 22928//22928 22102//22102 22929//22929 -f 22929//22929 22102//22102 22103//22103 -f 22929//22929 22103//22103 23001//23001 -f 23001//23001 22103//22103 22105//22105 -f 23001//23001 22105//22105 23002//23002 -f 20401//20401 22996//22996 22109//22109 -f 22109//22109 22996//22996 23003//23003 -f 22109//22109 23003//23003 22111//22111 -f 22111//22111 23003//23003 23002//23002 -f 22111//22111 23002//23002 22112//22112 -f 22112//22112 23002//23002 22105//22105 -f 20408//20408 23000//23000 20406//20406 -f 20406//20406 23000//23000 22999//22999 -f 20406//20406 22999//22999 20404//20404 -f 20404//20404 22999//22999 22998//22998 -f 20404//20404 22998//22998 20401//20401 -f 20401//20401 22998//22998 22997//22997 -f 20401//20401 22997//22997 22996//22996 -f 22930//22930 20408//20408 22994//22994 -f 22994//22994 20408//20408 20410//20410 -f 22994//22994 20410//20410 22995//22995 -f 22995//22995 20410//20410 20412//20412 -f 22995//22995 20412//20412 22993//22993 -f 22993//22993 20412//20412 20414//20414 -f 22993//22993 20414//20414 22991//22991 -f 22991//22991 20414//20414 20416//20416 -f 22991//22991 20416//20416 22992//22992 -f 20416//20416 20418//20418 22992//22992 -f 22992//22992 20418//20418 20420//20420 -f 22992//22992 20420//20420 22931//22931 -f 22931//22931 20420//20420 20422//20422 -f 22931//22931 20422//20422 22990//22990 -f 22990//22990 20422//20422 20424//20424 -f 22990//22990 20424//20424 20426//20426 -f 20430//20430 22988//22988 20428//20428 -f 20428//20428 22988//22988 22989//22989 -f 20428//20428 22989//22989 22990//22990 -f 20430//20430 20432//20432 22988//22988 -f 22988//22988 20432//20432 20435//20435 -f 22988//22988 20435//20435 22987//22987 -f 22987//22987 20435//20435 22982//22982 -f 20435//20435 20437//20437 22982//22982 -f 22982//22982 20437//20437 20439//20439 -f 22982//22982 20439//20439 22983//22983 -f 22983//22983 20439//20439 20441//20441 -f 22983//22983 20441//20441 22984//22984 -f 22984//22984 20441//20441 22985//22985 -f 22985//22985 20441//20441 20443//20443 -f 22985//22985 20443//20443 22986//22986 -f 22978//22978 22977//22977 20447//20447 -f 20447//20447 22977//22977 22986//22986 -f 20447//20447 22986//22986 20445//20445 -f 20445//20445 22986//22986 20443//20443 -f 22978//22978 20447//20447 22979//22979 -f 22979//22979 20447//20447 20449//20449 -f 22979//22979 20449//20449 22980//22980 -f 20449//20449 20451//20451 22980//22980 -f 22980//22980 20451//20451 20453//20453 -f 22980//22980 20453//20453 22981//22981 -f 22981//22981 20453//20453 20455//20455 -f 22981//22981 20455//20455 20465//20465 -f 22974//22974 20465//20465 22975//22975 -f 22975//22975 20465//20465 20464//20464 -f 22975//22975 20464//20464 22976//22976 -f 22976//22976 20464//20464 22968//22968 -f 22968//22968 20464//20464 20462//20462 -f 22968//22968 20462//20462 22969//22969 -f 22969//22969 20462//20462 20461//20461 -f 22969//22969 20461//20461 20460//20460 -f 22970//22970 20460//20460 22971//22971 -f 22971//22971 20460//20460 21987//21987 -f 22971//22971 21987//21987 22972//22972 -f 22972//22972 21987//21987 21986//21986 -f 22972//22972 21986//21986 22973//22973 -f 22973//22973 21986//21986 22932//22932 -f 22932//22932 21986//21986 21992//21992 -f 22932//22932 21992//21992 22967//22967 -f 22967//22967 21992//21992 21995//21995 -f 22967//22967 21995//21995 22966//22966 -f 22966//22966 21995//21995 21996//21996 -f 22966//22966 21996//21996 22965//22965 -f 22965//22965 21996//21996 21999//21999 -f 22965//22965 21999//21999 22964//22964 -f 22964//22964 21999//21999 22963//22963 -f 22963//22963 21999//21999 22001//22001 -f 22963//22963 22001//22001 22003//22003 -f 22961//22961 22962//22962 22006//22006 -f 22006//22006 22962//22962 22963//22963 -f 22006//22006 22963//22963 22004//22004 -f 22004//22004 22963//22963 22003//22003 -f 22006//22006 22009//22009 22961//22961 -f 22961//22961 22009//22009 22011//22011 -f 22961//22961 22011//22011 22960//22960 -f 22960//22960 22011//22011 22013//22013 -f 22960//22960 22013//22013 22959//22959 -f 22959//22959 22013//22013 22958//22958 -f 22013//22013 22015//22015 22958//22958 -f 22958//22958 22015//22015 22017//22017 -f 22958//22958 22017//22017 22957//22957 -f 22957//22957 22017//22017 22019//22019 -f 22957//22957 22019//22019 22956//22956 -f 22956//22956 22019//22019 22021//22021 -f 22956//22956 22021//22021 22955//22955 -f 22955//22955 22021//22021 22023//22023 -f 22955//22955 22023//22023 22025//22025 -f 22954//22954 22025//22025 22953//22953 -f 22953//22953 22025//22025 22027//22027 -f 22953//22953 22027//22027 22952//22952 -f 22027//22027 22029//22029 22952//22952 -f 22952//22952 22029//22029 22031//22031 -f 22952//22952 22031//22031 22939//22939 -f 22939//22939 22031//22031 22034//22034 -f 22939//22939 22034//22034 22940//22940 -f 22940//22940 22034//22034 22036//22036 -f 22940//22940 22036//22036 22038//22038 -f 22040//22040 22942//22942 22038//22038 -f 22038//22038 22942//22942 22941//22941 -f 22038//22038 22941//22941 22940//22940 -f 22040//22040 22042//22042 22942//22942 -f 22942//22942 22042//22042 22044//22044 -f 22942//22942 22044//22044 22943//22943 -f 22044//22044 22046//22046 22943//22943 -f 22943//22943 22046//22046 22048//22048 -f 22943//22943 22048//22048 22944//22944 -f 22944//22944 22048//22048 22050//22050 -f 22944//22944 22050//22050 22945//22945 -f 22945//22945 22050//22050 20338//20338 -f 22945//22945 20338//20338 20336//20336 -f 20334//20334 22947//22947 20336//20336 -f 20336//20336 22947//22947 22946//22946 -f 20336//20336 22946//22946 22945//22945 -f 22950//22950 22949//22949 20334//20334 -f 20334//20334 22949//22949 22948//22948 -f 20334//20334 22948//22948 22947//22947 -f 20334//20334 20341//20341 22950//22950 -f 22950//22950 20341//20341 20343//20343 -f 22950//22950 20343//20343 22951//22951 -f 22951//22951 20343//20343 20345//20345 -f 22951//22951 20345//20345 20347//20347 -f 20355//20355 22935//22935 20353//20353 -f 20353//20353 22935//22935 22936//22936 -f 20353//20353 22936//22936 20351//20351 -f 20351//20351 22936//22936 22937//22937 -f 20351//20351 22937//22937 20349//20349 -f 20349//20349 22937//22937 22938//22938 -f 20349//20349 22938//22938 20347//20347 -f 20347//20347 22938//22938 22933//22933 -f 20347//20347 22933//22933 22951//22951 -f 20355//20355 20357//20357 22935//22935 -f 22935//22935 20357//20357 20359//20359 -f 22935//22935 20359//20359 22934//22934 -f 22830//22830 22513//22513 22828//22828 -f 22828//22828 22513//22513 22543//22543 -f 22828//22828 22543//22543 22641//22641 -f 22641//22641 22543//22543 22643//22643 -f 22887//22887 22540//22540 22885//22885 -f 22885//22885 22540//22540 22539//22539 -f 22885//22885 22539//22539 22667//22667 -f 22667//22667 22539//22539 22669//22669 -f 22640//22640 22612//22612 22829//22829 -f 22829//22829 22612//22612 22514//22514 -f 22829//22829 22514//22514 22830//22830 -f 22830//22830 22514//22514 22513//22513 -f 22670//22670 22669//22669 22883//22883 -f 22883//22883 22669//22669 22539//22539 -f 22883//22883 22539//22539 22884//22884 -f 22884//22884 22539//22539 22530//22530 -f 20262//20262 23118//23118 21796//21796 -f 20229//20229 20227//20227 23119//23119 -f 20208//20208 23120//23120 23121//23121 -f 20289//20289 20286//20286 23122//23122 -f 20344//20344 20342//20342 23123//23123 -f 22032//22032 23124//23124 23125//23125 -f 23126//23126 23127//23127 22026//22026 -f 21988//21988 21989//21989 23128//23128 -f 20429//20429 22934//22934 23129//23129 -f 22934//22934 20429//20429 20427//20427 -f 23130//23130 20438//20438 20436//20436 -f 23130//23130 20436//20436 23131//23131 -f 23131//23131 20436//20436 20434//20434 -f 23131//23131 20434//20434 23132//23132 -f 23132//23132 20434//20434 20433//20433 -f 23132//23132 20433//20433 23129//23129 -f 23129//23129 20433//20433 20431//20431 -f 23129//23129 20431//20431 20429//20429 -f 23130//23130 23133//23133 20438//20438 -f 20438//20438 23133//23133 23134//23134 -f 20438//20438 23134//23134 20440//20440 -f 23134//23134 23135//23135 20440//20440 -f 20440//20440 23135//23135 23136//23136 -f 20440//20440 23136//23136 20442//20442 -f 20442//20442 23136//23136 23137//23137 -f 20442//20442 23137//23137 23138//23138 -f 23139//23139 20448//20448 23140//23140 -f 23140//23140 20448//20448 20446//20446 -f 23140//23140 20446//20446 23138//23138 -f 23138//23138 20446//20446 20444//20444 -f 23138//23138 20444//20444 20442//20442 -f 23139//23139 23141//23141 20448//20448 -f 20448//20448 23141//23141 23142//23142 -f 20448//20448 23142//23142 20450//20450 -f 20450//20450 23142//23142 23143//23143 -f 20450//20450 23143//23143 20452//20452 -f 23143//23143 23144//23144 20452//20452 -f 20452//20452 23144//23144 23145//23145 -f 20452//20452 23145//23145 20454//20454 -f 20454//20454 23145//23145 23146//23146 -f 20454//20454 23146//23146 23147//23147 -f 23148//23148 20463//20463 23149//23149 -f 23149//23149 20463//20463 20457//20457 -f 23149//23149 20457//20457 23147//23147 -f 23147//23147 20457//20457 20456//20456 -f 23147//23147 20456//20456 20454//20454 -f 23148//23148 23150//23150 20463//20463 -f 20463//20463 23150//23150 23151//23151 -f 20463//20463 23151//23151 20458//20458 -f 23151//23151 23152//23152 20458//20458 -f 20458//20458 23152//23152 23153//23153 -f 20458//20458 23153//23153 20459//20459 -f 20459//20459 23153//23153 23154//23154 -f 23154//23154 23155//23155 20459//20459 -f 20459//20459 23155//23155 23156//23156 -f 20459//20459 23156//23156 21989//21989 -f 21989//21989 23156//23156 23157//23157 -f 21989//21989 23157//23157 23128//23128 -f 21988//21988 23128//23128 21990//21990 -f 21990//21990 23128//23128 23158//23158 -f 21990//21990 23158//23158 21991//21991 -f 21991//21991 23158//23158 23159//23159 -f 21991//21991 23159//23159 21993//21993 -f 21993//21993 23159//23159 23160//23160 -f 21993//21993 23160//23160 21994//21994 -f 23160//23160 23161//23161 21994//21994 -f 21994//21994 23161//23161 23162//23162 -f 21994//21994 23162//23162 21997//21997 -f 21997//21997 23162//23162 23163//23163 -f 21997//21997 23163//23163 23164//23164 -f 23165//23165 23166//23166 22005//22005 -f 22005//22005 22002//22002 23165//23165 -f 23165//23165 22002//22002 22000//22000 -f 23165//23165 22000//22000 23164//23164 -f 23164//23164 22000//22000 21998//21998 -f 23164//23164 21998//21998 21997//21997 -f 23167//23167 22012//22012 23168//23168 -f 23168//23168 22012//22012 22010//22010 -f 23168//23168 22010//22010 23169//23169 -f 23169//23169 22010//22010 22008//22008 -f 23169//23169 22008//22008 23166//23166 -f 23166//23166 22008//22008 22007//22007 -f 23166//23166 22007//22007 22005//22005 -f 23170//23170 22018//22018 23171//23171 -f 23171//23171 22018//22018 22016//22016 -f 23171//23171 22016//22016 23167//23167 -f 23167//23167 22016//22016 22014//22014 -f 23167//23167 22014//22014 22012//22012 -f 23170//23170 23172//23172 22018//22018 -f 22018//22018 23172//23172 23173//23173 -f 22018//22018 23173//23173 22020//22020 -f 22020//22020 23173//23173 22022//22022 -f 22022//22022 23173//23173 23174//23174 -f 22022//22022 23174//23174 22024//22024 -f 23126//23126 22026//22026 23175//23175 -f 23174//23174 23176//23176 22024//22024 -f 22024//22024 23176//23176 23177//23177 -f 22024//22024 23177//23177 22026//22026 -f 22026//22026 23177//23177 23178//23178 -f 22026//22026 23178//23178 23175//23175 -f 23124//23124 22032//22032 23179//23179 -f 23179//23179 22032//22032 22030//22030 -f 23179//23179 22030//22030 23127//23127 -f 23127//23127 22030//22030 22028//22028 -f 23127//23127 22028//22028 22026//22026 -f 22037//22037 22035//22035 23125//23125 -f 23125//23125 22035//22035 22033//22033 -f 23125//23125 22033//22033 22032//22032 -f 23125//23125 23180//23180 22037//22037 -f 22037//22037 23180//23180 23181//23181 -f 22037//22037 23181//23181 22039//22039 -f 22039//22039 23181//23181 23182//23182 -f 22039//22039 23182//23182 22041//22041 -f 22041//22041 23182//23182 23183//23183 -f 22041//22041 23183//23183 22043//22043 -f 22043//22043 23183//23183 23184//23184 -f 22043//22043 23184//23184 22045//22045 -f 22045//22045 23184//23184 22047//22047 -f 22047//22047 23184//23184 23185//23185 -f 22047//22047 23185//23185 22049//22049 -f 23185//23185 23186//23186 22049//22049 -f 22049//22049 23186//23186 23187//23187 -f 22049//22049 23187//23187 22051//22051 -f 23187//23187 23188//23188 22051//22051 -f 22051//22051 23188//23188 23189//23189 -f 22051//22051 23189//23189 20337//20337 -f 20337//20337 23189//23189 20335//20335 -f 20335//20335 23189//23189 23190//23190 -f 20335//20335 23190//23190 20333//20333 -f 20333//20333 23190//23190 20339//20339 -f 20339//20339 23190//23190 23191//23191 -f 20339//20339 23191//23191 20340//20340 -f 23191//23191 23192//23192 20340//20340 -f 20340//20340 23192//23192 23193//23193 -f 20340//20340 23193//23193 20342//20342 -f 20342//20342 23193//23193 23194//23194 -f 20342//20342 23194//23194 23123//23123 -f 20344//20344 23123//23123 20346//20346 -f 20346//20346 23123//23123 23195//23195 -f 20346//20346 23195//23195 20348//20348 -f 20348//20348 23195//23195 23196//23196 -f 20348//20348 23196//23196 20350//20350 -f 20350//20350 23196//23196 23197//23197 -f 20350//20350 23197//23197 20352//20352 -f 23197//23197 23198//23198 20352//20352 -f 20352//20352 23198//23198 23199//23199 -f 20352//20352 23199//23199 20354//20354 -f 20354//20354 23199//23199 23200//23200 -f 20354//20354 23200//23200 20356//20356 -f 20356//20356 23200//23200 23201//23201 -f 20356//20356 23201//23201 20358//20358 -f 23201//23201 23202//23202 20358//20358 -f 20358//20358 23202//23202 23203//23203 -f 20358//20358 23203//23203 20360//20360 -f 20360//20360 23203//23203 20362//20362 -f 20362//20362 23203//23203 23204//23204 -f 20362//20362 23204//23204 20364//20364 -f 23205//23205 20368//20368 23204//23204 -f 23204//23204 20368//20368 20366//20366 -f 23204//23204 20366//20366 20364//20364 -f 23205//23205 23206//23206 20368//20368 -f 20368//20368 23206//23206 23207//23207 -f 20368//20368 23207//23207 20370//20370 -f 20370//20370 23207//23207 23208//23208 -f 20370//20370 23208//23208 20372//20372 -f 23208//23208 23209//23209 20372//20372 -f 20372//20372 23209//23209 23210//23210 -f 20372//20372 23210//23210 20374//20374 -f 20374//20374 23210//23210 23211//23211 -f 20374//20374 23211//23211 20377//20377 -f 20377//20377 23211//23211 23212//23212 -f 20377//20377 23212//23212 20379//20379 -f 20379//20379 23212//23212 23213//23213 -f 20379//20379 23213//23213 20381//20381 -f 23213//23213 23214//23214 20381//20381 -f 20381//20381 23214//23214 23215//23215 -f 20381//20381 23215//23215 23216//23216 -f 23216//23216 23217//23217 20381//20381 -f 20381//20381 23217//23217 23218//23218 -f 20381//20381 23218//23218 20383//20383 -f 20383//20383 23218//23218 20385//20385 -f 23218//23218 23219//23219 20385//20385 -f 20385//20385 23219//23219 23220//23220 -f 20385//20385 23220//23220 20387//20387 -f 20387//20387 23220//23220 23221//23221 -f 20387//20387 23221//23221 20389//20389 -f 20389//20389 23221//23221 23222//23222 -f 20389//20389 23222//23222 20390//20390 -f 20390//20390 23222//23222 23223//23223 -f 20390//20390 23223//23223 20392//20392 -f 23223//23223 23224//23224 20392//20392 -f 20392//20392 23224//23224 23225//23225 -f 20392//20392 23225//23225 20394//20394 -f 23225//23225 23226//23226 20394//20394 -f 20394//20394 23226//23226 23227//23227 -f 20394//20394 23227//23227 20400//20400 -f 20400//20400 23227//23227 23228//23228 -f 20400//20400 23228//23228 20399//20399 -f 20399//20399 23228//23228 23229//23229 -f 20399//20399 23229//23229 20397//20397 -f 23229//23229 23230//23230 20397//20397 -f 20397//20397 23230//23230 23231//23231 -f 20397//20397 23231//23231 21923//21923 -f 21923//21923 23231//23231 23232//23232 -f 21923//21923 23232//23232 21925//21925 -f 21925//21925 23232//23232 23233//23233 -f 21925//21925 23233//23233 21928//21928 -f 21939//21939 21938//21938 23234//23234 -f 23234//23234 21938//21938 23235//23235 -f 23235//23235 21938//21938 21936//21936 -f 23235//23235 21936//21936 23236//23236 -f 23236//23236 21936//21936 21934//21934 -f 23236//23236 21934//21934 23237//23237 -f 23237//23237 21934//21934 21932//21932 -f 23237//23237 21932//21932 23238//23238 -f 23238//23238 21932//21932 21931//21931 -f 23238//23238 21931//21931 23233//23233 -f 23233//23233 21931//21931 21929//21929 -f 23233//23233 21929//21929 21928//21928 -f 23239//23239 21948//21948 23240//23240 -f 23240//23240 21948//21948 21946//21946 -f 23240//23240 21946//21946 23241//23241 -f 23234//23234 23242//23242 21939//21939 -f 21939//21939 23242//23242 23243//23243 -f 21939//21939 23243//23243 21941//21941 -f 21941//21941 23243//23243 23244//23244 -f 21941//21941 23244//23244 21943//21943 -f 21943//21943 23244//23244 23241//23241 -f 21943//21943 23241//23241 21944//21944 -f 21944//21944 23241//23241 21946//21946 -f 23239//23239 23245//23245 21948//21948 -f 21948//21948 23245//23245 23246//23246 -f 21948//21948 23246//23246 21950//21950 -f 23246//23246 23247//23247 21950//21950 -f 21950//21950 23247//23247 23248//23248 -f 21950//21950 23248//23248 21952//21952 -f 21952//21952 23248//23248 23249//23249 -f 21952//21952 23249//23249 21954//21954 -f 21954//21954 23249//23249 23250//23250 -f 21954//21954 23250//23250 21956//21956 -f 21956//21956 23250//23250 21958//21958 -f 21958//21958 23250//23250 23251//23251 -f 21958//21958 23251//23251 21960//21960 -f 23251//23251 23252//23252 21960//21960 -f 21960//21960 23252//23252 23253//23253 -f 21960//21960 23253//23253 21966//21966 -f 23253//23253 23254//23254 21966//21966 -f 21966//21966 23254//23254 23255//23255 -f 21966//21966 23255//23255 21968//21968 -f 21968//21968 23255//23255 21970//21970 -f 23255//23255 23256//23256 21970//21970 -f 21970//21970 23256//23256 23257//23257 -f 21970//21970 23257//23257 21971//21971 -f 21971//21971 23257//23257 23258//23258 -f 21971//21971 23258//23258 21964//21964 -f 21964//21964 23258//23258 23259//23259 -f 21964//21964 23259//23259 21972//21972 -f 21972//21972 23259//23259 23260//23260 -f 21972//21972 23260//23260 21973//21973 -f 21973//21973 23260//23260 23261//23261 -f 21973//21973 23261//23261 21975//21975 -f 21975//21975 23261//23261 23262//23262 -f 21975//21975 23262//23262 21977//21977 -f 21977//21977 23262//23262 23263//23263 -f 23263//23263 23264//23264 21977//21977 -f 21977//21977 23264//23264 23265//23265 -f 21977//21977 23265//23265 21979//21979 -f 21979//21979 23265//23265 23266//23266 -f 21979//21979 23266//23266 21981//21981 -f 23266//23266 23267//23267 21981//21981 -f 21981//21981 23267//23267 23268//23268 -f 21981//21981 23268//23268 21983//21983 -f 23268//23268 23269//23269 21983//21983 -f 21983//21983 23269//23269 23270//23270 -f 21983//21983 23270//23270 21985//21985 -f 21985//21985 23270//23270 23271//23271 -f 21985//21985 23271//23271 20265//20265 -f 20265//20265 23271//23271 23272//23272 -f 20265//20265 23272//23272 23273//23273 -f 20271//20271 20269//20269 23273//23273 -f 23273//23273 20269//20269 20267//20267 -f 23273//23273 20267//20267 20265//20265 -f 23273//23273 23274//23274 20271//20271 -f 20271//20271 23274//23274 23275//23275 -f 20271//20271 23275//23275 20273//20273 -f 20273//20273 23275//23275 23276//23276 -f 20273//20273 23276//23276 20275//20275 -f 20275//20275 23276//23276 20278//20278 -f 23276//23276 23277//23277 20278//20278 -f 20278//20278 23277//23277 23278//23278 -f 20278//20278 23278//23278 20280//20280 -f 20280//20280 23278//23278 23279//23279 -f 20280//20280 23279//23279 20282//20282 -f 20282//20282 23279//23279 23280//23280 -f 20282//20282 23280//23280 20284//20284 -f 20284//20284 23280//23280 23281//23281 -f 20284//20284 23281//23281 23282//23282 -f 23282//23282 23283//23283 20284//20284 -f 20284//20284 23283//23283 23284//23284 -f 20284//20284 23284//23284 20286//20286 -f 20286//20286 23284//23284 23285//23285 -f 20286//20286 23285//23285 23122//23122 -f 20296//20296 20294//20294 23286//23286 -f 23286//23286 20294//20294 20292//20292 -f 23286//23286 20292//20292 23122//23122 -f 23122//23122 20292//20292 20291//20291 -f 23122//23122 20291//20291 20289//20289 -f 20296//20296 23286//23286 20298//20298 -f 20298//20298 23286//23286 23287//23287 -f 20298//20298 23287//23287 23288//23288 -f 23288//23288 23289//23289 20298//20298 -f 20298//20298 23289//23289 23290//23290 -f 20298//20298 23290//23290 20300//20300 -f 20300//20300 23290//23290 20302//20302 -f 20302//20302 23290//23290 23291//23291 -f 20302//20302 23291//23291 20304//20304 -f 20304//20304 23291//23291 23292//23292 -f 20304//20304 23292//23292 23293//23293 -f 23294//23294 20312//20312 23295//23295 -f 23295//23295 20312//20312 20310//20310 -f 23295//23295 20310//20310 23296//23296 -f 23296//23296 20310//20310 20308//20308 -f 23296//23296 20308//20308 23293//23293 -f 23293//23293 20308//20308 20306//20306 -f 23293//23293 20306//20306 20304//20304 -f 23294//23294 23297//23297 20312//20312 -f 20312//20312 23297//23297 23298//23298 -f 20312//20312 23298//23298 20313//20313 -f 20319//20319 20318//20318 23298//23298 -f 23298//23298 20318//20318 20315//20315 -f 23298//23298 20315//20315 20313//20313 -f 23298//23298 23299//23299 20319//20319 -f 20319//20319 23299//23299 23300//23300 -f 20319//20319 23300//23300 20321//20321 -f 20321//20321 23300//23300 23301//23301 -f 20321//20321 23301//23301 20322//20322 -f 23302//23302 23303//23303 20331//20331 -f 20331//20331 20330//20330 23302//23302 -f 23302//23302 20330//20330 20326//20326 -f 23302//23302 20326//20326 23304//23304 -f 23304//23304 20326//20326 20328//20328 -f 23304//23304 20328//20328 23305//23305 -f 23305//23305 20328//20328 20329//20329 -f 23305//23305 20329//20329 23306//23306 -f 23306//23306 20329//20329 20324//20324 -f 23306//23306 20324//20324 23301//23301 -f 23301//23301 20324//20324 20322//20322 -f 23303//23303 23307//23307 20331//20331 -f 20331//20331 23307//23307 23308//23308 -f 20331//20331 23308//23308 21860//21860 -f 23309//23309 21868//21868 23310//23310 -f 23310//23310 21868//21868 21862//21862 -f 23310//23310 21862//21862 23311//23311 -f 23311//23311 21862//21862 21860//21860 -f 23311//23311 21860//21860 23312//23312 -f 23312//23312 21860//21860 23308//23308 -f 21867//21867 21871//21871 23309//23309 -f 23309//23309 21871//21871 21869//21869 -f 23309//23309 21869//21869 21868//21868 -f 23313//23313 21877//21877 23314//23314 -f 23314//23314 21877//21877 21875//21875 -f 23314//23314 21875//21875 23315//23315 -f 23315//23315 21875//21875 21874//21874 -f 23315//23315 21874//21874 23316//23316 -f 23316//23316 21874//21874 21866//21866 -f 23316//23316 21866//21866 23317//23317 -f 23317//23317 21866//21866 21867//21867 -f 23317//23317 21867//21867 23318//23318 -f 23318//23318 21867//21867 23309//23309 -f 21883//21883 21881//21881 23313//23313 -f 23313//23313 21881//21881 21879//21879 -f 23313//23313 21879//21879 21877//21877 -f 23313//23313 23319//23319 21883//21883 -f 21883//21883 23319//23319 23320//23320 -f 21883//21883 23320//23320 21886//21886 -f 21886//21886 23320//23320 23321//23321 -f 21886//21886 23321//23321 21888//21888 -f 21888//21888 23321//23321 23322//23322 -f 21888//21888 23322//23322 21890//21890 -f 23322//23322 23323//23323 21890//21890 -f 21890//21890 23323//23323 23324//23324 -f 21890//21890 23324//23324 21892//21892 -f 23324//23324 23325//23325 21892//21892 -f 21892//21892 23325//23325 23326//23326 -f 21892//21892 23326//23326 21894//21894 -f 21894//21894 23326//23326 23327//23327 -f 21894//21894 23327//23327 21896//21896 -f 21896//21896 23327//23327 21899//21899 -f 23327//23327 23328//23328 21899//21899 -f 21899//21899 23328//23328 23329//23329 -f 21899//21899 23329//23329 21902//21902 -f 23329//23329 23330//23330 21902//21902 -f 21902//21902 23330//23330 23331//23331 -f 21902//21902 23331//23331 21904//21904 -f 21904//21904 23331//23331 23332//23332 -f 21904//21904 23332//23332 21906//21906 -f 23332//23332 23333//23333 21906//21906 -f 21906//21906 23333//23333 23334//23334 -f 21906//21906 23334//23334 21908//21908 -f 21908//21908 23334//23334 23335//23335 -f 21908//21908 23335//23335 21910//21910 -f 21910//21910 23335//23335 21912//21912 -f 23335//23335 23336//23336 21912//21912 -f 21912//21912 23336//23336 23337//23337 -f 21912//21912 23337//23337 21914//21914 -f 21914//21914 23337//23337 23338//23338 -f 21914//21914 23338//23338 21915//21915 -f 21915//21915 23338//23338 23339//23339 -f 21915//21915 23339//23339 21917//21917 -f 21917//21917 23339//23339 23340//23340 -f 21917//21917 23340//23340 21919//21919 -f 21919//21919 23340//23340 23341//23341 -f 21919//21919 23341//23341 23342//23342 -f 23342//23342 23343//23343 21919//21919 -f 21919//21919 23343//23343 23344//23344 -f 21919//21919 23344//23344 21921//21921 -f 21921//21921 23344//23344 23345//23345 -f 21921//21921 23345//23345 20197//20197 -f 23345//23345 23346//23346 20197//20197 -f 20197//20197 23346//23346 23347//23347 -f 20197//20197 23347//23347 20199//20199 -f 23348//23348 20201//20201 23349//23349 -f 23349//23349 20201//20201 20199//20199 -f 23349//23349 20199//20199 23350//23350 -f 23350//23350 20199//20199 23347//23347 -f 23348//23348 23351//23351 20201//20201 -f 20201//20201 23351//23351 23352//23352 -f 20201//20201 23352//23352 20202//20202 -f 20202//20202 23352//23352 23353//23353 -f 20202//20202 23353//23353 20204//20204 -f 20204//20204 23353//23353 23354//23354 -f 20204//20204 23354//23354 23355//23355 -f 23120//23120 20208//20208 23355//23355 -f 23355//23355 20208//20208 20206//20206 -f 23355//23355 20206//20206 20204//20204 -f 23356//23356 20216//20216 23357//23357 -f 23357//23357 20216//20216 20218//20218 -f 23357//23357 20218//20218 23358//23358 -f 23358//23358 20218//20218 20211//20211 -f 23358//23358 20211//20211 23121//23121 -f 23121//23121 20211//20211 20210//20210 -f 23121//23121 20210//20210 20208//20208 -f 23359//23359 20221//20221 23356//23356 -f 23356//23356 20221//20221 20214//20214 -f 23356//23356 20214//20214 20216//20216 -f 23119//23119 20227//20227 23360//23360 -f 23360//23360 20227//20227 20225//20225 -f 23360//23360 20225//20225 23361//23361 -f 23361//23361 20225//20225 20224//20224 -f 23361//23361 20224//20224 23359//23359 -f 23359//23359 20224//20224 20222//20222 -f 23359//23359 20222//20222 20221//20221 -f 20229//20229 23119//23119 20253//20253 -f 20253//20253 23119//23119 23362//23362 -f 20253//20253 23362//23362 23363//23363 -f 23363//23363 23364//23364 20253//20253 -f 20253//20253 23364//23364 23365//23365 -f 20253//20253 23365//23365 20251//20251 -f 20251//20251 23365//23365 23366//23366 -f 20251//20251 23366//23366 20249//20249 -f 20249//20249 23366//23366 23367//23367 -f 20249//20249 23367//23367 20247//20247 -f 20247//20247 23367//23367 23368//23368 -f 20247//20247 23368//23368 20245//20245 -f 20245//20245 23368//23368 23369//23369 -f 20245//20245 23369//23369 20243//20243 -f 20243//20243 23369//23369 23370//23370 -f 20243//20243 23370//23370 20241//20241 -f 23370//23370 23371//23371 20241//20241 -f 20241//20241 23371//23371 23372//23372 -f 20241//20241 23372//23372 20239//20239 -f 20239//20239 23372//23372 23373//23373 -f 20239//20239 23373//23373 20237//20237 -f 20237//20237 23373//23373 23374//23374 -f 20237//20237 23374//23374 20235//20235 -f 20235//20235 23374//23374 23375//23375 -f 20235//20235 23375//23375 20230//20230 -f 23375//23375 23376//23376 20230//20230 -f 20230//20230 23376//23376 23377//23377 -f 20230//20230 23377//23377 20231//20231 -f 20231//20231 23377//23377 23378//23378 -f 20231//20231 23378//23378 20258//20258 -f 20258//20258 23378//23378 23379//23379 -f 20258//20258 23379//23379 20261//20261 -f 23379//23379 23380//23380 20261//20261 -f 20261//20261 23380//23380 23381//23381 -f 20261//20261 23381//23381 20262//20262 -f 20262//20262 23381//23381 23382//23382 -f 20262//20262 23382//23382 23118//23118 -f 23118//23118 23383//23383 21796//21796 -f 21796//21796 23383//23383 23384//23384 -f 21796//21796 23384//23384 21798//21798 -f 21798//21798 23384//23384 23385//23385 -f 21798//21798 23385//23385 21800//21800 -f 21800//21800 23385//23385 21802//21802 -f 21802//21802 23385//23385 23386//23386 -f 21802//21802 23386//23386 21804//21804 -f 23386//23386 23387//23387 21804//21804 -f 21804//21804 23387//23387 23388//23388 -f 21804//21804 23388//23388 21806//21806 -f 23388//23388 23389//23389 21806//21806 -f 21806//21806 23389//23389 23390//23390 -f 21806//21806 23390//23390 21808//21808 -f 21808//21808 23390//23390 23391//23391 -f 21808//21808 23391//23391 21810//21810 -f 23391//23391 23392//23392 21810//21810 -f 21810//21810 23392//23392 23393//23393 -f 21810//21810 23393//23393 21812//21812 -f 21812//21812 23393//23393 21814//21814 -f 21814//21814 23393//23393 23394//23394 -f 21814//21814 23394//23394 21816//21816 -f 21816//21816 23394//23394 23395//23395 -f 21816//21816 23395//23395 21817//21817 -f 21817//21817 23395//23395 23396//23396 -f 21817//21817 23396//23396 21819//21819 -f 23397//23397 21823//21823 23396//23396 -f 23396//23396 21823//21823 21821//21821 -f 23396//23396 21821//21821 21819//21819 -f 22833//22833 22515//22515 22831//22831 -f 22831//22831 22515//22515 22514//22514 -f 22831//22831 22514//22514 22610//22610 -f 22610//22610 22514//22514 22612//22612 -f 22884//22884 22530//22530 22882//22882 -f 22882//22882 22530//22530 22550//22550 -f 22882//22882 22550//22550 22576//22576 -f 22576//22576 22550//22550 22615//22615 -f 20393//20393 23149//23149 23147//23147 -f 23202//23202 20293//20293 23203//23203 -f 23203//23203 20293//20293 23204//23204 -f 21903//21903 21905//21905 23256//23256 -f 20240//20240 23294//23294 23295//23295 -f 20238//20238 20236//20236 23298//23298 -f 21805//21805 23317//23317 23318//23318 -f 21807//21807 21809//21809 23315//23315 -f 21845//21845 23336//23336 21843//21843 -f 23336//23336 21845//21845 23337//23337 -f 21756//21756 23386//23386 23385//23385 -f 23386//23386 21756//21756 23387//23387 -f 21764//21764 23397//23397 21762//21762 -f 21762//21762 23397//23397 23396//23396 -f 21762//21762 23396//23396 21760//21760 -f 21760//21760 23396//23396 23395//23395 -f 21760//21760 23395//23395 21758//21758 -f 21758//21758 23395//23395 21743//21743 -f 21743//21743 23395//23395 23394//23394 -f 21743//21743 23394//23394 21744//21744 -f 21744//21744 23394//23394 21746//21746 -f 21746//21746 23394//23394 23393//23393 -f 21746//21746 23393//23393 21748//21748 -f 21748//21748 23393//23393 23392//23392 -f 21748//21748 23392//23392 21750//21750 -f 21750//21750 23392//23392 23391//23391 -f 21750//21750 23391//23391 21752//21752 -f 21752//21752 23391//23391 23390//23390 -f 21752//21752 23390//23390 21754//21754 -f 21754//21754 23390//23390 23389//23389 -f 21754//21754 23389//23389 21756//21756 -f 21756//21756 23389//23389 23388//23388 -f 21756//21756 23388//23388 23387//23387 -f 21738//21738 21740//21740 23385//23385 -f 23385//23385 21740//21740 21757//21757 -f 23385//23385 21757//21757 21756//21756 -f 23380//23380 20191//20191 23381//23381 -f 23381//23381 20191//20191 20193//20193 -f 23381//23381 20193//20193 23382//23382 -f 23382//23382 20193//20193 20195//20195 -f 23382//23382 20195//20195 23118//23118 -f 23118//23118 20195//20195 21735//21735 -f 23118//23118 21735//21735 23383//23383 -f 23383//23383 21735//21735 21738//21738 -f 23383//23383 21738//21738 23384//23384 -f 23384//23384 21738//21738 23385//23385 -f 20187//20187 20189//20189 23378//23378 -f 23378//23378 20189//20189 20191//20191 -f 23378//23378 20191//20191 23379//23379 -f 23379//23379 20191//20191 23380//23380 -f 23375//23375 20183//20183 23376//23376 -f 23376//23376 20183//20183 20187//20187 -f 23376//23376 20187//20187 23377//23377 -f 23377//23377 20187//20187 23378//23378 -f 23373//23373 20177//20177 23374//23374 -f 23374//23374 20177//20177 20179//20179 -f 23374//23374 20179//20179 23375//23375 -f 23375//23375 20179//20179 20181//20181 -f 23375//23375 20181//20181 20183//20183 -f 23373//23373 23372//23372 20177//20177 -f 20177//20177 23372//23372 23371//23371 -f 20177//20177 23371//23371 20175//20175 -f 20175//20175 23371//23371 23370//23370 -f 20175//20175 23370//23370 20173//20173 -f 20173//20173 23370//23370 23369//23369 -f 20173//20173 23369//23369 20171//20171 -f 20171//20171 23369//23369 23368//23368 -f 20171//20171 23368//23368 20169//20169 -f 20169//20169 23368//23368 23367//23367 -f 20169//20169 23367//23367 20167//20167 -f 20167//20167 23367//23367 23366//23366 -f 20167//20167 23366//23366 20164//20164 -f 23366//23366 23365//23365 20164//20164 -f 20164//20164 23365//23365 23364//23364 -f 20164//20164 23364//23364 20162//20162 -f 23364//23364 23363//23363 20162//20162 -f 20162//20162 23363//23363 23362//23362 -f 20162//20162 23362//23362 20160//20160 -f 20160//20160 23362//23362 23119//23119 -f 20160//20160 23119//23119 20158//20158 -f 23119//23119 23360//23360 20158//20158 -f 20158//20158 23360//23360 23361//23361 -f 20158//20158 23361//23361 20155//20155 -f 20155//20155 23361//23361 20153//20153 -f 20153//20153 23361//23361 23359//23359 -f 20153//20153 23359//23359 20152//20152 -f 20152//20152 23359//23359 23356//23356 -f 20152//20152 23356//23356 20150//20150 -f 23120//23120 20132//20132 23121//23121 -f 23121//23121 20132//20132 20131//20131 -f 23121//23121 20131//20131 23358//23358 -f 23358//23358 20131//20131 20129//20129 -f 23358//23358 20129//20129 23357//23357 -f 23357//23357 20129//20129 20128//20128 -f 23357//23357 20128//20128 23356//23356 -f 23356//23356 20128//20128 20148//20148 -f 23356//23356 20148//20148 20150//20150 -f 23353//23353 20140//20140 23354//23354 -f 23354//23354 20140//20140 20138//20138 -f 23354//23354 20138//20138 23355//23355 -f 23355//23355 20138//20138 20136//20136 -f 23355//23355 20136//20136 23120//23120 -f 23120//23120 20136//20136 20134//20134 -f 23120//23120 20134//20134 20132//20132 -f 23353//23353 23352//23352 20140//20140 -f 20140//20140 23352//23352 23351//23351 -f 20140//20140 23351//23351 20142//20142 -f 23351//23351 23348//23348 20142//20142 -f 20142//20142 23348//23348 23349//23349 -f 20142//20142 23349//23349 20144//20144 -f 20144//20144 23349//23349 23350//23350 -f 20144//20144 23350//23350 20146//20146 -f 20146//20146 23350//23350 23347//23347 -f 20146//20146 23347//23347 20147//20147 -f 20147//20147 23347//23347 23346//23346 -f 20147//20147 23346//23346 21856//21856 -f 23346//23346 23345//23345 21856//21856 -f 21856//21856 23345//23345 23344//23344 -f 21856//21856 23344//23344 21849//21849 -f 23344//23344 23343//23343 21849//21849 -f 21849//21849 23343//23343 23342//23342 -f 21849//21849 23342//23342 21850//21850 -f 21850//21850 23342//23342 23341//23341 -f 21850//21850 23341//23341 21855//21855 -f 21855//21855 23341//23341 23340//23340 -f 21855//21855 23340//23340 21854//21854 -f 21854//21854 23340//23340 23339//23339 -f 21854//21854 23339//23339 21847//21847 -f 21847//21847 23339//23339 21845//21845 -f 21845//21845 23339//23339 23338//23338 -f 21845//21845 23338//23338 23337//23337 -f 23335//23335 23334//23334 21836//21836 -f 21836//21836 21838//21838 23335//23335 -f 23335//23335 21838//21838 21840//21840 -f 23335//23335 21840//21840 23336//23336 -f 23336//23336 21840//21840 21841//21841 -f 23336//23336 21841//21841 21843//21843 -f 23334//23334 23333//23333 21836//21836 -f 21836//21836 23333//23333 23332//23332 -f 21836//21836 23332//23332 21833//21833 -f 21833//21833 23332//23332 23331//23331 -f 21833//21833 23331//23331 21831//21831 -f 23331//23331 23330//23330 21831//21831 -f 21831//21831 23330//23330 23329//23329 -f 21831//21831 23329//23329 21828//21828 -f 23329//23329 23328//23328 21828//21828 -f 21828//21828 23328//23328 23327//23327 -f 21828//21828 23327//23327 21826//21826 -f 21826//21826 23327//23327 21824//21824 -f 23324//23324 21822//21822 23325//23325 -f 23325//23325 21822//21822 21824//21824 -f 23325//23325 21824//21824 23326//23326 -f 23326//23326 21824//21824 23327//23327 -f 23324//23324 23323//23323 21822//21822 -f 21822//21822 23323//23323 23322//23322 -f 21822//21822 23322//23322 21820//21820 -f 21820//21820 23322//23322 23321//23321 -f 21820//21820 23321//23321 21818//21818 -f 23321//23321 23320//23320 21818//21818 -f 21818//21818 23320//23320 21815//21815 -f 21815//21815 23320//23320 23319//23319 -f 21815//21815 23319//23319 21813//21813 -f 21813//21813 23319//23319 23313//23313 -f 21813//21813 23313//23313 21811//21811 -f 21811//21811 23313//23313 21809//21809 -f 21809//21809 23313//23313 23314//23314 -f 21809//21809 23314//23314 23315//23315 -f 21807//21807 23315//23315 21805//21805 -f 21805//21805 23315//23315 23316//23316 -f 21805//21805 23316//23316 23317//23317 -f 23312//23312 21795//21795 23311//23311 -f 23311//23311 21795//21795 21797//21797 -f 23311//23311 21797//21797 23310//23310 -f 23310//23310 21797//21797 21799//21799 -f 23310//23310 21799//21799 23309//23309 -f 23309//23309 21799//21799 21801//21801 -f 23309//23309 21801//21801 23318//23318 -f 23318//23318 21801//21801 21803//21803 -f 23318//23318 21803//21803 21805//21805 -f 23312//23312 23308//23308 21795//21795 -f 21795//21795 23308//23308 23307//23307 -f 21795//21795 23307//23307 20263//20263 -f 23304//23304 20256//20256 23302//23302 -f 23302//23302 20256//20256 20263//20263 -f 23302//23302 20263//20263 23303//23303 -f 23303//23303 20263//20263 23307//23307 -f 23298//23298 20236//20236 23299//23299 -f 23299//23299 20236//20236 20234//20234 -f 23299//23299 20234//20234 23300//23300 -f 23300//23300 20234//20234 20233//20233 -f 23300//23300 20233//20233 23301//23301 -f 23301//23301 20233//20233 20232//20232 -f 23301//23301 20232//20232 23306//23306 -f 23306//23306 20232//20232 20260//20260 -f 23306//23306 20260//20260 23305//23305 -f 23305//23305 20260//20260 20259//20259 -f 23305//23305 20259//20259 23304//23304 -f 23304//23304 20259//20259 20257//20257 -f 23304//23304 20257//20257 20256//20256 -f 20238//20238 23298//23298 20240//20240 -f 20240//20240 23298//23298 23297//23297 -f 20240//20240 23297//23297 23294//23294 -f 20246//20246 20244//20244 23295//23295 -f 23295//23295 20244//20244 20242//20242 -f 23295//23295 20242//20242 20240//20240 -f 23295//23295 23296//23296 20246//20246 -f 20246//20246 23296//23296 23293//23293 -f 20246//20246 23293//23293 20248//20248 -f 23293//23293 23292//23292 20248//20248 -f 20248//20248 23292//23292 23291//23291 -f 20248//20248 23291//23291 20250//20250 -f 20250//20250 23291//23291 23290//23290 -f 20250//20250 23290//23290 20252//20252 -f 20252//20252 23290//23290 23289//23289 -f 20252//20252 23289//23289 20254//20254 -f 23289//23289 23288//23288 20254//20254 -f 20254//20254 23288//23288 23287//23287 -f 20254//20254 23287//23287 20255//20255 -f 20255//20255 23287//23287 23286//23286 -f 20255//20255 23286//23286 20228//20228 -f 20228//20228 23286//23286 23122//23122 -f 20228//20228 23122//23122 20226//20226 -f 23283//23283 20215//20215 23284//23284 -f 23284//23284 20215//20215 20213//20213 -f 23284//23284 20213//20213 23285//23285 -f 23285//23285 20213//20213 20212//20212 -f 23285//23285 20212//20212 23122//23122 -f 23122//23122 20212//20212 20223//20223 -f 23122//23122 20223//20223 20226//20226 -f 23283//23283 23282//23282 20215//20215 -f 20215//20215 23282//23282 23281//23281 -f 20215//20215 23281//23281 20217//20217 -f 20217//20217 23281//23281 20219//20219 -f 20219//20219 23281//23281 23280//23280 -f 20219//20219 23280//23280 20220//20220 -f 20220//20220 23280//23280 23279//23279 -f 20220//20220 23279//23279 20209//20209 -f 20209//20209 23279//23279 23278//23278 -f 20209//20209 23278//23278 20207//20207 -f 20207//20207 23278//23278 23277//23277 -f 20207//20207 23277//23277 20205//20205 -f 20205//20205 23277//23277 23276//23276 -f 20205//20205 23276//23276 20203//20203 -f 23276//23276 23275//23275 20203//20203 -f 20203//20203 23275//23275 23274//23274 -f 20203//20203 23274//23274 20200//20200 -f 20200//20200 23274//23274 23273//23273 -f 20200//20200 23273//23273 20198//20198 -f 20198//20198 23273//23273 23272//23272 -f 20198//20198 23272//23272 20196//20196 -f 20196//20196 23272//23272 23271//23271 -f 20196//20196 23271//23271 23270//23270 -f 23269//23269 21918//21918 23270//23270 -f 23270//23270 21918//21918 21920//21920 -f 23270//23270 21920//21920 20196//20196 -f 23269//23269 23268//23268 21918//21918 -f 21918//21918 23268//23268 23267//23267 -f 21918//21918 23267//23267 21916//21916 -f 23264//23264 21913//21913 23265//23265 -f 23265//23265 21913//21913 21916//21916 -f 23265//23265 21916//21916 23266//23266 -f 23266//23266 21916//21916 23267//23267 -f 23264//23264 23263//23263 21913//21913 -f 21913//21913 23263//23263 23262//23262 -f 21913//21913 23262//23262 21911//21911 -f 21911//21911 23262//23262 23261//23261 -f 21911//21911 23261//23261 21909//21909 -f 21909//21909 23261//23261 23260//23260 -f 21909//21909 23260//23260 21907//21907 -f 23260//23260 23259//23259 21907//21907 -f 21907//21907 23259//23259 23258//23258 -f 21907//21907 23258//23258 21905//21905 -f 21905//21905 23258//23258 23257//23257 -f 21905//21905 23257//23257 23256//23256 -f 21903//21903 23256//23256 21901//21901 -f 21901//21901 23256//23256 23255//23255 -f 21901//21901 23255//23255 21900//21900 -f 23255//23255 23254//23254 21900//21900 -f 21900//21900 23254//23254 23253//23253 -f 21900//21900 23253//23253 21898//21898 -f 21898//21898 23253//23253 23252//23252 -f 21898//21898 23252//23252 21897//21897 -f 21897//21897 23252//23252 23251//23251 -f 23249//23249 21891//21891 23250//23250 -f 23250//23250 21891//21891 21893//21893 -f 23250//23250 21893//21893 23251//23251 -f 23251//23251 21893//21893 21895//21895 -f 23251//23251 21895//21895 21897//21897 -f 23247//23247 21885//21885 23248//23248 -f 23248//23248 21885//21885 21887//21887 -f 23248//23248 21887//21887 23249//23249 -f 23249//23249 21887//21887 21889//21889 -f 23249//23249 21889//21889 21891//21891 -f 23247//23247 23246//23246 21885//21885 -f 21885//21885 23246//23246 23245//23245 -f 21885//21885 23245//23245 21884//21884 -f 21884//21884 23245//23245 23239//23239 -f 21884//21884 23239//23239 21882//21882 -f 21882//21882 23239//23239 21880//21880 -f 21880//21880 23239//23239 21878//21878 -f 21878//21878 23239//23239 23240//23240 -f 21878//21878 23240//23240 23241//23241 -f 23241//23241 23244//23244 21878//21878 -f 21878//21878 23244//23244 23243//23243 -f 21878//21878 23243//23243 21876//21876 -f 21876//21876 23243//23243 21864//21864 -f 21864//21864 23243//23243 23242//23242 -f 21864//21864 23242//23242 21865//21865 -f 23242//23242 23234//23234 21865//21865 -f 21865//21865 23234//23234 23235//23235 -f 21865//21865 23235//23235 21873//21873 -f 21873//21873 23235//23235 23236//23236 -f 21873//21873 23236//23236 21872//21872 -f 21872//21872 23236//23236 23237//23237 -f 21872//21872 23237//23237 21870//21870 -f 21870//21870 23237//23237 23238//23238 -f 21870//21870 23238//23238 21863//21863 -f 21863//21863 23238//23238 23233//23233 -f 21863//21863 23233//23233 21861//21861 -f 23233//23233 23232//23232 21861//21861 -f 21861//21861 23232//23232 23231//23231 -f 21861//21861 23231//23231 21859//21859 -f 21859//21859 23231//23231 23230//23230 -f 21859//21859 23230//23230 20332//20332 -f 23230//23230 23229//23229 20332//20332 -f 20332//20332 23229//23229 23228//23228 -f 20332//20332 23228//23228 20327//20327 -f 20327//20327 23228//23228 23227//23227 -f 23223//23223 20323//20323 23224//23224 -f 23224//23224 20323//20323 20325//20325 -f 23224//23224 20325//20325 23225//23225 -f 23225//23225 20325//20325 20327//20327 -f 23225//23225 20327//20327 23226//23226 -f 23226//23226 20327//20327 23227//23227 -f 20317//20317 23218//23218 20316//20316 -f 20316//20316 23218//23218 23217//23217 -f 20316//20316 23217//23217 20314//20314 -f 23223//23223 23222//23222 20323//20323 -f 20323//20323 23222//23222 23221//23221 -f 20323//20323 23221//23221 20320//20320 -f 20320//20320 23221//23221 23220//23220 -f 20320//20320 23220//23220 20317//20317 -f 20317//20317 23220//23220 23219//23219 -f 20317//20317 23219//23219 23218//23218 -f 20314//20314 23217//23217 20311//20311 -f 20311//20311 23217//23217 23216//23216 -f 20311//20311 23216//23216 23215//23215 -f 23215//23215 23214//23214 20311//20311 -f 20311//20311 23214//23214 23213//23213 -f 20311//20311 23213//23213 20309//20309 -f 20309//20309 23213//23213 23212//23212 -f 20309//20309 23212//23212 20307//20307 -f 20307//20307 23212//23212 20305//20305 -f 23212//23212 23211//23211 20305//20305 -f 20305//20305 23211//23211 23210//23210 -f 20305//20305 23210//23210 20303//20303 -f 23210//23210 23209//23209 20303//20303 -f 20303//20303 23209//23209 23208//23208 -f 20303//20303 23208//23208 20301//20301 -f 20301//20301 23208//23208 23207//23207 -f 20301//20301 23207//23207 20299//20299 -f 23207//23207 23206//23206 20299//20299 -f 20299//20299 23206//23206 23205//23205 -f 20299//20299 23205//23205 20297//20297 -f 20297//20297 23205//23205 23204//23204 -f 20297//20297 23204//23204 20295//20295 -f 20295//20295 23204//23204 20293//20293 -f 23200//23200 23199//23199 20283//20283 -f 20283//20283 20285//20285 23200//23200 -f 23200//23200 20285//20285 20287//20287 -f 23200//23200 20287//20287 23201//23201 -f 23201//23201 20287//20287 20288//20288 -f 23201//23201 20288//20288 23202//23202 -f 23202//23202 20288//20288 20290//20290 -f 23202//23202 20290//20290 20293//20293 -f 23199//23199 23198//23198 20283//20283 -f 20283//20283 23198//23198 23197//23197 -f 20283//20283 23197//23197 20281//20281 -f 20281//20281 23197//23197 23196//23196 -f 20281//20281 23196//23196 20279//20279 -f 20279//20279 23196//23196 23195//23195 -f 20279//20279 23195//23195 20277//20277 -f 20277//20277 23195//23195 20276//20276 -f 23195//23195 23123//23123 20276//20276 -f 20276//20276 23123//23123 23194//23194 -f 20276//20276 23194//23194 20274//20274 -f 20274//20274 23194//23194 23193//23193 -f 20274//20274 23193//23193 20272//20272 -f 20272//20272 23193//23193 23192//23192 -f 20272//20272 23192//23192 20270//20270 -f 20270//20270 23192//23192 23191//23191 -f 20270//20270 23191//23191 20268//20268 -f 20268//20268 23191//23191 23190//23190 -f 20268//20268 23190//23190 23189//23189 -f 23186//23186 21982//21982 23187//23187 -f 23187//23187 21982//21982 21984//21984 -f 23187//23187 21984//21984 23188//23188 -f 23188//23188 21984//21984 20264//20264 -f 23188//23188 20264//20264 23189//23189 -f 23189//23189 20264//20264 20266//20266 -f 23189//23189 20266//20266 20268//20268 -f 23186//23186 23185//23185 21982//21982 -f 21982//21982 23185//23185 23184//23184 -f 21982//21982 23184//23184 21980//21980 -f 21980//21980 23184//23184 23183//23183 -f 21980//21980 23183//23183 21978//21978 -f 23183//23183 23182//23182 21978//21978 -f 21978//21978 23182//23182 23181//23181 -f 21978//21978 23181//23181 21976//21976 -f 21962//21962 21974//21974 23125//23125 -f 23125//23125 21974//21974 21976//21976 -f 23125//23125 21976//21976 23180//23180 -f 23180//23180 21976//21976 23181//23181 -f 21962//21962 23125//23125 21963//21963 -f 21963//21963 23125//23125 23124//23124 -f 21963//21963 23124//23124 21969//21969 -f 23124//23124 23179//23179 21969//21969 -f 21969//21969 23179//23179 23127//23127 -f 21969//21969 23127//23127 21967//21967 -f 23127//23127 23126//23126 21967//21967 -f 21967//21967 23126//23126 23175//23175 -f 21967//21967 23175//23175 21965//21965 -f 21965//21965 23175//23175 23178//23178 -f 21965//21965 23178//23178 21961//21961 -f 23178//23178 23177//23177 21961//21961 -f 21961//21961 23177//23177 23176//23176 -f 21961//21961 23176//23176 21959//21959 -f 21959//21959 23176//23176 23174//23174 -f 21959//21959 23174//23174 21957//21957 -f 21957//21957 23174//23174 23173//23173 -f 21957//21957 23173//23173 21955//21955 -f 23173//23173 23172//23172 21955//21955 -f 21955//21955 23172//23172 23170//23170 -f 21955//21955 23170//23170 21953//21953 -f 21953//21953 23170//23170 21951//21951 -f 21951//21951 23170//23170 23171//23171 -f 21951//21951 23171//23171 21949//21949 -f 23171//23171 23167//23167 21949//21949 -f 21949//21949 23167//23167 23168//23168 -f 21949//21949 23168//23168 21947//21947 -f 21947//21947 23168//23168 21945//21945 -f 21945//21945 23168//23168 23169//23169 -f 21945//21945 23169//23169 21942//21942 -f 21942//21942 23169//23169 23166//23166 -f 21942//21942 23166//23166 21940//21940 -f 21940//21940 23166//23166 21937//21937 -f 21937//21937 23166//23166 23165//23165 -f 21937//21937 23165//23165 21935//21935 -f 21935//21935 23165//23165 23164//23164 -f 21935//21935 23164//23164 21933//21933 -f 23164//23164 23163//23163 21933//21933 -f 21933//21933 23163//23163 23162//23162 -f 21933//21933 23162//23162 21930//21930 -f 21930//21930 23162//23162 23161//23161 -f 21930//21930 23161//23161 21927//21927 -f 23161//23161 23160//23160 21927//21927 -f 21927//21927 23160//23160 23159//23159 -f 21927//21927 23159//23159 21926//21926 -f 23159//23159 23158//23158 21926//21926 -f 21926//21926 23158//23158 23128//23128 -f 21926//21926 23128//23128 21924//21924 -f 23128//23128 23157//23157 21924//21924 -f 21924//21924 23157//23157 23156//23156 -f 21924//21924 23156//23156 21922//21922 -f 21922//21922 23156//23156 23155//23155 -f 21922//21922 23155//23155 20398//20398 -f 20398//20398 23155//23155 23154//23154 -f 20398//20398 23154//23154 23153//23153 -f 23152//23152 20395//20395 23153//23153 -f 23153//23153 20395//20395 20396//20396 -f 23153//23153 20396//20396 20398//20398 -f 23152//23152 23151//23151 20395//20395 -f 20395//20395 23151//23151 23150//23150 -f 20395//20395 23150//23150 20393//20393 -f 20393//20393 23150//23150 23148//23148 -f 20393//20393 23148//23148 23149//23149 -f 20386//20386 20388//20388 23147//23147 -f 23147//23147 20388//20388 20391//20391 -f 23147//23147 20391//20391 20393//20393 -f 23147//23147 23146//23146 20386//20386 -f 20386//20386 23146//23146 23145//23145 -f 20386//20386 23145//23145 20384//20384 -f 20384//20384 23145//23145 23144//23144 -f 23144//23144 23143//23143 20384//20384 -f 20384//20384 23143//23143 23142//23142 -f 20384//20384 23142//23142 20382//20382 -f 20382//20382 23142//23142 23141//23141 -f 20382//20382 23141//23141 20380//20380 -f 20380//20380 23141//23141 23139//23139 -f 20380//20380 23139//23139 20378//20378 -f 23139//23139 23140//23140 20378//20378 -f 20378//20378 23140//23140 23138//23138 -f 20378//20378 23138//23138 20376//20376 -f 20376//20376 23138//23138 23137//23137 -f 20376//20376 23137//23137 20375//20375 -f 20375//20375 23137//23137 20373//20373 -f 23137//23137 23136//23136 20373//20373 -f 20373//20373 23136//23136 23135//23135 -f 20373//20373 23135//23135 20371//20371 -f 23135//23135 23134//23134 20371//20371 -f 20371//20371 23134//23134 23133//23133 -f 20371//20371 23133//23133 20369//20369 -f 20369//20369 23133//23133 23130//23130 -f 20369//20369 23130//23130 20367//20367 -f 23130//23130 23131//23131 20367//20367 -f 20367//20367 23131//23131 23132//23132 -f 20367//20367 23132//23132 20365//20365 -f 20365//20365 23132//23132 23129//23129 -f 20365//20365 23129//23129 20363//20363 -f 20363//20363 23129//23129 20361//20361 -f 20361//20361 23129//23129 22934//22934 -f 20361//20361 22934//22934 20359//20359 -f 22609//22609 22607//22607 22832//22832 -f 22832//22832 22607//22607 22544//22544 -f 22832//22832 22544//22544 22833//22833 -f 22833//22833 22544//22544 22515//22515 -f 22616//22616 22615//22615 22880//22880 -f 22880//22880 22615//22615 22550//22550 -f 22880//22880 22550//22550 22881//22881 -f 22881//22881 22550//22550 22508//22508 -f 23398//23398 23399//23399 20137//20137 -f 23400//23400 23401//23401 20133//20133 -f 23402//23402 23403//23403 21749//21749 -f 21749//21749 23403//23403 21747//21747 -f 23404//23404 23405//23405 20104//20104 -f 23406//23406 21686//21686 21684//21684 -f 23407//23407 23408//23408 21690//21690 -f 23409//23409 21698//21698 21696//21696 -f 21698//21698 23409//23409 23410//23410 -f 23411//23411 23412//23412 20032//20032 -f 20032//20032 23412//23412 20034//20034 -f 23413//23413 20039//20039 20037//20037 -f 23414//23414 23415//23415 20059//20059 -f 23416//23416 19941//19941 19943//19943 -f 23417//23417 19936//19936 23416//23416 -f 23416//23416 19936//19936 19939//19939 -f 23416//23416 19939//19939 19941//19941 -f 19963//19963 23418//23418 19964//19964 -f 19964//19964 23418//23418 23419//23419 -f 19964//19964 23419//23419 19943//19943 -f 19943//19943 23419//23419 23420//23420 -f 19943//19943 23420//23420 23416//23416 -f 19963//19963 19961//19961 23418//23418 -f 23418//23418 19961//19961 19959//19959 -f 23418//23418 19959//19959 23421//23421 -f 23421//23421 19959//19959 23422//23422 -f 23422//23422 19959//19959 19957//19957 -f 23422//23422 19957//19957 23423//23423 -f 19957//19957 19955//19955 23423//23423 -f 23423//23423 19955//19955 19953//19953 -f 23423//23423 19953//19953 23424//23424 -f 19970//19970 23425//23425 19971//19971 -f 19971//19971 23425//23425 23426//23426 -f 19971//19971 23426//23426 19947//19947 -f 19947//19947 23426//23426 23427//23427 -f 19947//19947 23427//23427 19949//19949 -f 19949//19949 23427//23427 23428//23428 -f 19949//19949 23428//23428 19951//19951 -f 19951//19951 23428//23428 23429//23429 -f 19951//19951 23429//23429 19953//19953 -f 19953//19953 23429//23429 23430//23430 -f 19953//19953 23430//23430 23424//23424 -f 19970//19970 19968//19968 23425//23425 -f 23425//23425 19968//19968 19966//19966 -f 23425//23425 19966//19966 23431//23431 -f 23431//23431 19966//19966 19976//19976 -f 23431//23431 19976//19976 23432//23432 -f 23432//23432 19976//19976 19975//19975 -f 23432//23432 19975//19975 23433//23433 -f 23433//23433 19975//19975 23434//23434 -f 19975//19975 19973//19973 23434//23434 -f 23434//23434 19973//19973 21674//21674 -f 23434//23434 21674//21674 23435//23435 -f 23435//23435 21674//21674 21673//21673 -f 23435//23435 21673//21673 23436//23436 -f 23436//23436 21673//21673 21671//21671 -f 23436//23436 21671//21671 23437//23437 -f 23437//23437 21671//21671 21669//21669 -f 23437//23437 21669//21669 21667//21667 -f 21663//21663 23438//23438 21665//21665 -f 21665//21665 23438//23438 23439//23439 -f 21665//21665 23439//23439 21667//21667 -f 21667//21667 23439//23439 23440//23440 -f 21667//21667 23440//23440 23437//23437 -f 21660//21660 23441//23441 21661//21661 -f 21661//21661 23441//23441 23442//23442 -f 21661//21661 23442//23442 21663//21663 -f 21663//21663 23442//23442 23443//23443 -f 21663//21663 23443//23443 23438//23438 -f 21660//21660 21658//21658 23441//23441 -f 23441//23441 21658//21658 21656//21656 -f 23441//23441 21656//21656 23444//23444 -f 23444//23444 21656//21656 21654//21654 -f 23444//23444 21654//21654 23445//23445 -f 23445//23445 21654//21654 23446//23446 -f 23446//23446 21654//21654 21652//21652 -f 23446//23446 21652//21652 23447//23447 -f 23447//23447 21652//21652 21650//21650 -f 23447//23447 21650//21650 23448//23448 -f 23448//23448 21650//21650 23449//23449 -f 23449//23449 21650//21650 21648//21648 -f 23449//23449 21648//21648 23450//23450 -f 23450//23450 21648//21648 21646//21646 -f 23450//23450 21646//21646 23451//23451 -f 23451//23451 21646//21646 21645//21645 -f 23451//23451 21645//21645 23452//23452 -f 23452//23452 21645//21645 21643//21643 -f 23452//23452 21643//21643 23453//23453 -f 21643//21643 21641//21641 23453//23453 -f 23453//23453 21641//21641 21639//21639 -f 23453//23453 21639//21639 23454//23454 -f 23454//23454 21639//21639 21637//21637 -f 23454//23454 21637//21637 23455//23455 -f 23455//23455 21637//21637 21636//21636 -f 21634//21634 23456//23456 21636//21636 -f 21636//21636 23456//23456 23457//23457 -f 21636//21636 23457//23457 23455//23455 -f 21634//21634 21631//21631 23456//23456 -f 23456//23456 21631//21631 21629//21629 -f 23456//23456 21629//21629 23458//23458 -f 23458//23458 21629//21629 21627//21627 -f 23458//23458 21627//21627 23459//23459 -f 23459//23459 21627//21627 21625//21625 -f 23459//23459 21625//21625 23460//23460 -f 21619//21619 23461//23461 21621//21621 -f 21621//21621 23461//23461 23460//23460 -f 21621//21621 23460//23460 21623//21623 -f 21623//21623 23460//23460 21625//21625 -f 21617//21617 23462//23462 21619//21619 -f 21619//21619 23462//23462 23463//23463 -f 21619//21619 23463//23463 23461//23461 -f 21615//21615 23464//23464 21617//21617 -f 21617//21617 23464//23464 23465//23465 -f 21617//21617 23465//23465 23462//23462 -f 20059//20059 23415//23415 21611//21611 -f 21611//21611 23415//23415 23466//23466 -f 21611//21611 23466//23466 21613//21613 -f 21613//21613 23466//23466 23467//23467 -f 21613//21613 23467//23467 21615//21615 -f 21615//21615 23467//23467 23468//23468 -f 21615//21615 23468//23468 23464//23464 -f 23414//23414 20059//20059 23469//23469 -f 23469//23469 20059//20059 20058//20058 -f 23469//23469 20058//20058 23470//23470 -f 20061//20061 23471//23471 20058//20058 -f 20058//20058 23471//23471 23472//23472 -f 20058//20058 23472//23472 23470//23470 -f 20052//20052 23473//23473 20050//20050 -f 20050//20050 23473//23473 23474//23474 -f 20050//20050 23474//23474 20048//20048 -f 20048//20048 23474//23474 23475//23475 -f 20048//20048 23475//23475 20061//20061 -f 20061//20061 23475//23475 23476//23476 -f 20061//20061 23476//23476 23471//23471 -f 20043//20043 23477//23477 20045//20045 -f 20045//20045 23477//23477 23478//23478 -f 20045//20045 23478//23478 20047//20047 -f 20047//20047 23478//23478 23479//23479 -f 20047//20047 23479//23479 20052//20052 -f 20052//20052 23479//23479 23480//23480 -f 20052//20052 23480//23480 23473//23473 -f 20039//20039 23413//23413 20041//20041 -f 20041//20041 23413//23413 23481//23481 -f 20041//20041 23481//23481 20043//20043 -f 20043//20043 23481//23481 23482//23482 -f 20043//20043 23482//23482 23477//23477 -f 20034//20034 23412//23412 20036//20036 -f 20036//20036 23412//23412 23483//23483 -f 20036//20036 23483//23483 20037//20037 -f 20037//20037 23483//23483 23484//23484 -f 20037//20037 23484//23484 23413//23413 -f 20015//20015 23485//23485 20028//20028 -f 20028//20028 23485//23485 23486//23486 -f 20028//20028 23486//23486 20030//20030 -f 20030//20030 23486//23486 23487//23487 -f 20030//20030 23487//23487 20032//20032 -f 20032//20032 23487//23487 23411//23411 -f 20015//20015 20026//20026 23485//23485 -f 23485//23485 20026//20026 20025//20025 -f 23485//23485 20025//20025 23488//23488 -f 20025//20025 20023//20023 23488//23488 -f 23488//23488 20023//20023 20021//20021 -f 23488//23488 20021//20021 23489//23489 -f 23489//23489 20021//20021 23490//23490 -f 20021//20021 20019//20019 23490//23490 -f 23490//23490 20019//20019 20017//20017 -f 23490//23490 20017//20017 23491//23491 -f 20017//20017 20016//20016 23491//23491 -f 23491//23491 20016//20016 20011//20011 -f 23491//23491 20011//20011 23492//23492 -f 23492//23492 20011//20011 20009//20009 -f 23492//23492 20009//20009 23493//23493 -f 23493//23493 20009//20009 23494//23494 -f 23494//23494 20009//20009 19998//19998 -f 23494//23494 19998//19998 23495//23495 -f 19998//19998 20007//20007 23495//23495 -f 23495//23495 20007//20007 20006//20006 -f 23495//23495 20006//20006 23496//23496 -f 23496//23496 20006//20006 23497//23497 -f 23497//23497 20006//20006 20004//20004 -f 23497//23497 20004//20004 23498//23498 -f 23498//23498 20004//20004 20002//20002 -f 23498//23498 20002//20002 23499//23499 -f 23499//23499 20002//20002 21732//21732 -f 23499//23499 21732//21732 23500//23500 -f 23500//23500 21732//21732 23501//23501 -f 23501//23501 21732//21732 21718//21718 -f 23501//23501 21718//21718 23502//23502 -f 23502//23502 21718//21718 21717//21717 -f 23502//23502 21717//21717 23503//23503 -f 23503//23503 21717//21717 21729//21729 -f 23503//23503 21729//21729 23504//23504 -f 23504//23504 21729//21729 21727//21727 -f 23504//23504 21727//21727 23505//23505 -f 23505//23505 21727//21727 21725//21725 -f 23505//23505 21725//21725 23506//23506 -f 23506//23506 21725//21725 21723//21723 -f 23506//23506 21723//21723 23507//23507 -f 21723//21723 21721//21721 23507//23507 -f 23507//23507 21721//21721 21720//21720 -f 23507//23507 21720//21720 23508//23508 -f 23508//23508 21720//21720 21715//21715 -f 23508//23508 21715//21715 23509//23509 -f 23509//23509 21715//21715 21713//21713 -f 23509//23509 21713//21713 23510//23510 -f 23510//23510 21713//21713 21711//21711 -f 23510//23510 21711//21711 23511//23511 -f 21711//21711 21710//21710 23511//23511 -f 23511//23511 21710//21710 21708//21708 -f 23511//23511 21708//21708 23512//23512 -f 23512//23512 21708//21708 23513//23513 -f 23513//23513 21708//21708 21706//21706 -f 23513//23513 21706//21706 23514//23514 -f 21706//21706 21704//21704 23514//23514 -f 23514//23514 21704//21704 21702//21702 -f 23514//23514 21702//21702 23410//23410 -f 23410//23410 21702//21702 21700//21700 -f 23410//23410 21700//21700 21698//21698 -f 21694//21694 23515//23515 21696//21696 -f 21696//21696 23515//23515 23516//23516 -f 21696//21696 23516//23516 23409//23409 -f 21690//21690 23408//23408 21692//21692 -f 23408//23408 23517//23517 21692//21692 -f 21692//21692 23517//23517 23518//23518 -f 21692//21692 23518//23518 21694//21694 -f 21694//21694 23518//23518 23519//23519 -f 21694//21694 23519//23519 23515//23515 -f 23407//23407 21690//21690 23406//23406 -f 23406//23406 21690//21690 21688//21688 -f 23406//23406 21688//21688 21686//21686 -f 21682//21682 23520//23520 21675//21675 -f 21675//21675 23520//23520 23521//23521 -f 21675//21675 23521//23521 21684//21684 -f 21684//21684 23521//23521 23522//23522 -f 21684//21684 23522//23522 23406//23406 -f 20123//20123 23523//23523 21679//21679 -f 21679//21679 23523//23523 23524//23524 -f 21679//21679 23524//23524 21681//21681 -f 21681//21681 23524//23524 23525//23525 -f 21681//21681 23525//23525 21682//21682 -f 21682//21682 23525//23525 23526//23526 -f 21682//21682 23526//23526 23520//23520 -f 23527//23527 23528//23528 20125//20125 -f 20125//20125 23528//23528 23529//23529 -f 20125//20125 23529//23529 20122//20122 -f 20122//20122 23529//23529 23530//23530 -f 20122//20122 23530//23530 20123//20123 -f 20123//20123 23530//23530 23531//23531 -f 20123//20123 23531//23531 23523//23523 -f 20107//20107 23532//23532 20125//20125 -f 20125//20125 23532//23532 23533//23533 -f 20125//20125 23533//23533 23527//23527 -f 23534//23534 23535//23535 20111//20111 -f 20111//20111 23535//23535 23536//23536 -f 20111//20111 23536//23536 20109//20109 -f 20109//20109 23536//23536 23537//23537 -f 20109//20109 23537//23537 20107//20107 -f 20107//20107 23537//23537 23538//23538 -f 20107//20107 23538//23538 23532//23532 -f 23534//23534 20111//20111 23539//23539 -f 23539//23539 20111//20111 20113//20113 -f 23539//23539 20113//20113 23540//23540 -f 23540//23540 20113//20113 20115//20115 -f 23540//23540 20115//20115 23541//23541 -f 23541//23541 20115//20115 23542//23542 -f 23542//23542 20115//20115 20117//20117 -f 23542//23542 20117//20117 23543//23543 -f 23543//23543 20117//20117 23405//23405 -f 23405//23405 20117//20117 20119//20119 -f 23405//23405 20119//20119 20104//20104 -f 23404//23404 20104//20104 23544//23544 -f 23544//23544 20104//20104 20102//20102 -f 23544//23544 20102//20102 23545//23545 -f 20102//20102 20100//20100 23545//23545 -f 23545//23545 20100//20100 20098//20098 -f 23545//23545 20098//20098 23546//23546 -f 23546//23546 20098//20098 20096//20096 -f 23546//23546 20096//20096 23547//23547 -f 23547//23547 20096//20096 23548//23548 -f 23548//23548 20096//20096 20094//20094 -f 23548//23548 20094//20094 23549//23549 -f 23549//23549 20094//20094 20092//20092 -f 23549//23549 20092//20092 23550//23550 -f 23550//23550 20092//20092 20090//20090 -f 23550//23550 20090//20090 23551//23551 -f 23551//23551 20090//20090 20089//20089 -f 23551//23551 20089//20089 23552//23552 -f 23552//23552 20089//20089 20087//20087 -f 23552//23552 20087//20087 23553//23553 -f 23553//23553 20087//20087 20085//20085 -f 23553//23553 20085//20085 20083//20083 -f 20082//20082 23554//23554 20083//20083 -f 20083//20083 23554//23554 23555//23555 -f 20083//20083 23555//23555 23553//23553 -f 23556//23556 23557//23557 20080//20080 -f 20080//20080 23557//23557 23558//23558 -f 20080//20080 23558//23558 20082//20082 -f 20082//20082 23558//23558 23559//23559 -f 20082//20082 23559//23559 23554//23554 -f 20080//20080 20078//20078 23556//23556 -f 23556//23556 20078//20078 20076//20076 -f 23556//23556 20076//20076 23560//23560 -f 23560//23560 20076//20076 20074//20074 -f 20063//20063 23561//23561 20074//20074 -f 20074//20074 23561//23561 23562//23562 -f 20074//20074 23562//23562 23560//23560 -f 23563//23563 23564//23564 20071//20071 -f 20071//20071 23564//23564 23561//23561 -f 20071//20071 23561//23561 20072//20072 -f 20072//20072 23561//23561 20063//20063 -f 20067//20067 23565//23565 20069//20069 -f 20069//20069 23565//23565 23566//23566 -f 20069//20069 23566//23566 20071//20071 -f 20071//20071 23566//23566 23567//23567 -f 20071//20071 23567//23567 23563//23563 -f 21790//21790 23568//23568 20067//20067 -f 20067//20067 23568//23568 23569//23569 -f 20067//20067 23569//23569 23565//23565 -f 21792//21792 23570//23570 21790//21790 -f 21790//21790 23570//23570 23571//23571 -f 21790//21790 23571//23571 23568//23568 -f 21786//21786 23572//23572 21788//21788 -f 21788//21788 23572//23572 23573//23573 -f 21788//21788 23573//23573 21789//21789 -f 21789//21789 23573//23573 23574//23574 -f 21789//21789 23574//23574 21792//21792 -f 21792//21792 23574//23574 23575//23575 -f 21792//21792 23575//23575 23570//23570 -f 23576//23576 23577//23577 21786//21786 -f 21786//21786 23577//23577 23578//23578 -f 21786//21786 23578//23578 23572//23572 -f 23576//23576 21786//21786 23579//23579 -f 23579//23579 21786//21786 21783//21783 -f 23579//23579 21783//21783 23580//23580 -f 23580//23580 21783//21783 21781//21781 -f 23580//23580 21781//21781 23581//23581 -f 23581//23581 21781//21781 21779//21779 -f 23581//23581 21779//21779 23582//23582 -f 23582//23582 21779//21779 21777//21777 -f 23582//23582 21777//21777 23583//23583 -f 23583//23583 21777//21777 21775//21775 -f 23583//23583 21775//21775 23584//23584 -f 21775//21775 21773//21773 23584//23584 -f 23584//23584 21773//21773 21771//21771 -f 23584//23584 21771//21771 23585//23585 -f 23585//23585 21771//21771 23586//23586 -f 23586//23586 21771//21771 21769//21769 -f 23586//23586 21769//21769 23587//23587 -f 23587//23587 21769//21769 21767//21767 -f 23587//23587 21767//21767 23588//23588 -f 23588//23588 21767//21767 21765//21765 -f 23588//23588 21765//21765 23589//23589 -f 23589//23589 21765//21765 23590//23590 -f 23590//23590 21765//21765 21763//21763 -f 23590//23590 21763//21763 21761//21761 -f 21759//21759 23591//23591 21761//21761 -f 21761//21761 23591//23591 23592//23592 -f 21761//21761 23592//23592 23590//23590 -f 21747//21747 23403//23403 21745//21745 -f 21745//21745 23403//23403 23593//23593 -f 21745//21745 23593//23593 21759//21759 -f 21759//21759 23593//23593 23594//23594 -f 21759//21759 23594//23594 23591//23591 -f 23402//23402 21749//21749 23595//23595 -f 23595//23595 21749//21749 21751//21751 -f 23595//23595 21751//21751 23596//23596 -f 23596//23596 21751//21751 21753//21753 -f 23596//23596 21753//21753 23597//23597 -f 23597//23597 21753//21753 21755//21755 -f 23597//23597 21755//21755 23598//23598 -f 23598//23598 21755//21755 21742//21742 -f 23598//23598 21742//21742 21741//21741 -f 21739//21739 23599//23599 21741//21741 -f 21741//21741 23599//23599 23600//23600 -f 21741//21741 23600//23600 23598//23598 -f 21737//21737 23601//23601 21739//21739 -f 21739//21739 23601//23601 23602//23602 -f 21739//21739 23602//23602 23599//23599 -f 21737//21737 21736//21736 23601//23601 -f 23601//23601 21736//21736 20194//20194 -f 23601//23601 20194//20194 23603//23603 -f 23603//23603 20194//20194 23604//23604 -f 23604//23604 20194//20194 20192//20192 -f 23604//23604 20192//20192 23605//23605 -f 23605//23605 20192//20192 20190//20190 -f 23605//23605 20190//20190 23606//23606 -f 23606//23606 20190//20190 23607//23607 -f 23607//23607 20190//20190 20188//20188 -f 23607//23607 20188//20188 23608//23608 -f 23608//23608 20188//20188 20186//20186 -f 23608//23608 20186//20186 23609//23609 -f 20182//20182 23610//23610 20184//20184 -f 20184//20184 23610//23610 23609//23609 -f 20184//20184 23609//23609 20185//20185 -f 20185//20185 23609//23609 20186//20186 -f 20178//20178 23611//23611 20180//20180 -f 20180//20180 23611//23611 23612//23612 -f 20180//20180 23612//23612 20182//20182 -f 20182//20182 23612//23612 23613//23613 -f 20182//20182 23613//23613 23610//23610 -f 23614//23614 23615//23615 20176//20176 -f 20176//20176 23615//23615 23616//23616 -f 20176//20176 23616//23616 20178//20178 -f 20178//20178 23616//23616 23617//23617 -f 20178//20178 23617//23617 23611//23611 -f 20170//20170 23618//23618 20172//20172 -f 20172//20172 23618//23618 23614//23614 -f 20172//20172 23614//23614 20174//20174 -f 20174//20174 23614//23614 20176//20176 -f 20166//20166 23619//23619 20168//20168 -f 20168//20168 23619//23619 23620//23620 -f 20168//20168 23620//23620 20170//20170 -f 20170//20170 23620//23620 23621//23621 -f 20170//20170 23621//23621 23618//23618 -f 20166//20166 20165//20165 23619//23619 -f 23619//23619 20165//20165 20163//20163 -f 23619//23619 20163//20163 23622//23622 -f 23622//23622 20163//20163 23623//23623 -f 23623//23623 20163//20163 20161//20161 -f 23623//23623 20161//20161 23624//23624 -f 20161//20161 20159//20159 23624//23624 -f 23624//23624 20159//20159 20157//20157 -f 23624//23624 20157//20157 23625//23625 -f 20157//20157 20156//20156 23625//23625 -f 23625//23625 20156//20156 20154//20154 -f 23625//23625 20154//20154 23626//23626 -f 23626//23626 20154//20154 20151//20151 -f 23626//23626 20151//20151 23627//23627 -f 23627//23627 20151//20151 20149//20149 -f 20127//20127 23628//23628 20149//20149 -f 20149//20149 23628//23628 23629//23629 -f 20149//20149 23629//23629 23627//23627 -f 20133//20133 23401//23401 20130//20130 -f 23401//23401 23630//23630 20130//20130 -f 20130//20130 23630//23630 23631//23631 -f 20130//20130 23631//23631 20127//20127 -f 20127//20127 23631//23631 23632//23632 -f 20127//20127 23632//23632 23628//23628 -f 23400//23400 20133//20133 23399//23399 -f 23399//23399 20133//20133 20135//20135 -f 23399//23399 20135//20135 20137//20137 -f 23398//23398 20137//20137 23633//23633 -f 23633//23633 20137//20137 20139//20139 -f 23633//23633 20139//20139 23634//23634 -f 23634//23634 20139//20139 23635//23635 -f 23635//23635 20139//20139 20141//20141 -f 23635//23635 20141//20141 23636//23636 -f 23636//23636 20141//20141 20143//20143 -f 23636//23636 20143//20143 23637//23637 -f 20145//20145 23638//23638 20143//20143 -f 20143//20143 23638//23638 23639//23639 -f 20143//20143 23639//23639 23637//23637 -f 20145//20145 21858//21858 23638//23638 -f 23638//23638 21858//21858 21857//21857 -f 23638//23638 21857//21857 23640//23640 -f 23640//23640 21857//21857 21848//21848 -f 23640//23640 21848//21848 23641//23641 -f 23641//23641 21848//21848 23642//23642 -f 23642//23642 21848//21848 21851//21851 -f 23642//23642 21851//21851 23643//23643 -f 23643//23643 21851//21851 21853//21853 -f 23643//23643 21853//21853 23644//23644 -f 23645//23645 23646//23646 21846//21846 -f 21846//21846 23646//23646 23644//23644 -f 21846//21846 23644//23644 21852//21852 -f 21852//21852 23644//23644 21853//21853 -f 23645//23645 21846//21846 23647//23647 -f 23647//23647 21846//21846 21844//21844 -f 23647//23647 21844//21844 23648//23648 -f 21844//21844 21842//21842 23648//23648 -f 23648//23648 21842//21842 21839//21839 -f 23648//23648 21839//21839 23649//23649 -f 23649//23649 21839//21839 23650//23650 -f 23650//23650 21839//21839 21837//21837 -f 23650//23650 21837//21837 23651//23651 -f 23651//23651 21837//21837 23652//23652 -f 23652//23652 21837//21837 21835//21835 -f 23652//23652 21835//21835 23653//23653 -f 23653//23653 21835//21835 21834//21834 -f 23653//23653 21834//21834 23654//23654 -f 23654//23654 21834//21834 21832//21832 -f 23654//23654 21832//21832 23655//23655 -f 23655//23655 21832//21832 21830//21830 -f 23655//23655 21830//21830 23656//23656 -f 23656//23656 21830//21830 21829//21829 -f 23656//23656 21829//21829 23657//23657 -f 21823//21823 23397//23397 21825//21825 -f 21825//21825 23397//23397 23657//23657 -f 21825//21825 23657//23657 21827//21827 -f 21827//21827 23657//23657 21829//21829 -f 22836//22836 22545//22545 22834//22834 -f 22834//22834 22545//22545 22544//22544 -f 22834//22834 22544//22544 22605//22605 -f 22605//22605 22544//22544 22607//22607 -f 22881//22881 22508//22508 22879//22879 -f 22879//22879 22508//22508 22507//22507 -f 22879//22879 22507//22507 22567//22567 -f 22567//22567 22507//22507 22618//22618 -f 23449//23449 21579//21579 21581//21581 -f 23414//23414 21543//21543 21544//21544 -f 23508//23508 21655//21655 21657//21657 -f 23512//23512 23513//23513 21649//21649 -f 23543//23543 23405//23405 20042//20042 -f 23633//23633 20070//20070 20065//20065 -f 23650//23650 21776//21776 21778//21778 -f 23657//23657 23397//23397 21764//21764 -f 21764//21764 21766//21766 23657//23657 -f 23657//23657 21766//21766 21768//21768 -f 23657//23657 21768//21768 23656//23656 -f 23656//23656 21768//21768 21770//21770 -f 23652//23652 23653//23653 21772//21772 -f 21772//21772 23653//23653 23654//23654 -f 21772//21772 23654//23654 21770//21770 -f 21770//21770 23654//23654 23655//23655 -f 21770//21770 23655//23655 23656//23656 -f 21772//21772 21774//21774 23652//23652 -f 23652//23652 21774//21774 21776//21776 -f 23652//23652 21776//21776 23651//23651 -f 23651//23651 21776//21776 23650//23650 -f 21787//21787 23644//23644 21785//21785 -f 21785//21785 23644//23644 23646//23646 -f 21785//21785 23646//23646 21784//21784 -f 21784//21784 23646//23646 23645//23645 -f 21784//21784 23645//23645 21782//21782 -f 21782//21782 23645//23645 23647//23647 -f 21782//21782 23647//23647 21780//21780 -f 21780//21780 23647//23647 23648//23648 -f 21780//21780 23648//23648 21778//21778 -f 21778//21778 23648//23648 23649//23649 -f 21778//21778 23649//23649 23650//23650 -f 20068//20068 23639//23639 20066//20066 -f 20066//20066 23639//23639 23638//23638 -f 20066//20066 23638//23638 21791//21791 -f 21791//21791 23638//23638 23640//23640 -f 21791//21791 23640//23640 21793//21793 -f 21793//21793 23640//23640 23641//23641 -f 21793//21793 23641//23641 21794//21794 -f 21794//21794 23641//23641 23642//23642 -f 21794//21794 23642//23642 21787//21787 -f 21787//21787 23642//23642 23643//23643 -f 21787//21787 23643//23643 23644//23644 -f 20070//20070 23636//23636 20068//20068 -f 20068//20068 23636//23636 23637//23637 -f 20068//20068 23637//23637 23639//23639 -f 23633//23633 23634//23634 20070//20070 -f 20070//20070 23634//23634 23635//23635 -f 20070//20070 23635//23635 23636//23636 -f 23631//23631 23630//23630 20075//20075 -f 20075//20075 23630//23630 23401//23401 -f 20075//20075 23401//23401 20073//20073 -f 20073//20073 23401//23401 23400//23400 -f 20073//20073 23400//23400 20064//20064 -f 20064//20064 23400//23400 23399//23399 -f 20064//20064 23399//23399 20065//20065 -f 20065//20065 23399//23399 23398//23398 -f 20065//20065 23398//23398 23633//23633 -f 23631//23631 20075//20075 23632//23632 -f 23632//23632 20075//20075 20077//20077 -f 23632//23632 20077//20077 23628//23628 -f 23628//23628 20077//20077 20079//20079 -f 23628//23628 20079//20079 23629//23629 -f 23629//23629 20079//20079 20081//20081 -f 23629//23629 20081//20081 23627//23627 -f 20084//20084 23625//23625 20081//20081 -f 20081//20081 23625//23625 23626//23626 -f 20081//20081 23626//23626 23627//23627 -f 20084//20084 20086//20086 23625//23625 -f 23625//23625 20086//20086 20088//20088 -f 23625//23625 20088//20088 23624//23624 -f 23624//23624 20088//20088 23623//23623 -f 20088//20088 20091//20091 23623//23623 -f 23623//23623 20091//20091 20093//20093 -f 23623//23623 20093//20093 23622//23622 -f 23622//23622 20093//20093 20095//20095 -f 23622//23622 20095//20095 23619//23619 -f 23619//23619 20095//20095 20097//20097 -f 23619//23619 20097//20097 23620//23620 -f 23620//23620 20097//20097 20099//20099 -f 23620//23620 20099//20099 23621//23621 -f 23621//23621 20099//20099 20101//20101 -f 23621//23621 20101//20101 23618//23618 -f 20118//20118 23615//23615 20120//20120 -f 20120//20120 23615//23615 23614//23614 -f 20120//20120 23614//23614 20121//20121 -f 20121//20121 23614//23614 23618//23618 -f 20121//20121 23618//23618 20103//20103 -f 20103//20103 23618//23618 20101//20101 -f 20116//20116 23617//23617 20118//20118 -f 20118//20118 23617//23617 23616//23616 -f 20118//20118 23616//23616 23615//23615 -f 20112//20112 23613//23613 20114//20114 -f 20114//20114 23613//23613 23612//23612 -f 20114//20114 23612//23612 20116//20116 -f 20116//20116 23612//23612 23611//23611 -f 20116//20116 23611//23611 23617//23617 -f 20108//20108 23608//23608 20110//20110 -f 20110//20110 23608//23608 23609//23609 -f 20110//20110 23609//23609 20112//20112 -f 20112//20112 23609//23609 23610//23610 -f 20112//20112 23610//23610 23613//23613 -f 23606//23606 23607//23607 20105//20105 -f 20105//20105 23607//23607 23608//23608 -f 20105//20105 23608//23608 20106//20106 -f 20106//20106 23608//23608 20108//20108 -f 23606//23606 20105//20105 23605//23605 -f 23605//23605 20105//20105 20126//20126 -f 23605//23605 20126//20126 23604//23604 -f 23604//23604 20126//20126 20124//20124 -f 23604//23604 20124//20124 23603//23603 -f 23603//23603 20124//20124 21678//21678 -f 23603//23603 21678//21678 23601//23601 -f 23601//23601 21678//21678 21680//21680 -f 23601//23601 21680//21680 23602//23602 -f 23602//23602 21680//21680 21677//21677 -f 23602//23602 21677//21677 23599//23599 -f 23402//23402 23595//23595 21685//21685 -f 21685//21685 23595//23595 23596//23596 -f 21685//21685 23596//23596 21683//21683 -f 21683//21683 23596//23596 23597//23597 -f 21683//21683 23597//23597 21676//21676 -f 21676//21676 23597//23597 23598//23598 -f 21676//21676 23598//23598 21677//21677 -f 21677//21677 23598//23598 23600//23600 -f 21677//21677 23600//23600 23599//23599 -f 23590//23590 23592//23592 21697//21697 -f 21697//21697 23592//23592 23591//23591 -f 21697//21697 23591//23591 21695//21695 -f 21695//21695 23591//23591 23594//23594 -f 21695//21695 23594//23594 21693//21693 -f 21693//21693 23594//23594 23593//23593 -f 21693//21693 23593//23593 21691//21691 -f 21691//21691 23593//23593 23403//23403 -f 21691//21691 23403//23403 21689//21689 -f 21689//21689 23403//23403 23402//23402 -f 21689//21689 23402//23402 21687//21687 -f 21687//21687 23402//23402 21685//21685 -f 23590//23590 21697//21697 23589//23589 -f 23589//23589 21697//21697 21699//21699 -f 23589//23589 21699//21699 23588//23588 -f 21699//21699 21701//21701 23588//23588 -f 23588//23588 21701//21701 21703//21703 -f 23588//23588 21703//21703 23587//23587 -f 23587//23587 21703//21703 21705//21705 -f 23587//23587 21705//21705 23586//23586 -f 23586//23586 21705//21705 21707//21707 -f 23586//23586 21707//21707 23585//23585 -f 23585//23585 21707//21707 23584//23584 -f 23584//23584 21707//21707 21709//21709 -f 23584//23584 21709//21709 23583//23583 -f 23583//23583 21709//21709 21712//21712 -f 23583//23583 21712//21712 23582//23582 -f 21712//21712 21714//21714 23582//23582 -f 23582//23582 21714//21714 21716//21716 -f 23582//23582 21716//21716 23581//23581 -f 23581//23581 21716//21716 23580//23580 -f 23580//23580 21716//21716 21722//21722 -f 23580//23580 21722//21722 23579//23579 -f 23579//23579 21722//21722 21724//21724 -f 23579//23579 21724//21724 23576//23576 -f 23576//23576 21724//21724 21726//21726 -f 23576//23576 21726//21726 23577//23577 -f 23574//23574 23573//23573 21728//21728 -f 21728//21728 23573//23573 23572//23572 -f 21728//21728 23572//23572 21726//21726 -f 21726//21726 23572//23572 23578//23578 -f 21726//21726 23578//23578 23577//23577 -f 21728//21728 21730//21730 23574//23574 -f 23574//23574 21730//21730 21731//21731 -f 23574//23574 21731//21731 23575//23575 -f 23575//23575 21731//21731 21719//21719 -f 23575//23575 21719//21719 23570//23570 -f 23570//23570 21719//21719 21734//21734 -f 23570//23570 21734//21734 23571//23571 -f 23571//23571 21734//21734 21733//21733 -f 23571//23571 21733//21733 23568//23568 -f 23568//23568 21733//21733 20001//20001 -f 20003//20003 23565//23565 20001//20001 -f 20001//20001 23565//23565 23569//23569 -f 20001//20001 23569//23569 23568//23568 -f 20005//20005 23567//23567 20003//20003 -f 20003//20003 23567//23567 23566//23566 -f 20003//20003 23566//23566 23565//23565 -f 23561//23561 23564//23564 20005//20005 -f 20005//20005 23564//23564 23563//23563 -f 20005//20005 23563//23563 23567//23567 -f 20005//20005 20000//20000 23561//23561 -f 23561//23561 20000//20000 19999//19999 -f 23561//23561 19999//19999 23562//23562 -f 19999//19999 20008//20008 23562//23562 -f 23562//23562 20008//20008 20010//20010 -f 23562//23562 20010//20010 23560//23560 -f 20020//20020 23559//23559 20018//20018 -f 20018//20018 23559//23559 23558//23558 -f 20018//20018 23558//23558 20012//20012 -f 20012//20012 23558//23558 23557//23557 -f 20012//20012 23557//23557 20010//20010 -f 20010//20010 23557//23557 23556//23556 -f 20010//20010 23556//23556 23560//23560 -f 20014//20014 23552//23552 20024//20024 -f 20024//20024 23552//23552 23553//23553 -f 20024//20024 23553//23553 20022//20022 -f 20022//20022 23553//23553 23555//23555 -f 20022//20022 23555//23555 20020//20020 -f 20020//20020 23555//23555 23554//23554 -f 20020//20020 23554//23554 23559//23559 -f 20013//20013 23550//23550 20014//20014 -f 20014//20014 23550//23550 23551//23551 -f 20014//20014 23551//23551 23552//23552 -f 20013//20013 20027//20027 23550//23550 -f 23550//23550 20027//20027 20029//20029 -f 23550//23550 20029//20029 23549//23549 -f 23549//23549 20029//20029 23548//23548 -f 23548//23548 20029//20029 23547//23547 -f 23547//23547 20029//20029 20031//20031 -f 23547//23547 20031//20031 23546//23546 -f 23546//23546 20031//20031 23545//23545 -f 23545//23545 20031//20031 20033//20033 -f 23545//23545 20033//20033 23544//23544 -f 20033//20033 20035//20035 23544//23544 -f 23544//23544 20035//20035 20038//20038 -f 23544//23544 20038//20038 23404//23404 -f 23404//23404 20038//20038 23405//23405 -f 23405//23405 20038//20038 20040//20040 -f 23405//23405 20040//20040 20042//20042 -f 20053//20053 23534//23534 20054//20054 -f 20054//20054 23534//23534 23539//23539 -f 20054//20054 23539//23539 20046//20046 -f 20046//20046 23539//23539 23540//23540 -f 20046//20046 23540//23540 20044//20044 -f 20044//20044 23540//23540 23541//23541 -f 20044//20044 23541//23541 20042//20042 -f 20042//20042 23541//23541 23542//23542 -f 20042//20042 23542//23542 23543//23543 -f 23538//23538 23537//23537 20051//20051 -f 20051//20051 23537//23537 23536//23536 -f 20051//20051 23536//23536 20053//20053 -f 20053//20053 23536//23536 23535//23535 -f 20053//20053 23535//23535 23534//23534 -f 20051//20051 20049//20049 23538//23538 -f 23538//23538 20049//20049 20057//20057 -f 23538//23538 20057//20057 23532//23532 -f 23532//23532 20057//20057 20056//20056 -f 23532//23532 20056//20056 23533//23533 -f 23533//23533 20056//20056 20055//20055 -f 23533//23533 20055//20055 23527//23527 -f 23527//23527 20055//20055 23528//23528 -f 23528//23528 20055//20055 23529//23529 -f 23529//23529 20055//20055 20062//20062 -f 23529//23529 20062//20062 23530//23530 -f 23530//23530 20062//20062 23531//23531 -f 23531//23531 20062//20062 20060//20060 -f 23531//23531 20060//20060 23523//23523 -f 20060//20060 21610//21610 23523//23523 -f 23523//23523 21610//21610 21612//21612 -f 23523//23523 21612//21612 23524//23524 -f 23524//23524 21612//21612 21614//21614 -f 23524//23524 21614//21614 23525//23525 -f 23525//23525 21614//21614 21616//21616 -f 23525//23525 21616//21616 23526//23526 -f 23526//23526 21616//21616 21618//21618 -f 23526//23526 21618//21618 23520//23520 -f 23520//23520 21618//21618 21620//21620 -f 21638//21638 23516//23516 21635//21635 -f 21635//21635 23516//23516 23515//23515 -f 21635//21635 23515//23515 21633//21633 -f 21633//21633 23515//23515 23519//23519 -f 21633//21633 23519//23519 21632//21632 -f 21632//21632 23519//23519 23518//23518 -f 21632//21632 23518//23518 21630//21630 -f 21630//21630 23518//23518 23517//23517 -f 21630//21630 23517//23517 21628//21628 -f 21628//21628 23517//23517 23408//23408 -f 21628//21628 23408//23408 21626//21626 -f 21626//21626 23408//23408 23407//23407 -f 21626//21626 23407//23407 21624//21624 -f 21624//21624 23407//23407 23406//23406 -f 21624//21624 23406//23406 21622//21622 -f 21622//21622 23406//23406 23522//23522 -f 21622//21622 23522//23522 21620//21620 -f 21620//21620 23522//23522 23521//23521 -f 21620//21620 23521//23521 23520//23520 -f 21640//21640 23410//23410 21638//21638 -f 21638//21638 23410//23410 23409//23409 -f 21638//21638 23409//23409 23516//23516 -f 21640//21640 21642//21642 23410//23410 -f 23410//23410 21642//21642 21644//21644 -f 23410//23410 21644//21644 23514//23514 -f 23514//23514 21644//21644 23513//23513 -f 23513//23513 21644//21644 21647//21647 -f 23513//23513 21647//21647 21649//21649 -f 21651//21651 23511//23511 21649//21649 -f 21649//21649 23511//23511 23512//23512 -f 21655//21655 23508//23508 21653//21653 -f 21653//21653 23508//23508 23509//23509 -f 21653//21653 23509//23509 21651//21651 -f 21651//21651 23509//23509 23510//23510 -f 21651//21651 23510//23510 23511//23511 -f 21659//21659 23506//23506 21657//21657 -f 21657//21657 23506//23506 23507//23507 -f 21657//21657 23507//23507 23508//23508 -f 21659//21659 21662//21662 23506//23506 -f 23506//23506 21662//21662 21664//21664 -f 23506//23506 21664//21664 23505//23505 -f 23505//23505 21664//21664 23504//23504 -f 23504//23504 21664//21664 21666//21666 -f 23504//23504 21666//21666 21668//21668 -f 23496//23496 23497//23497 19965//19965 -f 19965//19965 23497//23497 23498//23498 -f 19965//19965 23498//23498 19974//19974 -f 19974//19974 23498//23498 23499//23499 -f 19974//19974 23499//23499 19972//19972 -f 19972//19972 23499//23499 23500//23500 -f 19972//19972 23500//23500 21672//21672 -f 21672//21672 23500//23500 23501//23501 -f 21672//21672 23501//23501 21670//21670 -f 21670//21670 23501//23501 23502//23502 -f 21670//21670 23502//23502 21668//21668 -f 21668//21668 23502//23502 23503//23503 -f 21668//21668 23503//23503 23504//23504 -f 23496//23496 19965//19965 23495//23495 -f 23495//23495 19965//19965 19967//19967 -f 23495//23495 19967//19967 23494//23494 -f 23494//23494 19967//19967 19969//19969 -f 23494//23494 19969//19969 23493//23493 -f 23491//23491 23492//23492 19948//19948 -f 19948//19948 23492//23492 23493//23493 -f 19948//19948 23493//23493 19946//19946 -f 19946//19946 23493//23493 19969//19969 -f 23491//23491 19948//19948 23490//23490 -f 23490//23490 19948//19948 19950//19950 -f 23490//23490 19950//19950 23489//23489 -f 19950//19950 19952//19952 23489//23489 -f 23489//23489 19952//19952 19954//19954 -f 23489//23489 19954//19954 23488//23488 -f 19954//19954 19956//19956 23488//23488 -f 23488//23488 19956//19956 19958//19958 -f 23488//23488 19958//19958 23485//23485 -f 23485//23485 19958//19958 19960//19960 -f 23485//23485 19960//19960 23486//23486 -f 19960//19960 19962//19962 23486//23486 -f 23486//23486 19962//19962 19945//19945 -f 23486//23486 19945//19945 23487//23487 -f 23487//23487 19945//19945 19944//19944 -f 23487//23487 19944//19944 19942//19942 -f 23487//23487 19942//19942 23411//23411 -f 23411//23411 19942//19942 23412//23412 -f 23412//23412 19942//19942 19940//19940 -f 23412//23412 19940//19940 23483//23483 -f 19940//19940 19938//19938 23483//23483 -f 23483//23483 19938//19938 19937//19937 -f 23483//23483 19937//19937 23484//23484 -f 23484//23484 19937//19937 23413//23413 -f 19937//19937 19935//19935 23413//23413 -f 23413//23413 19935//19935 19933//19933 -f 23413//23413 19933//19933 23481//23481 -f 23481//23481 19933//19933 19992//19992 -f 23481//23481 19992//19992 23482//23482 -f 23482//23482 19992//19992 19991//19991 -f 23482//23482 19991//19991 23477//23477 -f 23477//23477 19991//19991 19989//19989 -f 23477//23477 19989//19989 23478//23478 -f 23478//23478 19989//19989 23479//23479 -f 23479//23479 19989//19989 19987//19987 -f 23479//23479 19987//19987 23480//23480 -f 23474//23474 23473//23473 19983//19983 -f 19983//19983 23473//23473 23480//23480 -f 19983//19983 23480//23480 19985//19985 -f 19985//19985 23480//23480 19987//19987 -f 19983//19983 19981//19981 23474//23474 -f 23474//23474 19981//19981 19980//19980 -f 23474//23474 19980//19980 23475//23475 -f 23475//23475 19980//19980 19979//19979 -f 19997//19997 23471//23471 19979//19979 -f 19979//19979 23471//23471 23476//23476 -f 19979//19979 23476//23476 23475//23475 -f 23469//23469 23470//23470 19997//19997 -f 19997//19997 23470//23470 23472//23472 -f 19997//19997 23472//23472 23471//23471 -f 23469//23469 19997//19997 23414//23414 -f 23414//23414 19997//19997 19995//19995 -f 23414//23414 19995//19995 21543//21543 -f 21546//21546 23466//23466 21544//21544 -f 21544//21544 23466//23466 23415//23415 -f 21544//21544 23415//23415 23414//23414 -f 21551//21551 23464//23464 21549//21549 -f 21549//21549 23464//23464 23468//23468 -f 21549//21549 23468//23468 21546//21546 -f 21546//21546 23468//23468 23467//23467 -f 21546//21546 23467//23467 23466//23466 -f 21553//21553 23462//23462 21551//21551 -f 21551//21551 23462//23462 23465//23465 -f 21551//21551 23465//23465 23464//23464 -f 21555//21555 23461//23461 21553//21553 -f 21553//21553 23461//23461 23463//23463 -f 21553//21553 23463//23463 23462//23462 -f 21541//21541 23459//23459 21555//21555 -f 21555//21555 23459//23459 23460//23460 -f 21555//21555 23460//23460 23461//23461 -f 21541//21541 21540//21540 23459//23459 -f 23459//23459 21540//21540 21558//21558 -f 23459//23459 21558//21558 23458//23458 -f 23458//23458 21558//21558 21560//21560 -f 23458//23458 21560//21560 23456//23456 -f 23456//23456 21560//21560 21562//21562 -f 23456//23456 21562//21562 23457//23457 -f 23457//23457 21562//21562 21565//21565 -f 23457//23457 21565//21565 23455//23455 -f 23455//23455 21565//21565 21567//21567 -f 21570//21570 23453//23453 21567//21567 -f 21567//21567 23453//23453 23454//23454 -f 21567//21567 23454//23454 23455//23455 -f 21576//21576 23452//23452 21574//21574 -f 21574//21574 23452//23452 23453//23453 -f 21574//21574 23453//23453 21572//21572 -f 21572//21572 23453//23453 21570//21570 -f 21579//21579 23449//23449 21577//21577 -f 21577//21577 23449//23449 23450//23450 -f 21577//21577 23450//23450 21576//21576 -f 21576//21576 23450//23450 23451//23451 -f 21576//21576 23451//23451 23452//23452 -f 21583//21583 23447//23447 21581//21581 -f 21581//21581 23447//23447 23448//23448 -f 21581//21581 23448//23448 23449//23449 -f 21586//21586 23444//23444 21585//21585 -f 21585//21585 23444//23444 23445//23445 -f 21585//21585 23445//23445 21583//21583 -f 21583//21583 23445//23445 23446//23446 -f 21583//21583 23446//23446 23447//23447 -f 21586//21586 21588//21588 23444//23444 -f 23444//23444 21588//21588 21590//21590 -f 23444//23444 21590//21590 23441//23441 -f 23441//23441 21590//21590 21592//21592 -f 23441//23441 21592//21592 23442//23442 -f 23442//23442 21592//21592 21593//21593 -f 23442//23442 21593//21593 23443//23443 -f 23443//23443 21593//21593 21595//21595 -f 23443//23443 21595//21595 23438//23438 -f 23438//23438 21595//21595 21607//21607 -f 21603//21603 23437//23437 21605//21605 -f 21605//21605 23437//23437 23440//23440 -f 21605//21605 23440//23440 21607//21607 -f 21607//21607 23440//23440 23439//23439 -f 21607//21607 23439//23439 23438//23438 -f 21603//21603 21601//21601 23437//23437 -f 23437//23437 21601//21601 21599//21599 -f 23437//23437 21599//21599 23436//23436 -f 23436//23436 21599//21599 21597//21597 -f 23436//23436 21597//21597 23435//23435 -f 23435//23435 21597//21597 23434//23434 -f 23434//23434 21597//21597 19864//19864 -f 23434//23434 19864//19864 23433//23433 -f 19864//19864 19866//19866 23433//23433 -f 23433//23433 19866//19866 19868//19868 -f 23433//23433 19868//19868 23432//23432 -f 23432//23432 19868//19868 19871//19871 -f 23432//23432 19871//19871 23431//23431 -f 23431//23431 19871//19871 19873//19873 -f 23431//23431 19873//19873 23425//23425 -f 23425//23425 19873//19873 19875//19875 -f 23425//23425 19875//19875 23426//23426 -f 19875//19875 19877//19877 23426//23426 -f 23426//23426 19877//19877 19880//19880 -f 23426//23426 19880//19880 23427//23427 -f 23422//23422 23423//23423 19886//19886 -f 19886//19886 23423//23423 23424//23424 -f 19886//19886 23424//23424 19884//19884 -f 19884//19884 23424//23424 23430//23430 -f 19884//19884 23430//23430 19882//19882 -f 19882//19882 23430//23430 23429//23429 -f 19882//19882 23429//23429 19880//19880 -f 19880//19880 23429//23429 23428//23428 -f 19880//19880 23428//23428 23427//23427 -f 19904//19904 23417//23417 19901//19901 -f 19901//19901 23417//23417 23416//23416 -f 19901//19901 23416//23416 19899//19899 -f 19899//19899 23416//23416 23420//23420 -f 19899//19899 23420//23420 19897//19897 -f 19897//19897 23420//23420 23419//23419 -f 19897//19897 23419//23419 19895//19895 -f 19895//19895 23419//23419 23418//23418 -f 19895//19895 23418//23418 19893//19893 -f 19893//19893 23418//23418 23421//23421 -f 19893//19893 23421//23421 19891//19891 -f 19891//19891 23421//23421 23422//23422 -f 19891//19891 23422//23422 19889//19889 -f 19889//19889 23422//23422 19886//19886 -f 22639//22639 22638//22638 22835//22835 -f 22835//22835 22638//22638 22546//22546 -f 22835//22835 22546//22546 22836//22836 -f 22836//22836 22546//22546 22545//22545 -f 22619//22619 22618//22618 22877//22877 -f 22877//22877 22618//22618 22507//22507 -f 22877//22877 22507//22507 22878//22878 -f 22878//22878 22507//22507 22506//22506 -f 21381//21381 21379//21379 23658//23658 -f 21345//21345 21344//21344 23659//23659 -f 19776//19776 19774//19774 23660//23660 -f 19766//19766 23661//23661 23662//23662 -f 19714//19714 19752//19752 23663//23663 -f 19722//19722 19720//19720 23664//23664 -f 21427//21427 23665//23665 23666//23666 -f 23667//23667 23668//23668 19788//19788 -f 23669//23669 23670//23670 21550//21550 -f 19936//19936 23417//23417 19934//19934 -f 19934//19934 23417//23417 23671//23671 -f 19934//19934 23671//23671 19932//19932 -f 19932//19932 23671//23671 23672//23672 -f 19932//19932 23672//23672 19990//19990 -f 19990//19990 23672//23672 23673//23673 -f 19990//19990 23673//23673 19988//19988 -f 19988//19988 23673//23673 23674//23674 -f 19988//19988 23674//23674 23675//23675 -f 23675//23675 23676//23676 19988//19988 -f 19988//19988 23676//23676 23677//23677 -f 19988//19988 23677//23677 19986//19986 -f 19986//19986 23677//23677 23678//23678 -f 19986//19986 23678//23678 19984//19984 -f 19984//19984 23678//23678 23679//23679 -f 19984//19984 23679//23679 19982//19982 -f 19982//19982 23679//23679 23680//23680 -f 19982//19982 23680//23680 23681//23681 -f 23681//23681 23682//23682 19982//19982 -f 19982//19982 23682//23682 23683//23683 -f 19982//19982 23683//23683 19977//19977 -f 19977//19977 23683//23683 23684//23684 -f 19977//19977 23684//23684 19978//19978 -f 19978//19978 23684//23684 23685//23685 -f 19978//19978 23685//23685 19996//19996 -f 23685//23685 23686//23686 19996//19996 -f 19996//19996 23686//23686 23687//23687 -f 19996//19996 23687//23687 19993//19993 -f 19993//19993 23687//23687 23688//23688 -f 19993//19993 23688//23688 23689//23689 -f 21548//21548 21547//21547 23690//23690 -f 23690//23690 21547//21547 21545//21545 -f 23690//23690 21545//21545 23689//23689 -f 23689//23689 21545//21545 19994//19994 -f 23689//23689 19994//19994 19993//19993 -f 21548//21548 23690//23690 21550//21550 -f 21550//21550 23690//23690 23691//23691 -f 21550//21550 23691//23691 23669//23669 -f 23692//23692 21554//21554 23670//23670 -f 23670//23670 21554//21554 21552//21552 -f 23670//23670 21552//21552 21550//21550 -f 23692//23692 23693//23693 21554//21554 -f 21554//21554 23693//23693 23694//23694 -f 21554//21554 23694//23694 21556//21556 -f 21556//21556 23694//23694 23695//23695 -f 21556//21556 23695//23695 21557//21557 -f 21557//21557 23695//23695 23696//23696 -f 21557//21557 23696//23696 21542//21542 -f 21542//21542 23696//23696 23697//23697 -f 21542//21542 23697//23697 21559//21559 -f 21559//21559 23697//23697 23698//23698 -f 21559//21559 23698//23698 21561//21561 -f 23699//23699 21568//21568 21566//21566 -f 23698//23698 23700//23700 21561//21561 -f 21561//21561 23700//23700 23701//23701 -f 21561//21561 23701//23701 21563//21563 -f 21563//21563 23701//23701 23702//23702 -f 21563//21563 23702//23702 21564//21564 -f 21564//21564 23702//23702 23703//23703 -f 21564//21564 23703//23703 21566//21566 -f 21566//21566 23703//23703 23704//23704 -f 21566//21566 23704//23704 23699//23699 -f 23699//23699 23705//23705 21568//21568 -f 21568//21568 23705//23705 23706//23706 -f 21568//21568 23706//23706 21569//21569 -f 23707//23707 21580//21580 21578//21578 -f 23707//23707 21578//21578 23708//23708 -f 23708//23708 21578//21578 21575//21575 -f 23708//23708 21575//21575 23709//23709 -f 23709//23709 21575//21575 21573//21573 -f 23709//23709 21573//21573 23706//23706 -f 23706//23706 21573//21573 21571//21571 -f 23706//23706 21571//21571 21569//21569 -f 23707//23707 23710//23710 21580//21580 -f 21580//21580 23710//23710 23711//23711 -f 21580//21580 23711//23711 21582//21582 -f 21582//21582 23711//23711 23712//23712 -f 21582//21582 23712//23712 21584//21584 -f 21584//21584 23712//23712 23713//23713 -f 21584//21584 23713//23713 21587//21587 -f 21587//21587 23713//23713 23714//23714 -f 21587//21587 23714//23714 21589//21589 -f 23714//23714 23715//23715 21589//21589 -f 21589//21589 23715//23715 23716//23716 -f 21589//21589 23716//23716 21591//21591 -f 21591//21591 23716//23716 21594//21594 -f 23716//23716 23717//23717 21594//21594 -f 21594//21594 23717//23717 23718//23718 -f 21594//21594 23718//23718 21609//21609 -f 21609//21609 23718//23718 23719//23719 -f 21609//21609 23719//23719 21608//21608 -f 21608//21608 23719//23719 23720//23720 -f 21608//21608 23720//23720 21606//21606 -f 21606//21606 23720//23720 23721//23721 -f 21606//21606 23721//23721 21604//21604 -f 21604//21604 23721//23721 23722//23722 -f 21604//21604 23722//23722 21602//21602 -f 23722//23722 23723//23723 21602//21602 -f 21602//21602 23723//23723 23724//23724 -f 21602//21602 23724//23724 21600//21600 -f 21600//21600 23724//23724 23725//23725 -f 21600//21600 23725//23725 21598//21598 -f 21598//21598 23725//23725 23726//23726 -f 21598//21598 23726//23726 21596//21596 -f 21596//21596 23726//23726 23727//23727 -f 21596//21596 23727//23727 19865//19865 -f 19865//19865 23727//23727 23728//23728 -f 19865//19865 23728//23728 19867//19867 -f 19867//19867 23728//23728 23729//23729 -f 19867//19867 23729//23729 19869//19869 -f 19869//19869 23729//23729 19870//19870 -f 19870//19870 23729//23729 23730//23730 -f 19870//19870 23730//23730 19872//19872 -f 19872//19872 23730//23730 23731//23731 -f 19872//19872 23731//23731 23732//23732 -f 19878//19878 19876//19876 23732//23732 -f 23732//23732 19876//19876 19874//19874 -f 23732//23732 19874//19874 19872//19872 -f 23732//23732 23733//23733 19878//19878 -f 19878//19878 23733//23733 23734//23734 -f 19878//19878 23734//23734 19879//19879 -f 23734//23734 23735//23735 19879//19879 -f 19879//19879 23735//23735 23736//23736 -f 19879//19879 23736//23736 19881//19881 -f 19881//19881 23736//23736 19883//19883 -f 19883//19883 23736//23736 23737//23737 -f 19883//19883 23737//23737 19885//19885 -f 19890//19890 19888//19888 23738//23738 -f 23738//23738 19888//19888 19887//19887 -f 23738//23738 19887//19887 23739//23739 -f 23739//23739 19887//19887 19885//19885 -f 23739//23739 19885//19885 23740//23740 -f 23740//23740 19885//19885 23737//23737 -f 19890//19890 23738//23738 19892//19892 -f 19892//19892 23738//23738 23741//23741 -f 19892//19892 23741//23741 19894//19894 -f 19894//19894 23741//23741 23742//23742 -f 19894//19894 23742//23742 19896//19896 -f 23742//23742 23743//23743 19896//19896 -f 19896//19896 23743//23743 23744//23744 -f 19896//19896 23744//23744 19898//19898 -f 23744//23744 23745//23745 19898//19898 -f 19898//19898 23745//23745 23746//23746 -f 19898//19898 23746//23746 19900//19900 -f 19900//19900 23746//23746 19902//19902 -f 19902//19902 23746//23746 23747//23747 -f 19902//19902 23747//23747 19903//19903 -f 19903//19903 23747//23747 23748//23748 -f 19903//19903 23748//23748 19905//19905 -f 19905//19905 23748//23748 23749//23749 -f 19905//19905 23749//23749 19907//19907 -f 19907//19907 23749//23749 19909//19909 -f 19909//19909 23749//23749 23750//23750 -f 19909//19909 23750//23750 19911//19911 -f 23750//23750 23751//23751 19911//19911 -f 19911//19911 23751//23751 23752//23752 -f 19911//19911 23752//23752 19913//19913 -f 19913//19913 23752//23752 23753//23753 -f 19913//19913 23753//23753 19914//19914 -f 19914//19914 23753//23753 23754//23754 -f 19914//19914 23754//23754 19916//19916 -f 19916//19916 23754//23754 19919//19919 -f 23754//23754 23755//23755 19919//19919 -f 19919//19919 23755//23755 23756//23756 -f 19919//19919 23756//23756 19920//19920 -f 19920//19920 23756//23756 19922//19922 -f 19922//19922 23756//23756 23757//23757 -f 19922//19922 23757//23757 19924//19924 -f 23758//23758 19926//19926 23759//23759 -f 23759//23759 19926//19926 19924//19924 -f 23759//23759 19924//19924 23760//23760 -f 23760//23760 19924//19924 23757//23757 -f 23758//23758 23761//23761 19926//19926 -f 19926//19926 23761//23761 23762//23762 -f 19926//19926 23762//23762 19927//19927 -f 19927//19927 23762//23762 23763//23763 -f 19927//19927 23763//23763 19929//19929 -f 23763//23763 23764//23764 19929//19929 -f 19929//19929 23764//23764 23765//23765 -f 19929//19929 23765//23765 19931//19931 -f 19931//19931 23765//23765 23766//23766 -f 19931//19931 23766//23766 21474//21474 -f 23767//23767 21476//21476 23768//23768 -f 23768//23768 21476//21476 21474//21474 -f 23768//23768 21474//21474 23769//23769 -f 23769//23769 21474//21474 23766//23766 -f 23767//23767 23770//23770 21476//21476 -f 21476//21476 23770//23770 23771//23771 -f 21476//21476 23771//23771 21478//21478 -f 21478//21478 23771//23771 21479//21479 -f 21479//21479 23771//23771 23772//23772 -f 21479//21479 23772//23772 21484//21484 -f 23772//23772 23773//23773 21484//21484 -f 21484//21484 23773//23773 23774//23774 -f 21484//21484 23774//23774 21482//21482 -f 21482//21482 23774//23774 23775//23775 -f 21482//21482 23775//23775 21480//21480 -f 21480//21480 23775//23775 21487//21487 -f 23775//23775 23776//23776 21487//21487 -f 21487//21487 23776//23776 23777//23777 -f 21487//21487 23777//23777 21510//21510 -f 21510//21510 23777//23777 23778//23778 -f 21510//21510 23778//23778 21508//21508 -f 21508//21508 23778//23778 21506//21506 -f 21506//21506 23778//23778 23779//23779 -f 21506//21506 23779//23779 21504//21504 -f 23779//23779 23780//23780 21504//21504 -f 21504//21504 23780//23780 23781//23781 -f 21504//21504 23781//23781 21502//21502 -f 21496//21496 21498//21498 23782//23782 -f 23781//23781 23783//23783 21502//21502 -f 21502//21502 23783//23783 23782//23782 -f 21502//21502 23782//23782 21500//21500 -f 21500//21500 23782//23782 21498//21498 -f 23782//23782 23784//23784 21496//21496 -f 21496//21496 23784//23784 23785//23785 -f 21496//21496 23785//23785 21494//21494 -f 23785//23785 23786//23786 21494//21494 -f 21494//21494 23786//23786 23787//23787 -f 21494//21494 23787//23787 21492//21492 -f 21492//21492 23787//23787 23788//23788 -f 21492//21492 23788//23788 21513//21513 -f 21513//21513 23788//23788 23789//23789 -f 21513//21513 23789//23789 21514//21514 -f 21514//21514 23789//23789 23790//23790 -f 21514//21514 23790//23790 21516//21516 -f 21516//21516 23790//23790 23791//23791 -f 21516//21516 23791//23791 21518//21518 -f 21518//21518 23791//23791 23792//23792 -f 21518//21518 23792//23792 21520//21520 -f 21520//21520 23792//23792 21522//21522 -f 23792//23792 23793//23793 21522//21522 -f 21522//21522 23793//23793 23794//23794 -f 21522//21522 23794//23794 21524//21524 -f 21524//21524 23794//23794 23795//23795 -f 21524//21524 23795//23795 21527//21527 -f 21527//21527 23795//23795 23796//23796 -f 21527//21527 23796//23796 21529//21529 -f 21529//21529 23796//23796 23797//23797 -f 21529//21529 23797//23797 21532//21532 -f 21532//21532 23797//23797 23798//23798 -f 21532//21532 23798//23798 21533//21533 -f 21533//21533 23798//23798 23799//23799 -f 23667//23667 19788//19788 23800//23800 -f 23799//23799 23801//23801 21533//21533 -f 21533//21533 23801//23801 23802//23802 -f 21533//21533 23802//23802 21537//21537 -f 21537//21537 23802//23802 23803//23803 -f 21537//21537 23803//23803 21534//21534 -f 21534//21534 23803//23803 23804//23804 -f 21534//21534 23804//23804 19788//19788 -f 19788//19788 23804//23804 23805//23805 -f 19788//19788 23805//23805 23800//23800 -f 19800//19800 19792//19792 23668//23668 -f 23668//23668 19792//19792 19790//19790 -f 23668//23668 19790//19790 19788//19788 -f 23668//23668 23806//23806 19800//19800 -f 19800//19800 23806//23806 23807//23807 -f 19800//19800 23807//23807 19801//19801 -f 19801//19801 23807//23807 23808//23808 -f 19801//19801 23808//23808 19803//19803 -f 19803//19803 23808//23808 19805//19805 -f 19805//19805 23808//23808 23809//23809 -f 19805//19805 23809//23809 19807//19807 -f 23810//23810 19811//19811 23809//23809 -f 23809//23809 19811//19811 19809//19809 -f 23809//23809 19809//19809 19807//19807 -f 23810//23810 23811//23811 19811//19811 -f 19811//19811 23811//23811 23812//23812 -f 19811//19811 23812//23812 19813//19813 -f 19813//19813 23812//23812 19814//19814 -f 19814//19814 23812//23812 19796//19796 -f 19796//19796 23812//23812 23813//23813 -f 19796//19796 23813//23813 19797//19797 -f 19797//19797 23813//23813 19798//19798 -f 19798//19798 23813//23813 23814//23814 -f 19798//19798 23814//23814 19815//19815 -f 19815//19815 23814//23814 19816//19816 -f 19816//19816 23814//23814 23815//23815 -f 19816//19816 23815//23815 19818//19818 -f 19818//19818 23815//23815 23816//23816 -f 19818//19818 23816//23816 19820//19820 -f 23816//23816 23817//23817 19820//19820 -f 19820//19820 23817//23817 23818//23818 -f 19820//19820 23818//23818 19822//19822 -f 19822//19822 23818//23818 23819//23819 -f 19822//19822 23819//23819 19824//19824 -f 19827//19827 19826//19826 23820//23820 -f 19824//19824 23819//23819 19826//19826 -f 19826//19826 23819//23819 23821//23821 -f 19826//19826 23821//23821 23820//23820 -f 19831//19831 19829//19829 23822//23822 -f 23822//23822 19829//19829 19827//19827 -f 23822//23822 19827//19827 23823//23823 -f 23823//23823 19827//19827 23820//23820 -f 19831//19831 23822//23822 19834//19834 -f 19834//19834 23822//23822 23824//23824 -f 19834//19834 23824//23824 19851//19851 -f 19851//19851 23824//23824 23825//23825 -f 19851//19851 23825//23825 19850//19850 -f 19850//19850 23825//23825 23826//23826 -f 19850//19850 23826//23826 19848//19848 -f 19848//19848 23826//23826 23827//23827 -f 19848//19848 23827//23827 19846//19846 -f 19846//19846 23827//23827 23828//23828 -f 19846//19846 23828//23828 19844//19844 -f 19844//19844 23828//23828 19842//19842 -f 19842//19842 23828//23828 23829//23829 -f 19842//19842 23829//23829 19840//19840 -f 19840//19840 23829//23829 23830//23830 -f 19840//19840 23830//23830 19838//19838 -f 23830//23830 23831//23831 19838//19838 -f 19838//19838 23831//23831 23832//23832 -f 19838//19838 23832//23832 19836//19836 -f 19836//19836 23832//23832 19856//19856 -f 19856//19856 23832//23832 23833//23833 -f 19856//19856 23833//23833 19854//19854 -f 19854//19854 23833//23833 23834//23834 -f 19854//19854 23834//23834 19852//19852 -f 23835//23835 19861//19861 23836//23836 -f 23836//23836 19861//19861 19852//19852 -f 23836//23836 19852//19852 23837//23837 -f 23837//23837 19852//19852 23834//23834 -f 23835//23835 23838//23838 19861//19861 -f 19861//19861 23838//23838 23839//23839 -f 19861//19861 23839//23839 19859//19859 -f 19859//19859 23839//23839 23840//23840 -f 19859//19859 23840//23840 21408//21408 -f 21408//21408 23840//23840 23841//23841 -f 21408//21408 23841//23841 21411//21411 -f 23842//23842 23843//23843 21418//21418 -f 21418//21418 23843//23843 23844//23844 -f 21418//21418 23844//23844 23845//23845 -f 23841//23841 23846//23846 21411//21411 -f 21411//21411 23846//23846 23847//23847 -f 21411//21411 23847//23847 21413//21413 -f 21413//21413 23847//23847 23848//23848 -f 21413//21413 23848//23848 21414//21414 -f 21414//21414 23848//23848 23842//23842 -f 21414//21414 23842//23842 21416//21416 -f 21416//21416 23842//23842 21418//21418 -f 23665//23665 21427//21427 23849//23849 -f 23849//23849 21427//21427 21424//21424 -f 23849//23849 21424//21424 23850//23850 -f 23850//23850 21424//21424 21422//21422 -f 23850//23850 21422//21422 23845//23845 -f 23845//23845 21422//21422 21420//21420 -f 23845//23845 21420//21420 21418//21418 -f 23851//23851 21438//21438 23852//23852 -f 23852//23852 21438//21438 21437//21437 -f 23852//23852 21437//21437 23853//23853 -f 23853//23853 21437//21437 21435//21435 -f 23853//23853 21435//21435 23854//23854 -f 23854//23854 21435//21435 21433//21433 -f 23854//23854 21433//21433 23855//23855 -f 23855//23855 21433//21433 21431//21431 -f 23855//23855 21431//21431 23666//23666 -f 23666//23666 21431//21431 21429//21429 -f 23666//23666 21429//21429 21427//21427 -f 23856//23856 23857//23857 21449//21449 -f 21449//21449 21448//21448 23856//23856 -f 23856//23856 21448//21448 21443//21443 -f 23856//23856 21443//21443 23858//23858 -f 23858//23858 21443//21443 21442//21442 -f 23858//23858 21442//21442 23851//23851 -f 23851//23851 21442//21442 21440//21440 -f 23851//23851 21440//21440 21438//21438 -f 21449//21449 23857//23857 23859//23859 -f 21449//21449 23859//23859 21451//21451 -f 21451//21451 23859//23859 23860//23860 -f 21451//21451 23860//23860 21453//21453 -f 21453//21453 23860//23860 23861//23861 -f 21453//21453 23861//23861 21455//21455 -f 23861//23861 23862//23862 21455//21455 -f 21455//21455 23862//23862 23863//23863 -f 21455//21455 23863//23863 21456//21456 -f 21456//21456 23863//23863 23864//23864 -f 21456//21456 23864//23864 21447//21447 -f 23864//23864 23865//23865 21447//21447 -f 21447//21447 23865//23865 23866//23866 -f 21447//21447 23866//23866 21457//21457 -f 21457//21457 23866//23866 23867//23867 -f 21457//21457 23867//23867 21458//21458 -f 21458//21458 23867//23867 23868//23868 -f 21458//21458 23868//23868 21461//21461 -f 21461//21461 23868//23868 21462//21462 -f 21462//21462 23868//23868 23869//23869 -f 21462//21462 23869//23869 21464//21464 -f 21464//21464 23869//23869 23870//23870 -f 21464//21464 23870//23870 21466//21466 -f 21472//21472 21470//21470 23871//23871 -f 23871//23871 21470//21470 21468//21468 -f 23871//23871 21468//21468 23872//23872 -f 23872//23872 21468//21468 21466//21466 -f 23872//23872 21466//21466 23873//23873 -f 23873//23873 21466//21466 23870//23870 -f 21472//21472 23871//23871 19716//19716 -f 19716//19716 23871//23871 23874//23874 -f 19716//19716 23874//23874 23875//23875 -f 23875//23875 23876//23876 19716//19716 -f 19716//19716 23876//23876 23877//23877 -f 19716//19716 23877//23877 19718//19718 -f 23877//23877 23878//23878 19718//19718 -f 19718//19718 23878//23878 23879//23879 -f 19718//19718 23879//23879 19720//19720 -f 19720//19720 23879//23879 23880//23880 -f 19720//19720 23880//23880 23664//23664 -f 19722//19722 23664//23664 19724//19724 -f 19724//19724 23664//23664 23881//23881 -f 19724//19724 23881//23881 19725//19725 -f 19725//19725 23881//23881 23882//23882 -f 19725//19725 23882//23882 19728//19728 -f 23882//23882 23883//23883 19728//19728 -f 19728//19728 23883//23883 23884//23884 -f 19728//19728 23884//23884 19735//19735 -f 23884//23884 23885//23885 19735//19735 -f 19735//19735 23885//23885 23886//23886 -f 19735//19735 23886//23886 19736//19736 -f 19736//19736 23886//23886 23887//23887 -f 19736//19736 23887//23887 19738//19738 -f 19738//19738 23887//23887 19740//19740 -f 23887//23887 23888//23888 19740//19740 -f 19740//19740 23888//23888 23889//23889 -f 19740//19740 23889//23889 19741//19741 -f 19741//19741 23889//23889 19732//19732 -f 19732//19732 23889//23889 23890//23890 -f 19732//19732 23890//23890 19734//19734 -f 19734//19734 23890//23890 23891//23891 -f 19734//19734 23891//23891 19744//19744 -f 23891//23891 23892//23892 19744//19744 -f 19744//19744 23892//23892 23893//23893 -f 19744//19744 23893//23893 19742//19742 -f 19742//19742 23893//23893 19749//19749 -f 19749//19749 23893//23893 23894//23894 -f 19749//19749 23894//23894 19747//19747 -f 19747//19747 23894//23894 23895//23895 -f 19747//19747 23895//23895 19752//19752 -f 19752//19752 23895//23895 23896//23896 -f 19752//19752 23896//23896 23663//23663 -f 19714//19714 23663//23663 19755//19755 -f 19755//19755 23663//23663 23897//23897 -f 19755//19755 23897//23897 19756//19756 -f 19756//19756 23897//23897 19758//19758 -f 19758//19758 23897//23897 23898//23898 -f 19758//19758 23898//23898 19760//19760 -f 19760//19760 23898//23898 23899//23899 -f 19760//19760 23899//23899 19762//19762 -f 23899//23899 23900//23900 19762//19762 -f 19762//19762 23900//23900 23901//23901 -f 19762//19762 23901//23901 19764//19764 -f 19764//19764 23901//23901 23661//23661 -f 19764//19764 23661//23661 19766//19766 -f 23660//23660 19774//19774 23902//23902 -f 23902//23902 19774//19774 19771//19771 -f 23902//23902 19771//19771 23903//23903 -f 23903//23903 19771//19771 19769//19769 -f 23903//23903 19769//19769 23662//23662 -f 23662//23662 19769//19769 19768//19768 -f 23662//23662 19768//19768 19766//19766 -f 19776//19776 23660//23660 19777//19777 -f 19777//19777 23660//23660 23904//23904 -f 19777//19777 23904//23904 19779//19779 -f 19779//19779 23904//23904 19781//19781 -f 19781//19781 23904//23904 23905//23905 -f 19781//19781 23905//23905 19782//19782 -f 19782//19782 23905//23905 23906//23906 -f 19782//19782 23906//23906 23907//23907 -f 23659//23659 21344//21344 23908//23908 -f 23908//23908 21344//21344 19786//19786 -f 23908//23908 19786//19786 23907//23907 -f 23907//23907 19786//19786 19784//19784 -f 23907//23907 19784//19784 19782//19782 -f 21345//21345 23659//23659 21347//21347 -f 21347//21347 23659//23659 23909//23909 -f 21347//21347 23909//23909 21349//21349 -f 21349//21349 23909//23909 21351//21351 -f 21351//21351 23909//23909 23910//23910 -f 21351//21351 23910//23910 21353//21353 -f 21365//21365 21367//21367 23911//23911 -f 23911//23911 21367//21367 21353//21353 -f 23911//23911 21353//21353 23912//23912 -f 23912//23912 21353//21353 23910//23910 -f 21365//21365 23911//23911 21363//21363 -f 21363//21363 23911//23911 23913//23913 -f 21363//21363 23913//23913 21360//21360 -f 23913//23913 23914//23914 21360//21360 -f 21360//21360 23914//23914 23915//23915 -f 21360//21360 23915//23915 21358//21358 -f 21358//21358 23915//23915 23916//23916 -f 21358//21358 23916//23916 21356//21356 -f 21356//21356 23916//23916 23917//23917 -f 21356//21356 23917//23917 21372//21372 -f 23917//23917 23918//23918 21372//21372 -f 21372//21372 23918//23918 23919//23919 -f 21372//21372 23919//23919 21373//21373 -f 21373//21373 23919//23919 23920//23920 -f 21373//21373 23920//23920 21375//21375 -f 21375//21375 23920//23920 23921//23921 -f 21375//21375 23921//23921 21377//21377 -f 21377//21377 23921//23921 21379//21379 -f 21379//21379 23921//23921 23922//23922 -f 21379//21379 23922//23922 23658//23658 -f 21381//21381 23658//23658 21382//21382 -f 21382//21382 23658//23658 23923//23923 -f 21382//21382 23923//23923 21369//21369 -f 21369//21369 23923//23923 23924//23924 -f 21369//21369 23924//23924 21370//21370 -f 23924//23924 23925//23925 21370//21370 -f 21370//21370 23925//23925 23926//23926 -f 21370//21370 23926//23926 21391//21391 -f 21391//21391 23926//23926 23927//23927 -f 21391//21391 23927//23927 21389//21389 -f 21389//21389 23927//23927 23928//23928 -f 21389//21389 23928//23928 21387//21387 -f 22839//22839 22533//22533 22837//22837 -f 22837//22837 22533//22533 22546//22546 -f 22837//22837 22546//22546 22636//22636 -f 22636//22636 22546//22546 22638//22638 -f 22878//22878 22506//22506 22876//22876 -f 22876//22876 22506//22506 22549//22549 -f 22876//22876 22549//22549 22581//22581 -f 22581//22581 22549//22549 22579//22579 -f 21531//21531 21539//21539 23722//23722 -f 19808//19808 23734//23734 23733//23733 -f 21355//21355 21354//21354 23666//23666 -f 23666//23666 21354//21354 23855//23855 -f 19672//19672 23893//23893 23892//23892 -f 19687//19687 23898//23898 23897//23897 -f 21319//21319 23928//23928 21317//21317 -f 21317//21317 23928//23928 23927//23927 -f 21317//21317 23927//23927 21315//21315 -f 21315//21315 23927//23927 23926//23926 -f 21315//21315 23926//23926 23925//23925 -f 23923//23923 21309//21309 23924//23924 -f 23924//23924 21309//21309 21311//21311 -f 23924//23924 21311//21311 23925//23925 -f 23925//23925 21311//21311 21313//21313 -f 23925//23925 21313//21313 21315//21315 -f 23923//23923 23658//23658 21309//21309 -f 21309//21309 23658//23658 23922//23922 -f 21309//21309 23922//23922 21307//21307 -f 21307//21307 23922//23922 21305//21305 -f 21305//21305 23922//23922 23921//23921 -f 21305//21305 23921//23921 21298//21298 -f 21298//21298 23921//23921 23920//23920 -f 21298//21298 23920//23920 21296//21296 -f 23920//23920 23919//23919 21296//21296 -f 21296//21296 23919//23919 23918//23918 -f 21296//21296 23918//23918 21294//21294 -f 21294//21294 23918//23918 23917//23917 -f 21294//21294 23917//23917 21292//21292 -f 23917//23917 23916//23916 21292//21292 -f 21292//21292 23916//23916 23915//23915 -f 21292//21292 23915//23915 21291//21291 -f 21291//21291 23915//23915 23914//23914 -f 23911//23911 21285//21285 23913//23913 -f 23913//23913 21285//21285 21287//21287 -f 23913//23913 21287//21287 23914//23914 -f 23914//23914 21287//21287 21289//21289 -f 23914//23914 21289//21289 21291//21291 -f 23911//23911 21279//21279 21283//21283 -f 23911//23911 21283//21283 21285//21285 -f 23911//23911 23912//23912 21279//21279 -f 21279//21279 23912//23912 23910//23910 -f 21279//21279 23910//23910 21277//21277 -f 23910//23910 23909//23909 21277//21277 -f 21277//21277 23909//23909 23659//23659 -f 21277//21277 23659//23659 21273//21273 -f 21273//21273 23659//23659 23908//23908 -f 21273//21273 23908//23908 23907//23907 -f 23904//23904 19705//19705 23905//23905 -f 23905//23905 19705//19705 19711//19711 -f 23905//23905 19711//19711 23906//23906 -f 23906//23906 19711//19711 19710//19710 -f 23906//23906 19710//19710 23907//23907 -f 23907//23907 19710//19710 19708//19708 -f 23907//23907 19708//19708 21273//21273 -f 19693//19693 19695//19695 23903//23903 -f 23903//23903 19695//19695 19697//19697 -f 23903//23903 19697//19697 23902//23902 -f 23902//23902 19697//19697 19699//19699 -f 23902//23902 19699//19699 23660//23660 -f 23660//23660 19699//19699 19701//19701 -f 23660//23660 19701//19701 23904//23904 -f 23904//23904 19701//19701 19703//19703 -f 23904//23904 19703//19703 19705//19705 -f 23903//23903 23662//23662 19693//19693 -f 19693//19693 23662//23662 23661//23661 -f 19693//19693 23661//23661 19691//19691 -f 19691//19691 23661//23661 23901//23901 -f 19691//19691 23901//23901 19689//19689 -f 19689//19689 23901//23901 23900//23900 -f 19689//19689 23900//23900 19687//19687 -f 19687//19687 23900//23900 23899//23899 -f 19687//19687 23899//23899 23898//23898 -f 23893//23893 19672//19672 23894//23894 -f 19672//19672 19675//19675 23894//23894 -f 23894//23894 19675//19675 19677//19677 -f 23894//23894 19677//19677 23895//23895 -f 23895//23895 19677//19677 19679//19679 -f 23895//23895 19679//19679 23896//23896 -f 23896//23896 19679//19679 19681//19681 -f 23896//23896 19681//19681 23663//23663 -f 23663//23663 19681//19681 19683//19683 -f 23663//23663 19683//19683 23897//23897 -f 23897//23897 19683//19683 19684//19684 -f 23897//23897 19684//19684 19687//19687 -f 23889//23889 19664//19664 23890//23890 -f 23890//23890 19664//19664 19666//19666 -f 23890//23890 19666//19666 23891//23891 -f 23891//23891 19666//19666 19668//19668 -f 23891//23891 19668//19668 23892//23892 -f 23892//23892 19668//19668 19670//19670 -f 23892//23892 19670//19670 19672//19672 -f 23889//23889 23888//23888 19664//19664 -f 19664//19664 23888//23888 23887//23887 -f 19664//19664 23887//23887 19662//19662 -f 19662//19662 23887//23887 23886//23886 -f 19662//19662 23886//23886 19660//19660 -f 23886//23886 23885//23885 19660//19660 -f 19660//19660 23885//23885 23884//23884 -f 19660//19660 23884//23884 19658//19658 -f 19658//19658 23884//23884 23883//23883 -f 19658//19658 23883//23883 19656//19656 -f 23883//23883 23882//23882 19656//19656 -f 19656//19656 23882//23882 23881//23881 -f 19656//19656 23881//23881 19654//19654 -f 23881//23881 23664//23664 19654//19654 -f 19654//19654 23664//23664 23880//23880 -f 19654//19654 23880//23880 19652//19652 -f 19652//19652 23880//23880 23879//23879 -f 19652//19652 23879//23879 19650//19650 -f 19650//19650 23879//23879 23878//23878 -f 23878//23878 23877//23877 19650//19650 -f 19650//19650 23877//23877 23876//23876 -f 19650//19650 23876//23876 19648//19648 -f 23876//23876 23875//23875 19648//19648 -f 19648//19648 23875//23875 23874//23874 -f 19648//19648 23874//23874 21405//21405 -f 21405//21405 23874//23874 23871//23871 -f 21405//21405 23871//23871 21402//21402 -f 21402//21402 23871//23871 23872//23872 -f 21402//21402 23872//23872 21401//21401 -f 21401//21401 23872//23872 23873//23873 -f 21401//21401 23873//23873 21399//21399 -f 21399//21399 23873//23873 21396//21396 -f 21396//21396 23873//23873 23870//23870 -f 21396//21396 23870//23870 21394//21394 -f 23865//23865 21384//21384 23866//23866 -f 23866//23866 21384//21384 21340//21340 -f 23866//23866 21340//21340 23867//23867 -f 23867//23867 21340//21340 21339//21339 -f 23867//23867 21339//21339 23868//23868 -f 23868//23868 21339//21339 21394//21394 -f 23868//23868 21394//21394 23869//23869 -f 23869//23869 21394//21394 23870//23870 -f 23865//23865 23864//23864 21384//21384 -f 21384//21384 23864//23864 23863//23863 -f 21384//21384 23863//23863 21386//21386 -f 21386//21386 23863//23863 23862//23862 -f 21386//21386 23862//23862 21388//21388 -f 21388//21388 23862//23862 23861//23861 -f 21388//21388 23861//23861 21390//21390 -f 21390//21390 23861//23861 23860//23860 -f 21393//21393 21392//21392 23857//23857 -f 23857//23857 21392//21392 21390//21390 -f 23857//23857 21390//21390 23859//23859 -f 23859//23859 21390//21390 23860//23860 -f 21393//21393 23857//23857 23856//23856 -f 21393//21393 23856//23856 21371//21371 -f 21371//21371 23856//23856 23858//23858 -f 21371//21371 23858//23858 21380//21380 -f 21380//21380 23858//23858 23851//23851 -f 21380//21380 23851//23851 23852//23852 -f 23855//23855 21354//21354 23854//23854 -f 23854//23854 21354//21354 21374//21374 -f 23854//23854 21374//21374 23853//23853 -f 23853//23853 21374//21374 21376//21376 -f 23853//23853 21376//21376 23852//23852 -f 23852//23852 21376//21376 21378//21378 -f 23852//23852 21378//21378 21380//21380 -f 21355//21355 23666//23666 21357//21357 -f 21357//21357 23666//23666 23665//23665 -f 21357//21357 23665//23665 21359//21359 -f 21359//21359 23665//23665 23849//23849 -f 21359//21359 23849//23849 21361//21361 -f 21361//21361 23849//23849 23850//23850 -f 21361//21361 23850//23850 21362//21362 -f 21362//21362 23850//23850 21364//21364 -f 21364//21364 23850//23850 23845//23845 -f 21364//21364 23845//23845 21366//21366 -f 21366//21366 23845//23845 23844//23844 -f 21366//21366 23844//23844 21368//21368 -f 21368//21368 23844//23844 23843//23843 -f 21368//21368 23843//23843 21352//21352 -f 21352//21352 23843//23843 23842//23842 -f 21352//21352 23842//23842 23848//23848 -f 21352//21352 23848//23848 21350//21350 -f 21350//21350 23848//23848 23847//23847 -f 21350//21350 23847//23847 21348//21348 -f 21348//21348 23847//23847 23846//23846 -f 21348//21348 23846//23846 21346//21346 -f 21346//21346 23846//23846 23841//23841 -f 21346//21346 23841//23841 21343//21343 -f 23841//23841 23840//23840 21343//21343 -f 21343//21343 23840//23840 23839//23839 -f 21343//21343 23839//23839 19785//19785 -f 19785//19785 23839//23839 23838//23838 -f 19785//19785 23838//23838 19783//19783 -f 19783//19783 23838//23838 23835//23835 -f 19783//19783 23835//23835 19780//19780 -f 23835//23835 23836//23836 19780//19780 -f 19780//19780 23836//23836 23837//23837 -f 19780//19780 23837//23837 19778//19778 -f 19778//19778 23837//23837 23834//23834 -f 19778//19778 23834//23834 23833//23833 -f 23831//23831 19772//19772 23832//23832 -f 23832//23832 19772//19772 19773//19773 -f 23832//23832 19773//19773 23833//23833 -f 23833//23833 19773//19773 19775//19775 -f 23833//23833 19775//19775 19778//19778 -f 23829//23829 19765//19765 23830//23830 -f 23830//23830 19765//19765 19767//19767 -f 23830//23830 19767//19767 23831//23831 -f 23831//23831 19767//19767 19770//19770 -f 23831//23831 19770//19770 19772//19772 -f 23829//23829 23828//23828 19765//19765 -f 19765//19765 23828//23828 19763//19763 -f 19763//19763 23828//23828 19761//19761 -f 19761//19761 23828//23828 23827//23827 -f 19761//19761 23827//23827 19759//19759 -f 23827//23827 23826//23826 19759//19759 -f 19759//19759 23826//23826 23825//23825 -f 19759//19759 23825//23825 19757//19757 -f 19757//19757 23825//23825 23824//23824 -f 19757//19757 23824//23824 19712//19712 -f 19712//19712 23824//23824 23822//23822 -f 19712//19712 23822//23822 19713//19713 -f 19713//19713 23822//23822 19753//19753 -f 19753//19753 23822//23822 23823//23823 -f 19753//19753 23823//23823 19754//19754 -f 19754//19754 23823//23823 23820//23820 -f 19754//19754 23820//23820 19748//19748 -f 19748//19748 23820//23820 23821//23821 -f 19748//19748 23821//23821 19750//19750 -f 19750//19750 23821//23821 23819//23819 -f 19750//19750 23819//23819 19751//19751 -f 23819//23819 23818//23818 19751//19751 -f 19751//19751 23818//23818 23817//23817 -f 19751//19751 23817//23817 19743//19743 -f 19743//19743 23817//23817 19745//19745 -f 19745//19745 23817//23817 23816//23816 -f 19745//19745 23816//23816 19746//19746 -f 19746//19746 23816//23816 23815//23815 -f 19746//19746 23815//23815 19733//19733 -f 19733//19733 23815//23815 19731//19731 -f 19731//19731 23815//23815 23814//23814 -f 19731//19731 23814//23814 19739//19739 -f 23814//23814 23813//23813 19739//19739 -f 19739//19739 23813//23813 23812//23812 -f 19739//19739 23812//23812 19737//19737 -f 19737//19737 23812//23812 19726//19726 -f 23809//23809 19727//19727 23810//23810 -f 23810//23810 19727//19727 19726//19726 -f 23810//23810 19726//19726 23811//23811 -f 23811//23811 19726//19726 23812//23812 -f 19723//19723 19730//19730 23809//23809 -f 23809//23809 19730//19730 19729//19729 -f 23809//23809 19729//19729 19727//19727 -f 23668//23668 23667//23667 19715//19715 -f 23809//23809 23808//23808 19723//19723 -f 19723//19723 23808//23808 23807//23807 -f 19723//19723 23807//23807 19721//19721 -f 19721//19721 23807//23807 23806//23806 -f 19721//19721 23806//23806 19719//19719 -f 19719//19719 23806//23806 23668//23668 -f 19719//19719 23668//23668 19717//19717 -f 19717//19717 23668//23668 19715//19715 -f 23667//23667 23800//23800 19715//19715 -f 19715//19715 23800//23800 23805//23805 -f 19715//19715 23805//23805 21471//21471 -f 21471//21471 23805//23805 23804//23804 -f 21471//21471 23804//23804 23803//23803 -f 23802//23802 21467//21467 23803//23803 -f 23803//23803 21467//21467 21469//21469 -f 23803//23803 21469//21469 21471//21471 -f 23802//23802 23801//23801 21467//21467 -f 21467//21467 23801//23801 23799//23799 -f 21467//21467 23799//23799 21465//21465 -f 21465//21465 23799//23799 21463//21463 -f 21463//21463 23799//23799 23798//23798 -f 21463//21463 23798//23798 21460//21460 -f 23798//23798 23797//23797 21460//21460 -f 21460//21460 23797//23797 23796//23796 -f 21460//21460 23796//23796 21459//21459 -f 21459//21459 23796//23796 23795//23795 -f 21459//21459 23795//23795 21445//21445 -f 21445//21445 23795//23795 23794//23794 -f 21445//21445 23794//23794 21446//21446 -f 21446//21446 23794//23794 23793//23793 -f 21446//21446 23793//23793 23792//23792 -f 21450//21450 21452//21452 23792//23792 -f 23792//23792 21452//21452 21454//21454 -f 23792//23792 21454//21454 21446//21446 -f 23792//23792 23791//23791 21450//21450 -f 21450//21450 23791//23791 23790//23790 -f 21450//21450 23790//23790 21444//21444 -f 21444//21444 23790//23790 23789//23789 -f 21444//21444 23789//23789 21441//21441 -f 21441//21441 23789//23789 23788//23788 -f 21441//21441 23788//23788 21439//21439 -f 21439//21439 23788//23788 23787//23787 -f 21439//21439 23787//23787 23786//23786 -f 23786//23786 23785//23785 21439//21439 -f 21439//21439 23785//23785 23784//23784 -f 21439//21439 23784//23784 21436//21436 -f 21436//21436 23784//23784 21434//21434 -f 21434//21434 23784//23784 23782//23782 -f 21434//21434 23782//23782 21432//21432 -f 23782//23782 23783//23783 21432//21432 -f 21432//21432 23783//23783 23781//23781 -f 21432//21432 23781//23781 21430//21430 -f 23781//23781 23780//23780 21430//21430 -f 21430//21430 23780//23780 23779//23779 -f 21430//21430 23779//23779 21428//21428 -f 21428//21428 23779//23779 23778//23778 -f 21428//21428 23778//23778 21426//21426 -f 21426//21426 23778//23778 23777//23777 -f 21426//21426 23777//23777 21425//21425 -f 21425//21425 23777//23777 23776//23776 -f 21425//21425 23776//23776 21423//21423 -f 21423//21423 23776//23776 21421//21421 -f 21421//21421 23776//23776 23775//23775 -f 21421//21421 23775//23775 21419//21419 -f 21419//21419 23775//23775 23774//23774 -f 21419//21419 23774//23774 21417//21417 -f 21417//21417 23774//23774 23773//23773 -f 21417//21417 23773//23773 21415//21415 -f 21415//21415 23773//23773 21412//21412 -f 21412//21412 23773//23773 23772//23772 -f 21412//21412 23772//23772 21410//21410 -f 21410//21410 23772//23772 23771//23771 -f 21410//21410 23771//23771 23770//23770 -f 23764//23764 19862//19862 19860//19860 -f 23770//23770 23767//23767 21410//21410 -f 21410//21410 23767//23767 23768//23768 -f 21410//21410 23768//23768 21409//21409 -f 21409//21409 23768//23768 23769//23769 -f 21409//21409 23769//23769 21407//21407 -f 21407//21407 23769//23769 23766//23766 -f 21407//21407 23766//23766 19860//19860 -f 19860//19860 23766//23766 23765//23765 -f 19860//19860 23765//23765 23764//23764 -f 23761//23761 19863//19863 23762//23762 -f 23762//23762 19863//19863 19862//19862 -f 23762//23762 19862//19862 23763//23763 -f 23763//23763 19862//19862 23764//23764 -f 19839//19839 19837//19837 23755//23755 -f 23755//23755 19837//19837 19858//19858 -f 23755//23755 19858//19858 23756//23756 -f 23756//23756 19858//19858 19857//19857 -f 23756//23756 19857//19857 23757//23757 -f 23757//23757 19857//19857 19855//19855 -f 23757//23757 19855//19855 23760//23760 -f 23760//23760 19855//19855 19853//19853 -f 23760//23760 19853//19853 23759//23759 -f 23759//23759 19853//19853 19863//19863 -f 23759//23759 19863//19863 23758//23758 -f 23758//23758 19863//19863 23761//23761 -f 23754//23754 19843//19843 23755//23755 -f 23755//23755 19843//19843 19841//19841 -f 23755//23755 19841//19841 19839//19839 -f 23754//23754 23753//23753 19843//19843 -f 19843//19843 23753//23753 23752//23752 -f 19843//19843 23752//23752 19845//19845 -f 19845//19845 23752//23752 19847//19847 -f 19847//19847 23752//23752 23751//23751 -f 19847//19847 23751//23751 19849//19849 -f 23751//23751 23750//23750 19849//19849 -f 19849//19849 23750//23750 23749//23749 -f 19849//19849 23749//23749 19835//19835 -f 19835//19835 23749//23749 23748//23748 -f 19835//19835 23748//23748 19833//19833 -f 19833//19833 23748//23748 19832//19832 -f 19832//19832 23748//23748 23747//23747 -f 19832//19832 23747//23747 19830//19830 -f 19830//19830 23747//23747 23746//23746 -f 19830//19830 23746//23746 19828//19828 -f 23746//23746 23745//23745 19828//19828 -f 19828//19828 23745//23745 23744//23744 -f 19828//19828 23744//23744 19825//19825 -f 19825//19825 23744//23744 19823//19823 -f 19823//19823 23744//23744 23743//23743 -f 19823//19823 23743//23743 19821//19821 -f 23738//23738 19819//19819 23741//23741 -f 23741//23741 19819//19819 19821//19821 -f 23741//23741 19821//19821 23742//23742 -f 23742//23742 19821//19821 23743//23743 -f 19794//19794 19799//19799 23738//23738 -f 23738//23738 19799//19799 19817//19817 -f 23738//23738 19817//19817 19819//19819 -f 23738//23738 23739//23739 19794//19794 -f 19794//19794 23739//23739 23740//23740 -f 19794//19794 23740//23740 19795//19795 -f 19795//19795 23740//23740 23737//23737 -f 19795//19795 23737//23737 19812//19812 -f 19812//19812 23737//23737 23736//23736 -f 19812//19812 23736//23736 19810//19810 -f 19810//19810 23736//23736 19808//19808 -f 19808//19808 23736//23736 23735//23735 -f 19808//19808 23735//23735 23734//23734 -f 19802//19802 19804//19804 23733//23733 -f 23733//23733 19804//19804 19806//19806 -f 23733//23733 19806//19806 19808//19808 -f 23733//23733 23732//23732 19802//19802 -f 19802//19802 23732//23732 23731//23731 -f 19802//19802 23731//23731 19793//19793 -f 19793//19793 23731//23731 23730//23730 -f 19793//19793 23730//23730 19791//19791 -f 19791//19791 23730//23730 23729//23729 -f 19791//19791 23729//23729 19789//19789 -f 19789//19789 23729//23729 23728//23728 -f 19789//19789 23728//23728 19787//19787 -f 19787//19787 23728//23728 23727//23727 -f 19787//19787 23727//23727 21535//21535 -f 21535//21535 23727//23727 21536//21536 -f 23727//23727 23726//23726 21536//21536 -f 21536//21536 23726//23726 23725//23725 -f 21536//21536 23725//23725 21538//21538 -f 21538//21538 23725//23725 23724//23724 -f 21538//21538 23724//23724 21539//21539 -f 21539//21539 23724//23724 23723//23723 -f 21539//21539 23723//23723 23722//23722 -f 21531//21531 23722//23722 21530//21530 -f 21530//21530 23722//23722 23721//23721 -f 21530//21530 23721//23721 21528//21528 -f 23721//23721 23720//23720 21528//21528 -f 21528//21528 23720//23720 23719//23719 -f 21528//21528 23719//23719 21526//21526 -f 21526//21526 23719//23719 23718//23718 -f 21526//21526 23718//23718 21525//21525 -f 21525//21525 23718//23718 23717//23717 -f 21525//21525 23717//23717 21523//21523 -f 21523//21523 23717//23717 23716//23716 -f 21523//21523 23716//23716 21521//21521 -f 23716//23716 23715//23715 21521//21521 -f 21521//21521 23715//23715 23714//23714 -f 21521//21521 23714//23714 21519//21519 -f 21519//21519 23714//23714 21517//21517 -f 21517//21517 23714//23714 23713//23713 -f 21517//21517 23713//23713 21515//21515 -f 23708//23708 23709//23709 21497//21497 -f 21497//21497 23709//23709 23706//23706 -f 21497//21497 23706//23706 21499//21499 -f 23713//23713 23712//23712 21515//21515 -f 21515//21515 23712//23712 23711//23711 -f 21515//21515 23711//23711 21490//21490 -f 21490//21490 23711//23711 23710//23710 -f 21490//21490 23710//23710 21491//21491 -f 21491//21491 23710//23710 23707//23707 -f 21491//21491 23707//23707 21493//21493 -f 21493//21493 23707//23707 23708//23708 -f 21493//21493 23708//23708 21495//21495 -f 21495//21495 23708//23708 21497//21497 -f 21499//21499 23706//23706 21501//21501 -f 21501//21501 23706//23706 23705//23705 -f 21501//21501 23705//23705 21503//21503 -f 21503//21503 23705//23705 23699//23699 -f 21503//21503 23699//23699 21505//21505 -f 21505//21505 23699//23699 23704//23704 -f 21505//21505 23704//23704 21507//21507 -f 21507//21507 23704//23704 23703//23703 -f 21507//21507 23703//23703 21509//21509 -f 21509//21509 23703//23703 23702//23702 -f 21509//21509 23702//23702 21511//21511 -f 23702//23702 23701//23701 21511//21511 -f 21511//21511 23701//23701 23700//23700 -f 21511//21511 23700//23700 21512//21512 -f 21512//21512 23700//23700 21488//21488 -f 21488//21488 23700//23700 23698//23698 -f 21488//21488 23698//23698 21489//21489 -f 21489//21489 23698//23698 23697//23697 -f 21489//21489 23697//23697 21481//21481 -f 21481//21481 23697//23697 23696//23696 -f 21481//21481 23696//23696 21483//21483 -f 23696//23696 23695//23695 21483//21483 -f 21483//21483 23695//23695 23694//23694 -f 21483//21483 23694//23694 21485//21485 -f 21485//21485 23694//23694 23693//23693 -f 21485//21485 23693//23693 23692//23692 -f 23669//23669 21475//21475 23670//23670 -f 23670//23670 21475//21475 21477//21477 -f 23670//23670 21477//21477 23692//23692 -f 23692//23692 21477//21477 21486//21486 -f 23692//23692 21486//21486 21485//21485 -f 23687//23687 19928//19928 23688//23688 -f 23688//23688 19928//19928 19930//19930 -f 23688//23688 19930//19930 23689//23689 -f 23689//23689 19930//19930 21473//21473 -f 23689//23689 21473//21473 23690//23690 -f 23690//23690 21473//21473 21475//21475 -f 23690//23690 21475//21475 23691//23691 -f 23691//23691 21475//21475 23669//23669 -f 23687//23687 23686//23686 19928//19928 -f 19928//19928 23686//23686 23685//23685 -f 19928//19928 23685//23685 19925//19925 -f 23685//23685 23684//23684 19925//19925 -f 19925//19925 23684//23684 23683//23683 -f 19925//19925 23683//23683 19923//19923 -f 19923//19923 23683//23683 23682//23682 -f 19923//19923 23682//23682 19921//19921 -f 19921//19921 23682//23682 19918//19918 -f 23682//23682 23681//23681 19918//19918 -f 19918//19918 23681//23681 23680//23680 -f 19918//19918 23680//23680 19917//19917 -f 23680//23680 23679//23679 19917//19917 -f 19917//19917 23679//23679 23678//23678 -f 19917//19917 23678//23678 19915//19915 -f 23678//23678 23677//23677 19915//19915 -f 19915//19915 23677//23677 23676//23676 -f 19915//19915 23676//23676 19912//19912 -f 23676//23676 23675//23675 19912//19912 -f 19912//19912 23675//23675 23674//23674 -f 19912//19912 23674//23674 19910//19910 -f 23674//23674 23673//23673 19910//19910 -f 19910//19910 23673//23673 23672//23672 -f 19910//19910 23672//23672 19908//19908 -f 19908//19908 23672//23672 23671//23671 -f 19908//19908 23671//23671 19906//19906 -f 19906//19906 23671//23671 23417//23417 -f 19906//19906 23417//23417 19904//19904 -f 22634//22634 22632//22632 22838//22838 -f 22838//22838 22632//22632 22547//22547 -f 22838//22838 22547//22547 22839//22839 -f 22839//22839 22547//22547 22533//22533 -f 22583//22583 22579//22579 22874//22874 -f 22874//22874 22579//22579 22549//22549 -f 22874//22874 22549//22549 22875//22875 -f 22875//22875 22549//22549 22529//22529 -f 22842//22842 22510//22510 22840//22840 -f 22840//22840 22510//22510 22547//22547 -f 22840//22840 22547//22547 22630//22630 -f 22630//22630 22547//22547 22632//22632 -f 22875//22875 22529//22529 22873//22873 -f 22873//22873 22529//22529 22538//22538 -f 22873//22873 22538//22538 22584//22584 -f 22584//22584 22538//22538 22586//22586 -f 23929//23929 19649//19649 21406//21406 -f 23930//23930 23931//23931 19674//19674 -f 23932//23932 19694//19694 19692//19692 -f 19600//19600 23933//23933 19602//19602 -f 19602//19602 23933//23933 19604//19604 -f 23934//23934 23935//23935 19616//19616 -f 23936//23936 19624//19624 19622//19622 -f 23937//23937 19632//19632 19630//19630 -f 23938//23938 19646//19646 19580//19580 -f 23939//23939 23940//23940 21237//21237 -f 21237//21237 23940//23940 21239//21239 -f 23941//23941 23942//23942 21163//21163 -f 21163//21163 23942//23942 21165//21165 -f 23943//23943 21189//21189 23944//23944 -f 19438//19438 19439//19439 23945//23945 -f 23945//23945 19439//19439 23946//23946 -f 23946//23946 19439//19439 23947//23947 -f 23947//23947 19439//19439 19441//19441 -f 23947//23947 19441//19441 23948//23948 -f 19441//19441 19443//19443 23948//23948 -f 23948//23948 19443//19443 19444//19444 -f 23948//23948 19444//19444 23949//23949 -f 19444//19444 19446//19446 23949//23949 -f 23949//23949 19446//19446 19448//19448 -f 23949//23949 19448//19448 23950//23950 -f 23950//23950 19448//19448 19450//19450 -f 23950//23950 19450//19450 23951//23951 -f 23951//23951 19450//19450 19452//19452 -f 23951//23951 19452//19452 19454//19454 -f 23952//23952 23953//23953 19454//19454 -f 19454//19454 23953//23953 23954//23954 -f 19454//19454 23954//23954 23951//23951 -f 19454//19454 19456//19456 23952//23952 -f 23952//23952 19456//19456 19458//19458 -f 23952//23952 19458//19458 23955//23955 -f 23955//23955 19458//19458 19460//19460 -f 19462//19462 23956//23956 19460//19460 -f 19460//19460 23956//23956 23957//23957 -f 19460//19460 23957//23957 23955//23955 -f 19462//19462 19464//19464 23956//23956 -f 23956//23956 19464//19464 19466//19466 -f 23956//23956 19466//19466 23958//23958 -f 23958//23958 19466//19466 19468//19468 -f 23958//23958 19468//19468 23959//23959 -f 23959//23959 19468//19468 19470//19470 -f 23959//23959 19470//19470 23960//23960 -f 23960//23960 19470//19470 19472//19472 -f 23960//23960 19472//19472 23961//23961 -f 23961//23961 19472//19472 19474//19474 -f 23961//23961 19474//19474 23962//23962 -f 23962//23962 19474//19474 19476//19476 -f 23962//23962 19476//19476 23963//23963 -f 23963//23963 19476//19476 19479//19479 -f 23963//23963 19479//19479 23964//23964 -f 23964//23964 19479//19479 19481//19481 -f 23964//23964 19481//19481 23965//23965 -f 23965//23965 19481//19481 19485//19485 -f 23965//23965 19485//19485 23966//23966 -f 23966//23966 19485//19485 23967//23967 -f 23967//23967 19485//19485 19483//19483 -f 23967//23967 19483//19483 23968//23968 -f 23968//23968 19483//19483 21212//21212 -f 23968//23968 21212//21212 23969//23969 -f 23969//23969 21212//21212 21213//21213 -f 23969//23969 21213//21213 23970//23970 -f 21207//21207 23971//23971 21208//21208 -f 21208//21208 23971//23971 23972//23972 -f 21208//21208 23972//23972 21157//21157 -f 21157//21157 23972//23972 23970//23970 -f 21157//21157 23970//23970 21210//21210 -f 21210//21210 23970//23970 21213//21213 -f 21203//21203 23973//23973 21205//21205 -f 21205//21205 23973//23973 23974//23974 -f 21205//21205 23974//23974 21207//21207 -f 21207//21207 23974//23974 23975//23975 -f 21207//21207 23975//23975 23971//23971 -f 23976//23976 23977//23977 21199//21199 -f 21199//21199 23977//23977 23978//23978 -f 21199//21199 23978//23978 21201//21201 -f 21201//21201 23978//23978 23979//23979 -f 21201//21201 23979//23979 21203//21203 -f 21203//21203 23979//23979 23980//23980 -f 21203//21203 23980//23980 23973//23973 -f 21199//21199 21197//21197 23976//23976 -f 23976//23976 21197//21197 21195//21195 -f 23976//23976 21195//21195 23981//23981 -f 23981//23981 21195//21195 21193//21193 -f 23981//23981 21193//21193 23982//23982 -f 23982//23982 21193//21193 23943//23943 -f 23943//23943 21193//21193 21191//21191 -f 23943//23943 21191//21191 21189//21189 -f 23944//23944 21189//21189 23983//23983 -f 23983//23983 21189//21189 21187//21187 -f 23983//23983 21187//21187 23984//23984 -f 23984//23984 21187//21187 21185//21185 -f 23984//23984 21185//21185 23985//23985 -f 21185//21185 21183//21183 23985//23985 -f 23985//23985 21183//21183 21181//21181 -f 23985//23985 21181//21181 23986//23986 -f 23986//23986 21181//21181 23987//23987 -f 23987//23987 21181//21181 21179//21179 -f 23987//23987 21179//21179 23988//23988 -f 23988//23988 21179//21179 21177//21177 -f 23988//23988 21177//21177 23989//23989 -f 23989//23989 21177//21177 21176//21176 -f 23989//23989 21176//21176 23990//23990 -f 23990//23990 21176//21176 23991//23991 -f 23991//23991 21176//21176 21174//21174 -f 23991//23991 21174//21174 23992//23992 -f 23992//23992 21174//21174 23993//23993 -f 23993//23993 21174//21174 21172//21172 -f 23993//23993 21172//21172 23994//23994 -f 21172//21172 21170//21170 23994//23994 -f 23994//23994 21170//21170 21168//21168 -f 23994//23994 21168//21168 23995//23995 -f 23995//23995 21168//21168 21166//21166 -f 23995//23995 21166//21166 23996//23996 -f 23996//23996 21166//21166 21165//21165 -f 23996//23996 21165//21165 23997//23997 -f 23997//23997 21165//21165 23942//23942 -f 23941//23941 21163//21163 23998//23998 -f 23998//23998 21163//21163 21161//21161 -f 23998//23998 21161//21161 23999//23999 -f 23999//23999 21161//21161 24000//24000 -f 24000//24000 21161//21161 21159//21159 -f 24000//24000 21159//21159 24001//24001 -f 24001//24001 21159//21159 19573//19573 -f 24001//24001 19573//19573 24002//24002 -f 24002//24002 19573//19573 19575//19575 -f 24002//24002 19575//19575 19566//19566 -f 19568//19568 24003//24003 19566//19566 -f 19566//19566 24003//24003 24004//24004 -f 24004//24004 24005//24005 19566//19566 -f 19566//19566 24005//24005 24006//24006 -f 19566//19566 24006//24006 24002//24002 -f 19558//19558 24007//24007 19560//19560 -f 19560//19560 24007//24007 24008//24008 -f 19560//19560 24008//24008 19562//19562 -f 19562//19562 24008//24008 24009//24009 -f 19562//19562 24009//24009 19564//19564 -f 19564//19564 24009//24009 24010//24010 -f 19564//19564 24010//24010 19565//19565 -f 19565//19565 24010//24010 24011//24011 -f 19565//19565 24011//24011 19570//19570 -f 19570//19570 24011//24011 24012//24012 -f 19570//19570 24012//24012 19568//19568 -f 19568//19568 24012//24012 24013//24013 -f 19568//19568 24013//24013 24003//24003 -f 19556//19556 24014//24014 19558//19558 -f 19558//19558 24014//24014 24015//24015 -f 19558//19558 24015//24015 24007//24007 -f 19553//19553 24016//24016 19555//19555 -f 19555//19555 24016//24016 24017//24017 -f 19555//19555 24017//24017 19556//19556 -f 19556//19556 24017//24017 24014//24014 -f 19553//19553 19551//19551 24016//24016 -f 24016//24016 19551//19551 19544//19544 -f 24016//24016 19544//19544 24018//24018 -f 24018//24018 19544//19544 19549//19549 -f 24018//24018 19549//19549 24019//24019 -f 24019//24019 19549//19549 19548//19548 -f 19548//19548 19546//19546 24019//24019 -f 24019//24019 19546//19546 19540//19540 -f 24019//24019 19540//19540 24020//24020 -f 24020//24020 19540//19540 24021//24021 -f 24021//24021 19540//19540 19538//19538 -f 24021//24021 19538//19538 24022//24022 -f 24022//24022 19538//19538 19536//19536 -f 24022//24022 19536//19536 24023//24023 -f 24023//24023 19536//19536 24024//24024 -f 24024//24024 19536//19536 19534//19534 -f 24024//24024 19534//19534 24025//24025 -f 19534//19534 19532//19532 24025//24025 -f 24025//24025 19532//19532 19530//19530 -f 24025//24025 19530//19530 24026//24026 -f 19530//19530 19528//19528 24026//24026 -f 24026//24026 19528//19528 19526//19526 -f 24026//24026 19526//19526 24027//24027 -f 24027//24027 19526//19526 24028//24028 -f 24028//24028 19526//19526 19523//19523 -f 24028//24028 19523//19523 24029//24029 -f 19523//19523 19521//19521 24029//24029 -f 24029//24029 19521//19521 19519//19519 -f 24029//24029 19519//19519 24030//24030 -f 19517//19517 24031//24031 19519//19519 -f 19519//19519 24031//24031 24032//24032 -f 19519//19519 24032//24032 24030//24030 -f 19517//19517 19515//19515 24031//24031 -f 24031//24031 19515//19515 19508//19508 -f 24031//24031 19508//19508 24033//24033 -f 24033//24033 19508//19508 19509//19509 -f 24033//24033 19509//19509 24034//24034 -f 24034//24034 19509//19509 24035//24035 -f 24035//24035 19509//19509 19511//19511 -f 24035//24035 19511//19511 24036//24036 -f 24036//24036 19511//19511 24037//24037 -f 24037//24037 19511//19511 21272//21272 -f 24037//24037 21272//21272 21270//21270 -f 21261//21261 24038//24038 24039//24039 -f 21261//21261 24039//24039 21263//21263 -f 21263//21263 24039//24039 24040//24040 -f 21263//21263 24040//24040 21265//21265 -f 21265//21265 24040//24040 24041//24041 -f 21265//21265 24041//24041 21266//21266 -f 21266//21266 24041//24041 24042//24042 -f 21266//21266 24042//24042 21269//21269 -f 21269//21269 24042//24042 24043//24043 -f 21269//21269 24043//24043 21270//21270 -f 21270//21270 24043//24043 24044//24044 -f 21270//21270 24044//24044 24037//24037 -f 24038//24038 21261//21261 24045//24045 -f 24045//24045 21261//21261 21259//21259 -f 24045//24045 21259//21259 24046//24046 -f 21259//21259 21257//21257 24046//24046 -f 24046//24046 21257//21257 21255//21255 -f 24046//24046 21255//21255 24047//24047 -f 24047//24047 21255//21255 24048//24048 -f 24048//24048 21255//21255 21253//21253 -f 24048//24048 21253//21253 24049//24049 -f 24049//24049 21253//21253 21251//21251 -f 24049//24049 21251//21251 24050//24050 -f 24050//24050 21251//21251 21249//21249 -f 24050//24050 21249//21249 24051//24051 -f 21249//21249 21247//21247 24051//24051 -f 24051//24051 21247//21247 21245//21245 -f 24051//24051 21245//21245 24052//24052 -f 24052//24052 21245//21245 24053//24053 -f 21243//21243 24054//24054 21245//21245 -f 21245//21245 24054//24054 24055//24055 -f 21245//21245 24055//24055 24053//24053 -f 21239//21239 23940//23940 21241//21241 -f 21241//21241 23940//23940 24056//24056 -f 21241//21241 24056//24056 21243//21243 -f 21243//21243 24056//24056 24057//24057 -f 21243//21243 24057//24057 24054//24054 -f 23939//23939 21237//21237 24058//24058 -f 24058//24058 21237//21237 21235//21235 -f 24058//24058 21235//21235 24059//24059 -f 21235//21235 21233//21233 24059//24059 -f 24059//24059 21233//21233 21231//21231 -f 24059//24059 21231//21231 24060//24060 -f 24060//24060 21231//21231 24061//24061 -f 24061//24061 21231//21231 21229//21229 -f 24061//24061 21229//21229 24062//24062 -f 21229//21229 21227//21227 24062//24062 -f 24062//24062 21227//21227 21225//21225 -f 24062//24062 21225//21225 24063//24063 -f 24063//24063 21225//21225 21224//21224 -f 24063//24063 21224//21224 24064//24064 -f 24064//24064 21224//21224 21221//21221 -f 24064//24064 21221//21221 24065//24065 -f 24065//24065 21221//21221 21220//21220 -f 24065//24065 21220//21220 21218//21218 -f 24066//24066 24067//24067 21218//21218 -f 21218//21218 24067//24067 24068//24068 -f 21218//21218 24068//24068 24065//24065 -f 24066//24066 21218//21218 24069//24069 -f 24069//24069 21218//21218 21215//21215 -f 24069//24069 21215//21215 24070//24070 -f 24070//24070 21215//21215 23938//23938 -f 23938//23938 21215//21215 19647//19647 -f 23938//23938 19647//19647 19646//19646 -f 19644//19644 24071//24071 19580//19580 -f 19580//19580 24071//24071 24072//24072 -f 19580//19580 24072//24072 23938//23938 -f 24073//24073 24074//24074 19643//19643 -f 19643//19643 24074//24074 24075//24075 -f 19643//19643 24075//24075 19644//19644 -f 19644//19644 24075//24075 24076//24076 -f 19644//19644 24076//24076 24071//24071 -f 19643//19643 19641//19641 24073//24073 -f 24073//24073 19641//19641 19639//19639 -f 24073//24073 19639//19639 24077//24077 -f 24077//24077 19639//19639 19637//19637 -f 24077//24077 19637//19637 24078//24078 -f 24078//24078 19637//19637 24079//24079 -f 24079//24079 19637//19637 19635//19635 -f 24079//24079 19635//19635 23937//23937 -f 23937//23937 19635//19635 19633//19633 -f 23937//23937 19633//19633 19632//19632 -f 24080//24080 24081//24081 19628//19628 -f 19628//19628 24081//24081 24082//24082 -f 19628//19628 24082//24082 19630//19630 -f 19630//19630 24082//24082 24083//24083 -f 19630//19630 24083//24083 23937//23937 -f 24080//24080 19628//19628 23936//23936 -f 23936//23936 19628//19628 19626//19626 -f 23936//23936 19626//19626 19624//19624 -f 19616//19616 23935//23935 19618//19618 -f 19618//19618 23935//23935 24084//24084 -f 19618//19618 24084//24084 19621//19621 -f 19621//19621 24084//24084 24085//24085 -f 19621//19621 24085//24085 19622//19622 -f 19622//19622 24085//24085 24086//24086 -f 19622//19622 24086//24086 23936//23936 -f 23934//23934 19616//19616 24087//24087 -f 24087//24087 19616//19616 19615//19615 -f 24087//24087 19615//19615 24088//24088 -f 24088//24088 19615//19615 24089//24089 -f 24089//24089 19615//19615 19613//19613 -f 24089//24089 19613//19613 24090//24090 -f 24090//24090 19613//19613 19611//19611 -f 24090//24090 19611//19611 19609//19609 -f 19604//19604 23933//23933 19606//19606 -f 19606//19606 23933//23933 24091//24091 -f 19606//19606 24091//24091 19607//19607 -f 19607//19607 24091//24091 24092//24092 -f 19607//19607 24092//24092 19609//19609 -f 19609//19609 24092//24092 24093//24093 -f 19609//19609 24093//24093 24090//24090 -f 19593//19593 24094//24094 19595//19595 -f 19595//19595 24094//24094 24095//24095 -f 19595//19595 24095//24095 19597//19597 -f 19597//19597 24095//24095 24096//24096 -f 19597//19597 24096//24096 19599//19599 -f 19599//19599 24096//24096 24097//24097 -f 19599//19599 24097//24097 19600//19600 -f 19600//19600 24097//24097 24098//24098 -f 19600//19600 24098//24098 23933//23933 -f 24099//24099 24100//24100 19587//19587 -f 19587//19587 24100//24100 24101//24101 -f 19587//19587 24101//24101 19585//19585 -f 19585//19585 24101//24101 24102//24102 -f 19585//19585 24102//24102 19583//19583 -f 19583//19583 24102//24102 24103//24103 -f 19583//19583 24103//24103 19588//19588 -f 19588//19588 24103//24103 24104//24104 -f 19588//19588 24104//24104 19589//19589 -f 19589//19589 24104//24104 24105//24105 -f 19589//19589 24105//24105 19591//19591 -f 19591//19591 24105//24105 24106//24106 -f 19591//19591 24106//24106 19593//19593 -f 19593//19593 24106//24106 24107//24107 -f 19593//19593 24107//24107 24094//24094 -f 24099//24099 19587//19587 24108//24108 -f 24108//24108 19587//19587 21336//21336 -f 24108//24108 21336//21336 24109//24109 -f 24109//24109 21336//21336 24110//24110 -f 24110//24110 21336//21336 21302//21302 -f 24110//24110 21302//21302 24111//24111 -f 24111//24111 21302//21302 21300//21300 -f 24111//24111 21300//21300 24112//24112 -f 21300//21300 21335//21335 24112//24112 -f 24112//24112 21335//21335 21334//21334 -f 24112//24112 21334//21334 24113//24113 -f 21334//21334 21332//21332 24113//24113 -f 24113//24113 21332//21332 21330//21330 -f 24113//24113 21330//21330 24114//24114 -f 24114//24114 21330//21330 21328//21328 -f 24114//24114 21328//21328 24115//24115 -f 24115//24115 21328//21328 24116//24116 -f 24116//24116 21328//21328 21326//21326 -f 24116//24116 21326//21326 24117//24117 -f 24117//24117 21326//21326 21324//21324 -f 24117//24117 21324//21324 24118//24118 -f 21314//21314 24119//24119 21316//21316 -f 21316//21316 24119//24119 24120//24120 -f 21316//21316 24120//24120 21318//21318 -f 21318//21318 24120//24120 24121//24121 -f 21318//21318 24121//24121 21320//21320 -f 21320//21320 24121//24121 24118//24118 -f 21320//21320 24118//24118 21322//21322 -f 21322//21322 24118//24118 21324//21324 -f 21310//21310 24122//24122 21312//21312 -f 21312//21312 24122//24122 24123//24123 -f 21312//21312 24123//24123 21314//21314 -f 21314//21314 24123//24123 24124//24124 -f 21314//21314 24124//24124 24119//24119 -f 21306//21306 24125//24125 21308//21308 -f 21308//21308 24125//24125 24126//24126 -f 21308//21308 24126//24126 21310//21310 -f 21310//21310 24126//24126 24127//24127 -f 21310//21310 24127//24127 24122//24122 -f 21306//21306 21304//21304 24125//24125 -f 24125//24125 21304//21304 21303//21303 -f 24125//24125 21303//21303 24128//24128 -f 24128//24128 21303//21303 21297//21297 -f 24128//24128 21297//21297 24129//24129 -f 24129//24129 21297//21297 24130//24130 -f 24130//24130 21297//21297 24131//24131 -f 24131//24131 21297//21297 21295//21295 -f 24131//24131 21295//21295 24132//24132 -f 24132//24132 21295//21295 21293//21293 -f 24132//24132 21293//21293 24133//24133 -f 24133//24133 21293//21293 21290//21290 -f 24133//24133 21290//21290 24134//24134 -f 21290//21290 21288//21288 24134//24134 -f 24134//24134 21288//21288 21286//21286 -f 24134//24134 21286//21286 24135//24135 -f 24135//24135 21286//21286 21284//21284 -f 24135//24135 21284//21284 24136//24136 -f 24136//24136 21284//21284 24137//24137 -f 24137//24137 21284//21284 21282//21282 -f 24137//24137 21282//21282 24138//24138 -f 24138//24138 21282//21282 21281//21281 -f 24138//24138 21281//21281 24139//24139 -f 21281//21281 21280//21280 24139//24139 -f 24139//24139 21280//21280 21278//21278 -f 24139//24139 21278//21278 24140//24140 -f 24140//24140 21278//21278 21276//21276 -f 24140//24140 21276//21276 24141//24141 -f 24141//24141 21276//21276 24142//24142 -f 19709//19709 24143//24143 19707//19707 -f 19707//19707 24143//24143 24144//24144 -f 19707//19707 24144//24144 21274//21274 -f 21274//21274 24144//24144 24142//24142 -f 21274//21274 24142//24142 21275//21275 -f 21275//21275 24142//24142 21276//21276 -f 24145//24145 24146//24146 19704//19704 -f 19704//19704 24146//24146 24147//24147 -f 19704//19704 24147//24147 19706//19706 -f 19706//19706 24147//24147 24148//24148 -f 19706//19706 24148//24148 19709//19709 -f 19709//19709 24148//24148 24149//24149 -f 19709//19709 24149//24149 24143//24143 -f 24145//24145 19704//19704 24150//24150 -f 24150//24150 19704//19704 19702//19702 -f 24150//24150 19702//19702 24151//24151 -f 24151//24151 19702//19702 19700//19700 -f 24151//24151 19700//19700 24152//24152 -f 24152//24152 19700//19700 19698//19698 -f 24152//24152 19698//19698 24153//24153 -f 19698//19698 19696//19696 24153//24153 -f 24153//24153 19696//19696 19694//19694 -f 24153//24153 19694//19694 24154//24154 -f 24154//24154 19694//19694 23932//23932 -f 19690//19690 24155//24155 19692//19692 -f 19692//19692 24155//24155 24156//24156 -f 19692//19692 24156//24156 23932//23932 -f 19690//19690 19688//19688 24155//24155 -f 24155//24155 19688//19688 19686//19686 -f 24155//24155 19686//19686 24157//24157 -f 24157//24157 19686//19686 19685//19685 -f 24157//24157 19685//19685 24158//24158 -f 24158//24158 19685//19685 19682//19682 -f 19682//19682 19680//19680 24158//24158 -f 24158//24158 19680//19680 19678//19678 -f 24158//24158 19678//19678 24159//24159 -f 24159//24159 19678//19678 23931//23931 -f 23931//23931 19678//19678 19676//19676 -f 23931//23931 19676//19676 19674//19674 -f 23930//23930 19674//19674 24160//24160 -f 24160//24160 19674//19674 19673//19673 -f 24160//24160 19673//19673 24161//24161 -f 24161//24161 19673//19673 24162//24162 -f 24162//24162 19673//19673 19671//19671 -f 24162//24162 19671//19671 24163//24163 -f 24163//24163 19671//19671 24164//24164 -f 24164//24164 19671//19671 19669//19669 -f 24164//24164 19669//19669 24165//24165 -f 19669//19669 19667//19667 24165//24165 -f 24165//24165 19667//19667 19665//19665 -f 24165//24165 19665//19665 24166//24166 -f 24166//24166 19665//19665 24167//24167 -f 24167//24167 19665//19665 24168//24168 -f 24168//24168 19665//19665 19663//19663 -f 24168//24168 19663//19663 24169//24169 -f 24169//24169 19663//19663 19661//19661 -f 24169//24169 19661//19661 24170//24170 -f 24170//24170 19661//19661 19659//19659 -f 24170//24170 19659//19659 24171//24171 -f 24171//24171 19659//19659 24172//24172 -f 24172//24172 19659//19659 19657//19657 -f 24172//24172 19657//19657 24173//24173 -f 24173//24173 19657//19657 19655//19655 -f 24173//24173 19655//19655 24174//24174 -f 24174//24174 19655//19655 19653//19653 -f 24174//24174 19653//19653 19651//19651 -f 23929//23929 24175//24175 19649//19649 -f 19649//19649 24175//24175 24176//24176 -f 19649//19649 24176//24176 19651//19651 -f 19651//19651 24176//24176 24177//24177 -f 19651//19651 24177//24177 24174//24174 -f 21400//21400 24178//24178 21403//21403 -f 21403//21403 24178//24178 24179//24179 -f 21403//21403 24179//24179 21404//21404 -f 21404//21404 24179//24179 24180//24180 -f 21404//21404 24180//24180 21406//21406 -f 21406//21406 24180//24180 24181//24181 -f 21406//21406 24181//24181 23929//23929 -f 24182//24182 24183//24183 21395//21395 -f 21395//21395 24183//24183 24184//24184 -f 21395//21395 24184//24184 21397//21397 -f 21397//21397 24184//24184 24185//24185 -f 21397//21397 24185//24185 21398//21398 -f 21398//21398 24185//24185 24186//24186 -f 21398//21398 24186//24186 21400//21400 -f 21400//21400 24186//24186 24187//24187 -f 21400//21400 24187//24187 24178//24178 -f 24182//24182 21395//21395 24188//24188 -f 24188//24188 21395//21395 21341//21341 -f 24188//24188 21341//21341 24189//24189 -f 21387//21387 23928//23928 21385//21385 -f 21385//21385 23928//23928 24190//24190 -f 21385//21385 24190//24190 21383//21383 -f 21383//21383 24190//24190 24189//24189 -f 21383//21383 24189//24189 21342//21342 -f 21342//21342 24189//24189 21341//21341 -f 22628//22628 22626//22626 22841//22841 -f 22841//22841 22626//22626 22511//22511 -f 22841//22841 22511//22511 22842//22842 -f 22842//22842 22511//22511 22510//22510 -f 22588//22588 22586//22586 22871//22871 -f 22871//22871 22586//22586 22538//22538 -f 22871//22871 22538//22538 22872//22872 -f 22872//22872 22538//22538 22528//22528 -f 24018//24018 19447//19447 19445//19445 -f 24027//24027 19467//19467 19465//19465 -f 24047//24047 21198//21198 21200//21200 -f 21198//21198 24047//24047 24048//24048 -f 24070//24070 19574//19574 21158//21158 -f 24167//24167 19601//19601 24166//24166 -f 24170//24170 19594//19594 19596//19596 -f 24190//24190 23928//23928 21319//21319 -f 21319//21319 21321//21321 24190//24190 -f 24190//24190 21321//21321 21323//21323 -f 24190//24190 21323//21323 24189//24189 -f 24189//24189 21323//21323 21325//21325 -f 24189//24189 21325//21325 24188//24188 -f 24188//24188 21325//21325 21327//21327 -f 24188//24188 21327//21327 24182//24182 -f 24182//24182 21327//21327 21329//21329 -f 24182//24182 21329//21329 24183//24183 -f 24183//24183 21329//21329 21331//21331 -f 24183//24183 21331//21331 24184//24184 -f 24184//24184 21331//21331 24185//24185 -f 24185//24185 21331//21331 21333//21333 -f 24185//24185 21333//21333 24186//24186 -f 21333//21333 21299//21299 24186//24186 -f 24186//24186 21299//21299 21301//21301 -f 24186//24186 21301//21301 24187//24187 -f 24187//24187 21301//21301 21338//21338 -f 24187//24187 21338//21338 24178//24178 -f 24178//24178 21338//21338 24179//24179 -f 24179//24179 21338//21338 21337//21337 -f 24179//24179 21337//21337 24180//24180 -f 24180//24180 21337//21337 24181//24181 -f 24181//24181 21337//21337 19586//19586 -f 24181//24181 19586//19586 23929//23929 -f 23929//23929 19586//19586 24175//24175 -f 24175//24175 19586//19586 19584//19584 -f 24175//24175 19584//19584 24176//24176 -f 24176//24176 19584//19584 24177//24177 -f 24177//24177 19584//19584 19582//19582 -f 24177//24177 19582//19582 24174//24174 -f 19582//19582 19581//19581 24174//24174 -f 24174//24174 19581//19581 19590//19590 -f 24174//24174 19590//19590 24173//24173 -f 24173//24173 19590//19590 19592//19592 -f 24173//24173 19592//19592 24172//24172 -f 24172//24172 19592//19592 19594//19594 -f 24172//24172 19594//19594 24171//24171 -f 24171//24171 19594//19594 24170//24170 -f 19601//19601 24167//24167 19598//19598 -f 19598//19598 24167//24167 24168//24168 -f 19598//19598 24168//24168 19596//19596 -f 19596//19596 24168//24168 24169//24169 -f 19596//19596 24169//24169 24170//24170 -f 24166//24166 19601//19601 24165//24165 -f 24165//24165 19601//19601 19603//19603 -f 24165//24165 19603//19603 24164//24164 -f 24164//24164 19603//19603 19605//19605 -f 24164//24164 19605//19605 24163//24163 -f 24163//24163 19605//19605 19608//19608 -f 24163//24163 19608//19608 24162//24162 -f 24162//24162 19608//19608 24161//24161 -f 24161//24161 19608//19608 19610//19610 -f 24161//24161 19610//19610 24160//24160 -f 24160//24160 19610//19610 23930//23930 -f 23930//23930 19610//19610 19612//19612 -f 23930//23930 19612//19612 23931//23931 -f 23931//23931 19612//19612 19614//19614 -f 23931//23931 19614//19614 24159//24159 -f 24159//24159 19614//19614 19617//19617 -f 24159//24159 19617//19617 24158//24158 -f 19617//19617 19619//19619 24158//24158 -f 24158//24158 19619//19619 19620//19620 -f 24158//24158 19620//19620 24157//24157 -f 24157//24157 19620//19620 19623//19623 -f 24157//24157 19623//19623 24155//24155 -f 24155//24155 19623//19623 19625//19625 -f 24155//24155 19625//19625 24156//24156 -f 24156//24156 19625//19625 19627//19627 -f 24156//24156 19627//19627 23932//23932 -f 23932//23932 19627//19627 19629//19629 -f 23932//23932 19629//19629 24154//24154 -f 24154//24154 19629//19629 24153//24153 -f 19629//19629 19631//19631 24153//24153 -f 24153//24153 19631//19631 19634//19634 -f 24153//24153 19634//19634 24152//24152 -f 24152//24152 19634//19634 19636//19636 -f 24152//24152 19636//19636 24151//24151 -f 24151//24151 19636//19636 19638//19638 -f 24151//24151 19638//19638 24150//24150 -f 24150//24150 19638//19638 19640//19640 -f 24150//24150 19640//19640 24145//24145 -f 24145//24145 19640//19640 19642//19642 -f 19579//19579 24147//24147 19642//19642 -f 19642//19642 24147//24147 24146//24146 -f 19642//19642 24146//24146 24145//24145 -f 24141//24141 24142//24142 21214//21214 -f 21214//21214 24142//24142 24144//24144 -f 21214//21214 24144//24144 19645//19645 -f 19645//19645 24144//24144 24143//24143 -f 19645//19645 24143//24143 19578//19578 -f 19578//19578 24143//24143 24149//24149 -f 19578//19578 24149//24149 19579//19579 -f 19579//19579 24149//24149 24148//24148 -f 19579//19579 24148//24148 24147//24147 -f 21214//21214 21216//21216 24141//24141 -f 24141//24141 21216//21216 21217//21217 -f 24141//24141 21217//21217 24140//24140 -f 24140//24140 21217//21217 24139//24139 -f 24139//24139 21217//21217 24138//24138 -f 24138//24138 21217//21217 21219//21219 -f 24138//24138 21219//21219 24137//24137 -f 24137//24137 21219//21219 21222//21222 -f 24137//24137 21222//21222 24136//24136 -f 21222//21222 21223//21223 24136//24136 -f 24136//24136 21223//21223 21226//21226 -f 24136//24136 21226//21226 24135//24135 -f 24135//24135 21226//21226 24134//24134 -f 24134//24134 21226//21226 21228//21228 -f 24134//24134 21228//21228 24133//24133 -f 21228//21228 21230//21230 24133//24133 -f 24133//24133 21230//21230 21232//21232 -f 24133//24133 21232//21232 24132//24132 -f 24132//24132 21232//21232 24131//24131 -f 24131//24131 21232//21232 21234//21234 -f 24131//24131 21234//21234 24130//24130 -f 24130//24130 21234//21234 24129//24129 -f 24129//24129 21234//21234 21236//21236 -f 24129//24129 21236//21236 24128//24128 -f 24128//24128 21236//21236 21238//21238 -f 24128//24128 21238//21238 24125//24125 -f 24125//24125 21238//21238 21240//21240 -f 24125//24125 21240//21240 24126//24126 -f 21240//21240 21242//21242 24126//24126 -f 24126//24126 21242//21242 21244//21244 -f 24126//24126 21244//21244 24127//24127 -f 24121//24121 24120//24120 21250//21250 -f 21250//21250 24120//24120 24119//24119 -f 21250//21250 24119//24119 21248//21248 -f 21248//21248 24119//24119 24124//24124 -f 21248//21248 24124//24124 21246//21246 -f 21246//21246 24124//24124 24123//24123 -f 21246//21246 24123//24123 21244//21244 -f 21244//21244 24123//24123 24122//24122 -f 21244//21244 24122//24122 24127//24127 -f 21250//21250 21252//21252 24121//24121 -f 24121//24121 21252//21252 21254//21254 -f 24121//24121 21254//21254 24118//24118 -f 24118//24118 21254//21254 21256//21256 -f 24118//24118 21256//21256 24117//24117 -f 24117//24117 21256//21256 24116//24116 -f 24116//24116 21256//21256 21258//21258 -f 24116//24116 21258//21258 24115//24115 -f 21258//21258 21260//21260 24115//24115 -f 24115//24115 21260//21260 21262//21262 -f 24115//24115 21262//21262 24114//24114 -f 21264//21264 24112//24112 21262//21262 -f 21262//21262 24112//24112 24113//24113 -f 21262//21262 24113//24113 24114//24114 -f 21271//21271 24111//24111 21268//21268 -f 21268//21268 24111//24111 24112//24112 -f 21268//21268 24112//24112 21267//21267 -f 21267//21267 24112//24112 21264//21264 -f 24108//24108 24109//24109 21271//21271 -f 21271//21271 24109//24109 24110//24110 -f 21271//21271 24110//24110 24111//24111 -f 24108//24108 21271//21271 24099//24099 -f 24099//24099 21271//21271 19513//19513 -f 24099//24099 19513//19513 19512//19512 -f 19506//19506 24103//24103 19507//19507 -f 19507//19507 24103//24103 24102//24102 -f 19507//19507 24102//24102 19510//19510 -f 19510//19510 24102//24102 24101//24101 -f 19510//19510 24101//24101 19512//19512 -f 19512//19512 24101//24101 24100//24100 -f 19512//19512 24100//24100 24099//24099 -f 19520//19520 24094//24094 19518//19518 -f 19518//19518 24094//24094 24107//24107 -f 19518//19518 24107//24107 19516//19516 -f 19516//19516 24107//24107 24106//24106 -f 19516//19516 24106//24106 19514//19514 -f 19514//19514 24106//24106 24105//24105 -f 19514//19514 24105//24105 19506//19506 -f 19506//19506 24105//24105 24104//24104 -f 19506//19506 24104//24104 24103//24103 -f 19522//19522 24096//24096 19520//19520 -f 19520//19520 24096//24096 24095//24095 -f 19520//19520 24095//24095 24094//24094 -f 19525//19525 23933//23933 19524//19524 -f 19524//19524 23933//23933 24098//24098 -f 19524//19524 24098//24098 19522//19522 -f 19522//19522 24098//24098 24097//24097 -f 19522//19522 24097//24097 24096//24096 -f 19525//19525 19527//19527 23933//23933 -f 23933//23933 19527//19527 19529//19529 -f 23933//23933 19529//19529 24091//24091 -f 24091//24091 19529//19529 19531//19531 -f 24091//24091 19531//19531 24092//24092 -f 24092//24092 19531//19531 19533//19533 -f 24092//24092 19533//19533 24093//24093 -f 24093//24093 19533//19533 24090//24090 -f 19533//19533 19535//19535 24090//24090 -f 24090//24090 19535//19535 19537//19537 -f 24090//24090 19537//19537 24089//24089 -f 24089//24089 19537//19537 19539//19539 -f 24089//24089 19539//19539 24088//24088 -f 24088//24088 19539//19539 19541//19541 -f 24088//24088 19541//19541 24087//24087 -f 24087//24087 19541//19541 19545//19545 -f 24087//24087 19545//19545 23934//23934 -f 23934//23934 19545//19545 23935//23935 -f 19545//19545 19547//19547 23935//23935 -f 23935//23935 19547//19547 19543//19543 -f 23935//23935 19543//19543 24084//24084 -f 24084//24084 19543//19543 19542//19542 -f 24084//24084 19542//19542 24085//24085 -f 24085//24085 19542//19542 19550//19550 -f 24085//24085 19550//19550 24086//24086 -f 24086//24086 19550//19550 23936//23936 -f 23936//23936 19550//19550 19552//19552 -f 23936//23936 19552//19552 24080//24080 -f 24080//24080 19552//19552 19554//19554 -f 24080//24080 19554//19554 24081//24081 -f 24081//24081 19554//19554 19557//19557 -f 24081//24081 19557//19557 24082//24082 -f 24082//24082 19557//19557 24083//24083 -f 24083//24083 19557//19557 19559//19559 -f 24083//24083 19559//19559 23937//23937 -f 23937//23937 19559//19559 19561//19561 -f 23937//23937 19561//19561 24079//24079 -f 24079//24079 19561//19561 19563//19563 -f 24079//24079 19563//19563 24078//24078 -f 24078//24078 19563//19563 19572//19572 -f 24078//24078 19572//19572 24077//24077 -f 24077//24077 19572//19572 24073//24073 -f 24073//24073 19572//19572 19571//19571 -f 24073//24073 19571//19571 24074//24074 -f 19571//19571 19569//19569 24074//24074 -f 24074//24074 19569//19569 19567//19567 -f 24074//24074 19567//19567 24075//24075 -f 24075//24075 19567//19567 24076//24076 -f 24076//24076 19567//19567 19577//19577 -f 24076//24076 19577//19577 24071//24071 -f 24071//24071 19577//19577 19576//19576 -f 24071//24071 19576//19576 24072//24072 -f 19574//19574 24070//24070 19576//19576 -f 19576//19576 24070//24070 23938//23938 -f 19576//19576 23938//23938 24072//24072 -f 24068//24068 24067//24067 21160//21160 -f 21160//21160 24067//24067 24066//24066 -f 21160//21160 24066//24066 21158//21158 -f 21158//21158 24066//24066 24069//24069 -f 21158//21158 24069//24069 24070//24070 -f 24068//24068 21160//21160 24065//24065 -f 24065//24065 21160//21160 21162//21162 -f 24065//24065 21162//21162 24064//24064 -f 24064//24064 21162//21162 21164//21164 -f 24064//24064 21164//21164 24063//24063 -f 21164//21164 21167//21167 24063//24063 -f 24063//24063 21167//21167 21169//21169 -f 24063//24063 21169//21169 24062//24062 -f 24062//24062 21169//21169 21171//21171 -f 24062//24062 21171//21171 24061//24061 -f 24061//24061 21171//21171 21173//21173 -f 24061//24061 21173//21173 24060//24060 -f 24060//24060 21173//21173 24059//24059 -f 24059//24059 21173//21173 21175//21175 -f 24059//24059 21175//21175 24058//24058 -f 24058//24058 21175//21175 21178//21178 -f 24058//24058 21178//21178 23939//23939 -f 23939//23939 21178//21178 21180//21180 -f 23939//23939 21180//21180 23940//23940 -f 23940//23940 21180//21180 21182//21182 -f 23940//23940 21182//21182 24056//24056 -f 24056//24056 21182//21182 24057//24057 -f 24057//24057 21182//21182 21184//21184 -f 24057//24057 21184//21184 24054//24054 -f 24054//24054 21184//21184 21186//21186 -f 24054//24054 21186//21186 24055//24055 -f 24055//24055 21186//21186 21188//21188 -f 24055//24055 21188//21188 24053//24053 -f 24053//24053 21188//21188 24052//24052 -f 24052//24052 21188//21188 21190//21190 -f 24052//24052 21190//21190 24051//24051 -f 24051//24051 21190//21190 21192//21192 -f 24051//24051 21192//21192 24050//24050 -f 24050//24050 21192//21192 24049//24049 -f 24049//24049 21192//21192 21194//21194 -f 24049//24049 21194//21194 24048//24048 -f 24048//24048 21194//21194 21196//21196 -f 24048//24048 21196//21196 21198//21198 -f 21206//21206 24038//24038 21204//21204 -f 21204//21204 24038//24038 21202//21202 -f 21202//21202 24038//24038 24045//24045 -f 21202//21202 24045//24045 21200//21200 -f 21200//21200 24045//24045 24046//24046 -f 21200//21200 24046//24046 24047//24047 -f 24041//24041 24040//24040 21206//21206 -f 21206//21206 24040//24040 24039//24039 -f 21206//21206 24039//24039 24038//24038 -f 21206//21206 21156//21156 24041//24041 -f 24041//24041 21156//21156 21155//21155 -f 24041//24041 21155//21155 24042//24042 -f 24042//24042 21155//21155 21209//21209 -f 24042//24042 21209//21209 24043//24043 -f 24043//24043 21209//21209 21211//21211 -f 24036//24036 24037//24037 21211//21211 -f 21211//21211 24037//24037 24044//24044 -f 21211//21211 24044//24044 24043//24043 -f 21211//21211 19482//19482 24036//24036 -f 24036//24036 19482//19482 19484//19484 -f 24036//24036 19484//19484 24035//24035 -f 24035//24035 19484//19484 19486//19486 -f 24035//24035 19486//19486 24034//24034 -f 24034//24034 19486//19486 19487//19487 -f 24034//24034 19487//19487 24033//24033 -f 24033//24033 19487//19487 19480//19480 -f 24033//24033 19480//19480 24031//24031 -f 24031//24031 19480//19480 19478//19478 -f 24031//24031 19478//19478 24032//24032 -f 24032//24032 19478//19478 19477//19477 -f 19471//19471 24030//24030 19473//19473 -f 19473//19473 24030//24030 24032//24032 -f 19473//19473 24032//24032 19475//19475 -f 19475//19475 24032//24032 19477//19477 -f 19467//19467 24027//24027 19469//19469 -f 19469//19469 24027//24027 24028//24028 -f 19469//19469 24028//24028 19471//19471 -f 19471//19471 24028//24028 24029//24029 -f 19471//19471 24029//24029 24030//24030 -f 24021//24021 24022//24022 19459//19459 -f 19459//19459 24022//24022 24023//24023 -f 19459//19459 24023//24023 19461//19461 -f 19461//19461 24023//24023 24024//24024 -f 19461//19461 24024//24024 19463//19463 -f 19463//19463 24024//24024 24025//24025 -f 19463//19463 24025//24025 19465//19465 -f 19465//19465 24025//24025 24026//24026 -f 19465//19465 24026//24026 24027//24027 -f 19459//19459 19457//19457 24021//24021 -f 24021//24021 19457//19457 19455//19455 -f 24021//24021 19455//19455 24020//24020 -f 24020//24020 19455//19455 24019//24019 -f 19455//19455 19453//19453 24019//24019 -f 24019//24019 19453//19453 19451//19451 -f 24019//24019 19451//19451 24018//24018 -f 24018//24018 19451//19451 19449//19449 -f 24018//24018 19449//19449 19447//19447 -f 19440//19440 24017//24017 19442//19442 -f 19442//19442 24017//24017 19445//19445 -f 19445//19445 24017//24017 24016//24016 -f 19445//19445 24016//24016 24018//24018 -f 24008//24008 24007//24007 19437//19437 -f 19437//19437 24007//24007 24015//24015 -f 19437//19437 24015//24015 19440//19440 -f 19440//19440 24015//24015 24014//24014 -f 19440//19440 24014//24014 24017//24017 -f 19437//19437 19436//19436 24008//24008 -f 24008//24008 19436//19436 19490//19490 -f 24008//24008 19490//19490 24009//24009 -f 24009//24009 19490//19490 19491//19491 -f 19498//19498 24013//24013 19495//19495 -f 19495//19495 24013//24013 24012//24012 -f 19495//19495 24012//24012 19494//19494 -f 19494//19494 24012//24012 24011//24011 -f 19494//19494 24011//24011 19491//19491 -f 19491//19491 24011//24011 24010//24010 -f 19491//19491 24010//24010 24009//24009 -f 19500//19500 24004//24004 19498//19498 -f 19498//19498 24004//24004 24003//24003 -f 19498//19498 24003//24003 24013//24013 -f 24002//24002 24006//24006 19500//19500 -f 19500//19500 24006//24006 24005//24005 -f 19500//19500 24005//24005 24004//24004 -f 19500//19500 19502//19502 24002//24002 -f 24002//24002 19502//19502 19504//19504 -f 24002//24002 19504//19504 24001//24001 -f 24001//24001 19504//19504 21088//21088 -f 24001//24001 21088//21088 24000//24000 -f 24000//24000 21088//21088 21091//21091 -f 24000//24000 21091//21091 23999//23999 -f 23999//23999 21091//21091 23998//23998 -f 23998//23998 21091//21091 21093//21093 -f 23998//23998 21093//21093 23941//23941 -f 23941//23941 21093//21093 23942//23942 -f 23942//23942 21093//21093 21095//21095 -f 23942//23942 21095//21095 23997//23997 -f 23997//23997 21095//21095 23996//23996 -f 21095//21095 21104//21104 23996//23996 -f 23996//23996 21104//21104 21103//21103 -f 23996//23996 21103//21103 23995//23995 -f 23995//23995 21103//21103 23994//23994 -f 21103//21103 21100//21100 23994//23994 -f 23994//23994 21100//21100 21098//21098 -f 23994//23994 21098//21098 23993//23993 -f 23993//23993 21098//21098 21097//21097 -f 23993//23993 21097//21097 23992//23992 -f 23992//23992 21097//21097 21105//21105 -f 23992//23992 21105//21105 23991//23991 -f 23991//23991 21105//21105 23990//23990 -f 23990//23990 21105//21105 23989//23989 -f 23989//23989 21105//21105 21107//21107 -f 23989//23989 21107//21107 23988//23988 -f 23988//23988 21107//21107 23987//23987 -f 23987//23987 21107//21107 21114//21114 -f 23987//23987 21114//21114 23986//23986 -f 23984//23984 23985//23985 21118//21118 -f 21118//21118 23985//23985 23986//23986 -f 21118//21118 23986//23986 21116//21116 -f 21116//21116 23986//23986 21114//21114 -f 21118//21118 21120//21120 23984//23984 -f 23984//23984 21120//21120 21109//21109 -f 23984//23984 21109//21109 23983//23983 -f 23983//23983 21109//21109 21108//21108 -f 23983//23983 21108//21108 23944//23944 -f 23944//23944 21108//21108 21111//21111 -f 23944//23944 21111//21111 23943//23943 -f 21111//21111 21128//21128 23943//23943 -f 23943//23943 21128//21128 21130//21130 -f 23943//23943 21130//21130 23982//23982 -f 23982//23982 21130//21130 21131//21131 -f 21125//21125 23976//23976 21131//21131 -f 21131//21131 23976//23976 23981//23981 -f 21131//21131 23981//23981 23982//23982 -f 21125//21125 21142//21142 23976//23976 -f 23976//23976 21142//21142 21141//21141 -f 23976//23976 21141//21141 23977//23977 -f 21141//21141 21139//21139 23977//23977 -f 23977//23977 21139//21139 21137//21137 -f 23977//23977 21137//21137 23978//23978 -f 21150//21150 23975//23975 21151//21151 -f 21151//21151 23975//23975 23974//23974 -f 21151//21151 23974//23974 21133//21133 -f 21133//21133 23974//23974 23973//23973 -f 21133//21133 23973//23973 21135//21135 -f 21135//21135 23973//23973 23980//23980 -f 21135//21135 23980//23980 21137//21137 -f 21137//21137 23980//23980 23979//23979 -f 21137//21137 23979//23979 23978//23978 -f 21148//21148 23972//23972 21150//21150 -f 21150//21150 23972//23972 23971//23971 -f 21150//21150 23971//23971 23975//23975 -f 21148//21148 21146//21146 23972//23972 -f 23972//23972 21146//21146 21144//21144 -f 23972//23972 21144//21144 23970//23970 -f 23970//23970 21144//21144 21154//21154 -f 23970//23970 21154//21154 23969//23969 -f 23969//23969 21154//21154 21153//21153 -f 23969//23969 21153//21153 23968//23968 -f 23968//23968 21153//21153 23967//23967 -f 23967//23967 21153//21153 19371//19371 -f 23967//23967 19371//19371 23966//23966 -f 23966//23966 19371//19371 19373//19373 -f 23966//23966 19373//19373 23965//23965 -f 23965//23965 19373//19373 19375//19375 -f 23965//23965 19375//19375 23964//23964 -f 23964//23964 19375//19375 23963//23963 -f 23963//23963 19375//19375 19377//19377 -f 23963//23963 19377//19377 23962//23962 -f 23962//23962 19377//19377 19380//19380 -f 23962//23962 19380//19380 23961//23961 -f 23961//23961 19380//19380 19381//19381 -f 23961//23961 19381//19381 23960//23960 -f 23960//23960 19381//19381 19384//19384 -f 23960//23960 19384//19384 23959//23959 -f 23959//23959 19384//19384 19386//19386 -f 23959//23959 19386//19386 23958//23958 -f 19386//19386 19389//19389 23958//23958 -f 23958//23958 19389//19389 19391//19391 -f 23958//23958 19391//19391 23956//23956 -f 23956//23956 19391//19391 19393//19393 -f 23956//23956 19393//19393 23957//23957 -f 19393//19393 19395//19395 23957//23957 -f 23957//23957 19395//19395 19397//19397 -f 23957//23957 19397//19397 23955//23955 -f 23955//23955 19397//19397 23952//23952 -f 23952//23952 19397//19397 19399//19399 -f 23952//23952 19399//19399 19401//19401 -f 23950//23950 23951//23951 19403//19403 -f 19403//19403 23951//23951 23954//23954 -f 19403//19403 23954//23954 19401//19401 -f 19401//19401 23954//23954 23953//23953 -f 19401//19401 23953//23953 23952//23952 -f 19403//19403 19405//19405 23950//23950 -f 23950//23950 19405//19405 19407//19407 -f 23950//23950 19407//19407 23949//23949 -f 23949//23949 19407//19407 19409//19409 -f 19411//19411 23947//23947 19409//19409 -f 19409//19409 23947//23947 23948//23948 -f 19409//19409 23948//23948 23949//23949 -f 19411//19411 19413//19413 23947//23947 -f 23947//23947 19413//19413 19415//19415 -f 23947//23947 19415//19415 23946//23946 -f 23946//23946 19415//19415 19417//19417 -f 23946//23946 19417//19417 23945//23945 -f 22845//22845 22512//22512 22843//22843 -f 22843//22843 22512//22512 22511//22511 -f 22843//22843 22511//22511 22625//22625 -f 22625//22625 22511//22511 22626//22626 -f 22872//22872 22528//22528 22870//22870 -f 22870//22870 22528//22528 22527//22527 -f 22870//22870 22527//22527 22589//22589 -f 22589//22589 22527//22527 22591//22591 -f 22575//22575 22574//22574 22844//22844 -f 22844//22844 22574//22574 22525//22525 -f 22844//22844 22525//22525 22845//22845 -f 22845//22845 22525//22525 22512//22512 -f 22620//22620 22591//22591 22868//22868 -f 22868//22868 22591//22591 22527//22527 -f 22868//22868 22527//22527 22869//22869 -f 22869//22869 22527//22527 22520//22520 -f 20898//20898 24191//24191 24192//24192 -f 19289//19289 19291//19291 24193//24193 -f 19253//19253 19251//19251 24194//24194 -f 24194//24194 19251//19251 24195//24195 -f 20960//20960 24196//24196 24197//24197 -f 19331//19331 24198//24198 24199//24199 -f 21079//21079 21077//21077 24200//24200 -f 19408//19408 24201//24201 24202//24202 -f 19396//19396 24203//24203 24204//24204 -f 19382//19382 24205//24205 24206//24206 -f 21138//21138 24207//24207 24208//24208 -f 21110//21110 24209//24209 24210//24210 -f 21121//21121 21119//21119 24211//24211 -f 19493//19493 19492//19492 24212//24212 -f 24212//24212 19492//19492 19489//19489 -f 24212//24212 19489//19489 23945//23945 -f 23945//23945 19489//19489 19488//19488 -f 23945//23945 19488//19488 19438//19438 -f 19493//19493 24212//24212 19496//19496 -f 19496//19496 24212//24212 24213//24213 -f 19496//19496 24213//24213 19497//19497 -f 19497//19497 24213//24213 24214//24214 -f 19497//19497 24214//24214 19499//19499 -f 19499//19499 24214//24214 24215//24215 -f 19499//19499 24215//24215 19501//19501 -f 19501//19501 24215//24215 24216//24216 -f 19501//19501 24216//24216 19503//19503 -f 19503//19503 24216//24216 24217//24217 -f 19503//19503 24217//24217 19505//19505 -f 19505//19505 24217//24217 24218//24218 -f 19505//19505 24218//24218 21089//21089 -f 21089//21089 24218//24218 24219//24219 -f 21089//21089 24219//24219 21090//21090 -f 21090//21090 24219//24219 24220//24220 -f 21090//21090 24220//24220 21092//21092 -f 24221//24221 24222//24222 21102//21102 -f 21102//21102 24222//24222 24223//24223 -f 21102//21102 24223//24223 24224//24224 -f 24220//24220 24225//24225 21092//21092 -f 21092//21092 24225//24225 24226//24226 -f 21092//21092 24226//24226 21094//21094 -f 21094//21094 24226//24226 24221//24221 -f 21094//21094 24221//24221 21096//21096 -f 21096//21096 24221//24221 21102//21102 -f 21106//21106 21099//21099 24224//24224 -f 24224//24224 21099//21099 21101//21101 -f 24224//24224 21101//21101 21102//21102 -f 24224//24224 24227//24227 21106//21106 -f 21106//21106 24227//24227 24228//24228 -f 21106//21106 24228//24228 21112//21112 -f 21112//21112 24228//24228 24229//24229 -f 21112//21112 24229//24229 21113//21113 -f 24211//24211 21119//21119 24230//24230 -f 24230//24230 21119//21119 21117//21117 -f 24230//24230 21117//21117 24229//24229 -f 24229//24229 21117//21117 21115//21115 -f 24229//24229 21115//21115 21113//21113 -f 24209//24209 21110//21110 24211//24211 -f 24211//24211 21110//21110 21122//21122 -f 24211//24211 21122//21122 21121//21121 -f 21123//21123 21129//21129 24210//24210 -f 21129//21129 21127//21127 24210//24210 -f 24210//24210 21127//21127 21126//21126 -f 24210//24210 21126//21126 21110//21110 -f 24210//24210 24231//24231 21123//21123 -f 21123//21123 24231//24231 24232//24232 -f 21123//21123 24232//24232 21124//21124 -f 24207//24207 21138//21138 24232//24232 -f 24232//24232 21138//21138 21140//21140 -f 24232//24232 21140//21140 21124//21124 -f 21145//21145 21147//21147 24233//24233 -f 24233//24233 21147//21147 21149//21149 -f 24233//24233 21149//21149 24234//24234 -f 24234//24234 21149//21149 21132//21132 -f 24234//24234 21132//21132 24235//24235 -f 24235//24235 21132//21132 21134//21134 -f 24235//24235 21134//21134 24208//24208 -f 24208//24208 21134//21134 21136//21136 -f 24208//24208 21136//21136 21138//21138 -f 24233//24233 24236//24236 21145//21145 -f 21145//21145 24236//24236 24237//24237 -f 21145//21145 24237//24237 21143//21143 -f 24237//24237 24238//24238 21143//21143 -f 21143//21143 24238//24238 24239//24239 -f 21143//21143 24239//24239 21152//21152 -f 21152//21152 24239//24239 24240//24240 -f 21152//21152 24240//24240 19372//19372 -f 19372//19372 24240//24240 24241//24241 -f 19372//19372 24241//24241 19374//19374 -f 19374//19374 24241//24241 24242//24242 -f 19374//19374 24242//24242 19376//19376 -f 24242//24242 24243//24243 19376//19376 -f 19376//19376 24243//24243 24244//24244 -f 19376//19376 24244//24244 19378//19378 -f 24205//24205 19382//19382 24244//24244 -f 24244//24244 19382//19382 19379//19379 -f 24244//24244 19379//19379 19378//19378 -f 24245//24245 19387//19387 24246//24246 -f 24246//24246 19387//19387 19385//19385 -f 24246//24246 19385//19385 24206//24206 -f 24206//24206 19385//19385 19383//19383 -f 24206//24206 19383//19383 19382//19382 -f 24203//24203 19396//19396 24247//24247 -f 19396//19396 19394//19394 24247//24247 -f 24247//24247 19394//19394 19392//19392 -f 24247//24247 19392//19392 24248//24248 -f 24248//24248 19392//19392 19390//19390 -f 24248//24248 19390//19390 24245//24245 -f 24245//24245 19390//19390 19388//19388 -f 24245//24245 19388//19388 19387//19387 -f 19408//19408 19406//19406 24201//24201 -f 24201//24201 19406//19406 19404//19404 -f 24201//24201 19404//19404 24249//24249 -f 24249//24249 19404//19404 19402//19402 -f 24249//24249 19402//19402 24250//24250 -f 24250//24250 19402//19402 19400//19400 -f 24250//24250 19400//19400 24204//24204 -f 24204//24204 19400//19400 19398//19398 -f 24204//24204 19398//19398 19396//19396 -f 24251//24251 19414//19414 24252//24252 -f 24252//24252 19414//19414 19412//19412 -f 24252//24252 19412//19412 24202//24202 -f 24202//24202 19412//19412 19410//19410 -f 24202//24202 19410//19410 19408//19408 -f 24251//24251 24253//24253 19414//19414 -f 19414//19414 24253//24253 24254//24254 -f 19414//19414 24254//24254 19416//19416 -f 19416//19416 24254//24254 19418//19418 -f 19418//19418 24254//24254 24255//24255 -f 19418//19418 24255//24255 19421//19421 -f 19421//19421 24255//24255 24256//24256 -f 19421//19421 24256//24256 19423//19423 -f 19423//19423 24256//24256 24257//24257 -f 19423//19423 24257//24257 19424//19424 -f 19424//19424 24257//24257 19426//19426 -f 19426//19426 24257//24257 24258//24258 -f 19426//19426 24258//24258 19428//19428 -f 19428//19428 24258//24258 24259//24259 -f 19428//19428 24259//24259 19430//19430 -f 19430//19430 24259//24259 24260//24260 -f 19430//19430 24260//24260 19433//19433 -f 24260//24260 24261//24261 19433//19433 -f 19433//19433 24261//24261 24262//24262 -f 19433//19433 24262//24262 19431//19431 -f 19431//19431 24262//24262 21020//21020 -f 21020//21020 24262//24262 24263//24263 -f 21020//21020 24263//24263 21027//21027 -f 21027//21027 24263//24263 24264//24264 -f 21027//21027 24264//24264 21028//21028 -f 21028//21028 24264//24264 24265//24265 -f 21028//21028 24265//24265 24266//24266 -f 21033//21033 21032//21032 24266//24266 -f 24266//24266 21032//21032 21030//21030 -f 24266//24266 21030//21030 21028//21028 -f 24266//24266 24267//24267 21033//21033 -f 21033//21033 24267//24267 24268//24268 -f 21033//21033 24268//24268 21023//21023 -f 21023//21023 24268//24268 24269//24269 -f 21023//21023 24269//24269 21025//21025 -f 21025//21025 24269//24269 24270//24270 -f 21025//21025 24270//24270 21038//21038 -f 21038//21038 24270//24270 24271//24271 -f 21038//21038 24271//24271 21039//21039 -f 21039//21039 24271//24271 21041//21041 -f 24272//24272 21051//21051 24273//24273 -f 24273//24273 21051//21051 21053//21053 -f 24273//24273 21053//21053 24274//24274 -f 24271//24271 24275//24275 21041//21041 -f 21041//21041 24275//24275 24276//24276 -f 21041//21041 24276//24276 21042//21042 -f 21042//21042 24276//24276 24277//24277 -f 21042//21042 24277//24277 21035//21035 -f 21035//21035 24277//24277 24274//24274 -f 21035//21035 24274//24274 21037//21037 -f 21037//21037 24274//24274 21053//21053 -f 21062//21062 21060//21060 24278//24278 -f 24278//24278 21060//21060 21059//21059 -f 24278//24278 21059//21059 24279//24279 -f 24279//24279 21059//21059 21057//21057 -f 24279//24279 21057//21057 24280//24280 -f 24280//24280 21057//21057 21043//21043 -f 24280//24280 21043//21043 24281//24281 -f 24281//24281 21043//21043 21046//21046 -f 24281//24281 21046//21046 24272//24272 -f 24272//24272 21046//21046 21049//21049 -f 24272//24272 21049//21049 21051//21051 -f 21062//21062 24278//24278 21064//21064 -f 21064//21064 24278//24278 24282//24282 -f 21064//21064 24282//24282 21065//21065 -f 21065//21065 24282//24282 21067//21067 -f 21067//21067 24282//24282 24283//24283 -f 21067//21067 24283//24283 21068//21068 -f 24283//24283 24284//24284 21068//21068 -f 21068//21068 24284//24284 24285//24285 -f 21068//21068 24285//24285 21070//21070 -f 21070//21070 24285//24285 21072//21072 -f 21072//21072 24285//24285 24286//24286 -f 21072//21072 24286//24286 21073//21073 -f 21073//21073 24286//24286 21075//21075 -f 21075//21075 24286//24286 24287//24287 -f 21075//21075 24287//24287 21077//21077 -f 21077//21077 24287//24287 24288//24288 -f 21077//21077 24288//24288 24200//24200 -f 21079//21079 24200//24200 21081//21081 -f 21081//21081 24200//24200 24289//24289 -f 21081//21081 24289//24289 21083//21083 -f 24290//24290 21087//21087 24289//24289 -f 24289//24289 21087//21087 21085//21085 -f 24289//24289 21085//21085 21083//21083 -f 24291//24291 19305//19305 24292//24292 -f 24292//24292 19305//19305 21087//21087 -f 24292//24292 21087//21087 24293//24293 -f 24293//24293 21087//21087 24290//24290 -f 19313//19313 19312//19312 24291//24291 -f 24291//24291 19312//19312 19307//19307 -f 24291//24291 19307//19307 19305//19305 -f 24291//24291 24294//24294 19313//19313 -f 19313//19313 24294//24294 24295//24295 -f 19313//19313 24295//24295 19315//19315 -f 24296//24296 19318//19318 24295//24295 -f 24295//24295 19318//19318 19317//19317 -f 24295//24295 19317//19317 19315//19315 -f 19324//19324 19322//19322 24297//24297 -f 24297//24297 19322//19322 19320//19320 -f 24297//24297 19320//19320 24296//24296 -f 24296//24296 19320//19320 19311//19311 -f 24296//24296 19311//19311 19318//19318 -f 24297//24297 24298//24298 19324//19324 -f 19324//19324 24298//24298 24299//24299 -f 19324//19324 24299//24299 19327//19327 -f 24198//24198 19331//19331 24299//24299 -f 24299//24299 19331//19331 19329//19329 -f 24299//24299 19329//19329 19327//19327 -f 24300//24300 19339//19339 24301//24301 -f 24301//24301 19339//19339 19337//19337 -f 24301//24301 19337//19337 24302//24302 -f 24302//24302 19337//19337 19335//19335 -f 24302//24302 19335//19335 24199//24199 -f 24199//24199 19335//19335 19333//19333 -f 24199//24199 19333//19333 19331//19331 -f 19346//19346 19344//19344 24300//24300 -f 19344//19344 19342//19342 24300//24300 -f 24300//24300 19342//19342 19341//19341 -f 24300//24300 19341//19341 19339//19339 -f 24300//24300 24303//24303 19346//19346 -f 19346//19346 24303//24303 24304//24304 -f 19346//19346 24304//24304 19348//19348 -f 19348//19348 24304//24304 24305//24305 -f 19348//19348 24305//24305 19350//19350 -f 19350//19350 24305//24305 24306//24306 -f 19350//19350 24306//24306 19352//19352 -f 19352//19352 24306//24306 19353//19353 -f 19353//19353 24306//24306 19355//19355 -f 19355//19355 24306//24306 24307//24307 -f 19355//19355 24307//24307 19357//19357 -f 19357//19357 24307//24307 24308//24308 -f 19357//19357 24308//24308 19359//19359 -f 19359//19359 24308//24308 24309//24309 -f 19359//19359 24309//24309 19366//19366 -f 19366//19366 24309//24309 24310//24310 -f 19366//19366 24310//24310 19364//19364 -f 24310//24310 24311//24311 19364//19364 -f 19364//19364 24311//24311 24312//24312 -f 19364//19364 24312//24312 19362//19362 -f 20952//20952 20951//20951 24313//24313 -f 20951//20951 20949//20949 24313//24313 -f 24313//24313 20949//20949 20948//20948 -f 24313//24313 20948//20948 24314//24314 -f 24314//24314 20948//20948 19367//19367 -f 24314//24314 19367//19367 24315//24315 -f 24315//24315 19367//19367 19369//19369 -f 24315//24315 19369//19369 24312//24312 -f 24312//24312 19369//19369 19370//19370 -f 24312//24312 19370//19370 19362//19362 -f 24196//24196 20954//20954 24316//24316 -f 24316//24316 20954//20954 20952//20952 -f 24316//24316 20952//20952 24317//24317 -f 24317//24317 20952//20952 24313//24313 -f 20960//20960 20958//20958 24196//24196 -f 24196//24196 20958//20958 20956//20956 -f 24196//24196 20956//20956 20954//20954 -f 20965//20965 20963//20963 24318//24318 -f 24318//24318 20963//20963 20973//20973 -f 24318//24318 20973//20973 24319//24319 -f 24319//24319 20973//20973 20972//20972 -f 24319//24319 20972//20972 24320//24320 -f 24320//24320 20972//20972 20970//20970 -f 24320//24320 20970//20970 24197//24197 -f 24197//24197 20970//20970 20968//20968 -f 24197//24197 20968//20968 20960//20960 -f 24318//24318 24321//24321 20965//20965 -f 20965//20965 24321//24321 24322//24322 -f 20965//20965 24322//24322 20975//20975 -f 20975//20975 24322//24322 20977//20977 -f 24323//24323 20979//20979 24324//24324 -f 24324//24324 20979//20979 20977//20977 -f 24324//24324 20977//20977 24325//24325 -f 24325//24325 20977//20977 24322//24322 -f 20990//20990 20988//20988 24323//24323 -f 24323//24323 20988//20988 20987//20987 -f 24323//24323 20987//20987 20979//20979 -f 24323//24323 24326//24326 20990//20990 -f 20990//20990 24326//24326 24327//24327 -f 20990//20990 24327//24327 20992//20992 -f 20992//20992 24327//24327 20994//20994 -f 20994//20994 24327//24327 24328//24328 -f 20994//20994 24328//24328 20986//20986 -f 20986//20986 24328//24328 24329//24329 -f 20986//20986 24329//24329 24330//24330 -f 24331//24331 20998//20998 24332//24332 -f 24332//24332 20998//20998 20981//20981 -f 24332//24332 20981//20981 24330//24330 -f 24330//24330 20981//20981 20984//20984 -f 24330//24330 20984//20984 20986//20986 -f 24333//24333 21008//21008 24334//24334 -f 24334//24334 21008//21008 21006//21006 -f 24334//24334 21006//21006 24335//24335 -f 24335//24335 21006//21006 21003//21003 -f 24335//24335 21003//21003 24331//24331 -f 24331//24331 21003//21003 21001//21001 -f 24331//24331 21001//21001 20998//20998 -f 21013//21013 21011//21011 24333//24333 -f 24333//24333 21011//21011 21009//21009 -f 24333//24333 21009//21009 21008//21008 -f 24333//24333 24336//24336 21013//21013 -f 21013//21013 24336//24336 24337//24337 -f 21013//21013 24337//24337 21015//21015 -f 21015//21015 24337//24337 24338//24338 -f 21015//21015 24338//24338 21016//21016 -f 24338//24338 24339//24339 21016//21016 -f 21016//21016 24339//24339 24340//24340 -f 21016//21016 24340//24340 19236//19236 -f 19236//19236 24340//24340 24341//24341 -f 19236//19236 24341//24341 19238//19238 -f 19238//19238 24341//24341 24342//24342 -f 19238//19238 24342//24342 19240//19240 -f 19240//19240 24342//24342 24343//24343 -f 19240//19240 24343//24343 19242//19242 -f 24344//24344 19245//19245 24343//24343 -f 24343//24343 19245//19245 19243//19243 -f 24343//24343 19243//19243 19242//19242 -f 24195//24195 19251//19251 24345//24345 -f 24345//24345 19251//19251 19249//19249 -f 24345//24345 19249//19249 24344//24344 -f 24344//24344 19249//19249 19247//19247 -f 24344//24344 19247//19247 19245//19245 -f 19253//19253 24194//24194 19255//19255 -f 19255//19255 24194//24194 24346//24346 -f 19255//19255 24346//24346 19257//19257 -f 24347//24347 19259//19259 24348//24348 -f 24348//24348 19259//19259 19257//19257 -f 24348//24348 19257//19257 24349//24349 -f 24349//24349 19257//19257 24346//24346 -f 24350//24350 19269//19269 19267//19267 -f 24350//24350 19267//19267 24351//24351 -f 19267//19267 19265//19265 24351//24351 -f 24351//24351 19265//19265 19264//19264 -f 24351//24351 19264//19264 24352//24352 -f 24352//24352 19264//19264 19262//19262 -f 24352//24352 19262//19262 24347//24347 -f 24347//24347 19262//19262 19260//19260 -f 24347//24347 19260//19260 19259//19259 -f 24353//24353 19271//19271 24354//24354 -f 24354//24354 19271//19271 19269//19269 -f 24354//24354 19269//19269 24355//24355 -f 24355//24355 19269//19269 24350//24350 -f 19280//19280 19282//19282 24353//24353 -f 24353//24353 19282//19282 19273//19273 -f 24353//24353 19273//19273 19271//19271 -f 24353//24353 24356//24356 19280//19280 -f 19280//19280 24356//24356 24357//24357 -f 19280//19280 24357//24357 19278//19278 -f 19278//19278 24357//24357 24358//24358 -f 19278//19278 24358//24358 19276//19276 -f 19276//19276 24358//24358 24359//24359 -f 24193//24193 19291//19291 24360//24360 -f 24360//24360 19291//19291 19293//19293 -f 24360//24360 19293//19293 24361//24361 -f 24361//24361 19293//19293 19295//19295 -f 24361//24361 19295//19295 24359//24359 -f 24359//24359 19295//19295 19274//19274 -f 24359//24359 19274//19274 19276//19276 -f 19289//19289 24193//24193 19287//19287 -f 19287//19287 24193//24193 24362//24362 -f 19287//19287 24362//24362 19285//19285 -f 24362//24362 24363//24363 19285//19285 -f 19285//19285 24363//24363 24364//24364 -f 19285//19285 24364//24364 19298//19298 -f 24364//24364 24365//24365 19298//19298 -f 19298//19298 24365//24365 24366//24366 -f 19298//19298 24366//24366 19299//19299 -f 19299//19299 24366//24366 24367//24367 -f 19299//19299 24367//24367 20889//20889 -f 20889//20889 24367//24367 24368//24368 -f 20889//20889 24368//24368 20892//20892 -f 24368//24368 24369//24369 20892//20892 -f 20892//20892 24369//24369 24370//24370 -f 20892//20892 24370//24370 20894//20894 -f 24191//24191 20898//20898 24370//24370 -f 24370//24370 20898//20898 20896//20896 -f 24370//24370 20896//20896 20894//20894 -f 20904//20904 20902//20902 24192//24192 -f 24192//24192 20902//20902 20900//20900 -f 24192//24192 20900//20900 20898//20898 -f 24192//24192 24371//24371 20904//20904 -f 20904//20904 24371//24371 24372//24372 -f 20904//20904 24372//24372 20906//20906 -f 20906//20906 24372//24372 24373//24373 -f 20906//20906 24373//24373 20908//20908 -f 20908//20908 24373//24373 20910//20910 -f 20910//20910 24373//24373 24374//24374 -f 20910//20910 24374//24374 24375//24375 -f 20917//20917 20914//20914 24375//24375 -f 24375//24375 20914//20914 20912//20912 -f 24375//24375 20912//20912 20910//20910 -f 24375//24375 24376//24376 20917//20917 -f 20917//20917 24376//24376 24377//24377 -f 20917//20917 24377//24377 20919//20919 -f 20919//20919 24377//24377 24378//24378 -f 20919//20919 24378//24378 20921//20921 -f 20921//20921 24378//24378 24379//24379 -f 20921//20921 24379//24379 20923//20923 -f 24380//24380 20931//20931 24381//24381 -f 24381//24381 20931//20931 20929//20929 -f 24381//24381 20929//20929 24382//24382 -f 24382//24382 20929//20929 20927//20927 -f 24382//24382 20927//20927 24383//24383 -f 24383//24383 20927//20927 20925//20925 -f 24383//24383 20925//20925 24384//24384 -f 24384//24384 20925//20925 20923//20923 -f 24384//24384 20923//20923 24385//24385 -f 24385//24385 20923//20923 24379//24379 -f 20936//20936 20934//20934 24380//24380 -f 24380//24380 20934//20934 20932//20932 -f 24380//24380 20932//20932 20931//20931 -f 24380//24380 24386//24386 20936//20936 -f 20936//20936 24386//24386 24387//24387 -f 20936//20936 24387//24387 20938//20938 -f 22848//22848 22526//22526 22846//22846 -f 22846//22846 22526//22526 22525//22525 -f 22846//22846 22525//22525 22573//22573 -f 22573//22573 22525//22525 22574//22574 -f 22869//22869 22520//22520 22867//22867 -f 22867//22867 22520//22520 22519//22519 -f 22867//22867 22519//22519 22621//22621 -f 22621//22621 22519//22519 22623//22623 -f 21052//21052 24211//24211 24230//24230 -f 21045//21045 24210//24210 24209//24209 -f 21061//21061 24232//24232 24231//24231 -f 24235//24235 21076//21076 24234//24234 -f 24234//24234 21076//21076 24233//24233 -f 19309//19309 24206//24206 24205//24205 -f 19332//19332 24204//24204 24203//24203 -f 20978//20978 24273//24273 20976//20976 -f 19263//19263 24199//24199 24198//24198 -f 19272//19272 24300//24300 24301//24301 -f 24317//24317 20893//20893 24316//24316 -f 24316//24316 20893//20893 24196//24196 -f 20930//20930 24331//24331 24332//24332 -f 19194//19194 19196//19196 24343//24343 -f 19206//19206 24349//24349 24346//24346 -f 22896//22896 22901//22901 24370//24370 -f 22902//22902 24372//24372 24371//24371 -f 22918//22918 20940//20940 24387//24387 -f 24382//24382 22921//22921 24381//24381 -f 24381//24381 22921//22921 22920//22920 -f 24381//24381 22920//22920 24380//24380 -f 24380//24380 22920//22920 22918//22918 -f 24380//24380 22918//22918 24386//24386 -f 24386//24386 22918//22918 24387//24387 -f 22916//22916 22914//22914 24382//24382 -f 24382//24382 22914//22914 22913//22913 -f 24382//24382 22913//22913 22921//22921 -f 24382//24382 24383//24383 22916//22916 -f 22916//22916 24383//24383 24384//24384 -f 22916//22916 24384//24384 22917//22917 -f 24384//24384 24385//24385 22917//22917 -f 22917//22917 24385//24385 24379//24379 -f 22917//22917 24379//24379 22912//22912 -f 22912//22912 24379//24379 22910//22910 -f 24379//24379 24378//24378 22910//22910 -f 22910//22910 24378//24378 24377//24377 -f 22910//22910 24377//24377 22905//22905 -f 22905//22905 24377//24377 24376//24376 -f 22905//22905 24376//24376 22906//22906 -f 22906//22906 24376//24376 24375//24375 -f 22906//22906 24375//24375 22908//22908 -f 24375//24375 24374//24374 22908//22908 -f 22908//22908 24374//24374 24373//24373 -f 22908//22908 24373//24373 22909//22909 -f 24372//24372 22902//22902 24373//24373 -f 24373//24373 22902//22902 22904//22904 -f 24373//24373 22904//22904 22909//22909 -f 24370//24370 22901//22901 24191//24191 -f 24191//24191 22901//22901 22900//22900 -f 24191//24191 22900//22900 24192//24192 -f 24192//24192 22900//22900 22898//22898 -f 24192//24192 22898//22898 24371//24371 -f 24371//24371 22898//22898 22897//22897 -f 24371//24371 22897//22897 22902//22902 -f 22896//22896 24370//24370 22894//22894 -f 22894//22894 24370//24370 24369//24369 -f 22894//22894 24369//24369 22893//22893 -f 22893//22893 24369//24369 24368//24368 -f 22893//22893 24368//24368 22891//22891 -f 24368//24368 24367//24367 22891//22891 -f 22891//22891 24367//24367 24366//24366 -f 22891//22891 24366//24366 19231//19231 -f 19231//19231 24366//24366 24365//24365 -f 19231//19231 24365//24365 19232//19232 -f 24365//24365 24364//24364 19232//19232 -f 19232//19232 24364//24364 24363//24363 -f 19232//19232 24363//24363 19233//19233 -f 19233//19233 24363//24363 24362//24362 -f 19233//19233 24362//24362 19234//19234 -f 19234//19234 24362//24362 19228//19228 -f 19228//19228 24362//24362 24193//24193 -f 19228//19228 24193//24193 19226//19226 -f 24193//24193 24360//24360 19226//19226 -f 19226//19226 24360//24360 24361//24361 -f 19226//19226 24361//24361 19221//19221 -f 19218//19218 19220//19220 24358//24358 -f 24358//24358 19220//19220 19225//19225 -f 24358//24358 19225//19225 24359//24359 -f 24359//24359 19225//19225 19224//19224 -f 24359//24359 19224//19224 24361//24361 -f 24361//24361 19224//19224 19222//19222 -f 24361//24361 19222//19222 19221//19221 -f 24350//24350 19217//19217 24355//24355 -f 24355//24355 19217//19217 19216//19216 -f 24355//24355 19216//19216 24354//24354 -f 24354//24354 19216//19216 19214//19214 -f 24354//24354 19214//19214 24353//24353 -f 24353//24353 19214//19214 19213//19213 -f 24353//24353 19213//19213 24356//24356 -f 24356//24356 19213//19213 19218//19218 -f 24356//24356 19218//19218 24357//24357 -f 24357//24357 19218//19218 24358//24358 -f 24347//24347 19212//19212 24352//24352 -f 24352//24352 19212//19212 19211//19211 -f 24352//24352 19211//19211 24351//24351 -f 24351//24351 19211//19211 19209//19209 -f 24351//24351 19209//19209 24350//24350 -f 24350//24350 19209//19209 19208//19208 -f 24350//24350 19208//19208 19217//19217 -f 24349//24349 19206//19206 24348//24348 -f 24348//24348 19206//19206 19204//19204 -f 24348//24348 19204//19204 24347//24347 -f 24347//24347 19204//19204 19203//19203 -f 24347//24347 19203//19203 19212//19212 -f 24343//24343 19196//19196 24344//24344 -f 19196//19196 19199//19199 24344//24344 -f 24344//24344 19199//19199 19198//19198 -f 24344//24344 19198//19198 24345//24345 -f 24345//24345 19198//19198 19197//19197 -f 24345//24345 19197//19197 24195//24195 -f 24195//24195 19197//19197 19200//19200 -f 24195//24195 19200//19200 24194//24194 -f 24194//24194 19200//19200 19202//19202 -f 24194//24194 19202//19202 24346//24346 -f 24346//24346 19202//19202 19207//19207 -f 24346//24346 19207//19207 19206//19206 -f 19194//19194 24343//24343 19193//19193 -f 19193//19193 24343//24343 24342//24342 -f 19193//19193 24342//24342 19192//19192 -f 19192//19192 24342//24342 24341//24341 -f 19192//19192 24341//24341 19190//19190 -f 19190//19190 24341//24341 24340//24340 -f 19190//19190 24340//24340 19188//19188 -f 19188//19188 24340//24340 24339//24339 -f 19188//19188 24339//24339 20944//20944 -f 24339//24339 24338//24338 20944//20944 -f 20944//20944 24338//24338 24337//24337 -f 20944//20944 24337//24337 20945//20945 -f 20945//20945 24337//24337 24336//24336 -f 20945//20945 24336//24336 20946//20946 -f 20946//20946 24336//24336 20942//20942 -f 20942//20942 24336//24336 24333//24333 -f 20942//20942 24333//24333 20939//20939 -f 20939//20939 24333//24333 24334//24334 -f 20939//20939 24334//24334 20937//20937 -f 20937//20937 24334//24334 24335//24335 -f 20937//20937 24335//24335 20935//20935 -f 24331//24331 20930//20930 24335//24335 -f 24335//24335 20930//20930 20933//20933 -f 24335//24335 20933//20933 20935//20935 -f 20924//20924 20926//20926 24332//24332 -f 24332//24332 20926//20926 20928//20928 -f 24332//24332 20928//20928 20930//20930 -f 24332//24332 24330//24330 20924//20924 -f 20924//20924 24330//24330 24329//24329 -f 20924//20924 24329//24329 20922//20922 -f 20922//20922 24329//24329 24328//24328 -f 20922//20922 24328//24328 20920//20920 -f 20920//20920 24328//24328 20918//20918 -f 24323//24323 20916//20916 24326//24326 -f 24326//24326 20916//20916 20918//20918 -f 24326//24326 20918//20918 24327//24327 -f 24327//24327 20918//20918 24328//24328 -f 20911//20911 20913//20913 24323//24323 -f 24323//24323 20913//20913 20915//20915 -f 24323//24323 20915//20915 20916//20916 -f 24323//24323 24324//24324 20911//20911 -f 20911//20911 24324//24324 24325//24325 -f 20911//20911 24325//24325 20909//20909 -f 20909//20909 24325//24325 20907//20907 -f 20907//20907 24325//24325 24322//24322 -f 20907//20907 24322//24322 20905//20905 -f 24322//24322 24321//24321 20905//20905 -f 20905//20905 24321//24321 24318//24318 -f 20905//20905 24318//24318 20903//20903 -f 20903//20903 24318//24318 24319//24319 -f 20903//20903 24319//24319 20901//20901 -f 20901//20901 24319//24319 24320//24320 -f 20901//20901 24320//24320 20899//20899 -f 20899//20899 24320//24320 24197//24197 -f 20899//20899 24197//24197 20897//20897 -f 20897//20897 24197//24197 24196//24196 -f 20897//20897 24196//24196 20895//20895 -f 20895//20895 24196//24196 20893//20893 -f 24313//24313 20890//20890 24317//24317 -f 24317//24317 20890//20890 20891//20891 -f 24317//24317 20891//20891 20893//20893 -f 24310//24310 24309//24309 19292//19292 -f 19292//19292 19290//19290 24310//24310 -f 24310//24310 19290//19290 19288//19288 -f 24310//24310 19288//19288 19286//19286 -f 24310//24310 19286//19286 24311//24311 -f 24311//24311 19286//19286 19303//19303 -f 24311//24311 19303//19303 24312//24312 -f 24312//24312 19303//19303 19302//19302 -f 24312//24312 19302//19302 24315//24315 -f 24315//24315 19302//19302 19301//19301 -f 24315//24315 19301//19301 24314//24314 -f 24314//24314 19301//19301 19300//19300 -f 24314//24314 19300//19300 24313//24313 -f 24313//24313 19300//19300 20888//20888 -f 24313//24313 20888//20888 20890//20890 -f 24309//24309 24308//24308 19292//19292 -f 19292//19292 24308//24308 24307//24307 -f 19292//19292 24307//24307 19294//19294 -f 19294//19294 24307//24307 19296//19296 -f 19296//19296 24307//24307 24306//24306 -f 19296//19296 24306//24306 19297//19297 -f 19281//19281 19279//19279 24305//24305 -f 24305//24305 19279//19279 19277//19277 -f 24305//24305 19277//19277 24306//24306 -f 24306//24306 19277//19277 19275//19275 -f 24306//24306 19275//19275 19297//19297 -f 24305//24305 24304//24304 19281//19281 -f 19281//19281 24304//24304 24303//24303 -f 19281//19281 24303//24303 19283//19283 -f 19283//19283 24303//24303 24300//24300 -f 19283//19283 24300//24300 19284//19284 -f 19284//19284 24300//24300 19272//19272 -f 24199//24199 19263//19263 24302//24302 -f 19263//19263 19266//19266 24302//24302 -f 24302//24302 19266//19266 19268//19268 -f 24302//24302 19268//19268 24301//24301 -f 24301//24301 19268//19268 19270//19270 -f 24301//24301 19270//19270 19272//19272 -f 24298//24298 19256//19256 24299//24299 -f 24299//24299 19256//19256 19258//19258 -f 24299//24299 19258//19258 24198//24198 -f 24198//24198 19258//19258 19261//19261 -f 24198//24198 19261//19261 19263//19263 -f 19246//19246 19248//19248 24296//24296 -f 24296//24296 19248//19248 19250//19250 -f 24296//24296 19250//19250 24297//24297 -f 24297//24297 19250//19250 19252//19252 -f 24297//24297 19252//19252 24298//24298 -f 24298//24298 19252//19252 19254//19254 -f 24298//24298 19254//19254 19256//19256 -f 19246//19246 24296//24296 19244//19244 -f 19244//19244 24296//24296 24295//24295 -f 19244//19244 24295//24295 19241//19241 -f 19241//19241 24295//24295 24294//24294 -f 19241//19241 24294//24294 19239//19239 -f 19239//19239 24294//24294 24291//24291 -f 19239//19239 24291//24291 19237//19237 -f 19237//19237 24291//24291 24292//24292 -f 19237//19237 24292//24292 19235//19235 -f 19235//19235 24292//24292 24293//24293 -f 19235//19235 24293//24293 21017//21017 -f 21017//21017 24293//24293 24290//24290 -f 21017//21017 24290//24290 21018//21018 -f 21018//21018 24290//24290 24289//24289 -f 21018//21018 24289//24289 21014//21014 -f 21014//21014 24289//24289 24200//24200 -f 21014//21014 24200//24200 21012//21012 -f 21000//21000 21002//21002 24286//24286 -f 24286//24286 21002//21002 21004//21004 -f 24286//24286 21004//21004 24287//24287 -f 24287//24287 21004//21004 21005//21005 -f 24287//24287 21005//21005 24288//24288 -f 24288//24288 21005//21005 21007//21007 -f 24288//24288 21007//21007 24200//24200 -f 24200//24200 21007//21007 21010//21010 -f 24200//24200 21010//21010 21012//21012 -f 24286//24286 24285//24285 21000//21000 -f 21000//21000 24285//24285 24284//24284 -f 21000//21000 24284//24284 20999//20999 -f 20999//20999 24284//24284 20997//20997 -f 20997//20997 24284//24284 24283//24283 -f 20997//20997 24283//24283 20982//20982 -f 20982//20982 24283//24283 24282//24282 -f 20982//20982 24282//24282 20983//20983 -f 20983//20983 24282//24282 20985//20985 -f 20985//20985 24282//24282 24278//24278 -f 20985//20985 24278//24278 20996//20996 -f 20996//20996 24278//24278 24279//24279 -f 20996//20996 24279//24279 20995//20995 -f 20995//20995 24279//24279 20993//20993 -f 20993//20993 24279//24279 24280//24280 -f 20993//20993 24280//24280 20991//20991 -f 24280//24280 24281//24281 20991//20991 -f 20991//20991 24281//24281 24272//24272 -f 20991//20991 24272//24272 20989//20989 -f 24273//24273 20978//20978 24272//24272 -f 24272//24272 20978//20978 20980//20980 -f 24272//24272 20980//20980 20989//20989 -f 20976//20976 24273//24273 20974//20974 -f 20974//20974 24273//24273 24274//24274 -f 20974//20974 24274//24274 20966//20966 -f 20966//20966 24274//24274 24277//24277 -f 20966//20966 24277//24277 20964//20964 -f 24277//24277 24276//24276 20964//20964 -f 20964//20964 24276//24276 24275//24275 -f 20964//20964 24275//24275 20962//20962 -f 20962//20962 24275//24275 20971//20971 -f 20971//20971 24275//24275 24271//24271 -f 20971//20971 24271//24271 20969//20969 -f 20969//20969 24271//24271 20967//20967 -f 20967//20967 24271//24271 24270//24270 -f 20967//20967 24270//24270 20961//20961 -f 24270//24270 24269//24269 20961//20961 -f 20961//20961 24269//24269 24268//24268 -f 20961//20961 24268//24268 20959//20959 -f 20959//20959 24268//24268 24267//24267 -f 20959//20959 24267//24267 20957//20957 -f 20957//20957 24267//24267 20955//20955 -f 24267//24267 24266//24266 20955//20955 -f 20955//20955 24266//24266 24265//24265 -f 20955//20955 24265//24265 20953//20953 -f 20953//20953 24265//24265 20950//20950 -f 20950//20950 24265//24265 24264//24264 -f 20950//20950 24264//24264 20947//20947 -f 24264//24264 24263//24263 20947//20947 -f 20947//20947 24263//24263 24262//24262 -f 20947//20947 24262//24262 19368//19368 -f 19368//19368 24262//24262 24261//24261 -f 19368//19368 24261//24261 19363//19363 -f 19363//19363 24261//24261 24260//24260 -f 19363//19363 24260//24260 19365//19365 -f 24255//24255 19358//19358 24256//24256 -f 24256//24256 19358//19358 19360//19360 -f 24256//24256 19360//19360 24257//24257 -f 24257//24257 19360//19360 19361//19361 -f 24257//24257 19361//19361 24258//24258 -f 24258//24258 19361//19361 19365//19365 -f 24258//24258 19365//19365 24259//24259 -f 24259//24259 19365//19365 24260//24260 -f 19351//19351 19354//19354 24255//24255 -f 24255//24255 19354//19354 19356//19356 -f 24255//24255 19356//19356 19358//19358 -f 24255//24255 24254//24254 19351//19351 -f 19351//19351 24254//24254 24253//24253 -f 19351//19351 24253//24253 19349//19349 -f 19349//19349 24253//24253 24251//24251 -f 19349//19349 24251//24251 19347//19347 -f 19347//19347 24251//24251 24252//24252 -f 19347//19347 24252//24252 19345//19345 -f 24252//24252 24202//24202 19345//19345 -f 19345//19345 24202//24202 24201//24201 -f 19345//19345 24201//24201 19343//19343 -f 24204//24204 19332//19332 24250//24250 -f 19332//19332 19334//19334 24250//24250 -f 24250//24250 19334//19334 19336//19336 -f 24250//24250 19336//19336 24249//24249 -f 24249//24249 19336//19336 19338//19338 -f 24249//24249 19338//19338 24201//24201 -f 24201//24201 19338//19338 19340//19340 -f 24201//24201 19340//19340 19343//19343 -f 24248//24248 24245//24245 19323//19323 -f 19323//19323 19325//19325 24248//24248 -f 24248//24248 19325//19325 19326//19326 -f 24248//24248 19326//19326 24247//24247 -f 24247//24247 19326//19326 19328//19328 -f 24247//24247 19328//19328 24203//24203 -f 24203//24203 19328//19328 19330//19330 -f 24203//24203 19330//19330 19332//19332 -f 24206//24206 19309//19309 24246//24246 -f 24246//24246 19309//19309 19319//19319 -f 24246//24246 19319//19319 24245//24245 -f 24245//24245 19319//19319 19321//19321 -f 24245//24245 19321//19321 19323//19323 -f 19314//19314 19316//19316 24205//24205 -f 24205//24205 19316//19316 19310//19310 -f 24205//24205 19310//19310 19309//19309 -f 24205//24205 24244//24244 19314//19314 -f 19314//19314 24244//24244 24243//24243 -f 19314//19314 24243//24243 19308//19308 -f 24243//24243 24242//24242 19308//19308 -f 19308//19308 24242//24242 24241//24241 -f 19308//19308 24241//24241 19306//19306 -f 19306//19306 24241//24241 24240//24240 -f 19306//19306 24240//24240 19304//19304 -f 19304//19304 24240//24240 21086//21086 -f 21086//21086 24240//24240 24239//24239 -f 21086//21086 24239//24239 21084//21084 -f 21084//21084 24239//24239 24238//24238 -f 21084//21084 24238//24238 21082//21082 -f 24238//24238 24237//24237 21082//21082 -f 21082//21082 24237//24237 24236//24236 -f 21082//21082 24236//24236 21080//21080 -f 24233//24233 21076//21076 24236//24236 -f 24236//24236 21076//21076 21078//21078 -f 24236//24236 21078//21078 21080//21080 -f 21069//21069 21071//21071 24235//24235 -f 24235//24235 21071//21071 21074//21074 -f 24235//24235 21074//21074 21076//21076 -f 24235//24235 24208//24208 21069//21069 -f 21069//21069 24208//24208 24207//24207 -f 21069//21069 24207//24207 21066//21066 -f 21066//21066 24207//24207 24232//24232 -f 21066//21066 24232//24232 21063//21063 -f 21063//21063 24232//24232 21061//21061 -f 21045//21045 21044//21044 24210//24210 -f 24210//24210 21044//21044 21056//21056 -f 24210//24210 21056//21056 24231//24231 -f 24231//24231 21056//21056 21058//21058 -f 24231//24231 21058//21058 21061//21061 -f 21052//21052 21050//21050 24211//24211 -f 24211//24211 21050//21050 21048//21048 -f 24211//24211 21048//21048 24209//24209 -f 24209//24209 21048//21048 21047//21047 -f 24209//24209 21047//21047 21045//21045 -f 24227//24227 21034//21034 24228//24228 -f 24228//24228 21034//21034 21036//21036 -f 24228//24228 21036//21036 24229//24229 -f 24229//24229 21036//21036 21055//21055 -f 24229//24229 21055//21055 24230//24230 -f 24230//24230 21055//21055 21054//21054 -f 24230//24230 21054//21054 21052//21052 -f 24225//24225 21021//21021 24226//24226 -f 24226//24226 21021//21021 21029//21029 -f 24226//24226 21029//21029 24221//24221 -f 24221//24221 21029//21029 21031//21031 -f 24221//24221 21031//21031 24222//24222 -f 24222//24222 21031//21031 21022//21022 -f 24222//24222 21022//21022 24223//24223 -f 24223//24223 21022//21022 21024//21024 -f 24223//24223 21024//21024 24224//24224 -f 24224//24224 21024//21024 21026//21026 -f 24224//24224 21026//21026 24227//24227 -f 24227//24227 21026//21026 21040//21040 -f 24227//24227 21040//21040 21034//21034 -f 24225//24225 24220//24220 21021//21021 -f 21021//21021 24220//24220 24219//24219 -f 21021//21021 24219//24219 21019//21019 -f 21019//21019 24219//24219 24218//24218 -f 21019//21019 24218//24218 19432//19432 -f 24218//24218 24217//24217 19432//19432 -f 19432//19432 24217//24217 24216//24216 -f 19432//19432 24216//24216 19434//19434 -f 19434//19434 24216//24216 24215//24215 -f 19434//19434 24215//24215 19435//19435 -f 19435//19435 24215//24215 24214//24214 -f 19435//19435 24214//24214 19429//19429 -f 19417//19417 19419//19419 23945//23945 -f 23945//23945 19419//19419 19420//19420 -f 23945//23945 19420//19420 24212//24212 -f 24212//24212 19420//19420 19422//19422 -f 24212//24212 19422//19422 24213//24213 -f 24213//24213 19422//19422 19425//19425 -f 24213//24213 19425//19425 24214//24214 -f 24214//24214 19425//19425 19427//19427 -f 24214//24214 19427//19427 19429//19429 -f 20940//20940 20938//20938 24387//24387 -f 22572//22572 22571//22571 22847//22847 -f 22847//22847 22571//22571 22548//22548 -f 22847//22847 22548//22548 22848//22848 -f 22848//22848 22548//22548 22526//22526 -f 22624//22624 22623//22623 22865//22865 -f 22865//22865 22623//22623 22519//22519 -f 22865//22865 22519//22519 22866//22866 -f 22866//22866 22519//22519 22518//22518 -f 22851//22851 22509//22509 22849//22849 -f 22849//22849 22509//22509 22548//22548 -f 22849//22849 22548//22548 22569//22569 -f 22569//22569 22548//22548 22571//22571 -f 22866//22866 22518//22518 22864//22864 -f 22864//22864 22518//22518 22537//22537 -f 22864//22864 22537//22537 22594//22594 -f 22594//22594 22537//22537 22593//22593 -f 19229//19229 19227//19227 20940//20940 -f 19189//19189 20943//20943 19227//19227 -f 19227//19227 20943//20943 20941//20941 -f 19227//19227 20941//20941 20940//20940 -f 19215//19215 19210//19210 19191//19191 -f 19215//19215 19191//19191 19219//19219 -f 19189//19189 19227//19227 19191//19191 -f 19191//19191 19227//19227 19223//19223 -f 19191//19191 19223//19223 19219//19219 -f 19210//19210 19205//19205 19191//19191 -f 19191//19191 19205//19205 19201//19201 -f 19191//19191 19201//19201 19195//19195 -f 19229//19229 20940//20940 19230//19230 -f 19230//19230 20940//20940 22919//22919 -f 19230//19230 22919//22919 22892//22892 -f 22892//22892 22919//22919 22915//22915 -f 22892//22892 22915//22915 22911//22911 -f 22899//22899 22895//22895 22903//22903 -f 22903//22903 22895//22895 22892//22892 -f 22903//22903 22892//22892 22907//22907 -f 22907//22907 22892//22892 22911//22911 -f 22568//22568 22570//22570 22850//22850 -f 22850//22850 22570//22570 22534//22534 -f 22850//22850 22534//22534 22851//22851 -f 22851//22851 22534//22534 22509//22509 -f 22598//22598 22593//22593 22862//22862 -f 22862//22862 22593//22593 22537//22537 -f 22862//22862 22537//22537 22863//22863 -f 22863//22863 22537//22537 22536//22536 -f 22854//22854 22503//22503 22852//22852 -f 22852//22852 22503//22503 22534//22534 -f 22852//22852 22534//22534 22603//22603 -f 22603//22603 22534//22534 22570//22570 -f 22863//22863 22536//22536 22861//22861 -f 22861//22861 22536//22536 22535//22535 -f 22861//22861 22535//22535 22597//22597 -f 22597//22597 22535//22535 22596//22596 -f 22602//22602 22557//22557 22853//22853 -f 22853//22853 22557//22557 22504//22504 -f 22853//22853 22504//22504 22854//22854 -f 22854//22854 22504//22504 22503//22503 -f 22599//22599 22596//22596 22859//22859 -f 22859//22859 22596//22596 22535//22535 -f 22859//22859 22535//22535 22860//22860 -f 22860//22860 22535//22535 22517//22517 -f 22857//22857 22505//22505 22855//22855 -f 22855//22855 22505//22505 22504//22504 -f 22855//22855 22504//22504 22563//22563 -f 22563//22563 22504//22504 22557//22557 -f 22860//22860 22517//22517 22858//22858 -f 22858//22858 22517//22517 22516//22516 -f 22858//22858 22516//22516 22600//22600 -f 22600//22600 22516//22516 22601//22601 -f 22564//22564 22601//22601 22856//22856 -f 22856//22856 22601//22601 22516//22516 -f 22856//22856 22516//22516 22857//22857 -f 22857//22857 22516//22516 22505//22505 -f 19141//19141 22460//22460 19139//19139 -f 19139//19139 22460//22460 22462//22462 -f 19147//19147 19149//19149 22452//22452 -f 19147//19147 22452//22452 19145//19145 -f 19145//19145 22452//22452 22454//22454 -f 19145//19145 22454//22454 22456//22456 -f 19141//19141 19143//19143 22460//22460 -f 22460//22460 19143//19143 19145//19145 -f 22460//22460 19145//19145 22458//22458 -f 22458//22458 19145//19145 22456//22456 -f 22466//22466 19127//19127 19129//19129 -f 22468//22468 19122//19122 22466//22466 -f 22466//22466 19122//19122 19125//19125 -f 22466//22466 19125//19125 19127//19127 -f 22468//22468 22470//22470 19122//19122 -f 19122//19122 22470//22470 22472//22472 -f 19122//19122 22472//22472 22474//22474 -f 19129//19129 19131//19131 22466//22466 -f 22466//22466 19131//19131 19133//19133 -f 22466//22466 19133//19133 19135//19135 -f 22462//22462 22464//22464 19139//19139 -f 19139//19139 22464//22464 22466//22466 -f 19139//19139 22466//22466 19137//19137 -f 19137//19137 22466//22466 19135//19135 -f 19149//19149 19151//19151 22452//22452 -f 22452//22452 19151//19151 19153//19153 -f 22452//22452 19153//19153 19155//19155 -f 19155//19155 22446//22446 22452//22452 -f 22452//22452 22446//22446 22448//22448 -f 22452//22452 22448//22448 22450//22450 -f 24388//24388 24389//24389 24390//24390 -f 24391//24391 24392//24392 24390//24390 -f 24390//24390 24392//24392 24393//24393 -f 24390//24390 24393//24393 24388//24388 -f 24388//24388 24393//24393 24394//24394 -f 24388//24388 24394//24394 24389//24389 -f 24392//24392 24395//24395 24393//24393 -f 24393//24393 24395//24395 24396//24396 -f 24393//24393 24396//24396 24397//24397 -f 24397//24397 24396//24396 24398//24398 -f 24397//24397 24398//24398 24399//24399 -f 24399//24399 24398//24398 24400//24400 -f 24399//24399 24400//24400 24401//24401 -f 24401//24401 24400//24400 24402//24402 -f 24401//24401 24402//24402 24403//24403 -f 24403//24403 24402//24402 24404//24404 -f 24403//24403 24404//24404 24405//24405 -f 24406//24406 24407//24407 24408//24408 -f 24409//24409 24410//24410 24408//24408 -f 24408//24408 24410//24410 24411//24411 -f 24408//24408 24411//24411 24406//24406 -f 24406//24406 24411//24411 24412//24412 -f 24406//24406 24412//24412 24407//24407 -f 24410//24410 24413//24413 24411//24411 -f 24411//24411 24413//24413 24414//24414 -f 24411//24411 24414//24414 24415//24415 -f 24415//24415 24414//24414 24416//24416 -f 24415//24415 24416//24416 24417//24417 -f 24417//24417 24416//24416 24418//24418 -f 24417//24417 24418//24418 24419//24419 -f 24419//24419 24418//24418 24420//24420 -f 24419//24419 24420//24420 24421//24421 -f 24421//24421 24420//24420 24422//24422 -f 24421//24421 24422//24422 24423//24423 -f 24424//24424 24425//24425 24426//24426 -f 24427//24427 24428//24428 24426//24426 -f 24426//24426 24428//24428 24429//24429 -f 24426//24426 24429//24429 24424//24424 -f 24424//24424 24429//24429 24430//24430 -f 24424//24424 24430//24430 24425//24425 -f 24428//24428 24431//24431 24429//24429 -f 24429//24429 24431//24431 24432//24432 -f 24429//24429 24432//24432 24433//24433 -f 24433//24433 24432//24432 24434//24434 -f 24433//24433 24434//24434 24435//24435 -f 24435//24435 24434//24434 24436//24436 -f 24435//24435 24436//24436 24437//24437 -f 24437//24437 24436//24436 24438//24438 -f 24437//24437 24438//24438 24439//24439 -f 24439//24439 24438//24438 24440//24440 -f 24439//24439 24440//24440 24441//24441 -f 24442//24442 24443//24443 24444//24444 -f 24445//24445 24446//24446 24444//24444 -f 24444//24444 24446//24446 24447//24447 -f 24444//24444 24447//24447 24442//24442 -f 24442//24442 24447//24447 24448//24448 -f 24442//24442 24448//24448 24443//24443 -f 24446//24446 24449//24449 24447//24447 -f 24447//24447 24449//24449 24450//24450 -f 24447//24447 24450//24450 24451//24451 -f 24451//24451 24450//24450 24452//24452 -f 24451//24451 24452//24452 24453//24453 -f 24453//24453 24452//24452 24454//24454 -f 24453//24453 24454//24454 24455//24455 -f 24455//24455 24454//24454 24456//24456 -f 24455//24455 24456//24456 24457//24457 -f 24457//24457 24456//24456 24458//24458 -f 24457//24457 24458//24458 24459//24459 -f 24460//24460 24461//24461 24462//24462 -f 24462//24462 24461//24461 24463//24463 -f 24464//24464 24465//24465 24466//24466 -f 24464//24464 24466//24466 24394//24394 -f 24466//24466 24467//24467 24394//24394 -f 24394//24394 24467//24467 24468//24468 -f 24394//24394 24468//24468 24469//24469 -f 24469//24469 24468//24468 24470//24470 -f 24469//24469 24470//24470 24390//24390 -f 24390//24390 24470//24470 24471//24471 -f 24390//24390 24471//24471 24472//24472 -f 24471//24471 24473//24473 24472//24472 -f 24472//24472 24473//24473 24474//24474 -f 24472//24472 24474//24474 24475//24475 -f 24474//24474 24476//24476 24475//24475 -f 24475//24475 24476//24476 24477//24477 -f 24475//24475 24477//24477 24478//24478 -f 24477//24477 24479//24479 24478//24478 -f 24478//24478 24479//24479 24480//24480 -f 24478//24478 24480//24480 24463//24463 -f 24463//24463 24480//24480 24481//24481 -f 24463//24463 24481//24481 24462//24462 -f 24482//24482 24483//24483 24484//24484 -f 24484//24484 24483//24483 24485//24485 -f 24486//24486 24487//24487 24488//24488 -f 24486//24486 24488//24488 24412//24412 -f 24488//24488 24489//24489 24412//24412 -f 24412//24412 24489//24489 24490//24490 -f 24412//24412 24490//24490 24491//24491 -f 24491//24491 24490//24490 24492//24492 -f 24491//24491 24492//24492 24408//24408 -f 24408//24408 24492//24492 24493//24493 -f 24408//24408 24493//24493 24494//24494 -f 24493//24493 24495//24495 24494//24494 -f 24494//24494 24495//24495 24496//24496 -f 24494//24494 24496//24496 24497//24497 -f 24496//24496 24498//24498 24497//24497 -f 24497//24497 24498//24498 24499//24499 -f 24497//24497 24499//24499 24500//24500 -f 24499//24499 24501//24501 24500//24500 -f 24500//24500 24501//24501 24502//24502 -f 24500//24500 24502//24502 24485//24485 -f 24485//24485 24502//24502 24503//24503 -f 24485//24485 24503//24503 24484//24484 -f 24504//24504 24505//24505 24506//24506 -f 24506//24506 24505//24505 24507//24507 -f 24508//24508 24509//24509 24510//24510 -f 24508//24508 24510//24510 24430//24430 -f 24510//24510 24511//24511 24430//24430 -f 24430//24430 24511//24511 24512//24512 -f 24430//24430 24512//24512 24513//24513 -f 24513//24513 24512//24512 24514//24514 -f 24513//24513 24514//24514 24426//24426 -f 24426//24426 24514//24514 24515//24515 -f 24426//24426 24515//24515 24516//24516 -f 24515//24515 24517//24517 24516//24516 -f 24516//24516 24517//24517 24518//24518 -f 24516//24516 24518//24518 24519//24519 -f 24518//24518 24520//24520 24519//24519 -f 24519//24519 24520//24520 24521//24521 -f 24519//24519 24521//24521 24522//24522 -f 24521//24521 24523//24523 24522//24522 -f 24522//24522 24523//24523 24524//24524 -f 24522//24522 24524//24524 24507//24507 -f 24507//24507 24524//24524 24525//24525 -f 24507//24507 24525//24525 24506//24506 -f 24526//24526 24527//24527 24528//24528 -f 24528//24528 24527//24527 24529//24529 -f 24530//24530 24531//24531 24532//24532 -f 24530//24530 24532//24532 24448//24448 -f 24532//24532 24533//24533 24448//24448 -f 24448//24448 24533//24533 24534//24534 -f 24448//24448 24534//24534 24535//24535 -f 24535//24535 24534//24534 24536//24536 -f 24535//24535 24536//24536 24444//24444 -f 24444//24444 24536//24536 24537//24537 -f 24444//24444 24537//24537 24538//24538 -f 24537//24537 24539//24539 24538//24538 -f 24538//24538 24539//24539 24540//24540 -f 24538//24538 24540//24540 24541//24541 -f 24540//24540 24542//24542 24541//24541 -f 24541//24541 24542//24542 24543//24543 -f 24541//24541 24543//24543 24544//24544 -f 24543//24543 24545//24545 24544//24544 -f 24544//24544 24545//24545 24546//24546 -f 24544//24544 24546//24546 24529//24529 -f 24529//24529 24546//24546 24547//24547 -f 24529//24529 24547//24547 24528//24528 -f 24473//24473 24471//24471 24548//24548 -f 24549//24549 24550//24550 24551//24551 -f 24552//24552 24553//24553 24550//24550 -f 24554//24554 24555//24555 24553//24553 -f 24556//24556 24555//24555 24557//24557 -f 24557//24557 24555//24555 24554//24554 -f 24557//24557 24554//24554 24558//24558 -f 24559//24559 24560//24560 24561//24561 -f 24551//24551 24562//24562 24559//24559 -f 24559//24559 24562//24562 24563//24563 -f 24559//24559 24563//24563 24560//24560 -f 24560//24560 24563//24563 24564//24564 -f 24565//24565 24566//24566 24567//24567 -f 24553//24553 24552//24552 24554//24554 -f 24554//24554 24552//24552 24565//24565 -f 24554//24554 24565//24565 24558//24558 -f 24558//24558 24565//24565 24567//24567 -f 24558//24558 24567//24567 24568//24568 -f 24569//24569 24570//24570 24571//24571 -f 24550//24550 24549//24549 24552//24552 -f 24552//24552 24549//24549 24569//24569 -f 24552//24552 24569//24569 24565//24565 -f 24565//24565 24569//24569 24571//24571 -f 24565//24565 24571//24571 24566//24566 -f 24561//24561 24572//24572 24573//24573 -f 24551//24551 24559//24559 24549//24549 -f 24549//24549 24559//24559 24561//24561 -f 24549//24549 24561//24561 24569//24569 -f 24569//24569 24561//24561 24573//24573 -f 24569//24569 24573//24573 24570//24570 -f 24470//24470 24468//24468 24564//24564 -f 24564//24564 24468//24468 24467//24467 -f 24564//24564 24467//24467 24560//24560 -f 24560//24560 24467//24467 24466//24466 -f 24560//24560 24466//24466 24561//24561 -f 24561//24561 24466//24466 24465//24465 -f 24561//24561 24465//24465 24572//24572 -f 24471//24471 24470//24470 24548//24548 -f 24548//24548 24470//24470 24564//24564 -f 24548//24548 24564//24564 24574//24574 -f 24574//24574 24564//24564 24563//24563 -f 24574//24574 24563//24563 24575//24575 -f 24575//24575 24563//24563 24562//24562 -f 24474//24474 24473//24473 24576//24576 -f 24576//24576 24473//24473 24548//24548 -f 24576//24576 24548//24548 24577//24577 -f 24577//24577 24548//24548 24574//24574 -f 24577//24577 24574//24574 24578//24578 -f 24578//24578 24574//24574 24575//24575 -f 24495//24495 24493//24493 24579//24579 -f 24492//24492 24490//24490 24580//24580 -f 24489//24489 24488//24488 24581//24581 -f 24487//24487 24582//24582 24583//24583 -f 24584//24584 24585//24585 24586//24586 -f 24587//24587 24588//24588 24589//24589 -f 24590//24590 24591//24591 24592//24592 -f 24588//24588 24590//24590 24589//24589 -f 24589//24589 24590//24590 24592//24592 -f 24589//24589 24592//24592 24593//24593 -f 24593//24593 24592//24592 24594//24594 -f 24593//24593 24594//24594 24595//24595 -f 24595//24595 24594//24594 24596//24596 -f 24585//24585 24587//24587 24586//24586 -f 24586//24586 24587//24587 24589//24589 -f 24586//24586 24589//24589 24597//24597 -f 24597//24597 24589//24589 24593//24593 -f 24597//24597 24593//24593 24598//24598 -f 24598//24598 24593//24593 24595//24595 -f 24582//24582 24584//24584 24583//24583 -f 24583//24583 24584//24584 24586//24586 -f 24583//24583 24586//24586 24599//24599 -f 24599//24599 24586//24586 24597//24597 -f 24599//24599 24597//24597 24600//24600 -f 24600//24600 24597//24597 24598//24598 -f 24488//24488 24487//24487 24581//24581 -f 24581//24581 24487//24487 24583//24583 -f 24581//24581 24583//24583 24601//24601 -f 24601//24601 24583//24583 24599//24599 -f 24601//24601 24599//24599 24602//24602 -f 24602//24602 24599//24599 24600//24600 -f 24490//24490 24489//24489 24580//24580 -f 24580//24580 24489//24489 24581//24581 -f 24580//24580 24581//24581 24603//24603 -f 24603//24603 24581//24581 24601//24601 -f 24603//24603 24601//24601 24604//24604 -f 24604//24604 24601//24601 24602//24602 -f 24493//24493 24492//24492 24579//24579 -f 24579//24579 24492//24492 24580//24580 -f 24579//24579 24580//24580 24605//24605 -f 24605//24605 24580//24580 24603//24603 -f 24605//24605 24603//24603 24606//24606 -f 24606//24606 24603//24603 24604//24604 -f 24496//24496 24495//24495 24607//24607 -f 24607//24607 24495//24495 24579//24579 -f 24607//24607 24579//24579 24608//24608 -f 24608//24608 24579//24579 24605//24605 -f 24608//24608 24605//24605 24609//24609 -f 24609//24609 24605//24605 24606//24606 -f 24517//24517 24515//24515 24610//24610 -f 24514//24514 24512//24512 24611//24611 -f 24511//24511 24510//24510 24612//24612 -f 24509//24509 24613//24613 24614//24614 -f 24615//24615 24616//24616 24617//24617 -f 24618//24618 24619//24619 24620//24620 -f 24621//24621 24622//24622 24623//24623 -f 24619//24619 24621//24621 24620//24620 -f 24620//24620 24621//24621 24623//24623 -f 24620//24620 24623//24623 24624//24624 -f 24624//24624 24623//24623 24625//24625 -f 24624//24624 24625//24625 24626//24626 -f 24626//24626 24625//24625 24627//24627 -f 24616//24616 24618//24618 24617//24617 -f 24617//24617 24618//24618 24620//24620 -f 24617//24617 24620//24620 24628//24628 -f 24628//24628 24620//24620 24624//24624 -f 24628//24628 24624//24624 24629//24629 -f 24629//24629 24624//24624 24626//24626 -f 24613//24613 24615//24615 24614//24614 -f 24614//24614 24615//24615 24617//24617 -f 24614//24614 24617//24617 24630//24630 -f 24630//24630 24617//24617 24628//24628 -f 24630//24630 24628//24628 24631//24631 -f 24631//24631 24628//24628 24629//24629 -f 24510//24510 24509//24509 24612//24612 -f 24612//24612 24509//24509 24614//24614 -f 24612//24612 24614//24614 24632//24632 -f 24632//24632 24614//24614 24630//24630 -f 24632//24632 24630//24630 24633//24633 -f 24633//24633 24630//24630 24631//24631 -f 24512//24512 24511//24511 24611//24611 -f 24611//24611 24511//24511 24612//24612 -f 24611//24611 24612//24612 24634//24634 -f 24634//24634 24612//24612 24632//24632 -f 24634//24634 24632//24632 24635//24635 -f 24635//24635 24632//24632 24633//24633 -f 24515//24515 24514//24514 24610//24610 -f 24610//24610 24514//24514 24611//24611 -f 24610//24610 24611//24611 24636//24636 -f 24636//24636 24611//24611 24634//24634 -f 24636//24636 24634//24634 24637//24637 -f 24637//24637 24634//24634 24635//24635 -f 24518//24518 24517//24517 24638//24638 -f 24638//24638 24517//24517 24610//24610 -f 24638//24638 24610//24610 24639//24639 -f 24639//24639 24610//24610 24636//24636 -f 24639//24639 24636//24636 24640//24640 -f 24640//24640 24636//24636 24637//24637 -f 24539//24539 24537//24537 24641//24641 -f 24642//24642 24643//24643 24644//24644 -f 24645//24645 24646//24646 24643//24643 -f 24647//24647 24648//24648 24646//24646 -f 24649//24649 24648//24648 24650//24650 -f 24650//24650 24648//24648 24647//24647 -f 24650//24650 24647//24647 24651//24651 -f 24652//24652 24653//24653 24654//24654 -f 24644//24644 24655//24655 24652//24652 -f 24652//24652 24655//24655 24656//24656 -f 24652//24652 24656//24656 24653//24653 -f 24653//24653 24656//24656 24657//24657 -f 24658//24658 24659//24659 24660//24660 -f 24646//24646 24645//24645 24647//24647 -f 24647//24647 24645//24645 24658//24658 -f 24647//24647 24658//24658 24651//24651 -f 24651//24651 24658//24658 24660//24660 -f 24651//24651 24660//24660 24661//24661 -f 24662//24662 24663//24663 24664//24664 -f 24643//24643 24642//24642 24645//24645 -f 24645//24645 24642//24642 24662//24662 -f 24645//24645 24662//24662 24658//24658 -f 24658//24658 24662//24662 24664//24664 -f 24658//24658 24664//24664 24659//24659 -f 24654//24654 24665//24665 24666//24666 -f 24644//24644 24652//24652 24642//24642 -f 24642//24642 24652//24652 24654//24654 -f 24642//24642 24654//24654 24662//24662 -f 24662//24662 24654//24654 24666//24666 -f 24662//24662 24666//24666 24663//24663 -f 24536//24536 24534//24534 24657//24657 -f 24657//24657 24534//24534 24533//24533 -f 24657//24657 24533//24533 24653//24653 -f 24653//24653 24533//24533 24532//24532 -f 24653//24653 24532//24532 24654//24654 -f 24654//24654 24532//24532 24531//24531 -f 24654//24654 24531//24531 24665//24665 -f 24537//24537 24536//24536 24641//24641 -f 24641//24641 24536//24536 24657//24657 -f 24641//24641 24657//24657 24667//24667 -f 24667//24667 24657//24657 24656//24656 -f 24667//24667 24656//24656 24668//24668 -f 24668//24668 24656//24656 24655//24655 -f 24540//24540 24539//24539 24669//24669 -f 24669//24669 24539//24539 24641//24641 -f 24669//24669 24641//24641 24670//24670 -f 24670//24670 24641//24641 24667//24667 -f 24670//24670 24667//24667 24671//24671 -f 24671//24671 24667//24667 24668//24668 -f 24672//24672 24673//24673 24674//24674 -f 24674//24674 24673//24673 24675//24675 -f 24674//24674 24675//24675 24676//24676 -f 24676//24676 24675//24675 24677//24677 -f 24677//24677 24675//24675 24678//24678 -f 24677//24677 24678//24678 24679//24679 -f 24679//24679 24678//24678 24680//24680 -f 24680//24680 24678//24678 24681//24681 -f 24680//24680 24681//24681 24682//24682 -f 24682//24682 24681//24681 24683//24683 -f 24683//24683 24681//24681 24684//24684 -f 24683//24683 24684//24684 24685//24685 -f 24685//24685 24684//24684 24686//24686 -f 24686//24686 24684//24684 24687//24687 -f 24686//24686 24687//24687 24688//24688 -f 24688//24688 24687//24687 24689//24689 -f 24689//24689 24687//24687 24690//24690 -f 24689//24689 24690//24690 24691//24691 -f 24692//24692 24693//24693 24694//24694 -f 24694//24694 24693//24693 24695//24695 -f 24694//24694 24695//24695 24696//24696 -f 24696//24696 24695//24695 24697//24697 -f 24697//24697 24695//24695 24698//24698 -f 24697//24697 24698//24698 24699//24699 -f 24699//24699 24698//24698 24700//24700 -f 24700//24700 24698//24698 24701//24701 -f 24700//24700 24701//24701 24702//24702 -f 24702//24702 24701//24701 24703//24703 -f 24703//24703 24701//24701 24704//24704 -f 24703//24703 24704//24704 24705//24705 -f 24705//24705 24704//24704 24706//24706 -f 24706//24706 24704//24704 24707//24707 -f 24706//24706 24707//24707 24708//24708 -f 24708//24708 24707//24707 24709//24709 -f 24709//24709 24707//24707 24710//24710 -f 24709//24709 24710//24710 24711//24711 -f 24712//24712 24713//24713 24714//24714 -f 24714//24714 24713//24713 24715//24715 -f 24714//24714 24715//24715 24716//24716 -f 24716//24716 24715//24715 24717//24717 -f 24717//24717 24715//24715 24718//24718 -f 24717//24717 24718//24718 24719//24719 -f 24719//24719 24718//24718 24720//24720 -f 24720//24720 24718//24718 24721//24721 -f 24720//24720 24721//24721 24722//24722 -f 24722//24722 24721//24721 24723//24723 -f 24723//24723 24721//24721 24724//24724 -f 24723//24723 24724//24724 24725//24725 -f 24725//24725 24724//24724 24726//24726 -f 24726//24726 24724//24724 24727//24727 -f 24726//24726 24727//24727 24728//24728 -f 24728//24728 24727//24727 24729//24729 -f 24729//24729 24727//24727 24730//24730 -f 24729//24729 24730//24730 24731//24731 -f 24732//24732 24733//24733 24734//24734 -f 24734//24734 24733//24733 24735//24735 -f 24734//24734 24735//24735 24736//24736 -f 24736//24736 24735//24735 24737//24737 -f 24737//24737 24735//24735 24738//24738 -f 24737//24737 24738//24738 24739//24739 -f 24739//24739 24738//24738 24740//24740 -f 24740//24740 24738//24738 24741//24741 -f 24740//24740 24741//24741 24742//24742 -f 24742//24742 24741//24741 24743//24743 -f 24743//24743 24741//24741 24744//24744 -f 24743//24743 24744//24744 24745//24745 -f 24745//24745 24744//24744 24746//24746 -f 24746//24746 24744//24744 24747//24747 -f 24746//24746 24747//24747 24748//24748 -f 24748//24748 24747//24747 24749//24749 -f 24749//24749 24747//24747 24750//24750 -f 24749//24749 24750//24750 24751//24751 -f 24752//24752 24753//24753 24754//24754 -f 24753//24753 24755//24755 24756//24756 -f 24755//24755 24672//24672 24674//24674 -f 24755//24755 24674//24674 24756//24756 -f 24756//24756 24674//24674 24676//24676 -f 24756//24756 24676//24676 24757//24757 -f 24676//24676 24677//24677 24757//24757 -f 24757//24757 24677//24677 24679//24679 -f 24757//24757 24679//24679 24758//24758 -f 24679//24679 24680//24680 24758//24758 -f 24758//24758 24680//24680 24682//24682 -f 24758//24758 24682//24682 24759//24759 -f 24682//24682 24683//24683 24759//24759 -f 24759//24759 24683//24683 24685//24685 -f 24759//24759 24685//24685 24760//24760 -f 24685//24685 24686//24686 24760//24760 -f 24760//24760 24686//24686 24688//24688 -f 24760//24760 24688//24688 24761//24761 -f 24688//24688 24689//24689 24761//24761 -f 24761//24761 24689//24689 24691//24691 -f 24761//24761 24691//24691 24762//24762 -f 24753//24753 24756//24756 24754//24754 -f 24754//24754 24756//24756 24757//24757 -f 24754//24754 24757//24757 24763//24763 -f 24763//24763 24757//24757 24758//24758 -f 24763//24763 24758//24758 24764//24764 -f 24764//24764 24758//24758 24759//24759 -f 24764//24764 24759//24759 24765//24765 -f 24765//24765 24759//24759 24760//24760 -f 24765//24765 24760//24760 24766//24766 -f 24766//24766 24760//24760 24761//24761 -f 24766//24766 24761//24761 24767//24767 -f 24767//24767 24761//24761 24762//24762 -f 24767//24767 24762//24762 24768//24768 -f 24752//24752 24754//24754 24769//24769 -f 24769//24769 24754//24754 24763//24763 -f 24769//24769 24763//24763 24770//24770 -f 24770//24770 24763//24763 24764//24764 -f 24770//24770 24764//24764 24771//24771 -f 24771//24771 24764//24764 24765//24765 -f 24771//24771 24765//24765 24772//24772 -f 24772//24772 24765//24765 24766//24766 -f 24772//24772 24766//24766 24773//24773 -f 24773//24773 24766//24766 24767//24767 -f 24773//24773 24767//24767 24774//24774 -f 24774//24774 24767//24767 24768//24768 -f 24774//24774 24768//24768 24775//24775 -f 24776//24776 24777//24777 24778//24778 -f 24777//24777 24779//24779 24780//24780 -f 24779//24779 24692//24692 24694//24694 -f 24779//24779 24694//24694 24780//24780 -f 24780//24780 24694//24694 24696//24696 -f 24780//24780 24696//24696 24781//24781 -f 24696//24696 24697//24697 24781//24781 -f 24781//24781 24697//24697 24699//24699 -f 24781//24781 24699//24699 24782//24782 -f 24782//24782 24699//24699 24700//24700 -f 24782//24782 24700//24700 24783//24783 -f 24783//24783 24700//24700 24702//24702 -f 24702//24702 24703//24703 24783//24783 -f 24783//24783 24703//24703 24705//24705 -f 24783//24783 24705//24705 24784//24784 -f 24705//24705 24706//24706 24784//24784 -f 24784//24784 24706//24706 24708//24708 -f 24784//24784 24708//24708 24785//24785 -f 24708//24708 24709//24709 24785//24785 -f 24785//24785 24709//24709 24711//24711 -f 24785//24785 24711//24711 24786//24786 -f 24777//24777 24780//24780 24778//24778 -f 24778//24778 24780//24780 24781//24781 -f 24778//24778 24781//24781 24787//24787 -f 24787//24787 24781//24781 24782//24782 -f 24787//24787 24782//24782 24788//24788 -f 24788//24788 24782//24782 24783//24783 -f 24788//24788 24783//24783 24789//24789 -f 24789//24789 24783//24783 24784//24784 -f 24789//24789 24784//24784 24790//24790 -f 24790//24790 24784//24784 24785//24785 -f 24790//24790 24785//24785 24791//24791 -f 24791//24791 24785//24785 24786//24786 -f 24791//24791 24786//24786 24792//24792 -f 24776//24776 24778//24778 24793//24793 -f 24793//24793 24778//24778 24787//24787 -f 24793//24793 24787//24787 24794//24794 -f 24794//24794 24787//24787 24788//24788 -f 24794//24794 24788//24788 24795//24795 -f 24795//24795 24788//24788 24789//24789 -f 24795//24795 24789//24789 24796//24796 -f 24796//24796 24789//24789 24790//24790 -f 24796//24796 24790//24790 24797//24797 -f 24797//24797 24790//24790 24791//24791 -f 24797//24797 24791//24791 24798//24798 -f 24798//24798 24791//24791 24792//24792 -f 24798//24798 24792//24792 24799//24799 -f 24800//24800 24801//24801 24802//24802 -f 24801//24801 24803//24803 24804//24804 -f 24803//24803 24712//24712 24714//24714 -f 24803//24803 24714//24714 24804//24804 -f 24804//24804 24714//24714 24716//24716 -f 24804//24804 24716//24716 24805//24805 -f 24716//24716 24717//24717 24805//24805 -f 24805//24805 24717//24717 24719//24719 -f 24805//24805 24719//24719 24806//24806 -f 24806//24806 24719//24719 24720//24720 -f 24806//24806 24720//24720 24807//24807 -f 24807//24807 24720//24720 24722//24722 -f 24722//24722 24723//24723 24807//24807 -f 24807//24807 24723//24723 24725//24725 -f 24807//24807 24725//24725 24808//24808 -f 24725//24725 24726//24726 24808//24808 -f 24808//24808 24726//24726 24728//24728 -f 24808//24808 24728//24728 24809//24809 -f 24728//24728 24729//24729 24809//24809 -f 24809//24809 24729//24729 24731//24731 -f 24809//24809 24731//24731 24810//24810 -f 24801//24801 24804//24804 24802//24802 -f 24802//24802 24804//24804 24805//24805 -f 24802//24802 24805//24805 24811//24811 -f 24811//24811 24805//24805 24806//24806 -f 24811//24811 24806//24806 24812//24812 -f 24812//24812 24806//24806 24807//24807 -f 24812//24812 24807//24807 24813//24813 -f 24813//24813 24807//24807 24808//24808 -f 24813//24813 24808//24808 24814//24814 -f 24814//24814 24808//24808 24809//24809 -f 24814//24814 24809//24809 24815//24815 -f 24815//24815 24809//24809 24810//24810 -f 24815//24815 24810//24810 24816//24816 -f 24800//24800 24802//24802 24817//24817 -f 24817//24817 24802//24802 24811//24811 -f 24817//24817 24811//24811 24818//24818 -f 24818//24818 24811//24811 24812//24812 -f 24818//24818 24812//24812 24819//24819 -f 24819//24819 24812//24812 24813//24813 -f 24819//24819 24813//24813 24820//24820 -f 24820//24820 24813//24813 24814//24814 -f 24820//24820 24814//24814 24821//24821 -f 24821//24821 24814//24814 24815//24815 -f 24821//24821 24815//24815 24822//24822 -f 24822//24822 24815//24815 24816//24816 -f 24822//24822 24816//24816 24823//24823 -f 24824//24824 24825//24825 24826//24826 -f 24825//24825 24827//24827 24828//24828 -f 24827//24827 24732//24732 24734//24734 -f 24827//24827 24734//24734 24828//24828 -f 24828//24828 24734//24734 24736//24736 -f 24828//24828 24736//24736 24829//24829 -f 24736//24736 24737//24737 24829//24829 -f 24829//24829 24737//24737 24739//24739 -f 24829//24829 24739//24739 24830//24830 -f 24830//24830 24739//24739 24740//24740 -f 24830//24830 24740//24740 24831//24831 -f 24831//24831 24740//24740 24742//24742 -f 24742//24742 24743//24743 24831//24831 -f 24831//24831 24743//24743 24745//24745 -f 24831//24831 24745//24745 24832//24832 -f 24745//24745 24746//24746 24832//24832 -f 24832//24832 24746//24746 24748//24748 -f 24832//24832 24748//24748 24833//24833 -f 24748//24748 24749//24749 24833//24833 -f 24833//24833 24749//24749 24751//24751 -f 24833//24833 24751//24751 24834//24834 -f 24825//24825 24828//24828 24826//24826 -f 24826//24826 24828//24828 24829//24829 -f 24826//24826 24829//24829 24835//24835 -f 24835//24835 24829//24829 24830//24830 -f 24835//24835 24830//24830 24836//24836 -f 24836//24836 24830//24830 24831//24831 -f 24836//24836 24831//24831 24837//24837 -f 24837//24837 24831//24831 24832//24832 -f 24837//24837 24832//24832 24838//24838 -f 24838//24838 24832//24832 24833//24833 -f 24838//24838 24833//24833 24839//24839 -f 24839//24839 24833//24833 24834//24834 -f 24839//24839 24834//24834 24840//24840 -f 24824//24824 24826//24826 24841//24841 -f 24841//24841 24826//24826 24835//24835 -f 24841//24841 24835//24835 24842//24842 -f 24842//24842 24835//24835 24836//24836 -f 24842//24842 24836//24836 24843//24843 -f 24843//24843 24836//24836 24837//24837 -f 24843//24843 24837//24837 24844//24844 -f 24844//24844 24837//24837 24838//24838 -f 24844//24844 24838//24838 24845//24845 -f 24845//24845 24838//24838 24839//24839 -f 24845//24845 24839//24839 24846//24846 -f 24846//24846 24839//24839 24840//24840 -f 24846//24846 24840//24840 24847//24847 -f 24848//24848 24849//24849 24850//24850 -f 24851//24851 24852//24852 24853//24853 -f 24853//24853 24852//24852 24854//24854 -f 24853//24853 24854//24854 24855//24855 -f 24855//24855 24854//24854 24856//24856 -f 24855//24855 24856//24856 24857//24857 -f 24858//24858 24852//24852 24859//24859 -f 24859//24859 24852//24852 24851//24851 -f 24859//24859 24851//24851 24860//24860 -f 24860//24860 24851//24851 24861//24861 -f 24860//24860 24861//24861 24862//24862 -f 24862//24862 24861//24861 24863//24863 -f 24864//24864 24865//24865 24866//24866 -f 24866//24866 24865//24865 24867//24867 -f 24866//24866 24867//24867 24858//24858 -f 24858//24858 24867//24867 24868//24868 -f 24858//24858 24868//24868 24852//24852 -f 24869//24869 24870//24870 24871//24871 -f 24871//24871 24870//24870 24872//24872 -f 24871//24871 24872//24872 24873//24873 -f 24873//24873 24872//24872 24874//24874 -f 24868//24868 24873//24873 24852//24852 -f 24852//24852 24873//24873 24874//24874 -f 24852//24852 24874//24874 24850//24850 -f 24850//24850 24874//24874 24875//24875 -f 24850//24850 24875//24875 24848//24848 -f 24848//24848 24875//24875 24876//24876 -f 24848//24848 24876//24876 24877//24877 -f 24878//24878 24876//24876 24879//24879 -f 24879//24879 24876//24876 24875//24875 -f 24879//24879 24875//24875 24880//24880 -f 24875//24875 24874//24874 24880//24880 -f 24880//24880 24874//24874 24881//24881 -f 24881//24881 24874//24874 24882//24882 -f 24882//24882 24874//24874 24872//24872 -f 24882//24882 24872//24872 24883//24883 -f 24870//24870 24884//24884 24872//24872 -f 24872//24872 24884//24884 24885//24885 -f 24872//24872 24885//24885 24883//24883 -f 24870//24870 24869//24869 24884//24884 -f 24884//24884 24869//24869 24886//24886 -f 24886//24886 24869//24869 24887//24887 -f 24887//24887 24869//24869 24871//24871 -f 24887//24887 24871//24871 24888//24888 -f 24888//24888 24871//24871 24889//24889 -f 24889//24889 24871//24871 24873//24873 -f 24889//24889 24873//24873 24890//24890 -f 24873//24873 24868//24868 24890//24890 -f 24890//24890 24868//24868 24891//24891 -f 24891//24891 24868//24868 24892//24892 -f 24892//24892 24868//24868 24867//24867 -f 24892//24892 24867//24867 24893//24893 -f 24865//24865 24894//24894 24867//24867 -f 24867//24867 24894//24894 24895//24895 -f 24867//24867 24895//24895 24893//24893 -f 24865//24865 24864//24864 24894//24894 -f 24894//24894 24864//24864 24896//24896 -f 24896//24896 24864//24864 24897//24897 -f 24897//24897 24864//24864 24866//24866 -f 24897//24897 24866//24866 24898//24898 -f 24898//24898 24866//24866 24899//24899 -f 24899//24899 24866//24866 24858//24858 -f 24899//24899 24858//24858 24900//24900 -f 24858//24858 24859//24859 24900//24900 -f 24900//24900 24859//24859 24901//24901 -f 24901//24901 24859//24859 24902//24902 -f 24902//24902 24859//24859 24860//24860 -f 24902//24902 24860//24860 24903//24903 -f 24862//24862 24904//24904 24860//24860 -f 24860//24860 24904//24904 24905//24905 -f 24860//24860 24905//24905 24903//24903 -f 24862//24862 24863//24863 24904//24904 -f 24904//24904 24863//24863 24906//24906 -f 24906//24906 24863//24863 24907//24907 -f 24907//24907 24863//24863 24861//24861 -f 24907//24907 24861//24861 24908//24908 -f 24908//24908 24861//24861 24909//24909 -f 24909//24909 24861//24861 24851//24851 -f 24909//24909 24851//24851 24910//24910 -f 24851//24851 24853//24853 24910//24910 -f 24910//24910 24853//24853 24911//24911 -f 24911//24911 24853//24853 24912//24912 -f 24912//24912 24853//24853 24855//24855 -f 24912//24912 24855//24855 24913//24913 -f 24857//24857 24914//24914 24855//24855 -f 24855//24855 24914//24914 24915//24915 -f 24855//24855 24915//24915 24913//24913 -f 24857//24857 24856//24856 24914//24914 -f 24914//24914 24856//24856 24916//24916 -f 24917//24917 24918//24918 24916//24916 -f 24919//24919 24920//24920 24921//24921 -f 24921//24921 24920//24920 24922//24922 -f 24921//24921 24922//24922 24854//24854 -f 24922//24922 24923//24923 24854//24854 -f 24854//24854 24923//24923 24917//24917 -f 24854//24854 24917//24917 24856//24856 -f 24856//24856 24917//24917 24916//24916 -f 24924//24924 24921//24921 24925//24925 -f 24925//24925 24921//24921 24854//24854 -f 24926//24926 24927//24927 24928//24928 -f 24928//24928 24927//24927 24929//24929 -f 24929//24929 24930//24930 24928//24928 -f 24928//24928 24930//24930 24931//24931 -f 24928//24928 24931//24931 24852//24852 -f 24852//24852 24931//24931 24932//24932 -f 24852//24852 24932//24932 24854//24854 -f 24854//24854 24932//24932 24933//24933 -f 24854//24854 24933//24933 24925//24925 -f 24934//24934 24928//24928 24850//24850 -f 24850//24850 24928//24928 24852//24852 -f 24935//24935 24926//24926 24928//24928 -f 24936//24936 24935//24935 24937//24937 -f 24937//24937 24935//24935 24928//24928 -f 24937//24937 24928//24928 24938//24938 -f 24938//24938 24928//24928 24934//24934 -f 24938//24938 24934//24934 24939//24939 -f 24940//24940 24941//24941 24848//24848 -f 24848//24848 24941//24941 24939//24939 -f 24848//24848 24939//24939 24849//24849 -f 24849//24849 24939//24939 24934//24934 -f 24942//24942 24940//24940 24877//24877 -f 24877//24877 24940//24940 24848//24848 -f 24942//24942 24877//24877 24943//24943 -f 24943//24943 24877//24877 24876//24876 -f 24943//24943 24876//24876 24878//24878 -f 24882//24882 24879//24879 24881//24881 -f 24881//24881 24879//24879 24880//24880 -f 24884//24884 24886//24886 24885//24885 -f 24885//24885 24886//24886 24887//24887 -f 24892//24892 24889//24889 24891//24891 -f 24891//24891 24889//24889 24890//24890 -f 24894//24894 24896//24896 24895//24895 -f 24895//24895 24896//24896 24897//24897 -f 24902//24902 24899//24899 24901//24901 -f 24901//24901 24899//24899 24900//24900 -f 24904//24904 24906//24906 24905//24905 -f 24905//24905 24906//24906 24907//24907 -f 24912//24912 24909//24909 24911//24911 -f 24911//24911 24909//24909 24910//24910 -f 24914//24914 24916//24916 24915//24915 -f 24915//24915 24916//24916 24918//24918 -f 24922//24922 24944//24944 24923//24923 -f 24923//24923 24944//24944 24945//24945 -f 24923//24923 24945//24945 24946//24946 -f 24922//24922 24920//24920 24944//24944 -f 24944//24944 24920//24920 24947//24947 -f 24920//24920 24919//24919 24947//24947 -f 24947//24947 24919//24919 24948//24948 -f 24921//24921 24924//24924 24919//24919 -f 24919//24919 24924//24924 24948//24948 -f 24933//24933 24932//24932 24949//24949 -f 24950//24950 24949//24949 24932//24932 -f 24951//24951 24931//24931 24952//24952 -f 24952//24952 24931//24931 24953//24953 -f 24951//24951 24954//24954 24931//24931 -f 24931//24931 24954//24954 24955//24955 -f 24931//24931 24955//24955 24932//24932 -f 24932//24932 24955//24955 24956//24956 -f 24932//24932 24956//24956 24950//24950 -f 24931//24931 24930//24930 24953//24953 -f 24926//24926 24935//24935 24927//24927 -f 24927//24927 24935//24935 24957//24957 -f 24934//24934 24850//24850 24849//24849 -f 24958//24958 24937//24937 24959//24959 -f 24959//24959 24937//24937 24938//24938 -f 24959//24959 24938//24938 24960//24960 -f 24936//24936 24961//24961 24935//24935 -f 24935//24935 24961//24961 24957//24957 -f 24937//24937 24958//24958 24936//24936 -f 24936//24936 24958//24958 24961//24961 -f 24943//24943 24941//24941 24942//24942 -f 24942//24942 24941//24941 24940//24940 -f 24915//24915 24918//24918 24913//24913 -f 24913//24913 24918//24918 24917//24917 -f 24913//24913 24917//24917 24912//24912 -f 24944//24944 24947//24947 24948//24948 -f 24962//24962 24945//24945 24925//24925 -f 24925//24925 24945//24945 24944//24944 -f 24925//24925 24944//24944 24924//24924 -f 24924//24924 24944//24944 24948//24948 -f 24963//24963 24964//24964 24965//24965 -f 24965//24965 24964//24964 24946//24946 -f 24965//24965 24946//24946 24966//24966 -f 24966//24966 24946//24946 24945//24945 -f 24955//24955 24954//24954 24967//24967 -f 24950//24950 24956//24956 24968//24968 -f 24951//24951 24952//24952 24969//24969 -f 24970//24970 24959//24959 24971//24971 -f 24971//24971 24959//24959 24960//24960 -f 24971//24971 24960//24960 24972//24972 -f 24972//24972 24960//24960 24973//24973 -f 24958//24958 24959//24959 24974//24974 -f 24957//24957 24961//24961 24927//24927 -f 24927//24927 24961//24961 24958//24958 -f 24927//24927 24958//24958 24929//24929 -f 24929//24929 24958//24958 24974//24974 -f 24879//24879 24939//24939 24878//24878 -f 24878//24878 24939//24939 24941//24941 -f 24878//24878 24941//24941 24943//24943 -f 24917//24917 24923//24923 24398//24398 -f 24452//24452 24946//24946 24454//24454 -f 24454//24454 24946//24946 24964//24964 -f 24454//24454 24964//24964 24456//24456 -f 24436//24436 24434//24434 24964//24964 -f 24398//24398 24923//24923 24400//24400 -f 24400//24400 24923//24923 24946//24946 -f 24400//24400 24946//24946 24402//24402 -f 24975//24975 24452//24452 24976//24976 -f 24976//24976 24452//24452 24450//24450 -f 24976//24976 24450//24450 24977//24977 -f 24977//24977 24450//24450 24978//24978 -f 24979//24979 24416//24416 24414//24414 -f 24416//24416 24979//24979 24418//24418 -f 24418//24418 24979//24979 24980//24980 -f 24418//24418 24980//24980 24420//24420 -f 24975//24975 24981//24981 24452//24452 -f 24452//24452 24981//24981 24982//24982 -f 24452//24452 24982//24982 24946//24946 -f 24946//24946 24982//24982 24404//24404 -f 24946//24946 24404//24404 24402//24402 -f 24398//24398 24396//24396 24917//24917 -f 24917//24917 24396//24396 24395//24395 -f 24917//24917 24395//24395 24912//24912 -f 24912//24912 24395//24395 24392//24392 -f 24912//24912 24392//24392 24391//24391 -f 24983//24983 24434//24434 24984//24984 -f 24984//24984 24434//24434 24432//24432 -f 24984//24984 24432//24432 24985//24985 -f 24985//24985 24432//24432 24986//24986 -f 24938//24938 24939//24939 24960//24960 -f 24960//24960 24939//24939 24879//24879 -f 24960//24960 24879//24879 24987//24987 -f 24983//24983 24988//24988 24434//24434 -f 24434//24434 24988//24988 24989//24989 -f 24434//24434 24989//24989 24964//24964 -f 24964//24964 24989//24989 24458//24458 -f 24964//24964 24458//24458 24456//24456 -f 24882//24882 24409//24409 24879//24879 -f 24879//24879 24409//24409 24990//24990 -f 24879//24879 24990//24990 24987//24987 -f 24987//24987 24991//24991 24960//24960 -f 24960//24960 24991//24991 24992//24992 -f 24960//24960 24992//24992 24973//24973 -f 24427//24427 24979//24979 24892//24892 -f 24892//24892 24979//24979 24414//24414 -f 24892//24892 24414//24414 24889//24889 -f 24889//24889 24414//24414 24413//24413 -f 24889//24889 24413//24413 24882//24882 -f 24882//24882 24413//24413 24410//24410 -f 24882//24882 24410//24410 24409//24409 -f 24992//24992 24993//24993 24973//24973 -f 24973//24973 24993//24993 24994//24994 -f 24973//24973 24994//24994 24422//24422 -f 24973//24973 24440//24440 24964//24964 -f 24964//24964 24440//24440 24438//24438 -f 24964//24964 24438//24438 24436//24436 -f 24391//24391 24978//24978 24912//24912 -f 24912//24912 24978//24978 24450//24450 -f 24912//24912 24450//24450 24909//24909 -f 24909//24909 24450//24450 24449//24449 -f 24909//24909 24449//24449 24902//24902 -f 24902//24902 24449//24449 24446//24446 -f 24902//24902 24446//24446 24445//24445 -f 24445//24445 24986//24986 24902//24902 -f 24902//24902 24986//24986 24432//24432 -f 24902//24902 24432//24432 24899//24899 -f 24899//24899 24432//24432 24431//24431 -f 24899//24899 24431//24431 24892//24892 -f 24892//24892 24431//24431 24428//24428 -f 24892//24892 24428//24428 24427//24427 -f 24980//24980 24995//24995 24420//24420 -f 24420//24420 24995//24995 24996//24996 -f 24420//24420 24996//24996 24422//24422 -f 24422//24422 24996//24996 24997//24997 -f 24422//24422 24997//24997 24973//24973 -f 24973//24973 24997//24997 24998//24998 -f 24973//24973 24998//24998 24440//24440 -f 24999//24999 24962//24962 24949//24949 -f 24949//24949 24962//24962 24925//24925 -f 24949//24949 24925//24925 24933//24933 -f 24974//24974 25000//25000 24929//24929 -f 24929//24929 25000//25000 24953//24953 -f 24929//24929 24953//24953 24930//24930 -f 24964//24964 24963//24963 24973//24973 -f 24973//24973 24963//24963 24972//24972 -f 24889//24889 24882//24882 24888//24888 -f 24888//24888 24882//24882 24883//24883 -f 24888//24888 24883//24883 24887//24887 -f 24887//24887 24883//24883 24885//24885 -f 24895//24895 24897//24897 24893//24893 -f 24893//24893 24897//24897 24898//24898 -f 24893//24893 24898//24898 24892//24892 -f 24892//24892 24898//24898 24899//24899 -f 24909//24909 24902//24902 24908//24908 -f 24908//24908 24902//24902 24903//24903 -f 24908//24908 24903//24903 24907//24907 -f 24907//24907 24903//24903 24905//24905 -f 24950//24950 25001//25001 24949//24949 -f 24949//24949 25001//25001 24999//24999 -f 25002//25002 24952//24952 25000//25000 -f 25000//25000 24952//24952 24953//24953 -f 24965//24965 25003//25003 24963//24963 -f 24963//24963 25003//25003 25004//25004 -f 24963//24963 25004//25004 24972//24972 -f 24972//24972 25004//25004 25005//25005 -f 24972//24972 25005//25005 24971//24971 -f 24971//24971 25005//25005 25006//25006 -f 24950//24950 24968//24968 25001//25001 -f 25001//25001 24968//24968 25007//25007 -f 25002//25002 25008//25008 24952//24952 -f 24952//24952 25008//25008 24969//24969 -f 24460//24460 25009//25009 24461//24461 -f 24461//24461 25009//25009 25010//25010 -f 24465//24465 24464//24464 24572//24572 -f 24572//24572 24464//24464 25011//25011 -f 25009//25009 25012//25012 25010//25010 -f 25010//25010 25012//25012 25013//25013 -f 25010//25010 25013//25013 25014//25014 -f 25013//25013 25015//25015 25014//25014 -f 25014//25014 25015//25015 25016//25016 -f 25014//25014 25016//25016 25017//25017 -f 25016//25016 25018//25018 25017//25017 -f 25017//25017 25018//25018 24568//24568 -f 25017//25017 24568//24568 25019//25019 -f 24568//24568 24567//24567 25019//25019 -f 25019//25019 24567//24567 24566//24566 -f 25019//25019 24566//24566 25020//25020 -f 24566//24566 24571//24571 25020//25020 -f 25020//25020 24571//24571 24570//24570 -f 25020//25020 24570//24570 25011//25011 -f 25011//25011 24570//24570 24573//24573 -f 25011//25011 24573//24573 24572//24572 -f 24482//24482 25021//25021 24483//24483 -f 24483//24483 25021//25021 25022//25022 -f 24487//24487 24486//24486 24582//24582 -f 24582//24582 24486//24486 25023//25023 -f 25021//25021 25024//25024 25022//25022 -f 25022//25022 25024//25024 25025//25025 -f 25022//25022 25025//25025 25026//25026 -f 25025//25025 25027//25027 25026//25026 -f 25026//25026 25027//25027 25028//25028 -f 25026//25026 25028//25028 25029//25029 -f 25028//25028 25030//25030 25029//25029 -f 25029//25029 25030//25030 24591//24591 -f 25029//25029 24591//24591 25031//25031 -f 24591//24591 24590//24590 25031//25031 -f 25031//25031 24590//24590 24588//24588 -f 25031//25031 24588//24588 25032//25032 -f 24588//24588 24587//24587 25032//25032 -f 25032//25032 24587//24587 24585//24585 -f 25032//25032 24585//24585 25023//25023 -f 25023//25023 24585//24585 24584//24584 -f 25023//25023 24584//24584 24582//24582 -f 24504//24504 25033//25033 24505//24505 -f 24505//24505 25033//25033 25034//25034 -f 24509//24509 24508//24508 24613//24613 -f 24613//24613 24508//24508 25035//25035 -f 25033//25033 25036//25036 25034//25034 -f 25034//25034 25036//25036 25037//25037 -f 25034//25034 25037//25037 25038//25038 -f 25037//25037 25039//25039 25038//25038 -f 25038//25038 25039//25039 25040//25040 -f 25038//25038 25040//25040 25041//25041 -f 25040//25040 25042//25042 25041//25041 -f 25041//25041 25042//25042 24622//24622 -f 25041//25041 24622//24622 25043//25043 -f 24622//24622 24621//24621 25043//25043 -f 25043//25043 24621//24621 24619//24619 -f 25043//25043 24619//24619 25044//25044 -f 24619//24619 24618//24618 25044//25044 -f 25044//25044 24618//24618 24616//24616 -f 25044//25044 24616//24616 25035//25035 -f 25035//25035 24616//24616 24615//24615 -f 25035//25035 24615//24615 24613//24613 -f 24526//24526 25045//25045 24527//24527 -f 24527//24527 25045//25045 25046//25046 -f 24531//24531 24530//24530 24665//24665 -f 24665//24665 24530//24530 25047//25047 -f 25045//25045 25048//25048 25046//25046 -f 25046//25046 25048//25048 25049//25049 -f 25046//25046 25049//25049 25050//25050 -f 25049//25049 25051//25051 25050//25050 -f 25050//25050 25051//25051 25052//25052 -f 25050//25050 25052//25052 25053//25053 -f 25052//25052 25054//25054 25053//25053 -f 25053//25053 25054//25054 24661//24661 -f 25053//25053 24661//24661 25055//25055 -f 24661//24661 24660//24660 25055//25055 -f 25055//25055 24660//24660 24659//24659 -f 25055//25055 24659//24659 25056//25056 -f 24659//24659 24664//24664 25056//25056 -f 25056//25056 24664//24664 24663//24663 -f 25056//25056 24663//24663 25047//25047 -f 25047//25047 24663//24663 24666//24666 -f 25047//25047 24666//24666 24665//24665 -f 25004//25004 25057//25057 25005//25005 -f 25005//25005 25057//25057 25058//25058 -f 25059//25059 25007//25007 24956//24956 -f 24956//24956 25007//25007 24968//24968 -f 24951//24951 24969//24969 25060//25060 -f 25060//25060 24969//24969 25008//25008 -f 25018//25018 25016//25016 25061//25061 -f 25015//25015 25013//25013 25062//25062 -f 25012//25012 25009//25009 25063//25063 -f 24460//24460 24462//24462 25064//25064 -f 24481//24481 24480//24480 25065//25065 -f 24479//24479 24477//24477 25066//25066 -f 24476//24476 24474//24474 24576//24576 -f 24477//24477 24476//24476 25066//25066 -f 25066//25066 24476//24476 24576//24576 -f 25066//25066 24576//24576 25067//25067 -f 25067//25067 24576//24576 24577//24577 -f 25067//25067 24577//24577 25068//25068 -f 25068//25068 24577//24577 24578//24578 -f 24480//24480 24479//24479 25065//25065 -f 25065//25065 24479//24479 25066//25066 -f 25065//25065 25066//25066 25069//25069 -f 25069//25069 25066//25066 25067//25067 -f 25069//25069 25067//25067 25070//25070 -f 25070//25070 25067//25067 25068//25068 -f 24462//24462 24481//24481 25064//25064 -f 25064//25064 24481//24481 25065//25065 -f 25064//25064 25065//25065 25071//25071 -f 25071//25071 25065//25065 25069//25069 -f 25071//25071 25069//25069 25072//25072 -f 25072//25072 25069//25069 25070//25070 -f 25009//25009 24460//24460 25063//25063 -f 25063//25063 24460//24460 25064//25064 -f 25063//25063 25064//25064 25073//25073 -f 25073//25073 25064//25064 25071//25071 -f 25073//25073 25071//25071 25074//25074 -f 25074//25074 25071//25071 25072//25072 -f 25013//25013 25012//25012 25062//25062 -f 25062//25062 25012//25012 25063//25063 -f 25062//25062 25063//25063 25075//25075 -f 25075//25075 25063//25063 25073//25073 -f 25075//25075 25073//25073 25076//25076 -f 25076//25076 25073//25073 25074//25074 -f 25016//25016 25015//25015 25061//25061 -f 25061//25061 25015//25015 25062//25062 -f 25061//25061 25062//25062 25077//25077 -f 25077//25077 25062//25062 25075//25075 -f 25077//25077 25075//25075 25078//25078 -f 25078//25078 25075//25075 25076//25076 -f 24568//24568 25018//25018 24558//24558 -f 24558//24558 25018//25018 25061//25061 -f 24558//24558 25061//25061 24557//24557 -f 24557//24557 25061//25061 25077//25077 -f 24557//24557 25077//25077 24556//24556 -f 24556//24556 25077//25077 25078//25078 -f 25030//25030 25028//25028 25079//25079 -f 25080//25080 25081//25081 25082//25082 -f 25083//25083 25084//25084 25081//25081 -f 25085//25085 25086//25086 25084//25084 -f 24609//24609 25086//25086 24608//24608 -f 24608//24608 25086//25086 25085//25085 -f 24608//24608 25085//25085 24607//24607 -f 25087//25087 25088//25088 25089//25089 -f 25082//25082 25090//25090 25087//25087 -f 25087//25087 25090//25090 25091//25091 -f 25087//25087 25091//25091 25088//25088 -f 25088//25088 25091//25091 25092//25092 -f 25093//25093 24499//24499 24498//24498 -f 25084//25084 25083//25083 25085//25085 -f 25085//25085 25083//25083 25093//25093 -f 25085//25085 25093//25093 24607//24607 -f 24607//24607 25093//25093 24498//24498 -f 24607//24607 24498//24498 24496//24496 -f 25094//25094 24502//24502 24501//24501 -f 25081//25081 25080//25080 25083//25083 -f 25083//25083 25080//25080 25094//25094 -f 25083//25083 25094//25094 25093//25093 -f 25093//25093 25094//25094 24501//24501 -f 25093//25093 24501//24501 24499//24499 -f 25089//25089 24484//24484 24503//24503 -f 25082//25082 25087//25087 25080//25080 -f 25080//25080 25087//25087 25089//25089 -f 25080//25080 25089//25089 25094//25094 -f 25094//25094 25089//25089 24503//24503 -f 25094//25094 24503//24503 24502//24502 -f 25027//25027 25025//25025 25092//25092 -f 25092//25092 25025//25025 25024//25024 -f 25092//25092 25024//25024 25088//25088 -f 25088//25088 25024//25024 25021//25021 -f 25088//25088 25021//25021 25089//25089 -f 25089//25089 25021//25021 24482//24482 -f 25089//25089 24482//24482 24484//24484 -f 25028//25028 25027//25027 25079//25079 -f 25079//25079 25027//25027 25092//25092 -f 25079//25079 25092//25092 25095//25095 -f 25095//25095 25092//25092 25091//25091 -f 25095//25095 25091//25091 25096//25096 -f 25096//25096 25091//25091 25090//25090 -f 24591//24591 25030//25030 24592//24592 -f 24592//24592 25030//25030 25079//25079 -f 24592//24592 25079//25079 24594//24594 -f 24594//24594 25079//25079 25095//25095 -f 24594//24594 25095//25095 24596//24596 -f 24596//24596 25095//25095 25096//25096 -f 25042//25042 25040//25040 25097//25097 -f 25098//25098 25099//25099 25100//25100 -f 25101//25101 25102//25102 25099//25099 -f 25103//25103 25104//25104 25102//25102 -f 24640//24640 25104//25104 24639//24639 -f 24639//24639 25104//25104 25103//25103 -f 24639//24639 25103//25103 24638//24638 -f 25105//25105 25106//25106 25107//25107 -f 25100//25100 25108//25108 25105//25105 -f 25105//25105 25108//25108 25109//25109 -f 25105//25105 25109//25109 25106//25106 -f 25106//25106 25109//25109 25110//25110 -f 25111//25111 24521//24521 24520//24520 -f 25102//25102 25101//25101 25103//25103 -f 25103//25103 25101//25101 25111//25111 -f 25103//25103 25111//25111 24638//24638 -f 24638//24638 25111//25111 24520//24520 -f 24638//24638 24520//24520 24518//24518 -f 25112//25112 24524//24524 24523//24523 -f 25099//25099 25098//25098 25101//25101 -f 25101//25101 25098//25098 25112//25112 -f 25101//25101 25112//25112 25111//25111 -f 25111//25111 25112//25112 24523//24523 -f 25111//25111 24523//24523 24521//24521 -f 25107//25107 24506//24506 24525//24525 -f 25100//25100 25105//25105 25098//25098 -f 25098//25098 25105//25105 25107//25107 -f 25098//25098 25107//25107 25112//25112 -f 25112//25112 25107//25107 24525//24525 -f 25112//25112 24525//24525 24524//24524 -f 25039//25039 25037//25037 25110//25110 -f 25110//25110 25037//25037 25036//25036 -f 25110//25110 25036//25036 25106//25106 -f 25106//25106 25036//25036 25033//25033 -f 25106//25106 25033//25033 25107//25107 -f 25107//25107 25033//25033 24504//24504 -f 25107//25107 24504//24504 24506//24506 -f 25040//25040 25039//25039 25097//25097 -f 25097//25097 25039//25039 25110//25110 -f 25097//25097 25110//25110 25113//25113 -f 25113//25113 25110//25110 25109//25109 -f 25113//25113 25109//25109 25114//25114 -f 25114//25114 25109//25109 25108//25108 -f 24622//24622 25042//25042 24623//24623 -f 24623//24623 25042//25042 25097//25097 -f 24623//24623 25097//25097 24625//24625 -f 24625//24625 25097//25097 25113//25113 -f 24625//24625 25113//25113 24627//24627 -f 24627//24627 25113//25113 25114//25114 -f 25054//25054 25052//25052 25115//25115 -f 25051//25051 25049//25049 25116//25116 -f 25048//25048 25045//25045 25117//25117 -f 24526//24526 24528//24528 25118//25118 -f 24547//24547 24546//24546 25119//25119 -f 24545//24545 24543//24543 25120//25120 -f 24542//24542 24540//24540 24669//24669 -f 24543//24543 24542//24542 25120//25120 -f 25120//25120 24542//24542 24669//24669 -f 25120//25120 24669//24669 25121//25121 -f 25121//25121 24669//24669 24670//24670 -f 25121//25121 24670//24670 25122//25122 -f 25122//25122 24670//24670 24671//24671 -f 24546//24546 24545//24545 25119//25119 -f 25119//25119 24545//24545 25120//25120 -f 25119//25119 25120//25120 25123//25123 -f 25123//25123 25120//25120 25121//25121 -f 25123//25123 25121//25121 25124//25124 -f 25124//25124 25121//25121 25122//25122 -f 24528//24528 24547//24547 25118//25118 -f 25118//25118 24547//24547 25119//25119 -f 25118//25118 25119//25119 25125//25125 -f 25125//25125 25119//25119 25123//25123 -f 25125//25125 25123//25123 25126//25126 -f 25126//25126 25123//25123 25124//25124 -f 25045//25045 24526//24526 25117//25117 -f 25117//25117 24526//24526 25118//25118 -f 25117//25117 25118//25118 25127//25127 -f 25127//25127 25118//25118 25125//25125 -f 25127//25127 25125//25125 25128//25128 -f 25128//25128 25125//25125 25126//25126 -f 25049//25049 25048//25048 25116//25116 -f 25116//25116 25048//25048 25117//25117 -f 25116//25116 25117//25117 25129//25129 -f 25129//25129 25117//25117 25127//25127 -f 25129//25129 25127//25127 25130//25130 -f 25130//25130 25127//25127 25128//25128 -f 25052//25052 25051//25051 25115//25115 -f 25115//25115 25051//25051 25116//25116 -f 25115//25115 25116//25116 25131//25131 -f 25131//25131 25116//25116 25129//25129 -f 25131//25131 25129//25129 25132//25132 -f 25132//25132 25129//25129 25130//25130 -f 24661//24661 25054//25054 24651//24651 -f 24651//24651 25054//25054 25115//25115 -f 24651//24651 25115//25115 24650//24650 -f 24650//24650 25115//25115 25131//25131 -f 24650//24650 25131//25131 24649//24649 -f 24649//24649 25131//25131 25132//25132 -f 25133//25133 25006//25006 25134//25134 -f 25134//25134 25006//25006 25005//25005 -f 25134//25134 25005//25005 25058//25058 -f 25135//25135 25134//25134 25136//25136 -f 25136//25136 25134//25134 25058//25058 -f 25136//25136 25058//25058 25137//25137 -f 25137//25137 25058//25058 25057//25057 -f 25137//25137 25057//25057 25138//25138 -f 25138//25138 25057//25057 25139//25139 -f 25003//25003 25140//25140 25004//25004 -f 25004//25004 25140//25140 25139//25139 -f 25004//25004 25139//25139 25057//25057 -f 24955//24955 25141//25141 24956//24956 -f 24956//24956 25141//25141 25059//25059 -f 24951//24951 25060//25060 24954//24954 -f 24954//24954 25060//25060 25142//25142 -f 25068//25068 24578//24578 25078//25078 -f 25078//25078 24578//24578 24556//24556 -f 24556//24556 24578//24578 24575//24575 -f 24556//24556 24575//24575 24562//24562 -f 24555//24555 24556//24556 24553//24553 -f 24553//24553 24556//24556 24562//24562 -f 24553//24553 24562//24562 24550//24550 -f 24550//24550 24562//24562 24551//24551 -f 25072//25072 25070//25070 25074//25074 -f 25074//25074 25070//25070 25068//25068 -f 25074//25074 25068//25068 25076//25076 -f 25076//25076 25068//25068 25078//25078 -f 24602//24602 24600//24600 24598//24598 -f 25082//25082 25081//25081 25084//25084 -f 24598//24598 24595//24595 24596//24596 -f 24602//24602 25090//25090 24604//24604 -f 24604//24604 25090//25090 25082//25082 -f 25084//25084 25086//25086 24609//24609 -f 24602//24602 24598//24598 25090//25090 -f 25090//25090 24598//24598 24596//24596 -f 25090//25090 24596//24596 25096//25096 -f 25082//25082 25084//25084 24604//24604 -f 24604//24604 25084//25084 24609//24609 -f 24604//24604 24609//24609 24606//24606 -f 25104//25104 24640//24640 25108//25108 -f 24637//24637 24635//24635 24627//24627 -f 24637//24637 24627//24627 24640//24640 -f 24640//24640 24627//24627 25114//25114 -f 24640//24640 25114//25114 25108//25108 -f 24626//24626 24627//24627 24629//24629 -f 24629//24629 24627//24627 24635//24635 -f 24629//24629 24635//24635 24631//24631 -f 24631//24631 24635//24635 24633//24633 -f 25100//25100 25099//25099 25108//25108 -f 25108//25108 25099//25099 25102//25102 -f 25108//25108 25102//25102 25104//25104 -f 25122//25122 24671//24671 25132//25132 -f 25132//25132 24671//24671 24649//24649 -f 24649//24649 24671//24671 24668//24668 -f 24649//24649 24668//24668 24655//24655 -f 24648//24648 24649//24649 24646//24646 -f 24646//24646 24649//24649 24655//24655 -f 24646//24646 24655//24655 24643//24643 -f 24643//24643 24655//24655 24644//24644 -f 25126//25126 25124//25124 25128//25128 -f 25128//25128 25124//25124 25122//25122 -f 25128//25128 25122//25122 25130//25130 -f 25130//25130 25122//25122 25132//25132 -f 25135//25135 25143//25143 25134//25134 -f 25134//25134 25143//25143 25133//25133 -f 25133//25133 25143//25143 25006//25006 -f 25006//25006 25143//25143 24970//24970 -f 25006//25006 24970//24970 24971//24971 -f 25137//25137 25144//25144 25136//25136 -f 25136//25136 25144//25144 25145//25145 -f 25138//25138 25139//25139 25146//25146 -f 25146//25146 25139//25139 25140//25140 -f 25146//25146 25140//25140 24966//24966 -f 24966//24966 25140//25140 25003//25003 -f 24966//24966 25003//25003 24965//24965 -f 24955//24955 24967//24967 25141//25141 -f 25141//25141 24967//24967 25147//25147 -f 25142//25142 25147//25147 24954//24954 -f 24954//24954 25147//25147 24967//24967 -f 25148//25148 24970//24970 25145//25145 -f 25145//25145 24970//24970 25143//25143 -f 25145//25145 25143//25143 25136//25136 -f 25136//25136 25143//25143 25135//25135 -f 25148//25148 25145//25145 25149//25149 -f 25149//25149 25145//25145 25144//25144 -f 25137//25137 25138//25138 25144//25144 -f 25144//25144 25138//25138 25146//25146 -f 25144//25144 25146//25146 25149//25149 -f 25149//25149 25146//25146 24966//24966 -f 25150//25150 25151//25151 24974//24974 -f 24974//24974 25151//25151 25152//25152 -f 24974//24974 25152//25152 25000//25000 -f 25008//25008 25002//25002 24710//24710 -f 24710//24710 25002//25002 25000//25000 -f 24710//24710 25000//25000 25153//25153 -f 25153//25153 25000//25000 25152//25152 -f 25147//25147 25142//25142 24730//24730 -f 24730//24730 25142//25142 25060//25060 -f 24730//24730 25060//25060 25154//25154 -f 24999//24999 24690//24690 24687//24687 -f 25007//25007 25059//25059 24750//24750 -f 24750//24750 25059//25059 25141//25141 -f 24750//24750 25141//25141 25155//25155 -f 24999//24999 24687//24687 24962//24962 -f 24690//24690 24999//24999 25156//25156 -f 25156//25156 24999//24999 25001//25001 -f 25156//25156 25001//25001 25157//25157 -f 25157//25157 25001//25001 25007//25007 -f 25157//25157 25007//25007 25158//25158 -f 25158//25158 25007//25007 24750//24750 -f 25158//25158 24750//24750 24747//24747 -f 25154//25154 25060//25060 25159//25159 -f 25159//25159 25060//25060 25008//25008 -f 25159//25159 25008//25008 25160//25160 -f 25160//25160 25008//25008 24710//24710 -f 25160//25160 24710//24710 24707//24707 -f 24747//24747 24744//24744 25158//25158 -f 25158//25158 24744//24744 24741//24741 -f 25158//25158 24741//24741 25161//25161 -f 25161//25161 24741//24741 24738//24738 -f 25161//25161 24738//24738 25162//25162 -f 25162//25162 24738//24738 25149//25149 -f 24687//24687 24684//24684 24962//24962 -f 24962//24962 24684//24684 24681//24681 -f 24962//24962 24681//24681 24945//24945 -f 24945//24945 24681//24681 24678//24678 -f 24945//24945 24678//24678 24966//24966 -f 24966//24966 24678//24678 24675//24675 -f 24966//24966 24675//24675 25149//25149 -f 25149//25149 24675//24675 24673//24673 -f 25149//25149 24673//24673 25162//25162 -f 25155//25155 25141//25141 25163//25163 -f 25163//25163 25141//25141 25147//25147 -f 25163//25163 25147//25147 25164//25164 -f 25164//25164 25147//25147 24730//24730 -f 25164//25164 24730//24730 24727//24727 -f 24698//24698 25165//25165 24701//24701 -f 24701//24701 25165//25165 25160//25160 -f 24701//24701 25160//25160 24704//24704 -f 24704//24704 25160//25160 24707//24707 -f 24727//24727 24724//24724 25164//25164 -f 25164//25164 24724//24724 24721//24721 -f 25164//25164 24721//24721 25166//25166 -f 25166//25166 24721//24721 24718//24718 -f 24718//24718 24715//24715 25149//25149 -f 25149//25149 24715//24715 24713//24713 -f 25149//25149 24713//24713 25148//25148 -f 24738//24738 24735//24735 25149//25149 -f 25149//25149 24735//24735 24733//24733 -f 25149//25149 24733//24733 24718//24718 -f 24718//24718 24733//24733 25167//25167 -f 24718//24718 25167//25167 25166//25166 -f 24698//24698 24695//24695 25165//25165 -f 25165//25165 24695//24695 25148//25148 -f 25165//25165 25148//25148 25168//25168 -f 25168//25168 25148//25148 24713//24713 -f 24695//24695 24693//24693 25148//25148 -f 25148//25148 24693//24693 25169//25169 -f 25148//25148 25169//25169 24970//24970 -f 24970//24970 25169//25169 25150//25150 -f 24970//24970 25150//25150 24959//24959 -f 24959//24959 25150//25150 24974//24974 -f 24691//24691 24690//24690 25170//25170 -f 25170//25170 24690//24690 25156//25156 -f 25170//25170 25156//25156 25171//25171 -f 25171//25171 25156//25156 25172//25172 -f 25172//25172 25156//25156 25157//25157 -f 25172//25172 25157//25157 25173//25173 -f 25173//25173 25157//25157 25174//25174 -f 25174//25174 25157//25157 25158//25158 -f 25174//25174 25158//25158 25175//25175 -f 25175//25175 25158//25158 25176//25176 -f 25176//25176 25158//25158 25161//25161 -f 25176//25176 25161//25161 25177//25177 -f 25177//25177 25161//25161 25178//25178 -f 25178//25178 25161//25161 25162//25162 -f 25178//25178 25162//25162 25179//25179 -f 25179//25179 25162//25162 25180//25180 -f 25180//25180 25162//25162 24673//24673 -f 25180//25180 24673//24673 24672//24672 -f 24711//24711 24710//24710 25181//25181 -f 25181//25181 24710//24710 25153//25153 -f 25181//25181 25153//25153 25182//25182 -f 25182//25182 25153//25153 25183//25183 -f 25183//25183 25153//25153 25152//25152 -f 25183//25183 25152//25152 25184//25184 -f 25184//25184 25152//25152 25185//25185 -f 25185//25185 25152//25152 25151//25151 -f 25185//25185 25151//25151 25186//25186 -f 25186//25186 25151//25151 25187//25187 -f 25187//25187 25151//25151 25150//25150 -f 25187//25187 25150//25150 25188//25188 -f 25188//25188 25150//25150 25189//25189 -f 25189//25189 25150//25150 25169//25169 -f 25189//25189 25169//25169 25190//25190 -f 25190//25190 25169//25169 25191//25191 -f 25191//25191 25169//25169 24693//24693 -f 25191//25191 24693//24693 24692//24692 -f 24731//24731 24730//24730 25192//25192 -f 25192//25192 24730//24730 25154//25154 -f 25192//25192 25154//25154 25193//25193 -f 25193//25193 25154//25154 25194//25194 -f 25194//25194 25154//25154 25159//25159 -f 25194//25194 25159//25159 25195//25195 -f 25195//25195 25159//25159 25196//25196 -f 25196//25196 25159//25159 25160//25160 -f 25196//25196 25160//25160 25197//25197 -f 25197//25197 25160//25160 25198//25198 -f 25198//25198 25160//25160 25165//25165 -f 25198//25198 25165//25165 25199//25199 -f 25199//25199 25165//25165 25200//25200 -f 25200//25200 25165//25165 25168//25168 -f 25200//25200 25168//25168 25201//25201 -f 25201//25201 25168//25168 25202//25202 -f 25202//25202 25168//25168 24713//24713 -f 25202//25202 24713//24713 24712//24712 -f 24751//24751 24750//24750 25203//25203 -f 25203//25203 24750//24750 25155//25155 -f 25203//25203 25155//25155 25204//25204 -f 25204//25204 25155//25155 25205//25205 -f 25205//25205 25155//25155 25163//25163 -f 25205//25205 25163//25163 25206//25206 -f 25206//25206 25163//25163 25207//25207 -f 25207//25207 25163//25163 25164//25164 -f 25207//25207 25164//25164 25208//25208 -f 25208//25208 25164//25164 25209//25209 -f 25209//25209 25164//25164 25166//25166 -f 25209//25209 25166//25166 25210//25210 -f 25210//25210 25166//25166 25211//25211 -f 25211//25211 25166//25166 25167//25167 -f 25211//25211 25167//25167 25212//25212 -f 25212//25212 25167//25167 25213//25213 -f 25213//25213 25167//25167 24733//24733 -f 25213//25213 24733//24733 24732//24732 -f 24775//24775 24768//24768 25214//25214 -f 24768//24768 24762//24762 25215//25215 -f 24762//24762 24691//24691 25170//25170 -f 24762//24762 25170//25170 25215//25215 -f 25215//25215 25170//25170 25171//25171 -f 25215//25215 25171//25171 25216//25216 -f 25171//25171 25172//25172 25216//25216 -f 25216//25216 25172//25172 25173//25173 -f 25216//25216 25173//25173 25217//25217 -f 25217//25217 25173//25173 25174//25174 -f 25217//25217 25174//25174 25218//25218 -f 25218//25218 25174//25174 25175//25175 -f 25175//25175 25176//25176 25218//25218 -f 25218//25218 25176//25176 25177//25177 -f 25218//25218 25177//25177 25219//25219 -f 25177//25177 25178//25178 25219//25219 -f 25219//25219 25178//25178 25179//25179 -f 25219//25219 25179//25179 25220//25220 -f 25179//25179 25180//25180 25220//25220 -f 25220//25220 25180//25180 24672//24672 -f 25220//25220 24672//24672 24755//24755 -f 24768//24768 25215//25215 25214//25214 -f 25214//25214 25215//25215 25216//25216 -f 25214//25214 25216//25216 25221//25221 -f 25221//25221 25216//25216 25217//25217 -f 25221//25221 25217//25217 25222//25222 -f 25222//25222 25217//25217 25218//25218 -f 25222//25222 25218//25218 25223//25223 -f 25223//25223 25218//25218 25219//25219 -f 25223//25223 25219//25219 25224//25224 -f 25224//25224 25219//25219 25220//25220 -f 25224//25224 25220//25220 25225//25225 -f 25225//25225 25220//25220 24755//24755 -f 25225//25225 24755//24755 24753//24753 -f 24775//24775 25214//25214 25226//25226 -f 25226//25226 25214//25214 25221//25221 -f 25226//25226 25221//25221 25227//25227 -f 25227//25227 25221//25221 25222//25222 -f 25227//25227 25222//25222 25228//25228 -f 25228//25228 25222//25222 25223//25223 -f 25228//25228 25223//25223 25229//25229 -f 25229//25229 25223//25223 25224//25224 -f 25229//25229 25224//25224 25230//25230 -f 25230//25230 25224//25224 25225//25225 -f 25230//25230 25225//25225 25231//25231 -f 25231//25231 25225//25225 24753//24753 -f 25231//25231 24753//24753 24752//24752 -f 24799//24799 24792//24792 25232//25232 -f 24792//24792 24786//24786 25233//25233 -f 24786//24786 24711//24711 25181//25181 -f 24786//24786 25181//25181 25233//25233 -f 25233//25233 25181//25181 25182//25182 -f 25233//25233 25182//25182 25234//25234 -f 25182//25182 25183//25183 25234//25234 -f 25234//25234 25183//25183 25184//25184 -f 25234//25234 25184//25184 25235//25235 -f 25235//25235 25184//25184 25185//25185 -f 25235//25235 25185//25185 25236//25236 -f 25236//25236 25185//25185 25186//25186 -f 25186//25186 25187//25187 25236//25236 -f 25236//25236 25187//25187 25188//25188 -f 25236//25236 25188//25188 25237//25237 -f 25188//25188 25189//25189 25237//25237 -f 25237//25237 25189//25189 25190//25190 -f 25237//25237 25190//25190 25238//25238 -f 25190//25190 25191//25191 25238//25238 -f 25238//25238 25191//25191 24692//24692 -f 25238//25238 24692//24692 24779//24779 -f 24792//24792 25233//25233 25232//25232 -f 25232//25232 25233//25233 25234//25234 -f 25232//25232 25234//25234 25239//25239 -f 25239//25239 25234//25234 25235//25235 -f 25239//25239 25235//25235 25240//25240 -f 25240//25240 25235//25235 25236//25236 -f 25240//25240 25236//25236 25241//25241 -f 25241//25241 25236//25236 25237//25237 -f 25241//25241 25237//25237 25242//25242 -f 25242//25242 25237//25237 25238//25238 -f 25242//25242 25238//25238 25243//25243 -f 25243//25243 25238//25238 24779//24779 -f 25243//25243 24779//24779 24777//24777 -f 24799//24799 25232//25232 25244//25244 -f 25244//25244 25232//25232 25239//25239 -f 25244//25244 25239//25239 25245//25245 -f 25245//25245 25239//25239 25240//25240 -f 25245//25245 25240//25240 25246//25246 -f 25246//25246 25240//25240 25241//25241 -f 25246//25246 25241//25241 25247//25247 -f 25247//25247 25241//25241 25242//25242 -f 25247//25247 25242//25242 25248//25248 -f 25248//25248 25242//25242 25243//25243 -f 25248//25248 25243//25243 25249//25249 -f 25249//25249 25243//25243 24777//24777 -f 25249//25249 24777//24777 24776//24776 -f 24823//24823 24816//24816 25250//25250 -f 24816//24816 24810//24810 25251//25251 -f 24810//24810 24731//24731 25192//25192 -f 24810//24810 25192//25192 25251//25251 -f 25251//25251 25192//25192 25193//25193 -f 25251//25251 25193//25193 25252//25252 -f 25193//25193 25194//25194 25252//25252 -f 25252//25252 25194//25194 25195//25195 -f 25252//25252 25195//25195 25253//25253 -f 25195//25195 25196//25196 25253//25253 -f 25253//25253 25196//25196 25197//25197 -f 25253//25253 25197//25197 25254//25254 -f 25197//25197 25198//25198 25254//25254 -f 25254//25254 25198//25198 25199//25199 -f 25254//25254 25199//25199 25255//25255 -f 25199//25199 25200//25200 25255//25255 -f 25255//25255 25200//25200 25201//25201 -f 25255//25255 25201//25201 25256//25256 -f 25201//25201 25202//25202 25256//25256 -f 25256//25256 25202//25202 24712//24712 -f 25256//25256 24712//24712 24803//24803 -f 24816//24816 25251//25251 25250//25250 -f 25250//25250 25251//25251 25252//25252 -f 25250//25250 25252//25252 25257//25257 -f 25257//25257 25252//25252 25253//25253 -f 25257//25257 25253//25253 25258//25258 -f 25258//25258 25253//25253 25254//25254 -f 25258//25258 25254//25254 25259//25259 -f 25259//25259 25254//25254 25255//25255 -f 25259//25259 25255//25255 25260//25260 -f 25260//25260 25255//25255 25256//25256 -f 25260//25260 25256//25256 25261//25261 -f 25261//25261 25256//25256 24803//24803 -f 25261//25261 24803//24803 24801//24801 -f 24823//24823 25250//25250 25262//25262 -f 25262//25262 25250//25250 25257//25257 -f 25262//25262 25257//25257 25263//25263 -f 25263//25263 25257//25257 25258//25258 -f 25263//25263 25258//25258 25264//25264 -f 25264//25264 25258//25258 25259//25259 -f 25264//25264 25259//25259 25265//25265 -f 25265//25265 25259//25259 25260//25260 -f 25265//25265 25260//25260 25266//25266 -f 25266//25266 25260//25260 25261//25261 -f 25266//25266 25261//25261 25267//25267 -f 25267//25267 25261//25261 24801//24801 -f 25267//25267 24801//24801 24800//24800 -f 24847//24847 24840//24840 25268//25268 -f 24840//24840 24834//24834 25269//25269 -f 24834//24834 24751//24751 25203//25203 -f 24834//24834 25203//25203 25269//25269 -f 25269//25269 25203//25203 25204//25204 -f 25269//25269 25204//25204 25270//25270 -f 25204//25204 25205//25205 25270//25270 -f 25270//25270 25205//25205 25206//25206 -f 25270//25270 25206//25206 25271//25271 -f 25271//25271 25206//25206 25207//25207 -f 25271//25271 25207//25207 25272//25272 -f 25272//25272 25207//25207 25208//25208 -f 25208//25208 25209//25209 25272//25272 -f 25272//25272 25209//25209 25210//25210 -f 25272//25272 25210//25210 25273//25273 -f 25210//25210 25211//25211 25273//25273 -f 25273//25273 25211//25211 25212//25212 -f 25273//25273 25212//25212 25274//25274 -f 25212//25212 25213//25213 25274//25274 -f 25274//25274 25213//25213 24732//24732 -f 25274//25274 24732//24732 24827//24827 -f 24840//24840 25269//25269 25268//25268 -f 25268//25268 25269//25269 25270//25270 -f 25268//25268 25270//25270 25275//25275 -f 25275//25275 25270//25270 25271//25271 -f 25275//25275 25271//25271 25276//25276 -f 25276//25276 25271//25271 25272//25272 -f 25276//25276 25272//25272 25277//25277 -f 25277//25277 25272//25272 25273//25273 -f 25277//25277 25273//25273 25278//25278 -f 25278//25278 25273//25273 25274//25274 -f 25278//25278 25274//25274 25279//25279 -f 25279//25279 25274//25274 24827//24827 -f 25279//25279 24827//24827 24825//24825 -f 24847//24847 25268//25268 25280//25280 -f 25280//25280 25268//25268 25275//25275 -f 25280//25280 25275//25275 25281//25281 -f 25281//25281 25275//25275 25276//25276 -f 25281//25281 25276//25276 25282//25282 -f 25282//25282 25276//25276 25277//25277 -f 25282//25282 25277//25277 25283//25283 -f 25283//25283 25277//25277 25278//25278 -f 25283//25283 25278//25278 25284//25284 -f 25284//25284 25278//25278 25279//25279 -f 25284//25284 25279//25279 25285//25285 -f 25285//25285 25279//25279 24825//24825 -f 25285//25285 24825//24825 24824//24824 -f 24752//24752 24769//24769 24774//24774 -f 24752//24752 24774//24774 25231//25231 -f 25231//25231 24774//24774 24775//24775 -f 25231//25231 24775//24775 25226//25226 -f 24772//24772 24773//24773 24771//24771 -f 24771//24771 24773//24773 24774//24774 -f 24771//24771 24774//24774 24770//24770 -f 24770//24770 24774//24774 24769//24769 -f 25229//25229 25230//25230 25228//25228 -f 25228//25228 25230//25230 25231//25231 -f 25228//25228 25231//25231 25227//25227 -f 25227//25227 25231//25231 25226//25226 -f 24776//24776 24793//24793 24798//24798 -f 24776//24776 24798//24798 25249//25249 -f 25249//25249 24798//24798 24799//24799 -f 25249//25249 24799//24799 25244//25244 -f 24796//24796 24797//24797 24795//24795 -f 24795//24795 24797//24797 24798//24798 -f 24795//24795 24798//24798 24794//24794 -f 24794//24794 24798//24798 24793//24793 -f 25247//25247 25248//25248 25246//25246 -f 25246//25246 25248//25248 25249//25249 -f 25246//25246 25249//25249 25245//25245 -f 25245//25245 25249//25249 25244//25244 -f 25267//25267 24800//24800 24817//24817 -f 25267//25267 24817//24817 25262//25262 -f 25262//25262 24817//24817 24822//24822 -f 25262//25262 24822//24822 24823//24823 -f 25265//25265 25266//25266 25264//25264 -f 25264//25264 25266//25266 25267//25267 -f 25264//25264 25267//25267 25263//25263 -f 25263//25263 25267//25267 25262//25262 -f 24820//24820 24821//24821 24819//24819 -f 24819//24819 24821//24821 24822//24822 -f 24819//24819 24822//24822 24818//24818 -f 24818//24818 24822//24822 24817//24817 -f 25285//25285 24824//24824 24841//24841 -f 25285//25285 24841//24841 25280//25280 -f 25280//25280 24841//24841 24846//24846 -f 25280//25280 24846//24846 24847//24847 -f 25283//25283 25284//25284 25282//25282 -f 25282//25282 25284//25284 25285//25285 -f 25282//25282 25285//25285 25281//25281 -f 25281//25281 25285//25285 25280//25280 -f 24844//24844 24845//24845 24843//24843 -f 24843//24843 24845//24845 24846//24846 -f 24843//24843 24846//24846 24842//24842 -f 24842//24842 24846//24846 24841//24841 -f 25286//25286 25287//25287 25288//25288 -f 25289//25289 25290//25290 25288//25288 -f 25288//25288 25290//25290 25291//25291 -f 25288//25288 25291//25291 25286//25286 -f 25286//25286 25291//25291 25292//25292 -f 25286//25286 25292//25292 25287//25287 -f 25290//25290 25293//25293 25291//25291 -f 25291//25291 25293//25293 25294//25294 -f 25291//25291 25294//25294 25295//25295 -f 25295//25295 25294//25294 25296//25296 -f 25295//25295 25296//25296 25297//25297 -f 25297//25297 25296//25296 25298//25298 -f 25297//25297 25298//25298 25299//25299 -f 25299//25299 25298//25298 25300//25300 -f 25299//25299 25300//25300 25301//25301 -f 25301//25301 25300//25300 25302//25302 -f 25301//25301 25302//25302 25303//25303 -f 25304//25304 25305//25305 25306//25306 -f 25307//25307 25308//25308 25306//25306 -f 25306//25306 25308//25308 25309//25309 -f 25306//25306 25309//25309 25304//25304 -f 25304//25304 25309//25309 25310//25310 -f 25304//25304 25310//25310 25305//25305 -f 25308//25308 25311//25311 25309//25309 -f 25309//25309 25311//25311 25312//25312 -f 25309//25309 25312//25312 25313//25313 -f 25313//25313 25312//25312 25314//25314 -f 25313//25313 25314//25314 25315//25315 -f 25315//25315 25314//25314 25316//25316 -f 25315//25315 25316//25316 25317//25317 -f 25317//25317 25316//25316 25318//25318 -f 25317//25317 25318//25318 25319//25319 -f 25319//25319 25318//25318 25320//25320 -f 25319//25319 25320//25320 25321//25321 -f 25322//25322 25323//25323 25324//25324 -f 25325//25325 25326//25326 25324//25324 -f 25324//25324 25326//25326 25327//25327 -f 25324//25324 25327//25327 25322//25322 -f 25322//25322 25327//25327 25328//25328 -f 25322//25322 25328//25328 25323//25323 -f 25326//25326 25329//25329 25327//25327 -f 25327//25327 25329//25329 25330//25330 -f 25327//25327 25330//25330 25331//25331 -f 25331//25331 25330//25330 25332//25332 -f 25331//25331 25332//25332 25333//25333 -f 25333//25333 25332//25332 25334//25334 -f 25333//25333 25334//25334 25335//25335 -f 25335//25335 25334//25334 25336//25336 -f 25335//25335 25336//25336 25337//25337 -f 25337//25337 25336//25336 25338//25338 -f 25337//25337 25338//25338 25339//25339 -f 25340//25340 25341//25341 25342//25342 -f 25343//25343 25344//25344 25342//25342 -f 25342//25342 25344//25344 25345//25345 -f 25342//25342 25345//25345 25340//25340 -f 25340//25340 25345//25345 25346//25346 -f 25340//25340 25346//25346 25341//25341 -f 25344//25344 25347//25347 25345//25345 -f 25345//25345 25347//25347 25348//25348 -f 25345//25345 25348//25348 25349//25349 -f 25349//25349 25348//25348 25350//25350 -f 25349//25349 25350//25350 25351//25351 -f 25351//25351 25350//25350 25352//25352 -f 25351//25351 25352//25352 25353//25353 -f 25353//25353 25352//25352 25354//25354 -f 25353//25353 25354//25354 25355//25355 -f 25355//25355 25354//25354 25356//25356 -f 25355//25355 25356//25356 25357//25357 -f 25358//25358 25359//25359 25360//25360 -f 25360//25360 25359//25359 25361//25361 -f 25362//25362 25363//25363 25364//25364 -f 25362//25362 25364//25364 25292//25292 -f 25364//25364 25365//25365 25292//25292 -f 25292//25292 25365//25365 25366//25366 -f 25292//25292 25366//25366 25367//25367 -f 25367//25367 25366//25366 25368//25368 -f 25367//25367 25368//25368 25288//25288 -f 25288//25288 25368//25368 25369//25369 -f 25288//25288 25369//25369 25370//25370 -f 25369//25369 25371//25371 25370//25370 -f 25370//25370 25371//25371 25372//25372 -f 25370//25370 25372//25372 25373//25373 -f 25372//25372 25374//25374 25373//25373 -f 25373//25373 25374//25374 25375//25375 -f 25373//25373 25375//25375 25376//25376 -f 25375//25375 25377//25377 25376//25376 -f 25376//25376 25377//25377 25378//25378 -f 25376//25376 25378//25378 25361//25361 -f 25361//25361 25378//25378 25379//25379 -f 25361//25361 25379//25379 25360//25360 -f 25380//25380 25381//25381 25382//25382 -f 25382//25382 25381//25381 25383//25383 -f 25384//25384 25385//25385 25386//25386 -f 25384//25384 25386//25386 25310//25310 -f 25386//25386 25387//25387 25310//25310 -f 25310//25310 25387//25387 25388//25388 -f 25310//25310 25388//25388 25389//25389 -f 25389//25389 25388//25388 25390//25390 -f 25389//25389 25390//25390 25306//25306 -f 25306//25306 25390//25390 25391//25391 -f 25306//25306 25391//25391 25392//25392 -f 25391//25391 25393//25393 25392//25392 -f 25392//25392 25393//25393 25394//25394 -f 25392//25392 25394//25394 25395//25395 -f 25394//25394 25396//25396 25395//25395 -f 25395//25395 25396//25396 25397//25397 -f 25395//25395 25397//25397 25398//25398 -f 25397//25397 25399//25399 25398//25398 -f 25398//25398 25399//25399 25400//25400 -f 25398//25398 25400//25400 25383//25383 -f 25383//25383 25400//25400 25401//25401 -f 25383//25383 25401//25401 25382//25382 -f 25402//25402 25403//25403 25404//25404 -f 25404//25404 25403//25403 25405//25405 -f 25406//25406 25407//25407 25408//25408 -f 25406//25406 25408//25408 25328//25328 -f 25408//25408 25409//25409 25328//25328 -f 25328//25328 25409//25409 25410//25410 -f 25328//25328 25410//25410 25411//25411 -f 25411//25411 25410//25410 25412//25412 -f 25411//25411 25412//25412 25324//25324 -f 25324//25324 25412//25412 25413//25413 -f 25324//25324 25413//25413 25414//25414 -f 25413//25413 25415//25415 25414//25414 -f 25414//25414 25415//25415 25416//25416 -f 25414//25414 25416//25416 25417//25417 -f 25416//25416 25418//25418 25417//25417 -f 25417//25417 25418//25418 25419//25419 -f 25417//25417 25419//25419 25420//25420 -f 25419//25419 25421//25421 25420//25420 -f 25420//25420 25421//25421 25422//25422 -f 25420//25420 25422//25422 25405//25405 -f 25405//25405 25422//25422 25423//25423 -f 25405//25405 25423//25423 25404//25404 -f 25424//25424 25425//25425 25426//25426 -f 25426//25426 25425//25425 25427//25427 -f 25428//25428 25429//25429 25430//25430 -f 25428//25428 25430//25430 25346//25346 -f 25430//25430 25431//25431 25346//25346 -f 25346//25346 25431//25431 25432//25432 -f 25346//25346 25432//25432 25433//25433 -f 25433//25433 25432//25432 25434//25434 -f 25433//25433 25434//25434 25342//25342 -f 25342//25342 25434//25434 25435//25435 -f 25342//25342 25435//25435 25436//25436 -f 25435//25435 25437//25437 25436//25436 -f 25436//25436 25437//25437 25438//25438 -f 25436//25436 25438//25438 25439//25439 -f 25438//25438 25440//25440 25439//25439 -f 25439//25439 25440//25440 25441//25441 -f 25439//25439 25441//25441 25442//25442 -f 25441//25441 25443//25443 25442//25442 -f 25442//25442 25443//25443 25444//25444 -f 25442//25442 25444//25444 25427//25427 -f 25427//25427 25444//25444 25445//25445 -f 25427//25427 25445//25445 25426//25426 -f 25371//25371 25369//25369 25446//25446 -f 25368//25368 25366//25366 25447//25447 -f 25365//25365 25364//25364 25448//25448 -f 25363//25363 25449//25449 25450//25450 -f 25451//25451 25452//25452 25453//25453 -f 25454//25454 25455//25455 25456//25456 -f 25457//25457 25458//25458 25459//25459 -f 25455//25455 25457//25457 25456//25456 -f 25456//25456 25457//25457 25459//25459 -f 25456//25456 25459//25459 25460//25460 -f 25460//25460 25459//25459 25461//25461 -f 25460//25460 25461//25461 25462//25462 -f 25462//25462 25461//25461 25463//25463 -f 25452//25452 25454//25454 25453//25453 -f 25453//25453 25454//25454 25456//25456 -f 25453//25453 25456//25456 25464//25464 -f 25464//25464 25456//25456 25460//25460 -f 25464//25464 25460//25460 25465//25465 -f 25465//25465 25460//25460 25462//25462 -f 25449//25449 25451//25451 25450//25450 -f 25450//25450 25451//25451 25453//25453 -f 25450//25450 25453//25453 25466//25466 -f 25466//25466 25453//25453 25464//25464 -f 25466//25466 25464//25464 25467//25467 -f 25467//25467 25464//25464 25465//25465 -f 25364//25364 25363//25363 25448//25448 -f 25448//25448 25363//25363 25450//25450 -f 25448//25448 25450//25450 25468//25468 -f 25468//25468 25450//25450 25466//25466 -f 25468//25468 25466//25466 25469//25469 -f 25469//25469 25466//25466 25467//25467 -f 25366//25366 25365//25365 25447//25447 -f 25447//25447 25365//25365 25448//25448 -f 25447//25447 25448//25448 25470//25470 -f 25470//25470 25448//25448 25468//25468 -f 25470//25470 25468//25468 25471//25471 -f 25471//25471 25468//25468 25469//25469 -f 25369//25369 25368//25368 25446//25446 -f 25446//25446 25368//25368 25447//25447 -f 25446//25446 25447//25447 25472//25472 -f 25472//25472 25447//25447 25470//25470 -f 25472//25472 25470//25470 25473//25473 -f 25473//25473 25470//25470 25471//25471 -f 25372//25372 25371//25371 25474//25474 -f 25474//25474 25371//25371 25446//25446 -f 25474//25474 25446//25446 25475//25475 -f 25475//25475 25446//25446 25472//25472 -f 25475//25475 25472//25472 25476//25476 -f 25476//25476 25472//25472 25473//25473 -f 25393//25393 25391//25391 25477//25477 -f 25478//25478 25479//25479 25480//25480 -f 25481//25481 25482//25482 25479//25479 -f 25483//25483 25484//25484 25482//25482 -f 25485//25485 25484//25484 25486//25486 -f 25486//25486 25484//25484 25483//25483 -f 25486//25486 25483//25483 25487//25487 -f 25488//25488 25489//25489 25490//25490 -f 25480//25480 25491//25491 25488//25488 -f 25488//25488 25491//25491 25492//25492 -f 25488//25488 25492//25492 25489//25489 -f 25489//25489 25492//25492 25493//25493 -f 25494//25494 25495//25495 25496//25496 -f 25482//25482 25481//25481 25483//25483 -f 25483//25483 25481//25481 25494//25494 -f 25483//25483 25494//25494 25487//25487 -f 25487//25487 25494//25494 25496//25496 -f 25487//25487 25496//25496 25497//25497 -f 25498//25498 25499//25499 25500//25500 -f 25479//25479 25478//25478 25481//25481 -f 25481//25481 25478//25478 25498//25498 -f 25481//25481 25498//25498 25494//25494 -f 25494//25494 25498//25498 25500//25500 -f 25494//25494 25500//25500 25495//25495 -f 25490//25490 25501//25501 25502//25502 -f 25480//25480 25488//25488 25478//25478 -f 25478//25478 25488//25488 25490//25490 -f 25478//25478 25490//25490 25498//25498 -f 25498//25498 25490//25490 25502//25502 -f 25498//25498 25502//25502 25499//25499 -f 25390//25390 25388//25388 25493//25493 -f 25493//25493 25388//25388 25387//25387 -f 25493//25493 25387//25387 25489//25489 -f 25489//25489 25387//25387 25386//25386 -f 25489//25489 25386//25386 25490//25490 -f 25490//25490 25386//25386 25385//25385 -f 25490//25490 25385//25385 25501//25501 -f 25391//25391 25390//25390 25477//25477 -f 25477//25477 25390//25390 25493//25493 -f 25477//25477 25493//25493 25503//25503 -f 25503//25503 25493//25493 25492//25492 -f 25503//25503 25492//25492 25504//25504 -f 25504//25504 25492//25492 25491//25491 -f 25394//25394 25393//25393 25505//25505 -f 25505//25505 25393//25393 25477//25477 -f 25505//25505 25477//25477 25506//25506 -f 25506//25506 25477//25477 25503//25503 -f 25506//25506 25503//25503 25507//25507 -f 25507//25507 25503//25503 25504//25504 -f 25415//25415 25413//25413 25508//25508 -f 25509//25509 25510//25510 25511//25511 -f 25512//25512 25513//25513 25510//25510 -f 25514//25514 25515//25515 25513//25513 -f 25516//25516 25515//25515 25517//25517 -f 25517//25517 25515//25515 25514//25514 -f 25517//25517 25514//25514 25518//25518 -f 25519//25519 25520//25520 25521//25521 -f 25511//25511 25522//25522 25519//25519 -f 25519//25519 25522//25522 25523//25523 -f 25519//25519 25523//25523 25520//25520 -f 25520//25520 25523//25523 25524//25524 -f 25525//25525 25526//25526 25527//25527 -f 25513//25513 25512//25512 25514//25514 -f 25514//25514 25512//25512 25525//25525 -f 25514//25514 25525//25525 25518//25518 -f 25518//25518 25525//25525 25527//25527 -f 25518//25518 25527//25527 25528//25528 -f 25529//25529 25530//25530 25531//25531 -f 25510//25510 25509//25509 25512//25512 -f 25512//25512 25509//25509 25529//25529 -f 25512//25512 25529//25529 25525//25525 -f 25525//25525 25529//25529 25531//25531 -f 25525//25525 25531//25531 25526//25526 -f 25521//25521 25532//25532 25533//25533 -f 25511//25511 25519//25519 25509//25509 -f 25509//25509 25519//25519 25521//25521 -f 25509//25509 25521//25521 25529//25529 -f 25529//25529 25521//25521 25533//25533 -f 25529//25529 25533//25533 25530//25530 -f 25412//25412 25410//25410 25524//25524 -f 25524//25524 25410//25410 25409//25409 -f 25524//25524 25409//25409 25520//25520 -f 25520//25520 25409//25409 25408//25408 -f 25520//25520 25408//25408 25521//25521 -f 25521//25521 25408//25408 25407//25407 -f 25521//25521 25407//25407 25532//25532 -f 25413//25413 25412//25412 25508//25508 -f 25508//25508 25412//25412 25524//25524 -f 25508//25508 25524//25524 25534//25534 -f 25534//25534 25524//25524 25523//25523 -f 25534//25534 25523//25523 25535//25535 -f 25535//25535 25523//25523 25522//25522 -f 25416//25416 25415//25415 25536//25536 -f 25536//25536 25415//25415 25508//25508 -f 25536//25536 25508//25508 25537//25537 -f 25537//25537 25508//25508 25534//25534 -f 25537//25537 25534//25534 25538//25538 -f 25538//25538 25534//25534 25535//25535 -f 25437//25437 25435//25435 25539//25539 -f 25434//25434 25432//25432 25540//25540 -f 25431//25431 25430//25430 25541//25541 -f 25429//25429 25542//25542 25543//25543 -f 25544//25544 25545//25545 25546//25546 -f 25547//25547 25548//25548 25549//25549 -f 25550//25550 25551//25551 25552//25552 -f 25548//25548 25550//25550 25549//25549 -f 25549//25549 25550//25550 25552//25552 -f 25549//25549 25552//25552 25553//25553 -f 25553//25553 25552//25552 25554//25554 -f 25553//25553 25554//25554 25555//25555 -f 25555//25555 25554//25554 25556//25556 -f 25545//25545 25547//25547 25546//25546 -f 25546//25546 25547//25547 25549//25549 -f 25546//25546 25549//25549 25557//25557 -f 25557//25557 25549//25549 25553//25553 -f 25557//25557 25553//25553 25558//25558 -f 25558//25558 25553//25553 25555//25555 -f 25542//25542 25544//25544 25543//25543 -f 25543//25543 25544//25544 25546//25546 -f 25543//25543 25546//25546 25559//25559 -f 25559//25559 25546//25546 25557//25557 -f 25559//25559 25557//25557 25560//25560 -f 25560//25560 25557//25557 25558//25558 -f 25430//25430 25429//25429 25541//25541 -f 25541//25541 25429//25429 25543//25543 -f 25541//25541 25543//25543 25561//25561 -f 25561//25561 25543//25543 25559//25559 -f 25561//25561 25559//25559 25562//25562 -f 25562//25562 25559//25559 25560//25560 -f 25432//25432 25431//25431 25540//25540 -f 25540//25540 25431//25431 25541//25541 -f 25540//25540 25541//25541 25563//25563 -f 25563//25563 25541//25541 25561//25561 -f 25563//25563 25561//25561 25564//25564 -f 25564//25564 25561//25561 25562//25562 -f 25435//25435 25434//25434 25539//25539 -f 25539//25539 25434//25434 25540//25540 -f 25539//25539 25540//25540 25565//25565 -f 25565//25565 25540//25540 25563//25563 -f 25565//25565 25563//25563 25566//25566 -f 25566//25566 25563//25563 25564//25564 -f 25438//25438 25437//25437 25567//25567 -f 25567//25567 25437//25437 25539//25539 -f 25567//25567 25539//25539 25568//25568 -f 25568//25568 25539//25539 25565//25565 -f 25568//25568 25565//25565 25569//25569 -f 25569//25569 25565//25565 25566//25566 -f 25570//25570 25571//25571 25572//25572 -f 25572//25572 25571//25571 25573//25573 -f 25572//25572 25573//25573 25574//25574 -f 25574//25574 25573//25573 25575//25575 -f 25575//25575 25573//25573 25576//25576 -f 25575//25575 25576//25576 25577//25577 -f 25577//25577 25576//25576 25578//25578 -f 25578//25578 25576//25576 25579//25579 -f 25578//25578 25579//25579 25580//25580 -f 25580//25580 25579//25579 25581//25581 -f 25581//25581 25579//25579 25582//25582 -f 25581//25581 25582//25582 25583//25583 -f 25583//25583 25582//25582 25584//25584 -f 25584//25584 25582//25582 25585//25585 -f 25584//25584 25585//25585 25586//25586 -f 25586//25586 25585//25585 25587//25587 -f 25587//25587 25585//25585 25588//25588 -f 25587//25587 25588//25588 25589//25589 -f 25590//25590 25591//25591 25592//25592 -f 25592//25592 25591//25591 25593//25593 -f 25592//25592 25593//25593 25594//25594 -f 25594//25594 25593//25593 25595//25595 -f 25595//25595 25593//25593 25596//25596 -f 25595//25595 25596//25596 25597//25597 -f 25597//25597 25596//25596 25598//25598 -f 25598//25598 25596//25596 25599//25599 -f 25598//25598 25599//25599 25600//25600 -f 25600//25600 25599//25599 25601//25601 -f 25601//25601 25599//25599 25602//25602 -f 25601//25601 25602//25602 25603//25603 -f 25603//25603 25602//25602 25604//25604 -f 25604//25604 25602//25602 25605//25605 -f 25604//25604 25605//25605 25606//25606 -f 25606//25606 25605//25605 25607//25607 -f 25607//25607 25605//25605 25608//25608 -f 25607//25607 25608//25608 25609//25609 -f 25610//25610 25611//25611 25612//25612 -f 25612//25612 25611//25611 25613//25613 -f 25612//25612 25613//25613 25614//25614 -f 25614//25614 25613//25613 25615//25615 -f 25615//25615 25613//25613 25616//25616 -f 25615//25615 25616//25616 25617//25617 -f 25617//25617 25616//25616 25618//25618 -f 25618//25618 25616//25616 25619//25619 -f 25618//25618 25619//25619 25620//25620 -f 25620//25620 25619//25619 25621//25621 -f 25621//25621 25619//25619 25622//25622 -f 25621//25621 25622//25622 25623//25623 -f 25623//25623 25622//25622 25624//25624 -f 25624//25624 25622//25622 25625//25625 -f 25624//25624 25625//25625 25626//25626 -f 25626//25626 25625//25625 25627//25627 -f 25627//25627 25625//25625 25628//25628 -f 25627//25627 25628//25628 25629//25629 -f 25630//25630 25631//25631 25632//25632 -f 25632//25632 25631//25631 25633//25633 -f 25632//25632 25633//25633 25634//25634 -f 25634//25634 25633//25633 25635//25635 -f 25635//25635 25633//25633 25636//25636 -f 25635//25635 25636//25636 25637//25637 -f 25637//25637 25636//25636 25638//25638 -f 25638//25638 25636//25636 25639//25639 -f 25638//25638 25639//25639 25640//25640 -f 25640//25640 25639//25639 25641//25641 -f 25641//25641 25639//25639 25642//25642 -f 25641//25641 25642//25642 25643//25643 -f 25643//25643 25642//25642 25644//25644 -f 25644//25644 25642//25642 25645//25645 -f 25644//25644 25645//25645 25646//25646 -f 25646//25646 25645//25645 25647//25647 -f 25647//25647 25645//25645 25648//25648 -f 25647//25647 25648//25648 25649//25649 -f 25650//25650 25651//25651 25652//25652 -f 25651//25651 25653//25653 25654//25654 -f 25653//25653 25570//25570 25572//25572 -f 25653//25653 25572//25572 25654//25654 -f 25654//25654 25572//25572 25574//25574 -f 25654//25654 25574//25574 25655//25655 -f 25574//25574 25575//25575 25655//25655 -f 25655//25655 25575//25575 25577//25577 -f 25655//25655 25577//25577 25656//25656 -f 25656//25656 25577//25577 25578//25578 -f 25656//25656 25578//25578 25657//25657 -f 25657//25657 25578//25578 25580//25580 -f 25580//25580 25581//25581 25657//25657 -f 25657//25657 25581//25581 25583//25583 -f 25657//25657 25583//25583 25658//25658 -f 25583//25583 25584//25584 25658//25658 -f 25658//25658 25584//25584 25586//25586 -f 25658//25658 25586//25586 25659//25659 -f 25586//25586 25587//25587 25659//25659 -f 25659//25659 25587//25587 25589//25589 -f 25659//25659 25589//25589 25660//25660 -f 25651//25651 25654//25654 25652//25652 -f 25652//25652 25654//25654 25655//25655 -f 25652//25652 25655//25655 25661//25661 -f 25661//25661 25655//25655 25656//25656 -f 25661//25661 25656//25656 25662//25662 -f 25662//25662 25656//25656 25657//25657 -f 25662//25662 25657//25657 25663//25663 -f 25663//25663 25657//25657 25658//25658 -f 25663//25663 25658//25658 25664//25664 -f 25664//25664 25658//25658 25659//25659 -f 25664//25664 25659//25659 25665//25665 -f 25665//25665 25659//25659 25660//25660 -f 25665//25665 25660//25660 25666//25666 -f 25650//25650 25652//25652 25667//25667 -f 25667//25667 25652//25652 25661//25661 -f 25667//25667 25661//25661 25668//25668 -f 25668//25668 25661//25661 25662//25662 -f 25668//25668 25662//25662 25669//25669 -f 25669//25669 25662//25662 25663//25663 -f 25669//25669 25663//25663 25670//25670 -f 25670//25670 25663//25663 25664//25664 -f 25670//25670 25664//25664 25671//25671 -f 25671//25671 25664//25664 25665//25665 -f 25671//25671 25665//25665 25672//25672 -f 25672//25672 25665//25665 25666//25666 -f 25672//25672 25666//25666 25673//25673 -f 25674//25674 25675//25675 25676//25676 -f 25675//25675 25677//25677 25678//25678 -f 25677//25677 25590//25590 25592//25592 -f 25677//25677 25592//25592 25678//25678 -f 25678//25678 25592//25592 25594//25594 -f 25678//25678 25594//25594 25679//25679 -f 25594//25594 25595//25595 25679//25679 -f 25679//25679 25595//25595 25597//25597 -f 25679//25679 25597//25597 25680//25680 -f 25597//25597 25598//25598 25680//25680 -f 25680//25680 25598//25598 25600//25600 -f 25680//25680 25600//25600 25681//25681 -f 25600//25600 25601//25601 25681//25681 -f 25681//25681 25601//25601 25603//25603 -f 25681//25681 25603//25603 25682//25682 -f 25603//25603 25604//25604 25682//25682 -f 25682//25682 25604//25604 25606//25606 -f 25682//25682 25606//25606 25683//25683 -f 25606//25606 25607//25607 25683//25683 -f 25683//25683 25607//25607 25609//25609 -f 25683//25683 25609//25609 25684//25684 -f 25675//25675 25678//25678 25676//25676 -f 25676//25676 25678//25678 25679//25679 -f 25676//25676 25679//25679 25685//25685 -f 25685//25685 25679//25679 25680//25680 -f 25685//25685 25680//25680 25686//25686 -f 25686//25686 25680//25680 25681//25681 -f 25686//25686 25681//25681 25687//25687 -f 25687//25687 25681//25681 25682//25682 -f 25687//25687 25682//25682 25688//25688 -f 25688//25688 25682//25682 25683//25683 -f 25688//25688 25683//25683 25689//25689 -f 25689//25689 25683//25683 25684//25684 -f 25689//25689 25684//25684 25690//25690 -f 25674//25674 25676//25676 25691//25691 -f 25691//25691 25676//25676 25685//25685 -f 25691//25691 25685//25685 25692//25692 -f 25692//25692 25685//25685 25686//25686 -f 25692//25692 25686//25686 25693//25693 -f 25693//25693 25686//25686 25687//25687 -f 25693//25693 25687//25687 25694//25694 -f 25694//25694 25687//25687 25688//25688 -f 25694//25694 25688//25688 25695//25695 -f 25695//25695 25688//25688 25689//25689 -f 25695//25695 25689//25689 25696//25696 -f 25696//25696 25689//25689 25690//25690 -f 25696//25696 25690//25690 25697//25697 -f 25698//25698 25699//25699 25700//25700 -f 25699//25699 25701//25701 25702//25702 -f 25701//25701 25610//25610 25612//25612 -f 25701//25701 25612//25612 25702//25702 -f 25702//25702 25612//25612 25614//25614 -f 25702//25702 25614//25614 25703//25703 -f 25614//25614 25615//25615 25703//25703 -f 25703//25703 25615//25615 25617//25617 -f 25703//25703 25617//25617 25704//25704 -f 25617//25617 25618//25618 25704//25704 -f 25704//25704 25618//25618 25620//25620 -f 25704//25704 25620//25620 25705//25705 -f 25620//25620 25621//25621 25705//25705 -f 25705//25705 25621//25621 25623//25623 -f 25705//25705 25623//25623 25706//25706 -f 25623//25623 25624//25624 25706//25706 -f 25706//25706 25624//25624 25626//25626 -f 25706//25706 25626//25626 25707//25707 -f 25626//25626 25627//25627 25707//25707 -f 25707//25707 25627//25627 25629//25629 -f 25707//25707 25629//25629 25708//25708 -f 25699//25699 25702//25702 25700//25700 -f 25700//25700 25702//25702 25703//25703 -f 25700//25700 25703//25703 25709//25709 -f 25709//25709 25703//25703 25704//25704 -f 25709//25709 25704//25704 25710//25710 -f 25710//25710 25704//25704 25705//25705 -f 25710//25710 25705//25705 25711//25711 -f 25711//25711 25705//25705 25706//25706 -f 25711//25711 25706//25706 25712//25712 -f 25712//25712 25706//25706 25707//25707 -f 25712//25712 25707//25707 25713//25713 -f 25713//25713 25707//25707 25708//25708 -f 25713//25713 25708//25708 25714//25714 -f 25698//25698 25700//25700 25715//25715 -f 25715//25715 25700//25700 25709//25709 -f 25715//25715 25709//25709 25716//25716 -f 25716//25716 25709//25709 25710//25710 -f 25716//25716 25710//25710 25717//25717 -f 25717//25717 25710//25710 25711//25711 -f 25717//25717 25711//25711 25718//25718 -f 25718//25718 25711//25711 25712//25712 -f 25718//25718 25712//25712 25719//25719 -f 25719//25719 25712//25712 25713//25713 -f 25719//25719 25713//25713 25720//25720 -f 25720//25720 25713//25713 25714//25714 -f 25720//25720 25714//25714 25721//25721 -f 25722//25722 25723//25723 25724//25724 -f 25723//25723 25725//25725 25726//25726 -f 25725//25725 25630//25630 25632//25632 -f 25725//25725 25632//25632 25726//25726 -f 25726//25726 25632//25632 25634//25634 -f 25726//25726 25634//25634 25727//25727 -f 25634//25634 25635//25635 25727//25727 -f 25727//25727 25635//25635 25637//25637 -f 25727//25727 25637//25637 25728//25728 -f 25728//25728 25637//25637 25638//25638 -f 25728//25728 25638//25638 25729//25729 -f 25729//25729 25638//25638 25640//25640 -f 25640//25640 25641//25641 25729//25729 -f 25729//25729 25641//25641 25643//25643 -f 25729//25729 25643//25643 25730//25730 -f 25643//25643 25644//25644 25730//25730 -f 25730//25730 25644//25644 25646//25646 -f 25730//25730 25646//25646 25731//25731 -f 25646//25646 25647//25647 25731//25731 -f 25731//25731 25647//25647 25649//25649 -f 25731//25731 25649//25649 25732//25732 -f 25723//25723 25726//25726 25724//25724 -f 25724//25724 25726//25726 25727//25727 -f 25724//25724 25727//25727 25733//25733 -f 25733//25733 25727//25727 25728//25728 -f 25733//25733 25728//25728 25734//25734 -f 25734//25734 25728//25728 25729//25729 -f 25734//25734 25729//25729 25735//25735 -f 25735//25735 25729//25729 25730//25730 -f 25735//25735 25730//25730 25736//25736 -f 25736//25736 25730//25730 25731//25731 -f 25736//25736 25731//25731 25737//25737 -f 25737//25737 25731//25731 25732//25732 -f 25737//25737 25732//25732 25738//25738 -f 25722//25722 25724//25724 25739//25739 -f 25739//25739 25724//25724 25733//25733 -f 25739//25739 25733//25733 25740//25740 -f 25740//25740 25733//25733 25734//25734 -f 25740//25740 25734//25734 25741//25741 -f 25741//25741 25734//25734 25735//25735 -f 25741//25741 25735//25735 25742//25742 -f 25742//25742 25735//25735 25736//25736 -f 25742//25742 25736//25736 25743//25743 -f 25743//25743 25736//25736 25737//25737 -f 25743//25743 25737//25737 25744//25744 -f 25744//25744 25737//25737 25738//25738 -f 25744//25744 25738//25738 25745//25745 -f 25746//25746 25747//25747 25748//25748 -f 25749//25749 25750//25750 25751//25751 -f 25751//25751 25750//25750 25752//25752 -f 25751//25751 25752//25752 25753//25753 -f 25753//25753 25752//25752 25754//25754 -f 25753//25753 25754//25754 25755//25755 -f 25756//25756 25750//25750 25757//25757 -f 25757//25757 25750//25750 25749//25749 -f 25757//25757 25749//25749 25758//25758 -f 25758//25758 25749//25749 25759//25759 -f 25758//25758 25759//25759 25760//25760 -f 25760//25760 25759//25759 25761//25761 -f 25762//25762 25763//25763 25764//25764 -f 25764//25764 25763//25763 25765//25765 -f 25764//25764 25765//25765 25756//25756 -f 25756//25756 25765//25765 25766//25766 -f 25756//25756 25766//25766 25750//25750 -f 25767//25767 25768//25768 25769//25769 -f 25769//25769 25768//25768 25770//25770 -f 25769//25769 25770//25770 25771//25771 -f 25771//25771 25770//25770 25772//25772 -f 25766//25766 25771//25771 25750//25750 -f 25750//25750 25771//25771 25772//25772 -f 25750//25750 25772//25772 25748//25748 -f 25748//25748 25772//25772 25773//25773 -f 25748//25748 25773//25773 25746//25746 -f 25746//25746 25773//25773 25774//25774 -f 25746//25746 25774//25774 25775//25775 -f 25776//25776 25774//25774 25777//25777 -f 25777//25777 25774//25774 25773//25773 -f 25777//25777 25773//25773 25778//25778 -f 25773//25773 25772//25772 25778//25778 -f 25778//25778 25772//25772 25779//25779 -f 25779//25779 25772//25772 25780//25780 -f 25780//25780 25772//25772 25770//25770 -f 25780//25780 25770//25770 25781//25781 -f 25768//25768 25782//25782 25770//25770 -f 25770//25770 25782//25782 25783//25783 -f 25770//25770 25783//25783 25781//25781 -f 25768//25768 25767//25767 25782//25782 -f 25782//25782 25767//25767 25784//25784 -f 25784//25784 25767//25767 25785//25785 -f 25785//25785 25767//25767 25769//25769 -f 25785//25785 25769//25769 25786//25786 -f 25786//25786 25769//25769 25787//25787 -f 25787//25787 25769//25769 25771//25771 -f 25787//25787 25771//25771 25788//25788 -f 25771//25771 25766//25766 25788//25788 -f 25788//25788 25766//25766 25789//25789 -f 25789//25789 25766//25766 25790//25790 -f 25790//25790 25766//25766 25765//25765 -f 25790//25790 25765//25765 25791//25791 -f 25763//25763 25792//25792 25765//25765 -f 25765//25765 25792//25792 25793//25793 -f 25765//25765 25793//25793 25791//25791 -f 25763//25763 25762//25762 25792//25792 -f 25792//25792 25762//25762 25794//25794 -f 25794//25794 25762//25762 25795//25795 -f 25795//25795 25762//25762 25764//25764 -f 25795//25795 25764//25764 25796//25796 -f 25796//25796 25764//25764 25797//25797 -f 25797//25797 25764//25764 25756//25756 -f 25797//25797 25756//25756 25798//25798 -f 25756//25756 25757//25757 25798//25798 -f 25798//25798 25757//25757 25799//25799 -f 25799//25799 25757//25757 25800//25800 -f 25800//25800 25757//25757 25758//25758 -f 25800//25800 25758//25758 25801//25801 -f 25760//25760 25802//25802 25758//25758 -f 25758//25758 25802//25802 25803//25803 -f 25758//25758 25803//25803 25801//25801 -f 25760//25760 25761//25761 25802//25802 -f 25802//25802 25761//25761 25804//25804 -f 25804//25804 25761//25761 25805//25805 -f 25805//25805 25761//25761 25759//25759 -f 25805//25805 25759//25759 25806//25806 -f 25806//25806 25759//25759 25807//25807 -f 25807//25807 25759//25759 25749//25749 -f 25807//25807 25749//25749 25808//25808 -f 25749//25749 25751//25751 25808//25808 -f 25808//25808 25751//25751 25809//25809 -f 25809//25809 25751//25751 25810//25810 -f 25810//25810 25751//25751 25753//25753 -f 25810//25810 25753//25753 25811//25811 -f 25755//25755 25812//25812 25753//25753 -f 25753//25753 25812//25812 25813//25813 -f 25753//25753 25813//25813 25811//25811 -f 25755//25755 25754//25754 25812//25812 -f 25812//25812 25754//25754 25814//25814 -f 25815//25815 25816//25816 25814//25814 -f 25817//25817 25818//25818 25819//25819 -f 25819//25819 25818//25818 25820//25820 -f 25819//25819 25820//25820 25752//25752 -f 25820//25820 25821//25821 25752//25752 -f 25752//25752 25821//25821 25815//25815 -f 25752//25752 25815//25815 25754//25754 -f 25754//25754 25815//25815 25814//25814 -f 25822//25822 25819//25819 25823//25823 -f 25823//25823 25819//25819 25752//25752 -f 25824//25824 25825//25825 25826//25826 -f 25826//25826 25825//25825 25827//25827 -f 25827//25827 25828//25828 25826//25826 -f 25826//25826 25828//25828 25829//25829 -f 25826//25826 25829//25829 25750//25750 -f 25750//25750 25829//25829 25830//25830 -f 25750//25750 25830//25830 25752//25752 -f 25752//25752 25830//25830 25831//25831 -f 25752//25752 25831//25831 25823//25823 -f 25832//25832 25826//25826 25748//25748 -f 25748//25748 25826//25826 25750//25750 -f 25833//25833 25824//25824 25826//25826 -f 25834//25834 25833//25833 25835//25835 -f 25835//25835 25833//25833 25826//25826 -f 25835//25835 25826//25826 25836//25836 -f 25836//25836 25826//25826 25832//25832 -f 25836//25836 25832//25832 25837//25837 -f 25838//25838 25839//25839 25746//25746 -f 25746//25746 25839//25839 25837//25837 -f 25746//25746 25837//25837 25747//25747 -f 25747//25747 25837//25837 25832//25832 -f 25840//25840 25838//25838 25775//25775 -f 25775//25775 25838//25838 25746//25746 -f 25840//25840 25775//25775 25841//25841 -f 25841//25841 25775//25775 25774//25774 -f 25841//25841 25774//25774 25776//25776 -f 25780//25780 25777//25777 25779//25779 -f 25779//25779 25777//25777 25778//25778 -f 25782//25782 25784//25784 25783//25783 -f 25783//25783 25784//25784 25785//25785 -f 25790//25790 25787//25787 25789//25789 -f 25789//25789 25787//25787 25788//25788 -f 25792//25792 25794//25794 25793//25793 -f 25793//25793 25794//25794 25795//25795 -f 25800//25800 25797//25797 25799//25799 -f 25799//25799 25797//25797 25798//25798 -f 25802//25802 25804//25804 25803//25803 -f 25803//25803 25804//25804 25805//25805 -f 25810//25810 25807//25807 25809//25809 -f 25809//25809 25807//25807 25808//25808 -f 25812//25812 25814//25814 25813//25813 -f 25813//25813 25814//25814 25816//25816 -f 25820//25820 25842//25842 25821//25821 -f 25821//25821 25842//25842 25843//25843 -f 25821//25821 25843//25843 25844//25844 -f 25820//25820 25818//25818 25842//25842 -f 25842//25842 25818//25818 25845//25845 -f 25818//25818 25817//25817 25845//25845 -f 25845//25845 25817//25817 25846//25846 -f 25819//25819 25822//25822 25817//25817 -f 25817//25817 25822//25822 25846//25846 -f 25831//25831 25830//25830 25847//25847 -f 25848//25848 25847//25847 25830//25830 -f 25849//25849 25829//25829 25850//25850 -f 25850//25850 25829//25829 25851//25851 -f 25849//25849 25852//25852 25829//25829 -f 25829//25829 25852//25852 25853//25853 -f 25829//25829 25853//25853 25830//25830 -f 25830//25830 25853//25853 25854//25854 -f 25830//25830 25854//25854 25848//25848 -f 25829//25829 25828//25828 25851//25851 -f 25824//25824 25833//25833 25825//25825 -f 25825//25825 25833//25833 25855//25855 -f 25832//25832 25748//25748 25747//25747 -f 25856//25856 25835//25835 25857//25857 -f 25857//25857 25835//25835 25836//25836 -f 25857//25857 25836//25836 25858//25858 -f 25834//25834 25859//25859 25833//25833 -f 25833//25833 25859//25859 25855//25855 -f 25835//25835 25856//25856 25834//25834 -f 25834//25834 25856//25856 25859//25859 -f 25841//25841 25839//25839 25840//25840 -f 25840//25840 25839//25839 25838//25838 -f 25813//25813 25816//25816 25811//25811 -f 25811//25811 25816//25816 25815//25815 -f 25811//25811 25815//25815 25810//25810 -f 25842//25842 25845//25845 25846//25846 -f 25860//25860 25843//25843 25823//25823 -f 25823//25823 25843//25843 25842//25842 -f 25823//25823 25842//25842 25822//25822 -f 25822//25822 25842//25842 25846//25846 -f 25861//25861 25862//25862 25863//25863 -f 25863//25863 25862//25862 25844//25844 -f 25863//25863 25844//25844 25864//25864 -f 25864//25864 25844//25844 25843//25843 -f 25853//25853 25852//25852 25865//25865 -f 25848//25848 25854//25854 25866//25866 -f 25849//25849 25850//25850 25867//25867 -f 25868//25868 25857//25857 25869//25869 -f 25869//25869 25857//25857 25858//25858 -f 25869//25869 25858//25858 25870//25870 -f 25870//25870 25858//25858 25871//25871 -f 25856//25856 25857//25857 25872//25872 -f 25855//25855 25859//25859 25825//25825 -f 25825//25825 25859//25859 25856//25856 -f 25825//25825 25856//25856 25827//25827 -f 25827//25827 25856//25856 25872//25872 -f 25777//25777 25837//25837 25776//25776 -f 25776//25776 25837//25837 25839//25839 -f 25776//25776 25839//25839 25841//25841 -f 25334//25334 25332//25332 25862//25862 -f 25334//25334 25862//25862 25336//25336 -f 25836//25836 25837//25837 25858//25858 -f 25858//25858 25837//25837 25777//25777 -f 25294//25294 25293//25293 25815//25815 -f 25354//25354 25352//25352 25862//25862 -f 25800//25800 25330//25330 25797//25797 -f 25797//25797 25330//25330 25329//25329 -f 25797//25797 25329//25329 25790//25790 -f 25815//25815 25293//25293 25810//25810 -f 25294//25294 25815//25815 25296//25296 -f 25296//25296 25815//25815 25821//25821 -f 25296//25296 25821//25821 25298//25298 -f 25298//25298 25821//25821 25844//25844 -f 25298//25298 25844//25844 25300//25300 -f 25873//25873 25332//25332 25874//25874 -f 25874//25874 25332//25332 25330//25330 -f 25329//25329 25326//25326 25790//25790 -f 25790//25790 25326//25326 25325//25325 -f 25790//25790 25325//25325 25875//25875 -f 25777//25777 25876//25876 25858//25858 -f 25858//25858 25876//25876 25877//25877 -f 25858//25858 25877//25877 25878//25878 -f 25862//25862 25352//25352 25844//25844 -f 25844//25844 25352//25352 25350//25350 -f 25844//25844 25350//25350 25348//25348 -f 25312//25312 25311//25311 25787//25787 -f 25787//25787 25311//25311 25780//25780 -f 25293//25293 25290//25290 25810//25810 -f 25810//25810 25290//25290 25289//25289 -f 25810//25810 25289//25289 25807//25807 -f 25807//25807 25289//25289 25879//25879 -f 25807//25807 25879//25879 25800//25800 -f 25800//25800 25879//25879 25880//25880 -f 25800//25800 25880//25880 25881//25881 -f 25800//25800 25347//25347 25344//25344 -f 25873//25873 25882//25882 25332//25332 -f 25332//25332 25882//25882 25883//25883 -f 25332//25332 25883//25883 25862//25862 -f 25862//25862 25883//25883 25356//25356 -f 25862//25862 25356//25356 25354//25354 -f 25884//25884 25318//25318 25885//25885 -f 25885//25885 25318//25318 25316//25316 -f 25885//25885 25316//25316 25886//25886 -f 25886//25886 25316//25316 25314//25314 -f 25886//25886 25314//25314 25875//25875 -f 25875//25875 25314//25314 25312//25312 -f 25875//25875 25312//25312 25790//25790 -f 25790//25790 25312//25312 25787//25787 -f 25878//25878 25887//25887 25858//25858 -f 25858//25858 25887//25887 25888//25888 -f 25858//25858 25888//25888 25320//25320 -f 25347//25347 25800//25800 25348//25348 -f 25344//25344 25343//25343 25800//25800 -f 25800//25800 25343//25343 25889//25889 -f 25800//25800 25889//25889 25330//25330 -f 25330//25330 25889//25889 25890//25890 -f 25330//25330 25890//25890 25874//25874 -f 25336//25336 25862//25862 25338//25338 -f 25338//25338 25862//25862 25871//25871 -f 25338//25338 25871//25871 25891//25891 -f 25311//25311 25308//25308 25780//25780 -f 25780//25780 25308//25308 25307//25307 -f 25780//25780 25307//25307 25777//25777 -f 25777//25777 25307//25307 25892//25892 -f 25777//25777 25892//25892 25876//25876 -f 25320//25320 25318//25318 25858//25858 -f 25858//25858 25318//25318 25884//25884 -f 25858//25858 25884//25884 25871//25871 -f 25871//25871 25884//25884 25893//25893 -f 25871//25871 25893//25893 25891//25891 -f 25881//25881 25894//25894 25800//25800 -f 25800//25800 25894//25894 25895//25895 -f 25800//25800 25895//25895 25348//25348 -f 25348//25348 25895//25895 25896//25896 -f 25348//25348 25896//25896 25844//25844 -f 25844//25844 25896//25896 25302//25302 -f 25844//25844 25302//25302 25300//25300 -f 25897//25897 25860//25860 25847//25847 -f 25847//25847 25860//25860 25823//25823 -f 25847//25847 25823//25823 25831//25831 -f 25872//25872 25898//25898 25827//25827 -f 25827//25827 25898//25898 25851//25851 -f 25827//25827 25851//25851 25828//25828 -f 25862//25862 25861//25861 25871//25871 -f 25871//25871 25861//25861 25870//25870 -f 25787//25787 25780//25780 25786//25786 -f 25786//25786 25780//25780 25781//25781 -f 25786//25786 25781//25781 25785//25785 -f 25785//25785 25781//25781 25783//25783 -f 25793//25793 25795//25795 25791//25791 -f 25791//25791 25795//25795 25796//25796 -f 25791//25791 25796//25796 25790//25790 -f 25790//25790 25796//25796 25797//25797 -f 25807//25807 25800//25800 25806//25806 -f 25806//25806 25800//25800 25801//25801 -f 25806//25806 25801//25801 25805//25805 -f 25805//25805 25801//25801 25803//25803 -f 25848//25848 25899//25899 25847//25847 -f 25847//25847 25899//25899 25897//25897 -f 25900//25900 25850//25850 25898//25898 -f 25898//25898 25850//25850 25851//25851 -f 25863//25863 25901//25901 25861//25861 -f 25861//25861 25901//25901 25902//25902 -f 25861//25861 25902//25902 25870//25870 -f 25870//25870 25902//25902 25903//25903 -f 25870//25870 25903//25903 25869//25869 -f 25869//25869 25903//25903 25904//25904 -f 25848//25848 25866//25866 25899//25899 -f 25899//25899 25866//25866 25905//25905 -f 25900//25900 25906//25906 25850//25850 -f 25850//25850 25906//25906 25867//25867 -f 25358//25358 25907//25907 25359//25359 -f 25359//25359 25907//25907 25908//25908 -f 25363//25363 25362//25362 25449//25449 -f 25449//25449 25362//25362 25909//25909 -f 25907//25907 25910//25910 25908//25908 -f 25908//25908 25910//25910 25911//25911 -f 25908//25908 25911//25911 25912//25912 -f 25911//25911 25913//25913 25912//25912 -f 25912//25912 25913//25913 25914//25914 -f 25912//25912 25914//25914 25915//25915 -f 25914//25914 25916//25916 25915//25915 -f 25915//25915 25916//25916 25458//25458 -f 25915//25915 25458//25458 25917//25917 -f 25458//25458 25457//25457 25917//25917 -f 25917//25917 25457//25457 25455//25455 -f 25917//25917 25455//25455 25918//25918 -f 25455//25455 25454//25454 25918//25918 -f 25918//25918 25454//25454 25452//25452 -f 25918//25918 25452//25452 25909//25909 -f 25909//25909 25452//25452 25451//25451 -f 25909//25909 25451//25451 25449//25449 -f 25380//25380 25919//25919 25381//25381 -f 25381//25381 25919//25919 25920//25920 -f 25385//25385 25384//25384 25501//25501 -f 25501//25501 25384//25384 25921//25921 -f 25919//25919 25922//25922 25920//25920 -f 25920//25920 25922//25922 25923//25923 -f 25920//25920 25923//25923 25924//25924 -f 25923//25923 25925//25925 25924//25924 -f 25924//25924 25925//25925 25926//25926 -f 25924//25924 25926//25926 25927//25927 -f 25926//25926 25928//25928 25927//25927 -f 25927//25927 25928//25928 25497//25497 -f 25927//25927 25497//25497 25929//25929 -f 25497//25497 25496//25496 25929//25929 -f 25929//25929 25496//25496 25495//25495 -f 25929//25929 25495//25495 25930//25930 -f 25495//25495 25500//25500 25930//25930 -f 25930//25930 25500//25500 25499//25499 -f 25930//25930 25499//25499 25921//25921 -f 25921//25921 25499//25499 25502//25502 -f 25921//25921 25502//25502 25501//25501 -f 25402//25402 25931//25931 25403//25403 -f 25403//25403 25931//25931 25932//25932 -f 25407//25407 25406//25406 25532//25532 -f 25532//25532 25406//25406 25933//25933 -f 25931//25931 25934//25934 25932//25932 -f 25932//25932 25934//25934 25935//25935 -f 25932//25932 25935//25935 25936//25936 -f 25935//25935 25937//25937 25936//25936 -f 25936//25936 25937//25937 25938//25938 -f 25936//25936 25938//25938 25939//25939 -f 25938//25938 25940//25940 25939//25939 -f 25939//25939 25940//25940 25528//25528 -f 25939//25939 25528//25528 25941//25941 -f 25528//25528 25527//25527 25941//25941 -f 25941//25941 25527//25527 25526//25526 -f 25941//25941 25526//25526 25942//25942 -f 25526//25526 25531//25531 25942//25942 -f 25942//25942 25531//25531 25530//25530 -f 25942//25942 25530//25530 25933//25933 -f 25933//25933 25530//25530 25533//25533 -f 25933//25933 25533//25533 25532//25532 -f 25424//25424 25943//25943 25425//25425 -f 25425//25425 25943//25943 25944//25944 -f 25429//25429 25428//25428 25542//25542 -f 25542//25542 25428//25428 25945//25945 -f 25943//25943 25946//25946 25944//25944 -f 25944//25944 25946//25946 25947//25947 -f 25944//25944 25947//25947 25948//25948 -f 25947//25947 25949//25949 25948//25948 -f 25948//25948 25949//25949 25950//25950 -f 25948//25948 25950//25950 25951//25951 -f 25950//25950 25952//25952 25951//25951 -f 25951//25951 25952//25952 25551//25551 -f 25951//25951 25551//25551 25953//25953 -f 25551//25551 25550//25550 25953//25953 -f 25953//25953 25550//25550 25548//25548 -f 25953//25953 25548//25548 25954//25954 -f 25548//25548 25547//25547 25954//25954 -f 25954//25954 25547//25547 25545//25545 -f 25954//25954 25545//25545 25945//25945 -f 25945//25945 25545//25545 25544//25544 -f 25945//25945 25544//25544 25542//25542 -f 25902//25902 25955//25955 25903//25903 -f 25903//25903 25955//25955 25956//25956 -f 25957//25957 25905//25905 25854//25854 -f 25854//25854 25905//25905 25866//25866 -f 25849//25849 25867//25867 25958//25958 -f 25958//25958 25867//25867 25906//25906 -f 25916//25916 25914//25914 25959//25959 -f 25960//25960 25961//25961 25962//25962 -f 25963//25963 25964//25964 25961//25961 -f 25965//25965 25966//25966 25964//25964 -f 25476//25476 25966//25966 25475//25475 -f 25475//25475 25966//25966 25965//25965 -f 25475//25475 25965//25965 25474//25474 -f 25967//25967 25968//25968 25969//25969 -f 25962//25962 25970//25970 25967//25967 -f 25967//25967 25970//25970 25971//25971 -f 25967//25967 25971//25971 25968//25968 -f 25968//25968 25971//25971 25972//25972 -f 25973//25973 25375//25375 25374//25374 -f 25964//25964 25963//25963 25965//25965 -f 25965//25965 25963//25963 25973//25973 -f 25965//25965 25973//25973 25474//25474 -f 25474//25474 25973//25973 25374//25374 -f 25474//25474 25374//25374 25372//25372 -f 25974//25974 25378//25378 25377//25377 -f 25961//25961 25960//25960 25963//25963 -f 25963//25963 25960//25960 25974//25974 -f 25963//25963 25974//25974 25973//25973 -f 25973//25973 25974//25974 25377//25377 -f 25973//25973 25377//25377 25375//25375 -f 25969//25969 25360//25360 25379//25379 -f 25962//25962 25967//25967 25960//25960 -f 25960//25960 25967//25967 25969//25969 -f 25960//25960 25969//25969 25974//25974 -f 25974//25974 25969//25969 25379//25379 -f 25974//25974 25379//25379 25378//25378 -f 25913//25913 25911//25911 25972//25972 -f 25972//25972 25911//25911 25910//25910 -f 25972//25972 25910//25910 25968//25968 -f 25968//25968 25910//25910 25907//25907 -f 25968//25968 25907//25907 25969//25969 -f 25969//25969 25907//25907 25358//25358 -f 25969//25969 25358//25358 25360//25360 -f 25914//25914 25913//25913 25959//25959 -f 25959//25959 25913//25913 25972//25972 -f 25959//25959 25972//25972 25975//25975 -f 25975//25975 25972//25972 25971//25971 -f 25975//25975 25971//25971 25976//25976 -f 25976//25976 25971//25971 25970//25970 -f 25458//25458 25916//25916 25459//25459 -f 25459//25459 25916//25916 25959//25959 -f 25459//25459 25959//25959 25461//25461 -f 25461//25461 25959//25959 25975//25975 -f 25461//25461 25975//25975 25463//25463 -f 25463//25463 25975//25975 25976//25976 -f 25928//25928 25926//25926 25977//25977 -f 25925//25925 25923//25923 25978//25978 -f 25922//25922 25919//25919 25979//25979 -f 25380//25380 25382//25382 25980//25980 -f 25401//25401 25400//25400 25981//25981 -f 25399//25399 25397//25397 25982//25982 -f 25396//25396 25394//25394 25505//25505 -f 25397//25397 25396//25396 25982//25982 -f 25982//25982 25396//25396 25505//25505 -f 25982//25982 25505//25505 25983//25983 -f 25983//25983 25505//25505 25506//25506 -f 25983//25983 25506//25506 25984//25984 -f 25984//25984 25506//25506 25507//25507 -f 25400//25400 25399//25399 25981//25981 -f 25981//25981 25399//25399 25982//25982 -f 25981//25981 25982//25982 25985//25985 -f 25985//25985 25982//25982 25983//25983 -f 25985//25985 25983//25983 25986//25986 -f 25986//25986 25983//25983 25984//25984 -f 25382//25382 25401//25401 25980//25980 -f 25980//25980 25401//25401 25981//25981 -f 25980//25980 25981//25981 25987//25987 -f 25987//25987 25981//25981 25985//25985 -f 25987//25987 25985//25985 25988//25988 -f 25988//25988 25985//25985 25986//25986 -f 25919//25919 25380//25380 25979//25979 -f 25979//25979 25380//25380 25980//25980 -f 25979//25979 25980//25980 25989//25989 -f 25989//25989 25980//25980 25987//25987 -f 25989//25989 25987//25987 25990//25990 -f 25990//25990 25987//25987 25988//25988 -f 25923//25923 25922//25922 25978//25978 -f 25978//25978 25922//25922 25979//25979 -f 25978//25978 25979//25979 25991//25991 -f 25991//25991 25979//25979 25989//25989 -f 25991//25991 25989//25989 25992//25992 -f 25992//25992 25989//25989 25990//25990 -f 25926//25926 25925//25925 25977//25977 -f 25977//25977 25925//25925 25978//25978 -f 25977//25977 25978//25978 25993//25993 -f 25993//25993 25978//25978 25991//25991 -f 25993//25993 25991//25991 25994//25994 -f 25994//25994 25991//25991 25992//25992 -f 25497//25497 25928//25928 25487//25487 -f 25487//25487 25928//25928 25977//25977 -f 25487//25487 25977//25977 25486//25486 -f 25486//25486 25977//25977 25993//25993 -f 25486//25486 25993//25993 25485//25485 -f 25485//25485 25993//25993 25994//25994 -f 25940//25940 25938//25938 25995//25995 -f 25937//25937 25935//25935 25996//25996 -f 25934//25934 25931//25931 25997//25997 -f 25402//25402 25404//25404 25998//25998 -f 25423//25423 25422//25422 25999//25999 -f 25421//25421 25419//25419 26000//26000 -f 25418//25418 25416//25416 25536//25536 -f 25419//25419 25418//25418 26000//26000 -f 26000//26000 25418//25418 25536//25536 -f 26000//26000 25536//25536 26001//26001 -f 26001//26001 25536//25536 25537//25537 -f 26001//26001 25537//25537 26002//26002 -f 26002//26002 25537//25537 25538//25538 -f 25422//25422 25421//25421 25999//25999 -f 25999//25999 25421//25421 26000//26000 -f 25999//25999 26000//26000 26003//26003 -f 26003//26003 26000//26000 26001//26001 -f 26003//26003 26001//26001 26004//26004 -f 26004//26004 26001//26001 26002//26002 -f 25404//25404 25423//25423 25998//25998 -f 25998//25998 25423//25423 25999//25999 -f 25998//25998 25999//25999 26005//26005 -f 26005//26005 25999//25999 26003//26003 -f 26005//26005 26003//26003 26006//26006 -f 26006//26006 26003//26003 26004//26004 -f 25931//25931 25402//25402 25997//25997 -f 25997//25997 25402//25402 25998//25998 -f 25997//25997 25998//25998 26007//26007 -f 26007//26007 25998//25998 26005//26005 -f 26007//26007 26005//26005 26008//26008 -f 26008//26008 26005//26005 26006//26006 -f 25935//25935 25934//25934 25996//25996 -f 25996//25996 25934//25934 25997//25997 -f 25996//25996 25997//25997 26009//26009 -f 26009//26009 25997//25997 26007//26007 -f 26009//26009 26007//26007 26010//26010 -f 26010//26010 26007//26007 26008//26008 -f 25938//25938 25937//25937 25995//25995 -f 25995//25995 25937//25937 25996//25996 -f 25995//25995 25996//25996 26011//26011 -f 26011//26011 25996//25996 26009//26009 -f 26011//26011 26009//26009 26012//26012 -f 26012//26012 26009//26009 26010//26010 -f 25528//25528 25940//25940 25518//25518 -f 25518//25518 25940//25940 25995//25995 -f 25518//25518 25995//25995 25517//25517 -f 25517//25517 25995//25995 26011//26011 -f 25517//25517 26011//26011 25516//25516 -f 25516//25516 26011//26011 26012//26012 -f 25952//25952 25950//25950 26013//26013 -f 26014//26014 26015//26015 26016//26016 -f 26017//26017 26018//26018 26015//26015 -f 26019//26019 26020//26020 26018//26018 -f 25569//25569 26020//26020 25568//25568 -f 25568//25568 26020//26020 26019//26019 -f 25568//25568 26019//26019 25567//25567 -f 26021//26021 26022//26022 26023//26023 -f 26016//26016 26024//26024 26021//26021 -f 26021//26021 26024//26024 26025//26025 -f 26021//26021 26025//26025 26022//26022 -f 26022//26022 26025//26025 26026//26026 -f 26027//26027 25441//25441 25440//25440 -f 26018//26018 26017//26017 26019//26019 -f 26019//26019 26017//26017 26027//26027 -f 26019//26019 26027//26027 25567//25567 -f 25567//25567 26027//26027 25440//25440 -f 25567//25567 25440//25440 25438//25438 -f 26028//26028 25444//25444 25443//25443 -f 26015//26015 26014//26014 26017//26017 -f 26017//26017 26014//26014 26028//26028 -f 26017//26017 26028//26028 26027//26027 -f 26027//26027 26028//26028 25443//25443 -f 26027//26027 25443//25443 25441//25441 -f 26023//26023 25426//25426 25445//25445 -f 26016//26016 26021//26021 26014//26014 -f 26014//26014 26021//26021 26023//26023 -f 26014//26014 26023//26023 26028//26028 -f 26028//26028 26023//26023 25445//25445 -f 26028//26028 25445//25445 25444//25444 -f 25949//25949 25947//25947 26026//26026 -f 26026//26026 25947//25947 25946//25946 -f 26026//26026 25946//25946 26022//26022 -f 26022//26022 25946//25946 25943//25943 -f 26022//26022 25943//25943 26023//26023 -f 26023//26023 25943//25943 25424//25424 -f 26023//26023 25424//25424 25426//25426 -f 25950//25950 25949//25949 26013//26013 -f 26013//26013 25949//25949 26026//26026 -f 26013//26013 26026//26026 26029//26029 -f 26029//26029 26026//26026 26025//26025 -f 26029//26029 26025//26025 26030//26030 -f 26030//26030 26025//26025 26024//26024 -f 25551//25551 25952//25952 25552//25552 -f 25552//25552 25952//25952 26013//26013 -f 25552//25552 26013//26013 25554//25554 -f 25554//25554 26013//26013 26029//26029 -f 25554//25554 26029//26029 25556//25556 -f 25556//25556 26029//26029 26030//26030 -f 26031//26031 25904//25904 26032//26032 -f 26032//26032 25904//25904 25903//25903 -f 26032//26032 25903//25903 25956//25956 -f 26033//26033 26032//26032 26034//26034 -f 26034//26034 26032//26032 25956//25956 -f 26034//26034 25956//25956 26035//26035 -f 26035//26035 25956//25956 25955//25955 -f 26035//26035 25955//25955 26036//26036 -f 26036//26036 25955//25955 26037//26037 -f 25901//25901 26038//26038 25902//25902 -f 25902//25902 26038//26038 26037//26037 -f 25902//25902 26037//26037 25955//25955 -f 25853//25853 26039//26039 25854//25854 -f 25854//25854 26039//26039 25957//25957 -f 25849//25849 25958//25958 25852//25852 -f 25852//25852 25958//25958 26040//26040 -f 25966//25966 25476//25476 25970//25970 -f 25473//25473 25471//25471 25463//25463 -f 25473//25473 25463//25463 25476//25476 -f 25476//25476 25463//25463 25976//25976 -f 25476//25476 25976//25976 25970//25970 -f 25462//25462 25463//25463 25465//25465 -f 25465//25465 25463//25463 25471//25471 -f 25465//25465 25471//25471 25467//25467 -f 25467//25467 25471//25471 25469//25469 -f 25962//25962 25961//25961 25970//25970 -f 25970//25970 25961//25961 25964//25964 -f 25970//25970 25964//25964 25966//25966 -f 25484//25484 25485//25485 25504//25504 -f 25504//25504 25485//25485 25507//25507 -f 25507//25507 25485//25485 25994//25994 -f 25507//25507 25994//25994 25992//25992 -f 25986//25986 25984//25984 25988//25988 -f 25988//25988 25984//25984 25507//25507 -f 25988//25988 25507//25507 25990//25990 -f 25990//25990 25507//25507 25992//25992 -f 25479//25479 25482//25482 25480//25480 -f 25480//25480 25482//25482 25484//25484 -f 25480//25480 25484//25484 25491//25491 -f 25491//25491 25484//25484 25504//25504 -f 26002//26002 25538//25538 26012//26012 -f 26012//26012 25538//25538 25516//25516 -f 25516//25516 25538//25538 25535//25535 -f 25516//25516 25535//25535 25522//25522 -f 25515//25515 25516//25516 25513//25513 -f 25513//25513 25516//25516 25522//25522 -f 25513//25513 25522//25522 25510//25510 -f 25510//25510 25522//25522 25511//25511 -f 26006//26006 26004//26004 26008//26008 -f 26008//26008 26004//26004 26002//26002 -f 26008//26008 26002//26002 26010//26010 -f 26010//26010 26002//26002 26012//26012 -f 25558//25558 25555//25555 25556//25556 -f 26020//26020 25569//25569 26018//26018 -f 26018//26018 25569//25569 26024//26024 -f 26018//26018 26024//26024 26015//26015 -f 26015//26015 26024//26024 26016//26016 -f 25562//25562 25560//25560 25564//25564 -f 25564//25564 25560//25560 25558//25558 -f 25564//25564 25558//25558 25566//25566 -f 25566//25566 25558//25558 25556//25556 -f 25566//25566 25556//25556 25569//25569 -f 25569//25569 25556//25556 26030//26030 -f 25569//25569 26030//26030 26024//26024 -f 26033//26033 26041//26041 26032//26032 -f 26032//26032 26041//26041 26031//26031 -f 26031//26031 26041//26041 25904//25904 -f 25904//25904 26041//26041 25868//25868 -f 25904//25904 25868//25868 25869//25869 -f 26035//26035 26042//26042 26034//26034 -f 26034//26034 26042//26042 26043//26043 -f 26036//26036 26037//26037 26044//26044 -f 26044//26044 26037//26037 26038//26038 -f 26044//26044 26038//26038 25864//25864 -f 25864//25864 26038//26038 25901//25901 -f 25864//25864 25901//25901 25863//25863 -f 25853//25853 25865//25865 26039//26039 -f 26039//26039 25865//25865 26045//26045 -f 26040//26040 26045//26045 25852//25852 -f 25852//25852 26045//26045 25865//25865 -f 26046//26046 25868//25868 26043//26043 -f 26043//26043 25868//25868 26041//26041 -f 26043//26043 26041//26041 26034//26034 -f 26034//26034 26041//26041 26033//26033 -f 26046//26046 26043//26043 26047//26047 -f 26047//26047 26043//26043 26042//26042 -f 26035//26035 26036//26036 26042//26042 -f 26042//26042 26036//26036 26044//26044 -f 26042//26042 26044//26044 26047//26047 -f 26047//26047 26044//26044 25864//25864 -f 26048//26048 26049//26049 25872//25872 -f 25872//25872 26049//26049 26050//26050 -f 25872//25872 26050//26050 25898//25898 -f 25906//25906 25900//25900 25608//25608 -f 25608//25608 25900//25900 25898//25898 -f 25608//25608 25898//25898 26051//26051 -f 26051//26051 25898//25898 26050//26050 -f 25897//25897 25588//25588 25585//25585 -f 26045//26045 26040//26040 25628//25628 -f 25628//25628 26040//26040 25958//25958 -f 25628//25628 25958//25958 26052//26052 -f 25897//25897 25585//25585 25860//25860 -f 25905//25905 25957//25957 25648//25648 -f 25648//25648 25957//25957 26039//26039 -f 25648//25648 26039//26039 26053//26053 -f 26052//26052 25958//25958 26054//26054 -f 26054//26054 25958//25958 25906//25906 -f 26054//26054 25906//25906 26055//26055 -f 26055//26055 25906//25906 25608//25608 -f 26055//26055 25608//25608 25605//25605 -f 25611//25611 25596//25596 25593//25593 -f 25872//25872 25857//25857 26048//26048 -f 26048//26048 25857//25857 25868//25868 -f 26048//26048 25868//25868 26056//26056 -f 26056//26056 25868//25868 26046//26046 -f 26056//26056 26046//26046 25591//25591 -f 25588//25588 25897//25897 26057//26057 -f 26057//26057 25897//25897 25899//25899 -f 26057//26057 25899//25899 26058//26058 -f 26058//26058 25899//25899 25905//25905 -f 26058//26058 25905//25905 26059//26059 -f 26059//26059 25905//25905 25648//25648 -f 26059//26059 25648//25648 25645//25645 -f 25605//25605 25602//25602 26055//26055 -f 26055//26055 25602//25602 25599//25599 -f 26055//26055 25599//25599 26060//26060 -f 26060//26060 25599//25599 25596//25596 -f 26060//26060 25596//25596 26061//26061 -f 26061//26061 25596//25596 25611//25611 -f 25585//25585 25582//25582 25860//25860 -f 25860//25860 25582//25582 25579//25579 -f 25860//25860 25579//25579 25843//25843 -f 25843//25843 25579//25579 25576//25576 -f 25843//25843 25576//25576 25864//25864 -f 25864//25864 25576//25576 25573//25573 -f 25864//25864 25573//25573 26047//26047 -f 26047//26047 25573//25573 25571//25571 -f 26047//26047 25571//25571 26046//26046 -f 25645//25645 25642//25642 26059//26059 -f 26059//26059 25642//25642 25639//25639 -f 26059//26059 25639//25639 26062//26062 -f 26062//26062 25639//25639 25636//25636 -f 26062//26062 25636//25636 25633//25633 -f 25571//25571 26063//26063 26046//26046 -f 26046//26046 26063//26063 26062//26062 -f 26046//26046 26062//26062 25631//25631 -f 25631//25631 26062//26062 25633//25633 -f 26053//26053 26039//26039 26064//26064 -f 26064//26064 26039//26039 26045//26045 -f 26064//26064 26045//26045 26065//26065 -f 26065//26065 26045//26045 25628//25628 -f 26065//26065 25628//25628 25625//25625 -f 25625//25625 25622//25622 26065//26065 -f 26065//26065 25622//25622 25619//25619 -f 26065//26065 25619//25619 26066//26066 -f 26066//26066 25619//25619 25616//25616 -f 26066//26066 25616//25616 26067//26067 -f 26067//26067 25616//25616 25631//25631 -f 25616//25616 25613//25613 25631//25631 -f 25631//25631 25613//25613 25611//25611 -f 25631//25631 25611//25611 26046//26046 -f 26046//26046 25611//25611 25593//25593 -f 26046//26046 25593//25593 25591//25591 -f 25589//25589 25588//25588 26068//26068 -f 26068//26068 25588//25588 26057//26057 -f 26068//26068 26057//26057 26069//26069 -f 26069//26069 26057//26057 26070//26070 -f 26070//26070 26057//26057 26058//26058 -f 26070//26070 26058//26058 26071//26071 -f 26071//26071 26058//26058 26072//26072 -f 26072//26072 26058//26058 26059//26059 -f 26072//26072 26059//26059 26073//26073 -f 26073//26073 26059//26059 26074//26074 -f 26074//26074 26059//26059 26062//26062 -f 26074//26074 26062//26062 26075//26075 -f 26075//26075 26062//26062 26076//26076 -f 26076//26076 26062//26062 26063//26063 -f 26076//26076 26063//26063 26077//26077 -f 26077//26077 26063//26063 26078//26078 -f 26078//26078 26063//26063 25571//25571 -f 26078//26078 25571//25571 25570//25570 -f 25609//25609 25608//25608 26079//26079 -f 26079//26079 25608//25608 26051//26051 -f 26079//26079 26051//26051 26080//26080 -f 26080//26080 26051//26051 26081//26081 -f 26081//26081 26051//26051 26050//26050 -f 26081//26081 26050//26050 26082//26082 -f 26082//26082 26050//26050 26083//26083 -f 26083//26083 26050//26050 26049//26049 -f 26083//26083 26049//26049 26084//26084 -f 26084//26084 26049//26049 26085//26085 -f 26085//26085 26049//26049 26048//26048 -f 26085//26085 26048//26048 26086//26086 -f 26086//26086 26048//26048 26087//26087 -f 26087//26087 26048//26048 26056//26056 -f 26087//26087 26056//26056 26088//26088 -f 26088//26088 26056//26056 26089//26089 -f 26089//26089 26056//26056 25591//25591 -f 26089//26089 25591//25591 25590//25590 -f 25629//25629 25628//25628 26090//26090 -f 26090//26090 25628//25628 26052//26052 -f 26090//26090 26052//26052 26091//26091 -f 26091//26091 26052//26052 26092//26092 -f 26092//26092 26052//26052 26054//26054 -f 26092//26092 26054//26054 26093//26093 -f 26093//26093 26054//26054 26094//26094 -f 26094//26094 26054//26054 26055//26055 -f 26094//26094 26055//26055 26095//26095 -f 26095//26095 26055//26055 26096//26096 -f 26096//26096 26055//26055 26060//26060 -f 26096//26096 26060//26060 26097//26097 -f 26097//26097 26060//26060 26098//26098 -f 26098//26098 26060//26060 26061//26061 -f 26098//26098 26061//26061 26099//26099 -f 26099//26099 26061//26061 26100//26100 -f 26100//26100 26061//26061 25611//25611 -f 26100//26100 25611//25611 25610//25610 -f 25649//25649 25648//25648 26101//26101 -f 26101//26101 25648//25648 26053//26053 -f 26101//26101 26053//26053 26102//26102 -f 26102//26102 26053//26053 26103//26103 -f 26103//26103 26053//26053 26064//26064 -f 26103//26103 26064//26064 26104//26104 -f 26104//26104 26064//26064 26105//26105 -f 26105//26105 26064//26064 26065//26065 -f 26105//26105 26065//26065 26106//26106 -f 26106//26106 26065//26065 26107//26107 -f 26107//26107 26065//26065 26066//26066 -f 26107//26107 26066//26066 26108//26108 -f 26108//26108 26066//26066 26109//26109 -f 26109//26109 26066//26066 26067//26067 -f 26109//26109 26067//26067 26110//26110 -f 26110//26110 26067//26067 26111//26111 -f 26111//26111 26067//26067 25631//25631 -f 26111//26111 25631//25631 25630//25630 -f 25673//25673 25666//25666 26112//26112 -f 25666//25666 25660//25660 26113//26113 -f 25660//25660 25589//25589 26068//26068 -f 25660//25660 26068//26068 26113//26113 -f 26113//26113 26068//26068 26069//26069 -f 26113//26113 26069//26069 26114//26114 -f 26069//26069 26070//26070 26114//26114 -f 26114//26114 26070//26070 26071//26071 -f 26114//26114 26071//26071 26115//26115 -f 26115//26115 26071//26071 26072//26072 -f 26115//26115 26072//26072 26116//26116 -f 26116//26116 26072//26072 26073//26073 -f 26073//26073 26074//26074 26116//26116 -f 26116//26116 26074//26074 26075//26075 -f 26116//26116 26075//26075 26117//26117 -f 26075//26075 26076//26076 26117//26117 -f 26117//26117 26076//26076 26077//26077 -f 26117//26117 26077//26077 26118//26118 -f 26077//26077 26078//26078 26118//26118 -f 26118//26118 26078//26078 25570//25570 -f 26118//26118 25570//25570 25653//25653 -f 25666//25666 26113//26113 26112//26112 -f 26112//26112 26113//26113 26114//26114 -f 26112//26112 26114//26114 26119//26119 -f 26119//26119 26114//26114 26115//26115 -f 26119//26119 26115//26115 26120//26120 -f 26120//26120 26115//26115 26116//26116 -f 26120//26120 26116//26116 26121//26121 -f 26121//26121 26116//26116 26117//26117 -f 26121//26121 26117//26117 26122//26122 -f 26122//26122 26117//26117 26118//26118 -f 26122//26122 26118//26118 26123//26123 -f 26123//26123 26118//26118 25653//25653 -f 26123//26123 25653//25653 25651//25651 -f 25673//25673 26112//26112 26124//26124 -f 26124//26124 26112//26112 26119//26119 -f 26124//26124 26119//26119 26125//26125 -f 26125//26125 26119//26119 26120//26120 -f 26125//26125 26120//26120 26126//26126 -f 26126//26126 26120//26120 26121//26121 -f 26126//26126 26121//26121 26127//26127 -f 26127//26127 26121//26121 26122//26122 -f 26127//26127 26122//26122 26128//26128 -f 26128//26128 26122//26122 26123//26123 -f 26128//26128 26123//26123 26129//26129 -f 26129//26129 26123//26123 25651//25651 -f 26129//26129 25651//25651 25650//25650 -f 25697//25697 25690//25690 26130//26130 -f 25690//25690 25684//25684 26131//26131 -f 25684//25684 25609//25609 26079//26079 -f 25684//25684 26079//26079 26131//26131 -f 26131//26131 26079//26079 26080//26080 -f 26131//26131 26080//26080 26132//26132 -f 26080//26080 26081//26081 26132//26132 -f 26132//26132 26081//26081 26082//26082 -f 26132//26132 26082//26082 26133//26133 -f 26133//26133 26082//26082 26083//26083 -f 26133//26133 26083//26083 26134//26134 -f 26134//26134 26083//26083 26084//26084 -f 26084//26084 26085//26085 26134//26134 -f 26134//26134 26085//26085 26086//26086 -f 26134//26134 26086//26086 26135//26135 -f 26086//26086 26087//26087 26135//26135 -f 26135//26135 26087//26087 26088//26088 -f 26135//26135 26088//26088 26136//26136 -f 26088//26088 26089//26089 26136//26136 -f 26136//26136 26089//26089 25590//25590 -f 26136//26136 25590//25590 25677//25677 -f 25690//25690 26131//26131 26130//26130 -f 26130//26130 26131//26131 26132//26132 -f 26130//26130 26132//26132 26137//26137 -f 26137//26137 26132//26132 26133//26133 -f 26137//26137 26133//26133 26138//26138 -f 26138//26138 26133//26133 26134//26134 -f 26138//26138 26134//26134 26139//26139 -f 26139//26139 26134//26134 26135//26135 -f 26139//26139 26135//26135 26140//26140 -f 26140//26140 26135//26135 26136//26136 -f 26140//26140 26136//26136 26141//26141 -f 26141//26141 26136//26136 25677//25677 -f 26141//26141 25677//25677 25675//25675 -f 25697//25697 26130//26130 26142//26142 -f 26142//26142 26130//26130 26137//26137 -f 26142//26142 26137//26137 26143//26143 -f 26143//26143 26137//26137 26138//26138 -f 26143//26143 26138//26138 26144//26144 -f 26144//26144 26138//26138 26139//26139 -f 26144//26144 26139//26139 26145//26145 -f 26145//26145 26139//26139 26140//26140 -f 26145//26145 26140//26140 26146//26146 -f 26146//26146 26140//26140 26141//26141 -f 26146//26146 26141//26141 26147//26147 -f 26147//26147 26141//26141 25675//25675 -f 26147//26147 25675//25675 25674//25674 -f 25721//25721 25714//25714 26148//26148 -f 25714//25714 25708//25708 26149//26149 -f 25708//25708 25629//25629 26090//26090 -f 25708//25708 26090//26090 26149//26149 -f 26149//26149 26090//26090 26091//26091 -f 26149//26149 26091//26091 26150//26150 -f 26091//26091 26092//26092 26150//26150 -f 26150//26150 26092//26092 26093//26093 -f 26150//26150 26093//26093 26151//26151 -f 26151//26151 26093//26093 26094//26094 -f 26151//26151 26094//26094 26152//26152 -f 26152//26152 26094//26094 26095//26095 -f 26095//26095 26096//26096 26152//26152 -f 26152//26152 26096//26096 26097//26097 -f 26152//26152 26097//26097 26153//26153 -f 26097//26097 26098//26098 26153//26153 -f 26153//26153 26098//26098 26099//26099 -f 26153//26153 26099//26099 26154//26154 -f 26099//26099 26100//26100 26154//26154 -f 26154//26154 26100//26100 25610//25610 -f 26154//26154 25610//25610 25701//25701 -f 25714//25714 26149//26149 26148//26148 -f 26148//26148 26149//26149 26150//26150 -f 26148//26148 26150//26150 26155//26155 -f 26155//26155 26150//26150 26151//26151 -f 26155//26155 26151//26151 26156//26156 -f 26156//26156 26151//26151 26152//26152 -f 26156//26156 26152//26152 26157//26157 -f 26157//26157 26152//26152 26153//26153 -f 26157//26157 26153//26153 26158//26158 -f 26158//26158 26153//26153 26154//26154 -f 26158//26158 26154//26154 26159//26159 -f 26159//26159 26154//26154 25701//25701 -f 26159//26159 25701//25701 25699//25699 -f 25721//25721 26148//26148 26160//26160 -f 26160//26160 26148//26148 26155//26155 -f 26160//26160 26155//26155 26161//26161 -f 26161//26161 26155//26155 26156//26156 -f 26161//26161 26156//26156 26162//26162 -f 26162//26162 26156//26156 26157//26157 -f 26162//26162 26157//26157 26163//26163 -f 26163//26163 26157//26157 26158//26158 -f 26163//26163 26158//26158 26164//26164 -f 26164//26164 26158//26158 26159//26159 -f 26164//26164 26159//26159 26165//26165 -f 26165//26165 26159//26159 25699//25699 -f 26165//26165 25699//25699 25698//25698 -f 25745//25745 25738//25738 26166//26166 -f 25738//25738 25732//25732 26167//26167 -f 25732//25732 25649//25649 26101//26101 -f 25732//25732 26101//26101 26167//26167 -f 26167//26167 26101//26101 26102//26102 -f 26167//26167 26102//26102 26168//26168 -f 26102//26102 26103//26103 26168//26168 -f 26168//26168 26103//26103 26104//26104 -f 26168//26168 26104//26104 26169//26169 -f 26104//26104 26105//26105 26169//26169 -f 26169//26169 26105//26105 26106//26106 -f 26169//26169 26106//26106 26170//26170 -f 26106//26106 26107//26107 26170//26170 -f 26170//26170 26107//26107 26108//26108 -f 26170//26170 26108//26108 26171//26171 -f 26108//26108 26109//26109 26171//26171 -f 26171//26171 26109//26109 26110//26110 -f 26171//26171 26110//26110 26172//26172 -f 26110//26110 26111//26111 26172//26172 -f 26172//26172 26111//26111 25630//25630 -f 26172//26172 25630//25630 25725//25725 -f 25738//25738 26167//26167 26166//26166 -f 26166//26166 26167//26167 26168//26168 -f 26166//26166 26168//26168 26173//26173 -f 26173//26173 26168//26168 26169//26169 -f 26173//26173 26169//26169 26174//26174 -f 26174//26174 26169//26169 26170//26170 -f 26174//26174 26170//26170 26175//26175 -f 26175//26175 26170//26170 26171//26171 -f 26175//26175 26171//26171 26176//26176 -f 26176//26176 26171//26171 26172//26172 -f 26176//26176 26172//26172 26177//26177 -f 26177//26177 26172//26172 25725//25725 -f 26177//26177 25725//25725 25723//25723 -f 25745//25745 26166//26166 26178//26178 -f 26178//26178 26166//26166 26173//26173 -f 26178//26178 26173//26173 26179//26179 -f 26179//26179 26173//26173 26174//26174 -f 26179//26179 26174//26174 26180//26180 -f 26180//26180 26174//26174 26175//26175 -f 26180//26180 26175//26175 26181//26181 -f 26181//26181 26175//26175 26176//26176 -f 26181//26181 26176//26176 26182//26182 -f 26182//26182 26176//26176 26177//26177 -f 26182//26182 26177//26177 26183//26183 -f 26183//26183 26177//26177 25723//25723 -f 26183//26183 25723//25723 25722//25722 -f 25650//25650 25667//25667 25672//25672 -f 25650//25650 25672//25672 26129//26129 -f 26129//26129 25672//25672 25673//25673 -f 26129//26129 25673//25673 26124//26124 -f 25670//25670 25671//25671 25669//25669 -f 25669//25669 25671//25671 25672//25672 -f 25669//25669 25672//25672 25668//25668 -f 25668//25668 25672//25672 25667//25667 -f 26127//26127 26128//26128 26126//26126 -f 26126//26126 26128//26128 26129//26129 -f 26126//26126 26129//26129 26125//26125 -f 26125//26125 26129//26129 26124//26124 -f 25674//25674 25691//25691 25696//25696 -f 25674//25674 25696//25696 26147//26147 -f 26147//26147 25696//25696 25697//25697 -f 26147//26147 25697//25697 26142//26142 -f 25694//25694 25695//25695 25693//25693 -f 25693//25693 25695//25695 25696//25696 -f 25693//25693 25696//25696 25692//25692 -f 25692//25692 25696//25696 25691//25691 -f 26145//26145 26146//26146 26144//26144 -f 26144//26144 26146//26146 26147//26147 -f 26144//26144 26147//26147 26143//26143 -f 26143//26143 26147//26147 26142//26142 -f 26165//26165 25698//25698 25715//25715 -f 26165//26165 25715//25715 26160//26160 -f 26160//26160 25715//25715 25720//25720 -f 26160//26160 25720//25720 25721//25721 -f 26163//26163 26164//26164 26162//26162 -f 26162//26162 26164//26164 26165//26165 -f 26162//26162 26165//26165 26161//26161 -f 26161//26161 26165//26165 26160//26160 -f 25718//25718 25719//25719 25717//25717 -f 25717//25717 25719//25719 25720//25720 -f 25717//25717 25720//25720 25716//25716 -f 25716//25716 25720//25720 25715//25715 -f 26183//26183 25722//25722 25739//25739 -f 26183//26183 25739//25739 26178//26178 -f 26178//26178 25739//25739 25744//25744 -f 26178//26178 25744//25744 25745//25745 -f 26181//26181 26182//26182 26180//26180 -f 26180//26180 26182//26182 26183//26183 -f 26180//26180 26183//26183 26179//26179 -f 26179//26179 26183//26183 26178//26178 -f 25742//25742 25743//25743 25741//25741 -f 25741//25741 25743//25743 25744//25744 -f 25741//25741 25744//25744 25740//25740 -f 25740//25740 25744//25744 25739//25739 -f 26184//26184 26185//26185 26186//26186 -f 26184//26184 26186//26186 26187//26187 -f 26187//26187 26186//26186 26188//26188 -f 26187//26187 26188//26188 26189//26189 -f 26189//26189 26188//26188 26190//26190 -f 26189//26189 26190//26190 26191//26191 -f 26191//26191 26190//26190 26192//26192 -f 26191//26191 26192//26192 26193//26193 -f 26193//26193 26192//26192 26194//26194 -f 26193//26193 26194//26194 26195//26195 -f 26195//26195 26194//26194 26196//26196 -f 26195//26195 26196//26196 26197//26197 -f 26197//26197 26196//26196 26198//26198 -f 26197//26197 26198//26198 26199//26199 -f 26199//26199 26198//26198 26200//26200 -f 26199//26199 26200//26200 26201//26201 -f 26201//26201 26200//26200 26202//26202 -f 26201//26201 26202//26202 26203//26203 -f 26203//26203 26202//26202 26204//26204 -f 26203//26203 26204//26204 26205//26205 -f 26205//26205 26204//26204 26206//26206 -f 26205//26205 26206//26206 26207//26207 -f 26207//26207 26206//26206 26208//26208 -f 26207//26207 26208//26208 26209//26209 -f 26209//26209 26208//26208 26210//26210 -f 26209//26209 26210//26210 26211//26211 -f 26211//26211 26210//26210 26212//26212 -f 26211//26211 26212//26212 26213//26213 -f 26213//26213 26212//26212 26214//26214 -f 26213//26213 26214//26214 26215//26215 -f 26215//26215 26214//26214 26216//26216 -f 26215//26215 26216//26216 26217//26217 -f 26217//26217 26216//26216 26218//26218 -f 26217//26217 26218//26218 26219//26219 -f 26219//26219 26218//26218 26220//26220 -f 26219//26219 26220//26220 26221//26221 -f 26221//26221 26220//26220 26222//26222 -f 26221//26221 26222//26222 26223//26223 -f 26223//26223 26222//26222 26224//26224 -f 26223//26223 26224//26224 26225//26225 -f 26226//26226 26227//26227 26228//26228 -f 26228//26228 26227//26227 26229//26229 -f 26228//26228 26229//26229 26230//26230 -f 26230//26230 26229//26229 26231//26231 -f 26230//26230 26231//26231 26232//26232 -f 26232//26232 26231//26231 26233//26233 -f 26232//26232 26233//26233 26234//26234 -f 26234//26234 26233//26233 26235//26235 -f 26234//26234 26235//26235 26236//26236 -f 26236//26236 26235//26235 26237//26237 -f 26236//26236 26237//26237 26238//26238 -f 26238//26238 26237//26237 26239//26239 -f 26240//26240 26241//26241 26242//26242 -f 26242//26242 26241//26241 26243//26243 -f 26242//26242 26243//26243 26244//26244 -f 26244//26244 26243//26243 26245//26245 -f 26244//26244 26245//26245 26246//26246 -f 26246//26246 26245//26245 26247//26247 -f 26246//26246 26247//26247 26248//26248 -f 26248//26248 26247//26247 26249//26249 -f 26248//26248 26249//26249 26250//26250 -f 26250//26250 26249//26249 26251//26251 -f 26250//26250 26251//26251 26252//26252 -f 26252//26252 26251//26251 26253//26253 -f 26254//26254 26255//26255 26256//26256 -f 26256//26256 26255//26255 26257//26257 -f 26256//26256 26257//26257 26258//26258 -f 26258//26258 26257//26257 26259//26259 -f 26258//26258 26259//26259 26260//26260 -f 26260//26260 26259//26259 26261//26261 -f 26260//26260 26261//26261 26262//26262 -f 26262//26262 26261//26261 26263//26263 -f 26262//26262 26263//26263 26264//26264 -f 26264//26264 26263//26263 26265//26265 -f 26264//26264 26265//26265 26266//26266 -f 26266//26266 26265//26265 26267//26267 -f 26268//26268 26269//26269 26270//26270 -f 26270//26270 26269//26269 26271//26271 -f 26270//26270 26271//26271 26272//26272 -f 26272//26272 26271//26271 26273//26273 -f 26272//26272 26273//26273 26274//26274 -f 26274//26274 26273//26273 26275//26275 -f 26274//26274 26275//26275 26276//26276 -f 26276//26276 26275//26275 26277//26277 -f 26276//26276 26277//26277 26278//26278 -f 26278//26278 26277//26277 26279//26279 -f 26278//26278 26279//26279 26280//26280 -f 26280//26280 26279//26279 26281//26281 -f 26282//26282 26283//26283 26284//26284 -f 26284//26284 26283//26283 26285//26285 -f 26284//26284 26285//26285 26286//26286 -f 26286//26286 26285//26285 26287//26287 -f 26286//26286 26287//26287 26288//26288 -f 26288//26288 26287//26287 26289//26289 -f 26288//26288 26289//26289 26290//26290 -f 26290//26290 26289//26289 26291//26291 -f 26290//26290 26291//26291 26292//26292 -f 26292//26292 26291//26291 26293//26293 -f 26292//26292 26293//26293 26294//26294 -f 26294//26294 26293//26293 26295//26295 -f 26296//26296 26297//26297 26298//26298 -f 26298//26298 26297//26297 26299//26299 -f 26298//26298 26299//26299 26300//26300 -f 26300//26300 26299//26299 26301//26301 -f 26300//26300 26301//26301 26302//26302 -f 26302//26302 26301//26301 26303//26303 -f 26302//26302 26303//26303 26304//26304 -f 26304//26304 26303//26303 26305//26305 -f 26304//26304 26305//26305 26306//26306 -f 26306//26306 26305//26305 26307//26307 -f 26306//26306 26307//26307 26308//26308 -f 26308//26308 26307//26307 26309//26309 -f 26310//26310 26311//26311 26312//26312 -f 26312//26312 26311//26311 26313//26313 -f 26312//26312 26313//26313 26314//26314 -f 26314//26314 26313//26313 26315//26315 -f 26314//26314 26315//26315 26316//26316 -f 26316//26316 26315//26315 26317//26317 -f 26316//26316 26317//26317 26318//26318 -f 26318//26318 26317//26317 26319//26319 -f 26318//26318 26319//26319 26320//26320 -f 26320//26320 26319//26319 26321//26321 -f 26320//26320 26321//26321 26322//26322 -f 26322//26322 26321//26321 26323//26323 -f 26322//26322 26323//26323 26324//26324 -f 26324//26324 26323//26323 26325//26325 -f 26324//26324 26325//26325 26326//26326 -f 26326//26326 26325//26325 26327//26327 -f 26326//26326 26327//26327 26328//26328 -f 26328//26328 26327//26327 26329//26329 -f 26328//26328 26329//26329 26330//26330 -f 26330//26330 26329//26329 26331//26331 -f 26330//26330 26331//26331 26332//26332 -f 26332//26332 26331//26331 26333//26333 -f 26332//26332 26333//26333 26334//26334 -f 26334//26334 26333//26333 26335//26335 -f 26334//26334 26335//26335 26336//26336 -f 26336//26336 26335//26335 26337//26337 -f 26336//26336 26337//26337 26338//26338 -f 26338//26338 26337//26337 26339//26339 -f 26338//26338 26339//26339 26340//26340 -f 26340//26340 26339//26339 26341//26341 -f 26340//26340 26341//26341 26342//26342 -f 26342//26342 26341//26341 26343//26343 -f 26342//26342 26343//26343 26344//26344 -f 26344//26344 26343//26343 26345//26345 -f 26344//26344 26345//26345 26346//26346 -f 26346//26346 26345//26345 26347//26347 -f 26346//26346 26347//26347 26348//26348 -f 26348//26348 26347//26347 26349//26349 -f 26348//26348 26349//26349 26310//26310 -f 26310//26310 26349//26349 26311//26311 -f 26308//26308 26309//26309 26350//26350 -f 26350//26350 26309//26309 26351//26351 -f 26350//26350 26351//26351 26352//26352 -f 26352//26352 26351//26351 26353//26353 -f 26352//26352 26353//26353 26354//26354 -f 26354//26354 26353//26353 26355//26355 -f 26354//26354 26355//26355 26356//26356 -f 26356//26356 26355//26355 26357//26357 -f 26356//26356 26357//26357 26358//26358 -f 26358//26358 26357//26357 26359//26359 -f 26358//26358 26359//26359 26296//26296 -f 26296//26296 26359//26359 26297//26297 -f 26294//26294 26295//26295 26360//26360 -f 26360//26360 26295//26295 26361//26361 -f 26360//26360 26361//26361 26362//26362 -f 26362//26362 26361//26361 26363//26363 -f 26362//26362 26363//26363 26364//26364 -f 26364//26364 26363//26363 26365//26365 -f 26364//26364 26365//26365 26366//26366 -f 26366//26366 26365//26365 26367//26367 -f 26366//26366 26367//26367 26368//26368 -f 26368//26368 26367//26367 26369//26369 -f 26368//26368 26369//26369 26282//26282 -f 26282//26282 26369//26369 26283//26283 -f 26280//26280 26281//26281 26370//26370 -f 26370//26370 26281//26281 26371//26371 -f 26370//26370 26371//26371 26372//26372 -f 26372//26372 26371//26371 26373//26373 -f 26372//26372 26373//26373 26374//26374 -f 26374//26374 26373//26373 26375//26375 -f 26374//26374 26375//26375 26376//26376 -f 26376//26376 26375//26375 26377//26377 -f 26376//26376 26377//26377 26378//26378 -f 26378//26378 26377//26377 26379//26379 -f 26378//26378 26379//26379 26268//26268 -f 26268//26268 26379//26379 26269//26269 -f 26266//26266 26267//26267 26380//26380 -f 26380//26380 26267//26267 26381//26381 -f 26380//26380 26381//26381 26382//26382 -f 26382//26382 26381//26381 26383//26383 -f 26382//26382 26383//26383 26384//26384 -f 26384//26384 26383//26383 26385//26385 -f 26384//26384 26385//26385 26386//26386 -f 26386//26386 26385//26385 26387//26387 -f 26386//26386 26387//26387 26388//26388 -f 26388//26388 26387//26387 26389//26389 -f 26388//26388 26389//26389 26254//26254 -f 26254//26254 26389//26389 26255//26255 -f 26252//26252 26253//26253 26390//26390 -f 26390//26390 26253//26253 26391//26391 -f 26390//26390 26391//26391 26392//26392 -f 26392//26392 26391//26391 26393//26393 -f 26392//26392 26393//26393 26394//26394 -f 26394//26394 26393//26393 26395//26395 -f 26394//26394 26395//26395 26396//26396 -f 26396//26396 26395//26395 26397//26397 -f 26396//26396 26397//26397 26398//26398 -f 26398//26398 26397//26397 26399//26399 -f 26398//26398 26399//26399 26240//26240 -f 26240//26240 26399//26399 26241//26241 -f 26238//26238 26239//26239 26400//26400 -f 26400//26400 26239//26239 26401//26401 -f 26400//26400 26401//26401 26402//26402 -f 26402//26402 26401//26401 26403//26403 -f 26402//26402 26403//26403 26404//26404 -f 26404//26404 26403//26403 26405//26405 -f 26404//26404 26405//26405 26406//26406 -f 26406//26406 26405//26405 26407//26407 -f 26406//26406 26407//26407 26408//26408 -f 26408//26408 26407//26407 26409//26409 -f 26408//26408 26409//26409 26226//26226 -f 26226//26226 26409//26409 26227//26227 -f 26225//26225 26224//26224 26410//26410 -f 26225//26225 26410//26410 26411//26411 -f 26411//26411 26410//26410 26412//26412 -f 26411//26411 26412//26412 26413//26413 -f 26413//26413 26412//26412 26414//26414 -f 26413//26413 26414//26414 26415//26415 -f 26415//26415 26414//26414 26416//26416 -f 26415//26415 26416//26416 26417//26417 -f 26417//26417 26416//26416 26418//26418 -f 26417//26417 26418//26418 26419//26419 -f 26419//26419 26418//26418 26420//26420 -f 26419//26419 26420//26420 26421//26421 -f 26421//26421 26420//26420 26422//26422 -f 26421//26421 26422//26422 26423//26423 -f 26423//26423 26422//26422 26424//26424 -f 26423//26423 26424//26424 26425//26425 -f 26425//26425 26424//26424 26426//26426 -f 26425//26425 26426//26426 26427//26427 -f 26427//26427 26426//26426 26428//26428 -f 26427//26427 26428//26428 26429//26429 -f 26429//26429 26428//26428 26430//26430 -f 26429//26429 26430//26430 26431//26431 -f 26431//26431 26430//26430 26432//26432 -f 26431//26431 26432//26432 26433//26433 -f 26433//26433 26432//26432 26434//26434 -f 26433//26433 26434//26434 26435//26435 -f 26435//26435 26434//26434 26436//26436 -f 26435//26435 26436//26436 26437//26437 -f 26437//26437 26436//26436 26438//26438 -f 26437//26437 26438//26438 26439//26439 -f 26439//26439 26438//26438 26440//26440 -f 26439//26439 26440//26440 26441//26441 -f 26441//26441 26440//26440 26442//26442 -f 26441//26441 26442//26442 26443//26443 -f 26443//26443 26442//26442 26444//26444 -f 26443//26443 26444//26444 26445//26445 -f 26445//26445 26444//26444 26446//26446 -f 26445//26445 26446//26446 26447//26447 -f 26447//26447 26446//26446 26185//26185 -f 26447//26447 26185//26185 26184//26184 -f 26437//26437 26448//26448 26435//26435 -f 26332//26332 26334//26334 26449//26449 -f 26344//26344 26346//26346 26450//26450 -f 26450//26450 26346//26346 26348//26348 -f 26451//26451 26310//26310 26312//26312 -f 26449//26449 26334//26334 26452//26452 -f 26334//26334 26336//26336 26452//26452 -f 26452//26452 26336//26336 26338//26338 -f 26452//26452 26338//26338 26453//26453 -f 26453//26453 26338//26338 26340//26340 -f 26453//26453 26340//26340 26342//26342 -f 26332//26332 26449//26449 26330//26330 -f 26330//26330 26449//26449 26454//26454 -f 26330//26330 26454//26454 26328//26328 -f 26455//26455 26324//26324 26454//26454 -f 26454//26454 26324//26324 26326//26326 -f 26454//26454 26326//26326 26328//26328 -f 26314//26314 26316//26316 26456//26456 -f 26316//26316 26318//26318 26456//26456 -f 26456//26456 26318//26318 26320//26320 -f 26456//26456 26320//26320 26455//26455 -f 26455//26455 26320//26320 26322//26322 -f 26455//26455 26322//26322 26324//26324 -f 26270//26270 26457//26457 26268//26268 -f 26268//26268 26457//26457 26458//26458 -f 26268//26268 26458//26458 26378//26378 -f 26378//26378 26458//26458 26376//26376 -f 26272//26272 26274//26274 26413//26413 -f 26413//26413 26274//26274 26276//26276 -f 26413//26413 26276//26276 26411//26411 -f 26411//26411 26276//26276 26278//26278 -f 26411//26411 26278//26278 26225//26225 -f 26225//26225 26278//26278 26280//26280 -f 26225//26225 26280//26280 26223//26223 -f 26223//26223 26280//26280 26370//26370 -f 26223//26223 26370//26370 26221//26221 -f 26221//26221 26370//26370 26372//26372 -f 26221//26221 26372//26372 26374//26374 -f 26217//26217 26459//26459 26215//26215 -f 26215//26215 26459//26459 26213//26213 -f 26217//26217 26219//26219 26459//26459 -f 26459//26459 26219//26219 26221//26221 -f 26459//26459 26221//26221 26458//26458 -f 26458//26458 26221//26221 26374//26374 -f 26458//26458 26374//26374 26376//26376 -f 26254//26254 26256//26256 26452//26452 -f 26452//26452 26256//26256 26258//26258 -f 26452//26452 26258//26258 26260//26260 -f 26260//26260 26262//26262 26459//26459 -f 26459//26459 26262//26262 26264//26264 -f 26459//26459 26264//26264 26213//26213 -f 26264//26264 26266//26266 26213//26213 -f 26213//26213 26266//26266 26380//26380 -f 26213//26213 26380//26380 26211//26211 -f 26211//26211 26380//26380 26382//26382 -f 26211//26211 26382//26382 26209//26209 -f 26209//26209 26382//26382 26384//26384 -f 26209//26209 26384//26384 26207//26207 -f 26207//26207 26384//26384 26386//26386 -f 26207//26207 26386//26386 26388//26388 -f 26388//26388 26254//26254 26207//26207 -f 26207//26207 26254//26254 26452//26452 -f 26207//26207 26452//26452 26205//26205 -f 26205//26205 26452//26452 26453//26453 -f 26460//26460 26197//26197 26240//26240 -f 26453//26453 26248//26248 26250//26250 -f 26240//26240 26242//26242 26460//26460 -f 26460//26460 26242//26242 26244//26244 -f 26460//26460 26244//26244 26453//26453 -f 26453//26453 26244//26244 26246//26246 -f 26453//26453 26246//26246 26248//26248 -f 26250//26250 26252//26252 26453//26453 -f 26453//26453 26252//26252 26203//26203 -f 26453//26453 26203//26203 26205//26205 -f 26252//26252 26390//26390 26203//26203 -f 26203//26203 26390//26390 26392//26392 -f 26203//26203 26392//26392 26201//26201 -f 26201//26201 26392//26392 26394//26394 -f 26201//26201 26394//26394 26199//26199 -f 26199//26199 26394//26394 26396//26396 -f 26199//26199 26396//26396 26197//26197 -f 26197//26197 26396//26396 26398//26398 -f 26197//26197 26398//26398 26240//26240 -f 26191//26191 26193//26193 26460//26460 -f 26460//26460 26193//26193 26195//26195 -f 26460//26460 26195//26195 26197//26197 -f 26191//26191 26461//26461 26189//26189 -f 26189//26189 26461//26461 26462//26462 -f 26189//26189 26462//26462 26187//26187 -f 26187//26187 26462//26462 26184//26184 -f 26184//26184 26462//26462 26463//26463 -f 26184//26184 26463//26463 26447//26447 -f 26448//26448 26437//26437 26464//26464 -f 26437//26437 26439//26439 26464//26464 -f 26464//26464 26439//26439 26441//26441 -f 26464//26464 26441//26441 26465//26465 -f 26465//26465 26441//26441 26443//26443 -f 26465//26465 26443//26443 26445//26445 -f 26433//26433 26466//26466 26431//26431 -f 26431//26431 26466//26466 26429//26429 -f 26429//26429 26466//26466 26427//26427 -f 26427//26427 26466//26466 26467//26467 -f 26427//26427 26467//26467 26425//26425 -f 26425//26425 26467//26467 26468//26468 -f 26425//26425 26468//26468 26423//26423 -f 26270//26270 26272//26272 26457//26457 -f 26457//26457 26272//26272 26413//26413 -f 26457//26457 26413//26413 26469//26469 -f 26469//26469 26413//26413 26415//26415 -f 26415//26415 26417//26417 26469//26469 -f 26469//26469 26417//26417 26419//26419 -f 26469//26469 26419//26419 26468//26468 -f 26468//26468 26419//26419 26421//26421 -f 26468//26468 26421//26421 26423//26423 -f 26282//26282 26284//26284 26467//26467 -f 26284//26284 26286//26286 26467//26467 -f 26467//26467 26286//26286 26288//26288 -f 26467//26467 26288//26288 26468//26468 -f 26468//26468 26288//26288 26290//26290 -f 26364//26364 26366//26366 26455//26455 -f 26455//26455 26366//26366 26368//26368 -f 26290//26290 26292//26292 26468//26468 -f 26468//26468 26292//26292 26294//26294 -f 26468//26468 26294//26294 26469//26469 -f 26469//26469 26294//26294 26360//26360 -f 26469//26469 26360//26360 26362//26362 -f 26260//26260 26459//26459 26452//26452 -f 26452//26452 26459//26459 26458//26458 -f 26452//26452 26458//26458 26449//26449 -f 26449//26449 26458//26458 26457//26457 -f 26449//26449 26457//26457 26454//26454 -f 26454//26454 26457//26457 26469//26469 -f 26454//26454 26469//26469 26455//26455 -f 26455//26455 26469//26469 26362//26362 -f 26455//26455 26362//26362 26364//26364 -f 26342//26342 26344//26344 26453//26453 -f 26453//26453 26344//26344 26450//26450 -f 26453//26453 26450//26450 26460//26460 -f 26460//26460 26450//26450 26470//26470 -f 26456//26456 26308//26308 26350//26350 -f 26298//26298 26300//26300 26448//26448 -f 26448//26448 26300//26300 26466//26466 -f 26448//26448 26466//26466 26435//26435 -f 26435//26435 26466//26466 26433//26433 -f 26300//26300 26302//26302 26466//26466 -f 26466//26466 26302//26302 26304//26304 -f 26466//26466 26304//26304 26306//26306 -f 26298//26298 26448//26448 26296//26296 -f 26296//26296 26448//26448 26464//26464 -f 26296//26296 26464//26464 26358//26358 -f 26368//26368 26282//26282 26455//26455 -f 26455//26455 26282//26282 26467//26467 -f 26455//26455 26467//26467 26456//26456 -f 26456//26456 26467//26467 26466//26466 -f 26456//26456 26466//26466 26308//26308 -f 26308//26308 26466//26466 26306//26306 -f 26350//26350 26352//26352 26456//26456 -f 26456//26456 26352//26352 26354//26354 -f 26456//26456 26354//26354 26464//26464 -f 26464//26464 26354//26354 26356//26356 -f 26464//26464 26356//26356 26358//26358 -f 26463//26463 26226//26226 26228//26228 -f 26238//26238 26400//26400 26470//26470 -f 26470//26470 26400//26400 26402//26402 -f 26470//26470 26402//26402 26404//26404 -f 26226//26226 26463//26463 26408//26408 -f 26408//26408 26463//26463 26462//26462 -f 26408//26408 26462//26462 26406//26406 -f 26228//26228 26230//26230 26463//26463 -f 26463//26463 26230//26230 26232//26232 -f 26463//26463 26232//26232 26471//26471 -f 26471//26471 26232//26232 26234//26234 -f 26471//26471 26234//26234 26236//26236 -f 26236//26236 26238//26238 26471//26471 -f 26471//26471 26238//26238 26470//26470 -f 26471//26471 26470//26470 26451//26451 -f 26451//26451 26470//26470 26450//26450 -f 26451//26451 26450//26450 26310//26310 -f 26310//26310 26450//26450 26348//26348 -f 26191//26191 26460//26460 26461//26461 -f 26461//26461 26460//26460 26470//26470 -f 26461//26461 26470//26470 26462//26462 -f 26462//26462 26470//26470 26404//26404 -f 26462//26462 26404//26404 26406//26406 -f 26312//26312 26314//26314 26451//26451 -f 26451//26451 26314//26314 26456//26456 -f 26451//26451 26456//26456 26471//26471 -f 26471//26471 26456//26456 26464//26464 -f 26471//26471 26464//26464 26463//26463 -f 26463//26463 26464//26464 26465//26465 -f 26463//26463 26465//26465 26447//26447 -f 26447//26447 26465//26465 26445//26445 -f 26472//26472 26473//26473 26474//26474 -f 26475//26475 26476//26476 26477//26477 -f 26412//26412 26478//26478 26479//26479 -f 26192//26192 26190//26190 26480//26480 -f 26481//26481 26482//26482 26331//26331 -f 26331//26331 26482//26482 26333//26333 -f 26345//26345 26483//26483 26347//26347 -f 26347//26347 26483//26483 26484//26484 -f 26347//26347 26484//26484 26349//26349 -f 26485//26485 26337//26337 26482//26482 -f 26482//26482 26337//26337 26335//26335 -f 26482//26482 26335//26335 26333//26333 -f 26345//26345 26343//26343 26483//26483 -f 26483//26483 26343//26343 26341//26341 -f 26483//26483 26341//26341 26485//26485 -f 26485//26485 26341//26341 26339//26339 -f 26485//26485 26339//26339 26337//26337 -f 26349//26349 26484//26484 26311//26311 -f 26311//26311 26484//26484 26486//26486 -f 26311//26311 26486//26486 26313//26313 -f 26331//26331 26329//26329 26481//26481 -f 26481//26481 26329//26329 26327//26327 -f 26481//26481 26327//26327 26487//26487 -f 26487//26487 26327//26327 26325//26325 -f 26487//26487 26325//26325 26323//26323 -f 26321//26321 26319//26319 26472//26472 -f 26472//26472 26319//26319 26317//26317 -f 26472//26472 26317//26317 26486//26486 -f 26486//26486 26317//26317 26315//26315 -f 26486//26486 26315//26315 26313//26313 -f 26186//26186 26185//26185 26475//26475 -f 26190//26190 26188//26188 26480//26480 -f 26480//26480 26188//26188 26186//26186 -f 26480//26480 26186//26186 26488//26488 -f 26488//26488 26186//26186 26475//26475 -f 26489//26489 26196//26196 26194//26194 -f 26251//26251 26249//26249 26483//26483 -f 26251//26251 26483//26483 26253//26253 -f 26247//26247 26245//26245 26489//26489 -f 26489//26489 26245//26245 26243//26243 -f 26489//26489 26243//26243 26196//26196 -f 26243//26243 26241//26241 26196//26196 -f 26196//26196 26241//26241 26399//26399 -f 26196//26196 26399//26399 26198//26198 -f 26198//26198 26399//26399 26397//26397 -f 26198//26198 26397//26397 26200//26200 -f 26200//26200 26397//26397 26395//26395 -f 26200//26200 26395//26395 26202//26202 -f 26202//26202 26395//26395 26393//26393 -f 26202//26202 26393//26393 26391//26391 -f 26391//26391 26253//26253 26202//26202 -f 26202//26202 26253//26253 26483//26483 -f 26202//26202 26483//26483 26204//26204 -f 26204//26204 26483//26483 26485//26485 -f 26257//26257 26255//26255 26485//26485 -f 26485//26485 26255//26255 26206//26206 -f 26485//26485 26206//26206 26204//26204 -f 26267//26267 26265//26265 26490//26490 -f 26263//26263 26261//26261 26485//26485 -f 26485//26485 26261//26261 26259//26259 -f 26485//26485 26259//26259 26257//26257 -f 26255//26255 26389//26389 26206//26206 -f 26206//26206 26389//26389 26387//26387 -f 26206//26206 26387//26387 26208//26208 -f 26208//26208 26387//26387 26385//26385 -f 26208//26208 26385//26385 26210//26210 -f 26210//26210 26385//26385 26383//26383 -f 26210//26210 26383//26383 26212//26212 -f 26212//26212 26383//26383 26381//26381 -f 26381//26381 26267//26267 26212//26212 -f 26212//26212 26267//26267 26490//26490 -f 26212//26212 26490//26490 26214//26214 -f 26214//26214 26490//26490 26216//26216 -f 26379//26379 26491//26491 26269//26269 -f 26269//26269 26491//26491 26478//26478 -f 26269//26269 26478//26478 26271//26271 -f 26379//26379 26377//26377 26491//26491 -f 26491//26491 26377//26377 26220//26220 -f 26491//26491 26220//26220 26490//26490 -f 26490//26490 26220//26220 26218//26218 -f 26490//26490 26218//26218 26216//26216 -f 26412//26412 26275//26275 26478//26478 -f 26478//26478 26275//26275 26273//26273 -f 26478//26478 26273//26273 26271//26271 -f 26377//26377 26375//26375 26220//26220 -f 26220//26220 26375//26375 26373//26373 -f 26220//26220 26373//26373 26222//26222 -f 26222//26222 26373//26373 26371//26371 -f 26222//26222 26371//26371 26224//26224 -f 26224//26224 26371//26371 26281//26281 -f 26224//26224 26281//26281 26410//26410 -f 26410//26410 26281//26281 26279//26279 -f 26410//26410 26279//26279 26412//26412 -f 26412//26412 26279//26279 26277//26277 -f 26412//26412 26277//26277 26275//26275 -f 26492//26492 26420//26420 26479//26479 -f 26479//26479 26420//26420 26418//26418 -f 26418//26418 26416//26416 26479//26479 -f 26479//26479 26416//26416 26414//26414 -f 26479//26479 26414//26414 26412//26412 -f 26474//26474 26424//26424 26422//26422 -f 26432//26432 26430//26430 26473//26473 -f 26473//26473 26430//26430 26428//26428 -f 26473//26473 26428//26428 26474//26474 -f 26474//26474 26428//26428 26426//26426 -f 26474//26474 26426//26426 26424//26424 -f 26493//26493 26434//26434 26432//26432 -f 26477//26477 26438//26438 26493//26493 -f 26493//26493 26438//26438 26436//26436 -f 26493//26493 26436//26436 26434//26434 -f 26185//26185 26446//26446 26475//26475 -f 26475//26475 26446//26446 26444//26444 -f 26475//26475 26444//26444 26476//26476 -f 26476//26476 26444//26444 26442//26442 -f 26476//26476 26442//26442 26477//26477 -f 26477//26477 26442//26442 26440//26440 -f 26477//26477 26440//26440 26438//26438 -f 26233//26233 26231//26231 26475//26475 -f 26405//26405 26403//26403 26494//26494 -f 26495//26495 26235//26235 26233//26233 -f 26231//26231 26229//26229 26475//26475 -f 26475//26475 26229//26229 26227//26227 -f 26475//26475 26227//26227 26488//26488 -f 26488//26488 26227//26227 26409//26409 -f 26488//26488 26409//26409 26407//26407 -f 26194//26194 26192//26192 26489//26489 -f 26489//26489 26192//26192 26480//26480 -f 26489//26489 26480//26480 26494//26494 -f 26494//26494 26480//26480 26488//26488 -f 26494//26494 26488//26488 26405//26405 -f 26405//26405 26488//26488 26407//26407 -f 26403//26403 26401//26401 26494//26494 -f 26494//26494 26401//26401 26239//26239 -f 26494//26494 26239//26239 26495//26495 -f 26495//26495 26239//26239 26237//26237 -f 26495//26495 26237//26237 26235//26235 -f 26249//26249 26247//26247 26483//26483 -f 26483//26483 26247//26247 26489//26489 -f 26483//26483 26489//26489 26484//26484 -f 26484//26484 26489//26489 26494//26494 -f 26484//26484 26494//26494 26486//26486 -f 26486//26486 26494//26494 26495//26495 -f 26486//26486 26495//26495 26472//26472 -f 26305//26305 26303//26303 26473//26473 -f 26355//26355 26353//26353 26472//26472 -f 26432//26432 26473//26473 26493//26493 -f 26493//26493 26473//26473 26303//26303 -f 26493//26493 26303//26303 26301//26301 -f 26353//26353 26351//26351 26472//26472 -f 26472//26472 26351//26351 26309//26309 -f 26472//26472 26309//26309 26473//26473 -f 26473//26473 26309//26309 26307//26307 -f 26473//26473 26307//26307 26305//26305 -f 26301//26301 26299//26299 26493//26493 -f 26493//26493 26299//26299 26297//26297 -f 26493//26493 26297//26297 26477//26477 -f 26477//26477 26297//26297 26359//26359 -f 26477//26477 26359//26359 26357//26357 -f 26233//26233 26475//26475 26495//26495 -f 26495//26495 26475//26475 26477//26477 -f 26495//26495 26477//26477 26472//26472 -f 26472//26472 26477//26477 26357//26357 -f 26472//26472 26357//26357 26355//26355 -f 26365//26365 26363//26363 26479//26479 -f 26291//26291 26474//26474 26492//26492 -f 26492//26492 26474//26474 26422//26422 -f 26492//26492 26422//26422 26420//26420 -f 26291//26291 26289//26289 26474//26474 -f 26474//26474 26289//26289 26287//26287 -f 26474//26474 26287//26287 26285//26285 -f 26367//26367 26487//26487 26369//26369 -f 26369//26369 26487//26487 26283//26283 -f 26363//26363 26361//26361 26479//26479 -f 26479//26479 26361//26361 26295//26295 -f 26479//26479 26295//26295 26492//26492 -f 26492//26492 26295//26295 26293//26293 -f 26492//26492 26293//26293 26291//26291 -f 26285//26285 26283//26283 26474//26474 -f 26474//26474 26283//26283 26487//26487 -f 26474//26474 26487//26487 26472//26472 -f 26472//26472 26487//26487 26323//26323 -f 26472//26472 26323//26323 26321//26321 -f 26367//26367 26365//26365 26487//26487 -f 26487//26487 26365//26365 26479//26479 -f 26487//26487 26479//26479 26481//26481 -f 26481//26481 26479//26479 26478//26478 -f 26481//26481 26478//26478 26482//26482 -f 26482//26482 26478//26478 26491//26491 -f 26482//26482 26491//26491 26485//26485 -f 26485//26485 26491//26491 26490//26490 -f 26485//26485 26490//26490 26263//26263 -f 26263//26263 26490//26490 26265//26265 -# 52862 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_motor_kuciste.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_motor_kuciste.obj deleted file mode 100644 index 3407a236a..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_motor_kuciste.obj +++ /dev/null @@ -1,1584 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object T_BOT_NOVE_SISE_I_LETVA2022 - motor sa kucistem-1 drzac servoa-1.obj -# -# Vertices: 385 -# Faces: 798 -# -#### -vn -6.265814 0.134855 0.252476 -v -0.005850 -0.003410 0.084750 -vn -2.864270 2.993613 0.848136 -v -0.005850 -0.003222 0.083393 -vn -3.208301 3.212070 1.970018 -v -0.006038 -0.003222 0.083393 -vn -2.920170 2.682850 1.590030 -v -0.005850 -0.002660 0.082117 -vn -2.812682 2.814060 3.281120 -v -0.006600 -0.002660 0.082117 -vn -2.507338 2.503551 4.056735 -v -0.006813 -0.002447 0.081800 -vn -0.572915 5.917612 1.083965 -v -0.005850 -0.001910 0.081179 -vn -1.587216 3.181440 2.630776 -v -0.007474 -0.001786 0.081062 -vn 4.712389 1.570796 -1.570796 -v 0.023150 -0.044710 0.104350 -vn 4.712389 -1.570795 -1.570796 -v 0.023150 -0.004910 0.104350 -vn 1.570796 1.570796 1.570796 -v 0.023150 -0.001910 0.107350 -vn 3.141593 -3.141595 0.000000 -v 0.023150 -0.004910 0.095715 -vn 1.570796 1.570796 -1.570796 -v 0.023150 -0.001910 0.073750 -vn 4.712389 -1.570799 1.570796 -v 0.023150 -0.004910 0.078750 -vn 1.570796 -1.570793 -1.570825 -v 0.023150 -0.047710 0.073750 -vn 4.712389 1.570796 1.570796 -v 0.023150 -0.044710 0.078750 -vn 3.141593 -3.141595 0.000000 -v 0.023150 -0.047710 0.095715 -vn 3.141593 3.141599 0.000000 -v 0.023150 -0.044710 0.095715 -vn 1.570796 -1.570794 1.570796 -v 0.023150 -0.047710 0.107350 -vn 1.517266 -3.665189 -2.627999 -v 0.001920 -0.047710 0.092589 -vn -0.000000 -3.665189 -3.034547 -v 0.002520 -0.047710 0.092750 -vn 0.000000 -6.283188 0.000000 -v 0.006685 -0.047710 0.095715 -vn -1.517266 -3.665188 -2.627999 -v 0.003120 -0.047710 0.092589 -vn 3.034547 -3.665189 0.000000 -v 0.001320 -0.047710 0.091550 -vn 2.627989 -3.665197 -1.517276 -v 0.001481 -0.047710 0.092150 -vn -3.141593 -3.141594 0.000000 -v -0.005850 -0.047710 0.095715 -vn -2.627989 -3.665197 -1.517276 -v 0.003559 -0.047710 0.092150 -vn -3.034547 -3.665190 -0.000000 -v 0.003720 -0.047710 0.091550 -vn 0.000000 -3.141592 -3.141594 -v 0.006685 -0.047710 0.073750 -vn -2.627990 -3.665196 1.517276 -v 0.003559 -0.047710 0.090950 -vn -1.517266 -3.665189 2.627998 -v 0.003120 -0.047710 0.090511 -vn -2.510684 -3.456849 1.823114 -v -0.006805 -0.047710 0.081811 -vn -1.823812 -3.455647 2.510343 -v -0.007911 -0.047710 0.080705 -vn 1.517266 -3.665025 2.627999 -v 0.001920 -0.047710 0.090511 -vn -0.000000 -3.665189 3.034547 -v 0.002520 -0.047710 0.090350 -vn -1.570796 -1.570796 1.570778 -v -0.025850 -0.047710 0.079750 -vn -1.570796 -1.570796 -1.570796 -v -0.025850 -0.047710 0.073750 -vn -0.245723 -3.298627 3.122250 -v -0.010850 -0.047710 0.079750 -vn -0.958847 -3.455708 2.951045 -v -0.009305 -0.047710 0.079995 -vn 2.627989 -3.665197 1.517276 -v 0.001481 -0.047710 0.090950 -vn -3.122348 -3.297740 0.245130 -v -0.005850 -0.047710 0.084750 -vn -2.950600 -3.456026 0.960141 -v -0.006095 -0.047710 0.083205 -vn 0.000000 -3.141593 3.141593 -v 0.006685 -0.047710 0.107350 -vn -1.570796 -1.570796 1.570796 -v -0.005850 -0.047710 0.107350 -vn 1.517275 -3.665197 -2.627989 -v 0.010250 -0.047710 0.100919 -vn 0.000000 -3.665189 -3.034547 -v 0.010850 -0.047710 0.101080 -vn 1.517275 -3.665197 2.627989 -v 0.010250 -0.047710 0.098841 -vn 2.627999 -3.665188 1.517266 -v 0.009811 -0.047710 0.099280 -vn 3.034545 -3.665193 -0.000005 -v 0.009650 -0.047710 0.099880 -vn 2.627997 -3.665185 -1.517271 -v 0.009811 -0.047710 0.100480 -vn -1.517275 -3.665197 -2.627989 -v 0.011450 -0.047710 0.100919 -vn -2.627997 -3.665185 -1.517271 -v 0.011889 -0.047710 0.100480 -vn -3.034545 -3.665193 -0.000005 -v 0.012050 -0.047710 0.099880 -vn -2.627999 -3.665188 1.517267 -v 0.011889 -0.047710 0.099280 -vn -1.517275 -3.665197 2.627989 -v 0.011450 -0.047710 0.098841 -vn -0.000000 -3.665189 3.034547 -v 0.010850 -0.047710 0.098680 -vn -2.627997 -3.665185 1.517271 -v 0.011889 -0.047710 0.082620 -vn -1.517275 -3.665197 2.627989 -v 0.011450 -0.047710 0.082181 -vn 3.034547 -3.665189 0.000000 -v 0.009650 -0.047710 0.091550 -vn 2.627990 -3.665197 -1.517276 -v 0.009811 -0.047710 0.092150 -vn 1.517266 -3.665188 -2.627998 -v 0.010250 -0.047710 0.092589 -vn 0.000000 -3.665190 -3.034547 -v 0.010850 -0.047710 0.092750 -vn 2.627989 -3.665197 1.517276 -v 0.009811 -0.047710 0.090950 -vn 1.517266 -3.665190 2.627999 -v 0.010250 -0.047710 0.090511 -vn -0.000000 -3.665189 3.034547 -v 0.010850 -0.047710 0.082020 -vn 1.517275 -3.665197 2.627989 -v 0.010250 -0.047710 0.082181 -vn -1.517266 -3.665189 -2.627999 -v 0.011450 -0.047710 0.092589 -vn 3.034545 -3.665201 0.000000 -v 0.017980 -0.047710 0.091550 -vn 2.627989 -3.665195 -1.517278 -v 0.018141 -0.047710 0.092150 -vn 1.517266 -3.665188 -2.627998 -v 0.018580 -0.047710 0.092589 -vn 0.000001 -3.665189 -3.034546 -v 0.019180 -0.047710 0.092750 -vn -1.517266 -3.665189 -2.627999 -v 0.019780 -0.047710 0.092589 -vn -2.627990 -3.665198 -1.517273 -v 0.020219 -0.047710 0.092150 -vn -3.034548 -3.665186 -0.000000 -v 0.020380 -0.047710 0.091550 -vn -2.627990 -3.665198 1.517274 -v 0.020219 -0.047710 0.090950 -vn -1.517265 -3.665189 2.627999 -v 0.019780 -0.047710 0.090511 -vn -3.034545 -3.665192 0.000005 -v 0.012050 -0.047710 0.083220 -vn -2.627989 -3.665197 -1.517276 -v 0.011889 -0.047710 0.083820 -vn 0.000001 -3.665189 3.034547 -v 0.019180 -0.047710 0.090350 -vn -1.517284 -3.665178 -2.627994 -v 0.011450 -0.047710 0.084259 -vn 1.517267 -3.665185 2.627998 -v 0.018580 -0.047710 0.090511 -vn -0.000000 -3.665212 -3.034537 -v 0.010850 -0.047710 0.084420 -vn -2.627989 -3.665197 -1.517276 -v 0.011889 -0.047710 0.092150 -vn -3.034547 -3.665190 -0.000000 -v 0.012050 -0.047710 0.091550 -vn 2.627988 -3.665196 1.517278 -v 0.018141 -0.047710 0.090950 -vn -2.627990 -3.665196 1.517276 -v 0.011889 -0.047710 0.090950 -vn 1.517283 -3.665177 -2.627994 -v 0.010250 -0.047710 0.084259 -vn 2.627997 -3.665185 1.517271 -v 0.009811 -0.047710 0.082620 -vn 3.034545 -3.665193 0.000005 -v 0.009650 -0.047710 0.083220 -vn 2.627990 -3.665196 -1.517276 -v 0.009811 -0.047710 0.083820 -vn -0.000000 -3.665188 3.034547 -v 0.010850 -0.047710 0.090350 -vn -1.517266 -3.665189 2.627998 -v 0.011450 -0.047710 0.090511 -vn -1.570797 1.570796 1.570796 -v -0.005850 -0.001910 0.107350 -vn -2.627997 3.665185 1.517271 -v 0.011889 -0.044710 0.082620 -vn -3.034545 3.665193 0.000005 -v 0.012050 -0.044710 0.083220 -vn 0.000001 3.665190 -3.034547 -v 0.019180 -0.044710 0.092750 -vn -3.034547 3.665190 0.000000 -v 0.012050 -0.044710 0.091550 -vn -2.627990 3.665197 -1.517276 -v 0.011889 -0.044710 0.092150 -vn -2.627990 3.665198 -1.517274 -v 0.020219 -0.044710 0.092150 -vn -1.517265 3.665189 -2.627999 -v 0.019780 -0.044710 0.092589 -vn 1.517266 3.665188 2.627998 -v 0.018580 -0.044710 0.090511 -vn 0.000001 3.665189 3.034546 -v 0.019180 -0.044710 0.090350 -vn -1.517266 3.665189 2.627999 -v 0.019780 -0.044710 0.090511 -vn -2.627990 3.665198 1.517273 -v 0.020219 -0.044710 0.090950 -vn -3.034548 3.665186 0.000000 -v 0.020380 -0.044710 0.091550 -vn -1.517266 3.665188 -2.627998 -v 0.011450 -0.044710 0.092589 -vn 0.000000 6.283183 0.000000 -v 0.006685 -0.044710 0.095715 -vn -0.000000 3.665189 -3.034547 -v 0.010850 -0.044710 0.092750 -vn 1.517266 3.665188 -2.627999 -v 0.010250 -0.044710 0.092589 -vn 2.627989 3.665197 -1.517276 -v 0.009811 -0.044710 0.092150 -vn 3.034547 3.665190 -0.000000 -v 0.009650 -0.044710 0.091550 -vn 0.000000 3.141596 3.141593 -v 0.006685 -0.044710 0.078750 -vn 2.627990 3.665196 1.517276 -v 0.009811 -0.044710 0.090950 -vn 1.517266 3.665189 2.627998 -v 0.010250 -0.044710 0.090511 -vn 0.000000 3.665189 3.034547 -v 0.010850 -0.044710 0.090350 -vn -1.517266 3.665189 2.627999 -v 0.011450 -0.044710 0.090511 -vn -2.627989 3.665196 1.517276 -v 0.011889 -0.044710 0.090950 -vn 1.517267 3.665189 -2.627998 -v 0.018580 -0.044710 0.092589 -vn 2.627988 3.665195 -1.517278 -v 0.018141 -0.044710 0.092150 -vn 3.034545 3.665193 -0.000000 -v 0.017980 -0.044710 0.091550 -vn 2.627989 3.665197 -1.517276 -v 0.009811 -0.044710 0.083820 -vn 3.034545 3.665192 0.000005 -v 0.009650 -0.044710 0.083220 -vn 2.627997 3.665185 1.517271 -v 0.009811 -0.044710 0.082620 -vn -1.517283 3.665177 -2.627994 -v 0.011450 -0.044710 0.084259 -vn 0.000000 3.665212 -3.034537 -v 0.010850 -0.044710 0.084420 -vn 1.517284 3.665177 -2.627994 -v 0.010250 -0.044710 0.084259 -vn -2.627990 3.665196 -1.517276 -v 0.011889 -0.044710 0.083820 -vn 2.627989 3.665195 1.517278 -v 0.018141 -0.044710 0.090950 -vn 1.517276 3.665197 2.627989 -v 0.010250 -0.044710 0.082181 -vn 0.000000 3.665189 3.034547 -v 0.010850 -0.044710 0.082020 -vn -1.517276 3.665197 2.627989 -v 0.011450 -0.044710 0.082181 -vn -3.034547 3.665189 0.000000 -v 0.003720 -0.044710 0.091550 -vn -2.627990 3.665197 -1.517276 -v 0.003559 -0.044710 0.092150 -vn -1.517266 3.665188 -2.627998 -v 0.003120 -0.044710 0.092589 -vn -0.000000 3.665189 -3.034547 -v 0.002520 -0.044710 0.092750 -vn 1.517266 3.665188 -2.627999 -v 0.001920 -0.044710 0.092589 -vn 3.141593 3.141592 0.000000 -v -0.001850 -0.044710 0.095715 -vn 2.627989 3.665197 -1.517276 -v 0.001481 -0.044710 0.092150 -vn 3.034547 3.665189 -0.000000 -v 0.001320 -0.044710 0.091550 -vn 1.570796 1.570793 1.570797 -v -0.001850 -0.044710 0.078750 -vn -2.627989 3.665197 1.517276 -v 0.003559 -0.044710 0.090950 -vn -1.517266 3.665188 2.627999 -v 0.003120 -0.044710 0.090511 -vn 2.627989 3.665197 1.517276 -v 0.001481 -0.044710 0.090950 -vn 1.517266 3.665188 2.627999 -v 0.001920 -0.044710 0.090511 -vn -0.000000 3.665189 3.034547 -v 0.002520 -0.044710 0.090350 -vn 0.000000 3.141595 -3.141593 -v 0.006685 -0.044710 0.104350 -vn 1.517276 3.665197 -2.627989 -v 0.010250 -0.044710 0.100919 -vn 2.627997 3.665185 -1.517271 -v 0.009811 -0.044710 0.100480 -vn 3.034545 3.665192 -0.000005 -v 0.009650 -0.044710 0.099880 -vn 2.627999 3.665188 1.517267 -v 0.009811 -0.044710 0.099280 -vn -1.517276 3.665197 -2.627989 -v 0.011450 -0.044710 0.100919 -vn -0.000000 3.665189 -3.034547 -v 0.010850 -0.044710 0.101080 -vn 1.517276 3.665197 2.627989 -v 0.010250 -0.044710 0.098841 -vn 0.000000 3.665189 3.034547 -v 0.010850 -0.044710 0.098680 -vn -1.517276 3.665197 2.627989 -v 0.011450 -0.044710 0.098841 -vn -2.627999 3.665188 1.517266 -v 0.011889 -0.044710 0.099280 -vn -3.034545 3.665192 -0.000005 -v 0.012050 -0.044710 0.099880 -vn -2.627997 3.665185 -1.517271 -v 0.011889 -0.044710 0.100480 -vn 1.570797 1.570796 -1.570796 -v -0.001850 -0.044710 0.104350 -vn 0.000000 -3.141595 3.141593 -v 0.006685 -0.004910 0.078750 -vn 1.570796 -1.570793 1.570796 -v -0.001850 -0.004910 0.078750 -vn 0.000000 -3.141594 -3.141593 -v 0.006685 -0.004910 0.104350 -vn 1.570796 -1.570796 -1.570797 -v -0.001850 -0.004910 0.104350 -vn 3.141593 -3.141591 0.000000 -v -0.001850 -0.004910 0.095715 -vn 3.034545 -2.617993 -0.000000 -v 0.017980 -0.003410 0.091550 -vn 3.034545 -3.665193 0.000000 -v 0.017980 -0.004910 0.091550 -vn 2.627989 -2.617990 1.517278 -v 0.018141 -0.003410 0.090950 -vn 2.627989 -3.665195 1.517278 -v 0.018141 -0.004910 0.090950 -vn 1.517267 -2.617997 2.627998 -v 0.018580 -0.003410 0.090511 -vn 1.517267 -3.665188 2.627998 -v 0.018580 -0.004910 0.090511 -vn 0.000001 -2.617997 3.034546 -v 0.019180 -0.003410 0.090350 -vn 0.000001 -3.665189 3.034547 -v 0.019180 -0.004910 0.090350 -vn -1.517266 -2.617996 2.627999 -v 0.019780 -0.003410 0.090511 -vn -1.517265 -3.665189 2.627999 -v 0.019780 -0.004910 0.090511 -vn -2.627990 -2.617987 1.517274 -v 0.020219 -0.003410 0.090950 -vn -2.627990 -3.665198 1.517274 -v 0.020219 -0.004910 0.090950 -vn -3.034547 -2.617999 -0.000000 -v 0.020380 -0.003410 0.091550 -vn -3.034547 -3.665187 0.000000 -v 0.020380 -0.004910 0.091550 -vn -2.627990 -2.617987 -1.517274 -v 0.020219 -0.003410 0.092150 -vn -2.627990 -3.665198 -1.517274 -v 0.020219 -0.004910 0.092150 -vn -1.517265 -2.617996 -2.627999 -v 0.019780 -0.003410 0.092589 -vn -1.517266 -3.665189 -2.627999 -v 0.019780 -0.004910 0.092589 -vn 0.000001 -2.617997 -3.034547 -v 0.019180 -0.003410 0.092750 -vn 0.000001 -3.665189 -3.034546 -v 0.019180 -0.004910 0.092750 -vn 1.517267 -2.617997 -2.627998 -v 0.018580 -0.003410 0.092589 -vn 1.517267 -3.665188 -2.627998 -v 0.018580 -0.004910 0.092589 -vn 2.627989 -2.617990 -1.517278 -v 0.018141 -0.003410 0.092150 -vn 2.627989 -3.665195 -1.517278 -v 0.018141 -0.004910 0.092150 -vn 3.034546 -2.617996 0.000000 -v 0.009650 -0.003410 0.091550 -vn 3.034546 -3.665189 -0.000000 -v 0.009650 -0.004910 0.091550 -vn 2.627989 -2.617989 1.517276 -v 0.009811 -0.003410 0.090950 -vn 2.627989 -3.665197 1.517276 -v 0.009811 -0.004910 0.090950 -vn 1.517266 -2.617997 2.627999 -v 0.010250 -0.003410 0.090511 -vn 1.517266 -3.665187 2.627999 -v 0.010250 -0.004910 0.090511 -vn 0.000000 -2.617996 3.034546 -v 0.010850 -0.003410 0.090350 -vn 0.000000 -3.665188 3.034546 -v 0.010850 -0.004910 0.090350 -vn -1.517266 -2.617997 2.627999 -v 0.011450 -0.003410 0.090511 -vn -1.517266 -3.665189 2.627999 -v 0.011450 -0.004910 0.090511 -vn -2.627989 -2.617989 1.517276 -v 0.011889 -0.003410 0.090950 -vn -2.627989 -3.665197 1.517276 -v 0.011889 -0.004910 0.090950 -vn -3.034546 -2.617996 -0.000000 -v 0.012050 -0.003410 0.091550 -vn -3.034546 -3.665189 0.000000 -v 0.012050 -0.004910 0.091550 -vn -2.627989 -2.617989 -1.517276 -v 0.011889 -0.003410 0.092150 -vn -2.627989 -3.665197 -1.517276 -v 0.011889 -0.004910 0.092150 -vn -1.517266 -2.617997 -2.627999 -v 0.011450 -0.003410 0.092589 -vn -1.517266 -3.665189 -2.627999 -v 0.011450 -0.004910 0.092589 -vn 0.000000 -2.617996 -3.034546 -v 0.010850 -0.003410 0.092750 -vn 0.000000 -3.665189 -3.034546 -v 0.010850 -0.004910 0.092750 -vn 1.517266 -2.617997 -2.627999 -v 0.010250 -0.003410 0.092589 -vn 1.517266 -3.665188 -2.627999 -v 0.010250 -0.004910 0.092589 -vn 2.627989 -2.617989 -1.517276 -v 0.009811 -0.003410 0.092150 -vn 2.627989 -3.665197 -1.517276 -v 0.009811 -0.004910 0.092150 -vn 3.034545 -2.617993 -0.000005 -v 0.009650 -0.003410 0.099880 -vn 3.034545 -3.665192 -0.000005 -v 0.009650 -0.004910 0.099880 -vn 2.627999 -2.617997 1.517266 -v 0.009811 -0.003410 0.099280 -vn 2.627999 -3.665188 1.517266 -v 0.009811 -0.004910 0.099280 -vn 1.517275 -2.617988 2.627989 -v 0.010250 -0.003410 0.098841 -vn 1.517276 -3.665197 2.627989 -v 0.010250 -0.004910 0.098841 -vn 0.000000 -2.617996 3.034546 -v 0.010850 -0.003410 0.098680 -vn 0.000000 -3.665189 3.034546 -v 0.010850 -0.004910 0.098680 -vn -1.517276 -2.617988 2.627989 -v 0.011450 -0.003410 0.098841 -vn -1.517275 -3.665197 2.627989 -v 0.011450 -0.004910 0.098841 -vn -2.627999 -2.617997 1.517266 -v 0.011889 -0.003410 0.099280 -vn -2.627999 -3.665188 1.517266 -v 0.011889 -0.004910 0.099280 -vn -3.034545 -2.617993 -0.000005 -v 0.012050 -0.003410 0.099880 -vn -3.034545 -3.665193 -0.000005 -v 0.012050 -0.004910 0.099880 -vn -2.627998 -2.618000 -1.517271 -v 0.011889 -0.003410 0.100480 -vn -2.627997 -3.665185 -1.517271 -v 0.011889 -0.004910 0.100480 -vn -1.517275 -2.617988 -2.627989 -v 0.011450 -0.003410 0.100919 -vn -1.517276 -3.665197 -2.627989 -v 0.011450 -0.004910 0.100919 -vn 0.000000 -2.617996 -3.034546 -v 0.010850 -0.003410 0.101080 -vn 0.000000 -3.665189 -3.034546 -v 0.010850 -0.004910 0.101080 -vn 1.517276 -2.617988 -2.627989 -v 0.010250 -0.003410 0.100919 -vn 1.517275 -3.665197 -2.627989 -v 0.010250 -0.004910 0.100919 -vn 2.627997 -2.618000 -1.517271 -v 0.009811 -0.003410 0.100480 -vn 2.627998 -3.665185 -1.517271 -v 0.009811 -0.004910 0.100480 -vn 3.034545 -2.617993 0.000005 -v 0.009650 -0.003410 0.083220 -vn 3.034545 -3.665192 0.000005 -v 0.009650 -0.004910 0.083220 -vn 2.627998 -2.618000 1.517271 -v 0.009811 -0.003410 0.082620 -vn 2.627997 -3.665185 1.517271 -v 0.009811 -0.004910 0.082620 -vn 1.517275 -2.617988 2.627989 -v 0.010250 -0.003410 0.082181 -vn 1.517276 -3.665197 2.627989 -v 0.010250 -0.004910 0.082181 -vn 0.000000 -2.617996 3.034546 -v 0.010850 -0.003410 0.082020 -vn 0.000000 -3.665189 3.034546 -v 0.010850 -0.004910 0.082020 -vn -1.517276 -2.617988 2.627989 -v 0.011450 -0.003410 0.082181 -vn -1.517275 -3.665197 2.627989 -v 0.011450 -0.004910 0.082181 -vn -2.627997 -2.618000 1.517271 -v 0.011889 -0.003410 0.082620 -vn -2.627998 -3.665185 1.517271 -v 0.011889 -0.004910 0.082620 -vn -3.034545 -2.617993 0.000005 -v 0.012050 -0.003410 0.083220 -vn -3.034545 -3.665193 0.000005 -v 0.012050 -0.004910 0.083220 -vn -2.627989 -2.617989 -1.517276 -v 0.011889 -0.003410 0.083820 -vn -2.627989 -3.665197 -1.517276 -v 0.011889 -0.004910 0.083820 -vn -1.517284 -2.618009 -2.627994 -v 0.011450 -0.003410 0.084259 -vn -1.517284 -3.665176 -2.627994 -v 0.011450 -0.004910 0.084259 -vn 0.000000 -2.617973 -3.034537 -v 0.010850 -0.003410 0.084420 -vn -0.000000 -3.665212 -3.034537 -v 0.010850 -0.004910 0.084420 -vn 1.517284 -2.618009 -2.627994 -v 0.010250 -0.003410 0.084259 -vn 1.517283 -3.665176 -2.627994 -v 0.010250 -0.004910 0.084259 -vn 2.627989 -2.617989 -1.517276 -v 0.009811 -0.003410 0.083820 -vn 2.627989 -3.665197 -1.517276 -v 0.009811 -0.004910 0.083820 -vn 3.034546 -2.617996 0.000000 -v 0.001320 -0.003410 0.091550 -vn 3.034546 -3.665189 -0.000000 -v 0.001320 -0.004910 0.091550 -vn 2.627989 -2.617988 1.517276 -v 0.001481 -0.003410 0.090950 -vn 2.627989 -3.665197 1.517276 -v 0.001481 -0.004910 0.090950 -vn 1.517266 -2.617997 2.627999 -v 0.001920 -0.003410 0.090511 -vn 1.517266 -3.665188 2.627999 -v 0.001920 -0.004910 0.090511 -vn -0.000000 -2.617997 3.034546 -v 0.002520 -0.003410 0.090350 -vn -0.000000 -3.665189 3.034546 -v 0.002520 -0.004910 0.090350 -vn -1.517266 -2.617997 2.627999 -v 0.003120 -0.003410 0.090511 -vn -1.517266 -3.665188 2.627999 -v 0.003120 -0.004910 0.090511 -vn -2.627989 -2.617989 1.517276 -v 0.003559 -0.003410 0.090950 -vn -2.627989 -3.665197 1.517276 -v 0.003559 -0.004910 0.090950 -vn -3.034546 -2.617996 -0.000000 -v 0.003720 -0.003410 0.091550 -vn -3.034546 -3.665190 0.000000 -v 0.003720 -0.004910 0.091550 -vn -2.627989 -2.617989 -1.517276 -v 0.003559 -0.003410 0.092150 -vn -2.627989 -3.665197 -1.517276 -v 0.003559 -0.004910 0.092150 -vn -1.517266 -2.617997 -2.627999 -v 0.003120 -0.003410 0.092589 -vn -1.517266 -3.665188 -2.627999 -v 0.003120 -0.004910 0.092589 -vn -0.000000 -2.617997 -3.034546 -v 0.002520 -0.003410 0.092750 -vn -0.000000 -3.665189 -3.034546 -v 0.002520 -0.004910 0.092750 -vn 1.517265 -2.617997 -2.627999 -v 0.001920 -0.003410 0.092589 -vn 1.517266 -3.665188 -2.627999 -v 0.001920 -0.004910 0.092589 -vn 2.627989 -2.617988 -1.517276 -v 0.001481 -0.003410 0.092150 -vn 2.627989 -3.665197 -1.517276 -v 0.001481 -0.004910 0.092150 -vn 1.517274 -2.627992 3.665193 -v -0.023450 0.001732 0.079750 -vn -0.000000 -3.034546 3.665191 -v -0.022450 0.002000 0.079750 -vn 0.429120 3.039872 2.713832 -v -0.022431 0.003445 0.079750 -vn 1.302285 2.849362 2.992435 -v -0.021236 0.003004 0.079750 -vn -1.517272 -2.627994 3.665192 -v -0.021450 0.001732 0.079750 -vn 1.331230 2.838335 3.271032 -v -0.017662 0.001036 0.079750 -vn -2.627994 -1.517273 3.665191 -v -0.020718 0.001000 0.079750 -vn 0.968151 2.982737 3.265865 -v -0.013863 -0.000455 0.079750 -vn 1.517274 2.627992 3.665184 -v -0.023450 -0.023732 0.079750 -vn 2.627994 1.517274 3.665189 -v -0.024182 -0.023000 0.079750 -vn 3.034544 0.000000 3.665174 -v -0.024450 -0.022000 0.079750 -vn 1.517275 -2.627991 3.665200 -v -0.023450 -0.042268 0.079750 -vn -3.034546 0.000000 3.665193 -v -0.020450 -0.022000 0.079750 -vn -2.627994 1.517272 3.665190 -v -0.020718 -0.023000 0.079750 -vn -0.870582 2.943987 2.713836 -v -0.023701 0.003352 0.079750 -vn -2.013400 2.317582 2.713834 -v -0.024817 0.002739 0.079750 -vn 2.627994 -1.517274 3.665188 -v -0.024182 0.001000 0.079750 -vn -2.793396 1.273540 2.713835 -v -0.025580 0.001719 0.079750 -vn 3.034544 -0.000001 3.665195 -v -0.024450 0.000000 0.079750 -vn -3.105802 0.333406 2.927713 -v -0.025850 0.000475 0.079750 -vn 2.627994 1.517274 3.665189 -v -0.024182 -0.001000 0.079750 -vn 1.517274 2.627992 3.665167 -v -0.023450 -0.001732 0.079750 -vn 0.000000 3.034546 3.665191 -v -0.022450 -0.002000 0.079750 -vn -1.517272 2.627994 3.665192 -v -0.021450 -0.001732 0.079750 -vn 2.627994 -1.517274 3.665189 -v -0.024182 -0.021000 0.079750 -vn -3.034546 -0.000001 3.665170 -v -0.020450 0.000000 0.079750 -vn -2.627994 1.517272 3.665191 -v -0.020718 -0.001000 0.079750 -vn 0.604823 3.148073 3.218919 -v -0.010850 -0.001255 0.079750 -vn 1.517274 -2.627992 3.665193 -v -0.023450 -0.020268 0.079750 -vn -0.000000 -3.034546 3.665191 -v -0.022450 -0.020000 0.079750 -vn -1.517272 2.627994 3.665192 -v -0.021450 -0.023732 0.079750 -vn 0.000000 3.034546 3.665193 -v -0.022450 -0.024000 0.079750 -vn 2.627995 -1.517273 3.665186 -v -0.024182 -0.043000 0.079750 -vn 3.034544 -0.000001 3.665194 -v -0.024450 -0.044000 0.079750 -vn 2.627993 1.517274 3.665190 -v -0.024182 -0.045000 0.079750 -vn -2.627992 1.517273 3.665194 -v -0.020718 -0.045000 0.079750 -vn -1.517271 2.627995 3.665190 -v -0.021450 -0.045732 0.079750 -vn 0.000000 3.034546 3.665192 -v -0.022450 -0.046000 0.079750 -vn 1.517272 2.627994 3.665192 -v -0.023450 -0.045732 0.079750 -vn -1.517272 -2.627994 3.665192 -v -0.021450 -0.020268 0.079750 -vn -2.627994 -1.517272 3.665192 -v -0.020718 -0.021000 0.079750 -vn -0.000000 -3.034546 3.665191 -v -0.022450 -0.042000 0.079750 -vn -1.517274 -2.627992 3.665193 -v -0.021450 -0.042268 0.079750 -vn -2.627995 -1.517272 3.665190 -v -0.020718 -0.043000 0.079750 -vn -3.034546 -0.000001 3.665191 -v -0.020450 -0.044000 0.079750 -vn -3.105801 0.333406 -2.927726 -v -0.025850 0.000475 0.073750 -vn 3.034544 -0.000001 -3.665174 -v -0.024450 0.000000 0.073750 -vn 2.627994 1.517274 -3.665188 -v -0.024182 -0.001000 0.073750 -vn 1.517274 2.627992 -3.665193 -v -0.023450 -0.001732 0.073750 -vn -0.000000 3.034546 -3.665191 -v -0.022450 -0.002000 0.073750 -vn -1.517272 2.627994 -3.665192 -v -0.021450 -0.001732 0.073750 -vn -2.627994 1.517272 -3.665192 -v -0.020718 -0.001000 0.073750 -vn -3.034545 -0.000001 -3.665191 -v -0.020450 0.000000 0.073750 -vn -2.627994 -1.517273 -3.665191 -v -0.020718 0.001000 0.073750 -vn -1.517272 -2.627994 -3.665192 -v -0.021450 0.001732 0.073750 -vn 0.000000 -3.034546 -3.665191 -v -0.022450 0.002000 0.073750 -vn 1.517274 -2.627992 -3.665193 -v -0.023450 0.001732 0.073750 -vn 2.627994 -1.517274 -3.665188 -v -0.024182 0.001000 0.073750 -vn 3.034544 0.000000 -3.665195 -v -0.024450 -0.022000 0.073750 -vn 2.627994 1.517274 -3.665188 -v -0.024182 -0.023000 0.073750 -vn 1.517274 2.627992 -3.665194 -v -0.023450 -0.023732 0.073750 -vn -0.000000 3.034546 -3.665193 -v -0.022450 -0.024000 0.073750 -vn -1.517272 2.627994 -3.665192 -v -0.021450 -0.023732 0.073750 -vn -2.627994 1.517272 -3.665190 -v -0.020718 -0.023000 0.073750 -vn -3.034546 -0.000000 -3.665171 -v -0.020450 -0.022000 0.073750 -vn -2.627994 -1.517272 -3.665190 -v -0.020718 -0.021000 0.073750 -vn -1.517272 -2.627994 -3.665192 -v -0.021450 -0.020268 0.073750 -vn 0.000000 -3.034546 -3.665191 -v -0.022450 -0.020000 0.073750 -vn 1.517274 -2.627992 -3.665193 -v -0.023450 -0.020268 0.073750 -vn 2.627994 -1.517274 -3.665188 -v -0.024182 -0.021000 0.073750 -vn 3.034544 -0.000001 -3.665194 -v -0.024450 -0.044000 0.073750 -vn 2.627993 1.517274 -3.665190 -v -0.024182 -0.045000 0.073750 -vn 1.517272 2.627994 -3.665192 -v -0.023450 -0.045732 0.073750 -vn -0.000000 3.034546 -3.665191 -v -0.022450 -0.046000 0.073750 -vn -1.517271 2.627995 -3.665190 -v -0.021450 -0.045732 0.073750 -vn -2.627993 1.517273 -3.665194 -v -0.020718 -0.045000 0.073750 -vn -3.034546 -0.000001 -3.665192 -v -0.020450 -0.044000 0.073750 -vn -2.627995 -1.517272 -3.665190 -v -0.020718 -0.043000 0.073750 -vn -1.517274 -2.627992 -3.665194 -v -0.021450 -0.042268 0.073750 -vn 0.000000 -3.034546 -3.665193 -v -0.022450 -0.042000 0.073750 -vn 1.517275 -2.627991 -3.665195 -v -0.023450 -0.042268 0.073750 -vn 2.627995 -1.517273 -3.665190 -v -0.024182 -0.043000 0.073750 -vn -1.498722 3.266056 2.619369 -v -0.007911 -0.001738 0.080705 -vn -0.991528 3.274177 2.875048 -v -0.008584 -0.001653 0.080293 -vn -0.478509 3.246516 3.092145 -v -0.009305 -0.001545 0.079995 -vn 0.031158 3.253805 3.156580 -v -0.009904 -0.001442 0.079840 -vn 0.178243 3.131427 -3.250577 -v -0.005850 -0.001910 0.073750 -vn 0.559122 3.084818 -3.266477 -v -0.009904 -0.001442 0.073750 -vn -2.793396 1.273540 -2.713835 -v -0.025580 0.001719 0.073750 -vn -2.013400 2.317582 -2.713834 -v -0.024817 0.002739 0.073750 -vn -0.870582 2.943987 -2.713836 -v -0.023701 0.003352 0.073750 -vn 0.429120 3.039872 -2.713832 -v -0.022431 0.003445 0.073750 -vn 1.302285 2.849362 -2.992435 -v -0.021236 0.003004 0.073750 -vn 1.331230 2.838335 -3.271032 -v -0.017662 0.001036 0.073750 -vn 0.953728 2.986423 -3.271031 -v -0.013863 -0.000455 0.073750 -vn 0.000000 -6.283186 0.000000 -v 0.006685 -0.004910 0.095715 -vn 0.000000 -6.283185 0.000000 -v 0.002520 -0.003410 0.091550 -vn 0.000000 -6.283185 0.000000 -v 0.010850 -0.003410 0.083220 -vn 0.000000 -6.283185 0.000000 -v 0.010850 -0.003410 0.099880 -vn 0.000000 -6.283185 0.000000 -v 0.010850 -0.003410 0.091550 -vn 0.000000 -6.283185 0.000000 -v 0.019180 -0.003410 0.091550 -# 385 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 6//6 4//4 7//7 -f 6//6 7//7 8//8 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 9//9 -f 19//19 9//9 11//11 -f 20//20 21//21 22//22 -f 22//22 21//21 23//23 -f 24//24 25//25 26//26 -f 26//26 25//25 20//20 -f 23//23 27//27 22//22 -f 22//22 27//27 28//28 -f 22//22 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 32//32 33//33 34//34 -f 34//34 33//33 29//29 -f 34//34 29//29 35//35 -f 35//35 29//29 31//31 -f 36//36 37//37 38//38 -f 38//38 37//37 29//29 -f 38//38 29//29 39//39 -f 39//39 29//29 33//33 -f 24//24 26//26 40//40 -f 40//40 26//26 41//41 -f 40//40 41//41 34//34 -f 34//34 41//41 42//42 -f 34//34 42//42 32//32 -f 20//20 22//22 26//26 -f 26//26 22//22 43//43 -f 26//26 43//43 44//44 -f 43//43 45//45 46//46 -f 43//43 46//46 19//19 -f 47//47 48//48 22//22 -f 22//22 48//48 49//49 -f 22//22 49//49 43//43 -f 43//43 49//49 50//50 -f 43//43 50//50 45//45 -f 46//46 51//51 19//19 -f 19//19 51//51 52//52 -f 19//19 52//52 17//17 -f 17//17 52//52 53//53 -f 53//53 54//54 17//17 -f 17//17 54//54 55//55 -f 17//17 55//55 22//22 -f 22//22 55//55 56//56 -f 22//22 56//56 47//47 -f 57//57 58//58 15//15 -f 59//59 60//60 22//22 -f 22//22 60//60 61//61 -f 22//22 61//61 62//62 -f 59//59 22//22 63//63 -f 63//63 22//22 29//29 -f 63//63 29//29 64//64 -f 15//15 58//58 29//29 -f 29//29 58//58 65//65 -f 29//29 65//65 66//66 -f 67//67 68//68 62//62 -f 62//62 68//68 69//69 -f 62//62 69//69 22//22 -f 22//22 69//69 70//70 -f 22//22 70//70 17//17 -f 17//17 70//70 71//71 -f 17//17 71//71 72//72 -f 72//72 73//73 17//17 -f 17//17 73//73 74//74 -f 17//17 74//74 15//15 -f 15//15 74//74 75//75 -f 15//15 75//75 76//76 -f 57//57 15//15 77//77 -f 77//77 15//15 76//76 -f 77//77 76//76 78//78 -f 78//78 76//76 79//79 -f 78//78 79//79 80//80 -f 80//80 79//79 81//81 -f 80//80 81//81 82//82 -f 67//67 83//83 68//68 -f 68//68 83//83 84//84 -f 68//68 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 81//81 -f 81//81 86//86 87//87 -f 81//81 87//87 82//82 -f 66//66 88//88 29//29 -f 29//29 88//88 89//89 -f 29//29 89//89 64//64 -f 64//64 89//89 90//90 -f 64//64 90//90 91//91 -f 91//91 90//90 87//87 -f 91//91 87//87 92//92 -f 92//92 87//87 86//86 -f 19//19 11//11 43//43 -f 43//43 11//11 93//93 -f 43//43 93//93 44//44 -f 94//94 95//95 16//16 -f 96//96 97//97 98//98 -f 99//99 100//100 18//18 -f 18//18 100//100 96//96 -f 101//101 102//102 16//16 -f 102//102 103//103 16//16 -f 16//16 103//103 104//104 -f 16//16 104//104 18//18 -f 18//18 104//104 105//105 -f 18//18 105//105 99//99 -f 96//96 98//98 18//18 -f 18//18 98//98 106//106 -f 18//18 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 110//110 107//107 -f 107//107 110//110 111//111 -f 107//107 111//111 112//112 -f 112//112 111//111 113//113 -f 112//112 113//113 114//114 -f 114//114 115//115 112//112 -f 112//112 115//115 116//116 -f 112//112 116//116 117//117 -f 96//96 118//118 97//97 -f 97//97 118//118 119//119 -f 97//97 119//119 120//120 -f 117//117 121//121 112//112 -f 112//112 121//121 122//122 -f 112//112 122//122 123//123 -f 124//124 125//125 117//117 -f 117//117 125//125 126//126 -f 117//117 126//126 121//121 -f 16//16 95//95 101//101 -f 101//101 95//95 127//127 -f 101//101 127//127 128//128 -f 128//128 127//127 124//124 -f 128//128 124//124 120//120 -f 120//120 124//124 117//117 -f 120//120 117//117 97//97 -f 123//123 129//129 112//112 -f 112//112 129//129 130//130 -f 112//112 130//130 16//16 -f 16//16 130//130 131//131 -f 16//16 131//131 94//94 -f 132//132 133//133 107//107 -f 107//107 133//133 134//134 -f 135//135 136//136 137//137 -f 136//136 138//138 137//137 -f 137//137 138//138 139//139 -f 137//137 139//139 140//140 -f 132//132 107//107 141//141 -f 141//141 107//107 112//112 -f 141//141 112//112 142//142 -f 139//139 143//143 140//140 -f 140//140 143//143 144//144 -f 140//140 144//144 112//112 -f 112//112 144//144 145//145 -f 112//112 145//145 142//142 -f 146//146 147//147 148//148 -f 146//146 148//148 107//107 -f 107//107 148//148 149//149 -f 107//107 149//149 150//150 -f 9//9 151//151 146//146 -f 146//146 151//151 152//152 -f 146//146 152//152 147//147 -f 150//150 153//153 107//107 -f 107//107 153//153 154//154 -f 107//107 154//154 18//18 -f 18//18 154//154 155//155 -f 155//155 156//156 18//18 -f 18//18 156//156 157//157 -f 18//18 157//157 9//9 -f 9//9 157//157 158//158 -f 9//9 158//158 151//151 -f 134//134 135//135 107//107 -f 107//107 135//135 137//137 -f 107//107 137//137 146//146 -f 146//146 137//137 159//159 -f 16//16 14//14 112//112 -f 112//112 14//14 160//160 -f 112//112 160//160 140//140 -f 140//140 160//160 161//161 -f 10//10 9//9 162//162 -f 162//162 9//9 146//146 -f 162//162 146//146 163//163 -f 163//163 146//146 159//159 -f 140//140 161//161 137//137 -f 137//137 161//161 164//164 -f 137//137 164//164 159//159 -f 159//159 164//164 163//163 -f 1//1 41//41 26//26 -f 2//2 1//1 4//4 -f 4//4 1//1 7//7 -f 7//7 1//1 93//93 -f 93//93 1//1 26//26 -f 93//93 26//26 44//44 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 175//175 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 185//185 -f 185//185 184//184 186//186 -f 185//185 186//186 187//187 -f 187//187 186//186 188//188 -f 187//187 188//188 165//165 -f 165//165 188//188 166//166 -f 120//120 68//68 128//128 -f 128//128 68//68 85//85 -f 128//128 85//85 101//101 -f 101//101 85//85 81//81 -f 101//101 81//81 102//102 -f 102//102 81//81 79//79 -f 102//102 79//79 103//103 -f 103//103 79//79 76//76 -f 103//103 76//76 104//104 -f 104//104 76//76 75//75 -f 104//104 75//75 105//105 -f 105//105 75//75 74//74 -f 105//105 74//74 99//99 -f 99//99 74//74 73//73 -f 99//99 73//73 100//100 -f 100//100 73//73 72//72 -f 100//100 72//72 96//96 -f 96//96 72//72 71//71 -f 96//96 71//71 118//118 -f 118//118 71//71 70//70 -f 118//118 70//70 119//119 -f 119//119 70//70 69//69 -f 119//119 69//69 120//120 -f 120//120 69//69 68//68 -f 189//189 190//190 191//191 -f 191//191 190//190 192//192 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 197//197 196//196 198//198 -f 197//197 198//198 199//199 -f 199//199 198//198 200//200 -f 199//199 200//200 201//201 -f 201//201 200//200 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 205//205 204//204 206//206 -f 205//205 206//206 207//207 -f 207//207 206//206 208//208 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 189//189 -f 189//189 212//212 190//190 -f 213//213 214//214 215//215 -f 215//215 214//214 216//216 -f 215//215 216//216 217//217 -f 217//217 216//216 218//218 -f 217//217 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 225//225 224//224 226//226 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 229//229 -f 229//229 228//228 230//230 -f 229//229 230//230 231//231 -f 231//231 230//230 232//232 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 213//213 -f 213//213 236//236 214//214 -f 237//237 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 241//241 -f 241//241 240//240 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 249//249 -f 249//249 248//248 250//250 -f 249//249 250//250 251//251 -f 251//251 250//250 252//252 -f 251//251 252//252 253//253 -f 253//253 252//252 254//254 -f 253//253 254//254 255//255 -f 255//255 254//254 256//256 -f 255//255 256//256 257//257 -f 257//257 256//256 258//258 -f 257//257 258//258 259//259 -f 259//259 258//258 260//260 -f 259//259 260//260 237//237 -f 237//237 260//260 238//238 -f 261//261 262//262 263//263 -f 263//263 262//262 264//264 -f 263//263 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 267//267 -f 267//267 266//266 268//268 -f 267//267 268//268 269//269 -f 269//269 268//268 270//270 -f 269//269 270//270 271//271 -f 271//271 270//270 272//272 -f 271//271 272//272 273//273 -f 273//273 272//272 274//274 -f 273//273 274//274 275//275 -f 275//275 274//274 276//276 -f 275//275 276//276 277//277 -f 277//277 276//276 278//278 -f 277//277 278//278 279//279 -f 279//279 278//278 280//280 -f 279//279 280//280 281//281 -f 281//281 280//280 282//282 -f 281//281 282//282 283//283 -f 283//283 282//282 284//284 -f 283//283 284//284 261//261 -f 261//261 284//284 262//262 -f 111//111 59//59 113//113 -f 113//113 59//59 63//63 -f 113//113 63//63 114//114 -f 114//114 63//63 64//64 -f 114//114 64//64 115//115 -f 115//115 64//64 91//91 -f 115//115 91//91 116//116 -f 116//116 91//91 92//92 -f 116//116 92//92 117//117 -f 117//117 92//92 86//86 -f 117//117 86//86 97//97 -f 97//97 86//86 84//84 -f 97//97 84//84 98//98 -f 98//98 84//84 83//83 -f 98//98 83//83 106//106 -f 106//106 83//83 67//67 -f 106//106 67//67 108//108 -f 108//108 67//67 62//62 -f 108//108 62//62 109//109 -f 109//109 62//62 61//61 -f 109//109 61//61 110//110 -f 110//110 61//61 60//60 -f 110//110 60//60 111//111 -f 111//111 60//60 59//59 -f 149//149 49//49 150//150 -f 150//150 49//49 48//48 -f 150//150 48//48 153//153 -f 153//153 48//48 47//47 -f 153//153 47//47 154//154 -f 154//154 47//47 56//56 -f 154//154 56//56 155//155 -f 155//155 56//56 55//55 -f 155//155 55//55 156//156 -f 156//156 55//55 54//54 -f 156//156 54//54 157//157 -f 157//157 54//54 53//53 -f 157//157 53//53 158//158 -f 158//158 53//53 52//52 -f 158//158 52//52 151//151 -f 151//151 52//52 51//51 -f 151//151 51//51 152//152 -f 152//152 51//51 46//46 -f 152//152 46//46 147//147 -f 147//147 46//46 45//45 -f 147//147 45//45 148//148 -f 148//148 45//45 50//50 -f 148//148 50//50 149//149 -f 149//149 50//50 49//49 -f 122//122 89//89 123//123 -f 123//123 89//89 88//88 -f 123//123 88//88 129//129 -f 129//129 88//88 66//66 -f 129//129 66//66 130//130 -f 130//130 66//66 65//65 -f 130//130 65//65 131//131 -f 131//131 65//65 58//58 -f 131//131 58//58 94//94 -f 94//94 58//58 57//57 -f 94//94 57//57 95//95 -f 95//95 57//57 77//77 -f 95//95 77//77 127//127 -f 127//127 77//77 78//78 -f 127//127 78//78 124//124 -f 124//124 78//78 80//80 -f 124//124 80//80 125//125 -f 125//125 80//80 82//82 -f 125//125 82//82 126//126 -f 126//126 82//82 87//87 -f 126//126 87//87 121//121 -f 121//121 87//87 90//90 -f 121//121 90//90 122//122 -f 122//122 90//90 89//89 -f 139//139 24//24 143//143 -f 143//143 24//24 40//40 -f 143//143 40//40 144//144 -f 144//144 40//40 34//34 -f 144//144 34//34 145//145 -f 145//145 34//34 35//35 -f 145//145 35//35 142//142 -f 142//142 35//35 31//31 -f 142//142 31//31 141//141 -f 141//141 31//31 30//30 -f 141//141 30//30 132//132 -f 132//132 30//30 28//28 -f 132//132 28//28 133//133 -f 133//133 28//28 27//27 -f 133//133 27//27 134//134 -f 134//134 27//27 23//23 -f 134//134 23//23 135//135 -f 135//135 23//23 21//21 -f 135//135 21//21 136//136 -f 136//136 21//21 20//20 -f 136//136 20//20 138//138 -f 138//138 20//20 25//25 -f 138//138 25//25 139//139 -f 139//139 25//25 24//24 -f 285//285 286//286 287//287 -f 287//287 286//286 288//288 -f 288//288 286//286 289//289 -f 288//288 289//289 290//290 -f 290//290 289//289 291//291 -f 290//290 291//291 292//292 -f 293//293 294//294 36//36 -f 36//36 294//294 295//295 -f 296//296 297//297 298//298 -f 287//287 299//299 285//285 -f 285//285 299//299 300//300 -f 285//285 300//300 301//301 -f 301//301 300//300 302//302 -f 301//301 302//302 303//303 -f 303//303 302//302 304//304 -f 303//303 304//304 305//305 -f 305//305 304//304 36//36 -f 305//305 36//36 306//306 -f 306//306 36//36 295//295 -f 306//306 295//295 307//307 -f 307//307 295//295 308//308 -f 309//309 310//310 295//295 -f 295//295 310//310 311//311 -f 295//295 311//311 308//308 -f 291//291 310//310 292//292 -f 292//292 310//310 309//309 -f 292//292 309//309 312//312 -f 312//312 309//309 313//313 -f 312//312 313//313 314//314 -f 298//298 315//315 296//296 -f 296//296 315//315 316//316 -f 296//296 316//316 317//317 -f 317//317 316//316 293//293 -f 317//317 293//293 318//318 -f 318//318 293//293 36//36 -f 318//318 36//36 319//319 -f 320//320 321//321 38//38 -f 38//38 321//321 322//322 -f 38//38 322//322 36//36 -f 36//36 322//322 323//323 -f 36//36 323//323 319//319 -f 314//314 324//324 312//312 -f 312//312 324//324 325//325 -f 312//312 325//325 297//297 -f 296//296 326//326 297//297 -f 297//297 326//326 327//327 -f 297//297 327//327 312//312 -f 312//312 327//327 328//328 -f 312//312 328//328 38//38 -f 38//38 328//328 329//329 -f 38//38 329//329 320//320 -f 330//330 37//37 304//304 -f 304//304 37//37 36//36 -f 331//331 303//303 332//332 -f 332//332 303//303 305//305 -f 332//332 305//305 333//333 -f 333//333 305//305 306//306 -f 333//333 306//306 334//334 -f 334//334 306//306 307//307 -f 334//334 307//307 335//335 -f 335//335 307//307 308//308 -f 335//335 308//308 336//336 -f 336//336 308//308 311//311 -f 336//336 311//311 337//337 -f 337//337 311//311 310//310 -f 337//337 310//310 338//338 -f 338//338 310//310 291//291 -f 338//338 291//291 339//339 -f 339//339 291//291 289//289 -f 339//339 289//289 340//340 -f 340//340 289//289 286//286 -f 340//340 286//286 341//341 -f 341//341 286//286 285//285 -f 341//341 285//285 342//342 -f 342//342 285//285 301//301 -f 342//342 301//301 331//331 -f 331//331 301//301 303//303 -f 343//343 295//295 344//344 -f 344//344 295//295 294//294 -f 344//344 294//294 345//345 -f 345//345 294//294 293//293 -f 345//345 293//293 346//346 -f 346//346 293//293 316//316 -f 346//346 316//316 347//347 -f 347//347 316//316 315//315 -f 347//347 315//315 348//348 -f 348//348 315//315 298//298 -f 348//348 298//298 349//349 -f 349//349 298//298 297//297 -f 349//349 297//297 350//350 -f 350//350 297//297 325//325 -f 350//350 325//325 351//351 -f 351//351 325//325 324//324 -f 351//351 324//324 352//352 -f 352//352 324//324 314//314 -f 352//352 314//314 353//353 -f 353//353 314//314 313//313 -f 353//353 313//313 354//354 -f 354//354 313//313 309//309 -f 354//354 309//309 343//343 -f 343//343 309//309 295//295 -f 355//355 318//318 356//356 -f 356//356 318//318 319//319 -f 356//356 319//319 357//357 -f 357//357 319//319 323//323 -f 357//357 323//323 358//358 -f 358//358 323//323 322//322 -f 358//358 322//322 359//359 -f 359//359 322//322 321//321 -f 359//359 321//321 360//360 -f 360//360 321//321 320//320 -f 360//360 320//320 361//361 -f 361//361 320//320 329//329 -f 361//361 329//329 362//362 -f 362//362 329//329 328//328 -f 362//362 328//328 363//363 -f 363//363 328//328 327//327 -f 363//363 327//327 364//364 -f 364//364 327//327 326//326 -f 364//364 326//326 365//365 -f 365//365 326//326 296//296 -f 365//365 296//296 366//366 -f 366//366 296//296 317//317 -f 366//366 317//317 355//355 -f 355//355 317//317 318//318 -f 39//39 33//33 367//367 -f 367//367 368//368 39//39 -f 39//39 368//368 369//369 -f 39//39 369//369 38//38 -f 38//38 369//369 370//370 -f 38//38 370//370 312//312 -f 3//3 5//5 32//32 -f 32//32 5//5 6//6 -f 32//32 6//6 33//33 -f 33//33 6//6 8//8 -f 33//33 8//8 367//367 -f 32//32 42//42 3//3 -f 3//3 42//42 41//41 -f 3//3 41//41 1//1 -f 356//356 37//37 355//355 -f 355//355 37//37 330//330 -f 355//355 330//330 366//366 -f 335//335 336//336 15//15 -f 15//15 336//336 337//337 -f 15//15 337//337 338//338 -f 349//349 350//350 331//331 -f 331//331 350//350 330//330 -f 331//331 330//330 342//342 -f 350//350 351//351 330//330 -f 330//330 351//351 352//352 -f 330//330 352//352 353//353 -f 362//362 15//15 361//361 -f 361//361 15//15 29//29 -f 361//361 29//29 360//360 -f 331//331 332//332 349//349 -f 349//349 332//332 333//333 -f 349//349 333//333 334//334 -f 356//356 357//357 37//37 -f 37//37 357//357 358//358 -f 37//37 358//358 29//29 -f 29//29 358//358 359//359 -f 29//29 359//359 360//360 -f 13//13 15//15 371//371 -f 371//371 15//15 372//372 -f 347//347 348//348 363//363 -f 330//330 373//373 342//342 -f 342//342 373//373 374//374 -f 342//342 374//374 341//341 -f 341//341 374//374 375//375 -f 341//341 375//375 340//340 -f 340//340 375//375 376//376 -f 340//340 376//376 339//339 -f 339//339 376//376 377//377 -f 339//339 377//377 338//338 -f 338//338 377//377 378//378 -f 338//338 378//378 15//15 -f 15//15 378//378 379//379 -f 15//15 379//379 372//372 -f 353//353 354//354 330//330 -f 330//330 354//354 343//343 -f 330//330 343//343 366//366 -f 366//366 343//343 344//344 -f 366//366 344//344 345//345 -f 334//334 335//335 349//349 -f 349//349 335//335 15//15 -f 349//349 15//15 348//348 -f 348//348 15//15 362//362 -f 348//348 362//362 363//363 -f 347//347 363//363 346//346 -f 346//346 363//363 364//364 -f 346//346 364//364 345//345 -f 345//345 364//364 365//365 -f 345//345 365//365 366//366 -f 214//214 236//236 162//162 -f 224//224 222//222 12//12 -f 236//236 234//234 162//162 -f 162//162 234//234 232//232 -f 162//162 232//232 10//10 -f 222//222 220//220 380//380 -f 380//380 220//220 218//218 -f 380//380 218//218 216//216 -f 232//232 230//230 10//10 -f 10//10 230//230 228//228 -f 10//10 228//228 12//12 -f 12//12 228//228 226//226 -f 12//12 226//226 224//224 -f 163//163 164//164 162//162 -f 162//162 164//164 380//380 -f 162//162 380//380 214//214 -f 214//214 380//380 216//216 -f 210//210 380//380 212//212 -f 212//212 380//380 190//190 -f 176//176 14//14 178//178 -f 178//178 14//14 12//12 -f 184//184 182//182 12//12 -f 12//12 182//182 180//180 -f 12//12 180//180 178//178 -f 176//176 174//174 14//14 -f 14//14 174//174 172//172 -f 14//14 172//172 170//170 -f 160//160 242//242 240//240 -f 190//190 380//380 192//192 -f 192//192 380//380 160//160 -f 192//192 160//160 194//194 -f 252//252 250//250 170//170 -f 170//170 250//250 248//248 -f 170//170 248//248 14//14 -f 14//14 248//248 246//246 -f 14//14 246//246 160//160 -f 160//160 246//246 244//244 -f 160//160 244//244 242//242 -f 222//222 380//380 12//12 -f 12//12 380//380 186//186 -f 12//12 186//186 184//184 -f 210//210 208//208 380//380 -f 380//380 208//208 206//206 -f 380//380 206//206 186//186 -f 186//186 206//206 204//204 -f 186//186 204//204 188//188 -f 188//188 204//204 166//166 -f 252//252 170//170 254//254 -f 254//254 170//170 168//168 -f 254//254 168//168 166//166 -f 204//204 202//202 166//166 -f 166//166 202//202 200//200 -f 166//166 200//200 254//254 -f 254//254 200//200 198//198 -f 254//254 198//198 256//256 -f 256//256 198//198 196//196 -f 256//256 196//196 258//258 -f 258//258 196//196 194//194 -f 258//258 194//194 260//260 -f 260//260 194//194 160//160 -f 260//260 160//160 238//238 -f 238//238 160//160 240//240 -f 164//164 284//284 282//282 -f 164//164 282//282 380//380 -f 380//380 282//282 280//280 -f 380//380 280//280 278//278 -f 270//270 268//268 160//160 -f 160//160 268//268 161//161 -f 278//278 276//276 380//380 -f 380//380 276//276 274//274 -f 380//380 274//274 160//160 -f 160//160 274//274 272//272 -f 160//160 272//272 270//270 -f 268//268 266//266 161//161 -f 161//161 266//266 264//264 -f 161//161 264//264 164//164 -f 164//164 264//264 262//262 -f 164//164 262//262 284//284 -f 93//93 11//11 7//7 -f 7//7 11//11 13//13 -f 7//7 13//13 371//371 -f 281//281 283//283 381//381 -f 381//381 283//283 261//261 -f 381//381 261//261 263//263 -f 275//275 277//277 381//381 -f 381//381 277//277 279//279 -f 381//381 279//279 281//281 -f 269//269 271//271 381//381 -f 381//381 271//271 273//273 -f 381//381 273//273 275//275 -f 263//263 265//265 381//381 -f 381//381 265//265 267//267 -f 381//381 267//267 269//269 -f 257//257 259//259 382//382 -f 382//382 259//259 237//237 -f 382//382 237//237 239//239 -f 251//251 253//253 382//382 -f 382//382 253//253 255//255 -f 382//382 255//255 257//257 -f 245//245 247//247 382//382 -f 382//382 247//247 249//249 -f 382//382 249//249 251//251 -f 239//239 241//241 382//382 -f 382//382 241//241 243//243 -f 382//382 243//243 245//245 -f 233//233 235//235 383//383 -f 383//383 235//235 213//213 -f 383//383 213//213 215//215 -f 227//227 229//229 383//383 -f 383//383 229//229 231//231 -f 383//383 231//231 233//233 -f 221//221 223//223 383//383 -f 383//383 223//223 225//225 -f 383//383 225//225 227//227 -f 215//215 217//217 383//383 -f 383//383 217//217 219//219 -f 383//383 219//219 221//221 -f 209//209 211//211 384//384 -f 384//384 211//211 189//189 -f 384//384 189//189 191//191 -f 203//203 205//205 384//384 -f 384//384 205//205 207//207 -f 384//384 207//207 209//209 -f 197//197 199//199 384//384 -f 384//384 199//199 201//201 -f 384//384 201//201 203//203 -f 191//191 193//193 384//384 -f 384//384 193//193 195//195 -f 384//384 195//195 197//197 -f 185//185 187//187 385//385 -f 385//385 187//187 165//165 -f 385//385 165//165 167//167 -f 179//179 181//181 385//385 -f 385//385 181//181 183//183 -f 385//385 183//183 185//185 -f 173//173 175//175 385//385 -f 385//385 175//175 177//177 -f 385//385 177//177 179//179 -f 167//167 169//169 385//385 -f 385//385 169//169 171//171 -f 385//385 171//171 173//173 -f 372//372 370//370 371//371 -f 371//371 370//370 369//369 -f 8//8 7//7 367//367 -f 367//367 7//7 371//371 -f 367//367 371//371 368//368 -f 368//368 371//371 369//369 -f 377//377 288//288 378//378 -f 378//378 288//288 290//290 -f 378//378 290//290 379//379 -f 379//379 290//290 292//292 -f 379//379 292//292 372//372 -f 372//372 292//292 312//312 -f 372//372 312//312 370//370 -f 330//330 304//304 302//302 -f 330//330 302//302 373//373 -f 373//373 302//302 300//300 -f 373//373 300//300 374//374 -f 374//374 300//300 299//299 -f 374//374 299//299 375//375 -f 375//375 299//299 287//287 -f 375//375 287//287 376//376 -f 376//376 287//287 288//288 -f 376//376 288//288 377//377 -# 798 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_plate.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_plate.obj deleted file mode 100644 index 980672b85..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_plate.obj +++ /dev/null @@ -1,2052 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object T_BOT_NOVE_SISE_I_LETVA2022 - lift za ruke-1.obj -# -# Vertices: 496 -# Faces: 1044 -# -#### -vn -1.570796 -1.570796 -1.570796 -v 0.052000 0.017500 0.011000 -vn -1.570796 -1.570796 1.570796 -v 0.052000 0.017500 0.014000 -vn -3.141593 0.000000 -3.141593 -v 0.052000 0.046407 0.011000 -vn -3.141593 0.000000 3.141593 -v 0.052000 0.046407 0.014000 -vn -3.141593 0.000000 -3.141593 -v 0.052000 0.068905 0.011000 -vn -3.141592 0.000000 3.141593 -v 0.052000 0.068905 0.014000 -vn -3.141592 0.000000 -3.141583 -v 0.052000 0.107750 0.011000 -vn -3.141592 0.000000 3.141588 -v 0.052000 0.107750 0.014000 -vn -3.088069 0.406551 -2.879793 -v 0.052000 0.140000 0.011000 -vn -3.088069 0.406551 2.879793 -v 0.052000 0.140000 0.014000 -vn 1.570796 -1.570796 -1.570796 -v 0.067000 0.017500 0.011000 -vn 1.570796 -1.570796 -4.712391 -v 0.067000 0.024705 0.011000 -vn 1.570796 -1.570796 1.570796 -v 0.067000 0.017500 0.014000 -vn 1.570796 -1.570796 4.712392 -v 0.067000 0.024705 0.014000 -vn -0.406548 3.088070 -2.879796 -v 0.057000 0.145000 0.011000 -vn -0.406548 3.088070 2.879796 -v 0.057000 0.145000 0.014000 -vn 0.000000 3.141593 -3.141591 -v 0.062800 0.145000 0.011000 -vn 0.000000 3.141593 3.141590 -v 0.062800 0.145000 0.014000 -vn 0.000000 3.141593 -3.141593 -v 0.077000 0.145000 0.011000 -vn 0.000000 3.141593 3.141593 -v 0.077000 0.145000 0.014000 -vn 0.000000 3.141593 -3.141590 -v 0.090035 0.145000 0.011000 -vn 0.000000 3.141593 3.141590 -v 0.090035 0.145000 0.014000 -vn 0.306449 3.111410 -2.945242 -v 0.095000 0.145000 0.011000 -vn 0.306449 3.111410 2.945242 -v 0.095000 0.145000 0.014000 -vn -0.406548 -3.088070 2.879796 -v 0.057000 -0.145000 0.014000 -vn -0.406548 -3.088070 -2.879796 -v 0.057000 -0.145000 0.011000 -vn 0.000000 -3.141593 3.141593 -v 0.062800 -0.145000 0.014000 -vn 0.000000 -3.141593 -3.141593 -v 0.062800 -0.145000 0.011000 -vn 0.000000 -3.141593 3.141593 -v 0.077000 -0.145000 0.014000 -vn 0.000000 -3.141593 -3.141593 -v 0.077000 -0.145000 0.011000 -vn 0.000000 -3.141593 3.141593 -v 0.090035 -0.145000 0.014000 -vn 0.000000 -3.141593 -3.141593 -v 0.090035 -0.145000 0.011000 -vn 0.406549 -3.088070 2.879795 -v 0.095000 -0.145000 0.014000 -vn 0.406549 -3.088070 -2.879795 -v 0.095000 -0.145000 0.011000 -vn 3.111410 0.306450 -2.945242 -v 0.100000 0.140000 0.011000 -vn 3.111409 0.306450 2.945241 -v 0.100000 0.140000 0.014000 -vn 3.141592 0.000000 -3.141594 -v 0.100000 0.107750 0.011000 -vn 3.141592 0.000000 3.141592 -v 0.100000 0.107750 0.014000 -vn 3.141592 0.000000 -3.141591 -v 0.100000 0.068905 0.011000 -vn 3.141593 0.000000 3.141591 -v 0.100000 0.068905 0.014000 -vn 3.141593 0.000000 -3.141593 -v 0.100000 0.046407 0.011000 -vn 3.141593 0.000000 3.141593 -v 0.100000 0.046407 0.014000 -vn 3.141593 0.000000 -3.141593 -v 0.100000 0.000000 0.011000 -vn 3.141593 0.000000 3.141593 -v 0.100000 0.000000 0.014000 -vn 3.141593 0.000000 -3.141593 -v 0.100000 -0.046407 0.011000 -vn 3.141593 0.000000 3.141593 -v 0.100000 -0.046407 0.014000 -vn 3.141593 0.000000 -3.141591 -v 0.100000 -0.068905 0.011000 -vn 3.141592 0.000000 3.141590 -v 0.100000 -0.068905 0.014000 -vn 3.141592 0.000000 -3.141592 -v 0.100000 -0.107750 0.011000 -vn 3.141592 0.000000 3.141594 -v 0.100000 -0.107750 0.014000 -vn 3.088068 -0.406553 -2.879793 -v 0.100000 -0.140000 0.011000 -vn 3.088069 -0.406553 2.879794 -v 0.100000 -0.140000 0.014000 -vn -2.628000 -1.517264 3.665189 -v 0.094302 -0.079000 0.014000 -vn -3.034548 -0.000003 3.665185 -v 0.094570 -0.080000 0.014000 -vn -2.627994 -1.517271 3.665192 -v 0.060819 0.058760 0.014000 -vn -3.034546 0.000000 3.665189 -v 0.061100 0.057710 0.014000 -vn 0.000000 0.000000 6.283181 -v 0.062800 0.068905 0.014000 -vn 1.570796 1.570796 4.712391 -v 0.067000 -0.024705 0.014000 -vn 1.570796 1.570796 1.570796 -v 0.067000 -0.017500 0.014000 -vn 0.000000 3.141593 3.141593 -v 0.062800 -0.017500 0.014000 -vn -1.517270 -2.627993 2.617990 -v 0.054500 -0.144330 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.056170 -0.141250 0.014000 -vn -0.000001 3.034543 3.665198 -v 0.057440 -0.137500 0.014000 -vn 1.517277 2.627992 3.665189 -v 0.056440 -0.137232 0.014000 -vn 2.627994 -1.517272 3.665193 -v 0.055708 0.136500 0.014000 -vn -2.627995 1.517271 2.617995 -v 0.052670 0.142500 0.014000 -vn 1.517277 -2.627992 3.665189 -v 0.056440 0.137232 0.014000 -vn -1.517278 -2.627992 3.665188 -v 0.058440 0.137232 0.014000 -vn -0.000001 -3.034543 3.665198 -v 0.057440 0.137500 0.014000 -vn -1.517270 2.627994 2.617990 -v 0.054500 0.144330 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.056170 0.107750 0.014000 -vn 0.000000 0.000000 6.283187 -v 0.062800 0.107750 0.014000 -vn -1.517278 2.627992 3.665187 -v 0.058440 0.133768 0.014000 -vn -0.000001 3.034543 3.665198 -v 0.057440 0.133500 0.014000 -vn 1.517277 2.627992 3.665189 -v 0.056440 0.133768 0.014000 -vn 2.627994 1.517272 3.665192 -v 0.055708 0.134500 0.014000 -vn 3.034546 -0.000000 3.665190 -v 0.055440 0.135500 0.014000 -vn -2.627992 -1.517277 3.665189 -v 0.059172 0.136500 0.014000 -vn -3.034543 0.000000 3.665197 -v 0.059440 0.135500 0.014000 -vn -2.627992 1.517277 3.665189 -v 0.059172 0.134500 0.014000 -vn -1.517278 2.627992 3.665188 -v 0.058440 -0.137232 0.014000 -vn -1.517278 -2.627992 3.665188 -v 0.058440 -0.133768 0.014000 -vn -2.627992 -1.517277 3.665189 -v 0.059172 -0.134500 0.014000 -vn 0.000000 0.000000 6.283188 -v 0.062800 -0.107750 0.014000 -vn -3.034543 0.000000 3.665196 -v 0.059440 -0.135500 0.014000 -vn 0.000000 0.000000 6.283184 -v 0.062800 -0.141250 0.014000 -vn -2.627992 1.517277 3.665189 -v 0.059172 -0.136500 0.014000 -vn 2.627994 1.517272 3.665192 -v 0.055708 -0.136500 0.014000 -vn -3.088069 -0.406551 2.879793 -v 0.052000 -0.140000 0.014000 -vn 3.034546 -0.000000 3.665190 -v 0.055440 -0.135500 0.014000 -vn -3.141592 0.000000 3.141583 -v 0.052000 -0.107750 0.014000 -vn 2.627994 -1.517272 3.665192 -v 0.055708 -0.134500 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.056170 -0.107750 0.014000 -vn 1.517277 -2.627992 3.665189 -v 0.056440 -0.133768 0.014000 -vn -0.000001 -3.034543 3.665198 -v 0.057440 -0.133500 0.014000 -vn -1.517278 2.627992 3.665187 -v 0.058440 -0.081732 0.014000 -vn 2.627999 -1.517269 3.665185 -v 0.055708 -0.079000 0.014000 -vn 1.517272 -2.627990 3.665201 -v 0.056440 -0.078268 0.014000 -vn 0.000000 0.000000 6.283181 -v 0.056170 -0.068905 0.014000 -vn -0.000001 -3.034549 3.665184 -v 0.057440 -0.078000 0.014000 -vn 0.000000 0.000000 6.283179 -v 0.062800 -0.068905 0.014000 -vn -1.517273 -2.627989 3.665200 -v 0.058440 -0.078268 0.014000 -vn -2.627997 -1.517274 3.665182 -v 0.059172 -0.079000 0.014000 -vn -3.034543 -0.000003 3.665199 -v 0.059440 -0.080000 0.014000 -vn -2.627992 1.517277 3.665189 -v 0.059172 -0.081000 0.014000 -vn 3.034545 -0.000003 3.665192 -v 0.055440 -0.080000 0.014000 -vn -3.141593 0.000000 3.141594 -v 0.052000 -0.068905 0.014000 -vn -0.000001 3.034543 3.665198 -v 0.057440 -0.082000 0.014000 -vn 1.517277 2.627992 3.665189 -v 0.056440 -0.081732 0.014000 -vn 2.627994 1.517272 3.665192 -v 0.055708 -0.081000 0.014000 -vn 1.517272 2.627990 3.665201 -v 0.056440 0.078268 0.014000 -vn 2.627999 1.517269 3.665185 -v 0.055708 0.079000 0.014000 -vn 3.034545 0.000003 3.665192 -v 0.055440 0.080000 0.014000 -vn 2.627994 -1.517272 3.665192 -v 0.055708 0.081000 0.014000 -vn -0.000001 3.034549 3.665184 -v 0.057440 0.078000 0.014000 -vn 0.000000 0.000000 6.283182 -v 0.056170 0.068905 0.014000 -vn -1.517273 2.627989 3.665200 -v 0.058440 0.078268 0.014000 -vn 1.517277 -2.627992 3.665189 -v 0.056440 0.081732 0.014000 -vn -0.000001 -3.034543 3.665198 -v 0.057440 0.082000 0.014000 -vn -1.517278 -2.627992 3.665188 -v 0.058440 0.081732 0.014000 -vn -2.627992 -1.517277 3.665189 -v 0.059172 0.081000 0.014000 -vn -3.034543 0.000003 3.665199 -v 0.059440 0.080000 0.014000 -vn -2.627997 1.517274 3.665182 -v 0.059172 0.079000 0.014000 -vn -1.517277 2.627992 3.665189 -v 0.093570 0.133768 0.014000 -vn 0.000000 0.000000 6.283190 -v 0.090035 0.107750 0.014000 -vn 0.000000 3.034543 3.665197 -v 0.092570 0.133500 0.014000 -vn 1.517277 2.627992 3.665189 -v 0.091570 0.133768 0.014000 -vn 2.627995 1.517266 3.665195 -v 0.090838 0.134500 0.014000 -vn 3.034549 0.000000 3.665183 -v 0.090570 0.135500 0.014000 -vn 2.627995 -1.517266 3.665196 -v 0.090838 0.136500 0.014000 -vn 1.517277 -2.627992 3.665189 -v 0.091570 0.137232 0.014000 -vn 0.000000 -3.034543 3.665196 -v 0.092570 0.137500 0.014000 -vn 1.179132 2.846686 2.748898 -v 0.096913 0.144619 0.014000 -vn -1.517277 -2.627992 3.665188 -v 0.093570 0.137232 0.014000 -vn 2.178754 2.178758 2.748888 -v 0.098536 0.143536 0.014000 -vn 2.846684 1.179136 2.748897 -v 0.099619 0.141913 0.014000 -vn -2.627995 -1.517266 3.665196 -v 0.094302 0.136500 0.014000 -vn -3.034549 0.000000 3.665183 -v 0.094570 0.135500 0.014000 -vn -2.627995 1.517266 3.665195 -v 0.094302 0.134500 0.014000 -vn 0.000000 3.034543 3.665197 -v 0.092570 -0.137500 0.014000 -vn 1.517277 2.627992 3.665189 -v 0.091570 -0.137232 0.014000 -vn 0.000000 0.000000 6.283187 -v 0.090035 -0.141250 0.014000 -vn -1.517277 2.627992 3.665189 -v 0.093570 -0.137232 0.014000 -vn 2.627993 -1.517274 2.617994 -v 0.099330 -0.142500 0.014000 -vn -2.627995 1.517266 3.665195 -v 0.094302 -0.136500 0.014000 -vn 0.000000 0.000000 6.283190 -v 0.090035 -0.107750 0.014000 -vn 1.517277 -2.627992 3.665189 -v 0.091570 -0.133768 0.014000 -vn 0.000000 -3.034543 3.665197 -v 0.092570 -0.133500 0.014000 -vn -1.517277 -2.627992 3.665189 -v 0.093570 -0.133768 0.014000 -vn -2.627995 -1.517266 3.665196 -v 0.094302 -0.134500 0.014000 -vn -3.034549 0.000000 3.665183 -v 0.094570 -0.135500 0.014000 -vn 2.627995 1.517266 3.665195 -v 0.090838 -0.136500 0.014000 -vn 3.034549 0.000000 3.665183 -v 0.090570 -0.135500 0.014000 -vn 2.627995 -1.517266 3.665195 -v 0.090838 -0.134500 0.014000 -vn 1.517270 -2.627994 2.617992 -v 0.097500 -0.144330 0.014000 -vn -2.627995 -1.517271 2.617994 -v 0.052670 -0.142500 0.014000 -vn 0.000000 0.000000 6.283188 -v 0.062800 -0.046407 0.014000 -vn 2.627990 1.517279 3.665191 -v 0.064835 -0.035955 0.014000 -vn 3.034543 -0.000001 3.665200 -v 0.064500 -0.034705 0.014000 -vn 2.627992 -1.517278 3.665190 -v 0.064835 -0.033455 0.014000 -vn 1.517269 -2.627994 3.665194 -v 0.065750 -0.032540 0.014000 -vn 0.000000 -3.034547 3.665187 -v 0.067000 -0.032205 0.014000 -vn 0.000000 3.141593 3.141590 -v 0.077000 -0.024705 0.014000 -vn -1.517270 -2.627995 3.665194 -v 0.068250 -0.032540 0.014000 -vn -2.627994 -1.517269 3.665194 -v 0.069165 -0.033455 0.014000 -vn -3.034548 -0.000001 3.665186 -v 0.069500 -0.034705 0.014000 -vn -2.627992 1.517271 3.665196 -v 0.069165 -0.035955 0.014000 -vn 0.000000 0.000000 6.283184 -v 0.077000 -0.046407 0.014000 -vn -1.517272 2.627995 3.665189 -v 0.068250 -0.036870 0.014000 -vn 0.000000 3.034545 3.665193 -v 0.067000 -0.037205 0.014000 -vn 1.517272 2.627995 3.665189 -v 0.065750 -0.036870 0.014000 -vn 0.000000 3.141593 3.141593 -v 0.056170 -0.017500 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.056170 -0.046407 0.014000 -vn 0.000000 3.034545 3.665193 -v 0.087000 -0.037205 0.014000 -vn 1.517272 2.627995 3.665189 -v 0.085750 -0.036870 0.014000 -vn 0.000000 -3.034547 3.665187 -v 0.087000 -0.032205 0.014000 -vn -1.517270 -2.627995 3.665194 -v 0.088250 -0.032540 0.014000 -vn -1.570797 1.570796 4.712385 -v 0.089000 -0.024705 0.014000 -vn -2.627992 -1.517278 3.665189 -v 0.089165 -0.033455 0.014000 -vn 0.000000 0.000000 6.283184 -v 0.090035 0.000000 0.014000 -vn -3.034543 -0.000001 3.665197 -v 0.089500 -0.034705 0.014000 -vn 0.000000 0.000000 6.283188 -v 0.090035 -0.046407 0.014000 -vn -2.627990 1.517279 3.665191 -v 0.089165 -0.035955 0.014000 -vn -1.517272 2.627995 3.665189 -v 0.088250 -0.036870 0.014000 -vn 2.627992 1.517271 3.665196 -v 0.084835 -0.035955 0.014000 -vn 3.034547 -0.000001 3.665186 -v 0.084500 -0.034705 0.014000 -vn 2.627995 -1.517270 3.665193 -v 0.084835 -0.033455 0.014000 -vn 1.517269 -2.627994 3.665194 -v 0.085750 -0.032540 0.014000 -vn -3.141593 0.000000 3.141593 -v 0.089000 0.000000 0.014000 -vn -2.627990 -1.517279 3.665191 -v 0.089165 0.035955 0.014000 -vn -3.034543 0.000001 3.665198 -v 0.089500 0.034705 0.014000 -vn 0.000000 0.000000 6.283188 -v 0.090035 0.046407 0.014000 -vn -1.570796 -1.570796 4.712389 -v 0.089000 0.024705 0.014000 -vn -2.627992 1.517278 3.665188 -v 0.089165 0.033455 0.014000 -vn 1.517272 -2.627995 3.665189 -v 0.085750 0.036870 0.014000 -vn -0.000000 -3.034545 3.665193 -v 0.087000 0.037205 0.014000 -vn -1.517272 -2.627995 3.665189 -v 0.088250 0.036870 0.014000 -vn 1.517270 2.627995 3.665194 -v 0.085750 0.032540 0.014000 -vn 0.000000 -3.141593 3.141590 -v 0.077000 0.024705 0.014000 -vn -0.000000 3.034547 3.665187 -v 0.087000 0.032205 0.014000 -vn -1.517269 2.627994 3.665194 -v 0.088250 0.032540 0.014000 -vn 2.627994 1.517269 3.665194 -v 0.084835 0.033455 0.014000 -vn 3.034548 0.000001 3.665186 -v 0.084500 0.034705 0.014000 -vn 0.000000 0.000000 6.283184 -v 0.077000 0.046407 0.014000 -vn 2.627992 -1.517271 3.665196 -v 0.084835 0.035955 0.014000 -vn 2.627990 -1.517279 3.665191 -v 0.064835 0.035955 0.014000 -vn 1.517272 -2.627995 3.665189 -v 0.065750 0.036870 0.014000 -vn 0.000000 0.000000 6.283187 -v 0.062800 0.046407 0.014000 -vn 3.034543 0.000001 3.665200 -v 0.064500 0.034705 0.014000 -vn -3.034547 0.000001 3.665186 -v 0.069500 0.034705 0.014000 -vn -2.627992 -1.517271 3.665196 -v 0.069165 0.035955 0.014000 -vn -1.517272 -2.627995 3.665189 -v 0.068250 0.036870 0.014000 -vn -0.000000 -3.034545 3.665193 -v 0.067000 0.037205 0.014000 -vn -2.627995 1.517270 3.665194 -v 0.069165 0.033455 0.014000 -vn -1.517269 2.627994 3.665194 -v 0.068250 0.032540 0.014000 -vn -0.000000 3.034547 3.665187 -v 0.067000 0.032205 0.014000 -vn 1.517270 2.627995 3.665194 -v 0.065750 0.032540 0.014000 -vn 0.000000 -3.141593 3.141593 -v 0.062800 0.017500 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.056170 0.046407 0.014000 -vn 0.000000 -3.141593 3.141593 -v 0.056170 0.017500 0.014000 -vn 1.517277 -2.627992 3.665189 -v 0.091570 0.081732 0.014000 -vn 0.000000 -3.034543 3.665197 -v 0.092570 0.082000 0.014000 -vn -2.628000 1.517264 3.665189 -v 0.094302 0.079000 0.014000 -vn -3.034548 0.000003 3.665185 -v 0.094570 0.080000 0.014000 -vn -2.627995 -1.517266 3.665195 -v 0.094302 0.081000 0.014000 -vn -1.517272 2.627990 3.665201 -v 0.093570 0.078268 0.014000 -vn 0.000000 3.034549 3.665183 -v 0.092570 0.078000 0.014000 -vn 0.000000 0.000000 6.283190 -v 0.090035 0.068905 0.014000 -vn 1.517272 2.627990 3.665201 -v 0.091570 0.078268 0.014000 -vn -1.517277 -2.627992 3.665189 -v 0.093570 0.081732 0.014000 -vn 2.628000 1.517264 3.665189 -v 0.090838 0.079000 0.014000 -vn 3.034548 0.000003 3.665185 -v 0.090570 0.080000 0.014000 -vn 2.627995 -1.517266 3.665195 -v 0.090838 0.081000 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.077000 0.107750 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.077000 0.068905 0.014000 -vn 0.000000 3.034546 3.665189 -v 0.059000 0.055610 0.014000 -vn 1.517271 2.627994 3.665193 -v 0.057950 0.055891 0.014000 -vn -2.627994 1.517271 3.665193 -v 0.060819 0.056660 0.014000 -vn -1.517271 2.627994 3.665193 -v 0.060050 0.055891 0.014000 -vn 2.627993 1.517276 3.665189 -v 0.057181 0.056660 0.014000 -vn 3.034544 0.000000 3.665196 -v 0.056900 0.057710 0.014000 -vn 2.627993 -1.517276 3.665190 -v 0.057181 0.058760 0.014000 -vn 2.627992 1.517278 3.665190 -v 0.064835 0.033455 0.014000 -vn 1.517276 -2.627993 3.665189 -v 0.057950 0.059529 0.014000 -vn 0.000000 -3.034544 3.665196 -v 0.059000 0.059810 0.014000 -vn -1.517276 -2.627993 3.665189 -v 0.060050 0.059529 0.014000 -vn 0.000000 0.000000 6.283190 -v 0.090035 -0.068905 0.014000 -vn -3.034546 0.000000 3.665189 -v 0.061100 -0.057710 0.014000 -vn -2.627994 -1.517271 3.665193 -v 0.060819 -0.056660 0.014000 -vn 2.627993 -1.517276 3.665189 -v 0.057181 -0.056660 0.014000 -vn 3.034544 0.000000 3.665196 -v 0.056900 -0.057710 0.014000 -vn 2.627993 1.517276 3.665190 -v 0.057181 -0.058760 0.014000 -vn 1.517276 2.627993 3.665189 -v 0.057950 -0.059529 0.014000 -vn -2.627994 1.517271 3.665192 -v 0.060819 -0.058760 0.014000 -vn -1.517276 2.627993 3.665189 -v 0.060050 -0.059529 0.014000 -vn -0.000000 3.034544 3.665195 -v 0.059000 -0.059810 0.014000 -vn 1.517271 -2.627994 3.665193 -v 0.057950 -0.055891 0.014000 -vn -0.000000 -3.034546 3.665189 -v 0.059000 -0.055610 0.014000 -vn -1.517271 -2.627994 3.665193 -v 0.060050 -0.055891 0.014000 -vn -1.570796 1.570796 1.570796 -v 0.052000 -0.017500 0.014000 -vn -3.141593 0.000000 3.141593 -v 0.052000 -0.046407 0.014000 -vn 1.517272 -2.627990 3.665201 -v 0.091570 -0.078268 0.014000 -vn 0.000000 -3.034549 3.665183 -v 0.092570 -0.078000 0.014000 -vn -1.517272 -2.627990 3.665201 -v 0.093570 -0.078268 0.014000 -vn -2.627995 1.517266 3.665195 -v 0.094302 -0.081000 0.014000 -vn -1.517277 2.627992 3.665189 -v 0.093570 -0.081732 0.014000 -vn 0.000000 3.034543 3.665197 -v 0.092570 -0.082000 0.014000 -vn 1.517277 2.627992 3.665189 -v 0.091570 -0.081732 0.014000 -vn 2.627995 1.517266 3.665195 -v 0.090838 -0.081000 0.014000 -vn 3.034548 -0.000003 3.665185 -v 0.090570 -0.080000 0.014000 -vn 2.628000 -1.517264 3.665189 -v 0.090838 -0.079000 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.077000 -0.068905 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.077000 -0.107750 0.014000 -vn 0.000000 0.000000 6.283185 -v 0.077000 -0.141250 0.014000 -vn -0.000001 -3.034549 -3.665184 -v 0.057440 -0.078000 0.011000 -vn 1.517272 -2.627990 -3.665201 -v 0.056440 -0.078268 0.011000 -vn 0.000000 0.000000 -6.283182 -v 0.056170 -0.068905 0.011000 -vn 0.000000 -3.141593 -3.141593 -v 0.062800 0.017500 0.011000 -vn 0.000000 -3.141593 -3.141593 -v 0.056170 0.017500 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.056170 0.046407 0.011000 -vn 1.517269 2.627994 -3.665194 -v 0.065750 0.032540 0.011000 -vn 0.000000 3.034547 -3.665187 -v 0.067000 0.032205 0.011000 -vn -2.627994 1.517269 -3.665194 -v 0.069165 0.033455 0.011000 -vn -3.034548 0.000001 -3.665186 -v 0.069500 0.034705 0.011000 -vn 0.000000 -3.141593 -3.141590 -v 0.077000 0.024705 0.011000 -vn -1.517270 2.627995 -3.665194 -v 0.068250 0.032540 0.011000 -vn 3.034543 0.000001 -3.665200 -v 0.064500 0.034705 0.011000 -vn 0.000000 0.000000 -6.283188 -v 0.062800 0.046407 0.011000 -vn 2.627990 -1.517279 -3.665191 -v 0.064835 0.035955 0.011000 -vn 1.517272 -2.627995 -3.665189 -v 0.065750 0.036870 0.011000 -vn -2.627992 -1.517271 -3.665196 -v 0.069165 0.035955 0.011000 -vn 0.000000 0.000000 -6.283184 -v 0.077000 0.046407 0.011000 -vn -1.517272 -2.627995 -3.665189 -v 0.068250 0.036870 0.011000 -vn 0.000000 -3.034545 -3.665193 -v 0.067000 0.037205 0.011000 -vn 2.627992 -1.517271 -3.665196 -v 0.084835 0.035955 0.011000 -vn 3.034547 0.000001 -3.665186 -v 0.084500 0.034705 0.011000 -vn -3.034543 0.000001 -3.665199 -v 0.089500 0.034705 0.011000 -vn -1.570797 -1.570796 -4.712388 -v 0.089000 0.024705 0.011000 -vn -2.627992 1.517278 -3.665188 -v 0.089165 0.033455 0.011000 -vn -1.517270 2.627995 -3.665194 -v 0.088250 0.032540 0.011000 -vn 2.627995 1.517270 -3.665194 -v 0.084835 0.033455 0.011000 -vn 1.517269 2.627994 -3.665194 -v 0.085750 0.032540 0.011000 -vn 0.000000 3.034547 -3.665187 -v 0.087000 0.032205 0.011000 -vn -2.627990 -1.517279 -3.665191 -v 0.089165 0.035955 0.011000 -vn 0.000000 0.000000 -6.283188 -v 0.090035 0.046407 0.011000 -vn 0.000000 0.000000 -6.283181 -v 0.090035 0.000000 0.011000 -vn -3.141593 0.000000 -3.141593 -v 0.089000 0.000000 0.011000 -vn -1.517272 -2.627995 -3.665189 -v 0.088250 0.036870 0.011000 -vn 0.000000 -3.034545 -3.665193 -v 0.087000 0.037205 0.011000 -vn 1.517272 -2.627995 -3.665189 -v 0.085750 0.036870 0.011000 -vn 2.627994 -1.517269 -3.665194 -v 0.084835 -0.033455 0.011000 -vn 3.034548 -0.000001 -3.665186 -v 0.084500 -0.034705 0.011000 -vn 0.000000 3.141593 -3.141591 -v 0.077000 -0.024705 0.011000 -vn -1.570796 1.570796 -4.712389 -v 0.089000 -0.024705 0.011000 -vn -3.034543 -0.000001 -3.665199 -v 0.089500 -0.034705 0.011000 -vn -2.627992 -1.517278 -3.665188 -v 0.089165 -0.033455 0.011000 -vn -0.000000 3.034545 -3.665193 -v 0.087000 -0.037205 0.011000 -vn -1.517272 2.627995 -3.665189 -v 0.088250 -0.036870 0.011000 -vn 0.000000 0.000000 -6.283188 -v 0.090035 -0.046407 0.011000 -vn 0.000000 0.000000 -6.283184 -v 0.077000 -0.046407 0.011000 -vn 2.627992 1.517271 -3.665196 -v 0.084835 -0.035955 0.011000 -vn 1.517272 2.627995 -3.665189 -v 0.085750 -0.036870 0.011000 -vn -1.517269 -2.627994 -3.665194 -v 0.088250 -0.032540 0.011000 -vn -0.000000 -3.034547 -3.665187 -v 0.087000 -0.032205 0.011000 -vn 1.517270 -2.627995 -3.665194 -v 0.085750 -0.032540 0.011000 -vn -2.627990 1.517279 -3.665191 -v 0.089165 -0.035955 0.011000 -vn 1.517272 2.627995 -3.665189 -v 0.065750 -0.036870 0.011000 -vn 0.000000 0.000000 -6.283188 -v 0.062800 -0.046407 0.011000 -vn 2.627990 1.517279 -3.665191 -v 0.064835 -0.035955 0.011000 -vn 3.034543 -0.000001 -3.665197 -v 0.064500 -0.034705 0.011000 -vn 0.000000 3.141593 -3.141598 -v 0.062800 -0.017500 0.011000 -vn 1.570796 1.570796 -1.570796 -v 0.067000 -0.017500 0.011000 -vn 1.570796 1.570796 -4.712417 -v 0.067000 -0.024705 0.011000 -vn 2.627992 -1.517278 -3.665188 -v 0.064835 -0.033455 0.011000 -vn 1.517270 -2.627995 -3.665194 -v 0.065750 -0.032540 0.011000 -vn -0.000000 -3.034547 -3.665187 -v 0.067000 -0.032205 0.011000 -vn -1.517269 -2.627994 -3.665194 -v 0.068250 -0.032540 0.011000 -vn -0.000000 3.034545 -3.665193 -v 0.067000 -0.037205 0.011000 -vn -1.517272 2.627995 -3.665189 -v 0.068250 -0.036870 0.011000 -vn -2.627992 1.517271 -3.665196 -v 0.069165 -0.035955 0.011000 -vn -3.034547 -0.000001 -3.665194 -v 0.069500 -0.034705 0.011000 -vn -2.627995 -1.517270 -3.665194 -v 0.069165 -0.033455 0.011000 -vn 0.000000 3.141593 -3.141593 -v 0.056170 -0.017500 0.011000 -vn 0.000000 0.000000 -6.283186 -v 0.056170 -0.046407 0.011000 -vn -1.570796 1.570796 -1.570796 -v 0.052000 -0.017500 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.056170 -0.141250 0.011000 -vn -3.088069 -0.406551 -2.879793 -v 0.052000 -0.140000 0.011000 -vn 2.627994 1.517272 -3.665192 -v 0.055708 -0.136500 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.062800 -0.141250 0.011000 -vn -1.517270 -2.627994 -2.617990 -v 0.054500 -0.144330 0.011000 -vn -2.627995 -1.517271 -2.617994 -v 0.052670 -0.142500 0.011000 -vn 2.627993 -1.517274 -2.617994 -v 0.099330 -0.142500 0.011000 -vn 1.517270 -2.627994 -2.617992 -v 0.097500 -0.144330 0.011000 -vn 0.000000 0.000000 -6.283186 -v 0.090035 -0.141250 0.011000 -vn 3.034549 0.000000 -3.665183 -v 0.090570 -0.135500 0.011000 -vn 2.627995 1.517266 -3.665195 -v 0.090838 -0.136500 0.011000 -vn -3.034549 0.000000 -3.665183 -v 0.094570 -0.135500 0.011000 -vn 1.517277 2.627992 -3.665189 -v 0.091570 -0.137232 0.011000 -vn 0.000000 3.034543 -3.665197 -v 0.092570 -0.137500 0.011000 -vn -1.517277 2.627992 -3.665189 -v 0.093570 -0.137232 0.011000 -vn -2.627995 1.517266 -3.665196 -v 0.094302 -0.136500 0.011000 -vn -2.627995 -1.517266 -3.665195 -v 0.094302 -0.134500 0.011000 -vn -1.517277 -2.627992 -3.665189 -v 0.093570 -0.133768 0.011000 -vn 0.000000 0.000000 -6.283190 -v 0.090035 -0.107750 0.011000 -vn 0.000000 -3.034543 -3.665197 -v 0.092570 -0.133500 0.011000 -vn 1.517277 -2.627992 -3.665189 -v 0.091570 -0.133768 0.011000 -vn 2.627995 -1.517266 -3.665195 -v 0.090838 -0.134500 0.011000 -vn 3.034549 0.000000 -3.665183 -v 0.090570 0.135500 0.011000 -vn 2.627995 1.517266 -3.665195 -v 0.090838 0.134500 0.011000 -vn 0.000000 0.000000 -6.283190 -v 0.090035 0.107750 0.011000 -vn 1.517277 2.627992 -3.665189 -v 0.091570 0.133768 0.011000 -vn 0.000000 3.034543 -3.665197 -v 0.092570 0.133500 0.011000 -vn -1.517277 2.627992 -3.665189 -v 0.093570 0.133768 0.011000 -vn -2.627995 1.517266 -3.665196 -v 0.094302 0.134500 0.011000 -vn 1.179132 2.846686 -2.748899 -v 0.096913 0.144619 0.011000 -vn -1.517277 -2.627992 -3.665189 -v 0.093570 0.137232 0.011000 -vn 0.000000 -3.034543 -3.665197 -v 0.092570 0.137500 0.011000 -vn 1.517277 -2.627992 -3.665189 -v 0.091570 0.137232 0.011000 -vn 2.627995 -1.517266 -3.665196 -v 0.090838 0.136500 0.011000 -vn -3.034549 0.000000 -3.665183 -v 0.094570 0.135500 0.011000 -vn -2.627995 -1.517266 -3.665195 -v 0.094302 0.136500 0.011000 -vn 2.846684 1.179136 -2.748897 -v 0.099619 0.141913 0.011000 -vn 2.178754 2.178758 -2.748888 -v 0.098536 0.143536 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.056170 0.107750 0.011000 -vn 1.517277 2.627992 -3.665189 -v 0.056440 0.133768 0.011000 -vn -0.000001 3.034543 -3.665198 -v 0.057440 0.133500 0.011000 -vn 0.000000 0.000000 -6.283188 -v 0.062800 0.107750 0.011000 -vn -1.517278 2.627992 -3.665188 -v 0.058440 0.133768 0.011000 -vn -2.627992 1.517277 -3.665189 -v 0.059172 0.134500 0.011000 -vn -3.034543 0.000000 -3.665197 -v 0.059440 0.135500 0.011000 -vn -2.627992 -1.517277 -3.665189 -v 0.059172 0.136500 0.011000 -vn -1.517278 -2.627992 -3.665188 -v 0.058440 0.137232 0.011000 -vn -0.000001 -3.034543 -3.665198 -v 0.057440 0.137500 0.011000 -vn 1.517277 -2.627992 -3.665189 -v 0.056440 0.137232 0.011000 -vn 3.034546 0.000000 -3.665190 -v 0.055440 0.135500 0.011000 -vn 2.627994 1.517272 -3.665192 -v 0.055708 0.134500 0.011000 -vn -1.517270 2.627993 -2.617990 -v 0.054500 0.144330 0.011000 -vn -2.627995 1.517271 -2.617994 -v 0.052670 0.142500 0.011000 -vn 2.627994 -1.517272 -3.665192 -v 0.055708 0.136500 0.011000 -vn -2.627992 1.517277 -3.665189 -v 0.059172 -0.136500 0.011000 -vn -3.034543 0.000000 -3.665196 -v 0.059440 -0.135500 0.011000 -vn -1.517278 -2.627992 -3.665187 -v 0.058440 -0.133768 0.011000 -vn -0.000001 -3.034543 -3.665198 -v 0.057440 -0.133500 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.056170 -0.107750 0.011000 -vn 1.517277 -2.627992 -3.665189 -v 0.056440 -0.133768 0.011000 -vn -3.141592 0.000000 -3.141588 -v 0.052000 -0.107750 0.011000 -vn 2.627994 -1.517272 -3.665192 -v 0.055708 -0.134500 0.011000 -vn 3.034546 0.000000 -3.665190 -v 0.055440 -0.135500 0.011000 -vn 1.517277 2.627992 -3.665189 -v 0.056440 -0.137232 0.011000 -vn -0.000001 3.034543 -3.665198 -v 0.057440 -0.137500 0.011000 -vn -1.517278 2.627992 -3.665188 -v 0.058440 -0.137232 0.011000 -vn 1.517277 2.627992 -3.665189 -v 0.056440 -0.081732 0.011000 -vn -0.000001 3.034543 -3.665198 -v 0.057440 -0.082000 0.011000 -vn 0.000000 0.000000 -6.283188 -v 0.062800 -0.107750 0.011000 -vn -2.627992 -1.517277 -3.665189 -v 0.059172 -0.134500 0.011000 -vn -1.517278 2.627992 -3.665188 -v 0.058440 -0.081732 0.011000 -vn -2.627992 1.517277 -3.665189 -v 0.059172 -0.081000 0.011000 -vn -3.034542 -0.000003 -3.665199 -v 0.059440 -0.080000 0.011000 -vn -1.517273 -2.627989 -3.665200 -v 0.058440 -0.078268 0.011000 -vn 0.000000 0.000000 -6.283180 -v 0.062800 -0.068905 0.011000 -vn -2.627997 -1.517274 -3.665182 -v 0.059172 -0.079000 0.011000 -vn 2.627994 1.517272 -3.665192 -v 0.055708 -0.081000 0.011000 -vn 3.034545 -0.000003 -3.665192 -v 0.055440 -0.080000 0.011000 -vn -3.141592 0.000000 -3.141593 -v 0.052000 -0.068905 0.011000 -vn 2.627999 -1.517269 -3.665185 -v 0.055708 -0.079000 0.011000 -vn 1.517277 -2.627992 -3.665189 -v 0.056440 0.081732 0.011000 -vn 2.627994 -1.517272 -3.665192 -v 0.055708 0.081000 0.011000 -vn 3.034545 0.000003 -3.665192 -v 0.055440 0.080000 0.011000 -vn 2.627999 1.517269 -3.665185 -v 0.055708 0.079000 0.011000 -vn 1.517272 2.627990 -3.665201 -v 0.056440 0.078268 0.011000 -vn 0.000000 0.000000 -6.283181 -v 0.056170 0.068905 0.011000 -vn -0.000001 3.034549 -3.665184 -v 0.057440 0.078000 0.011000 -vn 0.000000 0.000000 -6.283179 -v 0.062800 0.068905 0.011000 -vn -1.517273 2.627989 -3.665200 -v 0.058440 0.078268 0.011000 -vn -2.627997 1.517274 -3.665182 -v 0.059172 0.079000 0.011000 -vn -3.034543 0.000003 -3.665199 -v 0.059440 0.080000 0.011000 -vn -2.627992 -1.517277 -3.665189 -v 0.059172 0.081000 0.011000 -vn -1.517278 -2.627992 -3.665187 -v 0.058440 0.081732 0.011000 -vn -0.000001 -3.034543 -3.665198 -v 0.057440 0.082000 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.077000 -0.141250 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.077000 -0.107750 0.011000 -vn -1.517272 -2.627990 -3.665201 -v 0.093570 -0.078268 0.011000 -vn 0.000000 -3.034549 -3.665183 -v 0.092570 -0.078000 0.011000 -vn 0.000000 0.000000 -6.283190 -v 0.090035 -0.068905 0.011000 -vn 1.517272 -2.627990 -3.665201 -v 0.091570 -0.078268 0.011000 -vn 2.628000 -1.517264 -3.665189 -v 0.090838 -0.079000 0.011000 -vn 3.034548 -0.000003 -3.665185 -v 0.090570 -0.080000 0.011000 -vn 2.627995 1.517266 -3.665195 -v 0.090838 -0.081000 0.011000 -vn 1.517277 2.627992 -3.665189 -v 0.091570 -0.081732 0.011000 -vn 0.000000 3.034543 -3.665197 -v 0.092570 -0.082000 0.011000 -vn -1.517277 2.627992 -3.665189 -v 0.093570 -0.081732 0.011000 -vn -2.627995 1.517266 -3.665195 -v 0.094302 -0.081000 0.011000 -vn -3.034548 -0.000003 -3.665185 -v 0.094570 -0.080000 0.011000 -vn -2.628000 -1.517264 -3.665189 -v 0.094302 -0.079000 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.077000 -0.068905 0.011000 -vn -2.627994 -1.517271 -3.665193 -v 0.060819 -0.056660 0.011000 -vn -1.517271 -2.627994 -3.665193 -v 0.060050 -0.055891 0.011000 -vn -2.627994 1.517271 -3.665192 -v 0.060819 -0.058760 0.011000 -vn -3.034546 -0.000000 -3.665189 -v 0.061100 -0.057710 0.011000 -vn 1.517271 -2.627994 -3.665193 -v 0.057950 -0.055891 0.011000 -vn 2.627993 -1.517276 -3.665189 -v 0.057181 -0.056660 0.011000 -vn 3.034544 -0.000000 -3.665196 -v 0.056900 -0.057710 0.011000 -vn 2.627993 1.517276 -3.665190 -v 0.057181 -0.058760 0.011000 -vn 0.000000 -3.034546 -3.665189 -v 0.059000 -0.055610 0.011000 -vn 1.517276 2.627993 -3.665189 -v 0.057950 -0.059529 0.011000 -vn 0.000000 3.034544 -3.665196 -v 0.059000 -0.059810 0.011000 -vn -1.517276 2.627993 -3.665189 -v 0.060050 -0.059529 0.011000 -vn -3.141593 0.000000 -3.141593 -v 0.052000 -0.046407 0.011000 -vn 1.517276 -2.627993 -3.665189 -v 0.057950 0.059529 0.011000 -vn 2.627993 -1.517276 -3.665190 -v 0.057181 0.058760 0.011000 -vn 3.034544 -0.000000 -3.665196 -v 0.056900 0.057710 0.011000 -vn 2.627993 1.517276 -3.665189 -v 0.057181 0.056660 0.011000 -vn 1.517271 2.627994 -3.665193 -v 0.057950 0.055891 0.011000 -vn -3.034546 -0.000000 -3.665189 -v 0.061100 0.057710 0.011000 -vn -2.627994 -1.517271 -3.665192 -v 0.060819 0.058760 0.011000 -vn -1.517276 -2.627993 -3.665189 -v 0.060050 0.059529 0.011000 -vn -0.000000 -3.034544 -3.665195 -v 0.059000 0.059810 0.011000 -vn -0.000000 3.034546 -3.665189 -v 0.059000 0.055610 0.011000 -vn -1.517271 2.627994 -3.665193 -v 0.060050 0.055891 0.011000 -vn -2.627994 1.517271 -3.665193 -v 0.060819 0.056660 0.011000 -vn 2.627992 1.517278 -3.665190 -v 0.064835 0.033455 0.011000 -vn 0.000000 0.000000 -6.283190 -v 0.090035 0.068905 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.077000 0.068905 0.011000 -vn 1.517277 -2.627992 -3.665189 -v 0.091570 0.081732 0.011000 -vn 2.627995 -1.517266 -3.665195 -v 0.090838 0.081000 0.011000 -vn 3.034548 0.000003 -3.665185 -v 0.090570 0.080000 0.011000 -vn 2.628000 1.517264 -3.665189 -v 0.090838 0.079000 0.011000 -vn 1.517272 2.627990 -3.665201 -v 0.091570 0.078268 0.011000 -vn 0.000000 3.034549 -3.665183 -v 0.092570 0.078000 0.011000 -vn -1.517272 2.627990 -3.665201 -v 0.093570 0.078268 0.011000 -vn -2.628000 1.517264 -3.665189 -v 0.094302 0.079000 0.011000 -vn -3.034548 0.000003 -3.665185 -v 0.094570 0.080000 0.011000 -vn -2.627995 -1.517266 -3.665195 -v 0.094302 0.081000 0.011000 -vn -1.517277 -2.627992 -3.665189 -v 0.093570 0.081732 0.011000 -vn 0.000000 -3.034543 -3.665197 -v 0.092570 0.082000 0.011000 -vn 0.000000 0.000000 -6.283185 -v 0.077000 0.107750 0.011000 -# 496 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 53//53 54//54 48//48 -f 55//55 56//56 57//57 -f 58//58 59//59 60//60 -f 61//61 25//25 62//62 -f 63//63 64//64 62//62 -f 10//10 65//65 66//66 -f 66//66 65//65 67//67 -f 68//68 18//18 69//69 -f 69//69 18//18 16//16 -f 69//69 16//16 67//67 -f 67//67 16//16 70//70 -f 67//67 70//70 66//66 -f 71//71 72//72 73//73 -f 73//73 74//74 71//71 -f 71//71 74//74 75//75 -f 71//71 75//75 8//8 -f 8//8 75//75 76//76 -f 8//8 76//76 10//10 -f 10//10 76//76 77//77 -f 10//10 77//77 65//65 -f 68//68 78//78 18//18 -f 18//18 78//78 79//79 -f 18//18 79//79 72//72 -f 72//72 79//79 80//80 -f 72//72 80//80 73//73 -f 63//63 62//62 81//81 -f 82//82 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 86//86 87//87 81//81 -f 64//64 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 96//96 93//93 84//84 -f 84//84 93//93 95//95 -f 84//84 95//95 82//82 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 102//102 103//103 101//101 -f 101//101 103//103 104//104 -f 101//101 104//104 84//84 -f 84//84 104//104 105//105 -f 84//84 105//105 96//96 -f 106//106 107//107 91//91 -f 96//96 108//108 93//93 -f 93//93 108//108 109//109 -f 93//93 109//109 91//91 -f 91//91 109//109 110//110 -f 91//91 110//110 106//106 -f 111//111 112//112 6//6 -f 6//6 112//112 113//113 -f 6//6 113//113 8//8 -f 8//8 113//113 114//114 -f 8//8 114//114 71//71 -f 115//115 116//116 117//117 -f 117//117 116//116 57//57 -f 114//114 118//118 71//71 -f 71//71 118//118 119//119 -f 71//71 119//119 72//72 -f 72//72 119//119 120//120 -f 120//120 121//121 72//72 -f 72//72 121//121 122//122 -f 72//72 122//122 57//57 -f 57//57 122//122 123//123 -f 57//57 123//123 117//117 -f 38//38 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 128//128 125//125 -f 125//125 128//128 129//129 -f 125//125 129//129 22//22 -f 129//129 130//130 22//22 -f 22//22 130//130 131//131 -f 22//22 131//131 24//24 -f 24//24 131//131 132//132 -f 24//24 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 136//136 134//134 137//137 -f 136//136 137//137 36//36 -f 36//36 137//137 138//138 -f 36//36 138//138 38//38 -f 38//38 138//138 139//139 -f 38//38 139//139 124//124 -f 140//140 141//141 142//142 -f 143//143 144//144 145//145 -f 145//145 144//144 52//52 -f 140//140 142//142 143//143 -f 146//146 147//147 148//148 -f 146//146 148//148 50//50 -f 148//148 149//149 50//50 -f 50//50 149//149 150//150 -f 50//50 150//150 52//52 -f 52//52 150//150 151//151 -f 52//52 151//151 145//145 -f 141//141 152//152 142//142 -f 142//142 152//152 153//153 -f 142//142 153//153 146//146 -f 146//146 153//153 154//154 -f 146//146 154//154 147//147 -f 142//142 31//31 33//33 -f 143//143 142//142 144//144 -f 144//144 142//142 33//33 -f 144//144 33//33 155//155 -f 81//81 62//62 86//86 -f 86//86 62//62 25//25 -f 86//86 25//25 27//27 -f 64//64 89//89 62//62 -f 62//62 89//89 156//156 -f 62//62 156//156 61//61 -f 157//157 158//158 159//159 -f 160//160 161//161 58//58 -f 58//58 161//161 162//162 -f 58//58 162//162 163//163 -f 163//163 162//162 164//164 -f 163//163 164//164 165//165 -f 166//166 167//167 168//168 -f 169//169 170//170 157//157 -f 157//157 170//170 171//171 -f 157//157 171//171 158//158 -f 160//160 58//58 159//159 -f 159//159 58//58 60//60 -f 159//159 60//60 157//157 -f 157//157 60//60 172//172 -f 157//157 172//172 173//173 -f 174//174 175//175 168//168 -f 176//176 177//177 178//178 -f 178//178 177//177 179//179 -f 180//180 181//181 182//182 -f 182//182 181//181 183//183 -f 182//182 183//183 184//184 -f 175//175 185//185 168//168 -f 168//168 185//185 163//163 -f 168//168 163//163 166//166 -f 166//166 163//163 165//165 -f 185//185 186//186 163//163 -f 163//163 186//186 187//187 -f 163//163 187//187 178//178 -f 178//178 187//187 188//188 -f 178//178 188//188 176//176 -f 189//189 178//178 180//180 -f 180//180 178//178 179//179 -f 180//180 179//179 181//181 -f 190//190 191//191 192//192 -f 192//192 191//191 180//180 -f 189//189 180//180 193//193 -f 193//193 180//180 191//191 -f 193//193 191//191 194//194 -f 195//195 196//196 192//192 -f 192//192 196//196 197//197 -f 192//192 197//197 190//190 -f 198//198 199//199 200//200 -f 200//200 199//199 193//193 -f 200//200 193//193 201//201 -f 201//201 193//193 194//194 -f 198//198 202//202 199//199 -f 199//199 202//202 203//203 -f 199//199 203//203 204//204 -f 204//204 203//203 205//205 -f 206//206 207//207 208//208 -f 206//206 208//208 209//209 -f 210//210 199//199 211//211 -f 211//211 199//199 204//204 -f 211//211 204//204 212//212 -f 212//212 204//204 213//213 -f 210//210 214//214 199//199 -f 199//199 214//214 215//215 -f 199//199 215//215 14//14 -f 14//14 215//215 216//216 -f 14//14 216//216 217//217 -f 218//218 13//13 14//14 -f 219//219 220//220 218//218 -f 221//221 222//222 125//125 -f 223//223 40//40 224//224 -f 224//224 40//40 38//38 -f 224//224 38//38 225//225 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 125//125 222//222 38//38 -f 38//38 222//222 230//230 -f 38//38 230//230 225//225 -f 229//229 231//231 228//228 -f 228//228 231//231 232//232 -f 228//228 232//232 125//125 -f 125//125 232//232 233//233 -f 125//125 233//233 221//221 -f 22//22 20//20 125//125 -f 125//125 20//20 234//234 -f 125//125 234//234 228//228 -f 228//228 234//234 235//235 -f 228//228 235//235 192//192 -f 192//192 235//235 204//204 -f 192//192 204//204 195//195 -f 195//195 204//204 205//205 -f 20//20 18//18 234//234 -f 234//234 18//18 72//72 -f 234//234 72//72 235//235 -f 235//235 72//72 57//57 -f 235//235 57//57 204//204 -f 204//204 57//57 208//208 -f 204//204 208//208 213//213 -f 213//213 208//208 207//207 -f 236//236 237//237 219//219 -f 57//57 56//56 208//208 -f 208//208 56//56 238//238 -f 208//208 238//238 239//239 -f 237//237 240//240 219//219 -f 219//219 240//240 241//241 -f 219//219 241//241 116//116 -f 116//116 241//241 242//242 -f 217//217 243//243 14//14 -f 14//14 243//243 209//209 -f 14//14 209//209 218//218 -f 218//218 209//209 208//208 -f 218//218 208//208 219//219 -f 219//219 208//208 239//239 -f 219//219 239//239 236//236 -f 242//242 244//244 116//116 -f 116//116 244//244 245//245 -f 116//116 245//245 57//57 -f 57//57 245//245 246//246 -f 57//57 246//246 55//55 -f 115//115 111//111 116//116 -f 116//116 111//111 6//6 -f 116//116 6//6 219//219 -f 219//219 6//6 4//4 -f 219//219 4//4 220//220 -f 220//220 4//4 2//2 -f 223//223 226//226 40//40 -f 40//40 226//226 228//228 -f 40//40 228//228 42//42 -f 42//42 228//228 192//192 -f 42//42 192//192 44//44 -f 44//44 192//192 180//180 -f 44//44 180//180 46//46 -f 46//46 180//180 182//182 -f 46//46 182//182 48//48 -f 48//48 182//182 247//247 -f 101//101 157//157 248//248 -f 248//248 157//157 249//249 -f 250//250 173//173 251//251 -f 251//251 173//173 99//99 -f 251//251 99//99 252//252 -f 252//252 99//99 253//253 -f 248//248 254//254 101//101 -f 101//101 254//254 255//255 -f 101//101 255//255 99//99 -f 99//99 255//255 256//256 -f 99//99 256//256 253//253 -f 250//250 257//257 173//173 -f 173//173 257//257 258//258 -f 173//173 258//258 157//157 -f 157//157 258//258 259//259 -f 157//157 259//259 249//249 -f 172//172 260//260 173//173 -f 173//173 260//260 261//261 -f 173//173 261//261 99//99 -f 99//99 261//261 107//107 -f 99//99 107//107 97//97 -f 97//97 107//107 106//106 -f 262//262 263//263 247//247 -f 48//48 54//54 50//50 -f 247//247 263//263 48//48 -f 48//48 263//263 264//264 -f 48//48 264//264 53//53 -f 54//54 265//265 50//50 -f 50//50 265//265 266//266 -f 50//50 266//266 146//146 -f 146//146 266//266 267//267 -f 146//146 267//267 268//268 -f 268//268 269//269 146//146 -f 146//146 269//269 270//270 -f 146//146 270//270 247//247 -f 247//247 270//270 271//271 -f 247//247 271//271 262//262 -f 184//184 174//174 182//182 -f 182//182 174//174 168//168 -f 182//182 168//168 247//247 -f 247//247 168//168 272//272 -f 247//247 272//272 146//146 -f 146//146 272//272 273//273 -f 146//146 273//273 142//142 -f 142//142 273//273 274//274 -f 142//142 274//274 31//31 -f 31//31 274//274 29//29 -f 167//167 169//169 168//168 -f 168//168 169//169 157//157 -f 168//168 157//157 272//272 -f 272//272 157//157 101//101 -f 272//272 101//101 273//273 -f 273//273 101//101 84//84 -f 273//273 84//84 274//274 -f 274//274 84//84 86//86 -f 274//274 86//86 29//29 -f 29//29 86//86 27//27 -f 275//275 276//276 277//277 -f 278//278 279//279 280//280 -f 12//12 11//11 278//278 -f 12//12 281//281 282//282 -f 283//283 284//284 285//285 -f 12//12 282//282 285//285 -f 285//285 282//282 286//286 -f 285//285 286//286 283//283 -f 287//287 288//288 289//289 -f 289//289 288//288 290//290 -f 284//284 291//291 292//292 -f 292//292 291//291 293//293 -f 292//292 293//293 288//288 -f 288//288 293//293 294//294 -f 288//288 294//294 290//290 -f 284//284 292//292 285//285 -f 285//285 292//292 295//295 -f 285//285 295//295 296//296 -f 297//297 298//298 299//299 -f 299//299 298//298 300//300 -f 296//296 301//301 285//285 -f 285//285 301//301 302//302 -f 285//285 302//302 298//298 -f 298//298 302//302 303//303 -f 298//298 303//303 300//300 -f 304//304 305//305 297//297 -f 297//297 305//305 306//306 -f 297//297 306//306 298//298 -f 298//298 306//306 307//307 -f 304//304 308//308 305//305 -f 305//305 308//308 309//309 -f 305//305 309//309 292//292 -f 292//292 309//309 310//310 -f 292//292 310//310 295//295 -f 311//311 312//312 313//313 -f 314//314 315//315 316//316 -f 317//317 318//318 319//319 -f 313//313 312//312 320//320 -f 320//320 312//312 321//321 -f 320//320 321//321 322//322 -f 316//316 323//323 314//314 -f 314//314 323//323 324//324 -f 314//314 324//324 313//313 -f 313//313 324//324 325//325 -f 313//313 325//325 311//311 -f 318//318 326//326 319//319 -f 319//319 326//326 315//315 -f 319//319 315//315 306//306 -f 306//306 315//315 314//314 -f 306//306 314//314 307//307 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 331//331 332//332 333//333 -f 334//334 331//331 335//335 -f 335//335 331//331 333//333 -f 335//335 333//333 336//336 -f 336//336 333//333 337//337 -f 338//338 339//339 320//320 -f 320//320 339//339 340//340 -f 320//320 340//340 313//313 -f 313//313 340//340 341//341 -f 313//313 341//341 333//333 -f 333//333 341//341 342//342 -f 333//333 342//342 337//337 -f 334//334 330//330 331//331 -f 331//331 330//330 328//328 -f 331//331 328//328 343//343 -f 343//343 328//328 344//344 -f 343//343 344//344 345//345 -f 346//346 347//347 348//348 -f 30//30 28//28 349//349 -f 349//349 28//28 26//26 -f 349//349 26//26 346//346 -f 346//346 26//26 350//350 -f 346//346 350//350 347//347 -f 347//347 350//350 351//351 -f 352//352 353//353 354//354 -f 354//354 353//353 34//34 -f 354//354 355//355 356//356 -f 49//49 51//51 357//357 -f 356//356 358//358 354//354 -f 354//354 358//358 359//359 -f 354//354 359//359 352//352 -f 352//352 359//359 360//360 -f 352//352 360//360 51//51 -f 51//51 360//360 361//361 -f 51//51 361//361 357//357 -f 357//357 362//362 49//49 -f 49//49 362//362 363//363 -f 49//49 363//363 364//364 -f 364//364 363//363 365//365 -f 365//365 366//366 364//364 -f 364//364 366//366 367//367 -f 364//364 367//367 355//355 -f 368//368 369//369 370//370 -f 369//369 371//371 370//370 -f 370//370 371//371 372//372 -f 370//370 372//372 37//37 -f 372//372 373//373 37//37 -f 37//37 373//373 374//374 -f 37//37 374//374 35//35 -f 375//375 376//376 23//23 -f 23//23 376//376 377//377 -f 23//23 377//377 21//21 -f 21//21 377//377 378//378 -f 21//21 378//378 379//379 -f 374//374 380//380 35//35 -f 35//35 380//380 381//381 -f 35//35 381//381 382//382 -f 382//382 381//381 376//376 -f 382//382 376//376 383//383 -f 383//383 376//376 375//375 -f 384//384 385//385 386//386 -f 384//384 386//386 387//387 -f 387//387 386//386 388//388 -f 387//387 388//388 389//389 -f 390//390 391//391 17//17 -f 17//17 391//391 392//392 -f 17//17 392//392 15//15 -f 15//15 392//392 393//393 -f 15//15 393//393 394//394 -f 9//9 395//395 7//7 -f 7//7 395//395 396//396 -f 397//397 15//15 398//398 -f 398//398 15//15 394//394 -f 398//398 394//394 9//9 -f 9//9 394//394 399//399 -f 9//9 399//399 395//395 -f 400//400 401//401 349//349 -f 402//402 403//403 404//404 -f 404//404 403//403 405//405 -f 404//404 405//405 406//406 -f 406//406 405//405 407//407 -f 406//406 407//407 347//347 -f 347//347 407//407 408//408 -f 347//347 408//408 348//348 -f 348//348 409//409 346//346 -f 346//346 409//409 410//410 -f 346//346 410//410 349//349 -f 349//349 410//410 411//411 -f 349//349 411//411 400//400 -f 412//412 413//413 404//404 -f 404//404 413//413 414//414 -f 404//404 414//414 402//402 -f 402//402 414//414 415//415 -f 413//413 416//416 414//414 -f 414//414 416//416 417//417 -f 414//414 417//417 418//418 -f 275//275 277//277 419//419 -f 419//419 277//277 420//420 -f 419//419 420//420 421//421 -f 412//412 404//404 422//422 -f 422//422 404//404 406//406 -f 422//422 406//406 423//423 -f 423//423 406//406 424//424 -f 423//423 424//424 425//425 -f 426//426 7//7 384//384 -f 384//384 7//7 396//396 -f 384//384 396//396 385//385 -f 426//426 427//427 7//7 -f 7//7 427//427 428//428 -f 7//7 428//428 5//5 -f 5//5 428//428 429//429 -f 429//429 430//430 431//431 -f 431//431 430//430 432//432 -f 431//431 432//432 433//433 -f 433//433 432//432 434//434 -f 433//433 434//434 435//435 -f 436//436 437//437 387//387 -f 387//387 437//437 438//438 -f 387//387 438//438 384//384 -f 384//384 438//438 439//439 -f 384//384 439//439 426//426 -f 32//32 30//30 440//440 -f 440//440 30//30 349//349 -f 440//440 349//349 414//414 -f 414//414 349//349 401//401 -f 414//414 401//401 415//415 -f 34//34 32//32 354//354 -f 354//354 32//32 440//440 -f 354//354 440//440 441//441 -f 441//441 440//440 414//414 -f 441//441 414//414 420//420 -f 420//420 414//414 418//418 -f 420//420 418//418 421//421 -f 442//442 443//443 444//444 -f 443//443 445//445 444//444 -f 444//444 445//445 446//446 -f 444//444 446//446 447//447 -f 448//448 449//449 364//364 -f 364//364 449//449 450//450 -f 364//364 450//450 49//49 -f 49//49 450//450 451//451 -f 451//451 452//452 49//49 -f 49//49 452//452 453//453 -f 49//49 453//453 47//47 -f 47//47 453//453 454//454 -f 47//47 454//454 442//442 -f 444//444 320//320 319//319 -f 319//319 320//320 322//322 -f 319//319 322//322 317//317 -f 327//327 338//338 328//328 -f 328//328 338//338 320//320 -f 328//328 320//320 455//455 -f 455//455 320//320 444//444 -f 455//455 444//444 364//364 -f 364//364 444//444 447//447 -f 364//364 447//447 448//448 -f 456//456 457//457 328//328 -f 458//458 459//459 420//420 -f 460//460 461//461 344//344 -f 344//344 461//461 462//462 -f 344//344 462//462 277//277 -f 277//277 462//462 463//463 -f 328//328 457//457 344//344 -f 344//344 457//457 464//464 -f 344//344 464//464 460//460 -f 355//355 354//354 364//364 -f 364//364 354//354 441//441 -f 364//364 441//441 455//455 -f 455//455 441//441 420//420 -f 455//455 420//420 328//328 -f 328//328 420//420 459//459 -f 328//328 459//459 456//456 -f 463//463 465//465 277//277 -f 277//277 465//465 466//466 -f 277//277 466//466 420//420 -f 420//420 466//466 467//467 -f 420//420 467//467 458//458 -f 345//345 344//344 468//468 -f 468//468 344//344 277//277 -f 468//468 277//277 424//424 -f 424//424 277//277 276//276 -f 424//424 276//276 425//425 -f 469//469 470//470 431//431 -f 431//431 470//470 471//471 -f 431//431 471//471 280//280 -f 280//280 471//471 472//472 -f 280//280 472//472 473//473 -f 474//474 475//475 433//433 -f 433//433 475//475 476//476 -f 433//433 476//476 431//431 -f 431//431 476//476 477//477 -f 431//431 477//477 469//469 -f 478//478 479//479 288//288 -f 288//288 479//479 480//480 -f 473//473 478//478 280//280 -f 280//280 478//478 288//288 -f 280//280 288//288 278//278 -f 278//278 288//288 287//287 -f 278//278 287//287 12//12 -f 12//12 287//287 481//481 -f 12//12 481//481 281//281 -f 482//482 305//305 483//483 -f 483//483 305//305 292//292 -f 483//483 292//292 433//433 -f 433//433 292//292 288//288 -f 433//433 288//288 474//474 -f 474//474 288//288 480//480 -f 429//429 431//431 5//5 -f 5//5 431//431 280//280 -f 5//5 280//280 3//3 -f 3//3 280//280 279//279 -f 3//3 279//279 1//1 -f 484//484 485//485 370//370 -f 486//486 487//487 482//482 -f 482//482 487//487 488//488 -f 482//482 488//488 489//489 -f 442//442 444//444 47//47 -f 47//47 444//444 319//319 -f 47//47 319//319 45//45 -f 45//45 319//319 306//306 -f 45//45 306//306 43//43 -f 43//43 306//306 305//305 -f 43//43 305//305 41//41 -f 41//41 305//305 482//482 -f 41//41 482//482 39//39 -f 39//39 482//482 489//489 -f 39//39 489//489 490//490 -f 490//490 491//491 39//39 -f 39//39 491//491 492//492 -f 39//39 492//492 37//37 -f 492//492 493//493 37//37 -f 37//37 493//493 494//494 -f 37//37 494//494 370//370 -f 370//370 494//494 495//495 -f 370//370 495//495 484//484 -f 435//435 436//436 433//433 -f 433//433 436//436 387//387 -f 433//433 387//387 483//483 -f 483//483 387//387 496//496 -f 483//483 496//496 482//482 -f 482//482 496//496 370//370 -f 482//482 370//370 486//486 -f 486//486 370//370 485//485 -f 389//389 390//390 387//387 -f 387//387 390//390 17//17 -f 387//387 17//17 496//496 -f 496//496 17//17 19//19 -f 496//496 19//19 370//370 -f 370//370 19//19 21//21 -f 370//370 21//21 368//368 -f 368//368 21//21 379//379 -f 36//36 35//35 382//382 -f 36//36 382//382 136//136 -f 136//136 382//382 383//383 -f 136//136 383//383 135//135 -f 135//135 383//383 375//375 -f 135//135 375//375 133//133 -f 133//133 375//375 23//23 -f 133//133 23//23 24//24 -f 33//33 34//34 353//353 -f 33//33 353//353 155//155 -f 155//155 353//353 352//352 -f 155//155 352//352 144//144 -f 144//144 352//352 51//51 -f 144//144 51//51 52//52 -f 357//357 151//151 362//362 -f 362//362 151//151 150//150 -f 362//362 150//150 363//363 -f 363//363 150//150 149//149 -f 363//363 149//149 365//365 -f 365//365 149//149 148//148 -f 365//365 148//148 366//366 -f 366//366 148//148 147//147 -f 366//366 147//147 367//367 -f 367//367 147//147 154//154 -f 367//367 154//154 355//355 -f 355//355 154//154 153//153 -f 355//355 153//153 356//356 -f 356//356 153//153 152//152 -f 356//356 152//152 358//358 -f 358//358 152//152 141//141 -f 358//358 141//141 359//359 -f 359//359 141//141 140//140 -f 359//359 140//140 360//360 -f 360//360 140//140 143//143 -f 360//360 143//143 361//361 -f 361//361 143//143 145//145 -f 361//361 145//145 357//357 -f 357//357 145//145 151//151 -f 492//492 224//224 493//493 -f 493//493 224//224 225//225 -f 493//493 225//225 494//494 -f 494//494 225//225 230//230 -f 494//494 230//230 495//495 -f 495//495 230//230 222//222 -f 495//495 222//222 484//484 -f 484//484 222//222 221//221 -f 484//484 221//221 485//485 -f 485//485 221//221 233//233 -f 485//485 233//233 486//486 -f 486//486 233//233 232//232 -f 486//486 232//232 487//487 -f 487//487 232//232 231//231 -f 487//487 231//231 488//488 -f 488//488 231//231 229//229 -f 488//488 229//229 489//489 -f 489//489 229//229 227//227 -f 489//489 227//227 490//490 -f 490//490 227//227 226//226 -f 490//490 226//226 491//491 -f 491//491 226//226 223//223 -f 491//491 223//223 492//492 -f 492//492 223//223 224//224 -f 390//390 79//79 391//391 -f 391//391 79//79 78//78 -f 391//391 78//78 392//392 -f 392//392 78//78 68//68 -f 392//392 68//68 393//393 -f 393//393 68//68 69//69 -f 393//393 69//69 394//394 -f 394//394 69//69 67//67 -f 394//394 67//67 399//399 -f 399//399 67//67 65//65 -f 399//399 65//65 395//395 -f 395//395 65//65 77//77 -f 395//395 77//77 396//396 -f 396//396 77//77 76//76 -f 396//396 76//76 385//385 -f 385//385 76//76 75//75 -f 385//385 75//75 386//386 -f 386//386 75//75 74//74 -f 386//386 74//74 388//388 -f 388//388 74//74 73//73 -f 388//388 73//73 389//389 -f 389//389 73//73 80//80 -f 389//389 80//80 390//390 -f 390//390 80//80 79//79 -f 380//380 138//138 381//381 -f 381//381 138//138 137//137 -f 381//381 137//137 376//376 -f 376//376 137//137 134//134 -f 376//376 134//134 377//377 -f 377//377 134//134 132//132 -f 377//377 132//132 378//378 -f 378//378 132//132 131//131 -f 378//378 131//131 379//379 -f 379//379 131//131 130//130 -f 379//379 130//130 368//368 -f 368//368 130//130 129//129 -f 368//368 129//129 369//369 -f 369//369 129//129 128//128 -f 369//369 128//128 371//371 -f 371//371 128//128 127//127 -f 371//371 127//127 372//372 -f 372//372 127//127 126//126 -f 372//372 126//126 373//373 -f 373//373 126//126 124//124 -f 373//373 124//124 374//374 -f 374//374 124//124 139//139 -f 374//374 139//139 380//380 -f 380//380 139//139 138//138 -f 401//401 85//85 415//415 -f 415//415 85//85 83//83 -f 415//415 83//83 402//402 -f 402//402 83//83 82//82 -f 402//402 82//82 403//403 -f 403//403 82//82 95//95 -f 403//403 95//95 405//405 -f 405//405 95//95 94//94 -f 405//405 94//94 407//407 -f 407//407 94//94 92//92 -f 407//407 92//92 408//408 -f 408//408 92//92 90//90 -f 408//408 90//90 348//348 -f 348//348 90//90 88//88 -f 348//348 88//88 409//409 -f 409//409 88//88 64//64 -f 409//409 64//64 410//410 -f 410//410 64//64 63//63 -f 410//410 63//63 411//411 -f 411//411 63//63 81//81 -f 411//411 81//81 400//400 -f 400//400 81//81 87//87 -f 400//400 87//87 401//401 -f 401//401 87//87 85//85 -f 453//453 54//54 454//454 -f 454//454 54//54 53//53 -f 454//454 53//53 442//442 -f 442//442 53//53 264//264 -f 442//442 264//264 443//443 -f 443//443 264//264 263//263 -f 443//443 263//263 445//445 -f 445//445 263//263 262//262 -f 445//445 262//262 446//446 -f 446//446 262//262 271//271 -f 446//446 271//271 447//447 -f 447//447 271//271 270//270 -f 447//447 270//270 448//448 -f 448//448 270//270 269//269 -f 448//448 269//269 449//449 -f 449//449 269//269 268//268 -f 449//449 268//268 450//450 -f 450//450 268//268 267//267 -f 450//450 267//267 451//451 -f 451//451 267//267 266//266 -f 451//451 266//266 452//452 -f 452//452 266//266 265//265 -f 452//452 265//265 453//453 -f 453//453 265//265 54//54 -f 418//418 104//104 421//421 -f 421//421 104//104 103//103 -f 421//421 103//103 419//419 -f 419//419 103//103 102//102 -f 419//419 102//102 275//275 -f 275//275 102//102 100//100 -f 275//275 100//100 276//276 -f 276//276 100//100 98//98 -f 276//276 98//98 425//425 -f 425//425 98//98 97//97 -f 425//425 97//97 423//423 -f 423//423 97//97 106//106 -f 423//423 106//106 422//422 -f 422//422 106//106 110//110 -f 422//422 110//110 412//412 -f 412//412 110//110 109//109 -f 412//412 109//109 413//413 -f 413//413 109//109 108//108 -f 413//413 108//108 416//416 -f 416//416 108//108 96//96 -f 416//416 96//96 417//417 -f 417//417 96//96 105//105 -f 417//417 105//105 418//418 -f 418//418 105//105 104//104 -f 436//436 122//122 437//437 -f 437//437 122//122 121//121 -f 437//437 121//121 438//438 -f 438//438 121//121 120//120 -f 438//438 120//120 439//439 -f 439//439 120//120 119//119 -f 439//439 119//119 426//426 -f 426//426 119//119 118//118 -f 426//426 118//118 427//427 -f 427//427 118//118 114//114 -f 427//427 114//114 428//428 -f 428//428 114//114 113//113 -f 428//428 113//113 429//429 -f 429//429 113//113 112//112 -f 429//429 112//112 430//430 -f 430//430 112//112 111//111 -f 430//430 111//111 432//432 -f 432//432 111//111 115//115 -f 432//432 115//115 434//434 -f 434//434 115//115 117//117 -f 434//434 117//117 435//435 -f 435//435 117//117 123//123 -f 435//435 123//123 436//436 -f 436//436 123//123 122//122 -f 260//260 345//345 261//261 -f 261//261 345//345 468//468 -f 261//261 468//468 107//107 -f 107//107 468//468 424//424 -f 107//107 424//424 91//91 -f 91//91 424//424 406//406 -f 91//91 406//406 89//89 -f 89//89 406//406 347//347 -f 9//9 10//10 66//66 -f 9//9 66//66 398//398 -f 398//398 66//66 70//70 -f 398//398 70//70 397//397 -f 397//397 70//70 16//16 -f 397//397 16//16 15//15 -f 26//26 25//25 61//61 -f 26//26 61//61 350//350 -f 350//350 61//61 156//156 -f 350//350 156//156 351//351 -f 351//351 156//156 89//89 -f 351//351 89//89 347//347 -f 14//14 12//12 199//199 -f 199//199 12//12 285//285 -f 199//199 285//285 193//193 -f 193//193 285//285 298//298 -f 193//193 298//298 189//189 -f 189//189 298//298 307//307 -f 189//189 307//307 178//178 -f 178//178 307//307 314//314 -f 178//178 314//314 163//163 -f 163//163 314//314 313//313 -f 163//163 313//313 58//58 -f 58//58 313//313 333//333 -f 59//59 58//58 332//332 -f 332//332 58//58 333//333 -f 341//341 166//166 342//342 -f 342//342 166//166 165//165 -f 342//342 165//165 337//337 -f 337//337 165//165 164//164 -f 337//337 164//164 336//336 -f 336//336 164//164 162//162 -f 336//336 162//162 335//335 -f 335//335 162//162 161//161 -f 335//335 161//161 334//334 -f 334//334 161//161 160//160 -f 334//334 160//160 330//330 -f 330//330 160//160 159//159 -f 330//330 159//159 329//329 -f 329//329 159//159 158//158 -f 329//329 158//158 327//327 -f 327//327 158//158 171//171 -f 327//327 171//171 338//338 -f 338//338 171//171 170//170 -f 338//338 170//170 339//339 -f 339//339 170//170 169//169 -f 339//339 169//169 340//340 -f 340//340 169//169 167//167 -f 340//340 167//167 341//341 -f 341//341 167//167 166//166 -f 297//297 191//191 304//304 -f 304//304 191//191 190//190 -f 304//304 190//190 308//308 -f 308//308 190//190 197//197 -f 308//308 197//197 309//309 -f 309//309 197//197 196//196 -f 309//309 196//196 310//310 -f 310//310 196//196 195//195 -f 310//310 195//195 295//295 -f 295//295 195//195 205//205 -f 295//295 205//205 296//296 -f 296//296 205//205 203//203 -f 296//296 203//203 301//301 -f 301//301 203//203 202//202 -f 301//301 202//202 302//302 -f 302//302 202//202 198//198 -f 302//302 198//198 303//303 -f 303//303 198//198 200//200 -f 303//303 200//200 300//300 -f 300//300 200//200 201//201 -f 300//300 201//201 299//299 -f 299//299 201//201 194//194 -f 299//299 194//194 297//297 -f 297//297 194//194 191//191 -f 284//284 210//210 291//291 -f 291//291 210//210 211//211 -f 291//291 211//211 293//293 -f 293//293 211//211 212//212 -f 293//293 212//212 294//294 -f 294//294 212//212 213//213 -f 294//294 213//213 290//290 -f 290//290 213//213 207//207 -f 290//290 207//207 289//289 -f 289//289 207//207 206//206 -f 289//289 206//206 287//287 -f 287//287 206//206 209//209 -f 287//287 209//209 481//481 -f 481//481 209//209 243//243 -f 481//481 243//243 281//281 -f 281//281 243//243 217//217 -f 281//281 217//217 282//282 -f 282//282 217//217 216//216 -f 282//282 216//216 286//286 -f 286//286 216//216 215//215 -f 286//286 215//215 283//283 -f 283//283 215//215 214//214 -f 283//283 214//214 284//284 -f 284//284 214//214 210//210 -f 315//315 181//181 316//316 -f 316//316 181//181 179//179 -f 316//316 179//179 323//323 -f 323//323 179//179 177//177 -f 323//323 177//177 324//324 -f 324//324 177//177 176//176 -f 324//324 176//176 325//325 -f 325//325 176//176 188//188 -f 325//325 188//188 311//311 -f 311//311 188//188 187//187 -f 311//311 187//187 312//312 -f 312//312 187//187 186//186 -f 312//312 186//186 321//321 -f 321//321 186//186 185//185 -f 321//321 185//185 322//322 -f 322//322 185//185 175//175 -f 322//322 175//175 317//317 -f 317//317 175//175 174//174 -f 317//317 174//174 318//318 -f 318//318 174//174 184//184 -f 318//318 184//184 326//326 -f 326//326 184//184 183//183 -f 326//326 183//183 315//315 -f 315//315 183//183 181//181 -f 59//59 332//332 60//60 -f 60//60 332//332 331//331 -f 60//60 331//331 172//172 -f 172//172 331//331 343//343 -f 172//172 343//343 260//260 -f 260//260 343//343 345//345 -f 11//11 13//13 278//278 -f 278//278 13//13 218//218 -f 278//278 218//218 279//279 -f 279//279 218//218 220//220 -f 279//279 220//220 1//1 -f 1//1 220//220 2//2 -f 474//474 56//56 475//475 -f 475//475 56//56 55//55 -f 475//475 55//55 476//476 -f 476//476 55//55 246//246 -f 476//476 246//246 477//477 -f 477//477 246//246 245//245 -f 477//477 245//245 469//469 -f 469//469 245//245 244//244 -f 469//469 244//244 470//470 -f 470//470 244//244 242//242 -f 470//470 242//242 471//471 -f 471//471 242//242 241//241 -f 471//471 241//241 472//472 -f 472//472 241//241 240//240 -f 472//472 240//240 473//473 -f 473//473 240//240 237//237 -f 473//473 237//237 478//478 -f 478//478 237//237 236//236 -f 478//478 236//236 479//479 -f 479//479 236//236 239//239 -f 479//479 239//239 480//480 -f 480//480 239//239 238//238 -f 480//480 238//238 474//474 -f 474//474 238//238 56//56 -f 459//459 248//248 456//456 -f 456//456 248//248 249//249 -f 456//456 249//249 457//457 -f 457//457 249//249 259//259 -f 457//457 259//259 464//464 -f 464//464 259//259 258//258 -f 464//464 258//258 460//460 -f 460//460 258//258 257//257 -f 460//460 257//257 461//461 -f 461//461 257//257 250//250 -f 461//461 250//250 462//462 -f 462//462 250//250 251//251 -f 462//462 251//251 463//463 -f 463//463 251//251 252//252 -f 463//463 252//252 465//465 -f 465//465 252//252 253//253 -f 465//465 253//253 466//466 -f 466//466 253//253 256//256 -f 466//466 256//256 467//467 -f 467//467 256//256 255//255 -f 467//467 255//255 458//458 -f 458//458 255//255 254//254 -f 458//458 254//254 459//459 -f 459//459 254//254 248//248 -# 1044 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_sine.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_sine.obj deleted file mode 100644 index 4dea2a5ef..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_sine.obj +++ /dev/null @@ -1,2392 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sine.obj -# -# Vertices: 586 -# Faces: 1204 -# -#### -vn 3.088024 0.406552 2.879794 -v 0.046250 -0.053000 0.116800 -vn 3.088072 0.406551 -2.879794 -v 0.046250 -0.053000 0.005000 -vn 2.627997 1.517273 -2.617993 -v 0.046049 -0.052250 0.005000 -vn 2.627996 1.517274 2.617993 -v 0.046049 -0.052250 0.116800 -vn 1.517274 2.627996 -2.617993 -v 0.045500 -0.051701 0.005000 -vn 1.517273 2.627997 2.617993 -v 0.045500 -0.051701 0.116800 -vn 0.406552 3.088073 -2.879794 -v 0.044750 -0.051500 0.005000 -vn 0.406551 3.088072 2.879794 -v 0.044750 -0.051500 0.116800 -vn -1.517274 1.977356 -1.832598 -v 0.044250 -0.051500 0.005000 -vn -1.517272 1.977353 1.832598 -v 0.044250 -0.051500 0.116800 -vn -2.627995 1.517277 3.665189 -v 0.044116 -0.052000 0.116800 -vn -2.627994 1.517278 -3.665188 -v 0.044116 -0.052000 0.005000 -vn -1.517268 2.627997 3.665195 -v 0.043750 -0.052366 0.116800 -vn -1.517267 2.627997 -3.665195 -v 0.043750 -0.052366 0.005000 -vn 0.000002 3.034550 3.665184 -v 0.043250 -0.052500 0.116800 -vn 0.000003 3.034550 -3.665185 -v 0.043250 -0.052500 0.005000 -vn 1.517270 2.627997 3.665195 -v 0.042750 -0.052366 0.116800 -vn 1.517271 2.627996 -3.665194 -v 0.042750 -0.052366 0.005000 -vn 2.627994 1.517278 3.665188 -v 0.042384 -0.052000 0.116800 -vn 2.627995 1.517277 -3.665189 -v 0.042384 -0.052000 0.005000 -vn 1.517274 1.977355 1.832598 -v 0.042250 -0.051500 0.116800 -vn 1.517272 1.977353 -1.832599 -v 0.042250 -0.051500 0.005000 -vn -1.110723 2.681522 -2.356194 -v 0.039250 -0.051500 0.005000 -vn -1.110721 2.681517 2.356194 -v 0.039250 -0.051500 0.116800 -vn -2.681518 1.110721 2.356194 -v 0.038750 -0.052000 0.116800 -vn -5.362996 2.221442 0.000000 -v 0.038750 -0.052000 0.044300 -vn -2.681515 1.110721 -2.356195 -v 0.038750 -0.052000 0.005000 -vn -3.665192 2.627994 -1.517272 -v 0.038750 -0.059016 0.032675 -vn -3.665191 3.034546 0.000001 -v 0.038750 -0.059250 0.031800 -vn -6.283181 0.000000 0.000000 -v 0.038750 -0.061125 0.044300 -vn -3.665189 2.627991 -1.517273 -v 0.038750 -0.059016 0.007675 -vn -3.665190 3.034546 0.000003 -v 0.038750 -0.059250 0.006800 -vn -3.141594 0.000000 -3.141593 -v 0.038750 -0.061125 0.005000 -vn -3.665188 2.627997 1.517270 -v 0.038750 -0.059016 0.005925 -vn -3.665190 -3.034546 0.000001 -v 0.038750 -0.055750 0.031800 -vn -3.665192 -2.627994 -1.517272 -v 0.038750 -0.055984 0.032675 -vn -3.665189 1.517268 -2.627997 -v 0.038750 -0.058375 0.008316 -vn -3.665194 1.517272 2.627994 -v 0.038750 -0.058375 0.030284 -vn -3.665192 2.627994 1.517272 -v 0.038750 -0.059016 0.030925 -vn -3.665195 -1.517275 2.627990 -v 0.038750 -0.056625 0.005284 -vn -3.665189 -0.000000 3.034546 -v 0.038750 -0.057500 0.005050 -vn -3.665195 1.517275 2.627990 -v 0.038750 -0.058375 0.005284 -vn -3.665188 -2.627996 1.517270 -v 0.038750 -0.055984 0.005925 -vn -3.665190 -3.034546 0.000003 -v 0.038750 -0.055750 0.006800 -vn -3.665190 -2.627991 -1.517273 -v 0.038750 -0.055984 0.007675 -vn -3.665190 0.000000 -3.034546 -v 0.038750 -0.057500 0.008550 -vn -3.665190 -0.000000 3.034546 -v 0.038750 -0.057500 0.030050 -vn -3.665189 -1.517268 -2.627997 -v 0.038750 -0.056625 0.008316 -vn -3.665194 -1.517272 2.627994 -v 0.038750 -0.056625 0.030284 -vn -3.665192 -2.627994 1.517272 -v 0.038750 -0.055984 0.030925 -vn -3.665192 -1.517272 -2.627994 -v 0.038750 -0.056625 0.033316 -vn -3.665190 0.000000 -3.034546 -v 0.038750 -0.057500 0.033550 -vn -3.665192 1.517272 -2.627994 -v 0.038750 -0.058375 0.033316 -vn -2.681517 -1.110721 -2.356194 -v 0.038750 -0.063000 0.005000 -vn -5.363034 -2.221442 0.000000 -v 0.038750 -0.063000 0.044300 -vn -3.665192 1.517272 2.627994 -v 0.038750 -0.058375 0.055284 -vn -3.665192 2.627994 1.517272 -v 0.038750 -0.059016 0.055925 -vn -3.665190 3.034546 0.000000 -v 0.038750 -0.059250 0.056800 -vn -3.665190 -0.000000 3.034546 -v 0.038750 -0.057500 0.055050 -vn -3.665189 2.627997 1.517270 -v 0.038750 -0.059016 0.105925 -vn -3.665182 -3.034546 0.000003 -v 0.038750 -0.055750 0.081800 -vn -3.665188 3.034546 0.000003 -v 0.038750 -0.059250 0.106800 -vn -3.665197 -2.627991 -1.517273 -v 0.038750 -0.055984 0.082675 -vn -3.665189 -1.517268 -2.627997 -v 0.038750 -0.056625 0.083316 -vn -3.665188 -2.627996 1.517270 -v 0.038750 -0.055984 0.080925 -vn -3.665192 -1.517272 2.627994 -v 0.038750 -0.056625 0.055284 -vn -3.665192 -2.627994 1.517272 -v 0.038750 -0.055984 0.055925 -vn -3.665189 -3.034546 -0.000000 -v 0.038750 -0.055750 0.056800 -vn -3.665195 1.517275 2.627990 -v 0.038750 -0.058375 0.105284 -vn -3.665185 -0.000000 3.034546 -v 0.038750 -0.057500 0.105050 -vn -3.665195 -1.517275 2.627990 -v 0.038750 -0.056625 0.105284 -vn -3.141614 0.000000 3.141593 -v 0.038750 -0.061125 0.116800 -vn -3.665191 3.034546 0.000003 -v 0.038750 -0.059250 0.081800 -vn -3.665182 2.627994 -1.517272 -v 0.038750 -0.059016 0.057675 -vn -3.665186 2.627997 1.517270 -v 0.038750 -0.059016 0.080925 -vn -3.665190 1.517272 -2.627994 -v 0.038750 -0.058375 0.058316 -vn -3.665194 1.517275 2.627990 -v 0.038750 -0.058375 0.080284 -vn -3.665190 0.000000 -3.034546 -v 0.038750 -0.057500 0.058550 -vn -3.665195 -0.000000 3.034546 -v 0.038750 -0.057500 0.080050 -vn -3.665192 -1.517272 -2.627994 -v 0.038750 -0.056625 0.058316 -vn -3.665195 -1.517275 2.627990 -v 0.038750 -0.056625 0.080284 -vn -3.665192 -2.627994 -1.517272 -v 0.038750 -0.055984 0.057675 -vn -3.665189 1.517268 -2.627997 -v 0.038750 -0.058375 0.108316 -vn -3.665196 2.627991 -1.517273 -v 0.038750 -0.059016 0.107675 -vn -3.665188 -2.627996 1.517270 -v 0.038750 -0.055984 0.105925 -vn -3.665190 -3.034546 0.000003 -v 0.038750 -0.055750 0.106800 -vn -3.665196 -2.627991 -1.517273 -v 0.038750 -0.055984 0.107675 -vn -3.665189 -1.517268 -2.627997 -v 0.038750 -0.056625 0.108316 -vn -3.665190 0.000000 -3.034546 -v 0.038750 -0.057500 0.108550 -vn -3.665190 0.000000 -3.034546 -v 0.038750 -0.057500 0.083550 -vn -3.665189 1.517268 -2.627997 -v 0.038750 -0.058375 0.083316 -vn -3.665196 2.627991 -1.517273 -v 0.038750 -0.059016 0.082675 -vn -2.681517 -1.110721 2.356195 -v 0.038750 -0.063000 0.116800 -vn -1.110723 -2.681520 -2.356194 -v 0.039250 -0.063500 0.005000 -vn -1.110721 -2.681520 2.356194 -v 0.039250 -0.063500 0.116800 -vn 1.517274 -1.977355 -1.832598 -v 0.042250 -0.063500 0.005000 -vn 1.517272 -1.977353 1.832599 -v 0.042250 -0.063500 0.116800 -vn 2.627995 -1.517277 3.665189 -v 0.042384 -0.063000 0.116800 -vn 2.627994 -1.517278 -3.665188 -v 0.042384 -0.063000 0.005000 -vn 1.517281 -2.627993 3.665186 -v 0.042750 -0.062634 0.116800 -vn 1.517280 -2.627994 -3.665187 -v 0.042750 -0.062634 0.005000 -vn 0.000003 -3.034545 3.665198 -v 0.043250 -0.062500 0.116800 -vn 0.000002 -3.034544 -3.665199 -v 0.043250 -0.062500 0.005000 -vn -1.517277 -2.627995 3.665189 -v 0.043750 -0.062634 0.116800 -vn -1.517278 -2.627994 -3.665189 -v 0.043750 -0.062634 0.005000 -vn -2.627994 -1.517278 3.665188 -v 0.044116 -0.063000 0.116800 -vn -2.627995 -1.517277 -3.665188 -v 0.044116 -0.063000 0.005000 -vn -1.517274 -1.977356 1.832598 -v 0.044250 -0.063500 0.116800 -vn -1.517272 -1.977353 -1.832598 -v 0.044250 -0.063500 0.005000 -vn 0.406558 -3.088070 -2.879789 -v 0.044750 -0.063500 0.005000 -vn 0.406559 -3.088071 2.879789 -v 0.044750 -0.063500 0.116800 -vn 1.517280 -2.627995 -2.617998 -v 0.045500 -0.063299 0.005000 -vn 1.517281 -2.627994 2.617998 -v 0.045500 -0.063299 0.116800 -vn 2.627996 -1.517274 -2.617993 -v 0.046049 -0.062750 0.005000 -vn 2.627997 -1.517273 2.617993 -v 0.046049 -0.062750 0.116800 -vn 3.088073 -0.406552 -2.879794 -v 0.046250 -0.062000 0.005000 -vn 3.088054 -0.406551 2.879794 -v 0.046250 -0.062000 0.116800 -vn 3.665167 3.034544 0.000001 -v 0.046250 -0.060750 0.031800 -vn 3.665192 2.627993 -1.517274 -v 0.046250 -0.060315 0.033425 -vn 3.665161 -3.034545 -0.000001 -v 0.046250 -0.054250 0.056800 -vn 3.665192 1.517272 -2.627994 -v 0.046250 -0.059125 0.034615 -vn 3.665190 0.000001 -3.034546 -v 0.046250 -0.057500 0.035050 -vn 3.665189 -2.627993 -1.517274 -v 0.046250 -0.054685 0.083425 -vn 3.665191 -3.034544 0.000000 -v 0.046250 -0.054250 0.081800 -vn 3.621099 -0.724673 -2.964443 -v 0.046250 -0.056728 0.009957 -vn 3.621093 -2.010561 -2.295807 -v 0.046250 -0.055359 0.009245 -vn 3.665193 -1.517272 2.627992 -v 0.046250 -0.055875 0.028985 -vn 3.621103 -2.842961 -1.109340 -v 0.046250 -0.054472 0.007981 -vn 3.621094 -3.034127 0.327342 -v 0.046250 -0.054269 0.006451 -vn 1.223574 -1.477054 -1.036274 -v 0.046250 -0.054794 0.005000 -vn 1.223572 1.477053 -1.036272 -v 0.046250 -0.060206 0.005000 -vn 3.621099 3.034125 0.327342 -v 0.046250 -0.060731 0.006451 -vn 3.621098 2.842962 -1.109341 -v 0.046250 -0.060528 0.007981 -vn 3.621098 0.724671 -2.964443 -v 0.046250 -0.058272 0.009957 -vn 3.665191 0.000001 3.034546 -v 0.046250 -0.057500 0.028550 -vn 3.621097 2.010561 -2.295806 -v 0.046250 -0.059641 0.009245 -vn 3.665194 1.517274 2.627992 -v 0.046250 -0.059125 0.028985 -vn 3.665181 -2.627995 -1.517273 -v 0.046250 -0.054685 0.058425 -vn 3.665197 -1.517273 -2.627992 -v 0.046250 -0.055875 0.059615 -vn 3.665193 -1.517271 -2.627994 -v 0.046250 -0.055875 0.034615 -vn 3.665186 -2.627993 -1.517274 -v 0.046250 -0.054685 0.033425 -vn 3.665195 -3.034544 0.000001 -v 0.046250 -0.054250 0.031800 -vn 3.665188 -2.627994 1.517274 -v 0.046250 -0.054685 0.030175 -vn 3.665191 2.627993 -1.517274 -v 0.046250 -0.060315 0.083425 -vn 3.665190 1.517275 -2.627993 -v 0.046250 -0.059125 0.084615 -vn 3.665179 -1.517271 2.627991 -v 0.046250 -0.055875 0.103985 -vn 3.665195 0.000001 -3.034545 -v 0.046250 -0.057500 0.085050 -vn 3.665187 -2.627996 1.517272 -v 0.046250 -0.054685 0.105175 -vn 3.665192 -2.627993 1.517274 -v 0.046250 -0.054685 0.055175 -vn 3.665193 -1.517271 2.627994 -v 0.046250 -0.055875 0.053985 -vn 3.665190 0.000001 3.034546 -v 0.046250 -0.057500 0.053550 -vn 3.665191 -1.517274 -2.627993 -v 0.046250 -0.055875 0.109615 -vn 3.665190 -2.627993 -1.517274 -v 0.046250 -0.054685 0.108425 -vn 3.665194 -3.034544 0.000002 -v 0.046250 -0.054250 0.106800 -vn 3.665191 -1.517274 -2.627993 -v 0.046250 -0.055875 0.084615 -vn 3.665190 -2.627993 1.517274 -v 0.046250 -0.054685 0.080175 -vn 3.665195 -1.517267 2.627995 -v 0.046250 -0.055875 0.078985 -vn 3.665190 0.000001 -3.034546 -v 0.046250 -0.057500 0.060050 -vn 3.665185 0.000001 3.034548 -v 0.046250 -0.057500 0.078550 -vn 3.665196 1.517273 -2.627992 -v 0.046250 -0.059125 0.059615 -vn 3.665194 1.517269 2.627995 -v 0.046250 -0.059125 0.078985 -vn 3.665194 0.000001 -3.034545 -v 0.046250 -0.057500 0.110050 -vn 3.665190 1.517275 -2.627993 -v 0.046250 -0.059125 0.109615 -vn 3.665188 2.627995 1.517273 -v 0.046250 -0.060315 0.030175 -vn 3.665190 3.034544 -0.000000 -v 0.046250 -0.060750 0.081800 -vn 3.665185 0.000001 3.034548 -v 0.046250 -0.057500 0.103550 -vn 3.665198 1.517272 2.627991 -v 0.046250 -0.059125 0.103985 -vn 3.665186 2.627996 1.517272 -v 0.046250 -0.060315 0.105175 -vn 3.665194 3.034544 0.000002 -v 0.046250 -0.060750 0.106800 -vn 3.665190 2.627993 -1.517274 -v 0.046250 -0.060315 0.108425 -vn 3.665190 2.627993 1.517274 -v 0.046250 -0.060315 0.080175 -vn 3.665180 2.627995 -1.517273 -v 0.046250 -0.060315 0.058425 -vn 3.665194 3.034544 -0.000001 -v 0.046250 -0.060750 0.056800 -vn 3.665189 2.627993 1.517274 -v 0.046250 -0.060315 0.055175 -vn 3.665192 1.517272 2.627994 -v 0.046250 -0.059125 0.053985 -vn 3.665188 -2.627997 1.517270 -v 0.041750 -0.055984 0.005925 -vn 1.918021 -1.477054 -4.177867 -v 0.041750 -0.054794 0.005000 -vn 3.665190 -3.034546 0.000003 -v 0.041750 -0.055750 0.006800 -vn 2.662091 -3.034127 0.327342 -v 0.041750 -0.054269 0.006451 -vn 3.665196 -2.627991 -1.517273 -v 0.041750 -0.055984 0.007675 -vn 2.662083 -2.842961 -1.109340 -v 0.041750 -0.054472 0.007981 -vn 3.665189 -1.517268 -2.627997 -v 0.041750 -0.056625 0.008316 -vn 2.662093 -2.010561 -2.295807 -v 0.041750 -0.055359 0.009245 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 -0.057500 0.008550 -vn 3.665195 -1.517275 2.627990 -v 0.041750 -0.056625 0.005284 -vn 3.665188 0.000000 3.034546 -v 0.041750 -0.057500 0.005050 -vn 1.918022 1.477052 -4.177865 -v 0.041750 -0.060206 0.005000 -vn 2.662086 -0.724673 -2.964442 -v 0.041750 -0.056728 0.009957 -vn 2.662087 0.724671 -2.964443 -v 0.041750 -0.058272 0.009957 -vn 3.665189 1.517268 -2.627997 -v 0.041750 -0.058375 0.008316 -vn 2.662089 2.010561 -2.295805 -v 0.041750 -0.059641 0.009245 -vn 3.665196 2.627991 -1.517273 -v 0.041750 -0.059016 0.007675 -vn 2.662087 2.842962 -1.109341 -v 0.041750 -0.060528 0.007981 -vn 3.665190 3.034546 0.000003 -v 0.041750 -0.059250 0.006800 -vn 2.662086 3.034125 0.327342 -v 0.041750 -0.060731 0.006451 -vn 3.665188 2.627996 1.517270 -v 0.041750 -0.059016 0.005925 -vn 3.665195 1.517275 2.627990 -v 0.041750 -0.058375 0.005284 -vn 3.665190 -3.034546 0.000003 -v 0.041750 -0.055750 0.081800 -vn 3.665196 -2.627991 -1.517273 -v 0.041750 -0.055984 0.082675 -vn 3.665189 -1.517268 -2.627997 -v 0.041750 -0.056625 0.083316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 -0.057500 0.083550 -vn 3.665189 1.517268 -2.627997 -v 0.041750 -0.058375 0.083316 -vn 3.665196 2.627991 -1.517273 -v 0.041750 -0.059016 0.082675 -vn 3.665190 3.034546 0.000003 -v 0.041750 -0.059250 0.081800 -vn 3.665188 2.627996 1.517270 -v 0.041750 -0.059016 0.080925 -vn 3.665195 1.517275 2.627990 -v 0.041750 -0.058375 0.080284 -vn 3.665190 0.000000 3.034546 -v 0.041750 -0.057500 0.080050 -vn 3.665195 -1.517275 2.627990 -v 0.041750 -0.056625 0.080284 -vn 3.665188 -2.627997 1.517270 -v 0.041750 -0.055984 0.080925 -vn 3.665190 -3.034546 0.000000 -v 0.041750 -0.055750 0.056800 -vn 3.665192 -2.627994 -1.517272 -v 0.041750 -0.055984 0.057675 -vn 3.665192 -1.517272 -2.627994 -v 0.041750 -0.056625 0.058316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 -0.057500 0.058550 -vn 3.665192 1.517272 -2.627994 -v 0.041750 -0.058375 0.058316 -vn 3.665192 2.627994 -1.517272 -v 0.041750 -0.059016 0.057675 -vn 3.665190 3.034546 -0.000000 -v 0.041750 -0.059250 0.056800 -vn 3.665192 2.627994 1.517272 -v 0.041750 -0.059016 0.055925 -vn 3.665192 1.517272 2.627994 -v 0.041750 -0.058375 0.055284 -vn 3.665190 0.000000 3.034546 -v 0.041750 -0.057500 0.055050 -vn 3.665192 -1.517272 2.627994 -v 0.041750 -0.056625 0.055284 -vn 3.665192 -2.627994 1.517272 -v 0.041750 -0.055984 0.055925 -vn 3.665191 -3.034546 0.000001 -v 0.041750 -0.055750 0.031800 -vn 3.665192 -2.627994 -1.517272 -v 0.041750 -0.055984 0.032675 -vn 3.665192 -1.517272 -2.627994 -v 0.041750 -0.056625 0.033316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 -0.057500 0.033550 -vn 3.665192 1.517272 -2.627994 -v 0.041750 -0.058375 0.033316 -vn 3.665192 2.627994 -1.517272 -v 0.041750 -0.059016 0.032675 -vn 3.665191 3.034546 0.000001 -v 0.041750 -0.059250 0.031800 -vn 3.665191 2.627994 1.517272 -v 0.041750 -0.059016 0.030925 -vn 3.665192 1.517272 2.627994 -v 0.041750 -0.058375 0.030284 -vn 3.665190 0.000000 3.034546 -v 0.041750 -0.057500 0.030050 -vn 3.665192 -1.517272 2.627994 -v 0.041750 -0.056625 0.030284 -vn 3.665192 -2.627994 1.517272 -v 0.041750 -0.055984 0.030925 -vn 3.665190 -3.034546 0.000003 -v 0.041750 -0.055750 0.106800 -vn 3.665196 -2.627991 -1.517273 -v 0.041750 -0.055984 0.107675 -vn 3.665189 -1.517268 -2.627997 -v 0.041750 -0.056625 0.108316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 -0.057500 0.108550 -vn 3.665189 1.517268 -2.627997 -v 0.041750 -0.058375 0.108316 -vn 3.665196 2.627991 -1.517273 -v 0.041750 -0.059016 0.107675 -vn 3.665190 3.034546 0.000003 -v 0.041750 -0.059250 0.106800 -vn 3.665188 2.627996 1.517270 -v 0.041750 -0.059016 0.105925 -vn 3.665195 1.517275 2.627990 -v 0.041750 -0.058375 0.105284 -vn 3.665190 0.000000 3.034546 -v 0.041750 -0.057500 0.105050 -vn 3.665195 -1.517275 2.627990 -v 0.041750 -0.056625 0.105284 -vn 3.665188 -2.627997 1.517270 -v 0.041750 -0.055984 0.105925 -vn 2.617999 2.627996 1.517272 -v 0.041750 -0.060315 0.105175 -vn 2.617988 1.517272 2.627991 -v 0.041750 -0.059125 0.103985 -vn 2.618000 0.000001 3.034548 -v 0.041750 -0.057500 0.103550 -vn 2.617987 -1.517271 2.627991 -v 0.041750 -0.055875 0.103985 -vn 2.617999 -2.627996 1.517272 -v 0.041750 -0.054685 0.105175 -vn 2.617991 -3.034544 0.000002 -v 0.041750 -0.054250 0.106800 -vn 2.617995 -2.627993 -1.517274 -v 0.041750 -0.054685 0.108425 -vn 2.617995 -1.517274 -2.627993 -v 0.041750 -0.055875 0.109615 -vn 2.617992 0.000001 -3.034544 -v 0.041750 -0.057500 0.110050 -vn 2.617996 1.517275 -2.627993 -v 0.041750 -0.059125 0.109615 -vn 2.617995 2.627993 -1.517274 -v 0.041750 -0.060315 0.108425 -vn 2.617991 3.034544 0.000002 -v 0.041750 -0.060750 0.106800 -vn 2.617997 2.627994 1.517274 -v 0.041750 -0.060315 0.030175 -vn 2.617992 1.517273 2.627992 -v 0.041750 -0.059125 0.028985 -vn 2.617996 0.000001 3.034546 -v 0.041750 -0.057500 0.028550 -vn 2.617991 -1.517273 2.627992 -v 0.041750 -0.055875 0.028985 -vn 2.617997 -2.627995 1.517274 -v 0.041750 -0.054685 0.030175 -vn 2.617991 -3.034544 0.000001 -v 0.041750 -0.054250 0.031800 -vn 2.617995 -2.627993 -1.517274 -v 0.041750 -0.054685 0.033425 -vn 2.617993 -1.517271 -2.627994 -v 0.041750 -0.055875 0.034615 -vn 2.617996 0.000001 -3.034546 -v 0.041750 -0.057500 0.035050 -vn 2.617993 1.517272 -2.627994 -v 0.041750 -0.059125 0.034615 -vn 2.617995 2.627993 -1.517274 -v 0.041750 -0.060315 0.033425 -vn 2.617991 3.034544 0.000001 -v 0.041750 -0.060750 0.031800 -vn 2.617995 2.627993 1.517274 -v 0.041750 -0.060315 0.055175 -vn 2.617993 1.517272 2.627994 -v 0.041750 -0.059125 0.053985 -vn 2.617996 0.000001 3.034546 -v 0.041750 -0.057500 0.053550 -vn 2.617993 -1.517271 2.627994 -v 0.041750 -0.055875 0.053985 -vn 2.617995 -2.627993 1.517274 -v 0.041750 -0.054685 0.055175 -vn 2.617992 -3.034544 -0.000001 -v 0.041750 -0.054250 0.056800 -vn 2.617997 -2.627995 -1.517273 -v 0.041750 -0.054685 0.058425 -vn 2.617991 -1.517272 -2.627992 -v 0.041750 -0.055875 0.059615 -vn 2.617996 0.000001 -3.034546 -v 0.041750 -0.057500 0.060050 -vn 2.617992 1.517274 -2.627992 -v 0.041750 -0.059125 0.059615 -vn 2.617997 2.627995 -1.517273 -v 0.041750 -0.060315 0.058425 -vn 2.617991 3.034545 -0.000001 -v 0.041750 -0.060750 0.056800 -vn 2.617996 1.517275 -2.627993 -v 0.041750 -0.059125 0.084615 -vn 2.617995 2.627993 -1.517274 -v 0.041750 -0.060315 0.083425 -vn 2.617992 3.034544 0.000000 -v 0.041750 -0.060750 0.081800 -vn 2.617995 2.627993 1.517274 -v 0.041750 -0.060315 0.080175 -vn 2.617991 1.517268 2.627995 -v 0.041750 -0.059125 0.078985 -vn 2.618000 0.000001 3.034548 -v 0.041750 -0.057500 0.078550 -vn 2.617991 -1.517268 2.627995 -v 0.041750 -0.055875 0.078985 -vn 2.617995 -2.627993 1.517274 -v 0.041750 -0.054685 0.080175 -vn 2.617992 -3.034545 -0.000000 -v 0.041750 -0.054250 0.081800 -vn 2.617995 -2.627993 -1.517274 -v 0.041750 -0.054685 0.083425 -vn 2.617995 -1.517274 -2.627993 -v 0.041750 -0.055875 0.084615 -vn 2.617992 0.000001 -3.034544 -v 0.041750 -0.057500 0.085050 -vn 3.088024 0.406552 2.879794 -v 0.046250 0.062000 0.116800 -vn 3.088072 0.406551 -2.879793 -v 0.046250 0.062000 0.005000 -vn 2.627997 1.517273 -2.617993 -v 0.046049 0.062750 0.005000 -vn 2.627996 1.517274 2.617993 -v 0.046049 0.062750 0.116800 -vn 1.517281 2.627994 -2.617998 -v 0.045500 0.063299 0.005000 -vn 1.517280 2.627995 2.617998 -v 0.045500 0.063299 0.116800 -vn 0.406559 3.088071 -2.879789 -v 0.044750 0.063500 0.005000 -vn 0.406558 3.088070 2.879789 -v 0.044750 0.063500 0.116800 -vn -1.517274 1.977356 -1.832598 -v 0.044250 0.063500 0.005000 -vn -1.517272 1.977353 1.832598 -v 0.044250 0.063500 0.116800 -vn -2.627995 1.517277 3.665188 -v 0.044116 0.063000 0.116800 -vn -2.627994 1.517278 -3.665188 -v 0.044116 0.063000 0.005000 -vn -1.517278 2.627994 3.665188 -v 0.043750 0.062634 0.116800 -vn -1.517277 2.627995 -3.665189 -v 0.043750 0.062634 0.005000 -vn 0.000002 3.034544 3.665198 -v 0.043250 0.062500 0.116800 -vn 0.000003 3.034545 -3.665199 -v 0.043250 0.062500 0.005000 -vn 1.517280 2.627994 3.665188 -v 0.042750 0.062634 0.116800 -vn 1.517281 2.627993 -3.665187 -v 0.042750 0.062634 0.005000 -vn 2.627994 1.517278 3.665188 -v 0.042384 0.063000 0.116800 -vn 2.627995 1.517277 -3.665188 -v 0.042384 0.063000 0.005000 -vn 1.517274 1.977355 1.832598 -v 0.042250 0.063500 0.116800 -vn 1.517272 1.977353 -1.832599 -v 0.042250 0.063500 0.005000 -vn -1.110723 2.681522 -2.356194 -v 0.039250 0.063500 0.005000 -vn -1.110721 2.681517 2.356194 -v 0.039250 0.063500 0.116800 -vn -2.681518 1.110721 2.356194 -v 0.038750 0.063000 0.116800 -vn -5.362996 2.221442 0.000000 -v 0.038750 0.063000 0.044300 -vn -2.681515 1.110721 -2.356195 -v 0.038750 0.063000 0.005000 -vn -3.665192 2.627994 -1.517272 -v 0.038750 0.055984 0.032675 -vn -3.665191 3.034546 0.000001 -v 0.038750 0.055750 0.031800 -vn -6.283185 0.000000 0.000000 -v 0.038750 0.053875 0.044300 -vn -3.665190 2.627991 -1.517273 -v 0.038750 0.055984 0.007675 -vn -3.665190 3.034546 0.000003 -v 0.038750 0.055750 0.006800 -vn -3.141594 0.000000 -3.141593 -v 0.038750 0.053875 0.005000 -vn -3.665188 2.627997 1.517270 -v 0.038750 0.055984 0.005925 -vn -3.665190 -3.034546 0.000001 -v 0.038750 0.059250 0.031800 -vn -3.665192 -2.627994 -1.517272 -v 0.038750 0.059016 0.032675 -vn -3.665189 1.517268 -2.627997 -v 0.038750 0.056625 0.008316 -vn -3.665194 1.517272 2.627994 -v 0.038750 0.056625 0.030284 -vn -3.665192 2.627994 1.517272 -v 0.038750 0.055984 0.030925 -vn -3.665195 -1.517275 2.627990 -v 0.038750 0.058375 0.005284 -vn -3.665189 -0.000000 3.034546 -v 0.038750 0.057500 0.005050 -vn -3.665195 1.517275 2.627990 -v 0.038750 0.056625 0.005284 -vn -3.665188 -2.627996 1.517270 -v 0.038750 0.059016 0.005925 -vn -3.665190 -3.034546 0.000003 -v 0.038750 0.059250 0.006800 -vn -3.665190 -2.627991 -1.517273 -v 0.038750 0.059016 0.007675 -vn -3.665190 0.000000 -3.034546 -v 0.038750 0.057500 0.008550 -vn -3.665190 -0.000000 3.034546 -v 0.038750 0.057500 0.030050 -vn -3.665189 -1.517268 -2.627997 -v 0.038750 0.058375 0.008316 -vn -3.665194 -1.517272 2.627994 -v 0.038750 0.058375 0.030284 -vn -3.665192 -2.627994 1.517272 -v 0.038750 0.059016 0.030925 -vn -3.665192 -1.517272 -2.627994 -v 0.038750 0.058375 0.033316 -vn -3.665190 0.000000 -3.034546 -v 0.038750 0.057500 0.033550 -vn -3.665192 1.517272 -2.627994 -v 0.038750 0.056625 0.033316 -vn -2.681517 -1.110721 -2.356194 -v 0.038750 0.052000 0.005000 -vn -5.363034 -2.221442 0.000000 -v 0.038750 0.052000 0.044300 -vn -3.665192 1.517272 2.627994 -v 0.038750 0.056625 0.055284 -vn -3.665192 2.627994 1.517272 -v 0.038750 0.055984 0.055925 -vn -3.665190 3.034546 0.000000 -v 0.038750 0.055750 0.056800 -vn -3.665190 -0.000000 3.034546 -v 0.038750 0.057500 0.055050 -vn -3.665189 2.627997 1.517270 -v 0.038750 0.055984 0.105925 -vn -3.665182 -3.034546 0.000003 -v 0.038750 0.059250 0.081800 -vn -3.665188 3.034546 0.000003 -v 0.038750 0.055750 0.106800 -vn -3.665197 -2.627991 -1.517273 -v 0.038750 0.059016 0.082675 -vn -3.665189 -1.517268 -2.627997 -v 0.038750 0.058375 0.083316 -vn -3.665188 -2.627996 1.517270 -v 0.038750 0.059016 0.080925 -vn -3.665192 -1.517272 2.627994 -v 0.038750 0.058375 0.055284 -vn -3.665192 -2.627994 1.517272 -v 0.038750 0.059016 0.055925 -vn -3.665189 -3.034546 -0.000000 -v 0.038750 0.059250 0.056800 -vn -3.665195 1.517275 2.627990 -v 0.038750 0.056625 0.105284 -vn -3.665185 -0.000000 3.034546 -v 0.038750 0.057500 0.105050 -vn -3.665195 -1.517275 2.627990 -v 0.038750 0.058375 0.105284 -vn -3.141603 0.000000 3.141593 -v 0.038750 0.053875 0.116800 -vn -3.665191 3.034546 0.000003 -v 0.038750 0.055750 0.081800 -vn -3.665182 2.627994 -1.517272 -v 0.038750 0.055984 0.057675 -vn -3.665186 2.627997 1.517270 -v 0.038750 0.055984 0.080925 -vn -3.665190 1.517272 -2.627994 -v 0.038750 0.056625 0.058316 -vn -3.665194 1.517275 2.627990 -v 0.038750 0.056625 0.080284 -vn -3.665190 0.000000 -3.034546 -v 0.038750 0.057500 0.058550 -vn -3.665195 -0.000000 3.034546 -v 0.038750 0.057500 0.080050 -vn -3.665192 -1.517272 -2.627994 -v 0.038750 0.058375 0.058316 -vn -3.665195 -1.517275 2.627990 -v 0.038750 0.058375 0.080284 -vn -3.665192 -2.627994 -1.517272 -v 0.038750 0.059016 0.057675 -vn -3.665189 1.517268 -2.627997 -v 0.038750 0.056625 0.108316 -vn -3.665196 2.627991 -1.517273 -v 0.038750 0.055984 0.107675 -vn -3.665188 -2.627996 1.517270 -v 0.038750 0.059016 0.105925 -vn -3.665190 -3.034546 0.000003 -v 0.038750 0.059250 0.106800 -vn -3.665196 -2.627991 -1.517273 -v 0.038750 0.059016 0.107675 -vn -3.665189 -1.517268 -2.627997 -v 0.038750 0.058375 0.108316 -vn -3.665190 0.000000 -3.034546 -v 0.038750 0.057500 0.108550 -vn -3.665190 0.000000 -3.034546 -v 0.038750 0.057500 0.083550 -vn -3.665189 1.517268 -2.627997 -v 0.038750 0.056625 0.083316 -vn -3.665196 2.627991 -1.517273 -v 0.038750 0.055984 0.082675 -vn -2.681517 -1.110721 2.356195 -v 0.038750 0.052000 0.116800 -vn -1.110723 -2.681520 -2.356194 -v 0.039250 0.051500 0.005000 -vn -1.110721 -2.681520 2.356194 -v 0.039250 0.051500 0.116800 -vn 1.517274 -1.977355 -1.832598 -v 0.042250 0.051500 0.005000 -vn 1.517272 -1.977353 1.832599 -v 0.042250 0.051500 0.116800 -vn 2.627995 -1.517277 3.665189 -v 0.042384 0.052000 0.116800 -vn 2.627994 -1.517278 -3.665188 -v 0.042384 0.052000 0.005000 -vn 1.517271 -2.627996 3.665194 -v 0.042750 0.052366 0.116800 -vn 1.517270 -2.627997 -3.665194 -v 0.042750 0.052366 0.005000 -vn 0.000003 -3.034550 3.665184 -v 0.043250 0.052500 0.116800 -vn 0.000002 -3.034550 -3.665185 -v 0.043250 0.052500 0.005000 -vn -1.517267 -2.627997 3.665196 -v 0.043750 0.052366 0.116800 -vn -1.517268 -2.627997 -3.665195 -v 0.043750 0.052366 0.005000 -vn -2.627994 -1.517278 3.665189 -v 0.044116 0.052000 0.116800 -vn -2.627995 -1.517277 -3.665189 -v 0.044116 0.052000 0.005000 -vn -1.517274 -1.977356 1.832598 -v 0.044250 0.051500 0.116800 -vn -1.517272 -1.977353 -1.832598 -v 0.044250 0.051500 0.005000 -vn 0.406551 -3.088072 -2.879794 -v 0.044750 0.051500 0.005000 -vn 0.406552 -3.088073 2.879794 -v 0.044750 0.051500 0.116800 -vn 1.517273 -2.627997 -2.617993 -v 0.045500 0.051701 0.005000 -vn 1.517274 -2.627996 2.617993 -v 0.045500 0.051701 0.116800 -vn 2.627996 -1.517274 -2.617993 -v 0.046049 0.052250 0.005000 -vn 2.627997 -1.517273 2.617993 -v 0.046049 0.052250 0.116800 -vn 3.088073 -0.406552 -2.879794 -v 0.046250 0.053000 0.005000 -vn 3.088054 -0.406551 2.879792 -v 0.046250 0.053000 0.116800 -vn 3.665167 3.034544 0.000001 -v 0.046250 0.054250 0.031800 -vn 3.665192 2.627993 -1.517274 -v 0.046250 0.054685 0.033425 -vn 3.665162 -3.034545 -0.000001 -v 0.046250 0.060750 0.056800 -vn 3.665193 1.517271 -2.627994 -v 0.046250 0.055875 0.034615 -vn 3.665190 -0.000001 -3.034546 -v 0.046250 0.057500 0.035050 -vn 3.665189 -2.627993 -1.517274 -v 0.046250 0.060315 0.083425 -vn 3.665191 -3.034544 0.000000 -v 0.046250 0.060750 0.081800 -vn 3.621098 -0.724671 -2.964444 -v 0.046250 0.058272 0.009957 -vn 3.621096 -2.010561 -2.295805 -v 0.046250 0.059641 0.009245 -vn 3.665192 -1.517273 2.627992 -v 0.046250 0.059125 0.028985 -vn 3.621098 -2.842962 -1.109341 -v 0.046250 0.060528 0.007981 -vn 3.621099 -3.034125 0.327342 -v 0.046250 0.060731 0.006451 -vn 1.223572 -1.477052 -1.036271 -v 0.046250 0.060206 0.005000 -vn 1.223574 1.477054 -1.036275 -v 0.046250 0.054794 0.005000 -vn 3.621094 3.034127 0.327342 -v 0.046250 0.054269 0.006451 -vn 3.621103 2.842961 -1.109340 -v 0.046250 0.054472 0.007981 -vn 3.621099 0.724673 -2.964442 -v 0.046250 0.056728 0.009957 -vn 3.665190 -0.000001 3.034546 -v 0.046250 0.057500 0.028550 -vn 3.621094 2.010561 -2.295807 -v 0.046250 0.055359 0.009245 -vn 3.665194 1.517273 2.627992 -v 0.046250 0.055875 0.028985 -vn 3.665181 -2.627995 -1.517273 -v 0.046250 0.060315 0.058425 -vn 3.665196 -1.517274 -2.627992 -v 0.046250 0.059125 0.059615 -vn 3.665192 -1.517272 -2.627994 -v 0.046250 0.059125 0.034615 -vn 3.665186 -2.627993 -1.517274 -v 0.046250 0.060315 0.033425 -vn 3.665195 -3.034544 0.000001 -v 0.046250 0.060750 0.031800 -vn 3.665188 -2.627994 1.517274 -v 0.046250 0.060315 0.030175 -vn 3.665191 2.627993 -1.517274 -v 0.046250 0.054685 0.083425 -vn 3.665190 1.517274 -2.627993 -v 0.046250 0.055875 0.084615 -vn 3.665179 -1.517272 2.627991 -v 0.046250 0.059125 0.103985 -vn 3.665194 -0.000001 -3.034544 -v 0.046250 0.057500 0.085050 -vn 3.665186 -2.627996 1.517272 -v 0.046250 0.060315 0.105175 -vn 3.665192 -2.627993 1.517274 -v 0.046250 0.060315 0.055175 -vn 3.665192 -1.517272 2.627994 -v 0.046250 0.059125 0.053985 -vn 3.665190 -0.000001 3.034546 -v 0.046250 0.057500 0.053550 -vn 3.665190 -1.517275 -2.627993 -v 0.046250 0.059125 0.109615 -vn 3.665190 -2.627993 -1.517274 -v 0.046250 0.060315 0.108425 -vn 3.665194 -3.034544 0.000002 -v 0.046250 0.060750 0.106800 -vn 3.665190 -1.517275 -2.627993 -v 0.046250 0.059125 0.084615 -vn 3.665190 -2.627993 1.517274 -v 0.046250 0.060315 0.080175 -vn 3.665195 -1.517268 2.627995 -v 0.046250 0.059125 0.078985 -vn 3.665190 -0.000001 -3.034546 -v 0.046250 0.057500 0.060050 -vn 3.665185 -0.000001 3.034548 -v 0.046250 0.057500 0.078550 -vn 3.665197 1.517272 -2.627992 -v 0.046250 0.055875 0.059615 -vn 3.665195 1.517268 2.627995 -v 0.046250 0.055875 0.078985 -vn 3.665194 -0.000001 -3.034544 -v 0.046250 0.057500 0.110050 -vn 3.665191 1.517274 -2.627993 -v 0.046250 0.055875 0.109615 -vn 3.665188 2.627995 1.517273 -v 0.046250 0.054685 0.030175 -vn 3.665189 3.034544 -0.000000 -v 0.046250 0.054250 0.081800 -vn 3.665185 -0.000001 3.034548 -v 0.046250 0.057500 0.103550 -vn 3.665198 1.517271 2.627991 -v 0.046250 0.055875 0.103985 -vn 3.665186 2.627996 1.517272 -v 0.046250 0.054685 0.105175 -vn 3.665194 3.034544 0.000002 -v 0.046250 0.054250 0.106800 -vn 3.665190 2.627993 -1.517274 -v 0.046250 0.054685 0.108425 -vn 3.665190 2.627993 1.517274 -v 0.046250 0.054685 0.080175 -vn 3.665180 2.627995 -1.517273 -v 0.046250 0.054685 0.058425 -vn 3.665194 3.034544 -0.000001 -v 0.046250 0.054250 0.056800 -vn 3.665189 2.627993 1.517274 -v 0.046250 0.054685 0.055175 -vn 3.665193 1.517271 2.627994 -v 0.046250 0.055875 0.053985 -vn 3.665188 -2.627997 1.517270 -v 0.041750 0.059016 0.005925 -vn 1.918022 -1.477053 -4.177865 -v 0.041750 0.060206 0.005000 -vn 3.665190 -3.034546 0.000003 -v 0.041750 0.059250 0.006800 -vn 2.662086 -3.034125 0.327342 -v 0.041750 0.060731 0.006451 -vn 3.665196 -2.627991 -1.517273 -v 0.041750 0.059016 0.007675 -vn 2.662087 -2.842962 -1.109341 -v 0.041750 0.060528 0.007981 -vn 3.665189 -1.517268 -2.627997 -v 0.041750 0.058375 0.008316 -vn 2.662089 -2.010561 -2.295806 -v 0.041750 0.059641 0.009245 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 0.057500 0.008550 -vn 3.665195 -1.517275 2.627990 -v 0.041750 0.058375 0.005284 -vn 3.665188 0.000000 3.034546 -v 0.041750 0.057500 0.005050 -vn 1.918021 1.477054 -4.177868 -v 0.041750 0.054794 0.005000 -vn 2.662087 -0.724671 -2.964443 -v 0.041750 0.058272 0.009957 -vn 2.662086 0.724673 -2.964443 -v 0.041750 0.056728 0.009957 -vn 3.665189 1.517268 -2.627997 -v 0.041750 0.056625 0.008316 -vn 2.662092 2.010561 -2.295807 -v 0.041750 0.055359 0.009245 -vn 3.665196 2.627991 -1.517273 -v 0.041750 0.055984 0.007675 -vn 2.662083 2.842961 -1.109340 -v 0.041750 0.054472 0.007981 -vn 3.665190 3.034546 0.000003 -v 0.041750 0.055750 0.006800 -vn 2.662091 3.034127 0.327342 -v 0.041750 0.054269 0.006451 -vn 3.665188 2.627996 1.517270 -v 0.041750 0.055984 0.005925 -vn 3.665195 1.517275 2.627990 -v 0.041750 0.056625 0.005284 -vn 3.665190 -3.034546 0.000003 -v 0.041750 0.059250 0.081800 -vn 3.665196 -2.627991 -1.517273 -v 0.041750 0.059016 0.082675 -vn 3.665189 -1.517268 -2.627997 -v 0.041750 0.058375 0.083316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 0.057500 0.083550 -vn 3.665189 1.517268 -2.627997 -v 0.041750 0.056625 0.083316 -vn 3.665196 2.627991 -1.517273 -v 0.041750 0.055984 0.082675 -vn 3.665190 3.034546 0.000003 -v 0.041750 0.055750 0.081800 -vn 3.665188 2.627996 1.517270 -v 0.041750 0.055984 0.080925 -vn 3.665195 1.517275 2.627990 -v 0.041750 0.056625 0.080284 -vn 3.665190 0.000000 3.034546 -v 0.041750 0.057500 0.080050 -vn 3.665195 -1.517275 2.627990 -v 0.041750 0.058375 0.080284 -vn 3.665188 -2.627997 1.517270 -v 0.041750 0.059016 0.080925 -vn 3.665190 -3.034546 0.000000 -v 0.041750 0.059250 0.056800 -vn 3.665192 -2.627994 -1.517272 -v 0.041750 0.059016 0.057675 -vn 3.665192 -1.517272 -2.627994 -v 0.041750 0.058375 0.058316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 0.057500 0.058550 -vn 3.665192 1.517272 -2.627994 -v 0.041750 0.056625 0.058316 -vn 3.665192 2.627994 -1.517272 -v 0.041750 0.055984 0.057675 -vn 3.665190 3.034546 -0.000000 -v 0.041750 0.055750 0.056800 -vn 3.665192 2.627994 1.517272 -v 0.041750 0.055984 0.055925 -vn 3.665192 1.517272 2.627994 -v 0.041750 0.056625 0.055284 -vn 3.665190 0.000000 3.034546 -v 0.041750 0.057500 0.055050 -vn 3.665192 -1.517272 2.627994 -v 0.041750 0.058375 0.055284 -vn 3.665192 -2.627994 1.517272 -v 0.041750 0.059016 0.055925 -vn 3.665191 -3.034546 0.000001 -v 0.041750 0.059250 0.031800 -vn 3.665192 -2.627994 -1.517272 -v 0.041750 0.059016 0.032675 -vn 3.665192 -1.517272 -2.627994 -v 0.041750 0.058375 0.033316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 0.057500 0.033550 -vn 3.665192 1.517272 -2.627994 -v 0.041750 0.056625 0.033316 -vn 3.665192 2.627994 -1.517272 -v 0.041750 0.055984 0.032675 -vn 3.665191 3.034546 0.000001 -v 0.041750 0.055750 0.031800 -vn 3.665192 2.627994 1.517272 -v 0.041750 0.055984 0.030925 -vn 3.665192 1.517272 2.627994 -v 0.041750 0.056625 0.030284 -vn 3.665190 0.000000 3.034546 -v 0.041750 0.057500 0.030050 -vn 3.665192 -1.517272 2.627994 -v 0.041750 0.058375 0.030284 -vn 3.665192 -2.627994 1.517272 -v 0.041750 0.059016 0.030925 -vn 3.665190 -3.034546 0.000003 -v 0.041750 0.059250 0.106800 -vn 3.665196 -2.627991 -1.517273 -v 0.041750 0.059016 0.107675 -vn 3.665189 -1.517268 -2.627997 -v 0.041750 0.058375 0.108316 -vn 3.665190 -0.000000 -3.034546 -v 0.041750 0.057500 0.108550 -vn 3.665189 1.517268 -2.627997 -v 0.041750 0.056625 0.108316 -vn 3.665196 2.627991 -1.517273 -v 0.041750 0.055984 0.107675 -vn 3.665190 3.034546 0.000003 -v 0.041750 0.055750 0.106800 -vn 3.665188 2.627996 1.517270 -v 0.041750 0.055984 0.105925 -vn 3.665195 1.517275 2.627990 -v 0.041750 0.056625 0.105284 -vn 3.665190 0.000000 3.034546 -v 0.041750 0.057500 0.105050 -vn 3.665195 -1.517275 2.627990 -v 0.041750 0.058375 0.105284 -vn 3.665188 -2.627997 1.517270 -v 0.041750 0.059016 0.105925 -vn 2.617999 2.627996 1.517272 -v 0.041750 0.054685 0.105175 -vn 2.617987 1.517271 2.627991 -v 0.041750 0.055875 0.103985 -vn 2.618000 -0.000001 3.034548 -v 0.041750 0.057500 0.103550 -vn 2.617988 -1.517272 2.627991 -v 0.041750 0.059125 0.103985 -vn 2.617999 -2.627996 1.517272 -v 0.041750 0.060315 0.105175 -vn 2.617991 -3.034544 0.000002 -v 0.041750 0.060750 0.106800 -vn 2.617995 -2.627993 -1.517274 -v 0.041750 0.060315 0.108425 -vn 2.617996 -1.517275 -2.627993 -v 0.041750 0.059125 0.109615 -vn 2.617992 -0.000001 -3.034545 -v 0.041750 0.057500 0.110050 -vn 2.617995 1.517274 -2.627993 -v 0.041750 0.055875 0.109615 -vn 2.617995 2.627993 -1.517274 -v 0.041750 0.054685 0.108425 -vn 2.617991 3.034544 0.000002 -v 0.041750 0.054250 0.106800 -vn 2.617997 2.627994 1.517274 -v 0.041750 0.054685 0.030175 -vn 2.617991 1.517272 2.627992 -v 0.041750 0.055875 0.028985 -vn 2.617996 -0.000001 3.034546 -v 0.041750 0.057500 0.028550 -vn 2.617992 -1.517274 2.627992 -v 0.041750 0.059125 0.028985 -vn 2.617997 -2.627995 1.517274 -v 0.041750 0.060315 0.030175 -vn 2.617991 -3.034544 0.000001 -v 0.041750 0.060750 0.031800 -vn 2.617995 -2.627993 -1.517274 -v 0.041750 0.060315 0.033425 -vn 2.617993 -1.517272 -2.627994 -v 0.041750 0.059125 0.034615 -vn 2.617996 -0.000001 -3.034546 -v 0.041750 0.057500 0.035050 -vn 2.617993 1.517271 -2.627994 -v 0.041750 0.055875 0.034615 -vn 2.617995 2.627993 -1.517274 -v 0.041750 0.054685 0.033425 -vn 2.617991 3.034544 0.000001 -v 0.041750 0.054250 0.031800 -vn 2.617995 2.627993 1.517274 -v 0.041750 0.054685 0.055175 -vn 2.617993 1.517271 2.627994 -v 0.041750 0.055875 0.053985 -vn 2.617996 -0.000001 3.034546 -v 0.041750 0.057500 0.053550 -vn 2.617993 -1.517272 2.627994 -v 0.041750 0.059125 0.053985 -vn 2.617995 -2.627993 1.517274 -v 0.041750 0.060315 0.055175 -vn 2.617992 -3.034544 -0.000001 -v 0.041750 0.060750 0.056800 -vn 2.617997 -2.627995 -1.517273 -v 0.041750 0.060315 0.058425 -vn 2.617992 -1.517273 -2.627992 -v 0.041750 0.059125 0.059615 -vn 2.617996 -0.000001 -3.034546 -v 0.041750 0.057500 0.060050 -vn 2.617991 1.517273 -2.627992 -v 0.041750 0.055875 0.059615 -vn 2.617997 2.627995 -1.517273 -v 0.041750 0.054685 0.058425 -vn 2.617992 3.034545 -0.000001 -v 0.041750 0.054250 0.056800 -vn 2.617995 1.517274 -2.627993 -v 0.041750 0.055875 0.084615 -vn 2.617995 2.627993 -1.517274 -v 0.041750 0.054685 0.083425 -vn 2.617992 3.034544 0.000000 -v 0.041750 0.054250 0.081800 -vn 2.617995 2.627993 1.517274 -v 0.041750 0.054685 0.080175 -vn 2.617990 1.517267 2.627995 -v 0.041750 0.055875 0.078985 -vn 2.618000 -0.000001 3.034548 -v 0.041750 0.057500 0.078550 -vn 2.617991 -1.517269 2.627995 -v 0.041750 0.059125 0.078985 -vn 2.617995 -2.627993 1.517274 -v 0.041750 0.060315 0.080175 -vn 2.617992 -3.034545 -0.000000 -v 0.041750 0.060750 0.081800 -vn 2.617995 -2.627993 -1.517274 -v 0.041750 0.060315 0.083425 -vn 2.617996 -1.517275 -2.627993 -v 0.041750 0.059125 0.084615 -vn 2.617992 -0.000001 -3.034545 -v 0.041750 0.057500 0.085050 -# 586 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 1//1 3//3 4//4 -f 4//4 3//3 5//5 -f 4//4 5//5 6//6 -f 6//6 5//5 7//7 -f 6//6 7//7 8//8 -f 7//7 9//9 8//8 -f 8//8 9//9 10//10 -f 10//10 9//9 11//11 -f 11//11 9//9 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 22//22 23//23 21//21 -f 21//21 23//23 24//24 -f 25//25 24//24 26//26 -f 26//26 24//24 23//23 -f 26//26 23//23 27//27 -f 28//28 29//29 30//30 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 35//35 36//36 26//26 -f 37//37 31//31 38//38 -f 38//38 31//31 39//39 -f 40//40 27//27 41//41 -f 41//41 27//27 33//33 -f 41//41 33//33 42//42 -f 42//42 33//33 34//34 -f 40//40 43//43 27//27 -f 27//27 43//43 44//44 -f 27//27 44//44 26//26 -f 26//26 44//44 45//45 -f 26//26 45//45 35//35 -f 37//37 38//38 46//46 -f 46//46 38//38 47//47 -f 46//46 47//47 48//48 -f 48//48 47//47 49//49 -f 48//48 49//49 45//45 -f 45//45 49//49 50//50 -f 45//45 50//50 35//35 -f 51//51 52//52 30//30 -f 30//30 52//52 53//53 -f 30//30 53//53 28//28 -f 54//54 55//55 33//33 -f 33//33 55//55 30//30 -f 33//33 30//30 31//31 -f 31//31 30//30 29//29 -f 31//31 29//29 39//39 -f 56//56 30//30 57//57 -f 57//57 30//30 58//58 -f 56//56 59//59 30//30 -f 30//30 59//59 26//26 -f 30//30 26//26 51//51 -f 51//51 26//26 36//36 -f 60//60 61//61 62//62 -f 62//62 61//61 63//63 -f 62//62 63//63 64//64 -f 26//26 65//65 61//61 -f 59//59 66//66 26//26 -f 26//26 66//66 67//67 -f 26//26 67//67 68//68 -f 60//60 69//69 61//61 -f 61//61 69//69 70//70 -f 61//61 70//70 26//26 -f 26//26 70//70 71//71 -f 72//72 73//73 74//74 -f 74//74 73//73 75//75 -f 74//74 75//75 76//76 -f 76//76 75//75 77//77 -f 76//76 77//77 78//78 -f 78//78 77//77 79//79 -f 78//78 79//79 80//80 -f 65//65 26//26 81//81 -f 81//81 26//26 68//68 -f 81//81 68//68 79//79 -f 79//79 68//68 82//82 -f 79//79 82//82 80//80 -f 83//83 84//84 72//72 -f 72//72 84//84 62//62 -f 71//71 85//85 26//26 -f 26//26 85//85 86//86 -f 26//26 86//86 25//25 -f 86//86 87//87 25//25 -f 25//25 87//87 88//88 -f 25//25 88//88 72//72 -f 72//72 88//88 89//89 -f 72//72 89//89 83//83 -f 64//64 90//90 62//62 -f 62//62 90//90 91//91 -f 62//62 91//91 72//72 -f 72//72 91//91 92//92 -f 72//72 92//92 73//73 -f 55//55 93//93 30//30 -f 30//30 93//93 72//72 -f 30//30 72//72 58//58 -f 58//58 72//72 74//74 -f 54//54 94//94 55//55 -f 55//55 94//94 95//95 -f 55//55 95//95 93//93 -f 94//94 96//96 95//95 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 98//98 96//96 99//99 -f 98//98 99//99 100//100 -f 100//100 99//99 101//101 -f 100//100 101//101 102//102 -f 102//102 101//101 103//103 -f 102//102 103//103 104//104 -f 104//104 103//103 105//105 -f 104//104 105//105 106//106 -f 106//106 105//105 107//107 -f 106//106 107//107 108//108 -f 108//108 107//107 109//109 -f 109//109 110//110 108//108 -f 108//108 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 118//118 119//119 120//120 -f 120//120 119//119 121//121 -f 120//120 121//121 122//122 -f 123//123 124//124 1//1 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 2//2 -f 2//2 128//128 129//129 -f 2//2 129//129 130//130 -f 131//131 132//132 116//116 -f 116//116 132//132 133//133 -f 125//125 127//127 134//134 -f 134//134 127//127 135//135 -f 134//134 135//135 136//136 -f 136//136 135//135 137//137 -f 136//136 137//137 133//133 -f 120//120 1//1 138//138 -f 138//138 1//1 124//124 -f 138//138 124//124 139//139 -f 122//122 140//140 120//120 -f 120//120 140//140 141//141 -f 120//120 141//141 1//1 -f 1//1 141//141 142//142 -f 1//1 142//142 2//2 -f 2//2 142//142 143//143 -f 2//2 143//143 127//127 -f 144//144 145//145 146//146 -f 146//146 145//145 147//147 -f 146//146 147//147 148//148 -f 120//120 149//149 118//118 -f 118//118 149//149 150//150 -f 118//118 150//150 151//151 -f 152//152 153//153 1//1 -f 1//1 153//153 154//154 -f 1//1 154//154 123//123 -f 123//123 154//154 148//148 -f 123//123 148//148 155//155 -f 155//155 148//148 147//147 -f 124//124 156//156 139//139 -f 139//139 156//156 157//157 -f 139//139 157//157 158//158 -f 158//158 157//157 159//159 -f 158//158 159//159 160//160 -f 160//160 159//159 161//161 -f 152//152 1//1 162//162 -f 162//162 1//1 117//117 -f 162//162 117//117 163//163 -f 133//133 137//137 116//116 -f 116//116 137//137 164//164 -f 116//116 164//164 118//118 -f 144//144 146//146 165//165 -f 165//165 146//146 166//166 -f 165//165 166//166 167//167 -f 167//167 168//168 165//165 -f 165//165 168//168 169//169 -f 165//165 169//169 117//117 -f 117//117 169//169 170//170 -f 117//117 170//170 163//163 -f 161//161 171//171 160//160 -f 160//160 171//171 165//165 -f 160//160 165//165 172//172 -f 172//172 165//165 117//117 -f 172//172 117//117 173//173 -f 173//173 117//117 116//116 -f 173//173 116//116 174//174 -f 174//174 116//116 118//118 -f 174//174 118//118 175//175 -f 175//175 118//118 151//151 -f 176//176 177//177 178//178 -f 178//178 177//177 179//179 -f 178//178 179//179 180//180 -f 180//180 179//179 181//181 -f 180//180 181//181 182//182 -f 182//182 181//181 183//183 -f 182//182 183//183 184//184 -f 176//176 185//185 177//177 -f 177//177 185//185 186//186 -f 177//177 186//186 187//187 -f 183//183 188//188 184//184 -f 184//184 188//188 189//189 -f 184//184 189//189 190//190 -f 190//190 189//189 191//191 -f 190//190 191//191 192//192 -f 192//192 191//191 193//193 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 194//194 195//195 196//196 -f 196//196 195//195 187//187 -f 196//196 187//187 197//197 -f 197//197 187//187 186//186 -f 177//177 130//130 179//179 -f 179//179 130//130 129//129 -f 179//179 129//129 181//181 -f 181//181 129//129 128//128 -f 181//181 128//128 183//183 -f 183//183 128//128 126//126 -f 183//183 126//126 188//188 -f 188//188 126//126 125//125 -f 188//188 125//125 189//189 -f 189//189 125//125 134//134 -f 189//189 134//134 191//191 -f 191//191 134//134 136//136 -f 191//191 136//136 193//193 -f 193//193 136//136 133//133 -f 193//193 133//133 195//195 -f 195//195 133//133 132//132 -f 195//195 132//132 187//187 -f 187//187 132//132 131//131 -f 61//61 198//198 63//63 -f 63//63 198//198 199//199 -f 63//63 199//199 64//64 -f 64//64 199//199 200//200 -f 64//64 200//200 90//90 -f 90//90 200//200 201//201 -f 90//90 201//201 91//91 -f 91//91 201//201 202//202 -f 91//91 202//202 92//92 -f 92//92 202//202 203//203 -f 92//92 203//203 73//73 -f 73//73 203//203 204//204 -f 73//73 204//204 75//75 -f 75//75 204//204 205//205 -f 75//75 205//205 77//77 -f 77//77 205//205 206//206 -f 77//77 206//206 79//79 -f 79//79 206//206 207//207 -f 79//79 207//207 81//81 -f 81//81 207//207 208//208 -f 81//81 208//208 65//65 -f 65//65 208//208 209//209 -f 65//65 209//209 61//61 -f 61//61 209//209 198//198 -f 68//68 210//210 82//82 -f 82//82 210//210 211//211 -f 82//82 211//211 80//80 -f 80//80 211//211 212//212 -f 80//80 212//212 78//78 -f 78//78 212//212 213//213 -f 78//78 213//213 76//76 -f 76//76 213//213 214//214 -f 76//76 214//214 74//74 -f 74//74 214//214 215//215 -f 74//74 215//215 58//58 -f 58//58 215//215 216//216 -f 58//58 216//216 57//57 -f 57//57 216//216 217//217 -f 57//57 217//217 56//56 -f 56//56 217//217 218//218 -f 56//56 218//218 59//59 -f 59//59 218//218 219//219 -f 59//59 219//219 66//66 -f 66//66 219//219 220//220 -f 66//66 220//220 67//67 -f 67//67 220//220 221//221 -f 67//67 221//221 68//68 -f 68//68 221//221 210//210 -f 35//35 222//222 36//36 -f 36//36 222//222 223//223 -f 36//36 223//223 51//51 -f 51//51 223//223 224//224 -f 51//51 224//224 52//52 -f 52//52 224//224 225//225 -f 52//52 225//225 53//53 -f 53//53 225//225 226//226 -f 53//53 226//226 28//28 -f 28//28 226//226 227//227 -f 28//28 227//227 29//29 -f 29//29 227//227 228//228 -f 29//29 228//228 39//39 -f 39//39 228//228 229//229 -f 39//39 229//229 38//38 -f 38//38 229//229 230//230 -f 38//38 230//230 47//47 -f 47//47 230//230 231//231 -f 47//47 231//231 49//49 -f 49//49 231//231 232//232 -f 49//49 232//232 50//50 -f 50//50 232//232 233//233 -f 50//50 233//233 35//35 -f 35//35 233//233 222//222 -f 44//44 178//178 45//45 -f 45//45 178//178 180//180 -f 45//45 180//180 48//48 -f 48//48 180//180 182//182 -f 48//48 182//182 46//46 -f 46//46 182//182 184//184 -f 46//46 184//184 37//37 -f 37//37 184//184 190//190 -f 37//37 190//190 31//31 -f 31//31 190//190 192//192 -f 31//31 192//192 32//32 -f 32//32 192//192 194//194 -f 32//32 194//194 34//34 -f 34//34 194//194 196//196 -f 34//34 196//196 42//42 -f 42//42 196//196 197//197 -f 42//42 197//197 41//41 -f 41//41 197//197 186//186 -f 41//41 186//186 40//40 -f 40//40 186//186 185//185 -f 40//40 185//185 43//43 -f 43//43 185//185 176//176 -f 43//43 176//176 44//44 -f 44//44 176//176 178//178 -f 86//86 234//234 87//87 -f 87//87 234//234 235//235 -f 87//87 235//235 88//88 -f 88//88 235//235 236//236 -f 88//88 236//236 89//89 -f 89//89 236//236 237//237 -f 89//89 237//237 83//83 -f 83//83 237//237 238//238 -f 83//83 238//238 84//84 -f 84//84 238//238 239//239 -f 84//84 239//239 62//62 -f 62//62 239//239 240//240 -f 62//62 240//240 60//60 -f 60//60 240//240 241//241 -f 60//60 241//241 69//69 -f 69//69 241//241 242//242 -f 69//69 242//242 70//70 -f 70//70 242//242 243//243 -f 70//70 243//243 71//71 -f 71//71 243//243 244//244 -f 71//71 244//244 85//85 -f 85//85 244//244 245//245 -f 85//85 245//245 86//86 -f 86//86 245//245 234//234 -f 241//241 246//246 242//242 -f 242//242 246//246 247//247 -f 242//242 247//247 243//243 -f 243//243 247//247 248//248 -f 243//243 248//248 244//244 -f 244//244 248//248 249//249 -f 244//244 249//249 245//245 -f 245//245 249//249 250//250 -f 245//245 250//250 234//234 -f 234//234 250//250 251//251 -f 234//234 251//251 235//235 -f 235//235 251//251 252//252 -f 235//235 252//252 236//236 -f 236//236 252//252 253//253 -f 236//236 253//253 237//237 -f 237//237 253//253 254//254 -f 237//237 254//254 238//238 -f 238//238 254//254 255//255 -f 238//238 255//255 239//239 -f 239//239 255//255 256//256 -f 239//239 256//256 240//240 -f 240//240 256//256 257//257 -f 240//240 257//257 241//241 -f 241//241 257//257 246//246 -f 251//251 154//154 252//252 -f 252//252 154//154 153//153 -f 252//252 153//153 253//253 -f 253//253 153//153 152//152 -f 253//253 152//152 254//254 -f 254//254 152//152 162//162 -f 254//254 162//162 255//255 -f 255//255 162//162 163//163 -f 255//255 163//163 256//256 -f 256//256 163//163 170//170 -f 256//256 170//170 257//257 -f 257//257 170//170 169//169 -f 257//257 169//169 246//246 -f 246//246 169//169 168//168 -f 246//246 168//168 247//247 -f 247//247 168//168 167//167 -f 247//247 167//167 248//248 -f 248//248 167//167 166//166 -f 248//248 166//166 249//249 -f 249//249 166//166 146//146 -f 249//249 146//146 250//250 -f 250//250 146//146 148//148 -f 250//250 148//148 251//251 -f 251//251 148//148 154//154 -f 229//229 258//258 230//230 -f 230//230 258//258 259//259 -f 230//230 259//259 231//231 -f 231//231 259//259 260//260 -f 231//231 260//260 232//232 -f 232//232 260//260 261//261 -f 232//232 261//261 233//233 -f 233//233 261//261 262//262 -f 233//233 262//262 222//222 -f 222//222 262//262 263//263 -f 222//222 263//263 223//223 -f 223//223 263//263 264//264 -f 223//223 264//264 224//224 -f 224//224 264//264 265//265 -f 224//224 265//265 225//225 -f 225//225 265//265 266//266 -f 225//225 266//266 226//226 -f 226//226 266//266 267//267 -f 226//226 267//267 227//227 -f 227//227 267//267 268//268 -f 227//227 268//268 228//228 -f 228//228 268//268 269//269 -f 228//228 269//269 229//229 -f 229//229 269//269 258//258 -f 263//263 142//142 264//264 -f 264//264 142//142 141//141 -f 264//264 141//141 265//265 -f 265//265 141//141 140//140 -f 265//265 140//140 266//266 -f 266//266 140//140 122//122 -f 266//266 122//122 267//267 -f 267//267 122//122 121//121 -f 267//267 121//121 268//268 -f 268//268 121//121 119//119 -f 268//268 119//119 269//269 -f 269//269 119//119 118//118 -f 269//269 118//118 258//258 -f 258//258 118//118 164//164 -f 258//258 164//164 259//259 -f 259//259 164//164 137//137 -f 259//259 137//137 260//260 -f 260//260 137//137 135//135 -f 260//260 135//135 261//261 -f 261//261 135//135 127//127 -f 261//261 127//127 262//262 -f 262//262 127//127 143//143 -f 262//262 143//143 263//263 -f 263//263 143//143 142//142 -f 217//217 270//270 218//218 -f 218//218 270//270 271//271 -f 218//218 271//271 219//219 -f 219//219 271//271 272//272 -f 219//219 272//272 220//220 -f 220//220 272//272 273//273 -f 220//220 273//273 221//221 -f 221//221 273//273 274//274 -f 221//221 274//274 210//210 -f 210//210 274//274 275//275 -f 210//210 275//275 211//211 -f 211//211 275//275 276//276 -f 211//211 276//276 212//212 -f 212//212 276//276 277//277 -f 212//212 277//277 213//213 -f 213//213 277//277 278//278 -f 213//213 278//278 214//214 -f 214//214 278//278 279//279 -f 214//214 279//279 215//215 -f 215//215 279//279 280//280 -f 215//215 280//280 216//216 -f 216//216 280//280 281//281 -f 216//216 281//281 217//217 -f 217//217 281//281 270//270 -f 275//275 120//120 276//276 -f 276//276 120//120 138//138 -f 276//276 138//138 277//277 -f 277//277 138//138 139//139 -f 277//277 139//139 278//278 -f 278//278 139//139 158//158 -f 278//278 158//158 279//279 -f 279//279 158//158 160//160 -f 279//279 160//160 280//280 -f 280//280 160//160 172//172 -f 280//280 172//172 281//281 -f 281//281 172//172 173//173 -f 281//281 173//173 270//270 -f 270//270 173//173 174//174 -f 270//270 174//174 271//271 -f 271//271 174//174 175//175 -f 271//271 175//175 272//272 -f 272//272 175//175 151//151 -f 272//272 151//151 273//273 -f 273//273 151//151 150//150 -f 273//273 150//150 274//274 -f 274//274 150//150 149//149 -f 274//274 149//149 275//275 -f 275//275 149//149 120//120 -f 202//202 282//282 203//203 -f 203//203 282//282 283//283 -f 203//203 283//283 204//204 -f 204//204 283//283 284//284 -f 204//204 284//284 205//205 -f 205//205 284//284 285//285 -f 205//205 285//285 206//206 -f 206//206 285//285 286//286 -f 206//206 286//286 207//207 -f 207//207 286//286 287//287 -f 207//207 287//287 208//208 -f 208//208 287//287 288//288 -f 208//208 288//288 209//209 -f 209//209 288//288 289//289 -f 209//209 289//289 198//198 -f 198//198 289//289 290//290 -f 198//198 290//290 199//199 -f 199//199 290//290 291//291 -f 199//199 291//291 200//200 -f 200//200 291//291 292//292 -f 200//200 292//292 201//201 -f 201//201 292//292 293//293 -f 201//201 293//293 202//202 -f 202//202 293//293 282//282 -f 290//290 124//124 291//291 -f 291//291 124//124 123//123 -f 291//291 123//123 292//292 -f 292//292 123//123 155//155 -f 292//292 155//155 293//293 -f 293//293 155//155 147//147 -f 293//293 147//147 282//282 -f 282//282 147//147 145//145 -f 282//282 145//145 283//283 -f 283//283 145//145 144//144 -f 283//283 144//144 284//284 -f 284//284 144//144 165//165 -f 284//284 165//165 285//285 -f 285//285 165//165 171//171 -f 285//285 171//171 286//286 -f 286//286 171//171 161//161 -f 286//286 161//161 287//287 -f 287//287 161//161 159//159 -f 287//287 159//159 288//288 -f 288//288 159//159 157//157 -f 288//288 157//157 289//289 -f 289//289 157//157 156//156 -f 289//289 156//156 290//290 -f 290//290 156//156 124//124 -f 27//27 23//23 22//22 -f 110//110 109//109 107//107 -f 22//22 20//20 27//27 -f 27//27 20//20 177//177 -f 27//27 177//177 33//33 -f 33//33 177//177 187//187 -f 33//33 187//187 54//54 -f 9//9 7//7 12//12 -f 12//12 7//7 5//5 -f 20//20 18//18 177//177 -f 177//177 18//18 16//16 -f 177//177 16//16 130//130 -f 130//130 16//16 14//14 -f 130//130 14//14 2//2 -f 2//2 14//14 12//12 -f 2//2 12//12 3//3 -f 3//3 12//12 5//5 -f 112//112 110//110 114//114 -f 114//114 110//110 107//107 -f 114//114 107//107 116//116 -f 116//116 107//107 131//131 -f 131//131 107//107 105//105 -f 131//131 105//105 187//187 -f 96//96 94//94 99//99 -f 99//99 94//94 54//54 -f 99//99 54//54 101//101 -f 101//101 54//54 187//187 -f 101//101 187//187 103//103 -f 103//103 187//187 105//105 -f 113//113 115//115 117//117 -f 21//21 24//24 19//19 -f 19//19 24//24 25//25 -f 19//19 25//25 17//17 -f 17//17 25//25 72//72 -f 8//8 10//10 11//11 -f 106//106 108//108 111//111 -f 95//95 97//97 93//93 -f 93//93 97//97 98//98 -f 11//11 13//13 117//117 -f 6//6 8//8 4//4 -f 4//4 8//8 11//11 -f 4//4 11//11 1//1 -f 1//1 11//11 117//117 -f 111//111 113//113 106//106 -f 106//106 113//113 117//117 -f 106//106 117//117 104//104 -f 104//104 117//117 13//13 -f 104//104 13//13 102//102 -f 102//102 13//13 15//15 -f 102//102 15//15 100//100 -f 100//100 15//15 17//17 -f 100//100 17//17 98//98 -f 98//98 17//17 72//72 -f 98//98 72//72 93//93 -f 294//294 295//295 296//296 -f 294//294 296//296 297//297 -f 297//297 296//296 298//298 -f 297//297 298//298 299//299 -f 299//299 298//298 300//300 -f 299//299 300//300 301//301 -f 300//300 302//302 301//301 -f 301//301 302//302 303//303 -f 303//303 302//302 304//304 -f 304//304 302//302 305//305 -f 304//304 305//305 306//306 -f 306//306 305//305 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 309//309 -f 308//308 309//309 310//310 -f 310//310 309//309 311//311 -f 310//310 311//311 312//312 -f 312//312 311//311 313//313 -f 312//312 313//313 314//314 -f 314//314 313//313 315//315 -f 315//315 316//316 314//314 -f 314//314 316//316 317//317 -f 318//318 317//317 319//319 -f 319//319 317//317 316//316 -f 319//319 316//316 320//320 -f 321//321 322//322 323//323 -f 324//324 325//325 326//326 -f 326//326 325//325 327//327 -f 328//328 329//329 319//319 -f 330//330 324//324 331//331 -f 331//331 324//324 332//332 -f 333//333 320//320 334//334 -f 334//334 320//320 326//326 -f 334//334 326//326 335//335 -f 335//335 326//326 327//327 -f 333//333 336//336 320//320 -f 320//320 336//336 337//337 -f 320//320 337//337 319//319 -f 319//319 337//337 338//338 -f 319//319 338//338 328//328 -f 330//330 331//331 339//339 -f 339//339 331//331 340//340 -f 339//339 340//340 341//341 -f 341//341 340//340 342//342 -f 341//341 342//342 338//338 -f 338//338 342//342 343//343 -f 338//338 343//343 328//328 -f 344//344 345//345 323//323 -f 323//323 345//345 346//346 -f 323//323 346//346 321//321 -f 347//347 348//348 326//326 -f 326//326 348//348 323//323 -f 326//326 323//323 324//324 -f 324//324 323//323 322//322 -f 324//324 322//322 332//332 -f 349//349 323//323 350//350 -f 350//350 323//323 351//351 -f 349//349 352//352 323//323 -f 323//323 352//352 319//319 -f 323//323 319//319 344//344 -f 344//344 319//319 329//329 -f 353//353 354//354 355//355 -f 355//355 354//354 356//356 -f 355//355 356//356 357//357 -f 319//319 358//358 354//354 -f 352//352 359//359 319//319 -f 319//319 359//359 360//360 -f 319//319 360//360 361//361 -f 353//353 362//362 354//354 -f 354//354 362//362 363//363 -f 354//354 363//363 319//319 -f 319//319 363//363 364//364 -f 365//365 366//366 367//367 -f 367//367 366//366 368//368 -f 367//367 368//368 369//369 -f 369//369 368//368 370//370 -f 369//369 370//370 371//371 -f 371//371 370//370 372//372 -f 371//371 372//372 373//373 -f 358//358 319//319 374//374 -f 374//374 319//319 361//361 -f 374//374 361//361 372//372 -f 372//372 361//361 375//375 -f 372//372 375//375 373//373 -f 376//376 377//377 365//365 -f 365//365 377//377 355//355 -f 364//364 378//378 319//319 -f 319//319 378//378 379//379 -f 319//319 379//379 318//318 -f 379//379 380//380 318//318 -f 318//318 380//380 381//381 -f 318//318 381//381 365//365 -f 365//365 381//381 382//382 -f 365//365 382//382 376//376 -f 357//357 383//383 355//355 -f 355//355 383//383 384//384 -f 355//355 384//384 365//365 -f 365//365 384//384 385//385 -f 365//365 385//385 366//366 -f 348//348 386//386 323//323 -f 323//323 386//386 365//365 -f 323//323 365//365 351//351 -f 351//351 365//365 367//367 -f 347//347 387//387 348//348 -f 348//348 387//387 388//388 -f 348//348 388//388 386//386 -f 387//387 389//389 388//388 -f 388//388 389//389 390//390 -f 390//390 389//389 391//391 -f 391//391 389//389 392//392 -f 391//391 392//392 393//393 -f 393//393 392//392 394//394 -f 393//393 394//394 395//395 -f 395//395 394//394 396//396 -f 395//395 396//396 397//397 -f 397//397 396//396 398//398 -f 397//397 398//398 399//399 -f 399//399 398//398 400//400 -f 399//399 400//400 401//401 -f 401//401 400//400 402//402 -f 402//402 403//403 401//401 -f 401//401 403//403 404//404 -f 404//404 403//403 405//405 -f 404//404 405//405 406//406 -f 406//406 405//405 407//407 -f 406//406 407//407 408//408 -f 408//408 407//407 409//409 -f 408//408 409//409 410//410 -f 411//411 412//412 413//413 -f 413//413 412//412 414//414 -f 413//413 414//414 415//415 -f 416//416 417//417 294//294 -f 418//418 419//419 420//420 -f 420//420 419//419 421//421 -f 420//420 421//421 295//295 -f 295//295 421//421 422//422 -f 295//295 422//422 423//423 -f 424//424 425//425 409//409 -f 409//409 425//425 426//426 -f 418//418 420//420 427//427 -f 427//427 420//420 428//428 -f 427//427 428//428 429//429 -f 429//429 428//428 430//430 -f 429//429 430//430 426//426 -f 413//413 294//294 431//431 -f 431//431 294//294 417//417 -f 431//431 417//417 432//432 -f 415//415 433//433 413//413 -f 413//413 433//433 434//434 -f 413//413 434//434 294//294 -f 294//294 434//434 435//435 -f 294//294 435//435 295//295 -f 295//295 435//435 436//436 -f 295//295 436//436 420//420 -f 437//437 438//438 439//439 -f 439//439 438//438 440//440 -f 439//439 440//440 441//441 -f 413//413 442//442 411//411 -f 411//411 442//442 443//443 -f 411//411 443//443 444//444 -f 445//445 446//446 294//294 -f 294//294 446//446 447//447 -f 294//294 447//447 416//416 -f 416//416 447//447 441//441 -f 416//416 441//441 448//448 -f 448//448 441//441 440//440 -f 417//417 449//449 432//432 -f 432//432 449//449 450//450 -f 432//432 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 445//445 294//294 455//455 -f 455//455 294//294 410//410 -f 455//455 410//410 456//456 -f 426//426 430//430 409//409 -f 409//409 430//430 457//457 -f 409//409 457//457 411//411 -f 437//437 439//439 458//458 -f 458//458 439//439 459//459 -f 458//458 459//459 460//460 -f 460//460 461//461 458//458 -f 458//458 461//461 462//462 -f 458//458 462//462 410//410 -f 410//410 462//462 463//463 -f 410//410 463//463 456//456 -f 454//454 464//464 453//453 -f 453//453 464//464 458//458 -f 453//453 458//458 465//465 -f 465//465 458//458 410//410 -f 465//465 410//410 466//466 -f 466//466 410//410 409//409 -f 466//466 409//409 467//467 -f 467//467 409//409 411//411 -f 467//467 411//411 468//468 -f 468//468 411//411 444//444 -f 469//469 470//470 471//471 -f 471//471 470//470 472//472 -f 471//471 472//472 473//473 -f 473//473 472//472 474//474 -f 473//473 474//474 475//475 -f 475//475 474//474 476//476 -f 475//475 476//476 477//477 -f 469//469 478//478 470//470 -f 470//470 478//478 479//479 -f 470//470 479//479 480//480 -f 476//476 481//481 477//477 -f 477//477 481//481 482//482 -f 477//477 482//482 483//483 -f 483//483 482//482 484//484 -f 483//483 484//484 485//485 -f 485//485 484//484 486//486 -f 485//485 486//486 487//487 -f 487//487 486//486 488//488 -f 487//487 488//488 489//489 -f 489//489 488//488 480//480 -f 489//489 480//480 490//490 -f 490//490 480//480 479//479 -f 470//470 423//423 472//472 -f 472//472 423//423 422//422 -f 472//472 422//422 474//474 -f 474//474 422//422 421//421 -f 474//474 421//421 476//476 -f 476//476 421//421 419//419 -f 476//476 419//419 481//481 -f 481//481 419//419 418//418 -f 481//481 418//418 482//482 -f 482//482 418//418 427//427 -f 482//482 427//427 484//484 -f 484//484 427//427 429//429 -f 484//484 429//429 486//486 -f 486//486 429//429 426//426 -f 486//486 426//426 488//488 -f 488//488 426//426 425//425 -f 488//488 425//425 480//480 -f 480//480 425//425 424//424 -f 354//354 491//491 356//356 -f 356//356 491//491 492//492 -f 356//356 492//492 357//357 -f 357//357 492//492 493//493 -f 357//357 493//493 383//383 -f 383//383 493//493 494//494 -f 383//383 494//494 384//384 -f 384//384 494//494 495//495 -f 384//384 495//495 385//385 -f 385//385 495//495 496//496 -f 385//385 496//496 366//366 -f 366//366 496//496 497//497 -f 366//366 497//497 368//368 -f 368//368 497//497 498//498 -f 368//368 498//498 370//370 -f 370//370 498//498 499//499 -f 370//370 499//499 372//372 -f 372//372 499//499 500//500 -f 372//372 500//500 374//374 -f 374//374 500//500 501//501 -f 374//374 501//501 358//358 -f 358//358 501//501 502//502 -f 358//358 502//502 354//354 -f 354//354 502//502 491//491 -f 361//361 503//503 375//375 -f 375//375 503//503 504//504 -f 375//375 504//504 373//373 -f 373//373 504//504 505//505 -f 373//373 505//505 371//371 -f 371//371 505//505 506//506 -f 371//371 506//506 369//369 -f 369//369 506//506 507//507 -f 369//369 507//507 367//367 -f 367//367 507//507 508//508 -f 367//367 508//508 351//351 -f 351//351 508//508 509//509 -f 351//351 509//509 350//350 -f 350//350 509//509 510//510 -f 350//350 510//510 349//349 -f 349//349 510//510 511//511 -f 349//349 511//511 352//352 -f 352//352 511//511 512//512 -f 352//352 512//512 359//359 -f 359//359 512//512 513//513 -f 359//359 513//513 360//360 -f 360//360 513//513 514//514 -f 360//360 514//514 361//361 -f 361//361 514//514 503//503 -f 328//328 515//515 329//329 -f 329//329 515//515 516//516 -f 329//329 516//516 344//344 -f 344//344 516//516 517//517 -f 344//344 517//517 345//345 -f 345//345 517//517 518//518 -f 345//345 518//518 346//346 -f 346//346 518//518 519//519 -f 346//346 519//519 321//321 -f 321//321 519//519 520//520 -f 321//321 520//520 322//322 -f 322//322 520//520 521//521 -f 322//322 521//521 332//332 -f 332//332 521//521 522//522 -f 332//332 522//522 331//331 -f 331//331 522//522 523//523 -f 331//331 523//523 340//340 -f 340//340 523//523 524//524 -f 340//340 524//524 342//342 -f 342//342 524//524 525//525 -f 342//342 525//525 343//343 -f 343//343 525//525 526//526 -f 343//343 526//526 328//328 -f 328//328 526//526 515//515 -f 337//337 471//471 338//338 -f 338//338 471//471 473//473 -f 338//338 473//473 341//341 -f 341//341 473//473 475//475 -f 341//341 475//475 339//339 -f 339//339 475//475 477//477 -f 339//339 477//477 330//330 -f 330//330 477//477 483//483 -f 330//330 483//483 324//324 -f 324//324 483//483 485//485 -f 324//324 485//485 325//325 -f 325//325 485//485 487//487 -f 325//325 487//487 327//327 -f 327//327 487//487 489//489 -f 327//327 489//489 335//335 -f 335//335 489//489 490//490 -f 335//335 490//490 334//334 -f 334//334 490//490 479//479 -f 334//334 479//479 333//333 -f 333//333 479//479 478//478 -f 333//333 478//478 336//336 -f 336//336 478//478 469//469 -f 336//336 469//469 337//337 -f 337//337 469//469 471//471 -f 379//379 527//527 380//380 -f 380//380 527//527 528//528 -f 380//380 528//528 381//381 -f 381//381 528//528 529//529 -f 381//381 529//529 382//382 -f 382//382 529//529 530//530 -f 382//382 530//530 376//376 -f 376//376 530//530 531//531 -f 376//376 531//531 377//377 -f 377//377 531//531 532//532 -f 377//377 532//532 355//355 -f 355//355 532//532 533//533 -f 355//355 533//533 353//353 -f 353//353 533//533 534//534 -f 353//353 534//534 362//362 -f 362//362 534//534 535//535 -f 362//362 535//535 363//363 -f 363//363 535//535 536//536 -f 363//363 536//536 364//364 -f 364//364 536//536 537//537 -f 364//364 537//537 378//378 -f 378//378 537//537 538//538 -f 378//378 538//538 379//379 -f 379//379 538//538 527//527 -f 534//534 539//539 535//535 -f 535//535 539//539 540//540 -f 535//535 540//540 536//536 -f 536//536 540//540 541//541 -f 536//536 541//541 537//537 -f 537//537 541//541 542//542 -f 537//537 542//542 538//538 -f 538//538 542//542 543//543 -f 538//538 543//543 527//527 -f 527//527 543//543 544//544 -f 527//527 544//544 528//528 -f 528//528 544//544 545//545 -f 528//528 545//545 529//529 -f 529//529 545//545 546//546 -f 529//529 546//546 530//530 -f 530//530 546//546 547//547 -f 530//530 547//547 531//531 -f 531//531 547//547 548//548 -f 531//531 548//548 532//532 -f 532//532 548//548 549//549 -f 532//532 549//549 533//533 -f 533//533 549//549 550//550 -f 533//533 550//550 534//534 -f 534//534 550//550 539//539 -f 544//544 447//447 545//545 -f 545//545 447//447 446//446 -f 545//545 446//446 546//546 -f 546//546 446//446 445//445 -f 546//546 445//445 547//547 -f 547//547 445//445 455//455 -f 547//547 455//455 548//548 -f 548//548 455//455 456//456 -f 548//548 456//456 549//549 -f 549//549 456//456 463//463 -f 549//549 463//463 550//550 -f 550//550 463//463 462//462 -f 550//550 462//462 539//539 -f 539//539 462//462 461//461 -f 539//539 461//461 540//540 -f 540//540 461//461 460//460 -f 540//540 460//460 541//541 -f 541//541 460//460 459//459 -f 541//541 459//459 542//542 -f 542//542 459//459 439//439 -f 542//542 439//439 543//543 -f 543//543 439//439 441//441 -f 543//543 441//441 544//544 -f 544//544 441//441 447//447 -f 522//522 551//551 523//523 -f 523//523 551//551 552//552 -f 523//523 552//552 524//524 -f 524//524 552//552 553//553 -f 524//524 553//553 525//525 -f 525//525 553//553 554//554 -f 525//525 554//554 526//526 -f 526//526 554//554 555//555 -f 526//526 555//555 515//515 -f 515//515 555//555 556//556 -f 515//515 556//556 516//516 -f 516//516 556//556 557//557 -f 516//516 557//557 517//517 -f 517//517 557//557 558//558 -f 517//517 558//558 518//518 -f 518//518 558//558 559//559 -f 518//518 559//559 519//519 -f 519//519 559//559 560//560 -f 519//519 560//560 520//520 -f 520//520 560//560 561//561 -f 520//520 561//561 521//521 -f 521//521 561//561 562//562 -f 521//521 562//562 522//522 -f 522//522 562//562 551//551 -f 556//556 435//435 557//557 -f 557//557 435//435 434//434 -f 557//557 434//434 558//558 -f 558//558 434//434 433//433 -f 558//558 433//433 559//559 -f 559//559 433//433 415//415 -f 559//559 415//415 560//560 -f 560//560 415//415 414//414 -f 560//560 414//414 561//561 -f 561//561 414//414 412//412 -f 561//561 412//412 562//562 -f 562//562 412//412 411//411 -f 562//562 411//411 551//551 -f 551//551 411//411 457//457 -f 551//551 457//457 552//552 -f 552//552 457//457 430//430 -f 552//552 430//430 553//553 -f 553//553 430//430 428//428 -f 553//553 428//428 554//554 -f 554//554 428//428 420//420 -f 554//554 420//420 555//555 -f 555//555 420//420 436//436 -f 555//555 436//436 556//556 -f 556//556 436//436 435//435 -f 510//510 563//563 511//511 -f 511//511 563//563 564//564 -f 511//511 564//564 512//512 -f 512//512 564//564 565//565 -f 512//512 565//565 513//513 -f 513//513 565//565 566//566 -f 513//513 566//566 514//514 -f 514//514 566//566 567//567 -f 514//514 567//567 503//503 -f 503//503 567//567 568//568 -f 503//503 568//568 504//504 -f 504//504 568//568 569//569 -f 504//504 569//569 505//505 -f 505//505 569//569 570//570 -f 505//505 570//570 506//506 -f 506//506 570//570 571//571 -f 506//506 571//571 507//507 -f 507//507 571//571 572//572 -f 507//507 572//572 508//508 -f 508//508 572//572 573//573 -f 508//508 573//573 509//509 -f 509//509 573//573 574//574 -f 509//509 574//574 510//510 -f 510//510 574//574 563//563 -f 568//568 413//413 569//569 -f 569//569 413//413 431//431 -f 569//569 431//431 570//570 -f 570//570 431//431 432//432 -f 570//570 432//432 571//571 -f 571//571 432//432 451//451 -f 571//571 451//451 572//572 -f 572//572 451//451 453//453 -f 572//572 453//453 573//573 -f 573//573 453//453 465//465 -f 573//573 465//465 574//574 -f 574//574 465//465 466//466 -f 574//574 466//466 563//563 -f 563//563 466//466 467//467 -f 563//563 467//467 564//564 -f 564//564 467//467 468//468 -f 564//564 468//468 565//565 -f 565//565 468//468 444//444 -f 565//565 444//444 566//566 -f 566//566 444//444 443//443 -f 566//566 443//443 567//567 -f 567//567 443//443 442//442 -f 567//567 442//442 568//568 -f 568//568 442//442 413//413 -f 495//495 575//575 496//496 -f 496//496 575//575 576//576 -f 496//496 576//576 497//497 -f 497//497 576//576 577//577 -f 497//497 577//577 498//498 -f 498//498 577//577 578//578 -f 498//498 578//578 499//499 -f 499//499 578//578 579//579 -f 499//499 579//579 500//500 -f 500//500 579//579 580//580 -f 500//500 580//580 501//501 -f 501//501 580//580 581//581 -f 501//501 581//581 502//502 -f 502//502 581//581 582//582 -f 502//502 582//582 491//491 -f 491//491 582//582 583//583 -f 491//491 583//583 492//492 -f 492//492 583//583 584//584 -f 492//492 584//584 493//493 -f 493//493 584//584 585//585 -f 493//493 585//585 494//494 -f 494//494 585//585 586//586 -f 494//494 586//586 495//495 -f 495//495 586//586 575//575 -f 583//583 417//417 584//584 -f 584//584 417//417 416//416 -f 584//584 416//416 585//585 -f 585//585 416//416 448//448 -f 585//585 448//448 586//586 -f 586//586 448//448 440//440 -f 586//586 440//440 575//575 -f 575//575 440//440 438//438 -f 575//575 438//438 576//576 -f 576//576 438//438 437//437 -f 576//576 437//437 577//577 -f 577//577 437//437 458//458 -f 577//577 458//458 578//578 -f 578//578 458//458 464//464 -f 578//578 464//464 579//579 -f 579//579 464//464 454//454 -f 579//579 454//454 580//580 -f 580//580 454//454 452//452 -f 580//580 452//452 581//581 -f 581//581 452//452 450//450 -f 581//581 450//450 582//582 -f 582//582 450//450 449//449 -f 582//582 449//449 583//583 -f 583//583 449//449 417//417 -f 320//320 316//316 315//315 -f 403//403 402//402 400//400 -f 315//315 313//313 320//320 -f 320//320 313//313 470//470 -f 320//320 470//470 326//326 -f 326//326 470//470 480//480 -f 326//326 480//480 347//347 -f 302//302 300//300 305//305 -f 305//305 300//300 298//298 -f 313//313 311//311 470//470 -f 470//470 311//311 309//309 -f 470//470 309//309 423//423 -f 423//423 309//309 307//307 -f 423//423 307//307 295//295 -f 295//295 307//307 305//305 -f 295//295 305//305 296//296 -f 296//296 305//305 298//298 -f 405//405 403//403 407//407 -f 407//407 403//403 400//400 -f 407//407 400//400 409//409 -f 409//409 400//400 424//424 -f 424//424 400//400 398//398 -f 424//424 398//398 480//480 -f 389//389 387//387 392//392 -f 392//392 387//387 347//347 -f 392//392 347//347 394//394 -f 394//394 347//347 480//480 -f 394//394 480//480 396//396 -f 396//396 480//480 398//398 -f 406//406 408//408 410//410 -f 314//314 317//317 312//312 -f 312//312 317//317 318//318 -f 312//312 318//318 310//310 -f 310//310 318//318 365//365 -f 301//301 303//303 304//304 -f 399//399 401//401 404//404 -f 388//388 390//390 386//386 -f 386//386 390//390 391//391 -f 304//304 306//306 410//410 -f 299//299 301//301 297//297 -f 297//297 301//301 304//304 -f 297//297 304//304 294//294 -f 294//294 304//304 410//410 -f 404//404 406//406 399//399 -f 399//399 406//406 410//410 -f 399//399 410//410 397//397 -f 397//397 410//410 306//306 -f 397//397 306//306 395//395 -f 395//395 306//306 308//308 -f 395//395 308//308 393//393 -f 393//393 308//308 310//310 -f 393//393 310//310 391//391 -f 391//391 310//310 365//365 -f 391//391 365//365 386//386 -# 1204 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_sine_drzaci.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_sine_drzaci.obj deleted file mode 100644 index 53b105e6c..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_sine_drzaci.obj +++ /dev/null @@ -1,1920 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sine_drzaci.obj -# -# Vertices: 468 -# Faces: 968 -# -#### -vn 3.129554 0.192947 3.249543 -v 0.053750 -0.047257 0.035300 -vn 3.410154 -0.191010 -3.133804 -v 0.053750 -0.047257 0.033650 -vn 1.570800 1.570796 1.570796 -v 0.053750 -0.043786 0.035300 -vn 3.577200 -1.174256 -2.837933 -v 0.053750 -0.046754 0.033553 -vn 3.624910 -2.283186 -2.022727 -v 0.053750 -0.046163 0.033145 -vn 3.603828 -2.961517 -0.744448 -v 0.053750 -0.045830 0.032509 -vn 3.603827 -2.961517 0.744446 -v 0.053750 -0.045830 0.031791 -vn 3.385520 -0.174709 3.137177 -v 0.053750 -0.047257 0.015650 -vn 3.128751 0.199859 -3.257890 -v 0.053750 -0.047257 0.014000 -vn 3.554791 -1.190449 2.834983 -v 0.053750 -0.046754 0.015747 -vn 1.570796 1.570797 -1.570796 -v 0.053750 -0.043786 0.014000 -vn 3.624910 -2.283186 2.022727 -v 0.053750 -0.046163 0.016155 -vn 3.624911 -2.283187 -2.022726 -v 0.053750 -0.046163 0.018145 -vn 3.624916 -2.961667 -0.729987 -v 0.053750 -0.045830 0.017509 -vn 3.624917 -2.961666 0.729989 -v 0.053750 -0.045830 0.016791 -vn 3.554791 -1.190449 2.834983 -v 0.053750 -0.046754 0.030747 -vn 3.385521 -0.174709 3.137177 -v 0.053750 -0.047257 0.030650 -vn 3.410154 -0.191010 -3.133804 -v 0.053750 -0.047257 0.018650 -vn 3.624911 -2.283187 2.022726 -v 0.053750 -0.046163 0.031155 -vn 3.577199 -1.174256 -2.837933 -v 0.053750 -0.046754 0.018553 -vn 1.570797 -1.570796 -1.570796 -v 0.053750 -0.070786 0.014000 -vn 1.570792 -1.570797 1.570796 -v 0.053750 -0.070786 0.035300 -vn -1.570798 -1.570797 -1.570796 -v 0.050750 -0.070786 0.014000 -vn -1.570797 -1.570796 1.570796 -v 0.050750 -0.070786 0.035300 -vn -2.807272 -1.249876 -3.560470 -v 0.060577 -0.056473 0.014000 -vn 2.751700 1.466489 -2.896770 -v 0.063162 -0.054935 0.014000 -vn 3.025100 0.755783 -2.896766 -v 0.063601 -0.056074 0.014000 -vn -3.072940 -0.000000 -3.560472 -v 0.060750 -0.057286 0.014000 -vn 2.314187 2.089732 -2.896766 -v 0.062461 -0.053935 0.014000 -vn -2.056200 -2.283638 -3.560473 -v 0.060088 -0.055800 0.014000 -vn 1.738651 2.588346 -2.896767 -v 0.061538 -0.053136 0.014000 -vn -0.949589 -2.922540 -3.560473 -v 0.059368 -0.055384 0.014000 -vn 1.059427 2.932586 -2.896770 -v 0.060449 -0.052584 0.014000 -vn 0.655701 3.072089 -3.113639 -v 0.059258 -0.052312 0.014000 -vn 0.321212 -3.056107 -3.560470 -v 0.058541 -0.055297 0.014000 -vn 0.896655 2.996298 -3.330526 -v 0.058703 -0.052202 0.014000 -vn 3.118083 0.000000 -2.896768 -v 0.063750 -0.057286 0.014000 -vn 3.025100 -0.755785 -2.896765 -v 0.063601 -0.058498 0.014000 -vn -2.807272 1.249876 -3.560470 -v 0.060577 -0.058100 0.014000 -vn 2.751700 -1.466491 -2.896771 -v 0.063162 -0.059638 0.014000 -vn -2.056195 2.283641 -3.560477 -v 0.060088 -0.058772 0.014000 -vn 1.536468 -2.661247 -3.560472 -v 0.057750 -0.055554 0.014000 -vn 1.632617 2.675507 -3.277978 -v 0.055904 -0.050806 0.014000 -vn 1.315217 2.849177 -3.236052 -v 0.058179 -0.051989 0.014000 -vn 2.486059 -1.806230 -3.560475 -v 0.057132 -0.056111 0.014000 -vn -1.570795 1.570796 -1.570796 -v 0.050750 -0.043786 0.014000 -vn 3.005790 -0.638898 -3.560471 -v 0.056794 -0.056870 0.014000 -vn 3.129122 -0.196700 -3.253906 -v 0.053750 -0.067315 0.014000 -vn 2.314187 -2.089732 -2.896766 -v 0.062461 -0.060637 0.014000 -vn 1.738655 -2.588344 -2.896770 -v 0.061538 -0.061437 0.014000 -vn -0.949591 2.922543 -3.560464 -v 0.059368 -0.059188 0.014000 -vn 2.995197 0.852878 -3.392057 -v 0.053898 -0.048335 0.014000 -vn 2.659925 1.616535 -3.407610 -v 0.054331 -0.049333 0.014000 -vn 2.127169 2.272069 -3.414368 -v 0.055016 -0.050177 0.014000 -vn 3.005790 0.638899 -3.560471 -v 0.056794 -0.057702 0.014000 -vn 2.486063 1.806227 -3.560472 -v 0.057132 -0.058462 0.014000 -vn 1.536471 2.661243 -3.560472 -v 0.057750 -0.059018 0.014000 -vn 2.127172 -2.272069 -3.414358 -v 0.055016 -0.064395 0.014000 -vn 2.655858 -1.625757 -3.397931 -v 0.054331 -0.065240 0.014000 -vn 1.059426 -2.932585 -2.896765 -v 0.060449 -0.061989 0.014000 -vn 0.655707 -3.072088 -3.113648 -v 0.059258 -0.062260 0.014000 -vn 0.321204 3.056106 -3.560475 -v 0.058541 -0.059275 0.014000 -vn 2.999408 -0.844671 -3.372196 -v 0.053898 -0.066238 0.014000 -vn 0.896648 -2.996303 -3.330507 -v 0.058703 -0.062371 0.014000 -vn 1.315199 -2.849184 -3.236064 -v 0.058179 -0.062583 0.014000 -vn 1.632625 -2.675502 -3.277984 -v 0.055904 -0.063767 0.014000 -vn -1.570801 1.570797 1.570796 -v 0.050750 -0.043786 0.035300 -vn 2.486059 -1.806230 3.560475 -v 0.057132 -0.056111 0.035300 -vn 1.536467 -2.661247 3.560472 -v 0.057750 -0.055554 0.035300 -vn -2.807272 1.249876 3.560470 -v 0.060577 -0.058100 0.035300 -vn -2.056194 2.283641 3.560477 -v 0.060088 -0.058772 0.035300 -vn 2.314187 -2.089732 2.896766 -v 0.062461 -0.060637 0.035300 -vn 2.127169 2.272069 3.414368 -v 0.055016 -0.050177 0.035300 -vn 2.655819 1.625732 3.398080 -v 0.054331 -0.049333 0.035300 -vn 0.655701 3.072089 3.113639 -v 0.059258 -0.052312 0.035300 -vn 0.321211 -3.056107 3.560470 -v 0.058541 -0.055297 0.035300 -vn -0.949589 -2.922540 3.560473 -v 0.059368 -0.055384 0.035300 -vn -3.072941 0.000000 3.560472 -v 0.060750 -0.057286 0.035300 -vn 3.025100 0.755783 2.896766 -v 0.063601 -0.056074 0.035300 -vn -2.807272 -1.249876 3.560470 -v 0.060577 -0.056473 0.035300 -vn 2.751700 1.466489 2.896770 -v 0.063162 -0.054935 0.035300 -vn -2.056200 -2.283638 3.560473 -v 0.060088 -0.055800 0.035300 -vn 1.738655 -2.588344 2.896770 -v 0.061538 -0.061437 0.035300 -vn -0.949591 2.922543 3.560464 -v 0.059368 -0.059188 0.035300 -vn 1.059426 -2.932585 2.896765 -v 0.060449 -0.061989 0.035300 -vn 2.998866 0.848128 3.368692 -v 0.053898 -0.048335 0.035300 -vn 2.314187 2.089732 2.896766 -v 0.062461 -0.053935 0.035300 -vn 1.738651 2.588346 2.896767 -v 0.061538 -0.053136 0.035300 -vn 1.059427 2.932586 2.896770 -v 0.060449 -0.052584 0.035300 -vn 1.536472 2.661243 3.560472 -v 0.057750 -0.059018 0.035300 -vn 2.486063 1.806226 3.560472 -v 0.057132 -0.058462 0.035300 -vn 3.005790 0.638898 3.560471 -v 0.056794 -0.057702 0.035300 -vn 3.005790 -0.638899 3.560471 -v 0.056794 -0.056870 0.035300 -vn 0.896655 2.996298 3.330526 -v 0.058703 -0.052202 0.035300 -vn 1.315217 2.849177 3.236052 -v 0.058179 -0.051989 0.035300 -vn 1.632617 2.675507 3.277979 -v 0.055904 -0.050806 0.035300 -vn 2.751700 -1.466491 2.896771 -v 0.063162 -0.059638 0.035300 -vn 3.025100 -0.755785 2.896765 -v 0.063601 -0.058498 0.035300 -vn 3.118083 -0.000000 2.896768 -v 0.063750 -0.057286 0.035300 -vn 0.655706 -3.072088 3.113648 -v 0.059258 -0.062260 0.035300 -vn 0.321205 3.056106 3.560475 -v 0.058541 -0.059275 0.035300 -vn 0.896648 -2.996303 3.330507 -v 0.058703 -0.062371 0.035300 -vn 3.127007 -0.213572 3.277979 -v 0.053750 -0.067315 0.035300 -vn 1.632624 -2.675502 3.277984 -v 0.055904 -0.063767 0.035300 -vn 1.315199 -2.849184 3.236064 -v 0.058179 -0.062583 0.035300 -vn 2.996641 -0.842767 3.400139 -v 0.053898 -0.066238 0.035300 -vn 2.659868 -1.616595 3.407470 -v 0.054331 -0.065240 0.035300 -vn 2.127172 -2.272070 3.414358 -v 0.055016 -0.064395 0.035300 -vn 3.624918 1.732769 2.510350 -v 0.053750 -0.068138 0.015916 -vn 3.433952 0.667081 3.035656 -v 0.053750 -0.067467 0.015661 -vn 3.314529 -0.089692 3.166995 -v 0.053750 -0.067315 0.015650 -vn 3.624911 2.700911 1.417549 -v 0.053750 -0.068614 0.016453 -vn 3.624919 3.050302 -0.000000 -v 0.053750 -0.068786 0.017150 -vn 3.624911 2.700910 -1.417549 -v 0.053750 -0.068614 0.017847 -vn 3.624918 1.732769 -2.510351 -v 0.053750 -0.068138 0.018384 -vn 3.624908 2.700912 1.417548 -v 0.053750 -0.068614 0.031453 -vn 3.624920 3.050302 -0.000000 -v 0.053750 -0.068786 0.032150 -vn 3.624908 2.700912 -1.417548 -v 0.053750 -0.068614 0.032847 -vn 3.624922 1.732767 -2.510350 -v 0.053750 -0.068138 0.033384 -vn 3.433949 0.667077 -3.035657 -v 0.053750 -0.067467 0.033639 -vn 3.295228 -0.143070 -3.235244 -v 0.053750 -0.067315 0.033650 -vn 3.299416 -0.079545 -3.168109 -v 0.053750 -0.067315 0.018650 -vn 3.314527 -0.089692 3.166995 -v 0.053750 -0.067315 0.030650 -vn 3.433949 0.667081 -3.035656 -v 0.053750 -0.067467 0.018639 -vn 3.433952 0.667081 3.035656 -v 0.053750 -0.067467 0.030661 -vn 3.624919 1.732771 2.510348 -v 0.053750 -0.068138 0.030916 -vn -3.386706 -3.118655 0.000000 -v 0.050750 -0.045786 0.032150 -vn -3.504090 -2.950213 -0.919322 -v 0.050750 -0.045830 0.032509 -vn -3.602784 1.724691 -2.519545 -v 0.050750 -0.048138 0.033384 -vn -3.609923 -1.091237 2.850845 -v 0.050750 -0.066754 0.030747 -vn -3.602102 -2.277150 2.034307 -v 0.050750 -0.066163 0.031155 -vn -3.504089 -2.950214 0.919320 -v 0.050750 -0.045830 0.031791 -vn -3.609928 -1.091237 2.850845 -v 0.050750 -0.066754 0.015747 -vn -3.622123 0.367961 -3.028085 -v 0.050750 -0.047467 0.018639 -vn -3.602781 1.724693 -2.519547 -v 0.050750 -0.048138 0.018384 -vn -3.624912 2.700911 -1.417549 -v 0.050750 -0.068614 0.017847 -vn -3.624919 3.050302 0.000000 -v 0.050750 -0.068786 0.017150 -vn -3.624911 2.700910 1.417549 -v 0.050750 -0.068614 0.016453 -vn -3.624918 1.732769 2.510351 -v 0.050750 -0.068138 0.015916 -vn -3.610276 0.377220 3.029153 -v 0.050750 -0.067467 0.015661 -vn -3.624922 1.732767 -2.510349 -v 0.050750 -0.068138 0.033384 -vn -3.624908 2.700912 -1.417548 -v 0.050750 -0.068614 0.032847 -vn -3.624920 3.050302 0.000000 -v 0.050750 -0.068786 0.032150 -vn -3.602101 -2.277149 2.034308 -v 0.050750 -0.066163 0.016155 -vn -3.585958 -2.967662 0.731190 -v 0.050750 -0.065830 0.016791 -vn -3.585966 -2.967663 -0.731188 -v 0.050750 -0.065830 0.017509 -vn -3.586127 0.366150 3.034321 -v 0.050750 -0.047467 0.015661 -vn -3.608149 -1.093402 2.850558 -v 0.050750 -0.046754 0.015747 -vn -3.624910 -2.283186 2.022727 -v 0.050750 -0.046163 0.016155 -vn -3.584171 -1.083902 -2.857995 -v 0.050750 -0.066754 0.033553 -vn -3.604499 0.381349 -3.029587 -v 0.050750 -0.067467 0.033639 -vn -3.587563 2.705849 -1.420895 -v 0.050750 -0.048614 0.017847 -vn -3.586073 3.056385 0.000000 -v 0.050750 -0.048786 0.017150 -vn -3.587561 2.705849 1.420895 -v 0.050750 -0.048614 0.016453 -vn -3.585253 1.737627 2.514503 -v 0.050750 -0.048138 0.015916 -vn -3.624910 -2.283186 -2.022727 -v 0.050750 -0.046163 0.033145 -vn -3.624918 -1.081654 -2.852082 -v 0.050750 -0.046754 0.033553 -vn -3.622123 0.367958 -3.028086 -v 0.050750 -0.047467 0.033639 -vn -3.484427 -2.956335 0.907381 -v 0.050750 -0.065830 0.031791 -vn -3.383296 -3.118685 -0.000031 -v 0.050750 -0.065786 0.032150 -vn -3.484477 -2.956338 -0.907351 -v 0.050750 -0.065830 0.032509 -vn -3.584918 -2.288084 -2.026611 -v 0.050750 -0.066163 0.033145 -vn -3.587561 2.705850 -1.420895 -v 0.050750 -0.048614 0.032847 -vn -3.586075 3.056386 0.000000 -v 0.050750 -0.048786 0.032150 -vn -3.610277 0.377220 3.029153 -v 0.050750 -0.067467 0.030661 -vn -3.587552 2.705850 1.420894 -v 0.050750 -0.048614 0.031453 -vn -3.584919 -2.288085 -2.026609 -v 0.050750 -0.066163 0.018145 -vn -3.584172 -1.083902 -2.857995 -v 0.050750 -0.066754 0.018553 -vn -3.604501 0.381352 -3.029586 -v 0.050750 -0.067467 0.018639 -vn -3.624917 -2.961666 0.729989 -v 0.050750 -0.045830 0.016791 -vn -3.624916 -2.961666 -0.729987 -v 0.050750 -0.045830 0.017509 -vn -3.624911 -2.283187 -2.022726 -v 0.050750 -0.046163 0.018145 -vn -3.624909 2.700912 1.417547 -v 0.050750 -0.068614 0.031453 -vn -3.624920 1.732771 2.510348 -v 0.050750 -0.068138 0.030916 -vn -3.624917 1.732769 -2.510350 -v 0.050750 -0.068138 0.018384 -vn -3.585255 1.737629 2.514501 -v 0.050750 -0.048138 0.030916 -vn -3.586126 0.366150 3.034321 -v 0.050750 -0.047467 0.030661 -vn -3.624918 -1.081654 -2.852082 -v 0.050750 -0.046754 0.018553 -vn -3.608149 -1.093402 2.850558 -v 0.050750 -0.046754 0.030747 -vn -3.624911 -2.283187 2.022726 -v 0.050750 -0.046163 0.031155 -vn 3.252550 2.521560 2.616735 -v 0.053848 -0.048138 0.015916 -vn 3.339706 1.651780 3.028227 -v 0.053790 -0.047820 0.015748 -vn 3.190564 3.382618 2.176937 -v 0.053898 -0.048335 0.016077 -vn 3.165308 3.987175 1.497519 -v 0.053987 -0.048614 0.016453 -vn 3.090749 4.363961 0.733116 -v 0.054036 -0.048742 0.016790 -vn 3.044657 4.539260 0.001895 -v 0.054054 -0.048786 0.017150 -vn 3.132172 4.271480 -0.713619 -v 0.054036 -0.048742 0.017510 -vn 3.198464 3.908523 -1.439638 -v 0.053987 -0.048614 0.017847 -vn 3.232851 3.261468 -2.116045 -v 0.053898 -0.048335 0.018223 -vn 3.250797 2.529192 -2.612780 -v 0.053848 -0.048138 0.018384 -vn 3.363196 0.723650 -3.150569 -v 0.053756 -0.047467 0.018639 -vn 3.382183 1.635257 -2.971879 -v 0.053790 -0.047820 0.018552 -vn 3.318056 0.735534 3.208129 -v 0.053756 -0.047467 0.015661 -vn 3.333437 -0.800813 -3.144818 -v 0.053760 -0.067029 0.018628 -vn 3.135889 -3.444991 -1.946217 -v 0.053919 -0.066164 0.018145 -vn 3.160005 -3.014909 -2.303387 -v 0.053898 -0.066238 0.018223 -vn 3.268080 -2.463604 -2.637985 -v 0.053839 -0.066478 0.018414 -vn 3.296479 -1.657616 -2.960244 -v 0.053790 -0.066754 0.018553 -vn 3.176198 -3.909756 -1.392984 -v 0.053987 -0.065959 0.017849 -vn 3.129883 -4.272017 -0.711497 -v 0.054036 -0.065830 0.017509 -vn 3.046798 -4.539350 0.002560 -v 0.054054 -0.065786 0.017149 -vn 3.087877 -4.364183 0.732819 -v 0.054036 -0.065830 0.016791 -vn 3.132766 -4.017287 1.434642 -v 0.053987 -0.065959 0.016452 -vn 3.235531 -3.353502 2.048429 -v 0.053919 -0.066163 0.016155 -vn 3.342092 -1.689821 3.001189 -v 0.053790 -0.066754 0.015747 -vn 3.335470 -2.508443 2.621767 -v 0.053838 -0.066479 0.015886 -vn 3.343986 -0.830076 3.195133 -v 0.053760 -0.067030 0.015672 -vn 3.326415 -0.789005 -3.305581 -v 0.053760 -0.067029 0.033628 -vn 3.094344 -3.556059 -2.057524 -v 0.053919 -0.066164 0.033145 -vn 3.116147 -3.149238 -2.383558 -v 0.053898 -0.066238 0.033223 -vn 3.268678 -2.460035 -2.648073 -v 0.053839 -0.066478 0.033414 -vn 3.294809 -1.656208 -3.019083 -v 0.053790 -0.066754 0.033553 -vn 3.133520 -4.013897 -1.456144 -v 0.053987 -0.065959 0.032849 -vn 3.088515 -4.364453 -0.732050 -v 0.054036 -0.065830 0.032509 -vn 3.042013 -4.543267 -0.000412 -v 0.054054 -0.065786 0.032149 -vn 3.149657 -4.222934 0.705619 -v 0.054036 -0.065830 0.031791 -vn 3.176114 -3.910077 1.392551 -v 0.053987 -0.065959 0.031452 -vn 3.237230 -3.348333 2.046263 -v 0.053919 -0.066163 0.031155 -vn 3.343761 -1.691241 2.942229 -v 0.053790 -0.066754 0.030747 -vn 3.334194 -2.514686 2.613666 -v 0.053838 -0.066479 0.030886 -vn 3.349129 -0.789217 3.145588 -v 0.053760 -0.067030 0.030672 -vn 3.361816 0.736833 -3.168397 -v 0.053756 -0.047467 0.033639 -vn 3.252140 2.523915 2.609984 -v 0.053848 -0.048138 0.030916 -vn 3.340605 1.660567 2.968801 -v 0.053790 -0.047820 0.030748 -vn 3.232727 3.261953 2.114565 -v 0.053898 -0.048335 0.031077 -vn 3.207839 3.883838 1.430705 -v 0.053987 -0.048614 0.031453 -vn 3.150294 4.228044 0.706664 -v 0.054036 -0.048742 0.031790 -vn 3.034555 4.559025 0.002174 -v 0.054054 -0.048786 0.032150 -vn 3.090737 4.364085 -0.732779 -v 0.054036 -0.048742 0.032510 -vn 3.164540 3.991264 -1.472022 -v 0.053987 -0.048614 0.032847 -vn 3.232720 3.261956 -2.114564 -v 0.053898 -0.048335 0.033223 -vn 3.252509 2.521634 -2.616683 -v 0.053848 -0.048138 0.033384 -vn 3.380073 1.642426 -3.005616 -v 0.053790 -0.047820 0.033552 -vn 3.323045 0.692708 3.158785 -v 0.053756 -0.047467 0.030661 -vn 3.129554 0.192946 3.249542 -v 0.053750 0.067743 0.035300 -vn 3.410154 -0.191010 -3.133804 -v 0.053750 0.067743 0.033650 -vn 1.570801 1.570796 1.570796 -v 0.053750 0.071214 0.035300 -vn 3.577202 -1.174260 -2.837930 -v 0.053750 0.068246 0.033553 -vn 3.624902 -2.283186 -2.022731 -v 0.053750 0.068837 0.033145 -vn 3.603832 -2.961514 -0.744454 -v 0.053750 0.069170 0.032509 -vn 3.603831 -2.961514 0.744453 -v 0.053750 0.069170 0.031791 -vn 3.385520 -0.174709 3.137177 -v 0.053750 0.067743 0.015650 -vn 3.128751 0.199859 -3.257890 -v 0.053750 0.067743 0.014000 -vn 3.554795 -1.190453 2.834980 -v 0.053750 0.068246 0.015747 -vn 1.570798 1.570797 -1.570796 -v 0.053750 0.071214 0.014000 -vn 3.624902 -2.283187 2.022731 -v 0.053750 0.068837 0.016155 -vn 3.624902 -2.283187 -2.022729 -v 0.053750 0.068837 0.018145 -vn 3.624920 -2.961663 -0.729994 -v 0.053750 0.069170 0.017509 -vn 3.624922 -2.961662 0.729995 -v 0.053750 0.069170 0.016791 -vn 3.554794 -1.190453 2.834980 -v 0.053750 0.068246 0.030747 -vn 3.385521 -0.174709 3.137177 -v 0.053750 0.067743 0.030650 -vn 3.410154 -0.191010 -3.133804 -v 0.053750 0.067743 0.018650 -vn 3.624904 -2.283188 2.022729 -v 0.053750 0.068837 0.031155 -vn 3.577202 -1.174260 -2.837930 -v 0.053750 0.068246 0.018553 -vn 1.570796 -1.570796 -1.570796 -v 0.053750 0.044214 0.014000 -vn 1.570795 -1.570797 1.570796 -v 0.053750 0.044214 0.035300 -vn -1.570793 -1.570797 -1.570801 -v 0.050750 0.044214 0.014000 -vn -1.570799 -1.570796 1.570801 -v 0.050750 0.044214 0.035300 -vn -2.807272 -1.249876 -3.560470 -v 0.060577 0.058527 0.014000 -vn 2.751700 1.466491 -2.896771 -v 0.063162 0.060065 0.014000 -vn 3.025100 0.755785 -2.896765 -v 0.063601 0.058926 0.014000 -vn -3.072940 -0.000000 -3.560472 -v 0.060750 0.057714 0.014000 -vn 2.314187 2.089732 -2.896766 -v 0.062461 0.061065 0.014000 -vn -2.056194 -2.283641 -3.560477 -v 0.060088 0.059200 0.014000 -vn 1.738655 2.588344 -2.896770 -v 0.061538 0.061864 0.014000 -vn -0.949591 -2.922543 -3.560464 -v 0.059368 0.059616 0.014000 -vn 1.059426 2.932585 -2.896765 -v 0.060449 0.062416 0.014000 -vn 0.655706 3.072088 -3.113648 -v 0.059258 0.062688 0.014000 -vn 0.321205 -3.056106 -3.560475 -v 0.058541 0.059703 0.014000 -vn 0.896665 2.996296 -3.330519 -v 0.058703 0.062798 0.014000 -vn 3.118083 0.000000 -2.896768 -v 0.063750 0.057714 0.014000 -vn 3.025100 -0.755785 -2.896765 -v 0.063601 0.056502 0.014000 -vn -2.807272 1.249876 -3.560470 -v 0.060577 0.056900 0.014000 -vn 2.751701 -1.466488 -2.896773 -v 0.063162 0.055362 0.014000 -vn -2.056200 2.283638 -3.560473 -v 0.060088 0.056228 0.014000 -vn 1.536468 -2.661247 -3.560472 -v 0.057750 0.059446 0.014000 -vn 1.632617 2.675507 -3.277978 -v 0.055904 0.064194 0.014000 -vn 1.315217 2.849177 -3.236052 -v 0.058179 0.063011 0.014000 -vn 2.486059 -1.806230 -3.560475 -v 0.057132 0.058889 0.014000 -vn -1.570797 1.570796 -1.570791 -v 0.050750 0.071214 0.014000 -vn 3.005790 -0.638898 -3.560471 -v 0.056794 0.058130 0.014000 -vn 3.129122 -0.196700 -3.253906 -v 0.053750 0.047685 0.014000 -vn 2.314188 -2.089730 -2.896764 -v 0.062461 0.054363 0.014000 -vn 1.738651 -2.588346 -2.896767 -v 0.061538 0.053563 0.014000 -vn -0.949589 2.922540 -3.560473 -v 0.059368 0.055812 0.014000 -vn 2.995197 0.852878 -3.392057 -v 0.053898 0.066665 0.014000 -vn 2.659925 1.616535 -3.407609 -v 0.054331 0.065667 0.014000 -vn 2.127169 2.272069 -3.414368 -v 0.055016 0.064823 0.014000 -vn 3.005790 0.638899 -3.560471 -v 0.056794 0.057298 0.014000 -vn 2.486059 1.806230 -3.560475 -v 0.057132 0.056538 0.014000 -vn 1.536467 2.661247 -3.560471 -v 0.057750 0.055982 0.014000 -vn 2.127171 -2.272069 -3.414363 -v 0.055016 0.050605 0.014000 -vn 2.655856 -1.625756 -3.397929 -v 0.054331 0.049760 0.014000 -vn 1.059427 -2.932586 -2.896770 -v 0.060449 0.053011 0.014000 -vn 0.655701 -3.072089 -3.113639 -v 0.059258 0.052740 0.014000 -vn 0.321211 3.056107 -3.560470 -v 0.058541 0.055725 0.014000 -vn 2.999408 -0.844673 -3.372196 -v 0.053898 0.048762 0.014000 -vn 0.896647 -2.996302 -3.330520 -v 0.058703 0.052629 0.014000 -vn 1.315208 -2.849181 -3.236058 -v 0.058179 0.052417 0.014000 -vn 1.632621 -2.675505 -3.277981 -v 0.055904 0.051233 0.014000 -vn -1.570804 1.570797 1.570794 -v 0.050750 0.071214 0.035300 -vn 2.486059 -1.806230 3.560475 -v 0.057132 0.058889 0.035300 -vn 1.536467 -2.661247 3.560472 -v 0.057750 0.059446 0.035300 -vn -2.807272 1.249876 3.560470 -v 0.060577 0.056900 0.035300 -vn -2.056200 2.283638 3.560473 -v 0.060088 0.056228 0.035300 -vn 2.314188 -2.089730 2.896764 -v 0.062461 0.054363 0.035300 -vn 2.127169 2.272069 3.414368 -v 0.055016 0.064823 0.035300 -vn 2.655824 1.625735 3.398078 -v 0.054331 0.065667 0.035300 -vn 0.655707 3.072088 3.113648 -v 0.059258 0.062688 0.035300 -vn 0.321204 -3.056106 3.560475 -v 0.058541 0.059703 0.035300 -vn -0.949591 -2.922543 3.560464 -v 0.059368 0.059616 0.035300 -vn -3.072941 0.000000 3.560472 -v 0.060750 0.057714 0.035300 -vn 3.025100 0.755785 2.896765 -v 0.063601 0.058926 0.035300 -vn -2.807272 -1.249876 3.560470 -v 0.060577 0.058527 0.035300 -vn 2.751700 1.466491 2.896771 -v 0.063162 0.060065 0.035300 -vn -2.056195 -2.283641 3.560477 -v 0.060088 0.059200 0.035300 -vn 1.738651 -2.588346 2.896767 -v 0.061538 0.053563 0.035300 -vn -0.949589 2.922540 3.560473 -v 0.059368 0.055812 0.035300 -vn 1.059427 -2.932586 2.896770 -v 0.060449 0.053011 0.035300 -vn 2.998867 0.848127 3.368691 -v 0.053898 0.066665 0.035300 -vn 2.314187 2.089732 2.896766 -v 0.062461 0.061065 0.035300 -vn 1.738655 2.588344 2.896770 -v 0.061538 0.061864 0.035300 -vn 1.059426 2.932585 2.896765 -v 0.060449 0.062416 0.035300 -vn 1.536468 2.661247 3.560471 -v 0.057750 0.055982 0.035300 -vn 2.486059 1.806230 3.560475 -v 0.057132 0.056538 0.035300 -vn 3.005790 0.638898 3.560471 -v 0.056794 0.057298 0.035300 -vn 3.005790 -0.638899 3.560471 -v 0.056794 0.058130 0.035300 -vn 0.896665 2.996296 3.330519 -v 0.058703 0.062798 0.035300 -vn 1.315217 2.849177 3.236052 -v 0.058179 0.063011 0.035300 -vn 1.632617 2.675507 3.277979 -v 0.055904 0.064194 0.035300 -vn 2.751701 -1.466489 2.896773 -v 0.063162 0.055362 0.035300 -vn 3.025100 -0.755785 2.896765 -v 0.063601 0.056502 0.035300 -vn 3.118083 -0.000000 2.896768 -v 0.063750 0.057714 0.035300 -vn 0.655701 -3.072089 3.113639 -v 0.059258 0.052740 0.035300 -vn 0.321212 3.056107 3.560470 -v 0.058541 0.055725 0.035300 -vn 0.896647 -2.996302 3.330520 -v 0.058703 0.052629 0.035300 -vn 3.127006 -0.213572 3.277979 -v 0.053750 0.047685 0.035300 -vn 1.632621 -2.675504 3.277982 -v 0.055904 0.051233 0.035300 -vn 1.315208 -2.849181 3.236058 -v 0.058179 0.052417 0.035300 -vn 2.996640 -0.842769 3.400140 -v 0.053898 0.048762 0.035300 -vn 2.659883 -1.616600 3.407469 -v 0.054331 0.049760 0.035300 -vn 2.127171 -2.272069 3.414363 -v 0.055016 0.050605 0.035300 -vn 3.624916 1.732772 2.510349 -v 0.053750 0.046862 0.015916 -vn 3.433955 0.667081 3.035655 -v 0.053750 0.047533 0.015661 -vn 3.314527 -0.089695 3.166995 -v 0.053750 0.047685 0.015650 -vn 3.624911 2.700911 1.417549 -v 0.053750 0.046386 0.016453 -vn 3.624919 3.050302 -0.000000 -v 0.053750 0.046214 0.017150 -vn 3.624911 2.700910 -1.417549 -v 0.053750 0.046386 0.017847 -vn 3.624916 1.732772 -2.510349 -v 0.053750 0.046862 0.018384 -vn 3.624909 2.700912 1.417548 -v 0.053750 0.046386 0.031453 -vn 3.624920 3.050302 -0.000000 -v 0.053750 0.046214 0.032150 -vn 3.624909 2.700912 -1.417548 -v 0.053750 0.046386 0.032847 -vn 3.624920 1.732770 -2.510349 -v 0.053750 0.046862 0.033384 -vn 3.433953 0.667077 -3.035656 -v 0.053750 0.047533 0.033639 -vn 3.295226 -0.143073 -3.235244 -v 0.053750 0.047685 0.033650 -vn 3.299414 -0.079548 -3.168109 -v 0.053750 0.047685 0.018650 -vn 3.314525 -0.089695 3.166995 -v 0.053750 0.047685 0.030650 -vn 3.433953 0.667081 -3.035655 -v 0.053750 0.047533 0.018639 -vn 3.433955 0.667081 3.035655 -v 0.053750 0.047533 0.030661 -vn 3.624918 1.732773 2.510347 -v 0.053750 0.046862 0.030916 -vn -3.386706 -3.118655 0.000000 -v 0.050750 0.069214 0.032150 -vn -3.504095 -2.950210 -0.919328 -v 0.050750 0.069170 0.032509 -vn -3.602781 1.724688 -2.519550 -v 0.050750 0.066862 0.033384 -vn -3.609923 -1.091236 2.850845 -v 0.050750 0.048246 0.030747 -vn -3.602102 -2.277150 2.034307 -v 0.050750 0.048837 0.031155 -vn -3.504093 -2.950211 0.919327 -v 0.050750 0.069170 0.031791 -vn -3.609928 -1.091236 2.850845 -v 0.050750 0.048246 0.015747 -vn -3.622123 0.367961 -3.028085 -v 0.050750 0.067533 0.018639 -vn -3.602777 1.724690 -2.519552 -v 0.050750 0.066862 0.018384 -vn -3.624914 2.700911 -1.417549 -v 0.050750 0.046386 0.017847 -vn -3.624919 3.050302 0.000000 -v 0.050750 0.046214 0.017150 -vn -3.624911 2.700910 1.417549 -v 0.050750 0.046386 0.016453 -vn -3.624916 1.732772 2.510349 -v 0.050750 0.046862 0.015916 -vn -3.610277 0.377224 3.029154 -v 0.050750 0.047533 0.015661 -vn -3.624920 1.732770 -2.510348 -v 0.050750 0.046862 0.033384 -vn -3.624909 2.700912 -1.417548 -v 0.050750 0.046386 0.032847 -vn -3.624921 3.050302 0.000000 -v 0.050750 0.046214 0.032150 -vn -3.602101 -2.277149 2.034308 -v 0.050750 0.048837 0.016155 -vn -3.585958 -2.967662 0.731190 -v 0.050750 0.049170 0.016791 -vn -3.585967 -2.967663 -0.731189 -v 0.050750 0.049170 0.017509 -vn -3.586126 0.366150 3.034321 -v 0.050750 0.067533 0.015661 -vn -3.608152 -1.093406 2.850556 -v 0.050750 0.068246 0.015747 -vn -3.624902 -2.283186 2.022731 -v 0.050750 0.068837 0.016155 -vn -3.584173 -1.083902 -2.857994 -v 0.050750 0.048246 0.033553 -vn -3.604500 0.381352 -3.029591 -v 0.050750 0.047533 0.033639 -vn -3.587572 2.705846 -1.420893 -v 0.050750 0.066386 0.017847 -vn -3.586062 3.056389 0.000000 -v 0.050750 0.066214 0.017150 -vn -3.587570 2.705846 1.420893 -v 0.050750 0.066386 0.016453 -vn -3.585250 1.737623 2.514507 -v 0.050750 0.066862 0.015916 -vn -3.624902 -2.283187 -2.022731 -v 0.050750 0.068837 0.033145 -vn -3.624921 -1.081657 -2.852079 -v 0.050750 0.068246 0.033553 -vn -3.622123 0.367958 -3.028086 -v 0.050750 0.067533 0.033639 -vn -3.484427 -2.956335 0.907381 -v 0.050750 0.049170 0.031791 -vn -3.383296 -3.118685 -0.000031 -v 0.050750 0.049214 0.032150 -vn -3.484478 -2.956337 -0.907352 -v 0.050750 0.049170 0.032509 -vn -3.584921 -2.288085 -2.026611 -v 0.050750 0.048837 0.033145 -vn -3.587570 2.705848 -1.420892 -v 0.050750 0.066386 0.032847 -vn -3.586063 3.056389 0.000000 -v 0.050750 0.066214 0.032150 -vn -3.610277 0.377224 3.029154 -v 0.050750 0.047533 0.030661 -vn -3.587578 2.705848 1.420892 -v 0.050750 0.066386 0.031453 -vn -3.584922 -2.288086 -2.026610 -v 0.050750 0.048837 0.018145 -vn -3.584174 -1.083901 -2.857994 -v 0.050750 0.048246 0.018553 -vn -3.604502 0.381355 -3.029589 -v 0.050750 0.047533 0.018639 -vn -3.624922 -2.961662 0.729995 -v 0.050750 0.069170 0.016791 -vn -3.624920 -2.961663 -0.729994 -v 0.050750 0.069170 0.017509 -vn -3.624902 -2.283188 -2.022729 -v 0.050750 0.068837 0.018145 -vn -3.624909 2.700912 1.417547 -v 0.050750 0.046386 0.031453 -vn -3.624918 1.732774 2.510347 -v 0.050750 0.046862 0.030916 -vn -3.624916 1.732772 -2.510349 -v 0.050750 0.046862 0.018384 -vn -3.585251 1.737625 2.514505 -v 0.050750 0.066862 0.030916 -vn -3.586126 0.366150 3.034321 -v 0.050750 0.067533 0.030661 -vn -3.624920 -1.081657 -2.852079 -v 0.050750 0.068246 0.018553 -vn -3.608151 -1.093406 2.850556 -v 0.050750 0.068246 0.030747 -vn -3.624904 -2.283187 2.022729 -v 0.050750 0.068837 0.031155 -vn 3.252550 2.521560 2.616735 -v 0.053848 0.066862 0.015916 -vn 3.339706 1.651780 3.028227 -v 0.053790 0.067180 0.015748 -vn 3.190560 3.382604 2.176948 -v 0.053898 0.066665 0.016077 -vn 3.165314 3.987173 1.497529 -v 0.053987 0.066386 0.016453 -vn 3.090742 4.364001 0.733093 -v 0.054036 0.066258 0.016790 -vn 3.044637 4.539264 0.001894 -v 0.054054 0.066214 0.017150 -vn 3.132151 4.271553 -0.713600 -v 0.054036 0.066258 0.017510 -vn 3.198470 3.908519 -1.439646 -v 0.053987 0.066386 0.017847 -vn 3.232848 3.261450 -2.116054 -v 0.053898 0.066665 0.018223 -vn 3.250793 2.529198 -2.612776 -v 0.053848 0.066862 0.018384 -vn 3.363195 0.723645 -3.150568 -v 0.053756 0.067533 0.018639 -vn 3.382190 1.635265 -2.971878 -v 0.053790 0.067180 0.018552 -vn 3.318056 0.735534 3.208129 -v 0.053756 0.067533 0.015661 -vn 3.333437 -0.800813 -3.144819 -v 0.053760 0.047971 0.018628 -vn 3.135861 -3.445014 -1.946189 -v 0.053919 0.048836 0.018145 -vn 3.160025 -3.014969 -2.303366 -v 0.053898 0.048762 0.018223 -vn 3.268070 -2.463592 -2.637987 -v 0.053839 0.048522 0.018414 -vn 3.296483 -1.657630 -2.960241 -v 0.053790 0.048246 0.018553 -vn 3.176198 -3.909724 -1.392998 -v 0.053987 0.049041 0.017849 -vn 3.129893 -4.272014 -0.711510 -v 0.054036 0.049170 0.017509 -vn 3.046795 -4.539358 0.002560 -v 0.054054 0.049214 0.017149 -vn 3.087875 -4.364188 0.732820 -v 0.054036 0.049170 0.016791 -vn 3.132765 -4.017290 1.434643 -v 0.053987 0.049041 0.016452 -vn 3.235537 -3.353495 2.048436 -v 0.053919 0.048837 0.016155 -vn 3.342094 -1.689833 3.001186 -v 0.053790 0.048246 0.015747 -vn 3.335458 -2.508436 2.621766 -v 0.053838 0.048521 0.015886 -vn 3.343986 -0.830076 3.195133 -v 0.053760 0.047970 0.015672 -vn 3.326415 -0.789005 -3.305581 -v 0.053760 0.047971 0.033628 -vn 3.094316 -3.556084 -2.057489 -v 0.053919 0.048836 0.033145 -vn 3.116168 -3.149289 -2.383529 -v 0.053898 0.048762 0.033223 -vn 3.268668 -2.460022 -2.648074 -v 0.053839 0.048522 0.033414 -vn 3.294813 -1.656221 -3.019079 -v 0.053790 0.048246 0.033553 -vn 3.133516 -4.013875 -1.456164 -v 0.053987 0.049041 0.032849 -vn 3.088522 -4.364453 -0.732065 -v 0.054036 0.049170 0.032509 -vn 3.042009 -4.543274 -0.000412 -v 0.054054 0.049214 0.032149 -vn 3.149656 -4.222934 0.705619 -v 0.054036 0.049170 0.031791 -vn 3.176114 -3.910078 1.392551 -v 0.053987 0.049041 0.031452 -vn 3.237236 -3.348326 2.046269 -v 0.053919 0.048837 0.031155 -vn 3.343765 -1.691255 2.942226 -v 0.053790 0.048246 0.030747 -vn 3.334183 -2.514678 2.613667 -v 0.053838 0.048521 0.030886 -vn 3.349129 -0.789217 3.145588 -v 0.053760 0.047970 0.030672 -vn 3.361814 0.736827 -3.168396 -v 0.053756 0.067533 0.033639 -vn 3.252140 2.523915 2.609984 -v 0.053848 0.066862 0.030916 -vn 3.340605 1.660567 2.968801 -v 0.053790 0.067180 0.030748 -vn 3.232724 3.261935 2.114573 -v 0.053898 0.066665 0.031077 -vn 3.207845 3.883834 1.430713 -v 0.053987 0.066386 0.031453 -vn 3.150266 4.228139 0.706648 -v 0.054036 0.066258 0.031790 -vn 3.034536 4.559026 0.002174 -v 0.054054 0.066214 0.032150 -vn 3.090729 4.364126 -0.732756 -v 0.054036 0.066258 0.032510 -vn 3.164546 3.991261 -1.472031 -v 0.053987 0.066386 0.032847 -vn 3.232717 3.261937 -2.114573 -v 0.053898 0.066665 0.033223 -vn 3.252504 2.521641 -2.616678 -v 0.053848 0.066862 0.033384 -vn 3.380080 1.642434 -3.005615 -v 0.053790 0.067180 0.033552 -vn 3.323045 0.692708 3.158785 -v 0.053756 0.067533 0.030661 -# 468 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 4//4 5//5 3//3 -f 3//3 5//5 6//6 -f 3//3 6//6 7//7 -f 8//8 9//9 10//10 -f 10//10 9//9 11//11 -f 10//10 11//11 12//12 -f 7//7 13//13 3//3 -f 3//3 13//13 14//14 -f 3//3 14//14 11//11 -f 11//11 14//14 15//15 -f 11//11 15//15 12//12 -f 16//16 17//17 18//18 -f 7//7 19//19 13//13 -f 13//13 19//19 16//16 -f 13//13 16//16 20//20 -f 20//20 16//16 18//18 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 25//25 26//26 27//27 -f 25//25 27//27 28//28 -f 26//26 25//25 29//29 -f 29//29 25//25 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 34//34 32//32 35//35 -f 34//34 35//35 36//36 -f 27//27 37//37 28//28 -f 28//28 37//37 38//38 -f 28//28 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 42//42 43//43 35//35 -f 35//35 43//43 44//44 -f 35//35 44//44 36//36 -f 42//42 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 23//23 -f 48//48 21//21 23//23 -f 40//40 49//49 41//41 -f 41//41 49//49 50//50 -f 41//41 50//50 51//51 -f 46//46 11//11 9//9 -f 9//9 52//52 46//46 -f 46//46 52//52 53//53 -f 46//46 53//53 42//42 -f 42//42 53//53 54//54 -f 42//42 54//54 43//43 -f 47//47 55//55 23//23 -f 23//23 55//55 56//56 -f 23//23 56//56 57//57 -f 58//58 59//59 57//57 -f 50//50 60//60 51//51 -f 51//51 60//60 61//61 -f 51//51 61//61 62//62 -f 57//57 59//59 23//23 -f 23//23 59//59 63//63 -f 23//23 63//63 48//48 -f 61//61 64//64 62//62 -f 62//62 64//64 65//65 -f 62//62 65//65 57//57 -f 57//57 65//65 66//66 -f 57//57 66//66 58//58 -f 3//3 11//11 67//67 -f 67//67 11//11 46//46 -f 1//1 3//3 67//67 -f 68//68 69//69 67//67 -f 70//70 71//71 72//72 -f 73//73 74//74 69//69 -f 75//75 76//76 77//77 -f 78//78 79//79 80//80 -f 80//80 79//79 81//81 -f 80//80 81//81 82//82 -f 72//72 71//71 83//83 -f 83//83 71//71 84//84 -f 83//83 84//84 85//85 -f 69//69 74//74 67//67 -f 67//67 74//74 86//86 -f 67//67 86//86 1//1 -f 81//81 87//87 82//82 -f 82//82 87//87 88//88 -f 82//82 88//88 77//77 -f 77//77 88//88 89//89 -f 77//77 89//89 75//75 -f 90//90 91//91 24//24 -f 24//24 91//91 92//92 -f 24//24 92//92 67//67 -f 67//67 92//92 93//93 -f 67//67 93//93 68//68 -f 75//75 94//94 76//76 -f 76//76 94//94 95//95 -f 76//76 95//95 69//69 -f 69//69 95//95 96//96 -f 69//69 96//96 73//73 -f 72//72 97//97 70//70 -f 70//70 97//97 98//98 -f 70//70 98//98 78//78 -f 78//78 98//98 99//99 -f 78//78 99//99 79//79 -f 85//85 84//84 100//100 -f 100//100 84//84 101//101 -f 100//100 101//101 102//102 -f 24//24 22//22 103//103 -f 90//90 104//104 101//101 -f 101//101 104//104 105//105 -f 101//101 105//105 102//102 -f 103//103 106//106 24//24 -f 24//24 106//106 107//107 -f 24//24 107//107 90//90 -f 90//90 107//107 108//108 -f 90//90 108//108 104//104 -f 109//109 21//21 110//110 -f 110//110 21//21 48//48 -f 110//110 48//48 111//111 -f 109//109 112//112 21//21 -f 21//21 112//112 113//113 -f 21//21 113//113 22//22 -f 22//22 113//113 114//114 -f 114//114 115//115 22//22 -f 22//22 115//115 116//116 -f 22//22 116//116 117//117 -f 117//117 118//118 22//22 -f 22//22 118//118 119//119 -f 22//22 119//119 103//103 -f 103//103 119//119 120//120 -f 103//103 120//120 121//121 -f 122//122 123//123 124//124 -f 124//124 123//123 125//125 -f 124//124 125//125 115//115 -f 115//115 125//125 126//126 -f 115//115 126//126 116//116 -f 67//67 127//127 128//128 -f 129//129 130//130 131//131 -f 127//127 67//67 132//132 -f 133//133 134//134 135//135 -f 136//136 137//137 23//23 -f 137//137 138//138 23//23 -f 23//23 138//138 139//139 -f 23//23 139//139 140//140 -f 141//141 142//142 24//24 -f 24//24 142//142 143//143 -f 24//24 143//143 23//23 -f 133//133 144//144 134//134 -f 134//134 144//144 145//145 -f 134//134 145//145 146//146 -f 23//23 147//147 46//46 -f 46//46 147//147 148//148 -f 46//46 148//148 149//149 -f 67//67 150//150 24//24 -f 24//24 150//150 151//151 -f 24//24 151//151 141//141 -f 135//135 152//152 133//133 -f 133//133 152//152 153//153 -f 133//133 153//153 140//140 -f 140//140 153//153 154//154 -f 140//140 154//154 23//23 -f 23//23 154//154 155//155 -f 23//23 155//155 147//147 -f 128//128 156//156 67//67 -f 67//67 156//156 157//157 -f 67//67 157//157 158//158 -f 131//131 159//159 129//129 -f 129//129 159//159 160//160 -f 129//129 160//160 158//158 -f 158//158 160//160 161//161 -f 158//158 161//161 67//67 -f 67//67 161//161 162//162 -f 67//67 162//162 150//150 -f 129//129 163//163 130//130 -f 130//130 163//163 164//164 -f 130//130 164//164 165//165 -f 165//165 164//164 166//166 -f 146//146 167//167 134//134 -f 134//134 167//167 168//168 -f 134//134 168//168 169//169 -f 149//149 170//170 46//46 -f 46//46 170//170 171//171 -f 46//46 171//171 67//67 -f 67//67 171//171 172//172 -f 67//67 172//172 132//132 -f 143//143 173//173 23//23 -f 23//23 173//173 174//174 -f 23//23 174//174 136//136 -f 136//136 174//174 165//165 -f 136//136 165//165 175//175 -f 175//175 165//165 166//166 -f 175//175 166//166 169//169 -f 169//169 166//166 176//176 -f 169//169 176//176 134//134 -f 134//134 176//176 177//177 -f 134//134 177//177 178//178 -f 178//178 177//177 179//179 -f 178//178 179//179 172//172 -f 172//172 179//179 180//180 -f 172//172 180//180 132//132 -f 155//155 181//181 182//182 -f 155//155 182//182 147//147 -f 181//181 155//155 183//183 -f 183//183 155//155 154//154 -f 183//183 154//154 184//184 -f 184//184 154//154 185//185 -f 185//185 154//154 153//153 -f 185//185 153//153 186//186 -f 186//186 153//153 187//187 -f 187//187 153//153 152//152 -f 187//187 152//152 188//188 -f 188//188 152//152 189//189 -f 189//189 152//152 135//135 -f 189//189 135//135 190//190 -f 134//134 191//191 135//135 -f 135//135 191//191 192//192 -f 135//135 192//192 190//190 -f 182//182 193//193 147//147 -f 147//147 193//193 8//8 -f 147//147 8//8 148//148 -f 148//148 8//8 10//10 -f 148//148 10//10 149//149 -f 149//149 10//10 12//12 -f 149//149 12//12 170//170 -f 170//170 12//12 15//15 -f 170//170 15//15 171//171 -f 171//171 15//15 14//14 -f 171//171 14//14 172//172 -f 172//172 14//14 13//13 -f 172//172 13//13 178//178 -f 178//178 13//13 20//20 -f 178//178 20//20 134//134 -f 134//134 20//20 18//18 -f 134//134 18//18 191//191 -f 169//169 168//168 194//194 -f 195//195 196//196 167//167 -f 167//167 196//196 197//197 -f 167//167 197//197 168//168 -f 168//168 197//197 198//198 -f 168//168 198//198 194//194 -f 195//195 167//167 199//199 -f 199//199 167//167 146//146 -f 199//199 146//146 200//200 -f 200//200 146//146 201//201 -f 201//201 146//146 145//145 -f 201//201 145//145 202//202 -f 202//202 145//145 203//203 -f 203//203 145//145 144//144 -f 203//203 144//144 204//204 -f 133//133 205//205 144//144 -f 144//144 205//205 206//206 -f 144//144 206//206 204//204 -f 140//140 111//111 133//133 -f 133//133 111//111 207//207 -f 133//133 207//207 205//205 -f 194//194 122//122 169//169 -f 169//169 122//122 124//124 -f 169//169 124//124 175//175 -f 175//175 124//124 115//115 -f 175//175 115//115 136//136 -f 136//136 115//115 114//114 -f 136//136 114//114 137//137 -f 137//137 114//114 113//113 -f 137//137 113//113 138//138 -f 138//138 113//113 112//112 -f 138//138 112//112 139//139 -f 139//139 112//112 109//109 -f 139//139 109//109 140//140 -f 140//140 109//109 110//110 -f 140//140 110//110 111//111 -f 151//151 150//150 208//208 -f 209//209 210//210 162//162 -f 162//162 210//210 211//211 -f 162//162 211//211 150//150 -f 150//150 211//211 212//212 -f 150//150 212//212 208//208 -f 209//209 162//162 213//213 -f 213//213 162//162 161//161 -f 213//213 161//161 214//214 -f 214//214 161//161 215//215 -f 215//215 161//161 160//160 -f 215//215 160//160 216//216 -f 216//216 160//160 159//159 -f 216//216 159//159 217//217 -f 217//217 159//159 131//131 -f 217//217 131//131 218//218 -f 130//130 219//219 131//131 -f 131//131 219//219 220//220 -f 131//131 220//220 218//218 -f 165//165 123//123 130//130 -f 130//130 123//123 221//221 -f 130//130 221//221 219//219 -f 208//208 121//121 151//151 -f 151//151 121//121 120//120 -f 151//151 120//120 141//141 -f 141//141 120//120 119//119 -f 141//141 119//119 142//142 -f 142//142 119//119 118//118 -f 142//142 118//118 143//143 -f 143//143 118//118 117//117 -f 143//143 117//117 173//173 -f 173//173 117//117 116//116 -f 173//173 116//116 174//174 -f 174//174 116//116 126//126 -f 174//174 126//126 165//165 -f 165//165 126//126 125//125 -f 165//165 125//125 123//123 -f 2//2 222//222 158//158 -f 176//176 223//223 224//224 -f 176//176 224//224 177//177 -f 223//223 176//176 225//225 -f 225//225 176//176 166//166 -f 225//225 166//166 226//226 -f 226//226 166//166 227//227 -f 227//227 166//166 164//164 -f 227//227 164//164 228//228 -f 228//228 164//164 229//229 -f 229//229 164//164 163//163 -f 229//229 163//163 230//230 -f 230//230 163//163 231//231 -f 231//231 163//163 129//129 -f 231//231 129//129 232//232 -f 158//158 222//222 129//129 -f 129//129 222//222 233//233 -f 129//129 233//233 232//232 -f 2//2 158//158 4//4 -f 4//4 158//158 157//157 -f 4//4 157//157 5//5 -f 5//5 157//157 156//156 -f 5//5 156//156 6//6 -f 224//224 234//234 177//177 -f 177//177 234//234 17//17 -f 177//177 17//17 179//179 -f 179//179 17//17 16//16 -f 179//179 16//16 180//180 -f 180//180 16//16 19//19 -f 180//180 19//19 132//132 -f 132//132 19//19 7//7 -f 132//132 7//7 127//127 -f 127//127 7//7 6//6 -f 127//127 6//6 128//128 -f 128//128 6//6 156//156 -f 100//100 61//61 60//60 -f 100//100 60//60 85//85 -f 85//85 60//60 50//50 -f 85//85 50//50 83//83 -f 83//83 50//50 49//49 -f 83//83 49//49 72//72 -f 72//72 49//49 40//40 -f 72//72 40//40 97//97 -f 97//97 40//40 38//38 -f 97//97 38//38 98//98 -f 98//98 38//38 37//37 -f 98//98 37//37 99//99 -f 99//99 37//37 27//27 -f 99//99 27//27 79//79 -f 79//79 27//27 26//26 -f 79//79 26//26 81//81 -f 81//81 26//26 29//29 -f 81//81 29//29 87//87 -f 87//87 29//29 31//31 -f 87//87 31//31 88//88 -f 88//88 31//31 33//33 -f 88//88 33//33 89//89 -f 89//89 33//33 34//34 -f 89//89 34//34 75//75 -f 105//105 65//65 102//102 -f 102//102 65//65 64//64 -f 102//102 64//64 100//100 -f 100//100 64//64 61//61 -f 66//66 65//65 104//104 -f 104//104 65//65 105//105 -f 96//96 95//95 43//43 -f 43//43 95//95 44//44 -f 75//75 34//34 94//94 -f 94//94 34//34 36//36 -f 94//94 36//36 95//95 -f 95//95 36//36 44//44 -f 78//78 28//28 70//70 -f 70//70 28//28 39//39 -f 70//70 39//39 71//71 -f 71//71 39//39 41//41 -f 71//71 41//41 84//84 -f 84//84 41//41 51//51 -f 84//84 51//51 101//101 -f 101//101 51//51 62//62 -f 101//101 62//62 90//90 -f 90//90 62//62 57//57 -f 90//90 57//57 91//91 -f 91//91 57//57 56//56 -f 91//91 56//56 92//92 -f 92//92 56//56 55//55 -f 92//92 55//55 93//93 -f 93//93 55//55 47//47 -f 93//93 47//47 68//68 -f 68//68 47//47 45//45 -f 68//68 45//45 69//69 -f 69//69 45//45 42//42 -f 69//69 42//42 76//76 -f 76//76 42//42 35//35 -f 76//76 35//35 77//77 -f 77//77 35//35 32//32 -f 77//77 32//32 82//82 -f 82//82 32//32 30//30 -f 82//82 30//30 80//80 -f 80//80 30//30 25//25 -f 80//80 25//25 78//78 -f 78//78 25//25 28//28 -f 221//221 123//123 122//122 -f 122//122 194//194 221//221 -f 221//221 194//194 198//198 -f 221//221 198//198 219//219 -f 219//219 198//198 197//197 -f 219//219 197//197 220//220 -f 220//220 197//197 196//196 -f 220//220 196//196 218//218 -f 218//218 196//196 217//217 -f 213//213 214//214 107//107 -f 107//107 214//214 215//215 -f 107//107 215//215 200//200 -f 200//200 215//215 216//216 -f 200//200 216//216 199//199 -f 199//199 216//216 217//217 -f 199//199 217//217 195//195 -f 195//195 217//217 196//196 -f 212//212 211//211 106//106 -f 106//106 211//211 210//210 -f 106//106 210//210 107//107 -f 107//107 210//210 209//209 -f 107//107 209//209 213//213 -f 103//103 121//121 106//106 -f 106//106 121//121 208//208 -f 106//106 208//208 212//212 -f 201//201 202//202 59//59 -f 59//59 202//202 203//203 -f 59//59 203//203 63//63 -f 63//63 203//203 204//204 -f 63//63 204//204 206//206 -f 111//111 48//48 207//207 -f 207//207 48//48 63//63 -f 207//207 63//63 205//205 -f 205//205 63//63 206//206 -f 66//66 104//104 58//58 -f 58//58 104//104 108//108 -f 58//58 108//108 59//59 -f 59//59 108//108 107//107 -f 59//59 107//107 201//201 -f 201//201 107//107 200//200 -f 232//232 233//233 86//86 -f 86//86 233//233 1//1 -f 1//1 233//233 222//222 -f 1//1 222//222 2//2 -f 186//186 187//187 74//74 -f 74//74 187//187 188//188 -f 74//74 188//188 228//228 -f 228//228 188//188 227//227 -f 228//228 229//229 74//74 -f 74//74 229//229 230//230 -f 74//74 230//230 86//86 -f 86//86 230//230 231//231 -f 86//86 231//231 232//232 -f 224//224 189//189 190//190 -f 191//191 18//18 17//17 -f 190//190 192//192 224//224 -f 224//224 192//192 191//191 -f 224//224 191//191 234//234 -f 234//234 191//191 17//17 -f 224//224 223//223 189//189 -f 189//189 223//223 225//225 -f 189//189 225//225 188//188 -f 188//188 225//225 226//226 -f 188//188 226//226 227//227 -f 182//182 52//52 193//193 -f 193//193 52//52 9//9 -f 193//193 9//9 8//8 -f 182//182 181//181 52//52 -f 52//52 181//181 183//183 -f 52//52 183//183 53//53 -f 53//53 183//183 184//184 -f 53//53 184//184 185//185 -f 185//185 186//186 53//53 -f 53//53 186//186 74//74 -f 53//53 74//74 54//54 -f 54//54 74//74 73//73 -f 54//54 73//73 43//43 -f 43//43 73//73 96//96 -f 235//235 236//236 237//237 -f 237//237 236//236 238//238 -f 238//238 239//239 237//237 -f 237//237 239//239 240//240 -f 237//237 240//240 241//241 -f 242//242 243//243 244//244 -f 244//244 243//243 245//245 -f 244//244 245//245 246//246 -f 241//241 247//247 237//237 -f 237//237 247//247 248//248 -f 237//237 248//248 245//245 -f 245//245 248//248 249//249 -f 245//245 249//249 246//246 -f 250//250 251//251 252//252 -f 241//241 253//253 247//247 -f 247//247 253//253 250//250 -f 247//247 250//250 254//254 -f 254//254 250//250 252//252 -f 255//255 256//256 257//257 -f 257//257 256//256 258//258 -f 259//259 260//260 261//261 -f 259//259 261//261 262//262 -f 260//260 259//259 263//263 -f 263//263 259//259 264//264 -f 263//263 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 267//267 -f 267//267 266//266 268//268 -f 268//268 266//266 269//269 -f 268//268 269//269 270//270 -f 261//261 271//271 262//262 -f 262//262 271//271 272//272 -f 262//262 272//272 273//273 -f 273//273 272//272 274//274 -f 273//273 274//274 275//275 -f 276//276 277//277 269//269 -f 269//269 277//277 278//278 -f 269//269 278//278 270//270 -f 276//276 279//279 280//280 -f 280//280 279//279 281//281 -f 280//280 281//281 257//257 -f 282//282 255//255 257//257 -f 274//274 283//283 275//275 -f 275//275 283//283 284//284 -f 275//275 284//284 285//285 -f 280//280 245//245 243//243 -f 243//243 286//286 280//280 -f 280//280 286//286 287//287 -f 280//280 287//287 276//276 -f 276//276 287//287 288//288 -f 276//276 288//288 277//277 -f 281//281 289//289 257//257 -f 257//257 289//289 290//290 -f 257//257 290//290 291//291 -f 292//292 293//293 291//291 -f 284//284 294//294 285//285 -f 285//285 294//294 295//295 -f 285//285 295//295 296//296 -f 291//291 293//293 257//257 -f 257//257 293//293 297//297 -f 257//257 297//297 282//282 -f 295//295 298//298 296//296 -f 296//296 298//298 299//299 -f 296//296 299//299 291//291 -f 291//291 299//299 300//300 -f 291//291 300//300 292//292 -f 237//237 245//245 301//301 -f 301//301 245//245 280//280 -f 235//235 237//237 301//301 -f 302//302 303//303 301//301 -f 304//304 305//305 306//306 -f 307//307 308//308 303//303 -f 309//309 310//310 311//311 -f 312//312 313//313 314//314 -f 314//314 313//313 315//315 -f 314//314 315//315 316//316 -f 306//306 305//305 317//317 -f 317//317 305//305 318//318 -f 317//317 318//318 319//319 -f 303//303 308//308 301//301 -f 301//301 308//308 320//320 -f 301//301 320//320 235//235 -f 315//315 321//321 316//316 -f 316//316 321//321 322//322 -f 316//316 322//322 311//311 -f 311//311 322//322 323//323 -f 311//311 323//323 309//309 -f 324//324 325//325 258//258 -f 258//258 325//325 326//326 -f 258//258 326//326 301//301 -f 301//301 326//326 327//327 -f 301//301 327//327 302//302 -f 309//309 328//328 310//310 -f 310//310 328//328 329//329 -f 310//310 329//329 303//303 -f 303//303 329//329 330//330 -f 303//303 330//330 307//307 -f 306//306 331//331 304//304 -f 304//304 331//331 332//332 -f 304//304 332//332 312//312 -f 312//312 332//332 333//333 -f 312//312 333//333 313//313 -f 319//319 318//318 334//334 -f 334//334 318//318 335//335 -f 334//334 335//335 336//336 -f 258//258 256//256 337//337 -f 324//324 338//338 335//335 -f 335//335 338//338 339//339 -f 335//335 339//339 336//336 -f 337//337 340//340 258//258 -f 258//258 340//340 341//341 -f 258//258 341//341 324//324 -f 324//324 341//341 342//342 -f 324//324 342//342 338//338 -f 343//343 255//255 344//344 -f 344//344 255//255 282//282 -f 344//344 282//282 345//345 -f 343//343 346//346 255//255 -f 255//255 346//346 347//347 -f 255//255 347//347 256//256 -f 256//256 347//347 348//348 -f 348//348 349//349 256//256 -f 256//256 349//349 350//350 -f 256//256 350//350 351//351 -f 351//351 352//352 256//256 -f 256//256 352//352 353//353 -f 256//256 353//353 337//337 -f 337//337 353//353 354//354 -f 337//337 354//354 355//355 -f 356//356 357//357 358//358 -f 358//358 357//357 359//359 -f 358//358 359//359 349//349 -f 349//349 359//359 360//360 -f 349//349 360//360 350//350 -f 301//301 361//361 362//362 -f 363//363 364//364 365//365 -f 361//361 301//301 366//366 -f 367//367 368//368 369//369 -f 370//370 371//371 257//257 -f 371//371 372//372 257//257 -f 257//257 372//372 373//373 -f 257//257 373//373 374//374 -f 375//375 376//376 258//258 -f 258//258 376//376 377//377 -f 258//258 377//377 257//257 -f 367//367 378//378 368//368 -f 368//368 378//378 379//379 -f 368//368 379//379 380//380 -f 257//257 381//381 280//280 -f 280//280 381//381 382//382 -f 280//280 382//382 383//383 -f 301//301 384//384 258//258 -f 258//258 384//384 385//385 -f 258//258 385//385 375//375 -f 369//369 386//386 367//367 -f 367//367 386//386 387//387 -f 367//367 387//387 374//374 -f 374//374 387//387 388//388 -f 374//374 388//388 257//257 -f 257//257 388//388 389//389 -f 257//257 389//389 381//381 -f 362//362 390//390 301//301 -f 301//301 390//390 391//391 -f 301//301 391//391 392//392 -f 365//365 393//393 363//363 -f 363//363 393//393 394//394 -f 363//363 394//394 392//392 -f 392//392 394//394 395//395 -f 392//392 395//395 301//301 -f 301//301 395//395 396//396 -f 301//301 396//396 384//384 -f 363//363 397//397 364//364 -f 364//364 397//397 398//398 -f 364//364 398//398 399//399 -f 399//399 398//398 400//400 -f 380//380 401//401 368//368 -f 368//368 401//401 402//402 -f 368//368 402//402 403//403 -f 383//383 404//404 280//280 -f 280//280 404//404 405//405 -f 280//280 405//405 301//301 -f 301//301 405//405 406//406 -f 301//301 406//406 366//366 -f 377//377 407//407 257//257 -f 257//257 407//407 408//408 -f 257//257 408//408 370//370 -f 370//370 408//408 399//399 -f 370//370 399//399 409//409 -f 409//409 399//399 400//400 -f 409//409 400//400 403//403 -f 403//403 400//400 410//410 -f 403//403 410//410 368//368 -f 368//368 410//410 411//411 -f 368//368 411//411 412//412 -f 412//412 411//411 413//413 -f 412//412 413//413 406//406 -f 406//406 413//413 414//414 -f 406//406 414//414 366//366 -f 389//389 415//415 416//416 -f 389//389 416//416 381//381 -f 415//415 389//389 417//417 -f 417//417 389//389 388//388 -f 417//417 388//388 418//418 -f 418//418 388//388 419//419 -f 419//419 388//388 387//387 -f 419//419 387//387 420//420 -f 420//420 387//387 421//421 -f 421//421 387//387 386//386 -f 421//421 386//386 422//422 -f 422//422 386//386 423//423 -f 423//423 386//386 369//369 -f 423//423 369//369 424//424 -f 368//368 425//425 369//369 -f 369//369 425//425 426//426 -f 369//369 426//426 424//424 -f 416//416 427//427 381//381 -f 381//381 427//427 242//242 -f 381//381 242//242 382//382 -f 382//382 242//242 244//244 -f 382//382 244//244 383//383 -f 383//383 244//244 246//246 -f 383//383 246//246 404//404 -f 404//404 246//246 249//249 -f 404//404 249//249 405//405 -f 405//405 249//249 248//248 -f 405//405 248//248 406//406 -f 406//406 248//248 247//247 -f 406//406 247//247 412//412 -f 412//412 247//247 254//254 -f 412//412 254//254 368//368 -f 368//368 254//254 252//252 -f 368//368 252//252 425//425 -f 403//403 402//402 428//428 -f 429//429 430//430 401//401 -f 401//401 430//430 431//431 -f 401//401 431//431 402//402 -f 402//402 431//431 432//432 -f 402//402 432//432 428//428 -f 429//429 401//401 433//433 -f 433//433 401//401 380//380 -f 433//433 380//380 434//434 -f 434//434 380//380 435//435 -f 435//435 380//380 379//379 -f 435//435 379//379 436//436 -f 436//436 379//379 437//437 -f 437//437 379//379 378//378 -f 437//437 378//378 438//438 -f 367//367 439//439 378//378 -f 378//378 439//439 440//440 -f 378//378 440//440 438//438 -f 374//374 345//345 367//367 -f 367//367 345//345 441//441 -f 367//367 441//441 439//439 -f 428//428 356//356 403//403 -f 403//403 356//356 358//358 -f 403//403 358//358 409//409 -f 409//409 358//358 349//349 -f 409//409 349//349 370//370 -f 370//370 349//349 348//348 -f 370//370 348//348 371//371 -f 371//371 348//348 347//347 -f 371//371 347//347 372//372 -f 372//372 347//347 346//346 -f 372//372 346//346 373//373 -f 373//373 346//346 343//343 -f 373//373 343//343 374//374 -f 374//374 343//343 344//344 -f 374//374 344//344 345//345 -f 385//385 384//384 442//442 -f 443//443 444//444 396//396 -f 396//396 444//444 445//445 -f 396//396 445//445 384//384 -f 384//384 445//445 446//446 -f 384//384 446//446 442//442 -f 443//443 396//396 447//447 -f 447//447 396//396 395//395 -f 447//447 395//395 448//448 -f 448//448 395//395 449//449 -f 449//449 395//395 394//394 -f 449//449 394//394 450//450 -f 450//450 394//394 393//393 -f 450//450 393//393 451//451 -f 451//451 393//393 365//365 -f 451//451 365//365 452//452 -f 364//364 453//453 365//365 -f 365//365 453//453 454//454 -f 365//365 454//454 452//452 -f 399//399 357//357 364//364 -f 364//364 357//357 455//455 -f 364//364 455//455 453//453 -f 442//442 355//355 385//385 -f 385//385 355//355 354//354 -f 385//385 354//354 375//375 -f 375//375 354//354 353//353 -f 375//375 353//353 376//376 -f 376//376 353//353 352//352 -f 376//376 352//352 377//377 -f 377//377 352//352 351//351 -f 377//377 351//351 407//407 -f 407//407 351//351 350//350 -f 407//407 350//350 408//408 -f 408//408 350//350 360//360 -f 408//408 360//360 399//399 -f 399//399 360//360 359//359 -f 399//399 359//359 357//357 -f 236//236 456//456 392//392 -f 410//410 457//457 458//458 -f 410//410 458//458 411//411 -f 457//457 410//410 459//459 -f 459//459 410//410 400//400 -f 459//459 400//400 460//460 -f 460//460 400//400 461//461 -f 461//461 400//400 398//398 -f 461//461 398//398 462//462 -f 462//462 398//398 463//463 -f 463//463 398//398 397//397 -f 463//463 397//397 464//464 -f 464//464 397//397 465//465 -f 465//465 397//397 363//363 -f 465//465 363//363 466//466 -f 392//392 456//456 363//363 -f 363//363 456//456 467//467 -f 363//363 467//467 466//466 -f 236//236 392//392 238//238 -f 238//238 392//392 391//391 -f 238//238 391//391 239//239 -f 239//239 391//391 390//390 -f 239//239 390//390 240//240 -f 458//458 468//468 411//411 -f 411//411 468//468 251//251 -f 411//411 251//251 413//413 -f 413//413 251//251 250//250 -f 413//413 250//250 414//414 -f 414//414 250//250 253//253 -f 414//414 253//253 366//366 -f 366//366 253//253 241//241 -f 366//366 241//241 361//361 -f 361//361 241//241 240//240 -f 361//361 240//240 362//362 -f 362//362 240//240 390//390 -f 334//334 295//295 294//294 -f 334//334 294//294 319//319 -f 319//319 294//294 284//284 -f 319//319 284//284 317//317 -f 317//317 284//284 283//283 -f 317//317 283//283 306//306 -f 306//306 283//283 274//274 -f 306//306 274//274 331//331 -f 331//331 274//274 272//272 -f 331//331 272//272 332//332 -f 332//332 272//272 271//271 -f 332//332 271//271 333//333 -f 333//333 271//271 261//261 -f 333//333 261//261 313//313 -f 313//313 261//261 260//260 -f 313//313 260//260 315//315 -f 315//315 260//260 263//263 -f 315//315 263//263 321//321 -f 321//321 263//263 265//265 -f 321//321 265//265 322//322 -f 322//322 265//265 267//267 -f 322//322 267//267 323//323 -f 323//323 267//267 268//268 -f 323//323 268//268 309//309 -f 339//339 299//299 336//336 -f 336//336 299//299 298//298 -f 336//336 298//298 334//334 -f 334//334 298//298 295//295 -f 300//300 299//299 338//338 -f 338//338 299//299 339//339 -f 330//330 329//329 277//277 -f 277//277 329//329 278//278 -f 309//309 268//268 328//328 -f 328//328 268//268 270//270 -f 328//328 270//270 329//329 -f 329//329 270//270 278//278 -f 312//312 262//262 304//304 -f 304//304 262//262 273//273 -f 304//304 273//273 305//305 -f 305//305 273//273 275//275 -f 305//305 275//275 318//318 -f 318//318 275//275 285//285 -f 318//318 285//285 335//335 -f 335//335 285//285 296//296 -f 335//335 296//296 324//324 -f 324//324 296//296 291//291 -f 324//324 291//291 325//325 -f 325//325 291//291 290//290 -f 325//325 290//290 326//326 -f 326//326 290//290 289//289 -f 326//326 289//289 327//327 -f 327//327 289//289 281//281 -f 327//327 281//281 302//302 -f 302//302 281//281 279//279 -f 302//302 279//279 303//303 -f 303//303 279//279 276//276 -f 303//303 276//276 310//310 -f 310//310 276//276 269//269 -f 310//310 269//269 311//311 -f 311//311 269//269 266//266 -f 311//311 266//266 316//316 -f 316//316 266//266 264//264 -f 316//316 264//264 314//314 -f 314//314 264//264 259//259 -f 314//314 259//259 312//312 -f 312//312 259//259 262//262 -f 455//455 357//357 356//356 -f 356//356 428//428 455//455 -f 455//455 428//428 432//432 -f 455//455 432//432 453//453 -f 453//453 432//432 431//431 -f 453//453 431//431 454//454 -f 454//454 431//431 430//430 -f 454//454 430//430 452//452 -f 452//452 430//430 451//451 -f 447//447 448//448 341//341 -f 341//341 448//448 449//449 -f 341//341 449//449 434//434 -f 434//434 449//449 450//450 -f 434//434 450//450 433//433 -f 433//433 450//450 451//451 -f 433//433 451//451 429//429 -f 429//429 451//451 430//430 -f 446//446 445//445 340//340 -f 340//340 445//445 444//444 -f 340//340 444//444 341//341 -f 341//341 444//444 443//443 -f 341//341 443//443 447//447 -f 337//337 355//355 340//340 -f 340//340 355//355 442//442 -f 340//340 442//442 446//446 -f 435//435 436//436 293//293 -f 293//293 436//436 437//437 -f 293//293 437//437 297//297 -f 297//297 437//437 438//438 -f 297//297 438//438 440//440 -f 345//345 282//282 441//441 -f 441//441 282//282 297//297 -f 441//441 297//297 439//439 -f 439//439 297//297 440//440 -f 300//300 338//338 292//292 -f 292//292 338//338 342//342 -f 292//292 342//342 293//293 -f 293//293 342//342 341//341 -f 293//293 341//341 435//435 -f 435//435 341//341 434//434 -f 466//466 467//467 320//320 -f 320//320 467//467 235//235 -f 235//235 467//467 456//456 -f 235//235 456//456 236//236 -f 420//420 421//421 308//308 -f 308//308 421//421 422//422 -f 308//308 422//422 462//462 -f 462//462 422//422 461//461 -f 462//462 463//463 308//308 -f 308//308 463//463 464//464 -f 308//308 464//464 320//320 -f 320//320 464//464 465//465 -f 320//320 465//465 466//466 -f 458//458 423//423 424//424 -f 425//425 252//252 251//251 -f 424//424 426//426 458//458 -f 458//458 426//426 425//425 -f 458//458 425//425 468//468 -f 468//468 425//425 251//251 -f 458//458 457//457 423//423 -f 423//423 457//457 459//459 -f 423//423 459//459 422//422 -f 422//422 459//459 460//460 -f 422//422 460//460 461//461 -f 416//416 286//286 427//427 -f 427//427 286//286 243//243 -f 427//427 243//243 242//242 -f 416//416 415//415 286//286 -f 286//286 415//415 417//417 -f 286//286 417//417 287//287 -f 287//287 417//417 418//418 -f 287//287 418//418 419//419 -f 419//419 420//420 287//287 -f 287//287 420//420 308//308 -f 287//287 308//308 288//288 -f 288//288 308//308 307//307 -f 288//288 307//307 277//277 -f 277//277 307//307 330//330 -# 968 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_zupcanik.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_zupcanik.obj deleted file mode 100644 index 02edfbca2..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/lift_zupcanik.obj +++ /dev/null @@ -1,1164 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object T_BOT_NOVE_SISE_I_LETVA2022 - zupcanik m2z16-1.obj -# -# Vertices: 287 -# Faces: 574 -# -#### -vn 3.106582 -2.889303 0.250067 -v 0.040775 -0.000890 0.077143 -vn 2.138548 -4.526160 -1.129209 -v 0.040445 -0.000890 0.078719 -vn 3.070662 -2.889305 -0.533316 -v 0.040701 -0.000890 0.075535 -vn 1.807952 -2.065249 -2.001981 -v 0.040228 -0.000890 0.073995 -vn 2.407893 -4.526160 -0.224859 -v 0.045036 -0.000890 0.081301 -vn 1.861639 -4.526158 1.543636 -v 0.049709 -0.000890 0.090516 -vn 1.861639 -4.526158 -1.543636 -v 0.049709 -0.000890 0.092584 -vn -2.632826 -2.889299 -1.667816 -v 0.038266 -0.000890 0.075050 -vn -0.904218 -2.065266 -2.541471 -v 0.039292 -0.000890 0.073809 -vn -0.713720 -4.526159 -2.310655 -v 0.042356 -0.000890 0.079511 -vn -2.373511 -2.889302 -2.019859 -v 0.043237 -0.000890 0.078163 -vn 2.774408 -2.889303 1.419875 -v 0.045944 -0.000890 0.079972 -vn -1.794172 -2.889303 -2.548398 -v 0.044427 -0.000890 0.077078 -vn 3.041012 -2.889300 0.682369 -v 0.046491 -0.000890 0.078457 -vn 0.137196 -2.065255 -2.694034 -v 0.045850 -0.000890 0.076324 -vn 2.436465 -2.065261 -1.157714 -v 0.046644 -0.000890 0.076854 -vn 1.129206 -4.526159 2.138551 -v 0.049081 -0.000890 0.095745 -vn 0.957803 -2.889303 -2.965804 -v 0.051292 -0.000890 0.092883 -vn -0.250073 -2.889305 3.106582 -v 0.050657 -0.000890 0.096075 -vn 1.667812 -2.889302 -2.632829 -v 0.052750 -0.000890 0.093566 -vn 0.533320 -2.889297 3.070659 -v 0.052265 -0.000890 0.096001 -vn 2.541466 -2.065259 -0.904215 -v 0.053991 -0.000890 0.094592 -vn 2.001987 -2.065259 1.807956 -v 0.053805 -0.000890 0.095528 -vn 1.807952 -2.065250 2.001980 -v 0.040228 -0.000890 0.109105 -vn -0.904218 -2.065266 2.541471 -v 0.039292 -0.000890 0.109291 -vn 3.070662 -2.889306 0.533316 -v 0.040701 -0.000890 0.107565 -vn -2.632825 -2.889299 1.667816 -v 0.038266 -0.000890 0.108050 -vn -2.965806 -2.889301 0.957800 -v 0.037583 -0.000890 0.106592 -vn -0.713720 -4.526156 2.310654 -v 0.042356 -0.000890 0.103589 -vn 2.138548 -4.526160 1.129210 -v 0.040445 -0.000890 0.104381 -vn -1.861639 -4.526167 -1.543636 -v 0.022791 -0.000890 0.092584 -vn 2.001987 -2.065259 -1.807956 -v 0.053805 -0.000890 0.087572 -vn 2.541466 -2.065259 0.904216 -v 0.053991 -0.000890 0.088508 -vn 0.533320 -2.889297 -3.070660 -v 0.052265 -0.000890 0.087099 -vn 1.667812 -2.889302 2.632828 -v 0.052750 -0.000890 0.089534 -vn -0.250073 -2.889305 -3.106582 -v 0.050657 -0.000890 0.087025 -vn 0.957803 -2.889303 2.965805 -v 0.051292 -0.000890 0.090217 -vn 1.129207 -4.526159 -2.138551 -v 0.049081 -0.000890 0.087355 -vn -1.543636 -4.526159 1.861636 -v 0.037284 -0.000890 0.105009 -vn 1.543636 -4.526158 1.861640 -v 0.035216 -0.000890 0.105009 -vn -2.407893 -4.526158 0.224859 -v 0.027464 -0.000890 0.101799 -vn -0.224860 -4.526163 2.407889 -v 0.026001 -0.000890 0.100336 -vn 0.250072 -2.889305 3.106582 -v 0.021843 -0.000890 0.096075 -vn -0.957805 -2.889302 -2.965804 -v 0.021208 -0.000890 0.092883 -vn -0.533320 -2.889297 3.070659 -v 0.020235 -0.000890 0.096001 -vn -1.667813 -2.889304 -2.632829 -v 0.019750 -0.000890 0.093566 -vn -2.001987 -2.065261 1.807958 -v 0.018695 -0.000890 0.095528 -vn -2.541465 -2.065257 -0.904213 -v 0.018509 -0.000890 0.094592 -vn -1.861639 -4.526158 1.543636 -v 0.022791 -0.000890 0.090516 -vn -0.224860 -4.526162 -2.407889 -v 0.026001 -0.000890 0.082764 -vn -2.407893 -4.526158 -0.224859 -v 0.027464 -0.000890 0.081301 -vn 2.310653 -4.526159 -0.713716 -v 0.048289 -0.000890 0.097656 -vn 3.106582 -2.889304 -0.250067 -v 0.040775 -0.000890 0.105957 -vn 1.157711 -2.065259 -2.436465 -v 0.050946 -0.000890 0.081156 -vn 2.694034 -2.065255 -0.137196 -v 0.051476 -0.000890 0.081950 -vn -0.682369 -2.889304 -3.041013 -v 0.049343 -0.000890 0.081309 -vn 2.548398 -2.889303 1.794172 -v 0.050722 -0.000890 0.083373 -vn -1.419874 -2.889299 -2.774408 -v 0.047828 -0.000890 0.081856 -vn 2.019859 -2.889302 2.373511 -v 0.049637 -0.000890 0.084563 -vn 0.224860 -4.526163 -2.407889 -v 0.046499 -0.000890 0.082764 -vn 2.310653 -4.526159 0.713717 -v 0.048289 -0.000890 0.085444 -vn -2.965805 -2.889301 -0.957800 -v 0.037583 -0.000890 0.076508 -vn -1.157712 -2.065257 2.436463 -v 0.021554 -0.000890 0.101944 -vn -2.694035 -2.065257 0.137194 -v 0.021024 -0.000890 0.101150 -vn 0.682369 -2.889304 3.041013 -v 0.023157 -0.000890 0.101791 -vn -2.548398 -2.889304 -1.794171 -v 0.021778 -0.000890 0.099727 -vn 1.419874 -2.889299 2.774408 -v 0.024672 -0.000890 0.101244 -vn -2.019859 -2.889300 -2.373511 -v 0.022863 -0.000890 0.098537 -vn -2.310652 -4.526159 -0.713716 -v 0.024211 -0.000890 0.097656 -vn -1.129207 -4.526157 2.138552 -v 0.023419 -0.000890 0.095745 -vn -3.056107 -3.560473 0.321214 -v 0.038736 -0.000890 0.091289 -vn -2.922539 -3.560475 -0.949594 -v 0.038628 -0.000890 0.092323 -vn 0.224860 -4.526163 2.407889 -v 0.046499 -0.000890 0.100336 -vn -1.419874 -2.889299 2.774408 -v 0.047828 -0.000890 0.101244 -vn 2.019859 -2.889302 -2.373511 -v 0.049637 -0.000890 0.098537 -vn -0.682369 -2.889304 3.041013 -v 0.049343 -0.000890 0.101791 -vn 2.548398 -2.889303 -1.794172 -v 0.050722 -0.000890 0.099727 -vn 1.157710 -2.065259 2.436465 -v 0.050946 -0.000890 0.101944 -vn 2.694034 -2.065255 0.137196 -v 0.051476 -0.000890 0.101150 -vn -1.543637 -4.526160 -1.861636 -v 0.037284 -0.000890 0.078091 -vn -0.644360 -3.552174 3.005767 -v 0.036770 -0.000890 0.089105 -vn 1.543636 -4.526158 -1.861639 -v 0.035216 -0.000890 0.078091 -vn 0.644360 -3.552176 3.005767 -v 0.035730 -0.000890 0.089105 -vn 1.806231 -3.560471 2.486061 -v 0.034781 -0.000890 0.089527 -vn -2.661244 -3.560470 1.536474 -v 0.038415 -0.000890 0.090300 -vn -1.806231 -3.560471 2.486061 -v 0.037719 -0.000890 0.089527 -vn -2.774409 -2.889302 -1.419873 -v 0.026556 -0.000890 0.103128 -vn 1.794171 -2.889303 2.548398 -v 0.028073 -0.000890 0.106022 -vn -3.041012 -2.889303 -0.682371 -v 0.026009 -0.000890 0.104643 -vn -0.137195 -2.065257 2.694035 -v 0.026650 -0.000890 0.106776 -vn -2.436463 -2.065257 1.157711 -v 0.025856 -0.000890 0.106246 -vn -2.436463 -2.065257 -1.157711 -v 0.025856 -0.000890 0.076854 -vn -0.137195 -2.065257 -2.694035 -v 0.026650 -0.000890 0.076324 -vn -3.041012 -2.889303 0.682371 -v 0.026009 -0.000890 0.078457 -vn 1.794171 -2.889303 -2.548398 -v 0.028073 -0.000890 0.077078 -vn -2.774409 -2.889302 1.419873 -v 0.026556 -0.000890 0.079972 -vn 2.373511 -2.889302 -2.019859 -v 0.029263 -0.000890 0.078163 -vn 0.713720 -4.526156 -2.310654 -v 0.030144 -0.000890 0.079511 -vn -2.138548 -4.526162 -1.129206 -v 0.032055 -0.000890 0.078719 -vn 2.661246 -3.560473 1.536469 -v 0.034085 -0.000890 0.090300 -vn 3.056108 -3.560470 0.321209 -v 0.033764 -0.000890 0.091289 -vn 2.922541 -3.560472 -0.949590 -v 0.033872 -0.000890 0.092323 -vn 2.283640 -3.560472 -2.056200 -v 0.034392 -0.000890 0.093223 -vn -2.541465 -2.065257 0.904213 -v 0.018509 -0.000890 0.088508 -vn -2.001987 -2.065261 -1.807958 -v 0.018695 -0.000890 0.087572 -vn -1.667813 -2.889304 2.632829 -v 0.019750 -0.000890 0.089534 -vn -0.533321 -2.889297 -3.070659 -v 0.020235 -0.000890 0.087099 -vn -0.957804 -2.889302 2.965804 -v 0.021208 -0.000890 0.090217 -vn 0.250072 -2.889305 -3.106582 -v 0.021843 -0.000890 0.087025 -vn -1.129206 -4.526157 -2.138553 -v 0.023419 -0.000890 0.087355 -vn -2.310652 -4.526160 0.713716 -v 0.024211 -0.000890 0.085444 -vn 1.419874 -2.889299 -2.774408 -v 0.024672 -0.000890 0.081856 -vn -2.019858 -2.889300 2.373510 -v 0.022863 -0.000890 0.084563 -vn 0.682369 -2.889304 -3.041013 -v 0.023157 -0.000890 0.081309 -vn -2.548399 -2.889304 1.794171 -v 0.021778 -0.000890 0.083373 -vn -1.157712 -2.065257 -2.436463 -v 0.021554 -0.000890 0.081156 -vn -2.694035 -2.065257 -0.137194 -v 0.021024 -0.000890 0.081950 -vn -1.807951 -2.065249 -2.001981 -v 0.032272 -0.000890 0.073995 -vn 0.904219 -2.065267 -2.541472 -v 0.033208 -0.000890 0.073809 -vn -3.070662 -2.889305 -0.533316 -v 0.031799 -0.000890 0.075535 -vn 2.632827 -2.889297 -1.667813 -v 0.034234 -0.000890 0.075050 -vn -3.106582 -2.889301 0.250071 -v 0.031725 -0.000890 0.077143 -vn 2.965806 -2.889306 -0.957801 -v 0.034917 -0.000890 0.076508 -vn 1.249874 -3.560473 -2.807273 -v 0.035233 -0.000890 0.093834 -vn 2.407893 -4.526160 0.224859 -v 0.045036 -0.000890 0.101799 -vn 2.774408 -2.889303 -1.419875 -v 0.045944 -0.000890 0.103128 -vn -2.373511 -2.889301 2.019859 -v 0.043237 -0.000890 0.104937 -vn 3.041012 -2.889300 -0.682369 -v 0.046491 -0.000890 0.104643 -vn -1.794172 -2.889303 2.548398 -v 0.044427 -0.000890 0.106022 -vn 2.436466 -2.065261 1.157714 -v 0.046644 -0.000890 0.106246 -vn 0.137196 -2.065255 2.694034 -v 0.045850 -0.000890 0.106776 -vn 0.000001 -3.560467 -3.072943 -v 0.036250 -0.000890 0.094050 -vn -1.249875 -3.560476 -2.807271 -v 0.037267 -0.000890 0.093834 -vn -2.283640 -3.560468 -2.056202 -v 0.038108 -0.000890 0.093223 -vn 0.904219 -2.065267 2.541472 -v 0.033208 -0.000890 0.109291 -vn -1.807951 -2.065249 2.001981 -v 0.032272 -0.000890 0.109105 -vn 2.632827 -2.889297 1.667813 -v 0.034234 -0.000890 0.108050 -vn -3.070662 -2.889305 0.533316 -v 0.031799 -0.000890 0.107565 -vn 2.965806 -2.889306 0.957801 -v 0.034917 -0.000890 0.106592 -vn -3.106582 -2.889301 -0.250071 -v 0.031725 -0.000890 0.105957 -vn -2.138547 -4.526162 1.129206 -v 0.032055 -0.000890 0.104381 -vn 0.713720 -4.526156 2.310655 -v 0.030144 -0.000890 0.103589 -vn 2.373511 -2.889302 2.019859 -v 0.029263 -0.000890 0.104937 -vn 1.807952 2.065250 2.001981 -v 0.040228 0.009110 0.109105 -vn -0.904218 2.065266 2.541471 -v 0.039292 0.009110 0.109291 -vn 0.904219 2.065267 2.541472 -v 0.033208 0.009110 0.109291 -vn -1.807951 2.065249 2.001981 -v 0.032272 0.009110 0.109105 -vn 2.436465 2.065261 1.157714 -v 0.046644 0.009110 0.106246 -vn 0.137196 2.065255 2.694034 -v 0.045850 0.009110 0.106776 -vn 2.694034 2.065255 0.137196 -v 0.051476 0.009110 0.101150 -vn 1.157711 2.065259 2.436465 -v 0.050946 0.009110 0.101944 -vn -2.001987 2.065261 1.807958 -v 0.018695 0.009110 0.095528 -vn -2.541465 2.065257 -0.904213 -v 0.018509 0.009110 0.094592 -vn -2.541465 2.065257 0.904213 -v 0.018509 0.009110 0.088508 -vn -2.001987 2.065261 -1.807958 -v 0.018695 0.009110 0.087572 -vn -1.157712 2.065257 2.436463 -v 0.021554 0.009110 0.101944 -vn -2.694035 2.065257 0.137194 -v 0.021024 0.009110 0.101150 -vn -0.137195 2.065257 2.694035 -v 0.026650 0.009110 0.106776 -vn -2.436463 2.065257 1.157711 -v 0.025856 0.009110 0.106246 -vn -2.694035 2.065257 -0.137194 -v 0.021024 0.009110 0.081950 -vn -1.157712 2.065257 -2.436463 -v 0.021554 0.009110 0.081156 -vn -2.436463 2.065257 -1.157711 -v 0.025856 0.009110 0.076854 -vn -0.137195 2.065257 -2.694035 -v 0.026650 0.009110 0.076324 -vn -1.807951 2.065249 -2.001981 -v 0.032272 0.009110 0.073995 -vn 0.904219 2.065267 -2.541472 -v 0.033208 0.009110 0.073809 -vn 0.137196 2.065255 -2.694034 -v 0.045850 0.009110 0.076324 -vn 2.436466 2.065261 -1.157714 -v 0.046644 0.009110 0.076854 -vn 1.157710 2.065259 -2.436465 -v 0.050946 0.009110 0.081156 -vn 2.694034 2.065255 -0.137196 -v 0.051476 0.009110 0.081950 -vn 2.001987 2.065259 -1.807956 -v 0.053805 0.009110 0.087572 -vn 2.541466 2.065259 0.904215 -v 0.053991 0.009110 0.088508 -vn -0.904218 2.065266 -2.541471 -v 0.039292 0.009110 0.073809 -vn 1.807952 2.065250 -2.001980 -v 0.040228 0.009110 0.073995 -vn -0.533320 2.889297 -3.070659 -v 0.020235 0.009110 0.087099 -vn -1.667813 2.889304 2.632829 -v 0.019750 0.009110 0.089534 -vn -0.957805 2.889302 2.965804 -v 0.021208 0.009110 0.090217 -vn -2.310652 4.526160 0.713716 -v 0.024211 0.009110 0.085444 -vn -1.129207 4.526158 -2.138552 -v 0.023419 0.009110 0.087355 -vn 1.543636 4.526165 1.861639 -v 0.035216 0.009110 0.105009 -vn 2.774408 2.889303 -1.419875 -v 0.045944 0.009110 0.103128 -vn 2.407894 4.526158 0.224859 -v 0.045036 0.009110 0.101799 -vn -0.713720 4.526159 2.310655 -v 0.042356 0.009110 0.103589 -vn 1.861639 4.526158 -1.543636 -v 0.049709 0.009110 0.092584 -vn 1.861639 4.526158 1.543636 -v 0.049709 0.009110 0.090516 -vn 2.310653 4.526158 0.713716 -v 0.048289 0.009110 0.085444 -vn -1.861639 4.526157 1.543636 -v 0.022791 0.009110 0.090516 -vn -1.861639 4.526158 -1.543636 -v 0.022791 0.009110 0.092584 -vn -0.224860 4.526163 2.407889 -v 0.026001 0.009110 0.100336 -vn 0.250072 2.889305 -3.106582 -v 0.021843 0.009110 0.087025 -vn 0.682369 2.889304 3.041013 -v 0.023157 0.009110 0.101791 -vn -2.373511 2.889302 2.019859 -v 0.043237 0.009110 0.104937 -vn -1.794172 2.889303 2.548398 -v 0.044427 0.009110 0.106022 -vn 3.041012 2.889300 -0.682369 -v 0.046491 0.009110 0.104643 -vn 0.224860 4.526163 2.407889 -v 0.046499 0.009110 0.100336 -vn 1.129206 4.526158 -2.138551 -v 0.049081 0.009110 0.087355 -vn 0.957803 2.889303 2.965804 -v 0.051292 0.009110 0.090217 -vn -0.250073 2.889305 -3.106582 -v 0.050657 0.009110 0.087025 -vn 1.667812 2.889302 2.632829 -v 0.052750 0.009110 0.089534 -vn 0.533320 2.889297 -3.070659 -v 0.052265 0.009110 0.087099 -vn -2.548399 2.889304 -1.794171 -v 0.021778 0.009110 0.099727 -vn 1.419874 2.889299 2.774408 -v 0.024672 0.009110 0.101244 -vn -2.019858 2.889300 -2.373510 -v 0.022863 0.009110 0.098537 -vn -2.310652 4.526159 -0.713716 -v 0.024211 0.009110 0.097656 -vn -1.129206 4.526157 2.138552 -v 0.023419 0.009110 0.095745 -vn -0.957804 2.889302 -2.965804 -v 0.021208 0.009110 0.092883 -vn 0.250072 2.889305 3.106582 -v 0.021843 0.009110 0.096075 -vn -1.667813 2.889304 -2.632829 -v 0.019750 0.009110 0.093566 -vn -0.533321 2.889297 3.070659 -v 0.020235 0.009110 0.096001 -vn -2.138548 4.526162 1.129206 -v 0.032055 0.009110 0.104381 -vn -2.407893 4.526158 0.224859 -v 0.027464 0.009110 0.101799 -vn 0.713720 4.526156 2.310654 -v 0.030144 0.009110 0.103589 -vn -2.774409 2.889302 -1.419873 -v 0.026556 0.009110 0.103128 -vn 2.373511 2.889302 2.019859 -v 0.029263 0.009110 0.104937 -vn -3.041012 2.889303 -0.682371 -v 0.026009 0.009110 0.104643 -vn 1.794171 2.889303 2.548398 -v 0.028073 0.009110 0.106022 -vn -2.138547 4.526162 -1.129206 -v 0.032055 0.009110 0.078719 -vn 1.543636 4.526157 -1.861640 -v 0.035216 0.009110 0.078091 -vn 2.965806 2.889306 -0.957801 -v 0.034917 0.009110 0.076508 -vn -3.106582 2.889301 0.250071 -v 0.031725 0.009110 0.077143 -vn 2.632827 2.889297 -1.667813 -v 0.034234 0.009110 0.075050 -vn -3.070662 2.889305 -0.533316 -v 0.031799 0.009110 0.075535 -vn -1.543636 4.526160 -1.861636 -v 0.037284 0.009110 0.078091 -vn 2.407893 4.526157 -0.224859 -v 0.045036 0.009110 0.081301 -vn 0.224860 4.526164 -2.407889 -v 0.046499 0.009110 0.082764 -vn 0.713720 4.526156 -2.310655 -v 0.030144 0.009110 0.079511 -vn 2.138548 4.526163 1.129209 -v 0.040445 0.009110 0.104381 -vn -2.283640 3.560467 -2.056201 -v 0.038108 0.009110 0.093223 -vn -1.249876 3.560476 -2.807271 -v 0.037267 0.009110 0.093834 -vn -0.682369 2.889304 -3.041013 -v 0.049343 0.009110 0.081309 -vn -1.419874 2.889299 -2.774408 -v 0.047828 0.009110 0.081856 -vn 2.548398 2.889303 1.794172 -v 0.050722 0.009110 0.083373 -vn 2.019859 2.889302 2.373511 -v 0.049637 0.009110 0.084563 -vn 3.041012 2.889300 0.682369 -v 0.046491 0.009110 0.078457 -vn -1.794172 2.889303 -2.548398 -v 0.044427 0.009110 0.077078 -vn 2.774408 2.889303 1.419875 -v 0.045944 0.009110 0.079972 -vn -2.373511 2.889302 -2.019859 -v 0.043237 0.009110 0.078163 -vn -0.713720 4.526156 -2.310654 -v 0.042356 0.009110 0.079511 -vn 2.138548 4.526160 -1.129210 -v 0.040445 0.009110 0.078719 -vn -2.965806 2.889301 -0.957800 -v 0.037583 0.009110 0.076508 -vn 3.106582 2.889303 0.250067 -v 0.040775 0.009110 0.077143 -vn -2.632825 2.889299 -1.667816 -v 0.038266 0.009110 0.075050 -vn 3.070662 2.889305 -0.533316 -v 0.040701 0.009110 0.075535 -vn -0.682369 2.889304 3.041013 -v 0.049343 0.009110 0.101791 -vn 2.548398 2.889303 -1.794172 -v 0.050722 0.009110 0.099727 -vn -1.419874 2.889299 2.774408 -v 0.047828 0.009110 0.101244 -vn 2.019859 2.889302 -2.373511 -v 0.049637 0.009110 0.098537 -vn 2.310653 4.526159 -0.713717 -v 0.048289 0.009110 0.097656 -vn 1.129207 4.526158 2.138551 -v 0.049081 0.009110 0.095745 -vn -0.250073 2.889305 3.106582 -v 0.050657 0.009110 0.096075 -vn 0.957803 2.889303 -2.965805 -v 0.051292 0.009110 0.092883 -vn 0.533320 2.889297 3.070660 -v 0.052265 0.009110 0.096001 -vn 1.667812 2.889302 -2.632828 -v 0.052750 0.009110 0.093566 -vn 2.001987 2.065259 1.807956 -v 0.053805 0.009110 0.095528 -vn 2.541466 2.065259 -0.904216 -v 0.053991 0.009110 0.094592 -vn -3.070662 2.889305 0.533316 -v 0.031799 0.009110 0.107565 -vn 2.632827 2.889297 1.667813 -v 0.034234 0.009110 0.108050 -vn -3.106582 2.889301 -0.250071 -v 0.031725 0.009110 0.105957 -vn 2.965806 2.889306 0.957801 -v 0.034917 0.009110 0.106592 -vn -1.543637 4.526160 1.861636 -v 0.037284 0.009110 0.105009 -vn 0.000001 3.560467 -3.072943 -v 0.036250 0.009110 0.094050 -vn 1.249874 3.560473 -2.807273 -v 0.035233 0.009110 0.093834 -vn 2.283640 3.560472 -2.056199 -v 0.034392 0.009110 0.093223 -vn 2.922541 3.560472 -0.949590 -v 0.033872 0.009110 0.092323 -vn 3.056108 3.560470 0.321209 -v 0.033764 0.009110 0.091289 -vn -0.224860 4.526161 -2.407889 -v 0.026001 0.009110 0.082764 -vn 2.661246 3.560473 1.536469 -v 0.034085 0.009110 0.090300 -vn -2.407894 4.526161 -0.224859 -v 0.027464 0.009110 0.081301 -vn -0.803085 3.455759 2.997186 -v 0.036770 0.009110 0.089105 -vn -1.806231 3.560471 2.486061 -v 0.037719 0.009110 0.089527 -vn -2.661244 3.560470 1.536474 -v 0.038415 0.009110 0.090300 -vn -3.056107 3.560474 0.321214 -v 0.038736 0.009110 0.091289 -vn 3.106582 2.889303 -0.250067 -v 0.040775 0.009110 0.105957 -vn -2.965805 2.889301 0.957800 -v 0.037583 0.009110 0.106592 -vn 3.070662 2.889305 0.533316 -v 0.040701 0.009110 0.107565 -vn -2.632826 2.889299 1.667816 -v 0.038266 0.009110 0.108050 -vn 1.419874 2.889299 -2.774408 -v 0.024672 0.009110 0.081856 -vn -2.019859 2.889300 2.373511 -v 0.022863 0.009110 0.084563 -vn 0.682369 2.889304 -3.041013 -v 0.023157 0.009110 0.081309 -vn -2.548398 2.889304 1.794171 -v 0.021778 0.009110 0.083373 -vn -2.922539 3.560475 -0.949594 -v 0.038628 0.009110 0.092323 -vn 1.806231 3.560471 2.486061 -v 0.034781 0.009110 0.089527 -vn 0.803085 3.455759 2.997185 -v 0.035730 0.009110 0.089105 -vn 0.000000 3.351587 3.124383 -v 0.036250 0.009110 0.089050 -vn 1.794171 2.889303 -2.548398 -v 0.028073 0.009110 0.077078 -vn -3.041012 2.889303 0.682371 -v 0.026009 0.009110 0.078457 -vn 2.373511 2.889301 -2.019859 -v 0.029263 0.009110 0.078163 -vn -2.774409 2.889302 1.419873 -v 0.026556 0.009110 0.079972 -# 287 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 7//7 -f 8//8 9//9 4//4 -f 5//5 10//10 11//11 -f 5//5 11//11 12//12 -f 12//12 11//11 13//13 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 14//14 15//15 16//16 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 24//24 25//25 26//26 -f 26//26 25//25 27//27 -f 26//26 27//27 28//28 -f 29//29 30//30 31//31 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 34//34 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 38//38 -f 39//39 40//40 31//31 -f 31//31 40//40 41//41 -f 31//31 41//41 42//42 -f 31//31 43//43 44//44 -f 44//44 43//43 45//45 -f 44//44 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 48//48 -f 49//49 50//50 31//31 -f 31//31 50//50 51//51 -f 52//52 5//5 17//17 -f 17//17 5//5 7//7 -f 17//17 7//7 18//18 -f 28//28 39//39 26//26 -f 26//26 39//39 31//31 -f 26//26 31//31 53//53 -f 53//53 31//31 30//30 -f 54//54 55//55 56//56 -f 56//56 55//55 57//57 -f 56//56 57//57 58//58 -f 58//58 57//57 59//59 -f 58//58 59//59 60//60 -f 60//60 59//59 61//61 -f 60//60 61//61 5//5 -f 5//5 61//61 38//38 -f 5//5 38//38 6//6 -f 6//6 38//38 37//37 -f 8//8 4//4 62//62 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 42//42 -f 42//42 68//68 69//69 -f 42//42 69//69 31//31 -f 31//31 69//69 70//70 -f 31//31 70//70 43//43 -f 71//71 10//10 72//72 -f 72//72 10//10 5//5 -f 72//72 5//5 73//73 -f 73//73 5//5 52//52 -f 73//73 52//52 74//74 -f 74//74 52//52 75//75 -f 74//74 75//75 76//76 -f 76//76 75//75 77//77 -f 76//76 77//77 78//78 -f 78//78 77//77 79//79 -f 80//80 81//81 82//82 -f 82//82 81//81 83//83 -f 82//82 83//83 84//84 -f 71//71 85//85 10//10 -f 10//10 85//85 86//86 -f 10//10 86//86 2//2 -f 2//2 86//86 81//81 -f 2//2 81//81 4//4 -f 4//4 81//81 80//80 -f 4//4 80//80 62//62 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 92//92 93//93 94//94 -f 94//94 93//93 95//95 -f 94//94 95//95 96//96 -f 96//96 95//95 97//97 -f 96//96 97//97 51//51 -f 51//51 97//97 98//98 -f 51//51 98//98 31//31 -f 31//31 98//98 99//99 -f 100//100 101//101 31//31 -f 31//31 101//101 102//102 -f 31//31 102//102 103//103 -f 104//104 105//105 106//106 -f 106//106 105//105 107//107 -f 106//106 107//107 108//108 -f 108//108 107//107 109//109 -f 108//108 109//109 49//49 -f 49//49 109//109 110//110 -f 49//49 110//110 50//50 -f 50//50 110//110 111//111 -f 50//50 111//111 112//112 -f 112//112 111//111 113//113 -f 112//112 113//113 114//114 -f 114//114 113//113 115//115 -f 114//114 115//115 116//116 -f 116//116 115//115 117//117 -f 118//118 119//119 120//120 -f 120//120 119//119 121//121 -f 120//120 121//121 122//122 -f 122//122 121//121 123//123 -f 122//122 123//123 99//99 -f 99//99 123//123 82//82 -f 99//99 82//82 31//31 -f 31//31 82//82 84//84 -f 31//31 84//84 100//100 -f 103//103 124//124 31//31 -f 31//31 124//124 125//125 -f 31//31 125//125 29//29 -f 29//29 125//125 126//126 -f 29//29 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 131//131 -f 124//124 132//132 125//125 -f 125//125 132//132 133//133 -f 125//125 133//133 73//73 -f 73//73 133//133 134//134 -f 73//73 134//134 72//72 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 40//40 -f 40//40 140//140 141//141 -f 40//40 141//141 41//41 -f 41//41 141//141 142//142 -f 41//41 142//142 87//87 -f 87//87 142//142 143//143 -f 87//87 143//143 88//88 -f 144//144 145//145 24//24 -f 24//24 145//145 25//25 -f 146//146 147//147 135//135 -f 135//135 147//147 136//136 -f 148//148 149//149 130//130 -f 130//130 149//149 131//131 -f 150//150 151//151 79//79 -f 79//79 151//151 78//78 -f 152//152 153//153 47//47 -f 47//47 153//153 48//48 -f 154//154 155//155 104//104 -f 104//104 155//155 105//105 -f 156//156 157//157 63//63 -f 63//63 157//157 64//64 -f 158//158 159//159 90//90 -f 90//90 159//159 91//91 -f 160//160 161//161 117//117 -f 117//117 161//161 116//116 -f 162//162 163//163 92//92 -f 92//92 163//163 93//93 -f 164//164 165//165 118//118 -f 118//118 165//165 119//119 -f 166//166 167//167 15//15 -f 15//15 167//167 16//16 -f 168//168 169//169 54//54 -f 54//54 169//169 55//55 -f 170//170 171//171 32//32 -f 32//32 171//171 33//33 -f 172//172 173//173 9//9 -f 9//9 173//173 4//4 -f 155//155 154//154 174//174 -f 174//174 154//154 175//175 -f 174//174 175//175 176//176 -f 177//177 178//178 179//179 -f 180//180 181//181 182//182 -f 183//183 184//184 185//185 -f 186//186 187//187 179//179 -f 179//179 187//187 188//188 -f 176//176 186//186 174//174 -f 174//174 186//186 179//179 -f 174//174 179//179 189//189 -f 189//189 179//179 178//178 -f 157//157 156//156 190//190 -f 182//182 191//191 180//180 -f 180//180 191//191 192//192 -f 180//180 192//192 193//193 -f 193//193 192//192 149//149 -f 193//193 149//149 148//148 -f 181//181 194//194 185//185 -f 185//185 184//184 195//195 -f 195//195 184//184 196//196 -f 195//195 196//196 197//197 -f 197//197 196//196 198//198 -f 197//197 198//198 199//199 -f 199//199 198//198 171//171 -f 199//199 171//171 170//170 -f 157//157 190//190 200//200 -f 200//200 190//190 201//201 -f 200//200 201//201 202//202 -f 202//202 201//201 188//188 -f 202//202 188//188 203//203 -f 203//203 188//188 187//187 -f 203//203 187//187 204//204 -f 204//204 187//187 205//205 -f 204//204 205//205 206//206 -f 206//206 205//205 207//207 -f 206//206 207//207 208//208 -f 208//208 207//207 153//153 -f 208//208 153//153 152//152 -f 209//209 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 213//213 212//212 214//214 -f 213//213 214//214 215//215 -f 215//215 214//214 159//159 -f 215//215 159//159 158//158 -f 216//216 217//217 218//218 -f 216//216 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 165//165 -f 221//221 165//165 164//164 -f 222//222 217//217 223//223 -f 223//223 217//217 216//216 -f 223//223 216//216 224//224 -f 224//224 216//216 225//225 -f 226//226 227//227 228//228 -f 181//181 185//185 182//182 -f 182//182 185//185 229//229 -f 182//182 229//229 230//230 -f 169//169 168//168 231//231 -f 231//231 168//168 229//229 -f 231//231 229//229 232//232 -f 232//232 229//229 185//185 -f 167//167 166//166 233//233 -f 233//233 166//166 234//234 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 223//223 -f 223//223 236//236 237//237 -f 223//223 237//237 222//222 -f 222//222 237//237 238//238 -f 222//222 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 241//241 -f 241//241 240//240 242//242 -f 241//241 242//242 172//172 -f 172//172 242//242 173//173 -f 151//151 150//150 243//243 -f 243//243 150//150 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 194//194 -f 194//194 246//246 247//247 -f 194//194 247//247 185//185 -f 185//185 247//247 248//248 -f 185//185 248//248 183//183 -f 183//183 248//248 249//249 -f 183//183 249//249 250//250 -f 250//250 249//249 251//251 -f 250//250 251//251 252//252 -f 252//252 251//251 253//253 -f 252//252 253//253 254//254 -f 147//147 146//146 255//255 -f 255//255 146//146 256//256 -f 255//255 256//256 257//257 -f 257//257 256//256 258//258 -f 257//257 258//258 209//209 -f 209//209 258//258 179//179 -f 209//209 179//179 210//210 -f 210//210 179//179 188//188 -f 259//259 260//260 179//179 -f 179//179 260//260 261//261 -f 179//179 261//261 262//262 -f 263//263 264//264 265//265 -f 265//265 264//264 266//266 -f 265//265 266//266 267//267 -f 268//268 269//269 224//224 -f 224//224 269//269 270//270 -f 224//224 270//270 271//271 -f 228//228 260//260 226//226 -f 226//226 260//260 259//259 -f 226//226 259//259 272//272 -f 272//272 259//259 273//273 -f 272//272 273//273 274//274 -f 274//274 273//273 275//275 -f 274//274 275//275 144//144 -f 144//144 275//275 145//145 -f 262//262 263//263 179//179 -f 179//179 263//263 265//265 -f 179//179 265//265 177//177 -f 177//177 265//265 276//276 -f 177//177 276//276 277//277 -f 277//277 276//276 278//278 -f 277//277 278//278 279//279 -f 279//279 278//278 161//161 -f 279//279 161//161 160//160 -f 230//230 224//224 182//182 -f 182//182 224//224 271//271 -f 182//182 271//271 226//226 -f 226//226 271//271 280//280 -f 226//226 280//280 227//227 -f 266//266 281//281 267//267 -f 267//267 281//281 282//282 -f 267//267 282//282 283//283 -f 163//163 162//162 284//284 -f 284//284 162//162 285//285 -f 284//284 285//285 286//286 -f 286//286 285//285 287//287 -f 286//286 287//287 225//225 -f 225//225 287//287 267//267 -f 225//225 267//267 224//224 -f 224//224 267//267 283//283 -f 224//224 283//283 268//268 -f 254//254 253//253 22//22 -f 22//22 253//253 23//23 -f 33//33 171//171 198//198 -f 33//33 198//198 35//35 -f 35//35 198//198 196//196 -f 35//35 196//196 37//37 -f 37//37 196//196 184//184 -f 37//37 184//184 6//6 -f 7//7 183//183 250//250 -f 7//7 250//250 18//18 -f 18//18 250//250 252//252 -f 18//18 252//252 20//20 -f 20//20 252//252 254//254 -f 20//20 254//254 22//22 -f 184//184 183//183 6//6 -f 6//6 183//183 7//7 -f 23//23 253//253 251//251 -f 23//23 251//251 21//21 -f 21//21 251//251 249//249 -f 21//21 249//249 19//19 -f 19//19 249//249 248//248 -f 19//19 248//248 17//17 -f 52//52 247//247 246//246 -f 52//52 246//246 75//75 -f 75//75 246//246 244//244 -f 75//75 244//244 77//77 -f 77//77 244//244 150//150 -f 77//77 150//150 79//79 -f 248//248 247//247 17//17 -f 17//17 247//247 52//52 -f 119//119 165//165 220//220 -f 119//119 220//220 121//121 -f 121//121 220//220 218//218 -f 121//121 218//218 123//123 -f 123//123 218//218 217//217 -f 123//123 217//217 82//82 -f 80//80 222//222 239//239 -f 80//80 239//239 62//62 -f 62//62 239//239 241//241 -f 62//62 241//241 8//8 -f 8//8 241//241 172//172 -f 8//8 172//172 9//9 -f 217//217 222//222 82//82 -f 82//82 222//222 80//80 -f 4//4 173//173 242//242 -f 4//4 242//242 3//3 -f 3//3 242//242 240//240 -f 3//3 240//240 1//1 -f 1//1 240//240 238//238 -f 1//1 238//238 2//2 -f 10//10 237//237 236//236 -f 10//10 236//236 11//11 -f 11//11 236//236 234//234 -f 11//11 234//234 13//13 -f 13//13 234//234 166//166 -f 13//13 166//166 15//15 -f 238//238 237//237 2//2 -f 2//2 237//237 10//10 -f 55//55 169//169 231//231 -f 55//55 231//231 57//57 -f 57//57 231//231 232//232 -f 57//57 232//232 59//59 -f 59//59 232//232 185//185 -f 59//59 185//185 61//61 -f 38//38 195//195 197//197 -f 38//38 197//197 36//36 -f 36//36 197//197 199//199 -f 36//36 199//199 34//34 -f 34//34 199//199 170//170 -f 34//34 170//170 32//32 -f 185//185 195//195 61//61 -f 61//61 195//195 38//38 -f 16//16 167//167 233//233 -f 16//16 233//233 14//14 -f 14//14 233//233 235//235 -f 14//14 235//235 12//12 -f 12//12 235//235 223//223 -f 12//12 223//223 5//5 -f 60//60 224//224 230//230 -f 60//60 230//230 58//58 -f 58//58 230//230 229//229 -f 58//58 229//229 56//56 -f 56//56 229//229 168//168 -f 56//56 168//168 54//54 -f 223//223 224//224 5//5 -f 5//5 224//224 60//60 -f 105//105 155//155 174//174 -f 105//105 174//174 107//107 -f 107//107 174//174 189//189 -f 107//107 189//189 109//109 -f 109//109 189//189 178//178 -f 109//109 178//178 110//110 -f 111//111 177//177 277//277 -f 111//111 277//277 113//113 -f 113//113 277//277 279//279 -f 113//113 279//279 115//115 -f 115//115 279//279 160//160 -f 115//115 160//160 117//117 -f 178//178 177//177 110//110 -f 110//110 177//177 111//111 -f 93//93 163//163 284//284 -f 93//93 284//284 95//95 -f 95//95 284//284 286//286 -f 95//95 286//286 97//97 -f 97//97 286//286 225//225 -f 97//97 225//225 98//98 -f 99//99 216//216 219//219 -f 99//99 219//219 122//122 -f 122//122 219//219 221//221 -f 122//122 221//221 120//120 -f 120//120 221//221 164//164 -f 120//120 164//164 118//118 -f 225//225 216//216 98//98 -f 98//98 216//216 99//99 -f 116//116 161//161 278//278 -f 116//116 278//278 114//114 -f 114//114 278//278 276//276 -f 114//114 276//276 112//112 -f 112//112 276//276 265//265 -f 112//112 265//265 50//50 -f 51//51 267//267 287//287 -f 51//51 287//287 96//96 -f 96//96 287//287 285//285 -f 96//96 285//285 94//94 -f 94//94 285//285 162//162 -f 94//94 162//162 92//92 -f 265//265 267//267 50//50 -f 50//50 267//267 51//51 -f 91//91 159//159 214//214 -f 91//91 214//214 89//89 -f 89//89 214//214 212//212 -f 89//89 212//212 87//87 -f 87//87 212//212 210//210 -f 87//87 210//210 41//41 -f 42//42 188//188 201//201 -f 42//42 201//201 67//67 -f 67//67 201//201 190//190 -f 67//67 190//190 65//65 -f 65//65 190//190 156//156 -f 65//65 156//156 63//63 -f 210//210 188//188 41//41 -f 41//41 188//188 42//42 -f 136//136 147//147 255//255 -f 136//136 255//255 138//138 -f 138//138 255//255 257//257 -f 138//138 257//257 140//140 -f 140//140 257//257 209//209 -f 140//140 209//209 141//141 -f 142//142 211//211 213//213 -f 142//142 213//213 143//143 -f 143//143 213//213 215//215 -f 143//143 215//215 88//88 -f 88//88 215//215 158//158 -f 88//88 158//158 90//90 -f 209//209 211//211 141//141 -f 141//141 211//211 142//142 -f 64//64 157//157 200//200 -f 64//64 200//200 66//66 -f 66//66 200//200 202//202 -f 66//66 202//202 68//68 -f 68//68 202//202 203//203 -f 68//68 203//203 69//69 -f 70//70 204//204 206//206 -f 70//70 206//206 43//43 -f 43//43 206//206 208//208 -f 43//43 208//208 45//45 -f 45//45 208//208 152//152 -f 45//45 152//152 47//47 -f 203//203 204//204 69//69 -f 69//69 204//204 70//70 -f 48//48 153//153 207//207 -f 48//48 207//207 46//46 -f 46//46 207//207 205//205 -f 46//46 205//205 44//44 -f 44//44 205//205 187//187 -f 44//44 187//187 31//31 -f 49//49 186//186 176//176 -f 49//49 176//176 108//108 -f 108//108 176//176 175//175 -f 108//108 175//175 106//106 -f 106//106 175//175 154//154 -f 106//106 154//154 104//104 -f 187//187 186//186 31//31 -f 31//31 186//186 49//49 -f 78//78 151//151 243//243 -f 78//78 243//243 76//76 -f 76//76 243//243 245//245 -f 76//76 245//245 74//74 -f 74//74 245//245 194//194 -f 74//74 194//194 73//73 -f 125//125 181//181 180//180 -f 125//125 180//180 126//126 -f 126//126 180//180 193//193 -f 126//126 193//193 128//128 -f 128//128 193//193 148//148 -f 128//128 148//148 130//130 -f 194//194 181//181 73//73 -f 73//73 181//181 125//125 -f 131//131 149//149 192//192 -f 131//131 192//192 129//129 -f 129//129 192//192 191//191 -f 129//129 191//191 127//127 -f 127//127 191//191 182//182 -f 127//127 182//182 29//29 -f 30//30 226//226 272//272 -f 30//30 272//272 53//53 -f 53//53 272//272 274//274 -f 53//53 274//274 26//26 -f 26//26 274//274 144//144 -f 26//26 144//144 24//24 -f 182//182 226//226 29//29 -f 29//29 226//226 30//30 -f 25//25 145//145 275//275 -f 25//25 275//275 27//27 -f 27//27 275//275 273//273 -f 27//27 273//273 28//28 -f 28//28 273//273 259//259 -f 28//28 259//259 39//39 -f 40//40 179//179 258//258 -f 40//40 258//258 139//139 -f 139//139 258//258 256//256 -f 139//139 256//256 137//137 -f 137//137 256//256 146//146 -f 137//137 146//146 135//135 -f 259//259 179//179 39//39 -f 39//39 179//179 40//40 -f 269//269 268//268 81//81 -f 81//81 268//268 283//283 -f 81//81 283//283 83//83 -f 83//83 283//283 282//282 -f 83//83 282//282 84//84 -f 84//84 282//282 281//281 -f 84//84 281//281 100//100 -f 100//100 281//281 266//266 -f 100//100 266//266 101//101 -f 101//101 266//266 264//264 -f 101//101 264//264 102//102 -f 102//102 264//264 263//263 -f 102//102 263//263 103//103 -f 103//103 263//263 262//262 -f 103//103 262//262 124//124 -f 124//124 262//262 261//261 -f 124//124 261//261 132//132 -f 132//132 261//261 260//260 -f 132//132 260//260 133//133 -f 133//133 260//260 228//228 -f 133//133 228//228 134//134 -f 134//134 228//228 227//227 -f 134//134 227//227 72//72 -f 72//72 227//227 280//280 -f 72//72 280//280 71//71 -f 71//71 280//280 271//271 -f 71//71 271//271 85//85 -f 85//85 271//271 270//270 -f 85//85 270//270 86//86 -f 86//86 270//270 269//269 -f 86//86 269//269 81//81 -# 574 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/mushroom.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/mushroom.obj deleted file mode 100644 index bb865e18b..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/mushroom.obj +++ /dev/null @@ -1,8992 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object mushroom.obj -# -# Vertices: 2245 -# Faces: 4486 -# -#### -vn -0.080629 0.046552 -0.995657 -v 0.007361 -0.004250 0.006937 -vn -0.071323 0.059847 -0.995656 -v 0.006511 -0.005464 0.006937 -vn 0.046552 -0.080630 -0.995656 -v -0.004250 0.007361 0.006937 -vn 0.059845 -0.071321 -0.995657 -v -0.005464 0.006511 0.006937 -vn 0.087488 -0.031843 -0.995657 -v -0.007987 0.002907 0.006937 -vn 0.080630 -0.046552 -0.995656 -v -0.007361 0.004250 0.006937 -vn 0.071323 -0.059847 -0.995656 -v -0.006511 0.005464 0.006937 -vn -0.059845 0.071321 -0.995657 -v 0.005464 -0.006511 0.006937 -vn 0.046552 0.080630 -0.995656 -v -0.004250 -0.007361 0.006937 -vn 0.059845 0.071321 -0.995657 -v -0.005464 -0.006511 0.006937 -vn 0.071323 0.059847 -0.995656 -v -0.006511 -0.005464 0.006937 -vn 0.080630 0.046551 -0.995656 -v -0.007361 -0.004250 0.006937 -vn 0.087488 0.031843 -0.995656 -v -0.007987 -0.002907 0.006937 -vn 0.091688 0.016167 -0.995656 -v -0.008371 -0.001476 0.006937 -vn -0.087492 0.031844 -0.995656 -v 0.007987 -0.002907 0.006937 -vn 0.031843 -0.087488 -0.995656 -v -0.002907 0.007987 0.006937 -vn 0.016167 -0.091689 -0.995656 -v -0.001476 0.008371 0.006937 -vn 0.093102 -0.000000 -0.995657 -v -0.008500 -0.000000 0.006937 -vn 0.091688 -0.016167 -0.995656 -v -0.008371 0.001476 0.006937 -vn -0.046552 0.080630 -0.995656 -v 0.004250 -0.007361 0.006937 -vn -0.031843 0.087488 -0.995656 -v 0.002907 -0.007987 0.006937 -vn -0.016167 0.091689 -0.995656 -v 0.001476 -0.008371 0.006937 -vn -0.000000 0.093104 -0.995656 -v 0.000000 -0.008500 0.006937 -vn 0.016167 0.091689 -0.995656 -v -0.001476 -0.008371 0.006937 -vn 0.031843 0.087489 -0.995656 -v -0.002907 -0.007987 0.006937 -vn 0.000000 -0.093104 -0.995656 -v 0.000000 0.008500 0.006937 -vn -0.016167 -0.091689 -0.995656 -v 0.001476 0.008371 0.006937 -vn -0.031843 -0.087488 -0.995656 -v 0.002907 0.007987 0.006937 -vn -0.046552 -0.080630 -0.995656 -v 0.004250 0.007361 0.006937 -vn -0.059845 -0.071321 -0.995657 -v 0.005464 0.006511 0.006937 -vn -0.071323 -0.059847 -0.995656 -v 0.006511 0.005464 0.006937 -vn -0.091688 -0.016167 -0.995657 -v 0.008371 0.001476 0.006937 -vn -0.091689 0.016167 -0.995657 -v 0.008371 -0.001476 0.006937 -vn -0.093102 0.000000 -0.995657 -v 0.008500 -0.000000 0.006937 -vn -0.080630 -0.046551 -0.995657 -v 0.007361 0.004250 0.006937 -vn -0.087492 -0.031845 -0.995656 -v 0.007987 0.002907 0.006937 -vn 0.000000 -0.000000 1.000000 -v 0.000000 -0.000000 0.008437 -vn -0.000341 0.000000 1.000000 -v 0.004905 -0.000000 0.008563 -vn -0.000339 -0.000040 1.000000 -v 0.004870 0.000580 0.008563 -vn -0.000320 -0.000119 1.000000 -v 0.004598 0.001708 0.008563 -vn -0.000304 -0.000156 1.000000 -v 0.004363 0.002240 0.008563 -vn -0.000332 -0.000080 1.000000 -v 0.004767 0.001152 0.008563 -vn -0.000258 -0.000223 1.000000 -v 0.003715 0.003202 0.008563 -vn -0.000230 -0.000252 1.000000 -v 0.003310 0.003619 0.008563 -vn -0.000283 -0.000191 1.000000 -v 0.004068 0.002740 0.008563 -vn -0.000165 -0.000299 1.000000 -v 0.002368 0.004295 0.008563 -vn -0.000128 -0.000316 1.000000 -v 0.001843 0.004545 0.008563 -vn -0.000199 -0.000277 1.000000 -v 0.002859 0.003985 0.008563 -vn -0.000050 -0.000337 1.000000 -v 0.000724 0.004851 0.008563 -vn -0.000010 -0.000341 1.000000 -v 0.000145 0.004902 0.008563 -vn -0.000090 -0.000329 1.000000 -v 0.001293 0.004731 0.008563 -vn 0.000070 -0.000334 1.000000 -v -0.001010 0.004799 0.008563 -vn 0.000109 -0.000323 1.000000 -v -0.001571 0.004646 0.008563 -vn 0.000030 -0.000340 1.000000 -v -0.000435 0.004885 0.008563 -vn 0.000182 -0.000288 1.000000 -v -0.002618 0.004147 0.008563 -vn 0.000215 -0.000265 1.000000 -v -0.003090 0.003808 0.008563 -vn 0.000147 -0.000308 1.000000 -v -0.002109 0.004428 0.008563 -vn 0.000271 -0.000207 1.000000 -v -0.003898 0.002976 0.008563 -vn 0.000294 -0.000174 1.000000 -v -0.004223 0.002494 0.008563 -vn 0.000245 -0.000238 1.000000 -v -0.003519 0.003416 0.008563 -vn 0.000326 -0.000100 1.000000 -v -0.004691 0.001432 0.008563 -vn 0.000336 -0.000060 1.000000 -v -0.004827 0.000868 0.008563 -vn 0.000312 -0.000138 1.000000 -v -0.004488 0.001977 0.008563 -vn 0.000341 0.000020 1.000000 -v -0.004896 -0.000291 0.008563 -vn 0.000336 0.000060 1.000000 -v -0.004827 -0.000868 0.008563 -vn 0.000341 -0.000020 1.000000 -v -0.004896 0.000291 0.008563 -vn 0.000312 0.000138 1.000000 -v -0.004488 -0.001977 0.008563 -vn 0.000294 0.000174 1.000000 -v -0.004223 -0.002494 0.008563 -vn 0.000326 0.000100 1.000000 -v -0.004691 -0.001432 0.008563 -vn 0.000245 0.000238 1.000000 -v -0.003519 -0.003416 0.008563 -vn 0.000215 0.000265 1.000000 -v -0.003090 -0.003808 0.008563 -vn 0.000271 0.000207 1.000000 -v -0.003898 -0.002976 0.008563 -vn 0.000147 0.000308 1.000000 -v -0.002109 -0.004428 0.008563 -vn 0.000109 0.000323 1.000000 -v -0.001571 -0.004646 0.008563 -vn 0.000182 0.000288 1.000000 -v -0.002618 -0.004147 0.008563 -vn 0.000030 0.000340 1.000000 -v -0.000435 -0.004885 0.008563 -vn -0.000010 0.000341 1.000000 -v 0.000145 -0.004902 0.008563 -vn 0.000070 0.000334 1.000000 -v -0.001010 -0.004799 0.008563 -vn -0.000090 0.000329 1.000000 -v 0.001293 -0.004731 0.008563 -vn -0.000128 0.000316 1.000000 -v 0.001843 -0.004545 0.008563 -vn -0.000050 0.000337 1.000000 -v 0.000724 -0.004851 0.008563 -vn -0.000199 0.000277 1.000000 -v 0.002859 -0.003985 0.008563 -vn -0.000230 0.000252 1.000000 -v 0.003310 -0.003619 0.008563 -vn -0.000165 0.000299 1.000000 -v 0.002368 -0.004295 0.008563 -vn -0.000283 0.000191 1.000000 -v 0.004068 -0.002740 0.008563 -vn -0.000304 0.000156 1.000000 -v 0.004363 -0.002240 0.008563 -vn -0.000258 0.000223 1.000000 -v 0.003715 -0.003202 0.008563 -vn -0.000332 0.000080 1.000000 -v 0.004767 -0.001152 0.008563 -vn -0.000339 0.000040 1.000000 -v 0.004870 -0.000580 0.008563 -vn -0.000320 0.000119 1.000000 -v 0.004598 -0.001708 0.008563 -vn 0.096945 0.011547 0.995223 -v 0.014599 0.001739 0.008095 -vn 0.252562 0.030082 0.967113 -v 0.019435 0.002315 0.007500 -vn 0.094899 0.022932 0.995223 -v 0.014291 0.003453 0.008095 -vn 0.247233 0.059743 0.967113 -v 0.019025 0.004597 0.007500 -vn 0.091521 0.033995 0.995223 -v 0.013783 0.005119 0.008095 -vn 0.238430 0.088564 0.967113 -v 0.018348 0.006815 0.007500 -vn 0.086858 0.044581 0.995223 -v 0.013080 0.006714 0.008095 -vn 0.226284 0.116144 0.967112 -v 0.017413 0.008937 0.007500 -vn 0.080975 0.054541 0.995223 -v 0.012194 0.008214 0.008095 -vn 0.210957 0.142090 0.967113 -v 0.016234 0.010934 0.007500 -vn 0.073956 0.063735 0.995223 -v 0.011137 0.009598 0.008095 -vn 0.192670 0.166043 0.967113 -v 0.014827 0.012777 0.007500 -vn 0.065899 0.072035 0.995223 -v 0.009924 0.010848 0.008095 -vn 0.171680 0.187666 0.967113 -v 0.013211 0.014441 0.007500 -vn 0.056916 0.079324 0.995223 -v 0.008571 0.011946 0.008095 -vn 0.148280 0.206655 0.967113 -v 0.011410 0.015903 0.007500 -vn 0.047135 0.085498 0.995223 -v 0.007098 0.012876 0.008095 -vn 0.122798 0.222743 0.967112 -v 0.009450 0.017141 0.007500 -vn 0.036692 0.090473 0.995223 -v 0.005526 0.013625 0.008095 -vn 0.095591 0.235702 0.967113 -v 0.007356 0.018138 0.007500 -vn 0.025734 0.094178 0.995223 -v 0.003875 0.014183 0.008095 -vn 0.067042 0.245351 0.967113 -v 0.005159 0.018881 0.007500 -vn 0.014415 0.096560 0.995223 -v 0.002171 0.014542 0.008095 -vn 0.037554 0.251560 0.967113 -v 0.002890 0.019358 0.007500 -vn 0.002893 0.097588 0.995223 -v 0.000436 0.014696 0.008095 -vn 0.007537 0.254235 0.967113 -v 0.000580 0.019564 0.007500 -vn -0.008669 0.097245 0.995223 -v -0.001306 0.014645 0.008095 -vn -0.022585 0.253343 0.967113 -v -0.001738 0.019495 0.007500 -vn -0.020110 0.095537 0.995223 -v -0.003028 0.014387 0.008095 -vn -0.052390 0.248893 0.967113 -v -0.004032 0.019153 0.007500 -vn -0.031268 0.092488 0.995223 -v -0.004709 0.013928 0.008095 -vn -0.081460 0.240950 0.967113 -v -0.006269 0.018542 0.007500 -vn -0.041987 0.088141 0.995223 -v -0.006323 0.013274 0.008095 -vn -0.109387 0.229626 0.967112 -v -0.008418 0.017670 0.007500 -vn -0.052117 0.082556 0.995223 -v -0.007849 0.012433 0.008095 -vn -0.135778 0.215076 0.967113 -v -0.010448 0.016551 0.007500 -vn -0.061516 0.075812 0.995223 -v -0.009264 0.011417 0.008095 -vn -0.160263 0.197508 0.967112 -v -0.012333 0.015199 0.007500 -vn -0.070051 0.068005 0.995223 -v -0.010549 0.010241 0.008095 -vn -0.182497 0.177167 0.967112 -v -0.014044 0.013633 0.007500 -vn -0.077602 0.059242 0.995223 -v -0.011686 0.008922 0.008095 -vn -0.202167 0.154337 0.967114 -v -0.015557 0.011877 0.007500 -vn -0.084064 0.049648 0.995223 -v -0.012660 0.007477 0.008095 -vn -0.219002 0.129342 0.967114 -v -0.016853 0.009953 0.007500 -vn -0.089346 0.039357 0.995223 -v -0.013455 0.005927 0.008095 -vn -0.232764 0.102533 0.967113 -v -0.017912 0.007890 0.007500 -vn -0.093374 0.028514 0.995223 -v -0.014062 0.004294 0.008095 -vn -0.243256 0.074284 0.967113 -v -0.018719 0.005716 0.007500 -vn -0.096091 0.017270 0.995223 -v -0.014471 0.002601 0.008095 -vn -0.250341 0.044992 0.967112 -v -0.019264 0.003462 0.007500 -vn -0.097459 0.005784 0.995223 -v -0.014677 0.000871 0.008095 -vn -0.253907 0.015068 0.967111 -v -0.019538 0.001159 0.007500 -vn -0.097459 -0.005784 0.995223 -v -0.014677 -0.000871 0.008095 -vn -0.253907 -0.015068 0.967111 -v -0.019538 -0.001160 0.007500 -vn -0.096091 -0.017270 0.995223 -v -0.014471 -0.002601 0.008095 -vn -0.250341 -0.044993 0.967112 -v -0.019264 -0.003462 0.007500 -vn -0.093374 -0.028514 0.995223 -v -0.014062 -0.004294 0.008095 -vn -0.243257 -0.074284 0.967113 -v -0.018719 -0.005716 0.007500 -vn -0.089346 -0.039357 0.995223 -v -0.013455 -0.005927 0.008095 -vn -0.232764 -0.102533 0.967113 -v -0.017912 -0.007890 0.007500 -vn -0.084064 -0.049648 0.995223 -v -0.012660 -0.007477 0.008095 -vn -0.219002 -0.129342 0.967114 -v -0.016853 -0.009953 0.007500 -vn -0.077602 -0.059242 0.995223 -v -0.011686 -0.008922 0.008095 -vn -0.202167 -0.154336 0.967114 -v -0.015557 -0.011877 0.007500 -vn -0.070051 -0.068005 0.995223 -v -0.010549 -0.010241 0.008095 -vn -0.182497 -0.177167 0.967113 -v -0.014044 -0.013633 0.007500 -vn -0.061516 -0.075812 0.995223 -v -0.009264 -0.011417 0.008095 -vn -0.160263 -0.197508 0.967112 -v -0.012333 -0.015199 0.007500 -vn -0.052117 -0.082556 0.995223 -v -0.007849 -0.012433 0.008095 -vn -0.135778 -0.215076 0.967113 -v -0.010448 -0.016551 0.007500 -vn -0.041987 -0.088141 0.995223 -v -0.006323 -0.013274 0.008095 -vn -0.109387 -0.229626 0.967112 -v -0.008418 -0.017670 0.007500 -vn -0.031268 -0.092488 0.995223 -v -0.004709 -0.013928 0.008095 -vn -0.081460 -0.240950 0.967113 -v -0.006269 -0.018542 0.007500 -vn -0.020110 -0.095537 0.995223 -v -0.003028 -0.014387 0.008095 -vn -0.052390 -0.248893 0.967113 -v -0.004032 -0.019153 0.007500 -vn -0.008669 -0.097245 0.995223 -v -0.001306 -0.014645 0.008095 -vn -0.022585 -0.253343 0.967113 -v -0.001738 -0.019495 0.007500 -vn 0.002893 -0.097588 0.995223 -v 0.000436 -0.014696 0.008095 -vn 0.007537 -0.254235 0.967113 -v 0.000580 -0.019564 0.007500 -vn 0.014415 -0.096560 0.995223 -v 0.002171 -0.014542 0.008095 -vn 0.037554 -0.251560 0.967113 -v 0.002890 -0.019358 0.007500 -vn 0.025734 -0.094178 0.995223 -v 0.003875 -0.014183 0.008095 -vn 0.067042 -0.245351 0.967113 -v 0.005159 -0.018881 0.007500 -vn 0.036692 -0.090473 0.995223 -v 0.005526 -0.013625 0.008095 -vn 0.095591 -0.235701 0.967113 -v 0.007356 -0.018138 0.007500 -vn 0.047135 -0.085498 0.995223 -v 0.007098 -0.012876 0.008095 -vn 0.122798 -0.222743 0.967112 -v 0.009450 -0.017141 0.007500 -vn 0.056917 -0.079324 0.995223 -v 0.008571 -0.011946 0.008095 -vn 0.148280 -0.206655 0.967113 -v 0.011410 -0.015903 0.007500 -vn 0.065899 -0.072035 0.995223 -v 0.009924 -0.010848 0.008095 -vn 0.171681 -0.187666 0.967113 -v 0.013211 -0.014441 0.007500 -vn 0.073956 -0.063735 0.995223 -v 0.011137 -0.009598 0.008095 -vn 0.192670 -0.166043 0.967113 -v 0.014827 -0.012777 0.007500 -vn 0.080975 -0.054541 0.995223 -v 0.012194 -0.008214 0.008095 -vn 0.210957 -0.142090 0.967113 -v 0.016234 -0.010934 0.007500 -vn 0.086858 -0.044581 0.995223 -v 0.013080 -0.006714 0.008095 -vn 0.226284 -0.116143 0.967112 -v 0.017413 -0.008937 0.007500 -vn 0.091521 -0.033995 0.995223 -v 0.013783 -0.005119 0.008095 -vn 0.238430 -0.088564 0.967113 -v 0.018348 -0.006815 0.007500 -vn 0.094899 -0.022932 0.995223 -v 0.014291 -0.003453 0.008095 -vn 0.247233 -0.059743 0.967113 -v 0.019025 -0.004597 0.007500 -vn 0.096945 -0.011547 0.995223 -v 0.014599 -0.001739 0.008095 -vn 0.252562 -0.030083 0.967113 -v 0.019435 -0.002315 0.007500 -vn 0.097630 -0.000000 0.995223 -v 0.014703 -0.000000 0.008095 -vn 0.254350 0.000000 0.967112 -v 0.019573 -0.000000 0.007500 -vn 0.048704 -0.000000 0.998813 -v 0.009809 -0.000000 0.008449 -vn 0.048363 -0.005760 0.998813 -v 0.009740 -0.001160 0.008449 -vn 0.047342 -0.011440 0.998813 -v 0.009535 -0.002304 0.008449 -vn 0.045657 -0.016959 0.998813 -v 0.009195 -0.003416 0.008449 -vn 0.043330 -0.022240 0.998813 -v 0.008727 -0.004479 0.008449 -vn 0.040396 -0.027209 0.998813 -v 0.008136 -0.005480 0.008449 -vn 0.036894 -0.031795 0.998813 -v 0.007431 -0.006404 0.008449 -vn 0.032875 -0.035936 0.998813 -v 0.006621 -0.007238 0.008449 -vn 0.028394 -0.039572 0.998813 -v 0.005719 -0.007970 0.008449 -vn 0.023514 -0.042652 0.998813 -v 0.004736 -0.008590 0.008449 -vn 0.018304 -0.045134 0.998813 -v 0.003687 -0.009090 0.008449 -vn 0.012838 -0.046982 0.998813 -v 0.002586 -0.009462 0.008449 -vn 0.007191 -0.048171 0.998813 -v 0.001448 -0.009702 0.008449 -vn 0.001443 -0.048683 0.998813 -v 0.000291 -0.009805 0.008449 -vn -0.004325 -0.048512 0.998813 -v -0.000871 -0.009771 0.008449 -vn -0.010032 -0.047660 0.998813 -v -0.002021 -0.009599 0.008449 -vn -0.015599 -0.046139 0.998813 -v -0.003142 -0.009293 0.008449 -vn -0.020946 -0.043970 0.998813 -v -0.004219 -0.008856 0.008449 -vn -0.026000 -0.041184 0.998813 -v -0.005236 -0.008295 0.008449 -vn -0.030688 -0.037820 0.998813 -v -0.006181 -0.007617 0.008449 -vn -0.034946 -0.033925 0.998813 -v -0.007038 -0.006833 0.008449 -vn -0.038713 -0.029554 0.998813 -v -0.007797 -0.005952 0.008449 -vn -0.041937 -0.024768 0.998813 -v -0.008446 -0.004988 0.008449 -vn -0.044572 -0.019634 0.998813 -v -0.008977 -0.003954 0.008449 -vn -0.046581 -0.014224 0.998813 -v -0.009382 -0.002865 0.008449 -vn -0.047936 -0.008615 0.998813 -v -0.009655 -0.001735 0.008449 -vn -0.048619 -0.002885 0.998813 -v -0.009792 -0.000581 0.008449 -vn -0.048619 0.002885 0.998813 -v -0.009792 0.000581 0.008449 -vn -0.047936 0.008615 0.998813 -v -0.009655 0.001735 0.008449 -vn -0.046581 0.014224 0.998813 -v -0.009382 0.002865 0.008449 -vn -0.044572 0.019634 0.998813 -v -0.008977 0.003954 0.008449 -vn -0.041937 0.024768 0.998813 -v -0.008446 0.004988 0.008449 -vn -0.038713 0.029554 0.998813 -v -0.007797 0.005952 0.008449 -vn -0.034946 0.033925 0.998813 -v -0.007038 0.006833 0.008449 -vn -0.030688 0.037820 0.998813 -v -0.006181 0.007617 0.008449 -vn -0.026000 0.041184 0.998813 -v -0.005236 0.008295 0.008449 -vn -0.020946 0.043970 0.998813 -v -0.004219 0.008856 0.008449 -vn -0.015599 0.046139 0.998813 -v -0.003142 0.009293 0.008449 -vn -0.010032 0.047660 0.998813 -v -0.002021 0.009599 0.008449 -vn -0.004325 0.048512 0.998813 -v -0.000871 0.009771 0.008449 -vn 0.001443 0.048683 0.998813 -v 0.000291 0.009805 0.008449 -vn 0.007191 0.048171 0.998813 -v 0.001448 0.009702 0.008449 -vn 0.012838 0.046982 0.998813 -v 0.002586 0.009462 0.008449 -vn 0.018304 0.045134 0.998813 -v 0.003687 0.009090 0.008449 -vn 0.023514 0.042652 0.998813 -v 0.004736 0.008590 0.008449 -vn 0.028394 0.039572 0.998813 -v 0.005719 0.007970 0.008449 -vn 0.032875 0.035936 0.998813 -v 0.006621 0.007238 0.008449 -vn 0.036894 0.031795 0.998813 -v 0.007431 0.006404 0.008449 -vn 0.040396 0.027209 0.998813 -v 0.008136 0.005480 0.008449 -vn 0.043330 0.022240 0.998813 -v 0.008727 0.004479 0.008449 -vn 0.045657 0.016959 0.998813 -v 0.009195 0.003416 0.008449 -vn 0.047342 0.011440 0.998813 -v 0.009535 0.002304 0.008449 -vn 0.048363 0.005760 0.998813 -v 0.009740 0.001160 0.008449 -vn -0.955032 -0.249081 -0.160853 -v 0.008738 0.002154 0.006437 -vn -0.917427 -0.150268 -0.368439 -v 0.008833 0.001557 0.006610 -vn -0.872532 -0.320705 -0.368561 -v 0.008428 0.003068 0.006610 -vn -0.713079 -0.688326 -0.133138 -v 0.006737 0.005968 0.006437 -vn -0.786487 -0.611424 -0.087172 -v 0.006894 0.005785 0.006437 -vn -0.718247 -0.589294 -0.369936 -v 0.006871 0.005765 0.006610 -vn -0.845316 -0.527113 -0.087135 -v 0.007794 0.004500 0.006437 -vn -0.798364 -0.475132 -0.369952 -v 0.007767 0.004485 0.006610 -vn -0.890307 -0.433110 -0.140600 -v 0.007969 0.004183 0.006437 -vn -0.933763 -0.346954 -0.087803 -v 0.008457 0.003078 0.006437 -vn -0.652638 -0.752322 -0.089862 -v 0.005785 0.006894 0.006437 -vn -0.604915 -0.706878 -0.366609 -v 0.005765 0.006871 0.006610 -vn -0.563942 -0.809190 -0.164870 -v 0.005113 0.007407 0.006437 -vn -0.457291 -0.809373 -0.368512 -v 0.004485 0.007767 0.006610 -vn -0.480651 -0.872506 -0.087800 -v 0.004500 0.007794 0.006437 -vn -0.392132 -0.913868 -0.105251 -v 0.003191 0.008415 0.006437 -vn -0.310435 -0.876170 -0.368722 -v 0.003068 0.008428 0.006610 -vn -0.302689 -0.949044 -0.087715 -v 0.003078 0.008457 0.006437 -vn -0.172252 -0.913264 -0.369158 -v 0.001557 0.008833 0.006610 -vn -0.202584 -0.975338 -0.087611 -v 0.001563 0.008863 0.006437 -vn 0.393967 -0.912785 -0.107765 -v -0.003191 0.008415 0.006437 -vn 0.302181 -0.949279 -0.086929 -v -0.003078 0.008457 0.006437 -vn 0.311361 -0.875971 -0.368415 -v -0.003068 0.008428 0.006610 -vn 0.203145 -0.975294 -0.086793 -v -0.001563 0.008863 0.006437 -vn 0.173260 -0.913026 -0.369276 -v -0.001557 0.008833 0.006610 -vn 0.097285 -0.983460 -0.152783 -v -0.001085 0.008934 0.006437 -vn -0.006218 -0.931098 -0.364716 -v 0.000000 0.008969 0.006610 -vn -0.006074 -0.995745 -0.091951 -v 0.000000 0.009000 0.006437 -vn -0.086459 -0.978949 -0.184887 -v 0.001085 0.008934 0.006437 -vn 0.479276 -0.873157 -0.088833 -v -0.004500 0.007794 0.006437 -vn 0.456087 -0.810490 -0.367546 -v -0.004485 0.007767 0.006610 -vn 0.563942 -0.809190 -0.164870 -v -0.005113 0.007407 0.006437 -vn 0.602005 -0.708352 -0.368548 -v -0.005765 0.006871 0.006610 -vn 0.650462 -0.754448 -0.087792 -v -0.005785 0.006894 0.006437 -vn 0.717247 -0.685627 -0.124388 -v -0.006737 0.005968 0.006437 -vn 0.718892 -0.588361 -0.370168 -v -0.006871 0.005765 0.006610 -vn 0.786355 -0.611555 -0.087437 -v -0.006894 0.005785 0.006437 -vn 0.798988 -0.474209 -0.369788 -v -0.007767 0.004485 0.006610 -vn 0.845394 -0.526943 -0.087405 -v -0.007794 0.004500 0.006437 -vn 0.917425 0.150269 -0.368445 -v -0.008833 -0.001557 0.006610 -vn 0.996137 0.000000 -0.087815 -v -0.009000 -0.000000 0.006437 -vn 0.932619 -0.000000 -0.360863 -v -0.008969 -0.000000 0.006610 -vn 0.985283 -0.146660 -0.087800 -v -0.008863 0.001563 0.006437 -vn 0.917424 -0.150269 -0.368445 -v -0.008833 0.001557 0.006610 -vn 0.955030 -0.249078 -0.160864 -v -0.008738 0.002154 0.006437 -vn 0.871966 -0.325520 -0.365667 -v -0.008428 0.003068 0.006610 -vn 0.931905 -0.351124 -0.090912 -v -0.008457 0.003078 0.006437 -vn 0.891059 -0.425002 -0.159332 -v -0.007969 0.004183 0.006437 -vn 0.872532 0.320703 -0.368562 -v -0.008428 -0.003068 0.006610 -vn 0.955030 0.249078 -0.160864 -v -0.008738 -0.002154 0.006437 -vn 0.985283 0.146660 -0.087800 -v -0.008863 -0.001563 0.006437 -vn 0.713079 0.688326 -0.133137 -v -0.006737 -0.005968 0.006437 -vn 0.786487 0.611424 -0.087172 -v -0.006894 -0.005785 0.006437 -vn 0.718246 0.589295 -0.369938 -v -0.006871 -0.005765 0.006610 -vn 0.845316 0.527113 -0.087136 -v -0.007794 -0.004500 0.006437 -vn 0.798364 0.475132 -0.369952 -v -0.007767 -0.004485 0.006610 -vn 0.890307 0.433110 -0.140600 -v -0.007969 -0.004183 0.006437 -vn 0.933763 0.346954 -0.087804 -v -0.008457 -0.003078 0.006437 -vn 0.652638 0.752322 -0.089864 -v -0.005785 -0.006894 0.006437 -vn 0.604913 0.706874 -0.366619 -v -0.005765 -0.006871 0.006610 -vn 0.563942 0.809190 -0.164869 -v -0.005113 -0.007407 0.006437 -vn 0.457291 0.809372 -0.368513 -v -0.004485 -0.007767 0.006610 -vn 0.480651 0.872505 -0.087800 -v -0.004500 -0.007794 0.006437 -vn 0.392134 0.913867 -0.105249 -v -0.003191 -0.008415 0.006437 -vn 0.310435 0.876170 -0.368721 -v -0.003068 -0.008428 0.006610 -vn 0.302693 0.949043 -0.087715 -v -0.003078 -0.008457 0.006437 -vn 0.172252 0.913264 -0.369159 -v -0.001557 -0.008833 0.006610 -vn 0.202584 0.975338 -0.087614 -v -0.001563 -0.008863 0.006437 -vn -0.393969 0.912784 -0.107763 -v 0.003191 -0.008415 0.006437 -vn -0.302184 0.949278 -0.086929 -v 0.003078 -0.008457 0.006437 -vn -0.311362 0.875971 -0.368415 -v 0.003068 -0.008428 0.006610 -vn -0.203145 0.975294 -0.086795 -v 0.001563 -0.008863 0.006437 -vn -0.173260 0.913026 -0.369277 -v 0.001557 -0.008833 0.006610 -vn -0.097285 0.983460 -0.152784 -v 0.001085 -0.008934 0.006437 -vn 0.006218 0.931099 -0.364713 -v 0.000000 -0.008969 0.006610 -vn 0.006074 0.995745 -0.091949 -v 0.000000 -0.009000 0.006437 -vn 0.086459 0.978949 -0.184891 -v -0.001085 -0.008934 0.006437 -vn -0.479276 0.873157 -0.088833 -v 0.004500 -0.007794 0.006437 -vn -0.456086 0.810490 -0.367547 -v 0.004485 -0.007767 0.006610 -vn -0.563942 0.809190 -0.164869 -v 0.005113 -0.007407 0.006437 -vn -0.602006 0.708354 -0.368542 -v 0.005765 -0.006871 0.006610 -vn -0.650461 0.754448 -0.087795 -v 0.005785 -0.006894 0.006437 -vn -0.717247 0.685627 -0.124388 -v 0.006737 -0.005968 0.006437 -vn -0.718892 0.588361 -0.370170 -v 0.006871 -0.005765 0.006610 -vn -0.786355 0.611556 -0.087437 -v 0.006894 -0.005785 0.006437 -vn -0.798988 0.474209 -0.369788 -v 0.007767 -0.004485 0.006610 -vn -0.845394 0.526943 -0.087405 -v 0.007794 -0.004500 0.006437 -vn -0.985285 -0.146660 -0.087779 -v 0.008863 0.001563 0.006437 -vn -0.996137 0.000001 -0.087814 -v 0.009000 -0.000000 0.006437 -vn -0.932619 0.000001 -0.360863 -v 0.008969 -0.000000 0.006610 -vn -0.985285 0.146659 -0.087780 -v 0.008863 -0.001563 0.006437 -vn -0.917427 0.150269 -0.368439 -v 0.008833 -0.001557 0.006610 -vn -0.955032 0.249081 -0.160853 -v 0.008738 -0.002154 0.006437 -vn -0.871966 0.325520 -0.365668 -v 0.008428 -0.003068 0.006610 -vn -0.931905 0.351124 -0.090912 -v 0.008457 -0.003078 0.006437 -vn -0.891060 0.425001 -0.159332 -v 0.007969 -0.004183 0.006437 -vn 0.373802 0.000000 -0.927508 -v -0.008673 -0.000000 0.006906 -vn 0.368123 0.064910 -0.927508 -v -0.008541 -0.001506 0.006906 -vn 0.351252 0.127845 -0.927512 -v -0.008150 -0.002966 0.006906 -vn 0.323718 0.186899 -0.927510 -v -0.007511 -0.004337 0.006906 -vn 0.286346 0.240273 -0.927510 -v -0.006644 -0.005575 0.006906 -vn 0.240276 0.286349 -0.927509 -v -0.005575 -0.006644 0.006906 -vn 0.186901 0.323721 -0.927509 -v -0.004337 -0.007511 0.006906 -vn 0.127847 0.351257 -0.927510 -v -0.002966 -0.008150 0.006906 -vn 0.064910 0.368120 -0.927510 -v -0.001506 -0.008541 0.006906 -vn -0.000000 0.373798 -0.927510 -v 0.000000 -0.008673 0.006906 -vn -0.064910 0.368120 -0.927510 -v 0.001506 -0.008541 0.006906 -vn -0.127847 0.351256 -0.927510 -v 0.002966 -0.008150 0.006906 -vn -0.186901 0.323721 -0.927509 -v 0.004337 -0.007511 0.006906 -vn -0.240272 0.286345 -0.927511 -v 0.005575 -0.006644 0.006906 -vn -0.286346 0.240273 -0.927510 -v 0.006644 -0.005575 0.006906 -vn -0.323718 0.186899 -0.927510 -v 0.007511 -0.004337 0.006906 -vn -0.351254 0.127846 -0.927510 -v 0.008150 -0.002966 0.006906 -vn -0.368123 0.064910 -0.927509 -v 0.008541 -0.001506 0.006906 -vn -0.373802 -0.000000 -0.927508 -v 0.008673 -0.000000 0.006906 -vn -0.368124 -0.064910 -0.927508 -v 0.008541 0.001506 0.006906 -vn -0.351255 -0.127846 -0.927510 -v 0.008150 0.002966 0.006906 -vn -0.323718 -0.186898 -0.927511 -v 0.007511 0.004337 0.006906 -vn -0.286346 -0.240273 -0.927510 -v 0.006644 0.005575 0.006906 -vn -0.240272 -0.286344 -0.927511 -v 0.005575 0.006644 0.006906 -vn -0.186901 -0.323721 -0.927509 -v 0.004337 0.007511 0.006906 -vn -0.127848 -0.351257 -0.927509 -v 0.002966 0.008150 0.006906 -vn -0.064910 -0.368120 -0.927510 -v 0.001506 0.008541 0.006906 -vn -0.000000 -0.373799 -0.927510 -v 0.000000 0.008673 0.006906 -vn 0.064910 -0.368120 -0.927510 -v -0.001506 0.008541 0.006906 -vn 0.127848 -0.351257 -0.927509 -v -0.002966 0.008150 0.006906 -vn 0.186901 -0.323721 -0.927509 -v -0.004337 0.007511 0.006906 -vn 0.240276 -0.286348 -0.927509 -v -0.005575 0.006644 0.006906 -vn 0.286346 -0.240273 -0.927510 -v -0.006644 0.005575 0.006906 -vn 0.323718 -0.186898 -0.927511 -v -0.007511 0.004337 0.006906 -vn 0.351251 -0.127845 -0.927512 -v -0.008150 0.002966 0.006906 -vn 0.368123 -0.064910 -0.927509 -v -0.008541 0.001506 0.006906 -vn -0.712951 -0.000001 -0.701214 -v 0.008854 -0.000000 0.006790 -vn -0.702114 0.123802 -0.701220 -v 0.008719 -0.001537 0.006790 -vn -0.669957 0.243843 -0.701212 -v 0.008320 -0.003028 0.006790 -vn -0.617434 0.356475 -0.701214 -v 0.007667 -0.004427 0.006790 -vn -0.546149 0.458274 -0.701218 -v 0.006782 -0.005691 0.006790 -vn -0.458276 0.546152 -0.701214 -v 0.005691 -0.006782 0.006790 -vn -0.356475 0.617435 -0.701213 -v 0.004427 -0.007667 0.006790 -vn -0.243844 0.669956 -0.701213 -v 0.003028 -0.008320 0.006790 -vn -0.123802 0.702120 -0.701214 -v 0.001537 -0.008719 0.006790 -vn -0.000000 0.712950 -0.701215 -v 0.000000 -0.008854 0.006790 -vn 0.123802 0.702120 -0.701214 -v -0.001537 -0.008719 0.006790 -vn 0.243844 0.669956 -0.701213 -v -0.003028 -0.008320 0.006790 -vn 0.356475 0.617435 -0.701213 -v -0.004427 -0.007667 0.006790 -vn 0.458273 0.546151 -0.701217 -v -0.005691 -0.006782 0.006790 -vn 0.546149 0.458274 -0.701218 -v -0.006782 -0.005691 0.006790 -vn 0.617434 0.356476 -0.701214 -v -0.007667 -0.004427 0.006790 -vn 0.669957 0.243843 -0.701212 -v -0.008320 -0.003028 0.006790 -vn 0.702123 0.123803 -0.701210 -v -0.008719 -0.001537 0.006790 -vn 0.712952 -0.000000 -0.701213 -v -0.008854 -0.000000 0.006790 -vn 0.702124 -0.123803 -0.701209 -v -0.008719 0.001537 0.006790 -vn 0.669957 -0.243843 -0.701212 -v -0.008320 0.003028 0.006790 -vn 0.617434 -0.356475 -0.701214 -v -0.007667 0.004427 0.006790 -vn 0.546149 -0.458274 -0.701217 -v -0.006782 0.005691 0.006790 -vn 0.458272 -0.546150 -0.701218 -v -0.005691 0.006782 0.006790 -vn 0.356476 -0.617436 -0.701212 -v -0.004427 0.007667 0.006790 -vn 0.243844 -0.669956 -0.701212 -v -0.003028 0.008320 0.006790 -vn 0.123802 -0.702119 -0.701215 -v -0.001537 0.008719 0.006790 -vn -0.000000 -0.712951 -0.701214 -v 0.000000 0.008854 0.006790 -vn -0.123802 -0.702119 -0.701215 -v 0.001537 0.008719 0.006790 -vn -0.243844 -0.669956 -0.701212 -v 0.003028 0.008320 0.006790 -vn -0.356475 -0.617436 -0.701212 -v 0.004427 0.007667 0.006790 -vn -0.458275 -0.546151 -0.701215 -v 0.005691 0.006782 0.006790 -vn -0.546150 -0.458274 -0.701217 -v 0.006782 0.005691 0.006790 -vn -0.617434 -0.356475 -0.701214 -v 0.007667 0.004427 0.006790 -vn -0.669956 -0.243844 -0.701212 -v 0.008320 0.003028 0.006790 -vn -0.702114 -0.123801 -0.701220 -v 0.008719 0.001537 0.006790 -vn 0.793852 0.397953 0.459817 -v 0.017744 0.009107 0.007234 -vn 0.829750 0.316639 0.459626 -v 0.018697 0.006945 0.007234 -vn 0.922536 0.367391 0.118113 -v 0.018748 0.006964 0.007006 -vn 0.241951 0.854401 0.459847 -v 0.005257 0.019239 0.007234 -vn 0.326417 0.826012 0.459517 -v 0.007496 0.018483 0.007234 -vn 0.352345 0.928387 0.118112 -v 0.007517 0.018534 0.007006 -vn -0.467492 0.755010 0.459794 -v -0.010647 0.016865 0.007234 -vn -0.389142 0.798462 0.459376 -v -0.008577 0.018006 0.007234 -vn -0.446475 0.886967 0.118108 -v -0.008601 0.018056 0.007006 -vn -0.760660 0.458931 0.459107 -v -0.017173 0.010142 0.007234 -vn -0.709448 0.534851 0.458932 -v -0.015853 0.012102 0.007234 -vn -0.805405 0.580832 0.118137 -v -0.015897 0.012136 0.007006 -vn -0.872858 0.164006 0.459587 -v -0.019630 0.003528 0.007234 -vn -0.851854 0.251926 0.459215 -v -0.019075 0.005825 0.007234 -vn -0.955589 0.270005 0.118098 -v -0.019128 0.005841 0.007006 -vn -0.852002 -0.251304 0.459281 -v -0.019075 -0.005825 0.007234 -vn -0.873060 -0.163369 0.459431 -v -0.019630 -0.003528 0.007234 -vn -0.972353 -0.201420 0.118149 -v -0.019685 -0.003538 0.007006 -vn -0.709741 -0.534314 0.459103 -v -0.015853 -0.012102 0.007234 -vn -0.761006 -0.458415 0.459049 -v -0.017173 -0.010142 0.007234 -vn -0.844635 -0.522154 0.118098 -v -0.017221 -0.010171 0.007006 -vn -0.389717 -0.798140 0.459449 -v -0.008577 -0.018006 0.007234 -vn -0.468116 -0.754707 0.459657 -v -0.010647 -0.016865 0.007234 -vn -0.508357 -0.853005 0.118136 -v -0.010676 -0.016912 0.007006 -vn 0.325774 -0.826220 0.459600 -v 0.007496 -0.018483 0.007234 -vn 0.241297 -0.854651 0.459726 -v 0.005257 -0.019239 0.007234 -vn 0.285505 -0.951069 0.118127 -v 0.005272 -0.019293 0.007006 -vn 0.863213 -0.211085 0.458592 -v 0.019387 -0.004685 0.007234 -vn 0.829459 -0.317263 0.459719 -v 0.018697 -0.006945 0.007234 -vn 0.941207 -0.299658 0.155998 -v 0.018916 -0.006494 0.007006 -vn 0.793589 -0.398600 0.459711 -v 0.017744 -0.009107 0.007234 -vn 0.894104 -0.431999 0.118128 -v 0.017793 -0.009133 0.007006 -vn 0.922537 -0.367390 0.118112 -v 0.018748 -0.006964 0.007006 -vn 0.668525 -0.585504 0.458541 -v 0.015108 -0.013020 0.007234 -vn 0.780589 -0.599649 0.176354 -v 0.015783 -0.012284 0.007006 -vn 0.740849 -0.492137 0.457105 -v 0.016542 -0.011142 0.007234 -vn 0.828662 -0.546788 0.119755 -v 0.016588 -0.011173 0.007006 -vn 0.854287 -0.494214 0.161082 -v 0.017589 -0.009519 0.007006 -vn 0.598742 -0.658113 0.456503 -v 0.013462 -0.014716 0.007234 -vn 0.693799 -0.709734 0.122148 -v 0.013546 -0.014714 0.007006 -vn 0.741524 -0.660453 0.118084 -v 0.015150 -0.013056 0.007006 -vn 0.427514 -0.779055 0.458591 -v 0.009629 -0.017466 0.007234 -vn 0.529943 -0.830103 0.173461 -v 0.010939 -0.016743 0.007006 -vn 0.524465 -0.717291 0.458727 -v 0.011627 -0.016205 0.007234 -vn 0.593857 -0.795859 0.118079 -v 0.011660 -0.016250 0.007006 -vn 0.648888 -0.751655 0.118149 -v 0.013500 -0.014757 0.007006 -vn 0.352345 -0.928387 0.118112 -v 0.007517 -0.018534 0.007006 -vn 0.415066 -0.895640 0.159839 -v 0.008034 -0.018315 0.007006 -vn 0.476030 -0.871464 0.118095 -v 0.009656 -0.017515 0.007006 -vn 0.019880 -0.888443 0.458557 -v 0.000591 -0.019936 0.007234 -vn 0.085422 -0.980452 0.177247 -v 0.001652 -0.019932 0.007006 -vn 0.137247 -0.878654 0.457309 -v 0.002945 -0.019726 0.007234 -vn 0.157074 -0.980329 0.119511 -v 0.002953 -0.019781 0.007006 -vn 0.214287 -0.964524 0.154190 -v 0.004910 -0.019388 0.007006 -vn -0.083371 -0.884939 0.458184 -v -0.001771 -0.019866 0.007234 -vn -0.052237 -0.990537 0.126919 -v -0.001652 -0.019932 0.007006 -vn 0.014759 -0.992894 0.118085 -v 0.000593 -0.019991 0.007006 -vn -0.285593 -0.841506 0.458589 -v -0.006388 -0.018894 0.007234 -vn -0.253868 -0.951917 0.171478 -v -0.004910 -0.019388 0.007006 -vn -0.175011 -0.871071 0.458919 -v -0.004108 -0.019517 0.007234 -vn -0.185607 -0.975502 0.118090 -v -0.004120 -0.019571 0.007006 -vn -0.115846 -0.986216 0.118142 -v -0.001776 -0.019921 0.007006 -vn -0.446475 -0.886967 0.118108 -v -0.008601 -0.018056 0.007006 -vn -0.379372 -0.910720 0.163300 -v -0.008034 -0.018315 0.007006 -vn -0.320223 -0.939952 0.118097 -v -0.006405 -0.018947 0.007006 -vn -0.641650 -0.614820 0.458564 -v -0.014310 -0.013892 0.007234 -vn -0.664958 -0.725413 0.177784 -v -0.013546 -0.014714 0.007006 -vn -0.555348 -0.694450 0.457523 -v -0.012567 -0.015488 0.007234 -vn -0.616382 -0.778361 0.119283 -v -0.012602 -0.015530 0.007006 -vn -0.565744 -0.811313 0.147329 -v -0.010939 -0.016743 0.007006 -vn -0.805405 -0.580832 0.118136 -v -0.015897 -0.012136 0.007006 -vn -0.763922 -0.631647 0.132083 -v -0.015783 -0.012284 0.007006 -vn -0.721568 -0.682199 0.118080 -v -0.014350 -0.013931 0.007006 -vn -0.955589 -0.270007 0.118098 -v -0.019128 -0.005841 0.007006 -vn -0.927161 -0.335682 0.166401 -v -0.018916 -0.006494 0.007006 -vn -0.812815 -0.362422 0.456052 -v -0.018252 -0.008040 0.007234 -vn -0.907025 -0.403333 0.120951 -v -0.018303 -0.008062 0.007006 -vn -0.872745 -0.447569 0.194932 -v -0.017589 -0.009519 0.007006 -vn -0.886768 0.057775 0.458590 -v -0.019910 0.001182 0.007234 -vn -0.984035 -0.000000 0.177974 -v -0.020000 -0.000000 0.007006 -vn -0.887107 -0.059283 0.457741 -v -0.019910 -0.001182 0.007234 -vn -0.990290 -0.071784 0.119051 -v -0.019965 -0.001185 0.007006 -vn -0.981124 -0.132811 0.140557 -v -0.019727 -0.003292 0.007006 -vn -0.972353 0.201421 0.118150 -v -0.019685 0.003538 0.007006 -vn -0.981284 0.135005 0.137319 -v -0.019727 0.003292 0.007006 -vn -0.990504 0.070384 0.118105 -v -0.019965 0.001185 0.007006 -vn -0.844635 0.522154 0.118098 -v -0.017221 0.010171 0.007006 -vn -0.873590 0.456334 0.169115 -v -0.017589 0.009519 0.007006 -vn -0.816082 0.354731 0.456262 -v -0.018252 0.008040 0.007234 -vn -0.910320 0.395911 0.120713 -v -0.018303 0.008062 0.007006 -vn -0.921133 0.340671 0.188302 -v -0.018916 0.006494 0.007006 -vn -0.556451 0.692866 0.458583 -v -0.012567 0.015488 0.007234 -vn -0.664958 0.725413 0.177783 -v -0.013546 0.014714 0.007006 -vn -0.642659 0.614242 0.457926 -v -0.014310 0.013892 0.007234 -vn -0.722234 0.681371 0.118790 -v -0.014350 0.013931 0.007006 -vn -0.762750 0.632654 0.134016 -v -0.015783 0.012284 0.007006 -vn -0.508357 0.853005 0.118137 -v -0.010676 0.016912 0.007006 -vn -0.563849 0.813504 0.142425 -v -0.010939 0.016743 0.007006 -vn -0.617853 0.777374 0.118098 -v -0.012602 0.015530 0.007006 -vn -0.175011 0.871071 0.458919 -v -0.004108 0.019517 0.007234 -vn -0.253868 0.951917 0.171478 -v -0.004910 0.019388 0.007006 -vn -0.289399 0.841358 0.456470 -v -0.006388 0.018894 0.007234 -vn -0.323471 0.938538 0.120470 -v -0.006405 0.018947 0.007006 -vn -0.372504 0.910094 0.181577 -v -0.008034 0.018315 0.007006 -vn 0.019880 0.888443 0.458557 -v 0.000591 0.019936 0.007234 -vn -0.052237 0.990537 0.126919 -v -0.001652 0.019932 0.007006 -vn -0.083371 0.884939 0.458184 -v -0.001771 0.019866 0.007234 -vn -0.115846 0.986216 0.118142 -v -0.001776 0.019921 0.007006 -vn -0.185607 0.975502 0.118090 -v -0.004120 0.019571 0.007006 -vn 0.134957 0.878345 0.458582 -v 0.002945 0.019726 0.007234 -vn 0.085422 0.980452 0.177247 -v 0.001652 0.019932 0.007006 -vn 0.014759 0.992894 0.118085 -v 0.000593 0.019991 0.007006 -vn 0.285505 0.951069 0.118127 -v 0.005272 0.019293 0.007006 -vn 0.217903 0.964795 0.147272 -v 0.004910 0.019388 0.007006 -vn 0.155009 0.980830 0.118090 -v 0.002953 0.019781 0.007006 -vn 0.524465 0.717290 0.458727 -v 0.011627 0.016205 0.007234 -vn 0.529943 0.830103 0.173461 -v 0.010939 0.016743 0.007006 -vn 0.425093 0.781497 0.456683 -v 0.009629 0.017466 0.007234 -vn 0.473115 0.872758 0.120230 -v 0.009656 0.017515 0.007006 -vn 0.418936 0.891032 0.174799 -v 0.008034 0.018315 0.007006 -vn 0.668524 0.585505 0.458541 -v 0.015108 0.013020 0.007234 -vn 0.693800 0.709734 0.122147 -v 0.013546 0.014714 0.007006 -vn 0.598743 0.658113 0.456503 -v 0.013462 0.014716 0.007234 -vn 0.648889 0.751655 0.118147 -v 0.013500 0.014757 0.007006 -vn 0.593857 0.795859 0.118079 -v 0.011660 0.016250 0.007006 -vn 0.738783 0.493858 0.458590 -v 0.016542 0.011142 0.007234 -vn 0.780589 0.599649 0.176355 -v 0.015783 0.012284 0.007006 -vn 0.741524 0.660453 0.118085 -v 0.015150 0.013056 0.007006 -vn 0.894104 0.431999 0.118129 -v 0.017793 0.009133 0.007006 -vn 0.857621 0.491364 0.151813 -v 0.017589 0.009519 0.007006 -vn 0.827464 0.548959 0.118097 -v 0.016588 0.011173 0.007006 -vn 0.883319 0.097434 0.458534 -v 0.019805 0.002359 0.007234 -vn 0.969723 0.170245 0.175085 -v 0.019727 0.003292 0.007006 -vn 0.863359 0.214146 0.456895 -v 0.019387 0.004685 0.007234 -vn 0.963034 0.241180 0.119989 -v 0.019440 0.004698 0.007006 -vn 0.940779 0.294494 0.167951 -v 0.018916 0.006494 0.007006 -vn 0.963937 -0.238493 0.118093 -v 0.019440 -0.004698 0.007006 -vn 0.969723 -0.170245 0.175085 -v 0.019727 -0.003292 0.007006 -vn 0.883319 -0.097434 0.458534 -v 0.019805 -0.002359 0.007234 -vn 0.987977 -0.099793 0.118081 -v 0.019860 -0.002365 0.007006 -vn 0.891143 0.000000 0.453723 -v 0.019945 -0.000000 0.007234 -vn 0.993021 0.000000 0.117940 -v 0.020000 -0.000000 0.007006 -vn 0.987977 0.099793 0.118081 -v 0.019860 0.002365 0.007006 -vn 0.587580 0.000000 0.809166 -v 0.019791 -0.000000 0.007412 -vn 0.583455 -0.069494 0.809167 -v 0.019652 -0.002341 0.007412 -vn 0.571136 -0.138014 0.809170 -v 0.019237 -0.004649 0.007412 -vn 0.550810 -0.204597 0.809165 -v 0.018552 -0.006891 0.007412 -vn 0.522749 -0.268308 0.809163 -v 0.017607 -0.009037 0.007412 -vn 0.487340 -0.328249 0.809167 -v 0.016415 -0.011056 0.007412 -vn 0.445103 -0.383589 0.809162 -v 0.014992 -0.012920 0.007412 -vn 0.396609 -0.433538 0.809164 -v 0.013359 -0.014602 0.007412 -vn 0.342545 -0.477399 0.809168 -v 0.011538 -0.016080 0.007412 -vn 0.283679 -0.514565 0.809166 -v 0.009555 -0.017332 0.007412 -vn 0.220829 -0.544504 0.809166 -v 0.007438 -0.018340 0.007412 -vn 0.154879 -0.566802 0.809165 -v 0.005217 -0.019091 0.007412 -vn 0.086753 -0.581138 0.809168 -v 0.002922 -0.019574 0.007412 -vn 0.017412 -0.587321 0.809167 -v 0.000586 -0.019782 0.007412 -vn -0.052175 -0.585259 0.809166 -v -0.001757 -0.019713 0.007412 -vn -0.121029 -0.574980 0.809166 -v -0.004076 -0.019366 0.007412 -vn -0.188185 -0.556632 0.809165 -v -0.006338 -0.018748 0.007412 -vn -0.252699 -0.530467 0.809165 -v -0.008511 -0.017867 0.007412 -vn -0.313665 -0.496858 0.809164 -v -0.010565 -0.016735 0.007412 -vn -0.370228 -0.456271 0.809165 -v -0.012470 -0.015368 0.007412 -vn -0.421590 -0.409277 0.809169 -v -0.014200 -0.013785 0.007412 -vn -0.467042 -0.356545 0.809164 -v -0.015731 -0.012009 0.007412 -vn -0.505929 -0.298800 0.809169 -v -0.017041 -0.010064 0.007412 -vn -0.537724 -0.236868 0.809164 -v -0.018112 -0.007978 0.007412 -vn -0.561960 -0.171606 0.809167 -v -0.018928 -0.005780 0.007412 -vn -0.578320 -0.103939 0.809162 -v -0.019479 -0.003501 0.007412 -vn -0.586548 -0.034808 0.809166 -v -0.019756 -0.001172 0.007412 -vn -0.586549 0.034808 0.809166 -v -0.019756 0.001172 0.007412 -vn -0.578321 0.103938 0.809161 -v -0.019479 0.003501 0.007412 -vn -0.561960 0.171607 0.809167 -v -0.018928 0.005780 0.007412 -vn -0.537724 0.236867 0.809164 -v -0.018112 0.007978 0.007412 -vn -0.505929 0.298801 0.809168 -v -0.017041 0.010064 0.007412 -vn -0.467043 0.356545 0.809164 -v -0.015731 0.012009 0.007412 -vn -0.421590 0.409278 0.809169 -v -0.014200 0.013785 0.007412 -vn -0.370228 0.456271 0.809165 -v -0.012470 0.015368 0.007412 -vn -0.313665 0.496858 0.809164 -v -0.010565 0.016735 0.007412 -vn -0.252699 0.530467 0.809165 -v -0.008511 0.017867 0.007412 -vn -0.188185 0.556632 0.809165 -v -0.006338 0.018748 0.007412 -vn -0.121029 0.574980 0.809166 -v -0.004076 0.019366 0.007412 -vn -0.052175 0.585259 0.809166 -v -0.001757 0.019713 0.007412 -vn 0.017412 0.587321 0.809167 -v 0.000586 0.019782 0.007412 -vn 0.086754 0.581138 0.809167 -v 0.002922 0.019574 0.007412 -vn 0.154879 0.566802 0.809165 -v 0.005217 0.019091 0.007412 -vn 0.220829 0.544504 0.809166 -v 0.007438 0.018340 0.007412 -vn 0.283679 0.514565 0.809166 -v 0.009555 0.017332 0.007412 -vn 0.342545 0.477398 0.809168 -v 0.011538 0.016080 0.007412 -vn 0.396609 0.433539 0.809164 -v 0.013359 0.014602 0.007412 -vn 0.445103 0.383590 0.809161 -v 0.014992 0.012920 0.007412 -vn 0.487341 0.328249 0.809167 -v 0.016415 0.011056 0.007412 -vn 0.522749 0.268308 0.809163 -v 0.017607 0.009037 0.007412 -vn 0.550810 0.204597 0.809165 -v 0.018552 0.006891 0.007412 -vn 0.571136 0.138013 0.809170 -v 0.019237 0.004649 0.007412 -vn 0.583455 0.069495 0.809167 -v 0.019652 0.002341 0.007412 -vn -0.659744 -0.162397 -0.733733 -v 0.008738 0.002154 -0.006063 -vn -0.679210 -0.000000 -0.733944 -v 0.009000 -0.000000 -0.006063 -vn -0.600969 -0.316167 -0.734080 -v 0.007969 0.004183 -0.006063 -vn -0.508663 -0.449799 -0.734127 -v 0.006737 0.005968 -0.006063 -vn -0.385934 -0.559245 -0.733690 -v 0.005113 0.007407 -0.006063 -vn -0.240639 -0.635143 -0.733952 -v 0.003191 0.008415 -0.006063 -vn -0.082231 -0.674348 -0.733821 -v 0.001085 0.008934 -0.006063 -vn 0.082718 -0.673875 -0.734200 -v -0.001085 0.008934 -0.006063 -vn 0.239980 -0.634937 -0.734346 -v -0.003191 0.008415 -0.006063 -vn 0.385934 -0.559245 -0.733690 -v -0.005113 0.007407 -0.006063 -vn 0.508649 -0.450027 -0.733997 -v -0.006737 0.005968 -0.006063 -vn 0.601176 -0.316072 -0.733953 -v -0.007969 0.004183 -0.006063 -vn 0.659744 -0.162397 -0.733733 -v -0.008738 0.002154 -0.006063 -vn 0.679210 0.000000 -0.733944 -v -0.009000 -0.000000 -0.006063 -vn 0.659744 0.162397 -0.733733 -v -0.008738 -0.002154 -0.006063 -vn 0.600969 0.316167 -0.734080 -v -0.007969 -0.004183 -0.006063 -vn 0.508663 0.449799 -0.734127 -v -0.006737 -0.005968 -0.006063 -vn 0.385934 0.559245 -0.733690 -v -0.005113 -0.007407 -0.006063 -vn 0.240639 0.635143 -0.733952 -v -0.003191 -0.008415 -0.006063 -vn 0.082232 0.674348 -0.733821 -v -0.001085 -0.008934 -0.006063 -vn -0.082718 0.673875 -0.734200 -v 0.001085 -0.008934 -0.006063 -vn -0.239981 0.634937 -0.734346 -v 0.003191 -0.008415 -0.006063 -vn -0.385934 0.559245 -0.733690 -v 0.005113 -0.007407 -0.006063 -vn -0.508649 0.450027 -0.733997 -v 0.006737 -0.005968 -0.006063 -vn -0.601176 0.316072 -0.733952 -v 0.007969 -0.004183 -0.006063 -vn -0.659744 0.162397 -0.733733 -v 0.008738 -0.002154 -0.006063 -vn 0.991076 0.100093 -0.088028 -v 0.019860 0.002365 0.003937 -vn 0.996125 0.000000 -0.087951 -v 0.020000 -0.000000 0.003937 -vn 0.991076 -0.100093 -0.088028 -v 0.019860 -0.002365 0.003937 -vn 0.970896 -0.170650 -0.168045 -v 0.019727 -0.003292 0.003937 -vn 0.966089 -0.242027 -0.089972 -v 0.019440 -0.004698 0.003937 -vn 0.942611 -0.294044 -0.158183 -v 0.018916 -0.006494 0.003937 -vn 0.925427 -0.368557 -0.088034 -v 0.018748 -0.006964 0.003937 -vn 0.896918 -0.433342 -0.088057 -v 0.017793 -0.009133 0.003937 -vn 0.859159 -0.493192 -0.136406 -v 0.017589 -0.009519 0.003937 -vn 0.830062 -0.550677 -0.088048 -v 0.016588 -0.011173 0.003937 -vn 0.781598 -0.600241 -0.169751 -v 0.015783 -0.012284 0.003937 -vn 0.743842 -0.662534 -0.088025 -v 0.015150 -0.013056 0.003937 -vn 0.696493 -0.711399 -0.093851 -v 0.013546 -0.014714 0.003937 -vn 0.650915 -0.754026 -0.088059 -v 0.013500 -0.014757 0.003937 -vn 0.595731 -0.798346 -0.088023 -v 0.011660 -0.016250 0.003937 -vn 0.530436 -0.831341 -0.165861 -v 0.010939 -0.016743 0.003937 -vn 0.474551 -0.875592 -0.090218 -v 0.009656 -0.017515 0.003937 -vn 0.420283 -0.891809 -0.167448 -v 0.008034 -0.018315 0.003937 -vn 0.353437 -0.931306 -0.088038 -v 0.007517 -0.018534 0.003937 -vn 0.286416 -0.954051 -0.088044 -v 0.005272 -0.019293 0.003937 -vn 0.217510 -0.967346 -0.130119 -v 0.004910 -0.019388 0.003937 -vn 0.155501 -0.983905 -0.088034 -v 0.002953 -0.019781 0.003937 -vn 0.085614 -0.981553 -0.170951 -v 0.001652 -0.019932 0.003937 -vn 0.014066 -0.995976 -0.088514 -v 0.000593 -0.019991 0.003937 -vn -0.050207 -0.993498 -0.102183 -v -0.001652 -0.019932 0.003937 -vn -0.116226 -0.989312 -0.088052 -v -0.001776 -0.019921 0.003937 -vn -0.186176 -0.978565 -0.088028 -v -0.004120 -0.019571 0.003937 -vn -0.254530 -0.953198 -0.163182 -v -0.004910 -0.019388 0.003937 -vn -0.321229 -0.942901 -0.088031 -v -0.006405 -0.018947 0.003937 -vn -0.379577 -0.912570 -0.152111 -v -0.008034 -0.018315 0.003937 -vn -0.447889 -0.889744 -0.088038 -v -0.008601 -0.018056 0.003937 -vn -0.509940 -0.855691 -0.088056 -v -0.010676 -0.016912 0.003937 -vn -0.566189 -0.814994 -0.123350 -v -0.010939 -0.016743 0.003937 -vn -0.619785 -0.779818 -0.088040 -v -0.012602 -0.015530 0.003937 -vn -0.665657 -0.726244 -0.171669 -v -0.013546 -0.014714 0.003937 -vn -0.724541 -0.683494 -0.088750 -v -0.014350 -0.013931 0.003937 -vn -0.764041 -0.635536 -0.111068 -v -0.015783 -0.012284 0.003937 -vn -0.807945 -0.582645 -0.088035 -v -0.015897 -0.012136 0.003937 -vn -0.847278 -0.523803 -0.088039 -v -0.017221 -0.010171 0.003937 -vn -0.875111 -0.456708 -0.159995 -v -0.017589 -0.009519 0.003937 -vn -0.911904 -0.400850 -0.088038 -v -0.018303 -0.008062 0.003937 -vn -0.928561 -0.336663 -0.156309 -v -0.018916 -0.006494 0.003937 -vn -0.958592 -0.270841 -0.088013 -v -0.019128 -0.005841 0.003937 -vn -0.975403 -0.202067 -0.088078 -v -0.019685 -0.003538 0.003937 -vn -0.984127 -0.134192 -0.116131 -v -0.019727 -0.003292 0.003937 -vn -0.993609 -0.070614 -0.088060 -v -0.019965 -0.001185 0.003937 -vn -0.985109 -0.000000 -0.171930 -v -0.020000 -0.000000 0.003937 -vn -0.993419 0.072058 -0.089025 -v -0.019965 0.001185 0.003937 -vn -0.983935 0.131807 -0.120408 -v -0.019727 0.003292 0.003937 -vn -0.975403 0.202068 -0.088080 -v -0.019685 0.003538 0.003937 -vn -0.958593 0.270838 -0.088013 -v -0.019128 0.005841 0.003937 -vn -0.928561 0.336663 -0.156309 -v -0.018916 0.006494 0.003937 -vn -0.911904 0.400850 -0.088039 -v -0.018303 0.008062 0.003937 -vn -0.875111 0.456708 -0.159995 -v -0.017589 0.009519 0.003937 -vn -0.847277 0.523804 -0.088039 -v -0.017221 0.010171 0.003937 -vn -0.807945 0.582644 -0.088036 -v -0.015897 0.012136 0.003937 -vn -0.765316 0.634433 -0.108568 -v -0.015783 0.012284 0.003937 -vn -0.723838 0.684332 -0.088024 -v -0.014350 0.013931 0.003937 -vn -0.665657 0.726245 -0.171668 -v -0.013546 0.014714 0.003937 -vn -0.618293 0.780864 -0.089247 -v -0.012602 0.015530 0.003937 -vn -0.568194 0.812579 -0.129891 -v -0.010939 0.016743 0.003937 -vn -0.509940 0.855691 -0.088056 -v -0.010676 0.016912 0.003937 -vn -0.447889 0.889744 -0.088038 -v -0.008601 0.018056 0.003937 -vn -0.379577 0.912570 -0.152111 -v -0.008034 0.018315 0.003937 -vn -0.321229 0.942901 -0.088031 -v -0.006405 0.018947 0.003937 -vn -0.254530 0.953198 -0.163182 -v -0.004910 0.019388 0.003937 -vn -0.186176 0.978565 -0.088028 -v -0.004120 0.019571 0.003937 -vn -0.116226 0.989312 -0.088052 -v -0.001776 0.019921 0.003937 -vn -0.051230 0.993570 -0.100971 -v -0.001652 0.019932 0.003937 -vn 0.014794 0.996008 -0.088031 -v 0.000593 0.019991 0.003937 -vn 0.085614 0.981553 -0.170951 -v 0.001652 0.019932 0.003937 -vn 0.157636 0.983435 -0.089483 -v 0.002953 0.019781 0.003937 -vn 0.213612 0.966924 -0.139383 -v 0.004910 0.019388 0.003937 -vn 0.286416 0.954051 -0.088044 -v 0.005272 0.019293 0.003937 -vn 0.353438 0.931306 -0.088038 -v 0.007517 0.018534 0.003937 -vn 0.416434 0.897137 -0.147402 -v 0.008034 0.018315 0.003937 -vn 0.477520 0.874198 -0.088041 -v 0.009656 0.017515 0.003937 -vn 0.530436 0.831341 -0.165861 -v 0.010939 0.016743 0.003937 -vn 0.595731 0.798347 -0.088022 -v 0.011660 0.016250 0.003937 -vn 0.650915 0.754026 -0.088059 -v 0.013500 0.014757 0.003937 -vn 0.696493 0.711399 -0.093851 -v 0.013546 0.014714 0.003937 -vn 0.743842 0.662534 -0.088027 -v 0.015150 0.013056 0.003937 -vn 0.781598 0.600241 -0.169752 -v 0.015783 0.012284 0.003937 -vn 0.831341 0.548470 -0.089739 -v 0.016588 0.011173 0.003937 -vn 0.855411 0.496105 -0.148839 -v 0.017589 0.009519 0.003937 -vn 0.896918 0.433341 -0.088057 -v 0.017793 0.009133 0.003937 -vn 0.925427 0.368558 -0.088034 -v 0.018748 0.006964 0.003937 -vn 0.943411 0.299614 -0.142152 -v 0.018916 0.006494 0.003937 -vn 0.966960 0.239245 -0.088039 -v 0.019440 0.004698 0.003937 -vn 0.970896 0.170650 -0.168045 -v 0.019727 0.003292 0.003937 -vn -0.091480 -0.014489 -0.995701 -v -0.010371 -0.001643 -0.006063 -vn 0.091477 -0.014489 -0.995702 -v 0.010371 -0.001643 -0.006063 -vn 0.088084 -0.028620 -0.995702 -v 0.009986 -0.003245 -0.006063 -vn -0.042048 -0.082524 -0.995702 -v -0.004767 -0.009356 -0.006063 -vn -0.054440 -0.074930 -0.995702 -v -0.006172 -0.008495 -0.006063 -vn 0.014489 0.091478 -0.995702 -v 0.001643 0.010371 -0.006063 -vn -0.074931 0.054441 -0.995702 -v -0.008495 0.006172 -0.006063 -vn -0.065490 0.065490 -0.995702 -v -0.007425 0.007425 -0.006063 -vn -0.092621 0.000000 -0.995701 -v -0.010500 -0.000000 -0.006063 -vn -0.091480 0.014489 -0.995701 -v -0.010371 0.001643 -0.006063 -vn -0.088084 0.028621 -0.995702 -v -0.009986 0.003245 -0.006063 -vn -0.082527 0.042049 -0.995701 -v -0.009356 0.004767 -0.006063 -vn 0.000000 -0.092619 -0.995702 -v 0.000000 -0.010500 -0.006063 -vn -0.014489 -0.091478 -0.995702 -v -0.001643 -0.010371 -0.006063 -vn -0.028621 -0.088085 -0.995702 -v -0.003245 -0.009986 -0.006063 -vn 0.042048 -0.082524 -0.995702 -v 0.004767 -0.009356 -0.006063 -vn 0.028620 -0.088085 -0.995702 -v 0.003245 -0.009986 -0.006063 -vn 0.014489 -0.091478 -0.995702 -v 0.001643 -0.010371 -0.006063 -vn 0.082523 -0.042048 -0.995702 -v 0.009356 -0.004767 -0.006063 -vn 0.074931 -0.054441 -0.995702 -v 0.008495 -0.006172 -0.006063 -vn 0.065490 -0.065490 -0.995702 -v 0.007425 -0.007425 -0.006063 -vn 0.054440 -0.074930 -0.995702 -v 0.006172 -0.008495 -0.006063 -vn 0.091477 0.014488 -0.995702 -v 0.010371 0.001643 -0.006063 -vn 0.092621 0.000000 -0.995701 -v 0.010500 -0.000000 -0.006063 -vn -0.065490 -0.065490 -0.995702 -v -0.007425 -0.007425 -0.006063 -vn -0.074931 -0.054441 -0.995702 -v -0.008495 -0.006172 -0.006063 -vn -0.082526 -0.042049 -0.995701 -v -0.009356 -0.004767 -0.006063 -vn -0.088085 -0.028620 -0.995702 -v -0.009986 -0.003245 -0.006063 -vn 0.074931 0.054441 -0.995702 -v 0.008495 0.006172 -0.006063 -vn 0.082523 0.042048 -0.995702 -v 0.009356 0.004767 -0.006063 -vn 0.088084 0.028620 -0.995702 -v 0.009986 0.003245 -0.006063 -vn 0.028621 0.088085 -0.995702 -v 0.003245 0.009986 -0.006063 -vn 0.042048 0.082524 -0.995702 -v 0.004767 0.009356 -0.006063 -vn 0.054440 0.074930 -0.995702 -v 0.006172 0.008495 -0.006063 -vn 0.065490 0.065490 -0.995702 -v 0.007425 0.007425 -0.006063 -vn -0.054440 0.074930 -0.995702 -v -0.006172 0.008495 -0.006063 -vn -0.042048 0.082523 -0.995702 -v -0.004767 0.009356 -0.006063 -vn -0.028621 0.088085 -0.995702 -v -0.003245 0.009986 -0.006063 -vn -0.014489 0.091478 -0.995702 -v -0.001643 0.010371 -0.006063 -vn 0.000000 0.092619 -0.995702 -v 0.000000 0.010500 -0.006063 -vn 0.924562 0.101998 -0.367125 -v 0.019829 0.002362 0.003764 -vn 0.903543 0.220921 -0.367157 -v 0.019410 0.004690 0.003764 -vn 0.830985 0.416650 -0.368601 -v 0.017766 0.009118 0.003764 -vn 0.868148 0.332450 -0.368505 -v 0.018719 0.006953 0.003764 -vn 0.775249 0.515109 -0.365584 -v 0.016562 0.011156 0.003764 -vn 0.699760 0.612825 -0.367126 -v 0.015127 0.013036 0.003764 -vn 0.625870 0.688895 -0.365665 -v 0.013479 0.014734 0.003764 -vn 0.548976 0.750792 -0.367336 -v 0.011642 0.016225 0.003764 -vn 0.447500 0.815437 -0.367159 -v 0.009641 0.017488 0.003764 -vn 0.340766 0.864986 -0.368345 -v 0.007505 0.018505 0.003764 -vn 0.253317 0.894370 -0.368690 -v 0.005264 0.019263 0.003764 -vn 0.020842 0.929933 -0.367139 -v 0.000592 0.019960 0.003764 -vn 0.143539 0.919559 -0.365797 -v 0.002948 0.019750 0.003764 -vn -0.183145 0.911792 -0.367551 -v -0.004113 0.019541 0.003764 -vn -0.088193 0.925818 -0.367535 -v -0.001773 0.019890 0.003764 -vn -0.298924 0.880820 -0.367152 -v -0.006395 0.018917 0.003764 -vn -0.489190 0.790407 -0.368714 -v -0.010660 0.016886 0.003764 -vn -0.408131 0.835397 -0.368159 -v -0.008588 0.018028 0.003764 -vn -0.581280 0.726734 -0.366022 -v -0.012582 0.015506 0.003764 -vn -0.671593 0.643564 -0.367135 -v -0.014328 0.013909 0.003764 -vn -0.743334 0.558356 -0.368366 -v -0.015873 0.012117 0.003764 -vn -0.796183 0.480468 -0.367754 -v -0.017194 0.010155 0.003764 -vn -0.851375 0.374640 -0.367158 -v -0.018275 0.008050 0.003764 -vn -0.891900 0.262925 -0.367947 -v -0.019098 0.005832 0.003764 -vn -0.913534 0.171997 -0.368609 -v -0.019654 0.003532 0.003764 -vn -0.928191 -0.060435 -0.367162 -v -0.019934 -0.001183 0.003764 -vn -0.928447 0.061964 -0.366261 -v -0.019934 0.001183 0.003764 -vn -0.891899 -0.262928 -0.367948 -v -0.019098 -0.005832 0.003764 -vn -0.913392 -0.172520 -0.368717 -v -0.019654 -0.003532 0.003764 -vn -0.851375 -0.374641 -0.367158 -v -0.018275 -0.008050 0.003764 -vn -0.743064 -0.558799 -0.368239 -v -0.015873 -0.012117 0.003764 -vn -0.796184 -0.480466 -0.367756 -v -0.017194 -0.010155 0.003764 -vn -0.672570 -0.642928 -0.366461 -v -0.014328 -0.013909 0.003764 -vn -0.582472 -0.725208 -0.367150 -v -0.012582 -0.015506 0.003764 -vn -0.488701 -0.790667 -0.368805 -v -0.010660 -0.016886 0.003764 -vn -0.408131 -0.835397 -0.368159 -v -0.008588 -0.018028 0.003764 -vn -0.298924 -0.880820 -0.367152 -v -0.006395 -0.018917 0.003764 -vn -0.183145 -0.911792 -0.367551 -v -0.004113 -0.019541 0.003764 -vn -0.087755 -0.925916 -0.367395 -v -0.001773 -0.019890 0.003764 -vn 0.141226 -0.919378 -0.367149 -v 0.002948 -0.019750 0.003764 -vn 0.020089 -0.930127 -0.366688 -v 0.000592 -0.019960 0.003764 -vn 0.341256 -0.864814 -0.368294 -v 0.007505 -0.018505 0.003764 -vn 0.253839 -0.894190 -0.368767 -v 0.005264 -0.019263 0.003764 -vn 0.444930 -0.817751 -0.365131 -v 0.009641 -0.017488 0.003764 -vn 0.548977 -0.750792 -0.367336 -v 0.011642 -0.016225 0.003764 -vn 0.625869 -0.688895 -0.365666 -v 0.013479 -0.014734 0.003764 -vn 0.699760 -0.612826 -0.367125 -v 0.015127 -0.013036 0.003764 -vn 0.773275 -0.516952 -0.367161 -v 0.016562 -0.011156 0.003764 -vn 0.831205 -0.416153 -0.368667 -v 0.017766 -0.009118 0.003764 -vn 0.868360 -0.331960 -0.368448 -v 0.018719 -0.006953 0.003764 -vn 0.932186 0.000000 -0.361979 -v 0.019969 -0.000000 0.003764 -vn 0.924562 -0.101998 -0.367125 -v 0.019829 -0.002362 0.003764 -vn 0.903515 -0.224002 -0.365353 -v 0.019410 -0.004690 0.003764 -vn -0.109555 -0.000000 -0.993981 -v -0.019500 -0.000000 0.003437 -vn -0.090475 -0.006756 -0.995876 -v -0.019466 -0.001155 0.003437 -vn -0.370869 -0.023144 -0.928397 -v -0.019639 -0.001165 0.003468 -vn -0.090100 -0.016193 -0.995801 -v -0.019192 -0.003449 0.003437 -vn -0.364971 -0.065595 -0.928705 -v -0.019363 -0.003480 0.003468 -vn -0.087558 -0.026738 -0.995801 -v -0.018650 -0.005695 0.003437 -vn -0.354654 -0.108302 -0.928704 -v -0.018815 -0.005746 0.003468 -vn -0.083780 -0.036905 -0.995801 -v -0.017845 -0.007861 0.003437 -vn -0.339359 -0.149488 -0.928703 -v -0.018004 -0.007931 0.003468 -vn -0.078825 -0.046554 -0.995801 -v -0.016790 -0.009916 0.003437 -vn -0.319291 -0.188573 -0.928705 -v -0.016939 -0.010004 0.003468 -vn -0.072767 -0.055551 -0.995801 -v -0.015500 -0.011833 0.003437 -vn -0.294751 -0.225017 -0.928703 -v -0.015637 -0.011938 0.003468 -vn -0.065685 -0.063766 -0.995801 -v -0.013991 -0.013583 0.003437 -vn -0.266069 -0.258298 -0.928703 -v -0.014116 -0.013703 0.003468 -vn -0.057681 -0.071087 -0.995801 -v -0.012287 -0.015142 0.003437 -vn -0.233652 -0.287954 -0.928703 -v -0.012396 -0.015277 0.003468 -vn -0.048869 -0.077410 -0.995801 -v -0.010410 -0.016489 0.003437 -vn -0.197954 -0.313567 -0.928703 -v -0.010502 -0.016635 0.003468 -vn -0.039371 -0.082648 -0.995801 -v -0.008386 -0.017605 0.003437 -vn -0.159478 -0.334779 -0.928703 -v -0.008461 -0.017761 0.003468 -vn -0.029320 -0.086724 -0.995801 -v -0.006245 -0.018473 0.003437 -vn -0.118763 -0.351290 -0.928704 -v -0.006301 -0.018637 0.003468 -vn -0.018857 -0.089583 -0.995801 -v -0.004017 -0.019082 0.003437 -vn -0.076382 -0.362874 -0.928703 -v -0.004052 -0.019251 0.003468 -vn -0.008129 -0.091185 -0.995801 -v -0.001732 -0.019423 0.003437 -vn -0.032928 -0.369361 -0.928702 -v -0.001747 -0.019595 0.003468 -vn 0.002713 -0.091506 -0.995801 -v 0.000578 -0.019491 0.003437 -vn 0.010989 -0.370662 -0.928703 -v 0.000583 -0.019664 0.003468 -vn 0.013517 -0.090543 -0.995801 -v 0.002879 -0.019286 0.003437 -vn 0.054751 -0.366761 -0.928703 -v 0.002905 -0.019457 0.003468 -vn 0.024130 -0.088309 -0.995801 -v 0.005140 -0.018810 0.003437 -vn 0.097744 -0.357710 -0.928703 -v 0.005186 -0.018977 0.003468 -vn 0.034406 -0.084836 -0.995801 -v 0.007329 -0.018070 0.003437 -vn 0.139366 -0.343638 -0.928703 -v 0.007394 -0.018231 0.003468 -vn 0.044198 -0.080170 -0.995801 -v 0.009414 -0.017077 0.003437 -vn 0.179032 -0.324745 -0.928703 -v 0.009498 -0.017228 0.003468 -vn 0.053370 -0.074381 -0.995801 -v 0.011368 -0.015843 0.003437 -vn 0.216183 -0.301290 -0.928703 -v 0.011469 -0.015984 0.003468 -vn 0.061793 -0.067546 -0.995801 -v 0.013162 -0.014388 0.003437 -vn 0.250300 -0.273606 -0.928703 -v 0.013279 -0.014515 0.003468 -vn 0.069348 -0.059764 -0.995801 -v 0.014771 -0.012730 0.003437 -vn 0.280905 -0.242083 -0.928702 -v 0.014903 -0.012843 0.003468 -vn 0.075929 -0.051142 -0.995801 -v 0.016173 -0.010894 0.003437 -vn 0.307563 -0.207159 -0.928703 -v 0.016317 -0.010990 0.003468 -vn 0.081446 -0.041803 -0.995801 -v 0.017348 -0.008904 0.003437 -vn 0.329904 -0.169328 -0.928704 -v 0.017502 -0.008983 0.003468 -vn 0.085817 -0.031877 -0.995801 -v 0.018280 -0.006790 0.003437 -vn 0.347614 -0.129120 -0.928705 -v 0.018442 -0.006850 0.003468 -vn 0.088984 -0.021503 -0.995801 -v 0.018954 -0.004580 0.003437 -vn 0.360448 -0.087101 -0.928704 -v 0.019123 -0.004621 0.003468 -vn 0.090902 -0.010827 -0.995801 -v 0.019363 -0.002306 0.003437 -vn 0.368225 -0.043859 -0.928702 -v 0.019535 -0.002327 0.003468 -vn 0.091544 0.000000 -0.995801 -v 0.019500 -0.000000 0.003437 -vn 0.370828 -0.000000 -0.928702 -v 0.019673 -0.000000 0.003468 -vn 0.090902 0.010827 -0.995801 -v 0.019363 0.002306 0.003437 -vn 0.368225 0.043859 -0.928702 -v 0.019535 0.002327 0.003468 -vn 0.088984 0.021503 -0.995801 -v 0.018954 0.004580 0.003437 -vn 0.360447 0.087101 -0.928704 -v 0.019123 0.004621 0.003468 -vn 0.085817 0.031877 -0.995801 -v 0.018280 0.006790 0.003437 -vn 0.347614 0.129120 -0.928705 -v 0.018442 0.006850 0.003468 -vn 0.081446 0.041803 -0.995801 -v 0.017348 0.008904 0.003437 -vn 0.329904 0.169329 -0.928704 -v 0.017502 0.008983 0.003468 -vn 0.075929 0.051142 -0.995801 -v 0.016173 0.010894 0.003437 -vn 0.307563 0.207159 -0.928703 -v 0.016317 0.010990 0.003468 -vn 0.069348 0.059764 -0.995801 -v 0.014771 0.012730 0.003437 -vn 0.280905 0.242083 -0.928702 -v 0.014903 0.012843 0.003468 -vn 0.061793 0.067546 -0.995801 -v 0.013162 0.014388 0.003437 -vn 0.250300 0.273606 -0.928703 -v 0.013279 0.014515 0.003468 -vn 0.053370 0.074381 -0.995801 -v 0.011368 0.015843 0.003437 -vn 0.216183 0.301290 -0.928703 -v 0.011469 0.015984 0.003468 -vn 0.044198 0.080170 -0.995801 -v 0.009414 0.017077 0.003437 -vn 0.179032 0.324745 -0.928703 -v 0.009498 0.017228 0.003468 -vn 0.034406 0.084836 -0.995801 -v 0.007329 0.018070 0.003437 -vn 0.139365 0.343638 -0.928703 -v 0.007394 0.018231 0.003468 -vn 0.024131 0.088309 -0.995801 -v 0.005140 0.018810 0.003437 -vn 0.097744 0.357710 -0.928703 -v 0.005186 0.018977 0.003468 -vn 0.013517 0.090543 -0.995801 -v 0.002879 0.019286 0.003437 -vn 0.054751 0.366761 -0.928703 -v 0.002905 0.019457 0.003468 -vn 0.002713 0.091506 -0.995801 -v 0.000578 0.019491 0.003437 -vn 0.010989 0.370662 -0.928703 -v 0.000583 0.019664 0.003468 -vn -0.008129 0.091185 -0.995801 -v -0.001732 0.019423 0.003437 -vn -0.032928 0.369361 -0.928702 -v -0.001747 0.019595 0.003468 -vn -0.018857 0.089583 -0.995801 -v -0.004017 0.019082 0.003437 -vn -0.076382 0.362874 -0.928703 -v -0.004052 0.019251 0.003468 -vn -0.029320 0.086724 -0.995801 -v -0.006245 0.018473 0.003437 -vn -0.118763 0.351290 -0.928704 -v -0.006301 0.018637 0.003468 -vn -0.039371 0.082648 -0.995801 -v -0.008386 0.017605 0.003437 -vn -0.159478 0.334779 -0.928703 -v -0.008461 0.017761 0.003468 -vn -0.048869 0.077410 -0.995801 -v -0.010410 0.016489 0.003437 -vn -0.197954 0.313567 -0.928703 -v -0.010502 0.016635 0.003468 -vn -0.057681 0.071087 -0.995801 -v -0.012287 0.015142 0.003437 -vn -0.233652 0.287954 -0.928703 -v -0.012396 0.015277 0.003468 -vn -0.065685 0.063766 -0.995801 -v -0.013991 0.013583 0.003437 -vn -0.266069 0.258297 -0.928703 -v -0.014116 0.013703 0.003468 -vn -0.072767 0.055551 -0.995801 -v -0.015500 0.011833 0.003437 -vn -0.294752 0.225017 -0.928703 -v -0.015637 0.011938 0.003468 -vn -0.078825 0.046554 -0.995801 -v -0.016790 0.009916 0.003437 -vn -0.319291 0.188573 -0.928705 -v -0.016939 0.010004 0.003468 -vn -0.083780 0.036905 -0.995801 -v -0.017845 0.007861 0.003437 -vn -0.339359 0.149488 -0.928703 -v -0.018004 0.007931 0.003468 -vn -0.087558 0.026738 -0.995801 -v -0.018650 0.005695 0.003437 -vn -0.354654 0.108301 -0.928704 -v -0.018815 0.005746 0.003468 -vn -0.090100 0.016193 -0.995801 -v -0.019192 0.003449 0.003437 -vn -0.364971 0.065594 -0.928705 -v -0.019363 0.003480 0.003468 -vn -0.090475 0.006756 -0.995876 -v -0.019466 0.001155 0.003437 -vn -0.370869 0.023145 -0.928397 -v -0.019639 0.001165 0.003468 -vn 0.711124 0.000000 -0.703067 -v 0.019854 -0.000000 0.003583 -vn 0.706134 -0.084107 -0.703066 -v 0.019714 -0.002348 0.003583 -vn 0.691226 -0.167032 -0.703070 -v 0.019298 -0.004663 0.003583 -vn 0.666620 -0.247614 -0.703068 -v 0.018611 -0.006913 0.003583 -vn 0.632657 -0.324720 -0.703066 -v 0.017663 -0.009066 0.003583 -vn 0.589810 -0.397267 -0.703067 -v 0.016467 -0.011091 0.003583 -vn 0.538686 -0.464239 -0.703064 -v 0.015039 -0.012961 0.003583 -vn 0.479997 -0.524692 -0.703065 -v 0.013401 -0.014649 0.003583 -vn 0.414568 -0.577775 -0.703071 -v 0.011574 -0.016131 0.003583 -vn 0.343325 -0.622755 -0.703068 -v 0.009585 -0.017386 0.003583 -vn 0.267259 -0.658988 -0.703070 -v 0.007462 -0.018398 0.003583 -vn 0.187442 -0.685972 -0.703071 -v 0.005233 -0.019151 0.003583 -vn 0.104994 -0.703329 -0.703068 -v 0.002931 -0.019636 0.003583 -vn 0.021072 -0.710810 -0.703069 -v 0.000588 -0.019845 0.003583 -vn -0.063145 -0.708312 -0.703069 -v -0.001763 -0.019775 0.003583 -vn -0.146475 -0.695872 -0.703069 -v -0.004089 -0.019428 0.003583 -vn -0.227750 -0.673662 -0.703072 -v -0.006358 -0.018808 0.003583 -vn -0.305829 -0.641999 -0.703068 -v -0.008538 -0.017924 0.003583 -vn -0.379615 -0.601324 -0.703066 -v -0.010598 -0.016788 0.003583 -vn -0.448072 -0.552206 -0.703065 -v -0.012509 -0.015417 0.003583 -vn -0.510235 -0.495333 -0.703069 -v -0.014245 -0.013829 0.003583 -vn -0.565234 -0.431506 -0.703074 -v -0.015781 -0.012047 0.003583 -vn -0.612311 -0.361628 -0.703065 -v -0.017095 -0.010096 0.003583 -vn -0.650779 -0.286669 -0.703070 -v -0.018169 -0.008003 0.003583 -vn -0.680111 -0.207688 -0.703075 -v -0.018988 -0.005798 0.003583 -vn -0.699918 -0.125791 -0.703058 -v -0.019540 -0.003512 0.003583 -vn -0.709886 -0.042128 -0.703056 -v -0.019819 -0.001176 0.003583 -vn -0.709885 0.042128 -0.703056 -v -0.019819 0.001176 0.003583 -vn -0.699918 0.125792 -0.703058 -v -0.019540 0.003512 0.003583 -vn -0.680111 0.207686 -0.703075 -v -0.018988 0.005798 0.003583 -vn -0.650779 0.286669 -0.703070 -v -0.018169 0.008003 0.003583 -vn -0.612311 0.361629 -0.703065 -v -0.017095 0.010096 0.003583 -vn -0.565234 0.431506 -0.703074 -v -0.015781 0.012047 0.003583 -vn -0.510235 0.495332 -0.703070 -v -0.014245 0.013829 0.003583 -vn -0.448072 0.552207 -0.703064 -v -0.012509 0.015417 0.003583 -vn -0.379615 0.601324 -0.703066 -v -0.010598 0.016788 0.003583 -vn -0.305829 0.642000 -0.703068 -v -0.008538 0.017924 0.003583 -vn -0.227750 0.673662 -0.703072 -v -0.006358 0.018808 0.003583 -vn -0.146475 0.695873 -0.703069 -v -0.004089 0.019428 0.003583 -vn -0.063145 0.708312 -0.703070 -v -0.001763 0.019775 0.003583 -vn 0.021072 0.710809 -0.703069 -v 0.000588 0.019845 0.003583 -vn 0.104995 0.703329 -0.703068 -v 0.002931 0.019636 0.003583 -vn 0.187442 0.685972 -0.703071 -v 0.005233 0.019151 0.003583 -vn 0.267259 0.658988 -0.703070 -v 0.007462 0.018398 0.003583 -vn 0.343325 0.622755 -0.703068 -v 0.009585 0.017386 0.003583 -vn 0.414568 0.577776 -0.703071 -v 0.011574 0.016131 0.003583 -vn 0.479998 0.524692 -0.703065 -v 0.013401 0.014649 0.003583 -vn 0.538686 0.464239 -0.703064 -v 0.015039 0.012961 0.003583 -vn 0.589810 0.397267 -0.703068 -v 0.016467 0.011091 0.003583 -vn 0.632657 0.324720 -0.703066 -v 0.017663 0.009066 0.003583 -vn 0.666621 0.247614 -0.703068 -v 0.018611 0.006913 0.003583 -vn 0.691226 0.167032 -0.703070 -v 0.019298 0.004663 0.003583 -vn 0.706134 0.084107 -0.703065 -v 0.019714 0.002348 0.003583 -vn 0.960008 0.226740 -0.164235 -v 0.010724 0.002448 -0.005563 -vn 0.920026 0.135790 -0.367579 -v 0.010834 0.001716 -0.005736 -vn 0.882897 0.292132 -0.367631 -v 0.010432 0.003390 -0.005736 -vn 0.749796 0.637204 -0.178263 -v 0.008600 0.006858 -0.005563 -vn 0.821815 0.562878 -0.088253 -v 0.008899 0.006466 -0.005563 -vn 0.758002 0.537895 -0.368920 -v 0.008874 0.006447 -0.005736 -vn 0.871931 0.481612 -0.088237 -v 0.009801 0.004994 -0.005563 -vn 0.823072 0.431120 -0.369713 -v 0.009774 0.004980 -0.005736 -vn 0.908868 0.398720 -0.122396 -v 0.009911 0.004773 -0.005563 -vn 0.943845 0.318445 -0.088033 -v 0.010462 0.003399 -0.005563 -vn 0.707630 0.700614 -0.091652 -v 0.007778 0.007778 -0.005563 -vn 0.662191 0.654762 -0.364403 -v 0.007756 0.007756 -0.005736 -vn 0.633622 0.758886 -0.150380 -v 0.006858 0.008600 -0.005563 -vn 0.537160 0.758476 -0.369018 -v 0.006447 0.008874 -0.005736 -vn 0.562930 0.821762 -0.088418 -v 0.006466 0.008899 -0.005563 -vn 0.430317 0.823577 -0.369525 -v 0.004980 0.009774 -0.005736 -vn 0.481481 0.871983 -0.088436 -v 0.004994 0.009801 -0.005563 -vn -0.135789 0.920027 -0.367575 -v -0.001716 0.010834 -0.005736 -vn 0.000024 0.996025 -0.089077 -v 0.000000 0.011000 -0.005563 -vn 0.000001 0.932495 -0.361183 -v 0.000000 0.010969 -0.005736 -vn 0.134068 0.987003 -0.088606 -v 0.001721 0.010865 -0.005563 -vn 0.135788 0.920027 -0.367575 -v 0.001716 0.010834 -0.005736 -vn 0.226889 0.959960 -0.164310 -v 0.002448 0.010724 -0.005563 -vn 0.294865 0.882661 -0.366011 -v 0.003390 0.010432 -0.005736 -vn 0.320494 0.942957 -0.090086 -v 0.003399 0.010462 -0.005563 -vn 0.394826 0.909473 -0.130272 -v 0.004773 0.009911 -0.005563 -vn -0.292133 0.882898 -0.367627 -v -0.003390 0.010432 -0.005736 -vn -0.226613 0.960006 -0.164425 -v -0.002448 0.010724 -0.005563 -vn -0.134197 0.986990 -0.088557 -v -0.001721 0.010865 -0.005563 -vn -0.637092 0.749850 -0.178434 -v -0.006858 0.008600 -0.005563 -vn -0.563106 0.821614 -0.088668 -v -0.006466 0.008899 -0.005563 -vn -0.537896 0.758001 -0.368921 -v -0.006447 0.008874 -0.005736 -vn -0.481316 0.872053 -0.088647 -v -0.004994 0.009801 -0.005563 -vn -0.431117 0.823073 -0.369715 -v -0.004980 0.009774 -0.005736 -vn -0.398943 0.908722 -0.122758 -v -0.004773 0.009911 -0.005563 -vn -0.318306 0.943846 -0.088525 -v -0.003399 0.010462 -0.005563 -vn -0.700580 0.707622 -0.091972 -v -0.007778 0.007778 -0.005563 -vn -0.654762 0.662191 -0.364404 -v -0.007756 0.007756 -0.005736 -vn -0.758989 0.633463 -0.150534 -v -0.008600 0.006858 -0.005563 -vn -0.758477 0.537158 -0.369017 -v -0.008874 0.006447 -0.005736 -vn -0.821595 0.563132 -0.088677 -v -0.008899 0.006466 -0.005563 -vn -0.823579 0.430317 -0.369520 -v -0.009774 0.004980 -0.005736 -vn -0.872067 0.481273 -0.088746 -v -0.009801 0.004994 -0.005563 -vn -0.920026 -0.135789 -0.367578 -v -0.010834 -0.001716 -0.005736 -vn -0.995992 -0.000001 -0.089439 -v -0.011000 -0.000000 -0.005563 -vn -0.932501 -0.000001 -0.361167 -v -0.010969 -0.000000 -0.005736 -vn -0.986964 0.134311 -0.088667 -v -0.010865 0.001721 -0.005563 -vn -0.920026 0.135790 -0.367579 -v -0.010834 0.001716 -0.005736 -vn -0.960008 0.226755 -0.164217 -v -0.010724 0.002448 -0.005563 -vn -0.882660 0.294865 -0.366013 -v -0.010432 0.003390 -0.005736 -vn -0.942967 0.320415 -0.090259 -v -0.010462 0.003399 -0.005563 -vn -0.909403 0.394926 -0.130457 -v -0.009911 0.004773 -0.005563 -vn -0.882897 -0.292133 -0.367630 -v -0.010432 -0.003390 -0.005736 -vn -0.960008 -0.226755 -0.164217 -v -0.010724 -0.002448 -0.005563 -vn -0.986964 -0.134310 -0.088668 -v -0.010865 -0.001721 -0.005563 -vn -0.749786 -0.637220 -0.178246 -v -0.008600 -0.006858 -0.005563 -vn -0.821595 -0.563133 -0.088678 -v -0.008899 -0.006466 -0.005563 -vn -0.758002 -0.537895 -0.368920 -v -0.008874 -0.006447 -0.005736 -vn -0.872067 -0.481273 -0.088746 -v -0.009801 -0.004994 -0.005563 -vn -0.823075 -0.431117 -0.369710 -v -0.009774 -0.004980 -0.005736 -vn -0.908871 -0.398724 -0.122365 -v -0.009911 -0.004773 -0.005563 -vn -0.943854 -0.318429 -0.087994 -v -0.010462 -0.003399 -0.005563 -vn -0.707650 -0.700601 -0.091592 -v -0.007778 -0.007778 -0.005563 -vn -0.662191 -0.654762 -0.364405 -v -0.007756 -0.007756 -0.005736 -vn -0.633594 -0.758923 -0.150313 -v -0.006858 -0.008600 -0.005563 -vn -0.537160 -0.758476 -0.369018 -v -0.006447 -0.008874 -0.005736 -vn -0.563106 -0.821614 -0.088668 -v -0.006466 -0.008899 -0.005563 -vn -0.430316 -0.823576 -0.369527 -v -0.004980 -0.009774 -0.005736 -vn -0.481314 -0.872054 -0.088649 -v -0.004994 -0.009801 -0.005563 -vn 0.135789 -0.920027 -0.367576 -v 0.001716 -0.010834 -0.005736 -vn -0.000401 -0.996079 -0.088463 -v 0.000000 -0.011000 -0.005563 -vn 0.000000 -0.932495 -0.361182 -v 0.000000 -0.010969 -0.005736 -vn -0.134196 -0.987096 -0.087366 -v -0.001721 -0.010865 -0.005563 -vn -0.135789 -0.920027 -0.367576 -v -0.001716 -0.010834 -0.005736 -vn -0.226421 -0.960195 -0.163583 -v -0.002448 -0.010724 -0.005563 -vn -0.294865 -0.882661 -0.366011 -v -0.003390 -0.010432 -0.005736 -vn -0.320521 -0.942955 -0.090010 -v -0.003399 -0.010462 -0.005563 -vn -0.394806 -0.909483 -0.130261 -v -0.004773 -0.009911 -0.005563 -vn 0.292133 -0.882898 -0.367627 -v 0.003390 -0.010432 -0.005736 -vn 0.227133 -0.960007 -0.163702 -v 0.002448 -0.010724 -0.005563 -vn 0.134168 -0.987002 -0.088464 -v 0.001721 -0.010865 -0.005563 -vn 0.637560 -0.749623 -0.177714 -v 0.006858 -0.008600 -0.005563 -vn 0.562969 -0.821742 -0.088352 -v 0.006466 -0.008899 -0.005563 -vn 0.537896 -0.758001 -0.368921 -v 0.006447 -0.008874 -0.005736 -vn 0.481479 -0.871984 -0.088438 -v 0.004994 -0.009801 -0.005563 -vn 0.431116 -0.823072 -0.369717 -v 0.004980 -0.009774 -0.005736 -vn 0.398724 -0.908871 -0.122366 -v 0.004773 -0.009911 -0.005563 -vn 0.318100 -0.944012 -0.087485 -v 0.003399 -0.010462 -0.005563 -vn 0.700378 -0.707934 -0.091107 -v 0.007778 -0.007778 -0.005563 -vn 0.654762 -0.662190 -0.364405 -v 0.007756 -0.007756 -0.005736 -vn 0.758990 -0.633540 -0.150201 -v 0.008600 -0.006858 -0.005563 -vn 0.758477 -0.537158 -0.369018 -v 0.008874 -0.006447 -0.005736 -vn 0.822015 -0.562682 -0.087639 -v 0.008899 -0.006466 -0.005563 -vn 0.823576 -0.430320 -0.369523 -v 0.009774 -0.004980 -0.005736 -vn 0.871804 -0.481939 -0.087708 -v 0.009801 -0.004994 -0.005563 -vn 0.987087 0.133835 -0.088025 -v 0.010865 0.001721 -0.005563 -vn 0.996127 -0.000051 -0.087930 -v 0.011000 -0.000000 -0.005563 -vn 0.932494 0.000000 -0.361186 -v 0.010969 -0.000000 -0.005736 -vn 0.987100 -0.133809 -0.087918 -v 0.010865 -0.001721 -0.005563 -vn 0.920026 -0.135790 -0.367578 -v 0.010834 -0.001716 -0.005736 -vn 0.960020 -0.226776 -0.164120 -v 0.010724 -0.002448 -0.005563 -vn 0.882660 -0.294865 -0.366014 -v 0.010432 -0.003390 -0.005736 -vn 0.942882 -0.320865 -0.089549 -v 0.010462 -0.003399 -0.005563 -vn 0.909683 -0.394514 -0.129750 -v 0.009911 -0.004773 -0.005563 -vn 0.372871 0.000001 -0.927883 -v 0.010673 -0.000000 -0.006032 -vn 0.368284 0.058330 -0.927882 -v 0.010542 0.001670 -0.006032 -vn 0.354621 0.115224 -0.927883 -v 0.010151 0.003298 -0.006032 -vn 0.332233 0.169281 -0.927882 -v 0.009510 0.004845 -0.006032 -vn 0.301660 0.219170 -0.927882 -v 0.008635 0.006273 -0.006032 -vn 0.263660 0.263660 -0.927883 -v 0.007547 0.007547 -0.006032 -vn 0.219170 0.301662 -0.927882 -v 0.006273 0.008635 -0.006032 -vn 0.169281 0.332232 -0.927882 -v 0.004845 0.009510 -0.006032 -vn 0.115225 0.354624 -0.927882 -v 0.003298 0.010151 -0.006032 -vn 0.058330 0.368283 -0.927882 -v 0.001670 0.010542 -0.006032 -vn -0.000000 0.372872 -0.927883 -v 0.000000 0.010673 -0.006032 -vn -0.058330 0.368283 -0.927882 -v -0.001670 0.010542 -0.006032 -vn -0.115224 0.354625 -0.927882 -v -0.003298 0.010151 -0.006032 -vn -0.169281 0.332232 -0.927882 -v -0.004845 0.009510 -0.006032 -vn -0.219170 0.301662 -0.927882 -v -0.006273 0.008635 -0.006032 -vn -0.263660 0.263660 -0.927883 -v -0.007547 0.007547 -0.006032 -vn -0.301661 0.219169 -0.927882 -v -0.008635 0.006273 -0.006032 -vn -0.332228 0.169279 -0.927884 -v -0.009510 0.004845 -0.006032 -vn -0.354622 0.115224 -0.927883 -v -0.010151 0.003298 -0.006032 -vn -0.368278 0.058329 -0.927884 -v -0.010542 0.001670 -0.006032 -vn -0.372871 0.000000 -0.927883 -v -0.010673 -0.000000 -0.006032 -vn -0.368278 -0.058330 -0.927884 -v -0.010542 -0.001670 -0.006032 -vn -0.354622 -0.115223 -0.927883 -v -0.010151 -0.003298 -0.006032 -vn -0.332228 -0.169280 -0.927884 -v -0.009510 -0.004845 -0.006032 -vn -0.301661 -0.219169 -0.927882 -v -0.008635 -0.006273 -0.006032 -vn -0.263661 -0.263660 -0.927883 -v -0.007547 -0.007547 -0.006032 -vn -0.219170 -0.301662 -0.927882 -v -0.006273 -0.008635 -0.006032 -vn -0.169281 -0.332232 -0.927882 -v -0.004845 -0.009510 -0.006032 -vn -0.115224 -0.354623 -0.927882 -v -0.003298 -0.010151 -0.006032 -vn -0.058330 -0.368282 -0.927883 -v -0.001670 -0.010542 -0.006032 -vn 0.000000 -0.372873 -0.927882 -v 0.000000 -0.010673 -0.006032 -vn 0.058330 -0.368282 -0.927883 -v 0.001670 -0.010542 -0.006032 -vn 0.115224 -0.354623 -0.927882 -v 0.003298 -0.010151 -0.006032 -vn 0.169281 -0.332232 -0.927882 -v 0.004845 -0.009510 -0.006032 -vn 0.219170 -0.301662 -0.927882 -v 0.006273 -0.008635 -0.006032 -vn 0.263660 -0.263660 -0.927883 -v 0.007547 -0.007547 -0.006032 -vn 0.301661 -0.219169 -0.927882 -v 0.008635 -0.006273 -0.006032 -vn 0.332233 -0.169282 -0.927882 -v 0.009510 -0.004845 -0.006032 -vn 0.354622 -0.115223 -0.927883 -v 0.010151 -0.003298 -0.006032 -vn 0.368284 -0.058331 -0.927882 -v 0.010542 -0.001670 -0.006032 -vn 0.712397 0.000000 -0.701777 -v 0.010854 -0.000000 -0.005917 -vn 0.703631 -0.111445 -0.701772 -v 0.010720 -0.001698 -0.005917 -vn 0.677531 -0.220143 -0.701775 -v 0.010322 -0.003354 -0.005917 -vn 0.634759 -0.323427 -0.701767 -v 0.009671 -0.004927 -0.005917 -vn 0.576345 -0.418739 -0.701772 -v 0.008781 -0.006380 -0.005917 -vn 0.503747 -0.503747 -0.701768 -v 0.007675 -0.007675 -0.005917 -vn 0.418737 -0.576343 -0.701775 -v 0.006380 -0.008781 -0.005917 -vn 0.323422 -0.634752 -0.701775 -v 0.004927 -0.009671 -0.005917 -vn 0.220144 -0.677534 -0.701773 -v 0.003354 -0.010322 -0.005917 -vn 0.111444 -0.703630 -0.701773 -v 0.001698 -0.010720 -0.005917 -vn 0.000000 -0.712400 -0.701774 -v 0.000000 -0.010854 -0.005917 -vn -0.111444 -0.703630 -0.701773 -v -0.001698 -0.010720 -0.005917 -vn -0.220144 -0.677534 -0.701772 -v -0.003354 -0.010322 -0.005917 -vn -0.323422 -0.634752 -0.701775 -v -0.004927 -0.009671 -0.005917 -vn -0.418736 -0.576343 -0.701776 -v -0.006380 -0.008781 -0.005917 -vn -0.503748 -0.503746 -0.701768 -v -0.007675 -0.007675 -0.005917 -vn -0.576345 -0.418739 -0.701772 -v -0.008781 -0.006380 -0.005917 -vn -0.634754 -0.323424 -0.701772 -v -0.009671 -0.004927 -0.005917 -vn -0.677531 -0.220143 -0.701775 -v -0.010322 -0.003354 -0.005917 -vn -0.703625 -0.111444 -0.701778 -v -0.010720 -0.001698 -0.005917 -vn -0.712396 0.000000 -0.701777 -v -0.010854 -0.000000 -0.005917 -vn -0.703625 0.111443 -0.701778 -v -0.010720 0.001698 -0.005917 -vn -0.677531 0.220143 -0.701775 -v -0.010322 0.003354 -0.005917 -vn -0.634754 0.323424 -0.701772 -v -0.009671 0.004927 -0.005917 -vn -0.576345 0.418739 -0.701773 -v -0.008781 0.006380 -0.005917 -vn -0.503748 0.503748 -0.701767 -v -0.007675 0.007675 -0.005917 -vn -0.418737 0.576343 -0.701775 -v -0.006380 0.008781 -0.005917 -vn -0.323422 0.634752 -0.701775 -v -0.004927 0.009671 -0.005917 -vn -0.220144 0.677533 -0.701773 -v -0.003354 0.010322 -0.005917 -vn -0.111444 0.703629 -0.701774 -v -0.001698 0.010720 -0.005917 -vn 0.000000 0.712401 -0.701773 -v 0.000000 0.010854 -0.005917 -vn 0.111444 0.703629 -0.701774 -v 0.001698 0.010720 -0.005917 -vn 0.220144 0.677533 -0.701773 -v 0.003354 0.010322 -0.005917 -vn 0.323422 0.634752 -0.701775 -v 0.004927 0.009671 -0.005917 -vn 0.418736 0.576343 -0.701776 -v 0.006380 0.008781 -0.005917 -vn 0.503748 0.503747 -0.701767 -v 0.007675 0.007675 -0.005917 -vn 0.576344 0.418739 -0.701773 -v 0.008781 0.006380 -0.005917 -vn 0.634759 0.323426 -0.701767 -v 0.009671 0.004927 -0.005917 -vn 0.677531 0.220144 -0.701775 -v 0.010322 0.003354 -0.005917 -vn 0.703631 0.111444 -0.701772 -v 0.010720 0.001698 -0.005917 -vn -0.056922 -0.062678 -0.996409 -v -0.011093 -0.012215 0.003437 -vn -0.064469 -0.054883 -0.996409 -v -0.012564 -0.010696 0.003437 -vn -0.070959 -0.046189 -0.996409 -v -0.013828 -0.009001 0.003437 -vn -0.076284 -0.036737 -0.996409 -v -0.014866 -0.007159 0.003437 -vn -0.080356 -0.026680 -0.996409 -v -0.015659 -0.005199 0.003437 -vn -0.083111 -0.016186 -0.996409 -v -0.016196 -0.003154 0.003437 -vn -0.085301 -0.006811 -0.996332 -v -0.016466 -0.001057 0.003437 -vn -0.074151 0.000000 -0.997247 -v -0.016500 -0.000000 0.003437 -vn -0.085300 0.006811 -0.996332 -v -0.016466 0.001057 0.003437 -vn -0.083111 0.016186 -0.996409 -v -0.016196 0.003154 0.003437 -vn -0.080356 0.026680 -0.996409 -v -0.015659 0.005199 0.003437 -vn -0.076284 0.036737 -0.996409 -v -0.014866 0.007159 0.003437 -vn -0.070959 0.046189 -0.996409 -v -0.013828 0.009001 0.003437 -vn -0.064469 0.054883 -0.996409 -v -0.012564 0.010696 0.003437 -vn 0.060820 -0.058901 -0.996409 -v 0.011853 -0.011479 0.003437 -vn 0.052790 -0.066197 -0.996409 -v 0.010288 -0.012900 0.003437 -vn 0.043891 -0.072403 -0.996409 -v 0.008553 -0.014110 0.003437 -vn 0.034272 -0.077422 -0.996409 -v 0.006679 -0.015088 0.003437 -vn 0.024090 -0.081169 -0.996409 -v 0.004695 -0.015818 0.003437 -vn 0.013513 -0.083582 -0.996409 -v 0.002633 -0.016289 0.003437 -vn 0.002714 -0.084624 -0.996409 -v 0.000529 -0.016492 0.003437 -vn -0.008130 -0.084277 -0.996409 -v -0.001584 -0.016424 0.003437 -vn -0.018841 -0.082546 -0.996409 -v -0.003672 -0.016086 0.003437 -vn -0.029242 -0.079459 -0.996409 -v -0.005699 -0.015485 0.003437 -vn -0.039163 -0.075068 -0.996409 -v -0.007632 -0.014629 0.003437 -vn -0.048440 -0.069442 -0.996409 -v -0.009440 -0.013533 0.003437 -vn 0.052790 0.066197 -0.996409 -v 0.010288 0.012900 0.003437 -vn 0.060820 0.058901 -0.996409 -v 0.011853 0.011479 0.003437 -vn 0.067854 0.050641 -0.996409 -v 0.013223 0.009869 0.003437 -vn 0.073775 0.041549 -0.996409 -v 0.014377 0.008097 0.003437 -vn 0.078481 0.031773 -0.996409 -v 0.015294 0.006192 0.003437 -vn 0.081899 0.021476 -0.996409 -v 0.015960 0.004185 0.003437 -vn 0.083976 0.010828 -0.996409 -v 0.016365 0.002110 0.003437 -vn 0.084670 -0.000000 -0.996409 -v 0.016500 -0.000000 0.003437 -vn 0.083976 -0.010827 -0.996409 -v 0.016365 -0.002110 0.003437 -vn 0.081899 -0.021477 -0.996409 -v 0.015960 -0.004185 0.003437 -vn 0.078480 -0.031773 -0.996409 -v 0.015294 -0.006192 0.003437 -vn 0.073775 -0.041549 -0.996409 -v 0.014377 -0.008097 0.003437 -vn 0.067854 -0.050641 -0.996409 -v 0.013223 -0.009869 0.003437 -vn -0.056923 0.062678 -0.996409 -v -0.011093 0.012215 0.003437 -vn -0.048440 0.069442 -0.996409 -v -0.009440 0.013533 0.003437 -vn -0.039163 0.075068 -0.996409 -v -0.007632 0.014629 0.003437 -vn -0.029242 0.079459 -0.996409 -v -0.005699 0.015485 0.003437 -vn -0.018841 0.082546 -0.996409 -v -0.003672 0.016086 0.003437 -vn -0.008130 0.084277 -0.996409 -v -0.001584 0.016424 0.003437 -vn 0.002714 0.084624 -0.996409 -v 0.000529 0.016492 0.003437 -vn 0.013513 0.083582 -0.996409 -v 0.002633 0.016289 0.003437 -vn 0.024090 0.081169 -0.996409 -v 0.004695 0.015818 0.003437 -vn 0.034272 0.077422 -0.996409 -v 0.006679 0.015088 0.003437 -vn 0.043891 0.072403 -0.996409 -v 0.008553 0.014110 0.003437 -vn 0.498336 -0.862501 -0.088054 -v 0.005255 -0.009664 0.004437 -vn 0.416629 -0.908856 -0.020013 -v 0.004773 -0.009911 0.004437 -vn 0.333153 -0.938657 -0.089064 -v 0.003718 -0.010353 0.004437 -vn 0.250227 -0.967439 -0.038057 -v 0.002448 -0.010724 0.004437 -vn 0.160608 -0.983069 -0.088210 -v 0.002094 -0.010799 0.004437 -vn 0.066459 -0.993901 -0.087995 -v 0.000421 -0.010992 0.004437 -vn -0.034146 -0.999384 -0.008072 -v 0.000000 -0.011000 0.004437 -vn -0.107873 -0.990402 -0.086415 -v -0.001262 -0.010927 0.004437 -vn -0.201181 -0.979228 -0.025268 -v -0.002448 -0.010724 0.004437 -vn -0.612289 -0.790475 -0.015846 -v -0.006858 -0.008600 0.004437 -vn -0.533102 -0.841685 -0.085841 -v -0.005979 -0.009233 0.004437 -vn -0.466870 -0.883706 -0.033109 -v -0.004773 -0.009911 0.004437 -vn -0.379007 -0.921216 -0.087835 -v -0.004500 -0.010038 0.004437 -vn -0.289441 -0.953107 -0.088381 -v -0.002915 -0.010607 0.004437 -vn -0.898048 -0.439768 -0.010662 -v -0.009911 -0.004773 0.004437 -vn -0.849108 -0.521076 -0.086582 -v -0.009455 -0.005621 0.004437 -vn -0.804530 -0.591069 -0.058050 -v -0.008600 -0.006858 0.004437 -vn -0.746648 -0.659412 -0.087711 -v -0.008486 -0.006999 0.004437 -vn -0.680107 -0.727731 -0.088671 -v -0.007319 -0.008212 0.004437 -vn -0.931301 -0.353190 -0.089080 -v -0.010203 -0.004112 0.004437 -vn -0.961028 -0.262201 -0.087616 -v -0.010711 -0.002506 0.004437 -vn -0.979779 -0.183510 -0.079736 -v -0.010724 -0.002448 0.004437 -vn -0.991710 -0.094131 -0.087471 -v -0.010968 -0.000842 0.004437 -vn -0.999969 -0.000000 -0.007813 -v -0.011000 -0.000000 0.004437 -vn -0.991732 0.093491 -0.087902 -v -0.010968 0.000842 0.004437 -vn -0.979577 0.184269 -0.080455 -v -0.010724 0.002448 0.004437 -vn -0.961028 0.262200 -0.087617 -v -0.010711 0.002506 0.004437 -vn -0.931694 0.352473 -0.087806 -v -0.010203 0.004112 0.004437 -vn -0.897704 0.440496 -0.009505 -v -0.009911 0.004773 0.004437 -vn -0.850013 0.519380 -0.087873 -v -0.009455 0.005621 0.004437 -vn -0.802553 0.593290 -0.062582 -v -0.008600 0.006858 0.004437 -vn -0.746646 0.659413 -0.087714 -v -0.008486 0.006999 0.004437 -vn -0.680572 0.727404 -0.087783 -v -0.007319 0.008212 0.004437 -vn -0.611853 0.790829 -0.015029 -v -0.006858 0.008600 0.004437 -vn -0.535699 0.839812 -0.087993 -v -0.005979 0.009233 0.004437 -vn -0.461827 0.885817 -0.045221 -v -0.004773 0.009911 0.004437 -vn -0.379006 0.921216 -0.087835 -v -0.004500 0.010038 0.004437 -vn -0.289801 0.953050 -0.087811 -v -0.002915 0.010607 0.004437 -vn -0.192064 0.981362 0.006317 -v -0.002448 0.010724 0.004437 -vn -0.117743 0.989419 -0.084777 -v -0.001262 0.010927 0.004437 -vn -0.025578 0.999198 -0.030804 -v 0.000000 0.011000 0.004437 -vn 0.066460 0.993901 -0.087998 -v 0.000421 0.010992 0.004437 -vn 0.160412 0.983129 -0.087891 -v 0.002094 0.010799 0.004437 -vn 0.256819 0.966252 -0.020048 -v 0.002448 0.010724 0.004437 -vn 0.329523 0.940258 -0.085612 -v 0.003718 0.010353 0.004437 -vn 0.416959 0.908716 -0.019497 -v 0.004773 0.009911 0.004437 -vn 0.498336 0.862501 -0.088055 -v 0.005255 0.009664 0.004437 -vn 0.577686 0.811501 -0.088005 -v 0.006668 0.008748 0.004437 -vn 0.652620 0.756292 -0.045942 -v 0.006858 0.008600 0.004437 -vn 0.709487 0.699387 -0.086527 -v 0.007926 0.007628 0.004437 -vn 0.774689 0.632229 -0.011954 -v 0.008600 0.006858 0.004437 -vn 0.827845 0.553977 -0.088223 -v 0.008997 0.006329 0.004437 -vn 0.876413 0.473421 -0.088163 -v 0.009858 0.004881 0.004437 -vn 0.915405 0.396383 -0.070098 -v 0.009911 0.004773 0.004437 -vn 0.944716 0.315994 -0.087520 -v 0.010487 0.003319 0.004437 -vn 0.974047 0.226196 -0.008250 -v 0.010724 0.002448 0.004437 -vn 0.987330 0.131731 -0.088467 -v 0.010871 0.001679 0.004437 -vn 0.996061 -0.000051 -0.088676 -v 0.011000 -0.000000 0.004437 -vn 0.987324 -0.131701 -0.088575 -v 0.010871 -0.001679 0.004437 -vn 0.974037 -0.226232 -0.008372 -v 0.010724 -0.002448 0.004437 -vn 0.945021 -0.314778 -0.088597 -v 0.010487 -0.003319 0.004437 -vn 0.914561 -0.397908 -0.072440 -v 0.009911 -0.004773 0.004437 -vn 0.876209 -0.473698 -0.088704 -v 0.009858 -0.004881 0.004437 -vn 0.827969 -0.553692 -0.088840 -v 0.008997 -0.006329 0.004437 -vn 0.774606 -0.632325 -0.012320 -v 0.008600 -0.006858 0.004437 -vn 0.711139 -0.697422 -0.088791 -v 0.007926 -0.007628 0.004437 -vn 0.649248 -0.758644 -0.054188 -v 0.006858 -0.008600 0.004437 -vn 0.577752 -0.811439 -0.088145 -v 0.006668 -0.008748 0.004437 -vn -0.355871 0.024222 -0.934221 -v -0.016293 0.001046 0.003406 -vn -0.350933 0.068344 -0.933903 -v -0.016026 0.003121 0.003406 -vn -0.339321 0.112662 -0.933900 -v -0.015495 0.005145 0.003406 -vn -0.322129 0.155129 -0.933899 -v -0.014710 0.007084 0.003406 -vn -0.299642 0.195046 -0.933901 -v -0.013683 0.008907 0.003406 -vn -0.272242 0.231763 -0.933901 -v -0.012432 0.010584 0.003406 -vn -0.240368 0.264672 -0.933902 -v -0.010977 0.012086 0.003406 -vn -0.204549 0.293236 -0.933902 -v -0.009341 0.013391 0.003406 -vn -0.165372 0.316986 -0.933902 -v -0.007552 0.014475 0.003406 -vn -0.123479 0.335533 -0.933901 -v -0.005639 0.015322 0.003406 -vn -0.079558 0.348566 -0.933902 -v -0.003633 0.015918 0.003406 -vn -0.034331 0.355878 -0.933902 -v -0.001568 0.016251 0.003406 -vn 0.011459 0.357348 -0.933901 -v 0.000523 0.016319 0.003406 -vn 0.057062 0.352949 -0.933901 -v 0.002606 0.016118 0.003406 -vn 0.101727 0.342752 -0.933902 -v 0.004645 0.015652 0.003406 -vn 0.144722 0.326928 -0.933903 -v 0.006609 0.014930 0.003406 -vn 0.185342 0.305741 -0.933901 -v 0.008464 0.013962 0.003406 -vn 0.222919 0.279531 -0.933900 -v 0.010180 0.012765 0.003406 -vn 0.256833 0.248729 -0.933901 -v 0.011728 0.011358 0.003406 -vn 0.286533 0.213846 -0.933900 -v 0.013085 0.009765 0.003406 -vn 0.311526 0.175448 -0.933900 -v 0.014226 0.008012 0.003406 -vn 0.331402 0.134170 -0.933901 -v 0.015134 0.006127 0.003406 -vn 0.345832 0.090688 -0.933904 -v 0.015793 0.004141 0.003406 -vn 0.354596 0.045720 -0.933901 -v 0.016193 0.002088 0.003406 -vn 0.357530 -0.000000 -0.933902 -v 0.016327 -0.000000 0.003406 -vn 0.354596 -0.045720 -0.933901 -v 0.016193 -0.002088 0.003406 -vn 0.345832 -0.090689 -0.933904 -v 0.015793 -0.004141 0.003406 -vn 0.331402 -0.134170 -0.933901 -v 0.015134 -0.006127 0.003406 -vn 0.311527 -0.175448 -0.933900 -v 0.014226 -0.008012 0.003406 -vn 0.286534 -0.213846 -0.933900 -v 0.013085 -0.009765 0.003406 -vn 0.256833 -0.248729 -0.933901 -v 0.011728 -0.011358 0.003406 -vn 0.222918 -0.279531 -0.933900 -v 0.010180 -0.012765 0.003406 -vn 0.185342 -0.305741 -0.933901 -v 0.008464 -0.013962 0.003406 -vn 0.144722 -0.326928 -0.933902 -v 0.006609 -0.014930 0.003406 -vn 0.101727 -0.342752 -0.933902 -v 0.004645 -0.015652 0.003406 -vn 0.057062 -0.352948 -0.933901 -v 0.002606 -0.016118 0.003406 -vn 0.011459 -0.357348 -0.933901 -v 0.000523 -0.016319 0.003406 -vn -0.034331 -0.355878 -0.933902 -v -0.001568 -0.016251 0.003406 -vn -0.079558 -0.348566 -0.933902 -v -0.003633 -0.015918 0.003406 -vn -0.123479 -0.335533 -0.933901 -v -0.005639 -0.015322 0.003406 -vn -0.165371 -0.316985 -0.933902 -v -0.007552 -0.014475 0.003406 -vn -0.204549 -0.293236 -0.933902 -v -0.009341 -0.013391 0.003406 -vn -0.240368 -0.264672 -0.933902 -v -0.010977 -0.012086 0.003406 -vn -0.272242 -0.231763 -0.933901 -v -0.012432 -0.010584 0.003406 -vn -0.299643 -0.195046 -0.933901 -v -0.013683 -0.008907 0.003406 -vn -0.322128 -0.155129 -0.933899 -v -0.014710 -0.007084 0.003406 -vn -0.339321 -0.112662 -0.933900 -v -0.015495 -0.005145 0.003406 -vn -0.350933 -0.068344 -0.933903 -v -0.016026 -0.003121 0.003406 -vn -0.355870 -0.024222 -0.934221 -v -0.016293 -0.001046 0.003406 -vn 0.981970 -0.188956 -0.005620 -v 0.015728 -0.002940 0.002937 -vn 0.925478 -0.111509 -0.362017 -v 0.015899 -0.002050 0.003110 -vn 0.900533 -0.240855 -0.361980 -v 0.015507 -0.004066 0.003110 -vn 0.816914 -0.449820 -0.360990 -v 0.013968 -0.007867 0.003110 -vn 0.912248 -0.399935 -0.088632 -v 0.014831 -0.006004 0.002937 -vn 0.861576 -0.357836 -0.360057 -v 0.014859 -0.006016 0.003110 -vn 0.941687 -0.331358 -0.058552 -v 0.014920 -0.005780 0.002937 -vn 0.960829 -0.262617 -0.088544 -v 0.015477 -0.004058 0.002937 -vn 0.746322 -0.558554 -0.361969 -v 0.012847 -0.009588 0.003110 -vn 0.841695 -0.539709 -0.016215 -v 0.013603 -0.008423 0.002937 -vn 0.878385 -0.469651 -0.088697 -v 0.013941 -0.007851 0.002937 -vn 0.577295 -0.816267 -0.020942 -v 0.009642 -0.012768 0.002937 -vn 0.640928 -0.762435 -0.088905 -v 0.009976 -0.012509 0.002937 -vn 0.588458 -0.723840 -0.360240 -v 0.009995 -0.012533 0.003110 -vn 0.698105 -0.710451 -0.088932 -v 0.011494 -0.011131 0.002937 -vn 0.663517 -0.655681 -0.360315 -v 0.011516 -0.011152 0.003110 -vn 0.753920 -0.656246 -0.030761 -v 0.011824 -0.010779 0.002937 -vn 0.796656 -0.597890 -0.088692 -v 0.012823 -0.009570 0.002937 -vn 0.523367 -0.847668 -0.086862 -v 0.008294 -0.013682 0.002937 -vn 0.487205 -0.793855 -0.363903 -v 0.008310 -0.013709 0.003110 -vn 0.457187 -0.889280 -0.012695 -v 0.007132 -0.014323 0.002937 -vn 0.369496 -0.856146 -0.361230 -v 0.006489 -0.014659 0.003110 -vn 0.384623 -0.918841 -0.088301 -v 0.006477 -0.014631 0.002937 -vn 0.271828 -0.892228 -0.360609 -v 0.004561 -0.015368 0.003110 -vn 0.310991 -0.946331 -0.087988 -v 0.004552 -0.015339 0.002937 -vn 0.022910 -0.931897 -0.361998 -v 0.000514 -0.016023 0.003110 -vn 0.094546 -0.995508 -0.005060 -v 0.001476 -0.015932 0.002937 -vn 0.155310 -0.918829 -0.362811 -v 0.002559 -0.015825 0.003110 -vn 0.172203 -0.981179 -0.087370 -v 0.002554 -0.015795 0.002937 -vn 0.239895 -0.968740 -0.063192 -v 0.004379 -0.015389 0.002937 -vn -0.199561 -0.910668 -0.361744 -v -0.003567 -0.015629 0.003110 -vn -0.126136 -0.988120 -0.087795 -v -0.001536 -0.015926 0.002937 -vn -0.092662 -0.927028 -0.363362 -v -0.001539 -0.015957 0.003110 -vn -0.059108 -0.994859 -0.082229 -v -0.001476 -0.015932 0.002937 -vn 0.016271 -0.995903 -0.088950 -v 0.000513 -0.015992 0.002937 -vn -0.325447 -0.873533 -0.361973 -v -0.005537 -0.015044 0.003110 -vn -0.281727 -0.959462 -0.007937 -v -0.004379 -0.015389 0.002937 -vn -0.203624 -0.975088 -0.087984 -v -0.003560 -0.015599 0.002937 -vn -0.526062 -0.770146 -0.360742 -v -0.009172 -0.013148 0.003110 -vn -0.484404 -0.870432 -0.087756 -v -0.007401 -0.014186 0.002937 -vn -0.439461 -0.822987 -0.359955 -v -0.007415 -0.014213 0.003110 -vn -0.418553 -0.906773 -0.050756 -v -0.007132 -0.014323 0.002937 -vn -0.351421 -0.931950 -0.089288 -v -0.005526 -0.015015 0.002937 -vn -0.627024 -0.689804 -0.361956 -v -0.010778 -0.011867 0.003110 -vn -0.616836 -0.786834 -0.020129 -v -0.009642 -0.012768 0.002937 -vn -0.551580 -0.829480 -0.087879 -v -0.009154 -0.013123 0.002937 -vn -0.866187 -0.498751 -0.031112 -v -0.013603 -0.008423 0.002937 -vn -0.820444 -0.564952 -0.087760 -v -0.013409 -0.008729 0.002937 -vn -0.777116 -0.516141 -0.360125 -v -0.013435 -0.008745 0.003110 -vn -0.773263 -0.627981 -0.087771 -v -0.012183 -0.010372 0.002937 -vn -0.716244 -0.597510 -0.360522 -v -0.012207 -0.010392 0.003110 -vn -0.724728 -0.688577 -0.025121 -v -0.011824 -0.010779 0.002937 -vn -0.670417 -0.736699 -0.088406 -v -0.010757 -0.011844 0.002937 -vn -0.893661 -0.440352 -0.086375 -v -0.014415 -0.006942 0.002937 -vn -0.836886 -0.409134 -0.363636 -v -0.014443 -0.006956 0.003110 -vn -0.928594 -0.370977 -0.009476 -v -0.014920 -0.005780 0.002937 -vn -0.887485 -0.285818 -0.361495 -v -0.015214 -0.005051 0.003110 -vn -0.951294 -0.295517 -0.087803 -v -0.015185 -0.005042 0.002937 -vn -0.914165 -0.183294 -0.361532 -v -0.015735 -0.003064 0.003110 -vn -0.971684 -0.219416 -0.087675 -v -0.015705 -0.003059 0.002937 -vn -0.929848 0.065887 -0.361997 -v -0.015998 0.001027 0.003110 -vn -0.999991 0.000000 -0.004217 -v -0.016000 -0.000000 0.002937 -vn -0.929571 -0.066743 -0.362552 -v -0.015998 -0.001027 0.003110 -vn -0.993087 -0.078393 -0.087361 -v -0.015967 -0.001025 0.002937 -vn -0.986057 -0.149755 -0.072567 -v -0.015728 -0.002940 0.002937 -vn -0.887484 0.285819 -0.361496 -v -0.015214 0.005051 0.003110 -vn -0.971684 0.219416 -0.087676 -v -0.015705 0.003059 0.002937 -vn -0.914135 0.183821 -0.361341 -v -0.015735 0.003064 0.003110 -vn -0.985759 0.150976 -0.074066 -v -0.015728 0.002940 0.002937 -vn -0.993105 0.077501 -0.087954 -v -0.015967 0.001025 0.002937 -vn -0.838606 0.407080 -0.361975 -v -0.014443 0.006956 0.003110 -vn -0.928652 0.370838 -0.009244 -v -0.014920 0.005780 0.002937 -vn -0.951294 0.295517 -0.087804 -v -0.015185 0.005042 0.002937 -vn -0.716244 0.597510 -0.360523 -v -0.012207 0.010392 0.003110 -vn -0.820444 0.564952 -0.087759 -v -0.013409 0.008729 0.002937 -vn -0.776793 0.516712 -0.360000 -v -0.013435 0.008745 0.003110 -vn -0.863459 0.502577 -0.043065 -v -0.013603 0.008423 0.002937 -vn -0.894650 0.438028 -0.087943 -v -0.014415 0.006942 0.002937 -vn -0.627023 0.689804 -0.361956 -v -0.010778 0.011867 0.003110 -vn -0.724912 0.688397 -0.024735 -v -0.011824 0.010779 0.002937 -vn -0.773263 0.627981 -0.087771 -v -0.012183 0.010372 0.002937 -vn -0.415572 0.908593 -0.041945 -v -0.007132 0.014323 0.002937 -vn -0.484404 0.870432 -0.087756 -v -0.007401 0.014186 0.002937 -vn -0.438854 0.823249 -0.360093 -v -0.007415 0.014213 0.003110 -vn -0.551579 0.829480 -0.087879 -v -0.009154 0.013123 0.002937 -vn -0.526062 0.770146 -0.360740 -v -0.009172 0.013148 0.003110 -vn -0.616836 0.786834 -0.020130 -v -0.009642 0.012768 0.002937 -vn -0.670249 0.736893 -0.088058 -v -0.010757 0.011844 0.002937 -vn -0.353790 0.931311 -0.086564 -v -0.005526 0.015015 0.002937 -vn -0.327292 0.872268 -0.363358 -v -0.005537 0.015044 0.003110 -vn -0.281285 0.959598 -0.007084 -v -0.004379 0.015389 0.002937 -vn -0.199562 0.910668 -0.361744 -v -0.003567 0.015629 0.003110 -vn -0.203561 0.975109 -0.087889 -v -0.003560 0.015599 0.002937 -vn -0.092316 0.927000 -0.363524 -v -0.001539 0.015957 0.003110 -vn -0.126136 0.988120 -0.087795 -v -0.001536 0.015926 0.002937 -vn 0.154073 0.919365 -0.361980 -v 0.002559 0.015825 0.003110 -vn 0.094755 0.995491 -0.004369 -v 0.001476 0.015932 0.002937 -vn 0.022470 0.931800 -0.362275 -v 0.000514 0.016023 0.003110 -vn 0.015823 0.996024 -0.087670 -v 0.000513 0.015992 0.002937 -vn -0.058910 0.994952 -0.081244 -v -0.001476 0.015932 0.002937 -vn 0.369495 0.856146 -0.361230 -v 0.006489 0.014659 0.003110 -vn 0.310989 0.946332 -0.087988 -v 0.004552 0.015339 0.002937 -vn 0.272432 0.892116 -0.360430 -v 0.004561 0.015368 0.003110 -vn 0.241840 0.968048 -0.066310 -v 0.004379 0.015389 0.002937 -vn 0.171006 0.981326 -0.088072 -v 0.002554 0.015795 0.002937 -vn 0.485017 0.796076 -0.361968 -v 0.008310 0.013709 0.003110 -vn 0.457225 0.889268 -0.012185 -v 0.007132 0.014323 0.002937 -vn 0.384455 0.918939 -0.088007 -v 0.006477 0.014631 0.002937 -vn 0.758441 0.651676 -0.009273 -v 0.011824 0.010779 0.002937 -vn 0.698466 0.710200 -0.088100 -v 0.011494 0.011131 0.002937 -vn 0.663932 0.655207 -0.360414 -v 0.011516 0.011152 0.003110 -vn 0.640586 0.762813 -0.088130 -v 0.009976 0.012509 0.002937 -vn 0.588984 0.723466 -0.360133 -v 0.009995 0.012533 0.003110 -vn 0.581800 0.812502 -0.036725 -v 0.009642 0.012768 0.002937 -vn 0.520520 0.849274 -0.088276 -v 0.008294 0.013682 0.002937 -vn 0.794694 0.600899 -0.085918 -v 0.012823 0.009570 0.002937 -vn 0.743562 0.560792 -0.364180 -v 0.012847 0.009588 0.003110 -vn 0.841762 0.539614 -0.015935 -v 0.013603 0.008423 0.002937 -vn 0.816915 0.449819 -0.360989 -v 0.013968 0.007867 0.003110 -vn 0.878306 0.469884 -0.088241 -v 0.013941 0.007851 0.002937 -vn 0.861768 0.357214 -0.360214 -v 0.014859 0.006016 0.003110 -vn 0.912386 0.399713 -0.088214 -v 0.014831 0.006004 0.002937 -vn 0.990029 -0.109572 -0.088520 -v 0.015869 -0.002046 0.002937 -vn 0.996066 -0.000040 -0.088616 -v 0.016000 -0.000000 0.002937 -vn 0.930135 0.000000 -0.367217 -v 0.016031 -0.000000 0.003110 -vn 0.990034 0.109596 -0.088440 -v 0.015869 0.002046 0.002937 -vn 0.925478 0.111508 -0.362017 -v 0.015899 0.002050 0.003110 -vn 0.981976 0.188925 -0.005526 -v 0.015728 0.002940 0.002937 -vn 0.899665 0.242425 -0.363087 -v 0.015507 0.004066 0.003110 -vn 0.960477 0.264348 -0.087196 -v 0.015477 0.004058 0.002937 -vn 0.942925 0.328754 -0.053031 -v 0.014920 0.005780 0.002937 -vn 0.702668 0.000000 -0.711518 -v 0.016146 -0.000000 0.003290 -vn 0.696897 -0.089855 -0.711520 -v 0.016014 -0.002065 0.003290 -vn 0.679693 -0.178237 -0.711512 -v 0.015618 -0.004096 0.003290 -vn 0.651324 -0.263691 -0.711508 -v 0.014966 -0.006059 0.003290 -vn 0.612247 -0.344811 -0.711518 -v 0.014069 -0.007923 0.003290 -vn 0.563129 -0.420274 -0.711516 -v 0.012940 -0.009657 0.003290 -vn 0.504766 -0.488838 -0.711511 -v 0.011599 -0.011233 0.003290 -vn 0.438110 -0.549372 -0.711512 -v 0.010067 -0.012624 0.003290 -vn 0.364259 -0.600882 -0.711517 -v 0.008370 -0.013808 0.003290 -vn 0.284429 -0.642531 -0.711515 -v 0.006536 -0.014765 0.003290 -vn 0.199930 -0.673630 -0.711513 -v 0.004594 -0.015479 0.003290 -vn 0.112147 -0.693667 -0.711512 -v 0.002577 -0.015939 0.003290 -vn 0.022522 -0.702311 -0.711514 -v 0.000518 -0.016138 0.003290 -vn -0.067473 -0.699424 -0.711515 -v -0.001550 -0.016072 0.003290 -vn -0.156359 -0.685056 -0.711512 -v -0.003593 -0.015742 0.003290 -vn -0.242679 -0.659436 -0.711513 -v -0.005576 -0.015153 0.003290 -vn -0.325012 -0.622987 -0.711516 -v -0.007468 -0.014315 0.003290 -vn -0.402011 -0.576313 -0.711513 -v -0.009238 -0.013243 0.003290 -vn -0.472407 -0.520172 -0.711514 -v -0.010855 -0.011953 0.003290 -vn -0.535051 -0.455496 -0.711509 -v -0.012295 -0.010467 0.003290 -vn -0.588902 -0.383333 -0.711513 -v -0.013532 -0.008808 0.003290 -vn -0.633081 -0.304876 -0.711519 -v -0.014547 -0.007006 0.003290 -vn -0.666876 -0.221417 -0.711513 -v -0.015324 -0.005088 0.003290 -vn -0.689716 -0.134322 -0.711513 -v -0.015849 -0.003087 0.003290 -vn -0.701227 -0.045021 -0.711515 -v -0.016113 -0.001035 0.003290 -vn -0.701227 0.045021 -0.711515 -v -0.016113 0.001035 0.003290 -vn -0.689716 0.134322 -0.711512 -v -0.015849 0.003087 0.003290 -vn -0.666877 0.221417 -0.711512 -v -0.015324 0.005088 0.003290 -vn -0.633081 0.304877 -0.711519 -v -0.014547 0.007006 0.003290 -vn -0.588902 0.383332 -0.711513 -v -0.013532 0.008808 0.003290 -vn -0.535051 0.455495 -0.711509 -v -0.012295 0.010467 0.003290 -vn -0.472407 0.520173 -0.711514 -v -0.010855 0.011953 0.003290 -vn -0.402011 0.576313 -0.711512 -v -0.009238 0.013243 0.003290 -vn -0.325012 0.622988 -0.711515 -v -0.007468 0.014315 0.003290 -vn -0.242680 0.659437 -0.711512 -v -0.005576 0.015153 0.003290 -vn -0.156359 0.685056 -0.711512 -v -0.003593 0.015742 0.003290 -vn -0.067472 0.699424 -0.711515 -v -0.001550 0.016072 0.003290 -vn 0.022522 0.702311 -0.711514 -v 0.000518 0.016138 0.003290 -vn 0.112147 0.693667 -0.711512 -v 0.002577 0.015939 0.003290 -vn 0.199930 0.673630 -0.711513 -v 0.004594 0.015479 0.003290 -vn 0.284429 0.642532 -0.711514 -v 0.006536 0.014765 0.003290 -vn 0.364259 0.600882 -0.711517 -v 0.008370 0.013808 0.003290 -vn 0.438110 0.549373 -0.711512 -v 0.010067 0.012624 0.003290 -vn 0.504766 0.488839 -0.711511 -v 0.011599 0.011233 0.003290 -vn 0.563130 0.420274 -0.711516 -v 0.012940 0.009657 0.003290 -vn 0.612247 0.344810 -0.711519 -v 0.014069 0.007923 0.003290 -vn 0.651323 0.263692 -0.711509 -v 0.014966 0.006059 0.003290 -vn 0.679693 0.178237 -0.711512 -v 0.015618 0.004096 0.003290 -vn 0.696897 0.089855 -0.711520 -v 0.016014 0.002065 0.003290 -vn -0.074246 -0.000000 -0.997240 -v -0.011500 -0.000000 0.004937 -vn -0.084670 0.008079 -0.996376 -v -0.011466 0.000880 0.004937 -vn -0.353997 0.028806 -0.934803 -v -0.011294 0.000867 0.004906 -vn -0.081763 0.019133 -0.996468 -v -0.011197 0.002620 0.004937 -vn -0.346795 0.081153 -0.934424 -v -0.011029 0.002581 0.004906 -vn -0.077881 0.031389 -0.996468 -v -0.010666 0.004299 0.004937 -vn -0.330347 0.133142 -0.934422 -v -0.010506 0.004234 0.004906 -vn -0.072180 0.042911 -0.996468 -v -0.009885 0.005877 0.004937 -vn -0.306150 0.182007 -0.934423 -v -0.009736 0.005788 0.004906 -vn -0.064782 0.053425 -0.996468 -v -0.008872 0.007317 0.004937 -vn -0.274778 0.226608 -0.934423 -v -0.008739 0.007207 0.004906 -vn -0.055867 0.062688 -0.996468 -v -0.007651 0.008585 0.004937 -vn -0.236967 0.265897 -0.934423 -v -0.007536 0.008456 0.004906 -vn -0.045643 0.070481 -0.996468 -v -0.006251 0.009653 0.004937 -vn -0.193602 0.298956 -0.934422 -v -0.006157 0.009507 0.004906 -vn -0.034350 0.076624 -0.996468 -v -0.004704 0.010494 0.004937 -vn -0.145698 0.325006 -0.934421 -v -0.004633 0.010336 0.004906 -vn -0.022251 0.080969 -0.996468 -v -0.003047 0.011089 0.004937 -vn -0.094378 0.343434 -0.934423 -v -0.003001 0.010922 0.004906 -vn -0.009630 0.083416 -0.996468 -v -0.001319 0.011424 0.004937 -vn -0.040846 0.353816 -0.934423 -v -0.001299 0.011252 0.004906 -vn 0.003216 0.083908 -0.996468 -v 0.000440 0.011492 0.004937 -vn 0.013642 0.355904 -0.934423 -v 0.000434 0.011319 0.004906 -vn 0.015987 0.082435 -0.996468 -v 0.002190 0.011290 0.004937 -vn 0.067811 0.349652 -0.934422 -v 0.002157 0.011120 0.004906 -vn 0.028384 0.079028 -0.996468 -v 0.003887 0.010823 0.004937 -vn 0.120391 0.335202 -0.934423 -v 0.003829 0.010660 0.004906 -vn 0.040114 0.073769 -0.996468 -v 0.005494 0.010103 0.004937 -vn 0.170148 0.312898 -0.934422 -v 0.005411 0.009951 0.004906 -vn 0.050905 0.066781 -0.996468 -v 0.006972 0.009146 0.004937 -vn 0.215918 0.283258 -0.934422 -v 0.006867 0.009008 0.004906 -vn 0.060504 0.058229 -0.996468 -v 0.008286 0.007974 0.004937 -vn 0.256624 0.246974 -0.934424 -v 0.008161 0.007854 0.004906 -vn 0.068680 0.048309 -0.996468 -v 0.009406 0.006616 0.004937 -vn 0.291317 0.204908 -0.934423 -v 0.009265 0.006517 0.004906 -vn 0.075250 0.037259 -0.996468 -v 0.010306 0.005103 0.004937 -vn 0.319185 0.158039 -0.934422 -v 0.010151 0.005026 0.004906 -vn 0.080057 0.025335 -0.996468 -v 0.010964 0.003470 0.004937 -vn 0.339566 0.107462 -0.934423 -v 0.010799 0.003418 0.004906 -vn 0.082987 0.012818 -0.996468 -v 0.011365 0.001755 0.004937 -vn 0.351992 0.054368 -0.934423 -v 0.011194 0.001729 0.004906 -vn 0.083972 0.000000 -0.996468 -v 0.011500 -0.000000 0.004937 -vn 0.356166 -0.000000 -0.934423 -v 0.011327 -0.000000 0.004906 -vn 0.082987 -0.012818 -0.996468 -v 0.011365 -0.001755 0.004937 -vn 0.351992 -0.054368 -0.934423 -v 0.011194 -0.001729 0.004906 -vn 0.080057 -0.025335 -0.996468 -v 0.010964 -0.003470 0.004937 -vn 0.339566 -0.107462 -0.934423 -v 0.010799 -0.003418 0.004906 -vn 0.075250 -0.037259 -0.996468 -v 0.010306 -0.005103 0.004937 -vn 0.319185 -0.158039 -0.934422 -v 0.010151 -0.005026 0.004906 -vn 0.068680 -0.048309 -0.996468 -v 0.009406 -0.006616 0.004937 -vn 0.291318 -0.204909 -0.934423 -v 0.009265 -0.006517 0.004906 -vn 0.060504 -0.058229 -0.996468 -v 0.008286 -0.007974 0.004937 -vn 0.256624 -0.246975 -0.934423 -v 0.008161 -0.007854 0.004906 -vn 0.050905 -0.066781 -0.996468 -v 0.006972 -0.009146 0.004937 -vn 0.215918 -0.283258 -0.934422 -v 0.006867 -0.009008 0.004906 -vn 0.040114 -0.073769 -0.996468 -v 0.005494 -0.010103 0.004937 -vn 0.170149 -0.312898 -0.934422 -v 0.005411 -0.009951 0.004906 -vn 0.028384 -0.079028 -0.996468 -v 0.003887 -0.010823 0.004937 -vn 0.120390 -0.335203 -0.934422 -v 0.003829 -0.010660 0.004906 -vn 0.015987 -0.082434 -0.996468 -v 0.002190 -0.011290 0.004937 -vn 0.067811 -0.349651 -0.934423 -v 0.002157 -0.011120 0.004906 -vn 0.003216 -0.083908 -0.996468 -v 0.000440 -0.011492 0.004937 -vn 0.013642 -0.355905 -0.934422 -v 0.000434 -0.011319 0.004906 -vn -0.009630 -0.083416 -0.996468 -v -0.001319 -0.011424 0.004937 -vn -0.040846 -0.353817 -0.934422 -v -0.001299 -0.011252 0.004906 -vn -0.022251 -0.080969 -0.996468 -v -0.003047 -0.011089 0.004937 -vn -0.094378 -0.343435 -0.934422 -v -0.003001 -0.010922 0.004906 -vn -0.034350 -0.076624 -0.996468 -v -0.004704 -0.010494 0.004937 -vn -0.145697 -0.325005 -0.934422 -v -0.004633 -0.010336 0.004906 -vn -0.045643 -0.070481 -0.996468 -v -0.006251 -0.009653 0.004937 -vn -0.193601 -0.298955 -0.934422 -v -0.006157 -0.009507 0.004906 -vn -0.055867 -0.062688 -0.996468 -v -0.007651 -0.008585 0.004937 -vn -0.236967 -0.265897 -0.934423 -v -0.007536 -0.008456 0.004906 -vn -0.064782 -0.053425 -0.996468 -v -0.008872 -0.007317 0.004937 -vn -0.274778 -0.226608 -0.934423 -v -0.008739 -0.007207 0.004906 -vn -0.072180 -0.042911 -0.996468 -v -0.009885 -0.005877 0.004937 -vn -0.306150 -0.182007 -0.934423 -v -0.009736 -0.005788 0.004906 -vn -0.077881 -0.031389 -0.996468 -v -0.010666 -0.004299 0.004937 -vn -0.330347 -0.133142 -0.934422 -v -0.010506 -0.004234 0.004906 -vn -0.081763 -0.019133 -0.996468 -v -0.011197 -0.002620 0.004937 -vn -0.346795 -0.081153 -0.934424 -v -0.011029 -0.002581 0.004906 -vn -0.084670 -0.008079 -0.996376 -v -0.011466 -0.000880 0.004937 -vn -0.353997 -0.028807 -0.934803 -v -0.011294 -0.000867 0.004906 -vn 0.922613 -0.133741 -0.361798 -v 0.010902 -0.001684 0.004610 -vn 0.886861 -0.287396 -0.361776 -v 0.010517 -0.003328 0.004610 -vn 0.768206 -0.528674 -0.361059 -v 0.009023 -0.006346 0.004610 -vn 0.832801 -0.419795 -0.360853 -v 0.009886 -0.004895 0.004610 -vn 0.668868 -0.649426 -0.361747 -v 0.007948 -0.007649 0.004610 -vn 0.454584 -0.814553 -0.360356 -v 0.005270 -0.009691 0.004610 -vn 0.557991 -0.747961 -0.359444 -v 0.006687 -0.008773 0.004610 -vn 0.313461 -0.878001 -0.361740 -v 0.003729 -0.010382 0.004610 -vn 0.045425 -0.931881 -0.359910 -v 0.000423 -0.011023 0.004610 -vn 0.167304 -0.918014 -0.359527 -v 0.002100 -0.010829 0.004610 -vn -0.101954 -0.925588 -0.364543 -v -0.001265 -0.010958 0.004610 -vn -0.257283 -0.896760 -0.360037 -v -0.002923 -0.010637 0.004610 -vn -0.373149 -0.855246 -0.359603 -v -0.004512 -0.010066 0.004610 -vn -0.714825 -0.599476 -0.360074 -v -0.008510 -0.007018 0.004610 -vn -0.627909 -0.689658 -0.360697 -v -0.007339 -0.008235 0.004610 -vn -0.501266 -0.785123 -0.363750 -v -0.005996 -0.009259 0.004610 -vn -0.797285 -0.482285 -0.362957 -v -0.009482 -0.005637 0.004610 -vn -0.868170 -0.340068 -0.361435 -v -0.010231 -0.004124 0.004610 -vn -0.906363 -0.215491 -0.363413 -v -0.010741 -0.002513 0.004610 -vn -0.928917 0.078891 -0.361786 -v -0.010999 0.000844 0.004610 -vn -0.928709 -0.079500 -0.362188 -v -0.010999 -0.000844 0.004610 -vn -0.868170 0.340069 -0.361434 -v -0.010231 0.004124 0.004610 -vn -0.906340 0.215985 -0.363177 -v -0.010741 0.002513 0.004610 -vn -0.798648 0.480933 -0.361751 -v -0.009482 0.005637 0.004610 -vn -0.627909 0.689658 -0.360696 -v -0.007339 0.008235 0.004610 -vn -0.714346 0.600202 -0.359816 -v -0.008510 0.007018 0.004610 -vn -0.504283 0.784117 -0.361746 -v -0.005996 0.009259 0.004610 -vn -0.256451 0.896944 -0.360174 -v -0.002923 0.010637 0.004610 -vn -0.372339 0.855683 -0.359402 -v -0.004512 0.010066 0.004610 -vn -0.111021 0.924387 -0.364941 -v -0.001265 0.010958 0.004610 -vn 0.046306 0.931897 -0.359754 -v 0.000423 0.011023 0.004610 -vn 0.168180 0.917784 -0.359705 -v 0.002100 0.010829 0.004610 -vn 0.558666 0.747346 -0.359676 -v 0.006687 0.008773 0.004610 -vn 0.454584 0.814553 -0.360356 -v 0.005270 0.009691 0.004610 -vn 0.309675 0.878350 -0.364147 -v 0.003729 0.010382 0.004610 -vn 0.666694 0.650765 -0.363352 -v 0.007948 0.007649 0.004610 -vn 0.768206 0.528674 -0.361059 -v 0.009023 0.006346 0.004610 -vn 0.833039 0.419082 -0.361131 -v 0.009886 0.004895 0.004610 -vn 0.929930 0.000000 -0.367736 -v 0.011031 -0.000000 0.004610 -vn 0.922613 0.133741 -0.361799 -v 0.010902 0.001684 0.004610 -vn 0.886179 0.288485 -0.362580 -v 0.010517 0.003328 0.004610 -vn 0.701793 -0.000000 -0.712381 -v 0.011146 -0.000000 0.004790 -vn 0.693571 -0.107128 -0.712379 -v 0.011016 -0.001701 0.004790 -vn 0.669089 -0.211746 -0.712379 -v 0.010627 -0.003363 0.004790 -vn 0.628923 -0.311401 -0.712380 -v 0.009989 -0.004946 0.004790 -vn 0.574021 -0.403758 -0.712376 -v 0.009117 -0.006413 0.004790 -vn 0.505661 -0.486649 -0.712376 -v 0.008031 -0.007729 0.004790 -vn 0.425445 -0.558131 -0.712381 -v 0.006757 -0.008865 0.004790 -vn 0.335261 -0.616535 -0.712379 -v 0.005325 -0.009792 0.004790 -vn 0.237219 -0.660488 -0.712378 -v 0.003768 -0.010490 0.004790 -vn 0.133615 -0.688959 -0.712378 -v 0.002122 -0.010943 0.004790 -vn 0.026881 -0.701282 -0.712377 -v 0.000427 -0.011138 0.004790 -vn -0.080485 -0.697165 -0.712378 -v -0.001278 -0.011073 0.004790 -vn -0.185962 -0.676710 -0.712378 -v -0.002954 -0.010748 0.004790 -vn -0.287083 -0.640391 -0.712378 -v -0.004560 -0.010171 0.004790 -vn -0.381476 -0.589067 -0.712373 -v -0.006059 -0.009356 0.004790 -vn -0.466926 -0.523933 -0.712372 -v -0.007416 -0.008321 0.004790 -vn -0.541429 -0.446513 -0.712377 -v -0.008599 -0.007092 0.004790 -vn -0.603242 -0.358630 -0.712379 -v -0.009581 -0.005696 0.004790 -vn -0.650924 -0.262347 -0.712371 -v -0.010338 -0.004167 0.004790 -vn -0.683332 -0.159905 -0.712382 -v -0.010853 -0.002540 0.004790 -vn -0.699738 -0.053722 -0.712377 -v -0.011114 -0.000853 0.004790 -vn -0.699738 0.053722 -0.712377 -v -0.011114 0.000853 0.004790 -vn -0.683332 0.159906 -0.712382 -v -0.010853 0.002540 0.004790 -vn -0.650925 0.262345 -0.712370 -v -0.010338 0.004167 0.004790 -vn -0.603242 0.358631 -0.712379 -v -0.009581 0.005696 0.004790 -vn -0.541429 0.446513 -0.712377 -v -0.008599 0.007092 0.004790 -vn -0.466926 0.523932 -0.712373 -v -0.007416 0.008321 0.004790 -vn -0.381477 0.589068 -0.712372 -v -0.006059 0.009356 0.004790 -vn -0.287083 0.640392 -0.712377 -v -0.004560 0.010171 0.004790 -vn -0.185962 0.676709 -0.712379 -v -0.002954 0.010748 0.004790 -vn -0.080485 0.697165 -0.712379 -v -0.001278 0.011073 0.004790 -vn 0.026880 0.701283 -0.712376 -v 0.000427 0.011138 0.004790 -vn 0.133615 0.688959 -0.712378 -v 0.002122 0.010943 0.004790 -vn 0.237219 0.660488 -0.712378 -v 0.003768 0.010490 0.004790 -vn 0.335262 0.616535 -0.712379 -v 0.005325 0.009792 0.004790 -vn 0.425445 0.558130 -0.712381 -v 0.006757 0.008865 0.004790 -vn 0.505660 0.486649 -0.712376 -v 0.008031 0.007729 0.004790 -vn 0.574021 0.403758 -0.712376 -v 0.009117 0.006413 0.004790 -vn 0.628924 0.311400 -0.712380 -v 0.009989 0.004946 0.004790 -vn 0.669089 0.211746 -0.712379 -v 0.010627 0.003363 0.004790 -vn 0.693571 0.107128 -0.712378 -v 0.011016 0.001701 0.004790 -vn 0.368996 -0.925125 -0.089364 -v 0.006123 -0.014782 -0.008063 -vn 0.304318 -0.944552 -0.123338 -v 0.004379 -0.015389 -0.008063 -vn 0.230308 -0.969086 -0.088495 -v 0.004141 -0.015455 -0.008063 -vn 0.152167 -0.984413 -0.088179 -v 0.002088 -0.015863 -0.008063 -vn 0.073358 -0.985358 -0.153913 -v 0.001476 -0.015932 -0.008063 -vn -0.000466 -0.996181 -0.087316 -v 0.000000 -0.016000 -0.008063 -vn -0.072651 -0.985453 -0.153637 -v -0.001476 -0.015932 -0.008063 -vn -0.152352 -0.984351 -0.088557 -v -0.002088 -0.015863 -0.008063 -vn -0.230597 -0.969037 -0.088277 -v -0.004141 -0.015455 -0.008063 -vn -0.301722 -0.946116 -0.117591 -v -0.004379 -0.015389 -0.008063 -vn -0.371073 -0.924495 -0.087256 -v -0.006123 -0.014782 -0.008063 -vn -0.436524 -0.883877 -0.167952 -v -0.007132 -0.014323 -0.008063 -vn -0.511722 -0.854507 -0.089212 -v -0.008000 -0.013856 -0.008063 -vn -0.571483 -0.814006 -0.103933 -v -0.009642 -0.012768 -0.008063 -vn -0.629996 -0.771516 -0.088700 -v -0.009740 -0.012694 -0.008063 -vn -0.690053 -0.718407 -0.087850 -v -0.011314 -0.011314 -0.008063 -vn -0.737583 -0.655789 -0.160974 -v -0.011824 -0.010779 -0.008063 -vn -0.794541 -0.600364 -0.090925 -v -0.012694 -0.009740 -0.008063 -vn -0.823068 -0.543662 -0.164290 -v -0.013603 -0.008423 -0.008063 -vn -0.874545 -0.476765 -0.088694 -v -0.013856 -0.008000 -0.008063 -vn -0.910130 -0.404887 -0.087924 -v -0.014782 -0.006123 -0.008063 -vn -0.933631 -0.332946 -0.132213 -v -0.014920 -0.005780 -0.008063 -vn -0.960199 -0.264921 -0.088509 -v -0.015455 -0.004141 -0.008063 -vn -0.967837 -0.188821 -0.166248 -v -0.015728 -0.002940 -0.008063 -vn -0.989797 -0.111525 -0.088679 -v -0.015863 -0.002088 -0.008063 -vn -0.995996 -0.000000 -0.089397 -v -0.016000 -0.000000 -0.008063 -vn -0.989797 0.111525 -0.088679 -v -0.015863 0.002088 -0.008063 -vn -0.967837 0.188821 -0.166248 -v -0.015728 0.002940 -0.008063 -vn -0.959330 0.267455 -0.090298 -v -0.015455 0.004141 -0.008063 -vn -0.933740 0.327630 -0.144178 -v -0.014920 0.005780 -0.008063 -vn -0.909852 0.405330 -0.088754 -v -0.014782 0.006123 -0.008063 -vn -0.874546 0.476763 -0.088694 -v -0.013856 0.008000 -0.008063 -vn -0.828995 0.540155 -0.144914 -v -0.013603 0.008423 -0.008063 -vn -0.792559 0.603333 -0.088542 -v -0.012694 0.009740 -0.008063 -vn -0.737844 0.655312 -0.161715 -v -0.011824 0.010779 -0.008063 -vn -0.689623 0.718719 -0.088672 -v -0.011314 0.011314 -0.008063 -vn -0.629998 0.771515 -0.088700 -v -0.009740 0.012694 -0.008063 -vn -0.572590 0.813414 -0.102457 -v -0.009642 0.012768 -0.008063 -vn -0.510986 0.855009 -0.088615 -v -0.008000 0.013856 -0.008063 -vn -0.436929 0.883542 -0.168658 -v -0.007132 0.014323 -0.008063 -vn -0.369188 0.925017 -0.089689 -v -0.006123 0.014782 -0.008063 -vn -0.304102 0.944583 -0.123635 -v -0.004379 0.015389 -0.008063 -vn -0.230367 0.969058 -0.088642 -v -0.004141 0.015455 -0.008063 -vn -0.152352 0.984351 -0.088557 -v -0.002088 0.015863 -0.008063 -vn -0.073106 0.985320 -0.154272 -v -0.001476 0.015932 -0.008063 -vn -0.000227 0.996093 -0.088309 -v 0.000000 0.016000 -0.008063 -vn 0.073344 0.985255 -0.154577 -v 0.001476 0.015932 -0.008063 -vn 0.152392 0.984346 -0.088538 -v 0.002088 0.015863 -0.008063 -vn 0.230308 0.969086 -0.088495 -v 0.004141 0.015455 -0.008063 -vn 0.301790 0.946026 -0.118141 -v 0.004379 0.015389 -0.008063 -vn 0.370567 0.924594 -0.088354 -v 0.006123 0.014782 -0.008063 -vn 0.437126 0.883437 -0.168703 -v 0.007132 0.014323 -0.008063 -vn 0.511754 0.854512 -0.088979 -v 0.008000 0.013856 -0.008063 -vn 0.571406 0.814084 -0.103736 -v 0.009642 0.012768 -0.008063 -vn 0.630196 0.771386 -0.088416 -v 0.009740 0.012694 -0.008063 -vn 0.689438 0.718929 -0.088407 -v 0.011314 0.011314 -0.008063 -vn 0.738043 0.655141 -0.161500 -v 0.011824 0.010779 -0.008063 -vn 0.794484 0.600488 -0.090608 -v 0.012694 0.009740 -0.008063 -vn 0.823045 0.543731 -0.164175 -v 0.013603 0.008423 -0.008063 -vn 0.874740 0.476488 -0.088255 -v 0.013856 0.008000 -0.008063 -vn 0.909749 0.405672 -0.088239 -v 0.014782 0.006123 -0.008063 -vn 0.933891 0.332115 -0.132465 -v 0.014920 0.005780 -0.008063 -vn 0.960152 0.265240 -0.088073 -v 0.015455 0.004141 -0.008063 -vn 0.967839 0.188836 -0.166217 -v 0.015728 0.002940 -0.008063 -vn 0.989903 0.111073 -0.088064 -v 0.015863 0.002088 -0.008063 -vn 0.996121 -0.000040 -0.087990 -v 0.016000 -0.000000 -0.008063 -vn 0.989912 -0.111052 -0.087984 -v 0.015863 -0.002088 -0.008063 -vn 0.967849 -0.188866 -0.166128 -v 0.015728 -0.002940 -0.008063 -vn 0.959290 -0.267801 -0.089697 -v 0.015455 -0.004141 -0.008063 -vn 0.933959 -0.327274 -0.143566 -v 0.014920 -0.005780 -0.008063 -vn 0.909676 -0.405926 -0.087829 -v 0.014782 -0.006123 -0.008063 -vn 0.874882 -0.476311 -0.087801 -v 0.013856 -0.008000 -0.008063 -vn 0.828959 -0.540314 -0.144527 -v 0.013603 -0.008423 -0.008063 -vn 0.792518 -0.603493 -0.087811 -v 0.012694 -0.009740 -0.008063 -vn 0.738143 -0.655102 -0.161203 -v 0.011824 -0.010779 -0.008063 -vn 0.689157 -0.719299 -0.087589 -v 0.011314 -0.011314 -0.008063 -vn 0.630587 -0.771154 -0.087641 -v 0.009740 -0.012694 -0.008063 -vn 0.572378 -0.813644 -0.101813 -v 0.009642 -0.012768 -0.008063 -vn 0.511084 -0.855042 -0.087734 -v 0.008000 -0.013856 -0.008063 -vn 0.437234 -0.883475 -0.168223 -v 0.007132 -0.014323 -0.008063 -vn 0.030825 0.086734 -0.995754 -v -0.004856 -0.013663 0.004937 -vn 0.042348 0.081729 -0.995755 -v -0.006671 -0.012874 0.004937 -vn 0.053082 0.075201 -0.995755 -v -0.008362 -0.011846 0.004937 -vn 0.062828 0.067272 -0.995755 -v -0.009897 -0.010597 0.004937 -vn 0.071403 0.058090 -0.995755 -v -0.011248 -0.009151 0.004937 -vn 0.078648 0.047827 -0.995755 -v -0.012389 -0.007534 0.004937 -vn 0.084430 0.036673 -0.995754 -v -0.013300 -0.005777 0.004937 -vn 0.088636 0.024835 -0.995754 -v -0.013962 -0.003912 0.004937 -vn 0.091192 0.012534 -0.995754 -v -0.014365 -0.001974 0.004937 -vn 0.092047 -0.000000 -0.995755 -v -0.014500 -0.000000 0.004937 -vn 0.091192 -0.012534 -0.995754 -v -0.014365 0.001974 0.004937 -vn 0.088636 -0.024835 -0.995754 -v -0.013962 0.003912 0.004937 -vn 0.084430 -0.036673 -0.995754 -v -0.013300 0.005777 0.004937 -vn 0.078648 -0.047827 -0.995755 -v -0.012389 0.007534 0.004937 -vn 0.071403 -0.058091 -0.995755 -v -0.011248 0.009151 0.004937 -vn 0.062828 -0.067272 -0.995755 -v -0.009897 0.010597 0.004937 -vn 0.053083 -0.075201 -0.995755 -v -0.008362 0.011846 0.004937 -vn -0.071405 0.058092 -0.995754 -v 0.011248 -0.009151 0.004937 -vn -0.062828 0.067272 -0.995755 -v 0.009897 -0.010597 0.004937 -vn -0.053082 0.075201 -0.995755 -v 0.008362 -0.011846 0.004937 -vn -0.042347 0.081727 -0.995755 -v 0.006671 -0.012874 0.004937 -vn -0.030825 0.086734 -0.995754 -v 0.004856 -0.013663 0.004937 -vn -0.018728 0.090123 -0.995755 -v 0.002950 -0.014197 0.004937 -vn -0.006282 0.091834 -0.995755 -v 0.000990 -0.014466 0.004937 -vn 0.006282 0.091834 -0.995755 -v -0.000990 -0.014466 0.004937 -vn 0.018728 0.090123 -0.995755 -v -0.002950 -0.014197 0.004937 -vn 0.042348 -0.081728 -0.995755 -v -0.006671 0.012874 0.004937 -vn 0.030826 -0.086735 -0.995754 -v -0.004856 0.013663 0.004937 -vn 0.018728 -0.090123 -0.995755 -v -0.002950 0.014197 0.004937 -vn 0.006282 -0.091833 -0.995755 -v -0.000990 0.014466 0.004937 -vn -0.006282 -0.091833 -0.995755 -v 0.000990 0.014466 0.004937 -vn -0.018728 -0.090123 -0.995755 -v 0.002950 0.014197 0.004937 -vn -0.030825 -0.086735 -0.995754 -v 0.004856 0.013663 0.004937 -vn -0.042347 -0.081727 -0.995755 -v 0.006671 0.012874 0.004937 -vn -0.053083 -0.075201 -0.995755 -v 0.008362 0.011846 0.004937 -vn -0.062828 -0.067272 -0.995755 -v 0.009897 0.010597 0.004937 -vn -0.071405 -0.058093 -0.995754 -v 0.011248 0.009151 0.004937 -vn -0.078648 -0.047827 -0.995755 -v 0.012389 0.007534 0.004937 -vn -0.084430 -0.036673 -0.995754 -v 0.013300 0.005777 0.004937 -vn -0.088636 -0.024835 -0.995754 -v 0.013962 0.003912 0.004937 -vn -0.091192 -0.012534 -0.995754 -v 0.014365 0.001974 0.004937 -vn -0.092051 -0.000000 -0.995754 -v 0.014500 -0.000000 0.004937 -vn -0.091192 0.012534 -0.995754 -v 0.014365 -0.001974 0.004937 -vn -0.088636 0.024835 -0.995754 -v 0.013962 -0.003912 0.004937 -vn -0.084430 0.036673 -0.995754 -v 0.013300 -0.005777 0.004937 -vn -0.078648 0.047827 -0.995755 -v 0.012389 -0.007534 0.004937 -vn 0.923252 0.112896 -0.367235 -v 0.015832 0.002084 -0.008236 -vn 0.897509 0.244115 -0.367267 -v 0.015425 0.004133 -0.008236 -vn 0.809664 0.456666 -0.368646 -v 0.013830 0.007985 -0.008236 -vn 0.854834 0.364767 -0.369058 -v 0.014754 0.006111 -0.008236 -vn 0.741888 0.562431 -0.365067 -v 0.012669 0.009721 -0.008236 -vn 0.651006 0.664030 -0.367772 -v 0.011292 0.011292 -0.008236 -vn 0.570555 0.734384 -0.367625 -v 0.009721 0.012669 -0.008236 -vn 0.351098 0.861300 -0.367278 -v 0.006111 0.014754 -0.008236 -vn 0.471962 0.801737 -0.366700 -v 0.007985 0.013830 -0.008236 -vn 0.130973 0.920447 -0.368271 -v 0.002084 0.015832 -0.008236 -vn 0.231912 0.900013 -0.369044 -v 0.004133 0.015425 -0.008236 -vn 0.000000 0.930107 -0.367288 -v 0.000000 0.015969 -0.008236 -vn -0.232572 0.899898 -0.368910 -v -0.004133 0.015425 -0.008236 -vn -0.130973 0.920447 -0.368271 -v -0.002084 0.015832 -0.008236 -vn -0.349548 0.862403 -0.366166 -v -0.006111 0.014754 -0.008236 -vn -0.471048 0.802018 -0.367262 -v -0.007985 0.013830 -0.008236 -vn -0.570943 0.733996 -0.367796 -v -0.009721 0.012669 -0.008236 -vn -0.651006 0.664030 -0.367772 -v -0.011292 0.011292 -0.008236 -vn -0.738971 0.564819 -0.367289 -v -0.012669 0.009721 -0.008236 -vn -0.809953 0.456087 -0.368728 -v -0.013830 0.007985 -0.008236 -vn -0.855130 0.364163 -0.368968 -v -0.014754 0.006111 -0.008236 -vn -0.923239 -0.112897 -0.367265 -v -0.015832 -0.002084 -0.008236 -vn -0.932280 0.000000 -0.361739 -v -0.015969 -0.000000 -0.008236 -vn -0.923239 0.112897 -0.367266 -v -0.015832 0.002084 -0.008236 -vn -0.897408 0.246955 -0.365612 -v -0.015425 0.004133 -0.008236 -vn -0.897504 -0.244114 -0.367280 -v -0.015425 -0.004133 -0.008236 -vn -0.809660 -0.456664 -0.368658 -v -0.013830 -0.007985 -0.008236 -vn -0.854832 -0.364765 -0.369065 -v -0.014754 -0.006111 -0.008236 -vn -0.741889 -0.562430 -0.365066 -v -0.012669 -0.009721 -0.008236 -vn -0.651006 -0.664030 -0.367772 -v -0.011292 -0.011292 -0.008236 -vn -0.570553 -0.734387 -0.367621 -v -0.009721 -0.012669 -0.008236 -vn -0.351099 -0.861300 -0.367276 -v -0.006111 -0.014754 -0.008236 -vn -0.471960 -0.801735 -0.366708 -v -0.007985 -0.013830 -0.008236 -vn -0.130973 -0.920447 -0.368271 -v -0.002084 -0.015832 -0.008236 -vn -0.231911 -0.900013 -0.369045 -v -0.004133 -0.015425 -0.008236 -vn -0.000000 -0.930107 -0.367288 -v 0.000000 -0.015969 -0.008236 -vn 0.232571 -0.899897 -0.368912 -v 0.004133 -0.015425 -0.008236 -vn 0.130973 -0.920447 -0.368271 -v 0.002084 -0.015832 -0.008236 -vn 0.349548 -0.862404 -0.366165 -v 0.006111 -0.014754 -0.008236 -vn 0.471048 -0.802020 -0.367258 -v 0.007985 -0.013830 -0.008236 -vn 0.570945 -0.733993 -0.367799 -v 0.009721 -0.012669 -0.008236 -vn 0.651006 -0.664030 -0.367772 -v 0.011292 -0.011292 -0.008236 -vn 0.738971 -0.564820 -0.367288 -v 0.012669 -0.009721 -0.008236 -vn 0.809955 -0.456092 -0.368717 -v 0.013830 -0.007985 -0.008236 -vn 0.855133 -0.364162 -0.368963 -v 0.014754 -0.006111 -0.008236 -vn 0.932285 -0.000001 -0.361725 -v 0.015969 -0.000000 -0.008236 -vn 0.923252 -0.112894 -0.367234 -v 0.015832 -0.002084 -0.008236 -vn 0.897413 -0.246956 -0.365600 -v 0.015425 -0.004133 -0.008236 -vn 0.371477 -0.000000 -0.928442 -v 0.015673 -0.000000 -0.008532 -vn 0.091103 0.011994 -0.995769 -v 0.015367 0.002023 -0.008563 -vn 0.368297 0.048488 -0.928443 -v 0.015539 0.002046 -0.008532 -vn 0.088759 0.023783 -0.995769 -v 0.014972 0.004012 -0.008563 -vn 0.358817 0.096145 -0.928443 -v 0.015139 0.004056 -0.008532 -vn 0.084893 0.035164 -0.995769 -v 0.014320 0.005932 -0.008563 -vn 0.343207 0.142160 -0.928439 -v 0.014480 0.005998 -0.008532 -vn 0.079578 0.045944 -0.995769 -v 0.013423 0.007750 -0.008563 -vn 0.321711 0.185740 -0.928441 -v 0.013573 0.007837 -0.008532 -vn 0.072902 0.055940 -0.995769 -v 0.012297 0.009436 -0.008563 -vn 0.294714 0.226143 -0.928441 -v 0.012434 0.009541 -0.008532 -vn 0.064976 0.064976 -0.995769 -v 0.010960 0.010960 -0.008563 -vn 0.262678 0.262678 -0.928440 -v 0.011083 0.011083 -0.008532 -vn 0.055938 0.072900 -0.995769 -v 0.009436 0.012297 -0.008563 -vn 0.226145 0.294717 -0.928440 -v 0.009541 0.012434 -0.008532 -vn 0.045945 0.079578 -0.995769 -v 0.007750 0.013423 -0.008563 -vn 0.185740 0.321711 -0.928441 -v 0.007837 0.013573 -0.008532 -vn 0.035165 0.084895 -0.995769 -v 0.005932 0.014320 -0.008563 -vn 0.142159 0.343203 -0.928441 -v 0.005998 0.014480 -0.008532 -vn 0.023783 0.088759 -0.995769 -v 0.004012 0.014972 -0.008563 -vn 0.096147 0.358823 -0.928441 -v 0.004056 0.015139 -0.008532 -vn 0.011994 0.091103 -0.995769 -v 0.002023 0.015367 -0.008563 -vn 0.048488 0.368304 -0.928440 -v 0.002046 0.015539 -0.008532 -vn -0.000000 0.091890 -0.995769 -v 0.000000 0.015500 -0.008563 -vn -0.000000 0.371481 -0.928441 -v 0.000000 0.015673 -0.008532 -vn -0.011994 0.091103 -0.995769 -v -0.002023 0.015367 -0.008563 -vn -0.048488 0.368304 -0.928440 -v -0.002046 0.015539 -0.008532 -vn -0.023783 0.088759 -0.995769 -v -0.004012 0.014972 -0.008563 -vn -0.096147 0.358823 -0.928441 -v -0.004056 0.015139 -0.008532 -vn -0.035165 0.084895 -0.995769 -v -0.005932 0.014320 -0.008563 -vn -0.142160 0.343203 -0.928441 -v -0.005998 0.014480 -0.008532 -vn -0.045945 0.079578 -0.995769 -v -0.007750 0.013423 -0.008563 -vn -0.185742 0.321715 -0.928439 -v -0.007837 0.013573 -0.008532 -vn -0.055939 0.072902 -0.995769 -v -0.009436 0.012297 -0.008563 -vn -0.226143 0.294715 -0.928441 -v -0.009541 0.012434 -0.008532 -vn -0.064976 0.064976 -0.995769 -v -0.010960 0.010960 -0.008563 -vn -0.262678 0.262679 -0.928440 -v -0.011083 0.011083 -0.008532 -vn -0.072903 0.055940 -0.995769 -v -0.012297 0.009436 -0.008563 -vn -0.294715 0.226142 -0.928441 -v -0.012434 0.009541 -0.008532 -vn -0.079581 0.045946 -0.995769 -v -0.013423 0.007750 -0.008563 -vn -0.321713 0.185741 -0.928440 -v -0.013573 0.007837 -0.008532 -vn -0.084893 0.035164 -0.995769 -v -0.014320 0.005932 -0.008563 -vn -0.343207 0.142161 -0.928439 -v -0.014480 0.005998 -0.008532 -vn -0.088759 0.023783 -0.995769 -v -0.014972 0.004012 -0.008563 -vn -0.358825 0.096146 -0.928440 -v -0.015139 0.004056 -0.008532 -vn -0.091103 0.011994 -0.995769 -v -0.015367 0.002023 -0.008563 -vn -0.368306 0.048489 -0.928439 -v -0.015539 0.002046 -0.008532 -vn -0.091888 0.000000 -0.995769 -v -0.015500 -0.000000 -0.008563 -vn -0.371477 -0.000000 -0.928442 -v -0.015673 -0.000000 -0.008532 -vn -0.091103 -0.011994 -0.995769 -v -0.015367 -0.002023 -0.008563 -vn -0.368306 -0.048489 -0.928439 -v -0.015539 -0.002046 -0.008532 -vn -0.088759 -0.023783 -0.995769 -v -0.014972 -0.004012 -0.008563 -vn -0.358825 -0.096147 -0.928440 -v -0.015139 -0.004056 -0.008532 -vn -0.084894 -0.035164 -0.995769 -v -0.014320 -0.005932 -0.008563 -vn -0.343207 -0.142161 -0.928439 -v -0.014480 -0.005998 -0.008532 -vn -0.079581 -0.045946 -0.995769 -v -0.013423 -0.007750 -0.008563 -vn -0.321713 -0.185742 -0.928440 -v -0.013573 -0.007837 -0.008532 -vn -0.072903 -0.055940 -0.995769 -v -0.012297 -0.009436 -0.008563 -vn -0.294714 -0.226143 -0.928441 -v -0.012434 -0.009541 -0.008532 -vn -0.064977 -0.064977 -0.995769 -v -0.010960 -0.010960 -0.008563 -vn -0.262679 -0.262679 -0.928440 -v -0.011083 -0.011083 -0.008532 -vn -0.055939 -0.072901 -0.995769 -v -0.009436 -0.012297 -0.008563 -vn -0.226142 -0.294715 -0.928441 -v -0.009541 -0.012434 -0.008532 -vn -0.045945 -0.079579 -0.995769 -v -0.007750 -0.013423 -0.008563 -vn -0.185743 -0.321715 -0.928439 -v -0.007837 -0.013573 -0.008532 -vn -0.035165 -0.084895 -0.995769 -v -0.005932 -0.014320 -0.008563 -vn -0.142159 -0.343203 -0.928441 -v -0.005998 -0.014480 -0.008532 -vn -0.023783 -0.088759 -0.995769 -v -0.004012 -0.014972 -0.008563 -vn -0.096146 -0.358823 -0.928441 -v -0.004056 -0.015139 -0.008532 -vn -0.011994 -0.091104 -0.995769 -v -0.002023 -0.015367 -0.008563 -vn -0.048488 -0.368304 -0.928440 -v -0.002046 -0.015539 -0.008532 -vn 0.000000 -0.091890 -0.995769 -v 0.000000 -0.015500 -0.008563 -vn 0.000000 -0.371481 -0.928441 -v 0.000000 -0.015673 -0.008532 -vn 0.011994 -0.091104 -0.995769 -v 0.002023 -0.015367 -0.008563 -vn 0.048488 -0.368304 -0.928440 -v 0.002046 -0.015539 -0.008532 -vn 0.023783 -0.088759 -0.995769 -v 0.004012 -0.014972 -0.008563 -vn 0.096147 -0.358823 -0.928441 -v 0.004056 -0.015139 -0.008532 -vn 0.035165 -0.084895 -0.995769 -v 0.005932 -0.014320 -0.008563 -vn 0.142159 -0.343204 -0.928441 -v 0.005998 -0.014480 -0.008532 -vn 0.045945 -0.079579 -0.995769 -v 0.007750 -0.013423 -0.008563 -vn 0.185740 -0.321712 -0.928441 -v 0.007837 -0.013573 -0.008532 -vn 0.055938 -0.072900 -0.995769 -v 0.009436 -0.012297 -0.008563 -vn 0.226145 -0.294717 -0.928440 -v 0.009541 -0.012434 -0.008532 -vn 0.064977 -0.064977 -0.995769 -v 0.010960 -0.010960 -0.008563 -vn 0.262679 -0.262678 -0.928440 -v 0.011083 -0.011083 -0.008532 -vn 0.072903 -0.055940 -0.995769 -v 0.012297 -0.009436 -0.008563 -vn 0.294714 -0.226142 -0.928441 -v 0.012434 -0.009541 -0.008532 -vn 0.079578 -0.045945 -0.995769 -v 0.013423 -0.007750 -0.008563 -vn 0.321712 -0.185740 -0.928441 -v 0.013573 -0.007837 -0.008532 -vn 0.084893 -0.035164 -0.995769 -v 0.014320 -0.005932 -0.008563 -vn 0.343207 -0.142161 -0.928439 -v 0.014480 -0.005998 -0.008532 -vn 0.088759 -0.023783 -0.995769 -v 0.014972 -0.004012 -0.008563 -vn 0.358817 -0.096144 -0.928443 -v 0.015139 -0.004056 -0.008532 -vn 0.091103 -0.011994 -0.995769 -v 0.015367 -0.002023 -0.008563 -vn 0.368297 -0.048487 -0.928443 -v 0.015539 -0.002046 -0.008532 -vn 0.091888 -0.000000 -0.995769 -v 0.015500 -0.000000 -0.008563 -vn 0.711539 -0.000001 -0.702647 -v 0.015854 -0.000000 -0.008417 -vn 0.705443 -0.092873 -0.702655 -v 0.015718 -0.002069 -0.008417 -vn 0.687287 -0.184158 -0.702654 -v 0.015313 -0.004103 -0.008417 -vn 0.657368 -0.272291 -0.702656 -v 0.014647 -0.006067 -0.008417 -vn 0.616206 -0.355767 -0.702652 -v 0.013730 -0.007927 -0.008417 -vn 0.564496 -0.433154 -0.702654 -v 0.012577 -0.009651 -0.008417 -vn 0.503128 -0.503128 -0.702655 -v 0.011210 -0.011210 -0.008417 -vn 0.433153 -0.564496 -0.702654 -v 0.009651 -0.012577 -0.008417 -vn 0.355768 -0.616208 -0.702650 -v 0.007927 -0.013730 -0.008417 -vn 0.272291 -0.657369 -0.702655 -v 0.006067 -0.014647 -0.008417 -vn 0.184158 -0.687287 -0.702654 -v 0.004103 -0.015313 -0.008417 -vn 0.092874 -0.705446 -0.702653 -v 0.002069 -0.015718 -0.008417 -vn 0.000000 -0.711533 -0.702653 -v 0.000000 -0.015854 -0.008417 -vn -0.092874 -0.705446 -0.702653 -v -0.002069 -0.015718 -0.008417 -vn -0.184158 -0.687287 -0.702654 -v -0.004103 -0.015313 -0.008417 -vn -0.272291 -0.657369 -0.702655 -v -0.006067 -0.014647 -0.008417 -vn -0.355767 -0.616206 -0.702652 -v -0.007927 -0.013730 -0.008417 -vn -0.433150 -0.564494 -0.702658 -v -0.009651 -0.012577 -0.008417 -vn -0.503128 -0.503128 -0.702655 -v -0.011210 -0.011210 -0.008417 -vn -0.564497 -0.433153 -0.702654 -v -0.012577 -0.009651 -0.008417 -vn -0.616199 -0.355764 -0.702660 -v -0.013730 -0.007927 -0.008417 -vn -0.657377 -0.272293 -0.702646 -v -0.014647 -0.006067 -0.008417 -vn -0.687283 -0.184157 -0.702658 -v -0.015313 -0.004103 -0.008417 -vn -0.705439 -0.092874 -0.702660 -v -0.015718 -0.002069 -0.008417 -vn -0.711529 0.000000 -0.702657 -v -0.015854 -0.000000 -0.008417 -vn -0.705439 0.092874 -0.702660 -v -0.015718 0.002069 -0.008417 -vn -0.687283 0.184156 -0.702658 -v -0.015313 0.004103 -0.008417 -vn -0.657376 0.272295 -0.702646 -v -0.014647 0.006067 -0.008417 -vn -0.616200 0.355762 -0.702660 -v -0.013730 0.007927 -0.008417 -vn -0.564497 0.433153 -0.702653 -v -0.012577 0.009651 -0.008417 -vn -0.503128 0.503129 -0.702655 -v -0.011210 0.011210 -0.008417 -vn -0.433151 0.564493 -0.702658 -v -0.009651 0.012577 -0.008417 -vn -0.355766 0.616207 -0.702652 -v -0.007927 0.013730 -0.008417 -vn -0.272291 0.657367 -0.702656 -v -0.006067 0.014647 -0.008417 -vn -0.184158 0.687288 -0.702653 -v -0.004103 0.015313 -0.008417 -vn -0.092874 0.705446 -0.702653 -v -0.002069 0.015718 -0.008417 -vn 0.000000 0.711533 -0.702653 -v 0.000000 0.015854 -0.008417 -vn 0.092874 0.705446 -0.702653 -v 0.002069 0.015718 -0.008417 -vn 0.184158 0.687288 -0.702653 -v 0.004103 0.015313 -0.008417 -vn 0.272290 0.657368 -0.702656 -v 0.006067 0.014647 -0.008417 -vn 0.355769 0.616208 -0.702649 -v 0.007927 0.013730 -0.008417 -vn 0.433153 0.564496 -0.702654 -v 0.009651 0.012577 -0.008417 -vn 0.503128 0.503128 -0.702655 -v 0.011210 0.011210 -0.008417 -vn 0.564497 0.433154 -0.702653 -v 0.012577 0.009651 -0.008417 -vn 0.616207 0.355767 -0.702651 -v 0.013730 0.007927 -0.008417 -vn 0.657368 0.272291 -0.702656 -v 0.014647 0.006067 -0.008417 -vn 0.687287 0.184158 -0.702654 -v 0.015313 0.004103 -0.008417 -vn 0.705443 0.092874 -0.702655 -v 0.015718 0.002069 -0.008417 -vn -0.966372 -0.196221 -0.166198 -v 0.014729 0.002839 0.004437 -vn -0.922541 -0.117575 -0.367553 -v 0.014830 0.002038 0.004610 -vn -0.894733 -0.253616 -0.367602 -v 0.014414 0.004039 0.004610 -vn -0.813785 -0.562411 -0.146448 -v 0.012619 0.008110 0.004437 -vn -0.865473 -0.493286 -0.087318 -v 0.012816 0.007794 0.004437 -vn -0.799002 -0.474698 -0.369131 -v 0.012790 0.007778 0.004610 -vn -0.902541 -0.421659 -0.087311 -v 0.013758 0.005976 0.004437 -vn -0.848264 -0.379773 -0.369081 -v 0.013730 0.005964 0.004610 -vn -0.928428 -0.343754 -0.140910 -v 0.013926 0.005575 0.004437 -vn -0.957514 -0.274690 -0.087824 -v 0.014444 0.004047 0.004437 -vn -0.779534 -0.619896 -0.089756 -v 0.011636 0.009466 0.004437 -vn -0.726166 -0.582117 -0.365817 -v 0.011612 0.009447 0.004610 -vn -0.718243 -0.675174 -0.168128 -v 0.010856 0.010351 0.004437 -vn -0.628695 -0.685297 -0.367573 -v 0.010217 0.010940 0.004610 -vn -0.666270 -0.740518 -0.087847 -v 0.010238 0.010963 0.004437 -vn -0.603202 -0.792472 -0.090192 -v 0.008701 0.012219 0.004437 -vn -0.533693 -0.762441 -0.365863 -v 0.008632 0.012229 0.004610 -vn -0.549537 -0.831523 -0.081107 -v 0.008650 0.012255 0.004437 -vn -0.436198 -0.821237 -0.367834 -v 0.006887 0.013291 0.004610 -vn -0.478147 -0.873998 -0.086624 -v 0.006901 0.013318 0.004437 -vn -0.398354 -0.902515 -0.163646 -v 0.006231 0.013644 0.004437 -vn -0.309662 -0.876915 -0.367601 -v 0.005013 0.014105 0.004610 -vn -0.329707 -0.939989 -0.087827 -v 0.005023 0.014134 0.004437 -vn -0.255859 -0.955503 -0.146798 -v 0.003536 0.014577 0.004437 -vn -0.178957 -0.912093 -0.368865 -v 0.003046 0.014656 0.004610 -vn -0.176934 -0.980354 -0.087174 -v 0.003052 0.014686 0.004437 -vn -0.072628 -0.926508 -0.369199 -v 0.001022 0.014934 0.004610 -vn -0.097197 -0.991435 -0.087234 -v 0.001024 0.014965 0.004437 -vn 0.196449 -0.909008 -0.367575 -v -0.003046 0.014656 0.004610 -vn 0.136098 -0.976107 -0.169391 -v -0.002135 0.014847 0.004437 -vn 0.056362 -0.928866 -0.366103 -v -0.001022 0.014934 0.004610 -vn 0.055321 -0.994456 -0.089430 -v -0.001024 0.014965 0.004437 -vn -0.012616 -0.990673 -0.135677 -v 0.000714 0.014983 0.004437 -vn 0.419061 -0.829991 -0.368108 -v -0.006887 0.013291 0.004610 -vn 0.363563 -0.927418 -0.087847 -v -0.005023 0.014134 0.004437 -vn 0.317436 -0.873973 -0.367974 -v -0.005013 0.014105 0.004610 -vn 0.292115 -0.950868 -0.102560 -v -0.004906 0.014175 0.004437 -vn 0.218751 -0.971820 -0.087833 -v -0.003052 0.014686 0.004437 -vn 0.537071 -0.759226 -0.367602 -v -0.008632 0.012229 0.004610 -vn 0.506732 -0.847044 -0.160431 -v -0.007500 0.012990 0.004437 -vn 0.437990 -0.894690 -0.087718 -v -0.006901 0.013318 0.004437 -vn 0.801417 -0.584919 -0.124905 -v -0.011791 0.009272 0.004437 -vn 0.753208 -0.651984 -0.087151 -v -0.011636 0.009466 0.004437 -vn 0.715466 -0.593178 -0.369119 -v -0.011612 0.009447 0.004610 -vn 0.698217 -0.710576 -0.087040 -v -0.010238 0.010963 0.004437 -vn 0.641925 -0.672345 -0.368625 -v -0.010217 0.010940 0.004610 -vn 0.631432 -0.760385 -0.152014 -v -0.009823 0.011336 0.004437 -vn 0.576131 -0.812625 -0.087825 -v -0.008650 0.012255 0.004437 -vn 0.843528 -0.529642 -0.089108 -v -0.012816 0.007794 0.004437 -vn 0.791036 -0.489918 -0.366391 -v -0.012790 0.007778 0.004610 -vn 0.875249 -0.452799 -0.170035 -v -0.013333 0.006873 0.004437 -vn 0.855564 -0.364536 -0.367592 -v -0.013730 0.005964 0.004610 -vn 0.919306 -0.383614 -0.087842 -v -0.013758 0.005976 0.004437 -vn 0.943394 -0.312546 -0.111008 -v -0.014392 0.004226 0.004437 -vn 0.897186 -0.242830 -0.368906 -v -0.014414 0.004039 0.004610 -vn 0.967109 -0.238749 -0.087746 -v -0.014444 0.004047 0.004437 -vn 0.919597 -0.136518 -0.368381 -v -0.014830 0.002038 0.004610 -vn 0.983347 -0.159202 -0.087653 -v -0.014860 0.002042 0.004437 -vn 0.984747 -0.075898 -0.156564 -v -0.014932 0.001426 0.004437 -vn 0.929986 0.000000 -0.367595 -v -0.014969 -0.000000 0.004610 -vn 0.996136 0.000000 -0.087827 -v -0.015000 -0.000000 0.004437 -vn 0.984747 0.075898 -0.156564 -v -0.014932 -0.001426 0.004437 -vn 0.919597 0.136517 -0.368381 -v -0.014830 -0.002038 0.004610 -vn 0.983330 0.159710 -0.086922 -v -0.014860 -0.002043 0.004437 -vn 0.897072 0.243499 -0.368740 -v -0.014414 -0.004039 0.004610 -vn 0.967288 0.238277 -0.087049 -v -0.014444 -0.004047 0.004437 -vn 0.791681 0.487977 -0.367587 -v -0.012790 -0.007778 0.004610 -vn 0.875249 0.452799 -0.170036 -v -0.013333 -0.006873 0.004437 -vn 0.856474 0.363299 -0.366696 -v -0.013730 -0.005964 0.004610 -vn 0.919779 0.382258 -0.088801 -v -0.013758 -0.005976 0.004437 -vn 0.942352 0.314500 -0.114293 -v -0.014392 -0.004226 0.004437 -vn 0.622876 0.761783 -0.178077 -v -0.009823 -0.011336 0.004437 -vn 0.697927 0.710796 -0.087560 -v -0.010238 -0.010963 0.004437 -vn 0.641465 0.672819 -0.368562 -v -0.010217 -0.010940 0.004610 -vn 0.753410 0.651683 -0.087652 -v -0.011636 -0.009466 0.004437 -vn 0.714969 0.593688 -0.369260 -v -0.011612 -0.009447 0.004610 -vn 0.800162 0.587802 -0.119292 -v -0.011791 -0.009272 0.004437 -vn 0.844640 0.528081 -0.087830 -v -0.012816 -0.007794 0.004437 -vn 0.579486 0.809918 -0.090711 -v -0.008650 -0.012255 0.004437 -vn 0.541281 0.757529 -0.364917 -v -0.008632 -0.012229 0.004610 -vn 0.506732 0.847045 -0.160431 -v -0.007500 -0.012990 0.004437 -vn 0.419061 0.829991 -0.368108 -v -0.006887 -0.013291 0.004610 -vn 0.437442 0.895050 -0.086770 -v -0.006901 -0.013318 0.004437 -vn 0.316911 0.874242 -0.367788 -v -0.005013 -0.014105 0.004610 -vn 0.364192 0.927256 -0.086954 -v -0.005023 -0.014134 0.004437 -vn 0.058802 0.928125 -0.367595 -v -0.001022 -0.014934 0.004610 -vn 0.136098 0.976107 -0.169392 -v -0.002135 -0.014847 0.004437 -vn 0.197476 0.909027 -0.366980 -v -0.003046 -0.014656 0.004610 -vn 0.219671 0.971554 -0.088475 -v -0.003052 -0.014686 0.004437 -vn 0.290787 0.951102 -0.104153 -v -0.004906 -0.014175 0.004437 -vn -0.261383 0.950559 -0.167678 -v 0.003536 -0.014577 0.004437 -vn -0.177142 0.980289 -0.087485 -v 0.003052 -0.014686 0.004437 -vn -0.179631 0.911990 -0.368792 -v 0.003046 -0.014656 0.004610 -vn -0.096981 0.991429 -0.087537 -v 0.001024 -0.014965 0.004437 -vn -0.073343 0.926405 -0.369317 -v 0.001022 -0.014934 0.004610 -vn -0.016597 0.991749 -0.127118 -v 0.000714 -0.014983 0.004437 -vn 0.057716 0.994462 -0.087829 -v -0.001024 -0.014965 0.004437 -vn -0.326019 0.941032 -0.090388 -v 0.005023 -0.014134 0.004437 -vn -0.306258 0.879105 -0.365212 -v 0.005013 -0.014105 0.004610 -vn -0.398354 0.902515 -0.163646 -v 0.006231 -0.013644 0.004437 -vn -0.436198 0.821237 -0.367833 -v 0.006887 -0.013291 0.004610 -vn -0.478147 0.873998 -0.086621 -v 0.006901 -0.013318 0.004437 -vn -0.533694 0.762440 -0.365864 -v 0.008632 -0.012229 0.004610 -vn -0.546590 0.832884 -0.086857 -v 0.008650 -0.012255 0.004437 -vn -0.605516 0.790194 -0.094572 -v 0.008701 -0.012219 0.004437 -vn -0.628695 0.685297 -0.367575 -v 0.010217 -0.010940 0.004610 -vn -0.666270 0.740518 -0.087849 -v 0.010238 -0.010963 0.004437 -vn -0.718243 0.675174 -0.168127 -v 0.010856 -0.010351 0.004437 -vn -0.723755 0.583989 -0.367609 -v 0.011612 -0.009447 0.004610 -vn -0.777879 0.622246 -0.087835 -v 0.011636 -0.009466 0.004437 -vn -0.817953 0.559379 -0.134343 -v 0.012619 -0.008110 0.004437 -vn -0.799332 0.474063 -0.369233 -v 0.012790 -0.007778 0.004610 -vn -0.865430 0.493345 -0.087422 -v 0.012816 -0.007794 0.004437 -vn -0.848581 0.379149 -0.368995 -v 0.013730 -0.005964 0.004610 -vn -0.902563 0.421591 -0.087414 -v 0.013758 -0.005976 0.004437 -vn -0.989447 -0.115238 -0.087836 -v 0.014860 0.002042 0.004437 -vn -0.996130 -0.000001 -0.087887 -v 0.015000 -0.000000 0.004437 -vn -0.932325 -0.000001 -0.361622 -v 0.014969 -0.000000 0.004610 -vn -0.989447 0.115239 -0.087835 -v 0.014860 -0.002043 0.004437 -vn -0.922540 0.117576 -0.367553 -v 0.014830 -0.002038 0.004610 -vn -0.966372 0.196221 -0.166198 -v 0.014729 -0.002839 0.004437 -vn -0.894577 0.257165 -0.365512 -v 0.014414 -0.004039 0.004610 -vn -0.956393 0.277851 -0.090067 -v 0.014444 -0.004047 0.004437 -vn -0.928113 0.337514 -0.157131 -v 0.013926 -0.005575 0.004437 -vn 0.371780 -0.000000 -0.928321 -v -0.014673 -0.000000 0.004906 -vn 0.368322 0.050625 -0.928319 -v -0.014536 -0.001998 0.004906 -vn 0.358001 0.100307 -0.928318 -v -0.014129 -0.003959 0.004906 -vn 0.341006 0.148120 -0.928319 -v -0.013458 -0.005846 0.004906 -vn 0.317659 0.193173 -0.928320 -v -0.012537 -0.007624 0.004906 -vn 0.288397 0.234629 -0.928319 -v -0.011382 -0.009260 0.004906 -vn 0.253764 0.271715 -0.928318 -v -0.010015 -0.010724 0.004906 -vn 0.214402 0.303738 -0.928318 -v -0.008462 -0.011987 0.004906 -vn 0.171044 0.330100 -0.928320 -v -0.006751 -0.013028 0.004906 -vn 0.124503 0.350317 -0.928319 -v -0.004914 -0.013826 0.004906 -vn 0.075642 0.364010 -0.928319 -v -0.002985 -0.014366 0.004906 -vn 0.025372 0.370918 -0.928319 -v -0.001001 -0.014639 0.004906 -vn -0.025372 0.370918 -0.928319 -v 0.001001 -0.014639 0.004906 -vn -0.075643 0.364010 -0.928319 -v 0.002985 -0.014366 0.004906 -vn -0.124502 0.350317 -0.928319 -v 0.004914 -0.013826 0.004906 -vn -0.171046 0.330103 -0.928319 -v 0.006751 -0.013028 0.004906 -vn -0.214402 0.303738 -0.928318 -v 0.008462 -0.011987 0.004906 -vn -0.253764 0.271715 -0.928318 -v 0.010015 -0.010724 0.004906 -vn -0.288399 0.234630 -0.928318 -v 0.011382 -0.009260 0.004906 -vn -0.317659 0.193173 -0.928320 -v 0.012537 -0.007624 0.004906 -vn -0.341006 0.148120 -0.928319 -v 0.013458 -0.005846 0.004906 -vn -0.358001 0.100307 -0.928318 -v 0.014129 -0.003959 0.004906 -vn -0.368322 0.050625 -0.928319 -v 0.014536 -0.001998 0.004906 -vn -0.371783 0.000000 -0.928320 -v 0.014673 -0.000000 0.004906 -vn -0.368322 -0.050625 -0.928319 -v 0.014536 0.001998 0.004906 -vn -0.358000 -0.100307 -0.928318 -v 0.014129 0.003959 0.004906 -vn -0.341006 -0.148119 -0.928319 -v 0.013458 0.005846 0.004906 -vn -0.317659 -0.193173 -0.928319 -v 0.012537 0.007624 0.004906 -vn -0.288399 -0.234631 -0.928318 -v 0.011382 0.009260 0.004906 -vn -0.253764 -0.271714 -0.928319 -v 0.010015 0.010724 0.004906 -vn -0.214402 -0.303737 -0.928319 -v 0.008462 0.011987 0.004906 -vn -0.171045 -0.330102 -0.928319 -v 0.006751 0.013028 0.004906 -vn -0.124502 -0.350317 -0.928320 -v 0.004914 0.013826 0.004906 -vn -0.075642 -0.364009 -0.928319 -v 0.002985 0.014366 0.004906 -vn -0.025372 -0.370919 -0.928319 -v 0.001001 0.014639 0.004906 -vn 0.025372 -0.370919 -0.928319 -v -0.001001 0.014639 0.004906 -vn 0.075642 -0.364009 -0.928319 -v -0.002985 0.014366 0.004906 -vn 0.124502 -0.350317 -0.928320 -v -0.004914 0.013826 0.004906 -vn 0.171044 -0.330100 -0.928320 -v -0.006751 0.013028 0.004906 -vn 0.214402 -0.303737 -0.928319 -v -0.008462 0.011987 0.004906 -vn 0.253764 -0.271714 -0.928319 -v -0.010015 0.010724 0.004906 -vn 0.288398 -0.234629 -0.928319 -v -0.011382 0.009260 0.004906 -vn 0.317659 -0.193173 -0.928319 -v -0.012537 0.007624 0.004906 -vn 0.341006 -0.148119 -0.928319 -v -0.013458 0.005846 0.004906 -vn 0.358000 -0.100307 -0.928318 -v -0.014129 0.003959 0.004906 -vn 0.368322 -0.050625 -0.928319 -v -0.014536 0.001998 0.004906 -vn -0.711691 -0.000000 -0.702493 -v 0.014854 -0.000000 0.004790 -vn -0.705060 0.096909 -0.702495 -v 0.014715 -0.002023 0.004790 -vn -0.685302 0.192013 -0.702490 -v 0.014303 -0.004007 0.004790 -vn -0.652774 0.283540 -0.702489 -v 0.013624 -0.005918 0.004790 -vn -0.608087 0.369785 -0.702488 -v 0.012691 -0.007718 0.004790 -vn -0.552067 0.449141 -0.702491 -v 0.011522 -0.009374 0.004790 -vn -0.485770 0.520132 -0.702488 -v 0.010138 -0.010856 0.004790 -vn -0.410422 0.581435 -0.702486 -v 0.008566 -0.012135 0.004790 -vn -0.327429 0.631907 -0.702484 -v 0.006834 -0.013188 0.004790 -vn -0.238332 0.670603 -0.702488 -v 0.004974 -0.013996 0.004790 -vn -0.144797 0.696809 -0.702490 -v 0.003022 -0.014543 0.004790 -vn -0.048567 0.710036 -0.702488 -v 0.001014 -0.014819 0.004790 -vn 0.048567 0.710036 -0.702489 -v -0.001014 -0.014819 0.004790 -vn 0.144798 0.696809 -0.702489 -v -0.003022 -0.014543 0.004790 -vn 0.238333 0.670603 -0.702488 -v -0.004974 -0.013996 0.004790 -vn 0.327427 0.631905 -0.702487 -v -0.006834 -0.013188 0.004790 -vn 0.410422 0.581435 -0.702487 -v -0.008566 -0.012135 0.004790 -vn 0.485770 0.520132 -0.702488 -v -0.010138 -0.010856 0.004790 -vn 0.552068 0.449141 -0.702491 -v -0.011522 -0.009374 0.004790 -vn 0.608087 0.369786 -0.702488 -v -0.012691 -0.007718 0.004790 -vn 0.652774 0.283540 -0.702489 -v -0.013624 -0.005918 0.004790 -vn 0.685303 0.192013 -0.702489 -v -0.014303 -0.004007 0.004790 -vn 0.705070 0.096910 -0.702485 -v -0.014715 -0.002023 0.004790 -vn 0.711701 0.000000 -0.702482 -v -0.014854 -0.000000 0.004790 -vn 0.705070 -0.096910 -0.702485 -v -0.014715 0.002023 0.004790 -vn 0.685302 -0.192013 -0.702490 -v -0.014303 0.004007 0.004790 -vn 0.652774 -0.283540 -0.702489 -v -0.013624 0.005918 0.004790 -vn 0.608086 -0.369785 -0.702489 -v -0.012691 0.007718 0.004790 -vn 0.552067 -0.449141 -0.702491 -v -0.011522 0.009374 0.004790 -vn 0.485769 -0.520132 -0.702489 -v -0.010138 0.010856 0.004790 -vn 0.410422 -0.581436 -0.702486 -v -0.008566 0.012135 0.004790 -vn 0.327428 -0.631906 -0.702486 -v -0.006834 0.013188 0.004790 -vn 0.238333 -0.670603 -0.702488 -v -0.004974 0.013996 0.004790 -vn 0.144797 -0.696808 -0.702490 -v -0.003022 0.014543 0.004790 -vn 0.048567 -0.710035 -0.702489 -v -0.001014 0.014819 0.004790 -vn -0.048567 -0.710036 -0.702489 -v 0.001014 0.014819 0.004790 -vn -0.144798 -0.696808 -0.702490 -v 0.003022 0.014543 0.004790 -vn -0.238333 -0.670603 -0.702488 -v 0.004974 0.013996 0.004790 -vn -0.327429 -0.631908 -0.702483 -v 0.006834 0.013188 0.004790 -vn -0.410422 -0.581436 -0.702486 -v 0.008566 0.012135 0.004790 -vn -0.485769 -0.520132 -0.702489 -v 0.010138 0.010856 0.004790 -vn -0.552068 -0.449141 -0.702491 -v 0.011522 0.009374 0.004790 -vn -0.608086 -0.369785 -0.702489 -v 0.012691 0.007718 0.004790 -vn -0.652774 -0.283540 -0.702489 -v 0.013624 0.005918 0.004790 -vn -0.685302 -0.192013 -0.702490 -v 0.014303 0.004007 0.004790 -vn -0.705060 -0.096909 -0.702495 -v 0.014715 0.002023 0.004790 -vn -0.673630 -0.129633 -0.727611 -v 0.014729 0.002839 -0.008563 -vn -0.685764 0.000000 -0.727824 -v 0.015000 -0.000000 -0.008563 -vn -0.673630 0.129633 -0.727611 -v 0.014729 -0.002839 -0.008563 -vn 0.682344 0.066009 -0.728045 -v -0.014932 -0.001426 -0.008563 -vn 0.682743 -0.065556 -0.727712 -v -0.014932 0.001426 -0.008563 -vn 0.658049 -0.192952 -0.727833 -v -0.014392 0.004226 -0.008563 -vn 0.609783 -0.314334 -0.727571 -v -0.013333 0.006873 -0.008563 -vn 0.609783 0.314334 -0.727571 -v -0.013333 -0.006873 -0.008563 -vn 0.657832 0.192375 -0.728181 -v -0.014392 -0.004226 -0.008563 -vn 0.449440 0.518045 -0.727759 -v -0.009823 -0.011336 -0.008563 -vn 0.538816 0.424166 -0.727847 -v -0.011791 -0.009272 -0.008563 -vn 0.224896 0.647331 -0.728275 -v -0.004906 -0.014175 -0.008563 -vn 0.341929 0.594104 -0.728097 -v -0.007500 -0.012990 -0.008563 -vn -0.285655 0.623051 -0.728154 -v 0.006231 -0.013644 -0.008563 -vn -0.161220 0.666556 -0.727812 -v 0.003536 -0.014577 -0.008563 -vn -0.033055 0.684922 -0.727866 -v 0.000714 -0.014983 -0.008563 -vn -0.577113 -0.370195 -0.727940 -v 0.012619 0.008110 -0.008563 -vn -0.636323 -0.255389 -0.727921 -v 0.013926 0.005575 -0.008563 -vn -0.285714 -0.622958 -0.728210 -v 0.006231 0.013644 -0.008563 -vn -0.396614 -0.558618 -0.728452 -v 0.008701 0.012219 -0.008563 -vn -0.496394 -0.473503 -0.727591 -v 0.010856 0.010351 -0.008563 -vn -0.033258 -0.684755 -0.728014 -v 0.000714 0.014983 -0.008563 -vn -0.160979 -0.666457 -0.727957 -v 0.003536 0.014577 -0.008563 -vn 0.449537 -0.517624 -0.727998 -v -0.009823 0.011336 -0.008563 -vn 0.342699 -0.594182 -0.727671 -v -0.007500 0.012990 -0.008563 -vn 0.224454 -0.647991 -0.727825 -v -0.004906 0.014175 -0.008563 -vn 0.097714 0.679031 -0.727577 -v -0.002135 -0.014847 -0.008563 -vn -0.577119 0.370282 -0.727891 -v 0.012619 -0.008110 -0.008563 -vn -0.496394 0.473503 -0.727591 -v 0.010856 -0.010351 -0.008563 -vn -0.396740 0.558628 -0.728377 -v 0.008701 -0.012219 -0.008563 -vn -0.636397 0.255343 -0.727873 -v 0.013926 -0.005575 -0.008563 -vn 0.097714 -0.679031 -0.727577 -v -0.002135 0.014847 -0.008563 -vn 0.538392 -0.424280 -0.728094 -v -0.011791 0.009272 -0.008563 -# 2245 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 2//2 -f 2//2 6//6 7//7 -f 2//2 7//7 4//4 -f 8//8 9//9 2//2 -f 2//2 9//9 10//10 -f 2//2 10//10 11//11 -f 11//11 12//12 2//2 -f 2//2 12//12 13//13 -f 2//2 13//13 14//14 -f 1//1 3//3 15//15 -f 15//15 3//3 16//16 -f 15//15 16//16 17//17 -f 14//14 18//18 2//2 -f 2//2 18//18 19//19 -f 2//2 19//19 5//5 -f 8//8 20//20 9//9 -f 9//9 20//20 21//21 -f 9//9 21//21 22//22 -f 22//22 23//23 9//9 -f 9//9 23//23 24//24 -f 9//9 24//24 25//25 -f 17//17 26//26 15//15 -f 15//15 26//26 27//27 -f 15//15 27//27 28//28 -f 28//28 29//29 15//15 -f 15//15 29//29 30//30 -f 15//15 30//30 31//31 -f 15//15 32//32 33//33 -f 33//33 32//32 34//34 -f 31//31 35//35 15//15 -f 15//15 35//35 36//36 -f 15//15 36//36 32//32 -f 37//37 38//38 39//39 -f 37//37 40//40 41//41 -f 42//42 40//40 37//37 -f 39//39 42//42 37//37 -f 37//37 43//43 44//44 -f 45//45 43//43 37//37 -f 41//41 45//45 37//37 -f 37//37 46//46 47//47 -f 48//48 46//46 37//37 -f 44//44 48//48 37//37 -f 37//37 49//49 50//50 -f 51//51 49//49 37//37 -f 47//47 51//51 37//37 -f 37//37 52//52 53//53 -f 54//54 52//52 37//37 -f 50//50 54//54 37//37 -f 37//37 55//55 56//56 -f 57//57 55//55 37//37 -f 53//53 57//57 37//37 -f 37//37 58//58 59//59 -f 60//60 58//58 37//37 -f 56//56 60//60 37//37 -f 37//37 61//61 62//62 -f 63//63 61//61 37//37 -f 59//59 63//63 37//37 -f 37//37 64//64 65//65 -f 66//66 64//64 37//37 -f 62//62 66//66 37//37 -f 37//37 67//67 68//68 -f 69//69 67//67 37//37 -f 65//65 69//69 37//37 -f 37//37 70//70 71//71 -f 72//72 70//70 37//37 -f 68//68 72//72 37//37 -f 37//37 73//73 74//74 -f 75//75 73//73 37//37 -f 71//71 75//75 37//37 -f 37//37 76//76 77//77 -f 78//78 76//76 37//37 -f 74//74 78//78 37//37 -f 37//37 79//79 80//80 -f 81//81 79//79 37//37 -f 77//77 81//81 37//37 -f 37//37 82//82 83//83 -f 84//84 82//82 37//37 -f 80//80 84//84 37//37 -f 37//37 85//85 86//86 -f 87//87 85//85 37//37 -f 83//83 87//87 37//37 -f 37//37 88//88 89//89 -f 90//90 88//88 37//37 -f 86//86 90//90 37//37 -f 89//89 38//38 37//37 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 131//131 -f 131//131 130//130 132//132 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 141//141 -f 141//141 140//140 142//142 -f 141//141 142//142 143//143 -f 143//143 142//142 144//144 -f 143//143 144//144 145//145 -f 145//145 144//144 146//146 -f 145//145 146//146 147//147 -f 147//147 146//146 148//148 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 151//151 -f 151//151 150//150 152//152 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 158//158 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 175//175 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 185//185 -f 185//185 184//184 186//186 -f 185//185 186//186 187//187 -f 187//187 186//186 188//188 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 189//189 190//190 191//191 -f 191//191 190//190 192//192 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 91//91 -f 91//91 196//196 92//92 -f 195//195 197//197 193//193 -f 193//193 197//197 198//198 -f 193//193 198//198 191//191 -f 191//191 198//198 199//199 -f 191//191 199//199 189//189 -f 189//189 199//199 200//200 -f 189//189 200//200 187//187 -f 187//187 200//200 201//201 -f 187//187 201//201 185//185 -f 185//185 201//201 202//202 -f 185//185 202//202 183//183 -f 183//183 202//202 203//203 -f 183//183 203//203 181//181 -f 181//181 203//203 204//204 -f 181//181 204//204 179//179 -f 179//179 204//204 205//205 -f 179//179 205//205 177//177 -f 177//177 205//205 206//206 -f 177//177 206//206 175//175 -f 175//175 206//206 207//207 -f 175//175 207//207 173//173 -f 173//173 207//207 208//208 -f 173//173 208//208 171//171 -f 171//171 208//208 209//209 -f 171//171 209//209 169//169 -f 169//169 209//209 210//210 -f 169//169 210//210 167//167 -f 167//167 210//210 211//211 -f 167//167 211//211 165//165 -f 165//165 211//211 212//212 -f 165//165 212//212 163//163 -f 163//163 212//212 213//213 -f 163//163 213//213 161//161 -f 161//161 213//213 214//214 -f 161//161 214//214 159//159 -f 159//159 214//214 215//215 -f 159//159 215//215 157//157 -f 157//157 215//215 216//216 -f 157//157 216//216 155//155 -f 155//155 216//216 217//217 -f 155//155 217//217 153//153 -f 153//153 217//217 218//218 -f 153//153 218//218 151//151 -f 151//151 218//218 219//219 -f 151//151 219//219 149//149 -f 149//149 219//219 220//220 -f 149//149 220//220 147//147 -f 147//147 220//220 221//221 -f 147//147 221//221 145//145 -f 145//145 221//221 222//222 -f 145//145 222//222 143//143 -f 143//143 222//222 223//223 -f 143//143 223//223 141//141 -f 141//141 223//223 224//224 -f 141//141 224//224 139//139 -f 139//139 224//224 225//225 -f 139//139 225//225 137//137 -f 137//137 225//225 226//226 -f 137//137 226//226 135//135 -f 135//135 226//226 227//227 -f 135//135 227//227 133//133 -f 133//133 227//227 228//228 -f 133//133 228//228 131//131 -f 131//131 228//228 229//229 -f 131//131 229//229 129//129 -f 129//129 229//229 230//230 -f 129//129 230//230 127//127 -f 127//127 230//230 231//231 -f 127//127 231//231 125//125 -f 125//125 231//231 232//232 -f 125//125 232//232 123//123 -f 123//123 232//232 233//233 -f 123//123 233//233 121//121 -f 121//121 233//233 234//234 -f 121//121 234//234 119//119 -f 119//119 234//234 235//235 -f 119//119 235//235 117//117 -f 117//117 235//235 236//236 -f 117//117 236//236 115//115 -f 115//115 236//236 237//237 -f 115//115 237//237 113//113 -f 113//113 237//237 238//238 -f 113//113 238//238 111//111 -f 111//111 238//238 239//239 -f 111//111 239//239 109//109 -f 109//109 239//239 240//240 -f 109//109 240//240 107//107 -f 107//107 240//240 241//241 -f 107//107 241//241 105//105 -f 105//105 241//241 242//242 -f 105//105 242//242 103//103 -f 103//103 242//242 243//243 -f 103//103 243//243 101//101 -f 101//101 243//243 244//244 -f 101//101 244//244 99//99 -f 99//99 244//244 245//245 -f 99//99 245//245 97//97 -f 97//97 245//245 246//246 -f 97//97 246//246 95//95 -f 95//95 246//246 247//247 -f 95//95 247//247 93//93 -f 93//93 247//247 248//248 -f 93//93 248//248 91//91 -f 91//91 248//248 249//249 -f 91//91 249//249 195//195 -f 195//195 249//249 197//197 -f 197//197 38//38 198//198 -f 198//198 38//38 89//89 -f 198//198 89//89 199//199 -f 199//199 89//89 88//88 -f 199//199 88//88 200//200 -f 200//200 88//88 90//90 -f 200//200 90//90 201//201 -f 201//201 90//90 86//86 -f 201//201 86//86 202//202 -f 202//202 86//86 85//85 -f 202//202 85//85 203//203 -f 203//203 85//85 87//87 -f 203//203 87//87 204//204 -f 204//204 87//87 83//83 -f 204//204 83//83 205//205 -f 205//205 83//83 82//82 -f 205//205 82//82 206//206 -f 206//206 82//82 84//84 -f 206//206 84//84 207//207 -f 207//207 84//84 80//80 -f 207//207 80//80 208//208 -f 208//208 80//80 79//79 -f 208//208 79//79 209//209 -f 209//209 79//79 81//81 -f 209//209 81//81 210//210 -f 210//210 81//81 77//77 -f 210//210 77//77 211//211 -f 211//211 77//77 76//76 -f 211//211 76//76 212//212 -f 212//212 76//76 78//78 -f 212//212 78//78 213//213 -f 213//213 78//78 74//74 -f 213//213 74//74 214//214 -f 214//214 74//74 73//73 -f 214//214 73//73 215//215 -f 215//215 73//73 75//75 -f 215//215 75//75 216//216 -f 216//216 75//75 71//71 -f 216//216 71//71 217//217 -f 217//217 71//71 70//70 -f 217//217 70//70 218//218 -f 218//218 70//70 72//72 -f 218//218 72//72 219//219 -f 219//219 72//72 68//68 -f 219//219 68//68 220//220 -f 220//220 68//68 67//67 -f 220//220 67//67 221//221 -f 221//221 67//67 69//69 -f 221//221 69//69 222//222 -f 222//222 69//69 65//65 -f 222//222 65//65 223//223 -f 223//223 65//65 64//64 -f 223//223 64//64 224//224 -f 224//224 64//64 66//66 -f 224//224 66//66 225//225 -f 225//225 66//66 62//62 -f 225//225 62//62 226//226 -f 226//226 62//62 61//61 -f 226//226 61//61 227//227 -f 227//227 61//61 63//63 -f 227//227 63//63 228//228 -f 228//228 63//63 59//59 -f 228//228 59//59 229//229 -f 229//229 59//59 58//58 -f 229//229 58//58 230//230 -f 230//230 58//58 60//60 -f 230//230 60//60 231//231 -f 231//231 60//60 56//56 -f 231//231 56//56 232//232 -f 232//232 56//56 55//55 -f 232//232 55//55 233//233 -f 233//233 55//55 57//57 -f 233//233 57//57 234//234 -f 234//234 57//57 53//53 -f 234//234 53//53 235//235 -f 235//235 53//53 52//52 -f 235//235 52//52 236//236 -f 236//236 52//52 54//54 -f 236//236 54//54 237//237 -f 237//237 54//54 50//50 -f 237//237 50//50 238//238 -f 238//238 50//50 49//49 -f 238//238 49//49 239//239 -f 239//239 49//49 51//51 -f 239//239 51//51 240//240 -f 240//240 51//51 47//47 -f 240//240 47//47 241//241 -f 241//241 47//47 46//46 -f 241//241 46//46 242//242 -f 242//242 46//46 48//48 -f 242//242 48//48 243//243 -f 243//243 48//48 44//44 -f 243//243 44//44 244//244 -f 244//244 44//44 43//43 -f 244//244 43//43 245//245 -f 245//245 43//43 45//45 -f 245//245 45//45 246//246 -f 246//246 45//45 41//41 -f 246//246 41//41 247//247 -f 247//247 41//41 40//40 -f 247//247 40//40 248//248 -f 248//248 40//40 42//42 -f 248//248 42//42 249//249 -f 249//249 42//42 39//39 -f 249//249 39//39 197//197 -f 197//197 39//39 38//38 -f 250//250 251//251 252//252 -f 253//253 254//254 255//255 -f 255//255 254//254 256//256 -f 255//255 256//256 257//257 -f 257//257 256//256 258//258 -f 257//257 258//258 252//252 -f 252//252 258//258 259//259 -f 252//252 259//259 250//250 -f 253//253 255//255 260//260 -f 260//260 255//255 261//261 -f 260//260 261//261 262//262 -f 262//262 261//261 263//263 -f 262//262 263//263 264//264 -f 264//264 263//263 265//265 -f 265//265 263//263 266//266 -f 265//265 266//266 267//267 -f 267//267 266//266 268//268 -f 267//267 268//268 269//269 -f 270//270 271//271 272//272 -f 272//272 271//271 273//273 -f 272//272 273//273 274//274 -f 274//274 273//273 275//275 -f 274//274 275//275 276//276 -f 276//276 275//275 277//277 -f 276//276 277//277 268//268 -f 268//268 277//277 278//278 -f 268//268 278//278 269//269 -f 270//270 272//272 279//279 -f 279//279 272//272 280//280 -f 279//279 280//280 281//281 -f 281//281 280//280 282//282 -f 281//281 282//282 283//283 -f 283//283 282//282 284//284 -f 284//284 282//282 285//285 -f 284//284 285//285 286//286 -f 286//286 285//285 287//287 -f 286//286 287//287 288//288 -f 289//289 290//290 291//291 -f 291//291 290//290 292//292 -f 291//291 292//292 293//293 -f 293//293 292//292 294//294 -f 293//293 294//294 295//295 -f 295//295 294//294 296//296 -f 295//295 296//296 287//287 -f 287//287 296//296 297//297 -f 287//287 297//297 288//288 -f 298//298 299//299 289//289 -f 289//289 299//299 300//300 -f 289//289 300//300 290//290 -f 301//301 302//302 303//303 -f 303//303 302//302 304//304 -f 303//303 304//304 305//305 -f 305//305 304//304 306//306 -f 305//305 306//306 298//298 -f 298//298 306//306 307//307 -f 298//298 307//307 299//299 -f 301//301 303//303 308//308 -f 308//308 303//303 309//309 -f 308//308 309//309 310//310 -f 310//310 309//309 311//311 -f 310//310 311//311 312//312 -f 312//312 311//311 313//313 -f 313//313 311//311 314//314 -f 313//313 314//314 315//315 -f 315//315 314//314 316//316 -f 315//315 316//316 317//317 -f 318//318 319//319 320//320 -f 320//320 319//319 321//321 -f 320//320 321//321 322//322 -f 322//322 321//321 323//323 -f 322//322 323//323 324//324 -f 324//324 323//323 325//325 -f 324//324 325//325 316//316 -f 316//316 325//325 326//326 -f 316//316 326//326 317//317 -f 318//318 320//320 327//327 -f 327//327 320//320 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 331//331 -f 331//331 330//330 332//332 -f 332//332 330//330 333//333 -f 332//332 333//333 334//334 -f 334//334 333//333 335//335 -f 334//334 335//335 336//336 -f 250//250 337//337 251//251 -f 251//251 337//337 338//338 -f 251//251 338//338 339//339 -f 339//339 338//338 340//340 -f 339//339 340//340 341//341 -f 341//341 340//340 342//342 -f 341//341 342//342 343//343 -f 343//343 342//342 344//344 -f 343//343 344//344 335//335 -f 335//335 344//344 345//345 -f 335//335 345//345 336//336 -f 346//346 14//14 347//347 -f 347//347 14//14 13//13 -f 347//347 13//13 348//348 -f 348//348 13//13 12//12 -f 348//348 12//12 349//349 -f 349//349 12//12 11//11 -f 349//349 11//11 350//350 -f 350//350 11//11 10//10 -f 350//350 10//10 351//351 -f 351//351 10//10 9//9 -f 351//351 9//9 352//352 -f 352//352 9//9 25//25 -f 352//352 25//25 353//353 -f 353//353 25//25 24//24 -f 353//353 24//24 354//354 -f 354//354 24//24 23//23 -f 354//354 23//23 355//355 -f 355//355 23//23 22//22 -f 355//355 22//22 356//356 -f 356//356 22//22 21//21 -f 356//356 21//21 357//357 -f 357//357 21//21 20//20 -f 357//357 20//20 358//358 -f 358//358 20//20 8//8 -f 358//358 8//8 359//359 -f 359//359 8//8 2//2 -f 359//359 2//2 360//360 -f 360//360 2//2 1//1 -f 360//360 1//1 361//361 -f 361//361 1//1 15//15 -f 361//361 15//15 362//362 -f 362//362 15//15 33//33 -f 362//362 33//33 363//363 -f 363//363 33//33 34//34 -f 363//363 34//34 364//364 -f 364//364 34//34 32//32 -f 364//364 32//32 365//365 -f 365//365 32//32 36//36 -f 365//365 36//36 366//366 -f 366//366 36//36 35//35 -f 366//366 35//35 367//367 -f 367//367 35//35 31//31 -f 367//367 31//31 368//368 -f 368//368 31//31 30//30 -f 368//368 30//30 369//369 -f 369//369 30//30 29//29 -f 369//369 29//29 370//370 -f 370//370 29//29 28//28 -f 370//370 28//28 371//371 -f 371//371 28//28 27//27 -f 371//371 27//27 372//372 -f 372//372 27//27 26//26 -f 372//372 26//26 373//373 -f 373//373 26//26 17//17 -f 373//373 17//17 374//374 -f 374//374 17//17 16//16 -f 374//374 16//16 375//375 -f 375//375 16//16 3//3 -f 375//375 3//3 376//376 -f 376//376 3//3 4//4 -f 376//376 4//4 377//377 -f 377//377 4//4 7//7 -f 377//377 7//7 378//378 -f 378//378 7//7 6//6 -f 378//378 6//6 379//379 -f 379//379 6//6 5//5 -f 379//379 5//5 380//380 -f 380//380 5//5 19//19 -f 380//380 19//19 381//381 -f 381//381 19//19 18//18 -f 381//381 18//18 346//346 -f 346//346 18//18 14//14 -f 365//365 382//382 364//364 -f 364//364 382//382 383//383 -f 364//364 383//383 363//363 -f 363//363 383//383 384//384 -f 363//363 384//384 362//362 -f 362//362 384//384 385//385 -f 362//362 385//385 361//361 -f 361//361 385//385 386//386 -f 361//361 386//386 360//360 -f 360//360 386//386 387//387 -f 360//360 387//387 359//359 -f 359//359 387//387 388//388 -f 359//359 388//388 358//358 -f 358//358 388//388 389//389 -f 358//358 389//389 357//357 -f 357//357 389//389 390//390 -f 357//357 390//390 356//356 -f 356//356 390//390 391//391 -f 356//356 391//391 355//355 -f 355//355 391//391 392//392 -f 355//355 392//392 354//354 -f 354//354 392//392 393//393 -f 354//354 393//393 353//353 -f 353//353 393//393 394//394 -f 353//353 394//394 352//352 -f 352//352 394//394 395//395 -f 352//352 395//395 351//351 -f 351//351 395//395 396//396 -f 351//351 396//396 350//350 -f 350//350 396//396 397//397 -f 350//350 397//397 349//349 -f 349//349 397//397 398//398 -f 349//349 398//398 348//348 -f 348//348 398//398 399//399 -f 348//348 399//399 347//347 -f 347//347 399//399 400//400 -f 347//347 400//400 346//346 -f 346//346 400//400 401//401 -f 346//346 401//401 381//381 -f 381//381 401//401 402//402 -f 381//381 402//402 380//380 -f 380//380 402//402 403//403 -f 380//380 403//403 379//379 -f 379//379 403//403 404//404 -f 379//379 404//404 378//378 -f 378//378 404//404 405//405 -f 378//378 405//405 377//377 -f 377//377 405//405 406//406 -f 377//377 406//406 376//376 -f 376//376 406//406 407//407 -f 376//376 407//407 375//375 -f 375//375 407//407 408//408 -f 375//375 408//408 374//374 -f 374//374 408//408 409//409 -f 374//374 409//409 373//373 -f 373//373 409//409 410//410 -f 373//373 410//410 372//372 -f 372//372 410//410 411//411 -f 372//372 411//411 371//371 -f 371//371 411//411 412//412 -f 371//371 412//412 370//370 -f 370//370 412//412 413//413 -f 370//370 413//413 369//369 -f 369//369 413//413 414//414 -f 369//369 414//414 368//368 -f 368//368 414//414 415//415 -f 368//368 415//415 367//367 -f 367//367 415//415 416//416 -f 367//367 416//416 366//366 -f 366//366 416//416 417//417 -f 366//366 417//417 365//365 -f 365//365 417//417 382//382 -f 417//417 339//339 382//382 -f 382//382 339//339 341//341 -f 382//382 341//341 383//383 -f 383//383 341//341 343//343 -f 383//383 343//343 384//384 -f 384//384 343//343 335//335 -f 384//384 335//335 385//385 -f 385//385 335//335 333//333 -f 385//385 333//333 386//386 -f 386//386 333//333 330//330 -f 386//386 330//330 387//387 -f 387//387 330//330 328//328 -f 387//387 328//328 388//388 -f 388//388 328//328 320//320 -f 388//388 320//320 389//389 -f 389//389 320//320 322//322 -f 389//389 322//322 390//390 -f 390//390 322//322 324//324 -f 390//390 324//324 391//391 -f 391//391 324//324 316//316 -f 391//391 316//316 392//392 -f 392//392 316//316 314//314 -f 392//392 314//314 393//393 -f 393//393 314//314 311//311 -f 393//393 311//311 394//394 -f 394//394 311//311 309//309 -f 394//394 309//309 395//395 -f 395//395 309//309 303//303 -f 395//395 303//303 396//396 -f 396//396 303//303 305//305 -f 396//396 305//305 397//397 -f 397//397 305//305 298//298 -f 397//397 298//298 398//398 -f 398//398 298//298 289//289 -f 398//398 289//289 399//399 -f 399//399 289//289 291//291 -f 399//399 291//291 400//400 -f 400//400 291//291 293//293 -f 400//400 293//293 401//401 -f 401//401 293//293 295//295 -f 401//401 295//295 402//402 -f 402//402 295//295 287//287 -f 402//402 287//287 403//403 -f 403//403 287//287 285//285 -f 403//403 285//285 404//404 -f 404//404 285//285 282//282 -f 404//404 282//282 405//405 -f 405//405 282//282 280//280 -f 405//405 280//280 406//406 -f 406//406 280//280 272//272 -f 406//406 272//272 407//407 -f 407//407 272//272 274//274 -f 407//407 274//274 408//408 -f 408//408 274//274 276//276 -f 408//408 276//276 409//409 -f 409//409 276//276 268//268 -f 409//409 268//268 410//410 -f 410//410 268//268 266//266 -f 410//410 266//266 411//411 -f 411//411 266//266 263//263 -f 411//411 263//263 412//412 -f 412//412 263//263 261//261 -f 412//412 261//261 413//413 -f 413//413 261//261 255//255 -f 413//413 255//255 414//414 -f 414//414 255//255 257//257 -f 414//414 257//257 415//415 -f 415//415 257//257 252//252 -f 415//415 252//252 416//416 -f 416//416 252//252 251//251 -f 416//416 251//251 417//417 -f 417//417 251//251 339//339 -f 418//418 419//419 420//420 -f 421//421 422//422 423//423 -f 424//424 425//425 426//426 -f 427//427 428//428 429//429 -f 430//430 431//431 432//432 -f 433//433 434//434 435//435 -f 436//436 437//437 438//438 -f 439//439 440//440 441//441 -f 442//442 443//443 444//444 -f 445//445 446//446 447//447 -f 448//448 449//449 446//446 -f 446//446 449//449 450//450 -f 446//446 450//450 447//447 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 453//453 454//454 448//448 -f 448//448 454//454 455//455 -f 448//448 455//455 449//449 -f 456//456 457//457 451//451 -f 451//451 457//457 458//458 -f 451//451 458//458 452//452 -f 459//459 460//460 461//461 -f 461//461 460//460 462//462 -f 461//461 462//462 456//456 -f 456//456 462//462 463//463 -f 456//456 463//463 457//457 -f 444//444 464//464 442//442 -f 442//442 464//464 465//465 -f 442//442 465//465 459//459 -f 459//459 465//465 466//466 -f 459//459 466//466 460//460 -f 467//467 468//468 469//469 -f 469//469 468//468 470//470 -f 469//469 470//470 443//443 -f 443//443 470//470 471//471 -f 443//443 471//471 444//444 -f 472//472 473//473 467//467 -f 467//467 473//473 474//474 -f 467//467 474//474 468//468 -f 475//475 476//476 477//477 -f 477//477 476//476 478//478 -f 477//477 478//478 472//472 -f 472//472 478//478 479//479 -f 472//472 479//479 473//473 -f 441//441 480//480 439//439 -f 439//439 480//480 481//481 -f 439//439 481//481 475//475 -f 475//475 481//481 482//482 -f 475//475 482//482 476//476 -f 483//483 484//484 485//485 -f 485//485 484//484 486//486 -f 485//485 486//486 440//440 -f 440//440 486//486 487//487 -f 440//440 487//487 441//441 -f 438//438 488//488 436//436 -f 436//436 488//488 489//489 -f 436//436 489//489 483//483 -f 483//483 489//489 490//490 -f 483//483 490//490 484//484 -f 435//435 491//491 433//433 -f 433//433 491//491 492//492 -f 433//433 492//492 493//493 -f 493//493 492//492 494//494 -f 493//493 494//494 437//437 -f 437//437 494//494 495//495 -f 437//437 495//495 438//438 -f 496//496 497//497 498//498 -f 498//498 497//497 499//499 -f 498//498 499//499 434//434 -f 434//434 499//499 500//500 -f 434//434 500//500 435//435 -f 432//432 501//501 430//430 -f 430//430 501//501 502//502 -f 430//430 502//502 496//496 -f 496//496 502//502 503//503 -f 496//496 503//503 497//497 -f 429//429 504//504 427//427 -f 427//427 504//504 505//505 -f 427//427 505//505 506//506 -f 506//506 505//505 507//507 -f 506//506 507//507 431//431 -f 431//431 507//507 508//508 -f 431//431 508//508 432//432 -f 509//509 510//510 511//511 -f 511//511 510//510 512//512 -f 511//511 512//512 428//428 -f 428//428 512//512 513//513 -f 428//428 513//513 429//429 -f 426//426 514//514 424//424 -f 424//424 514//514 515//515 -f 424//424 515//515 509//509 -f 509//509 515//515 516//516 -f 509//509 516//516 510//510 -f 517//517 518//518 519//519 -f 519//519 518//518 520//520 -f 519//519 520//520 425//425 -f 425//425 520//520 521//521 -f 425//425 521//521 426//426 -f 522//522 523//523 524//524 -f 524//524 523//523 525//525 -f 524//524 525//525 517//517 -f 517//517 525//525 526//526 -f 517//517 526//526 518//518 -f 527//527 528//528 522//522 -f 522//522 528//528 529//529 -f 522//522 529//529 523//523 -f 423//423 530//530 421//421 -f 421//421 530//530 531//531 -f 421//421 531//531 527//527 -f 527//527 531//531 532//532 -f 527//527 532//532 528//528 -f 533//533 534//534 535//535 -f 535//535 534//534 536//536 -f 535//535 536//536 422//422 -f 422//422 536//536 537//537 -f 422//422 537//537 423//423 -f 538//538 539//539 540//540 -f 540//540 539//539 541//541 -f 540//540 541//541 533//533 -f 533//533 541//541 542//542 -f 533//533 542//542 534//534 -f 543//543 544//544 538//538 -f 538//538 544//544 545//545 -f 538//538 545//545 539//539 -f 420//420 546//546 418//418 -f 418//418 546//546 547//547 -f 418//418 547//547 543//543 -f 543//543 547//547 548//548 -f 543//543 548//548 544//544 -f 549//549 550//550 551//551 -f 551//551 550//550 552//552 -f 551//551 552//552 419//419 -f 419//419 552//552 553//553 -f 419//419 553//553 420//420 -f 447//447 554//554 445//445 -f 445//445 554//554 555//555 -f 445//445 555//555 556//556 -f 556//556 555//555 557//557 -f 556//556 557//557 558//558 -f 558//558 557//557 559//559 -f 558//558 559//559 549//549 -f 549//549 559//559 560//560 -f 549//549 560//560 550//550 -f 558//558 561//561 556//556 -f 556//556 561//561 562//562 -f 556//556 562//562 445//445 -f 445//445 562//562 563//563 -f 445//445 563//563 446//446 -f 446//446 563//563 564//564 -f 446//446 564//564 448//448 -f 448//448 564//564 565//565 -f 448//448 565//565 453//453 -f 453//453 565//565 566//566 -f 453//453 566//566 451//451 -f 451//451 566//566 567//567 -f 451//451 567//567 456//456 -f 456//456 567//567 568//568 -f 456//456 568//568 461//461 -f 461//461 568//568 569//569 -f 461//461 569//569 459//459 -f 459//459 569//569 570//570 -f 459//459 570//570 442//442 -f 442//442 570//570 571//571 -f 442//442 571//571 443//443 -f 443//443 571//571 572//572 -f 443//443 572//572 469//469 -f 469//469 572//572 573//573 -f 469//469 573//573 467//467 -f 467//467 573//573 574//574 -f 467//467 574//574 472//472 -f 472//472 574//574 575//575 -f 472//472 575//575 477//477 -f 477//477 575//575 576//576 -f 477//477 576//576 475//475 -f 475//475 576//576 577//577 -f 475//475 577//577 439//439 -f 439//439 577//577 578//578 -f 439//439 578//578 440//440 -f 440//440 578//578 579//579 -f 440//440 579//579 485//485 -f 485//485 579//579 580//580 -f 485//485 580//580 483//483 -f 483//483 580//580 581//581 -f 483//483 581//581 436//436 -f 436//436 581//581 582//582 -f 436//436 582//582 437//437 -f 437//437 582//582 583//583 -f 437//437 583//583 493//493 -f 493//493 583//583 584//584 -f 493//493 584//584 433//433 -f 433//433 584//584 585//585 -f 433//433 585//585 434//434 -f 434//434 585//585 586//586 -f 434//434 586//586 498//498 -f 498//498 586//586 587//587 -f 498//498 587//587 496//496 -f 496//496 587//587 588//588 -f 496//496 588//588 430//430 -f 430//430 588//588 589//589 -f 430//430 589//589 431//431 -f 431//431 589//589 590//590 -f 431//431 590//590 506//506 -f 506//506 590//590 591//591 -f 506//506 591//591 427//427 -f 427//427 591//591 592//592 -f 427//427 592//592 428//428 -f 428//428 592//592 593//593 -f 428//428 593//593 511//511 -f 511//511 593//593 594//594 -f 511//511 594//594 509//509 -f 509//509 594//594 595//595 -f 509//509 595//595 424//424 -f 424//424 595//595 596//596 -f 424//424 596//596 425//425 -f 425//425 596//596 597//597 -f 425//425 597//597 519//519 -f 519//519 597//597 598//598 -f 519//519 598//598 517//517 -f 517//517 598//598 599//599 -f 517//517 599//599 524//524 -f 524//524 599//599 600//600 -f 524//524 600//600 522//522 -f 522//522 600//600 601//601 -f 522//522 601//601 527//527 -f 527//527 601//601 602//602 -f 527//527 602//602 421//421 -f 421//421 602//602 603//603 -f 421//421 603//603 422//422 -f 422//422 603//603 604//604 -f 422//422 604//604 535//535 -f 535//535 604//604 605//605 -f 535//535 605//605 533//533 -f 533//533 605//605 606//606 -f 533//533 606//606 540//540 -f 540//540 606//606 607//607 -f 540//540 607//607 538//538 -f 538//538 607//607 608//608 -f 538//538 608//608 543//543 -f 543//543 608//608 609//609 -f 543//543 609//609 418//418 -f 418//418 609//609 610//610 -f 418//418 610//610 419//419 -f 419//419 610//610 611//611 -f 419//419 611//611 551//551 -f 551//551 611//611 612//612 -f 551//551 612//612 549//549 -f 549//549 612//612 613//613 -f 549//549 613//613 558//558 -f 558//558 613//613 561//561 -f 92//92 613//613 94//94 -f 94//94 613//613 612//612 -f 94//94 612//612 96//96 -f 96//96 612//612 611//611 -f 96//96 611//611 98//98 -f 98//98 611//611 610//610 -f 98//98 610//610 100//100 -f 100//100 610//610 609//609 -f 100//100 609//609 102//102 -f 102//102 609//609 608//608 -f 102//102 608//608 104//104 -f 104//104 608//608 607//607 -f 104//104 607//607 106//106 -f 106//106 607//607 606//606 -f 106//106 606//606 108//108 -f 108//108 606//606 605//605 -f 108//108 605//605 110//110 -f 110//110 605//605 604//604 -f 110//110 604//604 112//112 -f 112//112 604//604 603//603 -f 112//112 603//603 114//114 -f 114//114 603//603 602//602 -f 114//114 602//602 116//116 -f 116//116 602//602 601//601 -f 116//116 601//601 118//118 -f 118//118 601//601 600//600 -f 118//118 600//600 120//120 -f 120//120 600//600 599//599 -f 120//120 599//599 122//122 -f 122//122 599//599 598//598 -f 122//122 598//598 124//124 -f 124//124 598//598 597//597 -f 124//124 597//597 126//126 -f 126//126 597//597 596//596 -f 126//126 596//596 128//128 -f 128//128 596//596 595//595 -f 128//128 595//595 130//130 -f 130//130 595//595 594//594 -f 130//130 594//594 132//132 -f 132//132 594//594 593//593 -f 132//132 593//593 134//134 -f 134//134 593//593 592//592 -f 134//134 592//592 136//136 -f 136//136 592//592 591//591 -f 136//136 591//591 138//138 -f 138//138 591//591 590//590 -f 138//138 590//590 140//140 -f 140//140 590//590 589//589 -f 140//140 589//589 142//142 -f 142//142 589//589 588//588 -f 142//142 588//588 144//144 -f 144//144 588//588 587//587 -f 144//144 587//587 146//146 -f 146//146 587//587 586//586 -f 146//146 586//586 148//148 -f 148//148 586//586 585//585 -f 148//148 585//585 150//150 -f 150//150 585//585 584//584 -f 150//150 584//584 152//152 -f 152//152 584//584 583//583 -f 152//152 583//583 154//154 -f 154//154 583//583 582//582 -f 154//154 582//582 156//156 -f 156//156 582//582 581//581 -f 156//156 581//581 158//158 -f 158//158 581//581 580//580 -f 158//158 580//580 160//160 -f 160//160 580//580 579//579 -f 160//160 579//579 162//162 -f 162//162 579//579 578//578 -f 162//162 578//578 164//164 -f 164//164 578//578 577//577 -f 164//164 577//577 166//166 -f 166//166 577//577 576//576 -f 166//166 576//576 168//168 -f 168//168 576//576 575//575 -f 168//168 575//575 170//170 -f 170//170 575//575 574//574 -f 170//170 574//574 172//172 -f 172//172 574//574 573//573 -f 172//172 573//573 174//174 -f 174//174 573//573 572//572 -f 174//174 572//572 176//176 -f 176//176 572//572 571//571 -f 176//176 571//571 178//178 -f 178//178 571//571 570//570 -f 178//178 570//570 180//180 -f 180//180 570//570 569//569 -f 180//180 569//569 182//182 -f 182//182 569//569 568//568 -f 182//182 568//568 184//184 -f 184//184 568//568 567//567 -f 184//184 567//567 186//186 -f 186//186 567//567 566//566 -f 186//186 566//566 188//188 -f 188//188 566//566 565//565 -f 188//188 565//565 190//190 -f 190//190 565//565 564//564 -f 190//190 564//564 192//192 -f 192//192 564//564 563//563 -f 192//192 563//563 194//194 -f 194//194 563//563 562//562 -f 194//194 562//562 196//196 -f 196//196 562//562 561//561 -f 196//196 561//561 92//92 -f 92//92 561//561 613//613 -f 337//337 614//614 615//615 -f 258//258 616//616 259//259 -f 259//259 616//616 614//614 -f 259//259 614//614 250//250 -f 250//250 614//614 337//337 -f 258//258 256//256 616//616 -f 616//616 256//256 254//254 -f 616//616 254//254 617//617 -f 254//254 253//253 617//617 -f 617//617 253//253 260//260 -f 617//617 260//260 618//618 -f 265//265 619//619 264//264 -f 264//264 619//619 618//618 -f 264//264 618//618 262//262 -f 262//262 618//618 260//260 -f 265//265 267//267 619//619 -f 619//619 267//267 269//269 -f 619//619 269//269 620//620 -f 275//275 621//621 277//277 -f 277//277 621//621 620//620 -f 277//277 620//620 278//278 -f 278//278 620//620 269//269 -f 275//275 273//273 621//621 -f 621//621 273//273 271//271 -f 621//621 271//271 622//622 -f 271//271 270//270 622//622 -f 622//622 270//270 279//279 -f 622//622 279//279 623//623 -f 284//284 624//624 283//283 -f 283//283 624//624 623//623 -f 283//283 623//623 281//281 -f 281//281 623//623 279//279 -f 284//284 286//286 624//624 -f 624//624 286//286 288//288 -f 624//624 288//288 625//625 -f 288//288 297//297 625//625 -f 625//625 297//297 296//296 -f 625//625 296//296 626//626 -f 296//296 294//294 626//626 -f 626//626 294//294 292//292 -f 626//626 292//292 627//627 -f 292//292 290//290 627//627 -f 627//627 290//290 300//300 -f 627//627 300//300 628//628 -f 306//306 629//629 307//307 -f 307//307 629//629 628//628 -f 307//307 628//628 299//299 -f 299//299 628//628 300//300 -f 306//306 304//304 629//629 -f 629//629 304//304 302//302 -f 629//629 302//302 630//630 -f 302//302 301//301 630//630 -f 630//630 301//301 308//308 -f 630//630 308//308 631//631 -f 313//313 632//632 312//312 -f 312//312 632//632 631//631 -f 312//312 631//631 310//310 -f 310//310 631//631 308//308 -f 313//313 315//315 632//632 -f 632//632 315//315 317//317 -f 632//632 317//317 633//633 -f 323//323 634//634 325//325 -f 325//325 634//634 633//633 -f 325//325 633//633 326//326 -f 326//326 633//633 317//317 -f 323//323 321//321 634//634 -f 634//634 321//321 319//319 -f 634//634 319//319 635//635 -f 319//319 318//318 635//635 -f 635//635 318//318 327//327 -f 635//635 327//327 636//636 -f 332//332 637//637 331//331 -f 331//331 637//637 636//636 -f 331//331 636//636 329//329 -f 329//329 636//636 327//327 -f 332//332 334//334 637//637 -f 637//637 334//334 336//336 -f 637//637 336//336 638//638 -f 336//336 345//345 638//638 -f 638//638 345//345 344//344 -f 638//638 344//344 639//639 -f 344//344 342//342 639//639 -f 639//639 342//342 340//340 -f 639//639 340//340 615//615 -f 615//615 340//340 338//338 -f 615//615 338//338 337//337 -f 640//640 560//560 641//641 -f 641//641 560//560 559//559 -f 641//641 559//559 642//642 -f 642//642 559//559 557//557 -f 642//642 557//557 643//643 -f 643//643 557//557 555//555 -f 643//643 555//555 644//644 -f 644//644 555//555 554//554 -f 644//644 554//554 645//645 -f 645//645 554//554 447//447 -f 645//645 447//447 646//646 -f 646//646 447//447 450//450 -f 646//646 450//450 647//647 -f 647//647 450//450 449//449 -f 647//647 449//449 648//648 -f 648//648 449//449 455//455 -f 648//648 455//455 649//649 -f 649//649 455//455 454//454 -f 649//649 454//454 650//650 -f 650//650 454//454 452//452 -f 650//650 452//452 651//651 -f 651//651 452//452 458//458 -f 651//651 458//458 652//652 -f 652//652 458//458 457//457 -f 652//652 457//457 653//653 -f 653//653 457//457 463//463 -f 653//653 463//463 654//654 -f 654//654 463//463 462//462 -f 654//654 462//462 655//655 -f 655//655 462//462 460//460 -f 655//655 460//460 656//656 -f 656//656 460//460 466//466 -f 656//656 466//466 657//657 -f 657//657 466//466 465//465 -f 657//657 465//465 658//658 -f 658//658 465//465 464//464 -f 658//658 464//464 659//659 -f 659//659 464//464 444//444 -f 659//659 444//444 660//660 -f 660//660 444//444 471//471 -f 660//660 471//471 661//661 -f 661//661 471//471 470//470 -f 661//661 470//470 662//662 -f 662//662 470//470 468//468 -f 662//662 468//468 663//663 -f 663//663 468//468 474//474 -f 663//663 474//474 664//664 -f 664//664 474//474 473//473 -f 664//664 473//473 665//665 -f 665//665 473//473 479//479 -f 665//665 479//479 666//666 -f 666//666 479//479 478//478 -f 666//666 478//478 667//667 -f 667//667 478//478 476//476 -f 667//667 476//476 668//668 -f 668//668 476//476 482//482 -f 668//668 482//482 669//669 -f 669//669 482//482 481//481 -f 669//669 481//481 670//670 -f 670//670 481//481 480//480 -f 670//670 480//480 671//671 -f 671//671 480//480 441//441 -f 671//671 441//441 672//672 -f 672//672 441//441 487//487 -f 672//672 487//487 673//673 -f 673//673 487//487 486//486 -f 673//673 486//486 674//674 -f 674//674 486//486 484//484 -f 674//674 484//484 675//675 -f 675//675 484//484 490//490 -f 675//675 490//490 676//676 -f 676//676 490//490 489//489 -f 676//676 489//489 677//677 -f 677//677 489//489 488//488 -f 677//677 488//488 678//678 -f 678//678 488//488 438//438 -f 678//678 438//438 679//679 -f 679//679 438//438 495//495 -f 679//679 495//495 680//680 -f 680//680 495//495 494//494 -f 680//680 494//494 681//681 -f 681//681 494//494 492//492 -f 681//681 492//492 682//682 -f 682//682 492//492 491//491 -f 682//682 491//491 683//683 -f 683//683 491//491 435//435 -f 683//683 435//435 684//684 -f 684//684 435//435 500//500 -f 684//684 500//500 685//685 -f 685//685 500//500 499//499 -f 685//685 499//499 686//686 -f 686//686 499//499 497//497 -f 686//686 497//497 687//687 -f 687//687 497//497 503//503 -f 687//687 503//503 688//688 -f 688//688 503//503 502//502 -f 688//688 502//502 689//689 -f 689//689 502//502 501//501 -f 689//689 501//501 690//690 -f 690//690 501//501 432//432 -f 690//690 432//432 691//691 -f 691//691 432//432 508//508 -f 691//691 508//508 692//692 -f 692//692 508//508 507//507 -f 692//692 507//507 693//693 -f 693//693 507//507 505//505 -f 693//693 505//505 694//694 -f 694//694 505//505 504//504 -f 694//694 504//504 695//695 -f 695//695 504//504 429//429 -f 695//695 429//429 696//696 -f 696//696 429//429 513//513 -f 696//696 513//513 697//697 -f 697//697 513//513 512//512 -f 697//697 512//512 698//698 -f 698//698 512//512 510//510 -f 698//698 510//510 699//699 -f 699//699 510//510 516//516 -f 699//699 516//516 700//700 -f 700//700 516//516 515//515 -f 700//700 515//515 701//701 -f 701//701 515//515 514//514 -f 701//701 514//514 702//702 -f 702//702 514//514 426//426 -f 702//702 426//426 703//703 -f 703//703 426//426 521//521 -f 703//703 521//521 704//704 -f 704//704 521//521 520//520 -f 704//704 520//520 705//705 -f 705//705 520//520 518//518 -f 705//705 518//518 706//706 -f 706//706 518//518 526//526 -f 706//706 526//526 707//707 -f 707//707 526//526 525//525 -f 707//707 525//525 708//708 -f 708//708 525//525 523//523 -f 708//708 523//523 709//709 -f 709//709 523//523 529//529 -f 709//709 529//529 710//710 -f 710//710 529//529 528//528 -f 710//710 528//528 711//711 -f 711//711 528//528 532//532 -f 711//711 532//532 712//712 -f 712//712 532//532 531//531 -f 712//712 531//531 713//713 -f 713//713 531//531 530//530 -f 713//713 530//530 714//714 -f 714//714 530//530 423//423 -f 714//714 423//423 715//715 -f 715//715 423//423 537//537 -f 715//715 537//537 716//716 -f 716//716 537//537 536//536 -f 716//716 536//536 717//717 -f 717//717 536//536 534//534 -f 717//717 534//534 718//718 -f 718//718 534//534 542//542 -f 718//718 542//542 719//719 -f 719//719 542//542 541//541 -f 719//719 541//541 720//720 -f 720//720 541//541 539//539 -f 720//720 539//539 721//721 -f 721//721 539//539 545//545 -f 721//721 545//545 722//722 -f 722//722 545//545 544//544 -f 722//722 544//544 723//723 -f 723//723 544//544 548//548 -f 723//723 548//548 724//724 -f 724//724 548//548 547//547 -f 724//724 547//547 725//725 -f 725//725 547//547 546//546 -f 725//725 546//546 726//726 -f 726//726 546//546 420//420 -f 726//726 420//420 727//727 -f 727//727 420//420 553//553 -f 727//727 553//553 728//728 -f 728//728 553//553 552//552 -f 728//728 552//552 729//729 -f 729//729 552//552 550//550 -f 729//729 550//550 640//640 -f 640//640 550//550 560//560 -f 627//627 628//628 730//730 -f 615//615 731//731 639//639 -f 639//639 731//731 732//732 -f 639//639 732//732 638//638 -f 632//632 733//733 631//631 -f 631//631 733//733 734//734 -f 631//631 734//734 630//630 -f 619//619 620//620 735//735 -f 625//625 736//736 624//624 -f 624//624 736//736 737//737 -f 624//624 737//737 623//623 -f 730//730 738//738 627//627 -f 627//627 738//738 739//739 -f 627//627 739//739 626//626 -f 626//626 739//739 740//740 -f 626//626 740//740 625//625 -f 625//625 740//740 741//741 -f 625//625 741//741 736//736 -f 634//634 742//742 633//633 -f 633//633 742//742 743//743 -f 633//633 743//743 632//632 -f 632//632 743//743 744//744 -f 632//632 744//744 733//733 -f 636//636 745//745 635//635 -f 635//635 745//745 746//746 -f 635//635 746//746 634//634 -f 634//634 746//746 747//747 -f 634//634 747//747 742//742 -f 732//732 748//748 638//638 -f 638//638 748//748 749//749 -f 638//638 749//749 637//637 -f 637//637 749//749 750//750 -f 637//637 750//750 636//636 -f 636//636 750//750 751//751 -f 636//636 751//751 745//745 -f 614//614 752//752 615//615 -f 615//615 752//752 753//753 -f 615//615 753//753 731//731 -f 734//734 754//754 630//630 -f 630//630 754//754 755//755 -f 630//630 755//755 629//629 -f 629//629 755//755 756//756 -f 629//629 756//756 628//628 -f 628//628 756//756 757//757 -f 628//628 757//757 730//730 -f 617//617 758//758 616//616 -f 616//616 758//758 759//759 -f 616//616 759//759 614//614 -f 614//614 759//759 760//760 -f 614//614 760//760 752//752 -f 735//735 761//761 619//619 -f 619//619 761//761 762//762 -f 619//619 762//762 618//618 -f 618//618 762//762 763//763 -f 618//618 763//763 617//617 -f 617//617 763//763 764//764 -f 617//617 764//764 758//758 -f 737//737 765//765 623//623 -f 623//623 765//765 766//766 -f 623//623 766//766 622//622 -f 622//622 766//766 767//767 -f 622//622 767//767 621//621 -f 621//621 767//767 768//768 -f 621//621 768//768 620//620 -f 620//620 768//768 769//769 -f 620//620 769//769 735//735 -f 729//729 770//770 771//771 -f 724//724 725//725 772//772 -f 772//772 725//725 726//726 -f 772//772 726//726 773//773 -f 773//773 726//726 727//727 -f 773//773 727//727 771//771 -f 771//771 727//727 728//728 -f 771//771 728//728 729//729 -f 724//724 772//772 723//723 -f 723//723 772//772 774//774 -f 723//723 774//774 722//722 -f 722//722 774//774 775//775 -f 722//722 775//775 721//721 -f 721//721 775//775 720//720 -f 720//720 775//775 776//776 -f 720//720 776//776 719//719 -f 719//719 776//776 777//777 -f 719//719 777//777 718//718 -f 718//718 777//777 717//717 -f 717//717 777//777 778//778 -f 717//717 778//778 716//716 -f 716//716 778//778 715//715 -f 715//715 778//778 779//779 -f 715//715 779//779 714//714 -f 714//714 779//779 780//780 -f 714//714 780//780 713//713 -f 781//781 710//710 782//782 -f 782//782 710//710 711//711 -f 782//782 711//711 780//780 -f 780//780 711//711 712//712 -f 780//780 712//712 713//713 -f 783//783 707//707 784//784 -f 784//784 707//707 708//708 -f 784//784 708//708 781//781 -f 781//781 708//708 709//709 -f 781//781 709//709 710//710 -f 785//785 705//705 783//783 -f 783//783 705//705 706//706 -f 783//783 706//706 707//707 -f 700//700 701//701 786//786 -f 786//786 701//701 702//702 -f 786//786 702//702 787//787 -f 787//787 702//702 703//703 -f 787//787 703//703 785//785 -f 785//785 703//703 704//704 -f 785//785 704//704 705//705 -f 700//700 786//786 699//699 -f 699//699 786//786 788//788 -f 699//699 788//788 698//698 -f 698//698 788//788 789//789 -f 698//698 789//789 697//697 -f 697//697 789//789 696//696 -f 696//696 789//789 790//790 -f 696//696 790//790 695//695 -f 695//695 790//790 791//791 -f 695//695 791//791 694//694 -f 694//694 791//791 693//693 -f 693//693 791//791 792//792 -f 693//693 792//792 692//692 -f 692//692 792//792 691//691 -f 691//691 792//792 793//793 -f 691//691 793//793 690//690 -f 690//690 793//793 794//794 -f 690//690 794//794 689//689 -f 795//795 686//686 796//796 -f 796//796 686//686 687//687 -f 796//796 687//687 794//794 -f 794//794 687//687 688//688 -f 794//794 688//688 689//689 -f 797//797 683//683 798//798 -f 798//798 683//683 684//684 -f 798//798 684//684 795//795 -f 795//795 684//684 685//685 -f 795//795 685//685 686//686 -f 799//799 681//681 797//797 -f 797//797 681//681 682//682 -f 797//797 682//682 683//683 -f 676//676 677//677 800//800 -f 800//800 677//677 678//678 -f 800//800 678//678 801//801 -f 801//801 678//678 679//679 -f 801//801 679//679 799//799 -f 799//799 679//679 680//680 -f 799//799 680//680 681//681 -f 676//676 800//800 675//675 -f 675//675 800//800 802//802 -f 675//675 802//802 674//674 -f 674//674 802//802 803//803 -f 674//674 803//803 673//673 -f 673//673 803//803 672//672 -f 672//672 803//803 804//804 -f 672//672 804//804 671//671 -f 671//671 804//804 805//805 -f 671//671 805//805 670//670 -f 670//670 805//805 669//669 -f 669//669 805//805 806//806 -f 669//669 806//806 668//668 -f 668//668 806//806 667//667 -f 667//667 806//806 807//807 -f 667//667 807//807 666//666 -f 666//666 807//807 808//808 -f 666//666 808//808 665//665 -f 809//809 662//662 810//810 -f 810//810 662//662 663//663 -f 810//810 663//663 808//808 -f 808//808 663//663 664//664 -f 808//808 664//664 665//665 -f 657//657 658//658 811//811 -f 811//811 658//658 659//659 -f 811//811 659//659 812//812 -f 812//812 659//659 660//660 -f 812//812 660//660 809//809 -f 809//809 660//660 661//661 -f 809//809 661//661 662//662 -f 657//657 811//811 656//656 -f 656//656 811//811 813//813 -f 656//656 813//813 655//655 -f 655//655 813//813 814//814 -f 655//655 814//814 654//654 -f 654//654 814//814 815//815 -f 654//654 815//815 653//653 -f 653//653 815//815 652//652 -f 652//652 815//815 816//816 -f 652//652 816//816 651//651 -f 651//651 816//816 650//650 -f 650//650 816//816 817//817 -f 650//650 817//817 649//649 -f 649//649 817//817 648//648 -f 648//648 817//817 818//818 -f 648//648 818//818 647//647 -f 647//647 818//818 819//819 -f 647//647 819//819 646//646 -f 729//729 640//640 770//770 -f 770//770 640//640 641//641 -f 770//770 641//641 820//820 -f 820//820 641//641 642//642 -f 820//820 642//642 821//821 -f 821//821 642//642 643//643 -f 821//821 643//643 822//822 -f 822//822 643//643 644//644 -f 822//822 644//644 819//819 -f 819//819 644//644 645//645 -f 819//819 645//645 646//646 -f 823//823 824//824 825//825 -f 825//825 824//824 826//826 -f 825//825 826//826 827//827 -f 827//827 826//826 828//828 -f 827//827 828//828 829//829 -f 829//829 828//828 830//830 -f 829//829 830//830 831//831 -f 831//831 830//830 832//832 -f 831//831 832//832 833//833 -f 833//833 832//832 834//834 -f 833//833 834//834 835//835 -f 835//835 834//834 836//836 -f 835//835 836//836 837//837 -f 837//837 836//836 838//838 -f 837//837 838//838 839//839 -f 839//839 838//838 840//840 -f 839//839 840//840 841//841 -f 841//841 840//840 842//842 -f 841//841 842//842 843//843 -f 843//843 842//842 844//844 -f 843//843 844//844 845//845 -f 845//845 844//844 846//846 -f 845//845 846//846 847//847 -f 847//847 846//846 848//848 -f 847//847 848//848 849//849 -f 849//849 848//848 850//850 -f 849//849 850//850 851//851 -f 851//851 850//850 852//852 -f 851//851 852//852 853//853 -f 853//853 852//852 854//854 -f 853//853 854//854 855//855 -f 855//855 854//854 856//856 -f 855//855 856//856 857//857 -f 857//857 856//856 858//858 -f 857//857 858//858 859//859 -f 859//859 858//858 860//860 -f 859//859 860//860 861//861 -f 861//861 860//860 862//862 -f 861//861 862//862 863//863 -f 863//863 862//862 864//864 -f 863//863 864//864 865//865 -f 865//865 864//864 866//866 -f 865//865 866//866 867//867 -f 867//867 866//866 868//868 -f 867//867 868//868 869//869 -f 869//869 868//868 870//870 -f 869//869 870//870 871//871 -f 871//871 870//870 872//872 -f 871//871 872//872 873//873 -f 873//873 872//872 874//874 -f 873//873 874//874 875//875 -f 875//875 874//874 876//876 -f 875//875 876//876 877//877 -f 877//877 876//876 878//878 -f 877//877 878//878 879//879 -f 879//879 878//878 880//880 -f 879//879 880//880 881//881 -f 881//881 880//880 882//882 -f 881//881 882//882 883//883 -f 883//883 882//882 884//884 -f 883//883 884//884 885//885 -f 885//885 884//884 886//886 -f 885//885 886//886 887//887 -f 887//887 886//886 888//888 -f 887//887 888//888 889//889 -f 889//889 888//888 890//890 -f 889//889 890//890 891//891 -f 891//891 890//890 892//892 -f 891//891 892//892 893//893 -f 893//893 892//892 894//894 -f 893//893 894//894 895//895 -f 895//895 894//894 896//896 -f 895//895 896//896 897//897 -f 897//897 896//896 898//898 -f 897//897 898//898 899//899 -f 899//899 898//898 900//900 -f 899//899 900//900 901//901 -f 901//901 900//900 902//902 -f 901//901 902//902 903//903 -f 903//903 902//902 904//904 -f 903//903 904//904 905//905 -f 905//905 904//904 906//906 -f 905//905 906//906 907//907 -f 907//907 906//906 908//908 -f 907//907 908//908 909//909 -f 909//909 908//908 910//910 -f 909//909 910//910 911//911 -f 911//911 910//910 912//912 -f 911//911 912//912 913//913 -f 913//913 912//912 914//914 -f 913//913 914//914 915//915 -f 915//915 914//914 916//916 -f 915//915 916//916 917//917 -f 917//917 916//916 918//918 -f 917//917 918//918 919//919 -f 919//919 918//918 920//920 -f 919//919 920//920 921//921 -f 921//921 920//920 922//922 -f 921//921 922//922 923//923 -f 923//923 922//922 924//924 -f 923//923 924//924 925//925 -f 925//925 924//924 926//926 -f 925//925 926//926 927//927 -f 927//927 926//926 928//928 -f 927//927 928//928 929//929 -f 929//929 928//928 823//823 -f 929//929 823//823 825//825 -f 877//877 930//930 875//875 -f 875//875 930//930 931//931 -f 875//875 931//931 873//873 -f 873//873 931//931 932//932 -f 873//873 932//932 871//871 -f 871//871 932//932 933//933 -f 871//871 933//933 869//869 -f 869//869 933//933 934//934 -f 869//869 934//934 867//867 -f 867//867 934//934 935//935 -f 867//867 935//935 865//865 -f 865//865 935//935 936//936 -f 865//865 936//936 863//863 -f 863//863 936//936 937//937 -f 863//863 937//937 861//861 -f 861//861 937//937 938//938 -f 861//861 938//938 859//859 -f 859//859 938//938 939//939 -f 859//859 939//939 857//857 -f 857//857 939//939 940//940 -f 857//857 940//940 855//855 -f 855//855 940//940 941//941 -f 855//855 941//941 853//853 -f 853//853 941//941 942//942 -f 853//853 942//942 851//851 -f 851//851 942//942 943//943 -f 851//851 943//943 849//849 -f 849//849 943//943 944//944 -f 849//849 944//944 847//847 -f 847//847 944//944 945//945 -f 847//847 945//945 845//845 -f 845//845 945//945 946//946 -f 845//845 946//946 843//843 -f 843//843 946//946 947//947 -f 843//843 947//947 841//841 -f 841//841 947//947 948//948 -f 841//841 948//948 839//839 -f 839//839 948//948 949//949 -f 839//839 949//949 837//837 -f 837//837 949//949 950//950 -f 837//837 950//950 835//835 -f 835//835 950//950 951//951 -f 835//835 951//951 833//833 -f 833//833 951//951 952//952 -f 833//833 952//952 831//831 -f 831//831 952//952 953//953 -f 831//831 953//953 829//829 -f 829//829 953//953 954//954 -f 829//829 954//954 827//827 -f 827//827 954//954 955//955 -f 827//827 955//955 825//825 -f 825//825 955//955 956//956 -f 825//825 956//956 929//929 -f 929//929 956//956 957//957 -f 929//929 957//957 927//927 -f 927//927 957//957 958//958 -f 927//927 958//958 925//925 -f 925//925 958//958 959//959 -f 925//925 959//959 923//923 -f 923//923 959//959 960//960 -f 923//923 960//960 921//921 -f 921//921 960//960 961//961 -f 921//921 961//961 919//919 -f 919//919 961//961 962//962 -f 919//919 962//962 917//917 -f 917//917 962//962 963//963 -f 917//917 963//963 915//915 -f 915//915 963//963 964//964 -f 915//915 964//964 913//913 -f 913//913 964//964 965//965 -f 913//913 965//965 911//911 -f 911//911 965//965 966//966 -f 911//911 966//966 909//909 -f 909//909 966//966 967//967 -f 909//909 967//967 907//907 -f 907//907 967//967 968//968 -f 907//907 968//968 905//905 -f 905//905 968//968 969//969 -f 905//905 969//969 903//903 -f 903//903 969//969 970//970 -f 903//903 970//970 901//901 -f 901//901 970//970 971//971 -f 901//901 971//971 899//899 -f 899//899 971//971 972//972 -f 899//899 972//972 897//897 -f 897//897 972//972 973//973 -f 897//897 973//973 895//895 -f 895//895 973//973 974//974 -f 895//895 974//974 893//893 -f 893//893 974//974 975//975 -f 893//893 975//975 891//891 -f 891//891 975//975 976//976 -f 891//891 976//976 889//889 -f 889//889 976//976 977//977 -f 889//889 977//977 887//887 -f 887//887 977//977 978//978 -f 887//887 978//978 885//885 -f 885//885 978//978 979//979 -f 885//885 979//979 883//883 -f 883//883 979//979 980//980 -f 883//883 980//980 881//881 -f 881//881 980//980 981//981 -f 881//881 981//981 879//879 -f 879//879 981//981 982//982 -f 879//879 982//982 877//877 -f 877//877 982//982 930//930 -f 930//930 820//820 931//931 -f 931//931 820//820 821//821 -f 931//931 821//821 932//932 -f 932//932 821//821 822//822 -f 932//932 822//822 933//933 -f 933//933 822//822 819//819 -f 933//933 819//819 934//934 -f 934//934 819//819 818//818 -f 934//934 818//818 935//935 -f 935//935 818//818 817//817 -f 935//935 817//817 936//936 -f 936//936 817//817 816//816 -f 936//936 816//816 937//937 -f 937//937 816//816 815//815 -f 937//937 815//815 938//938 -f 938//938 815//815 814//814 -f 938//938 814//814 939//939 -f 939//939 814//814 813//813 -f 939//939 813//813 940//940 -f 940//940 813//813 811//811 -f 940//940 811//811 941//941 -f 941//941 811//811 812//812 -f 941//941 812//812 942//942 -f 942//942 812//812 809//809 -f 942//942 809//809 943//943 -f 943//943 809//809 810//810 -f 943//943 810//810 944//944 -f 944//944 810//810 808//808 -f 944//944 808//808 945//945 -f 945//945 808//808 807//807 -f 945//945 807//807 946//946 -f 946//946 807//807 806//806 -f 946//946 806//806 947//947 -f 947//947 806//806 805//805 -f 947//947 805//805 948//948 -f 948//948 805//805 804//804 -f 948//948 804//804 949//949 -f 949//949 804//804 803//803 -f 949//949 803//803 950//950 -f 950//950 803//803 802//802 -f 950//950 802//802 951//951 -f 951//951 802//802 800//800 -f 951//951 800//800 952//952 -f 952//952 800//800 801//801 -f 952//952 801//801 953//953 -f 953//953 801//801 799//799 -f 953//953 799//799 954//954 -f 954//954 799//799 797//797 -f 954//954 797//797 955//955 -f 955//955 797//797 798//798 -f 955//955 798//798 956//956 -f 956//956 798//798 795//795 -f 956//956 795//795 957//957 -f 957//957 795//795 796//796 -f 957//957 796//796 958//958 -f 958//958 796//796 794//794 -f 958//958 794//794 959//959 -f 959//959 794//794 793//793 -f 959//959 793//793 960//960 -f 960//960 793//793 792//792 -f 960//960 792//792 961//961 -f 961//961 792//792 791//791 -f 961//961 791//791 962//962 -f 962//962 791//791 790//790 -f 962//962 790//790 963//963 -f 963//963 790//790 789//789 -f 963//963 789//789 964//964 -f 964//964 789//789 788//788 -f 964//964 788//788 965//965 -f 965//965 788//788 786//786 -f 965//965 786//786 966//966 -f 966//966 786//786 787//787 -f 966//966 787//787 967//967 -f 967//967 787//787 785//785 -f 967//967 785//785 968//968 -f 968//968 785//785 783//783 -f 968//968 783//783 969//969 -f 969//969 783//783 784//784 -f 969//969 784//784 970//970 -f 970//970 784//784 781//781 -f 970//970 781//781 971//971 -f 971//971 781//781 782//782 -f 971//971 782//782 972//972 -f 972//972 782//782 780//780 -f 972//972 780//780 973//973 -f 973//973 780//780 779//779 -f 973//973 779//779 974//974 -f 974//974 779//779 778//778 -f 974//974 778//778 975//975 -f 975//975 778//778 777//777 -f 975//975 777//777 976//976 -f 976//976 777//777 776//776 -f 976//976 776//776 977//977 -f 977//977 776//776 775//775 -f 977//977 775//775 978//978 -f 978//978 775//775 774//774 -f 978//978 774//774 979//979 -f 979//979 774//774 772//772 -f 979//979 772//772 980//980 -f 980//980 772//772 773//773 -f 980//980 773//773 981//981 -f 981//981 773//773 771//771 -f 981//981 771//771 982//982 -f 982//982 771//771 770//770 -f 982//982 770//770 930//930 -f 930//930 770//770 820//820 -f 983//983 984//984 985//985 -f 986//986 987//987 988//988 -f 988//988 987//987 989//989 -f 988//988 989//989 990//990 -f 990//990 989//989 991//991 -f 990//990 991//991 985//985 -f 985//985 991//991 992//992 -f 985//985 992//992 983//983 -f 986//986 988//988 993//993 -f 993//993 988//988 994//994 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 997//997 996//996 998//998 -f 997//997 998//998 999//999 -f 1000//1000 1001//1001 1002//1002 -f 1002//1002 1001//1001 1003//1003 -f 1002//1002 1003//1003 1004//1004 -f 1004//1004 1003//1003 1005//1005 -f 1004//1004 1005//1005 1006//1006 -f 1006//1006 1005//1005 1007//1007 -f 1006//1006 1007//1007 998//998 -f 998//998 1007//1007 1008//1008 -f 998//998 1008//1008 999//999 -f 1009//1009 1010//1010 1000//1000 -f 1000//1000 1010//1010 1011//1011 -f 1000//1000 1011//1011 1001//1001 -f 1012//1012 1013//1013 1014//1014 -f 1014//1014 1013//1013 1015//1015 -f 1014//1014 1015//1015 1016//1016 -f 1016//1016 1015//1015 1017//1017 -f 1016//1016 1017//1017 1009//1009 -f 1009//1009 1017//1017 1018//1018 -f 1009//1009 1018//1018 1010//1010 -f 1012//1012 1014//1014 1019//1019 -f 1019//1019 1014//1014 1020//1020 -f 1019//1019 1020//1020 1021//1021 -f 1021//1021 1020//1020 1022//1022 -f 1021//1021 1022//1022 1023//1023 -f 1023//1023 1022//1022 1024//1024 -f 1023//1023 1024//1024 1025//1025 -f 1026//1026 1027//1027 1028//1028 -f 1028//1028 1027//1027 1029//1029 -f 1028//1028 1029//1029 1030//1030 -f 1030//1030 1029//1029 1031//1031 -f 1030//1030 1031//1031 1032//1032 -f 1032//1032 1031//1031 1033//1033 -f 1032//1032 1033//1033 1024//1024 -f 1024//1024 1033//1033 1034//1034 -f 1024//1024 1034//1034 1025//1025 -f 1035//1035 1036//1036 1026//1026 -f 1026//1026 1036//1036 1037//1037 -f 1026//1026 1037//1037 1027//1027 -f 1038//1038 1039//1039 1040//1040 -f 1040//1040 1039//1039 1041//1041 -f 1040//1040 1041//1041 1042//1042 -f 1042//1042 1041//1041 1043//1043 -f 1042//1042 1043//1043 1035//1035 -f 1035//1035 1043//1043 1044//1044 -f 1035//1035 1044//1044 1036//1036 -f 1038//1038 1040//1040 1045//1045 -f 1045//1045 1040//1040 1046//1046 -f 1045//1045 1046//1046 1047//1047 -f 1047//1047 1046//1046 1048//1048 -f 1047//1047 1048//1048 1049//1049 -f 1049//1049 1048//1048 1050//1050 -f 1049//1049 1050//1050 1051//1051 -f 1052//1052 1053//1053 1054//1054 -f 1054//1054 1053//1053 1055//1055 -f 1054//1054 1055//1055 1056//1056 -f 1056//1056 1055//1055 1057//1057 -f 1056//1056 1057//1057 1058//1058 -f 1058//1058 1057//1057 1059//1059 -f 1058//1058 1059//1059 1050//1050 -f 1050//1050 1059//1059 1060//1060 -f 1050//1050 1060//1060 1051//1051 -f 1061//1061 1062//1062 1052//1052 -f 1052//1052 1062//1062 1063//1063 -f 1052//1052 1063//1063 1053//1053 -f 1064//1064 1065//1065 1066//1066 -f 1066//1066 1065//1065 1067//1067 -f 1066//1066 1067//1067 1068//1068 -f 1068//1068 1067//1067 1069//1069 -f 1068//1068 1069//1069 1061//1061 -f 1061//1061 1069//1069 1070//1070 -f 1061//1061 1070//1070 1062//1062 -f 1064//1064 1066//1066 1071//1071 -f 1071//1071 1066//1066 1072//1072 -f 1071//1071 1072//1072 1073//1073 -f 1073//1073 1072//1072 1074//1074 -f 1073//1073 1074//1074 1075//1075 -f 1075//1075 1074//1074 1076//1076 -f 1075//1075 1076//1076 1077//1077 -f 983//983 1078//1078 984//984 -f 984//984 1078//1078 1079//1079 -f 984//984 1079//1079 1080//1080 -f 1080//1080 1079//1079 1081//1081 -f 1080//1080 1081//1081 1082//1082 -f 1082//1082 1081//1081 1083//1083 -f 1082//1082 1083//1083 1084//1084 -f 1084//1084 1083//1083 1085//1085 -f 1084//1084 1085//1085 1076//1076 -f 1076//1076 1085//1085 1086//1086 -f 1076//1076 1086//1086 1077//1077 -f 1087//1087 752//752 1088//1088 -f 1088//1088 752//752 760//760 -f 1088//1088 760//760 1089//1089 -f 1089//1089 760//760 759//759 -f 1089//1089 759//759 1090//1090 -f 1090//1090 759//759 758//758 -f 1090//1090 758//758 1091//1091 -f 1091//1091 758//758 764//764 -f 1091//1091 764//764 1092//1092 -f 1092//1092 764//764 763//763 -f 1092//1092 763//763 1093//1093 -f 1093//1093 763//763 762//762 -f 1093//1093 762//762 1094//1094 -f 1094//1094 762//762 761//761 -f 1094//1094 761//761 1095//1095 -f 1095//1095 761//761 735//735 -f 1095//1095 735//735 1096//1096 -f 1096//1096 735//735 769//769 -f 1096//1096 769//769 1097//1097 -f 1097//1097 769//769 768//768 -f 1097//1097 768//768 1098//1098 -f 1098//1098 768//768 767//767 -f 1098//1098 767//767 1099//1099 -f 1099//1099 767//767 766//766 -f 1099//1099 766//766 1100//1100 -f 1100//1100 766//766 765//765 -f 1100//1100 765//765 1101//1101 -f 1101//1101 765//765 737//737 -f 1101//1101 737//737 1102//1102 -f 1102//1102 737//737 736//736 -f 1102//1102 736//736 1103//1103 -f 1103//1103 736//736 741//741 -f 1103//1103 741//741 1104//1104 -f 1104//1104 741//741 740//740 -f 1104//1104 740//740 1105//1105 -f 1105//1105 740//740 739//739 -f 1105//1105 739//739 1106//1106 -f 1106//1106 739//739 738//738 -f 1106//1106 738//738 1107//1107 -f 1107//1107 738//738 730//730 -f 1107//1107 730//730 1108//1108 -f 1108//1108 730//730 757//757 -f 1108//1108 757//757 1109//1109 -f 1109//1109 757//757 756//756 -f 1109//1109 756//756 1110//1110 -f 1110//1110 756//756 755//755 -f 1110//1110 755//755 1111//1111 -f 1111//1111 755//755 754//754 -f 1111//1111 754//754 1112//1112 -f 1112//1112 754//754 734//734 -f 1112//1112 734//734 1113//1113 -f 1113//1113 734//734 733//733 -f 1113//1113 733//733 1114//1114 -f 1114//1114 733//733 744//744 -f 1114//1114 744//744 1115//1115 -f 1115//1115 744//744 743//743 -f 1115//1115 743//743 1116//1116 -f 1116//1116 743//743 742//742 -f 1116//1116 742//742 1117//1117 -f 1117//1117 742//742 747//747 -f 1117//1117 747//747 1118//1118 -f 1118//1118 747//747 746//746 -f 1118//1118 746//746 1119//1119 -f 1119//1119 746//746 745//745 -f 1119//1119 745//745 1120//1120 -f 1120//1120 745//745 751//751 -f 1120//1120 751//751 1121//1121 -f 1121//1121 751//751 750//750 -f 1121//1121 750//750 1122//1122 -f 1122//1122 750//750 749//749 -f 1122//1122 749//749 1123//1123 -f 1123//1123 749//749 748//748 -f 1123//1123 748//748 1124//1124 -f 1124//1124 748//748 732//732 -f 1124//1124 732//732 1125//1125 -f 1125//1125 732//732 731//731 -f 1125//1125 731//731 1126//1126 -f 1126//1126 731//731 753//753 -f 1126//1126 753//753 1087//1087 -f 1087//1087 753//753 752//752 -f 1087//1087 1127//1127 1126//1126 -f 1126//1126 1127//1127 1128//1128 -f 1126//1126 1128//1128 1125//1125 -f 1125//1125 1128//1128 1129//1129 -f 1125//1125 1129//1129 1124//1124 -f 1124//1124 1129//1129 1130//1130 -f 1124//1124 1130//1130 1123//1123 -f 1123//1123 1130//1130 1131//1131 -f 1123//1123 1131//1131 1122//1122 -f 1122//1122 1131//1131 1132//1132 -f 1122//1122 1132//1132 1121//1121 -f 1121//1121 1132//1132 1133//1133 -f 1121//1121 1133//1133 1120//1120 -f 1120//1120 1133//1133 1134//1134 -f 1120//1120 1134//1134 1119//1119 -f 1119//1119 1134//1134 1135//1135 -f 1119//1119 1135//1135 1118//1118 -f 1118//1118 1135//1135 1136//1136 -f 1118//1118 1136//1136 1117//1117 -f 1117//1117 1136//1136 1137//1137 -f 1117//1117 1137//1137 1116//1116 -f 1116//1116 1137//1137 1138//1138 -f 1116//1116 1138//1138 1115//1115 -f 1115//1115 1138//1138 1139//1139 -f 1115//1115 1139//1139 1114//1114 -f 1114//1114 1139//1139 1140//1140 -f 1114//1114 1140//1140 1113//1113 -f 1113//1113 1140//1140 1141//1141 -f 1113//1113 1141//1141 1112//1112 -f 1112//1112 1141//1141 1142//1142 -f 1112//1112 1142//1142 1111//1111 -f 1111//1111 1142//1142 1143//1143 -f 1111//1111 1143//1143 1110//1110 -f 1110//1110 1143//1143 1144//1144 -f 1110//1110 1144//1144 1109//1109 -f 1109//1109 1144//1144 1145//1145 -f 1109//1109 1145//1145 1108//1108 -f 1108//1108 1145//1145 1146//1146 -f 1108//1108 1146//1146 1107//1107 -f 1107//1107 1146//1146 1147//1147 -f 1107//1107 1147//1147 1106//1106 -f 1106//1106 1147//1147 1148//1148 -f 1106//1106 1148//1148 1105//1105 -f 1105//1105 1148//1148 1149//1149 -f 1105//1105 1149//1149 1104//1104 -f 1104//1104 1149//1149 1150//1150 -f 1104//1104 1150//1150 1103//1103 -f 1103//1103 1150//1150 1151//1151 -f 1103//1103 1151//1151 1102//1102 -f 1102//1102 1151//1151 1152//1152 -f 1102//1102 1152//1152 1101//1101 -f 1101//1101 1152//1152 1153//1153 -f 1101//1101 1153//1153 1100//1100 -f 1100//1100 1153//1153 1154//1154 -f 1100//1100 1154//1154 1099//1099 -f 1099//1099 1154//1154 1155//1155 -f 1099//1099 1155//1155 1098//1098 -f 1098//1098 1155//1155 1156//1156 -f 1098//1098 1156//1156 1097//1097 -f 1097//1097 1156//1156 1157//1157 -f 1097//1097 1157//1157 1096//1096 -f 1096//1096 1157//1157 1158//1158 -f 1096//1096 1158//1158 1095//1095 -f 1095//1095 1158//1158 1159//1159 -f 1095//1095 1159//1159 1094//1094 -f 1094//1094 1159//1159 1160//1160 -f 1094//1094 1160//1160 1093//1093 -f 1093//1093 1160//1160 1161//1161 -f 1093//1093 1161//1161 1092//1092 -f 1092//1092 1161//1161 1162//1162 -f 1092//1092 1162//1162 1091//1091 -f 1091//1091 1162//1162 1163//1163 -f 1091//1091 1163//1163 1090//1090 -f 1090//1090 1163//1163 1164//1164 -f 1090//1090 1164//1164 1089//1089 -f 1089//1089 1164//1164 1165//1165 -f 1089//1089 1165//1165 1088//1088 -f 1088//1088 1165//1165 1166//1166 -f 1088//1088 1166//1166 1087//1087 -f 1087//1087 1166//1166 1127//1127 -f 1127//1127 1080//1080 1128//1128 -f 1128//1128 1080//1080 1082//1082 -f 1128//1128 1082//1082 1129//1129 -f 1129//1129 1082//1082 1084//1084 -f 1129//1129 1084//1084 1130//1130 -f 1130//1130 1084//1084 1076//1076 -f 1130//1130 1076//1076 1131//1131 -f 1131//1131 1076//1076 1074//1074 -f 1131//1131 1074//1074 1132//1132 -f 1132//1132 1074//1074 1072//1072 -f 1132//1132 1072//1072 1133//1133 -f 1133//1133 1072//1072 1066//1066 -f 1133//1133 1066//1066 1134//1134 -f 1134//1134 1066//1066 1068//1068 -f 1134//1134 1068//1068 1135//1135 -f 1135//1135 1068//1068 1061//1061 -f 1135//1135 1061//1061 1136//1136 -f 1136//1136 1061//1061 1052//1052 -f 1136//1136 1052//1052 1137//1137 -f 1137//1137 1052//1052 1054//1054 -f 1137//1137 1054//1054 1138//1138 -f 1138//1138 1054//1054 1056//1056 -f 1138//1138 1056//1056 1139//1139 -f 1139//1139 1056//1056 1058//1058 -f 1139//1139 1058//1058 1140//1140 -f 1140//1140 1058//1058 1050//1050 -f 1140//1140 1050//1050 1141//1141 -f 1141//1141 1050//1050 1048//1048 -f 1141//1141 1048//1048 1142//1142 -f 1142//1142 1048//1048 1046//1046 -f 1142//1142 1046//1046 1143//1143 -f 1143//1143 1046//1046 1040//1040 -f 1143//1143 1040//1040 1144//1144 -f 1144//1144 1040//1040 1042//1042 -f 1144//1144 1042//1042 1145//1145 -f 1145//1145 1042//1042 1035//1035 -f 1145//1145 1035//1035 1146//1146 -f 1146//1146 1035//1035 1026//1026 -f 1146//1146 1026//1026 1147//1147 -f 1147//1147 1026//1026 1028//1028 -f 1147//1147 1028//1028 1148//1148 -f 1148//1148 1028//1028 1030//1030 -f 1148//1148 1030//1030 1149//1149 -f 1149//1149 1030//1030 1032//1032 -f 1149//1149 1032//1032 1150//1150 -f 1150//1150 1032//1032 1024//1024 -f 1150//1150 1024//1024 1151//1151 -f 1151//1151 1024//1024 1022//1022 -f 1151//1151 1022//1022 1152//1152 -f 1152//1152 1022//1022 1020//1020 -f 1152//1152 1020//1020 1153//1153 -f 1153//1153 1020//1020 1014//1014 -f 1153//1153 1014//1014 1154//1154 -f 1154//1154 1014//1014 1016//1016 -f 1154//1154 1016//1016 1155//1155 -f 1155//1155 1016//1016 1009//1009 -f 1155//1155 1009//1009 1156//1156 -f 1156//1156 1009//1009 1000//1000 -f 1156//1156 1000//1000 1157//1157 -f 1157//1157 1000//1000 1002//1002 -f 1157//1157 1002//1002 1158//1158 -f 1158//1158 1002//1002 1004//1004 -f 1158//1158 1004//1004 1159//1159 -f 1159//1159 1004//1004 1006//1006 -f 1159//1159 1006//1006 1160//1160 -f 1160//1160 1006//1006 998//998 -f 1160//1160 998//998 1161//1161 -f 1161//1161 998//998 996//996 -f 1161//1161 996//996 1162//1162 -f 1162//1162 996//996 994//994 -f 1162//1162 994//994 1163//1163 -f 1163//1163 994//994 988//988 -f 1163//1163 988//988 1164//1164 -f 1164//1164 988//988 990//990 -f 1164//1164 990//990 1165//1165 -f 1165//1165 990//990 985//985 -f 1165//1165 985//985 1166//1166 -f 1166//1166 985//985 984//984 -f 1166//1166 984//984 1127//1127 -f 1127//1127 984//984 1080//1080 -f 1167//1167 836//836 1168//1168 -f 1168//1168 836//836 834//834 -f 1168//1168 834//834 1169//1169 -f 1169//1169 834//834 832//832 -f 1169//1169 832//832 1170//1170 -f 1170//1170 832//832 830//830 -f 1170//1170 830//830 1171//1171 -f 1171//1171 830//830 828//828 -f 1171//1171 828//828 1172//1172 -f 1172//1172 828//828 826//826 -f 1172//1172 826//826 1173//1173 -f 1173//1173 826//826 824//824 -f 1173//1173 824//824 1174//1174 -f 1174//1174 824//824 823//823 -f 1174//1174 823//823 1175//1175 -f 1175//1175 823//823 928//928 -f 1175//1175 928//928 1176//1176 -f 1176//1176 928//928 926//926 -f 1176//1176 926//926 1177//1177 -f 1177//1177 926//926 924//924 -f 1177//1177 924//924 1178//1178 -f 1178//1178 924//924 922//922 -f 1178//1178 922//922 1179//1179 -f 1179//1179 922//922 920//920 -f 1179//1179 920//920 1180//1180 -f 1181//1181 862//862 1182//1182 -f 1182//1182 862//862 860//860 -f 1182//1182 860//860 1183//1183 -f 1183//1183 860//860 858//858 -f 1183//1183 858//858 1184//1184 -f 1184//1184 858//858 856//856 -f 1184//1184 856//856 1185//1185 -f 1185//1185 856//856 854//854 -f 1185//1185 854//854 1186//1186 -f 1186//1186 854//854 852//852 -f 1186//1186 852//852 1187//1187 -f 1187//1187 852//852 850//850 -f 1187//1187 850//850 1188//1188 -f 1188//1188 850//850 848//848 -f 1188//1188 848//848 1189//1189 -f 1189//1189 848//848 846//846 -f 1189//1189 846//846 1190//1190 -f 1190//1190 846//846 844//844 -f 1190//1190 844//844 1191//1191 -f 1191//1191 844//844 842//842 -f 1191//1191 842//842 1192//1192 -f 1192//1192 842//842 840//840 -f 1192//1192 840//840 1167//1167 -f 1167//1167 840//840 838//838 -f 1167//1167 838//838 836//836 -f 1193//1193 890//890 1194//1194 -f 1194//1194 890//890 888//888 -f 1194//1194 888//888 1195//1195 -f 1195//1195 888//888 886//886 -f 1195//1195 886//886 1196//1196 -f 1196//1196 886//886 884//884 -f 1196//1196 884//884 1197//1197 -f 1197//1197 884//884 882//882 -f 1197//1197 882//882 1198//1198 -f 1198//1198 882//882 880//880 -f 1198//1198 880//880 1199//1199 -f 1199//1199 880//880 878//878 -f 1199//1199 878//878 1200//1200 -f 1200//1200 878//878 876//876 -f 1200//1200 876//876 1201//1201 -f 1201//1201 876//876 874//874 -f 1201//1201 874//874 1202//1202 -f 1202//1202 874//874 872//872 -f 1202//1202 872//872 1203//1203 -f 1203//1203 872//872 870//870 -f 1203//1203 870//870 1204//1204 -f 1204//1204 870//870 868//868 -f 1204//1204 868//868 1205//1205 -f 1205//1205 868//868 866//866 -f 1205//1205 866//866 1181//1181 -f 1181//1181 866//866 864//864 -f 1181//1181 864//864 862//862 -f 920//920 918//918 1180//1180 -f 1180//1180 918//918 916//916 -f 1180//1180 916//916 1206//1206 -f 1206//1206 916//916 914//914 -f 1206//1206 914//914 1207//1207 -f 1207//1207 914//914 912//912 -f 1207//1207 912//912 1208//1208 -f 1208//1208 912//912 910//910 -f 1208//1208 910//910 1209//1209 -f 1209//1209 910//910 908//908 -f 1209//1209 908//908 1210//1210 -f 1210//1210 908//908 906//906 -f 1210//1210 906//906 1211//1211 -f 1211//1211 906//906 904//904 -f 1211//1211 904//904 1212//1212 -f 1212//1212 904//904 902//902 -f 1212//1212 902//902 1213//1213 -f 1213//1213 902//902 900//900 -f 1213//1213 900//900 1214//1214 -f 1214//1214 900//900 898//898 -f 1214//1214 898//898 1215//1215 -f 1215//1215 898//898 896//896 -f 1215//1215 896//896 1216//1216 -f 1216//1216 896//896 894//894 -f 1216//1216 894//894 1193//1193 -f 1193//1193 894//894 892//892 -f 1193//1193 892//892 890//890 -f 1065//1065 1217//1217 1067//1067 -f 1067//1067 1217//1217 1218//1218 -f 1067//1067 1218//1218 1069//1069 -f 1069//1069 1218//1218 1070//1070 -f 1070//1070 1218//1218 1219//1219 -f 1070//1070 1219//1219 1062//1062 -f 1062//1062 1219//1219 1220//1220 -f 1062//1062 1220//1220 1063//1063 -f 1220//1220 1221//1221 1063//1063 -f 1063//1063 1221//1221 1222//1222 -f 1063//1063 1222//1222 1053//1053 -f 1053//1053 1222//1222 1223//1223 -f 1053//1053 1223//1223 1055//1055 -f 1055//1055 1223//1223 1224//1224 -f 1055//1055 1224//1224 1057//1057 -f 1057//1057 1224//1224 1225//1225 -f 1057//1057 1225//1225 1059//1059 -f 1045//1045 1047//1047 1226//1226 -f 1226//1226 1047//1047 1049//1049 -f 1226//1226 1049//1049 1227//1227 -f 1227//1227 1049//1049 1051//1051 -f 1227//1227 1051//1051 1228//1228 -f 1228//1228 1051//1051 1060//1060 -f 1228//1228 1060//1060 1229//1229 -f 1229//1229 1060//1060 1059//1059 -f 1229//1229 1059//1059 1230//1230 -f 1230//1230 1059//1059 1225//1225 -f 1044//1044 1043//1043 1231//1231 -f 1231//1231 1043//1043 1041//1041 -f 1231//1231 1041//1041 1232//1232 -f 1232//1232 1041//1041 1039//1039 -f 1232//1232 1039//1039 1233//1233 -f 1233//1233 1039//1039 1038//1038 -f 1233//1233 1038//1038 1234//1234 -f 1234//1234 1038//1038 1045//1045 -f 1234//1234 1045//1045 1235//1235 -f 1235//1235 1045//1045 1226//1226 -f 1231//1231 1236//1236 1044//1044 -f 1044//1044 1236//1236 1237//1237 -f 1044//1044 1237//1237 1036//1036 -f 1036//1036 1237//1237 1238//1238 -f 1036//1036 1238//1238 1037//1037 -f 1037//1037 1238//1238 1239//1239 -f 1037//1037 1239//1239 1027//1027 -f 1239//1239 1240//1240 1027//1027 -f 1027//1027 1240//1240 1241//1241 -f 1027//1027 1241//1241 1029//1029 -f 1029//1029 1241//1241 1242//1242 -f 1029//1029 1242//1242 1031//1031 -f 1031//1031 1242//1242 1243//1243 -f 1031//1031 1243//1243 1033//1033 -f 1033//1033 1243//1243 1244//1244 -f 1033//1033 1244//1244 1034//1034 -f 1034//1034 1244//1244 1245//1245 -f 1034//1034 1245//1245 1025//1025 -f 1025//1025 1245//1245 1246//1246 -f 1025//1025 1246//1246 1023//1023 -f 1023//1023 1246//1246 1247//1247 -f 1023//1023 1247//1247 1021//1021 -f 1021//1021 1247//1247 1248//1248 -f 1021//1021 1248//1248 1019//1019 -f 1019//1019 1248//1248 1249//1249 -f 1019//1019 1249//1249 1012//1012 -f 1012//1012 1249//1249 1250//1250 -f 1012//1012 1250//1250 1013//1013 -f 1013//1013 1250//1250 1251//1251 -f 1013//1013 1251//1251 1015//1015 -f 1015//1015 1251//1251 1252//1252 -f 1015//1015 1252//1252 1017//1017 -f 1017//1017 1252//1252 1253//1253 -f 1017//1017 1253//1253 1018//1018 -f 1018//1018 1253//1253 1254//1254 -f 1018//1018 1254//1254 1010//1010 -f 1010//1010 1254//1254 1255//1255 -f 1010//1010 1255//1255 1011//1011 -f 1011//1011 1255//1255 1256//1256 -f 1011//1011 1256//1256 1001//1001 -f 1256//1256 1257//1257 1001//1001 -f 1001//1001 1257//1257 1258//1258 -f 1001//1001 1258//1258 1003//1003 -f 1003//1003 1258//1258 1259//1259 -f 1003//1003 1259//1259 1005//1005 -f 1005//1005 1259//1259 1260//1260 -f 1005//1005 1260//1260 1007//1007 -f 1007//1007 1260//1260 1261//1261 -f 1007//1007 1261//1261 1008//1008 -f 1008//1008 1261//1261 1262//1262 -f 1008//1008 1262//1262 999//999 -f 999//999 1262//1262 1263//1263 -f 999//999 1263//1263 997//997 -f 997//997 1263//1263 1264//1264 -f 997//997 1264//1264 995//995 -f 995//995 1264//1264 1265//1265 -f 995//995 1265//1265 993//993 -f 993//993 1265//1265 1266//1266 -f 993//993 1266//1266 986//986 -f 986//986 1266//1266 1267//1267 -f 986//986 1267//1267 987//987 -f 987//987 1267//1267 1268//1268 -f 987//987 1268//1268 989//989 -f 989//989 1268//1268 1269//1269 -f 989//989 1269//1269 991//991 -f 991//991 1269//1269 1270//1270 -f 991//991 1270//1270 992//992 -f 992//992 1270//1270 1271//1271 -f 992//992 1271//1271 983//983 -f 983//983 1271//1271 1272//1272 -f 983//983 1272//1272 1078//1078 -f 1078//1078 1272//1272 1273//1273 -f 1078//1078 1273//1273 1079//1079 -f 1079//1079 1273//1273 1274//1274 -f 1079//1079 1274//1274 1081//1081 -f 1081//1081 1274//1274 1275//1275 -f 1081//1081 1275//1275 1083//1083 -f 1083//1083 1275//1275 1276//1276 -f 1083//1083 1276//1276 1085//1085 -f 1085//1085 1276//1276 1277//1277 -f 1085//1085 1277//1277 1086//1086 -f 1086//1086 1277//1277 1278//1278 -f 1086//1086 1278//1278 1077//1077 -f 1077//1077 1278//1278 1279//1279 -f 1077//1077 1279//1279 1075//1075 -f 1075//1075 1279//1279 1280//1280 -f 1075//1075 1280//1280 1073//1073 -f 1073//1073 1280//1280 1281//1281 -f 1073//1073 1281//1281 1071//1071 -f 1071//1071 1281//1281 1282//1282 -f 1071//1071 1282//1282 1064//1064 -f 1064//1064 1282//1282 1283//1283 -f 1064//1064 1283//1283 1065//1065 -f 1065//1065 1283//1283 1284//1284 -f 1065//1065 1284//1284 1217//1217 -f 1174//1174 1175//1175 1285//1285 -f 1285//1285 1175//1175 1176//1176 -f 1285//1285 1176//1176 1286//1286 -f 1286//1286 1176//1176 1177//1177 -f 1286//1286 1177//1177 1287//1287 -f 1287//1287 1177//1177 1178//1178 -f 1287//1287 1178//1178 1288//1288 -f 1288//1288 1178//1178 1179//1179 -f 1288//1288 1179//1179 1289//1289 -f 1289//1289 1179//1179 1180//1180 -f 1289//1289 1180//1180 1290//1290 -f 1290//1290 1180//1180 1206//1206 -f 1290//1290 1206//1206 1291//1291 -f 1291//1291 1206//1206 1207//1207 -f 1291//1291 1207//1207 1292//1292 -f 1292//1292 1207//1207 1208//1208 -f 1292//1292 1208//1208 1293//1293 -f 1293//1293 1208//1208 1209//1209 -f 1293//1293 1209//1209 1294//1294 -f 1294//1294 1209//1209 1210//1210 -f 1294//1294 1210//1210 1295//1295 -f 1295//1295 1210//1210 1211//1211 -f 1295//1295 1211//1211 1296//1296 -f 1296//1296 1211//1211 1212//1212 -f 1296//1296 1212//1212 1297//1297 -f 1297//1297 1212//1212 1213//1213 -f 1297//1297 1213//1213 1298//1298 -f 1298//1298 1213//1213 1214//1214 -f 1298//1298 1214//1214 1299//1299 -f 1299//1299 1214//1214 1215//1215 -f 1299//1299 1215//1215 1300//1300 -f 1300//1300 1215//1215 1216//1216 -f 1300//1300 1216//1216 1301//1301 -f 1301//1301 1216//1216 1193//1193 -f 1301//1301 1193//1193 1302//1302 -f 1302//1302 1193//1193 1194//1194 -f 1302//1302 1194//1194 1303//1303 -f 1303//1303 1194//1194 1195//1195 -f 1303//1303 1195//1195 1304//1304 -f 1304//1304 1195//1195 1196//1196 -f 1304//1304 1196//1196 1305//1305 -f 1305//1305 1196//1196 1197//1197 -f 1305//1305 1197//1197 1306//1306 -f 1306//1306 1197//1197 1198//1198 -f 1306//1306 1198//1198 1307//1307 -f 1307//1307 1198//1198 1199//1199 -f 1307//1307 1199//1199 1308//1308 -f 1308//1308 1199//1199 1200//1200 -f 1308//1308 1200//1200 1309//1309 -f 1309//1309 1200//1200 1201//1201 -f 1309//1309 1201//1201 1310//1310 -f 1310//1310 1201//1201 1202//1202 -f 1310//1310 1202//1202 1311//1311 -f 1311//1311 1202//1202 1203//1203 -f 1311//1311 1203//1203 1312//1312 -f 1312//1312 1203//1203 1204//1204 -f 1312//1312 1204//1204 1313//1313 -f 1313//1313 1204//1204 1205//1205 -f 1313//1313 1205//1205 1314//1314 -f 1314//1314 1205//1205 1181//1181 -f 1314//1314 1181//1181 1315//1315 -f 1315//1315 1181//1181 1182//1182 -f 1315//1315 1182//1182 1316//1316 -f 1316//1316 1182//1182 1183//1183 -f 1316//1316 1183//1183 1317//1317 -f 1317//1317 1183//1183 1184//1184 -f 1317//1317 1184//1184 1318//1318 -f 1318//1318 1184//1184 1185//1185 -f 1318//1318 1185//1185 1319//1319 -f 1319//1319 1185//1185 1186//1186 -f 1319//1319 1186//1186 1320//1320 -f 1320//1320 1186//1186 1187//1187 -f 1320//1320 1187//1187 1321//1321 -f 1321//1321 1187//1187 1188//1188 -f 1321//1321 1188//1188 1322//1322 -f 1322//1322 1188//1188 1189//1189 -f 1322//1322 1189//1189 1323//1323 -f 1323//1323 1189//1189 1190//1190 -f 1323//1323 1190//1190 1324//1324 -f 1324//1324 1190//1190 1191//1191 -f 1324//1324 1191//1191 1325//1325 -f 1325//1325 1191//1191 1192//1192 -f 1325//1325 1192//1192 1326//1326 -f 1326//1326 1192//1192 1167//1167 -f 1326//1326 1167//1167 1327//1327 -f 1327//1327 1167//1167 1168//1168 -f 1327//1327 1168//1168 1328//1328 -f 1328//1328 1168//1168 1169//1169 -f 1328//1328 1169//1169 1329//1329 -f 1329//1329 1169//1169 1170//1170 -f 1329//1329 1170//1170 1330//1330 -f 1330//1330 1170//1170 1171//1171 -f 1330//1330 1171//1171 1331//1331 -f 1331//1331 1171//1171 1172//1172 -f 1331//1331 1172//1172 1332//1332 -f 1332//1332 1172//1172 1173//1173 -f 1332//1332 1173//1173 1333//1333 -f 1333//1333 1173//1173 1174//1174 -f 1333//1333 1174//1174 1285//1285 -f 1334//1334 1335//1335 1336//1336 -f 1337//1337 1338//1338 1339//1339 -f 1339//1339 1338//1338 1340//1340 -f 1339//1339 1340//1340 1336//1336 -f 1336//1336 1340//1340 1341//1341 -f 1336//1336 1341//1341 1334//1334 -f 1342//1342 1343//1343 1337//1337 -f 1337//1337 1343//1343 1344//1344 -f 1337//1337 1344//1344 1338//1338 -f 1345//1345 1346//1346 1347//1347 -f 1347//1347 1346//1346 1348//1348 -f 1347//1347 1348//1348 1349//1349 -f 1349//1349 1348//1348 1350//1350 -f 1349//1349 1350//1350 1342//1342 -f 1342//1342 1350//1350 1351//1351 -f 1342//1342 1351//1351 1343//1343 -f 1345//1345 1347//1347 1352//1352 -f 1352//1352 1347//1347 1353//1353 -f 1352//1352 1353//1353 1354//1354 -f 1354//1354 1353//1353 1355//1355 -f 1354//1354 1355//1355 1356//1356 -f 1356//1356 1355//1355 1357//1357 -f 1356//1356 1357//1357 1358//1358 -f 1359//1359 1360//1360 1361//1361 -f 1361//1361 1360//1360 1362//1362 -f 1361//1361 1362//1362 1357//1357 -f 1357//1357 1362//1362 1363//1363 -f 1357//1357 1363//1363 1358//1358 -f 1364//1364 1365//1365 1366//1366 -f 1366//1366 1365//1365 1367//1367 -f 1366//1366 1367//1367 1359//1359 -f 1359//1359 1367//1367 1368//1368 -f 1359//1359 1368//1368 1360//1360 -f 1369//1369 1370//1370 1364//1364 -f 1364//1364 1370//1370 1371//1371 -f 1364//1364 1371//1371 1365//1365 -f 1372//1372 1373//1373 1374//1374 -f 1374//1374 1373//1373 1375//1375 -f 1374//1374 1375//1375 1369//1369 -f 1369//1369 1375//1375 1376//1376 -f 1369//1369 1376//1376 1370//1370 -f 1377//1377 1378//1378 1372//1372 -f 1372//1372 1378//1378 1379//1379 -f 1372//1372 1379//1379 1373//1373 -f 1380//1380 1381//1381 1382//1382 -f 1382//1382 1381//1381 1383//1383 -f 1382//1382 1383//1383 1384//1384 -f 1384//1384 1383//1383 1385//1385 -f 1384//1384 1385//1385 1377//1377 -f 1377//1377 1385//1385 1386//1386 -f 1377//1377 1386//1386 1378//1378 -f 1380//1380 1382//1382 1387//1387 -f 1387//1387 1382//1382 1388//1388 -f 1387//1387 1388//1388 1389//1389 -f 1389//1389 1388//1388 1390//1390 -f 1389//1389 1390//1390 1391//1391 -f 1391//1391 1390//1390 1392//1392 -f 1391//1391 1392//1392 1393//1393 -f 1394//1394 1395//1395 1396//1396 -f 1396//1396 1395//1395 1397//1397 -f 1396//1396 1397//1397 1392//1392 -f 1392//1392 1397//1397 1398//1398 -f 1392//1392 1398//1398 1393//1393 -f 1399//1399 1400//1400 1401//1401 -f 1401//1401 1400//1400 1402//1402 -f 1401//1401 1402//1402 1394//1394 -f 1394//1394 1402//1402 1403//1403 -f 1394//1394 1403//1403 1395//1395 -f 1404//1404 1405//1405 1399//1399 -f 1399//1399 1405//1405 1406//1406 -f 1399//1399 1406//1406 1400//1400 -f 1407//1407 1408//1408 1409//1409 -f 1409//1409 1408//1408 1410//1410 -f 1409//1409 1410//1410 1404//1404 -f 1404//1404 1410//1410 1411//1411 -f 1404//1404 1411//1411 1405//1405 -f 1412//1412 1413//1413 1407//1407 -f 1407//1407 1413//1413 1414//1414 -f 1407//1407 1414//1414 1408//1408 -f 1415//1415 1416//1416 1417//1417 -f 1417//1417 1416//1416 1418//1418 -f 1417//1417 1418//1418 1419//1419 -f 1419//1419 1418//1418 1420//1420 -f 1419//1419 1420//1420 1412//1412 -f 1412//1412 1420//1420 1421//1421 -f 1412//1412 1421//1421 1413//1413 -f 1415//1415 1417//1417 1422//1422 -f 1422//1422 1417//1417 1423//1423 -f 1422//1422 1423//1423 1424//1424 -f 1424//1424 1423//1423 1425//1425 -f 1424//1424 1425//1425 1426//1426 -f 1426//1426 1425//1425 1427//1427 -f 1426//1426 1427//1427 1428//1428 -f 1429//1429 1430//1430 1431//1431 -f 1431//1431 1430//1430 1432//1432 -f 1431//1431 1432//1432 1427//1427 -f 1427//1427 1432//1432 1433//1433 -f 1427//1427 1433//1433 1428//1428 -f 1434//1434 1435//1435 1436//1436 -f 1436//1436 1435//1435 1437//1437 -f 1436//1436 1437//1437 1429//1429 -f 1429//1429 1437//1437 1438//1438 -f 1429//1429 1438//1438 1430//1430 -f 1439//1439 1440//1440 1434//1434 -f 1434//1434 1440//1440 1441//1441 -f 1434//1434 1441//1441 1435//1435 -f 1442//1442 1443//1443 1444//1444 -f 1444//1444 1443//1443 1445//1445 -f 1444//1444 1445//1445 1446//1446 -f 1446//1446 1445//1445 1447//1447 -f 1446//1446 1447//1447 1439//1439 -f 1439//1439 1447//1447 1448//1448 -f 1439//1439 1448//1448 1440//1440 -f 1442//1442 1444//1444 1449//1449 -f 1449//1449 1444//1444 1450//1450 -f 1449//1449 1450//1450 1451//1451 -f 1451//1451 1450//1450 1452//1452 -f 1451//1451 1452//1452 1453//1453 -f 1453//1453 1452//1452 1454//1454 -f 1453//1453 1454//1454 1455//1455 -f 1334//1334 1456//1456 1335//1335 -f 1335//1335 1456//1456 1457//1457 -f 1335//1335 1457//1457 1458//1458 -f 1458//1458 1457//1457 1459//1459 -f 1458//1458 1459//1459 1460//1460 -f 1460//1460 1459//1459 1461//1461 -f 1460//1460 1461//1461 1462//1462 -f 1462//1462 1461//1461 1463//1463 -f 1462//1462 1463//1463 1454//1454 -f 1454//1454 1463//1463 1464//1464 -f 1454//1454 1464//1464 1455//1455 -f 1460//1460 1465//1465 1458//1458 -f 1458//1458 1465//1465 1466//1466 -f 1458//1458 1466//1466 1335//1335 -f 1335//1335 1466//1466 1467//1467 -f 1335//1335 1467//1467 1336//1336 -f 1336//1336 1467//1467 1468//1468 -f 1336//1336 1468//1468 1339//1339 -f 1339//1339 1468//1468 1469//1469 -f 1339//1339 1469//1469 1337//1337 -f 1337//1337 1469//1469 1470//1470 -f 1337//1337 1470//1470 1342//1342 -f 1342//1342 1470//1470 1471//1471 -f 1342//1342 1471//1471 1349//1349 -f 1349//1349 1471//1471 1472//1472 -f 1349//1349 1472//1472 1347//1347 -f 1347//1347 1472//1472 1473//1473 -f 1347//1347 1473//1473 1353//1353 -f 1353//1353 1473//1473 1474//1474 -f 1353//1353 1474//1474 1355//1355 -f 1355//1355 1474//1474 1475//1475 -f 1355//1355 1475//1475 1357//1357 -f 1357//1357 1475//1475 1476//1476 -f 1357//1357 1476//1476 1361//1361 -f 1361//1361 1476//1476 1477//1477 -f 1361//1361 1477//1477 1359//1359 -f 1359//1359 1477//1477 1478//1478 -f 1359//1359 1478//1478 1366//1366 -f 1366//1366 1478//1478 1479//1479 -f 1366//1366 1479//1479 1364//1364 -f 1364//1364 1479//1479 1480//1480 -f 1364//1364 1480//1480 1369//1369 -f 1369//1369 1480//1480 1481//1481 -f 1369//1369 1481//1481 1374//1374 -f 1374//1374 1481//1481 1482//1482 -f 1374//1374 1482//1482 1372//1372 -f 1372//1372 1482//1482 1483//1483 -f 1372//1372 1483//1483 1377//1377 -f 1377//1377 1483//1483 1484//1484 -f 1377//1377 1484//1484 1384//1384 -f 1384//1384 1484//1484 1485//1485 -f 1384//1384 1485//1485 1382//1382 -f 1382//1382 1485//1485 1486//1486 -f 1382//1382 1486//1486 1388//1388 -f 1388//1388 1486//1486 1487//1487 -f 1388//1388 1487//1487 1390//1390 -f 1390//1390 1487//1487 1488//1488 -f 1390//1390 1488//1488 1392//1392 -f 1392//1392 1488//1488 1489//1489 -f 1392//1392 1489//1489 1396//1396 -f 1396//1396 1489//1489 1490//1490 -f 1396//1396 1490//1490 1394//1394 -f 1394//1394 1490//1490 1491//1491 -f 1394//1394 1491//1491 1401//1401 -f 1401//1401 1491//1491 1492//1492 -f 1401//1401 1492//1492 1399//1399 -f 1399//1399 1492//1492 1493//1493 -f 1399//1399 1493//1493 1404//1404 -f 1404//1404 1493//1493 1494//1494 -f 1404//1404 1494//1494 1409//1409 -f 1409//1409 1494//1494 1495//1495 -f 1409//1409 1495//1495 1407//1407 -f 1407//1407 1495//1495 1496//1496 -f 1407//1407 1496//1496 1412//1412 -f 1412//1412 1496//1496 1497//1497 -f 1412//1412 1497//1497 1419//1419 -f 1419//1419 1497//1497 1498//1498 -f 1419//1419 1498//1498 1417//1417 -f 1417//1417 1498//1498 1499//1499 -f 1417//1417 1499//1499 1423//1423 -f 1423//1423 1499//1499 1500//1500 -f 1423//1423 1500//1500 1425//1425 -f 1425//1425 1500//1500 1501//1501 -f 1425//1425 1501//1501 1427//1427 -f 1427//1427 1501//1501 1502//1502 -f 1427//1427 1502//1502 1431//1431 -f 1431//1431 1502//1502 1503//1503 -f 1431//1431 1503//1503 1429//1429 -f 1429//1429 1503//1503 1504//1504 -f 1429//1429 1504//1504 1436//1436 -f 1436//1436 1504//1504 1505//1505 -f 1436//1436 1505//1505 1434//1434 -f 1434//1434 1505//1505 1506//1506 -f 1434//1434 1506//1506 1439//1439 -f 1439//1439 1506//1506 1507//1507 -f 1439//1439 1507//1507 1446//1446 -f 1446//1446 1507//1507 1508//1508 -f 1446//1446 1508//1508 1444//1444 -f 1444//1444 1508//1508 1509//1509 -f 1444//1444 1509//1509 1450//1450 -f 1450//1450 1509//1509 1510//1510 -f 1450//1450 1510//1510 1452//1452 -f 1452//1452 1510//1510 1511//1511 -f 1452//1452 1511//1511 1454//1454 -f 1454//1454 1511//1511 1512//1512 -f 1454//1454 1512//1512 1462//1462 -f 1462//1462 1512//1512 1513//1513 -f 1462//1462 1513//1513 1460//1460 -f 1460//1460 1513//1513 1465//1465 -f 1513//1513 1309//1309 1465//1465 -f 1465//1465 1309//1309 1310//1310 -f 1465//1465 1310//1310 1466//1466 -f 1466//1466 1310//1310 1311//1311 -f 1466//1466 1311//1311 1467//1467 -f 1467//1467 1311//1311 1312//1312 -f 1467//1467 1312//1312 1468//1468 -f 1468//1468 1312//1312 1313//1313 -f 1468//1468 1313//1313 1469//1469 -f 1469//1469 1313//1313 1314//1314 -f 1469//1469 1314//1314 1470//1470 -f 1470//1470 1314//1314 1315//1315 -f 1470//1470 1315//1315 1471//1471 -f 1471//1471 1315//1315 1316//1316 -f 1471//1471 1316//1316 1472//1472 -f 1472//1472 1316//1316 1317//1317 -f 1472//1472 1317//1317 1473//1473 -f 1473//1473 1317//1317 1318//1318 -f 1473//1473 1318//1318 1474//1474 -f 1474//1474 1318//1318 1319//1319 -f 1474//1474 1319//1319 1475//1475 -f 1475//1475 1319//1319 1320//1320 -f 1475//1475 1320//1320 1476//1476 -f 1476//1476 1320//1320 1321//1321 -f 1476//1476 1321//1321 1477//1477 -f 1477//1477 1321//1321 1322//1322 -f 1477//1477 1322//1322 1478//1478 -f 1478//1478 1322//1322 1323//1323 -f 1478//1478 1323//1323 1479//1479 -f 1479//1479 1323//1323 1324//1324 -f 1479//1479 1324//1324 1480//1480 -f 1480//1480 1324//1324 1325//1325 -f 1480//1480 1325//1325 1481//1481 -f 1481//1481 1325//1325 1326//1326 -f 1481//1481 1326//1326 1482//1482 -f 1482//1482 1326//1326 1327//1327 -f 1482//1482 1327//1327 1483//1483 -f 1483//1483 1327//1327 1328//1328 -f 1483//1483 1328//1328 1484//1484 -f 1484//1484 1328//1328 1329//1329 -f 1484//1484 1329//1329 1485//1485 -f 1485//1485 1329//1329 1330//1330 -f 1485//1485 1330//1330 1486//1486 -f 1486//1486 1330//1330 1331//1331 -f 1486//1486 1331//1331 1487//1487 -f 1487//1487 1331//1331 1332//1332 -f 1487//1487 1332//1332 1488//1488 -f 1488//1488 1332//1332 1333//1333 -f 1488//1488 1333//1333 1489//1489 -f 1489//1489 1333//1333 1285//1285 -f 1489//1489 1285//1285 1490//1490 -f 1490//1490 1285//1285 1286//1286 -f 1490//1490 1286//1286 1491//1491 -f 1491//1491 1286//1286 1287//1287 -f 1491//1491 1287//1287 1492//1492 -f 1492//1492 1287//1287 1288//1288 -f 1492//1492 1288//1288 1493//1493 -f 1493//1493 1288//1288 1289//1289 -f 1493//1493 1289//1289 1494//1494 -f 1494//1494 1289//1289 1290//1290 -f 1494//1494 1290//1290 1495//1495 -f 1495//1495 1290//1290 1291//1291 -f 1495//1495 1291//1291 1496//1496 -f 1496//1496 1291//1291 1292//1292 -f 1496//1496 1292//1292 1497//1497 -f 1497//1497 1292//1292 1293//1293 -f 1497//1497 1293//1293 1498//1498 -f 1498//1498 1293//1293 1294//1294 -f 1498//1498 1294//1294 1499//1499 -f 1499//1499 1294//1294 1295//1295 -f 1499//1499 1295//1295 1500//1500 -f 1500//1500 1295//1295 1296//1296 -f 1500//1500 1296//1296 1501//1501 -f 1501//1501 1296//1296 1297//1297 -f 1501//1501 1297//1297 1502//1502 -f 1502//1502 1297//1297 1298//1298 -f 1502//1502 1298//1298 1503//1503 -f 1503//1503 1298//1298 1299//1299 -f 1503//1503 1299//1299 1504//1504 -f 1504//1504 1299//1299 1300//1300 -f 1504//1504 1300//1300 1505//1505 -f 1505//1505 1300//1300 1301//1301 -f 1505//1505 1301//1301 1506//1506 -f 1506//1506 1301//1301 1302//1302 -f 1506//1506 1302//1302 1507//1507 -f 1507//1507 1302//1302 1303//1303 -f 1507//1507 1303//1303 1508//1508 -f 1508//1508 1303//1303 1304//1304 -f 1508//1508 1304//1304 1509//1509 -f 1509//1509 1304//1304 1305//1305 -f 1509//1509 1305//1305 1510//1510 -f 1510//1510 1305//1305 1306//1306 -f 1510//1510 1306//1306 1511//1511 -f 1511//1511 1306//1306 1307//1307 -f 1511//1511 1307//1307 1512//1512 -f 1512//1512 1307//1307 1308//1308 -f 1512//1512 1308//1308 1513//1513 -f 1513//1513 1308//1308 1309//1309 -f 1514//1514 1515//1515 1516//1516 -f 1516//1516 1515//1515 1517//1517 -f 1516//1516 1517//1517 1518//1518 -f 1518//1518 1517//1517 1519//1519 -f 1518//1518 1519//1519 1520//1520 -f 1520//1520 1519//1519 1521//1521 -f 1520//1520 1521//1521 1522//1522 -f 1522//1522 1521//1521 1523//1523 -f 1522//1522 1523//1523 1524//1524 -f 1524//1524 1523//1523 1525//1525 -f 1524//1524 1525//1525 1526//1526 -f 1526//1526 1525//1525 1527//1527 -f 1526//1526 1527//1527 1528//1528 -f 1528//1528 1527//1527 1529//1529 -f 1528//1528 1529//1529 1530//1530 -f 1530//1530 1529//1529 1531//1531 -f 1530//1530 1531//1531 1532//1532 -f 1532//1532 1531//1531 1533//1533 -f 1532//1532 1533//1533 1534//1534 -f 1534//1534 1533//1533 1535//1535 -f 1534//1534 1535//1535 1536//1536 -f 1536//1536 1535//1535 1537//1537 -f 1536//1536 1537//1537 1538//1538 -f 1538//1538 1537//1537 1539//1539 -f 1538//1538 1539//1539 1540//1540 -f 1540//1540 1539//1539 1541//1541 -f 1540//1540 1541//1541 1542//1542 -f 1542//1542 1541//1541 1543//1543 -f 1542//1542 1543//1543 1544//1544 -f 1544//1544 1543//1543 1545//1545 -f 1544//1544 1545//1545 1546//1546 -f 1546//1546 1545//1545 1547//1547 -f 1546//1546 1547//1547 1548//1548 -f 1548//1548 1547//1547 1549//1549 -f 1548//1548 1549//1549 1550//1550 -f 1550//1550 1549//1549 1551//1551 -f 1550//1550 1551//1551 1552//1552 -f 1552//1552 1551//1551 1553//1553 -f 1552//1552 1553//1553 1554//1554 -f 1554//1554 1553//1553 1555//1555 -f 1554//1554 1555//1555 1556//1556 -f 1556//1556 1555//1555 1557//1557 -f 1556//1556 1557//1557 1558//1558 -f 1558//1558 1557//1557 1559//1559 -f 1558//1558 1559//1559 1560//1560 -f 1560//1560 1559//1559 1561//1561 -f 1560//1560 1561//1561 1562//1562 -f 1562//1562 1561//1561 1563//1563 -f 1562//1562 1563//1563 1564//1564 -f 1564//1564 1563//1563 1565//1565 -f 1564//1564 1565//1565 1566//1566 -f 1566//1566 1565//1565 1567//1567 -f 1566//1566 1567//1567 1568//1568 -f 1568//1568 1567//1567 1569//1569 -f 1568//1568 1569//1569 1570//1570 -f 1570//1570 1569//1569 1571//1571 -f 1570//1570 1571//1571 1572//1572 -f 1572//1572 1571//1571 1573//1573 -f 1572//1572 1573//1573 1574//1574 -f 1574//1574 1573//1573 1575//1575 -f 1574//1574 1575//1575 1576//1576 -f 1576//1576 1575//1575 1577//1577 -f 1576//1576 1577//1577 1578//1578 -f 1578//1578 1577//1577 1579//1579 -f 1578//1578 1579//1579 1580//1580 -f 1580//1580 1579//1579 1581//1581 -f 1580//1580 1581//1581 1582//1582 -f 1582//1582 1581//1581 1583//1583 -f 1582//1582 1583//1583 1584//1584 -f 1584//1584 1583//1583 1585//1585 -f 1584//1584 1585//1585 1586//1586 -f 1586//1586 1585//1585 1587//1587 -f 1586//1586 1587//1587 1588//1588 -f 1588//1588 1587//1587 1589//1589 -f 1588//1588 1589//1589 1590//1590 -f 1590//1590 1589//1589 1591//1591 -f 1590//1590 1591//1591 1592//1592 -f 1592//1592 1591//1591 1593//1593 -f 1592//1592 1593//1593 1594//1594 -f 1594//1594 1593//1593 1595//1595 -f 1594//1594 1595//1595 1596//1596 -f 1596//1596 1595//1595 1514//1514 -f 1596//1596 1514//1514 1516//1516 -f 1276//1276 1597//1597 1598//1598 -f 1599//1599 1279//1279 1600//1600 -f 1600//1600 1279//1279 1278//1278 -f 1600//1600 1278//1278 1598//1598 -f 1598//1598 1278//1278 1277//1277 -f 1598//1598 1277//1277 1276//1276 -f 1601//1601 1281//1281 1599//1599 -f 1599//1599 1281//1281 1280//1280 -f 1599//1599 1280//1280 1279//1279 -f 1602//1602 1284//1284 1603//1603 -f 1603//1603 1284//1284 1283//1283 -f 1603//1603 1283//1283 1601//1601 -f 1601//1601 1283//1283 1282//1282 -f 1601//1601 1282//1282 1281//1281 -f 1604//1604 1218//1218 1602//1602 -f 1602//1602 1218//1218 1217//1217 -f 1602//1602 1217//1217 1284//1284 -f 1223//1223 1222//1222 1605//1605 -f 1605//1605 1222//1222 1221//1221 -f 1605//1605 1221//1221 1606//1606 -f 1606//1606 1221//1221 1220//1220 -f 1606//1606 1220//1220 1604//1604 -f 1604//1604 1220//1220 1219//1219 -f 1604//1604 1219//1219 1218//1218 -f 1223//1223 1605//1605 1224//1224 -f 1224//1224 1605//1605 1607//1607 -f 1224//1224 1607//1607 1225//1225 -f 1225//1225 1607//1607 1608//1608 -f 1225//1225 1608//1608 1230//1230 -f 1230//1230 1608//1608 1609//1609 -f 1230//1230 1609//1609 1229//1229 -f 1233//1233 1234//1234 1610//1610 -f 1610//1610 1234//1234 1235//1235 -f 1610//1610 1235//1235 1611//1611 -f 1611//1611 1235//1235 1226//1226 -f 1611//1611 1226//1226 1612//1612 -f 1612//1612 1226//1226 1227//1227 -f 1612//1612 1227//1227 1609//1609 -f 1609//1609 1227//1227 1228//1228 -f 1609//1609 1228//1228 1229//1229 -f 1233//1233 1610//1610 1232//1232 -f 1232//1232 1610//1610 1613//1613 -f 1232//1232 1613//1613 1231//1231 -f 1231//1231 1613//1613 1614//1614 -f 1231//1231 1614//1614 1236//1236 -f 1236//1236 1614//1614 1615//1615 -f 1236//1236 1615//1615 1237//1237 -f 1616//1616 1240//1240 1617//1617 -f 1617//1617 1240//1240 1239//1239 -f 1617//1617 1239//1239 1615//1615 -f 1615//1615 1239//1239 1238//1238 -f 1615//1615 1238//1238 1237//1237 -f 1618//1618 1243//1243 1619//1619 -f 1619//1619 1243//1243 1242//1242 -f 1619//1619 1242//1242 1616//1616 -f 1616//1616 1242//1242 1241//1241 -f 1616//1616 1241//1241 1240//1240 -f 1620//1620 1245//1245 1618//1618 -f 1618//1618 1245//1245 1244//1244 -f 1618//1618 1244//1244 1243//1243 -f 1621//1621 1248//1248 1622//1622 -f 1622//1622 1248//1248 1247//1247 -f 1622//1622 1247//1247 1620//1620 -f 1620//1620 1247//1247 1246//1246 -f 1620//1620 1246//1246 1245//1245 -f 1623//1623 1250//1250 1621//1621 -f 1621//1621 1250//1250 1249//1249 -f 1621//1621 1249//1249 1248//1248 -f 1255//1255 1254//1254 1624//1624 -f 1624//1624 1254//1254 1253//1253 -f 1624//1624 1253//1253 1625//1625 -f 1625//1625 1253//1253 1252//1252 -f 1625//1625 1252//1252 1623//1623 -f 1623//1623 1252//1252 1251//1251 -f 1623//1623 1251//1251 1250//1250 -f 1255//1255 1624//1624 1256//1256 -f 1256//1256 1624//1624 1626//1626 -f 1256//1256 1626//1626 1257//1257 -f 1257//1257 1626//1626 1627//1627 -f 1257//1257 1627//1627 1258//1258 -f 1258//1258 1627//1627 1628//1628 -f 1258//1258 1628//1628 1259//1259 -f 1265//1265 1264//1264 1629//1629 -f 1629//1629 1264//1264 1263//1263 -f 1629//1629 1263//1263 1630//1630 -f 1630//1630 1263//1263 1262//1262 -f 1630//1630 1262//1262 1631//1631 -f 1631//1631 1262//1262 1261//1261 -f 1631//1631 1261//1261 1628//1628 -f 1628//1628 1261//1261 1260//1260 -f 1628//1628 1260//1260 1259//1259 -f 1265//1265 1629//1629 1266//1266 -f 1266//1266 1629//1629 1632//1632 -f 1266//1266 1632//1632 1267//1267 -f 1267//1267 1632//1632 1633//1633 -f 1267//1267 1633//1633 1268//1268 -f 1268//1268 1633//1633 1634//1634 -f 1268//1268 1634//1634 1269//1269 -f 1276//1276 1275//1275 1597//1597 -f 1597//1597 1275//1275 1274//1274 -f 1597//1597 1274//1274 1635//1635 -f 1635//1635 1274//1274 1273//1273 -f 1635//1635 1273//1273 1636//1636 -f 1636//1636 1273//1273 1272//1272 -f 1636//1636 1272//1272 1637//1637 -f 1637//1637 1272//1272 1271//1271 -f 1637//1637 1271//1271 1634//1634 -f 1634//1634 1271//1271 1270//1270 -f 1634//1634 1270//1270 1269//1269 -f 1636//1636 1638//1638 1635//1635 -f 1635//1635 1638//1638 1639//1639 -f 1635//1635 1639//1639 1597//1597 -f 1597//1597 1639//1639 1640//1640 -f 1597//1597 1640//1640 1598//1598 -f 1598//1598 1640//1640 1641//1641 -f 1598//1598 1641//1641 1600//1600 -f 1600//1600 1641//1641 1642//1642 -f 1600//1600 1642//1642 1599//1599 -f 1599//1599 1642//1642 1643//1643 -f 1599//1599 1643//1643 1601//1601 -f 1601//1601 1643//1643 1644//1644 -f 1601//1601 1644//1644 1603//1603 -f 1603//1603 1644//1644 1645//1645 -f 1603//1603 1645//1645 1602//1602 -f 1602//1602 1645//1645 1646//1646 -f 1602//1602 1646//1646 1604//1604 -f 1604//1604 1646//1646 1647//1647 -f 1604//1604 1647//1647 1606//1606 -f 1606//1606 1647//1647 1648//1648 -f 1606//1606 1648//1648 1605//1605 -f 1605//1605 1648//1648 1649//1649 -f 1605//1605 1649//1649 1607//1607 -f 1607//1607 1649//1649 1650//1650 -f 1607//1607 1650//1650 1608//1608 -f 1608//1608 1650//1650 1651//1651 -f 1608//1608 1651//1651 1609//1609 -f 1609//1609 1651//1651 1652//1652 -f 1609//1609 1652//1652 1612//1612 -f 1612//1612 1652//1652 1653//1653 -f 1612//1612 1653//1653 1611//1611 -f 1611//1611 1653//1653 1654//1654 -f 1611//1611 1654//1654 1610//1610 -f 1610//1610 1654//1654 1655//1655 -f 1610//1610 1655//1655 1613//1613 -f 1613//1613 1655//1655 1656//1656 -f 1613//1613 1656//1656 1614//1614 -f 1614//1614 1656//1656 1657//1657 -f 1614//1614 1657//1657 1615//1615 -f 1615//1615 1657//1657 1658//1658 -f 1615//1615 1658//1658 1617//1617 -f 1617//1617 1658//1658 1659//1659 -f 1617//1617 1659//1659 1616//1616 -f 1616//1616 1659//1659 1660//1660 -f 1616//1616 1660//1660 1619//1619 -f 1619//1619 1660//1660 1661//1661 -f 1619//1619 1661//1661 1618//1618 -f 1618//1618 1661//1661 1662//1662 -f 1618//1618 1662//1662 1620//1620 -f 1620//1620 1662//1662 1663//1663 -f 1620//1620 1663//1663 1622//1622 -f 1622//1622 1663//1663 1664//1664 -f 1622//1622 1664//1664 1621//1621 -f 1621//1621 1664//1664 1665//1665 -f 1621//1621 1665//1665 1623//1623 -f 1623//1623 1665//1665 1666//1666 -f 1623//1623 1666//1666 1625//1625 -f 1625//1625 1666//1666 1667//1667 -f 1625//1625 1667//1667 1624//1624 -f 1624//1624 1667//1667 1668//1668 -f 1624//1624 1668//1668 1626//1626 -f 1626//1626 1668//1668 1669//1669 -f 1626//1626 1669//1669 1627//1627 -f 1627//1627 1669//1669 1670//1670 -f 1627//1627 1670//1670 1628//1628 -f 1628//1628 1670//1670 1671//1671 -f 1628//1628 1671//1671 1631//1631 -f 1631//1631 1671//1671 1672//1672 -f 1631//1631 1672//1672 1630//1630 -f 1630//1630 1672//1672 1673//1673 -f 1630//1630 1673//1673 1629//1629 -f 1629//1629 1673//1673 1674//1674 -f 1629//1629 1674//1674 1632//1632 -f 1632//1632 1674//1674 1675//1675 -f 1632//1632 1675//1675 1633//1633 -f 1633//1633 1675//1675 1676//1676 -f 1633//1633 1676//1676 1634//1634 -f 1634//1634 1676//1676 1677//1677 -f 1634//1634 1677//1677 1637//1637 -f 1637//1637 1677//1677 1678//1678 -f 1637//1637 1678//1678 1636//1636 -f 1636//1636 1678//1678 1638//1638 -f 1678//1678 1556//1556 1638//1638 -f 1638//1638 1556//1556 1558//1558 -f 1638//1638 1558//1558 1639//1639 -f 1639//1639 1558//1558 1560//1560 -f 1639//1639 1560//1560 1640//1640 -f 1640//1640 1560//1560 1562//1562 -f 1640//1640 1562//1562 1641//1641 -f 1641//1641 1562//1562 1564//1564 -f 1641//1641 1564//1564 1642//1642 -f 1642//1642 1564//1564 1566//1566 -f 1642//1642 1566//1566 1643//1643 -f 1643//1643 1566//1566 1568//1568 -f 1643//1643 1568//1568 1644//1644 -f 1644//1644 1568//1568 1570//1570 -f 1644//1644 1570//1570 1645//1645 -f 1645//1645 1570//1570 1572//1572 -f 1645//1645 1572//1572 1646//1646 -f 1646//1646 1572//1572 1574//1574 -f 1646//1646 1574//1574 1647//1647 -f 1647//1647 1574//1574 1576//1576 -f 1647//1647 1576//1576 1648//1648 -f 1648//1648 1576//1576 1578//1578 -f 1648//1648 1578//1578 1649//1649 -f 1649//1649 1578//1578 1580//1580 -f 1649//1649 1580//1580 1650//1650 -f 1650//1650 1580//1580 1582//1582 -f 1650//1650 1582//1582 1651//1651 -f 1651//1651 1582//1582 1584//1584 -f 1651//1651 1584//1584 1652//1652 -f 1652//1652 1584//1584 1586//1586 -f 1652//1652 1586//1586 1653//1653 -f 1653//1653 1586//1586 1588//1588 -f 1653//1653 1588//1588 1654//1654 -f 1654//1654 1588//1588 1590//1590 -f 1654//1654 1590//1590 1655//1655 -f 1655//1655 1590//1590 1592//1592 -f 1655//1655 1592//1592 1656//1656 -f 1656//1656 1592//1592 1594//1594 -f 1656//1656 1594//1594 1657//1657 -f 1657//1657 1594//1594 1596//1596 -f 1657//1657 1596//1596 1658//1658 -f 1658//1658 1596//1596 1516//1516 -f 1658//1658 1516//1516 1659//1659 -f 1659//1659 1516//1516 1518//1518 -f 1659//1659 1518//1518 1660//1660 -f 1660//1660 1518//1518 1520//1520 -f 1660//1660 1520//1520 1661//1661 -f 1661//1661 1520//1520 1522//1522 -f 1661//1661 1522//1522 1662//1662 -f 1662//1662 1522//1522 1524//1524 -f 1662//1662 1524//1524 1663//1663 -f 1663//1663 1524//1524 1526//1526 -f 1663//1663 1526//1526 1664//1664 -f 1664//1664 1526//1526 1528//1528 -f 1664//1664 1528//1528 1665//1665 -f 1665//1665 1528//1528 1530//1530 -f 1665//1665 1530//1530 1666//1666 -f 1666//1666 1530//1530 1532//1532 -f 1666//1666 1532//1532 1667//1667 -f 1667//1667 1532//1532 1534//1534 -f 1667//1667 1534//1534 1668//1668 -f 1668//1668 1534//1534 1536//1536 -f 1668//1668 1536//1536 1669//1669 -f 1669//1669 1536//1536 1538//1538 -f 1669//1669 1538//1538 1670//1670 -f 1670//1670 1538//1538 1540//1540 -f 1670//1670 1540//1540 1671//1671 -f 1671//1671 1540//1540 1542//1542 -f 1671//1671 1542//1542 1672//1672 -f 1672//1672 1542//1542 1544//1544 -f 1672//1672 1544//1544 1673//1673 -f 1673//1673 1544//1544 1546//1546 -f 1673//1673 1546//1546 1674//1674 -f 1674//1674 1546//1546 1548//1548 -f 1674//1674 1548//1548 1675//1675 -f 1675//1675 1548//1548 1550//1550 -f 1675//1675 1550//1550 1676//1676 -f 1676//1676 1550//1550 1552//1552 -f 1676//1676 1552//1552 1677//1677 -f 1677//1677 1552//1552 1554//1554 -f 1677//1677 1554//1554 1678//1678 -f 1678//1678 1554//1554 1556//1556 -f 1679//1679 1358//1358 1680//1680 -f 1680//1680 1358//1358 1363//1363 -f 1680//1680 1363//1363 1681//1681 -f 1681//1681 1363//1363 1362//1362 -f 1681//1681 1362//1362 1682//1682 -f 1682//1682 1362//1362 1683//1683 -f 1683//1683 1362//1362 1360//1360 -f 1683//1683 1360//1360 1684//1684 -f 1684//1684 1360//1360 1368//1368 -f 1684//1684 1368//1368 1685//1685 -f 1368//1368 1367//1367 1685//1685 -f 1685//1685 1367//1367 1365//1365 -f 1685//1685 1365//1365 1686//1686 -f 1686//1686 1365//1365 1371//1371 -f 1686//1686 1371//1371 1687//1687 -f 1687//1687 1371//1371 1688//1688 -f 1688//1688 1371//1371 1370//1370 -f 1688//1688 1370//1370 1689//1689 -f 1689//1689 1370//1370 1376//1376 -f 1689//1689 1376//1376 1690//1690 -f 1376//1376 1375//1375 1690//1690 -f 1690//1690 1375//1375 1373//1373 -f 1690//1690 1373//1373 1691//1691 -f 1691//1691 1373//1373 1379//1379 -f 1691//1691 1379//1379 1692//1692 -f 1692//1692 1379//1379 1378//1378 -f 1692//1692 1378//1378 1693//1693 -f 1693//1693 1378//1378 1386//1386 -f 1693//1693 1386//1386 1694//1694 -f 1694//1694 1386//1386 1695//1695 -f 1386//1386 1385//1385 1695//1695 -f 1695//1695 1385//1385 1383//1383 -f 1695//1695 1383//1383 1696//1696 -f 1696//1696 1383//1383 1381//1381 -f 1696//1696 1381//1381 1697//1697 -f 1697//1697 1381//1381 1380//1380 -f 1697//1697 1380//1380 1698//1698 -f 1698//1698 1380//1380 1387//1387 -f 1698//1698 1387//1387 1699//1699 -f 1699//1699 1387//1387 1700//1700 -f 1387//1387 1389//1389 1700//1700 -f 1700//1700 1389//1389 1391//1391 -f 1700//1700 1391//1391 1701//1701 -f 1701//1701 1391//1391 1393//1393 -f 1701//1701 1393//1393 1702//1702 -f 1702//1702 1393//1393 1398//1398 -f 1702//1702 1398//1398 1703//1703 -f 1703//1703 1398//1398 1397//1397 -f 1703//1703 1397//1397 1704//1704 -f 1397//1397 1395//1395 1704//1704 -f 1704//1704 1395//1395 1403//1403 -f 1704//1704 1403//1403 1705//1705 -f 1705//1705 1403//1403 1402//1402 -f 1705//1705 1402//1402 1706//1706 -f 1706//1706 1402//1402 1400//1400 -f 1706//1706 1400//1400 1707//1707 -f 1707//1707 1400//1400 1406//1406 -f 1707//1707 1406//1406 1708//1708 -f 1708//1708 1406//1406 1405//1405 -f 1708//1708 1405//1405 1709//1709 -f 1709//1709 1405//1405 1411//1411 -f 1709//1709 1411//1411 1710//1710 -f 1710//1710 1411//1411 1410//1410 -f 1710//1710 1410//1410 1711//1711 -f 1711//1711 1410//1410 1408//1408 -f 1711//1711 1408//1408 1712//1712 -f 1712//1712 1408//1408 1414//1414 -f 1712//1712 1414//1414 1713//1713 -f 1713//1713 1414//1414 1413//1413 -f 1713//1713 1413//1413 1714//1714 -f 1714//1714 1413//1413 1421//1421 -f 1714//1714 1421//1421 1715//1715 -f 1715//1715 1421//1421 1420//1420 -f 1715//1715 1420//1420 1716//1716 -f 1716//1716 1420//1420 1418//1418 -f 1716//1716 1418//1418 1717//1717 -f 1717//1717 1418//1418 1416//1416 -f 1717//1717 1416//1416 1718//1718 -f 1718//1718 1416//1416 1415//1415 -f 1718//1718 1415//1415 1719//1719 -f 1719//1719 1415//1415 1422//1422 -f 1719//1719 1422//1422 1720//1720 -f 1720//1720 1422//1422 1424//1424 -f 1720//1720 1424//1424 1721//1721 -f 1721//1721 1424//1424 1426//1426 -f 1721//1721 1426//1426 1722//1722 -f 1722//1722 1426//1426 1428//1428 -f 1722//1722 1428//1428 1723//1723 -f 1723//1723 1428//1428 1433//1433 -f 1723//1723 1433//1433 1724//1724 -f 1724//1724 1433//1433 1432//1432 -f 1724//1724 1432//1432 1725//1725 -f 1725//1725 1432//1432 1430//1430 -f 1725//1725 1430//1430 1726//1726 -f 1726//1726 1430//1430 1438//1438 -f 1726//1726 1438//1438 1727//1727 -f 1727//1727 1438//1438 1437//1437 -f 1727//1727 1437//1437 1728//1728 -f 1728//1728 1437//1437 1435//1435 -f 1728//1728 1435//1435 1729//1729 -f 1729//1729 1435//1435 1441//1441 -f 1729//1729 1441//1441 1730//1730 -f 1730//1730 1441//1441 1440//1440 -f 1730//1730 1440//1440 1731//1731 -f 1731//1731 1440//1440 1448//1448 -f 1731//1731 1448//1448 1732//1732 -f 1732//1732 1448//1448 1447//1447 -f 1732//1732 1447//1447 1733//1733 -f 1733//1733 1447//1447 1445//1445 -f 1733//1733 1445//1445 1734//1734 -f 1734//1734 1445//1445 1443//1443 -f 1734//1734 1443//1443 1735//1735 -f 1735//1735 1443//1443 1442//1442 -f 1735//1735 1442//1442 1736//1736 -f 1736//1736 1442//1442 1449//1449 -f 1736//1736 1449//1449 1737//1737 -f 1737//1737 1449//1449 1451//1451 -f 1737//1737 1451//1451 1738//1738 -f 1738//1738 1451//1451 1453//1453 -f 1738//1738 1453//1453 1739//1739 -f 1739//1739 1453//1453 1455//1455 -f 1739//1739 1455//1455 1740//1740 -f 1740//1740 1455//1455 1464//1464 -f 1740//1740 1464//1464 1741//1741 -f 1741//1741 1464//1464 1463//1463 -f 1741//1741 1463//1463 1742//1742 -f 1742//1742 1463//1463 1461//1461 -f 1742//1742 1461//1461 1743//1743 -f 1743//1743 1461//1461 1459//1459 -f 1743//1743 1459//1459 1744//1744 -f 1744//1744 1459//1459 1457//1457 -f 1744//1744 1457//1457 1745//1745 -f 1745//1745 1457//1457 1456//1456 -f 1745//1745 1456//1456 1746//1746 -f 1746//1746 1456//1456 1334//1334 -f 1746//1746 1334//1334 1747//1747 -f 1747//1747 1334//1334 1341//1341 -f 1747//1747 1341//1341 1748//1748 -f 1748//1748 1341//1341 1340//1340 -f 1748//1748 1340//1340 1749//1749 -f 1749//1749 1340//1340 1338//1338 -f 1749//1749 1338//1338 1750//1750 -f 1750//1750 1338//1338 1344//1344 -f 1750//1750 1344//1344 1751//1751 -f 1751//1751 1344//1344 1343//1343 -f 1751//1751 1343//1343 1752//1752 -f 1752//1752 1343//1343 1351//1351 -f 1752//1752 1351//1351 1753//1753 -f 1753//1753 1351//1351 1350//1350 -f 1753//1753 1350//1350 1754//1754 -f 1754//1754 1350//1350 1348//1348 -f 1754//1754 1348//1348 1755//1755 -f 1755//1755 1348//1348 1346//1346 -f 1755//1755 1346//1346 1756//1756 -f 1756//1756 1346//1346 1345//1345 -f 1756//1756 1345//1345 1757//1757 -f 1757//1757 1345//1345 1352//1352 -f 1757//1757 1352//1352 1758//1758 -f 1758//1758 1352//1352 1354//1354 -f 1758//1758 1354//1354 1679//1679 -f 1679//1679 1354//1354 1356//1356 -f 1679//1679 1356//1356 1358//1358 -f 1579//1579 1759//1759 1581//1581 -f 1581//1581 1759//1759 1760//1760 -f 1581//1581 1760//1760 1583//1583 -f 1583//1583 1760//1760 1761//1761 -f 1583//1583 1761//1761 1585//1585 -f 1585//1585 1761//1761 1762//1762 -f 1585//1585 1762//1762 1587//1587 -f 1587//1587 1762//1762 1763//1763 -f 1587//1587 1763//1763 1589//1589 -f 1589//1589 1763//1763 1764//1764 -f 1589//1589 1764//1764 1591//1591 -f 1591//1591 1764//1764 1765//1765 -f 1591//1591 1765//1765 1593//1593 -f 1593//1593 1765//1765 1766//1766 -f 1593//1593 1766//1766 1595//1595 -f 1595//1595 1766//1766 1767//1767 -f 1595//1595 1767//1767 1514//1514 -f 1514//1514 1767//1767 1768//1768 -f 1514//1514 1768//1768 1515//1515 -f 1515//1515 1768//1768 1769//1769 -f 1515//1515 1769//1769 1517//1517 -f 1517//1517 1769//1769 1770//1770 -f 1517//1517 1770//1770 1519//1519 -f 1519//1519 1770//1770 1771//1771 -f 1519//1519 1771//1771 1521//1521 -f 1521//1521 1771//1771 1772//1772 -f 1521//1521 1772//1772 1523//1523 -f 1523//1523 1772//1772 1773//1773 -f 1523//1523 1773//1773 1525//1525 -f 1525//1525 1773//1773 1774//1774 -f 1525//1525 1774//1774 1527//1527 -f 1527//1527 1774//1774 1775//1775 -f 1527//1527 1775//1775 1529//1529 -f 1563//1563 1776//1776 1565//1565 -f 1565//1565 1776//1776 1777//1777 -f 1565//1565 1777//1777 1567//1567 -f 1567//1567 1777//1777 1778//1778 -f 1567//1567 1778//1778 1569//1569 -f 1569//1569 1778//1778 1779//1779 -f 1569//1569 1779//1779 1571//1571 -f 1571//1571 1779//1779 1780//1780 -f 1571//1571 1780//1780 1573//1573 -f 1573//1573 1780//1780 1781//1781 -f 1573//1573 1781//1781 1575//1575 -f 1575//1575 1781//1781 1782//1782 -f 1575//1575 1782//1782 1577//1577 -f 1577//1577 1782//1782 1783//1783 -f 1577//1577 1783//1783 1579//1579 -f 1579//1579 1783//1783 1784//1784 -f 1579//1579 1784//1784 1759//1759 -f 1775//1775 1785//1785 1529//1529 -f 1529//1529 1785//1785 1786//1786 -f 1529//1529 1786//1786 1531//1531 -f 1531//1531 1786//1786 1787//1787 -f 1531//1531 1787//1787 1533//1533 -f 1533//1533 1787//1787 1788//1788 -f 1533//1533 1788//1788 1535//1535 -f 1535//1535 1788//1788 1789//1789 -f 1535//1535 1789//1789 1537//1537 -f 1537//1537 1789//1789 1790//1790 -f 1537//1537 1790//1790 1539//1539 -f 1539//1539 1790//1790 1791//1791 -f 1539//1539 1791//1791 1541//1541 -f 1541//1541 1791//1791 1792//1792 -f 1541//1541 1792//1792 1543//1543 -f 1543//1543 1792//1792 1793//1793 -f 1543//1543 1793//1793 1545//1545 -f 1793//1793 1794//1794 1545//1545 -f 1545//1545 1794//1794 1795//1795 -f 1545//1545 1795//1795 1547//1547 -f 1547//1547 1795//1795 1796//1796 -f 1547//1547 1796//1796 1549//1549 -f 1549//1549 1796//1796 1797//1797 -f 1549//1549 1797//1797 1551//1551 -f 1551//1551 1797//1797 1798//1798 -f 1551//1551 1798//1798 1553//1553 -f 1553//1553 1798//1798 1799//1799 -f 1553//1553 1799//1799 1555//1555 -f 1555//1555 1799//1799 1800//1800 -f 1555//1555 1800//1800 1557//1557 -f 1557//1557 1800//1800 1801//1801 -f 1557//1557 1801//1801 1559//1559 -f 1559//1559 1801//1801 1802//1802 -f 1559//1559 1802//1802 1561//1561 -f 1561//1561 1802//1802 1803//1803 -f 1561//1561 1803//1803 1563//1563 -f 1563//1563 1803//1803 1804//1804 -f 1563//1563 1804//1804 1776//1776 -f 1742//1742 1805//1805 1806//1806 -f 1737//1737 1738//1738 1807//1807 -f 1807//1807 1738//1738 1739//1739 -f 1807//1807 1739//1739 1808//1808 -f 1808//1808 1739//1739 1740//1740 -f 1808//1808 1740//1740 1806//1806 -f 1806//1806 1740//1740 1741//1741 -f 1806//1806 1741//1741 1742//1742 -f 1737//1737 1807//1807 1736//1736 -f 1736//1736 1807//1807 1809//1809 -f 1736//1736 1809//1809 1735//1735 -f 1735//1735 1809//1809 1810//1810 -f 1735//1735 1810//1810 1734//1734 -f 1734//1734 1810//1810 1811//1811 -f 1734//1734 1811//1811 1733//1733 -f 1812//1812 1730//1730 1813//1813 -f 1813//1813 1730//1730 1731//1731 -f 1813//1813 1731//1731 1811//1811 -f 1811//1811 1731//1731 1732//1732 -f 1811//1811 1732//1732 1733//1733 -f 1814//1814 1727//1727 1815//1815 -f 1815//1815 1727//1727 1728//1728 -f 1815//1815 1728//1728 1812//1812 -f 1812//1812 1728//1728 1729//1729 -f 1812//1812 1729//1729 1730//1730 -f 1816//1816 1725//1725 1814//1814 -f 1814//1814 1725//1725 1726//1726 -f 1814//1814 1726//1726 1727//1727 -f 1720//1720 1721//1721 1817//1817 -f 1817//1817 1721//1721 1722//1722 -f 1817//1817 1722//1722 1818//1818 -f 1818//1818 1722//1722 1723//1723 -f 1818//1818 1723//1723 1816//1816 -f 1816//1816 1723//1723 1724//1724 -f 1816//1816 1724//1724 1725//1725 -f 1720//1720 1817//1817 1719//1719 -f 1719//1719 1817//1817 1819//1819 -f 1719//1719 1819//1819 1718//1718 -f 1718//1718 1819//1819 1820//1820 -f 1718//1718 1820//1820 1717//1717 -f 1717//1717 1820//1820 1716//1716 -f 1716//1716 1820//1820 1821//1821 -f 1716//1716 1821//1821 1715//1715 -f 1715//1715 1821//1821 1822//1822 -f 1715//1715 1822//1822 1714//1714 -f 1714//1714 1822//1822 1713//1713 -f 1713//1713 1822//1822 1823//1823 -f 1713//1713 1823//1823 1712//1712 -f 1712//1712 1823//1823 1711//1711 -f 1711//1711 1823//1823 1824//1824 -f 1711//1711 1824//1824 1710//1710 -f 1710//1710 1824//1824 1825//1825 -f 1710//1710 1825//1825 1709//1709 -f 1826//1826 1704//1704 1827//1827 -f 1827//1827 1704//1704 1705//1705 -f 1827//1827 1705//1705 1828//1828 -f 1828//1828 1705//1705 1706//1706 -f 1828//1828 1706//1706 1829//1829 -f 1829//1829 1706//1706 1707//1707 -f 1829//1829 1707//1707 1825//1825 -f 1825//1825 1707//1707 1708//1708 -f 1825//1825 1708//1708 1709//1709 -f 1830//1830 1702//1702 1826//1826 -f 1826//1826 1702//1702 1703//1703 -f 1826//1826 1703//1703 1704//1704 -f 1697//1697 1698//1698 1831//1831 -f 1831//1831 1698//1698 1699//1699 -f 1831//1831 1699//1699 1832//1832 -f 1832//1832 1699//1699 1700//1700 -f 1832//1832 1700//1700 1830//1830 -f 1830//1830 1700//1700 1701//1701 -f 1830//1830 1701//1701 1702//1702 -f 1697//1697 1831//1831 1696//1696 -f 1696//1696 1831//1831 1833//1833 -f 1696//1696 1833//1833 1695//1695 -f 1695//1695 1833//1833 1834//1834 -f 1695//1695 1834//1834 1694//1694 -f 1694//1694 1834//1834 1835//1835 -f 1694//1694 1835//1835 1693//1693 -f 1836//1836 1690//1690 1837//1837 -f 1837//1837 1690//1690 1691//1691 -f 1837//1837 1691//1691 1835//1835 -f 1835//1835 1691//1691 1692//1692 -f 1835//1835 1692//1692 1693//1693 -f 1838//1838 1687//1687 1839//1839 -f 1839//1839 1687//1687 1688//1688 -f 1839//1839 1688//1688 1836//1836 -f 1836//1836 1688//1688 1689//1689 -f 1836//1836 1689//1689 1690//1690 -f 1840//1840 1685//1685 1838//1838 -f 1838//1838 1685//1685 1686//1686 -f 1838//1838 1686//1686 1687//1687 -f 1680//1680 1681//1681 1841//1841 -f 1841//1841 1681//1681 1682//1682 -f 1841//1841 1682//1682 1842//1842 -f 1842//1842 1682//1682 1683//1683 -f 1842//1842 1683//1683 1840//1840 -f 1840//1840 1683//1683 1684//1684 -f 1840//1840 1684//1684 1685//1685 -f 1680//1680 1841//1841 1679//1679 -f 1679//1679 1841//1841 1843//1843 -f 1679//1679 1843//1843 1758//1758 -f 1758//1758 1843//1843 1844//1844 -f 1758//1758 1844//1844 1757//1757 -f 1757//1757 1844//1844 1756//1756 -f 1756//1756 1844//1844 1845//1845 -f 1756//1756 1845//1845 1755//1755 -f 1755//1755 1845//1845 1846//1846 -f 1755//1755 1846//1846 1754//1754 -f 1754//1754 1846//1846 1753//1753 -f 1753//1753 1846//1846 1847//1847 -f 1753//1753 1847//1847 1752//1752 -f 1752//1752 1847//1847 1751//1751 -f 1751//1751 1847//1847 1848//1848 -f 1751//1751 1848//1848 1750//1750 -f 1750//1750 1848//1848 1849//1849 -f 1750//1750 1849//1849 1749//1749 -f 1742//1742 1743//1743 1805//1805 -f 1805//1805 1743//1743 1744//1744 -f 1805//1805 1744//1744 1850//1850 -f 1850//1850 1744//1744 1745//1745 -f 1850//1850 1745//1745 1851//1851 -f 1851//1851 1745//1745 1746//1746 -f 1851//1851 1746//1746 1852//1852 -f 1852//1852 1746//1746 1747//1747 -f 1852//1852 1747//1747 1849//1849 -f 1849//1849 1747//1747 1748//1748 -f 1849//1849 1748//1748 1749//1749 -f 1853//1853 1854//1854 1855//1855 -f 1855//1855 1854//1854 1856//1856 -f 1855//1855 1856//1856 1857//1857 -f 1857//1857 1856//1856 1858//1858 -f 1857//1857 1858//1858 1859//1859 -f 1859//1859 1858//1858 1860//1860 -f 1859//1859 1860//1860 1861//1861 -f 1861//1861 1860//1860 1862//1862 -f 1861//1861 1862//1862 1863//1863 -f 1863//1863 1862//1862 1864//1864 -f 1863//1863 1864//1864 1865//1865 -f 1865//1865 1864//1864 1866//1866 -f 1865//1865 1866//1866 1867//1867 -f 1867//1867 1866//1866 1868//1868 -f 1867//1867 1868//1868 1869//1869 -f 1869//1869 1868//1868 1870//1870 -f 1869//1869 1870//1870 1871//1871 -f 1871//1871 1870//1870 1872//1872 -f 1871//1871 1872//1872 1873//1873 -f 1873//1873 1872//1872 1874//1874 -f 1873//1873 1874//1874 1875//1875 -f 1875//1875 1874//1874 1876//1876 -f 1875//1875 1876//1876 1877//1877 -f 1877//1877 1876//1876 1878//1878 -f 1877//1877 1878//1878 1879//1879 -f 1879//1879 1878//1878 1880//1880 -f 1879//1879 1880//1880 1881//1881 -f 1881//1881 1880//1880 1882//1882 -f 1881//1881 1882//1882 1883//1883 -f 1883//1883 1882//1882 1884//1884 -f 1883//1883 1884//1884 1885//1885 -f 1885//1885 1884//1884 1886//1886 -f 1885//1885 1886//1886 1887//1887 -f 1887//1887 1886//1886 1888//1888 -f 1887//1887 1888//1888 1889//1889 -f 1889//1889 1888//1888 1890//1890 -f 1889//1889 1890//1890 1891//1891 -f 1891//1891 1890//1890 1892//1892 -f 1891//1891 1892//1892 1893//1893 -f 1893//1893 1892//1892 1894//1894 -f 1893//1893 1894//1894 1895//1895 -f 1895//1895 1894//1894 1896//1896 -f 1895//1895 1896//1896 1897//1897 -f 1897//1897 1896//1896 1898//1898 -f 1897//1897 1898//1898 1899//1899 -f 1899//1899 1898//1898 1900//1900 -f 1899//1899 1900//1900 1901//1901 -f 1901//1901 1900//1900 1902//1902 -f 1901//1901 1902//1902 1903//1903 -f 1903//1903 1902//1902 1904//1904 -f 1903//1903 1904//1904 1905//1905 -f 1905//1905 1904//1904 1906//1906 -f 1905//1905 1906//1906 1907//1907 -f 1907//1907 1906//1906 1908//1908 -f 1907//1907 1908//1908 1909//1909 -f 1909//1909 1908//1908 1910//1910 -f 1909//1909 1910//1910 1911//1911 -f 1911//1911 1910//1910 1912//1912 -f 1911//1911 1912//1912 1913//1913 -f 1913//1913 1912//1912 1914//1914 -f 1913//1913 1914//1914 1915//1915 -f 1915//1915 1914//1914 1916//1916 -f 1915//1915 1916//1916 1917//1917 -f 1917//1917 1916//1916 1918//1918 -f 1917//1917 1918//1918 1919//1919 -f 1919//1919 1918//1918 1920//1920 -f 1919//1919 1920//1920 1921//1921 -f 1921//1921 1920//1920 1922//1922 -f 1921//1921 1922//1922 1923//1923 -f 1923//1923 1922//1922 1924//1924 -f 1923//1923 1924//1924 1925//1925 -f 1925//1925 1924//1924 1926//1926 -f 1925//1925 1926//1926 1927//1927 -f 1927//1927 1926//1926 1928//1928 -f 1927//1927 1928//1928 1929//1929 -f 1929//1929 1928//1928 1930//1930 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1935//1935 -f 1935//1935 1934//1934 1936//1936 -f 1935//1935 1936//1936 1937//1937 -f 1937//1937 1936//1936 1938//1938 -f 1937//1937 1938//1938 1939//1939 -f 1939//1939 1938//1938 1940//1940 -f 1939//1939 1940//1940 1941//1941 -f 1941//1941 1940//1940 1942//1942 -f 1941//1941 1942//1942 1943//1943 -f 1943//1943 1942//1942 1944//1944 -f 1943//1943 1944//1944 1945//1945 -f 1945//1945 1944//1944 1946//1946 -f 1945//1945 1946//1946 1947//1947 -f 1947//1947 1946//1946 1948//1948 -f 1947//1947 1948//1948 1853//1853 -f 1853//1853 1948//1948 1854//1854 -f 1853//1853 1949//1949 1947//1947 -f 1947//1947 1949//1949 1950//1950 -f 1947//1947 1950//1950 1945//1945 -f 1945//1945 1950//1950 1951//1951 -f 1945//1945 1951//1951 1943//1943 -f 1943//1943 1951//1951 1952//1952 -f 1943//1943 1952//1952 1941//1941 -f 1941//1941 1952//1952 1953//1953 -f 1941//1941 1953//1953 1939//1939 -f 1939//1939 1953//1953 1954//1954 -f 1939//1939 1954//1954 1937//1937 -f 1937//1937 1954//1954 1955//1955 -f 1937//1937 1955//1955 1935//1935 -f 1935//1935 1955//1955 1956//1956 -f 1935//1935 1956//1956 1933//1933 -f 1933//1933 1956//1956 1957//1957 -f 1933//1933 1957//1957 1931//1931 -f 1931//1931 1957//1957 1958//1958 -f 1931//1931 1958//1958 1929//1929 -f 1929//1929 1958//1958 1959//1959 -f 1929//1929 1959//1959 1927//1927 -f 1927//1927 1959//1959 1960//1960 -f 1927//1927 1960//1960 1925//1925 -f 1925//1925 1960//1960 1961//1961 -f 1925//1925 1961//1961 1923//1923 -f 1923//1923 1961//1961 1962//1962 -f 1923//1923 1962//1962 1921//1921 -f 1921//1921 1962//1962 1963//1963 -f 1921//1921 1963//1963 1919//1919 -f 1919//1919 1963//1963 1964//1964 -f 1919//1919 1964//1964 1917//1917 -f 1917//1917 1964//1964 1965//1965 -f 1917//1917 1965//1965 1915//1915 -f 1915//1915 1965//1965 1966//1966 -f 1915//1915 1966//1966 1913//1913 -f 1913//1913 1966//1966 1967//1967 -f 1913//1913 1967//1967 1911//1911 -f 1911//1911 1967//1967 1968//1968 -f 1911//1911 1968//1968 1909//1909 -f 1909//1909 1968//1968 1969//1969 -f 1909//1909 1969//1969 1907//1907 -f 1907//1907 1969//1969 1970//1970 -f 1907//1907 1970//1970 1905//1905 -f 1905//1905 1970//1970 1971//1971 -f 1905//1905 1971//1971 1903//1903 -f 1903//1903 1971//1971 1972//1972 -f 1903//1903 1972//1972 1901//1901 -f 1901//1901 1972//1972 1973//1973 -f 1901//1901 1973//1973 1899//1899 -f 1899//1899 1973//1973 1974//1974 -f 1899//1899 1974//1974 1897//1897 -f 1897//1897 1974//1974 1975//1975 -f 1897//1897 1975//1975 1895//1895 -f 1895//1895 1975//1975 1976//1976 -f 1895//1895 1976//1976 1893//1893 -f 1893//1893 1976//1976 1977//1977 -f 1893//1893 1977//1977 1891//1891 -f 1891//1891 1977//1977 1978//1978 -f 1891//1891 1978//1978 1889//1889 -f 1889//1889 1978//1978 1979//1979 -f 1889//1889 1979//1979 1887//1887 -f 1887//1887 1979//1979 1980//1980 -f 1887//1887 1980//1980 1885//1885 -f 1885//1885 1980//1980 1981//1981 -f 1885//1885 1981//1981 1883//1883 -f 1883//1883 1981//1981 1982//1982 -f 1883//1883 1982//1982 1881//1881 -f 1881//1881 1982//1982 1983//1983 -f 1881//1881 1983//1983 1879//1879 -f 1879//1879 1983//1983 1984//1984 -f 1879//1879 1984//1984 1877//1877 -f 1877//1877 1984//1984 1985//1985 -f 1877//1877 1985//1985 1875//1875 -f 1875//1875 1985//1985 1986//1986 -f 1875//1875 1986//1986 1873//1873 -f 1873//1873 1986//1986 1987//1987 -f 1873//1873 1987//1987 1871//1871 -f 1871//1871 1987//1987 1988//1988 -f 1871//1871 1988//1988 1869//1869 -f 1869//1869 1988//1988 1989//1989 -f 1869//1869 1989//1989 1867//1867 -f 1867//1867 1989//1989 1990//1990 -f 1867//1867 1990//1990 1865//1865 -f 1865//1865 1990//1990 1991//1991 -f 1865//1865 1991//1991 1863//1863 -f 1863//1863 1991//1991 1992//1992 -f 1863//1863 1992//1992 1861//1861 -f 1861//1861 1992//1992 1993//1993 -f 1861//1861 1993//1993 1859//1859 -f 1859//1859 1993//1993 1994//1994 -f 1859//1859 1994//1994 1857//1857 -f 1857//1857 1994//1994 1995//1995 -f 1857//1857 1995//1995 1855//1855 -f 1855//1855 1995//1995 1996//1996 -f 1855//1855 1996//1996 1853//1853 -f 1853//1853 1996//1996 1949//1949 -f 1949//1949 1850//1850 1950//1950 -f 1950//1950 1850//1850 1851//1851 -f 1950//1950 1851//1851 1951//1951 -f 1951//1951 1851//1851 1852//1852 -f 1951//1951 1852//1852 1952//1952 -f 1952//1952 1852//1852 1849//1849 -f 1952//1952 1849//1849 1953//1953 -f 1953//1953 1849//1849 1848//1848 -f 1953//1953 1848//1848 1954//1954 -f 1954//1954 1848//1848 1847//1847 -f 1954//1954 1847//1847 1955//1955 -f 1955//1955 1847//1847 1846//1846 -f 1955//1955 1846//1846 1956//1956 -f 1956//1956 1846//1846 1845//1845 -f 1956//1956 1845//1845 1957//1957 -f 1957//1957 1845//1845 1844//1844 -f 1957//1957 1844//1844 1958//1958 -f 1958//1958 1844//1844 1843//1843 -f 1958//1958 1843//1843 1959//1959 -f 1959//1959 1843//1843 1841//1841 -f 1959//1959 1841//1841 1960//1960 -f 1960//1960 1841//1841 1842//1842 -f 1960//1960 1842//1842 1961//1961 -f 1961//1961 1842//1842 1840//1840 -f 1961//1961 1840//1840 1962//1962 -f 1962//1962 1840//1840 1838//1838 -f 1962//1962 1838//1838 1963//1963 -f 1963//1963 1838//1838 1839//1839 -f 1963//1963 1839//1839 1964//1964 -f 1964//1964 1839//1839 1836//1836 -f 1964//1964 1836//1836 1965//1965 -f 1965//1965 1836//1836 1837//1837 -f 1965//1965 1837//1837 1966//1966 -f 1966//1966 1837//1837 1835//1835 -f 1966//1966 1835//1835 1967//1967 -f 1967//1967 1835//1835 1834//1834 -f 1967//1967 1834//1834 1968//1968 -f 1968//1968 1834//1834 1833//1833 -f 1968//1968 1833//1833 1969//1969 -f 1969//1969 1833//1833 1831//1831 -f 1969//1969 1831//1831 1970//1970 -f 1970//1970 1831//1831 1832//1832 -f 1970//1970 1832//1832 1971//1971 -f 1971//1971 1832//1832 1830//1830 -f 1971//1971 1830//1830 1972//1972 -f 1972//1972 1830//1830 1826//1826 -f 1972//1972 1826//1826 1973//1973 -f 1973//1973 1826//1826 1827//1827 -f 1973//1973 1827//1827 1974//1974 -f 1974//1974 1827//1827 1828//1828 -f 1974//1974 1828//1828 1975//1975 -f 1975//1975 1828//1828 1829//1829 -f 1975//1975 1829//1829 1976//1976 -f 1976//1976 1829//1829 1825//1825 -f 1976//1976 1825//1825 1977//1977 -f 1977//1977 1825//1825 1824//1824 -f 1977//1977 1824//1824 1978//1978 -f 1978//1978 1824//1824 1823//1823 -f 1978//1978 1823//1823 1979//1979 -f 1979//1979 1823//1823 1822//1822 -f 1979//1979 1822//1822 1980//1980 -f 1980//1980 1822//1822 1821//1821 -f 1980//1980 1821//1821 1981//1981 -f 1981//1981 1821//1821 1820//1820 -f 1981//1981 1820//1820 1982//1982 -f 1982//1982 1820//1820 1819//1819 -f 1982//1982 1819//1819 1983//1983 -f 1983//1983 1819//1819 1817//1817 -f 1983//1983 1817//1817 1984//1984 -f 1984//1984 1817//1817 1818//1818 -f 1984//1984 1818//1818 1985//1985 -f 1985//1985 1818//1818 1816//1816 -f 1985//1985 1816//1816 1986//1986 -f 1986//1986 1816//1816 1814//1814 -f 1986//1986 1814//1814 1987//1987 -f 1987//1987 1814//1814 1815//1815 -f 1987//1987 1815//1815 1988//1988 -f 1988//1988 1815//1815 1812//1812 -f 1988//1988 1812//1812 1989//1989 -f 1989//1989 1812//1812 1813//1813 -f 1989//1989 1813//1813 1990//1990 -f 1990//1990 1813//1813 1811//1811 -f 1990//1990 1811//1811 1991//1991 -f 1991//1991 1811//1811 1810//1810 -f 1991//1991 1810//1810 1992//1992 -f 1992//1992 1810//1810 1809//1809 -f 1992//1992 1809//1809 1993//1993 -f 1993//1993 1809//1809 1807//1807 -f 1993//1993 1807//1807 1994//1994 -f 1994//1994 1807//1807 1808//1808 -f 1994//1994 1808//1808 1995//1995 -f 1995//1995 1808//1808 1806//1806 -f 1995//1995 1806//1806 1996//1996 -f 1996//1996 1806//1806 1805//1805 -f 1996//1996 1805//1805 1949//1949 -f 1949//1949 1805//1805 1850//1850 -f 1997//1997 1998//1998 1999//1999 -f 2000//2000 2001//2001 2002//2002 -f 2002//2002 2001//2001 2003//2003 -f 2002//2002 2003//2003 2004//2004 -f 2004//2004 2003//2003 2005//2005 -f 2004//2004 2005//2005 1999//1999 -f 1999//1999 2005//2005 2006//2006 -f 1999//1999 2006//2006 1997//1997 -f 2000//2000 2002//2002 2007//2007 -f 2007//2007 2002//2002 2008//2008 -f 2007//2007 2008//2008 2009//2009 -f 2009//2009 2008//2008 2010//2010 -f 2009//2009 2010//2010 2011//2011 -f 2011//2011 2010//2010 2012//2012 -f 2012//2012 2010//2010 2013//2013 -f 2012//2012 2013//2013 2014//2014 -f 2014//2014 2013//2013 2015//2015 -f 2014//2014 2015//2015 2016//2016 -f 2016//2016 2015//2015 2017//2017 -f 2017//2017 2015//2015 2018//2018 -f 2017//2017 2018//2018 2019//2019 -f 2019//2019 2018//2018 2020//2020 -f 2020//2020 2018//2018 2021//2021 -f 2020//2020 2021//2021 2022//2022 -f 2022//2022 2021//2021 2023//2023 -f 2022//2022 2023//2023 2024//2024 -f 2025//2025 2026//2026 2027//2027 -f 2027//2027 2026//2026 2028//2028 -f 2027//2027 2028//2028 2023//2023 -f 2023//2023 2028//2028 2029//2029 -f 2023//2023 2029//2029 2024//2024 -f 2030//2030 2031//2031 2032//2032 -f 2032//2032 2031//2031 2033//2033 -f 2032//2032 2033//2033 2025//2025 -f 2025//2025 2033//2033 2034//2034 -f 2025//2025 2034//2034 2026//2026 -f 2035//2035 2036//2036 2030//2030 -f 2030//2030 2036//2036 2037//2037 -f 2030//2030 2037//2037 2031//2031 -f 2038//2038 2039//2039 2040//2040 -f 2040//2040 2039//2039 2041//2041 -f 2040//2040 2041//2041 2042//2042 -f 2042//2042 2041//2041 2043//2043 -f 2042//2042 2043//2043 2035//2035 -f 2035//2035 2043//2043 2044//2044 -f 2035//2035 2044//2044 2036//2036 -f 2038//2038 2040//2040 2045//2045 -f 2045//2045 2040//2040 2046//2046 -f 2045//2045 2046//2046 2047//2047 -f 2047//2047 2046//2046 2048//2048 -f 2047//2047 2048//2048 2049//2049 -f 2049//2049 2048//2048 2050//2050 -f 2050//2050 2048//2048 2051//2051 -f 2050//2050 2051//2051 2052//2052 -f 2052//2052 2051//2051 2053//2053 -f 2052//2052 2053//2053 2054//2054 -f 2054//2054 2053//2053 2055//2055 -f 2055//2055 2053//2053 2056//2056 -f 2055//2055 2056//2056 2057//2057 -f 2057//2057 2056//2056 2058//2058 -f 2058//2058 2056//2056 2059//2059 -f 2058//2058 2059//2059 2060//2060 -f 2060//2060 2059//2059 2061//2061 -f 2060//2060 2061//2061 2062//2062 -f 2063//2063 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2065//2065 2066//2066 2061//2061 -f 2061//2061 2066//2066 2067//2067 -f 2061//2061 2067//2067 2062//2062 -f 2068//2068 2069//2069 2070//2070 -f 2070//2070 2069//2069 2071//2071 -f 2070//2070 2071//2071 2072//2072 -f 2072//2072 2071//2071 2073//2073 -f 2072//2072 2073//2073 2063//2063 -f 2063//2063 2073//2073 2074//2074 -f 2063//2063 2074//2074 2064//2064 -f 2068//2068 2070//2070 2075//2075 -f 2075//2075 2070//2070 2076//2076 -f 2075//2075 2076//2076 2077//2077 -f 2077//2077 2076//2076 2078//2078 -f 2077//2077 2078//2078 2079//2079 -f 2079//2079 2078//2078 2080//2080 -f 2079//2079 2080//2080 2081//2081 -f 2082//2082 2083//2083 2084//2084 -f 2084//2084 2083//2083 2085//2085 -f 2084//2084 2085//2085 2080//2080 -f 2080//2080 2085//2085 2086//2086 -f 2080//2080 2086//2086 2081//2081 -f 2087//2087 2088//2088 2089//2089 -f 2089//2089 2088//2088 2090//2090 -f 2089//2089 2090//2090 2091//2091 -f 2091//2091 2090//2090 2092//2092 -f 2091//2091 2092//2092 2082//2082 -f 2082//2082 2092//2092 2093//2093 -f 2082//2082 2093//2093 2083//2083 -f 2087//2087 2089//2089 2094//2094 -f 2094//2094 2089//2089 2095//2095 -f 2094//2094 2095//2095 2096//2096 -f 2096//2096 2095//2095 2097//2097 -f 2096//2096 2097//2097 2098//2098 -f 2098//2098 2097//2097 2099//2099 -f 2098//2098 2099//2099 2100//2100 -f 2100//2100 2099//2099 2101//2101 -f 2101//2101 2099//2099 2102//2102 -f 2101//2101 2102//2102 2103//2103 -f 2103//2103 2102//2102 2104//2104 -f 2104//2104 2102//2102 2105//2105 -f 2104//2104 2105//2105 2106//2106 -f 2106//2106 2105//2105 2107//2107 -f 2107//2107 2105//2105 2108//2108 -f 2107//2107 2108//2108 2109//2109 -f 2109//2109 2108//2108 2110//2110 -f 2109//2109 2110//2110 2111//2111 -f 1997//1997 2112//2112 1998//1998 -f 1998//1998 2112//2112 2113//2113 -f 1998//1998 2113//2113 2114//2114 -f 2114//2114 2113//2113 2115//2115 -f 2114//2114 2115//2115 2116//2116 -f 2116//2116 2115//2115 2117//2117 -f 2116//2116 2117//2117 2118//2118 -f 2118//2118 2117//2117 2119//2119 -f 2118//2118 2119//2119 2110//2110 -f 2110//2110 2119//2119 2120//2120 -f 2110//2110 2120//2120 2111//2111 -f 2121//2121 1767//1767 2122//2122 -f 2122//2122 1767//1767 1766//1766 -f 2122//2122 1766//1766 2123//2123 -f 2123//2123 1766//1766 1765//1765 -f 2123//2123 1765//1765 2124//2124 -f 2124//2124 1765//1765 1764//1764 -f 2124//2124 1764//1764 2125//2125 -f 2125//2125 1764//1764 1763//1763 -f 2125//2125 1763//1763 2126//2126 -f 2126//2126 1763//1763 1762//1762 -f 2126//2126 1762//1762 2127//2127 -f 2127//2127 1762//1762 1761//1761 -f 2127//2127 1761//1761 2128//2128 -f 2128//2128 1761//1761 1760//1760 -f 2128//2128 1760//1760 2129//2129 -f 2129//2129 1760//1760 1759//1759 -f 2129//2129 1759//1759 2130//2130 -f 2130//2130 1759//1759 1784//1784 -f 2130//2130 1784//1784 2131//2131 -f 2131//2131 1784//1784 1783//1783 -f 2131//2131 1783//1783 2132//2132 -f 2132//2132 1783//1783 1782//1782 -f 2132//2132 1782//1782 2133//2133 -f 2133//2133 1782//1782 1781//1781 -f 2133//2133 1781//1781 2134//2134 -f 2134//2134 1781//1781 1780//1780 -f 2134//2134 1780//1780 2135//2135 -f 2135//2135 1780//1780 1779//1779 -f 2135//2135 1779//1779 2136//2136 -f 2136//2136 1779//1779 1778//1778 -f 2136//2136 1778//1778 2137//2137 -f 2137//2137 1778//1778 1777//1777 -f 2137//2137 1777//1777 2138//2138 -f 2138//2138 1777//1777 1776//1776 -f 2138//2138 1776//1776 2139//2139 -f 2139//2139 1776//1776 1804//1804 -f 2139//2139 1804//1804 2140//2140 -f 2140//2140 1804//1804 1803//1803 -f 2140//2140 1803//1803 2141//2141 -f 2141//2141 1803//1803 1802//1802 -f 2141//2141 1802//1802 2142//2142 -f 2142//2142 1802//1802 1801//1801 -f 2142//2142 1801//1801 2143//2143 -f 2143//2143 1801//1801 1800//1800 -f 2143//2143 1800//1800 2144//2144 -f 2144//2144 1800//1800 1799//1799 -f 2144//2144 1799//1799 2145//2145 -f 2145//2145 1799//1799 1798//1798 -f 2145//2145 1798//1798 2146//2146 -f 2146//2146 1798//1798 1797//1797 -f 2146//2146 1797//1797 2147//2147 -f 2147//2147 1797//1797 1796//1796 -f 2147//2147 1796//1796 2148//2148 -f 2148//2148 1796//1796 1795//1795 -f 2148//2148 1795//1795 2149//2149 -f 2149//2149 1795//1795 1794//1794 -f 2149//2149 1794//1794 2150//2150 -f 2150//2150 1794//1794 1793//1793 -f 2150//2150 1793//1793 2151//2151 -f 2151//2151 1793//1793 1792//1792 -f 2151//2151 1792//1792 2152//2152 -f 2152//2152 1792//1792 1791//1791 -f 2152//2152 1791//1791 2153//2153 -f 2153//2153 1791//1791 1790//1790 -f 2153//2153 1790//1790 2154//2154 -f 2154//2154 1790//1790 1789//1789 -f 2154//2154 1789//1789 2155//2155 -f 2155//2155 1789//1789 1788//1788 -f 2155//2155 1788//1788 2156//2156 -f 2156//2156 1788//1788 1787//1787 -f 2156//2156 1787//1787 2157//2157 -f 2157//2157 1787//1787 1786//1786 -f 2157//2157 1786//1786 2158//2158 -f 2158//2158 1786//1786 1785//1785 -f 2158//2158 1785//1785 2159//2159 -f 2159//2159 1785//1785 1775//1775 -f 2159//2159 1775//1775 2160//2160 -f 2160//2160 1775//1775 1774//1774 -f 2160//2160 1774//1774 2161//2161 -f 2161//2161 1774//1774 1773//1773 -f 2161//2161 1773//1773 2162//2162 -f 2162//2162 1773//1773 1772//1772 -f 2162//2162 1772//1772 2163//2163 -f 2163//2163 1772//1772 1771//1771 -f 2163//2163 1771//1771 2164//2164 -f 2164//2164 1771//1771 1770//1770 -f 2164//2164 1770//1770 2165//2165 -f 2165//2165 1770//1770 1769//1769 -f 2165//2165 1769//1769 2166//2166 -f 2166//2166 1769//1769 1768//1768 -f 2166//2166 1768//1768 2121//2121 -f 2121//2121 1768//1768 1767//1767 -f 2145//2145 2167//2167 2144//2144 -f 2144//2144 2167//2167 2168//2168 -f 2144//2144 2168//2168 2143//2143 -f 2143//2143 2168//2168 2169//2169 -f 2143//2143 2169//2169 2142//2142 -f 2142//2142 2169//2169 2170//2170 -f 2142//2142 2170//2170 2141//2141 -f 2141//2141 2170//2170 2171//2171 -f 2141//2141 2171//2171 2140//2140 -f 2140//2140 2171//2171 2172//2172 -f 2140//2140 2172//2172 2139//2139 -f 2139//2139 2172//2172 2173//2173 -f 2139//2139 2173//2173 2138//2138 -f 2138//2138 2173//2173 2174//2174 -f 2138//2138 2174//2174 2137//2137 -f 2137//2137 2174//2174 2175//2175 -f 2137//2137 2175//2175 2136//2136 -f 2136//2136 2175//2175 2176//2176 -f 2136//2136 2176//2176 2135//2135 -f 2135//2135 2176//2176 2177//2177 -f 2135//2135 2177//2177 2134//2134 -f 2134//2134 2177//2177 2178//2178 -f 2134//2134 2178//2178 2133//2133 -f 2133//2133 2178//2178 2179//2179 -f 2133//2133 2179//2179 2132//2132 -f 2132//2132 2179//2179 2180//2180 -f 2132//2132 2180//2180 2131//2131 -f 2131//2131 2180//2180 2181//2181 -f 2131//2131 2181//2181 2130//2130 -f 2130//2130 2181//2181 2182//2182 -f 2130//2130 2182//2182 2129//2129 -f 2129//2129 2182//2182 2183//2183 -f 2129//2129 2183//2183 2128//2128 -f 2128//2128 2183//2183 2184//2184 -f 2128//2128 2184//2184 2127//2127 -f 2127//2127 2184//2184 2185//2185 -f 2127//2127 2185//2185 2126//2126 -f 2126//2126 2185//2185 2186//2186 -f 2126//2126 2186//2186 2125//2125 -f 2125//2125 2186//2186 2187//2187 -f 2125//2125 2187//2187 2124//2124 -f 2124//2124 2187//2187 2188//2188 -f 2124//2124 2188//2188 2123//2123 -f 2123//2123 2188//2188 2189//2189 -f 2123//2123 2189//2189 2122//2122 -f 2122//2122 2189//2189 2190//2190 -f 2122//2122 2190//2190 2121//2121 -f 2121//2121 2190//2190 2191//2191 -f 2121//2121 2191//2191 2166//2166 -f 2166//2166 2191//2191 2192//2192 -f 2166//2166 2192//2192 2165//2165 -f 2165//2165 2192//2192 2193//2193 -f 2165//2165 2193//2193 2164//2164 -f 2164//2164 2193//2193 2194//2194 -f 2164//2164 2194//2194 2163//2163 -f 2163//2163 2194//2194 2195//2195 -f 2163//2163 2195//2195 2162//2162 -f 2162//2162 2195//2195 2196//2196 -f 2162//2162 2196//2196 2161//2161 -f 2161//2161 2196//2196 2197//2197 -f 2161//2161 2197//2197 2160//2160 -f 2160//2160 2197//2197 2198//2198 -f 2160//2160 2198//2198 2159//2159 -f 2159//2159 2198//2198 2199//2199 -f 2159//2159 2199//2199 2158//2158 -f 2158//2158 2199//2199 2200//2200 -f 2158//2158 2200//2200 2157//2157 -f 2157//2157 2200//2200 2201//2201 -f 2157//2157 2201//2201 2156//2156 -f 2156//2156 2201//2201 2202//2202 -f 2156//2156 2202//2202 2155//2155 -f 2155//2155 2202//2202 2203//2203 -f 2155//2155 2203//2203 2154//2154 -f 2154//2154 2203//2203 2204//2204 -f 2154//2154 2204//2204 2153//2153 -f 2153//2153 2204//2204 2205//2205 -f 2153//2153 2205//2205 2152//2152 -f 2152//2152 2205//2205 2206//2206 -f 2152//2152 2206//2206 2151//2151 -f 2151//2151 2206//2206 2207//2207 -f 2151//2151 2207//2207 2150//2150 -f 2150//2150 2207//2207 2208//2208 -f 2150//2150 2208//2208 2149//2149 -f 2149//2149 2208//2208 2209//2209 -f 2149//2149 2209//2209 2148//2148 -f 2148//2148 2209//2209 2210//2210 -f 2148//2148 2210//2210 2147//2147 -f 2147//2147 2210//2210 2211//2211 -f 2147//2147 2211//2211 2146//2146 -f 2146//2146 2211//2211 2212//2212 -f 2146//2146 2212//2212 2145//2145 -f 2145//2145 2212//2212 2167//2167 -f 2212//2212 2114//2114 2167//2167 -f 2167//2167 2114//2114 2116//2116 -f 2167//2167 2116//2116 2168//2168 -f 2168//2168 2116//2116 2118//2118 -f 2168//2168 2118//2118 2169//2169 -f 2169//2169 2118//2118 2110//2110 -f 2169//2169 2110//2110 2170//2170 -f 2170//2170 2110//2110 2108//2108 -f 2170//2170 2108//2108 2171//2171 -f 2171//2171 2108//2108 2105//2105 -f 2171//2171 2105//2105 2172//2172 -f 2172//2172 2105//2105 2102//2102 -f 2172//2172 2102//2102 2173//2173 -f 2173//2173 2102//2102 2099//2099 -f 2173//2173 2099//2099 2174//2174 -f 2174//2174 2099//2099 2097//2097 -f 2174//2174 2097//2097 2175//2175 -f 2175//2175 2097//2097 2095//2095 -f 2175//2175 2095//2095 2176//2176 -f 2176//2176 2095//2095 2089//2089 -f 2176//2176 2089//2089 2177//2177 -f 2177//2177 2089//2089 2091//2091 -f 2177//2177 2091//2091 2178//2178 -f 2178//2178 2091//2091 2082//2082 -f 2178//2178 2082//2082 2179//2179 -f 2179//2179 2082//2082 2084//2084 -f 2179//2179 2084//2084 2180//2180 -f 2180//2180 2084//2084 2080//2080 -f 2180//2180 2080//2080 2181//2181 -f 2181//2181 2080//2080 2078//2078 -f 2181//2181 2078//2078 2182//2182 -f 2182//2182 2078//2078 2076//2076 -f 2182//2182 2076//2076 2183//2183 -f 2183//2183 2076//2076 2070//2070 -f 2183//2183 2070//2070 2184//2184 -f 2184//2184 2070//2070 2072//2072 -f 2184//2184 2072//2072 2185//2185 -f 2185//2185 2072//2072 2063//2063 -f 2185//2185 2063//2063 2186//2186 -f 2186//2186 2063//2063 2065//2065 -f 2186//2186 2065//2065 2187//2187 -f 2187//2187 2065//2065 2061//2061 -f 2187//2187 2061//2061 2188//2188 -f 2188//2188 2061//2061 2059//2059 -f 2188//2188 2059//2059 2189//2189 -f 2189//2189 2059//2059 2056//2056 -f 2189//2189 2056//2056 2190//2190 -f 2190//2190 2056//2056 2053//2053 -f 2190//2190 2053//2053 2191//2191 -f 2191//2191 2053//2053 2051//2051 -f 2191//2191 2051//2051 2192//2192 -f 2192//2192 2051//2051 2048//2048 -f 2192//2192 2048//2048 2193//2193 -f 2193//2193 2048//2048 2046//2046 -f 2193//2193 2046//2046 2194//2194 -f 2194//2194 2046//2046 2040//2040 -f 2194//2194 2040//2040 2195//2195 -f 2195//2195 2040//2040 2042//2042 -f 2195//2195 2042//2042 2196//2196 -f 2196//2196 2042//2042 2035//2035 -f 2196//2196 2035//2035 2197//2197 -f 2197//2197 2035//2035 2030//2030 -f 2197//2197 2030//2030 2198//2198 -f 2198//2198 2030//2030 2032//2032 -f 2198//2198 2032//2032 2199//2199 -f 2199//2199 2032//2032 2025//2025 -f 2199//2199 2025//2025 2200//2200 -f 2200//2200 2025//2025 2027//2027 -f 2200//2200 2027//2027 2201//2201 -f 2201//2201 2027//2027 2023//2023 -f 2201//2201 2023//2023 2202//2202 -f 2202//2202 2023//2023 2021//2021 -f 2202//2202 2021//2021 2203//2203 -f 2203//2203 2021//2021 2018//2018 -f 2203//2203 2018//2018 2204//2204 -f 2204//2204 2018//2018 2015//2015 -f 2204//2204 2015//2015 2205//2205 -f 2205//2205 2015//2015 2013//2013 -f 2205//2205 2013//2013 2206//2206 -f 2206//2206 2013//2013 2010//2010 -f 2206//2206 2010//2010 2207//2207 -f 2207//2207 2010//2010 2008//2008 -f 2207//2207 2008//2008 2208//2208 -f 2208//2208 2008//2008 2002//2002 -f 2208//2208 2002//2002 2209//2209 -f 2209//2209 2002//2002 2004//2004 -f 2209//2209 2004//2004 2210//2210 -f 2210//2210 2004//2004 1999//1999 -f 2210//2210 1999//1999 2211//2211 -f 2211//2211 1999//1999 1998//1998 -f 2211//2211 1998//1998 2212//2212 -f 2212//2212 1998//1998 2114//2114 -f 2213//2213 1854//1854 2214//2214 -f 2214//2214 1854//1854 1948//1948 -f 2214//2214 1948//1948 2215//2215 -f 2216//2216 1900//1900 2217//2217 -f 2217//2217 1900//1900 1898//1898 -f 2217//2217 1898//1898 2218//2218 -f 2218//2218 1898//1898 1896//1896 -f 2218//2218 1896//1896 2219//2219 -f 2220//2220 1906//1906 2221//2221 -f 2221//2221 1906//1906 1904//1904 -f 2221//2221 1904//1904 2216//2216 -f 2216//2216 1904//1904 1902//1902 -f 2216//2216 1902//1902 1900//1900 -f 2222//2222 1912//1912 2223//2223 -f 2223//2223 1912//1912 1910//1910 -f 2223//2223 1910//1910 2220//2220 -f 2220//2220 1910//1910 1908//1908 -f 2220//2220 1908//1908 1906//1906 -f 2224//2224 1918//1918 2225//2225 -f 2225//2225 1918//1918 1916//1916 -f 2225//2225 1916//1916 2222//2222 -f 2222//2222 1916//1916 1914//1914 -f 2222//2222 1914//1914 1912//1912 -f 2226//2226 1930//1930 2227//2227 -f 2227//2227 1930//1930 1928//1928 -f 2227//2227 1928//1928 2228//2228 -f 2229//2229 1860//1860 2230//2230 -f 2230//2230 1860//1860 1858//1858 -f 2230//2230 1858//1858 2213//2213 -f 2213//2213 1858//1858 1856//1856 -f 2213//2213 1856//1856 1854//1854 -f 2231//2231 1868//1868 2232//2232 -f 2232//2232 1868//1868 1866//1866 -f 2232//2232 1866//1866 2233//2233 -f 2233//2233 1866//1866 1864//1864 -f 2233//2233 1864//1864 2229//2229 -f 2229//2229 1864//1864 1862//1862 -f 2229//2229 1862//1862 1860//1860 -f 2234//2234 1874//1874 2235//2235 -f 2235//2235 1874//1874 1872//1872 -f 2235//2235 1872//1872 2231//2231 -f 2231//2231 1872//1872 1870//1870 -f 2231//2231 1870//1870 1868//1868 -f 2236//2236 1886//1886 2237//2237 -f 2237//2237 1886//1886 1884//1884 -f 2237//2237 1884//1884 2238//2238 -f 1928//1928 1926//1926 2228//2228 -f 2228//2228 1926//1926 1924//1924 -f 2228//2228 1924//1924 2239//2239 -f 2239//2239 1924//1924 1922//1922 -f 2239//2239 1922//1922 2224//2224 -f 2224//2224 1922//1922 1920//1920 -f 2224//2224 1920//1920 1918//1918 -f 2240//2240 1938//1938 2241//2241 -f 2241//2241 1938//1938 1936//1936 -f 2241//2241 1936//1936 2242//2242 -f 2242//2242 1936//1936 1934//1934 -f 2242//2242 1934//1934 2226//2226 -f 2226//2226 1934//1934 1932//1932 -f 2226//2226 1932//1932 1930//1930 -f 1948//1948 1946//1946 2215//2215 -f 2215//2215 1946//1946 1944//1944 -f 2215//2215 1944//1944 2243//2243 -f 2243//2243 1944//1944 1942//1942 -f 2243//2243 1942//1942 2240//2240 -f 2240//2240 1942//1942 1940//1940 -f 2240//2240 1940//1940 1938//1938 -f 1884//1884 1882//1882 2238//2238 -f 2238//2238 1882//1882 1880//1880 -f 2238//2238 1880//1880 2244//2244 -f 2244//2244 1880//1880 1878//1878 -f 2244//2244 1878//1878 2234//2234 -f 2234//2234 1878//1878 1876//1876 -f 2234//2234 1876//1876 1874//1874 -f 1896//1896 1894//1894 2219//2219 -f 2219//2219 1894//1894 1892//1892 -f 2219//2219 1892//1892 2245//2245 -f 2245//2245 1892//1892 1890//1890 -f 2245//2245 1890//1890 2236//2236 -f 2236//2236 1890//1890 1888//1888 -f 2236//2236 1888//1888 1886//1886 -f 2112//2112 2213//2213 2214//2214 -f 2005//2005 2230//2230 2006//2006 -f 2006//2006 2230//2230 2213//2213 -f 2006//2006 2213//2213 1997//1997 -f 1997//1997 2213//2213 2112//2112 -f 2005//2005 2003//2003 2230//2230 -f 2230//2230 2003//2003 2001//2001 -f 2230//2230 2001//2001 2229//2229 -f 2001//2001 2000//2000 2229//2229 -f 2229//2229 2000//2000 2007//2007 -f 2229//2229 2007//2007 2233//2233 -f 2007//2007 2009//2009 2233//2233 -f 2233//2233 2009//2009 2011//2011 -f 2233//2233 2011//2011 2232//2232 -f 2232//2232 2011//2011 2012//2012 -f 2232//2232 2012//2012 2231//2231 -f 2231//2231 2012//2012 2014//2014 -f 2231//2231 2014//2014 2016//2016 -f 2020//2020 2235//2235 2019//2019 -f 2019//2019 2235//2235 2231//2231 -f 2019//2019 2231//2231 2017//2017 -f 2017//2017 2231//2231 2016//2016 -f 2020//2020 2022//2022 2235//2235 -f 2235//2235 2022//2022 2024//2024 -f 2235//2235 2024//2024 2234//2234 -f 2024//2024 2029//2029 2234//2234 -f 2234//2234 2029//2029 2028//2028 -f 2234//2234 2028//2028 2244//2244 -f 2033//2033 2238//2238 2034//2034 -f 2034//2034 2238//2238 2244//2244 -f 2034//2034 2244//2244 2026//2026 -f 2026//2026 2244//2244 2028//2028 -f 2033//2033 2031//2031 2238//2238 -f 2238//2238 2031//2031 2037//2037 -f 2238//2238 2037//2037 2237//2237 -f 2043//2043 2236//2236 2044//2044 -f 2044//2044 2236//2236 2237//2237 -f 2044//2044 2237//2237 2036//2036 -f 2036//2036 2237//2237 2037//2037 -f 2043//2043 2041//2041 2236//2236 -f 2236//2236 2041//2041 2039//2039 -f 2236//2236 2039//2039 2245//2245 -f 2039//2039 2038//2038 2245//2245 -f 2245//2245 2038//2038 2045//2045 -f 2245//2245 2045//2045 2219//2219 -f 2050//2050 2218//2218 2049//2049 -f 2049//2049 2218//2218 2219//2219 -f 2049//2049 2219//2219 2047//2047 -f 2047//2047 2219//2219 2045//2045 -f 2050//2050 2052//2052 2218//2218 -f 2218//2218 2052//2052 2054//2054 -f 2218//2218 2054//2054 2217//2217 -f 2058//2058 2216//2216 2057//2057 -f 2057//2057 2216//2216 2217//2217 -f 2057//2057 2217//2217 2055//2055 -f 2055//2055 2217//2217 2054//2054 -f 2058//2058 2060//2060 2216//2216 -f 2216//2216 2060//2060 2062//2062 -f 2216//2216 2062//2062 2221//2221 -f 2062//2062 2067//2067 2221//2221 -f 2221//2221 2067//2067 2066//2066 -f 2221//2221 2066//2066 2220//2220 -f 2073//2073 2223//2223 2074//2074 -f 2074//2074 2223//2223 2220//2220 -f 2074//2074 2220//2220 2064//2064 -f 2064//2064 2220//2220 2066//2066 -f 2073//2073 2071//2071 2223//2223 -f 2223//2223 2071//2071 2069//2069 -f 2223//2223 2069//2069 2222//2222 -f 2077//2077 2225//2225 2075//2075 -f 2075//2075 2225//2225 2222//2222 -f 2075//2075 2222//2222 2068//2068 -f 2068//2068 2222//2222 2069//2069 -f 2077//2077 2079//2079 2225//2225 -f 2225//2225 2079//2079 2081//2081 -f 2225//2225 2081//2081 2224//2224 -f 2081//2081 2086//2086 2224//2224 -f 2224//2224 2086//2086 2085//2085 -f 2224//2224 2085//2085 2239//2239 -f 2092//2092 2228//2228 2093//2093 -f 2093//2093 2228//2228 2239//2239 -f 2093//2093 2239//2239 2083//2083 -f 2083//2083 2239//2239 2085//2085 -f 2092//2092 2090//2090 2228//2228 -f 2228//2228 2090//2090 2088//2088 -f 2228//2228 2088//2088 2227//2227 -f 2096//2096 2226//2226 2094//2094 -f 2094//2094 2226//2226 2227//2227 -f 2094//2094 2227//2227 2087//2087 -f 2087//2087 2227//2227 2088//2088 -f 2096//2096 2098//2098 2226//2226 -f 2226//2226 2098//2098 2100//2100 -f 2226//2226 2100//2100 2242//2242 -f 2100//2100 2101//2101 2242//2242 -f 2242//2242 2101//2101 2103//2103 -f 2242//2242 2103//2103 2241//2241 -f 2107//2107 2240//2240 2106//2106 -f 2106//2106 2240//2240 2241//2241 -f 2106//2106 2241//2241 2104//2104 -f 2104//2104 2241//2241 2103//2103 -f 2107//2107 2109//2109 2240//2240 -f 2240//2240 2109//2109 2111//2111 -f 2240//2240 2111//2111 2243//2243 -f 2111//2111 2120//2120 2243//2243 -f 2243//2243 2120//2120 2119//2119 -f 2243//2243 2119//2119 2215//2215 -f 2119//2119 2117//2117 2215//2215 -f 2215//2215 2117//2117 2115//2115 -f 2215//2215 2115//2115 2214//2214 -f 2214//2214 2115//2115 2113//2113 -f 2214//2214 2113//2113 2112//2112 -# 4486 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/pogon_zatezaci.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/pogon_zatezaci.obj deleted file mode 100644 index 6fc0b912f..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/pogon_zatezaci.obj +++ /dev/null @@ -1,3392 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object pogon_zatezaci.obj -# -# Vertices: 846 -# Faces: 1684 -# -#### -vn -0.990579 -0.080492 0.110788 -v -0.101496 -0.015822 0.012196 -vn -0.990579 -0.062170 0.122016 -v -0.101496 -0.015293 0.012519 -vn -0.838628 0.272352 -0.471728 -v -0.101496 -0.014655 0.011000 -vn -0.990579 0.080492 -0.110788 -v -0.101496 -0.011178 0.005804 -vn -0.990579 0.062170 -0.122016 -v -0.101496 -0.011707 0.005481 -vn -0.838628 -0.272352 0.471728 -v -0.101496 -0.012345 0.007000 -vn -0.990579 -0.021422 -0.135255 -v -0.101496 -0.014118 0.005099 -vn -0.990579 -0.042317 -0.130239 -v -0.101496 -0.014721 0.005243 -vn -0.838628 0.272352 0.471728 -v -0.101496 -0.014655 0.007000 -vn -0.990579 -0.062170 -0.122016 -v -0.101496 -0.015293 0.005481 -vn -0.990579 -0.080492 -0.110788 -v -0.101496 -0.015822 0.005804 -vn -0.990579 0.135255 0.021422 -v -0.101496 -0.009599 0.009618 -vn -0.990579 0.136941 -0.000000 -v -0.101496 -0.009550 0.009000 -vn -0.838628 -0.544705 0.000000 -v -0.101496 -0.011191 0.009000 -vn -0.990579 0.135255 -0.021422 -v -0.101496 -0.009599 0.008382 -vn -0.990579 0.096832 -0.096832 -v -0.101496 -0.010707 0.006207 -vn -0.990579 0.021422 0.135255 -v -0.101496 -0.012882 0.012901 -vn -0.990579 0.042317 0.130239 -v -0.101496 -0.012279 0.012757 -vn -0.838628 -0.272352 -0.471728 -v -0.101496 -0.012345 0.011000 -vn -0.838628 0.544705 0.000000 -v -0.101496 -0.015809 0.009000 -vn -0.990579 -0.135256 0.021422 -v -0.101496 -0.017401 0.009618 -vn -0.990579 -0.130239 0.042317 -v -0.101496 -0.017257 0.010221 -vn -0.990579 -0.130239 -0.042317 -v -0.101496 -0.017257 0.007779 -vn -0.990579 -0.135256 -0.021422 -v -0.101496 -0.017401 0.008382 -vn -0.990579 -0.136941 0.000000 -v -0.101496 -0.017450 0.009000 -vn -0.990579 0.130239 -0.042317 -v -0.101496 -0.009743 0.007779 -vn -0.990579 0.122016 -0.062170 -v -0.101496 -0.009981 0.007207 -vn -0.990579 0.110788 -0.080492 -v -0.101496 -0.010304 0.006678 -vn -0.990579 0.062170 0.122016 -v -0.101496 -0.011707 0.012519 -vn -0.990579 0.080492 0.110788 -v -0.101496 -0.011178 0.012196 -vn -0.990579 0.096832 0.096832 -v -0.101496 -0.010707 0.011793 -vn -0.990579 -0.122015 0.062170 -v -0.101496 -0.017019 0.010793 -vn -0.990579 -0.110787 0.080492 -v -0.101496 -0.016696 0.011322 -vn -0.990579 -0.096832 0.096832 -v -0.101496 -0.016293 0.011793 -vn -0.990579 0.042317 -0.130239 -v -0.101496 -0.012279 0.005243 -vn -0.990579 0.021422 -0.135256 -v -0.101496 -0.012882 0.005099 -vn -0.990579 -0.000000 -0.136941 -v -0.101496 -0.013500 0.005050 -vn -0.990579 0.110788 0.080492 -v -0.101496 -0.010304 0.011322 -vn -0.990579 0.122016 0.062170 -v -0.101496 -0.009981 0.010793 -vn -0.990579 0.130239 0.042317 -v -0.101496 -0.009743 0.010221 -vn -0.990579 -0.042317 0.130239 -v -0.101496 -0.014721 0.012757 -vn -0.990579 -0.021422 0.135255 -v -0.101496 -0.014118 0.012901 -vn -0.990579 0.000000 0.136941 -v -0.101496 -0.013500 0.012950 -vn -0.990579 -0.096832 -0.096832 -v -0.101496 -0.016293 0.006207 -vn -0.990579 -0.110788 -0.080492 -v -0.101496 -0.016696 0.006678 -vn -0.990579 -0.122015 -0.062170 -v -0.101496 -0.017019 0.007207 -vn -0.129688 0.979347 0.155113 -v -0.101196 -0.009302 0.009665 -vn 0.129688 0.979347 0.155114 -v -0.096796 -0.009302 0.009665 -vn -0.129688 0.991555 0.000000 -v -0.101196 -0.009250 0.009000 -vn 0.129688 0.991555 -0.000000 -v -0.096796 -0.009250 0.009000 -vn -0.129688 0.979347 -0.155114 -v -0.101196 -0.009302 0.008335 -vn 0.129688 0.979347 -0.155114 -v -0.096796 -0.009302 0.008335 -vn -0.129688 0.943025 -0.306407 -v -0.101196 -0.009458 0.007687 -vn 0.129688 0.943025 -0.306407 -v -0.096796 -0.009458 0.007687 -vn -0.129686 0.883482 -0.450156 -v -0.101196 -0.009713 0.007071 -vn 0.129687 0.883482 -0.450156 -v -0.096796 -0.009713 0.007071 -vn -0.129687 0.802185 -0.582822 -v -0.101196 -0.010062 0.006502 -vn 0.129688 0.802185 -0.582822 -v -0.096796 -0.010062 0.006502 -vn -0.129687 0.701135 -0.701135 -v -0.101196 -0.010495 0.005995 -vn 0.129688 0.701135 -0.701135 -v -0.096796 -0.010495 0.005995 -vn -0.129686 0.582822 -0.802185 -v -0.101196 -0.011002 0.005562 -vn 0.129687 0.582821 -0.802185 -v -0.096796 -0.011002 0.005562 -vn -0.129686 0.450157 -0.883482 -v -0.101196 -0.011571 0.005213 -vn 0.129688 0.450157 -0.883482 -v -0.096796 -0.011571 0.005213 -vn -0.129687 0.306407 -0.943025 -v -0.101196 -0.012187 0.004958 -vn 0.129688 0.306407 -0.943025 -v -0.096796 -0.012187 0.004958 -vn -0.129686 0.155114 -0.979347 -v -0.101196 -0.012835 0.004802 -vn 0.129687 0.155113 -0.979347 -v -0.096796 -0.012835 0.004802 -vn -0.129687 -0.000000 -0.991555 -v -0.101196 -0.013500 0.004750 -vn 0.129689 0.000000 -0.991555 -v -0.096796 -0.013500 0.004750 -vn -0.129686 -0.155113 -0.979347 -v -0.101196 -0.014165 0.004802 -vn 0.129687 -0.155114 -0.979347 -v -0.096796 -0.014165 0.004802 -vn -0.129687 -0.306408 -0.943025 -v -0.101196 -0.014813 0.004958 -vn 0.129688 -0.306407 -0.943025 -v -0.096796 -0.014813 0.004958 -vn -0.129685 -0.450157 -0.883482 -v -0.101196 -0.015429 0.005213 -vn 0.129687 -0.450157 -0.883482 -v -0.096796 -0.015429 0.005213 -vn -0.129689 -0.582822 -0.802184 -v -0.101196 -0.015998 0.005562 -vn 0.129690 -0.582821 -0.802184 -v -0.096796 -0.015998 0.005562 -vn -0.129687 -0.701135 -0.701136 -v -0.101196 -0.016505 0.005995 -vn 0.129688 -0.701135 -0.701135 -v -0.096796 -0.016505 0.005995 -vn -0.129691 -0.802185 -0.582820 -v -0.101196 -0.016938 0.006502 -vn 0.129692 -0.802184 -0.582821 -v -0.096796 -0.016938 0.006502 -vn -0.129687 -0.883482 -0.450156 -v -0.101196 -0.017287 0.007071 -vn 0.129687 -0.883482 -0.450156 -v -0.096796 -0.017287 0.007071 -vn -0.129688 -0.943025 -0.306407 -v -0.101196 -0.017542 0.007687 -vn 0.129688 -0.943025 -0.306408 -v -0.096796 -0.017542 0.007687 -vn -0.129686 -0.979347 -0.155115 -v -0.101196 -0.017698 0.008335 -vn 0.129686 -0.979347 -0.155114 -v -0.096796 -0.017698 0.008335 -vn -0.129687 -0.991555 0.000000 -v -0.101196 -0.017750 0.009000 -vn 0.129687 -0.991555 -0.000000 -v -0.096796 -0.017750 0.009000 -vn -0.129686 -0.979347 0.155114 -v -0.101196 -0.017698 0.009665 -vn 0.129686 -0.979347 0.155114 -v -0.096796 -0.017698 0.009665 -vn -0.129688 -0.943025 0.306407 -v -0.101196 -0.017542 0.010313 -vn 0.129688 -0.943025 0.306407 -v -0.096796 -0.017542 0.010313 -vn -0.129688 -0.883482 0.450156 -v -0.101196 -0.017287 0.010929 -vn 0.129688 -0.883482 0.450156 -v -0.096796 -0.017287 0.010929 -vn -0.129691 -0.802184 0.582821 -v -0.101196 -0.016938 0.011498 -vn 0.129691 -0.802185 0.582821 -v -0.096796 -0.016938 0.011498 -vn -0.129688 -0.701135 0.701135 -v -0.101196 -0.016505 0.012005 -vn 0.129688 -0.701135 0.701135 -v -0.096796 -0.016505 0.012005 -vn -0.129690 -0.582822 0.802184 -v -0.101196 -0.015998 0.012438 -vn 0.129690 -0.582822 0.802184 -v -0.096796 -0.015998 0.012438 -vn -0.129687 -0.450157 0.883482 -v -0.101196 -0.015429 0.012787 -vn 0.129687 -0.450157 0.883482 -v -0.096796 -0.015429 0.012787 -vn -0.129688 -0.306407 0.943025 -v -0.101196 -0.014813 0.013042 -vn 0.129688 -0.306407 0.943025 -v -0.096796 -0.014813 0.013042 -vn -0.129688 -0.155113 0.979347 -v -0.101196 -0.014165 0.013198 -vn 0.129688 -0.155113 0.979347 -v -0.096796 -0.014165 0.013198 -vn -0.129688 -0.000000 0.991555 -v -0.101196 -0.013500 0.013250 -vn 0.129688 0.000000 0.991555 -v -0.096796 -0.013500 0.013250 -vn -0.129688 0.155114 0.979347 -v -0.101196 -0.012835 0.013198 -vn 0.129688 0.155113 0.979347 -v -0.096796 -0.012835 0.013198 -vn -0.129688 0.306407 0.943025 -v -0.101196 -0.012187 0.013042 -vn 0.129688 0.306407 0.943025 -v -0.096796 -0.012187 0.013042 -vn -0.129688 0.450156 0.883482 -v -0.101196 -0.011571 0.012787 -vn 0.129688 0.450156 0.883482 -v -0.096796 -0.011571 0.012787 -vn -0.129687 0.582822 0.802185 -v -0.101196 -0.011002 0.012438 -vn 0.129687 0.582822 0.802185 -v -0.096796 -0.011002 0.012438 -vn -0.129688 0.701135 0.701135 -v -0.101196 -0.010495 0.012005 -vn 0.129688 0.701135 0.701135 -v -0.096796 -0.010495 0.012005 -vn -0.129687 0.802185 0.582822 -v -0.101196 -0.010062 0.011498 -vn 0.129687 0.802185 0.582822 -v -0.096796 -0.010062 0.011498 -vn -0.129688 0.883482 0.450156 -v -0.101196 -0.009713 0.010929 -vn 0.129688 0.883482 0.450156 -v -0.096796 -0.009713 0.010929 -vn -0.129688 0.943025 0.306407 -v -0.101196 -0.009458 0.010313 -vn 0.129688 0.943025 0.306407 -v -0.096796 -0.009458 0.010313 -vn 0.990579 0.096832 -0.096832 -v -0.096496 -0.010707 0.006207 -vn 0.990579 0.110788 -0.080492 -v -0.096496 -0.010304 0.006678 -vn 0.757034 0.437193 -0.485552 -v -0.096496 -0.011827 0.007142 -vn 0.757034 0.596888 -0.265752 -v -0.096496 -0.011216 0.007983 -vn 0.990579 -0.021422 -0.135255 -v -0.096496 -0.014118 0.005099 -vn 0.757035 -0.068296 -0.649796 -v -0.096496 -0.013761 0.006514 -vn 0.990579 -0.042317 -0.130239 -v -0.096496 -0.014721 0.005243 -vn 0.757035 -0.326687 -0.565839 -v -0.096496 -0.014750 0.006835 -vn 0.990579 -0.062170 -0.122016 -v -0.096496 -0.015293 0.005481 -vn 0.990579 -0.080492 -0.110788 -v -0.096496 -0.015822 0.005804 -vn 0.990579 0.122016 -0.062170 -v -0.096496 -0.009981 0.007207 -vn 0.990579 0.130239 -0.042317 -v -0.096496 -0.009743 0.007779 -vn 0.757034 0.653375 -0.000000 -v -0.096496 -0.011000 0.009000 -vn 0.990579 0.135255 -0.021422 -v -0.096496 -0.009599 0.008382 -vn 0.990579 0.136941 0.000000 -v -0.096496 -0.009550 0.009000 -vn 0.990579 0.000000 -0.136941 -v -0.096496 -0.013500 0.005050 -vn 0.990579 0.021422 -0.135256 -v -0.096496 -0.012882 0.005099 -vn 0.757034 0.201904 -0.621397 -v -0.096496 -0.012727 0.006622 -vn 0.990579 -0.096832 -0.096832 -v -0.096496 -0.016293 0.006207 -vn 0.757035 -0.528591 -0.384044 -v -0.096496 -0.015523 0.007531 -vn 0.990579 -0.110788 -0.080492 -v -0.096496 -0.016696 0.006678 -vn 0.990579 -0.136941 -0.000000 -v -0.096496 -0.017450 0.009000 -vn 0.757034 -0.639097 -0.135844 -v -0.096496 -0.015945 0.008480 -vn 0.757034 -0.639097 0.135844 -v -0.096496 -0.015945 0.009520 -vn 0.990579 0.096832 0.096832 -v -0.096496 -0.010707 0.011793 -vn 0.757034 0.437193 0.485552 -v -0.096496 -0.011827 0.010858 -vn 0.990579 0.110788 0.080492 -v -0.096496 -0.010304 0.011322 -vn 0.757034 0.596888 0.265752 -v -0.096496 -0.011216 0.010017 -vn 0.990579 0.042317 -0.130239 -v -0.096496 -0.012279 0.005243 -vn 0.990579 0.062170 -0.122016 -v -0.096496 -0.011707 0.005481 -vn 0.990579 0.080492 -0.110788 -v -0.096496 -0.011178 0.005804 -vn 0.990579 -0.135256 -0.021422 -v -0.096496 -0.017401 0.008382 -vn 0.990579 -0.130239 -0.042317 -v -0.096496 -0.017257 0.007779 -vn 0.990579 -0.122015 -0.062170 -v -0.096496 -0.017019 0.007207 -vn 0.990579 0.021422 0.135255 -v -0.096496 -0.012882 0.012901 -vn 0.990579 -0.000000 0.136941 -v -0.096496 -0.013500 0.012950 -vn 0.757034 0.201904 0.621397 -v -0.096496 -0.012727 0.011378 -vn 0.757034 -0.068296 0.649796 -v -0.096496 -0.013761 0.011486 -vn 0.990579 0.080492 0.110788 -v -0.096496 -0.011178 0.012196 -vn 0.990579 0.062170 0.122016 -v -0.096496 -0.011707 0.012519 -vn 0.990579 0.042317 0.130239 -v -0.096496 -0.012279 0.012757 -vn 0.990579 0.135255 0.021422 -v -0.096496 -0.009599 0.009618 -vn 0.990579 0.130239 0.042317 -v -0.096496 -0.009743 0.010221 -vn 0.990579 0.122016 0.062170 -v -0.096496 -0.009981 0.010793 -vn 0.990579 -0.110787 0.080492 -v -0.096496 -0.016696 0.011322 -vn 0.990579 -0.122015 0.062170 -v -0.096496 -0.017019 0.010793 -vn 0.757035 -0.528592 0.384043 -v -0.096496 -0.015523 0.010469 -vn 0.990579 -0.130239 0.042317 -v -0.096496 -0.017257 0.010221 -vn 0.990579 -0.135256 0.021422 -v -0.096496 -0.017401 0.009618 -vn 0.990579 -0.096832 0.096832 -v -0.096496 -0.016293 0.011793 -vn 0.757035 -0.326688 0.565839 -v -0.096496 -0.014750 0.011165 -vn 0.990579 -0.080492 0.110788 -v -0.096496 -0.015822 0.012196 -vn 0.990579 -0.021422 0.135255 -v -0.096496 -0.014118 0.012901 -vn 0.990579 -0.042317 0.130239 -v -0.096496 -0.014721 0.012757 -vn 0.990579 -0.062170 0.122016 -v -0.096496 -0.015293 0.012519 -vn 0.663167 0.748472 0.000000 -v -0.095496 -0.011000 0.009000 -vn 0.663167 0.683763 0.304431 -v -0.095496 -0.011216 0.010017 -vn 0.663166 0.500825 0.556223 -v -0.095496 -0.011827 0.010858 -vn 0.663167 0.231291 0.711839 -v -0.095496 -0.012727 0.011378 -vn 0.663167 -0.078236 0.744372 -v -0.095496 -0.013761 0.011486 -vn 0.663167 -0.374236 0.648196 -v -0.095496 -0.014750 0.011165 -vn 0.663167 -0.605526 0.439940 -v -0.095496 -0.015523 0.010469 -vn 0.663167 -0.732116 0.155616 -v -0.095496 -0.015945 0.009520 -vn 0.663167 -0.732116 -0.155616 -v -0.095496 -0.015945 0.008480 -vn 0.663167 -0.605526 -0.439940 -v -0.095496 -0.015523 0.007531 -vn 0.663167 -0.374236 -0.648195 -v -0.095496 -0.014750 0.006835 -vn 0.663167 -0.078236 -0.744371 -v -0.095496 -0.013761 0.006514 -vn 0.663167 0.231291 -0.711839 -v -0.095496 -0.012727 0.006622 -vn 0.663167 0.500825 -0.556223 -v -0.095496 -0.011827 0.007142 -vn 0.663167 0.683763 -0.304431 -v -0.095496 -0.011216 0.007983 -vn 0.756608 -0.639580 0.135947 -v -0.095496 -0.015750 0.009478 -vn 0.756608 -0.639580 -0.135947 -v -0.095496 -0.015750 0.008522 -vn 0.756608 -0.528991 -0.384334 -v -0.095496 -0.015361 0.007648 -vn 0.756608 -0.326934 -0.566267 -v -0.095496 -0.014650 0.007008 -vn 0.756608 -0.068348 -0.650286 -v -0.095496 -0.013740 0.006713 -vn 0.756608 0.202056 -0.621866 -v -0.095496 -0.012789 0.006813 -vn 0.756608 0.437523 -0.485919 -v -0.095496 -0.011961 0.007291 -vn 0.756608 0.597339 -0.265952 -v -0.095496 -0.011399 0.008065 -vn 0.756608 0.653868 -0.000000 -v -0.095496 -0.011200 0.009000 -vn 0.756608 0.597339 0.265952 -v -0.095496 -0.011399 0.009935 -vn 0.756608 0.437523 0.485919 -v -0.095496 -0.011961 0.010709 -vn 0.756608 0.202056 0.621866 -v -0.095496 -0.012789 0.011187 -vn 0.756608 -0.068348 0.650286 -v -0.095496 -0.013740 0.011287 -vn 0.756608 -0.326934 0.566267 -v -0.095496 -0.014650 0.010992 -vn 0.756608 -0.528991 0.384334 -v -0.095496 -0.015361 0.010352 -vn 0.373956 0.907179 -0.192827 -v -0.056996 -0.011250 0.008522 -vn 0.379295 0.845281 -0.376344 -v -0.056996 -0.011399 0.008065 -vn 0.373956 0.750320 -0.545139 -v -0.056996 -0.011639 0.007648 -vn 0.379295 0.619131 -0.687614 -v -0.056996 -0.011961 0.007291 -vn 0.373956 0.463723 -0.803192 -v -0.056996 -0.012350 0.007008 -vn 0.379295 0.285926 -0.879990 -v -0.056996 -0.012789 0.006813 -vn 0.373956 0.096945 -0.922366 -v -0.056996 -0.013260 0.006713 -vn 0.379295 -0.096718 -0.920207 -v -0.056996 -0.013740 0.006713 -vn 0.373956 -0.286596 -0.882054 -v -0.056996 -0.014211 0.006813 -vn 0.379295 -0.462638 -0.801313 -v -0.056996 -0.014650 0.007008 -vn 0.373956 -0.620583 -0.689227 -v -0.056996 -0.015039 0.007291 -vn 0.379295 -0.748564 -0.543864 -v -0.056996 -0.015361 0.007648 -vn 0.373956 -0.847265 -0.377226 -v -0.056996 -0.015601 0.008065 -vn 0.379294 -0.905057 -0.192374 -v -0.056996 -0.015750 0.008522 -vn 0.373955 -0.927447 0.000000 -v -0.056996 -0.015800 0.009000 -vn 0.379294 -0.905057 0.192374 -v -0.056996 -0.015750 0.009478 -vn 0.373956 -0.847265 0.377225 -v -0.056996 -0.015601 0.009935 -vn 0.379295 -0.748564 0.543863 -v -0.056996 -0.015361 0.010352 -vn 0.373956 -0.620583 0.689227 -v -0.056996 -0.015039 0.010709 -vn 0.379295 -0.462637 0.801313 -v -0.056996 -0.014650 0.010992 -vn 0.373956 -0.286597 0.882054 -v -0.056996 -0.014211 0.011187 -vn 0.379295 -0.096718 0.920207 -v -0.056996 -0.013740 0.011287 -vn 0.373956 0.096945 0.922366 -v -0.056996 -0.013260 0.011287 -vn 0.379295 0.285926 0.879990 -v -0.056996 -0.012789 0.011187 -vn 0.373956 0.463722 0.803192 -v -0.056996 -0.012350 0.010992 -vn 0.379295 0.619130 0.687614 -v -0.056996 -0.011961 0.010709 -vn 0.373956 0.750320 0.545139 -v -0.056996 -0.011639 0.010352 -vn 0.379295 0.845282 0.376343 -v -0.056996 -0.011399 0.009935 -vn 0.373956 0.907179 0.192827 -v -0.056996 -0.011250 0.009478 -vn 0.379295 0.925276 -0.000000 -v -0.056996 -0.011200 0.009000 -vn 0.912392 -0.273887 0.304183 -v -0.056496 -0.014704 0.010338 -vn 0.912392 -0.373931 0.166484 -v -0.056496 -0.015144 0.009732 -vn 1.000000 0.000000 0.000000 -v -0.056496 -0.013500 0.009000 -vn 0.912391 -0.409319 -0.000000 -v -0.056496 -0.015300 0.009000 -vn 0.912392 -0.373931 -0.166485 -v -0.056496 -0.015144 0.008268 -vn 0.912392 0.204659 0.354480 -v -0.056496 -0.012600 0.010559 -vn 0.912392 0.042786 0.407076 -v -0.056496 -0.013312 0.010790 -vn 0.912392 -0.126486 0.389285 -v -0.056496 -0.014056 0.010712 -vn 0.912392 0.400374 -0.085102 -v -0.056496 -0.011739 0.008626 -vn 0.912392 0.400374 0.085102 -v -0.056496 -0.011739 0.009374 -vn 0.912392 0.331145 0.240591 -v -0.056496 -0.012044 0.010058 -vn 0.912392 0.042785 -0.407076 -v -0.056496 -0.013312 0.007210 -vn 0.912392 0.204659 -0.354480 -v -0.056496 -0.012600 0.007441 -vn 0.912392 0.331145 -0.240592 -v -0.056496 -0.012044 0.007942 -vn 0.912392 -0.273887 -0.304183 -v -0.056496 -0.014704 0.007662 -vn 0.912392 -0.126486 -0.389285 -v -0.056496 -0.014056 0.007288 -vn -0.609994 -0.792406 0.000000 -v -0.097496 -0.011191 0.009000 -vn -0.609994 -0.396203 -0.686244 -v -0.097496 -0.012345 0.011000 -vn -0.609994 0.396203 -0.686243 -v -0.097496 -0.014655 0.011000 -vn -0.609994 0.792406 0.000000 -v -0.097496 -0.015809 0.009000 -vn -0.609994 0.396203 0.686244 -v -0.097496 -0.014655 0.007000 -vn -0.609994 -0.396203 0.686244 -v -0.097496 -0.012345 0.007000 -vn 0.494480 -0.858488 0.135972 -v -0.096646 -0.017658 0.009659 -vn 0.494480 -0.826648 0.268594 -v -0.096646 -0.017504 0.010301 -vn 0.494480 -0.774453 0.394603 -v -0.096646 -0.017251 0.010911 -vn 0.494483 -0.703187 0.510896 -v -0.096646 -0.016906 0.011474 -vn 0.494481 -0.614609 0.614609 -v -0.096646 -0.016477 0.011977 -vn 0.494484 -0.510896 0.703187 -v -0.096646 -0.015974 0.012406 -vn 0.494481 -0.394604 0.774452 -v -0.096646 -0.015411 0.012751 -vn 0.494481 -0.268594 0.826648 -v -0.096646 -0.014801 0.013004 -vn 0.494481 -0.135971 0.858487 -v -0.096646 -0.014159 0.013158 -vn 0.494481 -0.000000 0.869189 -v -0.096646 -0.013500 0.013210 -vn 0.494481 0.135971 0.858487 -v -0.096646 -0.012841 0.013158 -vn 0.494480 0.268594 0.826648 -v -0.096646 -0.012199 0.013004 -vn 0.494482 0.394603 0.774453 -v -0.096646 -0.011589 0.012751 -vn 0.494481 0.510896 0.703188 -v -0.096646 -0.011026 0.012406 -vn 0.494480 0.614609 0.614609 -v -0.096646 -0.010523 0.011977 -vn 0.494481 0.703188 0.510896 -v -0.096646 -0.010094 0.011474 -vn 0.494481 0.774453 0.394603 -v -0.096646 -0.009749 0.010911 -vn 0.494480 0.826648 0.268594 -v -0.096646 -0.009496 0.010301 -vn 0.494481 0.858487 0.135971 -v -0.096646 -0.009342 0.009659 -vn 0.494481 0.869189 -0.000000 -v -0.096646 -0.009290 0.009000 -vn 0.494481 0.858488 -0.135971 -v -0.096646 -0.009342 0.008341 -vn 0.494481 0.826647 -0.268594 -v -0.096646 -0.009496 0.007699 -vn 0.494481 0.774453 -0.394603 -v -0.096646 -0.009749 0.007089 -vn 0.494482 0.703188 -0.510896 -v -0.096646 -0.010094 0.006526 -vn 0.494481 0.614609 -0.614609 -v -0.096646 -0.010523 0.006023 -vn 0.494481 0.510896 -0.703188 -v -0.096646 -0.011026 0.005594 -vn 0.494481 0.394603 -0.774453 -v -0.096646 -0.011589 0.005249 -vn 0.494481 0.268594 -0.826647 -v -0.096646 -0.012199 0.004996 -vn 0.494481 0.135971 -0.858488 -v -0.096646 -0.012841 0.004842 -vn 0.494482 0.000000 -0.869188 -v -0.096646 -0.013500 0.004790 -vn 0.494480 -0.135971 -0.858488 -v -0.096646 -0.014159 0.004842 -vn 0.494482 -0.268594 -0.826647 -v -0.096646 -0.014801 0.004996 -vn 0.494480 -0.394604 -0.774453 -v -0.096646 -0.015411 0.005249 -vn 0.494483 -0.510896 -0.703187 -v -0.096646 -0.015974 0.005594 -vn 0.494482 -0.614609 -0.614609 -v -0.096646 -0.016477 0.006023 -vn 0.494483 -0.703187 -0.510896 -v -0.096646 -0.016906 0.006526 -vn 0.494480 -0.774453 -0.394603 -v -0.096646 -0.017251 0.007089 -vn 0.494481 -0.826647 -0.268594 -v -0.096646 -0.017504 0.007699 -vn 0.494480 -0.858488 -0.135972 -v -0.096646 -0.017658 0.008341 -vn 0.494482 -0.869188 -0.000000 -v -0.096646 -0.017710 0.009000 -vn 0.860420 -0.503312 0.079717 -v -0.096536 -0.017550 0.009641 -vn 0.860419 -0.484647 0.157472 -v -0.096536 -0.017399 0.010267 -vn 0.860419 -0.454045 0.231348 -v -0.096536 -0.017153 0.010861 -vn 0.860419 -0.412265 0.299529 -v -0.096536 -0.016817 0.011410 -vn 0.860419 -0.360332 0.360332 -v -0.096536 -0.016399 0.011899 -vn 0.860419 -0.299528 0.412264 -v -0.096536 -0.015910 0.012317 -vn 0.860420 -0.231348 0.454044 -v -0.096536 -0.015361 0.012653 -vn 0.860419 -0.157471 0.484647 -v -0.096536 -0.014767 0.012899 -vn 0.860419 -0.079717 0.503314 -v -0.096536 -0.014141 0.013050 -vn 0.860419 -0.000000 0.509587 -v -0.096536 -0.013500 0.013100 -vn 0.860419 0.079717 0.503313 -v -0.096536 -0.012859 0.013050 -vn 0.860418 0.157472 0.484647 -v -0.096536 -0.012233 0.012899 -vn 0.860419 0.231348 0.454045 -v -0.096536 -0.011639 0.012653 -vn 0.860420 0.299527 0.412263 -v -0.096536 -0.011090 0.012317 -vn 0.860419 0.360333 0.360333 -v -0.096536 -0.010601 0.011899 -vn 0.860420 0.412263 0.299527 -v -0.096536 -0.010183 0.011410 -vn 0.860420 0.454045 0.231348 -v -0.096536 -0.009847 0.010861 -vn 0.860418 0.484647 0.157471 -v -0.096536 -0.009601 0.010267 -vn 0.860419 0.503314 0.079717 -v -0.096536 -0.009450 0.009641 -vn 0.860419 0.509587 0.000000 -v -0.096536 -0.009400 0.009000 -vn 0.860419 0.503314 -0.079717 -v -0.096536 -0.009450 0.008359 -vn 0.860419 0.484647 -0.157472 -v -0.096536 -0.009601 0.007733 -vn 0.860420 0.454045 -0.231347 -v -0.096536 -0.009847 0.007139 -vn 0.860420 0.412264 -0.299527 -v -0.096536 -0.010183 0.006590 -vn 0.860419 0.360333 -0.360333 -v -0.096536 -0.010601 0.006101 -vn 0.860420 0.299528 -0.412264 -v -0.096536 -0.011090 0.005683 -vn 0.860419 0.231348 -0.454045 -v -0.096536 -0.011639 0.005347 -vn 0.860419 0.157471 -0.484646 -v -0.096536 -0.012233 0.005101 -vn 0.860419 0.079717 -0.503313 -v -0.096536 -0.012859 0.004950 -vn 0.860419 -0.000000 -0.509587 -v -0.096536 -0.013500 0.004900 -vn 0.860419 -0.079717 -0.503313 -v -0.096536 -0.014141 0.004950 -vn 0.860419 -0.157471 -0.484646 -v -0.096536 -0.014767 0.005101 -vn 0.860420 -0.231348 -0.454045 -v -0.096536 -0.015361 0.005347 -vn 0.860419 -0.299528 -0.412264 -v -0.096536 -0.015910 0.005683 -vn 0.860420 -0.360332 -0.360332 -v -0.096536 -0.016399 0.006101 -vn 0.860419 -0.412266 -0.299528 -v -0.096536 -0.016817 0.006590 -vn 0.860419 -0.454045 -0.231348 -v -0.096536 -0.017153 0.007139 -vn 0.860419 -0.484647 -0.157471 -v -0.096536 -0.017399 0.007733 -vn 0.860420 -0.503313 -0.079717 -v -0.096536 -0.017550 0.008359 -vn 0.860420 -0.509585 -0.000000 -v -0.096536 -0.017600 0.009000 -vn -0.494481 0.858487 0.135971 -v -0.101346 -0.009342 0.009659 -vn -0.494480 0.826648 0.268594 -v -0.101346 -0.009496 0.010301 -vn -0.494482 0.774453 0.394603 -v -0.101346 -0.009749 0.010911 -vn -0.494481 0.703188 0.510896 -v -0.101346 -0.010094 0.011474 -vn -0.494480 0.614609 0.614609 -v -0.101346 -0.010523 0.011977 -vn -0.494481 0.510896 0.703188 -v -0.101346 -0.011026 0.012406 -vn -0.494481 0.394603 0.774453 -v -0.101346 -0.011589 0.012751 -vn -0.494480 0.268594 0.826648 -v -0.101346 -0.012199 0.013004 -vn -0.494481 0.135971 0.858487 -v -0.101346 -0.012841 0.013158 -vn -0.494481 -0.000000 0.869189 -v -0.101346 -0.013500 0.013210 -vn -0.494481 -0.135971 0.858488 -v -0.101346 -0.014159 0.013158 -vn -0.494481 -0.268594 0.826647 -v -0.101346 -0.014801 0.013004 -vn -0.494481 -0.394604 0.774452 -v -0.101346 -0.015411 0.012751 -vn -0.494483 -0.510896 0.703187 -v -0.101346 -0.015974 0.012406 -vn -0.494481 -0.614609 0.614609 -v -0.101346 -0.016477 0.011977 -vn -0.494483 -0.703187 0.510896 -v -0.101346 -0.016906 0.011474 -vn -0.494480 -0.774453 0.394603 -v -0.101346 -0.017251 0.010911 -vn -0.494480 -0.826648 0.268594 -v -0.101346 -0.017504 0.010301 -vn -0.494480 -0.858488 0.135972 -v -0.101346 -0.017658 0.009659 -vn -0.494482 -0.869188 0.000000 -v -0.101346 -0.017710 0.009000 -vn -0.494480 -0.858488 -0.135972 -v -0.101346 -0.017658 0.008341 -vn -0.494480 -0.826648 -0.268594 -v -0.101346 -0.017504 0.007699 -vn -0.494479 -0.774454 -0.394604 -v -0.101346 -0.017251 0.007089 -vn -0.494483 -0.703187 -0.510896 -v -0.101346 -0.016906 0.006526 -vn -0.494481 -0.614609 -0.614609 -v -0.101346 -0.016477 0.006023 -vn -0.494482 -0.510896 -0.703188 -v -0.101346 -0.015974 0.005594 -vn -0.494479 -0.394604 -0.774453 -v -0.101346 -0.015411 0.005249 -vn -0.494480 -0.268594 -0.826648 -v -0.101346 -0.014801 0.004996 -vn -0.494479 -0.135971 -0.858489 -v -0.101346 -0.014159 0.004842 -vn -0.494481 -0.000000 -0.869189 -v -0.101346 -0.013500 0.004790 -vn -0.494479 0.135971 -0.858488 -v -0.101346 -0.012841 0.004842 -vn -0.494480 0.268594 -0.826648 -v -0.101346 -0.012199 0.004996 -vn -0.494480 0.394603 -0.774453 -v -0.101346 -0.011589 0.005249 -vn -0.494480 0.510897 -0.703189 -v -0.101346 -0.011026 0.005594 -vn -0.494480 0.614610 -0.614610 -v -0.101346 -0.010523 0.006023 -vn -0.494481 0.703188 -0.510896 -v -0.101346 -0.010094 0.006526 -vn -0.494481 0.774453 -0.394603 -v -0.101346 -0.009749 0.007089 -vn -0.494480 0.826648 -0.268594 -v -0.101346 -0.009496 0.007699 -vn -0.494481 0.858487 -0.135971 -v -0.101346 -0.009342 0.008341 -vn -0.494481 0.869189 -0.000000 -v -0.101346 -0.009290 0.009000 -vn -0.860419 0.503313 0.079717 -v -0.101456 -0.009450 0.009641 -vn -0.860418 0.484647 0.157472 -v -0.101456 -0.009601 0.010267 -vn -0.860419 0.454045 0.231348 -v -0.101456 -0.009847 0.010861 -vn -0.860420 0.412263 0.299527 -v -0.101456 -0.010183 0.011410 -vn -0.860419 0.360333 0.360333 -v -0.101456 -0.010601 0.011899 -vn -0.860420 0.299527 0.412263 -v -0.101456 -0.011090 0.012317 -vn -0.860420 0.231348 0.454045 -v -0.101456 -0.011639 0.012653 -vn -0.860419 0.157471 0.484647 -v -0.101456 -0.012233 0.012899 -vn -0.860419 0.079717 0.503314 -v -0.101456 -0.012859 0.013050 -vn -0.860419 0.000000 0.509587 -v -0.101456 -0.013500 0.013100 -vn -0.860419 -0.079717 0.503314 -v -0.101456 -0.014141 0.013050 -vn -0.860419 -0.157471 0.484647 -v -0.101456 -0.014767 0.012899 -vn -0.860420 -0.231347 0.454044 -v -0.101456 -0.015361 0.012653 -vn -0.860420 -0.299528 0.412264 -v -0.101456 -0.015910 0.012317 -vn -0.860419 -0.360332 0.360332 -v -0.101456 -0.016399 0.011899 -vn -0.860419 -0.412265 0.299528 -v -0.101456 -0.016817 0.011410 -vn -0.860419 -0.454045 0.231348 -v -0.101456 -0.017153 0.010861 -vn -0.860418 -0.484647 0.157471 -v -0.101456 -0.017399 0.010267 -vn -0.860420 -0.503312 0.079717 -v -0.101456 -0.017550 0.009641 -vn -0.860420 -0.509585 0.000000 -v -0.101456 -0.017600 0.009000 -vn -0.860420 -0.503312 -0.079717 -v -0.101456 -0.017550 0.008359 -vn -0.860419 -0.484646 -0.157471 -v -0.101456 -0.017399 0.007733 -vn -0.860419 -0.454045 -0.231347 -v -0.101456 -0.017153 0.007139 -vn -0.860418 -0.412265 -0.299529 -v -0.101456 -0.016817 0.006590 -vn -0.860420 -0.360332 -0.360332 -v -0.101456 -0.016399 0.006101 -vn -0.860419 -0.299528 -0.412265 -v -0.101456 -0.015910 0.005683 -vn -0.860420 -0.231348 -0.454044 -v -0.101456 -0.015361 0.005347 -vn -0.860419 -0.157471 -0.484646 -v -0.101456 -0.014767 0.005101 -vn -0.860419 -0.079717 -0.503313 -v -0.101456 -0.014141 0.004950 -vn -0.860419 0.000000 -0.509587 -v -0.101456 -0.013500 0.004900 -vn -0.860419 0.079717 -0.503313 -v -0.101456 -0.012859 0.004950 -vn -0.860419 0.157471 -0.484646 -v -0.101456 -0.012233 0.005101 -vn -0.860419 0.231348 -0.454045 -v -0.101456 -0.011639 0.005347 -vn -0.860420 0.299527 -0.412264 -v -0.101456 -0.011090 0.005683 -vn -0.860419 0.360333 -0.360332 -v -0.101456 -0.010601 0.006101 -vn -0.860420 0.412263 -0.299527 -v -0.101456 -0.010183 0.006590 -vn -0.860420 0.454044 -0.231347 -v -0.101456 -0.009847 0.007139 -vn -0.860419 0.484647 -0.157471 -v -0.101456 -0.009601 0.007733 -vn -0.860419 0.503314 -0.079717 -v -0.101456 -0.009450 0.008359 -vn -0.860419 0.509587 -0.000000 -v -0.101456 -0.009400 0.009000 -vn -0.990579 -0.080492 0.110788 -v -0.101496 0.011178 0.012196 -vn -0.990579 -0.062170 0.122016 -v -0.101496 0.011707 0.012519 -vn -0.838628 0.272352 -0.471728 -v -0.101496 0.012345 0.011000 -vn -0.990579 0.080492 -0.110788 -v -0.101496 0.015822 0.005804 -vn -0.990579 0.062170 -0.122016 -v -0.101496 0.015293 0.005481 -vn -0.838628 -0.272352 0.471728 -v -0.101496 0.014655 0.007000 -vn -0.990579 -0.021422 -0.135256 -v -0.101496 0.012882 0.005099 -vn -0.990579 -0.042317 -0.130239 -v -0.101496 0.012279 0.005243 -vn -0.838628 0.272352 0.471728 -v -0.101496 0.012345 0.007000 -vn -0.990579 -0.062170 -0.122016 -v -0.101496 0.011707 0.005481 -vn -0.990579 -0.080492 -0.110788 -v -0.101496 0.011178 0.005804 -vn -0.990579 0.135256 0.021422 -v -0.101496 0.017401 0.009618 -vn -0.990579 0.136941 -0.000000 -v -0.101496 0.017450 0.009000 -vn -0.838628 -0.544705 0.000000 -v -0.101496 0.015809 0.009000 -vn -0.990579 0.135256 -0.021422 -v -0.101496 0.017401 0.008382 -vn -0.990579 0.096832 -0.096832 -v -0.101496 0.016293 0.006207 -vn -0.990579 0.021422 0.135255 -v -0.101496 0.014118 0.012901 -vn -0.990579 0.042317 0.130239 -v -0.101496 0.014721 0.012757 -vn -0.838628 -0.272352 -0.471728 -v -0.101496 0.014655 0.011000 -vn -0.838628 0.544705 0.000000 -v -0.101496 0.011191 0.009000 -vn -0.990579 -0.135255 0.021422 -v -0.101496 0.009599 0.009618 -vn -0.990579 -0.130239 0.042317 -v -0.101496 0.009743 0.010221 -vn -0.990579 -0.130239 -0.042317 -v -0.101496 0.009743 0.007779 -vn -0.990579 -0.135255 -0.021422 -v -0.101496 0.009599 0.008382 -vn -0.990579 -0.136941 0.000000 -v -0.101496 0.009550 0.009000 -vn -0.990579 0.130239 -0.042317 -v -0.101496 0.017257 0.007779 -vn -0.990579 0.122015 -0.062170 -v -0.101496 0.017019 0.007207 -vn -0.990579 0.110788 -0.080492 -v -0.101496 0.016696 0.006678 -vn -0.990579 0.062170 0.122016 -v -0.101496 0.015293 0.012519 -vn -0.990579 0.080492 0.110788 -v -0.101496 0.015822 0.012196 -vn -0.990579 0.096832 0.096832 -v -0.101496 0.016293 0.011793 -vn -0.990579 -0.122016 0.062170 -v -0.101496 0.009981 0.010793 -vn -0.990579 -0.110788 0.080492 -v -0.101496 0.010304 0.011322 -vn -0.990579 -0.096832 0.096832 -v -0.101496 0.010707 0.011793 -vn -0.990579 0.042317 -0.130239 -v -0.101496 0.014721 0.005243 -vn -0.990579 0.021422 -0.135255 -v -0.101496 0.014118 0.005099 -vn -0.990579 -0.000000 -0.136941 -v -0.101496 0.013500 0.005050 -vn -0.990579 0.110787 0.080492 -v -0.101496 0.016696 0.011322 -vn -0.990579 0.122015 0.062170 -v -0.101496 0.017019 0.010793 -vn -0.990579 0.130239 0.042317 -v -0.101496 0.017257 0.010221 -vn -0.990579 -0.042317 0.130239 -v -0.101496 0.012279 0.012757 -vn -0.990579 -0.021422 0.135255 -v -0.101496 0.012882 0.012901 -vn -0.990579 0.000000 0.136941 -v -0.101496 0.013500 0.012950 -vn -0.990579 -0.096832 -0.096832 -v -0.101496 0.010707 0.006207 -vn -0.990579 -0.110788 -0.080492 -v -0.101496 0.010304 0.006678 -vn -0.990579 -0.122016 -0.062170 -v -0.101496 0.009981 0.007207 -vn -0.129686 0.979347 0.155114 -v -0.101196 0.017698 0.009665 -vn 0.129686 0.979347 0.155114 -v -0.096796 0.017698 0.009665 -vn -0.129687 0.991555 -0.000000 -v -0.101196 0.017750 0.009000 -vn 0.129687 0.991555 0.000000 -v -0.096796 0.017750 0.009000 -vn -0.129686 0.979347 -0.155114 -v -0.101196 0.017698 0.008335 -vn 0.129686 0.979347 -0.155115 -v -0.096796 0.017698 0.008335 -vn -0.129688 0.943025 -0.306408 -v -0.101196 0.017542 0.007687 -vn 0.129688 0.943025 -0.306407 -v -0.096796 0.017542 0.007687 -vn -0.129686 0.883483 -0.450156 -v -0.101196 0.017287 0.007071 -vn 0.129687 0.883482 -0.450156 -v -0.096796 0.017287 0.007071 -vn -0.129691 0.802184 -0.582821 -v -0.101196 0.016938 0.006502 -vn 0.129692 0.802185 -0.582820 -v -0.096796 0.016938 0.006502 -vn -0.129687 0.701135 -0.701135 -v -0.101196 0.016505 0.005995 -vn 0.129688 0.701135 -0.701136 -v -0.096796 0.016505 0.005995 -vn -0.129689 0.582821 -0.802185 -v -0.101196 0.015998 0.005562 -vn 0.129690 0.582821 -0.802184 -v -0.096796 0.015998 0.005562 -vn -0.129685 0.450157 -0.883482 -v -0.101196 0.015429 0.005213 -vn 0.129687 0.450156 -0.883482 -v -0.096796 0.015429 0.005213 -vn -0.129687 0.306407 -0.943025 -v -0.101196 0.014813 0.004958 -vn 0.129688 0.306407 -0.943025 -v -0.096796 0.014813 0.004958 -vn -0.129686 0.155114 -0.979347 -v -0.101196 0.014165 0.004802 -vn 0.129687 0.155113 -0.979347 -v -0.096796 0.014165 0.004802 -vn -0.129687 -0.000000 -0.991555 -v -0.101196 0.013500 0.004750 -vn 0.129689 0.000000 -0.991555 -v -0.096796 0.013500 0.004750 -vn -0.129686 -0.155113 -0.979347 -v -0.101196 0.012835 0.004802 -vn 0.129687 -0.155114 -0.979347 -v -0.096796 0.012835 0.004802 -vn -0.129687 -0.306407 -0.943025 -v -0.101196 0.012187 0.004958 -vn 0.129688 -0.306407 -0.943025 -v -0.096796 0.012187 0.004958 -vn -0.129686 -0.450157 -0.883482 -v -0.101196 0.011571 0.005213 -vn 0.129688 -0.450157 -0.883482 -v -0.096796 0.011571 0.005213 -vn -0.129686 -0.582821 -0.802185 -v -0.101196 0.011002 0.005562 -vn 0.129687 -0.582822 -0.802185 -v -0.096796 0.011002 0.005562 -vn -0.129687 -0.701135 -0.701135 -v -0.101196 0.010495 0.005995 -vn 0.129688 -0.701135 -0.701135 -v -0.096796 0.010495 0.005995 -vn -0.129687 -0.802185 -0.582822 -v -0.101196 0.010062 0.006502 -vn 0.129688 -0.802185 -0.582822 -v -0.096796 0.010062 0.006502 -vn -0.129686 -0.883482 -0.450156 -v -0.101196 0.009713 0.007071 -vn 0.129687 -0.883482 -0.450156 -v -0.096796 0.009713 0.007071 -vn -0.129688 -0.943025 -0.306407 -v -0.101196 0.009458 0.007687 -vn 0.129688 -0.943025 -0.306407 -v -0.096796 0.009458 0.007687 -vn -0.129688 -0.979347 -0.155114 -v -0.101196 0.009302 0.008335 -vn 0.129688 -0.979347 -0.155114 -v -0.096796 0.009302 0.008335 -vn -0.129688 -0.991555 -0.000000 -v -0.101196 0.009250 0.009000 -vn 0.129688 -0.991555 0.000000 -v -0.096796 0.009250 0.009000 -vn -0.129688 -0.979347 0.155114 -v -0.101196 0.009302 0.009665 -vn 0.129688 -0.979347 0.155113 -v -0.096796 0.009302 0.009665 -vn -0.129688 -0.943025 0.306407 -v -0.101196 0.009458 0.010313 -vn 0.129688 -0.943025 0.306407 -v -0.096796 0.009458 0.010313 -vn -0.129688 -0.883482 0.450156 -v -0.101196 0.009713 0.010929 -vn 0.129688 -0.883482 0.450156 -v -0.096796 0.009713 0.010929 -vn -0.129687 -0.802185 0.582822 -v -0.101196 0.010062 0.011498 -vn 0.129687 -0.802185 0.582822 -v -0.096796 0.010062 0.011498 -vn -0.129688 -0.701135 0.701135 -v -0.101196 0.010495 0.012005 -vn 0.129688 -0.701135 0.701135 -v -0.096796 0.010495 0.012005 -vn -0.129687 -0.582822 0.802185 -v -0.101196 0.011002 0.012438 -vn 0.129687 -0.582822 0.802185 -v -0.096796 0.011002 0.012438 -vn -0.129688 -0.450156 0.883482 -v -0.101196 0.011571 0.012787 -vn 0.129688 -0.450156 0.883482 -v -0.096796 0.011571 0.012787 -vn -0.129688 -0.306407 0.943025 -v -0.101196 0.012187 0.013042 -vn 0.129688 -0.306407 0.943025 -v -0.096796 0.012187 0.013042 -vn -0.129688 -0.155113 0.979347 -v -0.101196 0.012835 0.013198 -vn 0.129688 -0.155114 0.979347 -v -0.096796 0.012835 0.013198 -vn -0.129688 -0.000000 0.991555 -v -0.101196 0.013500 0.013250 -vn 0.129688 0.000000 0.991555 -v -0.096796 0.013500 0.013250 -vn -0.129688 0.155113 0.979347 -v -0.101196 0.014165 0.013198 -vn 0.129688 0.155113 0.979347 -v -0.096796 0.014165 0.013198 -vn -0.129688 0.306407 0.943025 -v -0.101196 0.014813 0.013042 -vn 0.129688 0.306407 0.943025 -v -0.096796 0.014813 0.013042 -vn -0.129687 0.450156 0.883482 -v -0.101196 0.015429 0.012787 -vn 0.129687 0.450156 0.883482 -v -0.096796 0.015429 0.012787 -vn -0.129690 0.582822 0.802184 -v -0.101196 0.015998 0.012438 -vn 0.129690 0.582821 0.802185 -v -0.096796 0.015998 0.012438 -vn -0.129688 0.701135 0.701135 -v -0.101196 0.016505 0.012005 -vn 0.129688 0.701135 0.701135 -v -0.096796 0.016505 0.012005 -vn -0.129691 0.802185 0.582820 -v -0.101196 0.016938 0.011498 -vn 0.129691 0.802184 0.582821 -v -0.096796 0.016938 0.011498 -vn -0.129688 0.883482 0.450156 -v -0.101196 0.017287 0.010929 -vn 0.129688 0.883482 0.450156 -v -0.096796 0.017287 0.010929 -vn -0.129688 0.943025 0.306407 -v -0.101196 0.017542 0.010313 -vn 0.129688 0.943025 0.306407 -v -0.096796 0.017542 0.010313 -vn 0.990579 0.096832 -0.096832 -v -0.096496 0.016293 0.006207 -vn 0.990579 0.110788 -0.080492 -v -0.096496 0.016696 0.006678 -vn 0.757034 0.437193 -0.485552 -v -0.096496 0.015173 0.007142 -vn 0.757034 0.596888 -0.265752 -v -0.096496 0.015784 0.007983 -vn 0.990579 -0.021422 -0.135256 -v -0.096496 0.012882 0.005099 -vn 0.757035 -0.068296 -0.649796 -v -0.096496 0.013239 0.006514 -vn 0.990579 -0.042317 -0.130239 -v -0.096496 0.012279 0.005243 -vn 0.757035 -0.326687 -0.565839 -v -0.096496 0.012250 0.006835 -vn 0.990579 -0.062170 -0.122016 -v -0.096496 0.011707 0.005481 -vn 0.990579 -0.080492 -0.110788 -v -0.096496 0.011178 0.005804 -vn 0.990579 0.122015 -0.062170 -v -0.096496 0.017019 0.007207 -vn 0.990579 0.130239 -0.042317 -v -0.096496 0.017257 0.007779 -vn 0.757035 0.653374 -0.000000 -v -0.096496 0.016000 0.009000 -vn 0.990579 0.135256 -0.021422 -v -0.096496 0.017401 0.008382 -vn 0.990579 0.136941 0.000000 -v -0.096496 0.017450 0.009000 -vn 0.990579 0.000000 -0.136941 -v -0.096496 0.013500 0.005050 -vn 0.990579 0.021422 -0.135255 -v -0.096496 0.014118 0.005099 -vn 0.757034 0.201904 -0.621397 -v -0.096496 0.014273 0.006622 -vn 0.990579 -0.096832 -0.096832 -v -0.096496 0.010707 0.006207 -vn 0.757035 -0.528591 -0.384044 -v -0.096496 0.011477 0.007531 -vn 0.990579 -0.110788 -0.080492 -v -0.096496 0.010304 0.006678 -vn 0.990579 -0.136941 -0.000000 -v -0.096496 0.009550 0.009000 -vn 0.757035 -0.639097 -0.135844 -v -0.096496 0.011055 0.008480 -vn 0.757035 -0.639097 0.135844 -v -0.096496 0.011055 0.009520 -vn 0.990579 0.096832 0.096832 -v -0.096496 0.016293 0.011793 -vn 0.757034 0.437193 0.485552 -v -0.096496 0.015173 0.010858 -vn 0.990579 0.110787 0.080492 -v -0.096496 0.016696 0.011322 -vn 0.757034 0.596888 0.265752 -v -0.096496 0.015784 0.010017 -vn 0.990579 0.042317 -0.130239 -v -0.096496 0.014721 0.005243 -vn 0.990579 0.062170 -0.122016 -v -0.096496 0.015293 0.005481 -vn 0.990579 0.080492 -0.110788 -v -0.096496 0.015822 0.005804 -vn 0.990579 -0.135255 -0.021422 -v -0.096496 0.009599 0.008382 -vn 0.990579 -0.130239 -0.042317 -v -0.096496 0.009743 0.007779 -vn 0.990579 -0.122016 -0.062170 -v -0.096496 0.009981 0.007207 -vn 0.990579 0.021422 0.135255 -v -0.096496 0.014118 0.012901 -vn 0.990579 -0.000000 0.136941 -v -0.096496 0.013500 0.012950 -vn 0.757034 0.201904 0.621397 -v -0.096496 0.014273 0.011378 -vn 0.757034 -0.068296 0.649796 -v -0.096496 0.013239 0.011486 -vn 0.990579 0.080492 0.110788 -v -0.096496 0.015822 0.012196 -vn 0.990579 0.062170 0.122016 -v -0.096496 0.015293 0.012519 -vn 0.990579 0.042317 0.130239 -v -0.096496 0.014721 0.012757 -vn 0.990579 0.135256 0.021422 -v -0.096496 0.017401 0.009618 -vn 0.990579 0.130239 0.042317 -v -0.096496 0.017257 0.010221 -vn 0.990579 0.122015 0.062170 -v -0.096496 0.017019 0.010793 -vn 0.990579 -0.110788 0.080492 -v -0.096496 0.010304 0.011322 -vn 0.990579 -0.122016 0.062170 -v -0.096496 0.009981 0.010793 -vn 0.757035 -0.528592 0.384044 -v -0.096496 0.011477 0.010469 -vn 0.990579 -0.130239 0.042317 -v -0.096496 0.009743 0.010221 -vn 0.990579 -0.135255 0.021422 -v -0.096496 0.009599 0.009618 -vn 0.990579 -0.096832 0.096832 -v -0.096496 0.010707 0.011793 -vn 0.757035 -0.326688 0.565839 -v -0.096496 0.012250 0.011165 -vn 0.990579 -0.080492 0.110788 -v -0.096496 0.011178 0.012196 -vn 0.990579 -0.021422 0.135255 -v -0.096496 0.012882 0.012901 -vn 0.990579 -0.042317 0.130239 -v -0.096496 0.012279 0.012757 -vn 0.990579 -0.062170 0.122016 -v -0.096496 0.011707 0.012519 -vn 0.663167 0.748472 0.000000 -v -0.095496 0.016000 0.009000 -vn 0.663167 0.683763 0.304431 -v -0.095496 0.015784 0.010017 -vn 0.663166 0.500826 0.556223 -v -0.095496 0.015173 0.010858 -vn 0.663167 0.231291 0.711839 -v -0.095496 0.014273 0.011378 -vn 0.663167 -0.078236 0.744372 -v -0.095496 0.013239 0.011486 -vn 0.663167 -0.374236 0.648196 -v -0.095496 0.012250 0.011165 -vn 0.663167 -0.605526 0.439940 -v -0.095496 0.011477 0.010469 -vn 0.663167 -0.732115 0.155616 -v -0.095496 0.011055 0.009520 -vn 0.663168 -0.732115 -0.155616 -v -0.095496 0.011055 0.008480 -vn 0.663167 -0.605526 -0.439940 -v -0.095496 0.011477 0.007531 -vn 0.663167 -0.374236 -0.648195 -v -0.095496 0.012250 0.006835 -vn 0.663167 -0.078236 -0.744371 -v -0.095496 0.013239 0.006514 -vn 0.663167 0.231291 -0.711839 -v -0.095496 0.014273 0.006622 -vn 0.663167 0.500825 -0.556223 -v -0.095496 0.015173 0.007142 -vn 0.663167 0.683762 -0.304431 -v -0.095496 0.015784 0.007983 -vn 0.756608 -0.639580 0.135947 -v -0.095496 0.011250 0.009478 -vn 0.756608 -0.639580 -0.135947 -v -0.095496 0.011250 0.008522 -vn 0.756608 -0.528991 -0.384334 -v -0.095496 0.011639 0.007648 -vn 0.756608 -0.326934 -0.566267 -v -0.095496 0.012350 0.007008 -vn 0.756608 -0.068348 -0.650286 -v -0.095496 0.013260 0.006713 -vn 0.756608 0.202056 -0.621866 -v -0.095496 0.014211 0.006813 -vn 0.756608 0.437523 -0.485919 -v -0.095496 0.015039 0.007291 -vn 0.756608 0.597339 -0.265952 -v -0.095496 0.015601 0.008065 -vn 0.756608 0.653869 -0.000000 -v -0.095496 0.015800 0.009000 -vn 0.756608 0.597339 0.265952 -v -0.095496 0.015601 0.009935 -vn 0.756608 0.437523 0.485919 -v -0.095496 0.015039 0.010709 -vn 0.756608 0.202056 0.621866 -v -0.095496 0.014211 0.011187 -vn 0.756608 -0.068348 0.650286 -v -0.095496 0.013260 0.011287 -vn 0.756608 -0.326934 0.566267 -v -0.095496 0.012350 0.010992 -vn 0.756608 -0.528991 0.384334 -v -0.095496 0.011639 0.010352 -vn 0.373956 0.907180 -0.192826 -v -0.056996 0.015750 0.008522 -vn 0.379295 0.845281 -0.376344 -v -0.056996 0.015601 0.008065 -vn 0.373956 0.750320 -0.545139 -v -0.056996 0.015361 0.007648 -vn 0.379295 0.619131 -0.687614 -v -0.056996 0.015039 0.007291 -vn 0.373956 0.463723 -0.803192 -v -0.056996 0.014650 0.007008 -vn 0.379295 0.285926 -0.879990 -v -0.056996 0.014211 0.006813 -vn 0.373956 0.096945 -0.922366 -v -0.056996 0.013740 0.006713 -vn 0.379295 -0.096718 -0.920207 -v -0.056996 0.013260 0.006713 -vn 0.373957 -0.286596 -0.882054 -v -0.056996 0.012789 0.006813 -vn 0.379295 -0.462638 -0.801312 -v -0.056996 0.012350 0.007008 -vn 0.373956 -0.620583 -0.689227 -v -0.056996 0.011961 0.007291 -vn 0.379295 -0.748564 -0.543864 -v -0.056996 0.011639 0.007648 -vn 0.373956 -0.847264 -0.377227 -v -0.056996 0.011399 0.008065 -vn 0.379295 -0.905056 -0.192376 -v -0.056996 0.011250 0.008522 -vn 0.373956 -0.927446 0.000000 -v -0.056996 0.011200 0.009000 -vn 0.379295 -0.905056 0.192376 -v -0.056996 0.011250 0.009478 -vn 0.373956 -0.847264 0.377226 -v -0.056996 0.011399 0.009935 -vn 0.379295 -0.748564 0.543863 -v -0.056996 0.011639 0.010352 -vn 0.373956 -0.620583 0.689227 -v -0.056996 0.011961 0.010709 -vn 0.379295 -0.462637 0.801313 -v -0.056996 0.012350 0.010992 -vn 0.373956 -0.286597 0.882054 -v -0.056996 0.012789 0.011187 -vn 0.379295 -0.096718 0.920207 -v -0.056996 0.013260 0.011287 -vn 0.373956 0.096945 0.922366 -v -0.056996 0.013740 0.011287 -vn 0.379295 0.285926 0.879990 -v -0.056996 0.014211 0.011187 -vn 0.373956 0.463722 0.803192 -v -0.056996 0.014650 0.010992 -vn 0.379295 0.619130 0.687614 -v -0.056996 0.015039 0.010709 -vn 0.373956 0.750320 0.545139 -v -0.056996 0.015361 0.010352 -vn 0.379295 0.845282 0.376343 -v -0.056996 0.015601 0.009935 -vn 0.373956 0.907180 0.192826 -v -0.056996 0.015750 0.009478 -vn 0.379295 0.925276 -0.000000 -v -0.056996 0.015800 0.009000 -vn 0.912392 -0.273887 0.304183 -v -0.056496 0.012296 0.010338 -vn 0.912392 -0.373931 0.166485 -v -0.056496 0.011856 0.009732 -vn 1.000000 0.000000 0.000000 -v -0.056496 0.013500 0.009000 -vn 0.912392 -0.409318 -0.000000 -v -0.056496 0.011700 0.009000 -vn 0.912392 -0.373931 -0.166485 -v -0.056496 0.011856 0.008268 -vn 0.912392 0.204659 0.354480 -v -0.056496 0.014400 0.010559 -vn 0.912392 0.042786 0.407076 -v -0.056496 0.013688 0.010790 -vn 0.912392 -0.126486 0.389285 -v -0.056496 0.012944 0.010712 -vn 0.912392 0.400374 -0.085102 -v -0.056496 0.015261 0.008626 -vn 0.912392 0.400374 0.085102 -v -0.056496 0.015261 0.009374 -vn 0.912392 0.331145 0.240591 -v -0.056496 0.014956 0.010058 -vn 0.912392 0.042785 -0.407076 -v -0.056496 0.013688 0.007210 -vn 0.912392 0.204659 -0.354480 -v -0.056496 0.014400 0.007441 -vn 0.912392 0.331145 -0.240592 -v -0.056496 0.014956 0.007942 -vn 0.912392 -0.273887 -0.304183 -v -0.056496 0.012296 0.007662 -vn 0.912392 -0.126486 -0.389285 -v -0.056496 0.012944 0.007288 -vn -0.609994 -0.792406 0.000000 -v -0.097496 0.015809 0.009000 -vn -0.609994 -0.396203 -0.686244 -v -0.097496 0.014655 0.011000 -vn -0.609994 0.396203 -0.686244 -v -0.097496 0.012345 0.011000 -vn -0.609994 0.792406 0.000000 -v -0.097496 0.011191 0.009000 -vn -0.609994 0.396203 0.686244 -v -0.097496 0.012345 0.007000 -vn -0.609994 -0.396203 0.686244 -v -0.097496 0.014655 0.007000 -vn 0.494481 -0.858487 0.135971 -v -0.096646 0.009342 0.009659 -vn 0.494480 -0.826648 0.268594 -v -0.096646 0.009496 0.010301 -vn 0.494482 -0.774453 0.394603 -v -0.096646 0.009749 0.010911 -vn 0.494481 -0.703188 0.510896 -v -0.096646 0.010094 0.011474 -vn 0.494480 -0.614609 0.614609 -v -0.096646 0.010523 0.011977 -vn 0.494481 -0.510896 0.703188 -v -0.096646 0.011026 0.012406 -vn 0.494481 -0.394603 0.774453 -v -0.096646 0.011589 0.012751 -vn 0.494480 -0.268594 0.826648 -v -0.096646 0.012199 0.013004 -vn 0.494481 -0.135971 0.858487 -v -0.096646 0.012841 0.013158 -vn 0.494481 0.000000 0.869189 -v -0.096646 0.013500 0.013210 -vn 0.494481 0.135971 0.858488 -v -0.096646 0.014159 0.013158 -vn 0.494481 0.268594 0.826647 -v -0.096646 0.014801 0.013004 -vn 0.494481 0.394603 0.774453 -v -0.096646 0.015411 0.012751 -vn 0.494483 0.510895 0.703188 -v -0.096646 0.015974 0.012406 -vn 0.494481 0.614609 0.614609 -v -0.096646 0.016477 0.011977 -vn 0.494483 0.703187 0.510896 -v -0.096646 0.016906 0.011474 -vn 0.494480 0.774453 0.394603 -v -0.096646 0.017251 0.010911 -vn 0.494480 0.826648 0.268594 -v -0.096646 0.017504 0.010301 -vn 0.494480 0.858488 0.135972 -v -0.096646 0.017658 0.009659 -vn 0.494482 0.869188 0.000000 -v -0.096646 0.017710 0.009000 -vn 0.494480 0.858488 -0.135972 -v -0.096646 0.017658 0.008341 -vn 0.494481 0.826648 -0.268594 -v -0.096646 0.017504 0.007699 -vn 0.494480 0.774453 -0.394604 -v -0.096646 0.017251 0.007089 -vn 0.494483 0.703187 -0.510895 -v -0.096646 0.016906 0.006526 -vn 0.494482 0.614609 -0.614609 -v -0.096646 0.016477 0.006023 -vn 0.494483 0.510896 -0.703188 -v -0.096646 0.015974 0.005594 -vn 0.494480 0.394603 -0.774453 -v -0.096646 0.015411 0.005249 -vn 0.494482 0.268594 -0.826647 -v -0.096646 0.014801 0.004996 -vn 0.494480 0.135971 -0.858488 -v -0.096646 0.014159 0.004842 -vn 0.494482 0.000000 -0.869188 -v -0.096646 0.013500 0.004790 -vn 0.494481 -0.135971 -0.858488 -v -0.096646 0.012841 0.004842 -vn 0.494481 -0.268594 -0.826647 -v -0.096646 0.012199 0.004996 -vn 0.494481 -0.394603 -0.774453 -v -0.096646 0.011589 0.005249 -vn 0.494481 -0.510897 -0.703188 -v -0.096646 0.011026 0.005594 -vn 0.494481 -0.614609 -0.614609 -v -0.096646 0.010523 0.006023 -vn 0.494482 -0.703187 -0.510896 -v -0.096646 0.010094 0.006526 -vn 0.494481 -0.774453 -0.394603 -v -0.096646 0.009749 0.007089 -vn 0.494481 -0.826648 -0.268594 -v -0.096646 0.009496 0.007699 -vn 0.494481 -0.858487 -0.135971 -v -0.096646 0.009342 0.008341 -vn 0.494481 -0.869189 -0.000000 -v -0.096646 0.009290 0.009000 -vn 0.860419 -0.503313 0.079717 -v -0.096536 0.009450 0.009641 -vn 0.860418 -0.484647 0.157472 -v -0.096536 0.009601 0.010267 -vn 0.860419 -0.454045 0.231348 -v -0.096536 0.009847 0.010861 -vn 0.860420 -0.412263 0.299527 -v -0.096536 0.010183 0.011410 -vn 0.860419 -0.360333 0.360333 -v -0.096536 0.010601 0.011899 -vn 0.860420 -0.299527 0.412263 -v -0.096536 0.011090 0.012317 -vn 0.860420 -0.231348 0.454045 -v -0.096536 0.011639 0.012653 -vn 0.860419 -0.157471 0.484647 -v -0.096536 0.012233 0.012899 -vn 0.860419 -0.079717 0.503314 -v -0.096536 0.012859 0.013050 -vn 0.860419 -0.000000 0.509587 -v -0.096536 0.013500 0.013100 -vn 0.860419 0.079717 0.503314 -v -0.096536 0.014141 0.013050 -vn 0.860419 0.157471 0.484647 -v -0.096536 0.014767 0.012899 -vn 0.860420 0.231347 0.454044 -v -0.096536 0.015361 0.012653 -vn 0.860419 0.299528 0.412264 -v -0.096536 0.015910 0.012317 -vn 0.860419 0.360332 0.360332 -v -0.096536 0.016399 0.011899 -vn 0.860419 0.412265 0.299528 -v -0.096536 0.016817 0.011410 -vn 0.860419 0.454045 0.231348 -v -0.096536 0.017153 0.010861 -vn 0.860418 0.484647 0.157471 -v -0.096536 0.017399 0.010267 -vn 0.860420 0.503312 0.079717 -v -0.096536 0.017550 0.009641 -vn 0.860420 0.509585 0.000000 -v -0.096536 0.017600 0.009000 -vn 0.860420 0.503312 -0.079717 -v -0.096536 0.017550 0.008359 -vn 0.860419 0.484647 -0.157472 -v -0.096536 0.017399 0.007733 -vn 0.860419 0.454045 -0.231347 -v -0.096536 0.017153 0.007139 -vn 0.860418 0.412265 -0.299529 -v -0.096536 0.016817 0.006590 -vn 0.860420 0.360332 -0.360332 -v -0.096536 0.016399 0.006101 -vn 0.860419 0.299528 -0.412265 -v -0.096536 0.015910 0.005683 -vn 0.860420 0.231348 -0.454045 -v -0.096536 0.015361 0.005347 -vn 0.860419 0.157471 -0.484646 -v -0.096536 0.014767 0.005101 -vn 0.860419 0.079717 -0.503313 -v -0.096536 0.014141 0.004950 -vn 0.860419 -0.000000 -0.509587 -v -0.096536 0.013500 0.004900 -vn 0.860419 -0.079717 -0.503313 -v -0.096536 0.012859 0.004950 -vn 0.860419 -0.157471 -0.484646 -v -0.096536 0.012233 0.005101 -vn 0.860419 -0.231348 -0.454045 -v -0.096536 0.011639 0.005347 -vn 0.860420 -0.299527 -0.412264 -v -0.096536 0.011090 0.005683 -vn 0.860419 -0.360333 -0.360332 -v -0.096536 0.010601 0.006101 -vn 0.860420 -0.412263 -0.299527 -v -0.096536 0.010183 0.006590 -vn 0.860420 -0.454044 -0.231347 -v -0.096536 0.009847 0.007139 -vn 0.860419 -0.484647 -0.157471 -v -0.096536 0.009601 0.007733 -vn 0.860419 -0.503314 -0.079717 -v -0.096536 0.009450 0.008359 -vn 0.860419 -0.509587 -0.000000 -v -0.096536 0.009400 0.009000 -vn -0.494480 0.858488 0.135972 -v -0.101346 0.017658 0.009659 -vn -0.494480 0.826648 0.268594 -v -0.101346 0.017504 0.010301 -vn -0.494480 0.774453 0.394603 -v -0.101346 0.017251 0.010911 -vn -0.494483 0.703187 0.510896 -v -0.101346 0.016906 0.011474 -vn -0.494481 0.614609 0.614609 -v -0.101346 0.016477 0.011977 -vn -0.494483 0.510895 0.703187 -v -0.101346 0.015974 0.012406 -vn -0.494481 0.394603 0.774453 -v -0.101346 0.015411 0.012751 -vn -0.494481 0.268594 0.826648 -v -0.101346 0.014801 0.013004 -vn -0.494481 0.135971 0.858487 -v -0.101346 0.014159 0.013158 -vn -0.494481 0.000000 0.869189 -v -0.101346 0.013500 0.013210 -vn -0.494481 -0.135971 0.858487 -v -0.101346 0.012841 0.013158 -vn -0.494480 -0.268594 0.826648 -v -0.101346 0.012199 0.013004 -vn -0.494482 -0.394603 0.774453 -v -0.101346 0.011589 0.012751 -vn -0.494481 -0.510896 0.703188 -v -0.101346 0.011026 0.012406 -vn -0.494480 -0.614609 0.614609 -v -0.101346 0.010523 0.011977 -vn -0.494481 -0.703188 0.510896 -v -0.101346 0.010094 0.011474 -vn -0.494481 -0.774453 0.394603 -v -0.101346 0.009749 0.010911 -vn -0.494480 -0.826648 0.268594 -v -0.101346 0.009496 0.010301 -vn -0.494481 -0.858487 0.135971 -v -0.101346 0.009342 0.009659 -vn -0.494481 -0.869189 -0.000000 -v -0.101346 0.009290 0.009000 -vn -0.494481 -0.858488 -0.135971 -v -0.101346 0.009342 0.008341 -vn -0.494480 -0.826648 -0.268594 -v -0.101346 0.009496 0.007699 -vn -0.494481 -0.774453 -0.394603 -v -0.101346 0.009749 0.007089 -vn -0.494481 -0.703188 -0.510896 -v -0.101346 0.010094 0.006526 -vn -0.494480 -0.614609 -0.614610 -v -0.101346 0.010523 0.006023 -vn -0.494480 -0.510897 -0.703189 -v -0.101346 0.011026 0.005594 -vn -0.494480 -0.394603 -0.774454 -v -0.101346 0.011589 0.005249 -vn -0.494480 -0.268594 -0.826648 -v -0.101346 0.012199 0.004996 -vn -0.494479 -0.135971 -0.858488 -v -0.101346 0.012841 0.004842 -vn -0.494481 -0.000000 -0.869189 -v -0.101346 0.013500 0.004790 -vn -0.494479 0.135971 -0.858488 -v -0.101346 0.014159 0.004842 -vn -0.494480 0.268594 -0.826648 -v -0.101346 0.014801 0.004996 -vn -0.494479 0.394604 -0.774453 -v -0.101346 0.015411 0.005249 -vn -0.494482 0.510895 -0.703188 -v -0.101346 0.015974 0.005594 -vn -0.494481 0.614609 -0.614609 -v -0.101346 0.016477 0.006023 -vn -0.494483 0.703187 -0.510896 -v -0.101346 0.016906 0.006526 -vn -0.494479 0.774454 -0.394603 -v -0.101346 0.017251 0.007089 -vn -0.494480 0.826648 -0.268595 -v -0.101346 0.017504 0.007699 -vn -0.494480 0.858488 -0.135972 -v -0.101346 0.017658 0.008341 -vn -0.494482 0.869188 -0.000000 -v -0.101346 0.017710 0.009000 -vn -0.860420 0.503312 0.079717 -v -0.101456 0.017550 0.009641 -vn -0.860419 0.484647 0.157472 -v -0.101456 0.017399 0.010267 -vn -0.860419 0.454045 0.231348 -v -0.101456 0.017153 0.010861 -vn -0.860419 0.412265 0.299529 -v -0.101456 0.016817 0.011410 -vn -0.860419 0.360332 0.360332 -v -0.101456 0.016399 0.011899 -vn -0.860419 0.299528 0.412264 -v -0.101456 0.015910 0.012317 -vn -0.860420 0.231347 0.454044 -v -0.101456 0.015361 0.012653 -vn -0.860419 0.157471 0.484647 -v -0.101456 0.014767 0.012899 -vn -0.860419 0.079717 0.503314 -v -0.101456 0.014141 0.013050 -vn -0.860419 0.000000 0.509587 -v -0.101456 0.013500 0.013100 -vn -0.860419 -0.079717 0.503313 -v -0.101456 0.012859 0.013050 -vn -0.860418 -0.157472 0.484647 -v -0.101456 0.012233 0.012899 -vn -0.860419 -0.231348 0.454045 -v -0.101456 0.011639 0.012653 -vn -0.860420 -0.299527 0.412263 -v -0.101456 0.011090 0.012317 -vn -0.860419 -0.360333 0.360333 -v -0.101456 0.010601 0.011899 -vn -0.860420 -0.412263 0.299527 -v -0.101456 0.010183 0.011410 -vn -0.860420 -0.454045 0.231348 -v -0.101456 0.009847 0.010861 -vn -0.860418 -0.484647 0.157471 -v -0.101456 0.009601 0.010267 -vn -0.860419 -0.503314 0.079717 -v -0.101456 0.009450 0.009641 -vn -0.860419 -0.509587 0.000000 -v -0.101456 0.009400 0.009000 -vn -0.860419 -0.503314 -0.079717 -v -0.101456 0.009450 0.008359 -vn -0.860419 -0.484647 -0.157472 -v -0.101456 0.009601 0.007733 -vn -0.860420 -0.454045 -0.231347 -v -0.101456 0.009847 0.007139 -vn -0.860420 -0.412264 -0.299527 -v -0.101456 0.010183 0.006590 -vn -0.860419 -0.360333 -0.360333 -v -0.101456 0.010601 0.006101 -vn -0.860420 -0.299528 -0.412264 -v -0.101456 0.011090 0.005683 -vn -0.860419 -0.231348 -0.454045 -v -0.101456 0.011639 0.005347 -vn -0.860419 -0.157471 -0.484646 -v -0.101456 0.012233 0.005101 -vn -0.860419 -0.079717 -0.503313 -v -0.101456 0.012859 0.004950 -vn -0.860419 0.000000 -0.509587 -v -0.101456 0.013500 0.004900 -vn -0.860419 0.079717 -0.503313 -v -0.101456 0.014141 0.004950 -vn -0.860419 0.157471 -0.484646 -v -0.101456 0.014767 0.005101 -vn -0.860420 0.231347 -0.454045 -v -0.101456 0.015361 0.005347 -vn -0.860419 0.299528 -0.412265 -v -0.101456 0.015910 0.005683 -vn -0.860420 0.360332 -0.360332 -v -0.101456 0.016399 0.006101 -vn -0.860419 0.412266 -0.299528 -v -0.101456 0.016817 0.006590 -vn -0.860419 0.454045 -0.231348 -v -0.101456 0.017153 0.007139 -vn -0.860419 0.484647 -0.157471 -v -0.101456 0.017399 0.007733 -vn -0.860420 0.503312 -0.079717 -v -0.101456 0.017550 0.008359 -vn -0.860420 0.509585 -0.000000 -v -0.101456 0.017600 0.009000 -# 846 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 4//4 6//6 16//16 -f 17//17 18//18 19//19 -f 20//20 21//21 22//22 -f 23//23 24//24 20//20 -f 20//20 24//24 25//25 -f 20//20 25//25 21//21 -f 15//15 26//26 14//14 -f 14//14 26//26 27//27 -f 14//14 27//27 6//6 -f 6//6 27//27 28//28 -f 6//6 28//28 16//16 -f 18//18 29//29 19//19 -f 19//19 29//29 30//30 -f 19//19 30//30 31//31 -f 22//22 32//32 20//20 -f 20//20 32//32 33//33 -f 20//20 33//33 3//3 -f 3//3 33//33 34//34 -f 3//3 34//34 1//1 -f 5//5 35//35 6//6 -f 6//6 35//35 36//36 -f 6//6 36//36 9//9 -f 9//9 36//36 37//37 -f 9//9 37//37 7//7 -f 31//31 38//38 19//19 -f 19//19 38//38 39//39 -f 19//19 39//39 14//14 -f 14//14 39//39 40//40 -f 14//14 40//40 12//12 -f 2//2 41//41 3//3 -f 3//3 41//41 42//42 -f 3//3 42//42 19//19 -f 19//19 42//42 43//43 -f 19//19 43//43 17//17 -f 11//11 44//44 9//9 -f 9//9 44//44 45//45 -f 9//9 45//45 20//20 -f 20//20 45//45 46//46 -f 20//20 46//46 23//23 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 47//47 -f 47//47 126//126 48//48 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 128//128 137//137 130//130 -f 130//130 137//137 138//138 -f 130//130 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 141//141 -f 131//131 142//142 132//132 -f 132//132 142//142 143//143 -f 132//132 143//143 144//144 -f 136//136 134//134 145//145 -f 145//145 134//134 146//146 -f 145//145 146//146 147//147 -f 148//148 149//149 150//150 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 143//143 155//155 144//144 -f 144//144 155//155 156//156 -f 144//144 156//156 129//129 -f 129//129 156//156 157//157 -f 129//129 157//157 127//127 -f 148//148 158//158 149//149 -f 149//149 158//158 159//159 -f 149//149 159//159 146//146 -f 146//146 159//159 160//160 -f 146//146 160//160 147//147 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 151//151 165//165 152//152 -f 152//152 165//165 166//166 -f 152//152 166//166 163//163 -f 163//163 166//166 167//167 -f 163//163 167//167 161//161 -f 141//141 168//168 139//139 -f 139//139 168//168 169//169 -f 139//139 169//169 154//154 -f 154//154 169//169 170//170 -f 154//154 170//170 153//153 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 150//150 -f 150//150 174//174 175//175 -f 150//150 175//175 148//148 -f 171//171 173//173 176//176 -f 176//176 173//173 177//177 -f 176//176 177//177 178//178 -f 162//162 179//179 164//164 -f 164//164 179//179 180//180 -f 164//164 180//180 177//177 -f 177//177 180//180 181//181 -f 177//177 181//181 178//178 -f 182//182 154//154 183//183 -f 183//183 154//154 152//152 -f 183//183 152//152 184//184 -f 184//184 152//152 163//163 -f 184//184 163//163 185//185 -f 185//185 163//163 164//164 -f 185//185 164//164 186//186 -f 186//186 164//164 177//177 -f 186//186 177//177 187//187 -f 187//187 177//177 173//173 -f 187//187 173//173 188//188 -f 188//188 173//173 150//150 -f 188//188 150//150 189//189 -f 189//189 150//150 149//149 -f 189//189 149//149 190//190 -f 190//190 149//149 146//146 -f 190//190 146//146 191//191 -f 191//191 146//146 134//134 -f 191//191 134//134 192//192 -f 192//192 134//134 132//132 -f 192//192 132//132 193//193 -f 193//193 132//132 144//144 -f 193//193 144//144 194//194 -f 194//194 144//144 129//129 -f 194//194 129//129 195//195 -f 195//195 129//129 130//130 -f 195//195 130//130 196//196 -f 196//196 130//130 139//139 -f 196//196 139//139 182//182 -f 182//182 139//139 154//154 -f 197//197 189//189 198//198 -f 198//198 189//189 190//190 -f 198//198 190//190 199//199 -f 199//199 190//190 191//191 -f 199//199 191//191 200//200 -f 200//200 191//191 192//192 -f 200//200 192//192 201//201 -f 201//201 192//192 193//193 -f 201//201 193//193 202//202 -f 202//202 193//193 194//194 -f 202//202 194//194 203//203 -f 203//203 194//194 195//195 -f 203//203 195//195 204//204 -f 204//204 195//195 196//196 -f 204//204 196//196 205//205 -f 205//205 196//196 182//182 -f 205//205 182//182 206//206 -f 206//206 182//182 183//183 -f 206//206 183//183 207//207 -f 207//207 183//183 184//184 -f 207//207 184//184 208//208 -f 208//208 184//184 185//185 -f 208//208 185//185 209//209 -f 209//209 185//185 186//186 -f 209//209 186//186 210//210 -f 210//210 186//186 187//187 -f 210//210 187//187 211//211 -f 211//211 187//187 188//188 -f 211//211 188//188 197//197 -f 197//197 188//188 189//189 -f 212//212 204//204 205//205 -f 212//212 213//213 204//204 -f 204//204 213//213 214//214 -f 204//204 214//214 203//203 -f 214//214 215//215 203//203 -f 203//203 215//215 216//216 -f 203//203 216//216 202//202 -f 216//216 217//217 202//202 -f 202//202 217//217 218//218 -f 202//202 218//218 201//201 -f 218//218 219//219 201//201 -f 201//201 219//219 220//220 -f 201//201 220//220 200//200 -f 220//220 221//221 200//200 -f 200//200 221//221 222//222 -f 200//200 222//222 199//199 -f 222//222 223//223 199//199 -f 199//199 223//223 224//224 -f 199//199 224//224 198//198 -f 224//224 225//225 198//198 -f 198//198 225//225 226//226 -f 198//198 226//226 197//197 -f 226//226 227//227 197//197 -f 197//197 227//227 228//228 -f 197//197 228//228 211//211 -f 228//228 229//229 211//211 -f 211//211 229//229 230//230 -f 211//211 230//230 210//210 -f 230//230 231//231 210//210 -f 210//210 231//231 232//232 -f 210//210 232//232 209//209 -f 232//232 233//233 209//209 -f 209//209 233//233 234//234 -f 209//209 234//234 208//208 -f 234//234 235//235 208//208 -f 208//208 235//235 236//236 -f 208//208 236//236 207//207 -f 236//236 237//237 207//207 -f 207//207 237//237 238//238 -f 207//207 238//238 206//206 -f 238//238 239//239 206//206 -f 206//206 239//239 240//240 -f 206//206 240//240 205//205 -f 205//205 240//240 241//241 -f 205//205 241//241 212//212 -f 242//242 243//243 244//244 -f 244//244 243//243 245//245 -f 244//244 245//245 246//246 -f 247//247 248//248 244//244 -f 244//244 248//248 249//249 -f 244//244 249//249 242//242 -f 250//250 251//251 244//244 -f 244//244 251//251 252//252 -f 244//244 252//252 247//247 -f 253//253 254//254 244//244 -f 244//244 254//254 255//255 -f 244//244 255//255 250//250 -f 246//246 256//256 244//244 -f 244//244 256//256 257//257 -f 244//244 257//257 253//253 -f 258//258 259//259 14//14 -f 14//14 259//259 19//19 -f 259//259 260//260 19//19 -f 19//19 260//260 3//3 -f 260//260 261//261 3//3 -f 3//3 261//261 20//20 -f 261//261 262//262 20//20 -f 20//20 262//262 9//9 -f 262//262 263//263 9//9 -f 9//9 263//263 6//6 -f 263//263 258//258 6//6 -f 6//6 258//258 14//14 -f 263//263 262//262 258//258 -f 258//258 262//262 261//261 -f 258//258 261//261 259//259 -f 259//259 261//261 260//260 -f 246//246 245//245 225//225 -f 225//225 224//224 246//246 -f 246//246 224//224 223//223 -f 246//246 223//223 256//256 -f 223//223 222//222 256//256 -f 256//256 222//222 221//221 -f 256//256 221//221 257//257 -f 221//221 220//220 257//257 -f 257//257 220//220 219//219 -f 257//257 219//219 253//253 -f 219//219 218//218 253//253 -f 253//253 218//218 217//217 -f 253//253 217//217 254//254 -f 217//217 216//216 254//254 -f 254//254 216//216 215//215 -f 254//254 215//215 255//255 -f 215//215 214//214 255//255 -f 255//255 214//214 213//213 -f 255//255 213//213 250//250 -f 213//213 212//212 250//250 -f 250//250 212//212 241//241 -f 250//250 241//241 251//251 -f 241//241 240//240 251//251 -f 251//251 240//240 239//239 -f 251//251 239//239 252//252 -f 239//239 238//238 252//252 -f 252//252 238//238 237//237 -f 252//252 237//237 247//247 -f 237//237 236//236 247//247 -f 247//247 236//236 235//235 -f 247//247 235//235 248//248 -f 235//235 234//234 248//248 -f 248//248 234//234 233//233 -f 248//248 233//233 249//249 -f 233//233 232//232 249//249 -f 249//249 232//232 231//231 -f 249//249 231//231 242//242 -f 231//231 230//230 242//242 -f 242//242 230//230 229//229 -f 242//242 229//229 243//243 -f 229//229 228//228 243//243 -f 243//243 228//228 227//227 -f 243//243 227//227 245//245 -f 245//245 227//227 226//226 -f 245//245 226//226 225//225 -f 90//90 264//264 92//92 -f 92//92 264//264 265//265 -f 92//92 265//265 94//94 -f 94//94 265//265 266//266 -f 94//94 266//266 96//96 -f 96//96 266//266 267//267 -f 96//96 267//267 98//98 -f 98//98 267//267 268//268 -f 98//98 268//268 100//100 -f 100//100 268//268 269//269 -f 100//100 269//269 102//102 -f 102//102 269//269 270//270 -f 102//102 270//270 104//104 -f 104//104 270//270 271//271 -f 104//104 271//271 106//106 -f 106//106 271//271 272//272 -f 106//106 272//272 108//108 -f 108//108 272//272 273//273 -f 108//108 273//273 110//110 -f 110//110 273//273 274//274 -f 110//110 274//274 112//112 -f 112//112 274//274 275//275 -f 112//112 275//275 114//114 -f 114//114 275//275 276//276 -f 114//114 276//276 116//116 -f 116//116 276//276 277//277 -f 116//116 277//277 118//118 -f 118//118 277//277 278//278 -f 118//118 278//278 120//120 -f 120//120 278//278 279//279 -f 120//120 279//279 122//122 -f 122//122 279//279 280//280 -f 122//122 280//280 124//124 -f 124//124 280//280 281//281 -f 124//124 281//281 126//126 -f 126//126 281//281 282//282 -f 126//126 282//282 48//48 -f 48//48 282//282 283//283 -f 48//48 283//283 50//50 -f 50//50 283//283 284//284 -f 50//50 284//284 52//52 -f 52//52 284//284 285//285 -f 52//52 285//285 54//54 -f 54//54 285//285 286//286 -f 54//54 286//286 56//56 -f 56//56 286//286 287//287 -f 56//56 287//287 58//58 -f 58//58 287//287 288//288 -f 58//58 288//288 60//60 -f 60//60 288//288 289//289 -f 60//60 289//289 62//62 -f 62//62 289//289 290//290 -f 62//62 290//290 64//64 -f 64//64 290//290 291//291 -f 64//64 291//291 66//66 -f 66//66 291//291 292//292 -f 66//66 292//292 68//68 -f 68//68 292//292 293//293 -f 68//68 293//293 70//70 -f 70//70 293//293 294//294 -f 70//70 294//294 72//72 -f 72//72 294//294 295//295 -f 72//72 295//295 74//74 -f 74//74 295//295 296//296 -f 74//74 296//296 76//76 -f 76//76 296//296 297//297 -f 76//76 297//297 78//78 -f 78//78 297//297 298//298 -f 78//78 298//298 80//80 -f 80//80 298//298 299//299 -f 80//80 299//299 82//82 -f 82//82 299//299 300//300 -f 82//82 300//300 84//84 -f 84//84 300//300 301//301 -f 84//84 301//301 86//86 -f 86//86 301//301 302//302 -f 86//86 302//302 88//88 -f 88//88 302//302 303//303 -f 88//88 303//303 90//90 -f 90//90 303//303 264//264 -f 303//303 304//304 264//264 -f 264//264 304//304 305//305 -f 264//264 305//305 265//265 -f 265//265 305//305 306//306 -f 265//265 306//306 266//266 -f 266//266 306//306 307//307 -f 266//266 307//307 267//267 -f 267//267 307//307 308//308 -f 267//267 308//308 268//268 -f 268//268 308//308 309//309 -f 268//268 309//309 269//269 -f 269//269 309//309 310//310 -f 269//269 310//310 270//270 -f 270//270 310//310 311//311 -f 270//270 311//311 271//271 -f 271//271 311//311 312//312 -f 271//271 312//312 272//272 -f 272//272 312//312 313//313 -f 272//272 313//313 273//273 -f 273//273 313//313 314//314 -f 273//273 314//314 274//274 -f 274//274 314//314 315//315 -f 274//274 315//315 275//275 -f 275//275 315//315 316//316 -f 275//275 316//316 276//276 -f 276//276 316//316 317//317 -f 276//276 317//317 277//277 -f 277//277 317//317 318//318 -f 277//277 318//318 278//278 -f 278//278 318//318 319//319 -f 278//278 319//319 279//279 -f 279//279 319//319 320//320 -f 279//279 320//320 280//280 -f 280//280 320//320 321//321 -f 280//280 321//321 281//281 -f 281//281 321//321 322//322 -f 281//281 322//322 282//282 -f 282//282 322//322 323//323 -f 282//282 323//323 283//283 -f 283//283 323//323 324//324 -f 283//283 324//324 284//284 -f 284//284 324//324 325//325 -f 284//284 325//325 285//285 -f 285//285 325//325 326//326 -f 285//285 326//326 286//286 -f 286//286 326//326 327//327 -f 286//286 327//327 287//287 -f 287//287 327//327 328//328 -f 287//287 328//328 288//288 -f 288//288 328//328 329//329 -f 288//288 329//329 289//289 -f 289//289 329//329 330//330 -f 289//289 330//330 290//290 -f 290//290 330//330 331//331 -f 290//290 331//331 291//291 -f 291//291 331//331 332//332 -f 291//291 332//332 292//292 -f 292//292 332//332 333//333 -f 292//292 333//333 293//293 -f 293//293 333//333 334//334 -f 293//293 334//334 294//294 -f 294//294 334//334 335//335 -f 294//294 335//335 295//295 -f 295//295 335//335 336//336 -f 295//295 336//336 296//296 -f 296//296 336//336 337//337 -f 296//296 337//337 297//297 -f 297//297 337//337 338//338 -f 297//297 338//338 298//298 -f 298//298 338//338 339//339 -f 298//298 339//339 299//299 -f 299//299 339//339 340//340 -f 299//299 340//340 300//300 -f 300//300 340//340 341//341 -f 300//300 341//341 301//301 -f 301//301 341//341 342//342 -f 301//301 342//342 302//302 -f 302//302 342//342 343//343 -f 302//302 343//343 303//303 -f 303//303 343//343 304//304 -f 343//343 175//175 304//304 -f 304//304 175//175 174//174 -f 304//304 174//174 305//305 -f 305//305 174//174 172//172 -f 305//305 172//172 306//306 -f 306//306 172//172 171//171 -f 306//306 171//171 307//307 -f 307//307 171//171 176//176 -f 307//307 176//176 308//308 -f 308//308 176//176 178//178 -f 308//308 178//178 309//309 -f 309//309 178//178 181//181 -f 309//309 181//181 310//310 -f 310//310 181//181 180//180 -f 310//310 180//180 311//311 -f 311//311 180//180 179//179 -f 311//311 179//179 312//312 -f 312//312 179//179 162//162 -f 312//312 162//162 313//313 -f 313//313 162//162 161//161 -f 313//313 161//161 314//314 -f 314//314 161//161 167//167 -f 314//314 167//167 315//315 -f 315//315 167//167 166//166 -f 315//315 166//166 316//316 -f 316//316 166//166 165//165 -f 316//316 165//165 317//317 -f 317//317 165//165 151//151 -f 317//317 151//151 318//318 -f 318//318 151//151 153//153 -f 318//318 153//153 319//319 -f 319//319 153//153 170//170 -f 319//319 170//170 320//320 -f 320//320 170//170 169//169 -f 320//320 169//169 321//321 -f 321//321 169//169 168//168 -f 321//321 168//168 322//322 -f 322//322 168//168 141//141 -f 322//322 141//141 323//323 -f 323//323 141//141 140//140 -f 323//323 140//140 324//324 -f 324//324 140//140 138//138 -f 324//324 138//138 325//325 -f 325//325 138//138 137//137 -f 325//325 137//137 326//326 -f 326//326 137//137 128//128 -f 326//326 128//128 327//327 -f 327//327 128//128 127//127 -f 327//327 127//127 328//328 -f 328//328 127//127 157//157 -f 328//328 157//157 329//329 -f 329//329 157//157 156//156 -f 329//329 156//156 330//330 -f 330//330 156//156 155//155 -f 330//330 155//155 331//331 -f 331//331 155//155 143//143 -f 331//331 143//143 332//332 -f 332//332 143//143 142//142 -f 332//332 142//142 333//333 -f 333//333 142//142 131//131 -f 333//333 131//131 334//334 -f 334//334 131//131 133//133 -f 334//334 133//133 335//335 -f 335//335 133//133 135//135 -f 335//335 135//135 336//336 -f 336//336 135//135 136//136 -f 336//336 136//136 337//337 -f 337//337 136//136 145//145 -f 337//337 145//145 338//338 -f 338//338 145//145 147//147 -f 338//338 147//147 339//339 -f 339//339 147//147 160//160 -f 339//339 160//160 340//340 -f 340//340 160//160 159//159 -f 340//340 159//159 341//341 -f 341//341 159//159 158//158 -f 341//341 158//158 342//342 -f 342//342 158//158 148//148 -f 342//342 148//148 343//343 -f 343//343 148//148 175//175 -f 49//49 344//344 47//47 -f 47//47 344//344 345//345 -f 47//47 345//345 125//125 -f 125//125 345//345 346//346 -f 125//125 346//346 123//123 -f 123//123 346//346 347//347 -f 123//123 347//347 121//121 -f 121//121 347//347 348//348 -f 121//121 348//348 119//119 -f 119//119 348//348 349//349 -f 119//119 349//349 117//117 -f 117//117 349//349 350//350 -f 117//117 350//350 115//115 -f 115//115 350//350 351//351 -f 115//115 351//351 113//113 -f 113//113 351//351 352//352 -f 113//113 352//352 111//111 -f 111//111 352//352 353//353 -f 111//111 353//353 109//109 -f 109//109 353//353 354//354 -f 109//109 354//354 107//107 -f 107//107 354//354 355//355 -f 107//107 355//355 105//105 -f 105//105 355//355 356//356 -f 105//105 356//356 103//103 -f 103//103 356//356 357//357 -f 103//103 357//357 101//101 -f 101//101 357//357 358//358 -f 101//101 358//358 99//99 -f 99//99 358//358 359//359 -f 99//99 359//359 97//97 -f 97//97 359//359 360//360 -f 97//97 360//360 95//95 -f 95//95 360//360 361//361 -f 95//95 361//361 93//93 -f 93//93 361//361 362//362 -f 93//93 362//362 91//91 -f 91//91 362//362 363//363 -f 91//91 363//363 89//89 -f 89//89 363//363 364//364 -f 89//89 364//364 87//87 -f 87//87 364//364 365//365 -f 87//87 365//365 85//85 -f 85//85 365//365 366//366 -f 85//85 366//366 83//83 -f 83//83 366//366 367//367 -f 83//83 367//367 81//81 -f 81//81 367//367 368//368 -f 81//81 368//368 79//79 -f 79//79 368//368 369//369 -f 79//79 369//369 77//77 -f 77//77 369//369 370//370 -f 77//77 370//370 75//75 -f 75//75 370//370 371//371 -f 75//75 371//371 73//73 -f 73//73 371//371 372//372 -f 73//73 372//372 71//71 -f 71//71 372//372 373//373 -f 71//71 373//373 69//69 -f 69//69 373//373 374//374 -f 69//69 374//374 67//67 -f 67//67 374//374 375//375 -f 67//67 375//375 65//65 -f 65//65 375//375 376//376 -f 65//65 376//376 63//63 -f 63//63 376//376 377//377 -f 63//63 377//377 61//61 -f 61//61 377//377 378//378 -f 61//61 378//378 59//59 -f 59//59 378//378 379//379 -f 59//59 379//379 57//57 -f 57//57 379//379 380//380 -f 57//57 380//380 55//55 -f 55//55 380//380 381//381 -f 55//55 381//381 53//53 -f 53//53 381//381 382//382 -f 53//53 382//382 51//51 -f 51//51 382//382 383//383 -f 51//51 383//383 49//49 -f 49//49 383//383 344//344 -f 383//383 384//384 344//344 -f 344//344 384//384 385//385 -f 344//344 385//385 345//345 -f 345//345 385//385 386//386 -f 345//345 386//386 346//346 -f 346//346 386//386 387//387 -f 346//346 387//387 347//347 -f 347//347 387//387 388//388 -f 347//347 388//388 348//348 -f 348//348 388//388 389//389 -f 348//348 389//389 349//349 -f 349//349 389//389 390//390 -f 349//349 390//390 350//350 -f 350//350 390//390 391//391 -f 350//350 391//391 351//351 -f 351//351 391//391 392//392 -f 351//351 392//392 352//352 -f 352//352 392//392 393//393 -f 352//352 393//393 353//353 -f 353//353 393//393 394//394 -f 353//353 394//394 354//354 -f 354//354 394//394 395//395 -f 354//354 395//395 355//355 -f 355//355 395//395 396//396 -f 355//355 396//396 356//356 -f 356//356 396//396 397//397 -f 356//356 397//397 357//357 -f 357//357 397//397 398//398 -f 357//357 398//398 358//358 -f 358//358 398//398 399//399 -f 358//358 399//399 359//359 -f 359//359 399//399 400//400 -f 359//359 400//400 360//360 -f 360//360 400//400 401//401 -f 360//360 401//401 361//361 -f 361//361 401//401 402//402 -f 361//361 402//402 362//362 -f 362//362 402//402 403//403 -f 362//362 403//403 363//363 -f 363//363 403//403 404//404 -f 363//363 404//404 364//364 -f 364//364 404//404 405//405 -f 364//364 405//405 365//365 -f 365//365 405//405 406//406 -f 365//365 406//406 366//366 -f 366//366 406//406 407//407 -f 366//366 407//407 367//367 -f 367//367 407//407 408//408 -f 367//367 408//408 368//368 -f 368//368 408//408 409//409 -f 368//368 409//409 369//369 -f 369//369 409//409 410//410 -f 369//369 410//410 370//370 -f 370//370 410//410 411//411 -f 370//370 411//411 371//371 -f 371//371 411//411 412//412 -f 371//371 412//412 372//372 -f 372//372 412//412 413//413 -f 372//372 413//413 373//373 -f 373//373 413//413 414//414 -f 373//373 414//414 374//374 -f 374//374 414//414 415//415 -f 374//374 415//415 375//375 -f 375//375 415//415 416//416 -f 375//375 416//416 376//376 -f 376//376 416//416 417//417 -f 376//376 417//417 377//377 -f 377//377 417//417 418//418 -f 377//377 418//418 378//378 -f 378//378 418//418 419//419 -f 378//378 419//419 379//379 -f 379//379 419//419 420//420 -f 379//379 420//420 380//380 -f 380//380 420//420 421//421 -f 380//380 421//421 381//381 -f 381//381 421//421 422//422 -f 381//381 422//422 382//382 -f 382//382 422//422 423//423 -f 382//382 423//423 383//383 -f 383//383 423//423 384//384 -f 423//423 12//12 384//384 -f 384//384 12//12 40//40 -f 384//384 40//40 385//385 -f 385//385 40//40 39//39 -f 385//385 39//39 386//386 -f 386//386 39//39 38//38 -f 386//386 38//38 387//387 -f 387//387 38//38 31//31 -f 387//387 31//31 388//388 -f 388//388 31//31 30//30 -f 388//388 30//30 389//389 -f 389//389 30//30 29//29 -f 389//389 29//29 390//390 -f 390//390 29//29 18//18 -f 390//390 18//18 391//391 -f 391//391 18//18 17//17 -f 391//391 17//17 392//392 -f 392//392 17//17 43//43 -f 392//392 43//43 393//393 -f 393//393 43//43 42//42 -f 393//393 42//42 394//394 -f 394//394 42//42 41//41 -f 394//394 41//41 395//395 -f 395//395 41//41 2//2 -f 395//395 2//2 396//396 -f 396//396 2//2 1//1 -f 396//396 1//1 397//397 -f 397//397 1//1 34//34 -f 397//397 34//34 398//398 -f 398//398 34//34 33//33 -f 398//398 33//33 399//399 -f 399//399 33//33 32//32 -f 399//399 32//32 400//400 -f 400//400 32//32 22//22 -f 400//400 22//22 401//401 -f 401//401 22//22 21//21 -f 401//401 21//21 402//402 -f 402//402 21//21 25//25 -f 402//402 25//25 403//403 -f 403//403 25//25 24//24 -f 403//403 24//24 404//404 -f 404//404 24//24 23//23 -f 404//404 23//23 405//405 -f 405//405 23//23 46//46 -f 405//405 46//46 406//406 -f 406//406 46//46 45//45 -f 406//406 45//45 407//407 -f 407//407 45//45 44//44 -f 407//407 44//44 408//408 -f 408//408 44//44 11//11 -f 408//408 11//11 409//409 -f 409//409 11//11 10//10 -f 409//409 10//10 410//410 -f 410//410 10//10 8//8 -f 410//410 8//8 411//411 -f 411//411 8//8 7//7 -f 411//411 7//7 412//412 -f 412//412 7//7 37//37 -f 412//412 37//37 413//413 -f 413//413 37//37 36//36 -f 413//413 36//36 414//414 -f 414//414 36//36 35//35 -f 414//414 35//35 415//415 -f 415//415 35//35 5//5 -f 415//415 5//5 416//416 -f 416//416 5//5 4//4 -f 416//416 4//4 417//417 -f 417//417 4//4 16//16 -f 417//417 16//16 418//418 -f 418//418 16//16 28//28 -f 418//418 28//28 419//419 -f 419//419 28//28 27//27 -f 419//419 27//27 420//420 -f 420//420 27//27 26//26 -f 420//420 26//26 421//421 -f 421//421 26//26 15//15 -f 421//421 15//15 422//422 -f 422//422 15//15 13//13 -f 422//422 13//13 423//423 -f 423//423 13//13 12//12 -f 424//424 425//425 426//426 -f 427//427 428//428 429//429 -f 430//430 431//431 432//432 -f 432//432 431//431 433//433 -f 432//432 433//433 434//434 -f 435//435 436//436 437//437 -f 437//437 436//436 438//438 -f 427//427 429//429 439//439 -f 440//440 441//441 442//442 -f 443//443 444//444 445//445 -f 446//446 447//447 443//443 -f 443//443 447//447 448//448 -f 443//443 448//448 444//444 -f 438//438 449//449 437//437 -f 437//437 449//449 450//450 -f 437//437 450//450 429//429 -f 429//429 450//450 451//451 -f 429//429 451//451 439//439 -f 441//441 452//452 442//442 -f 442//442 452//452 453//453 -f 442//442 453//453 454//454 -f 445//445 455//455 443//443 -f 443//443 455//455 456//456 -f 443//443 456//456 426//426 -f 426//426 456//456 457//457 -f 426//426 457//457 424//424 -f 428//428 458//458 429//429 -f 429//429 458//458 459//459 -f 429//429 459//459 432//432 -f 432//432 459//459 460//460 -f 432//432 460//460 430//430 -f 454//454 461//461 442//442 -f 442//442 461//461 462//462 -f 442//442 462//462 437//437 -f 437//437 462//462 463//463 -f 437//437 463//463 435//435 -f 425//425 464//464 426//426 -f 426//426 464//464 465//465 -f 426//426 465//465 442//442 -f 442//442 465//465 466//466 -f 442//442 466//466 440//440 -f 434//434 467//467 432//432 -f 432//432 467//467 468//468 -f 432//432 468//468 443//443 -f 443//443 468//468 469//469 -f 443//443 469//469 446//446 -f 470//470 471//471 472//472 -f 472//472 471//471 473//473 -f 472//472 473//473 474//474 -f 474//474 473//473 475//475 -f 474//474 475//475 476//476 -f 476//476 475//475 477//477 -f 476//476 477//477 478//478 -f 478//478 477//477 479//479 -f 478//478 479//479 480//480 -f 480//480 479//479 481//481 -f 480//480 481//481 482//482 -f 482//482 481//481 483//483 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 486//486 -f 486//486 485//485 487//487 -f 486//486 487//487 488//488 -f 488//488 487//487 489//489 -f 488//488 489//489 490//490 -f 490//490 489//489 491//491 -f 490//490 491//491 492//492 -f 492//492 491//491 493//493 -f 492//492 493//493 494//494 -f 494//494 493//493 495//495 -f 494//494 495//495 496//496 -f 496//496 495//495 497//497 -f 496//496 497//497 498//498 -f 498//498 497//497 499//499 -f 498//498 499//499 500//500 -f 500//500 499//499 501//501 -f 500//500 501//501 502//502 -f 502//502 501//501 503//503 -f 502//502 503//503 504//504 -f 504//504 503//503 505//505 -f 504//504 505//505 506//506 -f 506//506 505//505 507//507 -f 506//506 507//507 508//508 -f 508//508 507//507 509//509 -f 508//508 509//509 510//510 -f 510//510 509//509 511//511 -f 510//510 511//511 512//512 -f 512//512 511//511 513//513 -f 512//512 513//513 514//514 -f 514//514 513//513 515//515 -f 514//514 515//515 516//516 -f 516//516 515//515 517//517 -f 516//516 517//517 518//518 -f 518//518 517//517 519//519 -f 518//518 519//519 520//520 -f 520//520 519//519 521//521 -f 520//520 521//521 522//522 -f 522//522 521//521 523//523 -f 522//522 523//523 524//524 -f 524//524 523//523 525//525 -f 524//524 525//525 526//526 -f 526//526 525//525 527//527 -f 526//526 527//527 528//528 -f 528//528 527//527 529//529 -f 528//528 529//529 530//530 -f 530//530 529//529 531//531 -f 530//530 531//531 532//532 -f 532//532 531//531 533//533 -f 532//532 533//533 534//534 -f 534//534 533//533 535//535 -f 534//534 535//535 536//536 -f 536//536 535//535 537//537 -f 536//536 537//537 538//538 -f 538//538 537//537 539//539 -f 538//538 539//539 540//540 -f 540//540 539//539 541//541 -f 540//540 541//541 542//542 -f 542//542 541//541 543//543 -f 542//542 543//543 544//544 -f 544//544 543//543 545//545 -f 544//544 545//545 546//546 -f 546//546 545//545 547//547 -f 546//546 547//547 548//548 -f 548//548 547//547 549//549 -f 548//548 549//549 470//470 -f 470//470 549//549 471//471 -f 550//550 551//551 552//552 -f 552//552 551//551 553//553 -f 554//554 555//555 556//556 -f 556//556 555//555 557//557 -f 556//556 557//557 558//558 -f 558//558 557//557 559//559 -f 551//551 560//560 553//553 -f 553//553 560//560 561//561 -f 553//553 561//561 562//562 -f 562//562 561//561 563//563 -f 562//562 563//563 564//564 -f 554//554 565//565 555//555 -f 555//555 565//565 566//566 -f 555//555 566//566 567//567 -f 559//559 557//557 568//568 -f 568//568 557//557 569//569 -f 568//568 569//569 570//570 -f 571//571 572//572 573//573 -f 574//574 575//575 576//576 -f 576//576 575//575 577//577 -f 566//566 578//578 567//567 -f 567//567 578//578 579//579 -f 567//567 579//579 552//552 -f 552//552 579//579 580//580 -f 552//552 580//580 550//550 -f 571//571 581//581 572//572 -f 572//572 581//581 582//582 -f 572//572 582//582 569//569 -f 569//569 582//582 583//583 -f 569//569 583//583 570//570 -f 584//584 585//585 586//586 -f 586//586 585//585 587//587 -f 574//574 588//588 575//575 -f 575//575 588//588 589//589 -f 575//575 589//589 586//586 -f 586//586 589//589 590//590 -f 586//586 590//590 584//584 -f 564//564 591//591 562//562 -f 562//562 591//591 592//592 -f 562//562 592//592 577//577 -f 577//577 592//592 593//593 -f 577//577 593//593 576//576 -f 594//594 595//595 596//596 -f 596//596 595//595 597//597 -f 596//596 597//597 573//573 -f 573//573 597//597 598//598 -f 573//573 598//598 571//571 -f 594//594 596//596 599//599 -f 599//599 596//596 600//600 -f 599//599 600//600 601//601 -f 585//585 602//602 587//587 -f 587//587 602//602 603//603 -f 587//587 603//603 600//600 -f 600//600 603//603 604//604 -f 600//600 604//604 601//601 -f 605//605 577//577 606//606 -f 606//606 577//577 575//575 -f 606//606 575//575 607//607 -f 607//607 575//575 586//586 -f 607//607 586//586 608//608 -f 608//608 586//586 587//587 -f 608//608 587//587 609//609 -f 609//609 587//587 600//600 -f 609//609 600//600 610//610 -f 610//610 600//600 596//596 -f 610//610 596//596 611//611 -f 611//611 596//596 573//573 -f 611//611 573//573 612//612 -f 612//612 573//573 572//572 -f 612//612 572//572 613//613 -f 613//613 572//572 569//569 -f 613//613 569//569 614//614 -f 614//614 569//569 557//557 -f 614//614 557//557 615//615 -f 615//615 557//557 555//555 -f 615//615 555//555 616//616 -f 616//616 555//555 567//567 -f 616//616 567//567 617//617 -f 617//617 567//567 552//552 -f 617//617 552//552 618//618 -f 618//618 552//552 553//553 -f 618//618 553//553 619//619 -f 619//619 553//553 562//562 -f 619//619 562//562 605//605 -f 605//605 562//562 577//577 -f 620//620 612//612 621//621 -f 621//621 612//612 613//613 -f 621//621 613//613 622//622 -f 622//622 613//613 614//614 -f 622//622 614//614 623//623 -f 623//623 614//614 615//615 -f 623//623 615//615 624//624 -f 624//624 615//615 616//616 -f 624//624 616//616 625//625 -f 625//625 616//616 617//617 -f 625//625 617//617 626//626 -f 626//626 617//617 618//618 -f 626//626 618//618 627//627 -f 627//627 618//618 619//619 -f 627//627 619//619 628//628 -f 628//628 619//619 605//605 -f 628//628 605//605 629//629 -f 629//629 605//605 606//606 -f 629//629 606//606 630//630 -f 630//630 606//606 607//607 -f 630//630 607//607 631//631 -f 631//631 607//607 608//608 -f 631//631 608//608 632//632 -f 632//632 608//608 609//609 -f 632//632 609//609 633//633 -f 633//633 609//609 610//610 -f 633//633 610//610 634//634 -f 634//634 610//610 611//611 -f 634//634 611//611 620//620 -f 620//620 611//611 612//612 -f 635//635 627//627 628//628 -f 635//635 636//636 627//627 -f 627//627 636//636 637//637 -f 627//627 637//637 626//626 -f 637//637 638//638 626//626 -f 626//626 638//638 639//639 -f 626//626 639//639 625//625 -f 639//639 640//640 625//625 -f 625//625 640//640 641//641 -f 625//625 641//641 624//624 -f 641//641 642//642 624//624 -f 624//624 642//642 643//643 -f 624//624 643//643 623//623 -f 643//643 644//644 623//623 -f 623//623 644//644 645//645 -f 623//623 645//645 622//622 -f 645//645 646//646 622//622 -f 622//622 646//646 647//647 -f 622//622 647//647 621//621 -f 647//647 648//648 621//621 -f 621//621 648//648 649//649 -f 621//621 649//649 620//620 -f 649//649 650//650 620//620 -f 620//620 650//650 651//651 -f 620//620 651//651 634//634 -f 651//651 652//652 634//634 -f 634//634 652//652 653//653 -f 634//634 653//653 633//633 -f 653//653 654//654 633//633 -f 633//633 654//654 655//655 -f 633//633 655//655 632//632 -f 655//655 656//656 632//632 -f 632//632 656//656 657//657 -f 632//632 657//657 631//631 -f 657//657 658//658 631//631 -f 631//631 658//658 659//659 -f 631//631 659//659 630//630 -f 659//659 660//660 630//630 -f 630//630 660//660 661//661 -f 630//630 661//661 629//629 -f 661//661 662//662 629//629 -f 629//629 662//662 663//663 -f 629//629 663//663 628//628 -f 628//628 663//663 664//664 -f 628//628 664//664 635//635 -f 665//665 666//666 667//667 -f 667//667 666//666 668//668 -f 667//667 668//668 669//669 -f 670//670 671//671 667//667 -f 667//667 671//671 672//672 -f 667//667 672//672 665//665 -f 673//673 674//674 667//667 -f 667//667 674//674 675//675 -f 667//667 675//675 670//670 -f 676//676 677//677 667//667 -f 667//667 677//677 678//678 -f 667//667 678//678 673//673 -f 669//669 679//679 667//667 -f 667//667 679//679 680//680 -f 667//667 680//680 676//676 -f 681//681 682//682 437//437 -f 437//437 682//682 442//442 -f 682//682 683//683 442//442 -f 442//442 683//683 426//426 -f 683//683 684//684 426//426 -f 426//426 684//684 443//443 -f 684//684 685//685 443//443 -f 443//443 685//685 432//432 -f 685//685 686//686 432//432 -f 432//432 686//686 429//429 -f 686//686 681//681 429//429 -f 429//429 681//681 437//437 -f 686//686 685//685 681//681 -f 681//681 685//685 684//684 -f 681//681 684//684 682//682 -f 682//682 684//684 683//683 -f 669//669 668//668 648//648 -f 648//648 647//647 669//669 -f 669//669 647//647 646//646 -f 669//669 646//646 679//679 -f 646//646 645//645 679//679 -f 679//679 645//645 644//644 -f 679//679 644//644 680//680 -f 644//644 643//643 680//680 -f 680//680 643//643 642//642 -f 680//680 642//642 676//676 -f 642//642 641//641 676//676 -f 676//676 641//641 640//640 -f 676//676 640//640 677//677 -f 640//640 639//639 677//677 -f 677//677 639//639 638//638 -f 677//677 638//638 678//678 -f 638//638 637//637 678//678 -f 678//678 637//637 636//636 -f 678//678 636//636 673//673 -f 636//636 635//635 673//673 -f 673//673 635//635 664//664 -f 673//673 664//664 674//674 -f 664//664 663//663 674//674 -f 674//674 663//663 662//662 -f 674//674 662//662 675//675 -f 662//662 661//661 675//675 -f 675//675 661//661 660//660 -f 675//675 660//660 670//670 -f 660//660 659//659 670//670 -f 670//670 659//659 658//658 -f 670//670 658//658 671//671 -f 658//658 657//657 671//671 -f 671//671 657//657 656//656 -f 671//671 656//656 672//672 -f 656//656 655//655 672//672 -f 672//672 655//655 654//654 -f 672//672 654//654 665//665 -f 654//654 653//653 665//665 -f 665//665 653//653 652//652 -f 665//665 652//652 666//666 -f 652//652 651//651 666//666 -f 666//666 651//651 650//650 -f 666//666 650//650 668//668 -f 668//668 650//650 649//649 -f 668//668 649//649 648//648 -f 513//513 687//687 515//515 -f 515//515 687//687 688//688 -f 515//515 688//688 517//517 -f 517//517 688//688 689//689 -f 517//517 689//689 519//519 -f 519//519 689//689 690//690 -f 519//519 690//690 521//521 -f 521//521 690//690 691//691 -f 521//521 691//691 523//523 -f 523//523 691//691 692//692 -f 523//523 692//692 525//525 -f 525//525 692//692 693//693 -f 525//525 693//693 527//527 -f 527//527 693//693 694//694 -f 527//527 694//694 529//529 -f 529//529 694//694 695//695 -f 529//529 695//695 531//531 -f 531//531 695//695 696//696 -f 531//531 696//696 533//533 -f 533//533 696//696 697//697 -f 533//533 697//697 535//535 -f 535//535 697//697 698//698 -f 535//535 698//698 537//537 -f 537//537 698//698 699//699 -f 537//537 699//699 539//539 -f 539//539 699//699 700//700 -f 539//539 700//700 541//541 -f 541//541 700//700 701//701 -f 541//541 701//701 543//543 -f 543//543 701//701 702//702 -f 543//543 702//702 545//545 -f 545//545 702//702 703//703 -f 545//545 703//703 547//547 -f 547//547 703//703 704//704 -f 547//547 704//704 549//549 -f 549//549 704//704 705//705 -f 549//549 705//705 471//471 -f 471//471 705//705 706//706 -f 471//471 706//706 473//473 -f 473//473 706//706 707//707 -f 473//473 707//707 475//475 -f 475//475 707//707 708//708 -f 475//475 708//708 477//477 -f 477//477 708//708 709//709 -f 477//477 709//709 479//479 -f 479//479 709//709 710//710 -f 479//479 710//710 481//481 -f 481//481 710//710 711//711 -f 481//481 711//711 483//483 -f 483//483 711//711 712//712 -f 483//483 712//712 485//485 -f 485//485 712//712 713//713 -f 485//485 713//713 487//487 -f 487//487 713//713 714//714 -f 487//487 714//714 489//489 -f 489//489 714//714 715//715 -f 489//489 715//715 491//491 -f 491//491 715//715 716//716 -f 491//491 716//716 493//493 -f 493//493 716//716 717//717 -f 493//493 717//717 495//495 -f 495//495 717//717 718//718 -f 495//495 718//718 497//497 -f 497//497 718//718 719//719 -f 497//497 719//719 499//499 -f 499//499 719//719 720//720 -f 499//499 720//720 501//501 -f 501//501 720//720 721//721 -f 501//501 721//721 503//503 -f 503//503 721//721 722//722 -f 503//503 722//722 505//505 -f 505//505 722//722 723//723 -f 505//505 723//723 507//507 -f 507//507 723//723 724//724 -f 507//507 724//724 509//509 -f 509//509 724//724 725//725 -f 509//509 725//725 511//511 -f 511//511 725//725 726//726 -f 511//511 726//726 513//513 -f 513//513 726//726 687//687 -f 726//726 727//727 687//687 -f 687//687 727//727 728//728 -f 687//687 728//728 688//688 -f 688//688 728//728 729//729 -f 688//688 729//729 689//689 -f 689//689 729//729 730//730 -f 689//689 730//730 690//690 -f 690//690 730//730 731//731 -f 690//690 731//731 691//691 -f 691//691 731//731 732//732 -f 691//691 732//732 692//692 -f 692//692 732//732 733//733 -f 692//692 733//733 693//693 -f 693//693 733//733 734//734 -f 693//693 734//734 694//694 -f 694//694 734//734 735//735 -f 694//694 735//735 695//695 -f 695//695 735//735 736//736 -f 695//695 736//736 696//696 -f 696//696 736//736 737//737 -f 696//696 737//737 697//697 -f 697//697 737//737 738//738 -f 697//697 738//738 698//698 -f 698//698 738//738 739//739 -f 698//698 739//739 699//699 -f 699//699 739//739 740//740 -f 699//699 740//740 700//700 -f 700//700 740//740 741//741 -f 700//700 741//741 701//701 -f 701//701 741//741 742//742 -f 701//701 742//742 702//702 -f 702//702 742//742 743//743 -f 702//702 743//743 703//703 -f 703//703 743//743 744//744 -f 703//703 744//744 704//704 -f 704//704 744//744 745//745 -f 704//704 745//745 705//705 -f 705//705 745//745 746//746 -f 705//705 746//746 706//706 -f 706//706 746//746 747//747 -f 706//706 747//747 707//707 -f 707//707 747//747 748//748 -f 707//707 748//748 708//708 -f 708//708 748//748 749//749 -f 708//708 749//749 709//709 -f 709//709 749//749 750//750 -f 709//709 750//750 710//710 -f 710//710 750//750 751//751 -f 710//710 751//751 711//711 -f 711//711 751//751 752//752 -f 711//711 752//752 712//712 -f 712//712 752//752 753//753 -f 712//712 753//753 713//713 -f 713//713 753//753 754//754 -f 713//713 754//754 714//714 -f 714//714 754//754 755//755 -f 714//714 755//755 715//715 -f 715//715 755//755 756//756 -f 715//715 756//756 716//716 -f 716//716 756//756 757//757 -f 716//716 757//757 717//717 -f 717//717 757//757 758//758 -f 717//717 758//758 718//718 -f 718//718 758//758 759//759 -f 718//718 759//759 719//719 -f 719//719 759//759 760//760 -f 719//719 760//760 720//720 -f 720//720 760//760 761//761 -f 720//720 761//761 721//721 -f 721//721 761//761 762//762 -f 721//721 762//762 722//722 -f 722//722 762//762 763//763 -f 722//722 763//763 723//723 -f 723//723 763//763 764//764 -f 723//723 764//764 724//724 -f 724//724 764//764 765//765 -f 724//724 765//765 725//725 -f 725//725 765//765 766//766 -f 725//725 766//766 726//726 -f 726//726 766//766 727//727 -f 766//766 598//598 727//727 -f 727//727 598//598 597//597 -f 727//727 597//597 728//728 -f 728//728 597//597 595//595 -f 728//728 595//595 729//729 -f 729//729 595//595 594//594 -f 729//729 594//594 730//730 -f 730//730 594//594 599//599 -f 730//730 599//599 731//731 -f 731//731 599//599 601//601 -f 731//731 601//601 732//732 -f 732//732 601//601 604//604 -f 732//732 604//604 733//733 -f 733//733 604//604 603//603 -f 733//733 603//603 734//734 -f 734//734 603//603 602//602 -f 734//734 602//602 735//735 -f 735//735 602//602 585//585 -f 735//735 585//585 736//736 -f 736//736 585//585 584//584 -f 736//736 584//584 737//737 -f 737//737 584//584 590//590 -f 737//737 590//590 738//738 -f 738//738 590//590 589//589 -f 738//738 589//589 739//739 -f 739//739 589//589 588//588 -f 739//739 588//588 740//740 -f 740//740 588//588 574//574 -f 740//740 574//574 741//741 -f 741//741 574//574 576//576 -f 741//741 576//576 742//742 -f 742//742 576//576 593//593 -f 742//742 593//593 743//743 -f 743//743 593//593 592//592 -f 743//743 592//592 744//744 -f 744//744 592//592 591//591 -f 744//744 591//591 745//745 -f 745//745 591//591 564//564 -f 745//745 564//564 746//746 -f 746//746 564//564 563//563 -f 746//746 563//563 747//747 -f 747//747 563//563 561//561 -f 747//747 561//561 748//748 -f 748//748 561//561 560//560 -f 748//748 560//560 749//749 -f 749//749 560//560 551//551 -f 749//749 551//551 750//750 -f 750//750 551//551 550//550 -f 750//750 550//550 751//751 -f 751//751 550//550 580//580 -f 751//751 580//580 752//752 -f 752//752 580//580 579//579 -f 752//752 579//579 753//753 -f 753//753 579//579 578//578 -f 753//753 578//578 754//754 -f 754//754 578//578 566//566 -f 754//754 566//566 755//755 -f 755//755 566//566 565//565 -f 755//755 565//565 756//756 -f 756//756 565//565 554//554 -f 756//756 554//554 757//757 -f 757//757 554//554 556//556 -f 757//757 556//556 758//758 -f 758//758 556//556 558//558 -f 758//758 558//558 759//759 -f 759//759 558//558 559//559 -f 759//759 559//559 760//760 -f 760//760 559//559 568//568 -f 760//760 568//568 761//761 -f 761//761 568//568 570//570 -f 761//761 570//570 762//762 -f 762//762 570//570 583//583 -f 762//762 583//583 763//763 -f 763//763 583//583 582//582 -f 763//763 582//582 764//764 -f 764//764 582//582 581//581 -f 764//764 581//581 765//765 -f 765//765 581//581 571//571 -f 765//765 571//571 766//766 -f 766//766 571//571 598//598 -f 472//472 767//767 470//470 -f 470//470 767//767 768//768 -f 470//470 768//768 548//548 -f 548//548 768//768 769//769 -f 548//548 769//769 546//546 -f 546//546 769//769 770//770 -f 546//546 770//770 544//544 -f 544//544 770//770 771//771 -f 544//544 771//771 542//542 -f 542//542 771//771 772//772 -f 542//542 772//772 540//540 -f 540//540 772//772 773//773 -f 540//540 773//773 538//538 -f 538//538 773//773 774//774 -f 538//538 774//774 536//536 -f 536//536 774//774 775//775 -f 536//536 775//775 534//534 -f 534//534 775//775 776//776 -f 534//534 776//776 532//532 -f 532//532 776//776 777//777 -f 532//532 777//777 530//530 -f 530//530 777//777 778//778 -f 530//530 778//778 528//528 -f 528//528 778//778 779//779 -f 528//528 779//779 526//526 -f 526//526 779//779 780//780 -f 526//526 780//780 524//524 -f 524//524 780//780 781//781 -f 524//524 781//781 522//522 -f 522//522 781//781 782//782 -f 522//522 782//782 520//520 -f 520//520 782//782 783//783 -f 520//520 783//783 518//518 -f 518//518 783//783 784//784 -f 518//518 784//784 516//516 -f 516//516 784//784 785//785 -f 516//516 785//785 514//514 -f 514//514 785//785 786//786 -f 514//514 786//786 512//512 -f 512//512 786//786 787//787 -f 512//512 787//787 510//510 -f 510//510 787//787 788//788 -f 510//510 788//788 508//508 -f 508//508 788//788 789//789 -f 508//508 789//789 506//506 -f 506//506 789//789 790//790 -f 506//506 790//790 504//504 -f 504//504 790//790 791//791 -f 504//504 791//791 502//502 -f 502//502 791//791 792//792 -f 502//502 792//792 500//500 -f 500//500 792//792 793//793 -f 500//500 793//793 498//498 -f 498//498 793//793 794//794 -f 498//498 794//794 496//496 -f 496//496 794//794 795//795 -f 496//496 795//795 494//494 -f 494//494 795//795 796//796 -f 494//494 796//796 492//492 -f 492//492 796//796 797//797 -f 492//492 797//797 490//490 -f 490//490 797//797 798//798 -f 490//490 798//798 488//488 -f 488//488 798//798 799//799 -f 488//488 799//799 486//486 -f 486//486 799//799 800//800 -f 486//486 800//800 484//484 -f 484//484 800//800 801//801 -f 484//484 801//801 482//482 -f 482//482 801//801 802//802 -f 482//482 802//802 480//480 -f 480//480 802//802 803//803 -f 480//480 803//803 478//478 -f 478//478 803//803 804//804 -f 478//478 804//804 476//476 -f 476//476 804//804 805//805 -f 476//476 805//805 474//474 -f 474//474 805//805 806//806 -f 474//474 806//806 472//472 -f 472//472 806//806 767//767 -f 806//806 807//807 767//767 -f 767//767 807//807 808//808 -f 767//767 808//808 768//768 -f 768//768 808//808 809//809 -f 768//768 809//809 769//769 -f 769//769 809//809 810//810 -f 769//769 810//810 770//770 -f 770//770 810//810 811//811 -f 770//770 811//811 771//771 -f 771//771 811//811 812//812 -f 771//771 812//812 772//772 -f 772//772 812//812 813//813 -f 772//772 813//813 773//773 -f 773//773 813//813 814//814 -f 773//773 814//814 774//774 -f 774//774 814//814 815//815 -f 774//774 815//815 775//775 -f 775//775 815//815 816//816 -f 775//775 816//816 776//776 -f 776//776 816//816 817//817 -f 776//776 817//817 777//777 -f 777//777 817//817 818//818 -f 777//777 818//818 778//778 -f 778//778 818//818 819//819 -f 778//778 819//819 779//779 -f 779//779 819//819 820//820 -f 779//779 820//820 780//780 -f 780//780 820//820 821//821 -f 780//780 821//821 781//781 -f 781//781 821//821 822//822 -f 781//781 822//822 782//782 -f 782//782 822//822 823//823 -f 782//782 823//823 783//783 -f 783//783 823//823 824//824 -f 783//783 824//824 784//784 -f 784//784 824//824 825//825 -f 784//784 825//825 785//785 -f 785//785 825//825 826//826 -f 785//785 826//826 786//786 -f 786//786 826//826 827//827 -f 786//786 827//827 787//787 -f 787//787 827//827 828//828 -f 787//787 828//828 788//788 -f 788//788 828//828 829//829 -f 788//788 829//829 789//789 -f 789//789 829//829 830//830 -f 789//789 830//830 790//790 -f 790//790 830//830 831//831 -f 790//790 831//831 791//791 -f 791//791 831//831 832//832 -f 791//791 832//832 792//792 -f 792//792 832//832 833//833 -f 792//792 833//833 793//793 -f 793//793 833//833 834//834 -f 793//793 834//834 794//794 -f 794//794 834//834 835//835 -f 794//794 835//835 795//795 -f 795//795 835//835 836//836 -f 795//795 836//836 796//796 -f 796//796 836//836 837//837 -f 796//796 837//837 797//797 -f 797//797 837//837 838//838 -f 797//797 838//838 798//798 -f 798//798 838//838 839//839 -f 798//798 839//839 799//799 -f 799//799 839//839 840//840 -f 799//799 840//840 800//800 -f 800//800 840//840 841//841 -f 800//800 841//841 801//801 -f 801//801 841//841 842//842 -f 801//801 842//842 802//802 -f 802//802 842//842 843//843 -f 802//802 843//843 803//803 -f 803//803 843//843 844//844 -f 803//803 844//844 804//804 -f 804//804 844//844 845//845 -f 804//804 845//845 805//805 -f 805//805 845//845 846//846 -f 805//805 846//846 806//806 -f 806//806 846//846 807//807 -f 846//846 435//435 807//807 -f 807//807 435//435 463//463 -f 807//807 463//463 808//808 -f 808//808 463//463 462//462 -f 808//808 462//462 809//809 -f 809//809 462//462 461//461 -f 809//809 461//461 810//810 -f 810//810 461//461 454//454 -f 810//810 454//454 811//811 -f 811//811 454//454 453//453 -f 811//811 453//453 812//812 -f 812//812 453//453 452//452 -f 812//812 452//452 813//813 -f 813//813 452//452 441//441 -f 813//813 441//441 814//814 -f 814//814 441//441 440//440 -f 814//814 440//440 815//815 -f 815//815 440//440 466//466 -f 815//815 466//466 816//816 -f 816//816 466//466 465//465 -f 816//816 465//465 817//817 -f 817//817 465//465 464//464 -f 817//817 464//464 818//818 -f 818//818 464//464 425//425 -f 818//818 425//425 819//819 -f 819//819 425//425 424//424 -f 819//819 424//424 820//820 -f 820//820 424//424 457//457 -f 820//820 457//457 821//821 -f 821//821 457//457 456//456 -f 821//821 456//456 822//822 -f 822//822 456//456 455//455 -f 822//822 455//455 823//823 -f 823//823 455//455 445//445 -f 823//823 445//445 824//824 -f 824//824 445//445 444//444 -f 824//824 444//444 825//825 -f 825//825 444//444 448//448 -f 825//825 448//448 826//826 -f 826//826 448//448 447//447 -f 826//826 447//447 827//827 -f 827//827 447//447 446//446 -f 827//827 446//446 828//828 -f 828//828 446//446 469//469 -f 828//828 469//469 829//829 -f 829//829 469//469 468//468 -f 829//829 468//468 830//830 -f 830//830 468//468 467//467 -f 830//830 467//467 831//831 -f 831//831 467//467 434//434 -f 831//831 434//434 832//832 -f 832//832 434//434 433//433 -f 832//832 433//433 833//833 -f 833//833 433//433 431//431 -f 833//833 431//431 834//834 -f 834//834 431//431 430//430 -f 834//834 430//430 835//835 -f 835//835 430//430 460//460 -f 835//835 460//460 836//836 -f 836//836 460//460 459//459 -f 836//836 459//459 837//837 -f 837//837 459//459 458//458 -f 837//837 458//458 838//838 -f 838//838 458//458 428//428 -f 838//838 428//428 839//839 -f 839//839 428//428 427//427 -f 839//839 427//427 840//840 -f 840//840 427//427 439//439 -f 840//840 439//439 841//841 -f 841//841 439//439 451//451 -f 841//841 451//451 842//842 -f 842//842 451//451 450//450 -f 842//842 450//450 843//843 -f 843//843 450//450 449//449 -f 843//843 449//449 844//844 -f 844//844 449//449 438//438 -f 844//844 438//438 845//845 -f 845//845 438//438 436//436 -f 845//845 436//436 846//846 -f 846//846 436//436 435//435 -# 1684 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_bosch.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_bosch.obj deleted file mode 100644 index f64c186f9..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_bosch.obj +++ /dev/null @@ -1,19664 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object robot_bosch.obj -# -# Vertices: 4900 -# Faces: 9848 -# -#### -vn -0.835724 0.154358 -0.527009 -v 0.016750 0.050500 0.089800 -vn -0.930676 -0.032168 -0.364427 -v 0.016750 0.050000 0.089800 -vn -0.724383 -0.071345 0.685697 -v 0.016750 0.050000 0.092800 -vn -0.835724 -0.154358 -0.527009 -v 0.016750 0.064500 0.089800 -vn -0.723069 0.069010 0.687320 -v 0.016750 0.065000 0.092800 -vn -0.929197 0.028377 -0.368493 -v 0.016750 0.065000 0.089800 -vn -0.565890 0.681580 -0.463915 -v 0.017957 0.066471 0.088593 -vn -0.507594 0.708580 -0.490167 -v 0.018250 0.066500 0.088300 -vn -0.462059 0.681951 -0.566960 -v 0.030543 0.066471 0.076007 -vn -0.364428 0.032166 -0.930676 -v 0.031750 0.065000 0.074800 -vn -0.490166 0.708581 -0.507593 -v 0.030250 0.066500 0.076300 -vn -0.527009 -0.154357 -0.835725 -v 0.031750 0.064500 0.074800 -vn -0.805199 0.443984 -0.393108 -v 0.017189 0.066061 0.089361 -vn -0.737770 0.534557 -0.412242 -v 0.017417 0.066247 0.089133 -vn -0.657787 0.614313 -0.435816 -v 0.017676 0.066386 0.088874 -vn -0.432827 0.620652 -0.653798 -v 0.030824 0.066386 0.075726 -vn -0.409974 0.534496 -0.739078 -v 0.031083 0.066247 0.075467 -vn -0.389297 0.450871 -0.803221 -v 0.031311 0.066061 0.075239 -vn -0.374088 0.343126 -0.861582 -v 0.031497 0.065833 0.075053 -vn -0.360861 0.241396 -0.900837 -v 0.031636 0.065574 0.074914 -vn -0.352696 0.117310 -0.928355 -v 0.031721 0.065293 0.074829 -vn -0.926433 0.119908 -0.356852 -v 0.016779 0.065293 0.089771 -vn -0.900671 0.235477 -0.365161 -v 0.016864 0.065574 0.089686 -vn -0.859908 0.343991 -0.377132 -v 0.017003 0.065833 0.089547 -vn 0.685820 0.724268 -0.071316 -v 0.034750 0.066500 0.076300 -vn 0.577350 0.577351 0.577350 -v 0.034750 0.066500 0.092800 -vn -0.069660 0.723418 0.686887 -v 0.018250 0.066500 0.092800 -vn 0.685697 0.071345 -0.724382 -v 0.034750 0.065000 0.074800 -vn -0.527010 0.154357 -0.835724 -v 0.031750 0.050500 0.074800 -vn 0.687320 -0.069011 -0.723069 -v 0.034750 0.050000 0.074800 -vn -0.368496 -0.028375 -0.929196 -v 0.031750 0.050000 0.074800 -vn 0.935652 -0.196022 -0.293480 -v 0.034750 0.058840 0.083851 -vn 0.936135 -0.279035 -0.213986 -v 0.034750 0.059433 0.083305 -vn 0.936831 -0.331247 -0.112349 -v 0.034750 0.059817 0.082596 -vn 0.577352 -0.577349 0.577350 -v 0.034750 0.048500 0.092800 -vn 0.935187 0.024235 -0.353324 -v 0.034750 0.057298 0.084242 -vn 0.935346 -0.091120 -0.341797 -v 0.034750 0.058101 0.084175 -vn 0.933285 0.026011 0.358194 -v 0.034750 0.057298 0.079358 -vn 0.933767 -0.091592 0.345964 -v 0.034750 0.058101 0.079425 -vn 0.934437 -0.197880 0.296093 -v 0.034750 0.058840 0.079749 -vn 0.935292 0.308561 -0.173263 -v 0.034750 0.055345 0.082966 -vn 0.935186 0.235752 -0.264288 -v 0.034750 0.055841 0.083603 -vn 0.935145 0.137351 -0.326555 -v 0.034750 0.056516 0.084044 -vn 0.937758 -0.347290 0.000001 -v 0.034750 0.059950 0.081800 -vn 0.936556 -0.332263 0.111645 -v 0.034750 0.059817 0.081004 -vn 0.665894 0.689268 -0.285474 -v 0.034750 0.066386 0.075726 -vn 0.935349 -0.281083 0.214746 -v 0.034750 0.059433 0.080295 -vn 0.665936 0.527534 -0.527483 -v 0.034750 0.066061 0.075239 -vn 0.665960 0.285515 -0.689187 -v 0.034750 0.065574 0.074914 -vn 0.932580 0.316735 0.173130 -v 0.034750 0.055345 0.080634 -vn 0.686888 -0.723418 -0.069659 -v 0.034750 0.048500 0.076300 -vn 0.668336 -0.687328 -0.284442 -v 0.034750 0.048614 0.075726 -vn 0.932948 0.141722 0.330943 -v 0.034750 0.056516 0.079556 -vn 0.932718 0.242449 0.266936 -v 0.034750 0.055841 0.079997 -vn 0.668942 -0.284596 -0.686674 -v 0.034750 0.049426 0.074914 -vn 0.668670 -0.525942 -0.525609 -v 0.034750 0.048939 0.075239 -vn 0.931816 0.356831 0.066256 -v 0.034750 0.055083 0.081397 -vn 0.930915 0.365236 -0.000001 -v 0.034750 0.055050 0.081800 -vn 0.934296 0.349065 -0.072415 -v 0.034750 0.055083 0.082203 -vn 0.279030 0.213982 0.936138 -v 0.021817 0.055995 0.092800 -vn 0.331242 0.112348 0.936833 -v 0.021433 0.056704 0.092800 -vn 0.347288 -0.000000 0.937759 -v 0.021300 0.057500 0.092800 -vn -0.284441 0.687328 0.668336 -v 0.017676 0.066386 0.092800 -vn 0.197877 -0.296088 0.934439 -v 0.022410 0.059551 0.092800 -vn 0.332260 -0.111643 0.936557 -v 0.021433 0.058296 0.092800 -vn 0.281076 -0.214741 0.935352 -v 0.021817 0.059005 0.092800 -vn -0.686675 0.284595 0.668942 -v 0.016864 0.065574 0.092800 -vn -0.525609 0.525943 0.668670 -v 0.017189 0.066061 0.092800 -vn -0.349056 0.072414 0.934300 -v 0.026167 0.057097 0.092800 -vn -0.308560 0.173261 0.935292 -v 0.025905 0.056334 0.092800 -vn -0.071317 -0.724268 0.685820 -v 0.018250 0.048500 0.092800 -vn 0.091119 0.341787 0.935350 -v 0.023149 0.055125 0.092800 -vn -0.285474 -0.689267 0.665894 -v 0.017676 0.048614 0.092800 -vn 0.196022 0.293479 0.935652 -v 0.022410 0.055449 0.092800 -vn -0.527482 -0.527534 0.665935 -v 0.017189 0.048939 0.092800 -vn 0.091591 -0.345959 0.933769 -v 0.023149 0.059875 0.092800 -vn -0.026012 -0.358192 0.933286 -v 0.023952 0.059942 0.092800 -vn -0.141722 -0.330943 0.932948 -v 0.024734 0.059744 0.092800 -vn -0.242443 -0.266930 0.932722 -v 0.025409 0.059303 0.092800 -vn -0.235751 0.264284 0.935187 -v 0.025409 0.055697 0.092800 -vn -0.137352 0.326553 0.935146 -v 0.024734 0.055256 0.092800 -vn -0.024233 0.353313 0.935191 -v 0.023952 0.055058 0.092800 -vn -0.689187 -0.285515 0.665960 -v 0.016864 0.049426 0.092800 -vn -0.316729 -0.173128 0.932582 -v 0.025905 0.058666 0.092800 -vn -0.356823 -0.066254 0.931820 -v 0.026167 0.057903 0.092800 -vn -0.365232 -0.000000 0.930917 -v 0.026200 0.057500 0.092800 -vn -0.933285 -0.026011 0.358194 -v 0.031750 0.057702 0.079358 -vn -0.933767 0.091592 0.345963 -v 0.031750 0.056899 0.079425 -vn -0.935292 -0.308561 -0.173263 -v 0.031750 0.059655 0.082966 -vn -0.935186 -0.235753 -0.264288 -v 0.031750 0.059159 0.083603 -vn -0.577351 -0.577350 -0.577350 -v 0.031750 0.064500 0.089800 -vn -0.936556 0.332263 0.111645 -v 0.031750 0.055183 0.081004 -vn -0.935349 0.281082 0.214744 -v 0.031750 0.055567 0.080295 -vn -0.934437 0.197879 0.296093 -v 0.031750 0.056160 0.079749 -vn -0.935145 -0.137351 -0.326554 -v 0.031750 0.058484 0.084044 -vn -0.935187 -0.024235 -0.353324 -v 0.031750 0.057702 0.084242 -vn -0.577351 0.577351 -0.577349 -v 0.031750 0.050500 0.089800 -vn -0.935346 0.091120 -0.341796 -v 0.031750 0.056899 0.084175 -vn -0.935652 0.196021 -0.293479 -v 0.031750 0.056160 0.083851 -vn -0.936136 0.279034 -0.213984 -v 0.031750 0.055567 0.083305 -vn -0.936832 0.331246 -0.112348 -v 0.031750 0.055183 0.082596 -vn -0.937756 0.347294 0.000000 -v 0.031750 0.055050 0.081800 -vn -0.932948 -0.141722 0.330943 -v 0.031750 0.058484 0.079556 -vn -0.932718 -0.242450 0.266936 -v 0.031750 0.059159 0.079997 -vn -0.932579 -0.316736 0.173131 -v 0.031750 0.059655 0.080634 -vn -0.931818 -0.356827 0.066256 -v 0.031750 0.059917 0.081397 -vn -0.930917 -0.365232 -0.000001 -v 0.031750 0.059950 0.081800 -vn -0.934298 -0.349061 -0.072415 -v 0.031750 0.059917 0.082203 -vn -0.347298 0.000000 -0.937755 -v 0.026200 0.057500 0.089800 -vn -0.332266 -0.111645 -0.936555 -v 0.026067 0.058296 0.089800 -vn -0.281083 -0.214747 -0.935348 -v 0.025683 0.059005 0.089800 -vn 0.141725 -0.330951 -0.932944 -v 0.022766 0.059744 0.089800 -vn 0.242450 -0.266937 -0.932718 -v 0.022091 0.059303 0.089800 -vn 0.316737 -0.173132 -0.932579 -v 0.021595 0.058666 0.089800 -vn 0.356128 -0.059950 -0.932512 -v 0.021333 0.057903 0.089800 -vn -0.197881 -0.296094 -0.934437 -v 0.025090 0.059551 0.089800 -vn -0.091593 -0.345967 -0.933765 -v 0.024351 0.059875 0.089800 -vn 0.026012 -0.358200 -0.933282 -v 0.023548 0.059942 0.089800 -vn 0.348376 0.066126 -0.935020 -v 0.021333 0.057097 0.089800 -vn 0.308569 0.173265 -0.935289 -v 0.021595 0.056334 0.089800 -vn 0.235757 0.264291 -0.935184 -v 0.022091 0.055697 0.089800 -vn 0.137355 0.326562 -0.935142 -v 0.022766 0.055256 0.089800 -vn 0.024234 0.353322 -0.935188 -v 0.023548 0.055058 0.089800 -vn -0.091121 0.341795 -0.935347 -v 0.024351 0.055125 0.089800 -vn -0.196026 0.293485 -0.935650 -v 0.025090 0.055449 0.089800 -vn -0.279037 0.213987 -0.936135 -v 0.025683 0.055995 0.089800 -vn -0.331249 0.112349 -0.936831 -v 0.026067 0.056704 0.089800 -vn -0.463917 -0.681588 -0.565879 -v 0.030543 0.048529 0.076007 -vn -0.490169 -0.708581 -0.507590 -v 0.030250 0.048500 0.076300 -vn -0.566954 -0.681960 -0.462054 -v 0.017957 0.048529 0.088593 -vn -0.507592 -0.708579 -0.490169 -v 0.018250 0.048500 0.088300 -vn -0.393128 -0.443972 -0.805195 -v 0.031311 0.048939 0.075239 -vn -0.412224 -0.534570 -0.737771 -v 0.031083 0.048753 0.075467 -vn -0.435827 -0.614297 -0.657794 -v 0.030824 0.048614 0.075726 -vn -0.653805 -0.620653 -0.432815 -v 0.017676 0.048614 0.088874 -vn -0.739072 -0.534492 -0.409989 -v 0.017417 0.048753 0.089133 -vn -0.803225 -0.450876 -0.389281 -v 0.017189 0.048939 0.089361 -vn -0.861576 -0.343123 -0.374102 -v 0.017003 0.049167 0.089547 -vn -0.900842 -0.241391 -0.360851 -v 0.016864 0.049426 0.089686 -vn -0.928370 -0.117323 -0.352652 -v 0.016779 0.049707 0.089771 -vn -0.356895 -0.119898 -0.926418 -v 0.031721 0.049707 0.074829 -vn -0.365172 -0.235478 -0.900666 -v 0.031636 0.049426 0.074914 -vn -0.377114 -0.343999 -0.859912 -v 0.031497 0.049167 0.075053 -vn 0.382703 0.908420 -0.168262 -v 0.034550 0.055281 0.082170 -vn -0.392630 0.919697 0.000000 -v 0.031950 0.055250 0.081800 -vn -0.387152 0.892580 -0.231116 -v 0.031950 0.055372 0.082531 -vn 0.323439 0.899171 -0.294751 -v 0.034550 0.055386 0.082570 -vn -0.381745 0.841815 -0.381600 -v 0.031950 0.055386 0.082570 -vn 0.383266 0.800952 -0.459982 -v 0.034550 0.055521 0.082871 -vn -0.386599 0.765579 -0.514228 -v 0.031950 0.055724 0.083182 -vn 0.333858 0.745436 -0.576944 -v 0.034550 0.055776 0.083246 -vn -0.375874 0.665792 -0.644546 -v 0.031950 0.055776 0.083246 -vn 0.383824 0.602845 -0.699469 -v 0.034550 0.055976 0.083455 -vn -0.386049 0.551769 -0.739268 -v 0.031950 0.056269 0.083684 -vn 0.343688 0.506745 -0.790625 -v 0.034550 0.056375 0.083749 -vn -0.369049 0.411131 -0.833531 -v 0.031950 0.056375 0.083749 -vn 0.384381 0.336589 -0.859627 -v 0.034550 0.056596 0.083860 -vn -0.385489 0.275372 -0.880663 -v 0.031950 0.056948 0.083981 -vn 0.352862 0.211100 -0.911551 -v 0.034550 0.057109 0.084016 -vn -0.361346 0.107158 -0.926254 -v 0.031950 0.057109 0.084016 -vn 0.384929 0.032372 -0.922378 -v 0.034550 0.057314 0.084042 -vn -0.384929 -0.032371 -0.922378 -v 0.031950 0.057686 0.084042 -vn 0.361346 -0.107160 -0.926254 -v 0.034550 0.057891 0.084016 -vn -0.352861 -0.211099 -0.911552 -v 0.031950 0.057891 0.084016 -vn 0.385489 -0.275374 -0.880663 -v 0.034550 0.058052 0.083981 -vn -0.384381 -0.336589 -0.859627 -v 0.031950 0.058404 0.083860 -vn 0.369049 -0.411136 -0.833529 -v 0.034550 0.058625 0.083749 -vn -0.343687 -0.506748 -0.790624 -v 0.031950 0.058625 0.083749 -vn 0.386048 -0.551775 -0.739264 -v 0.034550 0.058731 0.083684 -vn -0.383824 -0.602846 -0.699468 -v 0.031950 0.059024 0.083455 -vn 0.375870 -0.665783 -0.644557 -v 0.034550 0.059224 0.083246 -vn -0.333858 -0.745436 -0.576944 -v 0.031950 0.059224 0.083246 -vn 0.386598 -0.765571 -0.514240 -v 0.034550 0.059276 0.083182 -vn -0.383266 -0.800952 -0.459982 -v 0.031950 0.059479 0.082871 -vn 0.381745 -0.841816 -0.381598 -v 0.034550 0.059614 0.082570 -vn -0.323439 -0.899171 -0.294751 -v 0.031950 0.059614 0.082570 -vn 0.387153 -0.892579 -0.231116 -v 0.034550 0.059628 0.082531 -vn -0.382707 -0.908418 -0.168262 -v 0.031950 0.059719 0.082170 -vn 0.392634 -0.919695 0.000001 -v 0.034550 0.059750 0.081800 -vn -0.389988 -0.920820 -0.000001 -v 0.031950 0.059750 0.081800 -vn -0.390605 -0.907322 0.155545 -v 0.031950 0.059719 0.081430 -vn 0.387156 -0.892572 0.231142 -v 0.034550 0.059628 0.081069 -vn -0.363430 -0.878691 0.309548 -v 0.031950 0.059614 0.081030 -vn 0.383107 -0.842009 0.379802 -v 0.034550 0.059614 0.081030 -vn -0.390227 -0.803738 0.449142 -v 0.031950 0.059479 0.080729 -vn 0.387639 -0.764326 0.515308 -v 0.034550 0.059276 0.080418 -vn -0.364434 -0.725554 0.583746 -v 0.031950 0.059224 0.080354 -vn 0.379338 -0.667416 0.640826 -v 0.034550 0.059224 0.080354 -vn -0.389834 -0.608192 0.691471 -v 0.031950 0.059024 0.080145 -vn 0.388109 -0.548766 0.740424 -v 0.034550 0.058731 0.079916 -vn -0.366262 -0.489757 0.791195 -v 0.031950 0.058625 0.079851 -vn 0.375549 -0.415570 0.828411 -v 0.034550 0.058625 0.079851 -vn -0.389434 -0.343003 0.854804 -v 0.031950 0.058404 0.079740 -vn 0.388566 -0.270545 0.880807 -v 0.034550 0.058052 0.079619 -vn -0.368818 -0.198273 0.908109 -v 0.031950 0.057891 0.079584 -vn 0.371971 -0.115497 0.921031 -v 0.034550 0.057891 0.079584 -vn -0.389008 -0.038488 0.920430 -v 0.031950 0.057686 0.079558 -vn 0.389008 0.038489 0.920430 -v 0.034550 0.057314 0.079558 -vn -0.371971 0.115495 0.921031 -v 0.031950 0.057109 0.079584 -vn 0.368818 0.198274 0.908108 -v 0.034550 0.057109 0.079584 -vn -0.388567 0.270543 0.880808 -v 0.031950 0.056948 0.079619 -vn 0.389433 0.343003 0.854804 -v 0.034550 0.056596 0.079740 -vn -0.375549 0.415565 0.828413 -v 0.031950 0.056375 0.079851 -vn 0.366262 0.489755 0.791196 -v 0.034550 0.056375 0.079851 -vn -0.388110 0.548760 0.740428 -v 0.031950 0.056269 0.079916 -vn 0.389834 0.608190 0.691472 -v 0.034550 0.055976 0.080145 -vn -0.379342 0.667425 0.640815 -v 0.031950 0.055776 0.080354 -vn 0.364434 0.725554 0.583745 -v 0.034550 0.055776 0.080354 -vn -0.387640 0.764333 0.515296 -v 0.031950 0.055724 0.080418 -vn 0.390227 0.803738 0.449142 -v 0.034550 0.055521 0.080729 -vn -0.383107 0.842009 0.379803 -v 0.031950 0.055386 0.081030 -vn 0.363428 0.878693 0.309547 -v 0.034550 0.055386 0.081030 -vn -0.387156 0.892572 0.231142 -v 0.031950 0.055372 0.081069 -vn 0.390600 0.907324 0.155545 -v 0.034550 0.055281 0.081430 -vn 0.389984 0.920822 -0.000001 -v 0.034550 0.055250 0.081800 -vn 0.908419 0.168265 -0.382703 -v 0.021531 0.057130 0.090000 -vn 0.919694 -0.000001 0.392637 -v 0.021500 0.057500 0.092600 -vn 0.892572 0.231134 0.387160 -v 0.021622 0.056769 0.092600 -vn 0.899174 0.294749 -0.323435 -v 0.021636 0.056730 0.090000 -vn 0.841807 0.381614 0.381748 -v 0.021636 0.056730 0.092600 -vn 0.800954 0.459983 -0.383260 -v 0.021771 0.056429 0.090000 -vn 0.765561 0.514250 0.386606 -v 0.021974 0.056118 0.092600 -vn 0.745435 0.576943 -0.333861 -v 0.022026 0.056054 0.090000 -vn 0.665776 0.644561 0.375877 -v 0.022026 0.056054 0.092600 -vn 0.602853 0.699465 -0.383818 -v 0.022226 0.055845 0.090000 -vn 0.551772 0.739265 0.386050 -v 0.022519 0.055616 0.092600 -vn 0.506749 0.790626 -0.343681 -v 0.022625 0.055551 0.090000 -vn 0.411133 0.833530 0.369049 -v 0.022625 0.055551 0.092600 -vn 0.336595 0.859628 -0.384374 -v 0.022846 0.055440 0.090000 -vn 0.275374 0.880660 0.385497 -v 0.023198 0.055319 0.092600 -vn 0.211088 0.911552 -0.352866 -v 0.023359 0.055284 0.090000 -vn 0.107156 0.926251 0.361355 -v 0.023359 0.055284 0.092600 -vn 0.032364 0.922377 -0.384932 -v 0.023564 0.055258 0.090000 -vn -0.032364 0.922374 0.384941 -v 0.023936 0.055258 0.092600 -vn -0.107156 0.926254 -0.361346 -v 0.024141 0.055284 0.090000 -vn -0.211088 0.911549 0.352876 -v 0.024141 0.055284 0.092600 -vn -0.275374 0.880663 -0.385488 -v 0.024302 0.055319 0.090000 -vn -0.336593 0.859625 0.384384 -v 0.024654 0.055440 0.092600 -vn -0.411135 0.833533 -0.369041 -v 0.024875 0.055551 0.090000 -vn -0.506747 0.790622 0.343692 -v 0.024875 0.055551 0.092600 -vn -0.551774 0.739268 -0.386042 -v 0.024981 0.055616 0.090000 -vn -0.602849 0.699463 0.383829 -v 0.025274 0.055845 0.092600 -vn -0.665783 0.644559 -0.375868 -v 0.025474 0.056054 0.090000 -vn -0.745433 0.576941 0.333869 -v 0.025474 0.056054 0.092600 -vn -0.765568 0.514246 -0.386596 -v 0.025526 0.056118 0.090000 -vn -0.800950 0.459982 0.383270 -v 0.025729 0.056429 0.092600 -vn -0.841816 0.381599 -0.381742 -v 0.025864 0.056730 0.090000 -vn -0.899170 0.294749 0.323444 -v 0.025864 0.056730 0.092600 -vn -0.892581 0.231116 -0.387150 -v 0.025878 0.056769 0.090000 -vn -0.908415 0.168264 0.382712 -v 0.025969 0.057130 0.092600 -vn -0.919698 0.000000 -0.392626 -v 0.026000 0.057500 0.090000 -vn 0.931676 -0.000000 -0.363291 -v 0.021500 0.057500 0.090000 -vn 0.907325 -0.155546 -0.390599 -v 0.021531 0.057870 0.090000 -vn 0.892568 -0.231147 0.387161 -v 0.021622 0.058231 0.092600 -vn 0.878693 -0.309546 -0.363427 -v 0.021636 0.058270 0.090000 -vn 0.842005 -0.379806 0.383111 -v 0.021636 0.058270 0.092600 -vn 0.803738 -0.449143 -0.390224 -v 0.021771 0.058571 0.090000 -vn 0.764322 -0.515307 0.387647 -v 0.021974 0.058882 0.092600 -vn 0.725555 -0.583745 -0.364434 -v 0.022026 0.058946 0.090000 -vn 0.667413 -0.640824 0.379347 -v 0.022026 0.058946 0.092600 -vn 0.608193 -0.691471 -0.389833 -v 0.022226 0.059155 0.090000 -vn 0.548770 -0.740417 0.388116 -v 0.022519 0.059384 0.092600 -vn 0.489756 -0.791199 -0.366256 -v 0.022625 0.059449 0.090000 -vn 0.415575 -0.828405 0.375557 -v 0.022625 0.059449 0.092600 -vn 0.343005 -0.854808 -0.389424 -v 0.022846 0.059560 0.090000 -vn 0.270544 -0.880805 0.388572 -v 0.023198 0.059681 0.092600 -vn 0.198281 -0.908110 -0.368810 -v 0.023359 0.059716 0.090000 -vn 0.115498 -0.921029 0.371975 -v 0.023359 0.059716 0.092600 -vn 0.038493 -0.920433 -0.389000 -v 0.023564 0.059742 0.090000 -vn -0.038494 -0.920429 0.389009 -v 0.023936 0.059742 0.092600 -vn -0.115498 -0.921033 -0.371966 -v 0.024141 0.059716 0.090000 -vn -0.198281 -0.908106 0.368819 -v 0.024141 0.059716 0.092600 -vn -0.270544 -0.880809 -0.388563 -v 0.024302 0.059681 0.090000 -vn -0.343003 -0.854804 0.389434 -v 0.024654 0.059560 0.092600 -vn -0.415577 -0.828408 -0.375549 -v 0.024875 0.059449 0.090000 -vn -0.489754 -0.791196 0.366266 -v 0.024875 0.059449 0.092600 -vn -0.548771 -0.740420 -0.388109 -v 0.024981 0.059384 0.090000 -vn -0.608188 -0.691469 0.389843 -v 0.025274 0.059155 0.092600 -vn -0.667420 -0.640822 -0.379339 -v 0.025474 0.058946 0.090000 -vn -0.725551 -0.583743 0.364444 -v 0.025474 0.058946 0.092600 -vn -0.764330 -0.515303 -0.387637 -v 0.025526 0.058882 0.090000 -vn -0.803734 -0.449142 0.390235 -v 0.025729 0.058571 0.092600 -vn -0.842015 -0.379791 -0.383106 -v 0.025864 0.058270 0.090000 -vn -0.878689 -0.309547 0.363436 -v 0.025864 0.058270 0.092600 -vn -0.892576 -0.231130 -0.387152 -v 0.025878 0.058231 0.090000 -vn -0.907321 -0.155545 0.390608 -v 0.025969 0.057870 0.092600 -vn -0.920819 -0.000000 0.389990 -v 0.026000 0.057500 0.092600 -vn -0.835724 0.154358 -0.527010 -v 0.016750 -0.064500 0.089800 -vn -0.930676 -0.032168 -0.364427 -v 0.016750 -0.065000 0.089800 -vn -0.724383 -0.071345 0.685697 -v 0.016750 -0.065000 0.092800 -vn -0.835724 -0.154358 -0.527009 -v 0.016750 -0.050500 0.089800 -vn -0.723069 0.069011 0.687320 -v 0.016750 -0.050000 0.092800 -vn -0.929197 0.028377 -0.368494 -v 0.016750 -0.050000 0.089800 -vn -0.565882 0.681588 -0.463914 -v 0.017957 -0.048529 0.088593 -vn -0.507592 0.708580 -0.490169 -v 0.018250 -0.048500 0.088300 -vn -0.462058 0.681959 -0.566952 -v 0.030543 -0.048529 0.076007 -vn -0.364428 0.032166 -0.930676 -v 0.031750 -0.050000 0.074800 -vn -0.490169 0.708580 -0.507591 -v 0.030250 -0.048500 0.076300 -vn -0.527009 -0.154357 -0.835724 -v 0.031750 -0.050500 0.074800 -vn -0.805200 0.443980 -0.393109 -v 0.017189 -0.048939 0.089361 -vn -0.737768 0.534561 -0.412241 -v 0.017417 -0.048753 0.089133 -vn -0.657795 0.614305 -0.435816 -v 0.017676 -0.048614 0.088874 -vn -0.432827 0.620644 -0.653805 -v 0.030824 -0.048614 0.075726 -vn -0.409973 0.534499 -0.739076 -v 0.031083 -0.048753 0.075467 -vn -0.389294 0.450870 -0.803222 -v 0.031311 -0.048939 0.075239 -vn -0.374087 0.343129 -0.861581 -v 0.031497 -0.049167 0.075053 -vn -0.360862 0.241394 -0.900837 -v 0.031636 -0.049426 0.074914 -vn -0.352696 0.117312 -0.928355 -v 0.031721 -0.049707 0.074829 -vn -0.926433 0.119909 -0.356852 -v 0.016779 -0.049707 0.089771 -vn -0.900671 0.235475 -0.365162 -v 0.016864 -0.049426 0.089686 -vn -0.859907 0.343994 -0.377130 -v 0.017003 -0.049167 0.089547 -vn 0.685820 0.724268 -0.071316 -v 0.034750 -0.048500 0.076300 -vn 0.577350 0.577350 0.577351 -v 0.034750 -0.048500 0.092800 -vn -0.069660 0.723418 0.686887 -v 0.018250 -0.048500 0.092800 -vn 0.685697 0.071345 -0.724383 -v 0.034750 -0.050000 0.074800 -vn -0.527009 0.154357 -0.835724 -v 0.031750 -0.064500 0.074800 -vn 0.687320 -0.069010 -0.723069 -v 0.034750 -0.065000 0.074800 -vn -0.368495 -0.028375 -0.929197 -v 0.031750 -0.065000 0.074800 -vn 0.935652 -0.196021 -0.293479 -v 0.034750 -0.056160 0.083851 -vn 0.936136 -0.279034 -0.213984 -v 0.034750 -0.055567 0.083305 -vn 0.936832 -0.331246 -0.112348 -v 0.034750 -0.055183 0.082596 -vn 0.577350 -0.577351 0.577350 -v 0.034750 -0.066500 0.092800 -vn 0.935187 0.024235 -0.353324 -v 0.034750 -0.057702 0.084242 -vn 0.935346 -0.091120 -0.341796 -v 0.034750 -0.056899 0.084175 -vn 0.933285 0.026011 0.358194 -v 0.034750 -0.057702 0.079358 -vn 0.933767 -0.091592 0.345963 -v 0.034750 -0.056899 0.079425 -vn 0.934437 -0.197879 0.296093 -v 0.034750 -0.056160 0.079749 -vn 0.935292 0.308561 -0.173263 -v 0.034750 -0.059655 0.082966 -vn 0.935186 0.235753 -0.264288 -v 0.034750 -0.059159 0.083603 -vn 0.935145 0.137351 -0.326554 -v 0.034750 -0.058484 0.084044 -vn 0.937756 -0.347294 0.000000 -v 0.034750 -0.055050 0.081800 -vn 0.936556 -0.332263 0.111645 -v 0.034750 -0.055183 0.081004 -vn 0.665894 0.689267 -0.285474 -v 0.034750 -0.048614 0.075726 -vn 0.935349 -0.281082 0.214744 -v 0.034750 -0.055567 0.080295 -vn 0.665936 0.527533 -0.527483 -v 0.034750 -0.048939 0.075239 -vn 0.665960 0.285515 -0.689187 -v 0.034750 -0.049426 0.074914 -vn 0.932580 0.316735 0.173131 -v 0.034750 -0.059655 0.080634 -vn 0.686888 -0.723418 -0.069659 -v 0.034750 -0.066500 0.076300 -vn 0.668336 -0.687328 -0.284442 -v 0.034750 -0.066386 0.075726 -vn 0.932948 0.141722 0.330943 -v 0.034750 -0.058484 0.079556 -vn 0.932718 0.242450 0.266936 -v 0.034750 -0.059159 0.079997 -vn 0.668942 -0.284596 -0.686674 -v 0.034750 -0.065574 0.074914 -vn 0.668670 -0.525942 -0.525609 -v 0.034750 -0.066061 0.075239 -vn 0.931818 0.356827 0.066256 -v 0.034750 -0.059917 0.081397 -vn 0.930917 0.365232 -0.000001 -v 0.034750 -0.059950 0.081800 -vn 0.934298 0.349061 -0.072415 -v 0.034750 -0.059917 0.082203 -vn 0.279030 0.213984 0.936137 -v 0.021817 -0.059005 0.092800 -vn 0.331242 0.112348 0.936834 -v 0.021433 -0.058296 0.092800 -vn 0.347288 -0.000000 0.937759 -v 0.021300 -0.057500 0.092800 -vn -0.284442 0.687328 0.668337 -v 0.017676 -0.048614 0.092800 -vn 0.197875 -0.296087 0.934440 -v 0.022410 -0.055449 0.092800 -vn 0.332261 -0.111643 0.936557 -v 0.021433 -0.056704 0.092800 -vn 0.281075 -0.214740 0.935352 -v 0.021817 -0.055995 0.092800 -vn -0.686674 0.284596 0.668942 -v 0.016864 -0.049426 0.092800 -vn -0.525609 0.525942 0.668670 -v 0.017189 -0.048939 0.092800 -vn -0.349057 0.072414 0.934299 -v 0.026167 -0.057903 0.092800 -vn -0.308558 0.173260 0.935293 -v 0.025905 -0.058666 0.092800 -vn -0.071317 -0.724268 0.685821 -v 0.018250 -0.066500 0.092800 -vn 0.091120 0.341791 0.935348 -v 0.023149 -0.059875 0.092800 -vn -0.285474 -0.689267 0.665894 -v 0.017676 -0.066386 0.092800 -vn 0.196023 0.293480 0.935652 -v 0.022410 -0.059551 0.092800 -vn -0.527482 -0.527534 0.665936 -v 0.017189 -0.066061 0.092800 -vn 0.091590 -0.345955 0.933770 -v 0.023149 -0.055125 0.092800 -vn -0.026012 -0.358188 0.933287 -v 0.023952 -0.055058 0.092800 -vn -0.141721 -0.330942 0.932948 -v 0.024734 -0.055256 0.092800 -vn -0.242442 -0.266930 0.932722 -v 0.025409 -0.055697 0.092800 -vn -0.235751 0.264284 0.935187 -v 0.025409 -0.059303 0.092800 -vn -0.137352 0.326555 0.935145 -v 0.024734 -0.059744 0.092800 -vn -0.024234 0.353317 0.935190 -v 0.023952 -0.059942 0.092800 -vn -0.689187 -0.285515 0.665960 -v 0.016864 -0.065574 0.092800 -vn -0.316731 -0.173128 0.932581 -v 0.025905 -0.056334 0.092800 -vn -0.356822 -0.066254 0.931820 -v 0.026167 -0.057097 0.092800 -vn -0.365232 -0.000000 0.930917 -v 0.026200 -0.057500 0.092800 -vn -0.933285 -0.026011 0.358194 -v 0.031750 -0.057298 0.079358 -vn -0.933767 0.091592 0.345964 -v 0.031750 -0.058101 0.079425 -vn -0.935292 -0.308561 -0.173263 -v 0.031750 -0.055345 0.082966 -vn -0.935186 -0.235752 -0.264288 -v 0.031750 -0.055841 0.083603 -vn -0.577350 -0.577350 -0.577350 -v 0.031750 -0.050500 0.089800 -vn -0.936556 0.332263 0.111645 -v 0.031750 -0.059817 0.081004 -vn -0.935349 0.281083 0.214746 -v 0.031750 -0.059433 0.080295 -vn -0.934437 0.197880 0.296093 -v 0.031750 -0.058840 0.079749 -vn -0.935145 -0.137351 -0.326555 -v 0.031750 -0.056516 0.084044 -vn -0.935187 -0.024235 -0.353324 -v 0.031750 -0.057298 0.084242 -vn -0.577351 0.577351 -0.577349 -v 0.031750 -0.064500 0.089800 -vn -0.935346 0.091120 -0.341797 -v 0.031750 -0.058101 0.084175 -vn -0.935652 0.196022 -0.293480 -v 0.031750 -0.058840 0.083851 -vn -0.936135 0.279035 -0.213986 -v 0.031750 -0.059433 0.083305 -vn -0.936831 0.331247 -0.112349 -v 0.031750 -0.059817 0.082596 -vn -0.937758 0.347290 0.000001 -v 0.031750 -0.059950 0.081800 -vn -0.932948 -0.141722 0.330943 -v 0.031750 -0.056516 0.079556 -vn -0.932718 -0.242449 0.266936 -v 0.031750 -0.055841 0.079997 -vn -0.932579 -0.316736 0.173131 -v 0.031750 -0.055345 0.080634 -vn -0.931816 -0.356831 0.066256 -v 0.031750 -0.055083 0.081397 -vn -0.930915 -0.365236 -0.000001 -v 0.031750 -0.055050 0.081800 -vn -0.934296 -0.349065 -0.072415 -v 0.031750 -0.055083 0.082203 -vn -0.347298 0.000000 -0.937755 -v 0.026200 -0.057500 0.089800 -vn -0.332267 -0.111645 -0.936554 -v 0.026067 -0.056704 0.089800 -vn -0.281082 -0.214746 -0.935349 -v 0.025683 -0.055995 0.089800 -vn 0.141725 -0.330950 -0.932945 -v 0.022766 -0.055256 0.089800 -vn 0.242449 -0.266937 -0.932718 -v 0.022091 -0.055697 0.089800 -vn 0.316739 -0.173133 -0.932578 -v 0.021595 -0.056334 0.089800 -vn 0.356127 -0.059950 -0.932512 -v 0.021333 -0.057097 0.089800 -vn -0.197879 -0.296093 -0.934437 -v 0.025090 -0.055449 0.089800 -vn -0.091592 -0.345963 -0.933767 -v 0.024351 -0.055125 0.089800 -vn 0.026012 -0.358196 -0.933284 -v 0.023548 -0.055058 0.089800 -vn 0.348377 0.066126 -0.935019 -v 0.021333 -0.057903 0.089800 -vn 0.308566 0.173264 -0.935289 -v 0.021595 -0.058666 0.089800 -vn 0.235757 0.264291 -0.935184 -v 0.022091 -0.059303 0.089800 -vn 0.137355 0.326563 -0.935142 -v 0.022766 -0.059744 0.089800 -vn 0.024234 0.353325 -0.935187 -v 0.023548 -0.059942 0.089800 -vn -0.091122 0.341798 -0.935345 -v 0.024351 -0.059875 0.089800 -vn -0.196027 0.293485 -0.935649 -v 0.025090 -0.059551 0.089800 -vn -0.279037 0.213989 -0.936134 -v 0.025683 -0.059005 0.089800 -vn -0.331248 0.112349 -0.936831 -v 0.026067 -0.058296 0.089800 -vn -0.463918 -0.681580 -0.565888 -v 0.030543 -0.066471 0.076007 -vn -0.490166 -0.708581 -0.507593 -v 0.030250 -0.066500 0.076300 -vn -0.566963 -0.681952 -0.462055 -v 0.017957 -0.066471 0.088593 -vn -0.507594 -0.708580 -0.490167 -v 0.018250 -0.066500 0.088300 -vn -0.393123 -0.443977 -0.805195 -v 0.031311 -0.066061 0.075239 -vn -0.412226 -0.534565 -0.737773 -v 0.031083 -0.066247 0.075467 -vn -0.435827 -0.614306 -0.657787 -v 0.030824 -0.066386 0.075726 -vn -0.653799 -0.620660 -0.432815 -v 0.017676 -0.066386 0.088874 -vn -0.739074 -0.534488 -0.409991 -v 0.017417 -0.066247 0.089133 -vn -0.803224 -0.450879 -0.389281 -v 0.017189 -0.066061 0.089361 -vn -0.861577 -0.343121 -0.374104 -v 0.017003 -0.065833 0.089547 -vn -0.900842 -0.241393 -0.360851 -v 0.016864 -0.065574 0.089686 -vn -0.928370 -0.117322 -0.352653 -v 0.016779 -0.065293 0.089771 -vn -0.356896 -0.119897 -0.926418 -v 0.031721 -0.065293 0.074829 -vn -0.365171 -0.235480 -0.900666 -v 0.031636 -0.065574 0.074914 -vn -0.377116 -0.343997 -0.859913 -v 0.031497 -0.065833 0.075053 -vn 0.382707 0.908418 -0.168262 -v 0.034550 -0.059719 0.082170 -vn -0.392634 0.919695 0.000001 -v 0.031950 -0.059750 0.081800 -vn -0.387153 0.892579 -0.231116 -v 0.031950 -0.059628 0.082531 -vn 0.323439 0.899171 -0.294751 -v 0.034550 -0.059614 0.082570 -vn -0.381745 0.841816 -0.381598 -v 0.031950 -0.059614 0.082570 -vn 0.383266 0.800952 -0.459982 -v 0.034550 -0.059479 0.082871 -vn -0.386598 0.765571 -0.514240 -v 0.031950 -0.059276 0.083182 -vn 0.333858 0.745436 -0.576944 -v 0.034550 -0.059224 0.083246 -vn -0.375870 0.665783 -0.644557 -v 0.031950 -0.059224 0.083246 -vn 0.383824 0.602846 -0.699468 -v 0.034550 -0.059024 0.083455 -vn -0.386048 0.551775 -0.739264 -v 0.031950 -0.058731 0.083684 -vn 0.343687 0.506748 -0.790624 -v 0.034550 -0.058625 0.083749 -vn -0.369049 0.411136 -0.833529 -v 0.031950 -0.058625 0.083749 -vn 0.384381 0.336589 -0.859627 -v 0.034550 -0.058404 0.083860 -vn -0.385489 0.275374 -0.880663 -v 0.031950 -0.058052 0.083981 -vn 0.352861 0.211099 -0.911552 -v 0.034550 -0.057891 0.084016 -vn -0.361346 0.107160 -0.926254 -v 0.031950 -0.057891 0.084016 -vn 0.384929 0.032371 -0.922378 -v 0.034550 -0.057686 0.084042 -vn -0.384929 -0.032372 -0.922378 -v 0.031950 -0.057314 0.084042 -vn 0.361346 -0.107158 -0.926254 -v 0.034550 -0.057109 0.084016 -vn -0.352862 -0.211100 -0.911551 -v 0.031950 -0.057109 0.084016 -vn 0.385489 -0.275372 -0.880663 -v 0.034550 -0.056948 0.083981 -vn -0.384381 -0.336589 -0.859627 -v 0.031950 -0.056596 0.083860 -vn 0.369049 -0.411131 -0.833531 -v 0.034550 -0.056375 0.083749 -vn -0.343688 -0.506745 -0.790625 -v 0.031950 -0.056375 0.083749 -vn 0.386049 -0.551769 -0.739268 -v 0.034550 -0.056269 0.083684 -vn -0.383824 -0.602845 -0.699469 -v 0.031950 -0.055976 0.083455 -vn 0.375874 -0.665792 -0.644546 -v 0.034550 -0.055776 0.083246 -vn -0.333858 -0.745436 -0.576944 -v 0.031950 -0.055776 0.083246 -vn 0.386599 -0.765579 -0.514228 -v 0.034550 -0.055724 0.083182 -vn -0.383266 -0.800952 -0.459982 -v 0.031950 -0.055521 0.082871 -vn 0.381745 -0.841815 -0.381600 -v 0.034550 -0.055386 0.082570 -vn -0.323439 -0.899171 -0.294751 -v 0.031950 -0.055386 0.082570 -vn 0.387152 -0.892580 -0.231116 -v 0.034550 -0.055372 0.082531 -vn -0.382703 -0.908420 -0.168262 -v 0.031950 -0.055281 0.082170 -vn 0.392630 -0.919697 0.000000 -v 0.034550 -0.055250 0.081800 -vn -0.389984 -0.920822 -0.000001 -v 0.031950 -0.055250 0.081800 -vn -0.390600 -0.907324 0.155545 -v 0.031950 -0.055281 0.081430 -vn 0.387156 -0.892572 0.231142 -v 0.034550 -0.055372 0.081069 -vn -0.363428 -0.878693 0.309547 -v 0.031950 -0.055386 0.081030 -vn 0.383107 -0.842009 0.379803 -v 0.034550 -0.055386 0.081030 -vn -0.390227 -0.803738 0.449142 -v 0.031950 -0.055521 0.080729 -vn 0.387640 -0.764333 0.515296 -v 0.034550 -0.055724 0.080418 -vn -0.364434 -0.725554 0.583745 -v 0.031950 -0.055776 0.080354 -vn 0.379342 -0.667425 0.640815 -v 0.034550 -0.055776 0.080354 -vn -0.389834 -0.608190 0.691472 -v 0.031950 -0.055976 0.080145 -vn 0.388110 -0.548760 0.740428 -v 0.034550 -0.056269 0.079916 -vn -0.366262 -0.489755 0.791196 -v 0.031950 -0.056375 0.079851 -vn 0.375549 -0.415565 0.828413 -v 0.034550 -0.056375 0.079851 -vn -0.389433 -0.343003 0.854804 -v 0.031950 -0.056596 0.079740 -vn 0.388567 -0.270543 0.880808 -v 0.034550 -0.056948 0.079619 -vn -0.368818 -0.198274 0.908108 -v 0.031950 -0.057109 0.079584 -vn 0.371971 -0.115495 0.921031 -v 0.034550 -0.057109 0.079584 -vn -0.389008 -0.038489 0.920430 -v 0.031950 -0.057314 0.079558 -vn 0.389008 0.038488 0.920430 -v 0.034550 -0.057686 0.079558 -vn -0.371971 0.115497 0.921031 -v 0.031950 -0.057891 0.079584 -vn 0.368818 0.198273 0.908109 -v 0.034550 -0.057891 0.079584 -vn -0.388566 0.270545 0.880807 -v 0.031950 -0.058052 0.079619 -vn 0.389434 0.343003 0.854804 -v 0.034550 -0.058404 0.079740 -vn -0.375549 0.415570 0.828411 -v 0.031950 -0.058625 0.079851 -vn 0.366262 0.489757 0.791195 -v 0.034550 -0.058625 0.079851 -vn -0.388109 0.548766 0.740424 -v 0.031950 -0.058731 0.079916 -vn 0.389834 0.608192 0.691471 -v 0.034550 -0.059024 0.080145 -vn -0.379338 0.667416 0.640826 -v 0.031950 -0.059224 0.080354 -vn 0.364434 0.725554 0.583746 -v 0.034550 -0.059224 0.080354 -vn -0.387639 0.764326 0.515308 -v 0.031950 -0.059276 0.080418 -vn 0.390227 0.803738 0.449142 -v 0.034550 -0.059479 0.080729 -vn -0.383107 0.842009 0.379802 -v 0.031950 -0.059614 0.081030 -vn 0.363430 0.878691 0.309548 -v 0.034550 -0.059614 0.081030 -vn -0.387156 0.892572 0.231142 -v 0.031950 -0.059628 0.081069 -vn 0.390605 0.907322 0.155545 -v 0.034550 -0.059719 0.081430 -vn 0.389988 0.920820 -0.000001 -v 0.034550 -0.059750 0.081800 -vn 0.908419 0.168265 -0.382702 -v 0.021531 -0.057870 0.090000 -vn 0.919694 -0.000001 0.392637 -v 0.021500 -0.057500 0.092600 -vn 0.892568 0.231147 0.387161 -v 0.021622 -0.058231 0.092600 -vn 0.899172 0.294750 -0.323437 -v 0.021636 -0.058270 0.090000 -vn 0.841802 0.381625 0.381748 -v 0.021636 -0.058270 0.092600 -vn 0.800954 0.459982 -0.383261 -v 0.021771 -0.058571 0.090000 -vn 0.765554 0.514260 0.386606 -v 0.021974 -0.058882 0.092600 -vn 0.745435 0.576944 -0.333860 -v 0.022026 -0.058946 0.090000 -vn 0.665768 0.644571 0.375874 -v 0.022026 -0.058946 0.092600 -vn 0.602855 0.699464 -0.383818 -v 0.022226 -0.059155 0.090000 -vn 0.551782 0.739259 0.386048 -v 0.022519 -0.059384 0.092600 -vn 0.506749 0.790627 -0.343677 -v 0.022625 -0.059449 0.090000 -vn 0.411142 0.833527 0.369047 -v 0.022625 -0.059449 0.092600 -vn 0.336591 0.859630 -0.384372 -v 0.022846 -0.059560 0.090000 -vn 0.275374 0.880661 0.385493 -v 0.023198 -0.059681 0.092600 -vn 0.211093 0.911554 -0.352860 -v 0.023359 -0.059716 0.090000 -vn 0.107156 0.926253 0.361350 -v 0.023359 -0.059716 0.092600 -vn 0.032364 0.922379 -0.384927 -v 0.023564 -0.059742 0.090000 -vn -0.032364 0.922376 0.384937 -v 0.023936 -0.059742 0.092600 -vn -0.107156 0.926256 -0.361341 -v 0.024141 -0.059716 0.090000 -vn -0.211092 0.911550 0.352869 -v 0.024141 -0.059716 0.092600 -vn -0.275375 0.880665 -0.385484 -v 0.024302 -0.059681 0.090000 -vn -0.336589 0.859627 0.384382 -v 0.024654 -0.059560 0.092600 -vn -0.411144 0.833529 -0.369039 -v 0.024875 -0.059449 0.090000 -vn -0.506747 0.790624 0.343687 -v 0.024875 -0.059449 0.092600 -vn -0.551784 0.739262 -0.386040 -v 0.024981 -0.059384 0.090000 -vn -0.602850 0.699462 0.383828 -v 0.025274 -0.059155 0.092600 -vn -0.665775 0.644569 -0.375865 -v 0.025474 -0.058946 0.090000 -vn -0.745433 0.576941 0.333868 -v 0.025474 -0.058946 0.092600 -vn -0.765561 0.514257 -0.386596 -v 0.025526 -0.058882 0.090000 -vn -0.800949 0.459982 0.383272 -v 0.025729 -0.058571 0.092600 -vn -0.841812 0.381610 -0.381742 -v 0.025864 -0.058270 0.090000 -vn -0.899169 0.294750 0.323446 -v 0.025864 -0.058270 0.092600 -vn -0.892576 0.231130 -0.387152 -v 0.025878 -0.058231 0.090000 -vn -0.908416 0.168265 0.382712 -v 0.025969 -0.057870 0.092600 -vn -0.919698 0.000000 -0.392626 -v 0.026000 -0.057500 0.090000 -vn 0.931676 0.000000 -0.363291 -v 0.021500 -0.057500 0.090000 -vn 0.907325 -0.155544 -0.390600 -v 0.021531 -0.057130 0.090000 -vn 0.892572 -0.231134 0.387159 -v 0.021622 -0.056769 0.092600 -vn 0.878694 -0.309546 -0.363427 -v 0.021636 -0.056730 0.090000 -vn 0.842010 -0.379795 0.383112 -v 0.021636 -0.056730 0.092600 -vn 0.803739 -0.449144 -0.390222 -v 0.021771 -0.056429 0.090000 -vn 0.764329 -0.515297 0.387648 -v 0.021974 -0.056118 0.092600 -vn 0.725555 -0.583745 -0.364433 -v 0.022026 -0.056054 0.090000 -vn 0.667420 -0.640815 0.379350 -v 0.022026 -0.056054 0.092600 -vn 0.608191 -0.691472 -0.389833 -v 0.022226 -0.055845 0.090000 -vn 0.548760 -0.740424 0.388118 -v 0.022519 -0.055616 0.092600 -vn 0.489758 -0.791197 -0.366257 -v 0.022625 -0.055551 0.090000 -vn 0.415566 -0.828409 0.375558 -v 0.022625 -0.055551 0.092600 -vn 0.343008 -0.854806 -0.389425 -v 0.022846 -0.055440 0.090000 -vn 0.270543 -0.880804 0.388576 -v 0.023198 -0.055319 0.092600 -vn 0.198279 -0.908109 -0.368814 -v 0.023359 -0.055284 0.090000 -vn 0.115498 -0.921027 0.371980 -v 0.023359 -0.055284 0.092600 -vn 0.038493 -0.920431 -0.389004 -v 0.023564 -0.055258 0.090000 -vn -0.038494 -0.920428 0.389013 -v 0.023936 -0.055258 0.092600 -vn -0.115498 -0.921031 -0.371971 -v 0.024141 -0.055284 0.090000 -vn -0.198279 -0.908105 0.368823 -v 0.024141 -0.055284 0.092600 -vn -0.270544 -0.880808 -0.388567 -v 0.024302 -0.055319 0.090000 -vn -0.343006 -0.854803 0.389435 -v 0.024654 -0.055440 0.092600 -vn -0.415568 -0.828412 -0.375550 -v 0.024875 -0.055551 0.090000 -vn -0.489756 -0.791194 0.366267 -v 0.024875 -0.055551 0.092600 -vn -0.548761 -0.740427 -0.388110 -v 0.024981 -0.055616 0.090000 -vn -0.608186 -0.691471 0.389844 -v 0.025274 -0.055845 0.092600 -vn -0.667427 -0.640812 -0.379342 -v 0.025474 -0.056054 0.090000 -vn -0.725552 -0.583743 0.364443 -v 0.025474 -0.056054 0.092600 -vn -0.764336 -0.515293 -0.387638 -v 0.025526 -0.056118 0.090000 -vn -0.803735 -0.449142 0.390233 -v 0.025729 -0.056429 0.092600 -vn -0.842019 -0.379780 -0.383107 -v 0.025864 -0.056730 0.090000 -vn -0.878690 -0.309546 0.363436 -v 0.025864 -0.056730 0.092600 -vn -0.892580 -0.231117 -0.387150 -v 0.025878 -0.056769 0.090000 -vn -0.907321 -0.155543 0.390609 -v 0.025969 -0.057130 0.092600 -vn -0.920819 -0.000000 0.389989 -v 0.026000 -0.057500 0.092600 -vn -0.154358 -0.527009 0.835724 -v -0.073000 0.123000 0.023000 -vn 0.032167 -0.364426 0.930677 -v -0.072500 0.123000 0.023000 -vn 0.071345 0.685697 0.724383 -v -0.072500 0.126000 0.023000 -vn 0.154358 -0.527009 0.835724 -v -0.087000 0.123000 0.023000 -vn -0.069011 0.687320 0.723069 -v -0.087500 0.126000 0.023000 -vn -0.028376 -0.368493 0.929197 -v -0.087500 0.123000 0.023000 -vn -0.681580 -0.463916 0.565889 -v -0.088971 0.121793 0.021793 -vn -0.708580 -0.490167 0.507594 -v -0.089000 0.121500 0.021500 -vn -0.681950 -0.566963 0.462058 -v -0.088971 0.109207 0.009207 -vn -0.032166 -0.930676 0.364427 -v -0.087500 0.108000 0.008000 -vn -0.708580 -0.507593 0.490167 -v -0.089000 0.109500 0.009500 -vn 0.154358 -0.835724 0.527009 -v -0.087000 0.108000 0.008000 -vn -0.443974 -0.393123 0.805196 -v -0.088561 0.122561 0.022561 -vn -0.534564 -0.412232 0.737771 -v -0.088747 0.122333 0.022333 -vn -0.614305 -0.435826 0.657788 -v -0.088886 0.122074 0.022074 -vn -0.620657 -0.653800 0.432818 -v -0.088886 0.108926 0.008926 -vn -0.534492 -0.739075 0.409984 -v -0.088747 0.108667 0.008667 -vn -0.450875 -0.803225 0.389284 -v -0.088561 0.108439 0.008439 -vn -0.343122 -0.861578 0.374100 -v -0.088333 0.108253 0.008253 -vn -0.241387 -0.900843 0.360851 -v -0.088074 0.108114 0.008114 -vn -0.117315 -0.928358 0.352688 -v -0.087793 0.108029 0.008029 -vn -0.119899 -0.356881 0.926423 -v -0.087793 0.122971 0.022971 -vn -0.235462 -0.365193 0.900662 -v -0.088074 0.122886 0.022886 -vn -0.343996 -0.377115 0.859913 -v -0.088333 0.122747 0.022747 -vn -0.724268 -0.071317 -0.685820 -v -0.089000 0.109500 0.005000 -vn -0.577350 0.577351 -0.577349 -v -0.089000 0.126000 0.005000 -vn -0.723418 0.686887 0.069660 -v -0.089000 0.126000 0.021500 -vn -0.071345 -0.724383 -0.685696 -v -0.087500 0.108000 0.005000 -vn -0.154357 -0.835724 0.527009 -v -0.073000 0.108000 0.008000 -vn 0.069011 -0.723069 -0.687320 -v -0.072500 0.108000 0.005000 -vn 0.028375 -0.929197 0.368494 -v -0.072500 0.108000 0.008000 -vn 0.196025 -0.293481 -0.935651 -v -0.081340 0.117051 0.005000 -vn 0.279037 -0.213990 -0.936134 -v -0.081933 0.116505 0.005000 -vn 0.331241 -0.112346 -0.936834 -v -0.082317 0.115796 0.005000 -vn 0.577350 0.577352 -0.577349 -v -0.071000 0.126000 0.005000 -vn -0.024233 -0.353319 -0.935189 -v -0.079798 0.117442 0.005000 -vn 0.091121 -0.341794 -0.935347 -v -0.080601 0.117375 0.005000 -vn -0.026012 0.358191 -0.933286 -v -0.079798 0.112558 0.005000 -vn 0.091590 0.345955 -0.933770 -v -0.080601 0.112625 0.005000 -vn 0.197875 0.296089 -0.934439 -v -0.081340 0.112949 0.005000 -vn -0.308565 -0.173262 -0.935290 -v -0.077845 0.116166 0.005000 -vn -0.235757 -0.264287 -0.935185 -v -0.078341 0.116803 0.005000 -vn -0.137351 -0.326555 -0.935145 -v -0.079016 0.117244 0.005000 -vn 0.347290 -0.000001 -0.937758 -v -0.082450 0.115000 0.005000 -vn 0.332261 0.111642 -0.936557 -v -0.082317 0.114204 0.005000 -vn -0.689267 -0.285475 -0.665894 -v -0.088886 0.108926 0.005000 -vn 0.281082 0.214744 -0.935349 -v -0.081933 0.113495 0.005000 -vn -0.527532 -0.527485 -0.665935 -v -0.088561 0.108439 0.005000 -vn -0.285513 -0.689187 -0.665961 -v -0.088074 0.108114 0.005000 -vn -0.316735 0.173130 -0.932580 -v -0.077845 0.113834 0.005000 -vn 0.723418 -0.069660 -0.686887 -v -0.071000 0.109500 0.005000 -vn 0.687327 -0.284442 -0.668337 -v -0.071114 0.108926 0.005000 -vn -0.141724 0.330948 -0.932946 -v -0.079016 0.112756 0.005000 -vn -0.242446 0.266933 -0.932720 -v -0.078341 0.113197 0.005000 -vn 0.284596 -0.686674 -0.668943 -v -0.071926 0.108114 0.005000 -vn 0.525942 -0.525609 -0.668671 -v -0.071439 0.108439 0.005000 -vn -0.356829 0.066257 -0.931817 -v -0.077583 0.114597 0.005000 -vn -0.365240 0.000000 -0.930914 -v -0.077550 0.115000 0.005000 -vn -0.349066 -0.072417 -0.934296 -v -0.077583 0.115403 0.005000 -vn -0.213990 0.936133 -0.279039 -v -0.078495 0.126000 0.017933 -vn -0.112351 0.936831 -0.331248 -v -0.079204 0.126000 0.018317 -vn 0.000000 0.937756 -0.347296 -v -0.080000 0.126000 0.018450 -vn -0.687328 0.668336 0.284441 -v -0.088886 0.126000 0.022074 -vn 0.296092 0.934438 -0.197876 -v -0.082051 0.126000 0.017340 -vn 0.111645 0.936554 -0.332269 -v -0.080796 0.126000 0.018317 -vn 0.214745 0.935348 -0.281083 -v -0.081505 0.126000 0.017933 -vn -0.284593 0.668943 0.686674 -v -0.088074 0.126000 0.022886 -vn -0.525941 0.668670 0.525611 -v -0.088561 0.126000 0.022561 -vn -0.072416 0.934296 0.349065 -v -0.079597 0.126000 0.013583 -vn -0.173264 0.935289 0.308567 -v -0.078834 0.126000 0.013845 -vn 0.724268 0.685820 0.071317 -v -0.071000 0.126000 0.021500 -vn -0.341798 0.935345 -0.091122 -v -0.077625 0.126000 0.016601 -vn 0.689267 0.665894 0.285474 -v -0.071114 0.126000 0.022074 -vn -0.293488 0.935648 -0.196028 -v -0.077949 0.126000 0.017340 -vn 0.527534 0.665936 0.527482 -v -0.071439 0.126000 0.022561 -vn 0.345967 0.933765 -0.091594 -v -0.082375 0.126000 0.016601 -vn 0.358194 0.933285 0.026012 -v -0.082442 0.126000 0.015798 -vn 0.330951 0.932944 0.141726 -v -0.082244 0.126000 0.015016 -vn 0.266936 0.932719 0.242446 -v -0.081803 0.126000 0.014341 -vn -0.264292 0.935183 0.235760 -v -0.078197 0.126000 0.014341 -vn -0.326558 0.935144 0.137353 -v -0.077756 0.126000 0.015016 -vn -0.353323 0.935188 0.024233 -v -0.077558 0.126000 0.015798 -vn 0.285515 0.665960 0.689186 -v -0.071926 0.126000 0.022886 -vn 0.173131 0.932579 0.316738 -v -0.081166 0.126000 0.013845 -vn 0.066255 0.931816 0.356831 -v -0.080403 0.126000 0.013583 -vn 0.000000 0.930913 0.365240 -v -0.080000 0.126000 0.013550 -vn 0.026013 0.358190 0.933286 -v -0.080202 0.112558 0.008000 -vn -0.091590 0.345955 0.933770 -v -0.079399 0.112625 0.008000 -vn 0.308559 -0.173261 0.935293 -v -0.082155 0.116166 0.008000 -vn 0.235757 -0.264289 0.935184 -v -0.081659 0.116803 0.008000 -vn 0.577351 -0.577350 0.577350 -v -0.087000 0.123000 0.008000 -vn -0.332265 0.111645 0.936555 -v -0.077683 0.114204 0.008000 -vn -0.281077 0.214739 0.935352 -v -0.078067 0.113495 0.008000 -vn -0.197875 0.296087 0.934440 -v -0.078660 0.112949 0.008000 -vn 0.137351 -0.326555 0.935145 -v -0.080984 0.117244 0.008000 -vn 0.024233 -0.353319 0.935189 -v -0.080202 0.117442 0.008000 -vn -0.577350 -0.577350 0.577352 -v -0.073000 0.123000 0.008000 -vn -0.091121 -0.341794 0.935347 -v -0.079399 0.117375 0.008000 -vn -0.196025 -0.293480 0.935651 -v -0.078660 0.117051 0.008000 -vn -0.279032 -0.213984 0.936137 -v -0.078067 0.116505 0.008000 -vn -0.331244 -0.112349 0.936833 -v -0.077683 0.115796 0.008000 -vn -0.347298 -0.000001 0.937755 -v -0.077550 0.115000 0.008000 -vn 0.141724 0.330948 0.932946 -v -0.080984 0.112756 0.008000 -vn 0.242446 0.266936 0.932719 -v -0.081659 0.113197 0.008000 -vn 0.316731 0.173128 0.932581 -v -0.082155 0.113834 0.008000 -vn 0.356823 0.066254 0.931820 -v -0.082417 0.114597 0.008000 -vn 0.365231 0.000000 0.930917 -v -0.082450 0.115000 0.008000 -vn 0.349058 -0.072415 0.934299 -v -0.082417 0.115403 0.008000 -vn 0.000000 -0.937758 0.347290 -v -0.080000 0.123000 0.013550 -vn 0.111643 -0.936557 0.332261 -v -0.080796 0.123000 0.013683 -vn 0.214741 -0.935351 0.281078 -v -0.081505 0.123000 0.014067 -vn 0.330945 -0.932947 -0.141723 -v -0.082244 0.123000 0.016984 -vn 0.266931 -0.932722 -0.242442 -v -0.081803 0.123000 0.017659 -vn 0.173128 -0.932581 -0.316732 -v -0.081166 0.123000 0.018155 -vn 0.059948 -0.932515 -0.356121 -v -0.080403 0.123000 0.018417 -vn 0.296085 -0.934441 0.197872 -v -0.082051 0.123000 0.014660 -vn 0.345960 -0.933768 0.091592 -v -0.082375 0.123000 0.015399 -vn 0.358187 -0.933288 -0.026012 -v -0.082442 0.123000 0.016202 -vn -0.066125 -0.935022 -0.348369 -v -0.079597 0.123000 0.018417 -vn -0.173261 -0.935292 -0.308561 -v -0.078834 0.123000 0.018155 -vn -0.264287 -0.935185 -0.235755 -v -0.078197 0.123000 0.017659 -vn -0.326551 -0.935147 -0.137350 -v -0.077756 0.123000 0.016984 -vn -0.353315 -0.935191 -0.024232 -v -0.077558 0.123000 0.016202 -vn -0.341791 -0.935348 0.091120 -v -0.077625 0.123000 0.015399 -vn -0.293480 -0.935652 0.196024 -v -0.077949 0.123000 0.014660 -vn -0.213985 -0.936136 0.279033 -v -0.078495 0.123000 0.014067 -vn -0.112347 -0.936834 0.331240 -v -0.079204 0.123000 0.013683 -vn 0.681586 -0.565882 0.463917 -v -0.071029 0.109207 0.009207 -vn 0.708580 -0.507591 0.490170 -v -0.071000 0.109500 0.009500 -vn 0.681960 -0.462055 0.566953 -v -0.071029 0.121793 0.021793 -vn 0.708580 -0.490169 0.507591 -v -0.071000 0.121500 0.021500 -vn 0.443973 -0.805202 0.393114 -v -0.071439 0.108439 0.008439 -vn 0.534570 -0.737766 0.412234 -v -0.071253 0.108667 0.008667 -vn 0.614302 -0.657795 0.435820 -v -0.071114 0.108926 0.008926 -vn 0.620645 -0.432827 0.653805 -v -0.071114 0.122074 0.022074 -vn 0.534502 -0.409977 0.739071 -v -0.071253 0.122333 0.022333 -vn 0.450863 -0.389298 0.803225 -v -0.071439 0.122561 0.022561 -vn 0.343132 -0.374085 0.861580 -v -0.071667 0.122747 0.022747 -vn 0.241378 -0.360883 0.900833 -v -0.071926 0.122886 0.022886 -vn 0.117312 -0.352682 0.928361 -v -0.072207 0.122971 0.022971 -vn 0.119901 -0.926421 0.356887 -v -0.072207 0.108029 0.008029 -vn 0.235471 -0.900672 0.365162 -v -0.071926 0.108114 0.008114 -vn 0.343999 -0.859907 0.377127 -v -0.071667 0.108253 0.008253 -vn -0.908418 -0.168271 -0.382703 -v -0.077781 0.115370 0.005200 -vn -0.919698 -0.000001 0.392627 -v -0.077750 0.115000 0.007800 -vn -0.892560 -0.231181 0.387160 -v -0.077872 0.115731 0.007800 -vn -0.899168 -0.294752 -0.323447 -v -0.077886 0.115770 0.005200 -vn -0.841792 -0.381653 0.381741 -v -0.077886 0.115770 0.007800 -vn -0.800954 -0.459979 -0.383265 -v -0.078021 0.116071 0.005200 -vn -0.765554 -0.514260 0.386604 -v -0.078224 0.116382 0.007800 -vn -0.745432 -0.576942 -0.333869 -v -0.078276 0.116446 0.005200 -vn -0.665769 -0.644571 0.375871 -v -0.078276 0.116446 0.007800 -vn -0.602856 -0.699461 -0.383822 -v -0.078476 0.116655 0.005200 -vn -0.551790 -0.739254 0.386046 -v -0.078769 0.116884 0.007800 -vn -0.506748 -0.790624 -0.343687 -v -0.078875 0.116949 0.005200 -vn -0.411148 -0.833524 0.369046 -v -0.078875 0.116949 0.007800 -vn -0.336589 -0.859627 -0.384381 -v -0.079096 0.117060 0.005200 -vn -0.275375 -0.880663 0.385489 -v -0.079448 0.117181 0.007800 -vn -0.211085 -0.911553 -0.352866 -v -0.079609 0.117216 0.005200 -vn -0.107153 -0.926255 0.361345 -v -0.079609 0.117216 0.007800 -vn -0.032357 -0.922377 -0.384934 -v -0.079814 0.117242 0.005200 -vn 0.032357 -0.922377 0.384934 -v -0.080186 0.117242 0.007800 -vn 0.107153 -0.926255 -0.361345 -v -0.080391 0.117216 0.005200 -vn 0.211085 -0.911553 0.352866 -v -0.080391 0.117216 0.007800 -vn 0.275375 -0.880663 -0.385489 -v -0.080552 0.117181 0.005200 -vn 0.336589 -0.859627 0.384381 -v -0.080904 0.117060 0.007800 -vn 0.411149 -0.833524 -0.369045 -v -0.081125 0.116949 0.005200 -vn 0.506748 -0.790624 0.343686 -v -0.081125 0.116949 0.007800 -vn 0.551788 -0.739256 -0.386045 -v -0.081231 0.116884 0.005200 -vn 0.602850 -0.699466 0.383821 -v -0.081524 0.116655 0.007800 -vn 0.665769 -0.644576 -0.375864 -v -0.081724 0.116446 0.005200 -vn 0.745437 -0.576943 0.333857 -v -0.081724 0.116446 0.007800 -vn 0.765556 -0.514262 -0.386598 -v -0.081776 0.116382 0.005200 -vn 0.800950 -0.459984 0.383268 -v -0.081979 0.116071 0.007800 -vn 0.841818 -0.381584 -0.381755 -v -0.082114 0.115770 0.005200 -vn 0.899171 -0.294749 0.323443 -v -0.082114 0.115770 0.007800 -vn 0.892580 -0.231105 -0.387159 -v -0.082128 0.115731 0.005200 -vn 0.908416 -0.168265 0.382710 -v -0.082219 0.115370 0.007800 -vn 0.919694 -0.000001 -0.392635 -v -0.082250 0.115000 0.005200 -vn 0.920819 0.000000 0.389989 -v -0.082250 0.115000 0.007800 -vn 0.907321 0.155542 0.390608 -v -0.082219 0.114630 0.007800 -vn 0.892588 0.231079 -0.387156 -v -0.082128 0.114269 0.005200 -vn 0.878690 0.309545 0.363436 -v -0.082114 0.114230 0.007800 -vn 0.842030 0.379743 -0.383119 -v -0.082114 0.114230 0.005200 -vn 0.803735 0.449142 0.390233 -v -0.081979 0.113929 0.007800 -vn 0.764339 0.515287 -0.387640 -v -0.081776 0.113618 0.005200 -vn 0.725552 0.583746 0.364438 -v -0.081724 0.113554 0.007800 -vn 0.667429 0.640809 -0.379344 -v -0.081724 0.113554 0.005200 -vn 0.608183 0.691477 0.389836 -v -0.081524 0.113345 0.007800 -vn 0.548755 0.740428 -0.388116 -v -0.081231 0.113116 0.005200 -vn 0.489760 0.791194 0.366260 -v -0.081125 0.113051 0.007800 -vn 0.415563 0.828410 -0.375557 -v -0.081125 0.113051 0.005200 -vn 0.343010 0.854805 0.389427 -v -0.080904 0.112939 0.007800 -vn 0.270543 0.880804 -0.388575 -v -0.080552 0.112819 0.005200 -vn 0.198284 0.908106 0.368818 -v -0.080391 0.112784 0.007800 -vn 0.115501 0.921027 -0.371979 -v -0.080391 0.112784 0.005200 -vn 0.038498 0.920429 0.389009 -v -0.080186 0.112758 0.007800 -vn -0.038498 0.920429 -0.389009 -v -0.079814 0.112758 0.005200 -vn -0.115501 0.921027 0.371979 -v -0.079609 0.112784 0.007800 -vn -0.198284 0.908106 -0.368818 -v -0.079609 0.112784 0.005200 -vn -0.270543 0.880804 0.388576 -v -0.079448 0.112819 0.007800 -vn -0.343010 0.854805 -0.389427 -v -0.079096 0.112939 0.005200 -vn -0.415563 0.828410 0.375558 -v -0.078875 0.113051 0.007800 -vn -0.489760 0.791194 -0.366260 -v -0.078875 0.113051 0.005200 -vn -0.548758 0.740425 0.388117 -v -0.078769 0.113116 0.007800 -vn -0.608190 0.691471 -0.389837 -v -0.078476 0.113345 0.005200 -vn -0.667429 0.640806 0.379350 -v -0.078276 0.113554 0.007800 -vn -0.725554 0.583743 -0.364438 -v -0.078276 0.113554 0.005200 -vn -0.764336 0.515286 0.387647 -v -0.078224 0.113618 0.007800 -vn -0.803739 0.449140 -0.390227 -v -0.078021 0.113929 0.005200 -vn -0.842005 0.379812 0.383107 -v -0.077886 0.114230 0.007800 -vn -0.878693 0.309545 -0.363430 -v -0.077886 0.114230 0.005200 -vn -0.892568 0.231155 0.387157 -v -0.077872 0.114269 0.007800 -vn -0.907324 0.155550 -0.390600 -v -0.077781 0.114630 0.005200 -vn -0.920823 0.000000 -0.389980 -v -0.077750 0.115000 0.005200 -vn -0.168266 -0.382712 -0.908415 -v -0.079630 0.123200 0.018219 -vn 0.000000 0.392628 -0.919698 -v -0.080000 0.125800 0.018250 -vn -0.231161 0.387154 -0.892567 -v -0.079269 0.125800 0.018128 -vn -0.294749 -0.323446 -0.899170 -v -0.079230 0.123200 0.018114 -vn -0.381637 0.381738 -0.841801 -v -0.079230 0.125800 0.018114 -vn -0.459979 -0.383268 -0.800952 -v -0.078929 0.123200 0.017979 -vn -0.514263 0.386595 -0.765558 -v -0.078618 0.125800 0.017776 -vn -0.576942 -0.333866 -0.745434 -v -0.078554 0.123200 0.017724 -vn -0.644573 0.375862 -0.665773 -v -0.078554 0.125800 0.017724 -vn -0.699461 -0.383824 -0.602854 -v -0.078345 0.123200 0.017524 -vn -0.739268 0.386038 -0.551776 -v -0.078116 0.125800 0.017231 -vn -0.790623 -0.343690 -0.506746 -v -0.078051 0.123200 0.017125 -vn -0.833535 0.369036 -0.411135 -v -0.078051 0.125800 0.017125 -vn -0.859626 -0.384385 -0.336589 -v -0.077940 0.123200 0.016904 -vn -0.880665 0.385484 -0.275375 -v -0.077819 0.125800 0.016552 -vn -0.911551 -0.352871 -0.211085 -v -0.077784 0.123200 0.016391 -vn -0.926257 0.361340 -0.107153 -v -0.077784 0.125800 0.016391 -vn -0.922375 -0.384939 -0.032357 -v -0.077758 0.123200 0.016186 -vn -0.922378 0.384930 0.032358 -v -0.077758 0.125800 0.015814 -vn -0.926253 -0.361349 0.107152 -v -0.077784 0.123200 0.015609 -vn -0.911554 0.352862 0.211086 -v -0.077784 0.125800 0.015609 -vn -0.880661 -0.385493 0.275374 -v -0.077819 0.123200 0.015448 -vn -0.859629 0.384376 0.336591 -v -0.077940 0.125800 0.015096 -vn -0.833532 -0.369045 0.411132 -v -0.078051 0.123200 0.014875 -vn -0.790626 0.343683 0.506748 -v -0.078051 0.125800 0.014875 -vn -0.739266 -0.386047 0.551772 -v -0.078116 0.123200 0.014769 -vn -0.699465 0.383816 0.602854 -v -0.078345 0.125800 0.014476 -vn -0.644568 -0.375871 0.665772 -v -0.078554 0.123200 0.014276 -vn -0.576944 0.333857 0.745436 -v -0.078554 0.125800 0.014276 -vn -0.514258 -0.386603 0.765557 -v -0.078618 0.123200 0.014224 -vn -0.459982 0.383261 0.800954 -v -0.078929 0.125800 0.014021 -vn -0.381627 -0.381749 0.841801 -v -0.079230 0.123200 0.013886 -vn -0.294751 0.323438 0.899172 -v -0.079230 0.125800 0.013886 -vn -0.231151 -0.387163 0.892566 -v -0.079269 0.123200 0.013872 -vn -0.168266 0.382702 0.908419 -v -0.079630 0.125800 0.013781 -vn -0.000000 -0.392635 0.919694 -v -0.080000 0.123200 0.013750 -vn 0.000000 -0.363300 -0.931672 -v -0.080000 0.123200 0.018250 -vn 0.155544 -0.390608 -0.907321 -v -0.080370 0.123200 0.018219 -vn 0.231134 0.387150 -0.892576 -v -0.080731 0.125800 0.018128 -vn 0.309543 -0.363435 -0.878691 -v -0.080770 0.123200 0.018114 -vn 0.379796 0.383103 -0.842014 -v -0.080770 0.125800 0.018114 -vn 0.449140 -0.390232 -0.803737 -v -0.081071 0.123200 0.017979 -vn 0.515288 0.387637 -0.764340 -v -0.081382 0.125800 0.017776 -vn 0.583748 -0.364442 -0.725548 -v -0.081446 0.123200 0.017724 -vn 0.640809 0.379342 -0.667430 -v -0.081446 0.125800 0.017724 -vn 0.691472 -0.389844 -0.608184 -v -0.081655 0.123200 0.017524 -vn 0.740426 0.388112 -0.548760 -v -0.081884 0.125800 0.017231 -vn 0.791191 -0.366265 -0.489762 -v -0.081949 0.123200 0.017125 -vn 0.828412 0.375551 -0.415566 -v -0.081949 0.125800 0.017125 -vn 0.854803 -0.389431 -0.343009 -v -0.082061 0.123200 0.016904 -vn 0.880809 0.388562 -0.270545 -v -0.082181 0.125800 0.016552 -vn 0.908104 -0.368823 -0.198284 -v -0.082216 0.123200 0.016391 -vn 0.921032 0.371968 -0.115503 -v -0.082216 0.125800 0.016391 -vn 0.920427 -0.389014 -0.038499 -v -0.082242 0.123200 0.016186 -vn 0.920431 0.389006 0.038499 -v -0.082242 0.125800 0.015814 -vn 0.921028 -0.371976 0.115502 -v -0.082216 0.123200 0.015609 -vn 0.908107 0.368814 0.198285 -v -0.082216 0.125800 0.015609 -vn 0.880806 -0.388571 0.270543 -v -0.082181 0.123200 0.015448 -vn 0.854806 0.389423 0.343011 -v -0.082061 0.125800 0.015096 -vn 0.828409 -0.375561 0.415563 -v -0.081949 0.123200 0.014875 -vn 0.791193 0.366257 0.489764 -v -0.081949 0.125800 0.014875 -vn 0.740424 -0.388122 0.548756 -v -0.081884 0.123200 0.014769 -vn 0.691476 0.389837 0.608184 -v -0.081655 0.125800 0.014476 -vn 0.640804 -0.379351 0.667430 -v -0.081446 0.123200 0.014276 -vn 0.583750 0.364435 0.725550 -v -0.081446 0.125800 0.014276 -vn 0.515283 -0.387646 0.764339 -v -0.081382 0.123200 0.014224 -vn 0.449142 0.390224 0.803739 -v -0.081071 0.125800 0.014021 -vn 0.379787 -0.383114 0.842013 -v -0.080770 0.123200 0.013886 -vn 0.309545 0.363427 0.878694 -v -0.080770 0.125800 0.013886 -vn 0.231125 -0.387159 0.892574 -v -0.080731 0.123200 0.013872 -vn 0.155544 0.390599 0.907325 -v -0.080370 0.125800 0.013781 -vn 0.000000 0.389981 0.920823 -v -0.080000 0.125800 0.013750 -vn 0.154357 0.527009 0.835725 -v -0.087000 -0.123000 0.023000 -vn -0.032167 0.364426 0.930676 -v -0.087500 -0.123000 0.023000 -vn -0.071345 -0.685696 0.724383 -v -0.087500 -0.126000 0.023000 -vn -0.154358 0.527009 0.835724 -v -0.073000 -0.123000 0.023000 -vn 0.069011 -0.687320 0.723069 -v -0.072500 -0.126000 0.023000 -vn 0.028376 0.368493 0.929197 -v -0.072500 -0.123000 0.023000 -vn 0.681588 0.463915 0.565881 -v -0.071029 -0.121793 0.021793 -vn 0.708580 0.490169 0.507592 -v -0.071000 -0.121500 0.021500 -vn 0.681958 0.566954 0.462056 -v -0.071029 -0.109207 0.009207 -vn 0.032166 0.930676 0.364427 -v -0.072500 -0.108000 0.008000 -vn 0.708580 0.507591 0.490170 -v -0.071000 -0.109500 0.009500 -vn -0.154358 0.835724 0.527009 -v -0.073000 -0.108000 0.008000 -vn 0.443967 0.393126 0.805199 -v -0.071439 -0.122561 0.022561 -vn 0.534572 0.412229 0.737767 -v -0.071253 -0.122333 0.022333 -vn 0.614297 0.435828 0.657795 -v -0.071114 -0.122074 0.022074 -vn 0.620650 0.653805 0.432819 -v -0.071114 -0.108926 0.008926 -vn 0.534500 0.739071 0.409981 -v -0.071253 -0.108667 0.008667 -vn 0.450869 0.803227 0.389285 -v -0.071439 -0.108439 0.008439 -vn 0.343128 0.861576 0.374099 -v -0.071667 -0.108253 0.008253 -vn 0.241388 0.900843 0.360851 -v -0.071926 -0.108114 0.008114 -vn 0.117315 0.928358 0.352688 -v -0.072207 -0.108029 0.008029 -vn 0.119899 0.356881 0.926423 -v -0.072207 -0.122971 0.022971 -vn 0.235462 0.365193 0.900662 -v -0.071926 -0.122886 0.022886 -vn 0.344003 0.377114 0.859911 -v -0.071667 -0.122747 0.022747 -vn 0.724268 0.071317 -0.685820 -v -0.071000 -0.109500 0.005000 -vn 0.577350 -0.577351 -0.577351 -v -0.071000 -0.126000 0.005000 -vn 0.723418 -0.686887 0.069660 -v -0.071000 -0.126000 0.021500 -vn 0.071345 0.724383 -0.685697 -v -0.072500 -0.108000 0.005000 -vn 0.154357 0.835725 0.527009 -v -0.087000 -0.108000 0.008000 -vn -0.069011 0.723069 -0.687320 -v -0.087500 -0.108000 0.005000 -vn -0.028375 0.929197 0.368494 -v -0.087500 -0.108000 0.008000 -vn -0.196025 0.293481 -0.935651 -v -0.078660 -0.117051 0.005000 -vn -0.279033 0.213984 -0.936137 -v -0.078067 -0.116505 0.005000 -vn -0.331244 0.112349 -0.936832 -v -0.077683 -0.115796 0.005000 -vn -0.577350 -0.577349 -0.577352 -v -0.089000 -0.126000 0.005000 -vn 0.024233 0.353319 -0.935189 -v -0.080202 -0.117442 0.005000 -vn -0.091120 0.341795 -0.935347 -v -0.079399 -0.117375 0.005000 -vn 0.026013 -0.358190 -0.933286 -v -0.080202 -0.112558 0.005000 -vn -0.091590 -0.345955 -0.933770 -v -0.079399 -0.112625 0.005000 -vn -0.197875 -0.296088 -0.934440 -v -0.078660 -0.112949 0.005000 -vn 0.308559 0.173261 -0.935293 -v -0.082155 -0.116166 0.005000 -vn 0.235757 0.264289 -0.935184 -v -0.081659 -0.116803 0.005000 -vn 0.137351 0.326555 -0.935145 -v -0.080984 -0.117244 0.005000 -vn -0.347298 0.000001 -0.937755 -v -0.077550 -0.115000 0.005000 -vn -0.332265 -0.111645 -0.936555 -v -0.077683 -0.114204 0.005000 -vn 0.689267 0.285475 -0.665894 -v -0.071114 -0.108926 0.005000 -vn -0.281077 -0.214740 -0.935352 -v -0.078067 -0.113495 0.005000 -vn 0.527534 0.527483 -0.665936 -v -0.071439 -0.108439 0.005000 -vn 0.285515 0.689186 -0.665960 -v -0.071926 -0.108114 0.005000 -vn 0.316731 -0.173128 -0.932582 -v -0.082155 -0.113834 0.005000 -vn -0.723418 0.069660 -0.686887 -v -0.089000 -0.109500 0.005000 -vn -0.687328 0.284442 -0.668336 -v -0.088886 -0.108926 0.005000 -vn 0.141724 -0.330948 -0.932946 -v -0.080984 -0.112756 0.005000 -vn 0.242446 -0.266936 -0.932719 -v -0.081659 -0.113197 0.005000 -vn -0.284593 0.686674 -0.668944 -v -0.088074 -0.108114 0.005000 -vn -0.525941 0.525611 -0.668670 -v -0.088561 -0.108439 0.005000 -vn 0.356823 -0.066254 -0.931820 -v -0.082417 -0.114597 0.005000 -vn 0.365231 -0.000000 -0.930917 -v -0.082450 -0.115000 0.005000 -vn 0.349058 0.072415 -0.934299 -v -0.082417 -0.115403 0.005000 -vn 0.213987 -0.936134 -0.279037 -v -0.081505 -0.126000 0.017933 -vn 0.112350 -0.936830 -0.331250 -v -0.080796 -0.126000 0.018317 -vn -0.000000 -0.937756 -0.347296 -v -0.080000 -0.126000 0.018450 -vn 0.687328 -0.668337 0.284441 -v -0.071114 -0.126000 0.022074 -vn -0.296096 -0.934436 -0.197882 -v -0.077949 -0.126000 0.017340 -vn -0.111646 -0.936555 -0.332266 -v -0.079204 -0.126000 0.018317 -vn -0.214747 -0.935348 -0.281084 -v -0.078495 -0.126000 0.017933 -vn 0.284596 -0.668943 0.686674 -v -0.071926 -0.126000 0.022886 -vn 0.525942 -0.668671 0.525608 -v -0.071439 -0.126000 0.022561 -vn 0.072415 -0.934296 0.349065 -v -0.080403 -0.126000 0.013583 -vn 0.173264 -0.935289 0.308567 -v -0.081166 -0.126000 0.013845 -vn -0.724268 -0.685820 0.071317 -v -0.089000 -0.126000 0.021500 -vn 0.341800 -0.935345 -0.091122 -v -0.082375 -0.126000 0.016601 -vn -0.689267 -0.665894 0.285474 -v -0.088886 -0.126000 0.022074 -vn 0.293483 -0.935651 -0.196024 -v -0.082051 -0.126000 0.017340 -vn -0.527533 -0.665935 0.527485 -v -0.088561 -0.126000 0.022561 -vn -0.345967 -0.933765 -0.091593 -v -0.077625 -0.126000 0.016601 -vn -0.358198 -0.933283 0.026011 -v -0.077558 -0.126000 0.015798 -vn -0.330947 -0.932946 0.141724 -v -0.077756 -0.126000 0.015016 -vn -0.266938 -0.932717 0.242451 -v -0.078197 -0.126000 0.014341 -vn 0.264290 -0.935185 0.235754 -v -0.081803 -0.126000 0.014341 -vn 0.326563 -0.935141 0.137358 -v -0.082244 -0.126000 0.015016 -vn 0.353319 -0.935189 0.024233 -v -0.082442 -0.126000 0.015798 -vn -0.285513 -0.665961 0.689187 -v -0.088074 -0.126000 0.022886 -vn -0.173132 -0.932579 0.316738 -v -0.078834 -0.126000 0.013845 -vn -0.066256 -0.931817 0.356831 -v -0.079597 -0.126000 0.013583 -vn -0.000000 -0.930913 0.365240 -v -0.080000 -0.126000 0.013550 -vn -0.026013 -0.358190 0.933286 -v -0.079798 -0.112558 0.008000 -vn 0.091590 -0.345955 0.933770 -v -0.080601 -0.112625 0.008000 -vn -0.308565 0.173262 0.935290 -v -0.077845 -0.116166 0.008000 -vn -0.235757 0.264287 0.935185 -v -0.078341 -0.116803 0.008000 -vn -0.577350 0.577350 0.577351 -v -0.073000 -0.123000 0.008000 -vn 0.332261 -0.111642 0.936557 -v -0.082317 -0.114204 0.008000 -vn 0.281082 -0.214744 0.935349 -v -0.081933 -0.113495 0.008000 -vn 0.197875 -0.296089 0.934439 -v -0.081340 -0.112949 0.008000 -vn -0.137351 0.326554 0.935145 -v -0.079016 -0.117244 0.008000 -vn -0.024233 0.353319 0.935189 -v -0.079798 -0.117442 0.008000 -vn 0.577350 0.577350 0.577350 -v -0.087000 -0.123000 0.008000 -vn 0.091121 0.341794 0.935347 -v -0.080601 -0.117375 0.008000 -vn 0.196025 0.293481 0.935651 -v -0.081340 -0.117051 0.008000 -vn 0.279037 0.213990 0.936134 -v -0.081933 -0.116505 0.008000 -vn 0.331241 0.112346 0.936834 -v -0.082317 -0.115796 0.008000 -vn 0.347290 0.000001 0.937758 -v -0.082450 -0.115000 0.008000 -vn -0.141724 -0.330947 0.932946 -v -0.079016 -0.112756 0.008000 -vn -0.242446 -0.266933 0.932720 -v -0.078341 -0.113197 0.008000 -vn -0.316735 -0.173129 0.932580 -v -0.077845 -0.113834 0.008000 -vn -0.356829 -0.066257 0.931817 -v -0.077583 -0.114597 0.008000 -vn -0.365239 -0.000000 0.930914 -v -0.077550 -0.115000 0.008000 -vn -0.349066 0.072417 0.934296 -v -0.077583 -0.115403 0.008000 -vn -0.000000 0.937758 0.347290 -v -0.080000 -0.123000 0.013550 -vn -0.111644 0.936558 0.332258 -v -0.079204 -0.123000 0.013683 -vn -0.214742 0.935351 0.281079 -v -0.078495 -0.123000 0.014067 -vn -0.330940 0.932949 -0.141721 -v -0.077756 -0.123000 0.016984 -vn -0.266933 0.932720 -0.242447 -v -0.078197 -0.123000 0.017659 -vn -0.173128 0.932581 -0.316731 -v -0.078834 -0.123000 0.018155 -vn -0.059949 0.932516 -0.356119 -v -0.079597 -0.123000 0.018417 -vn -0.296089 0.934439 0.197877 -v -0.077949 -0.123000 0.014660 -vn -0.345959 0.933769 0.091591 -v -0.077625 -0.123000 0.015399 -vn -0.358190 0.933286 -0.026011 -v -0.077558 -0.123000 0.016202 -vn 0.066124 0.935023 -0.348368 -v -0.080403 -0.123000 0.018417 -vn 0.173260 0.935292 -0.308560 -v -0.081166 -0.123000 0.018155 -vn 0.264284 0.935188 -0.235749 -v -0.081803 -0.123000 0.017659 -vn 0.326556 0.935144 -0.137355 -v -0.082244 -0.123000 0.016984 -vn 0.353311 0.935192 -0.024232 -v -0.082442 -0.123000 0.016202 -vn 0.341791 0.935348 0.091120 -v -0.082375 -0.123000 0.015399 -vn 0.293475 0.935654 0.196019 -v -0.082051 -0.123000 0.014660 -vn 0.213982 0.936137 0.279031 -v -0.081505 -0.123000 0.014067 -vn 0.112347 0.936834 0.331241 -v -0.080796 -0.123000 0.013683 -vn -0.681578 0.565890 0.463918 -v -0.088971 -0.109207 0.009207 -vn -0.708580 0.507593 0.490167 -v -0.089000 -0.109500 0.009500 -vn -0.681952 0.462056 0.566962 -v -0.088971 -0.121793 0.021793 -vn -0.708580 0.490167 0.507594 -v -0.089000 -0.121500 0.021500 -vn -0.443980 0.805199 0.393111 -v -0.088561 -0.108439 0.008439 -vn -0.534561 0.737771 0.412236 -v -0.088747 -0.108667 0.008667 -vn -0.614310 0.657788 0.435819 -v -0.088886 -0.108926 0.008926 -vn -0.620652 0.432826 0.653799 -v -0.088886 -0.122074 0.022074 -vn -0.534494 0.409980 0.739076 -v -0.088747 -0.122333 0.022333 -vn -0.450869 0.389296 0.803222 -v -0.088561 -0.122561 0.022561 -vn -0.343126 0.374087 0.861582 -v -0.088333 -0.122747 0.022747 -vn -0.241378 0.360883 0.900833 -v -0.088074 -0.122886 0.022886 -vn -0.117312 0.352682 0.928361 -v -0.087793 -0.122971 0.022971 -vn -0.119901 0.926421 0.356887 -v -0.087793 -0.108029 0.008029 -vn -0.235471 0.900672 0.365162 -v -0.088074 -0.108114 0.008114 -vn -0.343993 0.859909 0.377128 -v -0.088333 -0.108253 0.008253 -vn 0.908416 0.168265 -0.382710 -v -0.082219 -0.115370 0.005200 -vn 0.919694 0.000001 0.392635 -v -0.082250 -0.115000 0.007800 -vn 0.892580 0.231105 0.387159 -v -0.082128 -0.115731 0.007800 -vn 0.899171 0.294749 -0.323443 -v -0.082114 -0.115770 0.005200 -vn 0.841818 0.381584 0.381755 -v -0.082114 -0.115770 0.007800 -vn 0.800950 0.459984 -0.383268 -v -0.081979 -0.116071 0.005200 -vn 0.765556 0.514262 0.386598 -v -0.081776 -0.116382 0.007800 -vn 0.745437 0.576943 -0.333857 -v -0.081724 -0.116446 0.005200 -vn 0.665769 0.644576 0.375864 -v -0.081724 -0.116446 0.007800 -vn 0.602850 0.699466 -0.383821 -v -0.081524 -0.116655 0.005200 -vn 0.551789 0.739256 0.386045 -v -0.081231 -0.116884 0.007800 -vn 0.506748 0.790624 -0.343687 -v -0.081125 -0.116949 0.005200 -vn 0.411149 0.833524 0.369045 -v -0.081125 -0.116949 0.007800 -vn 0.336589 0.859627 -0.384381 -v -0.080904 -0.117060 0.005200 -vn 0.275375 0.880663 0.385489 -v -0.080552 -0.117181 0.007800 -vn 0.211085 0.911553 -0.352866 -v -0.080391 -0.117216 0.005200 -vn 0.107152 0.926255 0.361344 -v -0.080391 -0.117216 0.007800 -vn 0.032357 0.922377 -0.384934 -v -0.080186 -0.117242 0.005200 -vn -0.032357 0.922376 0.384935 -v -0.079814 -0.117242 0.007800 -vn -0.107152 0.926255 -0.361344 -v -0.079609 -0.117216 0.005200 -vn -0.211085 0.911552 0.352867 -v -0.079609 -0.117216 0.007800 -vn -0.275375 0.880663 -0.385489 -v -0.079448 -0.117181 0.005200 -vn -0.336589 0.859627 0.384381 -v -0.079096 -0.117060 0.007800 -vn -0.411149 0.833524 -0.369045 -v -0.078875 -0.116949 0.005200 -vn -0.506748 0.790624 0.343687 -v -0.078875 -0.116949 0.007800 -vn -0.551790 0.739254 -0.386046 -v -0.078769 -0.116884 0.005200 -vn -0.602856 0.699460 0.383822 -v -0.078476 -0.116655 0.007800 -vn -0.665769 0.644571 -0.375871 -v -0.078276 -0.116446 0.005200 -vn -0.745432 0.576942 0.333869 -v -0.078276 -0.116446 0.007800 -vn -0.765555 0.514260 -0.386604 -v -0.078224 -0.116382 0.005200 -vn -0.800954 0.459978 0.383265 -v -0.078021 -0.116071 0.007800 -vn -0.841792 0.381654 -0.381741 -v -0.077886 -0.115770 0.005200 -vn -0.899168 0.294752 0.323448 -v -0.077886 -0.115770 0.007800 -vn -0.892560 0.231181 -0.387159 -v -0.077872 -0.115731 0.005200 -vn -0.908418 0.168271 0.382704 -v -0.077781 -0.115370 0.007800 -vn -0.919698 0.000001 -0.392626 -v -0.077750 -0.115000 0.005200 -vn -0.920823 -0.000000 0.389981 -v -0.077750 -0.115000 0.007800 -vn -0.907323 -0.155550 0.390600 -v -0.077781 -0.114630 0.007800 -vn -0.892568 -0.231155 -0.387157 -v -0.077872 -0.114269 0.005200 -vn -0.878692 -0.309545 0.363431 -v -0.077886 -0.114230 0.007800 -vn -0.842005 -0.379812 -0.383106 -v -0.077886 -0.114230 0.005200 -vn -0.803738 -0.449140 0.390228 -v -0.078021 -0.113929 0.007800 -vn -0.764336 -0.515287 -0.387647 -v -0.078224 -0.113618 0.005200 -vn -0.725554 -0.583743 0.364439 -v -0.078276 -0.113554 0.007800 -vn -0.667429 -0.640806 -0.379350 -v -0.078276 -0.113554 0.005200 -vn -0.608190 -0.691471 0.389838 -v -0.078476 -0.113345 0.007800 -vn -0.548758 -0.740426 -0.388116 -v -0.078769 -0.113116 0.005200 -vn -0.489760 -0.791194 0.366261 -v -0.078875 -0.113051 0.007800 -vn -0.415563 -0.828410 -0.375557 -v -0.078875 -0.113051 0.005200 -vn -0.343010 -0.854804 0.389427 -v -0.079096 -0.112939 0.007800 -vn -0.270543 -0.880804 -0.388575 -v -0.079448 -0.112819 0.005200 -vn -0.198284 -0.908106 0.368819 -v -0.079609 -0.112784 0.007800 -vn -0.115500 -0.921027 -0.371979 -v -0.079609 -0.112784 0.005200 -vn -0.038499 -0.920429 0.389010 -v -0.079814 -0.112758 0.007800 -vn 0.038499 -0.920429 -0.389010 -v -0.080186 -0.112758 0.005200 -vn 0.115501 -0.921027 0.371979 -v -0.080391 -0.112784 0.007800 -vn 0.198284 -0.908106 -0.368818 -v -0.080391 -0.112784 0.005200 -vn 0.270543 -0.880804 0.388575 -v -0.080552 -0.112819 0.007800 -vn 0.343010 -0.854805 -0.389427 -v -0.080904 -0.112939 0.005200 -vn 0.415563 -0.828410 0.375557 -v -0.081125 -0.113051 0.007800 -vn 0.489760 -0.791194 -0.366260 -v -0.081125 -0.113051 0.005200 -vn 0.548755 -0.740428 0.388116 -v -0.081231 -0.113116 0.007800 -vn 0.608183 -0.691477 -0.389836 -v -0.081524 -0.113345 0.005200 -vn 0.667429 -0.640809 0.379344 -v -0.081724 -0.113554 0.007800 -vn 0.725552 -0.583746 -0.364438 -v -0.081724 -0.113554 0.005200 -vn 0.764339 -0.515287 0.387640 -v -0.081776 -0.113618 0.007800 -vn 0.803735 -0.449142 -0.390233 -v -0.081979 -0.113929 0.005200 -vn 0.842030 -0.379743 0.383119 -v -0.082114 -0.114230 0.007800 -vn 0.878690 -0.309545 -0.363436 -v -0.082114 -0.114230 0.005200 -vn 0.892588 -0.231079 0.387156 -v -0.082128 -0.114269 0.007800 -vn 0.907321 -0.155542 -0.390608 -v -0.082219 -0.114630 0.005200 -vn 0.920819 -0.000000 -0.389989 -v -0.082250 -0.115000 0.005200 -vn 0.168264 0.382711 -0.908416 -v -0.080370 -0.123200 0.018219 -vn -0.000000 -0.392628 -0.919698 -v -0.080000 -0.125800 0.018250 -vn 0.231135 -0.387151 -0.892575 -v -0.080731 -0.125800 0.018128 -vn 0.294746 0.323444 -0.899171 -v -0.080770 -0.123200 0.018114 -vn 0.381616 -0.381739 -0.841811 -v -0.080770 -0.125800 0.018114 -vn 0.459980 0.383269 -0.800952 -v -0.081071 -0.123200 0.017979 -vn 0.514241 -0.386595 -0.765572 -v -0.081382 -0.125800 0.017776 -vn 0.576946 0.333869 -0.745429 -v -0.081446 -0.123200 0.017724 -vn 0.644557 -0.375868 -0.665785 -v -0.081446 -0.125800 0.017724 -vn 0.699466 0.383829 -0.602846 -v -0.081655 -0.123200 0.017524 -vn 0.739268 -0.386044 -0.551773 -v -0.081884 -0.125800 0.017231 -vn 0.790619 0.343686 -0.506755 -v -0.081949 -0.123200 0.017125 -vn 0.833532 -0.369044 -0.411134 -v -0.081949 -0.125800 0.017125 -vn 0.859624 0.384381 -0.336598 -v -0.082060 -0.123200 0.016904 -vn 0.880665 -0.385484 -0.275374 -v -0.082181 -0.125800 0.016552 -vn 0.911547 0.352879 -0.211090 -v -0.082216 -0.123200 0.016391 -vn 0.926255 -0.361342 -0.107160 -v -0.082216 -0.125800 0.016391 -vn 0.922373 0.384942 -0.032369 -v -0.082242 -0.123200 0.016186 -vn 0.922377 -0.384933 0.032369 -v -0.082242 -0.125800 0.015814 -vn 0.926252 0.361351 0.107159 -v -0.082216 -0.123200 0.015609 -vn 0.911550 -0.352871 0.211091 -v -0.082216 -0.125800 0.015609 -vn 0.880662 0.385494 0.275372 -v -0.082181 -0.123200 0.015448 -vn 0.859627 -0.384373 0.336600 -v -0.082060 -0.125800 0.015096 -vn 0.833529 0.369053 0.411131 -v -0.081949 -0.123200 0.014875 -vn 0.790621 -0.343679 0.506757 -v -0.081949 -0.125800 0.014875 -vn 0.739266 0.386054 0.551769 -v -0.081884 -0.123200 0.014769 -vn 0.699470 -0.383821 0.602846 -v -0.081655 -0.125800 0.014476 -vn 0.644553 0.375877 0.665784 -v -0.081446 -0.123200 0.014276 -vn 0.576948 -0.333859 0.745432 -v -0.081446 -0.125800 0.014276 -vn 0.514236 0.386604 0.765571 -v -0.081382 -0.123200 0.014224 -vn 0.459983 -0.383261 0.800954 -v -0.081071 -0.125800 0.014021 -vn 0.381606 0.381750 0.841810 -v -0.080770 -0.123200 0.013886 -vn 0.294749 -0.323436 0.899173 -v -0.080770 -0.125800 0.013886 -vn 0.231125 0.387159 0.892574 -v -0.080731 -0.123200 0.013872 -vn 0.168265 -0.382702 0.908420 -v -0.080370 -0.125800 0.013781 -vn 0.000000 0.392635 0.919694 -v -0.080000 -0.123200 0.013750 -vn 0.000000 0.363300 -0.931672 -v -0.080000 -0.123200 0.018250 -vn -0.155546 0.390608 -0.907321 -v -0.079630 -0.123200 0.018219 -vn -0.231161 -0.387154 -0.892567 -v -0.079269 -0.125800 0.018128 -vn -0.309545 0.363435 -0.878690 -v -0.079230 -0.123200 0.018114 -vn -0.379820 -0.383101 -0.842004 -v -0.079230 -0.125800 0.018114 -vn -0.449140 0.390231 -0.803737 -v -0.078929 -0.123200 0.017979 -vn -0.515309 -0.387636 -0.764327 -v -0.078618 -0.125800 0.017776 -vn -0.583744 0.364439 -0.725553 -v -0.078554 -0.123200 0.017724 -vn -0.640827 -0.379335 -0.667417 -v -0.078554 -0.125800 0.017724 -vn -0.691469 0.389839 -0.608191 -v -0.078345 -0.123200 0.017524 -vn -0.740426 -0.388105 -0.548765 -v -0.078116 -0.125800 0.017231 -vn -0.791195 0.366266 -0.489755 -v -0.078051 -0.123200 0.017125 -vn -0.828414 -0.375545 -0.415568 -v -0.078051 -0.125800 0.017125 -vn -0.854803 0.389437 -0.343003 -v -0.077940 -0.123200 0.016904 -vn -0.880809 -0.388563 -0.270545 -v -0.077819 -0.125800 0.016552 -vn -0.908107 0.368822 -0.198273 -v -0.077784 -0.123200 0.016391 -vn -0.921032 -0.371967 -0.115497 -v -0.077784 -0.125800 0.016391 -vn -0.920428 0.389012 -0.038488 -v -0.077758 -0.123200 0.016186 -vn -0.920432 -0.389003 0.038489 -v -0.077758 -0.125800 0.015814 -vn -0.921029 0.371976 0.115496 -v -0.077784 -0.123200 0.015609 -vn -0.908110 -0.368814 0.198274 -v -0.077784 -0.125800 0.015609 -vn -0.880805 0.388572 0.270544 -v -0.077819 -0.123200 0.015448 -vn -0.854806 -0.389429 0.343005 -v -0.077940 -0.125800 0.015096 -vn -0.828411 0.375554 0.415565 -v -0.078051 -0.123200 0.014875 -vn -0.791197 -0.366258 0.489757 -v -0.078051 -0.125800 0.014875 -vn -0.740425 0.388115 0.548761 -v -0.078116 -0.123200 0.014769 -vn -0.691473 -0.389831 0.608192 -v -0.078345 -0.125800 0.014476 -vn -0.640822 0.379344 0.667417 -v -0.078554 -0.123200 0.014276 -vn -0.583746 -0.364432 0.725555 -v -0.078554 -0.125800 0.014276 -vn -0.515304 0.387644 0.764326 -v -0.078618 -0.123200 0.014224 -vn -0.449142 -0.390224 0.803739 -v -0.078929 -0.125800 0.014021 -vn -0.379810 0.383112 0.842004 -v -0.079230 -0.123200 0.013886 -vn -0.309548 -0.363427 0.878693 -v -0.079230 -0.125800 0.013886 -vn -0.231151 0.387163 0.892566 -v -0.079269 -0.123200 0.013872 -vn -0.155546 -0.390599 0.907324 -v -0.079630 -0.125800 0.013781 -vn -0.000000 -0.389981 0.920823 -v -0.080000 -0.125800 0.013750 -vn -0.727971 -0.095836 0.678876 -v 0.031750 0.145000 0.164800 -vn -0.655723 -0.378578 0.653227 -v 0.031817 0.144750 0.164800 -vn -0.378575 -0.655726 0.653226 -v 0.032000 0.144567 0.164800 -vn -0.727973 0.095837 0.678874 -v 0.031750 0.127000 0.164800 -vn -0.577348 -0.577354 0.577348 -v 0.031750 0.126500 0.164800 -vn -0.088113 -0.669358 0.737697 -v 0.032100 0.126500 0.164800 -vn 0.727974 -0.095842 0.678873 -v 0.025750 0.145000 0.164800 -vn 0.577348 0.577354 0.577348 -v 0.025750 0.145500 0.164800 -vn 0.088114 0.669357 0.737697 -v 0.025400 0.145500 0.164800 -vn 0.552298 0.318870 0.770253 -v 0.025227 0.145600 0.164800 -vn 0.318867 -0.552296 0.770255 -v 0.023000 0.144433 0.164800 -vn 0.088131 -0.669346 0.737705 -v 0.023250 0.144500 0.164800 -vn 0.655720 -0.378579 0.653230 -v 0.025683 0.144750 0.164800 -vn -0.577349 -0.577352 0.577349 -v 0.019250 0.139000 0.164800 -vn 0.095851 -0.727973 0.678872 -v 0.019750 0.139000 0.164800 -vn -0.669355 -0.088118 0.737699 -v 0.019250 0.139350 0.164800 -vn 0.378576 -0.655717 0.653235 -v 0.020000 0.139067 0.164800 -vn -0.552295 -0.318853 0.770261 -v 0.019223 0.139450 0.164800 -vn 0.318863 0.552276 0.770271 -v 0.025300 0.145527 0.164800 -vn 0.095830 -0.727970 0.678878 -v 0.025250 0.144500 0.164800 -vn 0.378577 -0.655726 0.653225 -v 0.025500 0.144567 0.164800 -vn -0.095852 -0.727975 0.678870 -v 0.037750 0.139000 0.164800 -vn 0.577354 -0.577348 0.577348 -v 0.038250 0.139000 0.164800 -vn 0.669352 -0.088124 0.737701 -v 0.038250 0.139350 0.164800 -vn -0.577352 0.577349 0.577349 -v 0.031750 0.145500 0.164800 -vn -0.088112 0.669358 0.737697 -v 0.032100 0.145500 0.164800 -vn -0.318862 0.552273 0.770273 -v 0.032200 0.145527 0.164800 -vn -0.552300 0.318869 0.770251 -v 0.032273 0.145600 0.164800 -vn 0.318868 0.552295 0.770255 -v 0.023000 0.127567 0.164800 -vn 0.552279 0.318866 0.770268 -v 0.022817 0.127750 0.164800 -vn -0.095837 -0.727972 0.678876 -v 0.020250 0.126000 0.164800 -vn 0.727972 0.095838 0.678875 -v 0.038750 0.144500 0.164800 -vn -0.318868 -0.552295 0.770255 -v 0.037000 0.141933 0.164800 -vn -0.552279 -0.318866 0.770268 -v 0.037183 0.141750 0.164800 -vn -0.378576 -0.655716 0.653235 -v 0.037500 0.139067 0.164800 -vn -0.655722 -0.378589 0.653222 -v 0.037317 0.139250 0.164800 -vn -0.727971 -0.095831 0.678878 -v 0.037250 0.139500 0.164800 -vn -0.577350 -0.577350 0.577350 -v 0.018750 0.139550 0.164800 -vn -0.088114 -0.669357 0.737697 -v 0.019050 0.139550 0.164800 -vn -0.727972 0.095838 0.678875 -v 0.018750 0.144500 0.164800 -vn -0.318860 -0.552280 0.770270 -v 0.019150 0.139523 0.164800 -vn 0.552297 -0.318871 0.770253 -v 0.025227 0.126400 0.164800 -vn 0.669345 -0.088136 0.737705 -v 0.025200 0.126300 0.164800 -vn 0.577350 -0.577350 0.577350 -v 0.025200 0.126000 0.164800 -vn -0.669343 -0.088135 0.737707 -v 0.032300 0.126300 0.164800 -vn -0.577350 -0.577350 0.577350 -v 0.032300 0.126000 0.164800 -vn 0.095837 -0.727972 0.678876 -v 0.037250 0.126000 0.164800 -vn 0.655720 -0.378590 0.653223 -v 0.020183 0.139250 0.164800 -vn 0.727972 -0.095834 0.678876 -v 0.020250 0.139500 0.164800 -vn 0.669354 -0.088119 0.737699 -v 0.020250 0.141500 0.164800 -vn 0.095851 0.727975 0.678870 -v 0.019750 0.133000 0.164800 -vn -0.577354 0.577348 0.577348 -v 0.019250 0.133000 0.164800 -vn -0.669354 0.088118 0.737699 -v 0.019250 0.132650 0.164800 -vn -0.669353 -0.088119 0.737700 -v 0.037250 0.141500 0.164800 -vn 0.552294 -0.318861 0.770259 -v 0.038277 0.139450 0.164800 -vn 0.318861 -0.552280 0.770269 -v 0.038350 0.139523 0.164800 -vn 0.088115 -0.669354 0.737700 -v 0.038450 0.139550 0.164800 -vn 0.577350 -0.577350 0.577350 -v 0.038750 0.139550 0.164800 -vn -0.095837 0.727973 0.678875 -v 0.020250 0.146000 0.164800 -vn 0.669343 0.088135 0.737707 -v 0.025200 0.145700 0.164800 -vn 0.577350 0.577350 0.577350 -v 0.025200 0.146000 0.164800 -vn 0.088132 0.669347 0.737704 -v 0.023250 0.127500 0.164800 -vn 0.095830 0.727971 0.678877 -v 0.025250 0.127500 0.164800 -vn 0.577352 -0.577349 0.577349 -v 0.025750 0.126500 0.164800 -vn 0.727972 0.095841 0.678875 -v 0.025750 0.127000 0.164800 -vn 0.088113 -0.669357 0.737697 -v 0.025400 0.126500 0.164800 -vn 0.655721 0.378578 0.653230 -v 0.025683 0.127250 0.164800 -vn 0.727971 0.095833 0.678877 -v 0.020250 0.132500 0.164800 -vn 0.655721 0.378589 0.653223 -v 0.020183 0.132750 0.164800 -vn 0.378577 0.655716 0.653234 -v 0.020000 0.132933 0.164800 -vn -0.552301 -0.318868 0.770251 -v 0.032273 0.126400 0.164800 -vn 0.318861 -0.552277 0.770271 -v 0.025300 0.126473 0.164800 -vn 0.378578 0.655726 0.653225 -v 0.025500 0.127433 0.164800 -vn -0.088132 -0.669347 0.737704 -v 0.034250 0.144500 0.164800 -vn -0.318868 -0.552295 0.770255 -v 0.034500 0.144433 0.164800 -vn 0.095838 0.727975 0.678873 -v 0.037250 0.146000 0.164800 -vn -0.727972 0.095831 0.678877 -v 0.037250 0.132500 0.164800 -vn -0.669352 0.088124 0.737701 -v 0.037250 0.130500 0.164800 -vn 0.318862 0.552280 0.770269 -v 0.038350 0.132477 0.164800 -vn 0.727972 -0.095840 0.678875 -v 0.038750 0.127500 0.164800 -vn 0.088116 0.669356 0.737698 -v 0.038450 0.132450 0.164800 -vn 0.577350 0.577350 0.577350 -v 0.038750 0.132450 0.164800 -vn -0.727972 -0.095840 0.678875 -v 0.018750 0.127500 0.164800 -vn 0.318877 0.552283 0.770260 -v 0.020500 0.130067 0.164800 -vn 0.552290 0.318863 0.770261 -v 0.020317 0.130250 0.164800 -vn 0.577349 0.577352 0.577349 -v 0.038250 0.133000 0.164800 -vn -0.095852 0.727973 0.678872 -v 0.037750 0.133000 0.164800 -vn 0.669352 0.088123 0.737701 -v 0.038250 0.132650 0.164800 -vn -0.378575 0.655717 0.653235 -v 0.037500 0.132933 0.164800 -vn -0.669357 0.088115 0.737698 -v 0.034750 0.128000 0.164800 -vn -0.552279 0.318862 0.770270 -v 0.034683 0.127750 0.164800 -vn 0.251476 0.607118 0.753769 -v 0.035826 0.130038 0.164800 -vn 0.552295 0.318859 0.770259 -v 0.038277 0.132550 0.164800 -vn -0.655721 0.378590 0.653222 -v 0.037317 0.132750 0.164800 -vn -0.378583 -0.655722 0.653225 -v 0.019500 0.126201 0.164800 -vn 0.088132 0.669347 0.737704 -v 0.020750 0.130000 0.164800 -vn 0.669351 0.088124 0.737702 -v 0.020250 0.130500 0.164800 -vn -0.552294 0.318854 0.770262 -v 0.019223 0.132550 0.164800 -vn -0.318859 0.552281 0.770270 -v 0.019150 0.132477 0.164800 -vn -0.088114 0.669355 0.737699 -v 0.019050 0.132450 0.164800 -vn -0.577350 0.577350 0.577350 -v 0.018750 0.132450 0.164800 -vn -0.095831 -0.727972 0.678877 -v 0.032250 0.144500 0.164800 -vn -0.669345 0.088136 0.737706 -v 0.032300 0.145700 0.164800 -vn -0.577350 0.577350 0.577350 -v 0.032300 0.146000 0.164800 -vn -0.088131 0.669346 0.737705 -v 0.036750 0.130000 0.164800 -vn 0.067001 0.680319 0.729847 -v 0.036018 0.130000 0.164800 -vn -0.680319 -0.067006 0.729847 -v 0.034750 0.128732 0.164800 -vn 0.639164 0.077609 0.765145 -v 0.026020 0.135669 0.164800 -vn 0.602017 -0.228315 0.765145 -v 0.026179 0.136975 0.164800 -vn -0.607124 -0.251476 0.753764 -v 0.024212 0.139424 0.164800 -vn -0.528438 -0.433673 0.729850 -v 0.024104 0.139586 0.164800 -vn 0.433682 0.528437 0.729845 -v 0.035664 0.130146 0.164800 -vn 0.528439 0.433670 0.729851 -v 0.033396 0.132414 0.164800 -vn -0.529886 0.365752 0.765145 -v 0.031013 0.134438 0.164800 -vn 0.607126 0.251474 0.753763 -v 0.033288 0.132576 0.164800 -vn -0.639163 0.077608 0.765145 -v 0.031480 0.135669 0.164800 -vn 0.680319 0.067006 0.729847 -v 0.033250 0.132768 0.164800 -vn -0.602017 -0.228315 0.765145 -v 0.031321 0.136975 0.164800 -vn 0.680317 -0.067006 0.729849 -v 0.033250 0.139232 0.164800 -vn -0.426954 -0.481934 0.765147 -v 0.030574 0.138058 0.164800 -vn -0.552290 0.318864 0.770261 -v 0.037183 0.130250 0.164800 -vn -0.318876 0.552284 0.770260 -v 0.037000 0.130067 0.164800 -vn 0.655722 -0.378579 0.653228 -v 0.038549 0.126750 0.164800 -vn 0.378582 -0.655722 0.653226 -v 0.038000 0.126201 0.164800 -vn -0.655722 0.378579 0.653227 -v 0.031817 0.127250 0.164800 -vn -0.378574 0.655727 0.653226 -v 0.032000 0.127433 0.164800 -vn -0.095831 0.727971 0.678878 -v 0.032250 0.127500 0.164800 -vn -0.318864 -0.552272 0.770273 -v 0.032200 0.126473 0.164800 -vn -0.088131 0.669346 0.737705 -v 0.034250 0.127500 0.164800 -vn -0.318867 0.552296 0.770255 -v 0.034500 0.127567 0.164800 -vn 0.680319 0.067006 0.729847 -v 0.022750 0.143268 0.164800 -vn 0.669354 -0.088119 0.737699 -v 0.022750 0.144000 0.164800 -vn 0.552278 -0.318867 0.770268 -v 0.022817 0.144250 0.164800 -vn -0.552279 -0.318866 0.770268 -v 0.034683 0.144250 0.164800 -vn -0.669353 -0.088119 0.737700 -v 0.034750 0.144000 0.164800 -vn -0.680317 0.067006 0.729849 -v 0.034750 0.143268 0.164800 -vn 0.251477 -0.607118 0.753769 -v 0.035826 0.141962 0.164800 -vn 0.067001 -0.680321 0.729845 -v 0.036018 0.142000 0.164800 -vn -0.088132 -0.669347 0.737704 -v 0.036750 0.142000 0.164800 -vn 0.378577 0.655724 0.653227 -v 0.038000 0.145799 0.164800 -vn -0.251477 -0.607117 0.753770 -v 0.021674 0.141962 0.164800 -vn -0.067001 -0.680319 0.729847 -v 0.021482 0.142000 0.164800 -vn 0.088131 -0.669346 0.737705 -v 0.020750 0.142000 0.164800 -vn -0.000000 0.643858 0.765145 -v 0.028750 0.133250 0.164800 -vn -0.067025 -0.680307 0.729856 -v 0.031982 0.131500 0.164800 -vn -0.299217 0.570106 0.765146 -v 0.030028 0.133565 0.164800 -vn -0.251489 -0.607132 0.753753 -v 0.032174 0.131462 0.164800 -vn -0.433664 -0.528444 0.729851 -v 0.032336 0.131354 0.164800 -vn -0.528437 -0.433676 0.729849 -v 0.034604 0.129086 0.164800 -vn -0.607122 -0.251478 0.753765 -v 0.034712 0.128924 0.164800 -vn 0.669353 0.088119 0.737700 -v 0.022750 0.128000 0.164800 -vn -0.251479 0.607117 0.753769 -v 0.021674 0.130038 0.164800 -vn 0.680317 -0.067006 0.729849 -v 0.022750 0.128732 0.164800 -vn -0.067001 0.680321 0.729845 -v 0.021482 0.130000 0.164800 -vn -0.680319 -0.067006 0.729847 -v 0.024250 0.139232 0.164800 -vn -0.680317 0.067006 0.729849 -v 0.024250 0.132768 0.164800 -vn 0.529886 0.365752 0.765145 -v 0.026487 0.134438 0.164800 -vn -0.607124 0.251475 0.753764 -v 0.024212 0.132576 0.164800 -vn -0.528440 0.433674 0.729848 -v 0.024104 0.132414 0.164800 -vn -0.433684 -0.528437 0.729844 -v 0.021836 0.141854 0.164800 -vn 0.426954 -0.481934 0.765147 -v 0.026926 0.138058 0.164800 -vn -0.607111 0.251487 0.753770 -v 0.034712 0.143076 0.164800 -vn -0.528435 0.433691 0.729841 -v 0.034604 0.142914 0.164800 -vn -0.433664 0.528441 0.729854 -v 0.032336 0.140646 0.164800 -vn -0.251491 0.607132 0.753753 -v 0.032174 0.140538 0.164800 -vn 0.607126 -0.251473 0.753763 -v 0.033288 0.139424 0.164800 -vn 0.528441 -0.433672 0.729849 -v 0.033396 0.139586 0.164800 -vn 0.433681 -0.528435 0.729847 -v 0.035664 0.141854 0.164800 -vn 0.655722 0.378583 0.653226 -v 0.038549 0.145250 0.164800 -vn 0.607124 -0.251475 0.753764 -v 0.022788 0.128924 0.164800 -vn 0.528440 -0.433674 0.729848 -v 0.022896 0.129086 0.164800 -vn -0.433683 0.528435 0.729846 -v 0.021836 0.130146 0.164800 -vn 0.433661 -0.528442 0.729854 -v 0.025164 0.131354 0.164800 -vn -0.655722 -0.378579 0.653228 -v 0.018951 0.126750 0.164800 -vn 0.552278 -0.318867 0.770268 -v 0.020317 0.141750 0.164800 -vn 0.318867 -0.552296 0.770255 -v 0.020500 0.141933 0.164800 -vn -0.655722 0.378582 0.653226 -v 0.018951 0.145250 0.164800 -vn -0.378578 0.655724 0.653227 -v 0.019500 0.145799 0.164800 -vn 0.251488 0.607134 0.753752 -v 0.025326 0.140538 0.164800 -vn 0.067025 0.680307 0.729856 -v 0.025518 0.140500 0.164800 -vn 0.196775 -0.631470 0.750017 -v 0.028092 0.138670 0.164800 -vn -0.067026 0.680309 0.729854 -v 0.031982 0.140500 0.164800 -vn 0.000000 -0.677773 0.735272 -v 0.028750 0.138750 0.164800 -vn -0.196775 -0.631471 0.750016 -v 0.029408 0.138670 0.164800 -vn 0.433663 0.528443 0.729852 -v 0.025164 0.140646 0.164800 -vn 0.528434 0.433687 0.729845 -v 0.022896 0.142914 0.164800 -vn 0.607113 0.251487 0.753769 -v 0.022788 0.143076 0.164800 -vn 0.299216 0.570106 0.765146 -v 0.027472 0.133565 0.164800 -vn 0.251489 -0.607133 0.753752 -v 0.025326 0.131462 0.164800 -vn 0.067026 -0.680309 0.729854 -v 0.025518 0.131500 0.164800 -vn 0.655721 -0.378578 -0.653230 -v 0.025683 0.144750 0.094800 -vn 0.378578 -0.655726 -0.653225 -v 0.025500 0.144567 0.094800 -vn 0.095830 -0.727972 -0.678877 -v 0.025250 0.144500 0.094800 -vn -0.727973 -0.095837 -0.678874 -v 0.031750 0.145000 0.094800 -vn -0.577348 0.577354 -0.577348 -v 0.031750 0.145500 0.094800 -vn -0.088113 0.669358 -0.737697 -v 0.032100 0.145500 0.094800 -vn -0.552301 0.318868 -0.770251 -v 0.032273 0.145600 0.094800 -vn -0.318867 -0.552296 -0.770255 -v 0.034500 0.144433 0.094800 -vn -0.088131 -0.669346 -0.737705 -v 0.034250 0.144500 0.094800 -vn -0.655722 -0.378579 -0.653227 -v 0.031817 0.144750 0.094800 -vn 0.095852 -0.727975 -0.678870 -v 0.019750 0.139000 0.094800 -vn -0.577354 -0.577348 -0.577348 -v 0.019250 0.139000 0.094800 -vn -0.669355 -0.088118 -0.737699 -v 0.019250 0.139350 0.094800 -vn 0.577349 -0.577352 -0.577349 -v 0.038250 0.139000 0.094800 -vn -0.095852 -0.727973 -0.678872 -v 0.037750 0.139000 0.094800 -vn 0.669352 -0.088123 -0.737701 -v 0.038250 0.139350 0.094800 -vn -0.378575 -0.655717 -0.653235 -v 0.037500 0.139067 0.094800 -vn -0.318864 0.552272 -0.770273 -v 0.032200 0.145527 0.094800 -vn -0.095831 -0.727971 -0.678878 -v 0.032250 0.144500 0.094800 -vn -0.378574 -0.655727 -0.653226 -v 0.032000 0.144567 0.094800 -vn 0.088113 0.669357 -0.737697 -v 0.025400 0.145500 0.094800 -vn 0.577352 0.577349 -0.577349 -v 0.025750 0.145500 0.094800 -vn 0.727972 -0.095841 -0.678875 -v 0.025750 0.145000 0.094800 -vn 0.378577 -0.655716 -0.653234 -v 0.020000 0.139067 0.094800 -vn 0.655721 -0.378589 -0.653223 -v 0.020183 0.139250 0.094800 -vn 0.727971 -0.095833 -0.678877 -v 0.020250 0.139500 0.094800 -vn 0.669343 -0.088135 -0.737707 -v 0.025200 0.126300 0.094800 -vn 0.577350 -0.577350 -0.577350 -v 0.025200 0.126000 0.094800 -vn -0.095837 -0.727972 -0.678876 -v 0.020250 0.126000 0.094800 -vn -0.727972 0.095838 -0.678876 -v 0.018750 0.144500 0.094800 -vn 0.318868 -0.552295 -0.770255 -v 0.020500 0.141933 0.094800 -vn 0.552279 -0.318866 -0.770268 -v 0.020317 0.141750 0.094800 -vn -0.727971 0.095836 -0.678876 -v 0.031750 0.127000 0.094800 -vn -0.655723 0.378578 -0.653227 -v 0.031817 0.127250 0.094800 -vn -0.378575 0.655726 -0.653226 -v 0.032000 0.127433 0.094800 -vn -0.655721 -0.378590 -0.653222 -v 0.037317 0.139250 0.094800 -vn -0.727972 -0.095831 -0.678877 -v 0.037250 0.139500 0.094800 -vn 0.552295 -0.318859 -0.770259 -v 0.038277 0.139450 0.094800 -vn -0.669354 -0.088119 -0.737699 -v 0.037250 0.141500 0.094800 -vn 0.318862 -0.552280 -0.770269 -v 0.038350 0.139523 0.094800 -vn 0.727972 0.095838 -0.678875 -v 0.038750 0.144500 0.094800 -vn 0.088116 -0.669356 -0.737698 -v 0.038450 0.139550 0.094800 -vn 0.577350 -0.577350 -0.577350 -v 0.038750 0.139550 0.094800 -vn 0.318868 -0.552295 -0.770255 -v 0.023000 0.144433 0.094800 -vn 0.552279 -0.318866 -0.770268 -v 0.022817 0.144250 0.094800 -vn -0.095837 0.727973 -0.678875 -v 0.020250 0.146000 0.094800 -vn -0.577349 0.577352 -0.577349 -v 0.019250 0.133000 0.094800 -vn 0.095851 0.727973 -0.678872 -v 0.019750 0.133000 0.094800 -vn -0.669355 0.088118 -0.737699 -v 0.019250 0.132650 0.094800 -vn 0.378576 0.655717 -0.653235 -v 0.020000 0.132933 0.094800 -vn -0.552295 0.318853 -0.770261 -v 0.019223 0.132550 0.094800 -vn 0.669353 -0.088119 -0.737700 -v 0.020250 0.141500 0.094800 -vn -0.552295 -0.318855 -0.770261 -v 0.019223 0.139450 0.094800 -vn -0.318859 -0.552281 -0.770270 -v 0.019150 0.139523 0.094800 -vn -0.088114 -0.669355 -0.737699 -v 0.019050 0.139550 0.094800 -vn -0.577350 -0.577350 -0.577350 -v 0.018750 0.139550 0.094800 -vn 0.088132 -0.669347 -0.737704 -v 0.023250 0.144500 0.094800 -vn 0.727974 0.095842 -0.678873 -v 0.025750 0.127000 0.094800 -vn 0.577348 -0.577354 -0.577348 -v 0.025750 0.126500 0.094800 -vn 0.088114 -0.669357 -0.737697 -v 0.025400 0.126500 0.094800 -vn -0.095852 0.727975 -0.678870 -v 0.037750 0.133000 0.094800 -vn 0.577354 0.577348 -0.577348 -v 0.038250 0.133000 0.094800 -vn 0.669352 0.088124 -0.737701 -v 0.038250 0.132650 0.094800 -vn 0.552298 -0.318870 -0.770253 -v 0.025227 0.126400 0.094800 -vn 0.318861 0.552277 -0.770271 -v 0.025300 0.145527 0.094800 -vn 0.552297 0.318871 -0.770253 -v 0.025227 0.145600 0.094800 -vn 0.669345 0.088136 -0.737705 -v 0.025200 0.145700 0.094800 -vn 0.577350 0.577350 -0.577350 -v 0.025200 0.146000 0.094800 -vn -0.088132 0.669347 -0.737704 -v 0.034250 0.127500 0.094800 -vn -0.318869 0.552295 -0.770255 -v 0.034500 0.127567 0.094800 -vn 0.095837 -0.727972 -0.678875 -v 0.037250 0.126000 0.094800 -vn -0.552279 0.318861 -0.770270 -v 0.034683 0.127750 0.094800 -vn -0.727971 0.095831 -0.678878 -v 0.037250 0.132500 0.094800 -vn -0.655722 0.378589 -0.653222 -v 0.037317 0.132750 0.094800 -vn -0.378576 0.655716 -0.653235 -v 0.037500 0.132933 0.094800 -vn -0.577352 -0.577349 -0.577349 -v 0.031750 0.126500 0.094800 -vn -0.088112 -0.669358 -0.737697 -v 0.032100 0.126500 0.094800 -vn -0.318862 -0.552273 -0.770273 -v 0.032200 0.126473 0.094800 -vn -0.552300 -0.318869 -0.770251 -v 0.032273 0.126400 0.094800 -vn -0.095831 0.727972 -0.678877 -v 0.032250 0.127500 0.094800 -vn -0.669345 -0.088136 -0.737706 -v 0.032300 0.126300 0.094800 -vn -0.577350 -0.577350 -0.577350 -v 0.032300 0.126000 0.094800 -vn -0.577350 0.577350 -0.577350 -v 0.018750 0.132450 0.094800 -vn -0.088114 0.669357 -0.737697 -v 0.019050 0.132450 0.094800 -vn -0.727972 -0.095840 -0.678875 -v 0.018750 0.127500 0.094800 -vn -0.318860 0.552280 -0.770270 -v 0.019150 0.132477 0.094800 -vn 0.655720 0.378590 -0.653223 -v 0.020183 0.132750 0.094800 -vn 0.727972 0.095834 -0.678876 -v 0.020250 0.132500 0.094800 -vn 0.669352 0.088124 -0.737701 -v 0.020250 0.130500 0.094800 -vn 0.669354 0.088119 -0.737699 -v 0.022750 0.128000 0.094800 -vn 0.552278 0.318867 -0.770268 -v 0.022817 0.127750 0.094800 -vn -0.251477 0.607117 -0.753769 -v 0.021674 0.130038 0.094800 -vn 0.095838 0.727974 -0.678873 -v 0.037250 0.146000 0.094800 -vn -0.669343 0.088135 -0.737707 -v 0.032300 0.145700 0.094800 -vn -0.577350 0.577350 -0.577350 -v 0.032300 0.146000 0.094800 -vn -0.669350 0.088124 -0.737702 -v 0.037250 0.130500 0.094800 -vn 0.552294 0.318861 -0.770259 -v 0.038277 0.132550 0.094800 -vn -0.552290 0.318863 -0.770261 -v 0.037183 0.130250 0.094800 -vn 0.318861 0.552280 -0.770269 -v 0.038350 0.132477 0.094800 -vn 0.727972 -0.095840 -0.678875 -v 0.038750 0.127500 0.094800 -vn 0.088115 0.669354 -0.737700 -v 0.038450 0.132450 0.094800 -vn 0.577350 0.577351 -0.577350 -v 0.038750 0.132450 0.094800 -vn 0.528441 0.433672 -0.729849 -v 0.033396 0.132414 0.094800 -vn 0.433681 0.528436 -0.729847 -v 0.035664 0.130146 0.094800 -vn -0.529886 0.365751 -0.765145 -v 0.031013 0.134438 0.094800 -vn -0.639164 0.077608 -0.765145 -v 0.031480 0.135669 0.094800 -vn -0.602018 -0.228315 -0.765145 -v 0.031321 0.136975 0.094800 -vn 0.607126 -0.251474 -0.753763 -v 0.033288 0.139424 0.094800 -vn 0.528439 -0.433670 -0.729851 -v 0.033396 0.139586 0.094800 -vn 0.088131 0.669346 -0.737705 -v 0.020750 0.130000 0.094800 -vn -0.067001 0.680319 -0.729847 -v 0.021482 0.130000 0.094800 -vn 0.680319 -0.067006 -0.729847 -v 0.022750 0.128732 0.094800 -vn -0.669355 0.088114 -0.737699 -v 0.034750 0.128000 0.094800 -vn 0.251477 0.607118 -0.753769 -v 0.035826 0.130038 0.094800 -vn -0.680317 -0.067006 -0.729849 -v 0.034750 0.128732 0.094800 -vn 0.067001 0.680321 -0.729845 -v 0.036018 0.130000 0.094800 -vn -0.088132 0.669347 -0.737704 -v 0.036750 0.130000 0.094800 -vn 0.378582 -0.655722 -0.653226 -v 0.038000 0.126201 0.094800 -vn 0.655722 -0.378579 -0.653228 -v 0.038549 0.126750 0.094800 -vn -0.318877 0.552283 -0.770260 -v 0.037000 0.130067 0.094800 -vn -0.433683 -0.528435 -0.729846 -v 0.021836 0.141854 0.094800 -vn -0.251478 -0.607116 -0.753770 -v 0.021674 0.141962 0.094800 -vn 0.552290 0.318864 -0.770261 -v 0.020317 0.130250 0.094800 -vn 0.318876 0.552284 -0.770260 -v 0.020500 0.130067 0.094800 -vn -0.655722 -0.378579 -0.653228 -v 0.018951 0.126750 0.094800 -vn -0.378583 -0.655722 -0.653225 -v 0.019500 0.126201 0.094800 -vn 0.655720 0.378579 -0.653230 -v 0.025683 0.127250 0.094800 -vn 0.378577 0.655726 -0.653225 -v 0.025500 0.127433 0.094800 -vn 0.095830 0.727970 -0.678878 -v 0.025250 0.127500 0.094800 -vn 0.318863 -0.552276 -0.770271 -v 0.025300 0.126473 0.094800 -vn 0.088131 0.669346 -0.737705 -v 0.023250 0.127500 0.094800 -vn 0.318867 0.552296 -0.770255 -v 0.023000 0.127567 0.094800 -vn -0.680319 0.067006 -0.729847 -v 0.034750 0.143268 0.094800 -vn -0.669354 -0.088119 -0.737699 -v 0.034750 0.144000 0.094800 -vn -0.552278 -0.318867 -0.770268 -v 0.034683 0.144250 0.094800 -vn -0.299217 0.570106 -0.765146 -v 0.030028 0.133565 0.094800 -vn -0.433663 -0.528442 -0.729853 -v 0.032336 0.131354 0.094800 -vn -0.528439 -0.433677 -0.729847 -v 0.034604 0.129086 0.094800 -vn -0.607122 -0.251477 -0.753765 -v 0.034712 0.128924 0.094800 -vn 0.680319 -0.067006 -0.729847 -v 0.033250 0.139232 0.094800 -vn 0.680317 0.067006 -0.729849 -v 0.033250 0.132768 0.094800 -vn 0.607127 0.251473 -0.753763 -v 0.033288 0.132576 0.094800 -vn 0.251476 -0.607118 -0.753769 -v 0.035826 0.141962 0.094800 -vn 0.067001 -0.680319 -0.729847 -v 0.036018 0.142000 0.094800 -vn -0.088131 -0.669346 -0.737705 -v 0.036750 0.142000 0.094800 -vn -0.528440 -0.433674 -0.729848 -v 0.024104 0.139586 0.094800 -vn -0.067001 -0.680321 -0.729845 -v 0.021482 0.142000 0.094800 -vn 0.088132 -0.669347 -0.737704 -v 0.020750 0.142000 0.094800 -vn -0.378578 0.655724 -0.653227 -v 0.019500 0.145799 0.094800 -vn -0.433684 0.528437 -0.729844 -v 0.021836 0.130146 0.094800 -vn -0.528438 0.433673 -0.729850 -v 0.024104 0.132414 0.094800 -vn 0.529886 0.365752 -0.765145 -v 0.026487 0.134438 0.094800 -vn -0.607124 0.251476 -0.753764 -v 0.024212 0.132576 0.094800 -vn 0.639163 0.077608 -0.765145 -v 0.026020 0.135669 0.094800 -vn -0.680319 0.067006 -0.729847 -v 0.024250 0.132768 0.094800 -vn 0.602017 -0.228315 -0.765146 -v 0.026179 0.136975 0.094800 -vn -0.680317 -0.067006 -0.729849 -v 0.024250 0.139232 0.094800 -vn 0.426954 -0.481934 -0.765147 -v 0.026926 0.138058 0.094800 -vn -0.607124 -0.251475 -0.753764 -v 0.024212 0.139424 0.094800 -vn -0.251491 -0.607132 -0.753753 -v 0.032174 0.131462 0.094800 -vn -0.067026 -0.680309 -0.729854 -v 0.031982 0.131500 0.094800 -vn 0.000000 0.643858 -0.765145 -v 0.028750 0.133250 0.094800 -vn 0.067025 -0.680307 -0.729856 -v 0.025518 0.131500 0.094800 -vn 0.299217 0.570106 -0.765146 -v 0.027472 0.133565 0.094800 -vn 0.251488 -0.607134 -0.753752 -v 0.025326 0.131462 0.094800 -vn 0.433662 -0.528444 -0.729852 -v 0.025164 0.131354 0.094800 -vn 0.528438 -0.433673 -0.729850 -v 0.022896 0.129086 0.094800 -vn 0.607124 -0.251476 -0.753764 -v 0.022788 0.128924 0.094800 -vn 0.433682 -0.528437 -0.729845 -v 0.035664 0.141854 0.094800 -vn -0.426955 -0.481934 -0.765146 -v 0.030574 0.138058 0.094800 -vn 0.669353 -0.088119 -0.737700 -v 0.022750 0.144000 0.094800 -vn 0.680317 0.067006 -0.729849 -v 0.022750 0.143268 0.094800 -vn 0.607113 0.251486 -0.753769 -v 0.022788 0.143076 0.094800 -vn -0.552278 -0.318867 -0.770268 -v 0.037183 0.141750 0.094800 -vn -0.318867 -0.552296 -0.770255 -v 0.037000 0.141933 0.094800 -vn 0.655722 0.378583 -0.653226 -v 0.038549 0.145250 0.094800 -vn 0.378577 0.655724 -0.653227 -v 0.038000 0.145799 0.094800 -vn -0.655722 0.378582 -0.653226 -v 0.018951 0.145250 0.094800 -vn -0.067025 0.680307 -0.729856 -v 0.031982 0.140500 0.094800 -vn -0.251489 0.607132 -0.753753 -v 0.032174 0.140538 0.094800 -vn -0.433665 0.528443 -0.729852 -v 0.032336 0.140646 0.094800 -vn -0.528433 0.433690 -0.729843 -v 0.034604 0.142914 0.094800 -vn -0.607111 0.251489 -0.753770 -v 0.034712 0.143076 0.094800 -vn 0.528436 0.433688 -0.729843 -v 0.022896 0.142914 0.094800 -vn 0.433662 0.528441 -0.729854 -v 0.025164 0.140646 0.094800 -vn 0.251489 0.607133 -0.753752 -v 0.025326 0.140538 0.094800 -vn 0.196775 -0.631470 -0.750017 -v 0.028092 0.138670 0.094800 -vn 0.067026 0.680309 -0.729854 -v 0.025518 0.140500 0.094800 -vn -0.000000 -0.677773 -0.735272 -v 0.028750 0.138750 0.094800 -vn -0.196775 -0.631470 -0.750017 -v 0.029408 0.138670 0.094800 -vn -0.727971 -0.095836 0.678876 -v 0.031750 -0.127000 0.164800 -vn -0.655723 -0.378578 0.653227 -v 0.031817 -0.127250 0.164800 -vn -0.378575 -0.655726 0.653226 -v 0.032000 -0.127433 0.164800 -vn -0.727973 0.095837 0.678874 -v 0.031750 -0.145000 0.164800 -vn -0.577348 -0.577354 0.577348 -v 0.031750 -0.145500 0.164800 -vn -0.088113 -0.669358 0.737697 -v 0.032100 -0.145500 0.164800 -vn 0.727974 -0.095842 0.678873 -v 0.025750 -0.127000 0.164800 -vn 0.577348 0.577354 0.577348 -v 0.025750 -0.126500 0.164800 -vn 0.088114 0.669357 0.737697 -v 0.025400 -0.126500 0.164800 -vn 0.552298 0.318870 0.770253 -v 0.025227 -0.126400 0.164800 -vn 0.318867 -0.552296 0.770255 -v 0.023000 -0.127567 0.164800 -vn 0.088131 -0.669346 0.737705 -v 0.023250 -0.127500 0.164800 -vn 0.655720 -0.378579 0.653230 -v 0.025683 -0.127250 0.164800 -vn -0.577349 -0.577352 0.577349 -v 0.019250 -0.133000 0.164800 -vn 0.095851 -0.727973 0.678872 -v 0.019750 -0.133000 0.164800 -vn -0.669355 -0.088118 0.737699 -v 0.019250 -0.132650 0.164800 -vn 0.378576 -0.655717 0.653235 -v 0.020000 -0.132933 0.164800 -vn -0.552295 -0.318853 0.770261 -v 0.019223 -0.132550 0.164800 -vn 0.318863 0.552276 0.770271 -v 0.025300 -0.126473 0.164800 -vn 0.095830 -0.727970 0.678878 -v 0.025250 -0.127500 0.164800 -vn 0.378577 -0.655726 0.653225 -v 0.025500 -0.127433 0.164800 -vn -0.095852 -0.727975 0.678870 -v 0.037750 -0.133000 0.164800 -vn 0.577354 -0.577348 0.577348 -v 0.038250 -0.133000 0.164800 -vn 0.669352 -0.088124 0.737701 -v 0.038250 -0.132650 0.164800 -vn -0.577352 0.577349 0.577349 -v 0.031750 -0.126500 0.164800 -vn -0.088112 0.669358 0.737697 -v 0.032100 -0.126500 0.164800 -vn -0.318862 0.552273 0.770273 -v 0.032200 -0.126473 0.164800 -vn -0.552300 0.318869 0.770251 -v 0.032273 -0.126400 0.164800 -vn 0.318868 0.552295 0.770255 -v 0.023000 -0.144433 0.164800 -vn 0.552279 0.318866 0.770268 -v 0.022817 -0.144250 0.164800 -vn -0.095837 -0.727972 0.678876 -v 0.020250 -0.146000 0.164800 -vn 0.727973 0.095840 0.678874 -v 0.038750 -0.127500 0.164800 -vn -0.318877 -0.552283 0.770260 -v 0.037000 -0.130067 0.164800 -vn -0.552290 -0.318863 0.770261 -v 0.037183 -0.130250 0.164800 -vn -0.378576 -0.655716 0.653235 -v 0.037500 -0.132933 0.164800 -vn -0.655722 -0.378589 0.653222 -v 0.037317 -0.132750 0.164800 -vn -0.727971 -0.095831 0.678878 -v 0.037250 -0.132500 0.164800 -vn -0.577350 -0.577350 0.577350 -v 0.018750 -0.132450 0.164800 -vn -0.088114 -0.669357 0.737697 -v 0.019050 -0.132450 0.164800 -vn -0.727972 0.095840 0.678875 -v 0.018750 -0.127500 0.164800 -vn -0.318860 -0.552280 0.770270 -v 0.019150 -0.132477 0.164800 -vn 0.552297 -0.318871 0.770253 -v 0.025227 -0.145600 0.164800 -vn 0.669345 -0.088136 0.737705 -v 0.025200 -0.145700 0.164800 -vn 0.577350 -0.577350 0.577350 -v 0.025200 -0.146000 0.164800 -vn -0.669343 -0.088135 0.737707 -v 0.032300 -0.145700 0.164800 -vn -0.577350 -0.577350 0.577350 -v 0.032300 -0.146000 0.164800 -vn 0.095837 -0.727972 0.678876 -v 0.037250 -0.146000 0.164800 -vn 0.655720 -0.378590 0.653223 -v 0.020183 -0.132750 0.164800 -vn 0.727972 -0.095834 0.678876 -v 0.020250 -0.132500 0.164800 -vn 0.669352 -0.088124 0.737701 -v 0.020250 -0.130500 0.164800 -vn 0.095851 0.727975 0.678870 -v 0.019750 -0.139000 0.164800 -vn -0.577354 0.577348 0.577348 -v 0.019250 -0.139000 0.164800 -vn -0.669354 0.088118 0.737699 -v 0.019250 -0.139350 0.164800 -vn -0.669350 -0.088124 0.737702 -v 0.037250 -0.130500 0.164800 -vn 0.552294 -0.318861 0.770259 -v 0.038277 -0.132550 0.164800 -vn 0.318861 -0.552280 0.770269 -v 0.038350 -0.132477 0.164800 -vn 0.088115 -0.669354 0.737700 -v 0.038450 -0.132450 0.164800 -vn 0.577350 -0.577350 0.577350 -v 0.038750 -0.132450 0.164800 -vn -0.095837 0.727970 0.678878 -v 0.020250 -0.126000 0.164800 -vn 0.669343 0.088135 0.737707 -v 0.025200 -0.126300 0.164800 -vn 0.577350 0.577350 0.577350 -v 0.025200 -0.126000 0.164800 -vn 0.088132 0.669347 0.737704 -v 0.023250 -0.144500 0.164800 -vn 0.095830 0.727971 0.678877 -v 0.025250 -0.144500 0.164800 -vn 0.577352 -0.577349 0.577349 -v 0.025750 -0.145500 0.164800 -vn 0.727972 0.095841 0.678875 -v 0.025750 -0.145000 0.164800 -vn 0.088113 -0.669357 0.737697 -v 0.025400 -0.145500 0.164800 -vn 0.655721 0.378578 0.653230 -v 0.025683 -0.144750 0.164800 -vn 0.727971 0.095833 0.678877 -v 0.020250 -0.139500 0.164800 -vn 0.655721 0.378589 0.653223 -v 0.020183 -0.139250 0.164800 -vn 0.378577 0.655716 0.653234 -v 0.020000 -0.139067 0.164800 -vn -0.552301 -0.318868 0.770251 -v 0.032273 -0.145600 0.164800 -vn 0.318861 -0.552277 0.770271 -v 0.025300 -0.145527 0.164800 -vn 0.378578 0.655726 0.653225 -v 0.025500 -0.144567 0.164800 -vn -0.088132 -0.669347 0.737704 -v 0.034250 -0.127500 0.164800 -vn -0.318868 -0.552295 0.770255 -v 0.034500 -0.127567 0.164800 -vn 0.095837 0.727969 0.678878 -v 0.037250 -0.126000 0.164800 -vn -0.727972 0.095831 0.678877 -v 0.037250 -0.139500 0.164800 -vn -0.669354 0.088119 0.737699 -v 0.037250 -0.141500 0.164800 -vn 0.318862 0.552280 0.770269 -v 0.038350 -0.139523 0.164800 -vn 0.727972 -0.095838 0.678875 -v 0.038750 -0.144500 0.164800 -vn 0.088116 0.669356 0.737698 -v 0.038450 -0.139550 0.164800 -vn 0.577350 0.577350 0.577350 -v 0.038750 -0.139550 0.164800 -vn -0.727972 -0.095838 0.678876 -v 0.018750 -0.144500 0.164800 -vn 0.318868 0.552295 0.770255 -v 0.020500 -0.141933 0.164800 -vn 0.552279 0.318866 0.770268 -v 0.020317 -0.141750 0.164800 -vn 0.577349 0.577352 0.577349 -v 0.038250 -0.139000 0.164800 -vn -0.095852 0.727973 0.678872 -v 0.037750 -0.139000 0.164800 -vn 0.669352 0.088123 0.737701 -v 0.038250 -0.139350 0.164800 -vn -0.378575 0.655717 0.653235 -v 0.037500 -0.139067 0.164800 -vn -0.669354 0.088119 0.737699 -v 0.034750 -0.144000 0.164800 -vn -0.552278 0.318867 0.770268 -v 0.034683 -0.144250 0.164800 -vn 0.251475 0.607118 0.753769 -v 0.035826 -0.141962 0.164800 -vn 0.552295 0.318859 0.770259 -v 0.038277 -0.139450 0.164800 -vn -0.655721 0.378590 0.653222 -v 0.037317 -0.139250 0.164800 -vn -0.378578 -0.655724 0.653227 -v 0.019500 -0.145799 0.164800 -vn 0.088132 0.669347 0.737704 -v 0.020750 -0.142000 0.164800 -vn 0.669353 0.088119 0.737700 -v 0.020250 -0.141500 0.164800 -vn -0.552295 0.318855 0.770261 -v 0.019223 -0.139450 0.164800 -vn -0.318859 0.552281 0.770270 -v 0.019150 -0.139523 0.164800 -vn -0.088114 0.669355 0.737699 -v 0.019050 -0.139550 0.164800 -vn -0.577350 0.577350 0.577350 -v 0.018750 -0.139550 0.164800 -vn -0.095831 -0.727972 0.678877 -v 0.032250 -0.127500 0.164800 -vn -0.669345 0.088136 0.737706 -v 0.032300 -0.126300 0.164800 -vn -0.577350 0.577350 0.577350 -v 0.032300 -0.126000 0.164800 -vn -0.088131 0.669346 0.737705 -v 0.036750 -0.142000 0.164800 -vn 0.067001 0.680319 0.729847 -v 0.036018 -0.142000 0.164800 -vn -0.680319 -0.067006 0.729847 -v 0.034750 -0.143268 0.164800 -vn 0.639164 0.077609 0.765145 -v 0.026020 -0.136331 0.164800 -vn 0.602017 -0.228315 0.765145 -v 0.026179 -0.135025 0.164800 -vn -0.607124 -0.251476 0.753764 -v 0.024212 -0.132576 0.164800 -vn -0.528438 -0.433673 0.729850 -v 0.024104 -0.132414 0.164800 -vn 0.433682 0.528437 0.729845 -v 0.035664 -0.141854 0.164800 -vn 0.528439 0.433670 0.729851 -v 0.033396 -0.139586 0.164800 -vn -0.529886 0.365752 0.765144 -v 0.031013 -0.137562 0.164800 -vn 0.607126 0.251474 0.753763 -v 0.033288 -0.139424 0.164800 -vn -0.639163 0.077609 0.765146 -v 0.031480 -0.136331 0.164800 -vn 0.680319 0.067006 0.729847 -v 0.033250 -0.139232 0.164800 -vn -0.602017 -0.228316 0.765146 -v 0.031321 -0.135025 0.164800 -vn 0.680317 -0.067006 0.729849 -v 0.033250 -0.132768 0.164800 -vn -0.426953 -0.481934 0.765147 -v 0.030574 -0.133942 0.164800 -vn -0.552278 0.318867 0.770268 -v 0.037183 -0.141750 0.164800 -vn -0.318867 0.552296 0.770255 -v 0.037000 -0.141933 0.164800 -vn 0.655722 -0.378583 0.653226 -v 0.038549 -0.145250 0.164800 -vn 0.378577 -0.655724 0.653227 -v 0.038000 -0.145799 0.164800 -vn -0.655722 0.378579 0.653227 -v 0.031817 -0.144750 0.164800 -vn -0.378574 0.655727 0.653226 -v 0.032000 -0.144567 0.164800 -vn -0.095831 0.727971 0.678878 -v 0.032250 -0.144500 0.164800 -vn -0.318864 -0.552272 0.770273 -v 0.032200 -0.145527 0.164800 -vn -0.088131 0.669346 0.737705 -v 0.034250 -0.144500 0.164800 -vn -0.318867 0.552296 0.770255 -v 0.034500 -0.144433 0.164800 -vn 0.680319 0.067006 0.729847 -v 0.022750 -0.128732 0.164800 -vn 0.669354 -0.088119 0.737699 -v 0.022750 -0.128000 0.164800 -vn 0.552278 -0.318867 0.770268 -v 0.022817 -0.127750 0.164800 -vn -0.552279 -0.318871 0.770266 -v 0.034683 -0.127750 0.164800 -vn -0.669351 -0.088123 0.737702 -v 0.034750 -0.128000 0.164800 -vn -0.680317 0.067006 0.729849 -v 0.034750 -0.128732 0.164800 -vn 0.251477 -0.607118 0.753769 -v 0.035826 -0.130038 0.164800 -vn 0.067001 -0.680321 0.729845 -v 0.036018 -0.130000 0.164800 -vn -0.088132 -0.669347 0.737704 -v 0.036750 -0.130000 0.164800 -vn 0.378582 0.655722 0.653226 -v 0.038000 -0.126201 0.164800 -vn -0.251477 -0.607117 0.753770 -v 0.021674 -0.130038 0.164800 -vn -0.067001 -0.680319 0.729847 -v 0.021482 -0.130000 0.164800 -vn 0.088131 -0.669346 0.737705 -v 0.020750 -0.130000 0.164800 -vn -0.000000 0.643858 0.765145 -v 0.028750 -0.138750 0.164800 -vn -0.067025 -0.680307 0.729856 -v 0.031982 -0.140500 0.164800 -vn -0.299217 0.570106 0.765146 -v 0.030028 -0.138435 0.164800 -vn -0.251489 -0.607132 0.753753 -v 0.032174 -0.140538 0.164800 -vn -0.433665 -0.528443 0.729852 -v 0.032336 -0.140646 0.164800 -vn -0.528433 -0.433690 0.729844 -v 0.034604 -0.142914 0.164800 -vn -0.607111 -0.251489 0.753770 -v 0.034712 -0.143076 0.164800 -vn 0.669353 0.088119 0.737700 -v 0.022750 -0.144000 0.164800 -vn -0.251479 0.607117 0.753769 -v 0.021674 -0.141962 0.164800 -vn 0.680317 -0.067006 0.729849 -v 0.022750 -0.143268 0.164800 -vn -0.067001 0.680321 0.729845 -v 0.021482 -0.142000 0.164800 -vn -0.680319 -0.067006 0.729847 -v 0.024250 -0.132768 0.164800 -vn -0.680317 0.067006 0.729849 -v 0.024250 -0.139232 0.164800 -vn 0.529886 0.365752 0.765145 -v 0.026487 -0.137562 0.164800 -vn -0.607124 0.251475 0.753764 -v 0.024212 -0.139424 0.164800 -vn -0.528440 0.433674 0.729848 -v 0.024104 -0.139586 0.164800 -vn -0.433684 -0.528437 0.729844 -v 0.021836 -0.130146 0.164800 -vn 0.426954 -0.481934 0.765147 -v 0.026926 -0.133942 0.164800 -vn -0.607122 0.251477 0.753765 -v 0.034712 -0.128924 0.164800 -vn -0.528439 0.433678 0.729847 -v 0.034604 -0.129086 0.164800 -vn -0.433663 0.528442 0.729853 -v 0.032336 -0.131354 0.164800 -vn -0.251491 0.607132 0.753753 -v 0.032174 -0.131462 0.164800 -vn 0.607126 -0.251473 0.753763 -v 0.033288 -0.132576 0.164800 -vn 0.528441 -0.433672 0.729849 -v 0.033396 -0.132414 0.164800 -vn 0.433681 -0.528435 0.729847 -v 0.035664 -0.130146 0.164800 -vn 0.655722 0.378579 0.653228 -v 0.038549 -0.126750 0.164800 -vn 0.607113 -0.251486 0.753769 -v 0.022788 -0.143076 0.164800 -vn 0.528436 -0.433688 0.729842 -v 0.022896 -0.142914 0.164800 -vn -0.433683 0.528435 0.729846 -v 0.021836 -0.141854 0.164800 -vn 0.433662 -0.528441 0.729854 -v 0.025164 -0.140646 0.164800 -vn -0.655722 -0.378582 0.653226 -v 0.018951 -0.145250 0.164800 -vn 0.552290 -0.318864 0.770261 -v 0.020317 -0.130250 0.164800 -vn 0.318876 -0.552284 0.770260 -v 0.020500 -0.130067 0.164800 -vn -0.655722 0.378579 0.653228 -v 0.018951 -0.126750 0.164800 -vn -0.378583 0.655722 0.653225 -v 0.019500 -0.126201 0.164800 -vn 0.251488 0.607134 0.753752 -v 0.025326 -0.131462 0.164800 -vn 0.067025 0.680307 0.729856 -v 0.025518 -0.131500 0.164800 -vn 0.196775 -0.631470 0.750017 -v 0.028092 -0.133330 0.164800 -vn -0.067026 0.680309 0.729854 -v 0.031982 -0.131500 0.164800 -vn 0.000000 -0.677773 0.735272 -v 0.028750 -0.133250 0.164800 -vn -0.196775 -0.631471 0.750016 -v 0.029408 -0.133330 0.164800 -vn 0.433662 0.528444 0.729852 -v 0.025164 -0.131354 0.164800 -vn 0.528438 0.433674 0.729849 -v 0.022896 -0.129086 0.164800 -vn 0.607124 0.251476 0.753764 -v 0.022788 -0.128924 0.164800 -vn 0.299216 0.570106 0.765146 -v 0.027472 -0.138435 0.164800 -vn 0.251489 -0.607133 0.753752 -v 0.025326 -0.140538 0.164800 -vn 0.067026 -0.680309 0.729854 -v 0.025518 -0.140500 0.164800 -vn 0.655721 -0.378578 -0.653230 -v 0.025683 -0.127250 0.094800 -vn 0.378578 -0.655726 -0.653225 -v 0.025500 -0.127433 0.094800 -vn 0.095830 -0.727972 -0.678877 -v 0.025250 -0.127500 0.094800 -vn -0.727973 -0.095837 -0.678874 -v 0.031750 -0.127000 0.094800 -vn -0.577348 0.577354 -0.577348 -v 0.031750 -0.126500 0.094800 -vn -0.088113 0.669358 -0.737697 -v 0.032100 -0.126500 0.094800 -vn -0.552301 0.318868 -0.770251 -v 0.032273 -0.126400 0.094800 -vn -0.318867 -0.552296 -0.770255 -v 0.034500 -0.127567 0.094800 -vn -0.088131 -0.669346 -0.737705 -v 0.034250 -0.127500 0.094800 -vn -0.655722 -0.378579 -0.653227 -v 0.031817 -0.127250 0.094800 -vn 0.095852 -0.727975 -0.678870 -v 0.019750 -0.133000 0.094800 -vn -0.577354 -0.577348 -0.577348 -v 0.019250 -0.133000 0.094800 -vn -0.669355 -0.088118 -0.737699 -v 0.019250 -0.132650 0.094800 -vn 0.577349 -0.577352 -0.577349 -v 0.038250 -0.133000 0.094800 -vn -0.095852 -0.727973 -0.678872 -v 0.037750 -0.133000 0.094800 -vn 0.669352 -0.088123 -0.737701 -v 0.038250 -0.132650 0.094800 -vn -0.378575 -0.655717 -0.653235 -v 0.037500 -0.132933 0.094800 -vn -0.318864 0.552272 -0.770273 -v 0.032200 -0.126473 0.094800 -vn -0.095831 -0.727971 -0.678878 -v 0.032250 -0.127500 0.094800 -vn -0.378574 -0.655727 -0.653226 -v 0.032000 -0.127433 0.094800 -vn 0.088113 0.669357 -0.737697 -v 0.025400 -0.126500 0.094800 -vn 0.577352 0.577349 -0.577349 -v 0.025750 -0.126500 0.094800 -vn 0.727972 -0.095841 -0.678875 -v 0.025750 -0.127000 0.094800 -vn 0.378577 -0.655716 -0.653234 -v 0.020000 -0.132933 0.094800 -vn 0.655721 -0.378589 -0.653223 -v 0.020183 -0.132750 0.094800 -vn 0.727971 -0.095833 -0.678877 -v 0.020250 -0.132500 0.094800 -vn 0.669343 -0.088135 -0.737707 -v 0.025200 -0.145700 0.094800 -vn 0.577350 -0.577350 -0.577350 -v 0.025200 -0.146000 0.094800 -vn -0.095837 -0.727972 -0.678876 -v 0.020250 -0.146000 0.094800 -vn -0.727972 0.095840 -0.678875 -v 0.018750 -0.127500 0.094800 -vn 0.318877 -0.552283 -0.770260 -v 0.020500 -0.130067 0.094800 -vn 0.552290 -0.318863 -0.770261 -v 0.020317 -0.130250 0.094800 -vn -0.727971 0.095836 -0.678876 -v 0.031750 -0.145000 0.094800 -vn -0.655723 0.378578 -0.653227 -v 0.031817 -0.144750 0.094800 -vn -0.378575 0.655726 -0.653226 -v 0.032000 -0.144567 0.094800 -vn -0.655721 -0.378590 -0.653222 -v 0.037317 -0.132750 0.094800 -vn -0.727972 -0.095831 -0.678877 -v 0.037250 -0.132500 0.094800 -vn 0.552295 -0.318859 -0.770259 -v 0.038277 -0.132550 0.094800 -vn -0.669351 -0.088124 -0.737701 -v 0.037250 -0.130500 0.094800 -vn 0.318862 -0.552280 -0.770269 -v 0.038350 -0.132477 0.094800 -vn 0.727973 0.095840 -0.678874 -v 0.038750 -0.127500 0.094800 -vn 0.088116 -0.669356 -0.737698 -v 0.038450 -0.132450 0.094800 -vn 0.577351 -0.577350 -0.577350 -v 0.038750 -0.132450 0.094800 -vn 0.318868 -0.552295 -0.770255 -v 0.023000 -0.127567 0.094800 -vn 0.552279 -0.318866 -0.770268 -v 0.022817 -0.127750 0.094800 -vn -0.095837 0.727970 -0.678878 -v 0.020250 -0.126000 0.094800 -vn -0.577349 0.577352 -0.577349 -v 0.019250 -0.139000 0.094800 -vn 0.095851 0.727973 -0.678872 -v 0.019750 -0.139000 0.094800 -vn -0.669355 0.088118 -0.737699 -v 0.019250 -0.139350 0.094800 -vn 0.378576 0.655717 -0.653235 -v 0.020000 -0.139067 0.094800 -vn -0.552295 0.318853 -0.770261 -v 0.019223 -0.139450 0.094800 -vn 0.669351 -0.088124 -0.737702 -v 0.020250 -0.130500 0.094800 -vn -0.552294 -0.318854 -0.770262 -v 0.019223 -0.132550 0.094800 -vn -0.318859 -0.552281 -0.770270 -v 0.019150 -0.132477 0.094800 -vn -0.088114 -0.669355 -0.737699 -v 0.019050 -0.132450 0.094800 -vn -0.577350 -0.577350 -0.577350 -v 0.018750 -0.132450 0.094800 -vn 0.088132 -0.669347 -0.737704 -v 0.023250 -0.127500 0.094800 -vn 0.727974 0.095842 -0.678873 -v 0.025750 -0.145000 0.094800 -vn 0.577348 -0.577354 -0.577348 -v 0.025750 -0.145500 0.094800 -vn 0.088114 -0.669357 -0.737697 -v 0.025400 -0.145500 0.094800 -vn -0.095852 0.727975 -0.678870 -v 0.037750 -0.139000 0.094800 -vn 0.577354 0.577348 -0.577348 -v 0.038250 -0.139000 0.094800 -vn 0.669352 0.088124 -0.737701 -v 0.038250 -0.139350 0.094800 -vn 0.552298 -0.318870 -0.770253 -v 0.025227 -0.145600 0.094800 -vn 0.318861 0.552277 -0.770271 -v 0.025300 -0.126473 0.094800 -vn 0.552297 0.318871 -0.770253 -v 0.025227 -0.126400 0.094800 -vn 0.669345 0.088136 -0.737705 -v 0.025200 -0.126300 0.094800 -vn 0.577350 0.577350 -0.577350 -v 0.025200 -0.126000 0.094800 -vn -0.088132 0.669347 -0.737704 -v 0.034250 -0.144500 0.094800 -vn -0.318869 0.552295 -0.770255 -v 0.034500 -0.144433 0.094800 -vn 0.095837 -0.727973 -0.678875 -v 0.037250 -0.146000 0.094800 -vn -0.552279 0.318866 -0.770268 -v 0.034683 -0.144250 0.094800 -vn -0.727971 0.095831 -0.678878 -v 0.037250 -0.139500 0.094800 -vn -0.655722 0.378589 -0.653222 -v 0.037317 -0.139250 0.094800 -vn -0.378576 0.655716 -0.653235 -v 0.037500 -0.139067 0.094800 -vn -0.577352 -0.577349 -0.577349 -v 0.031750 -0.145500 0.094800 -vn -0.088112 -0.669358 -0.737697 -v 0.032100 -0.145500 0.094800 -vn -0.318862 -0.552273 -0.770273 -v 0.032200 -0.145527 0.094800 -vn -0.552300 -0.318869 -0.770251 -v 0.032273 -0.145600 0.094800 -vn -0.095831 0.727972 -0.678877 -v 0.032250 -0.144500 0.094800 -vn -0.669345 -0.088136 -0.737706 -v 0.032300 -0.145700 0.094800 -vn -0.577350 -0.577350 -0.577350 -v 0.032300 -0.146000 0.094800 -vn -0.577350 0.577350 -0.577350 -v 0.018750 -0.139550 0.094800 -vn -0.088114 0.669357 -0.737697 -v 0.019050 -0.139550 0.094800 -vn -0.727972 -0.095838 -0.678875 -v 0.018750 -0.144500 0.094800 -vn -0.318860 0.552280 -0.770270 -v 0.019150 -0.139523 0.094800 -vn 0.655720 0.378590 -0.653223 -v 0.020183 -0.139250 0.094800 -vn 0.727972 0.095834 -0.678876 -v 0.020250 -0.139500 0.094800 -vn 0.669354 0.088119 -0.737699 -v 0.020250 -0.141500 0.094800 -vn 0.669354 0.088119 -0.737699 -v 0.022750 -0.144000 0.094800 -vn 0.552278 0.318867 -0.770268 -v 0.022817 -0.144250 0.094800 -vn -0.251477 0.607117 -0.753769 -v 0.021674 -0.141962 0.094800 -vn 0.095837 0.727969 -0.678879 -v 0.037250 -0.126000 0.094800 -vn -0.669343 0.088135 -0.737707 -v 0.032300 -0.126300 0.094800 -vn -0.577350 0.577350 -0.577350 -v 0.032300 -0.126000 0.094800 -vn -0.669353 0.088119 -0.737700 -v 0.037250 -0.141500 0.094800 -vn 0.552294 0.318861 -0.770259 -v 0.038277 -0.139450 0.094800 -vn -0.552279 0.318866 -0.770268 -v 0.037183 -0.141750 0.094800 -vn 0.318861 0.552280 -0.770269 -v 0.038350 -0.139523 0.094800 -vn 0.727972 -0.095838 -0.678875 -v 0.038750 -0.144500 0.094800 -vn 0.088115 0.669354 -0.737700 -v 0.038450 -0.139550 0.094800 -vn 0.577350 0.577350 -0.577350 -v 0.038750 -0.139550 0.094800 -vn 0.528441 0.433672 -0.729849 -v 0.033396 -0.139586 0.094800 -vn 0.433681 0.528435 -0.729847 -v 0.035664 -0.141854 0.094800 -vn -0.529886 0.365753 -0.765144 -v 0.031013 -0.137562 0.094800 -vn -0.639163 0.077609 -0.765145 -v 0.031480 -0.136331 0.094800 -vn -0.602017 -0.228316 -0.765145 -v 0.031321 -0.135025 0.094800 -vn 0.607126 -0.251474 -0.753763 -v 0.033288 -0.132576 0.094800 -vn 0.528439 -0.433670 -0.729851 -v 0.033396 -0.132414 0.094800 -vn 0.088131 0.669346 -0.737705 -v 0.020750 -0.142000 0.094800 -vn -0.067001 0.680319 -0.729847 -v 0.021482 -0.142000 0.094800 -vn 0.680319 -0.067006 -0.729847 -v 0.022750 -0.143268 0.094800 -vn -0.669353 0.088119 -0.737700 -v 0.034750 -0.144000 0.094800 -vn 0.251477 0.607117 -0.753769 -v 0.035826 -0.141962 0.094800 -vn -0.680317 -0.067006 -0.729849 -v 0.034750 -0.143268 0.094800 -vn 0.067001 0.680321 -0.729845 -v 0.036018 -0.142000 0.094800 -vn -0.088132 0.669347 -0.737704 -v 0.036750 -0.142000 0.094800 -vn 0.378577 -0.655724 -0.653227 -v 0.038000 -0.145799 0.094800 -vn 0.655722 -0.378583 -0.653226 -v 0.038549 -0.145250 0.094800 -vn -0.318869 0.552295 -0.770255 -v 0.037000 -0.141933 0.094800 -vn -0.433683 -0.528435 -0.729846 -v 0.021836 -0.130146 0.094800 -vn -0.251478 -0.607116 -0.753770 -v 0.021674 -0.130038 0.094800 -vn 0.552278 0.318867 -0.770268 -v 0.020317 -0.141750 0.094800 -vn 0.318867 0.552296 -0.770255 -v 0.020500 -0.141933 0.094800 -vn -0.655722 -0.378582 -0.653226 -v 0.018951 -0.145250 0.094800 -vn -0.378578 -0.655724 -0.653227 -v 0.019500 -0.145799 0.094800 -vn 0.655720 0.378579 -0.653230 -v 0.025683 -0.144750 0.094800 -vn 0.378577 0.655726 -0.653225 -v 0.025500 -0.144567 0.094800 -vn 0.095830 0.727970 -0.678878 -v 0.025250 -0.144500 0.094800 -vn 0.318863 -0.552276 -0.770271 -v 0.025300 -0.145527 0.094800 -vn 0.088131 0.669346 -0.737705 -v 0.023250 -0.144500 0.094800 -vn 0.318867 0.552296 -0.770255 -v 0.023000 -0.144433 0.094800 -vn -0.680319 0.067006 -0.729847 -v 0.034750 -0.128732 0.094800 -vn -0.669352 -0.088124 -0.737701 -v 0.034750 -0.128000 0.094800 -vn -0.552278 -0.318872 -0.770266 -v 0.034683 -0.127750 0.094800 -vn -0.299217 0.570106 -0.765146 -v 0.030028 -0.138435 0.094800 -vn -0.433664 -0.528441 -0.729854 -v 0.032336 -0.140646 0.094800 -vn -0.528435 -0.433691 -0.729842 -v 0.034604 -0.142914 0.094800 -vn -0.607111 -0.251488 -0.753770 -v 0.034712 -0.143076 0.094800 -vn 0.680319 -0.067006 -0.729847 -v 0.033250 -0.132768 0.094800 -vn 0.680317 0.067006 -0.729849 -v 0.033250 -0.139232 0.094800 -vn 0.607127 0.251473 -0.753763 -v 0.033288 -0.139424 0.094800 -vn 0.251476 -0.607118 -0.753769 -v 0.035826 -0.130038 0.094800 -vn 0.067001 -0.680319 -0.729847 -v 0.036018 -0.130000 0.094800 -vn -0.088131 -0.669346 -0.737705 -v 0.036750 -0.130000 0.094800 -vn -0.528440 -0.433674 -0.729848 -v 0.024104 -0.132414 0.094800 -vn -0.067001 -0.680321 -0.729845 -v 0.021482 -0.130000 0.094800 -vn 0.088132 -0.669347 -0.737704 -v 0.020750 -0.130000 0.094800 -vn -0.378583 0.655722 -0.653225 -v 0.019500 -0.126201 0.094800 -vn -0.433684 0.528437 -0.729844 -v 0.021836 -0.141854 0.094800 -vn -0.528438 0.433673 -0.729850 -v 0.024104 -0.139586 0.094800 -vn 0.529886 0.365752 -0.765145 -v 0.026487 -0.137562 0.094800 -vn -0.607124 0.251476 -0.753764 -v 0.024212 -0.139424 0.094800 -vn 0.639163 0.077608 -0.765145 -v 0.026020 -0.136331 0.094800 -vn -0.680319 0.067006 -0.729847 -v 0.024250 -0.139232 0.094800 -vn 0.602017 -0.228315 -0.765146 -v 0.026179 -0.135025 0.094800 -vn -0.680317 -0.067006 -0.729849 -v 0.024250 -0.132768 0.094800 -vn 0.426954 -0.481934 -0.765147 -v 0.026926 -0.133942 0.094800 -vn -0.607124 -0.251475 -0.753764 -v 0.024212 -0.132576 0.094800 -vn -0.251491 -0.607132 -0.753753 -v 0.032174 -0.140538 0.094800 -vn -0.067026 -0.680309 -0.729854 -v 0.031982 -0.140500 0.094800 -vn 0.000000 0.643858 -0.765145 -v 0.028750 -0.138750 0.094800 -vn 0.067025 -0.680307 -0.729856 -v 0.025518 -0.140500 0.094800 -vn 0.299217 0.570106 -0.765146 -v 0.027472 -0.138435 0.094800 -vn 0.251488 -0.607134 -0.753752 -v 0.025326 -0.140538 0.094800 -vn 0.433663 -0.528443 -0.729852 -v 0.025164 -0.140646 0.094800 -vn 0.528434 -0.433687 -0.729845 -v 0.022896 -0.142914 0.094800 -vn 0.607113 -0.251487 -0.753769 -v 0.022788 -0.143076 0.094800 -vn 0.433682 -0.528437 -0.729845 -v 0.035664 -0.130146 0.094800 -vn -0.426953 -0.481934 -0.765148 -v 0.030574 -0.133942 0.094800 -vn 0.669353 -0.088119 -0.737700 -v 0.022750 -0.128000 0.094800 -vn 0.680317 0.067006 -0.729849 -v 0.022750 -0.128732 0.094800 -vn 0.607124 0.251475 -0.753764 -v 0.022788 -0.128924 0.094800 -vn -0.552290 -0.318864 -0.770261 -v 0.037183 -0.130250 0.094800 -vn -0.318876 -0.552284 -0.770260 -v 0.037000 -0.130067 0.094800 -vn 0.655722 0.378579 -0.653228 -v 0.038549 -0.126750 0.094800 -vn 0.378582 0.655722 -0.653226 -v 0.038000 -0.126201 0.094800 -vn -0.655722 0.378579 -0.653228 -v 0.018951 -0.126750 0.094800 -vn -0.067025 0.680307 -0.729856 -v 0.031982 -0.131500 0.094800 -vn -0.251489 0.607132 -0.753753 -v 0.032174 -0.131462 0.094800 -vn -0.433664 0.528444 -0.729851 -v 0.032336 -0.131354 0.094800 -vn -0.528437 0.433676 -0.729849 -v 0.034604 -0.129086 0.094800 -vn -0.607122 0.251478 -0.753765 -v 0.034712 -0.128924 0.094800 -vn 0.528440 0.433675 -0.729847 -v 0.022896 -0.129086 0.094800 -vn 0.433661 0.528442 -0.729854 -v 0.025164 -0.131354 0.094800 -vn 0.251489 0.607133 -0.753752 -v 0.025326 -0.131462 0.094800 -vn 0.196775 -0.631470 -0.750017 -v 0.028092 -0.133330 0.094800 -vn 0.067026 0.680309 -0.729854 -v 0.025518 -0.131500 0.094800 -vn -0.000000 -0.677773 -0.735272 -v 0.028750 -0.133250 0.094800 -vn -0.196775 -0.631470 -0.750017 -v 0.029408 -0.133330 0.094800 -vn 0.727971 -0.095840 -0.678876 -v 0.000750 -0.091720 0.166800 -vn 0.655721 -0.378577 -0.653230 -v 0.000683 -0.091970 0.166800 -vn 0.378585 -0.655718 -0.653228 -v 0.000500 -0.092153 0.166800 -vn 0.727973 0.095841 -0.678874 -v 0.000750 -0.109720 0.166800 -vn 0.577350 -0.577352 -0.577350 -v 0.000750 -0.110220 0.166800 -vn 0.088114 -0.669357 -0.737697 -v 0.000400 -0.110220 0.166800 -vn 0.577350 -0.577351 -0.577350 -v 0.013250 -0.097720 0.166800 -vn -0.095830 -0.727970 -0.678879 -v 0.012750 -0.097720 0.166800 -vn 0.669354 -0.088121 -0.737700 -v 0.013250 -0.097370 0.166800 -vn -0.378575 -0.655726 -0.653226 -v 0.012500 -0.097653 0.166800 -vn 0.552281 -0.318868 -0.770266 -v 0.013277 -0.097270 0.166800 -vn -0.378584 -0.655719 -0.653228 -v 0.007000 -0.092153 0.166800 -vn -0.655720 -0.378579 -0.653230 -v 0.006817 -0.091970 0.166800 -vn -0.088114 0.669357 -0.737697 -v 0.007100 -0.091220 0.166800 -vn -0.727973 -0.095841 -0.678874 -v 0.006750 -0.091720 0.166800 -vn -0.577350 0.577352 -0.577350 -v 0.006750 -0.091220 0.166800 -vn 0.095830 -0.727972 -0.678877 -v -0.005250 -0.097720 0.166800 -vn -0.577352 -0.577350 -0.577350 -v -0.005750 -0.097720 0.166800 -vn -0.669353 -0.088121 -0.737700 -v -0.005750 -0.097370 0.166800 -vn -0.669348 0.088127 -0.737704 -v 0.007300 -0.091020 0.166800 -vn -0.577350 0.577350 -0.577350 -v 0.007300 -0.090720 0.166800 -vn 0.095841 0.727974 -0.678873 -v 0.012250 -0.090720 0.166800 -vn 0.577351 0.577350 -0.577350 -v 0.000750 -0.091220 0.166800 -vn 0.088114 0.669357 -0.737697 -v 0.000400 -0.091220 0.166800 -vn 0.318861 0.552281 -0.770269 -v 0.000300 -0.091193 0.166800 -vn 0.552296 0.318863 -0.770257 -v 0.000227 -0.091120 0.166800 -vn -0.318863 0.552289 -0.770262 -v 0.009500 -0.109153 0.166800 -vn -0.552284 0.318863 -0.770265 -v 0.009683 -0.108970 0.166800 -vn 0.095841 -0.727973 -0.678874 -v 0.012250 -0.110720 0.166800 -vn -0.727973 0.095840 -0.678874 -v -0.006250 -0.092220 0.166800 -vn 0.318867 -0.552284 -0.770264 -v -0.004500 -0.094787 0.166800 -vn 0.552290 -0.318861 -0.770262 -v -0.004683 -0.094970 0.166800 -vn 0.378577 -0.655725 -0.653226 -v -0.005000 -0.097653 0.166800 -vn 0.655721 -0.378578 -0.653230 -v -0.004817 -0.097470 0.166800 -vn 0.727971 -0.095840 -0.678876 -v -0.004750 -0.097220 0.166800 -vn 0.577352 -0.577347 -0.577352 -v 0.013750 -0.097170 0.166800 -vn 0.088114 -0.669357 -0.737697 -v 0.013450 -0.097170 0.166800 -vn 0.727973 0.095840 -0.678874 -v 0.013750 -0.092220 0.166800 -vn 0.318850 -0.552296 -0.770262 -v 0.013350 -0.097197 0.166800 -vn -0.552296 -0.318864 -0.770256 -v 0.007273 -0.110320 0.166800 -vn -0.669350 -0.088127 -0.737702 -v 0.007300 -0.110420 0.166800 -vn -0.577347 -0.577352 -0.577352 -v 0.007300 -0.110720 0.166800 -vn 0.669348 -0.088126 -0.737704 -v 0.000200 -0.110420 0.166800 -vn 0.577350 -0.577350 -0.577350 -v 0.000200 -0.110720 0.166800 -vn -0.095841 -0.727973 -0.678874 -v -0.004750 -0.110720 0.166800 -vn -0.655720 -0.378579 -0.653230 -v 0.012317 -0.097470 0.166800 -vn -0.727973 -0.095841 -0.678874 -v 0.012250 -0.097220 0.166800 -vn -0.669352 -0.088123 -0.737701 -v 0.012250 -0.095220 0.166800 -vn -0.095841 0.727973 -0.678874 -v 0.012750 -0.103720 0.166800 -vn 0.577352 0.577350 -0.577350 -v 0.013250 -0.103720 0.166800 -vn 0.669353 0.088121 -0.737700 -v 0.013250 -0.104070 0.166800 -vn 0.669351 -0.088122 -0.737702 -v -0.004750 -0.095220 0.166800 -vn -0.552280 -0.318868 -0.770266 -v -0.005777 -0.097270 0.166800 -vn -0.318850 -0.552296 -0.770262 -v -0.005850 -0.097197 0.166800 -vn -0.088114 -0.669355 -0.737699 -v -0.005950 -0.097170 0.166800 -vn -0.577350 -0.577350 -0.577350 -v -0.006250 -0.097170 0.166800 -vn -0.552297 0.318864 -0.770256 -v 0.007273 -0.091120 0.166800 -vn -0.088123 0.669352 -0.737701 -v 0.009250 -0.109220 0.166800 -vn -0.095841 0.727973 -0.678874 -v 0.007250 -0.109220 0.166800 -vn -0.577351 -0.577350 -0.577350 -v 0.006750 -0.110220 0.166800 -vn -0.727971 0.095840 -0.678876 -v 0.006750 -0.109720 0.166800 -vn -0.088114 -0.669357 -0.737697 -v 0.007100 -0.110220 0.166800 -vn -0.655721 0.378577 -0.653230 -v 0.006817 -0.109470 0.166800 -vn -0.727971 0.095837 -0.678877 -v 0.012250 -0.104220 0.166800 -vn -0.655721 0.378583 -0.653227 -v 0.012317 -0.103970 0.166800 -vn -0.378578 0.655721 -0.653230 -v 0.012500 -0.103787 0.166800 -vn 0.669353 0.088121 -0.737700 -v -0.002250 -0.108720 0.166800 -vn 0.552283 0.318864 -0.770265 -v -0.002183 -0.108970 0.166800 -vn -0.251477 0.607115 -0.753771 -v -0.003326 -0.106682 0.166800 -vn 0.552296 -0.318863 -0.770257 -v 0.000227 -0.110320 0.166800 -vn -0.318861 -0.552281 -0.770269 -v 0.007200 -0.110247 0.166800 -vn -0.378585 0.655718 -0.653228 -v 0.007000 -0.109287 0.166800 -vn -0.378583 0.655721 -0.653226 -v -0.005500 -0.090921 0.166800 -vn -0.095841 0.727973 -0.678874 -v -0.004750 -0.090720 0.166800 -vn 0.088123 -0.669352 -0.737701 -v -0.004250 -0.094720 0.166800 -vn 0.318865 -0.552291 -0.770260 -v 0.002375 -0.098338 0.166800 -vn 0.528438 0.433675 -0.729849 -v -0.002104 -0.093806 0.166800 -vn 0.433672 0.528438 -0.729851 -v 0.000164 -0.096074 0.166800 -vn 0.088123 -0.669352 -0.737701 -v -0.001750 -0.092220 0.166800 -vn 0.318863 -0.552290 -0.770261 -v -0.002000 -0.092287 0.166800 -vn 0.552284 -0.318863 -0.770265 -v -0.002183 -0.092470 0.166800 -vn -0.528436 -0.433682 -0.729846 -v 0.009604 -0.107634 0.166800 -vn -0.433673 -0.528437 -0.729851 -v 0.007336 -0.105366 0.166800 -vn -0.318864 0.552290 -0.770260 -v 0.005125 -0.103102 0.166800 -vn -0.251483 -0.607123 -0.753763 -v 0.007174 -0.105258 0.166800 -vn 0.000000 0.637728 -0.770262 -v 0.003750 -0.103470 0.166800 -vn 0.095841 -0.727973 -0.678874 -v 0.000250 -0.092220 0.166800 -vn 0.669350 0.088126 -0.737702 -v 0.000200 -0.091020 0.166800 -vn 0.577347 0.577352 -0.577352 -v 0.000200 -0.090720 0.166800 -vn 0.378581 -0.655722 -0.653227 -v 0.013000 -0.110519 0.166800 -vn -0.088123 0.669352 -0.737701 -v 0.011750 -0.106720 0.166800 -vn -0.669353 -0.088121 -0.737700 -v 0.009750 -0.092720 0.166800 -vn -0.552284 -0.318864 -0.770265 -v 0.009683 -0.092470 0.166800 -vn 0.251477 -0.607114 -0.753771 -v 0.010826 -0.094758 0.166800 -vn 0.727973 -0.095839 -0.678875 -v 0.013750 -0.109220 0.166800 -vn -0.318863 0.552289 -0.770262 -v 0.012000 -0.106653 0.166800 -vn -0.552284 0.318863 -0.770265 -v 0.012183 -0.106470 0.166800 -vn -0.552288 -0.318864 -0.770263 -v 0.006132 -0.099345 0.166800 -vn 0.433684 -0.528435 -0.729846 -v 0.010664 -0.094866 0.166800 -vn 0.528438 -0.433675 -0.729849 -v 0.008396 -0.097134 0.166800 -vn -0.251478 -0.607115 -0.753771 -v -0.003326 -0.094758 0.166800 -vn 0.669352 -0.088120 -0.737701 -v -0.002250 -0.092720 0.166800 -vn 0.727973 0.095838 -0.678875 -v -0.004750 -0.104220 0.166800 -vn 0.669353 0.088121 -0.737700 -v -0.004750 -0.106220 0.166800 -vn -0.318875 0.552294 -0.770253 -v -0.005850 -0.104243 0.166800 -vn -0.727972 -0.095839 -0.678875 -v -0.006250 -0.109220 0.166800 -vn -0.088136 0.669345 -0.737706 -v -0.005950 -0.104270 0.166800 -vn -0.577352 0.577347 -0.577352 -v -0.006250 -0.104270 0.166800 -vn -0.433684 0.528435 -0.729846 -v -0.003164 -0.106574 0.166800 -vn -0.528437 0.433674 -0.729850 -v -0.000896 -0.104306 0.166800 -vn 0.552288 0.318865 -0.770262 -v 0.001368 -0.102095 0.166800 -vn -0.607121 0.251477 -0.753766 -v -0.000788 -0.104144 0.166800 -vn 0.637728 0.000000 -0.770261 -v 0.001000 -0.100720 0.166800 -vn -0.067001 -0.680320 -0.729847 -v -0.003518 -0.094720 0.166800 -vn -0.577350 0.577351 -0.577350 -v -0.005750 -0.103720 0.166800 -vn 0.095840 0.727971 -0.678876 -v -0.005250 -0.103720 0.166800 -vn -0.669353 0.088121 -0.737700 -v -0.005750 -0.104070 0.166800 -vn 0.378576 0.655722 -0.653230 -v -0.005000 -0.103787 0.166800 -vn 0.088122 0.669351 -0.737702 -v -0.004250 -0.106720 0.166800 -vn -0.067001 0.680319 -0.729847 -v -0.003518 -0.106720 0.166800 -vn 0.680318 -0.067004 -0.729848 -v -0.002250 -0.107988 0.166800 -vn 0.251478 0.607114 -0.753771 -v 0.010826 -0.106682 0.166800 -vn -0.669352 0.088120 -0.737701 -v 0.009750 -0.108720 0.166800 -vn -0.669352 0.088120 -0.737701 -v 0.012250 -0.106220 0.166800 -vn 0.552280 0.318868 -0.770266 -v 0.013277 -0.104170 0.166800 -vn 0.318875 0.552295 -0.770253 -v 0.013350 -0.104243 0.166800 -vn 0.088136 0.669343 -0.737708 -v 0.013450 -0.104270 0.166800 -vn 0.577351 0.577350 -0.577350 -v 0.013750 -0.104270 0.166800 -vn -0.088122 -0.669351 -0.737702 -v 0.011750 -0.094720 0.166800 -vn 0.067001 -0.680319 -0.729847 -v 0.011018 -0.094720 0.166800 -vn -0.680318 0.067004 -0.729848 -v 0.009750 -0.093452 0.166800 -vn -0.655722 0.378581 -0.653226 -v -0.006049 -0.091470 0.166800 -vn -0.552281 0.318868 -0.770266 -v -0.005777 -0.104170 0.166800 -vn 0.655720 0.378585 -0.653227 -v -0.004817 -0.103970 0.166800 -vn 0.552284 0.318864 -0.770265 -v -0.004683 -0.106470 0.166800 -vn 0.318861 0.552290 -0.770262 -v -0.004500 -0.106653 0.166800 -vn -0.655722 -0.378582 -0.653226 -v -0.006049 -0.109970 0.166800 -vn -0.378581 -0.655722 -0.653227 -v -0.005500 -0.110519 0.166800 -vn 0.655720 0.378579 -0.653230 -v 0.000683 -0.109470 0.166800 -vn 0.378584 0.655719 -0.653228 -v 0.000500 -0.109287 0.166800 -vn 0.095840 0.727971 -0.678876 -v 0.000250 -0.109220 0.166800 -vn 0.318861 -0.552280 -0.770269 -v 0.000300 -0.110247 0.166800 -vn 0.088122 0.669351 -0.737702 -v -0.001750 -0.109220 0.166800 -vn 0.318861 0.552291 -0.770261 -v -0.002000 -0.109153 0.166800 -vn 0.067001 0.680320 -0.729847 -v 0.011018 -0.106720 0.166800 -vn -0.095840 -0.727971 -0.678876 -v 0.007250 -0.092220 0.166800 -vn -0.318861 0.552280 -0.770269 -v 0.007200 -0.091193 0.166800 -vn -0.088122 -0.669351 -0.737702 -v 0.009250 -0.092220 0.166800 -vn -0.318861 -0.552290 -0.770262 -v 0.009500 -0.092287 0.166800 -vn -0.680317 0.067007 -0.729849 -v -0.000750 -0.103952 0.166800 -vn -0.680316 -0.067007 -0.729849 -v -0.000750 -0.097488 0.166800 -vn 0.552288 -0.318864 -0.770262 -v 0.001368 -0.099345 0.166800 -vn -0.607122 -0.251477 -0.753766 -v -0.000788 -0.097296 0.166800 -vn -0.528438 -0.433675 -0.729849 -v -0.000896 -0.097134 0.166800 -vn -0.433683 -0.528435 -0.729846 -v -0.003164 -0.094866 0.166800 -vn 0.607121 0.251474 -0.753767 -v -0.002212 -0.093644 0.166800 -vn 0.680318 0.067004 -0.729848 -v -0.002250 -0.093452 0.166800 -vn 0.655722 -0.378583 -0.653226 -v 0.013549 -0.109970 0.166800 -vn -0.552289 -0.318863 -0.770262 -v 0.012183 -0.094970 0.166800 -vn -0.318865 -0.552284 -0.770264 -v 0.012000 -0.094787 0.166800 -vn 0.655723 0.378580 -0.653226 -v 0.013549 -0.091470 0.166800 -vn 0.378584 0.655721 -0.653226 -v 0.013000 -0.090921 0.166800 -vn -0.067013 -0.680313 -0.729851 -v 0.006982 -0.105220 0.166800 -vn 0.067013 -0.680313 -0.729852 -v 0.000518 -0.105220 0.166800 -vn 0.318864 0.552289 -0.770261 -v 0.002375 -0.103102 0.166800 -vn 0.251483 -0.607123 -0.753763 -v 0.000326 -0.105258 0.166800 -vn 0.433673 -0.528438 -0.729850 -v 0.000164 -0.105366 0.166800 -vn 0.528435 -0.433682 -0.729847 -v -0.002104 -0.107634 0.166800 -vn 0.607116 -0.251480 -0.753769 -v -0.002212 -0.107796 0.166800 -vn 0.607121 -0.251477 -0.753766 -v 0.008288 -0.097296 0.166800 -vn 0.680317 -0.067007 -0.729849 -v 0.008250 -0.097488 0.166800 -vn -0.637728 0.000000 -0.770262 -v 0.006500 -0.100720 0.166800 -vn 0.680316 0.067007 -0.729849 -v 0.008250 -0.103952 0.166800 -vn -0.552288 0.318864 -0.770262 -v 0.006132 -0.102095 0.166800 -vn 0.607122 0.251477 -0.753766 -v 0.008288 -0.104144 0.166800 -vn 0.528438 0.433675 -0.729849 -v 0.008396 -0.104306 0.166800 -vn 0.433684 0.528434 -0.729846 -v 0.010664 -0.106574 0.166800 -vn -0.607116 -0.251479 -0.753769 -v 0.009712 -0.107796 0.166800 -vn -0.680318 -0.067004 -0.729848 -v 0.009750 -0.107988 0.166800 -vn 0.251483 0.607123 -0.753763 -v 0.000326 -0.096182 0.166800 -vn 0.067013 0.680313 -0.729851 -v 0.000518 -0.096220 0.166800 -vn -0.000000 -0.637728 -0.770262 -v 0.003750 -0.097970 0.166800 -vn -0.067013 0.680313 -0.729852 -v 0.006982 -0.096220 0.166800 -vn -0.318864 -0.552289 -0.770261 -v 0.005125 -0.098338 0.166800 -vn -0.251483 0.607123 -0.753763 -v 0.007174 -0.096182 0.166800 -vn -0.433673 0.528439 -0.729850 -v 0.007336 -0.096074 0.166800 -vn -0.528437 0.433675 -0.729850 -v 0.009604 -0.093806 0.166800 -vn -0.607121 0.251474 -0.753767 -v 0.009712 -0.093644 0.166800 -vn -0.655721 -0.378577 0.653230 -v 0.006817 -0.091970 0.246800 -vn -0.378585 -0.655718 0.653228 -v 0.007000 -0.092153 0.246800 -vn -0.095841 -0.727973 0.678874 -v 0.007250 -0.092220 0.246800 -vn -0.095830 -0.727972 0.678877 -v 0.012750 -0.097720 0.246800 -vn 0.577352 -0.577350 0.577350 -v 0.013250 -0.097720 0.246800 -vn 0.669353 -0.088121 0.737700 -v 0.013250 -0.097370 0.246800 -vn -0.577350 -0.577351 0.577350 -v -0.005750 -0.097720 0.246800 -vn 0.095830 -0.727970 0.678879 -v -0.005250 -0.097720 0.246800 -vn -0.669354 -0.088121 0.737700 -v -0.005750 -0.097370 0.246800 -vn 0.378575 -0.655726 0.653226 -v -0.005000 -0.097653 0.246800 -vn 0.378584 -0.655719 0.653228 -v 0.000500 -0.092153 0.246800 -vn 0.655720 -0.378579 0.653230 -v 0.000683 -0.091970 0.246800 -vn 0.088114 0.669357 0.737697 -v 0.000400 -0.091220 0.246800 -vn 0.727973 -0.095841 0.678874 -v 0.000750 -0.091720 0.246800 -vn 0.577350 0.577352 0.577350 -v 0.000750 -0.091220 0.246800 -vn -0.088114 0.669357 0.737697 -v 0.007100 -0.091220 0.246800 -vn -0.577351 0.577350 0.577350 -v 0.006750 -0.091220 0.246800 -vn -0.727971 -0.095840 0.678876 -v 0.006750 -0.091720 0.246800 -vn -0.378577 -0.655725 0.653226 -v 0.012500 -0.097653 0.246800 -vn -0.655721 -0.378578 0.653230 -v 0.012317 -0.097470 0.246800 -vn -0.727971 -0.095840 0.678876 -v 0.012250 -0.097220 0.246800 -vn -0.669348 -0.088127 0.737704 -v 0.007300 -0.110420 0.246800 -vn -0.577350 -0.577350 0.577350 -v 0.007300 -0.110720 0.246800 -vn 0.095841 -0.727974 0.678873 -v 0.012250 -0.110720 0.246800 -vn 0.727973 0.095840 0.678874 -v 0.013750 -0.092220 0.246800 -vn -0.318867 -0.552284 0.770264 -v 0.012000 -0.094787 0.246800 -vn -0.552291 -0.318862 0.770261 -v 0.012183 -0.094970 0.246800 -vn 0.727971 0.095840 0.678876 -v 0.000750 -0.109720 0.246800 -vn 0.655721 0.378577 0.653230 -v 0.000683 -0.109470 0.246800 -vn 0.378585 0.655718 0.653228 -v 0.000500 -0.109287 0.246800 -vn 0.655720 -0.378579 0.653230 -v -0.004817 -0.097470 0.246800 -vn 0.727973 -0.095841 0.678874 -v -0.004750 -0.097220 0.246800 -vn -0.552281 -0.318868 0.770266 -v -0.005777 -0.097270 0.246800 -vn 0.669352 -0.088123 0.737701 -v -0.004750 -0.095220 0.246800 -vn -0.318850 -0.552296 0.770262 -v -0.005850 -0.097197 0.246800 -vn -0.727972 0.095840 0.678875 -v -0.006250 -0.092220 0.246800 -vn -0.088114 -0.669357 0.737697 -v -0.005950 -0.097170 0.246800 -vn -0.577352 -0.577347 0.577352 -v -0.006250 -0.097170 0.246800 -vn -0.318863 -0.552289 0.770262 -v 0.009500 -0.092287 0.246800 -vn -0.552284 -0.318863 0.770265 -v 0.009683 -0.092470 0.246800 -vn 0.095841 0.727973 0.678874 -v 0.012250 -0.090720 0.246800 -vn 0.577350 0.577351 0.577350 -v 0.013250 -0.103720 0.246800 -vn -0.095840 0.727971 0.678876 -v 0.012750 -0.103720 0.246800 -vn 0.669354 0.088121 0.737700 -v 0.013250 -0.104070 0.246800 -vn -0.378576 0.655722 0.653230 -v 0.012500 -0.103787 0.246800 -vn 0.552281 0.318868 0.770266 -v 0.013277 -0.104170 0.246800 -vn -0.669351 -0.088122 0.737702 -v 0.012250 -0.095220 0.246800 -vn 0.552281 -0.318868 0.770265 -v 0.013277 -0.097270 0.246800 -vn 0.318850 -0.552296 0.770262 -v 0.013350 -0.097197 0.246800 -vn 0.088114 -0.669355 0.737699 -v 0.013450 -0.097170 0.246800 -vn 0.577351 -0.577350 0.577350 -v 0.013750 -0.097170 0.246800 -vn -0.088123 -0.669352 0.737701 -v 0.009250 -0.092220 0.246800 -vn -0.727973 0.095841 0.678874 -v 0.006750 -0.109720 0.246800 -vn -0.577350 -0.577352 0.577350 -v 0.006750 -0.110220 0.246800 -vn -0.088114 -0.669357 0.737697 -v 0.007100 -0.110220 0.246800 -vn 0.095841 0.727973 0.678874 -v -0.005250 -0.103720 0.246800 -vn -0.577352 0.577350 0.577350 -v -0.005750 -0.103720 0.246800 -vn -0.669353 0.088121 0.737700 -v -0.005750 -0.104070 0.246800 -vn -0.552297 -0.318864 0.770256 -v 0.007273 -0.110320 0.246800 -vn -0.318861 0.552281 0.770269 -v 0.007200 -0.091193 0.246800 -vn -0.552296 0.318864 0.770256 -v 0.007273 -0.091120 0.246800 -vn -0.669350 0.088127 0.737702 -v 0.007300 -0.091020 0.246800 -vn -0.577347 0.577352 0.577352 -v 0.007300 -0.090720 0.246800 -vn 0.088123 0.669352 0.737701 -v -0.001750 -0.109220 0.246800 -vn 0.318863 0.552290 0.770261 -v -0.002000 -0.109153 0.246800 -vn -0.095841 -0.727973 0.678874 -v -0.004750 -0.110720 0.246800 -vn 0.552284 0.318863 0.770265 -v -0.002183 -0.108970 0.246800 -vn 0.727971 0.095837 0.678877 -v -0.004750 -0.104220 0.246800 -vn 0.655721 0.378583 0.653227 -v -0.004817 -0.103970 0.246800 -vn 0.378578 0.655721 0.653230 -v -0.005000 -0.103787 0.246800 -vn 0.577351 -0.577350 0.577350 -v 0.000750 -0.110220 0.246800 -vn 0.088114 -0.669357 0.737697 -v 0.000400 -0.110220 0.246800 -vn 0.318861 -0.552281 0.770269 -v 0.000300 -0.110247 0.246800 -vn 0.552296 -0.318863 0.770257 -v 0.000227 -0.110320 0.246800 -vn 0.095841 0.727973 0.678874 -v 0.000250 -0.109220 0.246800 -vn 0.669350 -0.088126 0.737702 -v 0.000200 -0.110420 0.246800 -vn 0.577347 -0.577352 0.577352 -v 0.000200 -0.110720 0.246800 -vn -0.669353 0.088121 0.737700 -v 0.009750 -0.108720 0.246800 -vn -0.552284 0.318864 0.770265 -v 0.009683 -0.108970 0.246800 -vn 0.251477 0.607114 0.753771 -v 0.010826 -0.106682 0.246800 -vn 0.528438 -0.433683 0.729844 -v -0.002104 -0.107634 0.246800 -vn 0.433673 -0.528437 0.729851 -v 0.000164 -0.105366 0.246800 -vn 0.318864 0.552289 0.770262 -v 0.002375 -0.103102 0.246800 -vn 0.251483 -0.607123 0.753763 -v 0.000326 -0.105258 0.246800 -vn -0.000000 0.637728 0.770262 -v 0.003750 -0.103470 0.246800 -vn 0.669348 0.088126 0.737704 -v 0.000200 -0.091020 0.246800 -vn 0.577350 0.577350 0.577350 -v 0.000200 -0.090720 0.246800 -vn -0.095841 0.727974 0.678873 -v -0.004750 -0.090720 0.246800 -vn 0.552289 -0.318865 0.770261 -v 0.001368 -0.099345 0.246800 -vn -0.433684 -0.528436 0.729845 -v -0.003164 -0.094866 0.246800 -vn -0.528437 -0.433674 0.729850 -v -0.000896 -0.097134 0.246800 -vn 0.669353 -0.088120 0.737700 -v -0.002250 -0.092720 0.246800 -vn 0.552283 -0.318864 0.770265 -v -0.002183 -0.092470 0.246800 -vn -0.251477 -0.607115 0.753771 -v -0.003326 -0.094758 0.246800 -vn 0.378583 0.655721 0.653226 -v 0.013000 -0.090921 0.246800 -vn -0.088123 -0.669352 0.737701 -v 0.011750 -0.094720 0.246800 -vn -0.251478 0.607115 0.753771 -v -0.003326 -0.106682 0.246800 -vn 0.669352 0.088120 0.737701 -v -0.002250 -0.108720 0.246800 -vn 0.669352 0.088120 0.737701 -v -0.004750 -0.106220 0.246800 -vn -0.552280 0.318868 0.770266 -v -0.005777 -0.104170 0.246800 -vn 0.552284 0.318863 0.770265 -v -0.004683 -0.106470 0.246800 -vn -0.318875 0.552295 0.770253 -v -0.005850 -0.104243 0.246800 -vn -0.727973 -0.095839 0.678875 -v -0.006250 -0.109220 0.246800 -vn -0.088136 0.669343 0.737708 -v -0.005950 -0.104270 0.246800 -vn -0.577351 0.577350 0.577350 -v -0.006250 -0.104270 0.246800 -vn 0.577352 0.577347 0.577352 -v 0.013750 -0.104270 0.246800 -vn 0.088136 0.669345 0.737706 -v 0.013450 -0.104270 0.246800 -vn 0.727972 -0.095839 0.678875 -v 0.013750 -0.109220 0.246800 -vn 0.318875 0.552294 0.770253 -v 0.013350 -0.104243 0.246800 -vn -0.067001 0.680320 0.729847 -v -0.003518 -0.106720 0.246800 -vn 0.088123 0.669352 0.737701 -v -0.004250 -0.106720 0.246800 -vn -0.378581 -0.655722 0.653227 -v -0.005500 -0.110519 0.246800 -vn -0.655722 -0.378583 0.653226 -v -0.006049 -0.109970 0.246800 -vn 0.318863 0.552289 0.770262 -v -0.004500 -0.106653 0.246800 -vn 0.088122 -0.669351 0.737702 -v -0.004250 -0.094720 0.246800 -vn -0.067001 -0.680319 0.729847 -v -0.003518 -0.094720 0.246800 -vn 0.680318 0.067004 0.729848 -v -0.002250 -0.093452 0.246800 -vn 0.552296 0.318863 0.770257 -v 0.000227 -0.091120 0.246800 -vn -0.655720 0.378585 0.653227 -v 0.012317 -0.103970 0.246800 -vn -0.727973 0.095838 0.678875 -v 0.012250 -0.104220 0.246800 -vn -0.669353 0.088121 0.737700 -v 0.012250 -0.106220 0.246800 -vn 0.095840 -0.727971 0.678876 -v 0.000250 -0.092220 0.246800 -vn 0.318861 0.552280 0.770269 -v 0.000300 -0.091193 0.246800 -vn 0.088122 -0.669351 0.737702 -v -0.001750 -0.092220 0.246800 -vn 0.318861 -0.552291 0.770261 -v -0.002000 -0.092287 0.246800 -vn -0.318865 -0.552291 0.770260 -v 0.005125 -0.098338 0.246800 -vn -0.528438 0.433675 0.729849 -v 0.009604 -0.093806 0.246800 -vn -0.433672 0.528438 0.729850 -v 0.007336 -0.096074 0.246800 -vn -0.607121 -0.251477 0.753766 -v -0.000788 -0.097296 0.246800 -vn -0.680317 -0.067007 0.729849 -v -0.000750 -0.097488 0.246800 -vn 0.637728 0.000001 0.770262 -v 0.001000 -0.100720 0.246800 -vn -0.680316 0.067007 0.729849 -v -0.000750 -0.103952 0.246800 -vn 0.552288 0.318865 0.770262 -v 0.001368 -0.102095 0.246800 -vn -0.607122 0.251477 0.753766 -v -0.000788 -0.104144 0.246800 -vn -0.528438 0.433675 0.729849 -v -0.000896 -0.104306 0.246800 -vn -0.433683 0.528435 0.729846 -v -0.003164 -0.106574 0.246800 -vn 0.607116 -0.251479 0.753769 -v -0.002212 -0.107796 0.246800 -vn 0.680318 -0.067004 0.729848 -v -0.002250 -0.107988 0.246800 -vn 0.552289 -0.318863 0.770262 -v -0.004683 -0.094970 0.246800 -vn 0.318865 -0.552284 0.770264 -v -0.004500 -0.094787 0.246800 -vn -0.655723 0.378580 0.653226 -v -0.006049 -0.091470 0.246800 -vn -0.378584 0.655721 0.653226 -v -0.005500 -0.090921 0.246800 -vn 0.251478 -0.607114 0.753771 -v 0.010826 -0.094758 0.246800 -vn -0.669352 -0.088120 0.737701 -v 0.009750 -0.092720 0.246800 -vn 0.433684 0.528435 0.729846 -v 0.010664 -0.106574 0.246800 -vn 0.528437 0.433674 0.729850 -v 0.008396 -0.104306 0.246800 -vn -0.552288 0.318864 0.770262 -v 0.006132 -0.102095 0.246800 -vn 0.607121 0.251477 0.753766 -v 0.008288 -0.104144 0.246800 -vn -0.637728 0.000000 0.770262 -v 0.006500 -0.100720 0.246800 -vn -0.251483 0.607123 0.753763 -v 0.007174 -0.096182 0.246800 -vn -0.067013 0.680313 0.729851 -v 0.006982 -0.096220 0.246800 -vn 0.000000 -0.637728 0.770262 -v 0.003750 -0.097970 0.246800 -vn 0.067013 0.680313 0.729852 -v 0.000518 -0.096220 0.246800 -vn 0.318864 -0.552289 0.770261 -v 0.002375 -0.098338 0.246800 -vn 0.251483 0.607123 0.753763 -v 0.000326 -0.096182 0.246800 -vn 0.433673 0.528439 0.729850 -v 0.000164 -0.096074 0.246800 -vn 0.528437 0.433675 0.729850 -v -0.002104 -0.093806 0.246800 -vn 0.607121 0.251474 0.753767 -v -0.002212 -0.093644 0.246800 -vn 0.067001 -0.680320 0.729847 -v 0.011018 -0.094720 0.246800 -vn -0.088122 0.669351 0.737702 -v 0.011750 -0.106720 0.246800 -vn 0.067001 0.680319 0.729847 -v 0.011018 -0.106720 0.246800 -vn -0.680318 -0.067004 0.729848 -v 0.009750 -0.107988 0.246800 -vn 0.655722 0.378581 0.653226 -v 0.013549 -0.091470 0.246800 -vn -0.552284 0.318864 0.770265 -v 0.012183 -0.106470 0.246800 -vn -0.318861 0.552290 0.770262 -v 0.012000 -0.106653 0.246800 -vn 0.655722 -0.378582 0.653226 -v 0.013549 -0.109970 0.246800 -vn 0.378581 -0.655722 0.653227 -v 0.013000 -0.110519 0.246800 -vn -0.655720 0.378579 0.653230 -v 0.006817 -0.109470 0.246800 -vn -0.378584 0.655719 0.653228 -v 0.007000 -0.109287 0.246800 -vn -0.095840 0.727971 0.678876 -v 0.007250 -0.109220 0.246800 -vn -0.318861 -0.552280 0.770269 -v 0.007200 -0.110247 0.246800 -vn -0.088122 0.669351 0.737702 -v 0.009250 -0.109220 0.246800 -vn -0.318861 0.552290 0.770262 -v 0.009500 -0.109153 0.246800 -vn 0.680317 0.067007 0.729849 -v 0.008250 -0.103952 0.246800 -vn 0.680316 -0.067007 0.729849 -v 0.008250 -0.097488 0.246800 -vn -0.552288 -0.318864 0.770262 -v 0.006132 -0.099345 0.246800 -vn 0.607122 -0.251477 0.753766 -v 0.008288 -0.097296 0.246800 -vn 0.528438 -0.433675 0.729849 -v 0.008396 -0.097134 0.246800 -vn 0.433684 -0.528434 0.729846 -v 0.010664 -0.094866 0.246800 -vn -0.607121 0.251474 0.753767 -v 0.009712 -0.093644 0.246800 -vn -0.680318 0.067004 0.729848 -v 0.009750 -0.093452 0.246800 -vn 0.067013 -0.680313 0.729851 -v 0.000518 -0.105220 0.246800 -vn -0.067013 -0.680313 0.729852 -v 0.006982 -0.105220 0.246800 -vn -0.318864 0.552289 0.770261 -v 0.005125 -0.103102 0.246800 -vn -0.251483 -0.607123 0.753763 -v 0.007174 -0.105258 0.246800 -vn -0.433673 -0.528438 0.729850 -v 0.007336 -0.105366 0.246800 -vn -0.528435 -0.433682 0.729847 -v 0.009604 -0.107634 0.246800 -vn -0.607116 -0.251480 0.753769 -v 0.009712 -0.107796 0.246800 -vn 0.727971 -0.095840 -0.678876 -v 0.000750 0.109720 0.166800 -vn 0.655721 -0.378577 -0.653230 -v 0.000683 0.109470 0.166800 -vn 0.378585 -0.655718 -0.653228 -v 0.000500 0.109287 0.166800 -vn 0.727973 0.095841 -0.678874 -v 0.000750 0.091720 0.166800 -vn 0.577350 -0.577352 -0.577350 -v 0.000750 0.091220 0.166800 -vn 0.088114 -0.669357 -0.737697 -v 0.000400 0.091220 0.166800 -vn 0.577350 -0.577351 -0.577350 -v 0.013250 0.103720 0.166800 -vn -0.095840 -0.727971 -0.678876 -v 0.012750 0.103720 0.166800 -vn 0.669354 -0.088121 -0.737700 -v 0.013250 0.104070 0.166800 -vn -0.378576 -0.655722 -0.653230 -v 0.012500 0.103787 0.166800 -vn 0.552281 -0.318868 -0.770266 -v 0.013277 0.104170 0.166800 -vn -0.378584 -0.655719 -0.653228 -v 0.007000 0.109287 0.166800 -vn -0.655720 -0.378579 -0.653230 -v 0.006817 0.109470 0.166800 -vn -0.088114 0.669357 -0.737697 -v 0.007100 0.110220 0.166800 -vn -0.727973 -0.095841 -0.678874 -v 0.006750 0.109720 0.166800 -vn -0.577350 0.577352 -0.577350 -v 0.006750 0.110220 0.166800 -vn 0.095841 -0.727973 -0.678874 -v -0.005250 0.103720 0.166800 -vn -0.577352 -0.577350 -0.577350 -v -0.005750 0.103720 0.166800 -vn -0.669353 -0.088121 -0.737700 -v -0.005750 0.104070 0.166800 -vn -0.669348 0.088127 -0.737704 -v 0.007300 0.110420 0.166800 -vn -0.577350 0.577350 -0.577350 -v 0.007300 0.110720 0.166800 -vn 0.095841 0.727973 -0.678874 -v 0.012250 0.110720 0.166800 -vn 0.577351 0.577350 -0.577350 -v 0.000750 0.110220 0.166800 -vn 0.088114 0.669357 -0.737697 -v 0.000400 0.110220 0.166800 -vn 0.318861 0.552281 -0.770269 -v 0.000300 0.110247 0.166800 -vn 0.552296 0.318863 -0.770257 -v 0.000227 0.110320 0.166800 -vn -0.318863 0.552289 -0.770262 -v 0.009500 0.092287 0.166800 -vn -0.552284 0.318863 -0.770265 -v 0.009683 0.092470 0.166800 -vn 0.095841 -0.727974 -0.678873 -v 0.012250 0.090720 0.166800 -vn -0.727973 0.095839 -0.678875 -v -0.006250 0.109220 0.166800 -vn 0.318863 -0.552289 -0.770262 -v -0.004500 0.106653 0.166800 -vn 0.552284 -0.318863 -0.770265 -v -0.004683 0.106470 0.166800 -vn 0.378578 -0.655721 -0.653230 -v -0.005000 0.103787 0.166800 -vn 0.655721 -0.378583 -0.653227 -v -0.004817 0.103970 0.166800 -vn 0.727971 -0.095837 -0.678877 -v -0.004750 0.104220 0.166800 -vn 0.577352 -0.577347 -0.577352 -v 0.013750 0.104270 0.166800 -vn 0.088136 -0.669345 -0.737706 -v 0.013450 0.104270 0.166800 -vn 0.727972 0.095839 -0.678875 -v 0.013750 0.109220 0.166800 -vn 0.318875 -0.552294 -0.770253 -v 0.013350 0.104243 0.166800 -vn -0.552296 -0.318864 -0.770256 -v 0.007273 0.091120 0.166800 -vn -0.669350 -0.088127 -0.737702 -v 0.007300 0.091020 0.166800 -vn -0.577347 -0.577352 -0.577352 -v 0.007300 0.090720 0.166800 -vn 0.669348 -0.088126 -0.737704 -v 0.000200 0.091020 0.166800 -vn 0.577350 -0.577350 -0.577350 -v 0.000200 0.090720 0.166800 -vn -0.095841 -0.727973 -0.678874 -v -0.004750 0.090720 0.166800 -vn -0.655720 -0.378585 -0.653227 -v 0.012317 0.103970 0.166800 -vn -0.727973 -0.095838 -0.678875 -v 0.012250 0.104220 0.166800 -vn -0.669353 -0.088121 -0.737700 -v 0.012250 0.106220 0.166800 -vn -0.095830 0.727972 -0.678877 -v 0.012750 0.097720 0.166800 -vn 0.577352 0.577350 -0.577350 -v 0.013250 0.097720 0.166800 -vn 0.669353 0.088121 -0.737700 -v 0.013250 0.097370 0.166800 -vn 0.669352 -0.088120 -0.737701 -v -0.004750 0.106220 0.166800 -vn -0.552280 -0.318868 -0.770266 -v -0.005777 0.104170 0.166800 -vn -0.318875 -0.552295 -0.770253 -v -0.005850 0.104243 0.166800 -vn -0.088136 -0.669343 -0.737708 -v -0.005950 0.104270 0.166800 -vn -0.577350 -0.577350 -0.577350 -v -0.006250 0.104270 0.166800 -vn -0.552296 0.318864 -0.770256 -v 0.007273 0.110320 0.166800 -vn -0.088123 0.669352 -0.737701 -v 0.009250 0.092220 0.166800 -vn -0.095841 0.727973 -0.678874 -v 0.007250 0.092220 0.166800 -vn -0.577351 -0.577350 -0.577350 -v 0.006750 0.091220 0.166800 -vn -0.727971 0.095840 -0.678876 -v 0.006750 0.091720 0.166800 -vn -0.088114 -0.669357 -0.737697 -v 0.007100 0.091220 0.166800 -vn -0.655721 0.378577 -0.653230 -v 0.006817 0.091970 0.166800 -vn -0.727971 0.095840 -0.678876 -v 0.012250 0.097220 0.166800 -vn -0.655721 0.378578 -0.653230 -v 0.012317 0.097470 0.166800 -vn -0.378577 0.655725 -0.653226 -v 0.012500 0.097653 0.166800 -vn 0.669353 0.088121 -0.737700 -v -0.002250 0.092720 0.166800 -vn 0.552283 0.318864 -0.770265 -v -0.002183 0.092470 0.166800 -vn -0.251477 0.607114 -0.753771 -v -0.003326 0.094758 0.166800 -vn 0.552296 -0.318863 -0.770257 -v 0.000227 0.091120 0.166800 -vn -0.318861 -0.552281 -0.770269 -v 0.007200 0.091193 0.166800 -vn -0.378585 0.655718 -0.653228 -v 0.007000 0.092153 0.166800 -vn -0.378581 0.655722 -0.653227 -v -0.005500 0.110519 0.166800 -vn -0.095841 0.727973 -0.678874 -v -0.004750 0.110720 0.166800 -vn 0.088123 -0.669352 -0.737701 -v -0.004250 0.106720 0.166800 -vn 0.318864 -0.552290 -0.770261 -v 0.002375 0.103102 0.166800 -vn 0.528437 0.433683 -0.729845 -v -0.002104 0.107634 0.166800 -vn 0.433672 0.528437 -0.729851 -v 0.000164 0.105366 0.166800 -vn 0.088123 -0.669352 -0.737701 -v -0.001750 0.109220 0.166800 -vn 0.318863 -0.552290 -0.770261 -v -0.002000 0.109153 0.166800 -vn 0.552284 -0.318863 -0.770265 -v -0.002183 0.108970 0.166800 -vn -0.528438 -0.433675 -0.729849 -v 0.009604 0.093806 0.166800 -vn -0.433672 -0.528438 -0.729851 -v 0.007336 0.096074 0.166800 -vn -0.318864 0.552290 -0.770261 -v 0.005125 0.098338 0.166800 -vn -0.251483 -0.607123 -0.753763 -v 0.007174 0.096182 0.166800 -vn 0.000000 0.637728 -0.770262 -v 0.003750 0.097970 0.166800 -vn 0.095841 -0.727973 -0.678874 -v 0.000250 0.109220 0.166800 -vn 0.669350 0.088126 -0.737702 -v 0.000200 0.110420 0.166800 -vn 0.577347 0.577352 -0.577352 -v 0.000200 0.110720 0.166800 -vn 0.378583 -0.655721 -0.653226 -v 0.013000 0.090921 0.166800 -vn -0.088123 0.669352 -0.737701 -v 0.011750 0.094720 0.166800 -vn -0.669353 -0.088121 -0.737700 -v 0.009750 0.108720 0.166800 -vn -0.552284 -0.318864 -0.770265 -v 0.009683 0.108970 0.166800 -vn 0.251477 -0.607114 -0.753771 -v 0.010826 0.106682 0.166800 -vn 0.727973 -0.095840 -0.678874 -v 0.013750 0.092220 0.166800 -vn -0.318867 0.552284 -0.770264 -v 0.012000 0.094787 0.166800 -vn -0.552290 0.318861 -0.770262 -v 0.012183 0.094970 0.166800 -vn -0.552290 -0.318866 -0.770260 -v 0.006132 0.102095 0.166800 -vn 0.433685 -0.528436 -0.729845 -v 0.010664 0.106574 0.166800 -vn 0.528437 -0.433674 -0.729850 -v 0.008396 0.104306 0.166800 -vn -0.251478 -0.607115 -0.753771 -v -0.003326 0.106682 0.166800 -vn 0.669352 -0.088120 -0.737701 -v -0.002250 0.108720 0.166800 -vn 0.727973 0.095841 -0.678874 -v -0.004750 0.097220 0.166800 -vn 0.669352 0.088123 -0.737701 -v -0.004750 0.095220 0.166800 -vn -0.318850 0.552296 -0.770262 -v -0.005850 0.097197 0.166800 -vn -0.727972 -0.095840 -0.678875 -v -0.006250 0.092220 0.166800 -vn -0.088114 0.669357 -0.737697 -v -0.005950 0.097170 0.166800 -vn -0.577352 0.577347 -0.577352 -v -0.006250 0.097170 0.166800 -vn -0.433684 0.528435 -0.729846 -v -0.003164 0.094866 0.166800 -vn -0.528437 0.433674 -0.729850 -v -0.000896 0.097134 0.166800 -vn 0.552289 0.318865 -0.770261 -v 0.001368 0.099345 0.166800 -vn -0.607121 0.251477 -0.753766 -v -0.000788 0.097296 0.166800 -vn 0.637728 -0.000001 -0.770262 -v 0.001000 0.100720 0.166800 -vn -0.067001 -0.680320 -0.729847 -v -0.003518 0.106720 0.166800 -vn -0.577350 0.577351 -0.577350 -v -0.005750 0.097720 0.166800 -vn 0.095830 0.727970 -0.678879 -v -0.005250 0.097720 0.166800 -vn -0.669354 0.088121 -0.737700 -v -0.005750 0.097370 0.166800 -vn 0.378575 0.655726 -0.653226 -v -0.005000 0.097653 0.166800 -vn 0.088122 0.669351 -0.737702 -v -0.004250 0.094720 0.166800 -vn -0.067001 0.680319 -0.729847 -v -0.003518 0.094720 0.166800 -vn 0.680318 -0.067004 -0.729848 -v -0.002250 0.093452 0.166800 -vn 0.251478 0.607114 -0.753771 -v 0.010826 0.094758 0.166800 -vn -0.669352 0.088120 -0.737701 -v 0.009750 0.092720 0.166800 -vn -0.669351 0.088122 -0.737702 -v 0.012250 0.095220 0.166800 -vn 0.552281 0.318868 -0.770266 -v 0.013277 0.097270 0.166800 -vn 0.318850 0.552296 -0.770262 -v 0.013350 0.097197 0.166800 -vn 0.088114 0.669355 -0.737699 -v 0.013450 0.097170 0.166800 -vn 0.577350 0.577350 -0.577350 -v 0.013750 0.097170 0.166800 -vn -0.088122 -0.669351 -0.737702 -v 0.011750 0.106720 0.166800 -vn 0.067001 -0.680319 -0.729847 -v 0.011018 0.106720 0.166800 -vn -0.680318 0.067004 -0.729848 -v 0.009750 0.107988 0.166800 -vn -0.655722 0.378583 -0.653226 -v -0.006049 0.109970 0.166800 -vn -0.552281 0.318868 -0.770266 -v -0.005777 0.097270 0.166800 -vn 0.655720 0.378579 -0.653230 -v -0.004817 0.097470 0.166800 -vn 0.552289 0.318863 -0.770262 -v -0.004683 0.094970 0.166800 -vn 0.318865 0.552284 -0.770264 -v -0.004500 0.094787 0.166800 -vn -0.655723 -0.378580 -0.653226 -v -0.006049 0.091470 0.166800 -vn -0.378584 -0.655721 -0.653226 -v -0.005500 0.090921 0.166800 -vn 0.655720 0.378579 -0.653230 -v 0.000683 0.091970 0.166800 -vn 0.378584 0.655719 -0.653228 -v 0.000500 0.092153 0.166800 -vn 0.095840 0.727971 -0.678876 -v 0.000250 0.092220 0.166800 -vn 0.318861 -0.552280 -0.770269 -v 0.000300 0.091193 0.166800 -vn 0.088122 0.669350 -0.737702 -v -0.001750 0.092220 0.166800 -vn 0.318861 0.552291 -0.770261 -v -0.002000 0.092287 0.166800 -vn 0.067001 0.680320 -0.729847 -v 0.011018 0.094720 0.166800 -vn -0.095840 -0.727971 -0.678876 -v 0.007250 0.109220 0.166800 -vn -0.318861 0.552280 -0.770269 -v 0.007200 0.110247 0.166800 -vn -0.088122 -0.669351 -0.737702 -v 0.009250 0.109220 0.166800 -vn -0.318861 -0.552290 -0.770262 -v 0.009500 0.109153 0.166800 -vn -0.680317 0.067007 -0.729849 -v -0.000750 0.097488 0.166800 -vn -0.680316 -0.067007 -0.729849 -v -0.000750 0.103952 0.166800 -vn 0.552288 -0.318865 -0.770262 -v 0.001368 0.102095 0.166800 -vn -0.607122 -0.251477 -0.753766 -v -0.000788 0.104144 0.166800 -vn -0.528438 -0.433675 -0.729849 -v -0.000896 0.104306 0.166800 -vn -0.433683 -0.528435 -0.729846 -v -0.003164 0.106574 0.166800 -vn 0.607116 0.251479 -0.753769 -v -0.002212 0.107796 0.166800 -vn 0.680318 0.067004 -0.729848 -v -0.002250 0.107988 0.166800 -vn 0.655722 -0.378581 -0.653226 -v 0.013549 0.091470 0.166800 -vn -0.552284 -0.318864 -0.770265 -v 0.012183 0.106470 0.166800 -vn -0.318861 -0.552290 -0.770262 -v 0.012000 0.106653 0.166800 -vn 0.655722 0.378582 -0.653226 -v 0.013549 0.109970 0.166800 -vn 0.378581 0.655722 -0.653227 -v 0.013000 0.110519 0.166800 -vn -0.067013 -0.680313 -0.729851 -v 0.006982 0.096220 0.166800 -vn 0.067013 -0.680313 -0.729852 -v 0.000518 0.096220 0.166800 -vn 0.318864 0.552289 -0.770261 -v 0.002375 0.098338 0.166800 -vn 0.251483 -0.607123 -0.753763 -v 0.000326 0.096182 0.166800 -vn 0.433673 -0.528439 -0.729850 -v 0.000164 0.096074 0.166800 -vn 0.528437 -0.433675 -0.729850 -v -0.002104 0.093806 0.166800 -vn 0.607121 -0.251474 -0.753767 -v -0.002212 0.093644 0.166800 -vn 0.607121 -0.251477 -0.753766 -v 0.008288 0.104144 0.166800 -vn 0.680317 -0.067007 -0.729849 -v 0.008250 0.103952 0.166800 -vn -0.637728 -0.000000 -0.770262 -v 0.006500 0.100720 0.166800 -vn 0.680316 0.067007 -0.729849 -v 0.008250 0.097488 0.166800 -vn -0.552288 0.318864 -0.770262 -v 0.006132 0.099345 0.166800 -vn 0.607122 0.251477 -0.753766 -v 0.008288 0.097296 0.166800 -vn 0.528438 0.433675 -0.729849 -v 0.008396 0.097134 0.166800 -vn 0.433684 0.528435 -0.729846 -v 0.010664 0.094866 0.166800 -vn -0.607121 -0.251474 -0.753767 -v 0.009712 0.093644 0.166800 -vn -0.680318 -0.067004 -0.729848 -v 0.009750 0.093452 0.166800 -vn 0.251483 0.607123 -0.753763 -v 0.000326 0.105258 0.166800 -vn 0.067013 0.680313 -0.729851 -v 0.000518 0.105220 0.166800 -vn -0.000000 -0.637728 -0.770262 -v 0.003750 0.103470 0.166800 -vn -0.067013 0.680313 -0.729852 -v 0.006982 0.105220 0.166800 -vn -0.318864 -0.552289 -0.770261 -v 0.005125 0.103102 0.166800 -vn -0.251483 0.607123 -0.753763 -v 0.007174 0.105258 0.166800 -vn -0.433673 0.528438 -0.729850 -v 0.007336 0.105366 0.166800 -vn -0.528435 0.433682 -0.729847 -v 0.009604 0.107634 0.166800 -vn -0.607116 0.251480 -0.753769 -v 0.009712 0.107796 0.166800 -vn -0.655721 -0.378577 0.653230 -v 0.006817 0.109470 0.246800 -vn -0.378585 -0.655718 0.653228 -v 0.007000 0.109287 0.246800 -vn -0.095841 -0.727973 0.678874 -v 0.007250 0.109220 0.246800 -vn -0.095841 -0.727973 0.678874 -v 0.012750 0.103720 0.246800 -vn 0.577352 -0.577350 0.577350 -v 0.013250 0.103720 0.246800 -vn 0.669353 -0.088121 0.737700 -v 0.013250 0.104070 0.246800 -vn -0.577350 -0.577351 0.577350 -v -0.005750 0.103720 0.246800 -vn 0.095840 -0.727971 0.678876 -v -0.005250 0.103720 0.246800 -vn -0.669353 -0.088121 0.737700 -v -0.005750 0.104070 0.246800 -vn 0.378576 -0.655722 0.653230 -v -0.005000 0.103787 0.246800 -vn 0.378584 -0.655719 0.653228 -v 0.000500 0.109287 0.246800 -vn 0.655720 -0.378579 0.653230 -v 0.000683 0.109470 0.246800 -vn 0.088114 0.669357 0.737697 -v 0.000400 0.110220 0.246800 -vn 0.727973 -0.095840 0.678874 -v 0.000750 0.109720 0.246800 -vn 0.577349 0.577352 0.577350 -v 0.000750 0.110220 0.246800 -vn -0.088114 0.669357 0.737697 -v 0.007100 0.110220 0.246800 -vn -0.577351 0.577350 0.577350 -v 0.006750 0.110220 0.246800 -vn -0.727971 -0.095840 0.678876 -v 0.006750 0.109720 0.246800 -vn -0.378578 -0.655721 0.653230 -v 0.012500 0.103787 0.246800 -vn -0.655721 -0.378583 0.653227 -v 0.012317 0.103970 0.246800 -vn -0.727971 -0.095837 0.678877 -v 0.012250 0.104220 0.246800 -vn -0.669348 -0.088127 0.737704 -v 0.007300 0.091020 0.246800 -vn -0.577350 -0.577350 0.577350 -v 0.007300 0.090720 0.246800 -vn 0.095841 -0.727973 0.678874 -v 0.012250 0.090720 0.246800 -vn 0.727973 0.095839 0.678875 -v 0.013750 0.109220 0.246800 -vn -0.318863 -0.552289 0.770262 -v 0.012000 0.106653 0.246800 -vn -0.552284 -0.318863 0.770265 -v 0.012183 0.106470 0.246800 -vn 0.727971 0.095840 0.678876 -v 0.000750 0.091720 0.246800 -vn 0.655721 0.378577 0.653230 -v 0.000683 0.091970 0.246800 -vn 0.378585 0.655718 0.653228 -v 0.000500 0.092153 0.246800 -vn 0.655720 -0.378585 0.653227 -v -0.004817 0.103970 0.246800 -vn 0.727973 -0.095838 0.678875 -v -0.004750 0.104220 0.246800 -vn -0.552281 -0.318868 0.770266 -v -0.005777 0.104170 0.246800 -vn 0.669353 -0.088121 0.737700 -v -0.004750 0.106220 0.246800 -vn -0.318875 -0.552294 0.770253 -v -0.005850 0.104243 0.246800 -vn -0.727972 0.095839 0.678875 -v -0.006250 0.109220 0.246800 -vn -0.088136 -0.669345 0.737706 -v -0.005950 0.104270 0.246800 -vn -0.577352 -0.577347 0.577352 -v -0.006250 0.104270 0.246800 -vn -0.318863 -0.552289 0.770262 -v 0.009500 0.109153 0.246800 -vn -0.552284 -0.318863 0.770265 -v 0.009683 0.108970 0.246800 -vn 0.095841 0.727974 0.678873 -v 0.012250 0.110720 0.246800 -vn 0.577350 0.577351 0.577350 -v 0.013250 0.097720 0.246800 -vn -0.095830 0.727970 0.678879 -v 0.012750 0.097720 0.246800 -vn 0.669354 0.088121 0.737700 -v 0.013250 0.097370 0.246800 -vn -0.378575 0.655726 0.653226 -v 0.012500 0.097653 0.246800 -vn 0.552281 0.318868 0.770266 -v 0.013277 0.097270 0.246800 -vn -0.669352 -0.088120 0.737701 -v 0.012250 0.106220 0.246800 -vn 0.552280 -0.318868 0.770266 -v 0.013277 0.104170 0.246800 -vn 0.318875 -0.552295 0.770253 -v 0.013350 0.104243 0.246800 -vn 0.088136 -0.669343 0.737708 -v 0.013450 0.104270 0.246800 -vn 0.577350 -0.577350 0.577350 -v 0.013750 0.104270 0.246800 -vn -0.088123 -0.669352 0.737700 -v 0.009250 0.109220 0.246800 -vn -0.727973 0.095841 0.678874 -v 0.006750 0.091720 0.246800 -vn -0.577350 -0.577352 0.577350 -v 0.006750 0.091220 0.246800 -vn -0.088114 -0.669357 0.737697 -v 0.007100 0.091220 0.246800 -vn 0.095830 0.727972 0.678877 -v -0.005250 0.097720 0.246800 -vn -0.577352 0.577350 0.577350 -v -0.005750 0.097720 0.246800 -vn -0.669353 0.088121 0.737700 -v -0.005750 0.097370 0.246800 -vn -0.552296 -0.318864 0.770256 -v 0.007273 0.091120 0.246800 -vn -0.318861 0.552281 0.770269 -v 0.007200 0.110247 0.246800 -vn -0.552296 0.318864 0.770256 -v 0.007273 0.110320 0.246800 -vn -0.669350 0.088127 0.737702 -v 0.007300 0.110420 0.246800 -vn -0.577347 0.577352 0.577352 -v 0.007300 0.110720 0.246800 -vn 0.088123 0.669352 0.737701 -v -0.001750 0.092220 0.246800 -vn 0.318863 0.552290 0.770261 -v -0.002000 0.092287 0.246800 -vn -0.095841 -0.727973 0.678874 -v -0.004750 0.090720 0.246800 -vn 0.552284 0.318863 0.770265 -v -0.002183 0.092470 0.246800 -vn 0.727971 0.095840 0.678876 -v -0.004750 0.097220 0.246800 -vn 0.655721 0.378578 0.653230 -v -0.004817 0.097470 0.246800 -vn 0.378577 0.655725 0.653226 -v -0.005000 0.097653 0.246800 -vn 0.577351 -0.577350 0.577350 -v 0.000750 0.091220 0.246800 -vn 0.088114 -0.669357 0.737697 -v 0.000400 0.091220 0.246800 -vn 0.318861 -0.552281 0.770269 -v 0.000300 0.091193 0.246800 -vn 0.552296 -0.318863 0.770257 -v 0.000227 0.091120 0.246800 -vn 0.095841 0.727973 0.678874 -v 0.000250 0.092220 0.246800 -vn 0.669350 -0.088126 0.737702 -v 0.000200 0.091020 0.246800 -vn 0.577347 -0.577352 0.577352 -v 0.000200 0.090720 0.246800 -vn -0.669353 0.088121 0.737700 -v 0.009750 0.092720 0.246800 -vn -0.552284 0.318864 0.770265 -v 0.009683 0.092470 0.246800 -vn 0.251477 0.607114 0.753771 -v 0.010826 0.094758 0.246800 -vn 0.528438 -0.433675 0.729849 -v -0.002104 0.093806 0.246800 -vn 0.433672 -0.528438 0.729851 -v 0.000164 0.096074 0.246800 -vn 0.318865 0.552291 0.770260 -v 0.002375 0.098338 0.246800 -vn 0.251483 -0.607123 0.753763 -v 0.000326 0.096182 0.246800 -vn -0.000000 0.637728 0.770262 -v 0.003750 0.097970 0.246800 -vn 0.669348 0.088126 0.737704 -v 0.000200 0.110420 0.246800 -vn 0.577350 0.577350 0.577350 -v 0.000200 0.110720 0.246800 -vn -0.095841 0.727974 0.678873 -v -0.004750 0.110720 0.246800 -vn 0.552290 -0.318865 0.770260 -v 0.001368 0.102095 0.246800 -vn -0.433685 -0.528436 0.729845 -v -0.003164 0.106574 0.246800 -vn -0.528437 -0.433674 0.729850 -v -0.000896 0.104306 0.246800 -vn 0.669353 -0.088121 0.737700 -v -0.002250 0.108720 0.246800 -vn 0.552283 -0.318864 0.770265 -v -0.002183 0.108970 0.246800 -vn -0.251477 -0.607115 0.753771 -v -0.003326 0.106682 0.246800 -vn 0.378581 0.655722 0.653227 -v 0.013000 0.110519 0.246800 -vn -0.088123 -0.669352 0.737701 -v 0.011750 0.106720 0.246800 -vn -0.251477 0.607114 0.753771 -v -0.003326 0.094758 0.246800 -vn 0.669352 0.088120 0.737701 -v -0.002250 0.092720 0.246800 -vn 0.669351 0.088122 0.737702 -v -0.004750 0.095220 0.246800 -vn -0.552280 0.318868 0.770266 -v -0.005777 0.097270 0.246800 -vn 0.552290 0.318861 0.770262 -v -0.004683 0.094970 0.246800 -vn -0.318850 0.552296 0.770262 -v -0.005850 0.097197 0.246800 -vn -0.727973 -0.095840 0.678875 -v -0.006250 0.092220 0.246800 -vn -0.088114 0.669355 0.737699 -v -0.005950 0.097170 0.246800 -vn -0.577350 0.577350 0.577350 -v -0.006250 0.097170 0.246800 -vn 0.577352 0.577347 0.577352 -v 0.013750 0.097170 0.246800 -vn 0.088114 0.669357 0.737697 -v 0.013450 0.097170 0.246800 -vn 0.727973 -0.095839 0.678875 -v 0.013750 0.092220 0.246800 -vn 0.318850 0.552296 0.770262 -v 0.013350 0.097197 0.246800 -vn -0.067001 0.680320 0.729847 -v -0.003518 0.094720 0.246800 -vn 0.088123 0.669352 0.737701 -v -0.004250 0.094720 0.246800 -vn -0.378583 -0.655721 0.653226 -v -0.005500 0.090921 0.246800 -vn -0.655722 -0.378581 0.653226 -v -0.006049 0.091470 0.246800 -vn 0.318867 0.552284 0.770264 -v -0.004500 0.094787 0.246800 -vn 0.088122 -0.669351 0.737702 -v -0.004250 0.106720 0.246800 -vn -0.067001 -0.680319 0.729847 -v -0.003518 0.106720 0.246800 -vn 0.680318 0.067004 0.729848 -v -0.002250 0.107988 0.246800 -vn 0.552297 0.318863 0.770256 -v 0.000227 0.110320 0.246800 -vn -0.655720 0.378579 0.653230 -v 0.012317 0.097470 0.246800 -vn -0.727973 0.095840 0.678874 -v 0.012250 0.097220 0.246800 -vn -0.669352 0.088123 0.737701 -v 0.012250 0.095220 0.246800 -vn 0.095840 -0.727971 0.678876 -v 0.000250 0.109220 0.246800 -vn 0.318861 0.552280 0.770269 -v 0.000300 0.110247 0.246800 -vn 0.088122 -0.669350 0.737702 -v -0.001750 0.109220 0.246800 -vn 0.318861 -0.552291 0.770261 -v -0.002000 0.109153 0.246800 -vn -0.318864 -0.552290 0.770261 -v 0.005125 0.103102 0.246800 -vn -0.528436 0.433682 0.729846 -v 0.009604 0.107634 0.246800 -vn -0.433673 0.528437 0.729851 -v 0.007336 0.105366 0.246800 -vn -0.607121 -0.251477 0.753766 -v -0.000788 0.104144 0.246800 -vn -0.680317 -0.067007 0.729849 -v -0.000750 0.103952 0.246800 -vn 0.637728 -0.000000 0.770262 -v 0.001000 0.100720 0.246800 -vn -0.680316 0.067007 0.729849 -v -0.000750 0.097488 0.246800 -vn 0.552288 0.318864 0.770262 -v 0.001368 0.099345 0.246800 -vn -0.607122 0.251477 0.753766 -v -0.000788 0.097296 0.246800 -vn -0.528438 0.433675 0.729849 -v -0.000896 0.097134 0.246800 -vn -0.433683 0.528435 0.729846 -v -0.003164 0.094866 0.246800 -vn 0.607121 -0.251474 0.753767 -v -0.002212 0.093644 0.246800 -vn 0.680318 -0.067004 0.729848 -v -0.002250 0.093452 0.246800 -vn 0.552284 -0.318864 0.770265 -v -0.004683 0.106470 0.246800 -vn 0.318861 -0.552290 0.770262 -v -0.004500 0.106653 0.246800 -vn -0.655722 0.378582 0.653226 -v -0.006049 0.109970 0.246800 -vn -0.378581 0.655722 0.653227 -v -0.005500 0.110519 0.246800 -vn 0.251478 -0.607114 0.753771 -v 0.010826 0.106682 0.246800 -vn -0.669352 -0.088120 0.737701 -v 0.009750 0.108720 0.246800 -vn 0.433684 0.528435 0.729846 -v 0.010664 0.094866 0.246800 -vn 0.528438 0.433675 0.729849 -v 0.008396 0.097134 0.246800 -vn -0.552288 0.318864 0.770262 -v 0.006132 0.099345 0.246800 -vn 0.607121 0.251477 0.753766 -v 0.008288 0.097296 0.246800 -vn -0.637728 -0.000001 0.770262 -v 0.006500 0.100720 0.246800 -vn -0.251483 0.607123 0.753763 -v 0.007174 0.105258 0.246800 -vn -0.067013 0.680313 0.729851 -v 0.006982 0.105220 0.246800 -vn 0.000000 -0.637728 0.770262 -v 0.003750 0.103470 0.246800 -vn 0.067013 0.680313 0.729852 -v 0.000518 0.105220 0.246800 -vn 0.318864 -0.552289 0.770261 -v 0.002375 0.103102 0.246800 -vn 0.251483 0.607123 0.753763 -v 0.000326 0.105258 0.246800 -vn 0.433673 0.528438 0.729850 -v 0.000164 0.105366 0.246800 -vn 0.528435 0.433682 0.729847 -v -0.002104 0.107634 0.246800 -vn 0.607116 0.251480 0.753769 -v -0.002212 0.107796 0.246800 -vn 0.067001 -0.680320 0.729847 -v 0.011018 0.106720 0.246800 -vn -0.088122 0.669351 0.737702 -v 0.011750 0.094720 0.246800 -vn 0.067001 0.680319 0.729847 -v 0.011018 0.094720 0.246800 -vn -0.680318 -0.067004 0.729848 -v 0.009750 0.093452 0.246800 -vn 0.655722 0.378583 0.653226 -v 0.013549 0.109970 0.246800 -vn -0.552289 0.318863 0.770262 -v 0.012183 0.094970 0.246800 -vn -0.318865 0.552284 0.770264 -v 0.012000 0.094787 0.246800 -vn 0.655723 -0.378580 0.653226 -v 0.013549 0.091470 0.246800 -vn 0.378584 -0.655721 0.653226 -v 0.013000 0.090921 0.246800 -vn -0.655720 0.378579 0.653230 -v 0.006817 0.091970 0.246800 -vn -0.378584 0.655719 0.653228 -v 0.007000 0.092153 0.246800 -vn -0.095840 0.727971 0.678876 -v 0.007250 0.092220 0.246800 -vn -0.318861 -0.552280 0.770269 -v 0.007200 0.091193 0.246800 -vn -0.088122 0.669351 0.737702 -v 0.009250 0.092220 0.246800 -vn -0.318861 0.552290 0.770262 -v 0.009500 0.092287 0.246800 -vn 0.680317 0.067007 0.729849 -v 0.008250 0.097488 0.246800 -vn 0.680316 -0.067007 0.729849 -v 0.008250 0.103952 0.246800 -vn -0.552288 -0.318865 0.770262 -v 0.006132 0.102095 0.246800 -vn 0.607122 -0.251477 0.753766 -v 0.008288 0.104144 0.246800 -vn 0.528438 -0.433675 0.729849 -v 0.008396 0.104306 0.246800 -vn 0.433684 -0.528434 0.729846 -v 0.010664 0.106574 0.246800 -vn -0.607116 0.251479 0.753769 -v 0.009712 0.107796 0.246800 -vn -0.680318 0.067004 0.729848 -v 0.009750 0.107988 0.246800 -vn 0.067013 -0.680313 0.729851 -v 0.000518 0.096220 0.246800 -vn -0.067013 -0.680313 0.729852 -v 0.006982 0.096220 0.246800 -vn -0.318864 0.552289 0.770261 -v 0.005125 0.098338 0.246800 -vn -0.251483 -0.607123 0.753763 -v 0.007174 0.096182 0.246800 -vn -0.433673 -0.528439 0.729850 -v 0.007336 0.096074 0.246800 -vn -0.528437 -0.433675 0.729850 -v 0.009604 0.093806 0.246800 -vn -0.607121 -0.251474 0.753767 -v 0.009712 0.093644 0.246800 -vn -0.727973 -0.095837 0.678875 -v 0.031750 -0.127000 0.337300 -vn -0.655724 -0.378580 0.653225 -v 0.031817 -0.127250 0.337300 -vn -0.378575 -0.655728 0.653224 -v 0.032000 -0.127433 0.337300 -vn -0.727972 0.095837 0.678876 -v 0.031750 -0.145000 0.337300 -vn -0.577351 -0.577350 0.577351 -v 0.031750 -0.145500 0.337300 -vn -0.088113 -0.669358 0.737697 -v 0.032100 -0.145500 0.337300 -vn -0.577351 -0.577348 0.577351 -v 0.019250 -0.133000 0.337300 -vn 0.095852 -0.727975 0.678870 -v 0.019750 -0.133000 0.337300 -vn -0.669351 -0.088117 0.737702 -v 0.019250 -0.132650 0.337300 -vn 0.378578 -0.655718 0.653233 -v 0.020000 -0.132933 0.337300 -vn -0.552294 -0.318852 0.770263 -v 0.019223 -0.132550 0.337300 -vn 0.378578 -0.655727 0.653223 -v 0.025500 -0.127433 0.337300 -vn 0.655722 -0.378579 0.653228 -v 0.025683 -0.127250 0.337300 -vn 0.088114 0.669357 0.737697 -v 0.025400 -0.126500 0.337300 -vn 0.727972 -0.095842 0.678875 -v 0.025750 -0.127000 0.337300 -vn 0.577351 0.577350 0.577351 -v 0.025750 -0.126500 0.337300 -vn -0.095852 -0.727974 0.678872 -v 0.037750 -0.133000 0.337300 -vn 0.577350 -0.577351 0.577351 -v 0.038250 -0.133000 0.337300 -vn 0.669352 -0.088124 0.737701 -v 0.038250 -0.132650 0.337300 -vn 0.669342 0.088135 0.737709 -v 0.025200 -0.126300 0.337300 -vn 0.707107 -0.000000 0.707107 -v 0.025200 -0.126000 0.337300 -vn -0.134916 0.034558 0.990254 -v 0.020250 -0.126000 0.337300 -vn -0.577348 0.577351 0.577351 -v 0.031750 -0.126500 0.337300 -vn -0.088112 0.669354 0.737700 -v 0.032100 -0.126500 0.337300 -vn -0.318861 0.552272 0.770274 -v 0.032200 -0.126473 0.337300 -vn -0.552299 0.318869 0.770252 -v 0.032273 -0.126400 0.337300 -vn 0.318869 0.552297 0.770254 -v 0.023000 -0.144433 0.337300 -vn 0.552280 0.318868 0.770266 -v 0.022817 -0.144250 0.337300 -vn -0.095837 -0.727972 0.678876 -v 0.020250 -0.146000 0.337300 -vn 0.727973 0.095840 0.678874 -v 0.038750 -0.127500 0.337300 -vn -0.318877 -0.552285 0.770259 -v 0.037000 -0.130067 0.337300 -vn -0.552292 -0.318865 0.770259 -v 0.037183 -0.130250 0.337300 -vn -0.378576 -0.655719 0.653233 -v 0.037500 -0.132933 0.337300 -vn -0.655723 -0.378590 0.653220 -v 0.037317 -0.132750 0.337300 -vn -0.727972 -0.095831 0.678876 -v 0.037250 -0.132500 0.337300 -vn -0.577351 -0.577349 0.577351 -v 0.018750 -0.132450 0.337300 -vn -0.088114 -0.669357 0.737697 -v 0.019050 -0.132450 0.337300 -vn -0.727972 0.095840 0.678875 -v 0.018750 -0.127500 0.337300 -vn -0.318860 -0.552278 0.770271 -v 0.019150 -0.132477 0.337300 -vn 0.552295 -0.318871 0.770254 -v 0.025227 -0.145600 0.337300 -vn 0.669345 -0.088136 0.737705 -v 0.025200 -0.145700 0.337300 -vn 0.577349 -0.577351 0.577351 -v 0.025200 -0.146000 0.337300 -vn -0.669342 -0.088135 0.737709 -v 0.032300 -0.145700 0.337300 -vn -0.577350 -0.577350 0.577350 -v 0.032300 -0.146000 0.337300 -vn 0.095837 -0.727971 0.678876 -v 0.037250 -0.146000 0.337300 -vn 0.655722 -0.378590 0.653221 -v 0.020183 -0.132750 0.337300 -vn 0.727972 -0.095834 0.678876 -v 0.020250 -0.132500 0.337300 -vn 0.669352 -0.088124 0.737701 -v 0.020250 -0.130500 0.337300 -vn 0.095852 0.727973 0.678872 -v 0.019750 -0.139000 0.337300 -vn -0.577350 0.577351 0.577351 -v 0.019250 -0.139000 0.337300 -vn -0.669354 0.088118 0.737699 -v 0.019250 -0.139350 0.337300 -vn -0.669352 -0.088124 0.737700 -v 0.037250 -0.130500 0.337300 -vn 0.552292 -0.318861 0.770261 -v 0.038277 -0.132550 0.337300 -vn 0.318859 -0.552280 0.770270 -v 0.038350 -0.132477 0.337300 -vn 0.088115 -0.669352 0.737701 -v 0.038450 -0.132450 0.337300 -vn 0.577350 -0.577350 0.577350 -v 0.038750 -0.132450 0.337300 -vn 0.552297 0.318869 0.770254 -v 0.025227 -0.126400 0.337300 -vn 0.088132 0.669347 0.737704 -v 0.023250 -0.144500 0.337300 -vn 0.095830 0.727972 0.678877 -v 0.025250 -0.144500 0.337300 -vn 0.577348 -0.577351 0.577351 -v 0.025750 -0.145500 0.337300 -vn 0.727974 0.095842 0.678873 -v 0.025750 -0.145000 0.337300 -vn 0.088113 -0.669354 0.737700 -v 0.025400 -0.145500 0.337300 -vn 0.655722 0.378580 0.653228 -v 0.025683 -0.144750 0.337300 -vn 0.727973 0.095834 0.678875 -v 0.020250 -0.139500 0.337300 -vn 0.655722 0.378590 0.653221 -v 0.020183 -0.139250 0.337300 -vn 0.378577 0.655718 0.653233 -v 0.020000 -0.139067 0.337300 -vn -0.669354 0.088119 0.737699 -v 0.034750 -0.144000 0.337300 -vn -0.552280 0.318867 0.770266 -v 0.034683 -0.144250 0.337300 -vn 0.251475 0.607116 0.753771 -v 0.035826 -0.141962 0.337300 -vn -0.552301 -0.318866 0.770252 -v 0.032273 -0.145600 0.337300 -vn 0.318860 -0.552276 0.770272 -v 0.025300 -0.145527 0.337300 -vn 0.378578 0.655728 0.653223 -v 0.025500 -0.144567 0.337300 -vn 0.378582 0.655722 0.653226 -v 0.038000 -0.126201 0.337300 -vn 0.134916 0.034558 0.990254 -v 0.037250 -0.126000 0.337300 -vn -0.088132 -0.669347 0.737704 -v 0.036750 -0.130000 0.337300 -vn -0.318864 -0.552287 0.770263 -v 0.030125 -0.133618 0.337300 -vn -0.528438 0.433677 0.729848 -v 0.034604 -0.129086 0.337300 -vn -0.433663 0.528442 0.729853 -v 0.032336 -0.131354 0.337300 -vn -0.088132 -0.669347 0.737704 -v 0.034250 -0.127500 0.337300 -vn -0.318869 -0.552297 0.770253 -v 0.034500 -0.127567 0.337300 -vn -0.552280 -0.318873 0.770264 -v 0.034683 -0.127750 0.337300 -vn 0.528434 -0.433688 0.729844 -v 0.022896 -0.142914 0.337300 -vn 0.433662 -0.528442 0.729854 -v 0.025164 -0.140646 0.337300 -vn 0.318865 0.552289 0.770261 -v 0.027375 -0.138382 0.337300 -vn 0.251488 -0.607132 0.753754 -v 0.025326 -0.140538 0.337300 -vn -0.000000 0.637728 0.770262 -v 0.028750 -0.138750 0.337300 -vn -0.095831 -0.727972 0.678877 -v 0.032250 -0.127500 0.337300 -vn -0.669345 0.088136 0.737705 -v 0.032300 -0.126300 0.337300 -vn -0.707107 -0.000000 0.707107 -v 0.032300 -0.126000 0.337300 -vn -0.378578 -0.655723 0.653227 -v 0.019500 -0.145799 0.337300 -vn 0.088132 0.669347 0.737704 -v 0.020750 -0.142000 0.337300 -vn 0.669354 -0.088119 0.737699 -v 0.022750 -0.128000 0.337300 -vn 0.552280 -0.318867 0.770266 -v 0.022817 -0.127750 0.337300 -vn -0.251477 -0.607116 0.753770 -v 0.021674 -0.130038 0.337300 -vn -0.727971 -0.095838 0.678876 -v 0.018750 -0.144500 0.337300 -vn 0.318869 0.552297 0.770253 -v 0.020500 -0.141933 0.337300 -vn 0.552280 0.318868 0.770266 -v 0.020317 -0.141750 0.337300 -vn 0.552290 -0.318863 0.770261 -v 0.026368 -0.134625 0.337300 -vn -0.433684 -0.528436 0.729845 -v 0.021836 -0.130146 0.337300 -vn -0.528437 -0.433673 0.729850 -v 0.024104 -0.132414 0.337300 -vn 0.251476 -0.607116 0.753770 -v 0.035826 -0.130038 0.337300 -vn -0.669353 -0.088124 0.737700 -v 0.034750 -0.128000 0.337300 -vn -0.727972 0.095831 0.678877 -v 0.037250 -0.139500 0.337300 -vn -0.669354 0.088119 0.737699 -v 0.037250 -0.141500 0.337300 -vn 0.318862 0.552278 0.770270 -v 0.038350 -0.139523 0.337300 -vn 0.727972 -0.095838 0.678875 -v 0.038750 -0.144500 0.337300 -vn 0.088116 0.669356 0.737698 -v 0.038450 -0.139550 0.337300 -vn 0.577351 0.577349 0.577351 -v 0.038750 -0.139550 0.337300 -vn 0.433682 0.528436 0.729846 -v 0.035664 -0.141854 0.337300 -vn 0.528438 0.433670 0.729851 -v 0.033396 -0.139586 0.337300 -vn -0.552289 0.318865 0.770261 -v 0.031132 -0.137375 0.337300 -vn 0.607125 0.251473 0.753764 -v 0.033288 -0.139424 0.337300 -vn -0.637727 0.000001 0.770262 -v 0.031500 -0.136000 0.337300 -vn 0.067001 -0.680321 0.729846 -v 0.036018 -0.130000 0.337300 -vn 0.577351 0.577348 0.577351 -v 0.038250 -0.139000 0.337300 -vn -0.095853 0.727975 0.678870 -v 0.037750 -0.139000 0.337300 -vn 0.669348 0.088123 0.737704 -v 0.038250 -0.139350 0.337300 -vn -0.378577 0.655718 0.653233 -v 0.037500 -0.139067 0.337300 -vn -0.088132 0.669348 0.737703 -v 0.036750 -0.142000 0.337300 -vn 0.067001 0.680319 0.729847 -v 0.036018 -0.142000 0.337300 -vn -0.680318 -0.067006 0.729848 -v 0.034750 -0.143268 0.337300 -vn -0.251478 0.607116 0.753770 -v 0.021674 -0.141962 0.337300 -vn 0.669355 0.088119 0.737698 -v 0.022750 -0.144000 0.337300 -vn 0.669355 0.088119 0.737698 -v 0.020250 -0.141500 0.337300 -vn -0.552293 0.318855 0.770262 -v 0.019223 -0.139450 0.337300 -vn -0.318858 0.552280 0.770271 -v 0.019150 -0.139523 0.337300 -vn -0.088113 0.669353 0.737701 -v 0.019050 -0.139550 0.337300 -vn -0.577350 0.577350 0.577350 -v 0.018750 -0.139550 0.337300 -vn 0.088132 -0.669348 0.737703 -v 0.020750 -0.130000 0.337300 -vn -0.067001 -0.680319 0.729847 -v 0.021482 -0.130000 0.337300 -vn 0.680318 0.067006 0.729848 -v 0.022750 -0.128732 0.337300 -vn 0.655722 0.378579 0.653228 -v 0.038549 -0.126750 0.337300 -vn 0.552294 0.318858 0.770260 -v 0.038277 -0.139450 0.337300 -vn -0.655723 0.378590 0.653220 -v 0.037317 -0.139250 0.337300 -vn -0.552280 0.318867 0.770266 -v 0.037183 -0.141750 0.337300 -vn -0.318869 0.552297 0.770254 -v 0.037000 -0.141933 0.337300 -vn 0.655721 -0.378583 0.653226 -v 0.038549 -0.145250 0.337300 -vn 0.378577 -0.655724 0.653227 -v 0.038000 -0.145799 0.337300 -vn -0.655724 0.378579 0.653225 -v 0.031817 -0.144750 0.337300 -vn -0.378576 0.655728 0.653224 -v 0.032000 -0.144567 0.337300 -vn -0.095832 0.727972 0.678876 -v 0.032250 -0.144500 0.337300 -vn -0.318864 -0.552271 0.770274 -v 0.032200 -0.145527 0.337300 -vn -0.088132 0.669348 0.737703 -v 0.034250 -0.144500 0.337300 -vn -0.318869 0.552297 0.770254 -v 0.034500 -0.144433 0.337300 -vn -0.067001 0.680321 0.729846 -v 0.021482 -0.142000 0.337300 -vn 0.095830 -0.727972 0.678876 -v 0.025250 -0.127500 0.337300 -vn 0.318863 0.552275 0.770272 -v 0.025300 -0.126473 0.337300 -vn 0.088132 -0.669348 0.737703 -v 0.023250 -0.127500 0.337300 -vn 0.318869 -0.552297 0.770254 -v 0.023000 -0.127567 0.337300 -vn 0.680317 0.067006 0.729848 -v 0.033250 -0.139232 0.337300 -vn 0.680317 -0.067006 0.729849 -v 0.033250 -0.132768 0.337300 -vn -0.552289 -0.318864 0.770261 -v 0.031132 -0.134625 0.337300 -vn 0.607125 -0.251473 0.753764 -v 0.033288 -0.132576 0.337300 -vn 0.528439 -0.433671 0.729850 -v 0.033396 -0.132414 0.337300 -vn 0.433681 -0.528435 0.729847 -v 0.035664 -0.130146 0.337300 -vn -0.607121 0.251477 0.753766 -v 0.034712 -0.128924 0.337300 -vn -0.680317 0.067006 0.729849 -v 0.034750 -0.128732 0.337300 -vn -0.655722 -0.378582 0.653227 -v 0.018951 -0.145250 0.337300 -vn 0.552292 -0.318864 0.770259 -v 0.020317 -0.130250 0.337300 -vn 0.318877 -0.552285 0.770259 -v 0.020500 -0.130067 0.337300 -vn -0.655722 0.378579 0.653228 -v 0.018951 -0.126750 0.337300 -vn -0.378582 0.655722 0.653226 -v 0.019500 -0.126201 0.337300 -vn 0.067026 -0.680308 0.729855 -v 0.025518 -0.140500 0.337300 -vn -0.067025 -0.680307 0.729856 -v 0.031982 -0.140500 0.337300 -vn -0.318865 0.552288 0.770261 -v 0.030125 -0.138382 0.337300 -vn -0.251489 -0.607131 0.753754 -v 0.032174 -0.140538 0.337300 -vn -0.433664 -0.528441 0.729853 -v 0.032336 -0.140646 0.337300 -vn -0.528433 -0.433690 0.729844 -v 0.034604 -0.142914 0.337300 -vn -0.607110 -0.251488 0.753771 -v 0.034712 -0.143076 0.337300 -vn -0.607123 -0.251475 0.753765 -v 0.024212 -0.132576 0.337300 -vn -0.680317 -0.067006 0.729848 -v 0.024250 -0.132768 0.337300 -vn 0.637728 0.000001 0.770261 -v 0.026000 -0.136000 0.337300 -vn -0.680317 0.067006 0.729849 -v 0.024250 -0.139232 0.337300 -vn 0.552289 0.318864 0.770261 -v 0.026368 -0.137375 0.337300 -vn -0.607123 0.251475 0.753765 -v 0.024212 -0.139424 0.337300 -vn -0.528438 0.433674 0.729849 -v 0.024104 -0.139586 0.337300 -vn -0.433683 0.528435 0.729846 -v 0.021836 -0.141854 0.337300 -vn 0.607112 -0.251485 0.753771 -v 0.022788 -0.143076 0.337300 -vn 0.680317 -0.067006 0.729849 -v 0.022750 -0.143268 0.337300 -vn -0.251490 0.607131 0.753754 -v 0.032174 -0.131462 0.337300 -vn -0.067026 0.680308 0.729855 -v 0.031982 -0.131500 0.337300 -vn 0.000000 -0.637728 0.770262 -v 0.028750 -0.133250 0.337300 -vn 0.067025 0.680307 0.729856 -v 0.025518 -0.131500 0.337300 -vn 0.318865 -0.552288 0.770262 -v 0.027375 -0.133618 0.337300 -vn 0.251488 0.607132 0.753754 -v 0.025326 -0.131462 0.337300 -vn 0.433661 0.528443 0.729853 -v 0.025164 -0.131354 0.337300 -vn 0.528438 0.433673 0.729850 -v 0.022896 -0.129086 0.337300 -vn 0.607123 0.251475 0.753765 -v 0.022788 -0.128924 0.337300 -vn 0.655722 -0.378580 -0.653228 -v 0.025683 -0.127250 0.248800 -vn 0.378578 -0.655728 -0.653223 -v 0.025500 -0.127433 0.248800 -vn 0.095830 -0.727972 -0.678877 -v 0.025250 -0.127500 0.248800 -vn 0.095852 -0.727973 -0.678872 -v 0.019750 -0.133000 0.248800 -vn -0.577350 -0.577351 -0.577351 -v 0.019250 -0.133000 0.248800 -vn -0.669355 -0.088118 -0.737699 -v 0.019250 -0.132650 0.248800 -vn 0.577351 -0.577348 -0.577351 -v 0.038250 -0.133000 0.248800 -vn -0.095853 -0.727975 -0.678870 -v 0.037750 -0.133000 0.248800 -vn 0.669348 -0.088123 -0.737704 -v 0.038250 -0.132650 0.248800 -vn -0.378577 -0.655718 -0.653233 -v 0.037500 -0.132933 0.248800 -vn -0.378576 -0.655728 -0.653224 -v 0.032000 -0.127433 0.248800 -vn -0.655724 -0.378579 -0.653225 -v 0.031817 -0.127250 0.248800 -vn -0.088113 0.669358 -0.737697 -v 0.032100 -0.126500 0.248800 -vn -0.727972 -0.095837 -0.678876 -v 0.031750 -0.127000 0.248800 -vn -0.577351 0.577350 -0.577351 -v 0.031750 -0.126500 0.248800 -vn 0.088113 0.669354 -0.737700 -v 0.025400 -0.126500 0.248800 -vn 0.577348 0.577351 -0.577351 -v 0.025750 -0.126500 0.248800 -vn 0.727974 -0.095842 -0.678873 -v 0.025750 -0.127000 0.248800 -vn 0.378577 -0.655718 -0.653233 -v 0.020000 -0.132933 0.248800 -vn 0.655722 -0.378590 -0.653221 -v 0.020183 -0.132750 0.248800 -vn 0.727973 -0.095834 -0.678875 -v 0.020250 -0.132500 0.248800 -vn 0.669341 -0.088135 -0.737709 -v 0.025200 -0.145700 0.248800 -vn 0.577350 -0.577350 -0.577350 -v 0.025200 -0.146000 0.248800 -vn -0.095837 -0.727971 -0.678876 -v 0.020250 -0.146000 0.248800 -vn -0.727971 0.095840 -0.678876 -v 0.018750 -0.127500 0.248800 -vn 0.318877 -0.552285 -0.770259 -v 0.020500 -0.130067 0.248800 -vn 0.552292 -0.318865 -0.770259 -v 0.020317 -0.130250 0.248800 -vn -0.727973 0.095837 -0.678875 -v 0.031750 -0.145000 0.248800 -vn -0.655724 0.378580 -0.653225 -v 0.031817 -0.144750 0.248800 -vn -0.378575 0.655728 -0.653224 -v 0.032000 -0.144567 0.248800 -vn -0.655723 -0.378590 -0.653220 -v 0.037317 -0.132750 0.248800 -vn -0.727972 -0.095831 -0.678877 -v 0.037250 -0.132500 0.248800 -vn 0.552294 -0.318858 -0.770260 -v 0.038277 -0.132550 0.248800 -vn -0.669351 -0.088124 -0.737701 -v 0.037250 -0.130500 0.248800 -vn 0.318862 -0.552278 -0.770270 -v 0.038350 -0.132477 0.248800 -vn 0.727973 0.095840 -0.678874 -v 0.038750 -0.127500 0.248800 -vn 0.088116 -0.669356 -0.737698 -v 0.038450 -0.132450 0.248800 -vn 0.577351 -0.577348 -0.577351 -v 0.038750 -0.132450 0.248800 -vn 0.318869 -0.552297 -0.770254 -v 0.023000 -0.127567 0.248800 -vn 0.552280 -0.318868 -0.770266 -v 0.022817 -0.127750 0.248800 -vn -0.095837 0.727972 -0.678876 -v 0.020250 -0.126000 0.248800 -vn -0.577351 0.577348 -0.577351 -v 0.019250 -0.139000 0.248800 -vn 0.095852 0.727975 -0.678870 -v 0.019750 -0.139000 0.248800 -vn -0.669351 0.088117 -0.737702 -v 0.019250 -0.139350 0.248800 -vn 0.378578 0.655718 -0.653233 -v 0.020000 -0.139067 0.248800 -vn -0.552294 0.318852 -0.770263 -v 0.019223 -0.139450 0.248800 -vn 0.669352 -0.088124 -0.737700 -v 0.020250 -0.130500 0.248800 -vn -0.552293 -0.318854 -0.770263 -v 0.019223 -0.132550 0.248800 -vn -0.318858 -0.552280 -0.770271 -v 0.019150 -0.132477 0.248800 -vn -0.088113 -0.669353 -0.737701 -v 0.019050 -0.132450 0.248800 -vn -0.577350 -0.577350 -0.577350 -v 0.018750 -0.132450 0.248800 -vn 0.088132 -0.669347 -0.737704 -v 0.023250 -0.127500 0.248800 -vn 0.727972 0.095842 -0.678875 -v 0.025750 -0.145000 0.248800 -vn 0.577351 -0.577350 -0.577351 -v 0.025750 -0.145500 0.248800 -vn 0.088114 -0.669357 -0.737697 -v 0.025400 -0.145500 0.248800 -vn -0.095852 0.727973 -0.678872 -v 0.037750 -0.139000 0.248800 -vn 0.577350 0.577351 -0.577351 -v 0.038250 -0.139000 0.248800 -vn 0.669352 0.088124 -0.737701 -v 0.038250 -0.139350 0.248800 -vn 0.552297 -0.318869 -0.770254 -v 0.025227 -0.145600 0.248800 -vn 0.318860 0.552276 -0.770272 -v 0.025300 -0.126473 0.248800 -vn 0.552295 0.318871 -0.770254 -v 0.025227 -0.126400 0.248800 -vn 0.669345 0.088136 -0.737705 -v 0.025200 -0.126300 0.248800 -vn 0.577349 0.577351 -0.577351 -v 0.025200 -0.126000 0.248800 -vn -0.088132 0.669347 -0.737704 -v 0.034250 -0.144500 0.248800 -vn -0.318869 0.552297 -0.770253 -v 0.034500 -0.144433 0.248800 -vn 0.095837 -0.727973 -0.678875 -v 0.037250 -0.146000 0.248800 -vn -0.552280 0.318868 -0.770266 -v 0.034683 -0.144250 0.248800 -vn -0.727972 0.095831 -0.678876 -v 0.037250 -0.139500 0.248800 -vn -0.655723 0.378590 -0.653220 -v 0.037317 -0.139250 0.248800 -vn -0.378576 0.655718 -0.653233 -v 0.037500 -0.139067 0.248800 -vn -0.577348 -0.577351 -0.577351 -v 0.031750 -0.145500 0.248800 -vn -0.088112 -0.669354 -0.737700 -v 0.032100 -0.145500 0.248800 -vn -0.318861 -0.552272 -0.770274 -v 0.032200 -0.145527 0.248800 -vn -0.552299 -0.318869 -0.770252 -v 0.032273 -0.145600 0.248800 -vn -0.095831 0.727972 -0.678877 -v 0.032250 -0.144500 0.248800 -vn -0.669345 -0.088136 -0.737705 -v 0.032300 -0.145700 0.248800 -vn -0.577349 -0.577351 -0.577351 -v 0.032300 -0.146000 0.248800 -vn 0.669354 0.088119 -0.737699 -v 0.022750 -0.144000 0.248800 -vn 0.552280 0.318867 -0.770266 -v 0.022817 -0.144250 0.248800 -vn -0.251477 0.607116 -0.753770 -v 0.021674 -0.141962 0.248800 -vn -0.528434 -0.433690 -0.729843 -v 0.034604 -0.142914 0.248800 -vn -0.433664 -0.528441 -0.729853 -v 0.032336 -0.140646 0.248800 -vn -0.318864 0.552288 -0.770262 -v 0.030125 -0.138382 0.248800 -vn -0.251490 -0.607131 -0.753754 -v 0.032174 -0.140538 0.248800 -vn 0.000000 0.637728 -0.770262 -v 0.028750 -0.138750 0.248800 -vn -0.669341 0.088135 -0.737709 -v 0.032300 -0.126300 0.248800 -vn -0.577350 0.577350 -0.577350 -v 0.032300 -0.126000 0.248800 -vn 0.095837 0.727971 -0.678876 -v 0.037250 -0.126000 0.248800 -vn -0.552289 -0.318864 -0.770262 -v 0.031132 -0.134625 0.248800 -vn 0.433682 -0.528436 -0.729846 -v 0.035664 -0.130146 0.248800 -vn 0.528438 -0.433670 -0.729851 -v 0.033396 -0.132414 0.248800 -vn -0.669352 -0.088124 -0.737701 -v 0.034750 -0.128000 0.248800 -vn -0.552280 -0.318872 -0.770265 -v 0.034683 -0.127750 0.248800 -vn 0.251475 -0.607116 -0.753770 -v 0.035826 -0.130038 0.248800 -vn -0.378583 0.655722 -0.653226 -v 0.019500 -0.126201 0.248800 -vn 0.088132 -0.669347 -0.737704 -v 0.020750 -0.130000 0.248800 -vn 0.251476 0.607116 -0.753770 -v 0.035826 -0.141962 0.248800 -vn -0.669355 0.088119 -0.737698 -v 0.034750 -0.144000 0.248800 -vn -0.669355 0.088119 -0.737698 -v 0.037250 -0.141500 0.248800 -vn 0.552293 0.318861 -0.770260 -v 0.038277 -0.139450 0.248800 -vn -0.552280 0.318868 -0.770266 -v 0.037183 -0.141750 0.248800 -vn 0.318859 0.552280 -0.770270 -v 0.038350 -0.139523 0.248800 -vn 0.727972 -0.095838 -0.678876 -v 0.038750 -0.144500 0.248800 -vn 0.088115 0.669352 -0.737701 -v 0.038450 -0.139550 0.248800 -vn 0.577350 0.577350 -0.577350 -v 0.038750 -0.139550 0.248800 -vn -0.577351 0.577349 -0.577351 -v 0.018750 -0.139550 0.248800 -vn -0.088114 0.669357 -0.737697 -v 0.019050 -0.139550 0.248800 -vn -0.727972 -0.095838 -0.678876 -v 0.018750 -0.144500 0.248800 -vn -0.318860 0.552278 -0.770271 -v 0.019150 -0.139523 0.248800 -vn 0.067001 0.680321 -0.729846 -v 0.036018 -0.142000 0.248800 -vn -0.088132 0.669347 -0.737704 -v 0.036750 -0.142000 0.248800 -vn 0.378577 -0.655723 -0.653228 -v 0.038000 -0.145799 0.248800 -vn 0.655722 -0.378582 -0.653226 -v 0.038549 -0.145250 0.248800 -vn -0.318869 0.552297 -0.770253 -v 0.037000 -0.141933 0.248800 -vn -0.088132 -0.669349 -0.737703 -v 0.036750 -0.130000 0.248800 -vn 0.067001 -0.680319 -0.729847 -v 0.036018 -0.130000 0.248800 -vn -0.680318 0.067006 -0.729848 -v 0.034750 -0.128732 0.248800 -vn -0.552301 0.318866 -0.770252 -v 0.032273 -0.126400 0.248800 -vn 0.655722 0.378590 -0.653221 -v 0.020183 -0.139250 0.248800 -vn 0.727972 0.095834 -0.678876 -v 0.020250 -0.139500 0.248800 -vn 0.669354 0.088119 -0.737699 -v 0.020250 -0.141500 0.248800 -vn -0.095832 -0.727972 -0.678876 -v 0.032250 -0.127500 0.248800 -vn -0.318864 0.552271 -0.770274 -v 0.032200 -0.126473 0.248800 -vn -0.088132 -0.669348 -0.737703 -v 0.034250 -0.127500 0.248800 -vn -0.318869 -0.552297 -0.770254 -v 0.034500 -0.127567 0.248800 -vn 0.318864 -0.552287 -0.770263 -v 0.027375 -0.133618 0.248800 -vn 0.528439 0.433674 -0.729849 -v 0.022896 -0.129086 0.248800 -vn 0.433661 0.528442 -0.729854 -v 0.025164 -0.131354 0.248800 -vn 0.607125 -0.251473 -0.753764 -v 0.033288 -0.132576 0.248800 -vn 0.680317 -0.067006 -0.729848 -v 0.033250 -0.132768 0.248800 -vn -0.637728 0.000001 -0.770262 -v 0.031500 -0.136000 0.248800 -vn 0.680317 0.067006 -0.729849 -v 0.033250 -0.139232 0.248800 -vn -0.552289 0.318865 -0.770261 -v 0.031132 -0.137375 0.248800 -vn 0.607125 0.251473 -0.753764 -v 0.033288 -0.139424 0.248800 -vn 0.528439 0.433671 -0.729850 -v 0.033396 -0.139586 0.248800 -vn 0.433681 0.528435 -0.729847 -v 0.035664 -0.141854 0.248800 -vn -0.607110 -0.251487 -0.753772 -v 0.034712 -0.143076 0.248800 -vn -0.680317 -0.067006 -0.729849 -v 0.034750 -0.143268 0.248800 -vn -0.552292 -0.318864 -0.770259 -v 0.037183 -0.130250 0.248800 -vn -0.318877 -0.552285 -0.770259 -v 0.037000 -0.130067 0.248800 -vn 0.655722 0.378579 -0.653228 -v 0.038549 -0.126750 0.248800 -vn 0.378582 0.655722 -0.653226 -v 0.038000 -0.126201 0.248800 -vn -0.251478 -0.607116 -0.753770 -v 0.021674 -0.130038 0.248800 -vn 0.669355 -0.088119 -0.737698 -v 0.022750 -0.128000 0.248800 -vn -0.433684 0.528436 -0.729845 -v 0.021836 -0.141854 0.248800 -vn -0.528437 0.433673 -0.729850 -v 0.024104 -0.139586 0.248800 -vn 0.552289 0.318864 -0.770261 -v 0.026368 -0.137375 0.248800 -vn -0.607123 0.251475 -0.753765 -v 0.024212 -0.139424 0.248800 -vn 0.637728 0.000001 -0.770262 -v 0.026000 -0.136000 0.248800 -vn 0.251488 0.607132 -0.753754 -v 0.025326 -0.131462 0.248800 -vn 0.067026 0.680308 -0.729855 -v 0.025518 -0.131500 0.248800 -vn -0.000000 -0.637728 -0.770262 -v 0.028750 -0.133250 0.248800 -vn -0.067025 0.680307 -0.729856 -v 0.031982 -0.131500 0.248800 -vn -0.318865 -0.552288 -0.770261 -v 0.030125 -0.133618 0.248800 -vn -0.251489 0.607131 -0.753754 -v 0.032174 -0.131462 0.248800 -vn -0.433663 0.528442 -0.729853 -v 0.032336 -0.131354 0.248800 -vn -0.528437 0.433676 -0.729849 -v 0.034604 -0.129086 0.248800 -vn -0.607121 0.251477 -0.753766 -v 0.034712 -0.128924 0.248800 -vn -0.067001 -0.680321 -0.729846 -v 0.021482 -0.130000 0.248800 -vn 0.088132 0.669348 -0.737703 -v 0.020750 -0.142000 0.248800 -vn -0.067001 0.680319 -0.729847 -v 0.021482 -0.142000 0.248800 -vn 0.680318 -0.067006 -0.729848 -v 0.022750 -0.143268 0.248800 -vn -0.655722 0.378578 -0.653228 -v 0.018951 -0.126750 0.248800 -vn 0.552280 0.318867 -0.770266 -v 0.020317 -0.141750 0.248800 -vn 0.318869 0.552297 -0.770254 -v 0.020500 -0.141933 0.248800 -vn -0.655721 -0.378582 -0.653227 -v 0.018951 -0.145250 0.248800 -vn -0.378577 -0.655724 -0.653227 -v 0.019500 -0.145799 0.248800 -vn 0.655722 0.378579 -0.653228 -v 0.025683 -0.144750 0.248800 -vn 0.378578 0.655727 -0.653223 -v 0.025500 -0.144567 0.248800 -vn 0.095830 0.727972 -0.678876 -v 0.025250 -0.144500 0.248800 -vn 0.318863 -0.552275 -0.770272 -v 0.025300 -0.145527 0.248800 -vn 0.088132 0.669348 -0.737703 -v 0.023250 -0.144500 0.248800 -vn 0.318869 0.552297 -0.770253 -v 0.023000 -0.144433 0.248800 -vn -0.680317 0.067006 -0.729848 -v 0.024250 -0.139232 0.248800 -vn -0.680317 -0.067006 -0.729849 -v 0.024250 -0.132768 0.248800 -vn 0.552289 -0.318864 -0.770261 -v 0.026368 -0.134625 0.248800 -vn -0.607123 -0.251475 -0.753765 -v 0.024212 -0.132576 0.248800 -vn -0.528438 -0.433674 -0.729849 -v 0.024104 -0.132414 0.248800 -vn -0.433683 -0.528435 -0.729846 -v 0.021836 -0.130146 0.248800 -vn 0.607123 0.251475 -0.753765 -v 0.022788 -0.128924 0.248800 -vn 0.680317 0.067006 -0.729849 -v 0.022750 -0.128732 0.248800 -vn -0.067026 -0.680308 -0.729855 -v 0.031982 -0.140500 0.248800 -vn 0.067025 -0.680307 -0.729856 -v 0.025518 -0.140500 0.248800 -vn 0.318865 0.552288 -0.770262 -v 0.027375 -0.138382 0.248800 -vn 0.251488 -0.607132 -0.753754 -v 0.025326 -0.140538 0.248800 -vn 0.433662 -0.528442 -0.729854 -v 0.025164 -0.140646 0.248800 -vn 0.528434 -0.433687 -0.729845 -v 0.022896 -0.142914 0.248800 -vn 0.607112 -0.251486 -0.753771 -v 0.022788 -0.143076 0.248800 -vn -0.727973 -0.095837 0.678875 -v 0.031750 0.145000 0.337300 -vn -0.655724 -0.378580 0.653225 -v 0.031817 0.144750 0.337300 -vn -0.378575 -0.655728 0.653224 -v 0.032000 0.144567 0.337300 -vn -0.727972 0.095837 0.678876 -v 0.031750 0.127000 0.337300 -vn -0.577351 -0.577350 0.577351 -v 0.031750 0.126500 0.337300 -vn -0.088113 -0.669358 0.737697 -v 0.032100 0.126500 0.337300 -vn -0.577351 -0.577348 0.577351 -v 0.019250 0.139000 0.337300 -vn 0.095852 -0.727975 0.678870 -v 0.019750 0.139000 0.337300 -vn -0.669351 -0.088117 0.737702 -v 0.019250 0.139350 0.337300 -vn 0.378578 -0.655718 0.653233 -v 0.020000 0.139067 0.337300 -vn -0.552294 -0.318852 0.770263 -v 0.019223 0.139450 0.337300 -vn 0.378578 -0.655727 0.653223 -v 0.025500 0.144567 0.337300 -vn 0.655722 -0.378579 0.653228 -v 0.025683 0.144750 0.337300 -vn 0.088114 0.669357 0.737697 -v 0.025400 0.145500 0.337300 -vn 0.727972 -0.095842 0.678875 -v 0.025750 0.145000 0.337300 -vn 0.577351 0.577350 0.577351 -v 0.025750 0.145500 0.337300 -vn -0.095852 -0.727974 0.678872 -v 0.037750 0.139000 0.337300 -vn 0.577350 -0.577351 0.577351 -v 0.038250 0.139000 0.337300 -vn 0.669352 -0.088124 0.737701 -v 0.038250 0.139350 0.337300 -vn 0.669342 0.088135 0.737709 -v 0.025200 0.145700 0.337300 -vn 0.577350 0.577350 0.577350 -v 0.025200 0.146000 0.337300 -vn -0.095837 0.727971 0.678876 -v 0.020250 0.146000 0.337300 -vn -0.577348 0.577351 0.577351 -v 0.031750 0.145500 0.337300 -vn -0.088112 0.669354 0.737700 -v 0.032100 0.145500 0.337300 -vn -0.318861 0.552272 0.770274 -v 0.032200 0.145527 0.337300 -vn -0.552299 0.318869 0.770252 -v 0.032273 0.145600 0.337300 -vn 0.318869 0.552297 0.770254 -v 0.023000 0.127567 0.337300 -vn 0.552280 0.318868 0.770266 -v 0.022817 0.127750 0.337300 -vn -0.134916 -0.034558 0.990254 -v 0.020250 0.126000 0.337300 -vn 0.727972 0.095838 0.678876 -v 0.038750 0.144500 0.337300 -vn -0.318869 -0.552297 0.770253 -v 0.037000 0.141933 0.337300 -vn -0.552280 -0.318868 0.770266 -v 0.037183 0.141750 0.337300 -vn -0.378576 -0.655719 0.653233 -v 0.037500 0.139067 0.337300 -vn -0.655723 -0.378590 0.653220 -v 0.037317 0.139250 0.337300 -vn -0.727972 -0.095831 0.678876 -v 0.037250 0.139500 0.337300 -vn -0.577351 -0.577349 0.577351 -v 0.018750 0.139550 0.337300 -vn -0.088114 -0.669357 0.737697 -v 0.019050 0.139550 0.337300 -vn -0.727972 0.095838 0.678876 -v 0.018750 0.144500 0.337300 -vn -0.318860 -0.552278 0.770271 -v 0.019150 0.139523 0.337300 -vn 0.552295 -0.318871 0.770254 -v 0.025227 0.126400 0.337300 -vn 0.669345 -0.088136 0.737705 -v 0.025200 0.126300 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.025200 0.126000 0.337300 -vn -0.669342 -0.088135 0.737709 -v 0.032300 0.126300 0.337300 -vn -0.707107 0.000000 0.707107 -v 0.032300 0.126000 0.337300 -vn 0.134916 -0.034558 0.990254 -v 0.037250 0.126000 0.337300 -vn 0.655722 -0.378590 0.653221 -v 0.020183 0.139250 0.337300 -vn 0.727972 -0.095834 0.678876 -v 0.020250 0.139500 0.337300 -vn 0.669354 -0.088119 0.737699 -v 0.020250 0.141500 0.337300 -vn 0.095852 0.727973 0.678872 -v 0.019750 0.133000 0.337300 -vn -0.577350 0.577351 0.577351 -v 0.019250 0.133000 0.337300 -vn -0.669354 0.088118 0.737699 -v 0.019250 0.132650 0.337300 -vn -0.669355 -0.088119 0.737698 -v 0.037250 0.141500 0.337300 -vn 0.552293 -0.318861 0.770260 -v 0.038277 0.139450 0.337300 -vn 0.318859 -0.552280 0.770270 -v 0.038350 0.139523 0.337300 -vn 0.088115 -0.669352 0.737701 -v 0.038450 0.139550 0.337300 -vn 0.577350 -0.577350 0.577350 -v 0.038750 0.139550 0.337300 -vn 0.552297 0.318869 0.770254 -v 0.025227 0.145600 0.337300 -vn 0.088132 0.669347 0.737704 -v 0.023250 0.127500 0.337300 -vn 0.095830 0.727972 0.678877 -v 0.025250 0.127500 0.337300 -vn 0.577348 -0.577351 0.577351 -v 0.025750 0.126500 0.337300 -vn 0.727974 0.095842 0.678873 -v 0.025750 0.127000 0.337300 -vn 0.088113 -0.669354 0.737700 -v 0.025400 0.126500 0.337300 -vn 0.655722 0.378580 0.653228 -v 0.025683 0.127250 0.337300 -vn 0.727973 0.095834 0.678875 -v 0.020250 0.132500 0.337300 -vn 0.655722 0.378590 0.653221 -v 0.020183 0.132750 0.337300 -vn 0.378577 0.655718 0.653233 -v 0.020000 0.132933 0.337300 -vn -0.669357 0.088115 0.737698 -v 0.034750 0.128000 0.337300 -vn -0.552281 0.318862 0.770268 -v 0.034683 0.127750 0.337300 -vn 0.251475 0.607117 0.753770 -v 0.035826 0.130038 0.337300 -vn -0.552301 -0.318866 0.770252 -v 0.032273 0.126400 0.337300 -vn 0.318860 -0.552276 0.770272 -v 0.025300 0.126473 0.337300 -vn 0.378578 0.655728 0.653223 -v 0.025500 0.127433 0.337300 -vn 0.378577 0.655723 0.653227 -v 0.038000 0.145799 0.337300 -vn 0.095837 0.727973 0.678875 -v 0.037250 0.146000 0.337300 -vn -0.088132 -0.669347 0.737704 -v 0.036750 0.142000 0.337300 -vn -0.318864 -0.552287 0.770263 -v 0.030125 0.138382 0.337300 -vn -0.528432 0.433689 0.729845 -v 0.034604 0.142914 0.337300 -vn -0.433664 0.528442 0.729853 -v 0.032336 0.140646 0.337300 -vn -0.088132 -0.669347 0.737704 -v 0.034250 0.144500 0.337300 -vn -0.318869 -0.552297 0.770253 -v 0.034500 0.144433 0.337300 -vn -0.552280 -0.318868 0.770266 -v 0.034683 0.144250 0.337300 -vn 0.528439 -0.433674 0.729849 -v 0.022896 0.129086 0.337300 -vn 0.433661 -0.528442 0.729854 -v 0.025164 0.131354 0.337300 -vn 0.318864 0.552287 0.770263 -v 0.027375 0.133618 0.337300 -vn 0.251488 -0.607132 0.753754 -v 0.025326 0.131462 0.337300 -vn -0.000000 0.637728 0.770262 -v 0.028750 0.133250 0.337300 -vn -0.095831 -0.727972 0.678877 -v 0.032250 0.144500 0.337300 -vn -0.669345 0.088136 0.737705 -v 0.032300 0.145700 0.337300 -vn -0.577349 0.577351 0.577351 -v 0.032300 0.146000 0.337300 -vn -0.378583 -0.655722 0.653226 -v 0.019500 0.126201 0.337300 -vn 0.088132 0.669347 0.737704 -v 0.020750 0.130000 0.337300 -vn 0.669354 -0.088119 0.737699 -v 0.022750 0.144000 0.337300 -vn 0.552280 -0.318867 0.770266 -v 0.022817 0.144250 0.337300 -vn -0.251477 -0.607116 0.753770 -v 0.021674 0.141962 0.337300 -vn -0.727971 -0.095840 0.678876 -v 0.018750 0.127500 0.337300 -vn 0.318877 0.552285 0.770259 -v 0.020500 0.130067 0.337300 -vn 0.552292 0.318865 0.770259 -v 0.020317 0.130250 0.337300 -vn 0.552290 -0.318864 0.770261 -v 0.026368 0.137375 0.337300 -vn -0.433684 -0.528436 0.729845 -v 0.021836 0.141854 0.337300 -vn -0.528437 -0.433673 0.729850 -v 0.024104 0.139586 0.337300 -vn 0.251476 -0.607116 0.753770 -v 0.035826 0.141962 0.337300 -vn -0.669355 -0.088119 0.737698 -v 0.034750 0.144000 0.337300 -vn -0.727972 0.095831 0.678877 -v 0.037250 0.132500 0.337300 -vn -0.669352 0.088124 0.737701 -v 0.037250 0.130500 0.337300 -vn 0.318862 0.552278 0.770270 -v 0.038350 0.132477 0.337300 -vn 0.727972 -0.095840 0.678875 -v 0.038750 0.127500 0.337300 -vn 0.088116 0.669356 0.737698 -v 0.038450 0.132450 0.337300 -vn 0.577351 0.577349 0.577351 -v 0.038750 0.132450 0.337300 -vn 0.433682 0.528436 0.729846 -v 0.035664 0.130146 0.337300 -vn 0.528438 0.433670 0.729851 -v 0.033396 0.132414 0.337300 -vn -0.552288 0.318862 0.770263 -v 0.031132 0.134625 0.337300 -vn 0.607125 0.251473 0.753764 -v 0.033288 0.132576 0.337300 -vn -0.637728 -0.000001 0.770262 -v 0.031500 0.136000 0.337300 -vn 0.067001 -0.680321 0.729846 -v 0.036018 0.142000 0.337300 -vn 0.577351 0.577348 0.577351 -v 0.038250 0.133000 0.337300 -vn -0.095853 0.727975 0.678870 -v 0.037750 0.133000 0.337300 -vn 0.669348 0.088123 0.737704 -v 0.038250 0.132650 0.337300 -vn -0.378577 0.655718 0.653233 -v 0.037500 0.132933 0.337300 -vn -0.088132 0.669349 0.737703 -v 0.036750 0.130000 0.337300 -vn 0.067001 0.680319 0.729847 -v 0.036018 0.130000 0.337300 -vn -0.680318 -0.067006 0.729848 -v 0.034750 0.128732 0.337300 -vn -0.251478 0.607116 0.753770 -v 0.021674 0.130038 0.337300 -vn 0.669355 0.088119 0.737698 -v 0.022750 0.128000 0.337300 -vn 0.669352 0.088124 0.737700 -v 0.020250 0.130500 0.337300 -vn -0.552293 0.318854 0.770263 -v 0.019223 0.132550 0.337300 -vn -0.318858 0.552280 0.770271 -v 0.019150 0.132477 0.337300 -vn -0.088113 0.669353 0.737701 -v 0.019050 0.132450 0.337300 -vn -0.577350 0.577350 0.577350 -v 0.018750 0.132450 0.337300 -vn 0.088132 -0.669348 0.737703 -v 0.020750 0.142000 0.337300 -vn -0.067001 -0.680319 0.729847 -v 0.021482 0.142000 0.337300 -vn 0.680318 0.067006 0.729848 -v 0.022750 0.143268 0.337300 -vn 0.655722 0.378582 0.653226 -v 0.038549 0.145250 0.337300 -vn 0.552294 0.318858 0.770260 -v 0.038277 0.132550 0.337300 -vn -0.655723 0.378590 0.653220 -v 0.037317 0.132750 0.337300 -vn -0.552292 0.318864 0.770259 -v 0.037183 0.130250 0.337300 -vn -0.318877 0.552285 0.770259 -v 0.037000 0.130067 0.337300 -vn 0.655722 -0.378579 0.653228 -v 0.038549 0.126750 0.337300 -vn 0.378582 -0.655722 0.653226 -v 0.038000 0.126201 0.337300 -vn -0.655724 0.378579 0.653225 -v 0.031817 0.127250 0.337300 -vn -0.378576 0.655728 0.653224 -v 0.032000 0.127433 0.337300 -vn -0.095832 0.727972 0.678876 -v 0.032250 0.127500 0.337300 -vn -0.318864 -0.552271 0.770274 -v 0.032200 0.126473 0.337300 -vn -0.088132 0.669348 0.737703 -v 0.034250 0.127500 0.337300 -vn -0.318869 0.552297 0.770254 -v 0.034500 0.127567 0.337300 -vn -0.067001 0.680321 0.729846 -v 0.021482 0.130000 0.337300 -vn 0.095830 -0.727972 0.678876 -v 0.025250 0.144500 0.337300 -vn 0.318863 0.552275 0.770272 -v 0.025300 0.145527 0.337300 -vn 0.088132 -0.669348 0.737703 -v 0.023250 0.144500 0.337300 -vn 0.318869 -0.552297 0.770254 -v 0.023000 0.144433 0.337300 -vn 0.680317 0.067006 0.729848 -v 0.033250 0.132768 0.337300 -vn 0.680317 -0.067006 0.729849 -v 0.033250 0.139232 0.337300 -vn -0.552289 -0.318864 0.770261 -v 0.031132 0.137375 0.337300 -vn 0.607125 -0.251473 0.753764 -v 0.033288 0.139424 0.337300 -vn 0.528439 -0.433671 0.729850 -v 0.033396 0.139586 0.337300 -vn 0.433681 -0.528435 0.729847 -v 0.035664 0.141854 0.337300 -vn -0.607110 0.251487 0.753772 -v 0.034712 0.143076 0.337300 -vn -0.680317 0.067006 0.729849 -v 0.034750 0.143268 0.337300 -vn -0.655722 -0.378578 0.653228 -v 0.018951 0.126750 0.337300 -vn 0.552280 -0.318867 0.770266 -v 0.020317 0.141750 0.337300 -vn 0.318869 -0.552297 0.770254 -v 0.020500 0.141933 0.337300 -vn -0.655721 0.378582 0.653227 -v 0.018951 0.145250 0.337300 -vn -0.378577 0.655724 0.653227 -v 0.019500 0.145799 0.337300 -vn 0.067026 -0.680308 0.729855 -v 0.025518 0.131500 0.337300 -vn -0.067025 -0.680307 0.729856 -v 0.031982 0.131500 0.337300 -vn -0.318865 0.552288 0.770261 -v 0.030125 0.133618 0.337300 -vn -0.251489 -0.607131 0.753754 -v 0.032174 0.131462 0.337300 -vn -0.433663 -0.528442 0.729853 -v 0.032336 0.131354 0.337300 -vn -0.528437 -0.433676 0.729849 -v 0.034604 0.129086 0.337300 -vn -0.607121 -0.251477 0.753766 -v 0.034712 0.128924 0.337300 -vn -0.607123 -0.251475 0.753765 -v 0.024212 0.139424 0.337300 -vn -0.680317 -0.067006 0.729848 -v 0.024250 0.139232 0.337300 -vn 0.637728 -0.000001 0.770261 -v 0.026000 0.136000 0.337300 -vn -0.680317 0.067006 0.729849 -v 0.024250 0.132768 0.337300 -vn 0.552289 0.318864 0.770261 -v 0.026368 0.134625 0.337300 -vn -0.607123 0.251475 0.753765 -v 0.024212 0.132576 0.337300 -vn -0.528438 0.433674 0.729849 -v 0.024104 0.132414 0.337300 -vn -0.433683 0.528435 0.729846 -v 0.021836 0.130146 0.337300 -vn 0.607123 -0.251475 0.753765 -v 0.022788 0.128924 0.337300 -vn 0.680317 -0.067006 0.729849 -v 0.022750 0.128732 0.337300 -vn -0.251490 0.607131 0.753754 -v 0.032174 0.140538 0.337300 -vn -0.067026 0.680308 0.729855 -v 0.031982 0.140500 0.337300 -vn 0.000000 -0.637728 0.770262 -v 0.028750 0.138750 0.337300 -vn 0.067025 0.680307 0.729856 -v 0.025518 0.140500 0.337300 -vn 0.318865 -0.552288 0.770262 -v 0.027375 0.138382 0.337300 -vn 0.251488 0.607132 0.753754 -v 0.025326 0.140538 0.337300 -vn 0.433662 0.528442 0.729854 -v 0.025164 0.140646 0.337300 -vn 0.528434 0.433687 0.729845 -v 0.022896 0.142914 0.337300 -vn 0.607112 0.251486 0.753771 -v 0.022788 0.143076 0.337300 -vn 0.655722 -0.378580 -0.653228 -v 0.025683 0.144750 0.248800 -vn 0.378578 -0.655728 -0.653223 -v 0.025500 0.144567 0.248800 -vn 0.095830 -0.727972 -0.678877 -v 0.025250 0.144500 0.248800 -vn 0.095852 -0.727973 -0.678872 -v 0.019750 0.139000 0.248800 -vn -0.577350 -0.577351 -0.577351 -v 0.019250 0.139000 0.248800 -vn -0.669355 -0.088118 -0.737699 -v 0.019250 0.139350 0.248800 -vn 0.577351 -0.577348 -0.577351 -v 0.038250 0.139000 0.248800 -vn -0.095853 -0.727975 -0.678870 -v 0.037750 0.139000 0.248800 -vn 0.669348 -0.088123 -0.737704 -v 0.038250 0.139350 0.248800 -vn -0.378577 -0.655718 -0.653233 -v 0.037500 0.139067 0.248800 -vn -0.378576 -0.655728 -0.653224 -v 0.032000 0.144567 0.248800 -vn -0.655724 -0.378579 -0.653225 -v 0.031817 0.144750 0.248800 -vn -0.088113 0.669358 -0.737697 -v 0.032100 0.145500 0.248800 -vn -0.727972 -0.095837 -0.678876 -v 0.031750 0.145000 0.248800 -vn -0.577351 0.577350 -0.577351 -v 0.031750 0.145500 0.248800 -vn 0.088113 0.669354 -0.737700 -v 0.025400 0.145500 0.248800 -vn 0.577348 0.577351 -0.577351 -v 0.025750 0.145500 0.248800 -vn 0.727974 -0.095842 -0.678873 -v 0.025750 0.145000 0.248800 -vn 0.378577 -0.655718 -0.653233 -v 0.020000 0.139067 0.248800 -vn 0.655722 -0.378590 -0.653221 -v 0.020183 0.139250 0.248800 -vn 0.727973 -0.095834 -0.678875 -v 0.020250 0.139500 0.248800 -vn 0.669341 -0.088135 -0.737709 -v 0.025200 0.126300 0.248800 -vn 0.577350 -0.577350 -0.577350 -v 0.025200 0.126000 0.248800 -vn -0.095837 -0.727971 -0.678876 -v 0.020250 0.126000 0.248800 -vn -0.727971 0.095838 -0.678876 -v 0.018750 0.144500 0.248800 -vn 0.318869 -0.552297 -0.770253 -v 0.020500 0.141933 0.248800 -vn 0.552280 -0.318868 -0.770266 -v 0.020317 0.141750 0.248800 -vn -0.727973 0.095837 -0.678875 -v 0.031750 0.127000 0.248800 -vn -0.655724 0.378580 -0.653225 -v 0.031817 0.127250 0.248800 -vn -0.378575 0.655728 -0.653224 -v 0.032000 0.127433 0.248800 -vn -0.655723 -0.378590 -0.653220 -v 0.037317 0.139250 0.248800 -vn -0.727972 -0.095831 -0.678877 -v 0.037250 0.139500 0.248800 -vn 0.552294 -0.318858 -0.770260 -v 0.038277 0.139450 0.248800 -vn -0.669354 -0.088119 -0.737699 -v 0.037250 0.141500 0.248800 -vn 0.318862 -0.552278 -0.770270 -v 0.038350 0.139523 0.248800 -vn 0.727972 0.095838 -0.678875 -v 0.038750 0.144500 0.248800 -vn 0.088116 -0.669356 -0.737698 -v 0.038450 0.139550 0.248800 -vn 0.577351 -0.577349 -0.577351 -v 0.038750 0.139550 0.248800 -vn 0.318869 -0.552297 -0.770254 -v 0.023000 0.144433 0.248800 -vn 0.552280 -0.318868 -0.770266 -v 0.022817 0.144250 0.248800 -vn -0.095837 0.727972 -0.678876 -v 0.020250 0.146000 0.248800 -vn -0.577351 0.577348 -0.577351 -v 0.019250 0.133000 0.248800 -vn 0.095852 0.727975 -0.678870 -v 0.019750 0.133000 0.248800 -vn -0.669351 0.088117 -0.737702 -v 0.019250 0.132650 0.248800 -vn 0.378578 0.655718 -0.653233 -v 0.020000 0.132933 0.248800 -vn -0.552294 0.318852 -0.770263 -v 0.019223 0.132550 0.248800 -vn 0.669355 -0.088119 -0.737698 -v 0.020250 0.141500 0.248800 -vn -0.552293 -0.318855 -0.770262 -v 0.019223 0.139450 0.248800 -vn -0.318858 -0.552280 -0.770271 -v 0.019150 0.139523 0.248800 -vn -0.088113 -0.669353 -0.737701 -v 0.019050 0.139550 0.248800 -vn -0.577350 -0.577350 -0.577350 -v 0.018750 0.139550 0.248800 -vn 0.088132 -0.669347 -0.737704 -v 0.023250 0.144500 0.248800 -vn 0.727972 0.095842 -0.678875 -v 0.025750 0.127000 0.248800 -vn 0.577351 -0.577350 -0.577351 -v 0.025750 0.126500 0.248800 -vn 0.088114 -0.669357 -0.737697 -v 0.025400 0.126500 0.248800 -vn -0.095852 0.727973 -0.678872 -v 0.037750 0.133000 0.248800 -vn 0.577350 0.577351 -0.577351 -v 0.038250 0.133000 0.248800 -vn 0.669352 0.088124 -0.737701 -v 0.038250 0.132650 0.248800 -vn 0.552297 -0.318869 -0.770254 -v 0.025227 0.126400 0.248800 -vn 0.318860 0.552276 -0.770272 -v 0.025300 0.145527 0.248800 -vn 0.552295 0.318871 -0.770254 -v 0.025227 0.145600 0.248800 -vn 0.669345 0.088136 -0.737705 -v 0.025200 0.145700 0.248800 -vn 0.577349 0.577351 -0.577351 -v 0.025200 0.146000 0.248800 -vn -0.088132 0.669347 -0.737704 -v 0.034250 0.127500 0.248800 -vn -0.318869 0.552297 -0.770253 -v 0.034500 0.127567 0.248800 -vn 0.095837 -0.727972 -0.678875 -v 0.037250 0.126000 0.248800 -vn -0.552281 0.318863 -0.770268 -v 0.034683 0.127750 0.248800 -vn -0.727972 0.095831 -0.678876 -v 0.037250 0.132500 0.248800 -vn -0.655723 0.378590 -0.653220 -v 0.037317 0.132750 0.248800 -vn -0.378576 0.655718 -0.653233 -v 0.037500 0.132933 0.248800 -vn -0.577348 -0.577351 -0.577351 -v 0.031750 0.126500 0.248800 -vn -0.088112 -0.669354 -0.737700 -v 0.032100 0.126500 0.248800 -vn -0.318861 -0.552272 -0.770274 -v 0.032200 0.126473 0.248800 -vn -0.552299 -0.318869 -0.770252 -v 0.032273 0.126400 0.248800 -vn -0.095831 0.727972 -0.678877 -v 0.032250 0.127500 0.248800 -vn -0.669345 -0.088136 -0.737705 -v 0.032300 0.126300 0.248800 -vn -0.577349 -0.577351 -0.577351 -v 0.032300 0.126000 0.248800 -vn 0.669354 0.088119 -0.737699 -v 0.022750 0.128000 0.248800 -vn 0.552280 0.318867 -0.770266 -v 0.022817 0.127750 0.248800 -vn -0.251477 0.607116 -0.753770 -v 0.021674 0.130038 0.248800 -vn -0.528439 -0.433677 -0.729847 -v 0.034604 0.129086 0.248800 -vn -0.433663 -0.528442 -0.729853 -v 0.032336 0.131354 0.248800 -vn -0.318864 0.552288 -0.770262 -v 0.030125 0.133618 0.248800 -vn -0.251490 -0.607131 -0.753754 -v 0.032174 0.131462 0.248800 -vn 0.000000 0.637728 -0.770262 -v 0.028750 0.133250 0.248800 -vn -0.669341 0.088135 -0.737709 -v 0.032300 0.145700 0.248800 -vn -0.577350 0.577350 -0.577350 -v 0.032300 0.146000 0.248800 -vn 0.095837 0.727971 -0.678876 -v 0.037250 0.146000 0.248800 -vn -0.552288 -0.318863 -0.770263 -v 0.031132 0.137375 0.248800 -vn 0.433682 -0.528436 -0.729846 -v 0.035664 0.141854 0.248800 -vn 0.528438 -0.433670 -0.729851 -v 0.033396 0.139586 0.248800 -vn -0.669354 -0.088119 -0.737699 -v 0.034750 0.144000 0.248800 -vn -0.552280 -0.318867 -0.770266 -v 0.034683 0.144250 0.248800 -vn 0.251475 -0.607116 -0.753771 -v 0.035826 0.141962 0.248800 -vn -0.378578 0.655723 -0.653227 -v 0.019500 0.145799 0.248800 -vn 0.088132 -0.669347 -0.737704 -v 0.020750 0.142000 0.248800 -vn 0.251476 0.607117 -0.753770 -v 0.035826 0.130038 0.248800 -vn -0.669358 0.088115 -0.737696 -v 0.034750 0.128000 0.248800 -vn -0.669352 0.088124 -0.737700 -v 0.037250 0.130500 0.248800 -vn 0.552292 0.318861 -0.770261 -v 0.038277 0.132550 0.248800 -vn -0.552292 0.318865 -0.770259 -v 0.037183 0.130250 0.248800 -vn 0.318859 0.552280 -0.770270 -v 0.038350 0.132477 0.248800 -vn 0.727971 -0.095840 -0.678876 -v 0.038750 0.127500 0.248800 -vn 0.088115 0.669352 -0.737701 -v 0.038450 0.132450 0.248800 -vn 0.577350 0.577351 -0.577350 -v 0.038750 0.132450 0.248800 -vn -0.577351 0.577349 -0.577351 -v 0.018750 0.132450 0.248800 -vn -0.088114 0.669357 -0.737697 -v 0.019050 0.132450 0.248800 -vn -0.727972 -0.095840 -0.678875 -v 0.018750 0.127500 0.248800 -vn -0.318860 0.552278 -0.770271 -v 0.019150 0.132477 0.248800 -vn 0.067001 0.680321 -0.729846 -v 0.036018 0.130000 0.248800 -vn -0.088132 0.669347 -0.737704 -v 0.036750 0.130000 0.248800 -vn 0.378582 -0.655722 -0.653226 -v 0.038000 0.126201 0.248800 -vn 0.655722 -0.378579 -0.653228 -v 0.038549 0.126750 0.248800 -vn -0.318877 0.552285 -0.770259 -v 0.037000 0.130067 0.248800 -vn -0.088132 -0.669348 -0.737703 -v 0.036750 0.142000 0.248800 -vn 0.067001 -0.680319 -0.729847 -v 0.036018 0.142000 0.248800 -vn -0.680318 0.067006 -0.729848 -v 0.034750 0.143268 0.248800 -vn -0.552301 0.318866 -0.770252 -v 0.032273 0.145600 0.248800 -vn 0.655722 0.378590 -0.653221 -v 0.020183 0.132750 0.248800 -vn 0.727972 0.095834 -0.678876 -v 0.020250 0.132500 0.248800 -vn 0.669352 0.088124 -0.737701 -v 0.020250 0.130500 0.248800 -vn -0.095832 -0.727972 -0.678876 -v 0.032250 0.144500 0.248800 -vn -0.318864 0.552271 -0.770274 -v 0.032200 0.145527 0.248800 -vn -0.088132 -0.669348 -0.737703 -v 0.034250 0.144500 0.248800 -vn -0.318869 -0.552297 -0.770254 -v 0.034500 0.144433 0.248800 -vn 0.318865 -0.552289 -0.770261 -v 0.027375 0.138382 0.248800 -vn 0.528434 0.433688 -0.729844 -v 0.022896 0.142914 0.248800 -vn 0.433662 0.528442 -0.729854 -v 0.025164 0.140646 0.248800 -vn 0.607125 -0.251473 -0.753764 -v 0.033288 0.139424 0.248800 -vn 0.680317 -0.067006 -0.729848 -v 0.033250 0.139232 0.248800 -vn -0.637728 -0.000001 -0.770261 -v 0.031500 0.136000 0.248800 -vn 0.680317 0.067006 -0.729849 -v 0.033250 0.132768 0.248800 -vn -0.552289 0.318864 -0.770261 -v 0.031132 0.134625 0.248800 -vn 0.607125 0.251473 -0.753764 -v 0.033288 0.132576 0.248800 -vn 0.528439 0.433671 -0.729850 -v 0.033396 0.132414 0.248800 -vn 0.433681 0.528435 -0.729847 -v 0.035664 0.130146 0.248800 -vn -0.607121 -0.251477 -0.753766 -v 0.034712 0.128924 0.248800 -vn -0.680317 -0.067006 -0.729849 -v 0.034750 0.128732 0.248800 -vn -0.552280 -0.318867 -0.770266 -v 0.037183 0.141750 0.248800 -vn -0.318869 -0.552297 -0.770254 -v 0.037000 0.141933 0.248800 -vn 0.655721 0.378583 -0.653227 -v 0.038549 0.145250 0.248800 -vn 0.378577 0.655724 -0.653228 -v 0.038000 0.145799 0.248800 -vn -0.251478 -0.607116 -0.753770 -v 0.021674 0.141962 0.248800 -vn 0.669355 -0.088119 -0.737698 -v 0.022750 0.144000 0.248800 -vn -0.433684 0.528436 -0.729845 -v 0.021836 0.130146 0.248800 -vn -0.528437 0.433673 -0.729850 -v 0.024104 0.132414 0.248800 -vn 0.552290 0.318863 -0.770261 -v 0.026368 0.134625 0.248800 -vn -0.607123 0.251475 -0.753765 -v 0.024212 0.132576 0.248800 -vn 0.637728 -0.000001 -0.770262 -v 0.026000 0.136000 0.248800 -vn 0.251488 0.607132 -0.753754 -v 0.025326 0.140538 0.248800 -vn 0.067026 0.680308 -0.729855 -v 0.025518 0.140500 0.248800 -vn -0.000000 -0.637728 -0.770262 -v 0.028750 0.138750 0.248800 -vn -0.067025 0.680307 -0.729856 -v 0.031982 0.140500 0.248800 -vn -0.318865 -0.552288 -0.770261 -v 0.030125 0.138382 0.248800 -vn -0.251489 0.607131 -0.753754 -v 0.032174 0.140538 0.248800 -vn -0.433664 0.528441 -0.729853 -v 0.032336 0.140646 0.248800 -vn -0.528433 0.433690 -0.729844 -v 0.034604 0.142914 0.248800 -vn -0.607110 0.251488 -0.753772 -v 0.034712 0.143076 0.248800 -vn -0.067001 -0.680321 -0.729846 -v 0.021482 0.142000 0.248800 -vn 0.088132 0.669348 -0.737703 -v 0.020750 0.130000 0.248800 -vn -0.067001 0.680319 -0.729847 -v 0.021482 0.130000 0.248800 -vn 0.680318 -0.067006 -0.729848 -v 0.022750 0.128732 0.248800 -vn -0.655722 0.378582 -0.653227 -v 0.018951 0.145250 0.248800 -vn 0.552292 0.318864 -0.770259 -v 0.020317 0.130250 0.248800 -vn 0.318877 0.552285 -0.770259 -v 0.020500 0.130067 0.248800 -vn -0.655722 -0.378579 -0.653228 -v 0.018951 0.126750 0.248800 -vn -0.378582 -0.655722 -0.653226 -v 0.019500 0.126201 0.248800 -vn 0.655722 0.378579 -0.653228 -v 0.025683 0.127250 0.248800 -vn 0.378578 0.655727 -0.653223 -v 0.025500 0.127433 0.248800 -vn 0.095830 0.727972 -0.678876 -v 0.025250 0.127500 0.248800 -vn 0.318863 -0.552275 -0.770272 -v 0.025300 0.126473 0.248800 -vn 0.088132 0.669348 -0.737703 -v 0.023250 0.127500 0.248800 -vn 0.318869 0.552297 -0.770253 -v 0.023000 0.127567 0.248800 -vn -0.680317 0.067006 -0.729848 -v 0.024250 0.132768 0.248800 -vn -0.680317 -0.067006 -0.729849 -v 0.024250 0.139232 0.248800 -vn 0.552289 -0.318864 -0.770261 -v 0.026368 0.137375 0.248800 -vn -0.607123 -0.251475 -0.753765 -v 0.024212 0.139424 0.248800 -vn -0.528438 -0.433674 -0.729849 -v 0.024104 0.139586 0.248800 -vn -0.433683 -0.528435 -0.729846 -v 0.021836 0.141854 0.248800 -vn 0.607112 0.251486 -0.753771 -v 0.022788 0.143076 0.248800 -vn 0.680317 0.067006 -0.729849 -v 0.022750 0.143268 0.248800 -vn -0.067026 -0.680308 -0.729855 -v 0.031982 0.131500 0.248800 -vn 0.067025 -0.680307 -0.729856 -v 0.025518 0.131500 0.248800 -vn 0.318865 0.552288 -0.770262 -v 0.027375 0.133618 0.248800 -vn 0.251488 -0.607132 -0.753754 -v 0.025326 0.131462 0.248800 -vn 0.433661 -0.528443 -0.729853 -v 0.025164 0.131354 0.248800 -vn 0.528438 -0.433673 -0.729850 -v 0.022896 0.129086 0.248800 -vn 0.607123 -0.251475 -0.753765 -v 0.022788 0.128924 0.248800 -vn -0.095855 0.678863 -0.727981 -v 0.037750 0.126000 0.330300 -vn -0.378556 0.653244 -0.655720 -v 0.037500 0.126000 0.330367 -vn -0.655726 0.653209 -0.378604 -v 0.037317 0.126000 0.330550 -vn 0.095851 0.678868 -0.727978 -v 0.019750 0.126000 0.330300 -vn -0.577348 0.577351 -0.577351 -v 0.019250 0.126000 0.330300 -vn -0.669348 0.737703 -0.088130 -v 0.019250 0.126000 0.330650 -vn -0.577357 0.577347 -0.577347 -v 0.031750 0.126000 0.317800 -vn -0.727980 0.678866 0.095845 -v 0.031750 0.126000 0.318300 -vn -0.088116 0.737689 -0.669365 -v 0.032100 0.126000 0.317800 -vn -0.655717 0.653233 0.378578 -v 0.031817 0.126000 0.318550 -vn -0.318847 0.770248 -0.552318 -v 0.032200 0.126000 0.317773 -vn -0.655725 0.653231 0.378569 -v 0.037317 0.126000 0.324050 -vn -0.378559 0.653212 0.655750 -v 0.037500 0.126000 0.324233 -vn 0.669345 0.737705 0.088136 -v 0.038250 0.126000 0.323950 -vn -0.095810 0.678879 0.727972 -v 0.037750 0.126000 0.324300 -vn 0.577348 0.577351 0.577351 -v 0.038250 0.126000 0.324300 -vn -0.727976 0.678870 -0.095842 -v 0.031750 0.126000 0.336300 -vn -0.577351 0.577351 0.577348 -v 0.031750 0.126000 0.336800 -vn -0.088113 0.737697 0.669358 -v 0.032100 0.126000 0.336800 -vn 0.088119 0.737689 0.669365 -v 0.038450 0.126000 0.323750 -vn 0.577350 0.577351 0.577351 -v 0.038750 0.126000 0.323750 -vn 0.727972 0.678876 -0.095838 -v 0.038750 0.126000 0.318800 -vn 0.577347 0.577347 -0.577357 -v 0.038250 0.126000 0.330300 -vn 0.669353 0.737698 -0.088139 -v 0.038250 0.126000 0.330650 -vn 0.552331 0.770232 -0.318862 -v 0.038277 0.126000 0.330750 -vn 0.318883 0.770273 -0.552262 -v 0.038350 0.126000 0.330823 -vn 0.552299 0.770251 0.318870 -v 0.020317 0.126000 0.321550 -vn 0.318871 0.770264 0.552281 -v 0.020500 0.126000 0.321367 -vn -0.727972 0.678875 -0.095838 -v 0.018750 0.126000 0.318800 -vn -0.552300 0.770255 -0.318860 -v 0.034683 0.126000 0.335550 -vn -0.318833 0.770278 -0.552284 -v 0.034500 0.126000 0.335733 -vn -0.655728 0.653220 -0.378583 -v 0.031817 0.126000 0.336050 -vn -0.378586 0.653236 -0.655710 -v 0.032000 0.126000 0.335867 -vn -0.095855 0.678863 -0.727981 -v 0.032250 0.126000 0.335800 -vn -0.577352 0.577350 -0.577350 -v 0.032300 0.126000 0.317300 -vn -0.669351 0.737701 -0.088125 -v 0.032300 0.126000 0.317600 -vn 0.095837 0.678875 -0.727972 -v 0.037250 0.126000 0.317300 -vn -0.552276 0.770263 -0.318883 -v 0.032273 0.126000 0.317700 -vn -0.318882 0.770273 0.552262 -v 0.019150 0.126000 0.323777 -vn -0.088114 0.737697 0.669357 -v 0.019050 0.126000 0.323750 -vn -0.577350 0.577350 0.577352 -v 0.018750 0.126000 0.323750 -vn -0.088118 0.737688 -0.669366 -v 0.019050 0.126000 0.330850 -vn -0.577350 0.577351 -0.577351 -v 0.018750 0.126000 0.330850 -vn -0.727972 0.678876 0.095838 -v 0.018750 0.126000 0.335800 -vn -0.378591 0.653222 0.655721 -v 0.032000 0.126000 0.318733 -vn -0.095852 0.678871 0.727974 -v 0.032250 0.126000 0.318800 -vn -0.088133 0.737704 0.669347 -v 0.034250 0.126000 0.318800 -vn 0.727977 0.678869 0.095847 -v 0.025750 0.126000 0.318300 -vn 0.577351 0.577351 -0.577348 -v 0.025750 0.126000 0.317800 -vn 0.088114 0.737697 -0.669357 -v 0.025400 0.126000 0.317800 -vn -0.088100 0.737684 -0.669373 -v 0.034250 0.126000 0.335800 -vn -0.318840 0.770248 0.552322 -v 0.032200 0.126000 0.336827 -vn -0.552274 0.770272 0.318864 -v 0.032273 0.126000 0.336900 -vn -0.669374 0.737683 0.088104 -v 0.032300 0.126000 0.337000 -vn 0.318891 0.770273 0.552258 -v 0.038350 0.126000 0.323777 -vn 0.669349 0.737703 0.088129 -v 0.020250 0.126000 0.321800 -vn 0.727972 0.678876 0.095834 -v 0.020250 0.126000 0.323800 -vn -0.577347 0.577347 0.577357 -v 0.019250 0.126000 0.324300 -vn 0.095813 0.678875 0.727976 -v 0.019750 0.126000 0.324300 -vn -0.669356 0.737696 0.088134 -v 0.019250 0.126000 0.323950 -vn 0.378555 0.653225 0.655739 -v 0.020000 0.126000 0.324233 -vn 0.095854 0.678864 0.727981 -v 0.025250 0.126000 0.318800 -vn 0.378588 0.653235 0.655710 -v 0.025500 0.126000 0.318733 -vn 0.655725 0.653222 0.378583 -v 0.025683 0.126000 0.318550 -vn 0.088132 0.737704 -0.669347 -v 0.020750 0.126000 0.333300 -vn 0.318861 0.770242 -0.552317 -v 0.020500 0.126000 0.333233 -vn 0.607130 0.753758 0.251480 -v 0.022788 0.126000 0.334376 -vn -0.318889 0.770273 -0.552258 -v 0.019150 0.126000 0.330823 -vn -0.552331 0.770235 0.318856 -v 0.019223 0.126000 0.323850 -vn 0.655734 0.653218 0.378575 -v 0.020183 0.126000 0.324050 -vn 0.655722 0.653229 0.378578 -v 0.038549 0.126000 0.336550 -vn 0.727973 0.678875 0.095838 -v 0.038750 0.126000 0.335800 -vn -0.669354 0.737699 -0.088119 -v 0.034750 0.126000 0.335300 -vn -0.552288 0.770262 -0.318864 -v 0.031132 0.126000 0.328675 -vn 0.433685 0.729839 -0.528444 -v 0.035664 0.126000 0.333154 -vn 0.528438 0.729851 -0.433671 -v 0.033396 0.126000 0.330886 -vn -0.669354 0.737699 -0.088119 -v 0.037250 0.126000 0.332800 -vn -0.552276 0.770266 -0.318876 -v 0.037183 0.126000 0.333050 -vn -0.318855 0.770254 -0.552305 -v 0.037000 0.126000 0.333233 -vn -0.433687 0.729840 0.528440 -v 0.021836 0.126000 0.321446 -vn -0.528429 0.729839 0.433702 -v 0.024104 0.126000 0.323714 -vn 0.552288 0.770263 0.318862 -v 0.026368 0.126000 0.325925 -vn -0.607107 0.753771 0.251497 -v 0.024212 0.126000 0.323876 -vn 0.637729 0.770261 -0.000002 -v 0.026000 0.126000 0.327300 -vn -0.727971 0.678877 -0.095831 -v 0.037250 0.126000 0.330800 -vn 0.088116 0.737698 -0.669356 -v 0.038450 0.126000 0.330850 -vn 0.577350 0.577350 -0.577352 -v 0.038750 0.126000 0.330850 -vn -0.655722 0.653229 -0.378577 -v 0.018951 0.126000 0.318050 -vn 0.669350 0.737702 0.088127 -v 0.022750 0.126000 0.319300 -vn -0.088132 0.737704 0.669347 -v 0.036750 0.126000 0.321300 -vn -0.318878 0.770253 0.552293 -v 0.037000 0.126000 0.321367 -vn -0.607129 0.753760 -0.251476 -v 0.034712 0.126000 0.320224 -vn -0.095837 0.678877 -0.727970 -v 0.020250 0.126000 0.317300 -vn 0.552298 0.770253 0.318869 -v 0.022817 0.126000 0.319050 -vn 0.318871 0.770263 0.552282 -v 0.023000 0.126000 0.318867 -vn -0.318861 0.770263 0.552289 -v 0.030125 0.126000 0.324918 -vn -0.528445 0.729841 -0.433680 -v 0.034604 0.126000 0.320386 -vn -0.433682 0.729847 -0.528435 -v 0.032336 0.126000 0.322654 -vn -0.607127 0.753760 0.251482 -v 0.034712 0.126000 0.334376 -vn -0.088134 0.737697 -0.669355 -v 0.036750 0.126000 0.333300 -vn 0.095851 0.678872 -0.727974 -v 0.025250 0.126000 0.335800 -vn 0.088097 0.737691 -0.669366 -v 0.023250 0.126000 0.335800 -vn 0.552278 0.770270 0.318863 -v 0.025227 0.126000 0.336900 -vn 0.669361 0.737694 0.088107 -v 0.025200 0.126000 0.337000 -vn 0.528444 0.729843 0.433678 -v 0.022896 0.126000 0.334214 -vn 0.433641 0.729861 0.528450 -v 0.025164 0.126000 0.331946 -vn 0.318860 0.770265 -0.552287 -v 0.027375 0.126000 0.329682 -vn 0.251452 0.753748 0.607154 -v 0.025326 0.126000 0.331838 -vn -0.000000 0.770259 -0.637731 -v 0.028750 0.126000 0.330050 -vn -0.680326 0.729840 0.067007 -v 0.034750 0.126000 0.334568 -vn 0.577357 0.577347 0.577347 -v 0.025750 0.126000 0.336800 -vn 0.727980 0.678865 -0.095850 -v 0.025750 0.126000 0.336300 -vn 0.088118 0.737690 0.669365 -v 0.025400 0.126000 0.336800 -vn 0.655715 0.653236 -0.378578 -v 0.025683 0.126000 0.336050 -vn 0.669363 0.737691 -0.088120 -v 0.022750 0.126000 0.335300 -vn 0.680316 0.729850 0.067008 -v 0.022750 0.126000 0.334568 -vn -0.067003 0.729839 -0.680328 -v 0.021482 0.126000 0.333300 -vn 0.607127 0.753758 -0.251485 -v 0.022788 0.126000 0.320224 -vn 0.088134 0.737697 0.669355 -v 0.020750 0.126000 0.321300 -vn 0.088135 0.737698 0.669354 -v 0.023250 0.126000 0.318800 -vn 0.318841 0.770248 -0.552321 -v 0.025300 0.126000 0.317773 -vn 0.552271 0.770261 -0.318897 -v 0.025227 0.126000 0.317700 -vn 0.669357 0.737695 -0.088133 -v 0.025200 0.126000 0.317600 -vn 0.577351 0.577351 -0.577350 -v 0.025200 0.126000 0.317300 -vn -0.669357 0.737696 0.088131 -v 0.034750 0.126000 0.319300 -vn -0.680317 0.729848 -0.067005 -v 0.034750 0.126000 0.320032 -vn 0.067003 0.729839 0.680328 -v 0.036018 0.126000 0.321300 -vn 0.378581 0.653227 0.655722 -v 0.038000 0.126000 0.337099 -vn 0.318849 0.770247 0.552317 -v 0.025300 0.126000 0.336827 -vn 0.378593 0.653221 -0.655721 -v 0.025500 0.126000 0.335867 -vn 0.318838 0.770266 -0.552298 -v 0.023000 0.126000 0.335733 -vn 0.552287 0.770268 -0.318852 -v 0.022817 0.126000 0.335550 -vn -0.378583 0.653227 0.655721 -v 0.019500 0.126000 0.337099 -vn -0.655723 0.653229 0.378576 -v 0.018951 0.126000 0.336550 -vn 0.378562 0.653229 -0.655730 -v 0.020000 0.126000 0.330367 -vn 0.655714 0.653224 -0.378599 -v 0.020183 0.126000 0.330550 -vn 0.727979 0.678868 -0.095837 -v 0.020250 0.126000 0.330800 -vn -0.552335 0.770235 -0.318849 -v 0.019223 0.126000 0.330750 -vn 0.669361 0.737693 -0.088122 -v 0.020250 0.126000 0.332800 -vn 0.552264 0.770277 -0.318870 -v 0.020317 0.126000 0.333050 -vn 0.680324 0.729842 -0.067009 -v 0.022750 0.126000 0.320032 -vn -0.727978 0.678869 0.095834 -v 0.037250 0.126000 0.323800 -vn 0.552335 0.770232 0.318855 -v 0.038277 0.126000 0.323850 -vn -0.669356 0.737696 0.088132 -v 0.037250 0.126000 0.321800 -vn -0.552287 0.770263 0.318864 -v 0.037183 0.126000 0.321550 -vn 0.067004 0.729839 0.680327 -v 0.025518 0.126000 0.331800 -vn -0.067002 0.729847 0.680319 -v 0.031982 0.126000 0.331800 -vn -0.318861 0.770263 -0.552288 -v 0.030125 0.126000 0.329682 -vn -0.251446 0.753747 0.607158 -v 0.032174 0.126000 0.331838 -vn -0.433642 0.729855 0.528457 -v 0.032336 0.126000 0.331946 -vn -0.528438 0.729849 0.433675 -v 0.034604 0.126000 0.334214 -vn 0.251476 0.753763 -0.607125 -v 0.035826 0.126000 0.333262 -vn 0.067001 0.729847 -0.680319 -v 0.036018 0.126000 0.333300 -vn -0.378581 0.653227 -0.655722 -v 0.019500 0.126000 0.317501 -vn -0.318879 0.770252 0.552293 -v 0.034500 0.126000 0.318867 -vn -0.552287 0.770263 0.318864 -v 0.034683 0.126000 0.319050 -vn 0.378582 0.653227 -0.655721 -v 0.038000 0.126000 0.317501 -vn 0.655723 0.653229 -0.378576 -v 0.038549 0.126000 0.318050 -vn -0.680327 0.729839 0.067003 -v 0.024250 0.126000 0.324068 -vn -0.680319 0.729847 -0.067001 -v 0.024250 0.126000 0.330532 -vn 0.552289 0.770261 -0.318864 -v 0.026368 0.126000 0.328675 -vn -0.607131 0.753760 -0.251470 -v 0.024212 0.126000 0.330724 -vn -0.528444 0.729842 -0.433678 -v 0.024104 0.126000 0.330886 -vn -0.433682 0.729846 -0.528436 -v 0.021836 0.126000 0.333154 -vn -0.251483 0.753764 -0.607121 -v 0.021674 0.126000 0.333262 -vn -0.251483 0.753763 -0.607123 -v 0.032174 0.126000 0.322762 -vn -0.067004 0.729840 -0.680327 -v 0.031982 0.126000 0.322800 -vn 0.000000 0.770259 0.637731 -v 0.028750 0.126000 0.324550 -vn 0.067001 0.729847 -0.680319 -v 0.025518 0.126000 0.322800 -vn 0.318861 0.770263 0.552289 -v 0.027375 0.126000 0.324918 -vn 0.251478 0.753764 -0.607124 -v 0.025326 0.126000 0.322762 -vn 0.433688 0.729839 -0.528441 -v 0.025164 0.126000 0.322654 -vn 0.528438 0.729849 -0.433675 -v 0.022896 0.126000 0.320386 -vn -0.251477 0.753764 0.607124 -v 0.021674 0.126000 0.321338 -vn -0.067001 0.729847 0.680319 -v 0.021482 0.126000 0.321300 -vn 0.607131 0.753759 -0.251474 -v 0.033288 0.126000 0.330724 -vn 0.680327 0.729839 -0.067003 -v 0.033250 0.126000 0.330532 -vn -0.637728 0.770262 -0.000002 -v 0.031500 0.126000 0.327300 -vn 0.680319 0.729847 0.067001 -v 0.033250 0.126000 0.324068 -vn -0.552289 0.770262 0.318863 -v 0.031132 0.126000 0.325925 -vn 0.607111 0.753770 0.251489 -v 0.033288 0.126000 0.323876 -vn 0.528437 0.729833 0.433703 -v 0.033396 0.126000 0.323714 -vn 0.433682 0.729847 0.528434 -v 0.035664 0.126000 0.321446 -vn 0.251481 0.753763 0.607123 -v 0.035826 0.126000 0.321338 -vn -0.378554 -0.653226 0.655739 -v 0.037500 -0.126000 0.324233 -vn -0.655735 -0.653217 0.378574 -v 0.037317 -0.126000 0.324050 -vn -0.727971 -0.678877 0.095831 -v 0.037250 -0.126000 0.323800 -vn -0.727976 -0.678870 0.095842 -v 0.031750 -0.126000 0.318300 -vn -0.577351 -0.577351 -0.577348 -v 0.031750 -0.126000 0.317800 -vn -0.088113 -0.737697 -0.669358 -v 0.032100 -0.126000 0.317800 -vn -0.577357 -0.577347 0.577347 -v 0.031750 -0.126000 0.336800 -vn -0.727980 -0.678866 -0.095845 -v 0.031750 -0.126000 0.336300 -vn -0.088116 -0.737689 0.669365 -v 0.032100 -0.126000 0.336800 -vn -0.655717 -0.653233 -0.378578 -v 0.031817 -0.126000 0.336050 -vn -0.655715 -0.653223 -0.378599 -v 0.037317 -0.126000 0.330550 -vn -0.378561 -0.653230 -0.655731 -v 0.037500 -0.126000 0.330367 -vn 0.669345 -0.737705 -0.088136 -v 0.038250 -0.126000 0.330650 -vn -0.095852 -0.678868 -0.727978 -v 0.037750 -0.126000 0.330300 -vn 0.577348 -0.577351 -0.577351 -v 0.038250 -0.126000 0.330300 -vn 0.669353 -0.737698 0.088139 -v 0.038250 -0.126000 0.323950 -vn 0.577347 -0.577347 0.577357 -v 0.038250 -0.126000 0.324300 -vn -0.095813 -0.678875 0.727976 -v 0.037750 -0.126000 0.324300 -vn -0.655728 -0.653220 0.378583 -v 0.031817 -0.126000 0.318550 -vn -0.378586 -0.653236 0.655710 -v 0.032000 -0.126000 0.318733 -vn -0.095855 -0.678863 0.727981 -v 0.032250 -0.126000 0.318800 -vn -0.088118 -0.737688 0.669366 -v 0.019050 -0.126000 0.323750 -vn -0.577350 -0.577351 0.577350 -v 0.018750 -0.126000 0.323750 -vn -0.727972 -0.678876 -0.095838 -v 0.018750 -0.126000 0.318800 -vn 0.095837 -0.678876 -0.727971 -v 0.037250 -0.126000 0.317300 -vn -0.552299 -0.770251 0.318870 -v 0.034683 -0.126000 0.319050 -vn -0.318873 -0.770264 0.552281 -v 0.034500 -0.126000 0.318867 -vn 0.095855 -0.678864 -0.727981 -v 0.019750 -0.126000 0.330300 -vn 0.378557 -0.653243 -0.655720 -v 0.020000 -0.126000 0.330367 -vn 0.655724 -0.653211 -0.378604 -v 0.020183 -0.126000 0.330550 -vn -0.378591 -0.653222 -0.655721 -v 0.032000 -0.126000 0.335867 -vn -0.095852 -0.678871 -0.727974 -v 0.032250 -0.126000 0.335800 -vn -0.318847 -0.770248 0.552318 -v 0.032200 -0.126000 0.336827 -vn -0.088098 -0.737691 -0.669366 -v 0.034250 -0.126000 0.335800 -vn -0.552278 -0.770272 0.318857 -v 0.032273 -0.126000 0.336900 -vn -0.669364 -0.737692 0.088101 -v 0.032300 -0.126000 0.337000 -vn -0.552299 -0.770251 0.318870 -v 0.037183 -0.126000 0.321550 -vn -0.318871 -0.770264 0.552281 -v 0.037000 -0.126000 0.321367 -vn 0.727973 -0.678874 -0.095838 -v 0.038750 -0.126000 0.318800 -vn 0.577357 -0.577347 -0.577347 -v 0.025750 -0.126000 0.317800 -vn 0.727980 -0.678865 0.095850 -v 0.025750 -0.126000 0.318300 -vn 0.088118 -0.737690 -0.669365 -v 0.025400 -0.126000 0.317800 -vn 0.655715 -0.653236 0.378578 -v 0.025683 -0.126000 0.318550 -vn 0.318848 -0.770247 -0.552317 -v 0.025300 -0.126000 0.317773 -vn -0.088136 -0.737698 0.669353 -v 0.034250 -0.126000 0.318800 -vn -0.318839 -0.770248 -0.552322 -v 0.032200 -0.126000 0.317773 -vn -0.552272 -0.770263 -0.318890 -v 0.032273 -0.126000 0.317700 -vn -0.669361 -0.737692 -0.088128 -v 0.032300 -0.126000 0.317600 -vn -0.577351 -0.577351 -0.577350 -v 0.032300 -0.126000 0.317300 -vn -0.669349 -0.737703 0.088129 -v 0.037250 -0.126000 0.321800 -vn 0.095809 -0.678879 0.727972 -v 0.019750 -0.126000 0.324300 -vn -0.577348 -0.577351 0.577351 -v 0.019250 -0.126000 0.324300 -vn -0.669348 -0.737703 0.088130 -v 0.019250 -0.126000 0.323950 -vn 0.727977 -0.678869 -0.095847 -v 0.025750 -0.126000 0.336300 -vn 0.577351 -0.577351 0.577348 -v 0.025750 -0.126000 0.336800 -vn 0.088114 -0.737697 0.669357 -v 0.025400 -0.126000 0.336800 -vn -0.318889 -0.770274 0.552258 -v 0.019150 -0.126000 0.323777 -vn 0.552331 -0.770232 0.318862 -v 0.038277 -0.126000 0.323850 -vn 0.318883 -0.770273 0.552262 -v 0.038350 -0.126000 0.323777 -vn 0.088116 -0.737698 0.669356 -v 0.038450 -0.126000 0.323750 -vn 0.577350 -0.577350 0.577352 -v 0.038750 -0.126000 0.323750 -vn 0.669354 -0.737699 -0.088119 -v 0.020250 -0.126000 0.332800 -vn 0.552276 -0.770266 -0.318876 -v 0.020317 -0.126000 0.333050 -vn -0.727972 -0.678875 0.095838 -v 0.018750 -0.126000 0.335800 -vn 0.318855 -0.770254 -0.552305 -v 0.020500 -0.126000 0.333233 -vn 0.095854 -0.678864 -0.727981 -v 0.025250 -0.126000 0.335800 -vn 0.378588 -0.653235 -0.655710 -v 0.025500 -0.126000 0.335867 -vn 0.655725 -0.653222 -0.378583 -v 0.025683 -0.126000 0.336050 -vn -0.577347 -0.577347 -0.577357 -v 0.019250 -0.126000 0.330300 -vn -0.669356 -0.737696 -0.088134 -v 0.019250 -0.126000 0.330650 -vn -0.552331 -0.770235 -0.318856 -v 0.019223 -0.126000 0.330750 -vn -0.318882 -0.770273 -0.552262 -v 0.019150 -0.126000 0.330823 -vn 0.727972 -0.678876 -0.095834 -v 0.020250 -0.126000 0.330800 -vn -0.088114 -0.737697 -0.669357 -v 0.019050 -0.126000 0.330850 -vn -0.577350 -0.577350 -0.577352 -v 0.018750 -0.126000 0.330850 -vn 0.088132 -0.737704 0.669347 -v 0.020750 -0.126000 0.321300 -vn 0.318878 -0.770253 0.552293 -v 0.020500 -0.126000 0.321367 -vn 0.607130 -0.753758 -0.251480 -v 0.022788 -0.126000 0.320224 -vn -0.433686 -0.729839 -0.528442 -v 0.021836 -0.126000 0.333154 -vn -0.528437 -0.729850 -0.433674 -v 0.024104 -0.126000 0.330886 -vn 0.552288 -0.770263 -0.318863 -v 0.026368 -0.126000 0.328675 -vn -0.607129 -0.753760 -0.251476 -v 0.024212 -0.126000 0.330724 -vn 0.637728 -0.770261 -0.000002 -v 0.026000 -0.126000 0.327300 -vn 0.088119 -0.737689 -0.669365 -v 0.038450 -0.126000 0.330850 -vn 0.577350 -0.577351 -0.577351 -v 0.038750 -0.126000 0.330850 -vn 0.727972 -0.678876 0.095838 -v 0.038750 -0.126000 0.335800 -vn -0.318860 -0.770264 -0.552287 -v 0.030125 -0.126000 0.329682 -vn -0.528444 -0.729843 0.433678 -v 0.034604 -0.126000 0.334214 -vn -0.433639 -0.729861 0.528450 -v 0.032336 -0.126000 0.331946 -vn -0.088132 -0.737704 -0.669347 -v 0.036750 -0.126000 0.333300 -vn -0.318861 -0.770242 -0.552317 -v 0.037000 -0.126000 0.333233 -vn -0.607129 -0.753760 0.251476 -v 0.034712 -0.126000 0.334376 -vn 0.655722 -0.653229 -0.378578 -v 0.038549 -0.126000 0.318050 -vn -0.669349 -0.737703 0.088129 -v 0.034750 -0.126000 0.319300 -vn 0.607127 -0.753758 0.251485 -v 0.022788 -0.126000 0.334376 -vn 0.088134 -0.737697 -0.669355 -v 0.020750 -0.126000 0.333300 -vn 0.088100 -0.737684 -0.669373 -v 0.023250 -0.126000 0.335800 -vn 0.318841 -0.770247 0.552322 -v 0.025300 -0.126000 0.336827 -vn 0.318832 -0.770277 -0.552285 -v 0.023000 -0.126000 0.335733 -vn 0.552273 -0.770270 0.318870 -v 0.025227 -0.126000 0.336900 -vn 0.669370 -0.737686 0.088110 -v 0.025200 -0.126000 0.337000 -vn 0.577352 -0.577350 -0.577350 -v 0.025200 -0.126000 0.317300 -vn 0.669348 -0.737703 -0.088130 -v 0.025200 -0.126000 0.317600 -vn -0.095837 -0.678876 -0.727971 -v 0.020250 -0.126000 0.317300 -vn 0.552276 -0.770261 -0.318889 -v 0.025227 -0.126000 0.317700 -vn 0.680324 -0.729841 0.067010 -v 0.022750 -0.126000 0.334568 -vn 0.669355 -0.737698 -0.088117 -v 0.022750 -0.126000 0.335300 -vn -0.655722 -0.653229 0.378577 -v 0.018951 -0.126000 0.336550 -vn -0.378581 -0.653227 0.655722 -v 0.019500 -0.126000 0.337099 -vn 0.552299 -0.770257 -0.318858 -v 0.022817 -0.126000 0.335550 -vn -0.669362 -0.737692 -0.088122 -v 0.034750 -0.126000 0.335300 -vn -0.680317 -0.729848 0.067005 -v 0.034750 -0.126000 0.334568 -vn 0.067003 -0.729839 -0.680328 -v 0.036018 -0.126000 0.333300 -vn 0.318891 -0.770273 -0.552258 -v 0.038350 -0.126000 0.330823 -vn 0.378593 -0.653221 0.655721 -v 0.025500 -0.126000 0.318733 -vn 0.095851 -0.678872 0.727974 -v 0.025250 -0.126000 0.318800 -vn 0.088132 -0.737704 0.669347 -v 0.023250 -0.126000 0.318800 -vn -0.727978 -0.678869 -0.095834 -v 0.037250 -0.126000 0.330800 -vn 0.552335 -0.770232 -0.318855 -v 0.038277 -0.126000 0.330750 -vn -0.669361 -0.737693 -0.088122 -v 0.037250 -0.126000 0.332800 -vn -0.552264 -0.770277 -0.318870 -v 0.037183 -0.126000 0.333050 -vn -0.552290 -0.770261 0.318863 -v 0.031132 -0.126000 0.325925 -vn 0.433686 -0.729839 0.528442 -v 0.035664 -0.126000 0.321446 -vn 0.528430 -0.729840 0.433700 -v 0.033396 -0.126000 0.323714 -vn -0.251451 -0.753747 0.607155 -v 0.032174 -0.126000 0.331838 -vn -0.067004 -0.729840 0.680327 -v 0.031982 -0.126000 0.331800 -vn 0.000000 -0.770259 -0.637731 -v 0.028750 -0.126000 0.330050 -vn 0.067001 -0.729847 0.680319 -v 0.025518 -0.126000 0.331800 -vn 0.318861 -0.770263 -0.552289 -v 0.027375 -0.126000 0.329682 -vn 0.251446 -0.753748 0.607156 -v 0.025326 -0.126000 0.331838 -vn 0.433644 -0.729854 0.528456 -v 0.025164 -0.126000 0.331946 -vn 0.528438 -0.729849 0.433675 -v 0.022896 -0.126000 0.334214 -vn -0.251477 -0.753764 -0.607124 -v 0.021674 -0.126000 0.333262 -vn -0.067001 -0.729847 -0.680319 -v 0.021482 -0.126000 0.333300 -vn -0.318840 -0.770266 -0.552296 -v 0.034500 -0.126000 0.335733 -vn -0.552288 -0.770267 -0.318853 -v 0.034683 -0.126000 0.335550 -vn 0.378582 -0.653227 0.655721 -v 0.038000 -0.126000 0.337099 -vn 0.655723 -0.653229 0.378576 -v 0.038549 -0.126000 0.336550 -vn -0.607127 -0.753760 -0.251482 -v 0.034712 -0.126000 0.320224 -vn -0.088134 -0.737697 0.669355 -v 0.036750 -0.126000 0.321300 -vn 0.528444 -0.729843 -0.433678 -v 0.022896 -0.126000 0.320386 -vn 0.433684 -0.729846 -0.528435 -v 0.025164 -0.126000 0.322654 -vn 0.318860 -0.770264 0.552288 -v 0.027375 -0.126000 0.324918 -vn 0.251483 -0.753764 -0.607121 -v 0.025326 -0.126000 0.322762 -vn -0.000000 -0.770259 0.637731 -v 0.028750 -0.126000 0.324550 -vn 0.607109 -0.753770 0.251495 -v 0.033288 -0.126000 0.323876 -vn 0.680327 -0.729839 0.067003 -v 0.033250 -0.126000 0.324068 -vn -0.637729 -0.770261 -0.000002 -v 0.031500 -0.126000 0.327300 -vn 0.680319 -0.729847 -0.067001 -v 0.033250 -0.126000 0.330532 -vn -0.552289 -0.770261 -0.318864 -v 0.031132 -0.126000 0.328675 -vn 0.607133 -0.753759 -0.251468 -v 0.033288 -0.126000 0.330724 -vn 0.528445 -0.729843 -0.433675 -v 0.033396 -0.126000 0.330886 -vn 0.433681 -0.729847 -0.528436 -v 0.035664 -0.126000 0.333154 -vn 0.251481 -0.753763 -0.607123 -v 0.035826 -0.126000 0.333262 -vn -0.680326 -0.729840 -0.067007 -v 0.034750 -0.126000 0.320032 -vn 0.669358 -0.737694 0.088130 -v 0.022750 -0.126000 0.319300 -vn 0.680316 -0.729850 -0.067007 -v 0.022750 -0.126000 0.320032 -vn -0.067003 -0.729839 0.680328 -v 0.021482 -0.126000 0.321300 -vn 0.378581 -0.653227 -0.655722 -v 0.038000 -0.126000 0.317501 -vn 0.318877 -0.770252 0.552295 -v 0.023000 -0.126000 0.318867 -vn 0.552286 -0.770264 0.318863 -v 0.022817 -0.126000 0.319050 -vn -0.378583 -0.653227 -0.655721 -v 0.019500 -0.126000 0.317501 -vn -0.655723 -0.653229 -0.378576 -v 0.018951 -0.126000 0.318050 -vn 0.378560 -0.653211 0.655749 -v 0.020000 -0.126000 0.324233 -vn 0.655724 -0.653232 0.378569 -v 0.020183 -0.126000 0.324050 -vn 0.727979 -0.678868 0.095837 -v 0.020250 -0.126000 0.323800 -vn -0.552335 -0.770235 0.318849 -v 0.019223 -0.126000 0.323850 -vn 0.669356 -0.737696 0.088132 -v 0.020250 -0.126000 0.321800 -vn 0.552287 -0.770263 0.318864 -v 0.020317 -0.126000 0.321550 -vn 0.067004 -0.729839 -0.680327 -v 0.025518 -0.126000 0.322800 -vn -0.067002 -0.729847 -0.680319 -v 0.031982 -0.126000 0.322800 -vn -0.318861 -0.770263 0.552288 -v 0.030125 -0.126000 0.324918 -vn -0.251477 -0.753763 -0.607125 -v 0.032174 -0.126000 0.322762 -vn -0.433686 -0.729839 -0.528442 -v 0.032336 -0.126000 0.322654 -vn -0.528438 -0.729849 -0.433675 -v 0.034604 -0.126000 0.320386 -vn 0.251476 -0.753763 0.607125 -v 0.035826 -0.126000 0.321338 -vn 0.067001 -0.729847 0.680319 -v 0.036018 -0.126000 0.321300 -vn -0.680327 -0.729839 -0.067003 -v 0.024250 -0.126000 0.330532 -vn -0.680319 -0.729847 0.067001 -v 0.024250 -0.126000 0.324068 -vn 0.552290 -0.770262 0.318863 -v 0.026368 -0.126000 0.325925 -vn -0.607109 -0.753771 0.251491 -v 0.024212 -0.126000 0.323876 -vn -0.528436 -0.729832 0.433706 -v 0.024104 -0.126000 0.323714 -vn -0.433684 -0.729847 0.528434 -v 0.021836 -0.126000 0.321446 -vn -0.251483 -0.753764 0.607121 -v 0.021674 -0.126000 0.321338 -vn -0.095855 0.678863 -0.727981 -v -0.071000 0.126000 0.332200 -vn -0.378586 0.653236 -0.655710 -v -0.071250 0.126000 0.332267 -vn -0.655732 0.653219 -0.378578 -v -0.071433 0.126000 0.332450 -vn 0.095849 0.678868 -0.727977 -v -0.089000 0.126000 0.332200 -vn -0.577348 0.577351 -0.577351 -v -0.089500 0.126000 0.332200 -vn -0.669364 0.737692 -0.088101 -v -0.089500 0.126000 0.332550 -vn -0.577357 0.577347 -0.577347 -v -0.077000 0.126000 0.319700 -vn -0.727979 0.678868 0.095839 -v -0.077000 0.126000 0.320200 -vn -0.088116 0.737689 -0.669365 -v -0.076650 0.126000 0.319700 -vn -0.655724 0.653234 0.378566 -v -0.076933 0.126000 0.320450 -vn -0.318892 0.770277 -0.552251 -v -0.076550 0.126000 0.319673 -vn -0.655721 0.653232 0.378573 -v -0.071433 0.126000 0.325950 -vn -0.378591 0.653222 0.655721 -v -0.071250 0.126000 0.326133 -vn 0.669352 0.737701 0.088123 -v -0.070500 0.126000 0.325850 -vn -0.095852 0.678868 0.727978 -v -0.071000 0.126000 0.326200 -vn 0.577348 0.577351 0.577351 -v -0.070500 0.126000 0.326200 -vn -0.727976 0.678872 -0.095836 -v -0.077000 0.126000 0.338200 -vn -0.577351 0.577351 0.577348 -v -0.077000 0.126000 0.338700 -vn -0.088113 0.737697 0.669358 -v -0.076650 0.126000 0.338700 -vn 0.088116 0.737688 0.669367 -v -0.070300 0.126000 0.325650 -vn 0.577350 0.577351 0.577351 -v -0.070000 0.126000 0.325650 -vn 0.727973 0.678874 -0.095843 -v -0.070000 0.126000 0.320700 -vn 0.577347 0.577347 -0.577357 -v -0.070500 0.126000 0.332200 -vn 0.669360 0.737693 -0.088127 -v -0.070500 0.126000 0.332550 -vn 0.552279 0.770260 -0.318884 -v -0.070473 0.126000 0.332650 -vn 0.318845 0.770251 -0.552314 -v -0.070400 0.126000 0.332723 -vn 0.552297 0.770256 0.318862 -v -0.088433 0.126000 0.323450 -vn 0.318871 0.770262 0.552284 -v -0.088250 0.126000 0.323267 -vn -0.727973 0.678874 -0.095840 -v -0.090000 0.126000 0.320700 -vn 0.134916 -0.034557 0.990254 -v -0.071500 0.126000 0.339200 -vn -0.552303 0.770254 -0.318858 -v -0.074067 0.126000 0.337450 -vn -0.318872 0.770266 -0.552278 -v -0.074250 0.126000 0.337633 -vn -0.655734 0.653220 -0.378571 -v -0.076933 0.126000 0.337950 -vn -0.378559 0.653223 -0.655738 -v -0.076750 0.126000 0.337767 -vn -0.095811 0.678876 -0.727975 -v -0.076500 0.126000 0.337700 -vn -0.577352 0.577350 -0.577350 -v -0.076450 0.126000 0.319200 -vn -0.669339 0.737710 -0.088147 -v -0.076450 0.126000 0.319500 -vn 0.095837 0.678875 -0.727972 -v -0.071500 0.126000 0.319200 -vn -0.552341 0.770225 -0.318862 -v -0.076477 0.126000 0.319600 -vn -0.318845 0.770251 0.552314 -v -0.089600 0.126000 0.325677 -vn -0.088113 0.737697 0.669358 -v -0.089700 0.126000 0.325650 -vn -0.577350 0.577350 0.577352 -v -0.090000 0.126000 0.325650 -vn -0.088116 0.737688 -0.669367 -v -0.089700 0.126000 0.332750 -vn -0.577350 0.577351 -0.577351 -v -0.090000 0.126000 0.332750 -vn -0.727972 0.678876 0.095836 -v -0.090000 0.126000 0.337700 -vn -0.378564 0.653209 0.655749 -v -0.076750 0.126000 0.320633 -vn -0.095808 0.678883 0.727969 -v -0.076500 0.126000 0.320700 -vn -0.088130 0.737704 0.669348 -v -0.074500 0.126000 0.320700 -vn 0.727976 0.678872 0.095836 -v -0.083000 0.126000 0.320200 -vn 0.577351 0.577351 -0.577348 -v -0.083000 0.126000 0.319700 -vn 0.088119 0.737699 -0.669354 -v -0.083350 0.126000 0.319700 -vn -0.088133 0.737697 -0.669355 -v -0.074500 0.126000 0.337700 -vn -0.318885 0.770277 0.552255 -v -0.076550 0.126000 0.338727 -vn -0.552337 0.770225 0.318869 -v -0.076477 0.126000 0.338800 -vn -0.669348 0.737701 0.088150 -v -0.076450 0.126000 0.338900 -vn -0.707107 0.000000 0.707107 -v -0.076450 0.126000 0.339200 -vn 0.318852 0.770251 0.552310 -v -0.070400 0.126000 0.325677 -vn 0.669354 0.737699 0.088119 -v -0.088500 0.126000 0.323700 -vn 0.727972 0.678876 0.095836 -v -0.088500 0.126000 0.325700 -vn -0.577347 0.577347 0.577357 -v -0.089500 0.126000 0.326200 -vn 0.095852 0.678864 0.727981 -v -0.089000 0.126000 0.326200 -vn -0.669372 0.737685 0.088104 -v -0.089500 0.126000 0.325850 -vn 0.378591 0.653233 0.655710 -v -0.088750 0.126000 0.326133 -vn 0.095813 0.678875 0.727976 -v -0.083500 0.126000 0.320700 -vn 0.378554 0.653226 0.655739 -v -0.083250 0.126000 0.320633 -vn 0.655732 0.653218 0.378578 -v -0.083067 0.126000 0.320450 -vn 0.088133 0.737704 -0.669347 -v -0.088000 0.126000 0.335200 -vn 0.318877 0.770251 -0.552296 -v -0.088250 0.126000 0.335133 -vn 0.607111 0.753768 0.251496 -v -0.085962 0.126000 0.336276 -vn -0.318852 0.770251 -0.552310 -v -0.089600 0.126000 0.332723 -vn -0.552281 0.770269 0.318859 -v -0.089527 0.126000 0.325750 -vn 0.655734 0.653220 0.378571 -v -0.088567 0.126000 0.325950 -vn 0.655718 0.653227 0.378587 -v -0.070201 0.126000 0.338450 -vn 0.727973 0.678874 0.095840 -v -0.070000 0.126000 0.337700 -vn -0.669354 0.737699 -0.088119 -v -0.074000 0.126000 0.337200 -vn -0.552290 0.770260 -0.318866 -v -0.077618 0.126000 0.330575 -vn 0.433650 0.729852 -0.528455 -v -0.073086 0.126000 0.335054 -vn 0.528440 0.729850 -0.433670 -v -0.075354 0.126000 0.332786 -vn -0.669359 0.737696 -0.088110 -v -0.071500 0.126000 0.334700 -vn -0.552298 0.770260 -0.318852 -v -0.071567 0.126000 0.334950 -vn -0.318871 0.770262 -0.552284 -v -0.071750 0.126000 0.335133 -vn -0.433642 0.729855 0.528456 -v -0.086914 0.126000 0.323346 -vn -0.528436 0.729846 0.433681 -v -0.084646 0.126000 0.325614 -vn 0.552292 0.770259 0.318865 -v -0.082382 0.126000 0.327825 -vn -0.607123 0.753762 0.251485 -v -0.084538 0.126000 0.325776 -vn 0.637727 0.770263 -0.000000 -v -0.082750 0.126000 0.329200 -vn -0.727972 0.678876 -0.095836 -v -0.071500 0.126000 0.332700 -vn 0.088113 0.737697 -0.669358 -v -0.070300 0.126000 0.332750 -vn 0.577350 0.577350 -0.577352 -v -0.070000 0.126000 0.332750 -vn -0.655721 0.653229 -0.378579 -v -0.089799 0.126000 0.319950 -vn 0.669354 0.737699 0.088119 -v -0.086000 0.126000 0.321200 -vn -0.088133 0.737704 0.669347 -v -0.072000 0.126000 0.323200 -vn -0.318877 0.770251 0.552296 -v -0.071750 0.126000 0.323267 -vn -0.607133 0.753762 -0.251461 -v -0.074038 0.126000 0.322124 -vn -0.095837 0.678877 -0.727970 -v -0.088500 0.126000 0.319200 -vn 0.552297 0.770256 0.318862 -v -0.085933 0.126000 0.320950 -vn 0.318871 0.770263 0.552284 -v -0.085750 0.126000 0.320767 -vn -0.318868 0.770260 0.552289 -v -0.078625 0.126000 0.326818 -vn -0.528445 0.729843 -0.433676 -v -0.074146 0.126000 0.322286 -vn -0.433680 0.729847 -0.528436 -v -0.076414 0.126000 0.324554 -vn -0.607109 0.753772 0.251488 -v -0.074038 0.126000 0.336276 -vn -0.088136 0.737697 -0.669354 -v -0.072000 0.126000 0.335200 -vn 0.095811 0.678882 -0.727969 -v -0.083500 0.126000 0.337700 -vn 0.088133 0.737704 -0.669347 -v -0.085500 0.126000 0.337700 -vn 0.552328 0.770240 0.318848 -v -0.083523 0.126000 0.338800 -vn -0.134917 -0.034558 0.990254 -v -0.088500 0.126000 0.339200 -vn 0.669351 0.737701 0.088125 -v -0.083550 0.126000 0.338900 -vn 0.707109 0.000000 0.707104 -v -0.083550 0.126000 0.339200 -vn 0.528435 0.729835 0.433702 -v -0.085854 0.126000 0.336114 -vn 0.433689 0.729845 0.528432 -v -0.083586 0.126000 0.333846 -vn 0.318869 0.770260 -0.552289 -v -0.081375 0.126000 0.331582 -vn 0.251485 0.753766 0.607117 -v -0.083424 0.126000 0.333738 -vn -0.000001 0.770264 -0.637725 -v -0.080000 0.126000 0.331950 -vn -0.680331 0.729837 0.066997 -v -0.074000 0.126000 0.336468 -vn 0.577357 0.577347 0.577347 -v -0.083000 0.126000 0.338700 -vn 0.727979 0.678868 -0.095839 -v -0.083000 0.126000 0.338200 -vn 0.088122 0.737692 0.669362 -v -0.083350 0.126000 0.338700 -vn 0.655721 0.653232 -0.378573 -v -0.083067 0.126000 0.337950 -vn 0.669362 0.737692 -0.088122 -v -0.086000 0.126000 0.337200 -vn 0.680316 0.729849 0.067007 -v -0.086000 0.126000 0.336468 -vn -0.067053 0.729857 -0.680303 -v -0.087268 0.126000 0.335200 -vn 0.607131 0.753757 -0.251480 -v -0.085962 0.126000 0.322124 -vn 0.088136 0.737697 0.669354 -v -0.088000 0.126000 0.323200 -vn 0.088136 0.737698 0.669353 -v -0.085500 0.126000 0.320700 -vn 0.318882 0.770268 -0.552269 -v -0.083450 0.126000 0.319673 -vn 0.552324 0.770240 -0.318855 -v -0.083523 0.126000 0.319600 -vn 0.669361 0.737692 -0.088128 -v -0.083550 0.126000 0.319500 -vn 0.577351 0.577351 -0.577350 -v -0.083550 0.126000 0.319200 -vn -0.669362 0.737692 0.088122 -v -0.074000 0.126000 0.321200 -vn -0.680322 0.729845 -0.066995 -v -0.074000 0.126000 0.321932 -vn 0.067051 0.729856 0.680304 -v -0.072732 0.126000 0.323200 -vn 0.378573 0.653229 0.655724 -v -0.070750 0.126000 0.338999 -vn 0.318889 0.770268 0.552265 -v -0.083450 0.126000 0.338727 -vn 0.378559 0.653212 -0.655750 -v -0.083250 0.126000 0.337767 -vn 0.318877 0.770251 -0.552296 -v -0.085750 0.126000 0.337633 -vn 0.552285 0.770268 -0.318856 -v -0.085933 0.126000 0.337450 -vn -0.378572 0.653230 0.655724 -v -0.089250 0.126000 0.338999 -vn -0.655721 0.653226 0.378585 -v -0.089799 0.126000 0.338450 -vn 0.378596 0.653220 -0.655720 -v -0.088750 0.126000 0.332267 -vn 0.655724 0.653234 -0.378566 -v -0.088567 0.126000 0.332450 -vn 0.727979 0.678868 -0.095839 -v -0.088500 0.126000 0.332700 -vn -0.552286 0.770269 -0.318852 -v -0.089527 0.126000 0.332650 -vn 0.669361 0.737693 -0.088122 -v -0.088500 0.126000 0.334700 -vn 0.552285 0.770268 -0.318856 -v -0.088433 0.126000 0.334950 -vn 0.680325 0.729841 -0.067009 -v -0.086000 0.126000 0.321932 -vn -0.727979 0.678868 0.095839 -v -0.071500 0.126000 0.325700 -vn 0.552284 0.770260 0.318876 -v -0.070473 0.126000 0.325750 -vn -0.669366 0.737689 0.088113 -v -0.071500 0.126000 0.323700 -vn -0.552286 0.770271 0.318846 -v -0.071567 0.126000 0.323450 -vn 0.067002 0.729839 0.680328 -v -0.083232 0.126000 0.333700 -vn -0.067002 0.729847 0.680319 -v -0.076768 0.126000 0.333700 -vn -0.318868 0.770260 -0.552288 -v -0.078625 0.126000 0.331582 -vn -0.251477 0.753763 0.607125 -v -0.076576 0.126000 0.333738 -vn -0.433686 0.729839 0.528442 -v -0.076414 0.126000 0.333846 -vn -0.528429 0.729841 0.433699 -v -0.074146 0.126000 0.336114 -vn 0.251502 0.753732 -0.607153 -v -0.072924 0.126000 0.335162 -vn 0.067049 0.729864 -0.680296 -v -0.072732 0.126000 0.335200 -vn -0.378581 0.653227 -0.655722 -v -0.089250 0.126000 0.319401 -vn -0.318878 0.770255 0.552290 -v -0.074250 0.126000 0.320767 -vn -0.552291 0.770265 0.318852 -v -0.074067 0.126000 0.320950 -vn 0.378585 0.653226 -0.655720 -v -0.070750 0.126000 0.319401 -vn 0.655720 0.653231 -0.378578 -v -0.070201 0.126000 0.319950 -vn -0.680326 0.729840 0.067007 -v -0.084500 0.126000 0.325968 -vn -0.680317 0.729848 -0.067005 -v -0.084500 0.126000 0.332432 -vn 0.552290 0.770261 -0.318864 -v -0.082382 0.126000 0.330575 -vn -0.607125 0.753762 -0.251480 -v -0.084538 0.126000 0.332624 -vn -0.528444 0.729839 -0.433685 -v -0.084646 0.126000 0.332786 -vn -0.433638 0.729863 -0.528449 -v -0.086914 0.126000 0.335054 -vn -0.251505 0.753728 -0.607156 -v -0.087076 0.126000 0.335162 -vn -0.251483 0.753763 -0.607123 -v -0.076576 0.126000 0.324662 -vn -0.067004 0.729840 -0.680327 -v -0.076768 0.126000 0.324700 -vn -0.000000 0.770264 0.637725 -v -0.080000 0.126000 0.326450 -vn 0.067000 0.729847 -0.680320 -v -0.083232 0.126000 0.324700 -vn 0.318869 0.770261 0.552288 -v -0.081375 0.126000 0.326818 -vn 0.251480 0.753766 -0.607119 -v -0.083424 0.126000 0.324662 -vn 0.433692 0.729836 -0.528442 -v -0.083586 0.126000 0.324554 -vn 0.528437 0.729851 -0.433671 -v -0.085854 0.126000 0.322286 -vn -0.251499 0.753728 0.607159 -v -0.087076 0.126000 0.323238 -vn -0.067051 0.729865 0.680295 -v -0.087268 0.126000 0.323200 -vn 0.607131 0.753758 -0.251478 -v -0.075462 0.126000 0.332624 -vn 0.680326 0.729841 -0.067007 -v -0.075500 0.126000 0.332432 -vn -0.637727 0.770262 0.000000 -v -0.077250 0.126000 0.329200 -vn 0.680317 0.729848 0.067005 -v -0.075500 0.126000 0.325968 -vn -0.552289 0.770261 0.318865 -v -0.077618 0.126000 0.327825 -vn 0.607133 0.753758 0.251472 -v -0.075462 0.126000 0.325776 -vn 0.528447 0.729843 0.433674 -v -0.075354 0.126000 0.325614 -vn 0.433645 0.729860 0.528447 -v -0.073086 0.126000 0.323346 -vn 0.251507 0.753732 0.607151 -v -0.072924 0.126000 0.323238 -vn -0.378586 -0.653236 0.655710 -v -0.071250 -0.126000 0.326133 -vn -0.655732 -0.653218 0.378578 -v -0.071433 -0.126000 0.325950 -vn -0.727972 -0.678876 0.095836 -v -0.071500 -0.126000 0.325700 -vn -0.727976 -0.678872 0.095836 -v -0.077000 -0.126000 0.320200 -vn -0.577351 -0.577351 -0.577348 -v -0.077000 -0.126000 0.319700 -vn -0.088113 -0.737697 -0.669358 -v -0.076650 -0.126000 0.319700 -vn -0.577357 -0.577347 0.577347 -v -0.077000 -0.126000 0.338700 -vn -0.727979 -0.678868 -0.095839 -v -0.077000 -0.126000 0.338200 -vn -0.088116 -0.737689 0.669365 -v -0.076650 -0.126000 0.338700 -vn -0.655724 -0.653234 -0.378566 -v -0.076933 -0.126000 0.337950 -vn -0.655721 -0.653232 -0.378573 -v -0.071433 -0.126000 0.332450 -vn -0.378591 -0.653222 -0.655721 -v -0.071250 -0.126000 0.332267 -vn 0.669352 -0.737701 -0.088123 -v -0.070500 -0.126000 0.332550 -vn -0.095852 -0.678868 -0.727978 -v -0.071000 -0.126000 0.332200 -vn 0.577348 -0.577351 -0.577351 -v -0.070500 -0.126000 0.332200 -vn 0.669360 -0.737693 0.088127 -v -0.070500 -0.126000 0.325850 -vn 0.577347 -0.577347 0.577357 -v -0.070500 -0.126000 0.326200 -vn -0.095855 -0.678863 0.727981 -v -0.071000 -0.126000 0.326200 -vn -0.655734 -0.653220 0.378571 -v -0.076933 -0.126000 0.320450 -vn -0.378559 -0.653223 0.655738 -v -0.076750 -0.126000 0.320633 -vn -0.095811 -0.678876 0.727975 -v -0.076500 -0.126000 0.320700 -vn -0.088116 -0.737688 0.669367 -v -0.089700 -0.126000 0.325650 -vn -0.577350 -0.577351 0.577351 -v -0.090000 -0.126000 0.325650 -vn -0.727972 -0.678875 -0.095840 -v -0.090000 -0.126000 0.320700 -vn 0.095837 -0.678877 -0.727971 -v -0.071500 -0.126000 0.319200 -vn -0.552303 -0.770254 0.318858 -v -0.074067 -0.126000 0.320950 -vn -0.318872 -0.770266 0.552278 -v -0.074250 -0.126000 0.320767 -vn 0.095852 -0.678864 -0.727981 -v -0.089000 -0.126000 0.332200 -vn 0.378591 -0.653233 -0.655710 -v -0.088750 -0.126000 0.332267 -vn 0.655735 -0.653220 -0.378571 -v -0.088567 -0.126000 0.332450 -vn -0.378564 -0.653209 -0.655749 -v -0.076750 -0.126000 0.337767 -vn -0.095808 -0.678883 -0.727969 -v -0.076500 -0.126000 0.337700 -vn -0.318892 -0.770277 0.552251 -v -0.076550 -0.126000 0.338727 -vn -0.088130 -0.737704 -0.669348 -v -0.074500 -0.126000 0.337700 -vn -0.552341 -0.770225 0.318862 -v -0.076477 -0.126000 0.338800 -vn 0.134916 0.034559 0.990254 -v -0.071500 -0.126000 0.339200 -vn -0.669339 -0.737710 0.088147 -v -0.076450 -0.126000 0.338900 -vn -0.707109 -0.000000 0.707104 -v -0.076450 -0.126000 0.339200 -vn -0.552298 -0.770260 0.318852 -v -0.071567 -0.126000 0.323450 -vn -0.318871 -0.770262 0.552284 -v -0.071750 -0.126000 0.323267 -vn 0.727974 -0.678872 -0.095844 -v -0.070000 -0.126000 0.320700 -vn 0.577357 -0.577347 -0.577347 -v -0.083000 -0.126000 0.319700 -vn 0.727979 -0.678868 0.095839 -v -0.083000 -0.126000 0.320200 -vn 0.088122 -0.737692 -0.669362 -v -0.083350 -0.126000 0.319700 -vn 0.655721 -0.653232 0.378573 -v -0.083067 -0.126000 0.320450 -vn 0.318889 -0.770268 -0.552265 -v -0.083450 -0.126000 0.319673 -vn -0.088133 -0.737697 0.669355 -v -0.074500 -0.126000 0.320700 -vn -0.318885 -0.770277 -0.552255 -v -0.076550 -0.126000 0.319673 -vn -0.552337 -0.770225 -0.318869 -v -0.076477 -0.126000 0.319600 -vn -0.669348 -0.737701 -0.088150 -v -0.076450 -0.126000 0.319500 -vn -0.577351 -0.577351 -0.577350 -v -0.076450 -0.126000 0.319200 -vn -0.669359 -0.737696 0.088110 -v -0.071500 -0.126000 0.323700 -vn 0.095849 -0.678868 0.727977 -v -0.089000 -0.126000 0.326200 -vn -0.577348 -0.577351 0.577351 -v -0.089500 -0.126000 0.326200 -vn -0.669364 -0.737692 0.088101 -v -0.089500 -0.126000 0.325850 -vn 0.727976 -0.678872 -0.095836 -v -0.083000 -0.126000 0.338200 -vn 0.577351 -0.577351 0.577348 -v -0.083000 -0.126000 0.338700 -vn 0.088119 -0.737699 0.669354 -v -0.083350 -0.126000 0.338700 -vn -0.318852 -0.770251 0.552310 -v -0.089600 -0.126000 0.325677 -vn 0.552280 -0.770260 0.318884 -v -0.070473 -0.126000 0.325750 -vn 0.318845 -0.770251 0.552314 -v -0.070400 -0.126000 0.325677 -vn 0.088113 -0.737697 0.669358 -v -0.070300 -0.126000 0.325650 -vn 0.577350 -0.577350 0.577352 -v -0.070000 -0.126000 0.325650 -vn 0.669354 -0.737699 -0.088119 -v -0.088500 -0.126000 0.334700 -vn 0.552297 -0.770256 -0.318862 -v -0.088433 -0.126000 0.334950 -vn -0.727972 -0.678875 0.095837 -v -0.090000 -0.126000 0.337700 -vn 0.318871 -0.770262 -0.552284 -v -0.088250 -0.126000 0.335133 -vn 0.095813 -0.678875 -0.727976 -v -0.083500 -0.126000 0.337700 -vn 0.378554 -0.653226 -0.655739 -v -0.083250 -0.126000 0.337767 -vn 0.655732 -0.653218 -0.378578 -v -0.083067 -0.126000 0.337950 -vn -0.577347 -0.577347 -0.577357 -v -0.089500 -0.126000 0.332200 -vn -0.669372 -0.737685 -0.088104 -v -0.089500 -0.126000 0.332550 -vn -0.552281 -0.770269 -0.318859 -v -0.089527 -0.126000 0.332650 -vn -0.318845 -0.770251 -0.552314 -v -0.089600 -0.126000 0.332723 -vn 0.727972 -0.678876 -0.095836 -v -0.088500 -0.126000 0.332700 -vn -0.088113 -0.737697 -0.669358 -v -0.089700 -0.126000 0.332750 -vn -0.577350 -0.577350 -0.577352 -v -0.090000 -0.126000 0.332750 -vn 0.088133 -0.737704 0.669347 -v -0.088000 -0.126000 0.323200 -vn 0.318877 -0.770251 0.552296 -v -0.088250 -0.126000 0.323267 -vn 0.607133 -0.753757 -0.251475 -v -0.085962 -0.126000 0.322124 -vn -0.433642 -0.729855 -0.528456 -v -0.086914 -0.126000 0.335054 -vn -0.528436 -0.729846 -0.433681 -v -0.084646 -0.126000 0.332786 -vn 0.552292 -0.770259 -0.318865 -v -0.082382 -0.126000 0.330575 -vn -0.607123 -0.753762 -0.251485 -v -0.084538 -0.126000 0.332624 -vn 0.637727 -0.770263 0.000000 -v -0.082750 -0.126000 0.329200 -vn 0.088116 -0.737688 -0.669367 -v -0.070300 -0.126000 0.332750 -vn 0.577350 -0.577351 -0.577351 -v -0.070000 -0.126000 0.332750 -vn 0.727972 -0.678875 0.095840 -v -0.070000 -0.126000 0.337700 -vn -0.318868 -0.770260 -0.552289 -v -0.078625 -0.126000 0.331582 -vn -0.528435 -0.729835 0.433702 -v -0.074146 -0.126000 0.336114 -vn -0.433682 -0.729847 0.528435 -v -0.076414 -0.126000 0.333846 -vn -0.088133 -0.737704 -0.669347 -v -0.072000 -0.126000 0.335200 -vn -0.318877 -0.770251 -0.552296 -v -0.071750 -0.126000 0.335133 -vn -0.607111 -0.753773 0.251482 -v -0.074038 -0.126000 0.336276 -vn 0.655719 -0.653231 -0.378579 -v -0.070201 -0.126000 0.319950 -vn -0.669354 -0.737699 0.088119 -v -0.074000 -0.126000 0.321200 -vn 0.607109 -0.753768 0.251501 -v -0.085962 -0.126000 0.336276 -vn 0.088136 -0.737697 -0.669354 -v -0.088000 -0.126000 0.335200 -vn 0.088136 -0.737698 -0.669353 -v -0.085500 -0.126000 0.337700 -vn 0.318882 -0.770268 0.552269 -v -0.083450 -0.126000 0.338727 -vn 0.318871 -0.770263 -0.552284 -v -0.085750 -0.126000 0.337633 -vn 0.552324 -0.770240 0.318855 -v -0.083523 -0.126000 0.338800 -vn -0.134916 0.034557 0.990254 -v -0.088500 -0.126000 0.339200 -vn 0.669361 -0.737692 0.088128 -v -0.083550 -0.126000 0.338900 -vn 0.707107 0.000000 0.707107 -v -0.083550 -0.126000 0.339200 -vn 0.577352 -0.577350 -0.577350 -v -0.083550 -0.126000 0.319200 -vn 0.669351 -0.737701 -0.088125 -v -0.083550 -0.126000 0.319500 -vn -0.095837 -0.678876 -0.727972 -v -0.088500 -0.126000 0.319200 -vn 0.552328 -0.770240 -0.318848 -v -0.083523 -0.126000 0.319600 -vn 0.680325 -0.729841 0.067009 -v -0.086000 -0.126000 0.336468 -vn 0.669354 -0.737699 -0.088119 -v -0.086000 -0.126000 0.337200 -vn -0.655720 -0.653226 0.378586 -v -0.089799 -0.126000 0.338450 -vn -0.378571 -0.653230 0.655725 -v -0.089250 -0.126000 0.338999 -vn 0.552297 -0.770256 -0.318862 -v -0.085933 -0.126000 0.337450 -vn -0.669362 -0.737692 -0.088122 -v -0.074000 -0.126000 0.337200 -vn -0.680322 -0.729845 0.066995 -v -0.074000 -0.126000 0.336468 -vn 0.067051 -0.729856 -0.680304 -v -0.072732 -0.126000 0.335200 -vn 0.318852 -0.770252 -0.552310 -v -0.070400 -0.126000 0.332723 -vn 0.378559 -0.653212 0.655750 -v -0.083250 -0.126000 0.320633 -vn 0.095811 -0.678883 0.727969 -v -0.083500 -0.126000 0.320700 -vn 0.088133 -0.737704 0.669347 -v -0.085500 -0.126000 0.320700 -vn -0.727979 -0.678868 -0.095839 -v -0.071500 -0.126000 0.332700 -vn 0.552284 -0.770260 -0.318876 -v -0.070473 -0.126000 0.332650 -vn -0.669366 -0.737689 -0.088113 -v -0.071500 -0.126000 0.334700 -vn -0.552286 -0.770271 -0.318846 -v -0.071567 -0.126000 0.334950 -vn -0.552290 -0.770260 0.318866 -v -0.077618 -0.126000 0.327825 -vn 0.433650 -0.729852 0.528455 -v -0.073086 -0.126000 0.323346 -vn 0.528440 -0.729850 0.433670 -v -0.075354 -0.126000 0.325614 -vn -0.251483 -0.753763 0.607123 -v -0.076576 -0.126000 0.333738 -vn -0.067004 -0.729840 0.680327 -v -0.076768 -0.126000 0.333700 -vn -0.000000 -0.770264 -0.637725 -v -0.080000 -0.126000 0.331950 -vn 0.067000 -0.729847 0.680320 -v -0.083232 -0.126000 0.333700 -vn 0.318869 -0.770261 -0.552288 -v -0.081375 -0.126000 0.331582 -vn 0.251480 -0.753766 0.607119 -v -0.083424 -0.126000 0.333738 -vn 0.433693 -0.729837 0.528440 -v -0.083586 -0.126000 0.333846 -vn 0.528429 -0.729841 0.433699 -v -0.085854 -0.126000 0.336114 -vn -0.251499 -0.753728 -0.607159 -v -0.087076 -0.126000 0.335162 -vn -0.067051 -0.729865 -0.680295 -v -0.087268 -0.126000 0.335200 -vn -0.318878 -0.770255 -0.552290 -v -0.074250 -0.126000 0.337633 -vn -0.552291 -0.770265 -0.318852 -v -0.074067 -0.126000 0.337450 -vn 0.378575 -0.653229 0.655724 -v -0.070750 -0.126000 0.338999 -vn 0.655719 -0.653227 0.378585 -v -0.070201 -0.126000 0.338450 -vn -0.607131 -0.753762 -0.251467 -v -0.074038 -0.126000 0.322124 -vn -0.088136 -0.737697 0.669354 -v -0.072000 -0.126000 0.323200 -vn 0.528445 -0.729843 -0.433676 -v -0.085854 -0.126000 0.322286 -vn 0.433687 -0.729844 -0.528434 -v -0.083586 -0.126000 0.324554 -vn 0.318869 -0.770259 0.552289 -v -0.081375 -0.126000 0.326818 -vn 0.251485 -0.753766 -0.607117 -v -0.083424 -0.126000 0.324662 -vn -0.000001 -0.770264 0.637725 -v -0.080000 -0.126000 0.326450 -vn 0.607131 -0.753758 0.251478 -v -0.075462 -0.126000 0.325776 -vn 0.680326 -0.729841 0.067007 -v -0.075500 -0.126000 0.325968 -vn -0.637727 -0.770262 -0.000000 -v -0.077250 -0.126000 0.329200 -vn 0.680317 -0.729848 -0.067005 -v -0.075500 -0.126000 0.332432 -vn -0.552289 -0.770261 -0.318865 -v -0.077618 -0.126000 0.330575 -vn 0.607133 -0.753758 -0.251472 -v -0.075462 -0.126000 0.332624 -vn 0.528447 -0.729843 -0.433674 -v -0.075354 -0.126000 0.332786 -vn 0.433645 -0.729860 -0.528447 -v -0.073086 -0.126000 0.335054 -vn 0.251507 -0.753732 -0.607151 -v -0.072924 -0.126000 0.335162 -vn -0.680331 -0.729837 -0.066997 -v -0.074000 -0.126000 0.321932 -vn 0.669362 -0.737692 0.088122 -v -0.086000 -0.126000 0.321200 -vn 0.680316 -0.729849 -0.067007 -v -0.086000 -0.126000 0.321932 -vn -0.067053 -0.729857 0.680303 -v -0.087268 -0.126000 0.323200 -vn 0.378583 -0.653226 -0.655721 -v -0.070750 -0.126000 0.319401 -vn 0.318877 -0.770251 0.552296 -v -0.085750 -0.126000 0.320767 -vn 0.552285 -0.770268 0.318856 -v -0.085933 -0.126000 0.320950 -vn -0.378582 -0.653227 -0.655721 -v -0.089250 -0.126000 0.319401 -vn -0.655721 -0.653229 -0.378578 -v -0.089799 -0.126000 0.319950 -vn 0.378596 -0.653220 0.655720 -v -0.088750 -0.126000 0.326133 -vn 0.655724 -0.653234 0.378566 -v -0.088567 -0.126000 0.325950 -vn 0.727979 -0.678868 0.095839 -v -0.088500 -0.126000 0.325700 -vn -0.552286 -0.770269 0.318852 -v -0.089527 -0.126000 0.325750 -vn 0.669361 -0.737693 0.088122 -v -0.088500 -0.126000 0.323700 -vn 0.552285 -0.770268 0.318856 -v -0.088433 -0.126000 0.323450 -vn 0.067002 -0.729839 -0.680328 -v -0.083232 -0.126000 0.324700 -vn -0.067002 -0.729847 -0.680319 -v -0.076768 -0.126000 0.324700 -vn -0.318868 -0.770260 0.552288 -v -0.078625 -0.126000 0.326818 -vn -0.251477 -0.753763 -0.607125 -v -0.076576 -0.126000 0.324662 -vn -0.433685 -0.729839 -0.528444 -v -0.076414 -0.126000 0.324554 -vn -0.528437 -0.729851 -0.433671 -v -0.074146 -0.126000 0.322286 -vn 0.251502 -0.753732 0.607153 -v -0.072924 -0.126000 0.323238 -vn 0.067049 -0.729864 0.680296 -v -0.072732 -0.126000 0.323200 -vn -0.680326 -0.729840 -0.067007 -v -0.084500 -0.126000 0.332432 -vn -0.680317 -0.729848 0.067005 -v -0.084500 -0.126000 0.325968 -vn 0.552290 -0.770261 0.318864 -v -0.082382 -0.126000 0.327825 -vn -0.607125 -0.753762 0.251480 -v -0.084538 -0.126000 0.325776 -vn -0.528444 -0.729839 0.433685 -v -0.084646 -0.126000 0.325614 -vn -0.433638 -0.729863 0.528449 -v -0.086914 -0.126000 0.323346 -vn -0.251505 -0.753728 0.607156 -v -0.087076 -0.126000 0.323238 -vn 0.727980 -0.095845 -0.678865 -v -0.083000 0.145000 0.005000 -vn 0.655724 -0.378591 -0.653219 -v -0.083067 0.144750 0.005000 -vn 0.378575 -0.655736 -0.653216 -v -0.083250 0.144567 0.005000 -vn 0.727974 0.095842 -0.678873 -v -0.083000 0.127000 0.005000 -vn 0.577352 -0.577347 -0.577352 -v -0.083000 0.126500 0.005000 -vn 0.088119 -0.669354 -0.737699 -v -0.083350 0.126500 0.005000 -vn 0.577349 -0.577352 -0.577349 -v -0.070500 0.139000 0.005000 -vn -0.095856 -0.727982 -0.678863 -v -0.071000 0.139000 0.005000 -vn 0.669348 -0.088137 -0.737703 -v -0.070500 0.139350 0.005000 -vn -0.378584 -0.655722 -0.653225 -v -0.071250 0.139067 0.005000 -vn 0.552305 -0.318872 -0.770247 -v -0.070473 0.139450 0.005000 -vn -0.378588 -0.655731 -0.653214 -v -0.076750 0.144567 0.005000 -vn -0.655731 -0.378575 -0.653221 -v -0.076933 0.144750 0.005000 -vn -0.088113 0.669358 -0.737697 -v -0.076650 0.145500 0.005000 -vn -0.727974 -0.095842 -0.678873 -v -0.077000 0.145000 0.005000 -vn -0.577352 0.577348 -0.577352 -v -0.077000 0.145500 0.005000 -vn 0.095849 -0.727975 -0.678871 -v -0.089000 0.139000 0.005000 -vn -0.577347 -0.577352 -0.577352 -v -0.089500 0.139000 0.005000 -vn -0.669358 -0.088113 -0.737697 -v -0.089500 0.139350 0.005000 -vn -0.669345 0.088148 -0.737704 -v -0.076450 0.145700 0.005000 -vn -0.577350 0.577350 -0.577350 -v -0.076450 0.146000 0.005000 -vn 0.095837 0.727971 -0.678877 -v -0.071500 0.146000 0.005000 -vn 0.577352 0.577349 -0.577349 -v -0.083000 0.145500 0.005000 -vn 0.088120 0.669357 -0.737696 -v -0.083350 0.145500 0.005000 -vn 0.318864 0.552292 -0.770260 -v -0.083450 0.145527 0.005000 -vn 0.552293 0.318867 -0.770257 -v -0.083523 0.145600 0.005000 -vn -0.318870 0.552303 -0.770249 -v -0.074250 0.127567 0.005000 -vn -0.552288 0.318873 -0.770258 -v -0.074067 0.127750 0.005000 -vn 0.095837 -0.727972 -0.678876 -v -0.071500 0.126000 0.005000 -vn -0.727972 0.095836 -0.678876 -v -0.090000 0.144500 0.005000 -vn 0.318869 -0.552309 -0.770245 -v -0.088250 0.141933 0.005000 -vn 0.552282 -0.318877 -0.770261 -v -0.088433 0.141750 0.005000 -vn 0.378581 -0.655726 -0.653223 -v -0.088750 0.139067 0.005000 -vn 0.655726 -0.378594 -0.653216 -v -0.088567 0.139250 0.005000 -vn 0.727980 -0.095839 -0.678867 -v -0.088500 0.139500 0.005000 -vn 0.577348 -0.577354 -0.577348 -v -0.070000 0.139550 0.005000 -vn 0.088113 -0.669358 -0.737697 -v -0.070300 0.139550 0.005000 -vn 0.727973 0.095840 -0.678874 -v -0.070000 0.144500 0.005000 -vn 0.318864 -0.552279 -0.770268 -v -0.070400 0.139523 0.005000 -vn -0.552306 -0.318882 -0.770242 -v -0.076477 0.126400 0.005000 -vn -0.669339 -0.088147 -0.737710 -v -0.076450 0.126300 0.005000 -vn -0.577354 -0.577348 -0.577348 -v -0.076450 0.126000 0.005000 -vn 0.669357 -0.088126 -0.737696 -v -0.083550 0.126300 0.005000 -vn 0.577350 -0.577350 -0.577350 -v -0.083550 0.126000 0.005000 -vn -0.095837 -0.727971 -0.678877 -v -0.088500 0.126000 0.005000 -vn -0.655728 -0.378593 -0.653214 -v -0.071433 0.139250 0.005000 -vn -0.727973 -0.095836 -0.678875 -v -0.071500 0.139500 0.005000 -vn -0.669359 -0.088110 -0.737696 -v -0.071500 0.141500 0.005000 -vn -0.095852 0.727975 -0.678870 -v -0.071000 0.133000 0.005000 -vn 0.577348 0.577352 -0.577352 -v -0.070500 0.133000 0.005000 -vn 0.669345 0.088135 -0.737705 -v -0.070500 0.132650 0.005000 -vn 0.669363 -0.088122 -0.737691 -v -0.088500 0.141500 0.005000 -vn -0.552309 -0.318844 -0.770255 -v -0.089527 0.139450 0.005000 -vn -0.318868 -0.552277 -0.770268 -v -0.089600 0.139523 0.005000 -vn -0.088114 -0.669363 -0.737691 -v -0.089700 0.139550 0.005000 -vn -0.577350 -0.577350 -0.577350 -v -0.090000 0.139550 0.005000 -vn -0.552304 0.318885 -0.770242 -v -0.076477 0.145600 0.005000 -vn -0.088130 0.669348 -0.737704 -v -0.074500 0.127500 0.005000 -vn -0.095828 0.727972 -0.678877 -v -0.076500 0.127500 0.005000 -vn -0.577352 -0.577349 -0.577349 -v -0.077000 0.126500 0.005000 -vn -0.727980 0.095845 -0.678865 -v -0.077000 0.127000 0.005000 -vn -0.088114 -0.669360 -0.737694 -v -0.076650 0.126500 0.005000 -vn -0.655727 0.378583 -0.653221 -v -0.076933 0.127250 0.005000 -vn -0.727980 0.095839 -0.678867 -v -0.071500 0.132500 0.005000 -vn -0.655723 0.378601 -0.653214 -v -0.071433 0.132750 0.005000 -vn -0.378576 0.655726 -0.653225 -v -0.071250 0.132933 0.005000 -vn 0.669354 0.088119 -0.737699 -v -0.086000 0.128000 0.005000 -vn 0.552286 0.318870 -0.770261 -v -0.085933 0.127750 0.005000 -vn -0.251477 0.607118 -0.753768 -v -0.087076 0.130038 0.005000 -vn 0.552291 -0.318871 -0.770257 -v -0.083523 0.126400 0.005000 -vn -0.318868 -0.552277 -0.770268 -v -0.076550 0.126473 0.005000 -vn -0.378580 0.655735 -0.653214 -v -0.076750 0.127433 0.005000 -vn -0.378577 0.655723 -0.653228 -v -0.089250 0.145799 0.005000 -vn -0.095837 0.727973 -0.678875 -v -0.088500 0.146000 0.005000 -vn 0.088133 -0.669347 -0.737704 -v -0.088000 0.142000 0.005000 -vn 0.318866 -0.552292 -0.770259 -v -0.081375 0.138382 0.005000 -vn 0.528436 0.433686 -0.729844 -v -0.085854 0.142914 0.005000 -vn 0.433667 0.528440 -0.729852 -v -0.083586 0.140646 0.005000 -vn 0.088133 -0.669346 -0.737705 -v -0.085500 0.144500 0.005000 -vn 0.318869 -0.552309 -0.770245 -v -0.085750 0.144433 0.005000 -vn 0.552282 -0.318877 -0.770261 -v -0.085933 0.144250 0.005000 -vn -0.528437 -0.433683 -0.729845 -v -0.074146 0.129086 0.005000 -vn -0.433659 -0.528443 -0.729855 -v -0.076414 0.131354 0.005000 -vn -0.318864 0.552290 -0.770260 -v -0.078625 0.133618 0.005000 -vn -0.251489 -0.607134 -0.753752 -v -0.076576 0.131462 0.005000 -vn 0.000000 0.637729 -0.770261 -v -0.080000 0.133250 0.005000 -vn 0.095831 -0.727972 -0.678876 -v -0.083500 0.144500 0.005000 -vn 0.669351 0.088125 -0.737701 -v -0.083550 0.145700 0.005000 -vn 0.577354 0.577348 -0.577348 -v -0.083550 0.146000 0.005000 -vn 0.378585 -0.655721 -0.653226 -v -0.070750 0.126201 0.005000 -vn -0.088133 0.669347 -0.737704 -v -0.072000 0.130000 0.005000 -vn -0.669354 -0.088119 -0.737699 -v -0.074000 0.144000 0.005000 -vn -0.552292 -0.318866 -0.770258 -v -0.074067 0.144250 0.005000 -vn 0.251480 -0.607113 -0.753772 -v -0.072924 0.141962 0.005000 -vn 0.727973 -0.095842 -0.678874 -v -0.070000 0.127500 0.005000 -vn -0.318877 0.552297 -0.770250 -v -0.071750 0.130067 0.005000 -vn -0.552294 0.318864 -0.770258 -v -0.071567 0.130250 0.005000 -vn -0.552290 -0.318865 -0.770260 -v -0.077618 0.137375 0.005000 -vn 0.433690 -0.528435 -0.729842 -v -0.073086 0.141854 0.005000 -vn 0.528438 -0.433671 -0.729851 -v -0.075354 0.139586 0.005000 -vn -0.251478 -0.607118 -0.753768 -v -0.087076 0.141962 0.005000 -vn 0.669361 -0.088122 -0.737692 -v -0.086000 0.144000 0.005000 -vn 0.727973 0.095836 -0.678875 -v -0.088500 0.132500 0.005000 -vn 0.669352 0.088124 -0.737701 -v -0.088500 0.130500 0.005000 -vn -0.318864 0.552279 -0.770268 -v -0.089600 0.132477 0.005000 -vn -0.727973 -0.095838 -0.678875 -v -0.090000 0.127500 0.005000 -vn -0.088113 0.669358 -0.737697 -v -0.089700 0.132450 0.005000 -vn -0.577348 0.577354 -0.577348 -v -0.090000 0.132450 0.005000 -vn -0.433682 0.528437 -0.729846 -v -0.086914 0.130146 0.005000 -vn -0.528435 0.433681 -0.729847 -v -0.084646 0.132414 0.005000 -vn 0.552293 0.318864 -0.770259 -v -0.082382 0.134625 0.005000 -vn -0.607117 0.251475 -0.753770 -v -0.084538 0.132576 0.005000 -vn 0.637728 -0.000001 -0.770261 -v -0.082750 0.136000 0.005000 -vn -0.067003 -0.680319 -0.729847 -v -0.087268 0.142000 0.005000 -vn -0.577349 0.577352 -0.577349 -v -0.089500 0.133000 0.005000 -vn 0.095853 0.727981 -0.678863 -v -0.089000 0.133000 0.005000 -vn -0.669360 0.088114 -0.737694 -v -0.089500 0.132650 0.005000 -vn 0.378589 0.655721 -0.653223 -v -0.088750 0.132933 0.005000 -vn 0.088136 0.669354 -0.737698 -v -0.088000 0.130000 0.005000 -vn -0.067002 0.680319 -0.729847 -v -0.087268 0.130000 0.005000 -vn 0.680315 -0.067012 -0.729850 -v -0.086000 0.128732 0.005000 -vn 0.251481 0.607112 -0.753772 -v -0.072924 0.130038 0.005000 -vn -0.669361 0.088122 -0.737692 -v -0.074000 0.128000 0.005000 -vn -0.669365 0.088118 -0.737689 -v -0.071500 0.130500 0.005000 -vn 0.552307 0.318868 -0.770247 -v -0.070473 0.132550 0.005000 -vn 0.318868 0.552277 -0.770268 -v -0.070400 0.132477 0.005000 -vn 0.088114 0.669363 -0.737691 -v -0.070300 0.132450 0.005000 -vn 0.577350 0.577350 -0.577350 -v -0.070000 0.132450 0.005000 -vn -0.088136 -0.669354 -0.737698 -v -0.072000 0.142000 0.005000 -vn 0.067000 -0.680320 -0.729847 -v -0.072732 0.142000 0.005000 -vn -0.680321 0.067000 -0.729846 -v -0.074000 0.143268 0.005000 -vn -0.655723 0.378581 -0.653226 -v -0.089799 0.145250 0.005000 -vn -0.552307 0.318847 -0.770255 -v -0.089527 0.132550 0.005000 -vn 0.655730 0.378586 -0.653216 -v -0.088567 0.132750 0.005000 -vn 0.552298 0.318867 -0.770254 -v -0.088433 0.130250 0.005000 -vn 0.318884 0.552293 -0.770250 -v -0.088250 0.130067 0.005000 -vn -0.655723 -0.378578 -0.653228 -v -0.089799 0.126750 0.005000 -vn -0.378581 -0.655722 -0.653226 -v -0.089250 0.126201 0.005000 -vn 0.655729 0.378583 -0.653219 -v -0.083067 0.127250 0.005000 -vn 0.378583 0.655731 -0.653216 -v -0.083250 0.127433 0.005000 -vn 0.095835 0.727979 -0.678868 -v -0.083500 0.127500 0.005000 -vn 0.318861 -0.552293 -0.770260 -v -0.083450 0.126473 0.005000 -vn 0.088136 0.669355 -0.737696 -v -0.085500 0.127500 0.005000 -vn 0.318876 0.552305 -0.770245 -v -0.085750 0.127567 0.005000 -vn 0.067000 0.680321 -0.729846 -v -0.072732 0.130000 0.005000 -vn -0.095832 -0.727979 -0.678869 -v -0.076500 0.144500 0.005000 -vn -0.318864 0.552279 -0.770268 -v -0.076550 0.145527 0.005000 -vn -0.088133 -0.669357 -0.737695 -v -0.074500 0.144500 0.005000 -vn -0.318877 -0.552299 -0.770249 -v -0.074250 0.144433 0.005000 -vn -0.680321 0.067000 -0.729845 -v -0.084500 0.132768 0.005000 -vn -0.680320 -0.067000 -0.729847 -v -0.084500 0.139232 0.005000 -vn 0.552290 -0.318865 -0.770260 -v -0.082382 0.137375 0.005000 -vn -0.607118 -0.251474 -0.753770 -v -0.084538 0.139424 0.005000 -vn -0.528437 -0.433682 -0.729845 -v -0.084646 0.139586 0.005000 -vn -0.433681 -0.528435 -0.729847 -v -0.086914 0.141854 0.005000 -vn 0.607115 0.251490 -0.753766 -v -0.085962 0.143076 0.005000 -vn 0.680314 0.067012 -0.729851 -v -0.086000 0.143268 0.005000 -vn 0.655721 -0.378577 -0.653230 -v -0.070201 0.126750 0.005000 -vn -0.552287 -0.318860 -0.770265 -v -0.071567 0.141750 0.005000 -vn -0.318876 -0.552305 -0.770245 -v -0.071750 0.141933 0.005000 -vn 0.655720 0.378582 -0.653228 -v -0.070201 0.145250 0.005000 -vn 0.378579 0.655723 -0.653227 -v -0.070750 0.145799 0.005000 -vn -0.067027 -0.680308 -0.729855 -v -0.076768 0.131500 0.005000 -vn 0.067024 -0.680308 -0.729856 -v -0.083232 0.131500 0.005000 -vn 0.318866 0.552288 -0.770261 -v -0.081375 0.133618 0.005000 -vn 0.251491 -0.607129 -0.753755 -v -0.083424 0.131462 0.005000 -vn 0.433668 -0.528442 -0.729850 -v -0.083586 0.131354 0.005000 -vn 0.528438 -0.433671 -0.729851 -v -0.085854 0.129086 0.005000 -vn 0.607126 -0.251481 -0.753761 -v -0.085962 0.128924 0.005000 -vn 0.607126 -0.251467 -0.753766 -v -0.075462 0.139424 0.005000 -vn 0.680321 -0.067000 -0.729845 -v -0.075500 0.139232 0.005000 -vn -0.637729 -0.000000 -0.770261 -v -0.077250 0.136000 0.005000 -vn 0.680320 0.067000 -0.729847 -v -0.075500 0.132768 0.005000 -vn -0.552289 0.318865 -0.770261 -v -0.077618 0.134625 0.005000 -vn 0.607126 0.251466 -0.753766 -v -0.075462 0.132576 0.005000 -vn 0.528440 0.433671 -0.729850 -v -0.075354 0.132414 0.005000 -vn 0.433688 0.528433 -0.729844 -v -0.073086 0.130146 0.005000 -vn -0.607118 -0.251474 -0.753770 -v -0.074038 0.128924 0.005000 -vn -0.680320 -0.067000 -0.729847 -v -0.074000 0.128732 0.005000 -vn 0.251492 0.607129 -0.753755 -v -0.083424 0.140538 0.005000 -vn 0.067025 0.680310 -0.729854 -v -0.083232 0.140500 0.005000 -vn -0.000001 -0.637729 -0.770261 -v -0.080000 0.138750 0.005000 -vn -0.067027 0.680307 -0.729856 -v -0.076768 0.140500 0.005000 -vn -0.318865 -0.552289 -0.770261 -v -0.078625 0.138382 0.005000 -vn -0.251488 0.607135 -0.753752 -v -0.076576 0.140538 0.005000 -vn -0.433661 0.528443 -0.729854 -v -0.076414 0.140646 0.005000 -vn -0.528431 0.433695 -0.729842 -v -0.074146 0.142914 0.005000 -vn -0.607106 0.251486 -0.753775 -v -0.074038 0.143076 0.005000 -vn -0.655727 -0.378583 0.653221 -v -0.076933 0.144750 0.339200 -vn -0.378580 -0.655736 0.653214 -v -0.076750 0.144567 0.339200 -vn -0.095828 -0.727972 0.678877 -v -0.076500 0.144500 0.339200 -vn -0.095852 -0.727975 0.678870 -v -0.071000 0.139000 0.339200 -vn 0.577347 -0.577352 0.577352 -v -0.070500 0.139000 0.339200 -vn 0.669345 -0.088135 0.737705 -v -0.070500 0.139350 0.339200 -vn -0.577349 -0.577352 0.577349 -v -0.089500 0.139000 0.339200 -vn 0.095853 -0.727981 0.678863 -v -0.089000 0.139000 0.339200 -vn -0.669360 -0.088114 0.737694 -v -0.089500 0.139350 0.339200 -vn 0.378589 -0.655721 0.653223 -v -0.088750 0.139067 0.339200 -vn 0.378583 -0.655731 0.653216 -v -0.083250 0.144567 0.339200 -vn 0.655729 -0.378583 0.653219 -v -0.083067 0.144750 0.339200 -vn 0.088119 0.669354 0.737699 -v -0.083350 0.145500 0.339200 -vn 0.727974 -0.095842 0.678873 -v -0.083000 0.145000 0.339200 -vn 0.577352 0.577348 0.577352 -v -0.083000 0.145500 0.339200 -vn -0.088114 0.669360 0.737694 -v -0.076650 0.145500 0.339200 -vn -0.577352 0.577349 0.577349 -v -0.077000 0.145500 0.339200 -vn -0.727980 -0.095845 0.678865 -v -0.077000 0.145000 0.339200 -vn -0.378576 -0.655726 0.653225 -v -0.071250 0.139067 0.339200 -vn -0.655723 -0.378601 0.653214 -v -0.071433 0.139250 0.339200 -vn -0.727980 -0.095839 0.678867 -v -0.071500 0.139500 0.339200 -vn -0.669345 -0.088148 0.737704 -v -0.076450 0.126300 0.339200 -vn 0.727972 0.095840 0.678875 -v -0.070000 0.144500 0.339200 -vn -0.318869 -0.552309 0.770245 -v -0.071750 0.141933 0.339200 -vn -0.552283 -0.318867 0.770265 -v -0.071567 0.141750 0.339200 -vn 0.727980 0.095845 0.678865 -v -0.083000 0.127000 0.339200 -vn 0.655724 0.378591 0.653219 -v -0.083067 0.127250 0.339200 -vn 0.378575 0.655736 0.653216 -v -0.083250 0.127433 0.339200 -vn 0.655730 -0.378586 0.653216 -v -0.088567 0.139250 0.339200 -vn 0.727973 -0.095836 0.678875 -v -0.088500 0.139500 0.339200 -vn -0.552307 -0.318847 0.770255 -v -0.089527 0.139450 0.339200 -vn 0.669354 -0.088119 0.737699 -v -0.088500 0.141500 0.339200 -vn -0.318864 -0.552279 0.770268 -v -0.089600 0.139523 0.339200 -vn -0.727972 0.095836 0.678875 -v -0.090000 0.144500 0.339200 -vn -0.088113 -0.669358 0.737697 -v -0.089700 0.139550 0.339200 -vn -0.577348 -0.577354 0.577348 -v -0.090000 0.139550 0.339200 -vn -0.318870 -0.552303 0.770249 -v -0.074250 0.144433 0.339200 -vn -0.552288 -0.318873 0.770258 -v -0.074067 0.144250 0.339200 -vn 0.095837 0.727972 0.678876 -v -0.071500 0.146000 0.339200 -vn 0.577349 0.577352 0.577349 -v -0.070500 0.133000 0.339200 -vn -0.095856 0.727982 0.678863 -v -0.071000 0.133000 0.339200 -vn 0.669348 0.088137 0.737703 -v -0.070500 0.132650 0.339200 -vn -0.378584 0.655722 0.653225 -v -0.071250 0.132933 0.339200 -vn 0.552305 0.318872 0.770247 -v -0.070473 0.132550 0.339200 -vn -0.669368 -0.088113 0.737687 -v -0.071500 0.141500 0.339200 -vn 0.552307 -0.318869 0.770246 -v -0.070473 0.139450 0.339200 -vn 0.318868 -0.552277 0.770268 -v -0.070400 0.139523 0.339200 -vn 0.088114 -0.669364 0.737691 -v -0.070300 0.139550 0.339200 -vn 0.577350 -0.577350 0.577350 -v -0.070000 0.139550 0.339200 -vn -0.088130 -0.669348 0.737704 -v -0.074500 0.144500 0.339200 -vn -0.727974 0.095842 0.678873 -v -0.077000 0.127000 0.339200 -vn -0.577352 -0.577347 0.577352 -v -0.077000 0.126500 0.339200 -vn -0.088113 -0.669358 0.737697 -v -0.076650 0.126500 0.339200 -vn 0.095849 0.727975 0.678871 -v -0.089000 0.133000 0.339200 -vn -0.577348 0.577352 0.577352 -v -0.089500 0.133000 0.339200 -vn -0.669358 0.088113 0.737697 -v -0.089500 0.132650 0.339200 -vn -0.552304 -0.318885 0.770242 -v -0.076477 0.126400 0.339200 -vn -0.318868 0.552277 0.770268 -v -0.076550 0.145527 0.339200 -vn -0.552306 0.318882 0.770242 -v -0.076477 0.145600 0.339200 -vn -0.669339 0.088147 0.737710 -v -0.076450 0.145700 0.339200 -vn -0.577354 0.577348 0.577348 -v -0.076450 0.146000 0.339200 -vn 0.088133 0.669346 0.737705 -v -0.085500 0.127500 0.339200 -vn 0.318869 0.552309 0.770245 -v -0.085750 0.127567 0.339200 -vn 0.552282 0.318877 0.770261 -v -0.085933 0.127750 0.339200 -vn 0.727980 0.095839 0.678867 -v -0.088500 0.132500 0.339200 -vn 0.655726 0.378594 0.653216 -v -0.088567 0.132750 0.339200 -vn 0.378581 0.655726 0.653223 -v -0.088750 0.132933 0.339200 -vn 0.577352 -0.577349 0.577349 -v -0.083000 0.126500 0.339200 -vn 0.088120 -0.669357 0.737696 -v -0.083350 0.126500 0.339200 -vn 0.318864 -0.552291 0.770260 -v -0.083450 0.126473 0.339200 -vn 0.552293 -0.318867 0.770257 -v -0.083523 0.126400 0.339200 -vn 0.095831 0.727972 0.678876 -v -0.083500 0.127500 0.339200 -vn 0.669351 -0.088125 0.737701 -v -0.083550 0.126300 0.339200 -vn -0.669354 0.088119 0.737699 -v -0.074000 0.128000 0.339200 -vn -0.552292 0.318866 0.770258 -v -0.074067 0.127750 0.339200 -vn 0.251480 0.607113 0.753772 -v -0.072924 0.130038 0.339200 -vn 0.528440 -0.433672 0.729849 -v -0.085854 0.129086 0.339200 -vn 0.433666 -0.528440 0.729853 -v -0.083586 0.131354 0.339200 -vn 0.318865 0.552290 0.770260 -v -0.081375 0.133618 0.339200 -vn 0.251492 -0.607129 0.753755 -v -0.083424 0.131462 0.339200 -vn -0.000001 0.637729 0.770261 -v -0.080000 0.133250 0.339200 -vn 0.669357 0.088126 0.737696 -v -0.083550 0.145700 0.339200 -vn 0.577350 0.577350 0.577350 -v -0.083550 0.146000 0.339200 -vn -0.095837 0.727971 0.678877 -v -0.088500 0.146000 0.339200 -vn 0.552293 -0.318865 0.770258 -v -0.082382 0.137375 0.339200 -vn -0.433683 -0.528437 0.729845 -v -0.086914 0.141854 0.339200 -vn -0.528435 -0.433681 0.729847 -v -0.084646 0.139586 0.339200 -vn 0.669354 -0.088119 0.737699 -v -0.086000 0.144000 0.339200 -vn 0.552286 -0.318870 0.770261 -v -0.085933 0.144250 0.339200 -vn -0.251477 -0.607118 0.753768 -v -0.087076 0.141962 0.339200 -vn 0.378580 0.655722 0.653227 -v -0.070750 0.145799 0.339200 -vn -0.088133 -0.669347 0.737704 -v -0.072000 0.142000 0.339200 -vn -0.251478 0.607118 0.753768 -v -0.087076 0.130038 0.339200 -vn 0.669361 0.088122 0.737692 -v -0.086000 0.128000 0.339200 -vn 0.669360 0.088127 0.737693 -v -0.088500 0.130500 0.339200 -vn -0.552308 0.318844 0.770256 -v -0.089527 0.132550 0.339200 -vn 0.552294 0.318874 0.770254 -v -0.088433 0.130250 0.339200 -vn -0.318868 0.552277 0.770268 -v -0.089600 0.132477 0.339200 -vn -0.727972 -0.095838 0.678875 -v -0.090000 0.127500 0.339200 -vn -0.088114 0.669364 0.737691 -v -0.089700 0.132450 0.339200 -vn -0.577350 0.577350 0.577350 -v -0.090000 0.132450 0.339200 -vn 0.577348 0.577354 0.577348 -v -0.070000 0.132450 0.339200 -vn 0.088113 0.669358 0.737697 -v -0.070300 0.132450 0.339200 -vn 0.727973 -0.095842 0.678873 -v -0.070000 0.127500 0.339200 -vn 0.318864 0.552279 0.770268 -v -0.070400 0.132477 0.339200 -vn -0.067003 0.680319 0.729847 -v -0.087268 0.130000 0.339200 -vn 0.088133 0.669347 0.737704 -v -0.088000 0.130000 0.339200 -vn -0.378582 -0.655722 0.653226 -v -0.089250 0.126201 0.339200 -vn -0.655723 -0.378577 0.653228 -v -0.089799 0.126750 0.339200 -vn 0.318877 0.552297 0.770250 -v -0.088250 0.130067 0.339200 -vn 0.088136 -0.669354 0.737698 -v -0.088000 0.142000 0.339200 -vn -0.067002 -0.680319 0.729847 -v -0.087268 0.142000 0.339200 -vn 0.680315 0.067012 0.729850 -v -0.086000 0.143268 0.339200 -vn 0.552291 0.318871 0.770257 -v -0.083523 0.145600 0.339200 -vn -0.655728 0.378593 0.653214 -v -0.071433 0.132750 0.339200 -vn -0.727973 0.095836 0.678875 -v -0.071500 0.132500 0.339200 -vn -0.669356 0.088115 0.737698 -v -0.071500 0.130500 0.339200 -vn 0.095835 -0.727979 0.678868 -v -0.083500 0.144500 0.339200 -vn 0.318861 0.552293 0.770260 -v -0.083450 0.145527 0.339200 -vn 0.088136 -0.669355 0.737696 -v -0.085500 0.144500 0.339200 -vn 0.318876 -0.552305 0.770245 -v -0.085750 0.144433 0.339200 -vn -0.318865 -0.552290 0.770260 -v -0.078625 0.138382 0.339200 -vn -0.528432 0.433695 0.729841 -v -0.074146 0.142914 0.339200 -vn -0.433661 0.528442 0.729854 -v -0.076414 0.140646 0.339200 -vn -0.607117 -0.251475 0.753770 -v -0.084538 0.139424 0.339200 -vn -0.680321 -0.067000 0.729845 -v -0.084500 0.139232 0.339200 -vn 0.637729 -0.000000 0.770261 -v -0.082750 0.136000 0.339200 -vn -0.680320 0.067000 0.729847 -v -0.084500 0.132768 0.339200 -vn 0.552290 0.318864 0.770260 -v -0.082382 0.134625 0.339200 -vn -0.607118 0.251474 0.753770 -v -0.084538 0.132576 0.339200 -vn -0.528436 0.433682 0.729846 -v -0.084646 0.132414 0.339200 -vn -0.433681 0.528435 0.729847 -v -0.086914 0.130146 0.339200 -vn 0.607126 -0.251480 0.753761 -v -0.085962 0.128924 0.339200 -vn 0.680314 -0.067012 0.729851 -v -0.086000 0.128732 0.339200 -vn 0.552286 -0.318870 0.770261 -v -0.088433 0.141750 0.339200 -vn 0.318876 -0.552305 0.770245 -v -0.088250 0.141933 0.339200 -vn -0.655722 0.378581 0.653226 -v -0.089799 0.145250 0.339200 -vn -0.378576 0.655724 0.653228 -v -0.089250 0.145799 0.339200 -vn 0.251481 -0.607112 0.753772 -v -0.072924 0.141962 0.339200 -vn -0.669361 -0.088122 0.737692 -v -0.074000 0.144000 0.339200 -vn 0.433689 0.528434 0.729843 -v -0.073086 0.130146 0.339200 -vn 0.528438 0.433671 0.729851 -v -0.075354 0.132414 0.339200 -vn -0.552290 0.318864 0.770261 -v -0.077618 0.134625 0.339200 -vn 0.607126 0.251467 0.753766 -v -0.075462 0.132576 0.339200 -vn -0.637728 -0.000001 0.770261 -v -0.077250 0.136000 0.339200 -vn -0.251489 0.607134 0.753752 -v -0.076576 0.140538 0.339200 -vn -0.067027 0.680308 0.729855 -v -0.076768 0.140500 0.339200 -vn 0.000000 -0.637729 0.770261 -v -0.080000 0.138750 0.339200 -vn 0.067024 0.680308 0.729856 -v -0.083232 0.140500 0.339200 -vn 0.318866 -0.552288 0.770261 -v -0.081375 0.138382 0.339200 -vn 0.251491 0.607129 0.753755 -v -0.083424 0.140538 0.339200 -vn 0.433668 0.528441 0.729850 -v -0.083586 0.140646 0.339200 -vn 0.528434 0.433685 0.729846 -v -0.085854 0.142914 0.339200 -vn 0.607115 0.251491 0.753766 -v -0.085962 0.143076 0.339200 -vn 0.067000 -0.680321 0.729846 -v -0.072732 0.142000 0.339200 -vn -0.088136 0.669354 0.737698 -v -0.072000 0.130000 0.339200 -vn 0.067000 0.680320 0.729847 -v -0.072732 0.130000 0.339200 -vn -0.680320 -0.067000 0.729846 -v -0.074000 0.128732 0.339200 -vn 0.655721 0.378581 0.653228 -v -0.070201 0.145250 0.339200 -vn -0.552298 0.318857 0.770257 -v -0.071567 0.130250 0.339200 -vn -0.318884 0.552293 0.770250 -v -0.071750 0.130067 0.339200 -vn 0.655721 -0.378578 0.653230 -v -0.070201 0.126750 0.339200 -vn 0.378584 -0.655721 0.653226 -v -0.070750 0.126201 0.339200 -vn -0.655731 0.378575 0.653221 -v -0.076933 0.127250 0.339200 -vn -0.378588 0.655731 0.653214 -v -0.076750 0.127433 0.339200 -vn -0.095832 0.727979 0.678869 -v -0.076500 0.127500 0.339200 -vn -0.318864 -0.552279 0.770268 -v -0.076550 0.126473 0.339200 -vn -0.088133 0.669357 0.737695 -v -0.074500 0.127500 0.339200 -vn -0.318877 0.552299 0.770249 -v -0.074250 0.127567 0.339200 -vn 0.680321 0.067000 0.729845 -v -0.075500 0.132768 0.339200 -vn 0.680320 -0.067000 0.729847 -v -0.075500 0.139232 0.339200 -vn -0.552289 -0.318866 0.770260 -v -0.077618 0.137375 0.339200 -vn 0.607126 -0.251466 0.753766 -v -0.075462 0.139424 0.339200 -vn 0.528440 -0.433672 0.729849 -v -0.075354 0.139586 0.339200 -vn 0.433688 -0.528433 0.729844 -v -0.073086 0.141854 0.339200 -vn -0.607107 0.251485 0.753775 -v -0.074038 0.143076 0.339200 -vn -0.680320 0.067000 0.729847 -v -0.074000 0.143268 0.339200 -vn 0.067025 -0.680309 0.729854 -v -0.083232 0.131500 0.339200 -vn -0.067027 -0.680307 0.729856 -v -0.076768 0.131500 0.339200 -vn -0.318866 0.552289 0.770261 -v -0.078625 0.133618 0.339200 -vn -0.251488 -0.607135 0.753752 -v -0.076576 0.131462 0.339200 -vn -0.433661 -0.528445 0.729853 -v -0.076414 0.131354 0.339200 -vn -0.528435 -0.433681 0.729847 -v -0.074146 0.129086 0.339200 -vn -0.607117 -0.251475 0.753770 -v -0.074038 0.128924 0.339200 -vn 0.727980 -0.095845 -0.678865 -v -0.083000 -0.127000 0.005000 -vn 0.655724 -0.378591 -0.653219 -v -0.083067 -0.127250 0.005000 -vn 0.378575 -0.655736 -0.653216 -v -0.083250 -0.127433 0.005000 -vn 0.727974 0.095842 -0.678873 -v -0.083000 -0.145000 0.005000 -vn 0.577352 -0.577347 -0.577352 -v -0.083000 -0.145500 0.005000 -vn 0.088119 -0.669354 -0.737699 -v -0.083350 -0.145500 0.005000 -vn 0.577349 -0.577352 -0.577349 -v -0.070500 -0.133000 0.005000 -vn -0.095856 -0.727982 -0.678863 -v -0.071000 -0.133000 0.005000 -vn 0.669348 -0.088137 -0.737703 -v -0.070500 -0.132650 0.005000 -vn -0.378584 -0.655722 -0.653225 -v -0.071250 -0.132933 0.005000 -vn 0.552305 -0.318872 -0.770247 -v -0.070473 -0.132550 0.005000 -vn -0.378588 -0.655731 -0.653214 -v -0.076750 -0.127433 0.005000 -vn -0.655731 -0.378575 -0.653221 -v -0.076933 -0.127250 0.005000 -vn -0.088113 0.669358 -0.737697 -v -0.076650 -0.126500 0.005000 -vn -0.727974 -0.095842 -0.678873 -v -0.077000 -0.127000 0.005000 -vn -0.577352 0.577348 -0.577352 -v -0.077000 -0.126500 0.005000 -vn 0.095849 -0.727975 -0.678871 -v -0.089000 -0.133000 0.005000 -vn -0.577347 -0.577352 -0.577352 -v -0.089500 -0.133000 0.005000 -vn -0.669358 -0.088113 -0.737697 -v -0.089500 -0.132650 0.005000 -vn -0.669345 0.088148 -0.737704 -v -0.076450 -0.126300 0.005000 -vn -0.577350 0.577350 -0.577350 -v -0.076450 -0.126000 0.005000 -vn 0.095837 0.727971 -0.678877 -v -0.071500 -0.126000 0.005000 -vn 0.577352 0.577349 -0.577349 -v -0.083000 -0.126500 0.005000 -vn 0.088120 0.669357 -0.737696 -v -0.083350 -0.126500 0.005000 -vn 0.318864 0.552292 -0.770260 -v -0.083450 -0.126473 0.005000 -vn 0.552293 0.318867 -0.770257 -v -0.083523 -0.126400 0.005000 -vn -0.318870 0.552303 -0.770249 -v -0.074250 -0.144433 0.005000 -vn -0.552288 0.318873 -0.770258 -v -0.074067 -0.144250 0.005000 -vn 0.095837 -0.727972 -0.678876 -v -0.071500 -0.146000 0.005000 -vn -0.727972 0.095838 -0.678875 -v -0.090000 -0.127500 0.005000 -vn 0.318877 -0.552297 -0.770250 -v -0.088250 -0.130067 0.005000 -vn 0.552293 -0.318874 -0.770254 -v -0.088433 -0.130250 0.005000 -vn 0.378581 -0.655726 -0.653223 -v -0.088750 -0.132933 0.005000 -vn 0.655726 -0.378594 -0.653216 -v -0.088567 -0.132750 0.005000 -vn 0.727980 -0.095839 -0.678867 -v -0.088500 -0.132500 0.005000 -vn 0.577348 -0.577354 -0.577348 -v -0.070000 -0.132450 0.005000 -vn 0.088113 -0.669358 -0.737697 -v -0.070300 -0.132450 0.005000 -vn 0.727973 0.095842 -0.678873 -v -0.070000 -0.127500 0.005000 -vn 0.318864 -0.552279 -0.770268 -v -0.070400 -0.132477 0.005000 -vn -0.552306 -0.318882 -0.770242 -v -0.076477 -0.145600 0.005000 -vn -0.669339 -0.088147 -0.737710 -v -0.076450 -0.145700 0.005000 -vn -0.577354 -0.577348 -0.577348 -v -0.076450 -0.146000 0.005000 -vn 0.669357 -0.088126 -0.737696 -v -0.083550 -0.145700 0.005000 -vn 0.577350 -0.577350 -0.577350 -v -0.083550 -0.146000 0.005000 -vn -0.095837 -0.727971 -0.678877 -v -0.088500 -0.146000 0.005000 -vn -0.655728 -0.378593 -0.653214 -v -0.071433 -0.132750 0.005000 -vn -0.727973 -0.095836 -0.678875 -v -0.071500 -0.132500 0.005000 -vn -0.669356 -0.088115 -0.737698 -v -0.071500 -0.130500 0.005000 -vn -0.095852 0.727975 -0.678870 -v -0.071000 -0.139000 0.005000 -vn 0.577348 0.577352 -0.577352 -v -0.070500 -0.139000 0.005000 -vn 0.669345 0.088135 -0.737705 -v -0.070500 -0.139350 0.005000 -vn 0.669360 -0.088127 -0.737693 -v -0.088500 -0.130500 0.005000 -vn -0.552308 -0.318844 -0.770256 -v -0.089527 -0.132550 0.005000 -vn -0.318868 -0.552277 -0.770268 -v -0.089600 -0.132477 0.005000 -vn -0.088114 -0.669363 -0.737691 -v -0.089700 -0.132450 0.005000 -vn -0.577350 -0.577350 -0.577350 -v -0.090000 -0.132450 0.005000 -vn -0.552304 0.318885 -0.770242 -v -0.076477 -0.126400 0.005000 -vn -0.088130 0.669348 -0.737704 -v -0.074500 -0.144500 0.005000 -vn -0.095828 0.727972 -0.678877 -v -0.076500 -0.144500 0.005000 -vn -0.577352 -0.577349 -0.577349 -v -0.077000 -0.145500 0.005000 -vn -0.727980 0.095845 -0.678865 -v -0.077000 -0.145000 0.005000 -vn -0.088114 -0.669360 -0.737694 -v -0.076650 -0.145500 0.005000 -vn -0.655727 0.378583 -0.653221 -v -0.076933 -0.144750 0.005000 -vn -0.727980 0.095839 -0.678867 -v -0.071500 -0.139500 0.005000 -vn -0.655723 0.378601 -0.653214 -v -0.071433 -0.139250 0.005000 -vn -0.378576 0.655726 -0.653225 -v -0.071250 -0.139067 0.005000 -vn 0.669354 0.088119 -0.737699 -v -0.086000 -0.144000 0.005000 -vn 0.552286 0.318870 -0.770261 -v -0.085933 -0.144250 0.005000 -vn -0.251477 0.607118 -0.753768 -v -0.087076 -0.141962 0.005000 -vn 0.552291 -0.318871 -0.770257 -v -0.083523 -0.145600 0.005000 -vn -0.318868 -0.552277 -0.770268 -v -0.076550 -0.145527 0.005000 -vn -0.378580 0.655735 -0.653214 -v -0.076750 -0.144567 0.005000 -vn -0.378582 0.655721 -0.653226 -v -0.089250 -0.126201 0.005000 -vn -0.095837 0.727973 -0.678875 -v -0.088500 -0.126000 0.005000 -vn 0.088133 -0.669347 -0.737704 -v -0.088000 -0.130000 0.005000 -vn 0.318865 -0.552290 -0.770260 -v -0.081375 -0.133618 0.005000 -vn 0.528440 0.433671 -0.729850 -v -0.085854 -0.129086 0.005000 -vn 0.433666 0.528440 -0.729853 -v -0.083586 -0.131354 0.005000 -vn 0.088133 -0.669346 -0.737705 -v -0.085500 -0.127500 0.005000 -vn 0.318869 -0.552309 -0.770245 -v -0.085750 -0.127567 0.005000 -vn 0.552282 -0.318877 -0.770261 -v -0.085933 -0.127750 0.005000 -vn -0.528432 -0.433696 -0.729841 -v -0.074146 -0.142914 0.005000 -vn -0.433661 -0.528442 -0.729854 -v -0.076414 -0.140646 0.005000 -vn -0.318864 0.552290 -0.770260 -v -0.078625 -0.138382 0.005000 -vn -0.251489 -0.607134 -0.753752 -v -0.076576 -0.140538 0.005000 -vn 0.000000 0.637729 -0.770261 -v -0.080000 -0.138750 0.005000 -vn 0.095831 -0.727972 -0.678876 -v -0.083500 -0.127500 0.005000 -vn 0.669351 0.088125 -0.737701 -v -0.083550 -0.126300 0.005000 -vn 0.577354 0.577348 -0.577348 -v -0.083550 -0.126000 0.005000 -vn 0.378580 -0.655722 -0.653227 -v -0.070750 -0.145799 0.005000 -vn -0.088133 0.669347 -0.737704 -v -0.072000 -0.142000 0.005000 -vn -0.669354 -0.088119 -0.737699 -v -0.074000 -0.128000 0.005000 -vn -0.552292 -0.318866 -0.770258 -v -0.074067 -0.127750 0.005000 -vn 0.251480 -0.607113 -0.753772 -v -0.072924 -0.130038 0.005000 -vn 0.727972 -0.095840 -0.678875 -v -0.070000 -0.144500 0.005000 -vn -0.318869 0.552309 -0.770245 -v -0.071750 -0.141933 0.005000 -vn -0.552283 0.318867 -0.770265 -v -0.071567 -0.141750 0.005000 -vn -0.552290 -0.318864 -0.770261 -v -0.077618 -0.134625 0.005000 -vn 0.433690 -0.528435 -0.729842 -v -0.073086 -0.130146 0.005000 -vn 0.528438 -0.433671 -0.729851 -v -0.075354 -0.132414 0.005000 -vn -0.251478 -0.607118 -0.753768 -v -0.087076 -0.130038 0.005000 -vn 0.669361 -0.088122 -0.737692 -v -0.086000 -0.128000 0.005000 -vn 0.727973 0.095836 -0.678875 -v -0.088500 -0.139500 0.005000 -vn 0.669354 0.088119 -0.737699 -v -0.088500 -0.141500 0.005000 -vn -0.318864 0.552279 -0.770268 -v -0.089600 -0.139523 0.005000 -vn -0.727972 -0.095836 -0.678875 -v -0.090000 -0.144500 0.005000 -vn -0.088113 0.669358 -0.737697 -v -0.089700 -0.139550 0.005000 -vn -0.577348 0.577354 -0.577348 -v -0.090000 -0.139550 0.005000 -vn -0.433682 0.528437 -0.729846 -v -0.086914 -0.141854 0.005000 -vn -0.528435 0.433681 -0.729847 -v -0.084646 -0.139586 0.005000 -vn 0.552293 0.318865 -0.770258 -v -0.082382 -0.137375 0.005000 -vn -0.607117 0.251475 -0.753770 -v -0.084538 -0.139424 0.005000 -vn 0.637728 0.000000 -0.770261 -v -0.082750 -0.136000 0.005000 -vn -0.067003 -0.680319 -0.729847 -v -0.087268 -0.130000 0.005000 -vn -0.577349 0.577352 -0.577349 -v -0.089500 -0.139000 0.005000 -vn 0.095853 0.727981 -0.678863 -v -0.089000 -0.139000 0.005000 -vn -0.669360 0.088114 -0.737694 -v -0.089500 -0.139350 0.005000 -vn 0.378589 0.655721 -0.653223 -v -0.088750 -0.139067 0.005000 -vn 0.088136 0.669354 -0.737698 -v -0.088000 -0.142000 0.005000 -vn -0.067002 0.680319 -0.729847 -v -0.087268 -0.142000 0.005000 -vn 0.680315 -0.067012 -0.729850 -v -0.086000 -0.143268 0.005000 -vn 0.251481 0.607112 -0.753772 -v -0.072924 -0.141962 0.005000 -vn -0.669361 0.088122 -0.737692 -v -0.074000 -0.144000 0.005000 -vn -0.669368 0.088113 -0.737687 -v -0.071500 -0.141500 0.005000 -vn 0.552307 0.318869 -0.770246 -v -0.070473 -0.139450 0.005000 -vn 0.318868 0.552277 -0.770268 -v -0.070400 -0.139523 0.005000 -vn 0.088114 0.669363 -0.737691 -v -0.070300 -0.139550 0.005000 -vn 0.577350 0.577350 -0.577350 -v -0.070000 -0.139550 0.005000 -vn -0.088136 -0.669354 -0.737698 -v -0.072000 -0.130000 0.005000 -vn 0.067000 -0.680320 -0.729847 -v -0.072732 -0.130000 0.005000 -vn -0.680321 0.067000 -0.729846 -v -0.074000 -0.128732 0.005000 -vn -0.655723 0.378577 -0.653228 -v -0.089799 -0.126750 0.005000 -vn -0.552307 0.318847 -0.770255 -v -0.089527 -0.139450 0.005000 -vn 0.655730 0.378586 -0.653216 -v -0.088567 -0.139250 0.005000 -vn 0.552286 0.318870 -0.770261 -v -0.088433 -0.141750 0.005000 -vn 0.318876 0.552305 -0.770245 -v -0.088250 -0.141933 0.005000 -vn -0.655722 -0.378581 -0.653226 -v -0.089799 -0.145250 0.005000 -vn -0.378576 -0.655724 -0.653228 -v -0.089250 -0.145799 0.005000 -vn 0.655729 0.378583 -0.653219 -v -0.083067 -0.144750 0.005000 -vn 0.378583 0.655731 -0.653216 -v -0.083250 -0.144567 0.005000 -vn 0.095835 0.727979 -0.678868 -v -0.083500 -0.144500 0.005000 -vn 0.318861 -0.552293 -0.770260 -v -0.083450 -0.145527 0.005000 -vn 0.088136 0.669355 -0.737696 -v -0.085500 -0.144500 0.005000 -vn 0.318876 0.552305 -0.770245 -v -0.085750 -0.144433 0.005000 -vn 0.067000 0.680321 -0.729846 -v -0.072732 -0.142000 0.005000 -vn -0.095832 -0.727979 -0.678869 -v -0.076500 -0.127500 0.005000 -vn -0.318864 0.552279 -0.770268 -v -0.076550 -0.126473 0.005000 -vn -0.088133 -0.669357 -0.737695 -v -0.074500 -0.127500 0.005000 -vn -0.318877 -0.552299 -0.770249 -v -0.074250 -0.127567 0.005000 -vn -0.680321 0.067000 -0.729845 -v -0.084500 -0.139232 0.005000 -vn -0.680320 -0.067000 -0.729847 -v -0.084500 -0.132768 0.005000 -vn 0.552290 -0.318864 -0.770260 -v -0.082382 -0.134625 0.005000 -vn -0.607118 -0.251474 -0.753770 -v -0.084538 -0.132576 0.005000 -vn -0.528437 -0.433682 -0.729845 -v -0.084646 -0.132414 0.005000 -vn -0.433681 -0.528435 -0.729847 -v -0.086914 -0.130146 0.005000 -vn 0.607126 0.251480 -0.753761 -v -0.085962 -0.128924 0.005000 -vn 0.680314 0.067012 -0.729851 -v -0.086000 -0.128732 0.005000 -vn 0.655721 -0.378581 -0.653228 -v -0.070201 -0.145250 0.005000 -vn -0.552298 -0.318857 -0.770257 -v -0.071567 -0.130250 0.005000 -vn -0.318884 -0.552293 -0.770250 -v -0.071750 -0.130067 0.005000 -vn 0.655721 0.378578 -0.653230 -v -0.070201 -0.126750 0.005000 -vn 0.378584 0.655721 -0.653226 -v -0.070750 -0.126201 0.005000 -vn -0.067027 -0.680308 -0.729855 -v -0.076768 -0.140500 0.005000 -vn 0.067024 -0.680308 -0.729856 -v -0.083232 -0.140500 0.005000 -vn 0.318866 0.552288 -0.770261 -v -0.081375 -0.138382 0.005000 -vn 0.251491 -0.607129 -0.753755 -v -0.083424 -0.140538 0.005000 -vn 0.433668 -0.528441 -0.729850 -v -0.083586 -0.140646 0.005000 -vn 0.528434 -0.433685 -0.729846 -v -0.085854 -0.142914 0.005000 -vn 0.607115 -0.251491 -0.753766 -v -0.085962 -0.143076 0.005000 -vn 0.607126 -0.251467 -0.753766 -v -0.075462 -0.132576 0.005000 -vn 0.680321 -0.067000 -0.729845 -v -0.075500 -0.132768 0.005000 -vn -0.637729 0.000001 -0.770261 -v -0.077250 -0.136000 0.005000 -vn 0.680320 0.067000 -0.729847 -v -0.075500 -0.139232 0.005000 -vn -0.552289 0.318866 -0.770260 -v -0.077618 -0.137375 0.005000 -vn 0.607126 0.251466 -0.753766 -v -0.075462 -0.139424 0.005000 -vn 0.528440 0.433671 -0.729850 -v -0.075354 -0.139586 0.005000 -vn 0.433688 0.528433 -0.729844 -v -0.073086 -0.141854 0.005000 -vn -0.607107 -0.251485 -0.753775 -v -0.074038 -0.143076 0.005000 -vn -0.680320 -0.067000 -0.729847 -v -0.074000 -0.143268 0.005000 -vn 0.251492 0.607129 -0.753755 -v -0.083424 -0.131462 0.005000 -vn 0.067025 0.680310 -0.729854 -v -0.083232 -0.131500 0.005000 -vn -0.000001 -0.637729 -0.770261 -v -0.080000 -0.133250 0.005000 -vn -0.067027 0.680307 -0.729856 -v -0.076768 -0.131500 0.005000 -vn -0.318865 -0.552289 -0.770261 -v -0.078625 -0.133618 0.005000 -vn -0.251488 0.607135 -0.753752 -v -0.076576 -0.131462 0.005000 -vn -0.433660 0.528444 -0.729853 -v -0.076414 -0.131354 0.005000 -vn -0.528435 0.433681 -0.729847 -v -0.074146 -0.129086 0.005000 -vn -0.607117 0.251475 -0.753770 -v -0.074038 -0.128924 0.005000 -vn -0.655727 -0.378583 0.653221 -v -0.076933 -0.127250 0.339200 -vn -0.378580 -0.655736 0.653214 -v -0.076750 -0.127433 0.339200 -vn -0.095828 -0.727972 0.678877 -v -0.076500 -0.127500 0.339200 -vn -0.095852 -0.727975 0.678870 -v -0.071000 -0.133000 0.339200 -vn 0.577347 -0.577352 0.577352 -v -0.070500 -0.133000 0.339200 -vn 0.669345 -0.088135 0.737705 -v -0.070500 -0.132650 0.339200 -vn -0.577349 -0.577352 0.577349 -v -0.089500 -0.133000 0.339200 -vn 0.095853 -0.727981 0.678863 -v -0.089000 -0.133000 0.339200 -vn -0.669360 -0.088114 0.737694 -v -0.089500 -0.132650 0.339200 -vn 0.378589 -0.655721 0.653223 -v -0.088750 -0.132933 0.339200 -vn 0.378583 -0.655731 0.653216 -v -0.083250 -0.127433 0.339200 -vn 0.655729 -0.378583 0.653219 -v -0.083067 -0.127250 0.339200 -vn 0.088119 0.669354 0.737699 -v -0.083350 -0.126500 0.339200 -vn 0.727974 -0.095842 0.678873 -v -0.083000 -0.127000 0.339200 -vn 0.577352 0.577348 0.577352 -v -0.083000 -0.126500 0.339200 -vn -0.088114 0.669360 0.737694 -v -0.076650 -0.126500 0.339200 -vn -0.577352 0.577349 0.577349 -v -0.077000 -0.126500 0.339200 -vn -0.727980 -0.095845 0.678865 -v -0.077000 -0.127000 0.339200 -vn -0.378576 -0.655726 0.653225 -v -0.071250 -0.132933 0.339200 -vn -0.655723 -0.378601 0.653214 -v -0.071433 -0.132750 0.339200 -vn -0.727980 -0.095839 0.678867 -v -0.071500 -0.132500 0.339200 -vn -0.669345 -0.088148 0.737704 -v -0.076450 -0.145700 0.339200 -vn -0.577350 -0.577350 0.577350 -v -0.076450 -0.146000 0.339200 -vn 0.095837 -0.727971 0.678877 -v -0.071500 -0.146000 0.339200 -vn 0.727973 0.095842 0.678874 -v -0.070000 -0.127500 0.339200 -vn -0.318877 -0.552297 0.770250 -v -0.071750 -0.130067 0.339200 -vn -0.552294 -0.318864 0.770258 -v -0.071567 -0.130250 0.339200 -vn 0.727980 0.095845 0.678865 -v -0.083000 -0.145000 0.339200 -vn 0.655724 0.378591 0.653219 -v -0.083067 -0.144750 0.339200 -vn 0.378575 0.655736 0.653216 -v -0.083250 -0.144567 0.339200 -vn 0.655730 -0.378586 0.653216 -v -0.088567 -0.132750 0.339200 -vn 0.727973 -0.095836 0.678875 -v -0.088500 -0.132500 0.339200 -vn -0.552307 -0.318847 0.770255 -v -0.089527 -0.132550 0.339200 -vn 0.669352 -0.088124 0.737701 -v -0.088500 -0.130500 0.339200 -vn -0.318864 -0.552279 0.770268 -v -0.089600 -0.132477 0.339200 -vn -0.727973 0.095838 0.678875 -v -0.090000 -0.127500 0.339200 -vn -0.088113 -0.669358 0.737697 -v -0.089700 -0.132450 0.339200 -vn -0.577348 -0.577354 0.577348 -v -0.090000 -0.132450 0.339200 -vn -0.318870 -0.552303 0.770249 -v -0.074250 -0.127567 0.339200 -vn -0.552288 -0.318873 0.770258 -v -0.074067 -0.127750 0.339200 -vn 0.577349 0.577352 0.577349 -v -0.070500 -0.139000 0.339200 -vn -0.095856 0.727982 0.678863 -v -0.071000 -0.139000 0.339200 -vn 0.669348 0.088137 0.737703 -v -0.070500 -0.139350 0.339200 -vn -0.378584 0.655722 0.653225 -v -0.071250 -0.139067 0.339200 -vn 0.552305 0.318872 0.770247 -v -0.070473 -0.139450 0.339200 -vn -0.669365 -0.088118 0.737689 -v -0.071500 -0.130500 0.339200 -vn 0.552307 -0.318868 0.770247 -v -0.070473 -0.132550 0.339200 -vn 0.318868 -0.552277 0.770268 -v -0.070400 -0.132477 0.339200 -vn 0.088114 -0.669364 0.737691 -v -0.070300 -0.132450 0.339200 -vn 0.577350 -0.577350 0.577350 -v -0.070000 -0.132450 0.339200 -vn -0.088130 -0.669348 0.737704 -v -0.074500 -0.127500 0.339200 -vn -0.727974 0.095842 0.678873 -v -0.077000 -0.145000 0.339200 -vn -0.577352 -0.577347 0.577352 -v -0.077000 -0.145500 0.339200 -vn -0.088113 -0.669358 0.737697 -v -0.076650 -0.145500 0.339200 -vn 0.095849 0.727975 0.678871 -v -0.089000 -0.139000 0.339200 -vn -0.577348 0.577352 0.577352 -v -0.089500 -0.139000 0.339200 -vn -0.669358 0.088113 0.737697 -v -0.089500 -0.139350 0.339200 -vn -0.552304 -0.318885 0.770242 -v -0.076477 -0.145600 0.339200 -vn -0.318868 0.552277 0.770268 -v -0.076550 -0.126473 0.339200 -vn -0.552306 0.318882 0.770242 -v -0.076477 -0.126400 0.339200 -vn -0.669339 0.088147 0.737710 -v -0.076450 -0.126300 0.339200 -vn 0.088133 0.669346 0.737705 -v -0.085500 -0.144500 0.339200 -vn 0.318869 0.552309 0.770245 -v -0.085750 -0.144433 0.339200 -vn -0.095837 -0.727973 0.678875 -v -0.088500 -0.146000 0.339200 -vn 0.552282 0.318877 0.770261 -v -0.085933 -0.144250 0.339200 -vn 0.727980 0.095839 0.678867 -v -0.088500 -0.139500 0.339200 -vn 0.655726 0.378594 0.653216 -v -0.088567 -0.139250 0.339200 -vn 0.378581 0.655726 0.653223 -v -0.088750 -0.139067 0.339200 -vn 0.577352 -0.577349 0.577349 -v -0.083000 -0.145500 0.339200 -vn 0.088120 -0.669357 0.737696 -v -0.083350 -0.145500 0.339200 -vn 0.318864 -0.552291 0.770260 -v -0.083450 -0.145527 0.339200 -vn 0.552293 -0.318867 0.770257 -v -0.083523 -0.145600 0.339200 -vn 0.095831 0.727972 0.678876 -v -0.083500 -0.144500 0.339200 -vn 0.669351 -0.088125 0.737701 -v -0.083550 -0.145700 0.339200 -vn 0.577354 -0.577348 0.577348 -v -0.083550 -0.146000 0.339200 -vn -0.669354 0.088119 0.737699 -v -0.074000 -0.144000 0.339200 -vn -0.552292 0.318866 0.770258 -v -0.074067 -0.144250 0.339200 -vn 0.251480 0.607113 0.753772 -v -0.072924 -0.141962 0.339200 -vn 0.528436 -0.433686 0.729844 -v -0.085854 -0.142914 0.339200 -vn 0.433667 -0.528440 0.729852 -v -0.083586 -0.140646 0.339200 -vn 0.318866 0.552291 0.770259 -v -0.081375 -0.138382 0.339200 -vn 0.251492 -0.607129 0.753755 -v -0.083424 -0.140538 0.339200 -vn -0.000001 0.637729 0.770261 -v -0.080000 -0.138750 0.339200 -vn 0.669357 0.088126 0.737696 -v -0.083550 -0.126300 0.339200 -vn 0.552293 -0.318864 0.770259 -v -0.082382 -0.134625 0.339200 -vn -0.433683 -0.528437 0.729845 -v -0.086914 -0.130146 0.339200 -vn -0.528435 -0.433681 0.729847 -v -0.084646 -0.132414 0.339200 -vn 0.669354 -0.088119 0.737699 -v -0.086000 -0.128000 0.339200 -vn 0.552286 -0.318870 0.770261 -v -0.085933 -0.127750 0.339200 -vn -0.251477 -0.607118 0.753768 -v -0.087076 -0.130038 0.339200 -vn 0.378585 0.655721 0.653226 -v -0.070750 -0.126201 0.339200 -vn -0.088133 -0.669347 0.737704 -v -0.072000 -0.130000 0.339200 -vn -0.251478 0.607118 0.753768 -v -0.087076 -0.141962 0.339200 -vn 0.669361 0.088122 0.737692 -v -0.086000 -0.144000 0.339200 -vn 0.669363 0.088122 0.737691 -v -0.088500 -0.141500 0.339200 -vn -0.552309 0.318844 0.770255 -v -0.089527 -0.139450 0.339200 -vn 0.552282 0.318877 0.770261 -v -0.088433 -0.141750 0.339200 -vn -0.318868 0.552277 0.770268 -v -0.089600 -0.139523 0.339200 -vn -0.727972 -0.095836 0.678876 -v -0.090000 -0.144500 0.339200 -vn -0.088114 0.669364 0.737691 -v -0.089700 -0.139550 0.339200 -vn -0.577350 0.577350 0.577350 -v -0.090000 -0.139550 0.339200 -vn 0.577348 0.577354 0.577348 -v -0.070000 -0.139550 0.339200 -vn 0.088113 0.669358 0.737697 -v -0.070300 -0.139550 0.339200 -vn 0.727973 -0.095840 0.678874 -v -0.070000 -0.144500 0.339200 -vn 0.318864 0.552279 0.770268 -v -0.070400 -0.139523 0.339200 -vn -0.067003 0.680319 0.729847 -v -0.087268 -0.142000 0.339200 -vn 0.088133 0.669347 0.737704 -v -0.088000 -0.142000 0.339200 -vn -0.378577 -0.655723 0.653228 -v -0.089250 -0.145799 0.339200 -vn -0.655723 -0.378581 0.653226 -v -0.089799 -0.145250 0.339200 -vn 0.318869 0.552309 0.770245 -v -0.088250 -0.141933 0.339200 -vn 0.088136 -0.669354 0.737698 -v -0.088000 -0.130000 0.339200 -vn -0.067002 -0.680319 0.729847 -v -0.087268 -0.130000 0.339200 -vn 0.680315 0.067012 0.729850 -v -0.086000 -0.128732 0.339200 -vn 0.552291 0.318871 0.770257 -v -0.083523 -0.126400 0.339200 -vn -0.655728 0.378593 0.653214 -v -0.071433 -0.139250 0.339200 -vn -0.727973 0.095836 0.678875 -v -0.071500 -0.139500 0.339200 -vn -0.669359 0.088110 0.737696 -v -0.071500 -0.141500 0.339200 -vn 0.095835 -0.727979 0.678868 -v -0.083500 -0.127500 0.339200 -vn 0.318861 0.552293 0.770260 -v -0.083450 -0.126473 0.339200 -vn 0.088136 -0.669355 0.737696 -v -0.085500 -0.127500 0.339200 -vn 0.318876 -0.552305 0.770245 -v -0.085750 -0.127567 0.339200 -vn -0.318865 -0.552290 0.770260 -v -0.078625 -0.133618 0.339200 -vn -0.528437 0.433682 0.729846 -v -0.074146 -0.129086 0.339200 -vn -0.433659 0.528443 0.729855 -v -0.076414 -0.131354 0.339200 -vn -0.607117 -0.251475 0.753770 -v -0.084538 -0.132576 0.339200 -vn -0.680321 -0.067000 0.729845 -v -0.084500 -0.132768 0.339200 -vn 0.637729 0.000001 0.770261 -v -0.082750 -0.136000 0.339200 -vn -0.680320 0.067000 0.729847 -v -0.084500 -0.139232 0.339200 -vn 0.552290 0.318865 0.770260 -v -0.082382 -0.137375 0.339200 -vn -0.607118 0.251474 0.753770 -v -0.084538 -0.139424 0.339200 -vn -0.528436 0.433682 0.729846 -v -0.084646 -0.139586 0.339200 -vn -0.433681 0.528435 0.729847 -v -0.086914 -0.141854 0.339200 -vn 0.607115 -0.251490 0.753766 -v -0.085962 -0.143076 0.339200 -vn 0.680314 -0.067012 0.729851 -v -0.086000 -0.143268 0.339200 -vn 0.552298 -0.318867 0.770254 -v -0.088433 -0.130250 0.339200 -vn 0.318884 -0.552293 0.770250 -v -0.088250 -0.130067 0.339200 -vn -0.655723 0.378578 0.653228 -v -0.089799 -0.126750 0.339200 -vn -0.378581 0.655722 0.653227 -v -0.089250 -0.126201 0.339200 -vn 0.251481 -0.607112 0.753772 -v -0.072924 -0.130038 0.339200 -vn -0.669361 -0.088122 0.737692 -v -0.074000 -0.128000 0.339200 -vn 0.433689 0.528434 0.729843 -v -0.073086 -0.141854 0.339200 -vn 0.528438 0.433671 0.729851 -v -0.075354 -0.139586 0.339200 -vn -0.552290 0.318865 0.770260 -v -0.077618 -0.137375 0.339200 -vn 0.607126 0.251467 0.753766 -v -0.075462 -0.139424 0.339200 -vn -0.637728 0.000000 0.770261 -v -0.077250 -0.136000 0.339200 -vn -0.251489 0.607134 0.753752 -v -0.076576 -0.131462 0.339200 -vn -0.067027 0.680308 0.729855 -v -0.076768 -0.131500 0.339200 -vn 0.000000 -0.637729 0.770261 -v -0.080000 -0.133250 0.339200 -vn 0.067024 0.680308 0.729856 -v -0.083232 -0.131500 0.339200 -vn 0.318866 -0.552288 0.770261 -v -0.081375 -0.133618 0.339200 -vn 0.251491 0.607129 0.753755 -v -0.083424 -0.131462 0.339200 -vn 0.433667 0.528442 0.729851 -v -0.083586 -0.131354 0.339200 -vn 0.528438 0.433671 0.729851 -v -0.085854 -0.129086 0.339200 -vn 0.607126 0.251481 0.753761 -v -0.085962 -0.128924 0.339200 -vn 0.067000 -0.680321 0.729846 -v -0.072732 -0.130000 0.339200 -vn -0.088136 0.669354 0.737698 -v -0.072000 -0.142000 0.339200 -vn 0.067000 0.680320 0.729847 -v -0.072732 -0.142000 0.339200 -vn -0.680320 -0.067000 0.729846 -v -0.074000 -0.143268 0.339200 -vn 0.655721 0.378577 0.653230 -v -0.070201 -0.126750 0.339200 -vn -0.552287 0.318860 0.770265 -v -0.071567 -0.141750 0.339200 -vn -0.318876 0.552305 0.770245 -v -0.071750 -0.141933 0.339200 -vn 0.655721 -0.378582 0.653228 -v -0.070201 -0.145250 0.339200 -vn 0.378579 -0.655723 0.653227 -v -0.070750 -0.145799 0.339200 -vn -0.655731 0.378575 0.653221 -v -0.076933 -0.144750 0.339200 -vn -0.378588 0.655731 0.653214 -v -0.076750 -0.144567 0.339200 -vn -0.095832 0.727979 0.678869 -v -0.076500 -0.144500 0.339200 -vn -0.318864 -0.552279 0.770268 -v -0.076550 -0.145527 0.339200 -vn -0.088133 0.669357 0.737695 -v -0.074500 -0.144500 0.339200 -vn -0.318877 0.552299 0.770249 -v -0.074250 -0.144433 0.339200 -vn 0.680321 0.067000 0.729845 -v -0.075500 -0.139232 0.339200 -vn 0.680320 -0.067000 0.729847 -v -0.075500 -0.132768 0.339200 -vn -0.552289 -0.318865 0.770261 -v -0.077618 -0.134625 0.339200 -vn 0.607126 -0.251466 0.753766 -v -0.075462 -0.132576 0.339200 -vn 0.528440 -0.433672 0.729849 -v -0.075354 -0.132414 0.339200 -vn 0.433688 -0.528433 0.729844 -v -0.073086 -0.130146 0.339200 -vn -0.607118 0.251474 0.753770 -v -0.074038 -0.128924 0.339200 -vn -0.680320 0.067000 0.729847 -v -0.074000 -0.128732 0.339200 -vn 0.067025 -0.680309 0.729854 -v -0.083232 -0.140500 0.339200 -vn -0.067027 -0.680307 0.729856 -v -0.076768 -0.140500 0.339200 -vn -0.318866 0.552289 0.770261 -v -0.078625 -0.138382 0.339200 -vn -0.251488 -0.607135 0.753752 -v -0.076576 -0.140538 0.339200 -vn -0.433661 -0.528443 0.729853 -v -0.076414 -0.140646 0.339200 -vn -0.528431 -0.433695 0.729842 -v -0.074146 -0.142914 0.339200 -vn -0.607106 -0.251486 0.753775 -v -0.074038 -0.143076 0.339200 -# 4900 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 1//1 3//3 4//4 -f 4//4 3//3 5//5 -f 4//4 5//5 6//6 -f 7//7 8//8 6//6 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 8//8 -f 8//8 12//12 4//4 -f 8//8 4//4 6//6 -f 13//13 14//14 6//6 -f 6//6 14//14 15//15 -f 6//6 15//15 7//7 -f 9//9 16//16 10//10 -f 10//10 16//16 17//17 -f 10//10 17//17 18//18 -f 18//18 19//19 10//10 -f 10//10 19//19 20//20 -f 10//10 20//20 21//21 -f 22//22 23//23 6//6 -f 6//6 23//23 24//24 -f 6//6 24//24 13//13 -f 25//25 11//11 26//26 -f 26//26 11//11 8//8 -f 26//26 8//8 27//27 -f 12//12 10//10 28//28 -f 12//12 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 32//32 33//33 26//26 -f 26//26 33//33 34//34 -f 26//26 34//34 25//25 -f 35//35 36//36 26//26 -f 26//26 36//36 37//37 -f 26//26 37//37 32//32 -f 38//38 30//30 39//39 -f 39//39 30//30 28//28 -f 39//39 28//28 40//40 -f 41//41 42//42 35//35 -f 35//35 42//42 43//43 -f 35//35 43//43 36//36 -f 34//34 44//44 25//25 -f 25//25 44//44 45//45 -f 25//25 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 48//48 -f 40//40 28//28 47//47 -f 47//47 28//28 49//49 -f 47//47 49//49 48//48 -f 50//50 51//51 52//52 -f 38//38 53//53 30//30 -f 30//30 53//53 54//54 -f 30//30 54//54 55//55 -f 55//55 54//54 50//50 -f 55//55 50//50 56//56 -f 56//56 50//50 52//52 -f 50//50 57//57 51//51 -f 51//51 57//57 58//58 -f 51//51 58//58 35//35 -f 35//35 58//58 59//59 -f 35//35 59//59 41//41 -f 60//60 61//61 3//3 -f 3//3 61//61 62//62 -f 3//3 62//62 5//5 -f 27//27 63//63 64//64 -f 62//62 65//65 5//5 -f 5//5 65//65 66//66 -f 5//5 66//66 67//67 -f 67//67 66//66 64//64 -f 67//67 64//64 68//68 -f 68//68 64//64 63//63 -f 69//69 70//70 35//35 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 64//64 76//76 27//27 -f 27//27 76//76 77//77 -f 27//27 77//77 26//26 -f 26//26 77//77 78//78 -f 26//26 78//78 79//79 -f 70//70 80//80 35//35 -f 35//35 80//80 81//81 -f 35//35 81//81 71//71 -f 71//71 81//81 82//82 -f 71//71 82//82 72//72 -f 60//60 3//3 74//74 -f 74//74 3//3 83//83 -f 74//74 83//83 75//75 -f 79//79 84//84 26//26 -f 26//26 84//84 85//85 -f 26//26 85//85 35//35 -f 35//35 85//85 86//86 -f 35//35 86//86 69//69 -f 87//87 12//12 88//88 -f 88//88 12//12 29//29 -f 89//89 90//90 91//91 -f 92//92 93//93 29//29 -f 29//29 93//93 94//94 -f 29//29 94//94 88//88 -f 90//90 95//95 91//91 -f 91//91 95//95 96//96 -f 91//91 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 100//100 97//97 -f 97//97 100//100 101//101 -f 97//97 101//101 29//29 -f 29//29 101//101 102//102 -f 29//29 102//102 92//92 -f 87//87 103//103 12//12 -f 12//12 103//103 104//104 -f 12//12 104//104 105//105 -f 105//105 106//106 12//12 -f 12//12 106//106 107//107 -f 12//12 107//107 91//91 -f 91//91 107//107 108//108 -f 91//91 108//108 89//89 -f 12//12 91//91 4//4 -f 97//97 109//109 91//91 -f 91//91 109//109 110//110 -f 91//91 110//110 111//111 -f 112//112 113//113 4//4 -f 113//113 114//114 4//4 -f 4//4 114//114 115//115 -f 4//4 115//115 1//1 -f 111//111 116//116 91//91 -f 91//91 116//116 117//117 -f 91//91 117//117 4//4 -f 4//4 117//117 118//118 -f 4//4 118//118 112//112 -f 115//115 119//119 1//1 -f 1//1 119//119 120//120 -f 1//1 120//120 121//121 -f 121//121 122//122 1//1 -f 1//1 122//122 123//123 -f 1//1 123//123 97//97 -f 97//97 123//123 124//124 -f 97//97 124//124 125//125 -f 125//125 126//126 97//97 -f 97//97 126//126 127//127 -f 97//97 127//127 109//109 -f 97//97 29//29 1//1 -f 128//128 129//129 31//31 -f 130//130 2//2 131//131 -f 131//131 2//2 1//1 -f 131//131 1//1 129//129 -f 129//129 1//1 29//29 -f 129//129 29//29 31//31 -f 132//132 133//133 31//31 -f 31//31 133//133 134//134 -f 31//31 134//134 128//128 -f 130//130 135//135 2//2 -f 2//2 135//135 136//136 -f 2//2 136//136 137//137 -f 137//137 138//138 2//2 -f 2//2 138//138 139//139 -f 2//2 139//139 140//140 -f 141//141 142//142 31//31 -f 31//31 142//142 143//143 -f 31//31 143//143 132//132 -f 129//129 51//51 131//131 -f 131//131 51//51 35//35 -f 131//131 35//35 71//71 -f 144//144 145//145 146//146 -f 144//144 146//146 147//147 -f 147//147 146//146 148//148 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 151//151 -f 151//151 150//150 152//152 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 158//158 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 169//169 -f 169//169 168//168 170//170 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 175//175 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 178//178 180//180 179//179 -f 179//179 180//180 181//181 -f 179//179 181//181 182//182 -f 182//182 181//181 183//183 -f 182//182 183//183 184//184 -f 184//184 183//183 185//185 -f 184//184 185//185 186//186 -f 186//186 185//185 187//187 -f 186//186 187//187 188//188 -f 188//188 187//187 189//189 -f 188//188 189//189 190//190 -f 190//190 189//189 191//191 -f 190//190 191//191 192//192 -f 192//192 191//191 193//193 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 194//194 195//195 196//196 -f 196//196 195//195 197//197 -f 196//196 197//197 198//198 -f 198//198 197//197 199//199 -f 198//198 199//199 200//200 -f 200//200 199//199 201//201 -f 200//200 201//201 202//202 -f 202//202 201//201 203//203 -f 202//202 203//203 204//204 -f 204//204 203//203 205//205 -f 204//204 205//205 206//206 -f 206//206 205//205 207//207 -f 206//206 207//207 208//208 -f 208//208 207//207 209//209 -f 208//208 209//209 210//210 -f 210//210 209//209 211//211 -f 210//210 211//211 212//212 -f 212//212 211//211 213//213 -f 212//212 213//213 214//214 -f 214//214 213//213 145//145 -f 214//214 145//145 215//215 -f 215//215 145//145 144//144 -f 216//216 217//217 218//218 -f 216//216 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 225//225 224//224 226//226 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 229//229 -f 229//229 228//228 230//230 -f 229//229 230//230 231//231 -f 231//231 230//230 232//232 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 237//237 -f 237//237 236//236 238//238 -f 237//237 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 241//241 -f 241//241 240//240 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 249//249 -f 249//249 248//248 250//250 -f 249//249 250//250 251//251 -f 216//216 252//252 217//217 -f 217//217 252//252 253//253 -f 217//217 253//253 254//254 -f 254//254 253//253 255//255 -f 254//254 255//255 256//256 -f 256//256 255//255 257//257 -f 256//256 257//257 258//258 -f 258//258 257//257 259//259 -f 258//258 259//259 260//260 -f 260//260 259//259 261//261 -f 260//260 261//261 262//262 -f 262//262 261//261 263//263 -f 262//262 263//263 264//264 -f 264//264 263//263 265//265 -f 264//264 265//265 266//266 -f 266//266 265//265 267//267 -f 266//266 267//267 268//268 -f 268//268 267//267 269//269 -f 268//268 269//269 270//270 -f 270//270 269//269 271//271 -f 270//270 271//271 272//272 -f 272//272 271//271 273//273 -f 272//272 273//273 274//274 -f 274//274 273//273 275//275 -f 274//274 275//275 276//276 -f 276//276 275//275 277//277 -f 276//276 277//277 278//278 -f 278//278 277//277 279//279 -f 278//278 279//279 280//280 -f 280//280 279//279 281//281 -f 280//280 281//281 282//282 -f 282//282 281//281 283//283 -f 282//282 283//283 284//284 -f 284//284 283//283 285//285 -f 284//284 285//285 286//286 -f 286//286 285//285 251//251 -f 286//286 251//251 287//287 -f 287//287 251//251 250//250 -f 73//73 75//75 137//137 -f 137//137 136//136 73//73 -f 73//73 136//136 135//135 -f 73//73 135//135 71//71 -f 71//71 135//135 130//130 -f 71//71 130//130 131//131 -f 83//83 3//3 2//2 -f 2//2 140//140 83//83 -f 83//83 140//140 139//139 -f 83//83 139//139 75//75 -f 75//75 139//139 138//138 -f 75//75 138//138 137//137 -f 31//31 30//30 141//141 -f 141//141 30//30 55//55 -f 141//141 55//55 142//142 -f 142//142 55//55 143//143 -f 143//143 55//55 56//56 -f 143//143 56//56 132//132 -f 132//132 56//56 133//133 -f 133//133 56//56 52//52 -f 133//133 52//52 134//134 -f 134//134 52//52 128//128 -f 128//128 52//52 51//51 -f 128//128 51//51 129//129 -f 46//46 48//48 18//18 -f 18//18 17//17 46//46 -f 46//46 17//17 16//16 -f 46//46 16//16 25//25 -f 25//25 16//16 9//9 -f 25//25 9//9 11//11 -f 49//49 28//28 10//10 -f 10//10 21//21 49//49 -f 49//49 21//21 20//20 -f 49//49 20//20 48//48 -f 48//48 20//20 19//19 -f 48//48 19//19 18//18 -f 6//6 5//5 22//22 -f 22//22 5//5 67//67 -f 22//22 67//67 23//23 -f 23//23 67//67 24//24 -f 24//24 67//67 68//68 -f 24//24 68//68 13//13 -f 13//13 68//68 14//14 -f 14//14 68//68 63//63 -f 14//14 63//63 15//15 -f 15//15 63//63 7//7 -f 7//7 63//63 27//27 -f 7//7 27//27 8//8 -f 47//47 45//45 184//184 -f 184//184 186//186 47//47 -f 47//47 186//186 188//188 -f 47//47 188//188 40//40 -f 188//188 190//190 40//40 -f 40//40 190//190 192//192 -f 40//40 192//192 39//39 -f 192//192 194//194 39//39 -f 39//39 194//194 196//196 -f 39//39 196//196 38//38 -f 196//196 198//198 38//38 -f 38//38 198//198 200//200 -f 38//38 200//200 53//53 -f 200//200 202//202 53//53 -f 53//53 202//202 204//204 -f 53//53 204//204 54//54 -f 204//204 206//206 54//54 -f 54//54 206//206 208//208 -f 54//54 208//208 50//50 -f 208//208 210//210 50//50 -f 50//50 210//210 212//212 -f 50//50 212//212 57//57 -f 57//57 212//212 214//214 -f 57//57 214//214 58//58 -f 58//58 214//214 215//215 -f 58//58 215//215 59//59 -f 59//59 215//215 144//144 -f 59//59 144//144 41//41 -f 144//144 147//147 41//41 -f 41//41 147//147 149//149 -f 41//41 149//149 42//42 -f 149//149 151//151 42//42 -f 42//42 151//151 153//153 -f 42//42 153//153 43//43 -f 153//153 155//155 43//43 -f 43//43 155//155 157//157 -f 43//43 157//157 36//36 -f 157//157 159//159 36//36 -f 36//36 159//159 161//161 -f 36//36 161//161 37//37 -f 161//161 163//163 37//37 -f 37//37 163//163 165//165 -f 37//37 165//165 32//32 -f 165//165 167//167 32//32 -f 32//32 167//167 169//169 -f 32//32 169//169 33//33 -f 169//169 171//171 33//33 -f 33//33 171//171 173//173 -f 33//33 173//173 34//34 -f 173//173 175//175 34//34 -f 34//34 175//175 177//177 -f 34//34 177//177 44//44 -f 44//44 177//177 179//179 -f 44//44 179//179 45//45 -f 45//45 179//179 182//182 -f 45//45 182//182 184//184 -f 66//66 65//65 256//256 -f 256//256 258//258 66//66 -f 66//66 258//258 260//260 -f 66//66 260//260 64//64 -f 260//260 262//262 64//64 -f 64//64 262//262 264//264 -f 64//64 264//264 76//76 -f 264//264 266//266 76//76 -f 76//76 266//266 268//268 -f 76//76 268//268 77//77 -f 268//268 270//270 77//77 -f 77//77 270//270 272//272 -f 77//77 272//272 78//78 -f 272//272 274//274 78//78 -f 78//78 274//274 276//276 -f 78//78 276//276 79//79 -f 276//276 278//278 79//79 -f 79//79 278//278 280//280 -f 79//79 280//280 84//84 -f 280//280 282//282 84//84 -f 84//84 282//282 284//284 -f 84//84 284//284 85//85 -f 85//85 284//284 286//286 -f 85//85 286//286 86//86 -f 86//86 286//286 287//287 -f 86//86 287//287 69//69 -f 69//69 287//287 250//250 -f 69//69 250//250 70//70 -f 250//250 248//248 70//70 -f 70//70 248//248 246//246 -f 70//70 246//246 80//80 -f 246//246 244//244 80//80 -f 80//80 244//244 242//242 -f 80//80 242//242 81//81 -f 242//242 240//240 81//81 -f 81//81 240//240 238//238 -f 81//81 238//238 82//82 -f 238//238 236//236 82//82 -f 82//82 236//236 234//234 -f 82//82 234//234 72//72 -f 234//234 232//232 72//72 -f 72//72 232//232 230//230 -f 72//72 230//230 74//74 -f 230//230 228//228 74//74 -f 74//74 228//228 226//226 -f 74//74 226//226 60//60 -f 226//226 224//224 60//60 -f 60//60 224//224 222//222 -f 60//60 222//222 61//61 -f 222//222 220//220 61//61 -f 61//61 220//220 218//218 -f 61//61 218//218 62//62 -f 62//62 218//218 217//217 -f 62//62 217//217 65//65 -f 65//65 217//217 254//254 -f 65//65 254//254 256//256 -f 111//111 110//110 283//283 -f 283//283 281//281 111//111 -f 111//111 281//281 279//279 -f 111//111 279//279 116//116 -f 279//279 277//277 116//116 -f 116//116 277//277 275//275 -f 116//116 275//275 117//117 -f 275//275 273//273 117//117 -f 117//117 273//273 271//271 -f 117//117 271//271 118//118 -f 271//271 269//269 118//118 -f 118//118 269//269 267//267 -f 118//118 267//267 112//112 -f 267//267 265//265 112//112 -f 112//112 265//265 263//263 -f 112//112 263//263 113//113 -f 263//263 261//261 113//113 -f 113//113 261//261 259//259 -f 113//113 259//259 114//114 -f 259//259 257//257 114//114 -f 114//114 257//257 255//255 -f 114//114 255//255 115//115 -f 255//255 253//253 115//115 -f 115//115 253//253 252//252 -f 115//115 252//252 119//119 -f 119//119 252//252 216//216 -f 119//119 216//216 120//120 -f 216//216 219//219 120//120 -f 120//120 219//219 221//221 -f 120//120 221//221 121//121 -f 221//221 223//223 121//121 -f 121//121 223//223 225//225 -f 121//121 225//225 122//122 -f 225//225 227//227 122//122 -f 122//122 227//227 229//229 -f 122//122 229//229 123//123 -f 229//229 231//231 123//123 -f 123//123 231//231 233//233 -f 123//123 233//233 124//124 -f 233//233 235//235 124//124 -f 124//124 235//235 237//237 -f 124//124 237//237 125//125 -f 237//237 239//239 125//125 -f 125//125 239//239 241//241 -f 125//125 241//241 126//126 -f 241//241 243//243 126//126 -f 126//126 243//243 245//245 -f 126//126 245//245 127//127 -f 245//245 247//247 127//127 -f 127//127 247//247 249//249 -f 127//127 249//249 109//109 -f 109//109 249//249 251//251 -f 109//109 251//251 110//110 -f 110//110 251//251 285//285 -f 110//110 285//285 283//283 -f 93//93 92//92 211//211 -f 211//211 209//209 93//93 -f 93//93 209//209 207//207 -f 93//93 207//207 94//94 -f 207//207 205//205 94//94 -f 94//94 205//205 203//203 -f 94//94 203//203 88//88 -f 203//203 201//201 88//88 -f 88//88 201//201 199//199 -f 88//88 199//199 87//87 -f 199//199 197//197 87//87 -f 87//87 197//197 195//195 -f 87//87 195//195 103//103 -f 195//195 193//193 103//103 -f 103//103 193//193 191//191 -f 103//103 191//191 104//104 -f 191//191 189//189 104//104 -f 104//104 189//189 187//187 -f 104//104 187//187 105//105 -f 187//187 185//185 105//105 -f 105//105 185//185 183//183 -f 105//105 183//183 106//106 -f 106//106 183//183 181//181 -f 106//106 181//181 107//107 -f 107//107 181//181 180//180 -f 107//107 180//180 108//108 -f 108//108 180//180 178//178 -f 108//108 178//178 89//89 -f 178//178 176//176 89//89 -f 89//89 176//176 174//174 -f 89//89 174//174 90//90 -f 174//174 172//172 90//90 -f 90//90 172//172 170//170 -f 90//90 170//170 95//95 -f 170//170 168//168 95//95 -f 95//95 168//168 166//166 -f 95//95 166//166 96//96 -f 166//166 164//164 96//96 -f 96//96 164//164 162//162 -f 96//96 162//162 98//98 -f 162//162 160//160 98//98 -f 98//98 160//160 158//158 -f 98//98 158//158 99//99 -f 158//158 156//156 99//99 -f 99//99 156//156 154//154 -f 99//99 154//154 100//100 -f 154//154 152//152 100//100 -f 100//100 152//152 150//150 -f 100//100 150//150 101//101 -f 150//150 148//148 101//101 -f 101//101 148//148 146//146 -f 101//101 146//146 102//102 -f 102//102 146//146 145//145 -f 102//102 145//145 92//92 -f 92//92 145//145 213//213 -f 92//92 213//213 211//211 -f 288//288 289//289 290//290 -f 288//288 290//290 291//291 -f 291//291 290//290 292//292 -f 291//291 292//292 293//293 -f 294//294 295//295 293//293 -f 296//296 297//297 298//298 -f 298//298 297//297 299//299 -f 298//298 299//299 295//295 -f 295//295 299//299 291//291 -f 295//295 291//291 293//293 -f 300//300 301//301 293//293 -f 293//293 301//301 302//302 -f 293//293 302//302 294//294 -f 296//296 303//303 297//297 -f 297//297 303//303 304//304 -f 297//297 304//304 305//305 -f 305//305 306//306 297//297 -f 297//297 306//306 307//307 -f 297//297 307//307 308//308 -f 309//309 310//310 293//293 -f 293//293 310//310 311//311 -f 293//293 311//311 300//300 -f 312//312 298//298 313//313 -f 313//313 298//298 295//295 -f 313//313 295//295 314//314 -f 299//299 297//297 315//315 -f 299//299 315//315 316//316 -f 316//316 315//315 317//317 -f 316//316 317//317 318//318 -f 319//319 320//320 313//313 -f 313//313 320//320 321//321 -f 313//313 321//321 312//312 -f 322//322 323//323 313//313 -f 313//313 323//323 324//324 -f 313//313 324//324 319//319 -f 325//325 317//317 326//326 -f 326//326 317//317 315//315 -f 326//326 315//315 327//327 -f 328//328 329//329 322//322 -f 322//322 329//329 330//330 -f 322//322 330//330 323//323 -f 321//321 331//331 312//312 -f 312//312 331//331 332//332 -f 312//312 332//332 333//333 -f 333//333 332//332 334//334 -f 333//333 334//334 335//335 -f 327//327 315//315 334//334 -f 334//334 315//315 336//336 -f 334//334 336//336 335//335 -f 337//337 338//338 339//339 -f 325//325 340//340 317//317 -f 317//317 340//340 341//341 -f 317//317 341//341 342//342 -f 342//342 341//341 337//337 -f 342//342 337//337 343//343 -f 343//343 337//337 339//339 -f 337//337 344//344 338//338 -f 338//338 344//344 345//345 -f 338//338 345//345 322//322 -f 322//322 345//345 346//346 -f 322//322 346//346 328//328 -f 347//347 348//348 290//290 -f 290//290 348//348 349//349 -f 290//290 349//349 292//292 -f 314//314 350//350 351//351 -f 349//349 352//352 292//292 -f 292//292 352//352 353//353 -f 292//292 353//353 354//354 -f 354//354 353//353 351//351 -f 354//354 351//351 355//355 -f 355//355 351//351 350//350 -f 356//356 357//357 322//322 -f 358//358 359//359 360//360 -f 360//360 359//359 361//361 -f 360//360 361//361 362//362 -f 351//351 363//363 314//314 -f 314//314 363//363 364//364 -f 314//314 364//364 313//313 -f 313//313 364//364 365//365 -f 313//313 365//365 366//366 -f 357//357 367//367 322//322 -f 322//322 367//367 368//368 -f 322//322 368//368 358//358 -f 358//358 368//368 369//369 -f 358//358 369//369 359//359 -f 347//347 290//290 361//361 -f 361//361 290//290 370//370 -f 361//361 370//370 362//362 -f 366//366 371//371 313//313 -f 313//313 371//371 372//372 -f 313//313 372//372 322//322 -f 322//322 372//372 373//373 -f 322//322 373//373 356//356 -f 374//374 299//299 375//375 -f 375//375 299//299 316//316 -f 376//376 377//377 378//378 -f 379//379 380//380 316//316 -f 316//316 380//380 381//381 -f 316//316 381//381 375//375 -f 377//377 382//382 378//378 -f 378//378 382//382 383//383 -f 378//378 383//383 384//384 -f 384//384 383//383 385//385 -f 384//384 385//385 386//386 -f 386//386 387//387 384//384 -f 384//384 387//387 388//388 -f 384//384 388//388 316//316 -f 316//316 388//388 389//389 -f 316//316 389//389 379//379 -f 374//374 390//390 299//299 -f 299//299 390//390 391//391 -f 299//299 391//391 392//392 -f 392//392 393//393 299//299 -f 299//299 393//393 394//394 -f 299//299 394//394 378//378 -f 378//378 394//394 395//395 -f 378//378 395//395 376//376 -f 299//299 378//378 291//291 -f 384//384 396//396 378//378 -f 378//378 396//396 397//397 -f 378//378 397//397 398//398 -f 399//399 400//400 291//291 -f 400//400 401//401 291//291 -f 291//291 401//401 402//402 -f 291//291 402//402 288//288 -f 398//398 403//403 378//378 -f 378//378 403//403 404//404 -f 378//378 404//404 291//291 -f 291//291 404//404 405//405 -f 291//291 405//405 399//399 -f 402//402 406//406 288//288 -f 288//288 406//406 407//407 -f 288//288 407//407 408//408 -f 408//408 409//409 288//288 -f 288//288 409//409 410//410 -f 288//288 410//410 384//384 -f 384//384 410//410 411//411 -f 384//384 411//411 412//412 -f 412//412 413//413 384//384 -f 384//384 413//413 414//414 -f 384//384 414//414 396//396 -f 384//384 316//316 288//288 -f 415//415 416//416 318//318 -f 417//417 289//289 418//418 -f 418//418 289//289 288//288 -f 418//418 288//288 416//416 -f 416//416 288//288 316//316 -f 416//416 316//316 318//318 -f 419//419 420//420 318//318 -f 318//318 420//420 421//421 -f 318//318 421//421 415//415 -f 417//417 422//422 289//289 -f 289//289 422//422 423//423 -f 289//289 423//423 424//424 -f 424//424 425//425 289//289 -f 289//289 425//425 426//426 -f 289//289 426//426 427//427 -f 428//428 429//429 318//318 -f 318//318 429//429 430//430 -f 318//318 430//430 419//419 -f 416//416 338//338 418//418 -f 418//418 338//338 322//322 -f 418//418 322//322 358//358 -f 431//431 432//432 433//433 -f 431//431 433//433 434//434 -f 434//434 433//433 435//435 -f 434//434 435//435 436//436 -f 436//436 435//435 437//437 -f 436//436 437//437 438//438 -f 438//438 437//437 439//439 -f 438//438 439//439 440//440 -f 440//440 439//439 441//441 -f 440//440 441//441 442//442 -f 442//442 441//441 443//443 -f 442//442 443//443 444//444 -f 444//444 443//443 445//445 -f 444//444 445//445 446//446 -f 446//446 445//445 447//447 -f 446//446 447//447 448//448 -f 448//448 447//447 449//449 -f 448//448 449//449 450//450 -f 450//450 449//449 451//451 -f 450//450 451//451 452//452 -f 452//452 451//451 453//453 -f 452//452 453//453 454//454 -f 454//454 453//453 455//455 -f 454//454 455//455 456//456 -f 456//456 455//455 457//457 -f 456//456 457//457 458//458 -f 458//458 457//457 459//459 -f 458//458 459//459 460//460 -f 460//460 459//459 461//461 -f 460//460 461//461 462//462 -f 462//462 461//461 463//463 -f 462//462 463//463 464//464 -f 464//464 463//463 465//465 -f 464//464 465//465 466//466 -f 465//465 467//467 466//466 -f 466//466 467//467 468//468 -f 466//466 468//468 469//469 -f 469//469 468//468 470//470 -f 469//469 470//470 471//471 -f 471//471 470//470 472//472 -f 471//471 472//472 473//473 -f 473//473 472//472 474//474 -f 473//473 474//474 475//475 -f 475//475 474//474 476//476 -f 475//475 476//476 477//477 -f 477//477 476//476 478//478 -f 477//477 478//478 479//479 -f 479//479 478//478 480//480 -f 479//479 480//480 481//481 -f 481//481 480//480 482//482 -f 481//481 482//482 483//483 -f 483//483 482//482 484//484 -f 483//483 484//484 485//485 -f 485//485 484//484 486//486 -f 485//485 486//486 487//487 -f 487//487 486//486 488//488 -f 487//487 488//488 489//489 -f 489//489 488//488 490//490 -f 489//489 490//490 491//491 -f 491//491 490//490 492//492 -f 491//491 492//492 493//493 -f 493//493 492//492 494//494 -f 493//493 494//494 495//495 -f 495//495 494//494 496//496 -f 495//495 496//496 497//497 -f 497//497 496//496 498//498 -f 497//497 498//498 499//499 -f 499//499 498//498 500//500 -f 499//499 500//500 501//501 -f 501//501 500//500 432//432 -f 501//501 432//432 502//502 -f 502//502 432//432 431//431 -f 503//503 504//504 505//505 -f 503//503 505//505 506//506 -f 506//506 505//505 507//507 -f 506//506 507//507 508//508 -f 508//508 507//507 509//509 -f 508//508 509//509 510//510 -f 510//510 509//509 511//511 -f 510//510 511//511 512//512 -f 512//512 511//511 513//513 -f 512//512 513//513 514//514 -f 514//514 513//513 515//515 -f 514//514 515//515 516//516 -f 516//516 515//515 517//517 -f 516//516 517//517 518//518 -f 518//518 517//517 519//519 -f 518//518 519//519 520//520 -f 520//520 519//519 521//521 -f 520//520 521//521 522//522 -f 522//522 521//521 523//523 -f 522//522 523//523 524//524 -f 524//524 523//523 525//525 -f 524//524 525//525 526//526 -f 526//526 525//525 527//527 -f 526//526 527//527 528//528 -f 528//528 527//527 529//529 -f 528//528 529//529 530//530 -f 530//530 529//529 531//531 -f 530//530 531//531 532//532 -f 532//532 531//531 533//533 -f 532//532 533//533 534//534 -f 534//534 533//533 535//535 -f 534//534 535//535 536//536 -f 536//536 535//535 537//537 -f 536//536 537//537 538//538 -f 503//503 539//539 504//504 -f 504//504 539//539 540//540 -f 504//504 540//540 541//541 -f 541//541 540//540 542//542 -f 541//541 542//542 543//543 -f 543//543 542//542 544//544 -f 543//543 544//544 545//545 -f 545//545 544//544 546//546 -f 545//545 546//546 547//547 -f 547//547 546//546 548//548 -f 547//547 548//548 549//549 -f 549//549 548//548 550//550 -f 549//549 550//550 551//551 -f 551//551 550//550 552//552 -f 551//551 552//552 553//553 -f 553//553 552//552 554//554 -f 553//553 554//554 555//555 -f 555//555 554//554 556//556 -f 555//555 556//556 557//557 -f 557//557 556//556 558//558 -f 557//557 558//558 559//559 -f 559//559 558//558 560//560 -f 559//559 560//560 561//561 -f 561//561 560//560 562//562 -f 561//561 562//562 563//563 -f 563//563 562//562 564//564 -f 563//563 564//564 565//565 -f 565//565 564//564 566//566 -f 565//565 566//566 567//567 -f 567//567 566//566 568//568 -f 567//567 568//568 569//569 -f 569//569 568//568 570//570 -f 569//569 570//570 571//571 -f 571//571 570//570 572//572 -f 571//571 572//572 573//573 -f 573//573 572//572 538//538 -f 573//573 538//538 574//574 -f 574//574 538//538 537//537 -f 360//360 362//362 424//424 -f 424//424 423//423 360//360 -f 360//360 423//423 422//422 -f 360//360 422//422 358//358 -f 358//358 422//422 417//417 -f 358//358 417//417 418//418 -f 370//370 290//290 289//289 -f 289//289 427//427 370//370 -f 370//370 427//427 426//426 -f 370//370 426//426 362//362 -f 362//362 426//426 425//425 -f 362//362 425//425 424//424 -f 318//318 317//317 428//428 -f 428//428 317//317 342//342 -f 428//428 342//342 429//429 -f 429//429 342//342 430//430 -f 430//430 342//342 343//343 -f 430//430 343//343 419//419 -f 419//419 343//343 420//420 -f 420//420 343//343 339//339 -f 420//420 339//339 421//421 -f 421//421 339//339 415//415 -f 415//415 339//339 338//338 -f 415//415 338//338 416//416 -f 333//333 335//335 305//305 -f 305//305 304//304 333//333 -f 333//333 304//304 303//303 -f 333//333 303//303 312//312 -f 312//312 303//303 296//296 -f 312//312 296//296 298//298 -f 336//336 315//315 297//297 -f 297//297 308//308 336//336 -f 336//336 308//308 307//307 -f 336//336 307//307 335//335 -f 335//335 307//307 306//306 -f 335//335 306//306 305//305 -f 293//293 292//292 309//309 -f 309//309 292//292 354//354 -f 309//309 354//354 310//310 -f 310//310 354//354 311//311 -f 311//311 354//354 355//355 -f 311//311 355//355 300//300 -f 300//300 355//355 301//301 -f 301//301 355//355 350//350 -f 301//301 350//350 302//302 -f 302//302 350//350 294//294 -f 294//294 350//350 314//314 -f 294//294 314//314 295//295 -f 334//334 332//332 471//471 -f 471//471 473//473 334//334 -f 334//334 473//473 475//475 -f 334//334 475//475 327//327 -f 475//475 477//477 327//327 -f 327//327 477//477 479//479 -f 327//327 479//479 326//326 -f 479//479 481//481 326//326 -f 326//326 481//481 483//483 -f 326//326 483//483 325//325 -f 483//483 485//485 325//325 -f 325//325 485//485 487//487 -f 325//325 487//487 340//340 -f 487//487 489//489 340//340 -f 340//340 489//489 491//491 -f 340//340 491//491 341//341 -f 491//491 493//493 341//341 -f 341//341 493//493 495//495 -f 341//341 495//495 337//337 -f 495//495 497//497 337//337 -f 337//337 497//497 499//499 -f 337//337 499//499 344//344 -f 344//344 499//499 501//501 -f 344//344 501//501 345//345 -f 345//345 501//501 502//502 -f 345//345 502//502 346//346 -f 346//346 502//502 431//431 -f 346//346 431//431 328//328 -f 431//431 434//434 328//328 -f 328//328 434//434 436//436 -f 328//328 436//436 329//329 -f 436//436 438//438 329//329 -f 329//329 438//438 440//440 -f 329//329 440//440 330//330 -f 440//440 442//442 330//330 -f 330//330 442//442 444//444 -f 330//330 444//444 323//323 -f 444//444 446//446 323//323 -f 323//323 446//446 448//448 -f 323//323 448//448 324//324 -f 448//448 450//450 324//324 -f 324//324 450//450 452//452 -f 324//324 452//452 319//319 -f 452//452 454//454 319//319 -f 319//319 454//454 456//456 -f 319//319 456//456 320//320 -f 456//456 458//458 320//320 -f 320//320 458//458 460//460 -f 320//320 460//460 321//321 -f 460//460 462//462 321//321 -f 321//321 462//462 464//464 -f 321//321 464//464 331//331 -f 331//331 464//464 466//466 -f 331//331 466//466 332//332 -f 332//332 466//466 469//469 -f 332//332 469//469 471//471 -f 353//353 352//352 543//543 -f 543//543 545//545 353//353 -f 353//353 545//545 547//547 -f 353//353 547//547 351//351 -f 547//547 549//549 351//351 -f 351//351 549//549 551//551 -f 351//351 551//551 363//363 -f 551//551 553//553 363//363 -f 363//363 553//553 555//555 -f 363//363 555//555 364//364 -f 555//555 557//557 364//364 -f 364//364 557//557 559//559 -f 364//364 559//559 365//365 -f 559//559 561//561 365//365 -f 365//365 561//561 563//563 -f 365//365 563//563 366//366 -f 563//563 565//565 366//366 -f 366//366 565//565 567//567 -f 366//366 567//567 371//371 -f 567//567 569//569 371//371 -f 371//371 569//569 571//571 -f 371//371 571//571 372//372 -f 372//372 571//571 573//573 -f 372//372 573//573 373//373 -f 373//373 573//573 574//574 -f 373//373 574//574 356//356 -f 356//356 574//574 537//537 -f 356//356 537//537 357//357 -f 537//537 535//535 357//357 -f 357//357 535//535 533//533 -f 357//357 533//533 367//367 -f 533//533 531//531 367//367 -f 367//367 531//531 529//529 -f 367//367 529//529 368//368 -f 529//529 527//527 368//368 -f 368//368 527//527 525//525 -f 368//368 525//525 369//369 -f 525//525 523//523 369//369 -f 369//369 523//523 521//521 -f 369//369 521//521 359//359 -f 521//521 519//519 359//359 -f 359//359 519//519 517//517 -f 359//359 517//517 361//361 -f 517//517 515//515 361//361 -f 361//361 515//515 513//513 -f 361//361 513//513 347//347 -f 513//513 511//511 347//347 -f 347//347 511//511 509//509 -f 347//347 509//509 348//348 -f 509//509 507//507 348//348 -f 348//348 507//507 505//505 -f 348//348 505//505 349//349 -f 349//349 505//505 504//504 -f 349//349 504//504 352//352 -f 352//352 504//504 541//541 -f 352//352 541//541 543//543 -f 398//398 397//397 570//570 -f 570//570 568//568 398//398 -f 398//398 568//568 566//566 -f 398//398 566//566 403//403 -f 566//566 564//564 403//403 -f 403//403 564//564 562//562 -f 403//403 562//562 404//404 -f 562//562 560//560 404//404 -f 404//404 560//560 558//558 -f 404//404 558//558 405//405 -f 558//558 556//556 405//405 -f 405//405 556//556 554//554 -f 405//405 554//554 399//399 -f 554//554 552//552 399//399 -f 399//399 552//552 550//550 -f 399//399 550//550 400//400 -f 550//550 548//548 400//400 -f 400//400 548//548 546//546 -f 400//400 546//546 401//401 -f 546//546 544//544 401//401 -f 401//401 544//544 542//542 -f 401//401 542//542 402//402 -f 542//542 540//540 402//402 -f 402//402 540//540 539//539 -f 402//402 539//539 406//406 -f 406//406 539//539 503//503 -f 406//406 503//503 407//407 -f 503//503 506//506 407//407 -f 407//407 506//506 508//508 -f 407//407 508//508 408//408 -f 508//508 510//510 408//408 -f 408//408 510//510 512//512 -f 408//408 512//512 409//409 -f 512//512 514//514 409//409 -f 409//409 514//514 516//516 -f 409//409 516//516 410//410 -f 516//516 518//518 410//410 -f 410//410 518//518 520//520 -f 410//410 520//520 411//411 -f 520//520 522//522 411//411 -f 411//411 522//522 524//524 -f 411//411 524//524 412//412 -f 524//524 526//526 412//412 -f 412//412 526//526 528//528 -f 412//412 528//528 413//413 -f 528//528 530//530 413//413 -f 413//413 530//530 532//532 -f 413//413 532//532 414//414 -f 532//532 534//534 414//414 -f 414//414 534//534 536//536 -f 414//414 536//536 396//396 -f 396//396 536//536 538//538 -f 396//396 538//538 397//397 -f 397//397 538//538 572//572 -f 397//397 572//572 570//570 -f 380//380 379//379 498//498 -f 498//498 496//496 380//380 -f 380//380 496//496 494//494 -f 380//380 494//494 381//381 -f 494//494 492//492 381//381 -f 381//381 492//492 490//490 -f 381//381 490//490 375//375 -f 490//490 488//488 375//375 -f 375//375 488//488 486//486 -f 375//375 486//486 374//374 -f 486//486 484//484 374//374 -f 374//374 484//484 482//482 -f 374//374 482//482 390//390 -f 482//482 480//480 390//390 -f 390//390 480//480 478//478 -f 390//390 478//478 391//391 -f 478//478 476//476 391//391 -f 391//391 476//476 474//474 -f 391//391 474//474 392//392 -f 474//474 472//472 392//392 -f 392//392 472//472 470//470 -f 392//392 470//470 393//393 -f 393//393 470//470 468//468 -f 393//393 468//468 394//394 -f 394//394 468//468 467//467 -f 394//394 467//467 395//395 -f 395//395 467//467 465//465 -f 395//395 465//465 376//376 -f 465//465 463//463 376//376 -f 376//376 463//463 461//461 -f 376//376 461//461 377//377 -f 461//461 459//459 377//377 -f 377//377 459//459 457//457 -f 377//377 457//457 382//382 -f 457//457 455//455 382//382 -f 382//382 455//455 453//453 -f 382//382 453//453 383//383 -f 453//453 451//451 383//383 -f 383//383 451//451 449//449 -f 383//383 449//449 385//385 -f 449//449 447//447 385//385 -f 385//385 447//447 445//445 -f 385//385 445//445 386//386 -f 445//445 443//443 386//386 -f 386//386 443//443 441//441 -f 386//386 441//441 387//387 -f 441//441 439//439 387//387 -f 387//387 439//439 437//437 -f 387//387 437//437 388//388 -f 437//437 435//435 388//388 -f 388//388 435//435 433//433 -f 388//388 433//433 389//389 -f 389//389 433//433 432//432 -f 389//389 432//432 379//379 -f 379//379 432//432 500//500 -f 379//379 500//500 498//498 -f 575//575 576//576 577//577 -f 575//575 577//577 578//578 -f 578//578 577//577 579//579 -f 578//578 579//579 580//580 -f 581//581 582//582 580//580 -f 583//583 584//584 585//585 -f 585//585 584//584 586//586 -f 585//585 586//586 582//582 -f 582//582 586//586 578//578 -f 582//582 578//578 580//580 -f 587//587 588//588 580//580 -f 580//580 588//588 589//589 -f 580//580 589//589 581//581 -f 583//583 590//590 584//584 -f 584//584 590//590 591//591 -f 584//584 591//591 592//592 -f 592//592 593//593 584//584 -f 584//584 593//593 594//594 -f 584//584 594//594 595//595 -f 596//596 597//597 580//580 -f 580//580 597//597 598//598 -f 580//580 598//598 587//587 -f 599//599 585//585 600//600 -f 600//600 585//585 582//582 -f 600//600 582//582 601//601 -f 586//586 584//584 602//602 -f 586//586 602//602 603//603 -f 603//603 602//602 604//604 -f 603//603 604//604 605//605 -f 606//606 607//607 600//600 -f 600//600 607//607 608//608 -f 600//600 608//608 599//599 -f 609//609 610//610 600//600 -f 600//600 610//610 611//611 -f 600//600 611//611 606//606 -f 612//612 604//604 613//613 -f 613//613 604//604 602//602 -f 613//613 602//602 614//614 -f 615//615 616//616 609//609 -f 609//609 616//616 617//617 -f 609//609 617//617 610//610 -f 608//608 618//618 599//599 -f 599//599 618//618 619//619 -f 599//599 619//619 620//620 -f 620//620 619//619 621//621 -f 620//620 621//621 622//622 -f 614//614 602//602 621//621 -f 621//621 602//602 623//623 -f 621//621 623//623 622//622 -f 624//624 625//625 626//626 -f 612//612 627//627 604//604 -f 604//604 627//627 628//628 -f 604//604 628//628 629//629 -f 629//629 628//628 624//624 -f 629//629 624//624 630//630 -f 630//630 624//624 626//626 -f 624//624 631//631 625//625 -f 625//625 631//631 632//632 -f 625//625 632//632 609//609 -f 609//609 632//632 633//633 -f 609//609 633//633 615//615 -f 634//634 635//635 577//577 -f 577//577 635//635 636//636 -f 577//577 636//636 579//579 -f 601//601 637//637 638//638 -f 636//636 639//639 579//579 -f 579//579 639//639 640//640 -f 579//579 640//640 641//641 -f 641//641 640//640 638//638 -f 641//641 638//638 642//642 -f 642//642 638//638 637//637 -f 643//643 644//644 609//609 -f 645//645 646//646 647//647 -f 647//647 646//646 648//648 -f 647//647 648//648 649//649 -f 638//638 650//650 601//601 -f 601//601 650//650 651//651 -f 601//601 651//651 600//600 -f 600//600 651//651 652//652 -f 600//600 652//652 653//653 -f 644//644 654//654 609//609 -f 609//609 654//654 655//655 -f 609//609 655//655 645//645 -f 645//645 655//655 656//656 -f 645//645 656//656 646//646 -f 634//634 577//577 648//648 -f 648//648 577//577 657//657 -f 648//648 657//657 649//649 -f 653//653 658//658 600//600 -f 600//600 658//658 659//659 -f 600//600 659//659 609//609 -f 609//609 659//659 660//660 -f 609//609 660//660 643//643 -f 661//661 586//586 662//662 -f 662//662 586//586 603//603 -f 663//663 664//664 665//665 -f 666//666 667//667 603//603 -f 603//603 667//667 668//668 -f 603//603 668//668 662//662 -f 664//664 669//669 665//665 -f 665//665 669//669 670//670 -f 665//665 670//670 671//671 -f 671//671 670//670 672//672 -f 671//671 672//672 673//673 -f 673//673 674//674 671//671 -f 671//671 674//674 675//675 -f 671//671 675//675 603//603 -f 603//603 675//675 676//676 -f 603//603 676//676 666//666 -f 661//661 677//677 586//586 -f 586//586 677//677 678//678 -f 586//586 678//678 679//679 -f 679//679 680//680 586//586 -f 586//586 680//680 681//681 -f 586//586 681//681 665//665 -f 665//665 681//681 682//682 -f 665//665 682//682 663//663 -f 586//586 665//665 578//578 -f 671//671 683//683 665//665 -f 665//665 683//683 684//684 -f 665//665 684//684 685//685 -f 686//686 687//687 578//578 -f 687//687 688//688 578//578 -f 578//578 688//688 689//689 -f 578//578 689//689 575//575 -f 685//685 690//690 665//665 -f 665//665 690//690 691//691 -f 665//665 691//691 578//578 -f 578//578 691//691 692//692 -f 578//578 692//692 686//686 -f 689//689 693//693 575//575 -f 575//575 693//693 694//694 -f 575//575 694//694 695//695 -f 695//695 696//696 575//575 -f 575//575 696//696 697//697 -f 575//575 697//697 671//671 -f 671//671 697//697 698//698 -f 671//671 698//698 699//699 -f 699//699 700//700 671//671 -f 671//671 700//700 701//701 -f 671//671 701//701 683//683 -f 671//671 603//603 575//575 -f 702//702 703//703 605//605 -f 704//704 576//576 705//705 -f 705//705 576//576 575//575 -f 705//705 575//575 703//703 -f 703//703 575//575 603//603 -f 703//703 603//603 605//605 -f 706//706 707//707 605//605 -f 605//605 707//707 708//708 -f 605//605 708//708 702//702 -f 704//704 709//709 576//576 -f 576//576 709//709 710//710 -f 576//576 710//710 711//711 -f 711//711 712//712 576//576 -f 576//576 712//712 713//713 -f 576//576 713//713 714//714 -f 715//715 716//716 605//605 -f 605//605 716//716 717//717 -f 605//605 717//717 706//706 -f 703//703 625//625 705//705 -f 705//705 625//625 609//609 -f 705//705 609//609 645//645 -f 718//718 719//719 720//720 -f 718//718 720//720 721//721 -f 721//721 720//720 722//722 -f 721//721 722//722 723//723 -f 723//723 722//722 724//724 -f 723//723 724//724 725//725 -f 725//725 724//724 726//726 -f 725//725 726//726 727//727 -f 727//727 726//726 728//728 -f 727//727 728//728 729//729 -f 729//729 728//728 730//730 -f 729//729 730//730 731//731 -f 731//731 730//730 732//732 -f 731//731 732//732 733//733 -f 733//733 732//732 734//734 -f 733//733 734//734 735//735 -f 735//735 734//734 736//736 -f 735//735 736//736 737//737 -f 737//737 736//736 738//738 -f 737//737 738//738 739//739 -f 739//739 738//738 740//740 -f 739//739 740//740 741//741 -f 741//741 740//740 742//742 -f 741//741 742//742 743//743 -f 743//743 742//742 744//744 -f 743//743 744//744 745//745 -f 745//745 744//744 746//746 -f 745//745 746//746 747//747 -f 747//747 746//746 748//748 -f 747//747 748//748 749//749 -f 749//749 748//748 750//750 -f 749//749 750//750 751//751 -f 751//751 750//750 752//752 -f 751//751 752//752 753//753 -f 752//752 754//754 753//753 -f 753//753 754//754 755//755 -f 753//753 755//755 756//756 -f 756//756 755//755 757//757 -f 756//756 757//757 758//758 -f 758//758 757//757 759//759 -f 758//758 759//759 760//760 -f 760//760 759//759 761//761 -f 760//760 761//761 762//762 -f 762//762 761//761 763//763 -f 762//762 763//763 764//764 -f 764//764 763//763 765//765 -f 764//764 765//765 766//766 -f 766//766 765//765 767//767 -f 766//766 767//767 768//768 -f 768//768 767//767 769//769 -f 768//768 769//769 770//770 -f 770//770 769//769 771//771 -f 770//770 771//771 772//772 -f 772//772 771//771 773//773 -f 772//772 773//773 774//774 -f 774//774 773//773 775//775 -f 774//774 775//775 776//776 -f 776//776 775//775 777//777 -f 776//776 777//777 778//778 -f 778//778 777//777 779//779 -f 778//778 779//779 780//780 -f 780//780 779//779 781//781 -f 780//780 781//781 782//782 -f 782//782 781//781 783//783 -f 782//782 783//783 784//784 -f 784//784 783//783 785//785 -f 784//784 785//785 786//786 -f 786//786 785//785 787//787 -f 786//786 787//787 788//788 -f 788//788 787//787 719//719 -f 788//788 719//719 789//789 -f 789//789 719//719 718//718 -f 790//790 791//791 792//792 -f 790//790 792//792 793//793 -f 793//793 792//792 794//794 -f 793//793 794//794 795//795 -f 795//795 794//794 796//796 -f 795//795 796//796 797//797 -f 797//797 796//796 798//798 -f 797//797 798//798 799//799 -f 799//799 798//798 800//800 -f 799//799 800//800 801//801 -f 801//801 800//800 802//802 -f 801//801 802//802 803//803 -f 803//803 802//802 804//804 -f 803//803 804//804 805//805 -f 805//805 804//804 806//806 -f 805//805 806//806 807//807 -f 807//807 806//806 808//808 -f 807//807 808//808 809//809 -f 809//809 808//808 810//810 -f 809//809 810//810 811//811 -f 811//811 810//810 812//812 -f 811//811 812//812 813//813 -f 813//813 812//812 814//814 -f 813//813 814//814 815//815 -f 815//815 814//814 816//816 -f 815//815 816//816 817//817 -f 817//817 816//816 818//818 -f 817//817 818//818 819//819 -f 819//819 818//818 820//820 -f 819//819 820//820 821//821 -f 821//821 820//820 822//822 -f 821//821 822//822 823//823 -f 823//823 822//822 824//824 -f 823//823 824//824 825//825 -f 790//790 826//826 791//791 -f 791//791 826//826 827//827 -f 791//791 827//827 828//828 -f 828//828 827//827 829//829 -f 828//828 829//829 830//830 -f 830//830 829//829 831//831 -f 830//830 831//831 832//832 -f 832//832 831//831 833//833 -f 832//832 833//833 834//834 -f 834//834 833//833 835//835 -f 834//834 835//835 836//836 -f 836//836 835//835 837//837 -f 836//836 837//837 838//838 -f 838//838 837//837 839//839 -f 838//838 839//839 840//840 -f 840//840 839//839 841//841 -f 840//840 841//841 842//842 -f 842//842 841//841 843//843 -f 842//842 843//843 844//844 -f 844//844 843//843 845//845 -f 844//844 845//845 846//846 -f 846//846 845//845 847//847 -f 846//846 847//847 848//848 -f 848//848 847//847 849//849 -f 848//848 849//849 850//850 -f 850//850 849//849 851//851 -f 850//850 851//851 852//852 -f 852//852 851//851 853//853 -f 852//852 853//853 854//854 -f 854//854 853//853 855//855 -f 854//854 855//855 856//856 -f 856//856 855//855 857//857 -f 856//856 857//857 858//858 -f 858//858 857//857 859//859 -f 858//858 859//859 860//860 -f 860//860 859//859 825//825 -f 860//860 825//825 861//861 -f 861//861 825//825 824//824 -f 647//647 649//649 711//711 -f 711//711 710//710 647//647 -f 647//647 710//710 709//709 -f 647//647 709//709 645//645 -f 645//645 709//709 704//704 -f 645//645 704//704 705//705 -f 657//657 577//577 576//576 -f 576//576 714//714 657//657 -f 657//657 714//714 713//713 -f 657//657 713//713 649//649 -f 649//649 713//713 712//712 -f 649//649 712//712 711//711 -f 605//605 604//604 715//715 -f 715//715 604//604 629//629 -f 715//715 629//629 716//716 -f 716//716 629//629 717//717 -f 717//717 629//629 630//630 -f 717//717 630//630 706//706 -f 706//706 630//630 707//707 -f 707//707 630//630 626//626 -f 707//707 626//626 708//708 -f 708//708 626//626 702//702 -f 702//702 626//626 625//625 -f 702//702 625//625 703//703 -f 620//620 622//622 592//592 -f 592//592 591//591 620//620 -f 620//620 591//591 590//590 -f 620//620 590//590 599//599 -f 599//599 590//590 583//583 -f 599//599 583//583 585//585 -f 623//623 602//602 584//584 -f 584//584 595//595 623//623 -f 623//623 595//595 594//594 -f 623//623 594//594 622//622 -f 622//622 594//594 593//593 -f 622//622 593//593 592//592 -f 580//580 579//579 596//596 -f 596//596 579//579 641//641 -f 596//596 641//641 597//597 -f 597//597 641//641 598//598 -f 598//598 641//641 642//642 -f 598//598 642//642 587//587 -f 587//587 642//642 588//588 -f 588//588 642//642 637//637 -f 588//588 637//637 589//589 -f 589//589 637//637 581//581 -f 581//581 637//637 601//601 -f 581//581 601//601 582//582 -f 621//621 619//619 758//758 -f 758//758 760//760 621//621 -f 621//621 760//760 762//762 -f 621//621 762//762 614//614 -f 762//762 764//764 614//614 -f 614//614 764//764 766//766 -f 614//614 766//766 613//613 -f 766//766 768//768 613//613 -f 613//613 768//768 770//770 -f 613//613 770//770 612//612 -f 770//770 772//772 612//612 -f 612//612 772//772 774//774 -f 612//612 774//774 627//627 -f 774//774 776//776 627//627 -f 627//627 776//776 778//778 -f 627//627 778//778 628//628 -f 778//778 780//780 628//628 -f 628//628 780//780 782//782 -f 628//628 782//782 624//624 -f 782//782 784//784 624//624 -f 624//624 784//784 786//786 -f 624//624 786//786 631//631 -f 631//631 786//786 788//788 -f 631//631 788//788 632//632 -f 632//632 788//788 789//789 -f 632//632 789//789 633//633 -f 633//633 789//789 718//718 -f 633//633 718//718 615//615 -f 718//718 721//721 615//615 -f 615//615 721//721 723//723 -f 615//615 723//723 616//616 -f 723//723 725//725 616//616 -f 616//616 725//725 727//727 -f 616//616 727//727 617//617 -f 727//727 729//729 617//617 -f 617//617 729//729 731//731 -f 617//617 731//731 610//610 -f 731//731 733//733 610//610 -f 610//610 733//733 735//735 -f 610//610 735//735 611//611 -f 735//735 737//737 611//611 -f 611//611 737//737 739//739 -f 611//611 739//739 606//606 -f 739//739 741//741 606//606 -f 606//606 741//741 743//743 -f 606//606 743//743 607//607 -f 743//743 745//745 607//607 -f 607//607 745//745 747//747 -f 607//607 747//747 608//608 -f 747//747 749//749 608//608 -f 608//608 749//749 751//751 -f 608//608 751//751 618//618 -f 618//618 751//751 753//753 -f 618//618 753//753 619//619 -f 619//619 753//753 756//756 -f 619//619 756//756 758//758 -f 640//640 639//639 830//830 -f 830//830 832//832 640//640 -f 640//640 832//832 834//834 -f 640//640 834//834 638//638 -f 834//834 836//836 638//638 -f 638//638 836//836 838//838 -f 638//638 838//838 650//650 -f 838//838 840//840 650//650 -f 650//650 840//840 842//842 -f 650//650 842//842 651//651 -f 842//842 844//844 651//651 -f 651//651 844//844 846//846 -f 651//651 846//846 652//652 -f 846//846 848//848 652//652 -f 652//652 848//848 850//850 -f 652//652 850//850 653//653 -f 850//850 852//852 653//653 -f 653//653 852//852 854//854 -f 653//653 854//854 658//658 -f 854//854 856//856 658//658 -f 658//658 856//856 858//858 -f 658//658 858//858 659//659 -f 659//659 858//858 860//860 -f 659//659 860//860 660//660 -f 660//660 860//860 861//861 -f 660//660 861//861 643//643 -f 643//643 861//861 824//824 -f 643//643 824//824 644//644 -f 824//824 822//822 644//644 -f 644//644 822//822 820//820 -f 644//644 820//820 654//654 -f 820//820 818//818 654//654 -f 654//654 818//818 816//816 -f 654//654 816//816 655//655 -f 816//816 814//814 655//655 -f 655//655 814//814 812//812 -f 655//655 812//812 656//656 -f 812//812 810//810 656//656 -f 656//656 810//810 808//808 -f 656//656 808//808 646//646 -f 808//808 806//806 646//646 -f 646//646 806//806 804//804 -f 646//646 804//804 648//648 -f 804//804 802//802 648//648 -f 648//648 802//802 800//800 -f 648//648 800//800 634//634 -f 800//800 798//798 634//634 -f 634//634 798//798 796//796 -f 634//634 796//796 635//635 -f 796//796 794//794 635//635 -f 635//635 794//794 792//792 -f 635//635 792//792 636//636 -f 636//636 792//792 791//791 -f 636//636 791//791 639//639 -f 639//639 791//791 828//828 -f 639//639 828//828 830//830 -f 685//685 684//684 857//857 -f 857//857 855//855 685//685 -f 685//685 855//855 853//853 -f 685//685 853//853 690//690 -f 853//853 851//851 690//690 -f 690//690 851//851 849//849 -f 690//690 849//849 691//691 -f 849//849 847//847 691//691 -f 691//691 847//847 845//845 -f 691//691 845//845 692//692 -f 845//845 843//843 692//692 -f 692//692 843//843 841//841 -f 692//692 841//841 686//686 -f 841//841 839//839 686//686 -f 686//686 839//839 837//837 -f 686//686 837//837 687//687 -f 837//837 835//835 687//687 -f 687//687 835//835 833//833 -f 687//687 833//833 688//688 -f 833//833 831//831 688//688 -f 688//688 831//831 829//829 -f 688//688 829//829 689//689 -f 829//829 827//827 689//689 -f 689//689 827//827 826//826 -f 689//689 826//826 693//693 -f 693//693 826//826 790//790 -f 693//693 790//790 694//694 -f 790//790 793//793 694//694 -f 694//694 793//793 795//795 -f 694//694 795//795 695//695 -f 795//795 797//797 695//695 -f 695//695 797//797 799//799 -f 695//695 799//799 696//696 -f 799//799 801//801 696//696 -f 696//696 801//801 803//803 -f 696//696 803//803 697//697 -f 803//803 805//805 697//697 -f 697//697 805//805 807//807 -f 697//697 807//807 698//698 -f 807//807 809//809 698//698 -f 698//698 809//809 811//811 -f 698//698 811//811 699//699 -f 811//811 813//813 699//699 -f 699//699 813//813 815//815 -f 699//699 815//815 700//700 -f 815//815 817//817 700//700 -f 700//700 817//817 819//819 -f 700//700 819//819 701//701 -f 819//819 821//821 701//701 -f 701//701 821//821 823//823 -f 701//701 823//823 683//683 -f 683//683 823//823 825//825 -f 683//683 825//825 684//684 -f 684//684 825//825 859//859 -f 684//684 859//859 857//857 -f 667//667 666//666 785//785 -f 785//785 783//783 667//667 -f 667//667 783//783 781//781 -f 667//667 781//781 668//668 -f 781//781 779//779 668//668 -f 668//668 779//779 777//777 -f 668//668 777//777 662//662 -f 777//777 775//775 662//662 -f 662//662 775//775 773//773 -f 662//662 773//773 661//661 -f 773//773 771//771 661//661 -f 661//661 771//771 769//769 -f 661//661 769//769 677//677 -f 769//769 767//767 677//677 -f 677//677 767//767 765//765 -f 677//677 765//765 678//678 -f 765//765 763//763 678//678 -f 678//678 763//763 761//761 -f 678//678 761//761 679//679 -f 761//761 759//759 679//679 -f 679//679 759//759 757//757 -f 679//679 757//757 680//680 -f 680//680 757//757 755//755 -f 680//680 755//755 681//681 -f 681//681 755//755 754//754 -f 681//681 754//754 682//682 -f 682//682 754//754 752//752 -f 682//682 752//752 663//663 -f 752//752 750//750 663//663 -f 663//663 750//750 748//748 -f 663//663 748//748 664//664 -f 748//748 746//746 664//664 -f 664//664 746//746 744//744 -f 664//664 744//744 669//669 -f 744//744 742//742 669//669 -f 669//669 742//742 740//740 -f 669//669 740//740 670//670 -f 740//740 738//738 670//670 -f 670//670 738//738 736//736 -f 670//670 736//736 672//672 -f 736//736 734//734 672//672 -f 672//672 734//734 732//732 -f 672//672 732//732 673//673 -f 732//732 730//730 673//673 -f 673//673 730//730 728//728 -f 673//673 728//728 674//674 -f 728//728 726//726 674//674 -f 674//674 726//726 724//724 -f 674//674 724//724 675//675 -f 724//724 722//722 675//675 -f 675//675 722//722 720//720 -f 675//675 720//720 676//676 -f 676//676 720//720 719//719 -f 676//676 719//719 666//666 -f 666//666 719//719 787//787 -f 666//666 787//787 785//785 -f 862//862 863//863 864//864 -f 862//862 864//864 865//865 -f 865//865 864//864 866//866 -f 865//865 866//866 867//867 -f 868//868 869//869 867//867 -f 870//870 871//871 872//872 -f 872//872 871//871 873//873 -f 872//872 873//873 869//869 -f 869//869 873//873 865//865 -f 869//869 865//865 867//867 -f 874//874 875//875 867//867 -f 867//867 875//875 876//876 -f 867//867 876//876 868//868 -f 870//870 877//877 871//871 -f 871//871 877//877 878//878 -f 871//871 878//878 879//879 -f 879//879 880//880 871//871 -f 871//871 880//880 881//881 -f 871//871 881//881 882//882 -f 883//883 884//884 867//867 -f 867//867 884//884 885//885 -f 867//867 885//885 874//874 -f 886//886 872//872 887//887 -f 887//887 872//872 869//869 -f 887//887 869//869 888//888 -f 873//873 871//871 889//889 -f 873//873 889//889 890//890 -f 890//890 889//889 891//891 -f 890//890 891//891 892//892 -f 893//893 894//894 887//887 -f 887//887 894//894 895//895 -f 887//887 895//895 886//886 -f 896//896 897//897 887//887 -f 887//887 897//897 898//898 -f 887//887 898//898 893//893 -f 899//899 891//891 900//900 -f 900//900 891//891 889//889 -f 900//900 889//889 901//901 -f 902//902 903//903 896//896 -f 896//896 903//903 904//904 -f 896//896 904//904 897//897 -f 895//895 905//905 886//886 -f 886//886 905//905 906//906 -f 886//886 906//906 907//907 -f 907//907 906//906 908//908 -f 907//907 908//908 909//909 -f 901//901 889//889 908//908 -f 908//908 889//889 910//910 -f 908//908 910//910 909//909 -f 911//911 912//912 913//913 -f 899//899 914//914 891//891 -f 891//891 914//914 915//915 -f 891//891 915//915 916//916 -f 916//916 915//915 911//911 -f 916//916 911//911 917//917 -f 917//917 911//911 913//913 -f 911//911 918//918 912//912 -f 912//912 918//918 919//919 -f 912//912 919//919 896//896 -f 896//896 919//919 920//920 -f 896//896 920//920 902//902 -f 921//921 922//922 864//864 -f 864//864 922//922 923//923 -f 864//864 923//923 866//866 -f 888//888 924//924 925//925 -f 923//923 926//926 866//866 -f 866//866 926//926 927//927 -f 866//866 927//927 928//928 -f 928//928 927//927 925//925 -f 928//928 925//925 929//929 -f 929//929 925//925 924//924 -f 930//930 931//931 896//896 -f 932//932 933//933 934//934 -f 934//934 933//933 935//935 -f 934//934 935//935 936//936 -f 925//925 937//937 888//888 -f 888//888 937//937 938//938 -f 888//888 938//938 887//887 -f 887//887 938//938 939//939 -f 887//887 939//939 940//940 -f 931//931 941//941 896//896 -f 896//896 941//941 942//942 -f 896//896 942//942 932//932 -f 932//932 942//942 943//943 -f 932//932 943//943 933//933 -f 921//921 864//864 935//935 -f 935//935 864//864 944//944 -f 935//935 944//944 936//936 -f 940//940 945//945 887//887 -f 887//887 945//945 946//946 -f 887//887 946//946 896//896 -f 896//896 946//946 947//947 -f 896//896 947//947 930//930 -f 948//948 873//873 949//949 -f 949//949 873//873 890//890 -f 950//950 951//951 952//952 -f 953//953 954//954 890//890 -f 890//890 954//954 955//955 -f 890//890 955//955 949//949 -f 951//951 956//956 952//952 -f 952//952 956//956 957//957 -f 952//952 957//957 958//958 -f 958//958 957//957 959//959 -f 958//958 959//959 960//960 -f 960//960 961//961 958//958 -f 958//958 961//961 962//962 -f 958//958 962//962 890//890 -f 890//890 962//962 963//963 -f 890//890 963//963 953//953 -f 948//948 964//964 873//873 -f 873//873 964//964 965//965 -f 873//873 965//965 966//966 -f 966//966 967//967 873//873 -f 873//873 967//967 968//968 -f 873//873 968//968 952//952 -f 952//952 968//968 969//969 -f 952//952 969//969 950//950 -f 873//873 952//952 865//865 -f 958//958 970//970 952//952 -f 952//952 970//970 971//971 -f 952//952 971//971 972//972 -f 973//973 974//974 865//865 -f 974//974 975//975 865//865 -f 865//865 975//975 976//976 -f 865//865 976//976 862//862 -f 972//972 977//977 952//952 -f 952//952 977//977 978//978 -f 952//952 978//978 865//865 -f 865//865 978//978 979//979 -f 865//865 979//979 973//973 -f 976//976 980//980 862//862 -f 862//862 980//980 981//981 -f 862//862 981//981 982//982 -f 982//982 983//983 862//862 -f 862//862 983//983 984//984 -f 862//862 984//984 958//958 -f 958//958 984//984 985//985 -f 958//958 985//985 986//986 -f 986//986 987//987 958//958 -f 958//958 987//987 988//988 -f 958//958 988//988 970//970 -f 958//958 890//890 862//862 -f 989//989 990//990 892//892 -f 991//991 863//863 992//992 -f 992//992 863//863 862//862 -f 992//992 862//862 990//990 -f 990//990 862//862 890//890 -f 990//990 890//890 892//892 -f 993//993 994//994 892//892 -f 892//892 994//994 995//995 -f 892//892 995//995 989//989 -f 991//991 996//996 863//863 -f 863//863 996//996 997//997 -f 863//863 997//997 998//998 -f 998//998 999//999 863//863 -f 863//863 999//999 1000//1000 -f 863//863 1000//1000 1001//1001 -f 1002//1002 1003//1003 892//892 -f 892//892 1003//1003 1004//1004 -f 892//892 1004//1004 993//993 -f 990//990 912//912 992//992 -f 992//992 912//912 896//896 -f 992//992 896//896 932//932 -f 1005//1005 1006//1006 1007//1007 -f 1005//1005 1007//1007 1008//1008 -f 1008//1008 1007//1007 1009//1009 -f 1008//1008 1009//1009 1010//1010 -f 1010//1010 1009//1009 1011//1011 -f 1010//1010 1011//1011 1012//1012 -f 1012//1012 1011//1011 1013//1013 -f 1012//1012 1013//1013 1014//1014 -f 1014//1014 1013//1013 1015//1015 -f 1014//1014 1015//1015 1016//1016 -f 1016//1016 1015//1015 1017//1017 -f 1016//1016 1017//1017 1018//1018 -f 1018//1018 1017//1017 1019//1019 -f 1018//1018 1019//1019 1020//1020 -f 1020//1020 1019//1019 1021//1021 -f 1020//1020 1021//1021 1022//1022 -f 1022//1022 1021//1021 1023//1023 -f 1022//1022 1023//1023 1024//1024 -f 1024//1024 1023//1023 1025//1025 -f 1024//1024 1025//1025 1026//1026 -f 1026//1026 1025//1025 1027//1027 -f 1026//1026 1027//1027 1028//1028 -f 1028//1028 1027//1027 1029//1029 -f 1028//1028 1029//1029 1030//1030 -f 1030//1030 1029//1029 1031//1031 -f 1030//1030 1031//1031 1032//1032 -f 1032//1032 1031//1031 1033//1033 -f 1032//1032 1033//1033 1034//1034 -f 1034//1034 1033//1033 1035//1035 -f 1034//1034 1035//1035 1036//1036 -f 1036//1036 1035//1035 1037//1037 -f 1036//1036 1037//1037 1038//1038 -f 1038//1038 1037//1037 1039//1039 -f 1038//1038 1039//1039 1040//1040 -f 1039//1039 1041//1041 1040//1040 -f 1040//1040 1041//1041 1042//1042 -f 1040//1040 1042//1042 1043//1043 -f 1043//1043 1042//1042 1044//1044 -f 1043//1043 1044//1044 1045//1045 -f 1045//1045 1044//1044 1046//1046 -f 1045//1045 1046//1046 1047//1047 -f 1047//1047 1046//1046 1048//1048 -f 1047//1047 1048//1048 1049//1049 -f 1049//1049 1048//1048 1050//1050 -f 1049//1049 1050//1050 1051//1051 -f 1051//1051 1050//1050 1052//1052 -f 1051//1051 1052//1052 1053//1053 -f 1053//1053 1052//1052 1054//1054 -f 1053//1053 1054//1054 1055//1055 -f 1055//1055 1054//1054 1056//1056 -f 1055//1055 1056//1056 1057//1057 -f 1057//1057 1056//1056 1058//1058 -f 1057//1057 1058//1058 1059//1059 -f 1059//1059 1058//1058 1060//1060 -f 1059//1059 1060//1060 1061//1061 -f 1061//1061 1060//1060 1062//1062 -f 1061//1061 1062//1062 1063//1063 -f 1063//1063 1062//1062 1064//1064 -f 1063//1063 1064//1064 1065//1065 -f 1065//1065 1064//1064 1066//1066 -f 1065//1065 1066//1066 1067//1067 -f 1067//1067 1066//1066 1068//1068 -f 1067//1067 1068//1068 1069//1069 -f 1069//1069 1068//1068 1070//1070 -f 1069//1069 1070//1070 1071//1071 -f 1071//1071 1070//1070 1072//1072 -f 1071//1071 1072//1072 1073//1073 -f 1073//1073 1072//1072 1074//1074 -f 1073//1073 1074//1074 1075//1075 -f 1075//1075 1074//1074 1006//1006 -f 1075//1075 1006//1006 1076//1076 -f 1076//1076 1006//1006 1005//1005 -f 1077//1077 1078//1078 1079//1079 -f 1077//1077 1079//1079 1080//1080 -f 1080//1080 1079//1079 1081//1081 -f 1080//1080 1081//1081 1082//1082 -f 1082//1082 1081//1081 1083//1083 -f 1082//1082 1083//1083 1084//1084 -f 1084//1084 1083//1083 1085//1085 -f 1084//1084 1085//1085 1086//1086 -f 1086//1086 1085//1085 1087//1087 -f 1086//1086 1087//1087 1088//1088 -f 1088//1088 1087//1087 1089//1089 -f 1088//1088 1089//1089 1090//1090 -f 1090//1090 1089//1089 1091//1091 -f 1090//1090 1091//1091 1092//1092 -f 1092//1092 1091//1091 1093//1093 -f 1092//1092 1093//1093 1094//1094 -f 1094//1094 1093//1093 1095//1095 -f 1094//1094 1095//1095 1096//1096 -f 1096//1096 1095//1095 1097//1097 -f 1096//1096 1097//1097 1098//1098 -f 1098//1098 1097//1097 1099//1099 -f 1098//1098 1099//1099 1100//1100 -f 1100//1100 1099//1099 1101//1101 -f 1100//1100 1101//1101 1102//1102 -f 1102//1102 1101//1101 1103//1103 -f 1102//1102 1103//1103 1104//1104 -f 1104//1104 1103//1103 1105//1105 -f 1104//1104 1105//1105 1106//1106 -f 1106//1106 1105//1105 1107//1107 -f 1106//1106 1107//1107 1108//1108 -f 1108//1108 1107//1107 1109//1109 -f 1108//1108 1109//1109 1110//1110 -f 1110//1110 1109//1109 1111//1111 -f 1110//1110 1111//1111 1112//1112 -f 1077//1077 1113//1113 1078//1078 -f 1078//1078 1113//1113 1114//1114 -f 1078//1078 1114//1114 1115//1115 -f 1115//1115 1114//1114 1116//1116 -f 1115//1115 1116//1116 1117//1117 -f 1117//1117 1116//1116 1118//1118 -f 1117//1117 1118//1118 1119//1119 -f 1119//1119 1118//1118 1120//1120 -f 1119//1119 1120//1120 1121//1121 -f 1121//1121 1120//1120 1122//1122 -f 1121//1121 1122//1122 1123//1123 -f 1123//1123 1122//1122 1124//1124 -f 1123//1123 1124//1124 1125//1125 -f 1125//1125 1124//1124 1126//1126 -f 1125//1125 1126//1126 1127//1127 -f 1127//1127 1126//1126 1128//1128 -f 1127//1127 1128//1128 1129//1129 -f 1129//1129 1128//1128 1130//1130 -f 1129//1129 1130//1130 1131//1131 -f 1131//1131 1130//1130 1132//1132 -f 1131//1131 1132//1132 1133//1133 -f 1133//1133 1132//1132 1134//1134 -f 1133//1133 1134//1134 1135//1135 -f 1135//1135 1134//1134 1136//1136 -f 1135//1135 1136//1136 1137//1137 -f 1137//1137 1136//1136 1138//1138 -f 1137//1137 1138//1138 1139//1139 -f 1139//1139 1138//1138 1140//1140 -f 1139//1139 1140//1140 1141//1141 -f 1141//1141 1140//1140 1142//1142 -f 1141//1141 1142//1142 1143//1143 -f 1143//1143 1142//1142 1144//1144 -f 1143//1143 1144//1144 1145//1145 -f 1145//1145 1144//1144 1146//1146 -f 1145//1145 1146//1146 1147//1147 -f 1147//1147 1146//1146 1112//1112 -f 1147//1147 1112//1112 1148//1148 -f 1148//1148 1112//1112 1111//1111 -f 934//934 936//936 998//998 -f 998//998 997//997 934//934 -f 934//934 997//997 996//996 -f 934//934 996//996 932//932 -f 932//932 996//996 991//991 -f 932//932 991//991 992//992 -f 944//944 864//864 863//863 -f 863//863 1001//1001 944//944 -f 944//944 1001//1001 1000//1000 -f 944//944 1000//1000 936//936 -f 936//936 1000//1000 999//999 -f 936//936 999//999 998//998 -f 892//892 891//891 1002//1002 -f 1002//1002 891//891 916//916 -f 1002//1002 916//916 1003//1003 -f 1003//1003 916//916 1004//1004 -f 1004//1004 916//916 917//917 -f 1004//1004 917//917 993//993 -f 993//993 917//917 994//994 -f 994//994 917//917 913//913 -f 994//994 913//913 995//995 -f 995//995 913//913 989//989 -f 989//989 913//913 912//912 -f 989//989 912//912 990//990 -f 907//907 909//909 879//879 -f 879//879 878//878 907//907 -f 907//907 878//878 877//877 -f 907//907 877//877 886//886 -f 886//886 877//877 870//870 -f 886//886 870//870 872//872 -f 910//910 889//889 871//871 -f 871//871 882//882 910//910 -f 910//910 882//882 881//881 -f 910//910 881//881 909//909 -f 909//909 881//881 880//880 -f 909//909 880//880 879//879 -f 867//867 866//866 883//883 -f 883//883 866//866 928//928 -f 883//883 928//928 884//884 -f 884//884 928//928 885//885 -f 885//885 928//928 929//929 -f 885//885 929//929 874//874 -f 874//874 929//929 875//875 -f 875//875 929//929 924//924 -f 875//875 924//924 876//876 -f 876//876 924//924 868//868 -f 868//868 924//924 888//888 -f 868//868 888//888 869//869 -f 908//908 906//906 1045//1045 -f 1045//1045 1047//1047 908//908 -f 908//908 1047//1047 1049//1049 -f 908//908 1049//1049 901//901 -f 1049//1049 1051//1051 901//901 -f 901//901 1051//1051 1053//1053 -f 901//901 1053//1053 900//900 -f 1053//1053 1055//1055 900//900 -f 900//900 1055//1055 1057//1057 -f 900//900 1057//1057 899//899 -f 1057//1057 1059//1059 899//899 -f 899//899 1059//1059 1061//1061 -f 899//899 1061//1061 914//914 -f 1061//1061 1063//1063 914//914 -f 914//914 1063//1063 1065//1065 -f 914//914 1065//1065 915//915 -f 1065//1065 1067//1067 915//915 -f 915//915 1067//1067 1069//1069 -f 915//915 1069//1069 911//911 -f 1069//1069 1071//1071 911//911 -f 911//911 1071//1071 1073//1073 -f 911//911 1073//1073 918//918 -f 918//918 1073//1073 1075//1075 -f 918//918 1075//1075 919//919 -f 919//919 1075//1075 1076//1076 -f 919//919 1076//1076 920//920 -f 920//920 1076//1076 1005//1005 -f 920//920 1005//1005 902//902 -f 1005//1005 1008//1008 902//902 -f 902//902 1008//1008 1010//1010 -f 902//902 1010//1010 903//903 -f 1010//1010 1012//1012 903//903 -f 903//903 1012//1012 1014//1014 -f 903//903 1014//1014 904//904 -f 1014//1014 1016//1016 904//904 -f 904//904 1016//1016 1018//1018 -f 904//904 1018//1018 897//897 -f 1018//1018 1020//1020 897//897 -f 897//897 1020//1020 1022//1022 -f 897//897 1022//1022 898//898 -f 1022//1022 1024//1024 898//898 -f 898//898 1024//1024 1026//1026 -f 898//898 1026//1026 893//893 -f 1026//1026 1028//1028 893//893 -f 893//893 1028//1028 1030//1030 -f 893//893 1030//1030 894//894 -f 1030//1030 1032//1032 894//894 -f 894//894 1032//1032 1034//1034 -f 894//894 1034//1034 895//895 -f 1034//1034 1036//1036 895//895 -f 895//895 1036//1036 1038//1038 -f 895//895 1038//1038 905//905 -f 905//905 1038//1038 1040//1040 -f 905//905 1040//1040 906//906 -f 906//906 1040//1040 1043//1043 -f 906//906 1043//1043 1045//1045 -f 927//927 926//926 1117//1117 -f 1117//1117 1119//1119 927//927 -f 927//927 1119//1119 1121//1121 -f 927//927 1121//1121 925//925 -f 1121//1121 1123//1123 925//925 -f 925//925 1123//1123 1125//1125 -f 925//925 1125//1125 937//937 -f 1125//1125 1127//1127 937//937 -f 937//937 1127//1127 1129//1129 -f 937//937 1129//1129 938//938 -f 1129//1129 1131//1131 938//938 -f 938//938 1131//1131 1133//1133 -f 938//938 1133//1133 939//939 -f 1133//1133 1135//1135 939//939 -f 939//939 1135//1135 1137//1137 -f 939//939 1137//1137 940//940 -f 1137//1137 1139//1139 940//940 -f 940//940 1139//1139 1141//1141 -f 940//940 1141//1141 945//945 -f 1141//1141 1143//1143 945//945 -f 945//945 1143//1143 1145//1145 -f 945//945 1145//1145 946//946 -f 946//946 1145//1145 1147//1147 -f 946//946 1147//1147 947//947 -f 947//947 1147//1147 1148//1148 -f 947//947 1148//1148 930//930 -f 930//930 1148//1148 1111//1111 -f 930//930 1111//1111 931//931 -f 1111//1111 1109//1109 931//931 -f 931//931 1109//1109 1107//1107 -f 931//931 1107//1107 941//941 -f 1107//1107 1105//1105 941//941 -f 941//941 1105//1105 1103//1103 -f 941//941 1103//1103 942//942 -f 1103//1103 1101//1101 942//942 -f 942//942 1101//1101 1099//1099 -f 942//942 1099//1099 943//943 -f 1099//1099 1097//1097 943//943 -f 943//943 1097//1097 1095//1095 -f 943//943 1095//1095 933//933 -f 1095//1095 1093//1093 933//933 -f 933//933 1093//1093 1091//1091 -f 933//933 1091//1091 935//935 -f 1091//1091 1089//1089 935//935 -f 935//935 1089//1089 1087//1087 -f 935//935 1087//1087 921//921 -f 1087//1087 1085//1085 921//921 -f 921//921 1085//1085 1083//1083 -f 921//921 1083//1083 922//922 -f 1083//1083 1081//1081 922//922 -f 922//922 1081//1081 1079//1079 -f 922//922 1079//1079 923//923 -f 923//923 1079//1079 1078//1078 -f 923//923 1078//1078 926//926 -f 926//926 1078//1078 1115//1115 -f 926//926 1115//1115 1117//1117 -f 972//972 971//971 1144//1144 -f 1144//1144 1142//1142 972//972 -f 972//972 1142//1142 1140//1140 -f 972//972 1140//1140 977//977 -f 1140//1140 1138//1138 977//977 -f 977//977 1138//1138 1136//1136 -f 977//977 1136//1136 978//978 -f 1136//1136 1134//1134 978//978 -f 978//978 1134//1134 1132//1132 -f 978//978 1132//1132 979//979 -f 1132//1132 1130//1130 979//979 -f 979//979 1130//1130 1128//1128 -f 979//979 1128//1128 973//973 -f 1128//1128 1126//1126 973//973 -f 973//973 1126//1126 1124//1124 -f 973//973 1124//1124 974//974 -f 1124//1124 1122//1122 974//974 -f 974//974 1122//1122 1120//1120 -f 974//974 1120//1120 975//975 -f 1120//1120 1118//1118 975//975 -f 975//975 1118//1118 1116//1116 -f 975//975 1116//1116 976//976 -f 1116//1116 1114//1114 976//976 -f 976//976 1114//1114 1113//1113 -f 976//976 1113//1113 980//980 -f 980//980 1113//1113 1077//1077 -f 980//980 1077//1077 981//981 -f 1077//1077 1080//1080 981//981 -f 981//981 1080//1080 1082//1082 -f 981//981 1082//1082 982//982 -f 1082//1082 1084//1084 982//982 -f 982//982 1084//1084 1086//1086 -f 982//982 1086//1086 983//983 -f 1086//1086 1088//1088 983//983 -f 983//983 1088//1088 1090//1090 -f 983//983 1090//1090 984//984 -f 1090//1090 1092//1092 984//984 -f 984//984 1092//1092 1094//1094 -f 984//984 1094//1094 985//985 -f 1094//1094 1096//1096 985//985 -f 985//985 1096//1096 1098//1098 -f 985//985 1098//1098 986//986 -f 1098//1098 1100//1100 986//986 -f 986//986 1100//1100 1102//1102 -f 986//986 1102//1102 987//987 -f 1102//1102 1104//1104 987//987 -f 987//987 1104//1104 1106//1106 -f 987//987 1106//1106 988//988 -f 1106//1106 1108//1108 988//988 -f 988//988 1108//1108 1110//1110 -f 988//988 1110//1110 970//970 -f 970//970 1110//1110 1112//1112 -f 970//970 1112//1112 971//971 -f 971//971 1112//1112 1146//1146 -f 971//971 1146//1146 1144//1144 -f 954//954 953//953 1072//1072 -f 1072//1072 1070//1070 954//954 -f 954//954 1070//1070 1068//1068 -f 954//954 1068//1068 955//955 -f 1068//1068 1066//1066 955//955 -f 955//955 1066//1066 1064//1064 -f 955//955 1064//1064 949//949 -f 1064//1064 1062//1062 949//949 -f 949//949 1062//1062 1060//1060 -f 949//949 1060//1060 948//948 -f 1060//1060 1058//1058 948//948 -f 948//948 1058//1058 1056//1056 -f 948//948 1056//1056 964//964 -f 1056//1056 1054//1054 964//964 -f 964//964 1054//1054 1052//1052 -f 964//964 1052//1052 965//965 -f 1052//1052 1050//1050 965//965 -f 965//965 1050//1050 1048//1048 -f 965//965 1048//1048 966//966 -f 1048//1048 1046//1046 966//966 -f 966//966 1046//1046 1044//1044 -f 966//966 1044//1044 967//967 -f 967//967 1044//1044 1042//1042 -f 967//967 1042//1042 968//968 -f 968//968 1042//1042 1041//1041 -f 968//968 1041//1041 969//969 -f 969//969 1041//1041 1039//1039 -f 969//969 1039//1039 950//950 -f 1039//1039 1037//1037 950//950 -f 950//950 1037//1037 1035//1035 -f 950//950 1035//1035 951//951 -f 1035//1035 1033//1033 951//951 -f 951//951 1033//1033 1031//1031 -f 951//951 1031//1031 956//956 -f 1031//1031 1029//1029 956//956 -f 956//956 1029//1029 1027//1027 -f 956//956 1027//1027 957//957 -f 1027//1027 1025//1025 957//957 -f 957//957 1025//1025 1023//1023 -f 957//957 1023//1023 959//959 -f 1023//1023 1021//1021 959//959 -f 959//959 1021//1021 1019//1019 -f 959//959 1019//1019 960//960 -f 1019//1019 1017//1017 960//960 -f 960//960 1017//1017 1015//1015 -f 960//960 1015//1015 961//961 -f 1015//1015 1013//1013 961//961 -f 961//961 1013//1013 1011//1011 -f 961//961 1011//1011 962//962 -f 1011//1011 1009//1009 962//962 -f 962//962 1009//1009 1007//1007 -f 962//962 1007//1007 963//963 -f 963//963 1007//1007 1006//1006 -f 963//963 1006//1006 953//953 -f 953//953 1006//1006 1074//1074 -f 953//953 1074//1074 1072//1072 -f 1149//1149 1150//1150 1151//1151 -f 1152//1152 1153//1153 1154//1154 -f 1155//1155 1156//1156 1157//1157 -f 1158//1158 1159//1159 1160//1160 -f 1155//1155 1157//1157 1161//1161 -f 1162//1162 1163//1163 1164//1164 -f 1164//1164 1163//1163 1165//1165 -f 1164//1164 1165//1165 1166//1166 -f 1158//1158 1160//1160 1167//1167 -f 1167//1167 1160//1160 1168//1168 -f 1167//1167 1168//1168 1157//1157 -f 1157//1157 1168//1168 1169//1169 -f 1157//1157 1169//1169 1161//1161 -f 1170//1170 1171//1171 1172//1172 -f 1173//1173 1149//1149 1174//1174 -f 1174//1174 1149//1149 1151//1151 -f 1174//1174 1151//1151 1175//1175 -f 1175//1175 1151//1151 1176//1176 -f 1177//1177 1178//1178 1179//1179 -f 1180//1180 1181//1181 1182//1182 -f 1183//1183 1170//1170 1184//1184 -f 1184//1184 1170//1170 1172//1172 -f 1184//1184 1172//1172 1185//1185 -f 1186//1186 1187//1187 1188//1188 -f 1188//1188 1187//1187 1189//1189 -f 1190//1190 1179//1179 1191//1191 -f 1191//1191 1179//1179 1192//1192 -f 1193//1193 1194//1194 1195//1195 -f 1165//1165 1196//1196 1166//1166 -f 1166//1166 1196//1196 1197//1197 -f 1166//1166 1197//1197 1189//1189 -f 1189//1189 1197//1197 1198//1198 -f 1189//1189 1198//1198 1188//1188 -f 1199//1199 1200//1200 1201//1201 -f 1185//1185 1172//1172 1202//1202 -f 1202//1202 1172//1172 1203//1203 -f 1202//1202 1203//1203 1182//1182 -f 1182//1182 1203//1203 1204//1204 -f 1182//1182 1204//1204 1180//1180 -f 1180//1180 1204//1204 1205//1205 -f 1180//1180 1205//1205 1206//1206 -f 1159//1159 1158//1158 1207//1207 -f 1207//1207 1158//1158 1208//1208 -f 1207//1207 1208//1208 1209//1209 -f 1177//1177 1179//1179 1210//1210 -f 1210//1210 1179//1179 1190//1190 -f 1210//1210 1190//1190 1211//1211 -f 1212//1212 1213//1213 1214//1214 -f 1214//1214 1213//1213 1215//1215 -f 1216//1216 1217//1217 1201//1201 -f 1201//1201 1217//1217 1218//1218 -f 1201//1201 1218//1218 1199//1199 -f 1193//1193 1195//1195 1219//1219 -f 1190//1190 1220//1220 1211//1211 -f 1211//1211 1220//1220 1214//1214 -f 1211//1211 1214//1214 1221//1221 -f 1221//1221 1214//1214 1215//1215 -f 1222//1222 1223//1223 1224//1224 -f 1225//1225 1226//1226 1227//1227 -f 1227//1227 1226//1226 1228//1228 -f 1227//1227 1228//1228 1229//1229 -f 1229//1229 1228//1228 1230//1230 -f 1231//1231 1232//1232 1233//1233 -f 1234//1234 1235//1235 1236//1236 -f 1236//1236 1235//1235 1237//1237 -f 1238//1238 1239//1239 1240//1240 -f 1227//1227 1241//1241 1225//1225 -f 1225//1225 1241//1241 1236//1236 -f 1225//1225 1236//1236 1242//1242 -f 1242//1242 1236//1236 1237//1237 -f 1243//1243 1179//1179 1244//1244 -f 1216//1216 1201//1201 1245//1245 -f 1245//1245 1201//1201 1246//1246 -f 1245//1245 1246//1246 1233//1233 -f 1233//1233 1246//1246 1247//1247 -f 1233//1233 1247//1247 1231//1231 -f 1231//1231 1247//1247 1248//1248 -f 1231//1231 1248//1248 1249//1249 -f 1151//1151 1250//1250 1176//1176 -f 1176//1176 1250//1250 1222//1222 -f 1176//1176 1222//1222 1251//1251 -f 1251//1251 1222//1222 1224//1224 -f 1251//1251 1224//1224 1252//1252 -f 1195//1195 1253//1253 1254//1254 -f 1238//1238 1240//1240 1255//1255 -f 1256//1256 1257//1257 1258//1258 -f 1258//1258 1257//1257 1259//1259 -f 1260//1260 1261//1261 1262//1262 -f 1262//1262 1261//1261 1263//1263 -f 1262//1262 1263//1263 1264//1264 -f 1264//1264 1263//1263 1265//1265 -f 1264//1264 1265//1265 1266//1266 -f 1266//1266 1265//1265 1267//1267 -f 1266//1266 1267//1267 1268//1268 -f 1226//1226 1269//1269 1228//1228 -f 1228//1228 1269//1269 1270//1270 -f 1228//1228 1270//1270 1271//1271 -f 1271//1271 1270//1270 1253//1253 -f 1271//1271 1253//1253 1272//1272 -f 1272//1272 1253//1253 1195//1195 -f 1273//1273 1152//1152 1274//1274 -f 1274//1274 1152//1152 1154//1154 -f 1274//1274 1154//1154 1275//1275 -f 1275//1275 1154//1154 1276//1276 -f 1275//1275 1276//1276 1277//1277 -f 1277//1277 1276//1276 1219//1219 -f 1277//1277 1219//1219 1278//1278 -f 1278//1278 1219//1219 1195//1195 -f 1278//1278 1195//1195 1239//1239 -f 1239//1239 1195//1195 1254//1254 -f 1239//1239 1254//1254 1240//1240 -f 1279//1279 1280//1280 1207//1207 -f 1207//1207 1280//1280 1281//1281 -f 1207//1207 1281//1281 1159//1159 -f 1223//1223 1282//1282 1224//1224 -f 1224//1224 1282//1282 1283//1283 -f 1224//1224 1283//1283 1284//1284 -f 1285//1285 1286//1286 1224//1224 -f 1224//1224 1286//1286 1287//1287 -f 1224//1224 1287//1287 1288//1288 -f 1289//1289 1207//1207 1290//1290 -f 1290//1290 1207//1207 1291//1291 -f 1292//1292 1293//1293 1294//1294 -f 1294//1294 1293//1293 1295//1295 -f 1294//1294 1295//1295 1262//1262 -f 1262//1262 1295//1295 1296//1296 -f 1262//1262 1296//1296 1260//1260 -f 1260//1260 1296//1296 1297//1297 -f 1260//1260 1297//1297 1240//1240 -f 1240//1240 1297//1297 1298//1298 -f 1240//1240 1298//1298 1255//1255 -f 1178//1178 1299//1299 1300//1300 -f 1300//1300 1299//1299 1301//1301 -f 1178//1178 1300//1300 1179//1179 -f 1179//1179 1300//1300 1302//1302 -f 1179//1179 1302//1302 1244//1244 -f 1258//1258 1303//1303 1256//1256 -f 1256//1256 1303//1303 1304//1304 -f 1256//1256 1304//1304 1305//1305 -f 1305//1305 1304//1304 1306//1306 -f 1305//1305 1306//1306 1307//1307 -f 1289//1289 1308//1308 1207//1207 -f 1207//1207 1308//1308 1259//1259 -f 1207//1207 1259//1259 1309//1309 -f 1309//1309 1259//1259 1257//1257 -f 1284//1284 1310//1310 1224//1224 -f 1224//1224 1310//1310 1311//1311 -f 1224//1224 1311//1311 1268//1268 -f 1268//1268 1311//1311 1312//1312 -f 1268//1268 1312//1312 1313//1313 -f 1267//1267 1314//1314 1268//1268 -f 1268//1268 1314//1314 1315//1315 -f 1268//1268 1315//1315 1224//1224 -f 1224//1224 1315//1315 1316//1316 -f 1224//1224 1316//1316 1285//1285 -f 1181//1181 1180//1180 1287//1287 -f 1287//1287 1180//1180 1317//1317 -f 1287//1287 1317//1317 1288//1288 -f 1301//1301 1318//1318 1300//1300 -f 1300//1300 1318//1318 1319//1319 -f 1300//1300 1319//1319 1320//1320 -f 1320//1320 1319//1319 1321//1321 -f 1232//1232 1231//1231 1244//1244 -f 1244//1244 1231//1231 1322//1322 -f 1244//1244 1322//1322 1243//1243 -f 1198//1198 1323//1323 1188//1188 -f 1188//1188 1323//1323 1324//1324 -f 1188//1188 1324//1324 1325//1325 -f 1325//1325 1324//1324 1291//1291 -f 1325//1325 1291//1291 1326//1326 -f 1326//1326 1291//1291 1207//1207 -f 1327//1327 1309//1309 1328//1328 -f 1328//1328 1309//1309 1329//1329 -f 1328//1328 1329//1329 1330//1330 -f 1330//1330 1329//1329 1331//1331 -f 1330//1330 1331//1331 1313//1313 -f 1313//1313 1331//1331 1332//1332 -f 1313//1313 1332//1332 1268//1268 -f 1327//1327 1333//1333 1309//1309 -f 1309//1309 1333//1333 1334//1334 -f 1309//1309 1334//1334 1207//1207 -f 1207//1207 1334//1334 1335//1335 -f 1207//1207 1335//1335 1279//1279 -f 1307//1307 1320//1320 1305//1305 -f 1305//1305 1320//1320 1321//1321 -f 1305//1305 1321//1321 1336//1336 -f 1336//1336 1321//1321 1337//1337 -f 1336//1336 1337//1337 1292//1292 -f 1292//1292 1337//1337 1338//1338 -f 1292//1292 1338//1338 1293//1293 -f 1339//1339 1340//1340 1341//1341 -f 1342//1342 1343//1343 1344//1344 -f 1345//1345 1346//1346 1347//1347 -f 1342//1342 1344//1344 1348//1348 -f 1349//1349 1350//1350 1351//1351 -f 1352//1352 1353//1353 1354//1354 -f 1354//1354 1353//1353 1355//1355 -f 1345//1345 1347//1347 1356//1356 -f 1356//1356 1347//1347 1357//1357 -f 1356//1356 1357//1357 1344//1344 -f 1344//1344 1357//1357 1358//1358 -f 1344//1344 1358//1358 1348//1348 -f 1359//1359 1360//1360 1361//1361 -f 1362//1362 1349//1349 1363//1363 -f 1363//1363 1349//1349 1351//1351 -f 1363//1363 1351//1351 1364//1364 -f 1365//1365 1366//1366 1367//1367 -f 1368//1368 1369//1369 1370//1370 -f 1371//1371 1372//1372 1373//1373 -f 1355//1355 1374//1374 1354//1354 -f 1354//1354 1374//1374 1375//1375 -f 1354//1354 1375//1375 1376//1376 -f 1376//1376 1375//1375 1377//1377 -f 1376//1376 1377//1377 1378//1378 -f 1378//1378 1377//1377 1379//1379 -f 1378//1378 1379//1379 1380//1380 -f 1380//1380 1379//1379 1381//1381 -f 1382//1382 1383//1383 1384//1384 -f 1385//1385 1386//1386 1387//1387 -f 1387//1387 1386//1386 1388//1388 -f 1387//1387 1388//1388 1389//1389 -f 1364//1364 1351//1351 1390//1390 -f 1390//1390 1351//1351 1391//1391 -f 1390//1390 1391//1391 1370//1370 -f 1370//1370 1391//1391 1392//1392 -f 1370//1370 1392//1392 1368//1368 -f 1368//1368 1392//1392 1393//1393 -f 1368//1368 1393//1393 1394//1394 -f 1382//1382 1384//1384 1395//1395 -f 1396//1396 1397//1397 1398//1398 -f 1399//1399 1400//1400 1401//1401 -f 1365//1365 1367//1367 1402//1402 -f 1361//1361 1339//1339 1359//1359 -f 1359//1359 1339//1339 1341//1341 -f 1359//1359 1341//1341 1403//1403 -f 1403//1403 1341//1341 1395//1395 -f 1403//1403 1395//1395 1404//1404 -f 1404//1404 1395//1395 1384//1384 -f 1404//1404 1384//1384 1405//1405 -f 1405//1405 1384//1384 1406//1406 -f 1407//1407 1408//1408 1409//1409 -f 1409//1409 1408//1408 1410//1410 -f 1411//1411 1412//1412 1401//1401 -f 1401//1401 1412//1412 1413//1413 -f 1401//1401 1413//1413 1399//1399 -f 1414//1414 1371//1371 1415//1415 -f 1415//1415 1371//1371 1373//1373 -f 1415//1415 1373//1373 1416//1416 -f 1416//1416 1373//1373 1417//1417 -f 1373//1373 1418//1418 1417//1417 -f 1417//1417 1418//1418 1407//1407 -f 1417//1417 1407//1407 1419//1419 -f 1419//1419 1407//1407 1409//1409 -f 1419//1419 1409//1409 1420//1420 -f 1421//1421 1422//1422 1423//1423 -f 1423//1423 1422//1422 1424//1424 -f 1388//1388 1425//1425 1389//1389 -f 1389//1389 1425//1425 1426//1426 -f 1389//1389 1426//1426 1424//1424 -f 1424//1424 1426//1426 1427//1427 -f 1424//1424 1427//1427 1423//1423 -f 1428//1428 1429//1429 1430//1430 -f 1346//1346 1345//1345 1431//1431 -f 1431//1431 1345//1345 1432//1432 -f 1431//1431 1432//1432 1433//1433 -f 1411//1411 1401//1401 1434//1434 -f 1434//1434 1401//1401 1435//1435 -f 1434//1434 1435//1435 1436//1436 -f 1436//1436 1435//1435 1437//1437 -f 1436//1436 1437//1437 1438//1438 -f 1438//1438 1437//1437 1439//1439 -f 1438//1438 1439//1439 1440//1440 -f 1441//1441 1442//1442 1443//1443 -f 1444//1444 1445//1445 1446//1446 -f 1446//1446 1445//1445 1447//1447 -f 1367//1367 1448//1448 1449//1449 -f 1428//1428 1430//1430 1450//1450 -f 1410//1410 1451//1451 1452//1452 -f 1452//1452 1451//1451 1453//1453 -f 1410//1410 1452//1452 1409//1409 -f 1409//1409 1452//1452 1454//1454 -f 1409//1409 1454//1454 1455//1455 -f 1456//1456 1409//1409 1457//1457 -f 1457//1457 1409//1409 1455//1455 -f 1457//1457 1455//1455 1438//1438 -f 1438//1438 1455//1455 1458//1458 -f 1438//1438 1458//1458 1436//1436 -f 1459//1459 1460//1460 1384//1384 -f 1427//1427 1461//1461 1423//1423 -f 1423//1423 1461//1461 1462//1462 -f 1423//1423 1462//1462 1463//1463 -f 1463//1463 1462//1462 1448//1448 -f 1463//1463 1448//1448 1464//1464 -f 1464//1464 1448//1448 1367//1367 -f 1465//1465 1396//1396 1466//1466 -f 1466//1466 1396//1396 1398//1398 -f 1466//1466 1398//1398 1467//1467 -f 1467//1467 1398//1398 1468//1468 -f 1467//1467 1468//1468 1469//1469 -f 1469//1469 1468//1468 1402//1402 -f 1469//1469 1402//1402 1470//1470 -f 1470//1470 1402//1402 1367//1367 -f 1470//1470 1367//1367 1429//1429 -f 1429//1429 1367//1367 1449//1449 -f 1429//1429 1449//1449 1430//1430 -f 1471//1471 1472//1472 1431//1431 -f 1431//1431 1472//1472 1473//1473 -f 1431//1431 1473//1473 1346//1346 -f 1474//1474 1443//1443 1475//1475 -f 1475//1475 1443//1443 1442//1442 -f 1475//1475 1442//1442 1476//1476 -f 1476//1476 1442//1442 1452//1452 -f 1476//1476 1452//1452 1477//1477 -f 1477//1477 1452//1452 1453//1453 -f 1446//1446 1478//1478 1444//1444 -f 1444//1444 1478//1478 1479//1479 -f 1444//1444 1479//1479 1443//1443 -f 1443//1443 1479//1479 1480//1480 -f 1443//1443 1480//1480 1441//1441 -f 1481//1481 1431//1431 1482//1482 -f 1482//1482 1431//1431 1483//1483 -f 1459//1459 1384//1384 1484//1484 -f 1460//1460 1485//1485 1384//1384 -f 1384//1384 1485//1485 1486//1486 -f 1384//1384 1486//1486 1487//1487 -f 1488//1488 1489//1489 1490//1490 -f 1490//1490 1489//1489 1491//1491 -f 1490//1490 1491//1491 1492//1492 -f 1492//1492 1491//1491 1493//1493 -f 1492//1492 1493//1493 1494//1494 -f 1494//1494 1493//1493 1495//1495 -f 1494//1494 1495//1495 1496//1496 -f 1496//1496 1495//1495 1497//1497 -f 1475//1475 1498//1498 1474//1474 -f 1474//1474 1498//1498 1499//1499 -f 1474//1474 1499//1499 1500//1500 -f 1500//1500 1499//1499 1501//1501 -f 1500//1500 1501//1501 1502//1502 -f 1502//1502 1501//1501 1503//1503 -f 1502//1502 1503//1503 1490//1490 -f 1490//1490 1503//1503 1504//1504 -f 1490//1490 1504//1504 1488//1488 -f 1488//1488 1504//1504 1505//1505 -f 1488//1488 1505//1505 1430//1430 -f 1430//1430 1505//1505 1506//1506 -f 1430//1430 1506//1506 1450//1450 -f 1481//1481 1507//1507 1431//1431 -f 1431//1431 1507//1507 1447//1447 -f 1431//1431 1447//1447 1508//1508 -f 1508//1508 1447//1447 1445//1445 -f 1383//1383 1509//1509 1384//1384 -f 1384//1384 1509//1509 1510//1510 -f 1384//1384 1510//1510 1511//1511 -f 1377//1377 1512//1512 1379//1379 -f 1379//1379 1512//1512 1513//1513 -f 1379//1379 1513//1513 1514//1514 -f 1514//1514 1513//1513 1483//1483 -f 1514//1514 1483//1483 1515//1515 -f 1515//1515 1483//1483 1431//1431 -f 1369//1369 1368//1368 1486//1486 -f 1486//1486 1368//1368 1516//1516 -f 1486//1486 1516//1516 1487//1487 -f 1517//1517 1518//1518 1508//1508 -f 1518//1518 1519//1519 1508//1508 -f 1508//1508 1519//1519 1520//1520 -f 1508//1508 1520//1520 1431//1431 -f 1431//1431 1520//1520 1521//1521 -f 1431//1431 1521//1521 1471//1471 -f 1511//1511 1522//1522 1384//1384 -f 1384//1384 1522//1522 1496//1496 -f 1384//1384 1496//1496 1484//1484 -f 1484//1484 1496//1496 1497//1497 -f 1522//1522 1523//1523 1496//1496 -f 1496//1496 1523//1523 1524//1524 -f 1496//1496 1524//1524 1525//1525 -f 1525//1525 1524//1524 1526//1526 -f 1525//1525 1526//1526 1527//1527 -f 1527//1527 1526//1526 1517//1517 -f 1527//1527 1517//1517 1528//1528 -f 1528//1528 1517//1517 1508//1508 -f 1213//1213 1212//1212 1396//1396 -f 1396//1396 1212//1212 1397//1397 -f 1213//1213 1396//1396 1465//1465 -f 1213//1213 1465//1465 1215//1215 -f 1215//1215 1465//1465 1466//1466 -f 1215//1215 1466//1466 1221//1221 -f 1221//1221 1466//1466 1467//1467 -f 1221//1221 1467//1467 1211//1211 -f 1210//1210 1211//1211 1469//1469 -f 1469//1469 1211//1211 1467//1467 -f 1210//1210 1469//1469 1177//1177 -f 1177//1177 1469//1469 1470//1470 -f 1177//1177 1470//1470 1178//1178 -f 1178//1178 1470//1470 1429//1429 -f 1178//1178 1429//1429 1299//1299 -f 1299//1299 1429//1429 1428//1428 -f 1301//1301 1299//1299 1450//1450 -f 1450//1450 1299//1299 1428//1428 -f 1301//1301 1450//1450 1318//1318 -f 1318//1318 1450//1450 1506//1506 -f 1318//1318 1506//1506 1319//1319 -f 1319//1319 1506//1506 1505//1505 -f 1321//1321 1319//1319 1504//1504 -f 1504//1504 1319//1319 1505//1505 -f 1321//1321 1504//1504 1337//1337 -f 1337//1337 1504//1504 1503//1503 -f 1337//1337 1503//1503 1338//1338 -f 1338//1338 1503//1503 1501//1501 -f 1293//1293 1338//1338 1499//1499 -f 1499//1499 1338//1338 1501//1501 -f 1293//1293 1499//1499 1295//1295 -f 1295//1295 1499//1499 1498//1498 -f 1295//1295 1498//1498 1296//1296 -f 1296//1296 1498//1498 1475//1475 -f 1297//1297 1296//1296 1476//1476 -f 1476//1476 1296//1296 1475//1475 -f 1297//1297 1476//1476 1298//1298 -f 1298//1298 1476//1476 1477//1477 -f 1298//1298 1477//1477 1255//1255 -f 1255//1255 1477//1477 1453//1453 -f 1238//1238 1255//1255 1451//1451 -f 1451//1451 1255//1255 1453//1453 -f 1238//1238 1451//1451 1239//1239 -f 1239//1239 1451//1451 1410//1410 -f 1239//1239 1410//1410 1278//1278 -f 1278//1278 1410//1410 1408//1408 -f 1278//1278 1408//1408 1277//1277 -f 1277//1277 1408//1408 1407//1407 -f 1275//1275 1277//1277 1418//1418 -f 1418//1418 1277//1277 1407//1407 -f 1275//1275 1418//1418 1373//1373 -f 1275//1275 1373//1373 1274//1274 -f 1274//1274 1373//1373 1372//1372 -f 1274//1274 1372//1372 1273//1273 -f 1273//1273 1372//1372 1371//1371 -f 1273//1273 1371//1371 1152//1152 -f 1153//1153 1152//1152 1414//1414 -f 1414//1414 1152//1152 1371//1371 -f 1154//1154 1153//1153 1415//1415 -f 1415//1415 1153//1153 1414//1414 -f 1154//1154 1415//1415 1276//1276 -f 1276//1276 1415//1415 1416//1416 -f 1276//1276 1416//1416 1219//1219 -f 1219//1219 1416//1416 1417//1417 -f 1219//1219 1417//1417 1193//1193 -f 1193//1193 1417//1417 1419//1419 -f 1194//1194 1193//1193 1420//1420 -f 1420//1420 1193//1193 1419//1419 -f 1195//1195 1194//1194 1409//1409 -f 1409//1409 1194//1194 1420//1420 -f 1195//1195 1409//1409 1456//1456 -f 1195//1195 1456//1456 1272//1272 -f 1272//1272 1456//1456 1457//1457 -f 1272//1272 1457//1457 1271//1271 -f 1271//1271 1457//1457 1438//1438 -f 1271//1271 1438//1438 1228//1228 -f 1230//1230 1228//1228 1440//1440 -f 1440//1440 1228//1228 1438//1438 -f 1229//1229 1230//1230 1439//1439 -f 1439//1439 1230//1230 1440//1440 -f 1229//1229 1439//1439 1227//1227 -f 1227//1227 1439//1439 1437//1437 -f 1227//1227 1437//1437 1241//1241 -f 1241//1241 1437//1437 1435//1435 -f 1241//1241 1435//1435 1236//1236 -f 1236//1236 1435//1435 1401//1401 -f 1234//1234 1236//1236 1400//1400 -f 1400//1400 1236//1236 1401//1401 -f 1235//1235 1234//1234 1399//1399 -f 1399//1399 1234//1234 1400//1400 -f 1235//1235 1399//1399 1413//1413 -f 1235//1235 1413//1413 1237//1237 -f 1237//1237 1413//1413 1412//1412 -f 1237//1237 1412//1412 1242//1242 -f 1242//1242 1412//1412 1411//1411 -f 1242//1242 1411//1411 1225//1225 -f 1226//1226 1225//1225 1434//1434 -f 1434//1434 1225//1225 1411//1411 -f 1226//1226 1434//1434 1269//1269 -f 1269//1269 1434//1434 1436//1436 -f 1269//1269 1436//1436 1270//1270 -f 1270//1270 1436//1436 1458//1458 -f 1270//1270 1458//1458 1253//1253 -f 1253//1253 1458//1458 1455//1455 -f 1254//1254 1253//1253 1454//1454 -f 1454//1454 1253//1253 1455//1455 -f 1254//1254 1454//1454 1240//1240 -f 1240//1240 1454//1454 1452//1452 -f 1240//1240 1452//1452 1260//1260 -f 1260//1260 1452//1452 1442//1442 -f 1261//1261 1260//1260 1441//1441 -f 1441//1441 1260//1260 1442//1442 -f 1261//1261 1441//1441 1263//1263 -f 1263//1263 1441//1441 1480//1480 -f 1263//1263 1480//1480 1265//1265 -f 1265//1265 1480//1480 1479//1479 -f 1267//1267 1265//1265 1478//1478 -f 1478//1478 1265//1265 1479//1479 -f 1267//1267 1478//1478 1314//1314 -f 1314//1314 1478//1478 1446//1446 -f 1314//1314 1446//1446 1315//1315 -f 1315//1315 1446//1446 1447//1447 -f 1316//1316 1315//1315 1507//1507 -f 1507//1507 1315//1315 1447//1447 -f 1316//1316 1507//1507 1285//1285 -f 1285//1285 1507//1507 1481//1481 -f 1285//1285 1481//1481 1286//1286 -f 1286//1286 1481//1481 1482//1482 -f 1287//1287 1286//1286 1483//1483 -f 1483//1483 1286//1286 1482//1482 -f 1287//1287 1483//1483 1181//1181 -f 1181//1181 1483//1483 1513//1513 -f 1181//1181 1513//1513 1182//1182 -f 1182//1182 1513//1513 1512//1512 -f 1182//1182 1512//1512 1202//1202 -f 1202//1202 1512//1512 1377//1377 -f 1185//1185 1202//1202 1375//1375 -f 1375//1375 1202//1202 1377//1377 -f 1185//1185 1375//1375 1374//1374 -f 1185//1185 1374//1374 1184//1184 -f 1184//1184 1374//1374 1355//1355 -f 1184//1184 1355//1355 1183//1183 -f 1183//1183 1355//1355 1353//1353 -f 1183//1183 1353//1353 1170//1170 -f 1171//1171 1170//1170 1352//1352 -f 1352//1352 1170//1170 1353//1353 -f 1172//1172 1171//1171 1354//1354 -f 1354//1354 1171//1171 1352//1352 -f 1172//1172 1354//1354 1203//1203 -f 1203//1203 1354//1354 1376//1376 -f 1203//1203 1376//1376 1204//1204 -f 1204//1204 1376//1376 1378//1378 -f 1204//1204 1378//1378 1205//1205 -f 1205//1205 1378//1378 1380//1380 -f 1206//1206 1205//1205 1381//1381 -f 1381//1381 1205//1205 1380//1380 -f 1180//1180 1206//1206 1379//1379 -f 1379//1379 1206//1206 1381//1381 -f 1180//1180 1379//1379 1514//1514 -f 1180//1180 1514//1514 1317//1317 -f 1317//1317 1514//1514 1515//1515 -f 1317//1317 1515//1515 1288//1288 -f 1288//1288 1515//1515 1431//1431 -f 1288//1288 1431//1431 1224//1224 -f 1252//1252 1224//1224 1433//1433 -f 1433//1433 1224//1224 1431//1431 -f 1251//1251 1252//1252 1432//1432 -f 1432//1432 1252//1252 1433//1433 -f 1251//1251 1432//1432 1176//1176 -f 1176//1176 1432//1432 1345//1345 -f 1176//1176 1345//1345 1175//1175 -f 1175//1175 1345//1345 1356//1356 -f 1175//1175 1356//1356 1174//1174 -f 1174//1174 1356//1356 1344//1344 -f 1173//1173 1174//1174 1343//1343 -f 1343//1343 1174//1174 1344//1344 -f 1149//1149 1173//1173 1342//1342 -f 1342//1342 1173//1173 1343//1343 -f 1149//1149 1342//1342 1348//1348 -f 1149//1149 1348//1348 1150//1150 -f 1150//1150 1348//1348 1358//1358 -f 1150//1150 1358//1358 1151//1151 -f 1151//1151 1358//1358 1357//1357 -f 1151//1151 1357//1357 1250//1250 -f 1222//1222 1250//1250 1347//1347 -f 1347//1347 1250//1250 1357//1357 -f 1222//1222 1347//1347 1223//1223 -f 1223//1223 1347//1347 1346//1346 -f 1223//1223 1346//1346 1282//1282 -f 1282//1282 1346//1346 1473//1473 -f 1282//1282 1473//1473 1283//1283 -f 1283//1283 1473//1473 1472//1472 -f 1284//1284 1283//1283 1471//1471 -f 1471//1471 1283//1283 1472//1472 -f 1284//1284 1471//1471 1310//1310 -f 1310//1310 1471//1471 1521//1521 -f 1310//1310 1521//1521 1311//1311 -f 1311//1311 1521//1521 1520//1520 -f 1312//1312 1311//1311 1519//1519 -f 1519//1519 1311//1311 1520//1520 -f 1312//1312 1519//1519 1313//1313 -f 1313//1313 1519//1519 1518//1518 -f 1313//1313 1518//1518 1330//1330 -f 1330//1330 1518//1518 1517//1517 -f 1328//1328 1330//1330 1526//1526 -f 1526//1526 1330//1330 1517//1517 -f 1328//1328 1526//1526 1327//1327 -f 1327//1327 1526//1526 1524//1524 -f 1327//1327 1524//1524 1333//1333 -f 1333//1333 1524//1524 1523//1523 -f 1334//1334 1333//1333 1522//1522 -f 1522//1522 1333//1333 1523//1523 -f 1334//1334 1522//1522 1335//1335 -f 1335//1335 1522//1522 1511//1511 -f 1335//1335 1511//1511 1279//1279 -f 1279//1279 1511//1511 1510//1510 -f 1280//1280 1279//1279 1509//1509 -f 1509//1509 1279//1279 1510//1510 -f 1280//1280 1509//1509 1281//1281 -f 1281//1281 1509//1509 1383//1383 -f 1281//1281 1383//1383 1159//1159 -f 1159//1159 1383//1383 1382//1382 -f 1159//1159 1382//1382 1160//1160 -f 1160//1160 1382//1382 1395//1395 -f 1168//1168 1160//1160 1341//1341 -f 1341//1341 1160//1160 1395//1395 -f 1168//1168 1341//1341 1340//1340 -f 1168//1168 1340//1340 1169//1169 -f 1169//1169 1340//1340 1339//1339 -f 1169//1169 1339//1339 1161//1161 -f 1161//1161 1339//1339 1361//1361 -f 1161//1161 1361//1361 1155//1155 -f 1156//1156 1155//1155 1360//1360 -f 1360//1360 1155//1155 1361//1361 -f 1157//1157 1156//1156 1359//1359 -f 1359//1359 1156//1156 1360//1360 -f 1157//1157 1359//1359 1167//1167 -f 1167//1167 1359//1359 1403//1403 -f 1167//1167 1403//1403 1158//1158 -f 1158//1158 1403//1403 1404//1404 -f 1158//1158 1404//1404 1208//1208 -f 1208//1208 1404//1404 1405//1405 -f 1209//1209 1208//1208 1406//1406 -f 1406//1406 1208//1208 1405//1405 -f 1207//1207 1209//1209 1384//1384 -f 1384//1384 1209//1209 1406//1406 -f 1207//1207 1384//1384 1487//1487 -f 1207//1207 1487//1487 1326//1326 -f 1326//1326 1487//1487 1516//1516 -f 1326//1326 1516//1516 1325//1325 -f 1325//1325 1516//1516 1368//1368 -f 1325//1325 1368//1368 1188//1188 -f 1186//1186 1188//1188 1394//1394 -f 1394//1394 1188//1188 1368//1368 -f 1187//1187 1186//1186 1393//1393 -f 1393//1393 1186//1186 1394//1394 -f 1187//1187 1393//1393 1189//1189 -f 1189//1189 1393//1393 1392//1392 -f 1189//1189 1392//1392 1166//1166 -f 1166//1166 1392//1392 1391//1391 -f 1166//1166 1391//1391 1164//1164 -f 1164//1164 1391//1391 1351//1351 -f 1162//1162 1164//1164 1350//1350 -f 1350//1350 1164//1164 1351//1351 -f 1163//1163 1162//1162 1349//1349 -f 1349//1349 1162//1162 1350//1350 -f 1163//1163 1349//1349 1362//1362 -f 1163//1163 1362//1362 1165//1165 -f 1165//1165 1362//1362 1363//1363 -f 1165//1165 1363//1363 1196//1196 -f 1196//1196 1363//1363 1364//1364 -f 1196//1196 1364//1364 1197//1197 -f 1198//1198 1197//1197 1390//1390 -f 1390//1390 1197//1197 1364//1364 -f 1198//1198 1390//1390 1323//1323 -f 1323//1323 1390//1390 1370//1370 -f 1323//1323 1370//1370 1324//1324 -f 1324//1324 1370//1370 1369//1369 -f 1324//1324 1369//1369 1291//1291 -f 1291//1291 1369//1369 1486//1486 -f 1290//1290 1291//1291 1485//1485 -f 1485//1485 1291//1291 1486//1486 -f 1290//1290 1485//1485 1289//1289 -f 1289//1289 1485//1485 1460//1460 -f 1289//1289 1460//1460 1308//1308 -f 1308//1308 1460//1460 1459//1459 -f 1259//1259 1308//1308 1484//1484 -f 1484//1484 1308//1308 1459//1459 -f 1259//1259 1484//1484 1258//1258 -f 1258//1258 1484//1484 1497//1497 -f 1258//1258 1497//1497 1303//1303 -f 1303//1303 1497//1497 1495//1495 -f 1304//1304 1303//1303 1493//1493 -f 1493//1493 1303//1303 1495//1495 -f 1304//1304 1493//1493 1306//1306 -f 1306//1306 1493//1493 1491//1491 -f 1306//1306 1491//1491 1307//1307 -f 1307//1307 1491//1491 1489//1489 -f 1320//1320 1307//1307 1488//1488 -f 1488//1488 1307//1307 1489//1489 -f 1320//1320 1488//1488 1300//1300 -f 1300//1300 1488//1488 1430//1430 -f 1300//1300 1430//1430 1302//1302 -f 1302//1302 1430//1430 1449//1449 -f 1244//1244 1302//1302 1448//1448 -f 1448//1448 1302//1302 1449//1449 -f 1244//1244 1448//1448 1232//1232 -f 1232//1232 1448//1448 1462//1462 -f 1232//1232 1462//1462 1233//1233 -f 1233//1233 1462//1462 1461//1461 -f 1233//1233 1461//1461 1245//1245 -f 1245//1245 1461//1461 1427//1427 -f 1216//1216 1245//1245 1426//1426 -f 1426//1426 1245//1245 1427//1427 -f 1216//1216 1426//1426 1425//1425 -f 1216//1216 1425//1425 1217//1217 -f 1217//1217 1425//1425 1388//1388 -f 1217//1217 1388//1388 1218//1218 -f 1218//1218 1388//1388 1386//1386 -f 1218//1218 1386//1386 1199//1199 -f 1200//1200 1199//1199 1385//1385 -f 1385//1385 1199//1199 1386//1386 -f 1201//1201 1200//1200 1387//1387 -f 1387//1387 1200//1200 1385//1385 -f 1201//1201 1387//1387 1246//1246 -f 1246//1246 1387//1387 1389//1389 -f 1246//1246 1389//1389 1247//1247 -f 1247//1247 1389//1389 1424//1424 -f 1247//1247 1424//1424 1248//1248 -f 1248//1248 1424//1424 1422//1422 -f 1249//1249 1248//1248 1421//1421 -f 1421//1421 1248//1248 1422//1422 -f 1231//1231 1249//1249 1423//1423 -f 1423//1423 1249//1249 1421//1421 -f 1231//1231 1423//1423 1463//1463 -f 1231//1231 1463//1463 1322//1322 -f 1322//1322 1463//1463 1464//1464 -f 1322//1322 1464//1464 1243//1243 -f 1243//1243 1464//1464 1367//1367 -f 1243//1243 1367//1367 1179//1179 -f 1192//1192 1179//1179 1366//1366 -f 1366//1366 1179//1179 1367//1367 -f 1191//1191 1192//1192 1365//1365 -f 1365//1365 1192//1192 1366//1366 -f 1191//1191 1365//1365 1190//1190 -f 1190//1190 1365//1365 1402//1402 -f 1190//1190 1402//1402 1220//1220 -f 1220//1220 1402//1402 1468//1468 -f 1220//1220 1468//1468 1214//1214 -f 1214//1214 1468//1468 1398//1398 -f 1212//1212 1214//1214 1397//1397 -f 1397//1397 1214//1214 1398//1398 -f 1292//1292 1500//1500 1336//1336 -f 1336//1336 1500//1500 1502//1502 -f 1336//1336 1502//1502 1305//1305 -f 1305//1305 1502//1502 1490//1490 -f 1305//1305 1490//1490 1256//1256 -f 1256//1256 1490//1490 1492//1492 -f 1256//1256 1492//1492 1257//1257 -f 1257//1257 1492//1492 1494//1494 -f 1257//1257 1494//1494 1309//1309 -f 1309//1309 1494//1494 1496//1496 -f 1309//1309 1496//1496 1329//1329 -f 1329//1329 1496//1496 1525//1525 -f 1329//1329 1525//1525 1331//1331 -f 1331//1331 1525//1525 1527//1527 -f 1331//1331 1527//1527 1332//1332 -f 1332//1332 1527//1527 1528//1528 -f 1332//1332 1528//1528 1268//1268 -f 1268//1268 1528//1528 1508//1508 -f 1268//1268 1508//1508 1266//1266 -f 1266//1266 1508//1508 1445//1445 -f 1266//1266 1445//1445 1264//1264 -f 1264//1264 1445//1445 1444//1444 -f 1264//1264 1444//1444 1262//1262 -f 1262//1262 1444//1444 1443//1443 -f 1262//1262 1443//1443 1294//1294 -f 1294//1294 1443//1443 1474//1474 -f 1294//1294 1474//1474 1292//1292 -f 1292//1292 1474//1474 1500//1500 -f 1529//1529 1530//1530 1531//1531 -f 1532//1532 1533//1533 1534//1534 -f 1535//1535 1536//1536 1537//1537 -f 1538//1538 1539//1539 1540//1540 -f 1535//1535 1537//1537 1541//1541 -f 1542//1542 1543//1543 1544//1544 -f 1544//1544 1543//1543 1545//1545 -f 1544//1544 1545//1545 1546//1546 -f 1538//1538 1540//1540 1547//1547 -f 1547//1547 1540//1540 1548//1548 -f 1547//1547 1548//1548 1537//1537 -f 1537//1537 1548//1548 1549//1549 -f 1537//1537 1549//1549 1541//1541 -f 1550//1550 1551//1551 1552//1552 -f 1553//1553 1529//1529 1554//1554 -f 1554//1554 1529//1529 1531//1531 -f 1554//1554 1531//1531 1555//1555 -f 1555//1555 1531//1531 1556//1556 -f 1557//1557 1558//1558 1559//1559 -f 1560//1560 1561//1561 1562//1562 -f 1563//1563 1550//1550 1564//1564 -f 1564//1564 1550//1550 1552//1552 -f 1564//1564 1552//1552 1565//1565 -f 1566//1566 1567//1567 1568//1568 -f 1568//1568 1567//1567 1569//1569 -f 1570//1570 1559//1559 1571//1571 -f 1571//1571 1559//1559 1572//1572 -f 1573//1573 1574//1574 1575//1575 -f 1545//1545 1576//1576 1546//1546 -f 1546//1546 1576//1576 1577//1577 -f 1546//1546 1577//1577 1569//1569 -f 1569//1569 1577//1577 1578//1578 -f 1569//1569 1578//1578 1568//1568 -f 1579//1579 1580//1580 1581//1581 -f 1565//1565 1552//1552 1582//1582 -f 1582//1582 1552//1552 1583//1583 -f 1582//1582 1583//1583 1562//1562 -f 1562//1562 1583//1583 1584//1584 -f 1562//1562 1584//1584 1560//1560 -f 1560//1560 1584//1584 1585//1585 -f 1560//1560 1585//1585 1586//1586 -f 1539//1539 1538//1538 1587//1587 -f 1587//1587 1538//1538 1588//1588 -f 1587//1587 1588//1588 1589//1589 -f 1557//1557 1559//1559 1590//1590 -f 1590//1590 1559//1559 1570//1570 -f 1590//1590 1570//1570 1591//1591 -f 1592//1592 1593//1593 1594//1594 -f 1594//1594 1593//1593 1595//1595 -f 1596//1596 1597//1597 1581//1581 -f 1581//1581 1597//1597 1598//1598 -f 1581//1581 1598//1598 1579//1579 -f 1573//1573 1575//1575 1599//1599 -f 1570//1570 1600//1600 1591//1591 -f 1591//1591 1600//1600 1594//1594 -f 1591//1591 1594//1594 1601//1601 -f 1601//1601 1594//1594 1595//1595 -f 1602//1602 1603//1603 1604//1604 -f 1605//1605 1606//1606 1607//1607 -f 1607//1607 1606//1606 1608//1608 -f 1607//1607 1608//1608 1609//1609 -f 1609//1609 1608//1608 1610//1610 -f 1611//1611 1612//1612 1613//1613 -f 1614//1614 1615//1615 1616//1616 -f 1616//1616 1615//1615 1617//1617 -f 1618//1618 1619//1619 1620//1620 -f 1607//1607 1621//1621 1605//1605 -f 1605//1605 1621//1621 1616//1616 -f 1605//1605 1616//1616 1622//1622 -f 1622//1622 1616//1616 1617//1617 -f 1623//1623 1559//1559 1624//1624 -f 1596//1596 1581//1581 1625//1625 -f 1625//1625 1581//1581 1626//1626 -f 1625//1625 1626//1626 1613//1613 -f 1613//1613 1626//1626 1627//1627 -f 1613//1613 1627//1627 1611//1611 -f 1611//1611 1627//1627 1628//1628 -f 1611//1611 1628//1628 1629//1629 -f 1531//1531 1630//1630 1556//1556 -f 1556//1556 1630//1630 1602//1602 -f 1556//1556 1602//1602 1631//1631 -f 1631//1631 1602//1602 1604//1604 -f 1631//1631 1604//1604 1632//1632 -f 1575//1575 1633//1633 1634//1634 -f 1618//1618 1620//1620 1635//1635 -f 1636//1636 1637//1637 1638//1638 -f 1638//1638 1637//1637 1639//1639 -f 1640//1640 1641//1641 1642//1642 -f 1642//1642 1641//1641 1643//1643 -f 1642//1642 1643//1643 1644//1644 -f 1644//1644 1643//1643 1645//1645 -f 1644//1644 1645//1645 1646//1646 -f 1646//1646 1645//1645 1647//1647 -f 1646//1646 1647//1647 1648//1648 -f 1606//1606 1649//1649 1608//1608 -f 1608//1608 1649//1649 1650//1650 -f 1608//1608 1650//1650 1651//1651 -f 1651//1651 1650//1650 1633//1633 -f 1651//1651 1633//1633 1652//1652 -f 1652//1652 1633//1633 1575//1575 -f 1653//1653 1532//1532 1654//1654 -f 1654//1654 1532//1532 1534//1534 -f 1654//1654 1534//1534 1655//1655 -f 1655//1655 1534//1534 1656//1656 -f 1655//1655 1656//1656 1657//1657 -f 1657//1657 1656//1656 1599//1599 -f 1657//1657 1599//1599 1658//1658 -f 1658//1658 1599//1599 1575//1575 -f 1658//1658 1575//1575 1619//1619 -f 1619//1619 1575//1575 1634//1634 -f 1619//1619 1634//1634 1620//1620 -f 1659//1659 1660//1660 1587//1587 -f 1587//1587 1660//1660 1661//1661 -f 1587//1587 1661//1661 1539//1539 -f 1603//1603 1662//1662 1604//1604 -f 1604//1604 1662//1662 1663//1663 -f 1604//1604 1663//1663 1664//1664 -f 1665//1665 1666//1666 1604//1604 -f 1604//1604 1666//1666 1667//1667 -f 1604//1604 1667//1667 1668//1668 -f 1669//1669 1587//1587 1670//1670 -f 1670//1670 1587//1587 1671//1671 -f 1672//1672 1673//1673 1674//1674 -f 1674//1674 1673//1673 1675//1675 -f 1674//1674 1675//1675 1642//1642 -f 1642//1642 1675//1675 1676//1676 -f 1642//1642 1676//1676 1640//1640 -f 1640//1640 1676//1676 1677//1677 -f 1640//1640 1677//1677 1620//1620 -f 1620//1620 1677//1677 1678//1678 -f 1620//1620 1678//1678 1635//1635 -f 1558//1558 1679//1679 1680//1680 -f 1680//1680 1679//1679 1681//1681 -f 1558//1558 1680//1680 1559//1559 -f 1559//1559 1680//1680 1682//1682 -f 1559//1559 1682//1682 1624//1624 -f 1638//1638 1683//1683 1636//1636 -f 1636//1636 1683//1683 1684//1684 -f 1636//1636 1684//1684 1685//1685 -f 1685//1685 1684//1684 1686//1686 -f 1685//1685 1686//1686 1687//1687 -f 1669//1669 1688//1688 1587//1587 -f 1587//1587 1688//1688 1639//1639 -f 1587//1587 1639//1639 1689//1689 -f 1689//1689 1639//1639 1637//1637 -f 1664//1664 1690//1690 1604//1604 -f 1604//1604 1690//1690 1691//1691 -f 1604//1604 1691//1691 1648//1648 -f 1648//1648 1691//1691 1692//1692 -f 1648//1648 1692//1692 1693//1693 -f 1647//1647 1694//1694 1648//1648 -f 1648//1648 1694//1694 1695//1695 -f 1648//1648 1695//1695 1604//1604 -f 1604//1604 1695//1695 1696//1696 -f 1604//1604 1696//1696 1665//1665 -f 1561//1561 1560//1560 1667//1667 -f 1667//1667 1560//1560 1697//1697 -f 1667//1667 1697//1697 1668//1668 -f 1681//1681 1698//1698 1680//1680 -f 1680//1680 1698//1698 1699//1699 -f 1680//1680 1699//1699 1700//1700 -f 1700//1700 1699//1699 1701//1701 -f 1612//1612 1611//1611 1624//1624 -f 1624//1624 1611//1611 1702//1702 -f 1624//1624 1702//1702 1623//1623 -f 1578//1578 1703//1703 1568//1568 -f 1568//1568 1703//1703 1704//1704 -f 1568//1568 1704//1704 1705//1705 -f 1705//1705 1704//1704 1671//1671 -f 1705//1705 1671//1671 1706//1706 -f 1706//1706 1671//1671 1587//1587 -f 1707//1707 1689//1689 1708//1708 -f 1708//1708 1689//1689 1709//1709 -f 1708//1708 1709//1709 1710//1710 -f 1710//1710 1709//1709 1711//1711 -f 1710//1710 1711//1711 1693//1693 -f 1693//1693 1711//1711 1712//1712 -f 1693//1693 1712//1712 1648//1648 -f 1707//1707 1713//1713 1689//1689 -f 1689//1689 1713//1713 1714//1714 -f 1689//1689 1714//1714 1587//1587 -f 1587//1587 1714//1714 1715//1715 -f 1587//1587 1715//1715 1659//1659 -f 1687//1687 1700//1700 1685//1685 -f 1685//1685 1700//1700 1701//1701 -f 1685//1685 1701//1701 1716//1716 -f 1716//1716 1701//1701 1717//1717 -f 1716//1716 1717//1717 1672//1672 -f 1672//1672 1717//1717 1718//1718 -f 1672//1672 1718//1718 1673//1673 -f 1719//1719 1720//1720 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1725//1725 1726//1726 1727//1727 -f 1722//1722 1724//1724 1728//1728 -f 1729//1729 1730//1730 1731//1731 -f 1732//1732 1733//1733 1734//1734 -f 1734//1734 1733//1733 1735//1735 -f 1725//1725 1727//1727 1736//1736 -f 1736//1736 1727//1727 1737//1737 -f 1736//1736 1737//1737 1724//1724 -f 1724//1724 1737//1737 1738//1738 -f 1724//1724 1738//1738 1728//1728 -f 1739//1739 1740//1740 1741//1741 -f 1742//1742 1729//1729 1743//1743 -f 1743//1743 1729//1729 1731//1731 -f 1743//1743 1731//1731 1744//1744 -f 1745//1745 1746//1746 1747//1747 -f 1748//1748 1749//1749 1750//1750 -f 1751//1751 1752//1752 1753//1753 -f 1735//1735 1754//1754 1734//1734 -f 1734//1734 1754//1754 1755//1755 -f 1734//1734 1755//1755 1756//1756 -f 1756//1756 1755//1755 1757//1757 -f 1756//1756 1757//1757 1758//1758 -f 1758//1758 1757//1757 1759//1759 -f 1758//1758 1759//1759 1760//1760 -f 1760//1760 1759//1759 1761//1761 -f 1762//1762 1763//1763 1764//1764 -f 1765//1765 1766//1766 1767//1767 -f 1767//1767 1766//1766 1768//1768 -f 1767//1767 1768//1768 1769//1769 -f 1744//1744 1731//1731 1770//1770 -f 1770//1770 1731//1731 1771//1771 -f 1770//1770 1771//1771 1750//1750 -f 1750//1750 1771//1771 1772//1772 -f 1750//1750 1772//1772 1748//1748 -f 1748//1748 1772//1772 1773//1773 -f 1748//1748 1773//1773 1774//1774 -f 1762//1762 1764//1764 1775//1775 -f 1776//1776 1777//1777 1778//1778 -f 1779//1779 1780//1780 1781//1781 -f 1745//1745 1747//1747 1782//1782 -f 1741//1741 1719//1719 1739//1739 -f 1739//1739 1719//1719 1721//1721 -f 1739//1739 1721//1721 1783//1783 -f 1783//1783 1721//1721 1775//1775 -f 1783//1783 1775//1775 1784//1784 -f 1784//1784 1775//1775 1764//1764 -f 1784//1784 1764//1764 1785//1785 -f 1785//1785 1764//1764 1786//1786 -f 1787//1787 1788//1788 1789//1789 -f 1789//1789 1788//1788 1790//1790 -f 1791//1791 1792//1792 1781//1781 -f 1781//1781 1792//1792 1793//1793 -f 1781//1781 1793//1793 1779//1779 -f 1794//1794 1751//1751 1795//1795 -f 1795//1795 1751//1751 1753//1753 -f 1795//1795 1753//1753 1796//1796 -f 1796//1796 1753//1753 1797//1797 -f 1753//1753 1798//1798 1797//1797 -f 1797//1797 1798//1798 1787//1787 -f 1797//1797 1787//1787 1799//1799 -f 1799//1799 1787//1787 1789//1789 -f 1799//1799 1789//1789 1800//1800 -f 1801//1801 1802//1802 1803//1803 -f 1803//1803 1802//1802 1804//1804 -f 1768//1768 1805//1805 1769//1769 -f 1769//1769 1805//1805 1806//1806 -f 1769//1769 1806//1806 1804//1804 -f 1804//1804 1806//1806 1807//1807 -f 1804//1804 1807//1807 1803//1803 -f 1808//1808 1809//1809 1810//1810 -f 1726//1726 1725//1725 1811//1811 -f 1811//1811 1725//1725 1812//1812 -f 1811//1811 1812//1812 1813//1813 -f 1791//1791 1781//1781 1814//1814 -f 1814//1814 1781//1781 1815//1815 -f 1814//1814 1815//1815 1816//1816 -f 1816//1816 1815//1815 1817//1817 -f 1816//1816 1817//1817 1818//1818 -f 1818//1818 1817//1817 1819//1819 -f 1818//1818 1819//1819 1820//1820 -f 1821//1821 1822//1822 1823//1823 -f 1824//1824 1825//1825 1826//1826 -f 1826//1826 1825//1825 1827//1827 -f 1747//1747 1828//1828 1829//1829 -f 1808//1808 1810//1810 1830//1830 -f 1790//1790 1831//1831 1832//1832 -f 1832//1832 1831//1831 1833//1833 -f 1790//1790 1832//1832 1789//1789 -f 1789//1789 1832//1832 1834//1834 -f 1789//1789 1834//1834 1835//1835 -f 1836//1836 1789//1789 1837//1837 -f 1837//1837 1789//1789 1835//1835 -f 1837//1837 1835//1835 1818//1818 -f 1818//1818 1835//1835 1838//1838 -f 1818//1818 1838//1838 1816//1816 -f 1839//1839 1840//1840 1764//1764 -f 1807//1807 1841//1841 1803//1803 -f 1803//1803 1841//1841 1842//1842 -f 1803//1803 1842//1842 1843//1843 -f 1843//1843 1842//1842 1828//1828 -f 1843//1843 1828//1828 1844//1844 -f 1844//1844 1828//1828 1747//1747 -f 1845//1845 1776//1776 1846//1846 -f 1846//1846 1776//1776 1778//1778 -f 1846//1846 1778//1778 1847//1847 -f 1847//1847 1778//1778 1848//1848 -f 1847//1847 1848//1848 1849//1849 -f 1849//1849 1848//1848 1782//1782 -f 1849//1849 1782//1782 1850//1850 -f 1850//1850 1782//1782 1747//1747 -f 1850//1850 1747//1747 1809//1809 -f 1809//1809 1747//1747 1829//1829 -f 1809//1809 1829//1829 1810//1810 -f 1851//1851 1852//1852 1811//1811 -f 1811//1811 1852//1852 1853//1853 -f 1811//1811 1853//1853 1726//1726 -f 1854//1854 1823//1823 1855//1855 -f 1855//1855 1823//1823 1822//1822 -f 1855//1855 1822//1822 1856//1856 -f 1856//1856 1822//1822 1832//1832 -f 1856//1856 1832//1832 1857//1857 -f 1857//1857 1832//1832 1833//1833 -f 1826//1826 1858//1858 1824//1824 -f 1824//1824 1858//1858 1859//1859 -f 1824//1824 1859//1859 1823//1823 -f 1823//1823 1859//1859 1860//1860 -f 1823//1823 1860//1860 1821//1821 -f 1861//1861 1811//1811 1862//1862 -f 1862//1862 1811//1811 1863//1863 -f 1839//1839 1764//1764 1864//1864 -f 1840//1840 1865//1865 1764//1764 -f 1764//1764 1865//1865 1866//1866 -f 1764//1764 1866//1866 1867//1867 -f 1868//1868 1869//1869 1870//1870 -f 1870//1870 1869//1869 1871//1871 -f 1870//1870 1871//1871 1872//1872 -f 1872//1872 1871//1871 1873//1873 -f 1872//1872 1873//1873 1874//1874 -f 1874//1874 1873//1873 1875//1875 -f 1874//1874 1875//1875 1876//1876 -f 1876//1876 1875//1875 1877//1877 -f 1855//1855 1878//1878 1854//1854 -f 1854//1854 1878//1878 1879//1879 -f 1854//1854 1879//1879 1880//1880 -f 1880//1880 1879//1879 1881//1881 -f 1880//1880 1881//1881 1882//1882 -f 1882//1882 1881//1881 1883//1883 -f 1882//1882 1883//1883 1870//1870 -f 1870//1870 1883//1883 1884//1884 -f 1870//1870 1884//1884 1868//1868 -f 1868//1868 1884//1884 1885//1885 -f 1868//1868 1885//1885 1810//1810 -f 1810//1810 1885//1885 1886//1886 -f 1810//1810 1886//1886 1830//1830 -f 1861//1861 1887//1887 1811//1811 -f 1811//1811 1887//1887 1827//1827 -f 1811//1811 1827//1827 1888//1888 -f 1888//1888 1827//1827 1825//1825 -f 1763//1763 1889//1889 1764//1764 -f 1764//1764 1889//1889 1890//1890 -f 1764//1764 1890//1890 1891//1891 -f 1757//1757 1892//1892 1759//1759 -f 1759//1759 1892//1892 1893//1893 -f 1759//1759 1893//1893 1894//1894 -f 1894//1894 1893//1893 1863//1863 -f 1894//1894 1863//1863 1895//1895 -f 1895//1895 1863//1863 1811//1811 -f 1749//1749 1748//1748 1866//1866 -f 1866//1866 1748//1748 1896//1896 -f 1866//1866 1896//1896 1867//1867 -f 1897//1897 1898//1898 1888//1888 -f 1898//1898 1899//1899 1888//1888 -f 1888//1888 1899//1899 1900//1900 -f 1888//1888 1900//1900 1811//1811 -f 1811//1811 1900//1900 1901//1901 -f 1811//1811 1901//1901 1851//1851 -f 1891//1891 1902//1902 1764//1764 -f 1764//1764 1902//1902 1876//1876 -f 1764//1764 1876//1876 1864//1864 -f 1864//1864 1876//1876 1877//1877 -f 1902//1902 1903//1903 1876//1876 -f 1876//1876 1903//1903 1904//1904 -f 1876//1876 1904//1904 1905//1905 -f 1905//1905 1904//1904 1906//1906 -f 1905//1905 1906//1906 1907//1907 -f 1907//1907 1906//1906 1897//1897 -f 1907//1907 1897//1897 1908//1908 -f 1908//1908 1897//1897 1888//1888 -f 1593//1593 1592//1592 1776//1776 -f 1776//1776 1592//1592 1777//1777 -f 1593//1593 1776//1776 1845//1845 -f 1593//1593 1845//1845 1595//1595 -f 1595//1595 1845//1845 1846//1846 -f 1595//1595 1846//1846 1601//1601 -f 1601//1601 1846//1846 1847//1847 -f 1601//1601 1847//1847 1591//1591 -f 1590//1590 1591//1591 1849//1849 -f 1849//1849 1591//1591 1847//1847 -f 1590//1590 1849//1849 1557//1557 -f 1557//1557 1849//1849 1850//1850 -f 1557//1557 1850//1850 1558//1558 -f 1558//1558 1850//1850 1809//1809 -f 1558//1558 1809//1809 1679//1679 -f 1679//1679 1809//1809 1808//1808 -f 1681//1681 1679//1679 1830//1830 -f 1830//1830 1679//1679 1808//1808 -f 1681//1681 1830//1830 1698//1698 -f 1698//1698 1830//1830 1886//1886 -f 1698//1698 1886//1886 1699//1699 -f 1699//1699 1886//1886 1885//1885 -f 1701//1701 1699//1699 1884//1884 -f 1884//1884 1699//1699 1885//1885 -f 1701//1701 1884//1884 1717//1717 -f 1717//1717 1884//1884 1883//1883 -f 1717//1717 1883//1883 1718//1718 -f 1718//1718 1883//1883 1881//1881 -f 1673//1673 1718//1718 1879//1879 -f 1879//1879 1718//1718 1881//1881 -f 1673//1673 1879//1879 1675//1675 -f 1675//1675 1879//1879 1878//1878 -f 1675//1675 1878//1878 1676//1676 -f 1676//1676 1878//1878 1855//1855 -f 1677//1677 1676//1676 1856//1856 -f 1856//1856 1676//1676 1855//1855 -f 1677//1677 1856//1856 1678//1678 -f 1678//1678 1856//1856 1857//1857 -f 1678//1678 1857//1857 1635//1635 -f 1635//1635 1857//1857 1833//1833 -f 1618//1618 1635//1635 1831//1831 -f 1831//1831 1635//1635 1833//1833 -f 1618//1618 1831//1831 1619//1619 -f 1619//1619 1831//1831 1790//1790 -f 1619//1619 1790//1790 1658//1658 -f 1658//1658 1790//1790 1788//1788 -f 1658//1658 1788//1788 1657//1657 -f 1657//1657 1788//1788 1787//1787 -f 1655//1655 1657//1657 1798//1798 -f 1798//1798 1657//1657 1787//1787 -f 1655//1655 1798//1798 1753//1753 -f 1655//1655 1753//1753 1654//1654 -f 1654//1654 1753//1753 1752//1752 -f 1654//1654 1752//1752 1653//1653 -f 1653//1653 1752//1752 1751//1751 -f 1653//1653 1751//1751 1532//1532 -f 1533//1533 1532//1532 1794//1794 -f 1794//1794 1532//1532 1751//1751 -f 1534//1534 1533//1533 1795//1795 -f 1795//1795 1533//1533 1794//1794 -f 1534//1534 1795//1795 1656//1656 -f 1656//1656 1795//1795 1796//1796 -f 1656//1656 1796//1796 1599//1599 -f 1599//1599 1796//1796 1797//1797 -f 1599//1599 1797//1797 1573//1573 -f 1573//1573 1797//1797 1799//1799 -f 1574//1574 1573//1573 1800//1800 -f 1800//1800 1573//1573 1799//1799 -f 1575//1575 1574//1574 1789//1789 -f 1789//1789 1574//1574 1800//1800 -f 1575//1575 1789//1789 1836//1836 -f 1575//1575 1836//1836 1652//1652 -f 1652//1652 1836//1836 1837//1837 -f 1652//1652 1837//1837 1651//1651 -f 1651//1651 1837//1837 1818//1818 -f 1651//1651 1818//1818 1608//1608 -f 1610//1610 1608//1608 1820//1820 -f 1820//1820 1608//1608 1818//1818 -f 1609//1609 1610//1610 1819//1819 -f 1819//1819 1610//1610 1820//1820 -f 1609//1609 1819//1819 1607//1607 -f 1607//1607 1819//1819 1817//1817 -f 1607//1607 1817//1817 1621//1621 -f 1621//1621 1817//1817 1815//1815 -f 1621//1621 1815//1815 1616//1616 -f 1616//1616 1815//1815 1781//1781 -f 1614//1614 1616//1616 1780//1780 -f 1780//1780 1616//1616 1781//1781 -f 1615//1615 1614//1614 1779//1779 -f 1779//1779 1614//1614 1780//1780 -f 1615//1615 1779//1779 1793//1793 -f 1615//1615 1793//1793 1617//1617 -f 1617//1617 1793//1793 1792//1792 -f 1617//1617 1792//1792 1622//1622 -f 1622//1622 1792//1792 1791//1791 -f 1622//1622 1791//1791 1605//1605 -f 1606//1606 1605//1605 1814//1814 -f 1814//1814 1605//1605 1791//1791 -f 1606//1606 1814//1814 1649//1649 -f 1649//1649 1814//1814 1816//1816 -f 1649//1649 1816//1816 1650//1650 -f 1650//1650 1816//1816 1838//1838 -f 1650//1650 1838//1838 1633//1633 -f 1633//1633 1838//1838 1835//1835 -f 1634//1634 1633//1633 1834//1834 -f 1834//1834 1633//1633 1835//1835 -f 1634//1634 1834//1834 1620//1620 -f 1620//1620 1834//1834 1832//1832 -f 1620//1620 1832//1832 1640//1640 -f 1640//1640 1832//1832 1822//1822 -f 1641//1641 1640//1640 1821//1821 -f 1821//1821 1640//1640 1822//1822 -f 1641//1641 1821//1821 1643//1643 -f 1643//1643 1821//1821 1860//1860 -f 1643//1643 1860//1860 1645//1645 -f 1645//1645 1860//1860 1859//1859 -f 1647//1647 1645//1645 1858//1858 -f 1858//1858 1645//1645 1859//1859 -f 1647//1647 1858//1858 1694//1694 -f 1694//1694 1858//1858 1826//1826 -f 1694//1694 1826//1826 1695//1695 -f 1695//1695 1826//1826 1827//1827 -f 1696//1696 1695//1695 1887//1887 -f 1887//1887 1695//1695 1827//1827 -f 1696//1696 1887//1887 1665//1665 -f 1665//1665 1887//1887 1861//1861 -f 1665//1665 1861//1861 1666//1666 -f 1666//1666 1861//1861 1862//1862 -f 1667//1667 1666//1666 1863//1863 -f 1863//1863 1666//1666 1862//1862 -f 1667//1667 1863//1863 1561//1561 -f 1561//1561 1863//1863 1893//1893 -f 1561//1561 1893//1893 1562//1562 -f 1562//1562 1893//1893 1892//1892 -f 1562//1562 1892//1892 1582//1582 -f 1582//1582 1892//1892 1757//1757 -f 1565//1565 1582//1582 1755//1755 -f 1755//1755 1582//1582 1757//1757 -f 1565//1565 1755//1755 1754//1754 -f 1565//1565 1754//1754 1564//1564 -f 1564//1564 1754//1754 1735//1735 -f 1564//1564 1735//1735 1563//1563 -f 1563//1563 1735//1735 1733//1733 -f 1563//1563 1733//1733 1550//1550 -f 1551//1551 1550//1550 1732//1732 -f 1732//1732 1550//1550 1733//1733 -f 1552//1552 1551//1551 1734//1734 -f 1734//1734 1551//1551 1732//1732 -f 1552//1552 1734//1734 1583//1583 -f 1583//1583 1734//1734 1756//1756 -f 1583//1583 1756//1756 1584//1584 -f 1584//1584 1756//1756 1758//1758 -f 1584//1584 1758//1758 1585//1585 -f 1585//1585 1758//1758 1760//1760 -f 1586//1586 1585//1585 1761//1761 -f 1761//1761 1585//1585 1760//1760 -f 1560//1560 1586//1586 1759//1759 -f 1759//1759 1586//1586 1761//1761 -f 1560//1560 1759//1759 1894//1894 -f 1560//1560 1894//1894 1697//1697 -f 1697//1697 1894//1894 1895//1895 -f 1697//1697 1895//1895 1668//1668 -f 1668//1668 1895//1895 1811//1811 -f 1668//1668 1811//1811 1604//1604 -f 1632//1632 1604//1604 1813//1813 -f 1813//1813 1604//1604 1811//1811 -f 1631//1631 1632//1632 1812//1812 -f 1812//1812 1632//1632 1813//1813 -f 1631//1631 1812//1812 1556//1556 -f 1556//1556 1812//1812 1725//1725 -f 1556//1556 1725//1725 1555//1555 -f 1555//1555 1725//1725 1736//1736 -f 1555//1555 1736//1736 1554//1554 -f 1554//1554 1736//1736 1724//1724 -f 1553//1553 1554//1554 1723//1723 -f 1723//1723 1554//1554 1724//1724 -f 1529//1529 1553//1553 1722//1722 -f 1722//1722 1553//1553 1723//1723 -f 1529//1529 1722//1722 1728//1728 -f 1529//1529 1728//1728 1530//1530 -f 1530//1530 1728//1728 1738//1738 -f 1530//1530 1738//1738 1531//1531 -f 1531//1531 1738//1738 1737//1737 -f 1531//1531 1737//1737 1630//1630 -f 1602//1602 1630//1630 1727//1727 -f 1727//1727 1630//1630 1737//1737 -f 1602//1602 1727//1727 1603//1603 -f 1603//1603 1727//1727 1726//1726 -f 1603//1603 1726//1726 1662//1662 -f 1662//1662 1726//1726 1853//1853 -f 1662//1662 1853//1853 1663//1663 -f 1663//1663 1853//1853 1852//1852 -f 1664//1664 1663//1663 1851//1851 -f 1851//1851 1663//1663 1852//1852 -f 1664//1664 1851//1851 1690//1690 -f 1690//1690 1851//1851 1901//1901 -f 1690//1690 1901//1901 1691//1691 -f 1691//1691 1901//1901 1900//1900 -f 1692//1692 1691//1691 1899//1899 -f 1899//1899 1691//1691 1900//1900 -f 1692//1692 1899//1899 1693//1693 -f 1693//1693 1899//1899 1898//1898 -f 1693//1693 1898//1898 1710//1710 -f 1710//1710 1898//1898 1897//1897 -f 1708//1708 1710//1710 1906//1906 -f 1906//1906 1710//1710 1897//1897 -f 1708//1708 1906//1906 1707//1707 -f 1707//1707 1906//1906 1904//1904 -f 1707//1707 1904//1904 1713//1713 -f 1713//1713 1904//1904 1903//1903 -f 1714//1714 1713//1713 1902//1902 -f 1902//1902 1713//1713 1903//1903 -f 1714//1714 1902//1902 1715//1715 -f 1715//1715 1902//1902 1891//1891 -f 1715//1715 1891//1891 1659//1659 -f 1659//1659 1891//1891 1890//1890 -f 1660//1660 1659//1659 1889//1889 -f 1889//1889 1659//1659 1890//1890 -f 1660//1660 1889//1889 1661//1661 -f 1661//1661 1889//1889 1763//1763 -f 1661//1661 1763//1763 1539//1539 -f 1539//1539 1763//1763 1762//1762 -f 1539//1539 1762//1762 1540//1540 -f 1540//1540 1762//1762 1775//1775 -f 1548//1548 1540//1540 1721//1721 -f 1721//1721 1540//1540 1775//1775 -f 1548//1548 1721//1721 1720//1720 -f 1548//1548 1720//1720 1549//1549 -f 1549//1549 1720//1720 1719//1719 -f 1549//1549 1719//1719 1541//1541 -f 1541//1541 1719//1719 1741//1741 -f 1541//1541 1741//1741 1535//1535 -f 1536//1536 1535//1535 1740//1740 -f 1740//1740 1535//1535 1741//1741 -f 1537//1537 1536//1536 1739//1739 -f 1739//1739 1536//1536 1740//1740 -f 1537//1537 1739//1739 1547//1547 -f 1547//1547 1739//1739 1783//1783 -f 1547//1547 1783//1783 1538//1538 -f 1538//1538 1783//1783 1784//1784 -f 1538//1538 1784//1784 1588//1588 -f 1588//1588 1784//1784 1785//1785 -f 1589//1589 1588//1588 1786//1786 -f 1786//1786 1588//1588 1785//1785 -f 1587//1587 1589//1589 1764//1764 -f 1764//1764 1589//1589 1786//1786 -f 1587//1587 1764//1764 1867//1867 -f 1587//1587 1867//1867 1706//1706 -f 1706//1706 1867//1867 1896//1896 -f 1706//1706 1896//1896 1705//1705 -f 1705//1705 1896//1896 1748//1748 -f 1705//1705 1748//1748 1568//1568 -f 1566//1566 1568//1568 1774//1774 -f 1774//1774 1568//1568 1748//1748 -f 1567//1567 1566//1566 1773//1773 -f 1773//1773 1566//1566 1774//1774 -f 1567//1567 1773//1773 1569//1569 -f 1569//1569 1773//1773 1772//1772 -f 1569//1569 1772//1772 1546//1546 -f 1546//1546 1772//1772 1771//1771 -f 1546//1546 1771//1771 1544//1544 -f 1544//1544 1771//1771 1731//1731 -f 1542//1542 1544//1544 1730//1730 -f 1730//1730 1544//1544 1731//1731 -f 1543//1543 1542//1542 1729//1729 -f 1729//1729 1542//1542 1730//1730 -f 1543//1543 1729//1729 1742//1742 -f 1543//1543 1742//1742 1545//1545 -f 1545//1545 1742//1742 1743//1743 -f 1545//1545 1743//1743 1576//1576 -f 1576//1576 1743//1743 1744//1744 -f 1576//1576 1744//1744 1577//1577 -f 1578//1578 1577//1577 1770//1770 -f 1770//1770 1577//1577 1744//1744 -f 1578//1578 1770//1770 1703//1703 -f 1703//1703 1770//1770 1750//1750 -f 1703//1703 1750//1750 1704//1704 -f 1704//1704 1750//1750 1749//1749 -f 1704//1704 1749//1749 1671//1671 -f 1671//1671 1749//1749 1866//1866 -f 1670//1670 1671//1671 1865//1865 -f 1865//1865 1671//1671 1866//1866 -f 1670//1670 1865//1865 1669//1669 -f 1669//1669 1865//1865 1840//1840 -f 1669//1669 1840//1840 1688//1688 -f 1688//1688 1840//1840 1839//1839 -f 1639//1639 1688//1688 1864//1864 -f 1864//1864 1688//1688 1839//1839 -f 1639//1639 1864//1864 1638//1638 -f 1638//1638 1864//1864 1877//1877 -f 1638//1638 1877//1877 1683//1683 -f 1683//1683 1877//1877 1875//1875 -f 1684//1684 1683//1683 1873//1873 -f 1873//1873 1683//1683 1875//1875 -f 1684//1684 1873//1873 1686//1686 -f 1686//1686 1873//1873 1871//1871 -f 1686//1686 1871//1871 1687//1687 -f 1687//1687 1871//1871 1869//1869 -f 1700//1700 1687//1687 1868//1868 -f 1868//1868 1687//1687 1869//1869 -f 1700//1700 1868//1868 1680//1680 -f 1680//1680 1868//1868 1810//1810 -f 1680//1680 1810//1810 1682//1682 -f 1682//1682 1810//1810 1829//1829 -f 1624//1624 1682//1682 1828//1828 -f 1828//1828 1682//1682 1829//1829 -f 1624//1624 1828//1828 1612//1612 -f 1612//1612 1828//1828 1842//1842 -f 1612//1612 1842//1842 1613//1613 -f 1613//1613 1842//1842 1841//1841 -f 1613//1613 1841//1841 1625//1625 -f 1625//1625 1841//1841 1807//1807 -f 1596//1596 1625//1625 1806//1806 -f 1806//1806 1625//1625 1807//1807 -f 1596//1596 1806//1806 1805//1805 -f 1596//1596 1805//1805 1597//1597 -f 1597//1597 1805//1805 1768//1768 -f 1597//1597 1768//1768 1598//1598 -f 1598//1598 1768//1768 1766//1766 -f 1598//1598 1766//1766 1579//1579 -f 1580//1580 1579//1579 1765//1765 -f 1765//1765 1579//1579 1766//1766 -f 1581//1581 1580//1580 1767//1767 -f 1767//1767 1580//1580 1765//1765 -f 1581//1581 1767//1767 1626//1626 -f 1626//1626 1767//1767 1769//1769 -f 1626//1626 1769//1769 1627//1627 -f 1627//1627 1769//1769 1804//1804 -f 1627//1627 1804//1804 1628//1628 -f 1628//1628 1804//1804 1802//1802 -f 1629//1629 1628//1628 1801//1801 -f 1801//1801 1628//1628 1802//1802 -f 1611//1611 1629//1629 1803//1803 -f 1803//1803 1629//1629 1801//1801 -f 1611//1611 1803//1803 1843//1843 -f 1611//1611 1843//1843 1702//1702 -f 1702//1702 1843//1843 1844//1844 -f 1702//1702 1844//1844 1623//1623 -f 1623//1623 1844//1844 1747//1747 -f 1623//1623 1747//1747 1559//1559 -f 1572//1572 1559//1559 1746//1746 -f 1746//1746 1559//1559 1747//1747 -f 1571//1571 1572//1572 1745//1745 -f 1745//1745 1572//1572 1746//1746 -f 1571//1571 1745//1745 1570//1570 -f 1570//1570 1745//1745 1782//1782 -f 1570//1570 1782//1782 1600//1600 -f 1600//1600 1782//1782 1848//1848 -f 1600//1600 1848//1848 1594//1594 -f 1594//1594 1848//1848 1778//1778 -f 1592//1592 1594//1594 1777//1777 -f 1777//1777 1594//1594 1778//1778 -f 1672//1672 1880//1880 1716//1716 -f 1716//1716 1880//1880 1882//1882 -f 1716//1716 1882//1882 1685//1685 -f 1685//1685 1882//1882 1870//1870 -f 1685//1685 1870//1870 1636//1636 -f 1636//1636 1870//1870 1872//1872 -f 1636//1636 1872//1872 1637//1637 -f 1637//1637 1872//1872 1874//1874 -f 1637//1637 1874//1874 1689//1689 -f 1689//1689 1874//1874 1876//1876 -f 1689//1689 1876//1876 1709//1709 -f 1709//1709 1876//1876 1905//1905 -f 1709//1709 1905//1905 1711//1711 -f 1711//1711 1905//1905 1907//1907 -f 1711//1711 1907//1907 1712//1712 -f 1712//1712 1907//1907 1908//1908 -f 1712//1712 1908//1908 1648//1648 -f 1648//1648 1908//1908 1888//1888 -f 1648//1648 1888//1888 1646//1646 -f 1646//1646 1888//1888 1825//1825 -f 1646//1646 1825//1825 1644//1644 -f 1644//1644 1825//1825 1824//1824 -f 1644//1644 1824//1824 1642//1642 -f 1642//1642 1824//1824 1823//1823 -f 1642//1642 1823//1823 1674//1674 -f 1674//1674 1823//1823 1854//1854 -f 1674//1674 1854//1854 1672//1672 -f 1672//1672 1854//1854 1880//1880 -f 1909//1909 1910//1910 1911//1911 -f 1912//1912 1913//1913 1914//1914 -f 1915//1915 1916//1916 1917//1917 -f 1917//1917 1916//1916 1918//1918 -f 1917//1917 1918//1918 1919//1919 -f 1920//1920 1921//1921 1922//1922 -f 1922//1922 1921//1921 1923//1923 -f 1922//1922 1923//1923 1924//1924 -f 1925//1925 1926//1926 1927//1927 -f 1928//1928 1929//1929 1930//1930 -f 1931//1931 1909//1909 1932//1932 -f 1932//1932 1909//1909 1911//1911 -f 1932//1932 1911//1911 1933//1933 -f 1933//1933 1911//1911 1934//1934 -f 1935//1935 1936//1936 1937//1937 -f 1938//1938 1939//1939 1940//1940 -f 1941//1941 1925//1925 1942//1942 -f 1942//1942 1925//1925 1927//1927 -f 1942//1942 1927//1927 1943//1943 -f 1944//1944 1945//1945 1946//1946 -f 1946//1946 1945//1945 1947//1947 -f 1948//1948 1937//1937 1949//1949 -f 1949//1949 1937//1937 1950//1950 -f 1951//1951 1952//1952 1953//1953 -f 1918//1918 1954//1954 1919//1919 -f 1919//1919 1954//1954 1955//1955 -f 1919//1919 1955//1955 1947//1947 -f 1947//1947 1955//1955 1956//1956 -f 1947//1947 1956//1956 1946//1946 -f 1957//1957 1958//1958 1959//1959 -f 1943//1943 1927//1927 1960//1960 -f 1960//1960 1927//1927 1961//1961 -f 1960//1960 1961//1961 1940//1940 -f 1940//1940 1961//1961 1962//1962 -f 1940//1940 1962//1962 1938//1938 -f 1938//1938 1962//1962 1963//1963 -f 1938//1938 1963//1963 1964//1964 -f 1928//1928 1930//1930 1965//1965 -f 1935//1935 1937//1937 1966//1966 -f 1966//1966 1937//1937 1948//1948 -f 1966//1966 1948//1948 1967//1967 -f 1968//1968 1969//1969 1970//1970 -f 1970//1970 1969//1969 1971//1971 -f 1972//1972 1973//1973 1959//1959 -f 1959//1959 1973//1973 1974//1974 -f 1959//1959 1974//1974 1957//1957 -f 1975//1975 1976//1976 1977//1977 -f 1951//1951 1953//1953 1978//1978 -f 1948//1948 1979//1979 1967//1967 -f 1967//1967 1979//1979 1970//1970 -f 1967//1967 1970//1970 1980//1980 -f 1980//1980 1970//1970 1971//1971 -f 1981//1981 1982//1982 1983//1983 -f 1984//1984 1985//1985 1986//1986 -f 1987//1987 1988//1988 1982//1982 -f 1982//1982 1988//1988 1989//1989 -f 1990//1990 1991//1991 1992//1992 -f 1992//1992 1991//1991 1993//1993 -f 1992//1992 1993//1993 1994//1994 -f 1911//1911 1995//1995 1934//1934 -f 1934//1934 1995//1995 1987//1987 -f 1934//1934 1987//1987 1996//1996 -f 1996//1996 1987//1987 1982//1982 -f 1996//1996 1982//1982 1997//1997 -f 1998//1998 1937//1937 1999//1999 -f 2000//2000 2001//2001 2002//2002 -f 2003//2003 2004//2004 2005//2005 -f 2006//2006 2007//2007 2008//2008 -f 2009//2009 1989//1989 2010//2010 -f 2011//2011 2012//2012 2013//2013 -f 2013//2013 2012//2012 2014//2014 -f 2013//2013 2014//2014 2015//2015 -f 2015//2015 2014//2014 2016//2016 -f 2017//2017 2018//2018 2019//2019 -f 2019//2019 2018//2018 2020//2020 -f 2019//2019 2020//2020 2021//2021 -f 1989//1989 2009//2009 1982//1982 -f 1982//1982 2009//2009 2022//2022 -f 1982//1982 2022//2022 1983//1983 -f 2023//2023 2024//2024 2025//2025 -f 2025//2025 2024//2024 2026//2026 -f 1953//1953 2027//2027 2028//2028 -f 1975//1975 1977//1977 2029//2029 -f 2030//2030 1936//1936 2031//2031 -f 1972//1972 1959//1959 2032//2032 -f 2032//2032 1959//1959 2033//2033 -f 2032//2032 2033//2033 2005//2005 -f 2005//2005 2033//2033 2034//2034 -f 2005//2005 2034//2034 2003//2003 -f 2003//2003 2034//2034 2035//2035 -f 2003//2003 2035//2035 2036//2036 -f 1930//1930 2037//2037 2038//2038 -f 2000//2000 2002//2002 2039//2039 -f 1939//1939 1938//1938 1983//1983 -f 1983//1983 1938//1938 2040//2040 -f 1983//1983 2040//2040 1981//1981 -f 2013//2013 2041//2041 2011//2011 -f 2011//2011 2041//2041 2025//2025 -f 2011//2011 2025//2025 2042//2042 -f 2042//2042 2025//2025 2026//2026 -f 2012//2012 2043//2043 2014//2014 -f 2014//2014 2043//2043 2044//2044 -f 2014//2014 2044//2044 2045//2045 -f 2045//2045 2044//2044 2027//2027 -f 2045//2045 2027//2027 2046//2046 -f 2046//2046 2027//2027 1953//1953 -f 2047//2047 1912//1912 2048//2048 -f 2048//2048 1912//1912 1914//1914 -f 2048//2048 1914//1914 2049//2049 -f 2049//2049 1914//1914 2050//2050 -f 2049//2049 2050//2050 2051//2051 -f 2051//2051 2050//2050 1978//1978 -f 2051//2051 1978//1978 2052//2052 -f 2052//2052 1978//1978 1953//1953 -f 2052//2052 1953//1953 1976//1976 -f 1976//1976 1953//1953 2028//2028 -f 1976//1976 2028//2028 1977//1977 -f 1936//1936 2030//2030 1937//1937 -f 1937//1937 2030//2030 2053//2053 -f 1937//1937 2053//2053 1999//1999 -f 1920//1920 1922//1922 2054//2054 -f 2054//2054 1922//1922 2055//2055 -f 2054//2054 2055//2055 2056//2056 -f 2056//2056 2055//2055 1965//1965 -f 2056//2056 1965//1965 2057//2057 -f 2057//2057 1965//1965 1930//1930 -f 2057//2057 1930//1930 2001//2001 -f 2001//2001 1930//1930 2038//2038 -f 2001//2001 2038//2038 2002//2002 -f 2020//2020 2058//2058 2021//2021 -f 2021//2021 2058//2058 2059//2059 -f 2021//2021 2059//2059 2060//2060 -f 2060//2060 2059//2059 2061//2061 -f 2060//2060 2061//2061 1984//1984 -f 1984//1984 2061//2061 2062//2062 -f 1984//1984 2062//2062 1985//1985 -f 1985//1985 2062//2062 2063//2063 -f 1985//1985 2063//2063 2064//2064 -f 2064//2064 2063//2063 2009//2009 -f 2064//2064 2009//2009 2065//2065 -f 2065//2065 2009//2009 2010//2010 -f 2004//2004 2003//2003 1999//1999 -f 1999//1999 2003//2003 2066//2066 -f 1999//1999 2066//2066 1998//1998 -f 1956//1956 2067//2067 1946//1946 -f 1946//1946 2067//2067 2068//2068 -f 1946//1946 2068//2068 2069//2069 -f 2069//2069 2068//2068 2037//2037 -f 2069//2069 2037//2037 2070//2070 -f 2070//2070 2037//2037 1930//1930 -f 1993//1993 2071//2071 1994//1994 -f 1994//1994 2071//2071 2072//2072 -f 1994//1994 2072//2072 2073//2073 -f 2073//2073 2072//2072 2074//2074 -f 2073//2073 2074//2074 2019//2019 -f 2019//2019 2074//2074 2075//2075 -f 2019//2019 2075//2075 2017//2017 -f 2017//2017 2075//2075 2076//2076 -f 2017//2017 2076//2076 1977//1977 -f 1977//1977 2076//2076 2077//2077 -f 1977//1977 2077//2077 2029//2029 -f 2008//2008 2078//2078 2006//2006 -f 2006//2006 2078//2078 2079//2079 -f 2006//2006 2079//2079 2080//2080 -f 2080//2080 2079//2079 2081//2081 -f 2080//2080 2081//2081 2082//2082 -f 2082//2082 2081//2081 2083//2083 -f 2082//2082 2083//2083 1992//1992 -f 1992//1992 2083//2083 2084//2084 -f 1992//1992 2084//2084 1990//1990 -f 1990//1990 2084//2084 2085//2085 -f 1990//1990 2085//2085 2086//2086 -f 2086//2086 2085//2085 2030//2030 -f 2086//2086 2030//2030 2087//2087 -f 2087//2087 2030//2030 2031//2031 -f 1986//1986 2088//2088 1984//1984 -f 1984//1984 2088//2088 2089//2089 -f 1984//1984 2089//2089 2090//2090 -f 2090//2090 2089//2089 2091//2091 -f 2090//2090 2091//2091 2092//2092 -f 2092//2092 2091//2091 2093//2093 -f 2092//2092 2093//2093 2006//2006 -f 2006//2006 2093//2093 2094//2094 -f 2006//2006 2094//2094 2007//2007 -f 2007//2007 2094//2094 2095//2095 -f 2007//2007 2095//2095 2002//2002 -f 2002//2002 2095//2095 2096//2096 -f 2002//2002 2096//2096 2039//2039 -f 2097//2097 2098//2098 2099//2099 -f 2100//2100 2101//2101 2102//2102 -f 2103//2103 2104//2104 2105//2105 -f 2105//2105 2104//2104 2106//2106 -f 2107//2107 2108//2108 2109//2109 -f 2109//2109 2108//2108 2110//2110 -f 2109//2109 2110//2110 2111//2111 -f 2112//2112 2113//2113 2114//2114 -f 2115//2115 2100//2100 2116//2116 -f 2116//2116 2100//2100 2102//2102 -f 2116//2116 2102//2102 2117//2117 -f 2118//2118 2119//2119 2120//2120 -f 2121//2121 2122//2122 2123//2123 -f 2124//2124 2125//2125 2126//2126 -f 2106//2106 2127//2127 2105//2105 -f 2105//2105 2127//2127 2128//2128 -f 2105//2105 2128//2128 2129//2129 -f 2129//2129 2128//2128 2130//2130 -f 2129//2129 2130//2130 2131//2131 -f 2131//2131 2130//2130 2132//2132 -f 2131//2131 2132//2132 2133//2133 -f 2133//2133 2132//2132 2134//2134 -f 2135//2135 2136//2136 2137//2137 -f 2138//2138 2139//2139 2140//2140 -f 2140//2140 2139//2139 2141//2141 -f 2140//2140 2141//2141 2142//2142 -f 2117//2117 2102//2102 2143//2143 -f 2143//2143 2102//2102 2144//2144 -f 2143//2143 2144//2144 2123//2123 -f 2123//2123 2144//2144 2145//2145 -f 2123//2123 2145//2145 2121//2121 -f 2121//2121 2145//2145 2146//2146 -f 2121//2121 2146//2146 2147//2147 -f 2135//2135 2137//2137 2148//2148 -f 2149//2149 2150//2150 2151//2151 -f 2152//2152 2153//2153 2154//2154 -f 2118//2118 2120//2120 2155//2155 -f 2114//2114 2097//2097 2112//2112 -f 2112//2112 2097//2097 2099//2099 -f 2112//2112 2099//2099 2156//2156 -f 2156//2156 2099//2099 2148//2148 -f 2156//2156 2148//2148 2157//2157 -f 2157//2157 2148//2148 2137//2137 -f 2157//2157 2137//2137 2158//2158 -f 2158//2158 2137//2137 2159//2159 -f 2160//2160 2161//2161 2162//2162 -f 2162//2162 2161//2161 2163//2163 -f 2164//2164 2165//2165 2154//2154 -f 2154//2154 2165//2165 2166//2166 -f 2154//2154 2166//2166 2152//2152 -f 2167//2167 2124//2124 2168//2168 -f 2168//2168 2124//2124 2126//2126 -f 2168//2168 2126//2126 2169//2169 -f 2169//2169 2126//2126 2170//2170 -f 2126//2126 2171//2171 2170//2170 -f 2170//2170 2171//2171 2160//2160 -f 2170//2170 2160//2160 2172//2172 -f 2172//2172 2160//2160 2162//2162 -f 2172//2172 2162//2162 2173//2173 -f 2174//2174 2175//2175 2176//2176 -f 2177//2177 2178//2178 2179//2179 -f 2179//2179 2178//2178 2180//2180 -f 2179//2179 2180//2180 2181//2181 -f 2182//2182 2183//2183 2184//2184 -f 2185//2185 2186//2186 2187//2187 -f 2188//2188 2189//2189 2190//2190 -f 2191//2191 2137//2137 2192//2192 -f 2193//2193 2163//2163 2194//2194 -f 2164//2164 2154//2154 2195//2195 -f 2195//2195 2154//2154 2196//2196 -f 2195//2195 2196//2196 2197//2197 -f 2197//2197 2196//2196 2198//2198 -f 2197//2197 2198//2198 2199//2199 -f 2199//2199 2198//2198 2200//2200 -f 2199//2199 2200//2200 2201//2201 -f 2202//2202 2203//2203 2204//2204 -f 2204//2204 2203//2203 2205//2205 -f 2163//2163 2193//2193 2162//2162 -f 2162//2162 2193//2193 2206//2206 -f 2162//2162 2206//2206 2207//2207 -f 2208//2208 2162//2162 2209//2209 -f 2209//2209 2162//2162 2207//2207 -f 2209//2209 2207//2207 2199//2199 -f 2199//2199 2207//2207 2210//2210 -f 2199//2199 2210//2210 2197//2197 -f 2184//2184 2211//2211 2212//2212 -f 2188//2188 2190//2190 2213//2213 -f 2182//2182 2184//2184 2214//2214 -f 2141//2141 2215//2215 2142//2142 -f 2142//2142 2215//2215 2216//2216 -f 2142//2142 2216//2216 2205//2205 -f 2205//2205 2216//2216 2217//2217 -f 2205//2205 2217//2217 2204//2204 -f 2107//2107 2109//2109 2218//2218 -f 2218//2218 2109//2109 2219//2219 -f 2218//2218 2219//2219 2220//2220 -f 2220//2220 2219//2219 2214//2214 -f 2220//2220 2214//2214 2221//2221 -f 2221//2221 2214//2214 2184//2184 -f 2221//2221 2184//2184 2189//2189 -f 2189//2189 2184//2184 2212//2212 -f 2189//2189 2212//2212 2190//2190 -f 2222//2222 2223//2223 2224//2224 -f 2187//2187 2225//2225 2185//2185 -f 2185//2185 2225//2225 2226//2226 -f 2185//2185 2226//2226 2227//2227 -f 2227//2227 2226//2226 2228//2228 -f 2227//2227 2228//2228 2229//2229 -f 2229//2229 2228//2228 2230//2230 -f 2229//2229 2230//2230 2179//2179 -f 2179//2179 2230//2230 2231//2231 -f 2179//2179 2231//2231 2177//2177 -f 2177//2177 2231//2231 2232//2232 -f 2177//2177 2232//2232 2233//2233 -f 2233//2233 2232//2232 2193//2193 -f 2233//2233 2193//2193 2234//2234 -f 2234//2234 2193//2193 2194//2194 -f 2130//2130 2235//2235 2132//2132 -f 2132//2132 2235//2235 2236//2236 -f 2132//2132 2236//2236 2237//2237 -f 2237//2237 2236//2236 2211//2211 -f 2237//2237 2211//2211 2238//2238 -f 2238//2238 2211//2211 2184//2184 -f 2239//2239 2136//2136 2240//2240 -f 2241//2241 2242//2242 2243//2243 -f 2243//2243 2242//2242 2244//2244 -f 2243//2243 2244//2244 2245//2245 -f 2224//2224 2246//2246 2222//2222 -f 2222//2222 2246//2246 2247//2247 -f 2222//2222 2247//2247 2248//2248 -f 2248//2248 2247//2247 2249//2249 -f 2248//2248 2249//2249 2250//2250 -f 2250//2250 2249//2249 2251//2251 -f 2250//2250 2251//2251 2185//2185 -f 2185//2185 2251//2251 2252//2252 -f 2185//2185 2252//2252 2186//2186 -f 2186//2186 2252//2252 2253//2253 -f 2186//2186 2253//2253 2190//2190 -f 2190//2190 2253//2253 2254//2254 -f 2190//2190 2254//2254 2213//2213 -f 2136//2136 2239//2239 2137//2137 -f 2137//2137 2239//2239 2255//2255 -f 2137//2137 2255//2255 2192//2192 -f 2120//2120 2256//2256 2257//2257 -f 2174//2174 2176//2176 2258//2258 -f 2122//2122 2121//2121 2192//2192 -f 2192//2192 2121//2121 2259//2259 -f 2192//2192 2259//2259 2191//2191 -f 2217//2217 2260//2260 2204//2204 -f 2204//2204 2260//2260 2261//2261 -f 2204//2204 2261//2261 2262//2262 -f 2262//2262 2261//2261 2256//2256 -f 2262//2262 2256//2256 2263//2263 -f 2263//2263 2256//2256 2120//2120 -f 2264//2264 2149//2149 2265//2265 -f 2265//2265 2149//2149 2151//2151 -f 2265//2265 2151//2151 2266//2266 -f 2266//2266 2151//2151 2267//2267 -f 2266//2266 2267//2267 2268//2268 -f 2268//2268 2267//2267 2155//2155 -f 2268//2268 2155//2155 2269//2269 -f 2269//2269 2155//2155 2120//2120 -f 2269//2269 2120//2120 2175//2175 -f 2175//2175 2120//2120 2257//2257 -f 2175//2175 2257//2257 2176//2176 -f 2244//2244 2270//2270 2245//2245 -f 2245//2245 2270//2270 2271//2271 -f 2245//2245 2271//2271 2272//2272 -f 2272//2272 2271//2271 2273//2273 -f 2272//2272 2273//2273 2222//2222 -f 2222//2222 2273//2273 2274//2274 -f 2222//2222 2274//2274 2223//2223 -f 2223//2223 2274//2274 2275//2275 -f 2223//2223 2275//2275 2276//2276 -f 2276//2276 2275//2275 2239//2239 -f 2276//2276 2239//2239 2277//2277 -f 2277//2277 2239//2239 2240//2240 -f 2180//2180 2278//2278 2181//2181 -f 2181//2181 2278//2278 2279//2279 -f 2181//2181 2279//2279 2280//2280 -f 2280//2280 2279//2279 2281//2281 -f 2280//2280 2281//2281 2243//2243 -f 2243//2243 2281//2281 2282//2282 -f 2243//2243 2282//2282 2241//2241 -f 2241//2241 2282//2282 2283//2283 -f 2241//2241 2283//2283 2176//2176 -f 2176//2176 2283//2283 2284//2284 -f 2176//2176 2284//2284 2258//2258 -f 1969//1969 1968//1968 2149//2149 -f 2149//2149 1968//1968 2150//2150 -f 1969//1969 2149//2149 2264//2264 -f 1969//1969 2264//2264 1971//1971 -f 1971//1971 2264//2264 2265//2265 -f 1971//1971 2265//2265 1980//1980 -f 1980//1980 2265//2265 2266//2266 -f 1980//1980 2266//2266 1967//1967 -f 1966//1966 1967//1967 2268//2268 -f 2268//2268 1967//1967 2266//2266 -f 1966//1966 2268//2268 1935//1935 -f 1935//1935 2268//2268 2269//2269 -f 1935//1935 2269//2269 1936//1936 -f 1936//1936 2269//2269 2175//2175 -f 1936//1936 2175//2175 2031//2031 -f 2031//2031 2175//2175 2174//2174 -f 2087//2087 2031//2031 2258//2258 -f 2258//2258 2031//2031 2174//2174 -f 2087//2087 2258//2258 2086//2086 -f 2086//2086 2258//2258 2284//2284 -f 2086//2086 2284//2284 1990//1990 -f 1990//1990 2284//2284 2283//2283 -f 1991//1991 1990//1990 2282//2282 -f 2282//2282 1990//1990 2283//2283 -f 1991//1991 2282//2282 1993//1993 -f 1993//1993 2282//2282 2281//2281 -f 1993//1993 2281//2281 2071//2071 -f 2071//2071 2281//2281 2279//2279 -f 2072//2072 2071//2071 2278//2278 -f 2278//2278 2071//2071 2279//2279 -f 2072//2072 2278//2278 2074//2074 -f 2074//2074 2278//2278 2180//2180 -f 2074//2074 2180//2180 2075//2075 -f 2075//2075 2180//2180 2178//2178 -f 2076//2076 2075//2075 2177//2177 -f 2177//2177 2075//2075 2178//2178 -f 2076//2076 2177//2177 2077//2077 -f 2077//2077 2177//2177 2233//2233 -f 2077//2077 2233//2233 2029//2029 -f 2029//2029 2233//2233 2234//2234 -f 1975//1975 2029//2029 2194//2194 -f 2194//2194 2029//2029 2234//2234 -f 1975//1975 2194//2194 1976//1976 -f 1976//1976 2194//2194 2163//2163 -f 1976//1976 2163//2163 2052//2052 -f 2052//2052 2163//2163 2161//2161 -f 2052//2052 2161//2161 2051//2051 -f 2051//2051 2161//2161 2160//2160 -f 2049//2049 2051//2051 2171//2171 -f 2171//2171 2051//2051 2160//2160 -f 2049//2049 2171//2171 2126//2126 -f 2049//2049 2126//2126 2048//2048 -f 2048//2048 2126//2126 2125//2125 -f 2048//2048 2125//2125 2047//2047 -f 2047//2047 2125//2125 2124//2124 -f 2047//2047 2124//2124 1912//1912 -f 1913//1913 1912//1912 2167//2167 -f 2167//2167 1912//1912 2124//2124 -f 1914//1914 1913//1913 2168//2168 -f 2168//2168 1913//1913 2167//2167 -f 1914//1914 2168//2168 2050//2050 -f 2050//2050 2168//2168 2169//2169 -f 2050//2050 2169//2169 1978//1978 -f 1978//1978 2169//2169 2170//2170 -f 1978//1978 2170//2170 1951//1951 -f 1951//1951 2170//2170 2172//2172 -f 1952//1952 1951//1951 2173//2173 -f 2173//2173 1951//1951 2172//2172 -f 1953//1953 1952//1952 2162//2162 -f 2162//2162 1952//1952 2173//2173 -f 1953//1953 2162//2162 2208//2208 -f 1953//1953 2208//2208 2046//2046 -f 2046//2046 2208//2208 2209//2209 -f 2046//2046 2209//2209 2045//2045 -f 2045//2045 2209//2209 2199//2199 -f 2045//2045 2199//2199 2014//2014 -f 2016//2016 2014//2014 2201//2201 -f 2201//2201 2014//2014 2199//2199 -f 2015//2015 2016//2016 2200//2200 -f 2200//2200 2016//2016 2201//2201 -f 2015//2015 2200//2200 2013//2013 -f 2013//2013 2200//2200 2198//2198 -f 2013//2013 2198//2198 2041//2041 -f 2041//2041 2198//2198 2196//2196 -f 2041//2041 2196//2196 2025//2025 -f 2025//2025 2196//2196 2154//2154 -f 2023//2023 2025//2025 2153//2153 -f 2153//2153 2025//2025 2154//2154 -f 2024//2024 2023//2023 2152//2152 -f 2152//2152 2023//2023 2153//2153 -f 2024//2024 2152//2152 2166//2166 -f 2024//2024 2166//2166 2026//2026 -f 2026//2026 2166//2166 2165//2165 -f 2026//2026 2165//2165 2042//2042 -f 2042//2042 2165//2165 2164//2164 -f 2042//2042 2164//2164 2011//2011 -f 2012//2012 2011//2011 2195//2195 -f 2195//2195 2011//2011 2164//2164 -f 2012//2012 2195//2195 2043//2043 -f 2043//2043 2195//2195 2197//2197 -f 2043//2043 2197//2197 2044//2044 -f 2044//2044 2197//2197 2210//2210 -f 2044//2044 2210//2210 2027//2027 -f 2027//2027 2210//2210 2207//2207 -f 2028//2028 2027//2027 2206//2206 -f 2206//2206 2027//2027 2207//2207 -f 2028//2028 2206//2206 1977//1977 -f 1977//1977 2206//2206 2193//2193 -f 1977//1977 2193//2193 2017//2017 -f 2017//2017 2193//2193 2232//2232 -f 2018//2018 2017//2017 2231//2231 -f 2231//2231 2017//2017 2232//2232 -f 2018//2018 2231//2231 2020//2020 -f 2020//2020 2231//2231 2230//2230 -f 2020//2020 2230//2230 2058//2058 -f 2058//2058 2230//2230 2228//2228 -f 2059//2059 2058//2058 2226//2226 -f 2226//2226 2058//2058 2228//2228 -f 2059//2059 2226//2226 2061//2061 -f 2061//2061 2226//2226 2225//2225 -f 2061//2061 2225//2225 2062//2062 -f 2062//2062 2225//2225 2187//2187 -f 2063//2063 2062//2062 2186//2186 -f 2186//2186 2062//2062 2187//2187 -f 2063//2063 2186//2186 2009//2009 -f 2009//2009 2186//2186 2190//2190 -f 2009//2009 2190//2190 2022//2022 -f 2022//2022 2190//2190 2212//2212 -f 1983//1983 2022//2022 2211//2211 -f 2211//2211 2022//2022 2212//2212 -f 1983//1983 2211//2211 1939//1939 -f 1939//1939 2211//2211 2236//2236 -f 1939//1939 2236//2236 1940//1940 -f 1940//1940 2236//2236 2235//2235 -f 1940//1940 2235//2235 1960//1960 -f 1960//1960 2235//2235 2130//2130 -f 1943//1943 1960//1960 2128//2128 -f 2128//2128 1960//1960 2130//2130 -f 1943//1943 2128//2128 2127//2127 -f 1943//1943 2127//2127 1942//1942 -f 1942//1942 2127//2127 2106//2106 -f 1942//1942 2106//2106 1941//1941 -f 1941//1941 2106//2106 2104//2104 -f 1941//1941 2104//2104 1925//1925 -f 1926//1926 1925//1925 2103//2103 -f 2103//2103 1925//1925 2104//2104 -f 1927//1927 1926//1926 2105//2105 -f 2105//2105 1926//1926 2103//2103 -f 1927//1927 2105//2105 1961//1961 -f 1961//1961 2105//2105 2129//2129 -f 1961//1961 2129//2129 1962//1962 -f 1962//1962 2129//2129 2131//2131 -f 1962//1962 2131//2131 1963//1963 -f 1963//1963 2131//2131 2133//2133 -f 1964//1964 1963//1963 2134//2134 -f 2134//2134 1963//1963 2133//2133 -f 1938//1938 1964//1964 2132//2132 -f 2132//2132 1964//1964 2134//2134 -f 1938//1938 2132//2132 2237//2237 -f 1938//1938 2237//2237 2040//2040 -f 2040//2040 2237//2237 2238//2238 -f 2040//2040 2238//2238 1981//1981 -f 1981//1981 2238//2238 2184//2184 -f 1981//1981 2184//2184 1982//1982 -f 1997//1997 1982//1982 2183//2183 -f 2183//2183 1982//1982 2184//2184 -f 1996//1996 1997//1997 2182//2182 -f 2182//2182 1997//1997 2183//2183 -f 1996//1996 2182//2182 1934//1934 -f 1934//1934 2182//2182 2214//2214 -f 1934//1934 2214//2214 1933//1933 -f 1933//1933 2214//2214 2219//2219 -f 1933//1933 2219//2219 1932//1932 -f 1932//1932 2219//2219 2109//2109 -f 1931//1931 1932//1932 2111//2111 -f 2111//2111 1932//1932 2109//2109 -f 1909//1909 1931//1931 2110//2110 -f 2110//2110 1931//1931 2111//2111 -f 1909//1909 2110//2110 2108//2108 -f 1909//1909 2108//2108 1910//1910 -f 1910//1910 2108//2108 2107//2107 -f 1910//1910 2107//2107 1911//1911 -f 1911//1911 2107//2107 2218//2218 -f 1911//1911 2218//2218 1995//1995 -f 1987//1987 1995//1995 2220//2220 -f 2220//2220 1995//1995 2218//2218 -f 1987//1987 2220//2220 1988//1988 -f 1988//1988 2220//2220 2221//2221 -f 1988//1988 2221//2221 1989//1989 -f 1989//1989 2221//2221 2189//2189 -f 1989//1989 2189//2189 2010//2010 -f 2010//2010 2189//2189 2188//2188 -f 2065//2065 2010//2010 2213//2213 -f 2213//2213 2010//2010 2188//2188 -f 2065//2065 2213//2213 2064//2064 -f 2064//2064 2213//2213 2254//2254 -f 2064//2064 2254//2254 1985//1985 -f 1985//1985 2254//2254 2253//2253 -f 1986//1986 1985//1985 2252//2252 -f 2252//2252 1985//1985 2253//2253 -f 1986//1986 2252//2252 2088//2088 -f 2088//2088 2252//2252 2251//2251 -f 2088//2088 2251//2251 2089//2089 -f 2089//2089 2251//2251 2249//2249 -f 2091//2091 2089//2089 2247//2247 -f 2247//2247 2089//2089 2249//2249 -f 2091//2091 2247//2247 2093//2093 -f 2093//2093 2247//2247 2246//2246 -f 2093//2093 2246//2246 2094//2094 -f 2094//2094 2246//2246 2224//2224 -f 2095//2095 2094//2094 2223//2223 -f 2223//2223 2094//2094 2224//2224 -f 2095//2095 2223//2223 2096//2096 -f 2096//2096 2223//2223 2276//2276 -f 2096//2096 2276//2276 2039//2039 -f 2039//2039 2276//2276 2277//2277 -f 2000//2000 2039//2039 2240//2240 -f 2240//2240 2039//2039 2277//2277 -f 2000//2000 2240//2240 2001//2001 -f 2001//2001 2240//2240 2136//2136 -f 2001//2001 2136//2136 2057//2057 -f 2057//2057 2136//2136 2135//2135 -f 2057//2057 2135//2135 2056//2056 -f 2056//2056 2135//2135 2148//2148 -f 2054//2054 2056//2056 2099//2099 -f 2099//2099 2056//2056 2148//2148 -f 2054//2054 2099//2099 2098//2098 -f 2054//2054 2098//2098 1920//1920 -f 1920//1920 2098//2098 2097//2097 -f 1920//1920 2097//2097 1921//1921 -f 1921//1921 2097//2097 2114//2114 -f 1921//1921 2114//2114 1923//1923 -f 1924//1924 1923//1923 2113//2113 -f 2113//2113 1923//1923 2114//2114 -f 1922//1922 1924//1924 2112//2112 -f 2112//2112 1924//1924 2113//2113 -f 1922//1922 2112//2112 2055//2055 -f 2055//2055 2112//2112 2156//2156 -f 2055//2055 2156//2156 1965//1965 -f 1965//1965 2156//2156 2157//2157 -f 1965//1965 2157//2157 1928//1928 -f 1928//1928 2157//2157 2158//2158 -f 1929//1929 1928//1928 2159//2159 -f 2159//2159 1928//1928 2158//2158 -f 1930//1930 1929//1929 2137//2137 -f 2137//2137 1929//1929 2159//2159 -f 1930//1930 2137//2137 2191//2191 -f 1930//1930 2191//2191 2070//2070 -f 2070//2070 2191//2191 2259//2259 -f 2070//2070 2259//2259 2069//2069 -f 2069//2069 2259//2259 2121//2121 -f 2069//2069 2121//2121 1946//1946 -f 1944//1944 1946//1946 2147//2147 -f 2147//2147 1946//1946 2121//2121 -f 1945//1945 1944//1944 2146//2146 -f 2146//2146 1944//1944 2147//2147 -f 1945//1945 2146//2146 1947//1947 -f 1947//1947 2146//2146 2145//2145 -f 1947//1947 2145//2145 1919//1919 -f 1919//1919 2145//2145 2144//2144 -f 1919//1919 2144//2144 1917//1917 -f 1917//1917 2144//2144 2102//2102 -f 1915//1915 1917//1917 2101//2101 -f 2101//2101 1917//1917 2102//2102 -f 1916//1916 1915//1915 2100//2100 -f 2100//2100 1915//1915 2101//2101 -f 1916//1916 2100//2100 2115//2115 -f 1916//1916 2115//2115 1918//1918 -f 1918//1918 2115//2115 2116//2116 -f 1918//1918 2116//2116 1954//1954 -f 1954//1954 2116//2116 2117//2117 -f 1954//1954 2117//2117 1955//1955 -f 1956//1956 1955//1955 2143//2143 -f 2143//2143 1955//1955 2117//2117 -f 1956//1956 2143//2143 2067//2067 -f 2067//2067 2143//2143 2123//2123 -f 2067//2067 2123//2123 2068//2068 -f 2068//2068 2123//2123 2122//2122 -f 2068//2068 2122//2122 2037//2037 -f 2037//2037 2122//2122 2192//2192 -f 2038//2038 2037//2037 2255//2255 -f 2255//2255 2037//2037 2192//2192 -f 2038//2038 2255//2255 2002//2002 -f 2002//2002 2255//2255 2239//2239 -f 2002//2002 2239//2239 2007//2007 -f 2007//2007 2239//2239 2275//2275 -f 2008//2008 2007//2007 2274//2274 -f 2274//2274 2007//2007 2275//2275 -f 2008//2008 2274//2274 2078//2078 -f 2078//2078 2274//2274 2273//2273 -f 2078//2078 2273//2273 2079//2079 -f 2079//2079 2273//2273 2271//2271 -f 2081//2081 2079//2079 2270//2270 -f 2270//2270 2079//2079 2271//2271 -f 2081//2081 2270//2270 2083//2083 -f 2083//2083 2270//2270 2244//2244 -f 2083//2083 2244//2244 2084//2084 -f 2084//2084 2244//2244 2242//2242 -f 2085//2085 2084//2084 2241//2241 -f 2241//2241 2084//2084 2242//2242 -f 2085//2085 2241//2241 2030//2030 -f 2030//2030 2241//2241 2176//2176 -f 2030//2030 2176//2176 2053//2053 -f 2053//2053 2176//2176 2257//2257 -f 1999//1999 2053//2053 2256//2256 -f 2256//2256 2053//2053 2257//2257 -f 1999//1999 2256//2256 2004//2004 -f 2004//2004 2256//2256 2261//2261 -f 2004//2004 2261//2261 2005//2005 -f 2005//2005 2261//2261 2260//2260 -f 2005//2005 2260//2260 2032//2032 -f 2032//2032 2260//2260 2217//2217 -f 1972//1972 2032//2032 2216//2216 -f 2216//2216 2032//2032 2217//2217 -f 1972//1972 2216//2216 2215//2215 -f 1972//1972 2215//2215 1973//1973 -f 1973//1973 2215//2215 2141//2141 -f 1973//1973 2141//2141 1974//1974 -f 1974//1974 2141//2141 2139//2139 -f 1974//1974 2139//2139 1957//1957 -f 1958//1958 1957//1957 2138//2138 -f 2138//2138 1957//1957 2139//2139 -f 1959//1959 1958//1958 2140//2140 -f 2140//2140 1958//1958 2138//2138 -f 1959//1959 2140//2140 2033//2033 -f 2033//2033 2140//2140 2142//2142 -f 2033//2033 2142//2142 2034//2034 -f 2034//2034 2142//2142 2205//2205 -f 2034//2034 2205//2205 2035//2035 -f 2035//2035 2205//2205 2203//2203 -f 2036//2036 2035//2035 2202//2202 -f 2202//2202 2035//2035 2203//2203 -f 2003//2003 2036//2036 2204//2204 -f 2204//2204 2036//2036 2202//2202 -f 2003//2003 2204//2204 2262//2262 -f 2003//2003 2262//2262 2066//2066 -f 2066//2066 2262//2262 2263//2263 -f 2066//2066 2263//2263 1998//1998 -f 1998//1998 2263//2263 2120//2120 -f 1998//1998 2120//2120 1937//1937 -f 1950//1950 1937//1937 2119//2119 -f 2119//2119 1937//1937 2120//2120 -f 1949//1949 1950//1950 2118//2118 -f 2118//2118 1950//1950 2119//2119 -f 1949//1949 2118//2118 1948//1948 -f 1948//1948 2118//2118 2155//2155 -f 1948//1948 2155//2155 1979//1979 -f 1979//1979 2155//2155 2267//2267 -f 1979//1979 2267//2267 1970//1970 -f 1970//1970 2267//2267 2151//2151 -f 1968//1968 1970//1970 2150//2150 -f 2150//2150 1970//1970 2151//2151 -f 1994//1994 2181//2181 1992//1992 -f 1992//1992 2181//2181 2280//2280 -f 1992//1992 2280//2280 2082//2082 -f 2082//2082 2280//2280 2243//2243 -f 2082//2082 2243//2243 2080//2080 -f 2080//2080 2243//2243 2245//2245 -f 2080//2080 2245//2245 2006//2006 -f 2006//2006 2245//2245 2272//2272 -f 2006//2006 2272//2272 2092//2092 -f 2092//2092 2272//2272 2222//2222 -f 2092//2092 2222//2222 2090//2090 -f 2090//2090 2222//2222 2248//2248 -f 2090//2090 2248//2248 1984//1984 -f 1984//1984 2248//2248 2250//2250 -f 1984//1984 2250//2250 2060//2060 -f 2060//2060 2250//2250 2185//2185 -f 2060//2060 2185//2185 2021//2021 -f 2021//2021 2185//2185 2227//2227 -f 2021//2021 2227//2227 2019//2019 -f 2019//2019 2227//2227 2229//2229 -f 2019//2019 2229//2229 2073//2073 -f 2073//2073 2229//2229 2179//2179 -f 2073//2073 2179//2179 1994//1994 -f 1994//1994 2179//2179 2181//2181 -f 2285//2285 2286//2286 2287//2287 -f 2288//2288 2289//2289 2290//2290 -f 2291//2291 2292//2292 2293//2293 -f 2293//2293 2292//2292 2294//2294 -f 2293//2293 2294//2294 2295//2295 -f 2296//2296 2297//2297 2298//2298 -f 2298//2298 2297//2297 2299//2299 -f 2298//2298 2299//2299 2300//2300 -f 2301//2301 2302//2302 2303//2303 -f 2304//2304 2305//2305 2306//2306 -f 2307//2307 2285//2285 2308//2308 -f 2308//2308 2285//2285 2287//2287 -f 2308//2308 2287//2287 2309//2309 -f 2309//2309 2287//2287 2310//2310 -f 2311//2311 2312//2312 2313//2313 -f 2314//2314 2315//2315 2316//2316 -f 2317//2317 2301//2301 2318//2318 -f 2318//2318 2301//2301 2303//2303 -f 2318//2318 2303//2303 2319//2319 -f 2320//2320 2321//2321 2322//2322 -f 2322//2322 2321//2321 2323//2323 -f 2324//2324 2313//2313 2325//2325 -f 2325//2325 2313//2313 2326//2326 -f 2327//2327 2328//2328 2329//2329 -f 2294//2294 2330//2330 2295//2295 -f 2295//2295 2330//2330 2331//2331 -f 2295//2295 2331//2331 2323//2323 -f 2323//2323 2331//2331 2332//2332 -f 2323//2323 2332//2332 2322//2322 -f 2333//2333 2334//2334 2335//2335 -f 2319//2319 2303//2303 2336//2336 -f 2336//2336 2303//2303 2337//2337 -f 2336//2336 2337//2337 2316//2316 -f 2316//2316 2337//2337 2338//2338 -f 2316//2316 2338//2338 2314//2314 -f 2314//2314 2338//2338 2339//2339 -f 2314//2314 2339//2339 2340//2340 -f 2304//2304 2306//2306 2341//2341 -f 2311//2311 2313//2313 2342//2342 -f 2342//2342 2313//2313 2324//2324 -f 2342//2342 2324//2324 2343//2343 -f 2344//2344 2345//2345 2346//2346 -f 2346//2346 2345//2345 2347//2347 -f 2348//2348 2349//2349 2335//2335 -f 2335//2335 2349//2349 2350//2350 -f 2335//2335 2350//2350 2333//2333 -f 2351//2351 2352//2352 2353//2353 -f 2327//2327 2329//2329 2354//2354 -f 2324//2324 2355//2355 2343//2343 -f 2343//2343 2355//2355 2346//2346 -f 2343//2343 2346//2346 2356//2356 -f 2356//2356 2346//2346 2347//2347 -f 2357//2357 2358//2358 2359//2359 -f 2360//2360 2361//2361 2362//2362 -f 2363//2363 2364//2364 2358//2358 -f 2358//2358 2364//2364 2365//2365 -f 2366//2366 2367//2367 2368//2368 -f 2368//2368 2367//2367 2369//2369 -f 2368//2368 2369//2369 2370//2370 -f 2287//2287 2371//2371 2310//2310 -f 2310//2310 2371//2371 2363//2363 -f 2310//2310 2363//2363 2372//2372 -f 2372//2372 2363//2363 2358//2358 -f 2372//2372 2358//2358 2373//2373 -f 2374//2374 2313//2313 2375//2375 -f 2376//2376 2377//2377 2378//2378 -f 2379//2379 2380//2380 2381//2381 -f 2382//2382 2383//2383 2384//2384 -f 2385//2385 2365//2365 2386//2386 -f 2387//2387 2388//2388 2389//2389 -f 2389//2389 2388//2388 2390//2390 -f 2389//2389 2390//2390 2391//2391 -f 2391//2391 2390//2390 2392//2392 -f 2393//2393 2394//2394 2395//2395 -f 2395//2395 2394//2394 2396//2396 -f 2395//2395 2396//2396 2397//2397 -f 2365//2365 2385//2385 2358//2358 -f 2358//2358 2385//2385 2398//2398 -f 2358//2358 2398//2398 2359//2359 -f 2399//2399 2400//2400 2401//2401 -f 2401//2401 2400//2400 2402//2402 -f 2329//2329 2403//2403 2404//2404 -f 2351//2351 2353//2353 2405//2405 -f 2406//2406 2312//2312 2407//2407 -f 2348//2348 2335//2335 2408//2408 -f 2408//2408 2335//2335 2409//2409 -f 2408//2408 2409//2409 2381//2381 -f 2381//2381 2409//2409 2410//2410 -f 2381//2381 2410//2410 2379//2379 -f 2379//2379 2410//2410 2411//2411 -f 2379//2379 2411//2411 2412//2412 -f 2306//2306 2413//2413 2414//2414 -f 2376//2376 2378//2378 2415//2415 -f 2315//2315 2314//2314 2359//2359 -f 2359//2359 2314//2314 2416//2416 -f 2359//2359 2416//2416 2357//2357 -f 2389//2389 2417//2417 2387//2387 -f 2387//2387 2417//2417 2401//2401 -f 2387//2387 2401//2401 2418//2418 -f 2418//2418 2401//2401 2402//2402 -f 2388//2388 2419//2419 2390//2390 -f 2390//2390 2419//2419 2420//2420 -f 2390//2390 2420//2420 2421//2421 -f 2421//2421 2420//2420 2403//2403 -f 2421//2421 2403//2403 2422//2422 -f 2422//2422 2403//2403 2329//2329 -f 2423//2423 2288//2288 2424//2424 -f 2424//2424 2288//2288 2290//2290 -f 2424//2424 2290//2290 2425//2425 -f 2425//2425 2290//2290 2426//2426 -f 2425//2425 2426//2426 2427//2427 -f 2427//2427 2426//2426 2354//2354 -f 2427//2427 2354//2354 2428//2428 -f 2428//2428 2354//2354 2329//2329 -f 2428//2428 2329//2329 2352//2352 -f 2352//2352 2329//2329 2404//2404 -f 2352//2352 2404//2404 2353//2353 -f 2312//2312 2406//2406 2313//2313 -f 2313//2313 2406//2406 2429//2429 -f 2313//2313 2429//2429 2375//2375 -f 2296//2296 2298//2298 2430//2430 -f 2430//2430 2298//2298 2431//2431 -f 2430//2430 2431//2431 2432//2432 -f 2432//2432 2431//2431 2341//2341 -f 2432//2432 2341//2341 2433//2433 -f 2433//2433 2341//2341 2306//2306 -f 2433//2433 2306//2306 2377//2377 -f 2377//2377 2306//2306 2414//2414 -f 2377//2377 2414//2414 2378//2378 -f 2396//2396 2434//2434 2397//2397 -f 2397//2397 2434//2434 2435//2435 -f 2397//2397 2435//2435 2436//2436 -f 2436//2436 2435//2435 2437//2437 -f 2436//2436 2437//2437 2360//2360 -f 2360//2360 2437//2437 2438//2438 -f 2360//2360 2438//2438 2361//2361 -f 2361//2361 2438//2438 2439//2439 -f 2361//2361 2439//2439 2440//2440 -f 2440//2440 2439//2439 2385//2385 -f 2440//2440 2385//2385 2441//2441 -f 2441//2441 2385//2385 2386//2386 -f 2380//2380 2379//2379 2375//2375 -f 2375//2375 2379//2379 2442//2442 -f 2375//2375 2442//2442 2374//2374 -f 2332//2332 2443//2443 2322//2322 -f 2322//2322 2443//2443 2444//2444 -f 2322//2322 2444//2444 2445//2445 -f 2445//2445 2444//2444 2413//2413 -f 2445//2445 2413//2413 2446//2446 -f 2446//2446 2413//2413 2306//2306 -f 2369//2369 2447//2447 2370//2370 -f 2370//2370 2447//2447 2448//2448 -f 2370//2370 2448//2448 2449//2449 -f 2449//2449 2448//2448 2450//2450 -f 2449//2449 2450//2450 2395//2395 -f 2395//2395 2450//2450 2451//2451 -f 2395//2395 2451//2451 2393//2393 -f 2393//2393 2451//2451 2452//2452 -f 2393//2393 2452//2452 2353//2353 -f 2353//2353 2452//2452 2453//2453 -f 2353//2353 2453//2453 2405//2405 -f 2384//2384 2454//2454 2382//2382 -f 2382//2382 2454//2454 2455//2455 -f 2382//2382 2455//2455 2456//2456 -f 2456//2456 2455//2455 2457//2457 -f 2456//2456 2457//2457 2458//2458 -f 2458//2458 2457//2457 2459//2459 -f 2458//2458 2459//2459 2368//2368 -f 2368//2368 2459//2459 2460//2460 -f 2368//2368 2460//2460 2366//2366 -f 2366//2366 2460//2460 2461//2461 -f 2366//2366 2461//2461 2462//2462 -f 2462//2462 2461//2461 2406//2406 -f 2462//2462 2406//2406 2463//2463 -f 2463//2463 2406//2406 2407//2407 -f 2362//2362 2464//2464 2360//2360 -f 2360//2360 2464//2464 2465//2465 -f 2360//2360 2465//2465 2466//2466 -f 2466//2466 2465//2465 2467//2467 -f 2466//2466 2467//2467 2468//2468 -f 2468//2468 2467//2467 2469//2469 -f 2468//2468 2469//2469 2382//2382 -f 2382//2382 2469//2469 2470//2470 -f 2382//2382 2470//2470 2383//2383 -f 2383//2383 2470//2470 2471//2471 -f 2383//2383 2471//2471 2378//2378 -f 2378//2378 2471//2471 2472//2472 -f 2378//2378 2472//2472 2415//2415 -f 2473//2473 2474//2474 2475//2475 -f 2476//2476 2477//2477 2478//2478 -f 2479//2479 2480//2480 2481//2481 -f 2481//2481 2480//2480 2482//2482 -f 2483//2483 2484//2484 2485//2485 -f 2485//2485 2484//2484 2486//2486 -f 2485//2485 2486//2486 2487//2487 -f 2488//2488 2489//2489 2490//2490 -f 2491//2491 2476//2476 2492//2492 -f 2492//2492 2476//2476 2478//2478 -f 2492//2492 2478//2478 2493//2493 -f 2494//2494 2495//2495 2496//2496 -f 2497//2497 2498//2498 2499//2499 -f 2500//2500 2501//2501 2502//2502 -f 2482//2482 2503//2503 2481//2481 -f 2481//2481 2503//2503 2504//2504 -f 2481//2481 2504//2504 2505//2505 -f 2505//2505 2504//2504 2506//2506 -f 2505//2505 2506//2506 2507//2507 -f 2507//2507 2506//2506 2508//2508 -f 2507//2507 2508//2508 2509//2509 -f 2509//2509 2508//2508 2510//2510 -f 2511//2511 2512//2512 2513//2513 -f 2514//2514 2515//2515 2516//2516 -f 2516//2516 2515//2515 2517//2517 -f 2516//2516 2517//2517 2518//2518 -f 2493//2493 2478//2478 2519//2519 -f 2519//2519 2478//2478 2520//2520 -f 2519//2519 2520//2520 2499//2499 -f 2499//2499 2520//2520 2521//2521 -f 2499//2499 2521//2521 2497//2497 -f 2497//2497 2521//2521 2522//2522 -f 2497//2497 2522//2522 2523//2523 -f 2511//2511 2513//2513 2524//2524 -f 2525//2525 2526//2526 2527//2527 -f 2528//2528 2529//2529 2530//2530 -f 2494//2494 2496//2496 2531//2531 -f 2490//2490 2473//2473 2488//2488 -f 2488//2488 2473//2473 2475//2475 -f 2488//2488 2475//2475 2532//2532 -f 2532//2532 2475//2475 2524//2524 -f 2532//2532 2524//2524 2533//2533 -f 2533//2533 2524//2524 2513//2513 -f 2533//2533 2513//2513 2534//2534 -f 2534//2534 2513//2513 2535//2535 -f 2536//2536 2537//2537 2538//2538 -f 2538//2538 2537//2537 2539//2539 -f 2540//2540 2541//2541 2530//2530 -f 2530//2530 2541//2541 2542//2542 -f 2530//2530 2542//2542 2528//2528 -f 2543//2543 2500//2500 2544//2544 -f 2544//2544 2500//2500 2502//2502 -f 2544//2544 2502//2502 2545//2545 -f 2545//2545 2502//2502 2546//2546 -f 2502//2502 2547//2547 2546//2546 -f 2546//2546 2547//2547 2536//2536 -f 2546//2546 2536//2536 2548//2548 -f 2548//2548 2536//2536 2538//2538 -f 2548//2548 2538//2538 2549//2549 -f 2550//2550 2551//2551 2552//2552 -f 2553//2553 2554//2554 2555//2555 -f 2555//2555 2554//2554 2556//2556 -f 2555//2555 2556//2556 2557//2557 -f 2558//2558 2559//2559 2560//2560 -f 2561//2561 2562//2562 2563//2563 -f 2564//2564 2565//2565 2566//2566 -f 2567//2567 2513//2513 2568//2568 -f 2569//2569 2539//2539 2570//2570 -f 2540//2540 2530//2530 2571//2571 -f 2571//2571 2530//2530 2572//2572 -f 2571//2571 2572//2572 2573//2573 -f 2573//2573 2572//2572 2574//2574 -f 2573//2573 2574//2574 2575//2575 -f 2575//2575 2574//2574 2576//2576 -f 2575//2575 2576//2576 2577//2577 -f 2578//2578 2579//2579 2580//2580 -f 2580//2580 2579//2579 2581//2581 -f 2539//2539 2569//2569 2538//2538 -f 2538//2538 2569//2569 2582//2582 -f 2538//2538 2582//2582 2583//2583 -f 2584//2584 2538//2538 2585//2585 -f 2585//2585 2538//2538 2583//2583 -f 2585//2585 2583//2583 2575//2575 -f 2575//2575 2583//2583 2586//2586 -f 2575//2575 2586//2586 2573//2573 -f 2560//2560 2587//2587 2588//2588 -f 2564//2564 2566//2566 2589//2589 -f 2558//2558 2560//2560 2590//2590 -f 2517//2517 2591//2591 2518//2518 -f 2518//2518 2591//2591 2592//2592 -f 2518//2518 2592//2592 2581//2581 -f 2581//2581 2592//2592 2593//2593 -f 2581//2581 2593//2593 2580//2580 -f 2483//2483 2485//2485 2594//2594 -f 2594//2594 2485//2485 2595//2595 -f 2594//2594 2595//2595 2596//2596 -f 2596//2596 2595//2595 2590//2590 -f 2596//2596 2590//2590 2597//2597 -f 2597//2597 2590//2590 2560//2560 -f 2597//2597 2560//2560 2565//2565 -f 2565//2565 2560//2560 2588//2588 -f 2565//2565 2588//2588 2566//2566 -f 2598//2598 2599//2599 2600//2600 -f 2563//2563 2601//2601 2561//2561 -f 2561//2561 2601//2601 2602//2602 -f 2561//2561 2602//2602 2603//2603 -f 2603//2603 2602//2602 2604//2604 -f 2603//2603 2604//2604 2605//2605 -f 2605//2605 2604//2604 2606//2606 -f 2605//2605 2606//2606 2555//2555 -f 2555//2555 2606//2606 2607//2607 -f 2555//2555 2607//2607 2553//2553 -f 2553//2553 2607//2607 2608//2608 -f 2553//2553 2608//2608 2609//2609 -f 2609//2609 2608//2608 2569//2569 -f 2609//2609 2569//2569 2610//2610 -f 2610//2610 2569//2569 2570//2570 -f 2506//2506 2611//2611 2508//2508 -f 2508//2508 2611//2611 2612//2612 -f 2508//2508 2612//2612 2613//2613 -f 2613//2613 2612//2612 2587//2587 -f 2613//2613 2587//2587 2614//2614 -f 2614//2614 2587//2587 2560//2560 -f 2615//2615 2512//2512 2616//2616 -f 2617//2617 2618//2618 2619//2619 -f 2619//2619 2618//2618 2620//2620 -f 2619//2619 2620//2620 2621//2621 -f 2600//2600 2622//2622 2598//2598 -f 2598//2598 2622//2622 2623//2623 -f 2598//2598 2623//2623 2624//2624 -f 2624//2624 2623//2623 2625//2625 -f 2624//2624 2625//2625 2626//2626 -f 2626//2626 2625//2625 2627//2627 -f 2626//2626 2627//2627 2561//2561 -f 2561//2561 2627//2627 2628//2628 -f 2561//2561 2628//2628 2562//2562 -f 2562//2562 2628//2628 2629//2629 -f 2562//2562 2629//2629 2566//2566 -f 2566//2566 2629//2629 2630//2630 -f 2566//2566 2630//2630 2589//2589 -f 2512//2512 2615//2615 2513//2513 -f 2513//2513 2615//2615 2631//2631 -f 2513//2513 2631//2631 2568//2568 -f 2496//2496 2632//2632 2633//2633 -f 2550//2550 2552//2552 2634//2634 -f 2498//2498 2497//2497 2568//2568 -f 2568//2568 2497//2497 2635//2635 -f 2568//2568 2635//2635 2567//2567 -f 2593//2593 2636//2636 2580//2580 -f 2580//2580 2636//2636 2637//2637 -f 2580//2580 2637//2637 2638//2638 -f 2638//2638 2637//2637 2632//2632 -f 2638//2638 2632//2632 2639//2639 -f 2639//2639 2632//2632 2496//2496 -f 2640//2640 2525//2525 2641//2641 -f 2641//2641 2525//2525 2527//2527 -f 2641//2641 2527//2527 2642//2642 -f 2642//2642 2527//2527 2643//2643 -f 2642//2642 2643//2643 2644//2644 -f 2644//2644 2643//2643 2531//2531 -f 2644//2644 2531//2531 2645//2645 -f 2645//2645 2531//2531 2496//2496 -f 2645//2645 2496//2496 2551//2551 -f 2551//2551 2496//2496 2633//2633 -f 2551//2551 2633//2633 2552//2552 -f 2620//2620 2646//2646 2621//2621 -f 2621//2621 2646//2646 2647//2647 -f 2621//2621 2647//2647 2648//2648 -f 2648//2648 2647//2647 2649//2649 -f 2648//2648 2649//2649 2598//2598 -f 2598//2598 2649//2649 2650//2650 -f 2598//2598 2650//2650 2599//2599 -f 2599//2599 2650//2650 2651//2651 -f 2599//2599 2651//2651 2652//2652 -f 2652//2652 2651//2651 2615//2615 -f 2652//2652 2615//2615 2653//2653 -f 2653//2653 2615//2615 2616//2616 -f 2556//2556 2654//2654 2557//2557 -f 2557//2557 2654//2654 2655//2655 -f 2557//2557 2655//2655 2656//2656 -f 2656//2656 2655//2655 2657//2657 -f 2656//2656 2657//2657 2619//2619 -f 2619//2619 2657//2657 2658//2658 -f 2619//2619 2658//2658 2617//2617 -f 2617//2617 2658//2658 2659//2659 -f 2617//2617 2659//2659 2552//2552 -f 2552//2552 2659//2659 2660//2660 -f 2552//2552 2660//2660 2634//2634 -f 2345//2345 2344//2344 2525//2525 -f 2525//2525 2344//2344 2526//2526 -f 2345//2345 2525//2525 2640//2640 -f 2345//2345 2640//2640 2347//2347 -f 2347//2347 2640//2640 2641//2641 -f 2347//2347 2641//2641 2356//2356 -f 2356//2356 2641//2641 2642//2642 -f 2356//2356 2642//2642 2343//2343 -f 2342//2342 2343//2343 2644//2644 -f 2644//2644 2343//2343 2642//2642 -f 2342//2342 2644//2644 2311//2311 -f 2311//2311 2644//2644 2645//2645 -f 2311//2311 2645//2645 2312//2312 -f 2312//2312 2645//2645 2551//2551 -f 2312//2312 2551//2551 2407//2407 -f 2407//2407 2551//2551 2550//2550 -f 2463//2463 2407//2407 2634//2634 -f 2634//2634 2407//2407 2550//2550 -f 2463//2463 2634//2634 2462//2462 -f 2462//2462 2634//2634 2660//2660 -f 2462//2462 2660//2660 2366//2366 -f 2366//2366 2660//2660 2659//2659 -f 2367//2367 2366//2366 2658//2658 -f 2658//2658 2366//2366 2659//2659 -f 2367//2367 2658//2658 2369//2369 -f 2369//2369 2658//2658 2657//2657 -f 2369//2369 2657//2657 2447//2447 -f 2447//2447 2657//2657 2655//2655 -f 2448//2448 2447//2447 2654//2654 -f 2654//2654 2447//2447 2655//2655 -f 2448//2448 2654//2654 2450//2450 -f 2450//2450 2654//2654 2556//2556 -f 2450//2450 2556//2556 2451//2451 -f 2451//2451 2556//2556 2554//2554 -f 2452//2452 2451//2451 2553//2553 -f 2553//2553 2451//2451 2554//2554 -f 2452//2452 2553//2553 2453//2453 -f 2453//2453 2553//2553 2609//2609 -f 2453//2453 2609//2609 2405//2405 -f 2405//2405 2609//2609 2610//2610 -f 2351//2351 2405//2405 2570//2570 -f 2570//2570 2405//2405 2610//2610 -f 2351//2351 2570//2570 2352//2352 -f 2352//2352 2570//2570 2539//2539 -f 2352//2352 2539//2539 2428//2428 -f 2428//2428 2539//2539 2537//2537 -f 2428//2428 2537//2537 2427//2427 -f 2427//2427 2537//2537 2536//2536 -f 2425//2425 2427//2427 2547//2547 -f 2547//2547 2427//2427 2536//2536 -f 2425//2425 2547//2547 2502//2502 -f 2425//2425 2502//2502 2424//2424 -f 2424//2424 2502//2502 2501//2501 -f 2424//2424 2501//2501 2423//2423 -f 2423//2423 2501//2501 2500//2500 -f 2423//2423 2500//2500 2288//2288 -f 2289//2289 2288//2288 2543//2543 -f 2543//2543 2288//2288 2500//2500 -f 2290//2290 2289//2289 2544//2544 -f 2544//2544 2289//2289 2543//2543 -f 2290//2290 2544//2544 2426//2426 -f 2426//2426 2544//2544 2545//2545 -f 2426//2426 2545//2545 2354//2354 -f 2354//2354 2545//2545 2546//2546 -f 2354//2354 2546//2546 2327//2327 -f 2327//2327 2546//2546 2548//2548 -f 2328//2328 2327//2327 2549//2549 -f 2549//2549 2327//2327 2548//2548 -f 2329//2329 2328//2328 2538//2538 -f 2538//2538 2328//2328 2549//2549 -f 2329//2329 2538//2538 2584//2584 -f 2329//2329 2584//2584 2422//2422 -f 2422//2422 2584//2584 2585//2585 -f 2422//2422 2585//2585 2421//2421 -f 2421//2421 2585//2585 2575//2575 -f 2421//2421 2575//2575 2390//2390 -f 2392//2392 2390//2390 2577//2577 -f 2577//2577 2390//2390 2575//2575 -f 2391//2391 2392//2392 2576//2576 -f 2576//2576 2392//2392 2577//2577 -f 2391//2391 2576//2576 2389//2389 -f 2389//2389 2576//2576 2574//2574 -f 2389//2389 2574//2574 2417//2417 -f 2417//2417 2574//2574 2572//2572 -f 2417//2417 2572//2572 2401//2401 -f 2401//2401 2572//2572 2530//2530 -f 2399//2399 2401//2401 2529//2529 -f 2529//2529 2401//2401 2530//2530 -f 2400//2400 2399//2399 2528//2528 -f 2528//2528 2399//2399 2529//2529 -f 2400//2400 2528//2528 2542//2542 -f 2400//2400 2542//2542 2402//2402 -f 2402//2402 2542//2542 2541//2541 -f 2402//2402 2541//2541 2418//2418 -f 2418//2418 2541//2541 2540//2540 -f 2418//2418 2540//2540 2387//2387 -f 2388//2388 2387//2387 2571//2571 -f 2571//2571 2387//2387 2540//2540 -f 2388//2388 2571//2571 2419//2419 -f 2419//2419 2571//2571 2573//2573 -f 2419//2419 2573//2573 2420//2420 -f 2420//2420 2573//2573 2586//2586 -f 2420//2420 2586//2586 2403//2403 -f 2403//2403 2586//2586 2583//2583 -f 2404//2404 2403//2403 2582//2582 -f 2582//2582 2403//2403 2583//2583 -f 2404//2404 2582//2582 2353//2353 -f 2353//2353 2582//2582 2569//2569 -f 2353//2353 2569//2569 2393//2393 -f 2393//2393 2569//2569 2608//2608 -f 2394//2394 2393//2393 2607//2607 -f 2607//2607 2393//2393 2608//2608 -f 2394//2394 2607//2607 2396//2396 -f 2396//2396 2607//2607 2606//2606 -f 2396//2396 2606//2606 2434//2434 -f 2434//2434 2606//2606 2604//2604 -f 2435//2435 2434//2434 2602//2602 -f 2602//2602 2434//2434 2604//2604 -f 2435//2435 2602//2602 2437//2437 -f 2437//2437 2602//2602 2601//2601 -f 2437//2437 2601//2601 2438//2438 -f 2438//2438 2601//2601 2563//2563 -f 2439//2439 2438//2438 2562//2562 -f 2562//2562 2438//2438 2563//2563 -f 2439//2439 2562//2562 2385//2385 -f 2385//2385 2562//2562 2566//2566 -f 2385//2385 2566//2566 2398//2398 -f 2398//2398 2566//2566 2588//2588 -f 2359//2359 2398//2398 2587//2587 -f 2587//2587 2398//2398 2588//2588 -f 2359//2359 2587//2587 2315//2315 -f 2315//2315 2587//2587 2612//2612 -f 2315//2315 2612//2612 2316//2316 -f 2316//2316 2612//2612 2611//2611 -f 2316//2316 2611//2611 2336//2336 -f 2336//2336 2611//2611 2506//2506 -f 2319//2319 2336//2336 2504//2504 -f 2504//2504 2336//2336 2506//2506 -f 2319//2319 2504//2504 2503//2503 -f 2319//2319 2503//2503 2318//2318 -f 2318//2318 2503//2503 2482//2482 -f 2318//2318 2482//2482 2317//2317 -f 2317//2317 2482//2482 2480//2480 -f 2317//2317 2480//2480 2301//2301 -f 2302//2302 2301//2301 2479//2479 -f 2479//2479 2301//2301 2480//2480 -f 2303//2303 2302//2302 2481//2481 -f 2481//2481 2302//2302 2479//2479 -f 2303//2303 2481//2481 2337//2337 -f 2337//2337 2481//2481 2505//2505 -f 2337//2337 2505//2505 2338//2338 -f 2338//2338 2505//2505 2507//2507 -f 2338//2338 2507//2507 2339//2339 -f 2339//2339 2507//2507 2509//2509 -f 2340//2340 2339//2339 2510//2510 -f 2510//2510 2339//2339 2509//2509 -f 2314//2314 2340//2340 2508//2508 -f 2508//2508 2340//2340 2510//2510 -f 2314//2314 2508//2508 2613//2613 -f 2314//2314 2613//2613 2416//2416 -f 2416//2416 2613//2613 2614//2614 -f 2416//2416 2614//2614 2357//2357 -f 2357//2357 2614//2614 2560//2560 -f 2357//2357 2560//2560 2358//2358 -f 2373//2373 2358//2358 2559//2559 -f 2559//2559 2358//2358 2560//2560 -f 2372//2372 2373//2373 2558//2558 -f 2558//2558 2373//2373 2559//2559 -f 2372//2372 2558//2558 2310//2310 -f 2310//2310 2558//2558 2590//2590 -f 2310//2310 2590//2590 2309//2309 -f 2309//2309 2590//2590 2595//2595 -f 2309//2309 2595//2595 2308//2308 -f 2308//2308 2595//2595 2485//2485 -f 2307//2307 2308//2308 2487//2487 -f 2487//2487 2308//2308 2485//2485 -f 2285//2285 2307//2307 2486//2486 -f 2486//2486 2307//2307 2487//2487 -f 2285//2285 2486//2486 2484//2484 -f 2285//2285 2484//2484 2286//2286 -f 2286//2286 2484//2484 2483//2483 -f 2286//2286 2483//2483 2287//2287 -f 2287//2287 2483//2483 2594//2594 -f 2287//2287 2594//2594 2371//2371 -f 2363//2363 2371//2371 2596//2596 -f 2596//2596 2371//2371 2594//2594 -f 2363//2363 2596//2596 2364//2364 -f 2364//2364 2596//2596 2597//2597 -f 2364//2364 2597//2597 2365//2365 -f 2365//2365 2597//2597 2565//2565 -f 2365//2365 2565//2565 2386//2386 -f 2386//2386 2565//2565 2564//2564 -f 2441//2441 2386//2386 2589//2589 -f 2589//2589 2386//2386 2564//2564 -f 2441//2441 2589//2589 2440//2440 -f 2440//2440 2589//2589 2630//2630 -f 2440//2440 2630//2630 2361//2361 -f 2361//2361 2630//2630 2629//2629 -f 2362//2362 2361//2361 2628//2628 -f 2628//2628 2361//2361 2629//2629 -f 2362//2362 2628//2628 2464//2464 -f 2464//2464 2628//2628 2627//2627 -f 2464//2464 2627//2627 2465//2465 -f 2465//2465 2627//2627 2625//2625 -f 2467//2467 2465//2465 2623//2623 -f 2623//2623 2465//2465 2625//2625 -f 2467//2467 2623//2623 2469//2469 -f 2469//2469 2623//2623 2622//2622 -f 2469//2469 2622//2622 2470//2470 -f 2470//2470 2622//2622 2600//2600 -f 2471//2471 2470//2470 2599//2599 -f 2599//2599 2470//2470 2600//2600 -f 2471//2471 2599//2599 2472//2472 -f 2472//2472 2599//2599 2652//2652 -f 2472//2472 2652//2652 2415//2415 -f 2415//2415 2652//2652 2653//2653 -f 2376//2376 2415//2415 2616//2616 -f 2616//2616 2415//2415 2653//2653 -f 2376//2376 2616//2616 2377//2377 -f 2377//2377 2616//2616 2512//2512 -f 2377//2377 2512//2512 2433//2433 -f 2433//2433 2512//2512 2511//2511 -f 2433//2433 2511//2511 2432//2432 -f 2432//2432 2511//2511 2524//2524 -f 2430//2430 2432//2432 2475//2475 -f 2475//2475 2432//2432 2524//2524 -f 2430//2430 2475//2475 2474//2474 -f 2430//2430 2474//2474 2296//2296 -f 2296//2296 2474//2474 2473//2473 -f 2296//2296 2473//2473 2297//2297 -f 2297//2297 2473//2473 2490//2490 -f 2297//2297 2490//2490 2299//2299 -f 2300//2300 2299//2299 2489//2489 -f 2489//2489 2299//2299 2490//2490 -f 2298//2298 2300//2300 2488//2488 -f 2488//2488 2300//2300 2489//2489 -f 2298//2298 2488//2488 2431//2431 -f 2431//2431 2488//2488 2532//2532 -f 2431//2431 2532//2532 2341//2341 -f 2341//2341 2532//2532 2533//2533 -f 2341//2341 2533//2533 2304//2304 -f 2304//2304 2533//2533 2534//2534 -f 2305//2305 2304//2304 2535//2535 -f 2535//2535 2304//2304 2534//2534 -f 2306//2306 2305//2305 2513//2513 -f 2513//2513 2305//2305 2535//2535 -f 2306//2306 2513//2513 2567//2567 -f 2306//2306 2567//2567 2446//2446 -f 2446//2446 2567//2567 2635//2635 -f 2446//2446 2635//2635 2445//2445 -f 2445//2445 2635//2635 2497//2497 -f 2445//2445 2497//2497 2322//2322 -f 2320//2320 2322//2322 2523//2523 -f 2523//2523 2322//2322 2497//2497 -f 2321//2321 2320//2320 2522//2522 -f 2522//2522 2320//2320 2523//2523 -f 2321//2321 2522//2522 2323//2323 -f 2323//2323 2522//2522 2521//2521 -f 2323//2323 2521//2521 2295//2295 -f 2295//2295 2521//2521 2520//2520 -f 2295//2295 2520//2520 2293//2293 -f 2293//2293 2520//2520 2478//2478 -f 2291//2291 2293//2293 2477//2477 -f 2477//2477 2293//2293 2478//2478 -f 2292//2292 2291//2291 2476//2476 -f 2476//2476 2291//2291 2477//2477 -f 2292//2292 2476//2476 2491//2491 -f 2292//2292 2491//2491 2294//2294 -f 2294//2294 2491//2491 2492//2492 -f 2294//2294 2492//2492 2330//2330 -f 2330//2330 2492//2492 2493//2493 -f 2330//2330 2493//2493 2331//2331 -f 2332//2332 2331//2331 2519//2519 -f 2519//2519 2331//2331 2493//2493 -f 2332//2332 2519//2519 2443//2443 -f 2443//2443 2519//2519 2499//2499 -f 2443//2443 2499//2499 2444//2444 -f 2444//2444 2499//2499 2498//2498 -f 2444//2444 2498//2498 2413//2413 -f 2413//2413 2498//2498 2568//2568 -f 2414//2414 2413//2413 2631//2631 -f 2631//2631 2413//2413 2568//2568 -f 2414//2414 2631//2631 2378//2378 -f 2378//2378 2631//2631 2615//2615 -f 2378//2378 2615//2615 2383//2383 -f 2383//2383 2615//2615 2651//2651 -f 2384//2384 2383//2383 2650//2650 -f 2650//2650 2383//2383 2651//2651 -f 2384//2384 2650//2650 2454//2454 -f 2454//2454 2650//2650 2649//2649 -f 2454//2454 2649//2649 2455//2455 -f 2455//2455 2649//2649 2647//2647 -f 2457//2457 2455//2455 2646//2646 -f 2646//2646 2455//2455 2647//2647 -f 2457//2457 2646//2646 2459//2459 -f 2459//2459 2646//2646 2620//2620 -f 2459//2459 2620//2620 2460//2460 -f 2460//2460 2620//2620 2618//2618 -f 2461//2461 2460//2460 2617//2617 -f 2617//2617 2460//2460 2618//2618 -f 2461//2461 2617//2617 2406//2406 -f 2406//2406 2617//2617 2552//2552 -f 2406//2406 2552//2552 2429//2429 -f 2429//2429 2552//2552 2633//2633 -f 2375//2375 2429//2429 2632//2632 -f 2632//2632 2429//2429 2633//2633 -f 2375//2375 2632//2632 2380//2380 -f 2380//2380 2632//2632 2637//2637 -f 2380//2380 2637//2637 2381//2381 -f 2381//2381 2637//2637 2636//2636 -f 2381//2381 2636//2636 2408//2408 -f 2408//2408 2636//2636 2593//2593 -f 2348//2348 2408//2408 2592//2592 -f 2592//2592 2408//2408 2593//2593 -f 2348//2348 2592//2592 2591//2591 -f 2348//2348 2591//2591 2349//2349 -f 2349//2349 2591//2591 2517//2517 -f 2349//2349 2517//2517 2350//2350 -f 2350//2350 2517//2517 2515//2515 -f 2350//2350 2515//2515 2333//2333 -f 2334//2334 2333//2333 2514//2514 -f 2514//2514 2333//2333 2515//2515 -f 2335//2335 2334//2334 2516//2516 -f 2516//2516 2334//2334 2514//2514 -f 2335//2335 2516//2516 2409//2409 -f 2409//2409 2516//2516 2518//2518 -f 2409//2409 2518//2518 2410//2410 -f 2410//2410 2518//2518 2581//2581 -f 2410//2410 2581//2581 2411//2411 -f 2411//2411 2581//2581 2579//2579 -f 2412//2412 2411//2411 2578//2578 -f 2578//2578 2411//2411 2579//2579 -f 2379//2379 2412//2412 2580//2580 -f 2580//2580 2412//2412 2578//2578 -f 2379//2379 2580//2580 2638//2638 -f 2379//2379 2638//2638 2442//2442 -f 2442//2442 2638//2638 2639//2639 -f 2442//2442 2639//2639 2374//2374 -f 2374//2374 2639//2639 2496//2496 -f 2374//2374 2496//2496 2313//2313 -f 2326//2326 2313//2313 2495//2495 -f 2495//2495 2313//2313 2496//2496 -f 2325//2325 2326//2326 2494//2494 -f 2494//2494 2326//2326 2495//2495 -f 2325//2325 2494//2494 2324//2324 -f 2324//2324 2494//2494 2531//2531 -f 2324//2324 2531//2531 2355//2355 -f 2355//2355 2531//2531 2643//2643 -f 2355//2355 2643//2643 2346//2346 -f 2346//2346 2643//2643 2527//2527 -f 2344//2344 2346//2346 2526//2526 -f 2526//2526 2346//2346 2527//2527 -f 2370//2370 2557//2557 2368//2368 -f 2368//2368 2557//2557 2656//2656 -f 2368//2368 2656//2656 2458//2458 -f 2458//2458 2656//2656 2619//2619 -f 2458//2458 2619//2619 2456//2456 -f 2456//2456 2619//2619 2621//2621 -f 2456//2456 2621//2621 2382//2382 -f 2382//2382 2621//2621 2648//2648 -f 2382//2382 2648//2648 2468//2468 -f 2468//2468 2648//2648 2598//2598 -f 2468//2468 2598//2598 2466//2466 -f 2466//2466 2598//2598 2624//2624 -f 2466//2466 2624//2624 2360//2360 -f 2360//2360 2624//2624 2626//2626 -f 2360//2360 2626//2626 2436//2436 -f 2436//2436 2626//2626 2561//2561 -f 2436//2436 2561//2561 2397//2397 -f 2397//2397 2561//2561 2603//2603 -f 2397//2397 2603//2603 2395//2395 -f 2395//2395 2603//2603 2605//2605 -f 2395//2395 2605//2605 2449//2449 -f 2449//2449 2605//2605 2555//2555 -f 2449//2449 2555//2555 2370//2370 -f 2370//2370 2555//2555 2557//2557 -f 2661//2661 2662//2662 2663//2663 -f 2664//2664 2665//2665 2666//2666 -f 2667//2667 2668//2668 2669//2669 -f 2669//2669 2668//2668 2670//2670 -f 2669//2669 2670//2670 2671//2671 -f 2672//2672 2673//2673 2674//2674 -f 2674//2674 2673//2673 2675//2675 -f 2674//2674 2675//2675 2676//2676 -f 2677//2677 2678//2678 2679//2679 -f 2680//2680 2681//2681 2682//2682 -f 2683//2683 2661//2661 2684//2684 -f 2684//2684 2661//2661 2663//2663 -f 2684//2684 2663//2663 2685//2685 -f 2685//2685 2663//2663 2686//2686 -f 2687//2687 2688//2688 2689//2689 -f 2690//2690 2691//2691 2692//2692 -f 2693//2693 2677//2677 2694//2694 -f 2694//2694 2677//2677 2679//2679 -f 2694//2694 2679//2679 2695//2695 -f 2696//2696 2697//2697 2698//2698 -f 2698//2698 2697//2697 2699//2699 -f 2700//2700 2689//2689 2701//2701 -f 2701//2701 2689//2689 2702//2702 -f 2703//2703 2704//2704 2705//2705 -f 2670//2670 2706//2706 2671//2671 -f 2671//2671 2706//2706 2707//2707 -f 2671//2671 2707//2707 2699//2699 -f 2699//2699 2707//2707 2708//2708 -f 2699//2699 2708//2708 2698//2698 -f 2709//2709 2710//2710 2711//2711 -f 2695//2695 2679//2679 2712//2712 -f 2712//2712 2679//2679 2713//2713 -f 2712//2712 2713//2713 2692//2692 -f 2692//2692 2713//2713 2714//2714 -f 2692//2692 2714//2714 2690//2690 -f 2690//2690 2714//2714 2715//2715 -f 2690//2690 2715//2715 2716//2716 -f 2680//2680 2682//2682 2717//2717 -f 2687//2687 2689//2689 2718//2718 -f 2718//2718 2689//2689 2700//2700 -f 2718//2718 2700//2700 2719//2719 -f 2720//2720 2721//2721 2722//2722 -f 2722//2722 2721//2721 2723//2723 -f 2724//2724 2725//2725 2711//2711 -f 2711//2711 2725//2725 2726//2726 -f 2711//2711 2726//2726 2709//2709 -f 2727//2727 2728//2728 2729//2729 -f 2703//2703 2705//2705 2730//2730 -f 2700//2700 2731//2731 2719//2719 -f 2719//2719 2731//2731 2722//2722 -f 2719//2719 2722//2722 2732//2732 -f 2732//2732 2722//2722 2723//2723 -f 2733//2733 2734//2734 2735//2735 -f 2736//2736 2737//2737 2738//2738 -f 2739//2739 2740//2740 2734//2734 -f 2734//2734 2740//2740 2741//2741 -f 2742//2742 2743//2743 2744//2744 -f 2744//2744 2743//2743 2745//2745 -f 2744//2744 2745//2745 2746//2746 -f 2663//2663 2747//2747 2686//2686 -f 2686//2686 2747//2747 2739//2739 -f 2686//2686 2739//2739 2748//2748 -f 2748//2748 2739//2739 2734//2734 -f 2748//2748 2734//2734 2749//2749 -f 2750//2750 2689//2689 2751//2751 -f 2752//2752 2753//2753 2754//2754 -f 2755//2755 2756//2756 2757//2757 -f 2758//2758 2759//2759 2760//2760 -f 2761//2761 2741//2741 2762//2762 -f 2763//2763 2764//2764 2765//2765 -f 2765//2765 2764//2764 2766//2766 -f 2765//2765 2766//2766 2767//2767 -f 2767//2767 2766//2766 2768//2768 -f 2769//2769 2770//2770 2771//2771 -f 2771//2771 2770//2770 2772//2772 -f 2771//2771 2772//2772 2773//2773 -f 2741//2741 2761//2761 2734//2734 -f 2734//2734 2761//2761 2774//2774 -f 2734//2734 2774//2774 2735//2735 -f 2775//2775 2776//2776 2777//2777 -f 2777//2777 2776//2776 2778//2778 -f 2705//2705 2779//2779 2780//2780 -f 2727//2727 2729//2729 2781//2781 -f 2782//2782 2688//2688 2783//2783 -f 2724//2724 2711//2711 2784//2784 -f 2784//2784 2711//2711 2785//2785 -f 2784//2784 2785//2785 2757//2757 -f 2757//2757 2785//2785 2786//2786 -f 2757//2757 2786//2786 2755//2755 -f 2755//2755 2786//2786 2787//2787 -f 2755//2755 2787//2787 2788//2788 -f 2682//2682 2789//2789 2790//2790 -f 2752//2752 2754//2754 2791//2791 -f 2691//2691 2690//2690 2735//2735 -f 2735//2735 2690//2690 2792//2792 -f 2735//2735 2792//2792 2733//2733 -f 2765//2765 2793//2793 2763//2763 -f 2763//2763 2793//2793 2777//2777 -f 2763//2763 2777//2777 2794//2794 -f 2794//2794 2777//2777 2778//2778 -f 2764//2764 2795//2795 2766//2766 -f 2766//2766 2795//2795 2796//2796 -f 2766//2766 2796//2796 2797//2797 -f 2797//2797 2796//2796 2779//2779 -f 2797//2797 2779//2779 2798//2798 -f 2798//2798 2779//2779 2705//2705 -f 2799//2799 2664//2664 2800//2800 -f 2800//2800 2664//2664 2666//2666 -f 2800//2800 2666//2666 2801//2801 -f 2801//2801 2666//2666 2802//2802 -f 2801//2801 2802//2802 2803//2803 -f 2803//2803 2802//2802 2730//2730 -f 2803//2803 2730//2730 2804//2804 -f 2804//2804 2730//2730 2705//2705 -f 2804//2804 2705//2705 2728//2728 -f 2728//2728 2705//2705 2780//2780 -f 2728//2728 2780//2780 2729//2729 -f 2688//2688 2782//2782 2689//2689 -f 2689//2689 2782//2782 2805//2805 -f 2689//2689 2805//2805 2751//2751 -f 2672//2672 2674//2674 2806//2806 -f 2806//2806 2674//2674 2807//2807 -f 2806//2806 2807//2807 2808//2808 -f 2808//2808 2807//2807 2717//2717 -f 2808//2808 2717//2717 2809//2809 -f 2809//2809 2717//2717 2682//2682 -f 2809//2809 2682//2682 2753//2753 -f 2753//2753 2682//2682 2790//2790 -f 2753//2753 2790//2790 2754//2754 -f 2772//2772 2810//2810 2773//2773 -f 2773//2773 2810//2810 2811//2811 -f 2773//2773 2811//2811 2812//2812 -f 2812//2812 2811//2811 2813//2813 -f 2812//2812 2813//2813 2736//2736 -f 2736//2736 2813//2813 2814//2814 -f 2736//2736 2814//2814 2737//2737 -f 2737//2737 2814//2814 2815//2815 -f 2737//2737 2815//2815 2816//2816 -f 2816//2816 2815//2815 2761//2761 -f 2816//2816 2761//2761 2817//2817 -f 2817//2817 2761//2761 2762//2762 -f 2756//2756 2755//2755 2751//2751 -f 2751//2751 2755//2755 2818//2818 -f 2751//2751 2818//2818 2750//2750 -f 2708//2708 2819//2819 2698//2698 -f 2698//2698 2819//2819 2820//2820 -f 2698//2698 2820//2820 2821//2821 -f 2821//2821 2820//2820 2789//2789 -f 2821//2821 2789//2789 2822//2822 -f 2822//2822 2789//2789 2682//2682 -f 2745//2745 2823//2823 2746//2746 -f 2746//2746 2823//2823 2824//2824 -f 2746//2746 2824//2824 2825//2825 -f 2825//2825 2824//2824 2826//2826 -f 2825//2825 2826//2826 2771//2771 -f 2771//2771 2826//2826 2827//2827 -f 2771//2771 2827//2827 2769//2769 -f 2769//2769 2827//2827 2828//2828 -f 2769//2769 2828//2828 2729//2729 -f 2729//2729 2828//2828 2829//2829 -f 2729//2729 2829//2829 2781//2781 -f 2760//2760 2830//2830 2758//2758 -f 2758//2758 2830//2830 2831//2831 -f 2758//2758 2831//2831 2832//2832 -f 2832//2832 2831//2831 2833//2833 -f 2832//2832 2833//2833 2834//2834 -f 2834//2834 2833//2833 2835//2835 -f 2834//2834 2835//2835 2744//2744 -f 2744//2744 2835//2835 2836//2836 -f 2744//2744 2836//2836 2742//2742 -f 2742//2742 2836//2836 2837//2837 -f 2742//2742 2837//2837 2838//2838 -f 2838//2838 2837//2837 2782//2782 -f 2838//2838 2782//2782 2839//2839 -f 2839//2839 2782//2782 2783//2783 -f 2738//2738 2840//2840 2736//2736 -f 2736//2736 2840//2840 2841//2841 -f 2736//2736 2841//2841 2842//2842 -f 2842//2842 2841//2841 2843//2843 -f 2842//2842 2843//2843 2844//2844 -f 2844//2844 2843//2843 2845//2845 -f 2844//2844 2845//2845 2758//2758 -f 2758//2758 2845//2845 2846//2846 -f 2758//2758 2846//2846 2759//2759 -f 2759//2759 2846//2846 2847//2847 -f 2759//2759 2847//2847 2754//2754 -f 2754//2754 2847//2847 2848//2848 -f 2754//2754 2848//2848 2791//2791 -f 2849//2849 2850//2850 2851//2851 -f 2852//2852 2853//2853 2854//2854 -f 2855//2855 2856//2856 2857//2857 -f 2857//2857 2856//2856 2858//2858 -f 2859//2859 2860//2860 2861//2861 -f 2861//2861 2860//2860 2862//2862 -f 2861//2861 2862//2862 2863//2863 -f 2864//2864 2865//2865 2866//2866 -f 2867//2867 2852//2852 2868//2868 -f 2868//2868 2852//2852 2854//2854 -f 2868//2868 2854//2854 2869//2869 -f 2870//2870 2871//2871 2872//2872 -f 2873//2873 2874//2874 2875//2875 -f 2876//2876 2877//2877 2878//2878 -f 2858//2858 2879//2879 2857//2857 -f 2857//2857 2879//2879 2880//2880 -f 2857//2857 2880//2880 2881//2881 -f 2881//2881 2880//2880 2882//2882 -f 2881//2881 2882//2882 2883//2883 -f 2883//2883 2882//2882 2884//2884 -f 2883//2883 2884//2884 2885//2885 -f 2885//2885 2884//2884 2886//2886 -f 2887//2887 2888//2888 2889//2889 -f 2890//2890 2891//2891 2892//2892 -f 2892//2892 2891//2891 2893//2893 -f 2892//2892 2893//2893 2894//2894 -f 2869//2869 2854//2854 2895//2895 -f 2895//2895 2854//2854 2896//2896 -f 2895//2895 2896//2896 2875//2875 -f 2875//2875 2896//2896 2897//2897 -f 2875//2875 2897//2897 2873//2873 -f 2873//2873 2897//2897 2898//2898 -f 2873//2873 2898//2898 2899//2899 -f 2887//2887 2889//2889 2900//2900 -f 2901//2901 2902//2902 2903//2903 -f 2904//2904 2905//2905 2906//2906 -f 2870//2870 2872//2872 2907//2907 -f 2866//2866 2849//2849 2864//2864 -f 2864//2864 2849//2849 2851//2851 -f 2864//2864 2851//2851 2908//2908 -f 2908//2908 2851//2851 2900//2900 -f 2908//2908 2900//2900 2909//2909 -f 2909//2909 2900//2900 2889//2889 -f 2909//2909 2889//2889 2910//2910 -f 2910//2910 2889//2889 2911//2911 -f 2912//2912 2913//2913 2914//2914 -f 2914//2914 2913//2913 2915//2915 -f 2916//2916 2917//2917 2906//2906 -f 2906//2906 2917//2917 2918//2918 -f 2906//2906 2918//2918 2904//2904 -f 2919//2919 2876//2876 2920//2920 -f 2920//2920 2876//2876 2878//2878 -f 2920//2920 2878//2878 2921//2921 -f 2921//2921 2878//2878 2922//2922 -f 2878//2878 2923//2923 2922//2922 -f 2922//2922 2923//2923 2912//2912 -f 2922//2922 2912//2912 2924//2924 -f 2924//2924 2912//2912 2914//2914 -f 2924//2924 2914//2914 2925//2925 -f 2926//2926 2927//2927 2928//2928 -f 2929//2929 2930//2930 2931//2931 -f 2931//2931 2930//2930 2932//2932 -f 2931//2931 2932//2932 2933//2933 -f 2934//2934 2935//2935 2936//2936 -f 2937//2937 2938//2938 2939//2939 -f 2940//2940 2941//2941 2942//2942 -f 2943//2943 2889//2889 2944//2944 -f 2945//2945 2915//2915 2946//2946 -f 2916//2916 2906//2906 2947//2947 -f 2947//2947 2906//2906 2948//2948 -f 2947//2947 2948//2948 2949//2949 -f 2949//2949 2948//2948 2950//2950 -f 2949//2949 2950//2950 2951//2951 -f 2951//2951 2950//2950 2952//2952 -f 2951//2951 2952//2952 2953//2953 -f 2954//2954 2955//2955 2956//2956 -f 2956//2956 2955//2955 2957//2957 -f 2915//2915 2945//2945 2914//2914 -f 2914//2914 2945//2945 2958//2958 -f 2914//2914 2958//2958 2959//2959 -f 2960//2960 2914//2914 2961//2961 -f 2961//2961 2914//2914 2959//2959 -f 2961//2961 2959//2959 2951//2951 -f 2951//2951 2959//2959 2962//2962 -f 2951//2951 2962//2962 2949//2949 -f 2936//2936 2963//2963 2964//2964 -f 2940//2940 2942//2942 2965//2965 -f 2934//2934 2936//2936 2966//2966 -f 2893//2893 2967//2967 2894//2894 -f 2894//2894 2967//2967 2968//2968 -f 2894//2894 2968//2968 2957//2957 -f 2957//2957 2968//2968 2969//2969 -f 2957//2957 2969//2969 2956//2956 -f 2859//2859 2861//2861 2970//2970 -f 2970//2970 2861//2861 2971//2971 -f 2970//2970 2971//2971 2972//2972 -f 2972//2972 2971//2971 2966//2966 -f 2972//2972 2966//2966 2973//2973 -f 2973//2973 2966//2966 2936//2936 -f 2973//2973 2936//2936 2941//2941 -f 2941//2941 2936//2936 2964//2964 -f 2941//2941 2964//2964 2942//2942 -f 2974//2974 2975//2975 2976//2976 -f 2939//2939 2977//2977 2937//2937 -f 2937//2937 2977//2977 2978//2978 -f 2937//2937 2978//2978 2979//2979 -f 2979//2979 2978//2978 2980//2980 -f 2979//2979 2980//2980 2981//2981 -f 2981//2981 2980//2980 2982//2982 -f 2981//2981 2982//2982 2931//2931 -f 2931//2931 2982//2982 2983//2983 -f 2931//2931 2983//2983 2929//2929 -f 2929//2929 2983//2983 2984//2984 -f 2929//2929 2984//2984 2985//2985 -f 2985//2985 2984//2984 2945//2945 -f 2985//2985 2945//2945 2986//2986 -f 2986//2986 2945//2945 2946//2946 -f 2882//2882 2987//2987 2884//2884 -f 2884//2884 2987//2987 2988//2988 -f 2884//2884 2988//2988 2989//2989 -f 2989//2989 2988//2988 2963//2963 -f 2989//2989 2963//2963 2990//2990 -f 2990//2990 2963//2963 2936//2936 -f 2991//2991 2888//2888 2992//2992 -f 2993//2993 2994//2994 2995//2995 -f 2995//2995 2994//2994 2996//2996 -f 2995//2995 2996//2996 2997//2997 -f 2976//2976 2998//2998 2974//2974 -f 2974//2974 2998//2998 2999//2999 -f 2974//2974 2999//2999 3000//3000 -f 3000//3000 2999//2999 3001//3001 -f 3000//3000 3001//3001 3002//3002 -f 3002//3002 3001//3001 3003//3003 -f 3002//3002 3003//3003 2937//2937 -f 2937//2937 3003//3003 3004//3004 -f 2937//2937 3004//3004 2938//2938 -f 2938//2938 3004//3004 3005//3005 -f 2938//2938 3005//3005 2942//2942 -f 2942//2942 3005//3005 3006//3006 -f 2942//2942 3006//3006 2965//2965 -f 2888//2888 2991//2991 2889//2889 -f 2889//2889 2991//2991 3007//3007 -f 2889//2889 3007//3007 2944//2944 -f 2872//2872 3008//3008 3009//3009 -f 2926//2926 2928//2928 3010//3010 -f 2874//2874 2873//2873 2944//2944 -f 2944//2944 2873//2873 3011//3011 -f 2944//2944 3011//3011 2943//2943 -f 2969//2969 3012//3012 2956//2956 -f 2956//2956 3012//3012 3013//3013 -f 2956//2956 3013//3013 3014//3014 -f 3014//3014 3013//3013 3008//3008 -f 3014//3014 3008//3008 3015//3015 -f 3015//3015 3008//3008 2872//2872 -f 3016//3016 2901//2901 3017//3017 -f 3017//3017 2901//2901 2903//2903 -f 3017//3017 2903//2903 3018//3018 -f 3018//3018 2903//2903 3019//3019 -f 3018//3018 3019//3019 3020//3020 -f 3020//3020 3019//3019 2907//2907 -f 3020//3020 2907//2907 3021//3021 -f 3021//3021 2907//2907 2872//2872 -f 3021//3021 2872//2872 2927//2927 -f 2927//2927 2872//2872 3009//3009 -f 2927//2927 3009//3009 2928//2928 -f 2996//2996 3022//3022 2997//2997 -f 2997//2997 3022//3022 3023//3023 -f 2997//2997 3023//3023 3024//3024 -f 3024//3024 3023//3023 3025//3025 -f 3024//3024 3025//3025 2974//2974 -f 2974//2974 3025//3025 3026//3026 -f 2974//2974 3026//3026 2975//2975 -f 2975//2975 3026//3026 3027//3027 -f 2975//2975 3027//3027 3028//3028 -f 3028//3028 3027//3027 2991//2991 -f 3028//3028 2991//2991 3029//3029 -f 3029//3029 2991//2991 2992//2992 -f 2932//2932 3030//3030 2933//2933 -f 2933//2933 3030//3030 3031//3031 -f 2933//2933 3031//3031 3032//3032 -f 3032//3032 3031//3031 3033//3033 -f 3032//3032 3033//3033 2995//2995 -f 2995//2995 3033//3033 3034//3034 -f 2995//2995 3034//3034 2993//2993 -f 2993//2993 3034//3034 3035//3035 -f 2993//2993 3035//3035 2928//2928 -f 2928//2928 3035//3035 3036//3036 -f 2928//2928 3036//3036 3010//3010 -f 2721//2721 2720//2720 2901//2901 -f 2901//2901 2720//2720 2902//2902 -f 2721//2721 2901//2901 3016//3016 -f 2721//2721 3016//3016 2723//2723 -f 2723//2723 3016//3016 3017//3017 -f 2723//2723 3017//3017 2732//2732 -f 2732//2732 3017//3017 3018//3018 -f 2732//2732 3018//3018 2719//2719 -f 2718//2718 2719//2719 3020//3020 -f 3020//3020 2719//2719 3018//3018 -f 2718//2718 3020//3020 2687//2687 -f 2687//2687 3020//3020 3021//3021 -f 2687//2687 3021//3021 2688//2688 -f 2688//2688 3021//3021 2927//2927 -f 2688//2688 2927//2927 2783//2783 -f 2783//2783 2927//2927 2926//2926 -f 2839//2839 2783//2783 3010//3010 -f 3010//3010 2783//2783 2926//2926 -f 2839//2839 3010//3010 2838//2838 -f 2838//2838 3010//3010 3036//3036 -f 2838//2838 3036//3036 2742//2742 -f 2742//2742 3036//3036 3035//3035 -f 2743//2743 2742//2742 3034//3034 -f 3034//3034 2742//2742 3035//3035 -f 2743//2743 3034//3034 2745//2745 -f 2745//2745 3034//3034 3033//3033 -f 2745//2745 3033//3033 2823//2823 -f 2823//2823 3033//3033 3031//3031 -f 2824//2824 2823//2823 3030//3030 -f 3030//3030 2823//2823 3031//3031 -f 2824//2824 3030//3030 2826//2826 -f 2826//2826 3030//3030 2932//2932 -f 2826//2826 2932//2932 2827//2827 -f 2827//2827 2932//2932 2930//2930 -f 2828//2828 2827//2827 2929//2929 -f 2929//2929 2827//2827 2930//2930 -f 2828//2828 2929//2929 2829//2829 -f 2829//2829 2929//2929 2985//2985 -f 2829//2829 2985//2985 2781//2781 -f 2781//2781 2985//2985 2986//2986 -f 2727//2727 2781//2781 2946//2946 -f 2946//2946 2781//2781 2986//2986 -f 2727//2727 2946//2946 2728//2728 -f 2728//2728 2946//2946 2915//2915 -f 2728//2728 2915//2915 2804//2804 -f 2804//2804 2915//2915 2913//2913 -f 2804//2804 2913//2913 2803//2803 -f 2803//2803 2913//2913 2912//2912 -f 2801//2801 2803//2803 2923//2923 -f 2923//2923 2803//2803 2912//2912 -f 2801//2801 2923//2923 2878//2878 -f 2801//2801 2878//2878 2800//2800 -f 2800//2800 2878//2878 2877//2877 -f 2800//2800 2877//2877 2799//2799 -f 2799//2799 2877//2877 2876//2876 -f 2799//2799 2876//2876 2664//2664 -f 2665//2665 2664//2664 2919//2919 -f 2919//2919 2664//2664 2876//2876 -f 2666//2666 2665//2665 2920//2920 -f 2920//2920 2665//2665 2919//2919 -f 2666//2666 2920//2920 2802//2802 -f 2802//2802 2920//2920 2921//2921 -f 2802//2802 2921//2921 2730//2730 -f 2730//2730 2921//2921 2922//2922 -f 2730//2730 2922//2922 2703//2703 -f 2703//2703 2922//2922 2924//2924 -f 2704//2704 2703//2703 2925//2925 -f 2925//2925 2703//2703 2924//2924 -f 2705//2705 2704//2704 2914//2914 -f 2914//2914 2704//2704 2925//2925 -f 2705//2705 2914//2914 2960//2960 -f 2705//2705 2960//2960 2798//2798 -f 2798//2798 2960//2960 2961//2961 -f 2798//2798 2961//2961 2797//2797 -f 2797//2797 2961//2961 2951//2951 -f 2797//2797 2951//2951 2766//2766 -f 2768//2768 2766//2766 2953//2953 -f 2953//2953 2766//2766 2951//2951 -f 2767//2767 2768//2768 2952//2952 -f 2952//2952 2768//2768 2953//2953 -f 2767//2767 2952//2952 2765//2765 -f 2765//2765 2952//2952 2950//2950 -f 2765//2765 2950//2950 2793//2793 -f 2793//2793 2950//2950 2948//2948 -f 2793//2793 2948//2948 2777//2777 -f 2777//2777 2948//2948 2906//2906 -f 2775//2775 2777//2777 2905//2905 -f 2905//2905 2777//2777 2906//2906 -f 2776//2776 2775//2775 2904//2904 -f 2904//2904 2775//2775 2905//2905 -f 2776//2776 2904//2904 2918//2918 -f 2776//2776 2918//2918 2778//2778 -f 2778//2778 2918//2918 2917//2917 -f 2778//2778 2917//2917 2794//2794 -f 2794//2794 2917//2917 2916//2916 -f 2794//2794 2916//2916 2763//2763 -f 2764//2764 2763//2763 2947//2947 -f 2947//2947 2763//2763 2916//2916 -f 2764//2764 2947//2947 2795//2795 -f 2795//2795 2947//2947 2949//2949 -f 2795//2795 2949//2949 2796//2796 -f 2796//2796 2949//2949 2962//2962 -f 2796//2796 2962//2962 2779//2779 -f 2779//2779 2962//2962 2959//2959 -f 2780//2780 2779//2779 2958//2958 -f 2958//2958 2779//2779 2959//2959 -f 2780//2780 2958//2958 2729//2729 -f 2729//2729 2958//2958 2945//2945 -f 2729//2729 2945//2945 2769//2769 -f 2769//2769 2945//2945 2984//2984 -f 2770//2770 2769//2769 2983//2983 -f 2983//2983 2769//2769 2984//2984 -f 2770//2770 2983//2983 2772//2772 -f 2772//2772 2983//2983 2982//2982 -f 2772//2772 2982//2982 2810//2810 -f 2810//2810 2982//2982 2980//2980 -f 2811//2811 2810//2810 2978//2978 -f 2978//2978 2810//2810 2980//2980 -f 2811//2811 2978//2978 2813//2813 -f 2813//2813 2978//2978 2977//2977 -f 2813//2813 2977//2977 2814//2814 -f 2814//2814 2977//2977 2939//2939 -f 2815//2815 2814//2814 2938//2938 -f 2938//2938 2814//2814 2939//2939 -f 2815//2815 2938//2938 2761//2761 -f 2761//2761 2938//2938 2942//2942 -f 2761//2761 2942//2942 2774//2774 -f 2774//2774 2942//2942 2964//2964 -f 2735//2735 2774//2774 2963//2963 -f 2963//2963 2774//2774 2964//2964 -f 2735//2735 2963//2963 2691//2691 -f 2691//2691 2963//2963 2988//2988 -f 2691//2691 2988//2988 2692//2692 -f 2692//2692 2988//2988 2987//2987 -f 2692//2692 2987//2987 2712//2712 -f 2712//2712 2987//2987 2882//2882 -f 2695//2695 2712//2712 2880//2880 -f 2880//2880 2712//2712 2882//2882 -f 2695//2695 2880//2880 2879//2879 -f 2695//2695 2879//2879 2694//2694 -f 2694//2694 2879//2879 2858//2858 -f 2694//2694 2858//2858 2693//2693 -f 2693//2693 2858//2858 2856//2856 -f 2693//2693 2856//2856 2677//2677 -f 2678//2678 2677//2677 2855//2855 -f 2855//2855 2677//2677 2856//2856 -f 2679//2679 2678//2678 2857//2857 -f 2857//2857 2678//2678 2855//2855 -f 2679//2679 2857//2857 2713//2713 -f 2713//2713 2857//2857 2881//2881 -f 2713//2713 2881//2881 2714//2714 -f 2714//2714 2881//2881 2883//2883 -f 2714//2714 2883//2883 2715//2715 -f 2715//2715 2883//2883 2885//2885 -f 2716//2716 2715//2715 2886//2886 -f 2886//2886 2715//2715 2885//2885 -f 2690//2690 2716//2716 2884//2884 -f 2884//2884 2716//2716 2886//2886 -f 2690//2690 2884//2884 2989//2989 -f 2690//2690 2989//2989 2792//2792 -f 2792//2792 2989//2989 2990//2990 -f 2792//2792 2990//2990 2733//2733 -f 2733//2733 2990//2990 2936//2936 -f 2733//2733 2936//2936 2734//2734 -f 2749//2749 2734//2734 2935//2935 -f 2935//2935 2734//2734 2936//2936 -f 2748//2748 2749//2749 2934//2934 -f 2934//2934 2749//2749 2935//2935 -f 2748//2748 2934//2934 2686//2686 -f 2686//2686 2934//2934 2966//2966 -f 2686//2686 2966//2966 2685//2685 -f 2685//2685 2966//2966 2971//2971 -f 2685//2685 2971//2971 2684//2684 -f 2684//2684 2971//2971 2861//2861 -f 2683//2683 2684//2684 2863//2863 -f 2863//2863 2684//2684 2861//2861 -f 2661//2661 2683//2683 2862//2862 -f 2862//2862 2683//2683 2863//2863 -f 2661//2661 2862//2862 2860//2860 -f 2661//2661 2860//2860 2662//2662 -f 2662//2662 2860//2860 2859//2859 -f 2662//2662 2859//2859 2663//2663 -f 2663//2663 2859//2859 2970//2970 -f 2663//2663 2970//2970 2747//2747 -f 2739//2739 2747//2747 2972//2972 -f 2972//2972 2747//2747 2970//2970 -f 2739//2739 2972//2972 2740//2740 -f 2740//2740 2972//2972 2973//2973 -f 2740//2740 2973//2973 2741//2741 -f 2741//2741 2973//2973 2941//2941 -f 2741//2741 2941//2941 2762//2762 -f 2762//2762 2941//2941 2940//2940 -f 2817//2817 2762//2762 2965//2965 -f 2965//2965 2762//2762 2940//2940 -f 2817//2817 2965//2965 2816//2816 -f 2816//2816 2965//2965 3006//3006 -f 2816//2816 3006//3006 2737//2737 -f 2737//2737 3006//3006 3005//3005 -f 2738//2738 2737//2737 3004//3004 -f 3004//3004 2737//2737 3005//3005 -f 2738//2738 3004//3004 2840//2840 -f 2840//2840 3004//3004 3003//3003 -f 2840//2840 3003//3003 2841//2841 -f 2841//2841 3003//3003 3001//3001 -f 2843//2843 2841//2841 2999//2999 -f 2999//2999 2841//2841 3001//3001 -f 2843//2843 2999//2999 2845//2845 -f 2845//2845 2999//2999 2998//2998 -f 2845//2845 2998//2998 2846//2846 -f 2846//2846 2998//2998 2976//2976 -f 2847//2847 2846//2846 2975//2975 -f 2975//2975 2846//2846 2976//2976 -f 2847//2847 2975//2975 2848//2848 -f 2848//2848 2975//2975 3028//3028 -f 2848//2848 3028//3028 2791//2791 -f 2791//2791 3028//3028 3029//3029 -f 2752//2752 2791//2791 2992//2992 -f 2992//2992 2791//2791 3029//3029 -f 2752//2752 2992//2992 2753//2753 -f 2753//2753 2992//2992 2888//2888 -f 2753//2753 2888//2888 2809//2809 -f 2809//2809 2888//2888 2887//2887 -f 2809//2809 2887//2887 2808//2808 -f 2808//2808 2887//2887 2900//2900 -f 2806//2806 2808//2808 2851//2851 -f 2851//2851 2808//2808 2900//2900 -f 2806//2806 2851//2851 2850//2850 -f 2806//2806 2850//2850 2672//2672 -f 2672//2672 2850//2850 2849//2849 -f 2672//2672 2849//2849 2673//2673 -f 2673//2673 2849//2849 2866//2866 -f 2673//2673 2866//2866 2675//2675 -f 2676//2676 2675//2675 2865//2865 -f 2865//2865 2675//2675 2866//2866 -f 2674//2674 2676//2676 2864//2864 -f 2864//2864 2676//2676 2865//2865 -f 2674//2674 2864//2864 2807//2807 -f 2807//2807 2864//2864 2908//2908 -f 2807//2807 2908//2908 2717//2717 -f 2717//2717 2908//2908 2909//2909 -f 2717//2717 2909//2909 2680//2680 -f 2680//2680 2909//2909 2910//2910 -f 2681//2681 2680//2680 2911//2911 -f 2911//2911 2680//2680 2910//2910 -f 2682//2682 2681//2681 2889//2889 -f 2889//2889 2681//2681 2911//2911 -f 2682//2682 2889//2889 2943//2943 -f 2682//2682 2943//2943 2822//2822 -f 2822//2822 2943//2943 3011//3011 -f 2822//2822 3011//3011 2821//2821 -f 2821//2821 3011//3011 2873//2873 -f 2821//2821 2873//2873 2698//2698 -f 2696//2696 2698//2698 2899//2899 -f 2899//2899 2698//2698 2873//2873 -f 2697//2697 2696//2696 2898//2898 -f 2898//2898 2696//2696 2899//2899 -f 2697//2697 2898//2898 2699//2699 -f 2699//2699 2898//2898 2897//2897 -f 2699//2699 2897//2897 2671//2671 -f 2671//2671 2897//2897 2896//2896 -f 2671//2671 2896//2896 2669//2669 -f 2669//2669 2896//2896 2854//2854 -f 2667//2667 2669//2669 2853//2853 -f 2853//2853 2669//2669 2854//2854 -f 2668//2668 2667//2667 2852//2852 -f 2852//2852 2667//2667 2853//2853 -f 2668//2668 2852//2852 2867//2867 -f 2668//2668 2867//2867 2670//2670 -f 2670//2670 2867//2867 2868//2868 -f 2670//2670 2868//2868 2706//2706 -f 2706//2706 2868//2868 2869//2869 -f 2706//2706 2869//2869 2707//2707 -f 2708//2708 2707//2707 2895//2895 -f 2895//2895 2707//2707 2869//2869 -f 2708//2708 2895//2895 2819//2819 -f 2819//2819 2895//2895 2875//2875 -f 2819//2819 2875//2875 2820//2820 -f 2820//2820 2875//2875 2874//2874 -f 2820//2820 2874//2874 2789//2789 -f 2789//2789 2874//2874 2944//2944 -f 2790//2790 2789//2789 3007//3007 -f 3007//3007 2789//2789 2944//2944 -f 2790//2790 3007//3007 2754//2754 -f 2754//2754 3007//3007 2991//2991 -f 2754//2754 2991//2991 2759//2759 -f 2759//2759 2991//2991 3027//3027 -f 2760//2760 2759//2759 3026//3026 -f 3026//3026 2759//2759 3027//3027 -f 2760//2760 3026//3026 2830//2830 -f 2830//2830 3026//3026 3025//3025 -f 2830//2830 3025//3025 2831//2831 -f 2831//2831 3025//3025 3023//3023 -f 2833//2833 2831//2831 3022//3022 -f 3022//3022 2831//2831 3023//3023 -f 2833//2833 3022//3022 2835//2835 -f 2835//2835 3022//3022 2996//2996 -f 2835//2835 2996//2996 2836//2836 -f 2836//2836 2996//2996 2994//2994 -f 2837//2837 2836//2836 2993//2993 -f 2993//2993 2836//2836 2994//2994 -f 2837//2837 2993//2993 2782//2782 -f 2782//2782 2993//2993 2928//2928 -f 2782//2782 2928//2928 2805//2805 -f 2805//2805 2928//2928 3009//3009 -f 2751//2751 2805//2805 3008//3008 -f 3008//3008 2805//2805 3009//3009 -f 2751//2751 3008//3008 2756//2756 -f 2756//2756 3008//3008 3013//3013 -f 2756//2756 3013//3013 2757//2757 -f 2757//2757 3013//3013 3012//3012 -f 2757//2757 3012//3012 2784//2784 -f 2784//2784 3012//3012 2969//2969 -f 2724//2724 2784//2784 2968//2968 -f 2968//2968 2784//2784 2969//2969 -f 2724//2724 2968//2968 2967//2967 -f 2724//2724 2967//2967 2725//2725 -f 2725//2725 2967//2967 2893//2893 -f 2725//2725 2893//2893 2726//2726 -f 2726//2726 2893//2893 2891//2891 -f 2726//2726 2891//2891 2709//2709 -f 2710//2710 2709//2709 2890//2890 -f 2890//2890 2709//2709 2891//2891 -f 2711//2711 2710//2710 2892//2892 -f 2892//2892 2710//2710 2890//2890 -f 2711//2711 2892//2892 2785//2785 -f 2785//2785 2892//2892 2894//2894 -f 2785//2785 2894//2894 2786//2786 -f 2786//2786 2894//2894 2957//2957 -f 2786//2786 2957//2957 2787//2787 -f 2787//2787 2957//2957 2955//2955 -f 2788//2788 2787//2787 2954//2954 -f 2954//2954 2787//2787 2955//2955 -f 2755//2755 2788//2788 2956//2956 -f 2956//2956 2788//2788 2954//2954 -f 2755//2755 2956//2956 3014//3014 -f 2755//2755 3014//3014 2818//2818 -f 2818//2818 3014//3014 3015//3015 -f 2818//2818 3015//3015 2750//2750 -f 2750//2750 3015//3015 2872//2872 -f 2750//2750 2872//2872 2689//2689 -f 2702//2702 2689//2689 2871//2871 -f 2871//2871 2689//2689 2872//2872 -f 2701//2701 2702//2702 2870//2870 -f 2870//2870 2702//2702 2871//2871 -f 2701//2701 2870//2870 2700//2700 -f 2700//2700 2870//2870 2907//2907 -f 2700//2700 2907//2907 2731//2731 -f 2731//2731 2907//2907 3019//3019 -f 2731//2731 3019//3019 2722//2722 -f 2722//2722 3019//3019 2903//2903 -f 2720//2720 2722//2722 2902//2902 -f 2902//2902 2722//2722 2903//2903 -f 2746//2746 2933//2933 2744//2744 -f 2744//2744 2933//2933 3032//3032 -f 2744//2744 3032//3032 2834//2834 -f 2834//2834 3032//3032 2995//2995 -f 2834//2834 2995//2995 2832//2832 -f 2832//2832 2995//2995 2997//2997 -f 2832//2832 2997//2997 2758//2758 -f 2758//2758 2997//2997 3024//3024 -f 2758//2758 3024//3024 2844//2844 -f 2844//2844 3024//3024 2974//2974 -f 2844//2844 2974//2974 2842//2842 -f 2842//2842 2974//2974 3000//3000 -f 2842//2842 3000//3000 2736//2736 -f 2736//2736 3000//3000 3002//3002 -f 2736//2736 3002//3002 2812//2812 -f 2812//2812 3002//3002 2937//2937 -f 2812//2812 2937//2937 2773//2773 -f 2773//2773 2937//2937 2979//2979 -f 2773//2773 2979//2979 2771//2771 -f 2771//2771 2979//2979 2981//2981 -f 2771//2771 2981//2981 2825//2825 -f 2825//2825 2981//2981 2931//2931 -f 2825//2825 2931//2931 2746//2746 -f 2746//2746 2931//2931 2933//2933 -f 3037//3037 3038//3038 3039//3039 -f 3040//3040 3041//3041 3042//3042 -f 3043//3043 3044//3044 3045//3045 -f 3045//3045 3044//3044 3046//3046 -f 3045//3045 3046//3046 3047//3047 -f 3048//3048 3049//3049 3050//3050 -f 3050//3050 3049//3049 3051//3051 -f 3050//3050 3051//3051 3052//3052 -f 3053//3053 3054//3054 3055//3055 -f 3056//3056 3057//3057 3058//3058 -f 3059//3059 3037//3037 3060//3060 -f 3060//3060 3037//3037 3039//3039 -f 3060//3060 3039//3039 3061//3061 -f 3061//3061 3039//3039 3062//3062 -f 3063//3063 3064//3064 3065//3065 -f 3066//3066 3067//3067 3068//3068 -f 3069//3069 3053//3053 3070//3070 -f 3070//3070 3053//3053 3055//3055 -f 3070//3070 3055//3055 3071//3071 -f 3072//3072 3073//3073 3074//3074 -f 3074//3074 3073//3073 3075//3075 -f 3076//3076 3065//3065 3077//3077 -f 3077//3077 3065//3065 3078//3078 -f 3079//3079 3080//3080 3081//3081 -f 3046//3046 3082//3082 3047//3047 -f 3047//3047 3082//3082 3083//3083 -f 3047//3047 3083//3083 3075//3075 -f 3075//3075 3083//3083 3084//3084 -f 3075//3075 3084//3084 3074//3074 -f 3085//3085 3086//3086 3087//3087 -f 3071//3071 3055//3055 3088//3088 -f 3088//3088 3055//3055 3089//3089 -f 3088//3088 3089//3089 3068//3068 -f 3068//3068 3089//3089 3090//3090 -f 3068//3068 3090//3090 3066//3066 -f 3066//3066 3090//3090 3091//3091 -f 3066//3066 3091//3091 3092//3092 -f 3056//3056 3058//3058 3093//3093 -f 3063//3063 3065//3065 3094//3094 -f 3094//3094 3065//3065 3076//3076 -f 3094//3094 3076//3076 3095//3095 -f 3096//3096 3097//3097 3098//3098 -f 3098//3098 3097//3097 3099//3099 -f 3100//3100 3101//3101 3087//3087 -f 3087//3087 3101//3101 3102//3102 -f 3087//3087 3102//3102 3085//3085 -f 3103//3103 3104//3104 3105//3105 -f 3079//3079 3081//3081 3106//3106 -f 3076//3076 3107//3107 3095//3095 -f 3095//3095 3107//3107 3098//3098 -f 3095//3095 3098//3098 3108//3108 -f 3108//3108 3098//3098 3099//3099 -f 3109//3109 3110//3110 3111//3111 -f 3112//3112 3113//3113 3114//3114 -f 3115//3115 3116//3116 3110//3110 -f 3110//3110 3116//3116 3117//3117 -f 3118//3118 3119//3119 3120//3120 -f 3120//3120 3119//3119 3121//3121 -f 3120//3120 3121//3121 3122//3122 -f 3039//3039 3123//3123 3062//3062 -f 3062//3062 3123//3123 3115//3115 -f 3062//3062 3115//3115 3124//3124 -f 3124//3124 3115//3115 3110//3110 -f 3124//3124 3110//3110 3125//3125 -f 3126//3126 3065//3065 3127//3127 -f 3128//3128 3129//3129 3130//3130 -f 3131//3131 3132//3132 3133//3133 -f 3134//3134 3135//3135 3136//3136 -f 3137//3137 3117//3117 3138//3138 -f 3139//3139 3140//3140 3141//3141 -f 3141//3141 3140//3140 3142//3142 -f 3141//3141 3142//3142 3143//3143 -f 3143//3143 3142//3142 3144//3144 -f 3145//3145 3146//3146 3147//3147 -f 3147//3147 3146//3146 3148//3148 -f 3147//3147 3148//3148 3149//3149 -f 3117//3117 3137//3137 3110//3110 -f 3110//3110 3137//3137 3150//3150 -f 3110//3110 3150//3150 3111//3111 -f 3151//3151 3152//3152 3153//3153 -f 3153//3153 3152//3152 3154//3154 -f 3081//3081 3155//3155 3156//3156 -f 3103//3103 3105//3105 3157//3157 -f 3158//3158 3064//3064 3159//3159 -f 3100//3100 3087//3087 3160//3160 -f 3160//3160 3087//3087 3161//3161 -f 3160//3160 3161//3161 3133//3133 -f 3133//3133 3161//3161 3162//3162 -f 3133//3133 3162//3162 3131//3131 -f 3131//3131 3162//3162 3163//3163 -f 3131//3131 3163//3163 3164//3164 -f 3058//3058 3165//3165 3166//3166 -f 3128//3128 3130//3130 3167//3167 -f 3067//3067 3066//3066 3111//3111 -f 3111//3111 3066//3066 3168//3168 -f 3111//3111 3168//3168 3109//3109 -f 3141//3141 3169//3169 3139//3139 -f 3139//3139 3169//3169 3153//3153 -f 3139//3139 3153//3153 3170//3170 -f 3170//3170 3153//3153 3154//3154 -f 3140//3140 3171//3171 3142//3142 -f 3142//3142 3171//3171 3172//3172 -f 3142//3142 3172//3172 3173//3173 -f 3173//3173 3172//3172 3155//3155 -f 3173//3173 3155//3155 3174//3174 -f 3174//3174 3155//3155 3081//3081 -f 3175//3175 3040//3040 3176//3176 -f 3176//3176 3040//3040 3042//3042 -f 3176//3176 3042//3042 3177//3177 -f 3177//3177 3042//3042 3178//3178 -f 3177//3177 3178//3178 3179//3179 -f 3179//3179 3178//3178 3106//3106 -f 3179//3179 3106//3106 3180//3180 -f 3180//3180 3106//3106 3081//3081 -f 3180//3180 3081//3081 3104//3104 -f 3104//3104 3081//3081 3156//3156 -f 3104//3104 3156//3156 3105//3105 -f 3064//3064 3158//3158 3065//3065 -f 3065//3065 3158//3158 3181//3181 -f 3065//3065 3181//3181 3127//3127 -f 3048//3048 3050//3050 3182//3182 -f 3182//3182 3050//3050 3183//3183 -f 3182//3182 3183//3183 3184//3184 -f 3184//3184 3183//3183 3093//3093 -f 3184//3184 3093//3093 3185//3185 -f 3185//3185 3093//3093 3058//3058 -f 3185//3185 3058//3058 3129//3129 -f 3129//3129 3058//3058 3166//3166 -f 3129//3129 3166//3166 3130//3130 -f 3148//3148 3186//3186 3149//3149 -f 3149//3149 3186//3186 3187//3187 -f 3149//3149 3187//3187 3188//3188 -f 3188//3188 3187//3187 3189//3189 -f 3188//3188 3189//3189 3112//3112 -f 3112//3112 3189//3189 3190//3190 -f 3112//3112 3190//3190 3113//3113 -f 3113//3113 3190//3190 3191//3191 -f 3113//3113 3191//3191 3192//3192 -f 3192//3192 3191//3191 3137//3137 -f 3192//3192 3137//3137 3193//3193 -f 3193//3193 3137//3137 3138//3138 -f 3132//3132 3131//3131 3127//3127 -f 3127//3127 3131//3131 3194//3194 -f 3127//3127 3194//3194 3126//3126 -f 3084//3084 3195//3195 3074//3074 -f 3074//3074 3195//3195 3196//3196 -f 3074//3074 3196//3196 3197//3197 -f 3197//3197 3196//3196 3165//3165 -f 3197//3197 3165//3165 3198//3198 -f 3198//3198 3165//3165 3058//3058 -f 3121//3121 3199//3199 3122//3122 -f 3122//3122 3199//3199 3200//3200 -f 3122//3122 3200//3200 3201//3201 -f 3201//3201 3200//3200 3202//3202 -f 3201//3201 3202//3202 3147//3147 -f 3147//3147 3202//3202 3203//3203 -f 3147//3147 3203//3203 3145//3145 -f 3145//3145 3203//3203 3204//3204 -f 3145//3145 3204//3204 3105//3105 -f 3105//3105 3204//3204 3205//3205 -f 3105//3105 3205//3205 3157//3157 -f 3136//3136 3206//3206 3134//3134 -f 3134//3134 3206//3206 3207//3207 -f 3134//3134 3207//3207 3208//3208 -f 3208//3208 3207//3207 3209//3209 -f 3208//3208 3209//3209 3210//3210 -f 3210//3210 3209//3209 3211//3211 -f 3210//3210 3211//3211 3120//3120 -f 3120//3120 3211//3211 3212//3212 -f 3120//3120 3212//3212 3118//3118 -f 3118//3118 3212//3212 3213//3213 -f 3118//3118 3213//3213 3214//3214 -f 3214//3214 3213//3213 3158//3158 -f 3214//3214 3158//3158 3215//3215 -f 3215//3215 3158//3158 3159//3159 -f 3114//3114 3216//3216 3112//3112 -f 3112//3112 3216//3216 3217//3217 -f 3112//3112 3217//3217 3218//3218 -f 3218//3218 3217//3217 3219//3219 -f 3218//3218 3219//3219 3220//3220 -f 3220//3220 3219//3219 3221//3221 -f 3220//3220 3221//3221 3134//3134 -f 3134//3134 3221//3221 3222//3222 -f 3134//3134 3222//3222 3135//3135 -f 3135//3135 3222//3222 3223//3223 -f 3135//3135 3223//3223 3130//3130 -f 3130//3130 3223//3223 3224//3224 -f 3130//3130 3224//3224 3167//3167 -f 3225//3225 3226//3226 3227//3227 -f 3228//3228 3229//3229 3230//3230 -f 3231//3231 3232//3232 3233//3233 -f 3233//3233 3232//3232 3234//3234 -f 3235//3235 3236//3236 3237//3237 -f 3237//3237 3236//3236 3238//3238 -f 3237//3237 3238//3238 3239//3239 -f 3240//3240 3241//3241 3242//3242 -f 3243//3243 3228//3228 3244//3244 -f 3244//3244 3228//3228 3230//3230 -f 3244//3244 3230//3230 3245//3245 -f 3246//3246 3247//3247 3248//3248 -f 3249//3249 3250//3250 3251//3251 -f 3252//3252 3253//3253 3254//3254 -f 3234//3234 3255//3255 3233//3233 -f 3233//3233 3255//3255 3256//3256 -f 3233//3233 3256//3256 3257//3257 -f 3257//3257 3256//3256 3258//3258 -f 3257//3257 3258//3258 3259//3259 -f 3259//3259 3258//3258 3260//3260 -f 3259//3259 3260//3260 3261//3261 -f 3261//3261 3260//3260 3262//3262 -f 3263//3263 3264//3264 3265//3265 -f 3266//3266 3267//3267 3268//3268 -f 3268//3268 3267//3267 3269//3269 -f 3268//3268 3269//3269 3270//3270 -f 3245//3245 3230//3230 3271//3271 -f 3271//3271 3230//3230 3272//3272 -f 3271//3271 3272//3272 3251//3251 -f 3251//3251 3272//3272 3273//3273 -f 3251//3251 3273//3273 3249//3249 -f 3249//3249 3273//3273 3274//3274 -f 3249//3249 3274//3274 3275//3275 -f 3263//3263 3265//3265 3276//3276 -f 3277//3277 3278//3278 3279//3279 -f 3280//3280 3281//3281 3282//3282 -f 3246//3246 3248//3248 3283//3283 -f 3242//3242 3225//3225 3240//3240 -f 3240//3240 3225//3225 3227//3227 -f 3240//3240 3227//3227 3284//3284 -f 3284//3284 3227//3227 3276//3276 -f 3284//3284 3276//3276 3285//3285 -f 3285//3285 3276//3276 3265//3265 -f 3285//3285 3265//3265 3286//3286 -f 3286//3286 3265//3265 3287//3287 -f 3288//3288 3289//3289 3290//3290 -f 3290//3290 3289//3289 3291//3291 -f 3292//3292 3293//3293 3282//3282 -f 3282//3282 3293//3293 3294//3294 -f 3282//3282 3294//3294 3280//3280 -f 3295//3295 3252//3252 3296//3296 -f 3296//3296 3252//3252 3254//3254 -f 3296//3296 3254//3254 3297//3297 -f 3297//3297 3254//3254 3298//3298 -f 3254//3254 3299//3299 3298//3298 -f 3298//3298 3299//3299 3288//3288 -f 3298//3298 3288//3288 3300//3300 -f 3300//3300 3288//3288 3290//3290 -f 3300//3300 3290//3290 3301//3301 -f 3302//3302 3303//3303 3304//3304 -f 3305//3305 3306//3306 3307//3307 -f 3307//3307 3306//3306 3308//3308 -f 3307//3307 3308//3308 3309//3309 -f 3310//3310 3311//3311 3312//3312 -f 3313//3313 3314//3314 3315//3315 -f 3316//3316 3317//3317 3318//3318 -f 3319//3319 3265//3265 3320//3320 -f 3321//3321 3291//3291 3322//3322 -f 3292//3292 3282//3282 3323//3323 -f 3323//3323 3282//3282 3324//3324 -f 3323//3323 3324//3324 3325//3325 -f 3325//3325 3324//3324 3326//3326 -f 3325//3325 3326//3326 3327//3327 -f 3327//3327 3326//3326 3328//3328 -f 3327//3327 3328//3328 3329//3329 -f 3330//3330 3331//3331 3332//3332 -f 3332//3332 3331//3331 3333//3333 -f 3291//3291 3321//3321 3290//3290 -f 3290//3290 3321//3321 3334//3334 -f 3290//3290 3334//3334 3335//3335 -f 3336//3336 3290//3290 3337//3337 -f 3337//3337 3290//3290 3335//3335 -f 3337//3337 3335//3335 3327//3327 -f 3327//3327 3335//3335 3338//3338 -f 3327//3327 3338//3338 3325//3325 -f 3312//3312 3339//3339 3340//3340 -f 3316//3316 3318//3318 3341//3341 -f 3310//3310 3312//3312 3342//3342 -f 3269//3269 3343//3343 3270//3270 -f 3270//3270 3343//3343 3344//3344 -f 3270//3270 3344//3344 3333//3333 -f 3333//3333 3344//3344 3345//3345 -f 3333//3333 3345//3345 3332//3332 -f 3235//3235 3237//3237 3346//3346 -f 3346//3346 3237//3237 3347//3347 -f 3346//3346 3347//3347 3348//3348 -f 3348//3348 3347//3347 3342//3342 -f 3348//3348 3342//3342 3349//3349 -f 3349//3349 3342//3342 3312//3312 -f 3349//3349 3312//3312 3317//3317 -f 3317//3317 3312//3312 3340//3340 -f 3317//3317 3340//3340 3318//3318 -f 3350//3350 3351//3351 3352//3352 -f 3315//3315 3353//3353 3313//3313 -f 3313//3313 3353//3353 3354//3354 -f 3313//3313 3354//3354 3355//3355 -f 3355//3355 3354//3354 3356//3356 -f 3355//3355 3356//3356 3357//3357 -f 3357//3357 3356//3356 3358//3358 -f 3357//3357 3358//3358 3307//3307 -f 3307//3307 3358//3358 3359//3359 -f 3307//3307 3359//3359 3305//3305 -f 3305//3305 3359//3359 3360//3360 -f 3305//3305 3360//3360 3361//3361 -f 3361//3361 3360//3360 3321//3321 -f 3361//3361 3321//3321 3362//3362 -f 3362//3362 3321//3321 3322//3322 -f 3258//3258 3363//3363 3260//3260 -f 3260//3260 3363//3363 3364//3364 -f 3260//3260 3364//3364 3365//3365 -f 3365//3365 3364//3364 3339//3339 -f 3365//3365 3339//3339 3366//3366 -f 3366//3366 3339//3339 3312//3312 -f 3367//3367 3264//3264 3368//3368 -f 3369//3369 3370//3370 3371//3371 -f 3371//3371 3370//3370 3372//3372 -f 3371//3371 3372//3372 3373//3373 -f 3352//3352 3374//3374 3350//3350 -f 3350//3350 3374//3374 3375//3375 -f 3350//3350 3375//3375 3376//3376 -f 3376//3376 3375//3375 3377//3377 -f 3376//3376 3377//3377 3378//3378 -f 3378//3378 3377//3377 3379//3379 -f 3378//3378 3379//3379 3313//3313 -f 3313//3313 3379//3379 3380//3380 -f 3313//3313 3380//3380 3314//3314 -f 3314//3314 3380//3380 3381//3381 -f 3314//3314 3381//3381 3318//3318 -f 3318//3318 3381//3381 3382//3382 -f 3318//3318 3382//3382 3341//3341 -f 3264//3264 3367//3367 3265//3265 -f 3265//3265 3367//3367 3383//3383 -f 3265//3265 3383//3383 3320//3320 -f 3248//3248 3384//3384 3385//3385 -f 3302//3302 3304//3304 3386//3386 -f 3250//3250 3249//3249 3320//3320 -f 3320//3320 3249//3249 3387//3387 -f 3320//3320 3387//3387 3319//3319 -f 3345//3345 3388//3388 3332//3332 -f 3332//3332 3388//3388 3389//3389 -f 3332//3332 3389//3389 3390//3390 -f 3390//3390 3389//3389 3384//3384 -f 3390//3390 3384//3384 3391//3391 -f 3391//3391 3384//3384 3248//3248 -f 3392//3392 3277//3277 3393//3393 -f 3393//3393 3277//3277 3279//3279 -f 3393//3393 3279//3279 3394//3394 -f 3394//3394 3279//3279 3395//3395 -f 3394//3394 3395//3395 3396//3396 -f 3396//3396 3395//3395 3283//3283 -f 3396//3396 3283//3283 3397//3397 -f 3397//3397 3283//3283 3248//3248 -f 3397//3397 3248//3248 3303//3303 -f 3303//3303 3248//3248 3385//3385 -f 3303//3303 3385//3385 3304//3304 -f 3372//3372 3398//3398 3373//3373 -f 3373//3373 3398//3398 3399//3399 -f 3373//3373 3399//3399 3400//3400 -f 3400//3400 3399//3399 3401//3401 -f 3400//3400 3401//3401 3350//3350 -f 3350//3350 3401//3401 3402//3402 -f 3350//3350 3402//3402 3351//3351 -f 3351//3351 3402//3402 3403//3403 -f 3351//3351 3403//3403 3404//3404 -f 3404//3404 3403//3403 3367//3367 -f 3404//3404 3367//3367 3405//3405 -f 3405//3405 3367//3367 3368//3368 -f 3308//3308 3406//3406 3309//3309 -f 3309//3309 3406//3406 3407//3407 -f 3309//3309 3407//3407 3408//3408 -f 3408//3408 3407//3407 3409//3409 -f 3408//3408 3409//3409 3371//3371 -f 3371//3371 3409//3409 3410//3410 -f 3371//3371 3410//3410 3369//3369 -f 3369//3369 3410//3410 3411//3411 -f 3369//3369 3411//3411 3304//3304 -f 3304//3304 3411//3411 3412//3412 -f 3304//3304 3412//3412 3386//3386 -f 3097//3097 3096//3096 3277//3277 -f 3277//3277 3096//3096 3278//3278 -f 3097//3097 3277//3277 3392//3392 -f 3097//3097 3392//3392 3099//3099 -f 3099//3099 3392//3392 3393//3393 -f 3099//3099 3393//3393 3108//3108 -f 3108//3108 3393//3393 3394//3394 -f 3108//3108 3394//3394 3095//3095 -f 3094//3094 3095//3095 3396//3396 -f 3396//3396 3095//3095 3394//3394 -f 3094//3094 3396//3396 3063//3063 -f 3063//3063 3396//3396 3397//3397 -f 3063//3063 3397//3397 3064//3064 -f 3064//3064 3397//3397 3303//3303 -f 3064//3064 3303//3303 3159//3159 -f 3159//3159 3303//3303 3302//3302 -f 3215//3215 3159//3159 3386//3386 -f 3386//3386 3159//3159 3302//3302 -f 3215//3215 3386//3386 3214//3214 -f 3214//3214 3386//3386 3412//3412 -f 3214//3214 3412//3412 3118//3118 -f 3118//3118 3412//3412 3411//3411 -f 3119//3119 3118//3118 3410//3410 -f 3410//3410 3118//3118 3411//3411 -f 3119//3119 3410//3410 3121//3121 -f 3121//3121 3410//3410 3409//3409 -f 3121//3121 3409//3409 3199//3199 -f 3199//3199 3409//3409 3407//3407 -f 3200//3200 3199//3199 3406//3406 -f 3406//3406 3199//3199 3407//3407 -f 3200//3200 3406//3406 3202//3202 -f 3202//3202 3406//3406 3308//3308 -f 3202//3202 3308//3308 3203//3203 -f 3203//3203 3308//3308 3306//3306 -f 3204//3204 3203//3203 3305//3305 -f 3305//3305 3203//3203 3306//3306 -f 3204//3204 3305//3305 3205//3205 -f 3205//3205 3305//3305 3361//3361 -f 3205//3205 3361//3361 3157//3157 -f 3157//3157 3361//3361 3362//3362 -f 3103//3103 3157//3157 3322//3322 -f 3322//3322 3157//3157 3362//3362 -f 3103//3103 3322//3322 3104//3104 -f 3104//3104 3322//3322 3291//3291 -f 3104//3104 3291//3291 3180//3180 -f 3180//3180 3291//3291 3289//3289 -f 3180//3180 3289//3289 3179//3179 -f 3179//3179 3289//3289 3288//3288 -f 3177//3177 3179//3179 3299//3299 -f 3299//3299 3179//3179 3288//3288 -f 3177//3177 3299//3299 3254//3254 -f 3177//3177 3254//3254 3176//3176 -f 3176//3176 3254//3254 3253//3253 -f 3176//3176 3253//3253 3175//3175 -f 3175//3175 3253//3253 3252//3252 -f 3175//3175 3252//3252 3040//3040 -f 3041//3041 3040//3040 3295//3295 -f 3295//3295 3040//3040 3252//3252 -f 3042//3042 3041//3041 3296//3296 -f 3296//3296 3041//3041 3295//3295 -f 3042//3042 3296//3296 3178//3178 -f 3178//3178 3296//3296 3297//3297 -f 3178//3178 3297//3297 3106//3106 -f 3106//3106 3297//3297 3298//3298 -f 3106//3106 3298//3298 3079//3079 -f 3079//3079 3298//3298 3300//3300 -f 3080//3080 3079//3079 3301//3301 -f 3301//3301 3079//3079 3300//3300 -f 3081//3081 3080//3080 3290//3290 -f 3290//3290 3080//3080 3301//3301 -f 3081//3081 3290//3290 3336//3336 -f 3081//3081 3336//3336 3174//3174 -f 3174//3174 3336//3336 3337//3337 -f 3174//3174 3337//3337 3173//3173 -f 3173//3173 3337//3337 3327//3327 -f 3173//3173 3327//3327 3142//3142 -f 3144//3144 3142//3142 3329//3329 -f 3329//3329 3142//3142 3327//3327 -f 3143//3143 3144//3144 3328//3328 -f 3328//3328 3144//3144 3329//3329 -f 3143//3143 3328//3328 3141//3141 -f 3141//3141 3328//3328 3326//3326 -f 3141//3141 3326//3326 3169//3169 -f 3169//3169 3326//3326 3324//3324 -f 3169//3169 3324//3324 3153//3153 -f 3153//3153 3324//3324 3282//3282 -f 3151//3151 3153//3153 3281//3281 -f 3281//3281 3153//3153 3282//3282 -f 3152//3152 3151//3151 3280//3280 -f 3280//3280 3151//3151 3281//3281 -f 3152//3152 3280//3280 3294//3294 -f 3152//3152 3294//3294 3154//3154 -f 3154//3154 3294//3294 3293//3293 -f 3154//3154 3293//3293 3170//3170 -f 3170//3170 3293//3293 3292//3292 -f 3170//3170 3292//3292 3139//3139 -f 3140//3140 3139//3139 3323//3323 -f 3323//3323 3139//3139 3292//3292 -f 3140//3140 3323//3323 3171//3171 -f 3171//3171 3323//3323 3325//3325 -f 3171//3171 3325//3325 3172//3172 -f 3172//3172 3325//3325 3338//3338 -f 3172//3172 3338//3338 3155//3155 -f 3155//3155 3338//3338 3335//3335 -f 3156//3156 3155//3155 3334//3334 -f 3334//3334 3155//3155 3335//3335 -f 3156//3156 3334//3334 3105//3105 -f 3105//3105 3334//3334 3321//3321 -f 3105//3105 3321//3321 3145//3145 -f 3145//3145 3321//3321 3360//3360 -f 3146//3146 3145//3145 3359//3359 -f 3359//3359 3145//3145 3360//3360 -f 3146//3146 3359//3359 3148//3148 -f 3148//3148 3359//3359 3358//3358 -f 3148//3148 3358//3358 3186//3186 -f 3186//3186 3358//3358 3356//3356 -f 3187//3187 3186//3186 3354//3354 -f 3354//3354 3186//3186 3356//3356 -f 3187//3187 3354//3354 3189//3189 -f 3189//3189 3354//3354 3353//3353 -f 3189//3189 3353//3353 3190//3190 -f 3190//3190 3353//3353 3315//3315 -f 3191//3191 3190//3190 3314//3314 -f 3314//3314 3190//3190 3315//3315 -f 3191//3191 3314//3314 3137//3137 -f 3137//3137 3314//3314 3318//3318 -f 3137//3137 3318//3318 3150//3150 -f 3150//3150 3318//3318 3340//3340 -f 3111//3111 3150//3150 3339//3339 -f 3339//3339 3150//3150 3340//3340 -f 3111//3111 3339//3339 3067//3067 -f 3067//3067 3339//3339 3364//3364 -f 3067//3067 3364//3364 3068//3068 -f 3068//3068 3364//3364 3363//3363 -f 3068//3068 3363//3363 3088//3088 -f 3088//3088 3363//3363 3258//3258 -f 3071//3071 3088//3088 3256//3256 -f 3256//3256 3088//3088 3258//3258 -f 3071//3071 3256//3256 3255//3255 -f 3071//3071 3255//3255 3070//3070 -f 3070//3070 3255//3255 3234//3234 -f 3070//3070 3234//3234 3069//3069 -f 3069//3069 3234//3234 3232//3232 -f 3069//3069 3232//3232 3053//3053 -f 3054//3054 3053//3053 3231//3231 -f 3231//3231 3053//3053 3232//3232 -f 3055//3055 3054//3054 3233//3233 -f 3233//3233 3054//3054 3231//3231 -f 3055//3055 3233//3233 3089//3089 -f 3089//3089 3233//3233 3257//3257 -f 3089//3089 3257//3257 3090//3090 -f 3090//3090 3257//3257 3259//3259 -f 3090//3090 3259//3259 3091//3091 -f 3091//3091 3259//3259 3261//3261 -f 3092//3092 3091//3091 3262//3262 -f 3262//3262 3091//3091 3261//3261 -f 3066//3066 3092//3092 3260//3260 -f 3260//3260 3092//3092 3262//3262 -f 3066//3066 3260//3260 3365//3365 -f 3066//3066 3365//3365 3168//3168 -f 3168//3168 3365//3365 3366//3366 -f 3168//3168 3366//3366 3109//3109 -f 3109//3109 3366//3366 3312//3312 -f 3109//3109 3312//3312 3110//3110 -f 3125//3125 3110//3110 3311//3311 -f 3311//3311 3110//3110 3312//3312 -f 3124//3124 3125//3125 3310//3310 -f 3310//3310 3125//3125 3311//3311 -f 3124//3124 3310//3310 3062//3062 -f 3062//3062 3310//3310 3342//3342 -f 3062//3062 3342//3342 3061//3061 -f 3061//3061 3342//3342 3347//3347 -f 3061//3061 3347//3347 3060//3060 -f 3060//3060 3347//3347 3237//3237 -f 3059//3059 3060//3060 3239//3239 -f 3239//3239 3060//3060 3237//3237 -f 3037//3037 3059//3059 3238//3238 -f 3238//3238 3059//3059 3239//3239 -f 3037//3037 3238//3238 3236//3236 -f 3037//3037 3236//3236 3038//3038 -f 3038//3038 3236//3236 3235//3235 -f 3038//3038 3235//3235 3039//3039 -f 3039//3039 3235//3235 3346//3346 -f 3039//3039 3346//3346 3123//3123 -f 3115//3115 3123//3123 3348//3348 -f 3348//3348 3123//3123 3346//3346 -f 3115//3115 3348//3348 3116//3116 -f 3116//3116 3348//3348 3349//3349 -f 3116//3116 3349//3349 3117//3117 -f 3117//3117 3349//3349 3317//3317 -f 3117//3117 3317//3317 3138//3138 -f 3138//3138 3317//3317 3316//3316 -f 3193//3193 3138//3138 3341//3341 -f 3341//3341 3138//3138 3316//3316 -f 3193//3193 3341//3341 3192//3192 -f 3192//3192 3341//3341 3382//3382 -f 3192//3192 3382//3382 3113//3113 -f 3113//3113 3382//3382 3381//3381 -f 3114//3114 3113//3113 3380//3380 -f 3380//3380 3113//3113 3381//3381 -f 3114//3114 3380//3380 3216//3216 -f 3216//3216 3380//3380 3379//3379 -f 3216//3216 3379//3379 3217//3217 -f 3217//3217 3379//3379 3377//3377 -f 3219//3219 3217//3217 3375//3375 -f 3375//3375 3217//3217 3377//3377 -f 3219//3219 3375//3375 3221//3221 -f 3221//3221 3375//3375 3374//3374 -f 3221//3221 3374//3374 3222//3222 -f 3222//3222 3374//3374 3352//3352 -f 3223//3223 3222//3222 3351//3351 -f 3351//3351 3222//3222 3352//3352 -f 3223//3223 3351//3351 3224//3224 -f 3224//3224 3351//3351 3404//3404 -f 3224//3224 3404//3404 3167//3167 -f 3167//3167 3404//3404 3405//3405 -f 3128//3128 3167//3167 3368//3368 -f 3368//3368 3167//3167 3405//3405 -f 3128//3128 3368//3368 3129//3129 -f 3129//3129 3368//3368 3264//3264 -f 3129//3129 3264//3264 3185//3185 -f 3185//3185 3264//3264 3263//3263 -f 3185//3185 3263//3263 3184//3184 -f 3184//3184 3263//3263 3276//3276 -f 3182//3182 3184//3184 3227//3227 -f 3227//3227 3184//3184 3276//3276 -f 3182//3182 3227//3227 3226//3226 -f 3182//3182 3226//3226 3048//3048 -f 3048//3048 3226//3226 3225//3225 -f 3048//3048 3225//3225 3049//3049 -f 3049//3049 3225//3225 3242//3242 -f 3049//3049 3242//3242 3051//3051 -f 3052//3052 3051//3051 3241//3241 -f 3241//3241 3051//3051 3242//3242 -f 3050//3050 3052//3052 3240//3240 -f 3240//3240 3052//3052 3241//3241 -f 3050//3050 3240//3240 3183//3183 -f 3183//3183 3240//3240 3284//3284 -f 3183//3183 3284//3284 3093//3093 -f 3093//3093 3284//3284 3285//3285 -f 3093//3093 3285//3285 3056//3056 -f 3056//3056 3285//3285 3286//3286 -f 3057//3057 3056//3056 3287//3287 -f 3287//3287 3056//3056 3286//3286 -f 3058//3058 3057//3057 3265//3265 -f 3265//3265 3057//3057 3287//3287 -f 3058//3058 3265//3265 3319//3319 -f 3058//3058 3319//3319 3198//3198 -f 3198//3198 3319//3319 3387//3387 -f 3198//3198 3387//3387 3197//3197 -f 3197//3197 3387//3387 3249//3249 -f 3197//3197 3249//3249 3074//3074 -f 3072//3072 3074//3074 3275//3275 -f 3275//3275 3074//3074 3249//3249 -f 3073//3073 3072//3072 3274//3274 -f 3274//3274 3072//3072 3275//3275 -f 3073//3073 3274//3274 3075//3075 -f 3075//3075 3274//3274 3273//3273 -f 3075//3075 3273//3273 3047//3047 -f 3047//3047 3273//3273 3272//3272 -f 3047//3047 3272//3272 3045//3045 -f 3045//3045 3272//3272 3230//3230 -f 3043//3043 3045//3045 3229//3229 -f 3229//3229 3045//3045 3230//3230 -f 3044//3044 3043//3043 3228//3228 -f 3228//3228 3043//3043 3229//3229 -f 3044//3044 3228//3228 3243//3243 -f 3044//3044 3243//3243 3046//3046 -f 3046//3046 3243//3243 3244//3244 -f 3046//3046 3244//3244 3082//3082 -f 3082//3082 3244//3244 3245//3245 -f 3082//3082 3245//3245 3083//3083 -f 3084//3084 3083//3083 3271//3271 -f 3271//3271 3083//3083 3245//3245 -f 3084//3084 3271//3271 3195//3195 -f 3195//3195 3271//3271 3251//3251 -f 3195//3195 3251//3251 3196//3196 -f 3196//3196 3251//3251 3250//3250 -f 3196//3196 3250//3250 3165//3165 -f 3165//3165 3250//3250 3320//3320 -f 3166//3166 3165//3165 3383//3383 -f 3383//3383 3165//3165 3320//3320 -f 3166//3166 3383//3383 3130//3130 -f 3130//3130 3383//3383 3367//3367 -f 3130//3130 3367//3367 3135//3135 -f 3135//3135 3367//3367 3403//3403 -f 3136//3136 3135//3135 3402//3402 -f 3402//3402 3135//3135 3403//3403 -f 3136//3136 3402//3402 3206//3206 -f 3206//3206 3402//3402 3401//3401 -f 3206//3206 3401//3401 3207//3207 -f 3207//3207 3401//3401 3399//3399 -f 3209//3209 3207//3207 3398//3398 -f 3398//3398 3207//3207 3399//3399 -f 3209//3209 3398//3398 3211//3211 -f 3211//3211 3398//3398 3372//3372 -f 3211//3211 3372//3372 3212//3212 -f 3212//3212 3372//3372 3370//3370 -f 3213//3213 3212//3212 3369//3369 -f 3369//3369 3212//3212 3370//3370 -f 3213//3213 3369//3369 3158//3158 -f 3158//3158 3369//3369 3304//3304 -f 3158//3158 3304//3304 3181//3181 -f 3181//3181 3304//3304 3385//3385 -f 3127//3127 3181//3181 3384//3384 -f 3384//3384 3181//3181 3385//3385 -f 3127//3127 3384//3384 3132//3132 -f 3132//3132 3384//3384 3389//3389 -f 3132//3132 3389//3389 3133//3133 -f 3133//3133 3389//3389 3388//3388 -f 3133//3133 3388//3388 3160//3160 -f 3160//3160 3388//3388 3345//3345 -f 3100//3100 3160//3160 3344//3344 -f 3344//3344 3160//3160 3345//3345 -f 3100//3100 3344//3344 3343//3343 -f 3100//3100 3343//3343 3101//3101 -f 3101//3101 3343//3343 3269//3269 -f 3101//3101 3269//3269 3102//3102 -f 3102//3102 3269//3269 3267//3267 -f 3102//3102 3267//3267 3085//3085 -f 3086//3086 3085//3085 3266//3266 -f 3266//3266 3085//3085 3267//3267 -f 3087//3087 3086//3086 3268//3268 -f 3268//3268 3086//3086 3266//3266 -f 3087//3087 3268//3268 3161//3161 -f 3161//3161 3268//3268 3270//3270 -f 3161//3161 3270//3270 3162//3162 -f 3162//3162 3270//3270 3333//3333 -f 3162//3162 3333//3333 3163//3163 -f 3163//3163 3333//3333 3331//3331 -f 3164//3164 3163//3163 3330//3330 -f 3330//3330 3163//3163 3331//3331 -f 3131//3131 3164//3164 3332//3332 -f 3332//3332 3164//3164 3330//3330 -f 3131//3131 3332//3332 3390//3390 -f 3131//3131 3390//3390 3194//3194 -f 3194//3194 3390//3390 3391//3391 -f 3194//3194 3391//3391 3126//3126 -f 3126//3126 3391//3391 3248//3248 -f 3126//3126 3248//3248 3065//3065 -f 3078//3078 3065//3065 3247//3247 -f 3247//3247 3065//3065 3248//3248 -f 3077//3077 3078//3078 3246//3246 -f 3246//3246 3078//3078 3247//3247 -f 3077//3077 3246//3246 3076//3076 -f 3076//3076 3246//3246 3283//3283 -f 3076//3076 3283//3283 3107//3107 -f 3107//3107 3283//3283 3395//3395 -f 3107//3107 3395//3395 3098//3098 -f 3098//3098 3395//3395 3279//3279 -f 3096//3096 3098//3098 3278//3278 -f 3278//3278 3098//3098 3279//3279 -f 3122//3122 3309//3309 3120//3120 -f 3120//3120 3309//3309 3408//3408 -f 3120//3120 3408//3408 3210//3210 -f 3210//3210 3408//3408 3371//3371 -f 3210//3210 3371//3371 3208//3208 -f 3208//3208 3371//3371 3373//3373 -f 3208//3208 3373//3373 3134//3134 -f 3134//3134 3373//3373 3400//3400 -f 3134//3134 3400//3400 3220//3220 -f 3220//3220 3400//3400 3350//3350 -f 3220//3220 3350//3350 3218//3218 -f 3218//3218 3350//3350 3376//3376 -f 3218//3218 3376//3376 3112//3112 -f 3112//3112 3376//3376 3378//3378 -f 3112//3112 3378//3378 3188//3188 -f 3188//3188 3378//3378 3313//3313 -f 3188//3188 3313//3313 3149//3149 -f 3149//3149 3313//3313 3355//3355 -f 3149//3149 3355//3355 3147//3147 -f 3147//3147 3355//3355 3357//3357 -f 3147//3147 3357//3357 3201//3201 -f 3201//3201 3357//3357 3307//3307 -f 3201//3201 3307//3307 3122//3122 -f 3122//3122 3307//3307 3309//3309 -f 3413//3413 3414//3414 3415//3415 -f 3416//3416 3417//3417 3418//3418 -f 3419//3419 3420//3420 3421//3421 -f 3421//3421 3420//3420 3422//3422 -f 3421//3421 3422//3422 3423//3423 -f 3424//3424 3425//3425 3426//3426 -f 3426//3426 3425//3425 3427//3427 -f 3426//3426 3427//3427 3428//3428 -f 3429//3429 3430//3430 3431//3431 -f 3432//3432 3433//3433 3434//3434 -f 3435//3435 3413//3413 3436//3436 -f 3436//3436 3413//3413 3415//3415 -f 3436//3436 3415//3415 3437//3437 -f 3437//3437 3415//3415 3438//3438 -f 3439//3439 3440//3440 3441//3441 -f 3081//3081 3442//3442 3443//3443 -f 3444//3444 3429//3429 3445//3445 -f 3445//3445 3429//3429 3431//3431 -f 3445//3445 3431//3431 3446//3446 -f 3447//3447 3448//3448 3449//3449 -f 3449//3449 3448//3448 3450//3450 -f 3451//3451 3441//3441 3452//3452 -f 3452//3452 3441//3441 3453//3453 -f 3454//3454 3455//3455 3456//3456 -f 3422//3422 3457//3457 3423//3423 -f 3423//3423 3457//3457 3458//3458 -f 3423//3423 3458//3458 3450//3450 -f 3450//3450 3458//3458 3459//3459 -f 3450//3450 3459//3459 3449//3449 -f 3460//3460 3461//3461 3462//3462 -f 3446//3446 3431//3431 3463//3463 -f 3463//3463 3431//3431 3464//3464 -f 3463//3463 3464//3464 3443//3443 -f 3443//3443 3464//3464 3465//3465 -f 3443//3443 3465//3465 3081//3081 -f 3081//3081 3465//3465 3466//3466 -f 3081//3081 3466//3466 3080//3080 -f 3432//3432 3434//3434 3467//3467 -f 3439//3439 3441//3441 3468//3468 -f 3468//3468 3441//3441 3451//3451 -f 3468//3468 3451//3451 3469//3469 -f 3470//3470 3471//3471 3472//3472 -f 3472//3472 3471//3471 3473//3473 -f 3474//3474 3475//3475 3462//3462 -f 3462//3462 3475//3475 3476//3476 -f 3462//3462 3476//3476 3460//3460 -f 3477//3477 3478//3478 3479//3479 -f 3454//3454 3456//3456 3480//3480 -f 3451//3451 3481//3481 3469//3469 -f 3469//3469 3481//3481 3472//3472 -f 3469//3469 3472//3472 3482//3482 -f 3482//3482 3472//3472 3473//3473 -f 3483//3483 3484//3484 3485//3485 -f 3486//3486 3487//3487 3488//3488 -f 3489//3489 3490//3490 3484//3484 -f 3484//3484 3490//3490 3491//3491 -f 3492//3492 3493//3493 3494//3494 -f 3494//3494 3493//3493 3495//3495 -f 3494//3494 3495//3495 3496//3496 -f 3415//3415 3497//3497 3438//3438 -f 3438//3438 3497//3497 3489//3489 -f 3438//3438 3489//3489 3498//3498 -f 3498//3498 3489//3489 3484//3484 -f 3498//3498 3484//3484 3499//3499 -f 3500//3500 3441//3441 3501//3501 -f 3502//3502 3503//3503 3504//3504 -f 3505//3505 3506//3506 3507//3507 -f 3508//3508 3509//3509 3510//3510 -f 3511//3511 3491//3491 3512//3512 -f 3513//3513 3514//3514 3515//3515 -f 3515//3515 3514//3514 3065//3065 -f 3515//3515 3065//3065 3516//3516 -f 3516//3516 3065//3065 3078//3078 -f 3517//3517 3518//3518 3519//3519 -f 3519//3519 3518//3518 3520//3520 -f 3519//3519 3520//3520 3521//3521 -f 3491//3491 3511//3511 3484//3484 -f 3484//3484 3511//3511 3522//3522 -f 3484//3484 3522//3522 3485//3485 -f 3523//3523 3524//3524 3525//3525 -f 3525//3525 3524//3524 3526//3526 -f 3456//3456 3527//3527 3528//3528 -f 3477//3477 3479//3479 3529//3529 -f 3530//3530 3440//3440 3531//3531 -f 3474//3474 3462//3462 3532//3532 -f 3532//3532 3462//3462 3533//3533 -f 3532//3532 3533//3533 3507//3507 -f 3507//3507 3533//3533 3534//3534 -f 3507//3507 3534//3534 3505//3505 -f 3505//3505 3534//3534 3535//3535 -f 3505//3505 3535//3535 3536//3536 -f 3434//3434 3537//3537 3538//3538 -f 3502//3502 3504//3504 3539//3539 -f 3442//3442 3081//3081 3485//3485 -f 3485//3485 3081//3081 3540//3540 -f 3485//3485 3540//3540 3483//3483 -f 3515//3515 3541//3541 3513//3513 -f 3513//3513 3541//3541 3525//3525 -f 3513//3513 3525//3525 3542//3542 -f 3542//3542 3525//3525 3526//3526 -f 3514//3514 3543//3543 3065//3065 -f 3065//3065 3543//3543 3544//3544 -f 3065//3065 3544//3544 3545//3545 -f 3545//3545 3544//3544 3527//3527 -f 3545//3545 3527//3527 3546//3546 -f 3546//3546 3527//3527 3456//3456 -f 3547//3547 3416//3416 3548//3548 -f 3548//3548 3416//3416 3418//3418 -f 3548//3548 3418//3418 3549//3549 -f 3549//3549 3418//3418 3550//3550 -f 3549//3549 3550//3550 3551//3551 -f 3551//3551 3550//3550 3480//3480 -f 3551//3551 3480//3480 3552//3552 -f 3552//3552 3480//3480 3456//3456 -f 3552//3552 3456//3456 3478//3478 -f 3478//3478 3456//3456 3528//3528 -f 3478//3478 3528//3528 3479//3479 -f 3440//3440 3530//3530 3441//3441 -f 3441//3441 3530//3530 3553//3553 -f 3441//3441 3553//3553 3501//3501 -f 3424//3424 3426//3426 3554//3554 -f 3554//3554 3426//3426 3555//3555 -f 3554//3554 3555//3555 3556//3556 -f 3556//3556 3555//3555 3467//3467 -f 3556//3556 3467//3467 3557//3557 -f 3557//3557 3467//3467 3434//3434 -f 3557//3557 3434//3434 3503//3503 -f 3503//3503 3434//3434 3538//3538 -f 3503//3503 3538//3538 3504//3504 -f 3520//3520 3558//3558 3521//3521 -f 3521//3521 3558//3558 3559//3559 -f 3521//3521 3559//3559 3560//3560 -f 3560//3560 3559//3559 3561//3561 -f 3560//3560 3561//3561 3486//3486 -f 3486//3486 3561//3561 3562//3562 -f 3486//3486 3562//3562 3487//3487 -f 3487//3487 3562//3562 3563//3563 -f 3487//3487 3563//3563 3564//3564 -f 3564//3564 3563//3563 3511//3511 -f 3564//3564 3511//3511 3565//3565 -f 3565//3565 3511//3511 3512//3512 -f 3506//3506 3505//3505 3501//3501 -f 3501//3501 3505//3505 3566//3566 -f 3501//3501 3566//3566 3500//3500 -f 3459//3459 3567//3567 3449//3449 -f 3449//3449 3567//3567 3568//3568 -f 3449//3449 3568//3568 3569//3569 -f 3569//3569 3568//3568 3537//3537 -f 3569//3569 3537//3537 3570//3570 -f 3570//3570 3537//3537 3434//3434 -f 3495//3495 3571//3571 3496//3496 -f 3496//3496 3571//3571 3572//3572 -f 3496//3496 3572//3572 3573//3573 -f 3573//3573 3572//3572 3574//3574 -f 3573//3573 3574//3574 3519//3519 -f 3519//3519 3574//3574 3575//3575 -f 3519//3519 3575//3575 3517//3517 -f 3517//3517 3575//3575 3576//3576 -f 3517//3517 3576//3576 3479//3479 -f 3479//3479 3576//3576 3577//3577 -f 3479//3479 3577//3577 3529//3529 -f 3510//3510 3578//3578 3508//3508 -f 3508//3508 3578//3578 3579//3579 -f 3508//3508 3579//3579 3580//3580 -f 3580//3580 3579//3579 3581//3581 -f 3580//3580 3581//3581 3582//3582 -f 3582//3582 3581//3581 3583//3583 -f 3582//3582 3583//3583 3494//3494 -f 3494//3494 3583//3583 3584//3584 -f 3494//3494 3584//3584 3492//3492 -f 3492//3492 3584//3584 3585//3585 -f 3492//3492 3585//3585 3586//3586 -f 3586//3586 3585//3585 3530//3530 -f 3586//3586 3530//3530 3587//3587 -f 3587//3587 3530//3530 3531//3531 -f 3488//3488 3588//3588 3486//3486 -f 3486//3486 3588//3588 3589//3589 -f 3486//3486 3589//3589 3590//3590 -f 3590//3590 3589//3589 3591//3591 -f 3590//3590 3591//3591 3592//3592 -f 3592//3592 3591//3591 3593//3593 -f 3592//3592 3593//3593 3508//3508 -f 3508//3508 3593//3593 3594//3594 -f 3508//3508 3594//3594 3509//3509 -f 3509//3509 3594//3594 3595//3595 -f 3509//3509 3595//3595 3504//3504 -f 3504//3504 3595//3595 3596//3596 -f 3504//3504 3596//3596 3539//3539 -f 3597//3597 3598//3598 3599//3599 -f 3600//3600 3601//3601 3602//3602 -f 3603//3603 3604//3604 3605//3605 -f 3605//3605 3604//3604 3606//3606 -f 3607//3607 3608//3608 3609//3609 -f 3609//3609 3608//3608 3610//3610 -f 3609//3609 3610//3610 3611//3611 -f 3612//3612 3613//3613 3614//3614 -f 3615//3615 3600//3600 3616//3616 -f 3616//3616 3600//3600 3602//3602 -f 3616//3616 3602//3602 3617//3617 -f 3618//3618 3619//3619 3620//3620 -f 3621//3621 3622//3622 3623//3623 -f 3624//3624 3625//3625 3626//3626 -f 3606//3606 3627//3627 3605//3605 -f 3605//3605 3627//3627 3628//3628 -f 3605//3605 3628//3628 3629//3629 -f 3629//3629 3628//3628 3630//3630 -f 3629//3629 3630//3630 3631//3631 -f 3631//3631 3630//3630 2734//2734 -f 3631//3631 2734//2734 3632//3632 -f 3632//3632 2734//2734 2749//2749 -f 3633//3633 3634//3634 3635//3635 -f 3636//3636 3637//3637 3638//3638 -f 3638//3638 3637//3637 3639//3639 -f 3638//3638 3639//3639 3640//3640 -f 3617//3617 3602//3602 3641//3641 -f 3641//3641 3602//3602 3642//3642 -f 3641//3641 3642//3642 3623//3623 -f 3623//3623 3642//3642 3643//3643 -f 3623//3623 3643//3643 3621//3621 -f 3621//3621 3643//3643 3644//3644 -f 3621//3621 3644//3644 3645//3645 -f 3633//3633 3635//3635 3646//3646 -f 3647//3647 3648//3648 3649//3649 -f 3650//3650 3651//3651 3652//3652 -f 3618//3618 3620//3620 3653//3653 -f 3614//3614 3597//3597 3612//3612 -f 3612//3612 3597//3597 3599//3599 -f 3612//3612 3599//3599 3654//3654 -f 3654//3654 3599//3599 3646//3646 -f 3654//3654 3646//3646 3655//3655 -f 3655//3655 3646//3646 3635//3635 -f 3655//3655 3635//3635 3656//3656 -f 3656//3656 3635//3635 3657//3657 -f 3658//3658 3659//3659 3660//3660 -f 3660//3660 3659//3659 3661//3661 -f 3662//3662 3663//3663 3652//3652 -f 3652//3652 3663//3663 3664//3664 -f 3652//3652 3664//3664 3650//3650 -f 3665//3665 3624//3624 3666//3666 -f 3666//3666 3624//3624 3626//3626 -f 3666//3666 3626//3626 3667//3667 -f 3667//3667 3626//3626 3668//3668 -f 3626//3626 3669//3669 3668//3668 -f 3668//3668 3669//3669 3658//3658 -f 3668//3668 3658//3658 3670//3670 -f 3670//3670 3658//3658 3660//3660 -f 3670//3670 3660//3660 3671//3671 -f 3672//3672 3673//3673 3674//3674 -f 3675//3675 3676//3676 3677//3677 -f 3677//3677 3676//3676 3678//3678 -f 3677//3677 3678//3678 3679//3679 -f 3680//3680 3681//3681 3682//3682 -f 3683//3683 3684//3684 3685//3685 -f 3686//3686 3687//3687 3688//3688 -f 3689//3689 3635//3635 3690//3690 -f 3691//3691 3661//3661 3692//3692 -f 3662//3662 3652//3652 3693//3693 -f 3693//3693 3652//3652 3694//3694 -f 3693//3693 3694//3694 3695//3695 -f 3695//3695 3694//3694 3696//3696 -f 3695//3695 3696//3696 2682//2682 -f 2682//2682 3696//3696 3697//3697 -f 2682//2682 3697//3697 2681//2681 -f 3698//3698 3699//3699 3700//3700 -f 3700//3700 3699//3699 3701//3701 -f 3661//3661 3691//3691 3660//3660 -f 3660//3660 3691//3691 3702//3702 -f 3660//3660 3702//3702 3703//3703 -f 3704//3704 3660//3660 3705//3705 -f 3705//3705 3660//3660 3703//3703 -f 3705//3705 3703//3703 2682//2682 -f 2682//2682 3703//3703 3706//3706 -f 2682//2682 3706//3706 3695//3695 -f 3682//3682 3707//3707 3708//3708 -f 3686//3686 3688//3688 3709//3709 -f 3680//3680 3682//3682 3710//3710 -f 3639//3639 3711//3711 3640//3640 -f 3640//3640 3711//3711 3712//3712 -f 3640//3640 3712//3712 3701//3701 -f 3701//3701 3712//3712 3713//3713 -f 3701//3701 3713//3713 3700//3700 -f 3607//3607 3609//3609 3714//3714 -f 3714//3714 3609//3609 3715//3715 -f 3714//3714 3715//3715 3716//3716 -f 3716//3716 3715//3715 3710//3710 -f 3716//3716 3710//3710 3717//3717 -f 3717//3717 3710//3710 3682//3682 -f 3717//3717 3682//3682 3687//3687 -f 3687//3687 3682//3682 3708//3708 -f 3687//3687 3708//3708 3688//3688 -f 3718//3718 3719//3719 3720//3720 -f 3685//3685 3721//3721 3683//3683 -f 3683//3683 3721//3721 3722//3722 -f 3683//3683 3722//3722 3723//3723 -f 3723//3723 3722//3722 3724//3724 -f 3723//3723 3724//3724 3725//3725 -f 3725//3725 3724//3724 3726//3726 -f 3725//3725 3726//3726 3677//3677 -f 3677//3677 3726//3726 3727//3727 -f 3677//3677 3727//3727 3675//3675 -f 3675//3675 3727//3727 3728//3728 -f 3675//3675 3728//3728 3729//3729 -f 3729//3729 3728//3728 3691//3691 -f 3729//3729 3691//3691 3730//3730 -f 3730//3730 3691//3691 3692//3692 -f 3630//3630 3731//3731 2734//2734 -f 2734//2734 3731//3731 3732//3732 -f 2734//2734 3732//3732 3733//3733 -f 3733//3733 3732//3732 3707//3707 -f 3733//3733 3707//3707 3734//3734 -f 3734//3734 3707//3707 3682//3682 -f 3735//3735 3634//3634 3736//3736 -f 3737//3737 3738//3738 3739//3739 -f 3739//3739 3738//3738 3740//3740 -f 3739//3739 3740//3740 3741//3741 -f 3720//3720 3742//3742 3718//3718 -f 3718//3718 3742//3742 3743//3743 -f 3718//3718 3743//3743 3744//3744 -f 3744//3744 3743//3743 3745//3745 -f 3744//3744 3745//3745 3746//3746 -f 3746//3746 3745//3745 3747//3747 -f 3746//3746 3747//3747 3683//3683 -f 3683//3683 3747//3747 3748//3748 -f 3683//3683 3748//3748 3684//3684 -f 3684//3684 3748//3748 3749//3749 -f 3684//3684 3749//3749 3688//3688 -f 3688//3688 3749//3749 3750//3750 -f 3688//3688 3750//3750 3709//3709 -f 3634//3634 3735//3735 3635//3635 -f 3635//3635 3735//3735 3751//3751 -f 3635//3635 3751//3751 3690//3690 -f 3620//3620 3752//3752 3753//3753 -f 3672//3672 3674//3674 3754//3754 -f 3622//3622 3621//3621 3690//3690 -f 3690//3690 3621//3621 3755//3755 -f 3690//3690 3755//3755 3689//3689 -f 3713//3713 3756//3756 3700//3700 -f 3700//3700 3756//3756 3757//3757 -f 3700//3700 3757//3757 3758//3758 -f 3758//3758 3757//3757 3752//3752 -f 3758//3758 3752//3752 3759//3759 -f 3759//3759 3752//3752 3620//3620 -f 3760//3760 3647//3647 3761//3761 -f 3761//3761 3647//3647 3649//3649 -f 3761//3761 3649//3649 3762//3762 -f 3762//3762 3649//3649 3763//3763 -f 3762//3762 3763//3763 3764//3764 -f 3764//3764 3763//3763 3653//3653 -f 3764//3764 3653//3653 3765//3765 -f 3765//3765 3653//3653 3620//3620 -f 3765//3765 3620//3620 3673//3673 -f 3673//3673 3620//3620 3753//3753 -f 3673//3673 3753//3753 3674//3674 -f 3740//3740 3766//3766 3741//3741 -f 3741//3741 3766//3766 3767//3767 -f 3741//3741 3767//3767 3768//3768 -f 3768//3768 3767//3767 3769//3769 -f 3768//3768 3769//3769 3718//3718 -f 3718//3718 3769//3769 3770//3770 -f 3718//3718 3770//3770 3719//3719 -f 3719//3719 3770//3770 3771//3771 -f 3719//3719 3771//3771 3772//3772 -f 3772//3772 3771//3771 3735//3735 -f 3772//3772 3735//3735 3773//3773 -f 3773//3773 3735//3735 3736//3736 -f 3678//3678 3774//3774 3679//3679 -f 3679//3679 3774//3774 3775//3775 -f 3679//3679 3775//3775 3776//3776 -f 3776//3776 3775//3775 3777//3777 -f 3776//3776 3777//3777 3739//3739 -f 3739//3739 3777//3777 3778//3778 -f 3739//3739 3778//3778 3737//3737 -f 3737//3737 3778//3778 3779//3779 -f 3737//3737 3779//3779 3674//3674 -f 3674//3674 3779//3779 3780//3780 -f 3674//3674 3780//3780 3754//3754 -f 3471//3471 3470//3470 3647//3647 -f 3647//3647 3470//3470 3648//3648 -f 3471//3471 3647//3647 3760//3760 -f 3471//3471 3760//3760 3473//3473 -f 3473//3473 3760//3760 3761//3761 -f 3473//3473 3761//3761 3482//3482 -f 3482//3482 3761//3761 3762//3762 -f 3482//3482 3762//3762 3469//3469 -f 3468//3468 3469//3469 3764//3764 -f 3764//3764 3469//3469 3762//3762 -f 3468//3468 3764//3764 3439//3439 -f 3439//3439 3764//3764 3765//3765 -f 3439//3439 3765//3765 3440//3440 -f 3440//3440 3765//3765 3673//3673 -f 3440//3440 3673//3673 3531//3531 -f 3531//3531 3673//3673 3672//3672 -f 3587//3587 3531//3531 3754//3754 -f 3754//3754 3531//3531 3672//3672 -f 3587//3587 3754//3754 3586//3586 -f 3586//3586 3754//3754 3780//3780 -f 3586//3586 3780//3780 3492//3492 -f 3492//3492 3780//3780 3779//3779 -f 3493//3493 3492//3492 3778//3778 -f 3778//3778 3492//3492 3779//3779 -f 3493//3493 3778//3778 3495//3495 -f 3495//3495 3778//3778 3777//3777 -f 3495//3495 3777//3777 3571//3571 -f 3571//3571 3777//3777 3775//3775 -f 3572//3572 3571//3571 3774//3774 -f 3774//3774 3571//3571 3775//3775 -f 3572//3572 3774//3774 3574//3574 -f 3574//3574 3774//3774 3678//3678 -f 3574//3574 3678//3678 3575//3575 -f 3575//3575 3678//3678 3676//3676 -f 3576//3576 3575//3575 3675//3675 -f 3675//3675 3575//3575 3676//3676 -f 3576//3576 3675//3675 3577//3577 -f 3577//3577 3675//3675 3729//3729 -f 3577//3577 3729//3729 3529//3529 -f 3529//3529 3729//3729 3730//3730 -f 3477//3477 3529//3529 3692//3692 -f 3692//3692 3529//3529 3730//3730 -f 3477//3477 3692//3692 3478//3478 -f 3478//3478 3692//3692 3661//3661 -f 3478//3478 3661//3661 3552//3552 -f 3552//3552 3661//3661 3659//3659 -f 3552//3552 3659//3659 3551//3551 -f 3551//3551 3659//3659 3658//3658 -f 3549//3549 3551//3551 3669//3669 -f 3669//3669 3551//3551 3658//3658 -f 3549//3549 3669//3669 3626//3626 -f 3549//3549 3626//3626 3548//3548 -f 3548//3548 3626//3626 3625//3625 -f 3548//3548 3625//3625 3547//3547 -f 3547//3547 3625//3625 3624//3624 -f 3547//3547 3624//3624 3416//3416 -f 3417//3417 3416//3416 3665//3665 -f 3665//3665 3416//3416 3624//3624 -f 3418//3418 3417//3417 3666//3666 -f 3666//3666 3417//3417 3665//3665 -f 3418//3418 3666//3666 3550//3550 -f 3550//3550 3666//3666 3667//3667 -f 3550//3550 3667//3667 3480//3480 -f 3480//3480 3667//3667 3668//3668 -f 3480//3480 3668//3668 3454//3454 -f 3454//3454 3668//3668 3670//3670 -f 3455//3455 3454//3454 3671//3671 -f 3671//3671 3454//3454 3670//3670 -f 3456//3456 3455//3455 3660//3660 -f 3660//3660 3455//3455 3671//3671 -f 3456//3456 3660//3660 3704//3704 -f 3456//3456 3704//3704 3546//3546 -f 3546//3546 3704//3704 3705//3705 -f 3546//3546 3705//3705 3545//3545 -f 3545//3545 3705//3705 2682//2682 -f 3545//3545 2682//2682 3065//3065 -f 3078//3078 3065//3065 2681//2681 -f 2681//2681 3065//3065 2682//2682 -f 3516//3516 3078//3078 3697//3697 -f 3697//3697 3078//3078 2681//2681 -f 3516//3516 3697//3697 3515//3515 -f 3515//3515 3697//3697 3696//3696 -f 3515//3515 3696//3696 3541//3541 -f 3541//3541 3696//3696 3694//3694 -f 3541//3541 3694//3694 3525//3525 -f 3525//3525 3694//3694 3652//3652 -f 3523//3523 3525//3525 3651//3651 -f 3651//3651 3525//3525 3652//3652 -f 3524//3524 3523//3523 3650//3650 -f 3650//3650 3523//3523 3651//3651 -f 3524//3524 3650//3650 3664//3664 -f 3524//3524 3664//3664 3526//3526 -f 3526//3526 3664//3664 3663//3663 -f 3526//3526 3663//3663 3542//3542 -f 3542//3542 3663//3663 3662//3662 -f 3542//3542 3662//3662 3513//3513 -f 3514//3514 3513//3513 3693//3693 -f 3693//3693 3513//3513 3662//3662 -f 3514//3514 3693//3693 3543//3543 -f 3543//3543 3693//3693 3695//3695 -f 3543//3543 3695//3695 3544//3544 -f 3544//3544 3695//3695 3706//3706 -f 3544//3544 3706//3706 3527//3527 -f 3527//3527 3706//3706 3703//3703 -f 3528//3528 3527//3527 3702//3702 -f 3702//3702 3527//3527 3703//3703 -f 3528//3528 3702//3702 3479//3479 -f 3479//3479 3702//3702 3691//3691 -f 3479//3479 3691//3691 3517//3517 -f 3517//3517 3691//3691 3728//3728 -f 3518//3518 3517//3517 3727//3727 -f 3727//3727 3517//3517 3728//3728 -f 3518//3518 3727//3727 3520//3520 -f 3520//3520 3727//3727 3726//3726 -f 3520//3520 3726//3726 3558//3558 -f 3558//3558 3726//3726 3724//3724 -f 3559//3559 3558//3558 3722//3722 -f 3722//3722 3558//3558 3724//3724 -f 3559//3559 3722//3722 3561//3561 -f 3561//3561 3722//3722 3721//3721 -f 3561//3561 3721//3721 3562//3562 -f 3562//3562 3721//3721 3685//3685 -f 3563//3563 3562//3562 3684//3684 -f 3684//3684 3562//3562 3685//3685 -f 3563//3563 3684//3684 3511//3511 -f 3511//3511 3684//3684 3688//3688 -f 3511//3511 3688//3688 3522//3522 -f 3522//3522 3688//3688 3708//3708 -f 3485//3485 3522//3522 3707//3707 -f 3707//3707 3522//3522 3708//3708 -f 3485//3485 3707//3707 3442//3442 -f 3442//3442 3707//3707 3732//3732 -f 3442//3442 3732//3732 3443//3443 -f 3443//3443 3732//3732 3731//3731 -f 3443//3443 3731//3731 3463//3463 -f 3463//3463 3731//3731 3630//3630 -f 3446//3446 3463//3463 3628//3628 -f 3628//3628 3463//3463 3630//3630 -f 3446//3446 3628//3628 3627//3627 -f 3446//3446 3627//3627 3445//3445 -f 3445//3445 3627//3627 3606//3606 -f 3445//3445 3606//3606 3444//3444 -f 3444//3444 3606//3606 3604//3604 -f 3444//3444 3604//3604 3429//3429 -f 3430//3430 3429//3429 3603//3603 -f 3603//3603 3429//3429 3604//3604 -f 3431//3431 3430//3430 3605//3605 -f 3605//3605 3430//3430 3603//3603 -f 3431//3431 3605//3605 3464//3464 -f 3464//3464 3605//3605 3629//3629 -f 3464//3464 3629//3629 3465//3465 -f 3465//3465 3629//3629 3631//3631 -f 3465//3465 3631//3631 3466//3466 -f 3466//3466 3631//3631 3632//3632 -f 3080//3080 3466//3466 2749//2749 -f 2749//2749 3466//3466 3632//3632 -f 3081//3081 3080//3080 2734//2734 -f 2734//2734 3080//3080 2749//2749 -f 3081//3081 2734//2734 3733//3733 -f 3081//3081 3733//3733 3540//3540 -f 3540//3540 3733//3733 3734//3734 -f 3540//3540 3734//3734 3483//3483 -f 3483//3483 3734//3734 3682//3682 -f 3483//3483 3682//3682 3484//3484 -f 3499//3499 3484//3484 3681//3681 -f 3681//3681 3484//3484 3682//3682 -f 3498//3498 3499//3499 3680//3680 -f 3680//3680 3499//3499 3681//3681 -f 3498//3498 3680//3680 3438//3438 -f 3438//3438 3680//3680 3710//3710 -f 3438//3438 3710//3710 3437//3437 -f 3437//3437 3710//3710 3715//3715 -f 3437//3437 3715//3715 3436//3436 -f 3436//3436 3715//3715 3609//3609 -f 3435//3435 3436//3436 3611//3611 -f 3611//3611 3436//3436 3609//3609 -f 3413//3413 3435//3435 3610//3610 -f 3610//3610 3435//3435 3611//3611 -f 3413//3413 3610//3610 3608//3608 -f 3413//3413 3608//3608 3414//3414 -f 3414//3414 3608//3608 3607//3607 -f 3414//3414 3607//3607 3415//3415 -f 3415//3415 3607//3607 3714//3714 -f 3415//3415 3714//3714 3497//3497 -f 3489//3489 3497//3497 3716//3716 -f 3716//3716 3497//3497 3714//3714 -f 3489//3489 3716//3716 3490//3490 -f 3490//3490 3716//3716 3717//3717 -f 3490//3490 3717//3717 3491//3491 -f 3491//3491 3717//3717 3687//3687 -f 3491//3491 3687//3687 3512//3512 -f 3512//3512 3687//3687 3686//3686 -f 3565//3565 3512//3512 3709//3709 -f 3709//3709 3512//3512 3686//3686 -f 3565//3565 3709//3709 3564//3564 -f 3564//3564 3709//3709 3750//3750 -f 3564//3564 3750//3750 3487//3487 -f 3487//3487 3750//3750 3749//3749 -f 3488//3488 3487//3487 3748//3748 -f 3748//3748 3487//3487 3749//3749 -f 3488//3488 3748//3748 3588//3588 -f 3588//3588 3748//3748 3747//3747 -f 3588//3588 3747//3747 3589//3589 -f 3589//3589 3747//3747 3745//3745 -f 3591//3591 3589//3589 3743//3743 -f 3743//3743 3589//3589 3745//3745 -f 3591//3591 3743//3743 3593//3593 -f 3593//3593 3743//3743 3742//3742 -f 3593//3593 3742//3742 3594//3594 -f 3594//3594 3742//3742 3720//3720 -f 3595//3595 3594//3594 3719//3719 -f 3719//3719 3594//3594 3720//3720 -f 3595//3595 3719//3719 3596//3596 -f 3596//3596 3719//3719 3772//3772 -f 3596//3596 3772//3772 3539//3539 -f 3539//3539 3772//3772 3773//3773 -f 3502//3502 3539//3539 3736//3736 -f 3736//3736 3539//3539 3773//3773 -f 3502//3502 3736//3736 3503//3503 -f 3503//3503 3736//3736 3634//3634 -f 3503//3503 3634//3634 3557//3557 -f 3557//3557 3634//3634 3633//3633 -f 3557//3557 3633//3633 3556//3556 -f 3556//3556 3633//3633 3646//3646 -f 3554//3554 3556//3556 3599//3599 -f 3599//3599 3556//3556 3646//3646 -f 3554//3554 3599//3599 3598//3598 -f 3554//3554 3598//3598 3424//3424 -f 3424//3424 3598//3598 3597//3597 -f 3424//3424 3597//3597 3425//3425 -f 3425//3425 3597//3597 3614//3614 -f 3425//3425 3614//3614 3427//3427 -f 3428//3428 3427//3427 3613//3613 -f 3613//3613 3427//3427 3614//3614 -f 3426//3426 3428//3428 3612//3612 -f 3612//3612 3428//3428 3613//3613 -f 3426//3426 3612//3612 3555//3555 -f 3555//3555 3612//3612 3654//3654 -f 3555//3555 3654//3654 3467//3467 -f 3467//3467 3654//3654 3655//3655 -f 3467//3467 3655//3655 3432//3432 -f 3432//3432 3655//3655 3656//3656 -f 3433//3433 3432//3432 3657//3657 -f 3657//3657 3432//3432 3656//3656 -f 3434//3434 3433//3433 3635//3635 -f 3635//3635 3433//3433 3657//3657 -f 3434//3434 3635//3635 3689//3689 -f 3434//3434 3689//3689 3570//3570 -f 3570//3570 3689//3689 3755//3755 -f 3570//3570 3755//3755 3569//3569 -f 3569//3569 3755//3755 3621//3621 -f 3569//3569 3621//3621 3449//3449 -f 3447//3447 3449//3449 3645//3645 -f 3645//3645 3449//3449 3621//3621 -f 3448//3448 3447//3447 3644//3644 -f 3644//3644 3447//3447 3645//3645 -f 3448//3448 3644//3644 3450//3450 -f 3450//3450 3644//3644 3643//3643 -f 3450//3450 3643//3643 3423//3423 -f 3423//3423 3643//3643 3642//3642 -f 3423//3423 3642//3642 3421//3421 -f 3421//3421 3642//3642 3602//3602 -f 3419//3419 3421//3421 3601//3601 -f 3601//3601 3421//3421 3602//3602 -f 3420//3420 3419//3419 3600//3600 -f 3600//3600 3419//3419 3601//3601 -f 3420//3420 3600//3600 3615//3615 -f 3420//3420 3615//3615 3422//3422 -f 3422//3422 3615//3615 3616//3616 -f 3422//3422 3616//3616 3457//3457 -f 3457//3457 3616//3616 3617//3617 -f 3457//3457 3617//3617 3458//3458 -f 3459//3459 3458//3458 3641//3641 -f 3641//3641 3458//3458 3617//3617 -f 3459//3459 3641//3641 3567//3567 -f 3567//3567 3641//3641 3623//3623 -f 3567//3567 3623//3623 3568//3568 -f 3568//3568 3623//3623 3622//3622 -f 3568//3568 3622//3622 3537//3537 -f 3537//3537 3622//3622 3690//3690 -f 3538//3538 3537//3537 3751//3751 -f 3751//3751 3537//3537 3690//3690 -f 3538//3538 3751//3751 3504//3504 -f 3504//3504 3751//3751 3735//3735 -f 3504//3504 3735//3735 3509//3509 -f 3509//3509 3735//3735 3771//3771 -f 3510//3510 3509//3509 3770//3770 -f 3770//3770 3509//3509 3771//3771 -f 3510//3510 3770//3770 3578//3578 -f 3578//3578 3770//3770 3769//3769 -f 3578//3578 3769//3769 3579//3579 -f 3579//3579 3769//3769 3767//3767 -f 3581//3581 3579//3579 3766//3766 -f 3766//3766 3579//3579 3767//3767 -f 3581//3581 3766//3766 3583//3583 -f 3583//3583 3766//3766 3740//3740 -f 3583//3583 3740//3740 3584//3584 -f 3584//3584 3740//3740 3738//3738 -f 3585//3585 3584//3584 3737//3737 -f 3737//3737 3584//3584 3738//3738 -f 3585//3585 3737//3737 3530//3530 -f 3530//3530 3737//3737 3674//3674 -f 3530//3530 3674//3674 3553//3553 -f 3553//3553 3674//3674 3753//3753 -f 3501//3501 3553//3553 3752//3752 -f 3752//3752 3553//3553 3753//3753 -f 3501//3501 3752//3752 3506//3506 -f 3506//3506 3752//3752 3757//3757 -f 3506//3506 3757//3757 3507//3507 -f 3507//3507 3757//3757 3756//3756 -f 3507//3507 3756//3756 3532//3532 -f 3532//3532 3756//3756 3713//3713 -f 3474//3474 3532//3532 3712//3712 -f 3712//3712 3532//3532 3713//3713 -f 3474//3474 3712//3712 3711//3711 -f 3474//3474 3711//3711 3475//3475 -f 3475//3475 3711//3711 3639//3639 -f 3475//3475 3639//3639 3476//3476 -f 3476//3476 3639//3639 3637//3637 -f 3476//3476 3637//3637 3460//3460 -f 3461//3461 3460//3460 3636//3636 -f 3636//3636 3460//3460 3637//3637 -f 3462//3462 3461//3461 3638//3638 -f 3638//3638 3461//3461 3636//3636 -f 3462//3462 3638//3638 3533//3533 -f 3533//3533 3638//3638 3640//3640 -f 3533//3533 3640//3640 3534//3534 -f 3534//3534 3640//3640 3701//3701 -f 3534//3534 3701//3701 3535//3535 -f 3535//3535 3701//3701 3699//3699 -f 3536//3536 3535//3535 3698//3698 -f 3698//3698 3535//3535 3699//3699 -f 3505//3505 3536//3536 3700//3700 -f 3700//3700 3536//3536 3698//3698 -f 3505//3505 3700//3700 3758//3758 -f 3505//3505 3758//3758 3566//3566 -f 3566//3566 3758//3758 3759//3759 -f 3566//3566 3759//3759 3500//3500 -f 3500//3500 3759//3759 3620//3620 -f 3500//3500 3620//3620 3441//3441 -f 3453//3453 3441//3441 3619//3619 -f 3619//3619 3441//3441 3620//3620 -f 3452//3452 3453//3453 3618//3618 -f 3618//3618 3453//3453 3619//3619 -f 3452//3452 3618//3618 3451//3451 -f 3451//3451 3618//3618 3653//3653 -f 3451//3451 3653//3653 3481//3481 -f 3481//3481 3653//3653 3763//3763 -f 3481//3481 3763//3763 3472//3472 -f 3472//3472 3763//3763 3649//3649 -f 3470//3470 3472//3472 3648//3648 -f 3648//3648 3472//3472 3649//3649 -f 3496//3496 3679//3679 3494//3494 -f 3494//3494 3679//3679 3776//3776 -f 3494//3494 3776//3776 3582//3582 -f 3582//3582 3776//3776 3739//3739 -f 3582//3582 3739//3739 3580//3580 -f 3580//3580 3739//3739 3741//3741 -f 3580//3580 3741//3741 3508//3508 -f 3508//3508 3741//3741 3768//3768 -f 3508//3508 3768//3768 3592//3592 -f 3592//3592 3768//3768 3718//3718 -f 3592//3592 3718//3718 3590//3590 -f 3590//3590 3718//3718 3744//3744 -f 3590//3590 3744//3744 3486//3486 -f 3486//3486 3744//3744 3746//3746 -f 3486//3486 3746//3746 3560//3560 -f 3560//3560 3746//3746 3683//3683 -f 3560//3560 3683//3683 3521//3521 -f 3521//3521 3683//3683 3723//3723 -f 3521//3521 3723//3723 3519//3519 -f 3519//3519 3723//3723 3725//3725 -f 3519//3519 3725//3725 3573//3573 -f 3573//3573 3725//3725 3677//3677 -f 3573//3573 3677//3677 3496//3496 -f 3496//3496 3677//3677 3679//3679 -f 3781//3781 3782//3782 3783//3783 -f 3784//3784 3785//3785 3786//3786 -f 3787//3787 3788//3788 3789//3789 -f 3789//3789 3788//3788 3790//3790 -f 3789//3789 3790//3790 3791//3791 -f 3792//3792 3793//3793 3794//3794 -f 3794//3794 3793//3793 3795//3795 -f 3794//3794 3795//3795 3796//3796 -f 3797//3797 3798//3798 3799//3799 -f 3800//3800 3801//3801 3802//3802 -f 3803//3803 3781//3781 3804//3804 -f 3804//3804 3781//3781 3783//3783 -f 3804//3804 3783//3783 3805//3805 -f 3805//3805 3783//3783 3806//3806 -f 3807//3807 3808//3808 3809//3809 -f 3810//3810 3811//3811 3812//3812 -f 3813//3813 3797//3797 3814//3814 -f 3814//3814 3797//3797 3799//3799 -f 3814//3814 3799//3799 3815//3815 -f 3816//3816 3817//3817 3818//3818 -f 3818//3818 3817//3817 3819//3819 -f 3820//3820 3809//3809 3821//3821 -f 3821//3821 3809//3809 3822//3822 -f 3823//3823 3824//3824 3825//3825 -f 3790//3790 3826//3826 3791//3791 -f 3791//3791 3826//3826 3827//3827 -f 3791//3791 3827//3827 3819//3819 -f 3819//3819 3827//3827 3828//3828 -f 3819//3819 3828//3828 3818//3818 -f 3829//3829 3830//3830 3831//3831 -f 3815//3815 3799//3799 3832//3832 -f 3832//3832 3799//3799 3833//3833 -f 3832//3832 3833//3833 3812//3812 -f 3812//3812 3833//3833 3834//3834 -f 3812//3812 3834//3834 3810//3810 -f 3810//3810 3834//3834 3835//3835 -f 3810//3810 3835//3835 3836//3836 -f 3800//3800 3802//3802 3837//3837 -f 3807//3807 3809//3809 3838//3838 -f 3838//3838 3809//3809 3820//3820 -f 3838//3838 3820//3820 3839//3839 -f 3840//3840 3841//3841 3842//3842 -f 3842//3842 3841//3841 3843//3843 -f 3844//3844 3845//3845 3831//3831 -f 3831//3831 3845//3845 3846//3846 -f 3831//3831 3846//3846 3829//3829 -f 3847//3847 3848//3848 3849//3849 -f 3823//3823 3825//3825 3850//3850 -f 3820//3820 3851//3851 3839//3839 -f 3839//3839 3851//3851 3842//3842 -f 3839//3839 3842//3842 3852//3852 -f 3852//3852 3842//3842 3843//3843 -f 3853//3853 3854//3854 3855//3855 -f 3856//3856 3857//3857 3858//3858 -f 3859//3859 3860//3860 3854//3854 -f 3854//3854 3860//3860 3861//3861 -f 3862//3862 3863//3863 3864//3864 -f 3864//3864 3863//3863 3865//3865 -f 3864//3864 3865//3865 3866//3866 -f 3783//3783 3867//3867 3806//3806 -f 3806//3806 3867//3867 3859//3859 -f 3806//3806 3859//3859 3868//3868 -f 3868//3868 3859//3859 3854//3854 -f 3868//3868 3854//3854 3869//3869 -f 3870//3870 3809//3809 3871//3871 -f 3872//3872 3873//3873 3874//3874 -f 3875//3875 3876//3876 3877//3877 -f 3878//3878 3879//3879 3880//3880 -f 3881//3881 3861//3861 3882//3882 -f 3883//3883 3884//3884 3885//3885 -f 3885//3885 3884//3884 3886//3886 -f 3885//3885 3886//3886 3887//3887 -f 3887//3887 3886//3886 3888//3888 -f 3889//3889 3890//3890 3891//3891 -f 3891//3891 3890//3890 3892//3892 -f 3891//3891 3892//3892 3893//3893 -f 3861//3861 3881//3881 3854//3854 -f 3854//3854 3881//3881 3894//3894 -f 3854//3854 3894//3894 3855//3855 -f 3895//3895 3896//3896 3897//3897 -f 3897//3897 3896//3896 3898//3898 -f 3825//3825 3899//3899 3900//3900 -f 3847//3847 3849//3849 3901//3901 -f 3902//3902 3808//3808 3903//3903 -f 3844//3844 3831//3831 3904//3904 -f 3904//3904 3831//3831 3905//3905 -f 3904//3904 3905//3905 3877//3877 -f 3877//3877 3905//3905 3906//3906 -f 3877//3877 3906//3906 3875//3875 -f 3875//3875 3906//3906 3907//3907 -f 3875//3875 3907//3907 3908//3908 -f 3802//3802 3909//3909 3910//3910 -f 3872//3872 3874//3874 3911//3911 -f 3811//3811 3810//3810 3855//3855 -f 3855//3855 3810//3810 3912//3912 -f 3855//3855 3912//3912 3853//3853 -f 3885//3885 3913//3913 3883//3883 -f 3883//3883 3913//3913 3897//3897 -f 3883//3883 3897//3897 3914//3914 -f 3914//3914 3897//3897 3898//3898 -f 3884//3884 3915//3915 3886//3886 -f 3886//3886 3915//3915 3916//3916 -f 3886//3886 3916//3916 3917//3917 -f 3917//3917 3916//3916 3899//3899 -f 3917//3917 3899//3899 3918//3918 -f 3918//3918 3899//3899 3825//3825 -f 3919//3919 3784//3784 3920//3920 -f 3920//3920 3784//3784 3786//3786 -f 3920//3920 3786//3786 3921//3921 -f 3921//3921 3786//3786 3922//3922 -f 3921//3921 3922//3922 3923//3923 -f 3923//3923 3922//3922 3850//3850 -f 3923//3923 3850//3850 3924//3924 -f 3924//3924 3850//3850 3825//3825 -f 3924//3924 3825//3825 3848//3848 -f 3848//3848 3825//3825 3900//3900 -f 3848//3848 3900//3900 3849//3849 -f 3808//3808 3902//3902 3809//3809 -f 3809//3809 3902//3902 3925//3925 -f 3809//3809 3925//3925 3871//3871 -f 3792//3792 3794//3794 3926//3926 -f 3926//3926 3794//3794 3927//3927 -f 3926//3926 3927//3927 3928//3928 -f 3928//3928 3927//3927 3837//3837 -f 3928//3928 3837//3837 3929//3929 -f 3929//3929 3837//3837 3802//3802 -f 3929//3929 3802//3802 3873//3873 -f 3873//3873 3802//3802 3910//3910 -f 3873//3873 3910//3910 3874//3874 -f 3892//3892 3930//3930 3893//3893 -f 3893//3893 3930//3930 3931//3931 -f 3893//3893 3931//3931 3932//3932 -f 3932//3932 3931//3931 3933//3933 -f 3932//3932 3933//3933 3856//3856 -f 3856//3856 3933//3933 3934//3934 -f 3856//3856 3934//3934 3857//3857 -f 3857//3857 3934//3934 3935//3935 -f 3857//3857 3935//3935 3936//3936 -f 3936//3936 3935//3935 3881//3881 -f 3936//3936 3881//3881 3937//3937 -f 3937//3937 3881//3881 3882//3882 -f 3876//3876 3875//3875 3871//3871 -f 3871//3871 3875//3875 3938//3938 -f 3871//3871 3938//3938 3870//3870 -f 3828//3828 3939//3939 3818//3818 -f 3818//3818 3939//3939 3940//3940 -f 3818//3818 3940//3940 3941//3941 -f 3941//3941 3940//3940 3909//3909 -f 3941//3941 3909//3909 3942//3942 -f 3942//3942 3909//3909 3802//3802 -f 3865//3865 3943//3943 3866//3866 -f 3866//3866 3943//3943 3944//3944 -f 3866//3866 3944//3944 3945//3945 -f 3945//3945 3944//3944 3946//3946 -f 3945//3945 3946//3946 3891//3891 -f 3891//3891 3946//3946 3947//3947 -f 3891//3891 3947//3947 3889//3889 -f 3889//3889 3947//3947 3948//3948 -f 3889//3889 3948//3948 3849//3849 -f 3849//3849 3948//3948 3949//3949 -f 3849//3849 3949//3949 3901//3901 -f 3880//3880 3950//3950 3878//3878 -f 3878//3878 3950//3950 3951//3951 -f 3878//3878 3951//3951 3952//3952 -f 3952//3952 3951//3951 3953//3953 -f 3952//3952 3953//3953 3954//3954 -f 3954//3954 3953//3953 3955//3955 -f 3954//3954 3955//3955 3864//3864 -f 3864//3864 3955//3955 3956//3956 -f 3864//3864 3956//3956 3862//3862 -f 3862//3862 3956//3956 3957//3957 -f 3862//3862 3957//3957 3958//3958 -f 3958//3958 3957//3957 3902//3902 -f 3958//3958 3902//3902 3959//3959 -f 3959//3959 3902//3902 3903//3903 -f 3858//3858 3960//3960 3856//3856 -f 3856//3856 3960//3960 3961//3961 -f 3856//3856 3961//3961 3962//3962 -f 3962//3962 3961//3961 3963//3963 -f 3962//3962 3963//3963 3964//3964 -f 3964//3964 3963//3963 3965//3965 -f 3964//3964 3965//3965 3878//3878 -f 3878//3878 3965//3965 3966//3966 -f 3878//3878 3966//3966 3879//3879 -f 3879//3879 3966//3966 3967//3967 -f 3879//3879 3967//3967 3874//3874 -f 3874//3874 3967//3967 3968//3968 -f 3874//3874 3968//3968 3911//3911 -f 3969//3969 3970//3970 3971//3971 -f 3972//3972 3973//3973 3974//3974 -f 3975//3975 3976//3976 3977//3977 -f 3977//3977 3976//3976 3978//3978 -f 3979//3979 3980//3980 3981//3981 -f 3981//3981 3980//3980 3982//3982 -f 3981//3981 3982//3982 3983//3983 -f 3984//3984 3985//3985 3986//3986 -f 3987//3987 3972//3972 3988//3988 -f 3988//3988 3972//3972 3974//3974 -f 3988//3988 3974//3974 3989//3989 -f 3990//3990 3991//3991 3992//3992 -f 3993//3993 3994//3994 3995//3995 -f 3996//3996 3997//3997 3998//3998 -f 3978//3978 3999//3999 3977//3977 -f 3977//3977 3999//3999 4000//4000 -f 3977//3977 4000//4000 4001//4001 -f 4001//4001 4000//4000 4002//4002 -f 4001//4001 4002//4002 4003//4003 -f 4003//4003 4002//4002 4004//4004 -f 4003//4003 4004//4004 4005//4005 -f 4005//4005 4004//4004 4006//4006 -f 4007//4007 4008//4008 4009//4009 -f 4010//4010 4011//4011 4012//4012 -f 4012//4012 4011//4011 4013//4013 -f 4012//4012 4013//4013 4014//4014 -f 3989//3989 3974//3974 4015//4015 -f 4015//4015 3974//3974 4016//4016 -f 4015//4015 4016//4016 3995//3995 -f 3995//3995 4016//4016 4017//4017 -f 3995//3995 4017//4017 3993//3993 -f 3993//3993 4017//4017 4018//4018 -f 3993//3993 4018//4018 4019//4019 -f 4007//4007 4009//4009 4020//4020 -f 4021//4021 4022//4022 4023//4023 -f 4024//4024 4025//4025 4026//4026 -f 3990//3990 3992//3992 4027//4027 -f 3986//3986 3969//3969 3984//3984 -f 3984//3984 3969//3969 3971//3971 -f 3984//3984 3971//3971 4028//4028 -f 4028//4028 3971//3971 4020//4020 -f 4028//4028 4020//4020 4029//4029 -f 4029//4029 4020//4020 4009//4009 -f 4029//4029 4009//4009 4030//4030 -f 4030//4030 4009//4009 4031//4031 -f 4032//4032 4033//4033 4034//4034 -f 4034//4034 4033//4033 4035//4035 -f 4036//4036 4037//4037 4026//4026 -f 4026//4026 4037//4037 4038//4038 -f 4026//4026 4038//4038 4024//4024 -f 4039//4039 3996//3996 4040//4040 -f 4040//4040 3996//3996 3998//3998 -f 4040//4040 3998//3998 4041//4041 -f 4041//4041 3998//3998 4042//4042 -f 3998//3998 4043//4043 4042//4042 -f 4042//4042 4043//4043 4032//4032 -f 4042//4042 4032//4032 4044//4044 -f 4044//4044 4032//4032 4034//4034 -f 4044//4044 4034//4034 4045//4045 -f 4046//4046 4047//4047 4048//4048 -f 4049//4049 4050//4050 4051//4051 -f 4051//4051 4050//4050 4052//4052 -f 4051//4051 4052//4052 4053//4053 -f 4054//4054 4055//4055 4056//4056 -f 4057//4057 4058//4058 4059//4059 -f 4060//4060 4061//4061 4062//4062 -f 4063//4063 4009//4009 4064//4064 -f 4065//4065 4035//4035 4066//4066 -f 4036//4036 4026//4026 4067//4067 -f 4067//4067 4026//4026 4068//4068 -f 4067//4067 4068//4068 4069//4069 -f 4069//4069 4068//4068 4070//4070 -f 4069//4069 4070//4070 4071//4071 -f 4071//4071 4070//4070 4072//4072 -f 4071//4071 4072//4072 4073//4073 -f 4074//4074 4075//4075 4076//4076 -f 4076//4076 4075//4075 4077//4077 -f 4035//4035 4065//4065 4034//4034 -f 4034//4034 4065//4065 4078//4078 -f 4034//4034 4078//4078 4079//4079 -f 4080//4080 4034//4034 4081//4081 -f 4081//4081 4034//4034 4079//4079 -f 4081//4081 4079//4079 4071//4071 -f 4071//4071 4079//4079 4082//4082 -f 4071//4071 4082//4082 4069//4069 -f 4056//4056 4083//4083 4084//4084 -f 4060//4060 4062//4062 4085//4085 -f 4054//4054 4056//4056 4086//4086 -f 4013//4013 4087//4087 4014//4014 -f 4014//4014 4087//4087 4088//4088 -f 4014//4014 4088//4088 4077//4077 -f 4077//4077 4088//4088 4089//4089 -f 4077//4077 4089//4089 4076//4076 -f 3979//3979 3981//3981 4090//4090 -f 4090//4090 3981//3981 4091//4091 -f 4090//4090 4091//4091 4092//4092 -f 4092//4092 4091//4091 4086//4086 -f 4092//4092 4086//4086 4093//4093 -f 4093//4093 4086//4086 4056//4056 -f 4093//4093 4056//4056 4061//4061 -f 4061//4061 4056//4056 4084//4084 -f 4061//4061 4084//4084 4062//4062 -f 4094//4094 4095//4095 4096//4096 -f 4059//4059 4097//4097 4057//4057 -f 4057//4057 4097//4097 4098//4098 -f 4057//4057 4098//4098 4099//4099 -f 4099//4099 4098//4098 4100//4100 -f 4099//4099 4100//4100 4101//4101 -f 4101//4101 4100//4100 4102//4102 -f 4101//4101 4102//4102 4051//4051 -f 4051//4051 4102//4102 4103//4103 -f 4051//4051 4103//4103 4049//4049 -f 4049//4049 4103//4103 4104//4104 -f 4049//4049 4104//4104 4105//4105 -f 4105//4105 4104//4104 4065//4065 -f 4105//4105 4065//4065 4106//4106 -f 4106//4106 4065//4065 4066//4066 -f 4002//4002 4107//4107 4004//4004 -f 4004//4004 4107//4107 4108//4108 -f 4004//4004 4108//4108 4109//4109 -f 4109//4109 4108//4108 4083//4083 -f 4109//4109 4083//4083 4110//4110 -f 4110//4110 4083//4083 4056//4056 -f 4111//4111 4008//4008 4112//4112 -f 4113//4113 4114//4114 4115//4115 -f 4115//4115 4114//4114 4116//4116 -f 4115//4115 4116//4116 4117//4117 -f 4096//4096 4118//4118 4094//4094 -f 4094//4094 4118//4118 4119//4119 -f 4094//4094 4119//4119 4120//4120 -f 4120//4120 4119//4119 4121//4121 -f 4120//4120 4121//4121 4122//4122 -f 4122//4122 4121//4121 4123//4123 -f 4122//4122 4123//4123 4057//4057 -f 4057//4057 4123//4123 4124//4124 -f 4057//4057 4124//4124 4058//4058 -f 4058//4058 4124//4124 4125//4125 -f 4058//4058 4125//4125 4062//4062 -f 4062//4062 4125//4125 4126//4126 -f 4062//4062 4126//4126 4085//4085 -f 4008//4008 4111//4111 4009//4009 -f 4009//4009 4111//4111 4127//4127 -f 4009//4009 4127//4127 4064//4064 -f 3992//3992 4128//4128 4129//4129 -f 4046//4046 4048//4048 4130//4130 -f 3994//3994 3993//3993 4064//4064 -f 4064//4064 3993//3993 4131//4131 -f 4064//4064 4131//4131 4063//4063 -f 4089//4089 4132//4132 4076//4076 -f 4076//4076 4132//4132 4133//4133 -f 4076//4076 4133//4133 4134//4134 -f 4134//4134 4133//4133 4128//4128 -f 4134//4134 4128//4128 4135//4135 -f 4135//4135 4128//4128 3992//3992 -f 4136//4136 4021//4021 4137//4137 -f 4137//4137 4021//4021 4023//4023 -f 4137//4137 4023//4023 4138//4138 -f 4138//4138 4023//4023 4139//4139 -f 4138//4138 4139//4139 4140//4140 -f 4140//4140 4139//4139 4027//4027 -f 4140//4140 4027//4027 4141//4141 -f 4141//4141 4027//4027 3992//3992 -f 4141//4141 3992//3992 4047//4047 -f 4047//4047 3992//3992 4129//4129 -f 4047//4047 4129//4129 4048//4048 -f 4116//4116 4142//4142 4117//4117 -f 4117//4117 4142//4142 4143//4143 -f 4117//4117 4143//4143 4144//4144 -f 4144//4144 4143//4143 4145//4145 -f 4144//4144 4145//4145 4094//4094 -f 4094//4094 4145//4145 4146//4146 -f 4094//4094 4146//4146 4095//4095 -f 4095//4095 4146//4146 4147//4147 -f 4095//4095 4147//4147 4148//4148 -f 4148//4148 4147//4147 4111//4111 -f 4148//4148 4111//4111 4149//4149 -f 4149//4149 4111//4111 4112//4112 -f 4052//4052 4150//4150 4053//4053 -f 4053//4053 4150//4150 4151//4151 -f 4053//4053 4151//4151 4152//4152 -f 4152//4152 4151//4151 4153//4153 -f 4152//4152 4153//4153 4115//4115 -f 4115//4115 4153//4153 4154//4154 -f 4115//4115 4154//4154 4113//4113 -f 4113//4113 4154//4154 4155//4155 -f 4113//4113 4155//4155 4048//4048 -f 4048//4048 4155//4155 4156//4156 -f 4048//4048 4156//4156 4130//4130 -f 3841//3841 3840//3840 4021//4021 -f 4021//4021 3840//3840 4022//4022 -f 3841//3841 4021//4021 4136//4136 -f 3841//3841 4136//4136 3843//3843 -f 3843//3843 4136//4136 4137//4137 -f 3843//3843 4137//4137 3852//3852 -f 3852//3852 4137//4137 4138//4138 -f 3852//3852 4138//4138 3839//3839 -f 3838//3838 3839//3839 4140//4140 -f 4140//4140 3839//3839 4138//4138 -f 3838//3838 4140//4140 3807//3807 -f 3807//3807 4140//4140 4141//4141 -f 3807//3807 4141//4141 3808//3808 -f 3808//3808 4141//4141 4047//4047 -f 3808//3808 4047//4047 3903//3903 -f 3903//3903 4047//4047 4046//4046 -f 3959//3959 3903//3903 4130//4130 -f 4130//4130 3903//3903 4046//4046 -f 3959//3959 4130//4130 3958//3958 -f 3958//3958 4130//4130 4156//4156 -f 3958//3958 4156//4156 3862//3862 -f 3862//3862 4156//4156 4155//4155 -f 3863//3863 3862//3862 4154//4154 -f 4154//4154 3862//3862 4155//4155 -f 3863//3863 4154//4154 3865//3865 -f 3865//3865 4154//4154 4153//4153 -f 3865//3865 4153//4153 3943//3943 -f 3943//3943 4153//4153 4151//4151 -f 3944//3944 3943//3943 4150//4150 -f 4150//4150 3943//3943 4151//4151 -f 3944//3944 4150//4150 3946//3946 -f 3946//3946 4150//4150 4052//4052 -f 3946//3946 4052//4052 3947//3947 -f 3947//3947 4052//4052 4050//4050 -f 3948//3948 3947//3947 4049//4049 -f 4049//4049 3947//3947 4050//4050 -f 3948//3948 4049//4049 3949//3949 -f 3949//3949 4049//4049 4105//4105 -f 3949//3949 4105//4105 3901//3901 -f 3901//3901 4105//4105 4106//4106 -f 3847//3847 3901//3901 4066//4066 -f 4066//4066 3901//3901 4106//4106 -f 3847//3847 4066//4066 3848//3848 -f 3848//3848 4066//4066 4035//4035 -f 3848//3848 4035//4035 3924//3924 -f 3924//3924 4035//4035 4033//4033 -f 3924//3924 4033//4033 3923//3923 -f 3923//3923 4033//4033 4032//4032 -f 3921//3921 3923//3923 4043//4043 -f 4043//4043 3923//3923 4032//4032 -f 3921//3921 4043//4043 3998//3998 -f 3921//3921 3998//3998 3920//3920 -f 3920//3920 3998//3998 3997//3997 -f 3920//3920 3997//3997 3919//3919 -f 3919//3919 3997//3997 3996//3996 -f 3919//3919 3996//3996 3784//3784 -f 3785//3785 3784//3784 4039//4039 -f 4039//4039 3784//3784 3996//3996 -f 3786//3786 3785//3785 4040//4040 -f 4040//4040 3785//3785 4039//4039 -f 3786//3786 4040//4040 3922//3922 -f 3922//3922 4040//4040 4041//4041 -f 3922//3922 4041//4041 3850//3850 -f 3850//3850 4041//4041 4042//4042 -f 3850//3850 4042//4042 3823//3823 -f 3823//3823 4042//4042 4044//4044 -f 3824//3824 3823//3823 4045//4045 -f 4045//4045 3823//3823 4044//4044 -f 3825//3825 3824//3824 4034//4034 -f 4034//4034 3824//3824 4045//4045 -f 3825//3825 4034//4034 4080//4080 -f 3825//3825 4080//4080 3918//3918 -f 3918//3918 4080//4080 4081//4081 -f 3918//3918 4081//4081 3917//3917 -f 3917//3917 4081//4081 4071//4071 -f 3917//3917 4071//4071 3886//3886 -f 3888//3888 3886//3886 4073//4073 -f 4073//4073 3886//3886 4071//4071 -f 3887//3887 3888//3888 4072//4072 -f 4072//4072 3888//3888 4073//4073 -f 3887//3887 4072//4072 3885//3885 -f 3885//3885 4072//4072 4070//4070 -f 3885//3885 4070//4070 3913//3913 -f 3913//3913 4070//4070 4068//4068 -f 3913//3913 4068//4068 3897//3897 -f 3897//3897 4068//4068 4026//4026 -f 3895//3895 3897//3897 4025//4025 -f 4025//4025 3897//3897 4026//4026 -f 3896//3896 3895//3895 4024//4024 -f 4024//4024 3895//3895 4025//4025 -f 3896//3896 4024//4024 4038//4038 -f 3896//3896 4038//4038 3898//3898 -f 3898//3898 4038//4038 4037//4037 -f 3898//3898 4037//4037 3914//3914 -f 3914//3914 4037//4037 4036//4036 -f 3914//3914 4036//4036 3883//3883 -f 3884//3884 3883//3883 4067//4067 -f 4067//4067 3883//3883 4036//4036 -f 3884//3884 4067//4067 3915//3915 -f 3915//3915 4067//4067 4069//4069 -f 3915//3915 4069//4069 3916//3916 -f 3916//3916 4069//4069 4082//4082 -f 3916//3916 4082//4082 3899//3899 -f 3899//3899 4082//4082 4079//4079 -f 3900//3900 3899//3899 4078//4078 -f 4078//4078 3899//3899 4079//4079 -f 3900//3900 4078//4078 3849//3849 -f 3849//3849 4078//4078 4065//4065 -f 3849//3849 4065//4065 3889//3889 -f 3889//3889 4065//4065 4104//4104 -f 3890//3890 3889//3889 4103//4103 -f 4103//4103 3889//3889 4104//4104 -f 3890//3890 4103//4103 3892//3892 -f 3892//3892 4103//4103 4102//4102 -f 3892//3892 4102//4102 3930//3930 -f 3930//3930 4102//4102 4100//4100 -f 3931//3931 3930//3930 4098//4098 -f 4098//4098 3930//3930 4100//4100 -f 3931//3931 4098//4098 3933//3933 -f 3933//3933 4098//4098 4097//4097 -f 3933//3933 4097//4097 3934//3934 -f 3934//3934 4097//4097 4059//4059 -f 3935//3935 3934//3934 4058//4058 -f 4058//4058 3934//3934 4059//4059 -f 3935//3935 4058//4058 3881//3881 -f 3881//3881 4058//4058 4062//4062 -f 3881//3881 4062//4062 3894//3894 -f 3894//3894 4062//4062 4084//4084 -f 3855//3855 3894//3894 4083//4083 -f 4083//4083 3894//3894 4084//4084 -f 3855//3855 4083//4083 3811//3811 -f 3811//3811 4083//4083 4108//4108 -f 3811//3811 4108//4108 3812//3812 -f 3812//3812 4108//4108 4107//4107 -f 3812//3812 4107//4107 3832//3832 -f 3832//3832 4107//4107 4002//4002 -f 3815//3815 3832//3832 4000//4000 -f 4000//4000 3832//3832 4002//4002 -f 3815//3815 4000//4000 3999//3999 -f 3815//3815 3999//3999 3814//3814 -f 3814//3814 3999//3999 3978//3978 -f 3814//3814 3978//3978 3813//3813 -f 3813//3813 3978//3978 3976//3976 -f 3813//3813 3976//3976 3797//3797 -f 3798//3798 3797//3797 3975//3975 -f 3975//3975 3797//3797 3976//3976 -f 3799//3799 3798//3798 3977//3977 -f 3977//3977 3798//3798 3975//3975 -f 3799//3799 3977//3977 3833//3833 -f 3833//3833 3977//3977 4001//4001 -f 3833//3833 4001//4001 3834//3834 -f 3834//3834 4001//4001 4003//4003 -f 3834//3834 4003//4003 3835//3835 -f 3835//3835 4003//4003 4005//4005 -f 3836//3836 3835//3835 4006//4006 -f 4006//4006 3835//3835 4005//4005 -f 3810//3810 3836//3836 4004//4004 -f 4004//4004 3836//3836 4006//4006 -f 3810//3810 4004//4004 4109//4109 -f 3810//3810 4109//4109 3912//3912 -f 3912//3912 4109//4109 4110//4110 -f 3912//3912 4110//4110 3853//3853 -f 3853//3853 4110//4110 4056//4056 -f 3853//3853 4056//4056 3854//3854 -f 3869//3869 3854//3854 4055//4055 -f 4055//4055 3854//3854 4056//4056 -f 3868//3868 3869//3869 4054//4054 -f 4054//4054 3869//3869 4055//4055 -f 3868//3868 4054//4054 3806//3806 -f 3806//3806 4054//4054 4086//4086 -f 3806//3806 4086//4086 3805//3805 -f 3805//3805 4086//4086 4091//4091 -f 3805//3805 4091//4091 3804//3804 -f 3804//3804 4091//4091 3981//3981 -f 3803//3803 3804//3804 3983//3983 -f 3983//3983 3804//3804 3981//3981 -f 3781//3781 3803//3803 3982//3982 -f 3982//3982 3803//3803 3983//3983 -f 3781//3781 3982//3982 3980//3980 -f 3781//3781 3980//3980 3782//3782 -f 3782//3782 3980//3980 3979//3979 -f 3782//3782 3979//3979 3783//3783 -f 3783//3783 3979//3979 4090//4090 -f 3783//3783 4090//4090 3867//3867 -f 3859//3859 3867//3867 4092//4092 -f 4092//4092 3867//3867 4090//4090 -f 3859//3859 4092//4092 3860//3860 -f 3860//3860 4092//4092 4093//4093 -f 3860//3860 4093//4093 3861//3861 -f 3861//3861 4093//4093 4061//4061 -f 3861//3861 4061//4061 3882//3882 -f 3882//3882 4061//4061 4060//4060 -f 3937//3937 3882//3882 4085//4085 -f 4085//4085 3882//3882 4060//4060 -f 3937//3937 4085//4085 3936//3936 -f 3936//3936 4085//4085 4126//4126 -f 3936//3936 4126//4126 3857//3857 -f 3857//3857 4126//4126 4125//4125 -f 3858//3858 3857//3857 4124//4124 -f 4124//4124 3857//3857 4125//4125 -f 3858//3858 4124//4124 3960//3960 -f 3960//3960 4124//4124 4123//4123 -f 3960//3960 4123//4123 3961//3961 -f 3961//3961 4123//4123 4121//4121 -f 3963//3963 3961//3961 4119//4119 -f 4119//4119 3961//3961 4121//4121 -f 3963//3963 4119//4119 3965//3965 -f 3965//3965 4119//4119 4118//4118 -f 3965//3965 4118//4118 3966//3966 -f 3966//3966 4118//4118 4096//4096 -f 3967//3967 3966//3966 4095//4095 -f 4095//4095 3966//3966 4096//4096 -f 3967//3967 4095//4095 3968//3968 -f 3968//3968 4095//4095 4148//4148 -f 3968//3968 4148//4148 3911//3911 -f 3911//3911 4148//4148 4149//4149 -f 3872//3872 3911//3911 4112//4112 -f 4112//4112 3911//3911 4149//4149 -f 3872//3872 4112//4112 3873//3873 -f 3873//3873 4112//4112 4008//4008 -f 3873//3873 4008//4008 3929//3929 -f 3929//3929 4008//4008 4007//4007 -f 3929//3929 4007//4007 3928//3928 -f 3928//3928 4007//4007 4020//4020 -f 3926//3926 3928//3928 3971//3971 -f 3971//3971 3928//3928 4020//4020 -f 3926//3926 3971//3971 3970//3970 -f 3926//3926 3970//3970 3792//3792 -f 3792//3792 3970//3970 3969//3969 -f 3792//3792 3969//3969 3793//3793 -f 3793//3793 3969//3969 3986//3986 -f 3793//3793 3986//3986 3795//3795 -f 3796//3796 3795//3795 3985//3985 -f 3985//3985 3795//3795 3986//3986 -f 3794//3794 3796//3796 3984//3984 -f 3984//3984 3796//3796 3985//3985 -f 3794//3794 3984//3984 3927//3927 -f 3927//3927 3984//3984 4028//4028 -f 3927//3927 4028//4028 3837//3837 -f 3837//3837 4028//4028 4029//4029 -f 3837//3837 4029//4029 3800//3800 -f 3800//3800 4029//4029 4030//4030 -f 3801//3801 3800//3800 4031//4031 -f 4031//4031 3800//3800 4030//4030 -f 3802//3802 3801//3801 4009//4009 -f 4009//4009 3801//3801 4031//4031 -f 3802//3802 4009//4009 4063//4063 -f 3802//3802 4063//4063 3942//3942 -f 3942//3942 4063//4063 4131//4131 -f 3942//3942 4131//4131 3941//3941 -f 3941//3941 4131//4131 3993//3993 -f 3941//3941 3993//3993 3818//3818 -f 3816//3816 3818//3818 4019//4019 -f 4019//4019 3818//3818 3993//3993 -f 3817//3817 3816//3816 4018//4018 -f 4018//4018 3816//3816 4019//4019 -f 3817//3817 4018//4018 3819//3819 -f 3819//3819 4018//4018 4017//4017 -f 3819//3819 4017//4017 3791//3791 -f 3791//3791 4017//4017 4016//4016 -f 3791//3791 4016//4016 3789//3789 -f 3789//3789 4016//4016 3974//3974 -f 3787//3787 3789//3789 3973//3973 -f 3973//3973 3789//3789 3974//3974 -f 3788//3788 3787//3787 3972//3972 -f 3972//3972 3787//3787 3973//3973 -f 3788//3788 3972//3972 3987//3987 -f 3788//3788 3987//3987 3790//3790 -f 3790//3790 3987//3987 3988//3988 -f 3790//3790 3988//3988 3826//3826 -f 3826//3826 3988//3988 3989//3989 -f 3826//3826 3989//3989 3827//3827 -f 3828//3828 3827//3827 4015//4015 -f 4015//4015 3827//3827 3989//3989 -f 3828//3828 4015//4015 3939//3939 -f 3939//3939 4015//4015 3995//3995 -f 3939//3939 3995//3995 3940//3940 -f 3940//3940 3995//3995 3994//3994 -f 3940//3940 3994//3994 3909//3909 -f 3909//3909 3994//3994 4064//4064 -f 3910//3910 3909//3909 4127//4127 -f 4127//4127 3909//3909 4064//4064 -f 3910//3910 4127//4127 3874//3874 -f 3874//3874 4127//4127 4111//4111 -f 3874//3874 4111//4111 3879//3879 -f 3879//3879 4111//4111 4147//4147 -f 3880//3880 3879//3879 4146//4146 -f 4146//4146 3879//3879 4147//4147 -f 3880//3880 4146//4146 3950//3950 -f 3950//3950 4146//4146 4145//4145 -f 3950//3950 4145//4145 3951//3951 -f 3951//3951 4145//4145 4143//4143 -f 3953//3953 3951//3951 4142//4142 -f 4142//4142 3951//3951 4143//4143 -f 3953//3953 4142//4142 3955//3955 -f 3955//3955 4142//4142 4116//4116 -f 3955//3955 4116//4116 3956//3956 -f 3956//3956 4116//4116 4114//4114 -f 3957//3957 3956//3956 4113//4113 -f 4113//4113 3956//3956 4114//4114 -f 3957//3957 4113//4113 3902//3902 -f 3902//3902 4113//4113 4048//4048 -f 3902//3902 4048//4048 3925//3925 -f 3925//3925 4048//4048 4129//4129 -f 3871//3871 3925//3925 4128//4128 -f 4128//4128 3925//3925 4129//4129 -f 3871//3871 4128//4128 3876//3876 -f 3876//3876 4128//4128 4133//4133 -f 3876//3876 4133//4133 3877//3877 -f 3877//3877 4133//4133 4132//4132 -f 3877//3877 4132//4132 3904//3904 -f 3904//3904 4132//4132 4089//4089 -f 3844//3844 3904//3904 4088//4088 -f 4088//4088 3904//3904 4089//4089 -f 3844//3844 4088//4088 4087//4087 -f 3844//3844 4087//4087 3845//3845 -f 3845//3845 4087//4087 4013//4013 -f 3845//3845 4013//4013 3846//3846 -f 3846//3846 4013//4013 4011//4011 -f 3846//3846 4011//4011 3829//3829 -f 3830//3830 3829//3829 4010//4010 -f 4010//4010 3829//3829 4011//4011 -f 3831//3831 3830//3830 4012//4012 -f 4012//4012 3830//3830 4010//4010 -f 3831//3831 4012//4012 3905//3905 -f 3905//3905 4012//4012 4014//4014 -f 3905//3905 4014//4014 3906//3906 -f 3906//3906 4014//4014 4077//4077 -f 3906//3906 4077//4077 3907//3907 -f 3907//3907 4077//4077 4075//4075 -f 3908//3908 3907//3907 4074//4074 -f 4074//4074 3907//3907 4075//4075 -f 3875//3875 3908//3908 4076//4076 -f 4076//4076 3908//3908 4074//4074 -f 3875//3875 4076//4076 4134//4134 -f 3875//3875 4134//4134 3938//3938 -f 3938//3938 4134//4134 4135//4135 -f 3938//3938 4135//4135 3870//3870 -f 3870//3870 4135//4135 3992//3992 -f 3870//3870 3992//3992 3809//3809 -f 3822//3822 3809//3809 3991//3991 -f 3991//3991 3809//3809 3992//3992 -f 3821//3821 3822//3822 3990//3990 -f 3990//3990 3822//3822 3991//3991 -f 3821//3821 3990//3990 3820//3820 -f 3820//3820 3990//3990 4027//4027 -f 3820//3820 4027//4027 3851//3851 -f 3851//3851 4027//4027 4139//4139 -f 3851//3851 4139//4139 3842//3842 -f 3842//3842 4139//4139 4023//4023 -f 3840//3840 3842//3842 4022//4022 -f 4022//4022 3842//3842 4023//4023 -f 3866//3866 4053//4053 3864//3864 -f 3864//3864 4053//4053 4152//4152 -f 3864//3864 4152//4152 3954//3954 -f 3954//3954 4152//4152 4115//4115 -f 3954//3954 4115//4115 3952//3952 -f 3952//3952 4115//4115 4117//4117 -f 3952//3952 4117//4117 3878//3878 -f 3878//3878 4117//4117 4144//4144 -f 3878//3878 4144//4144 3964//3964 -f 3964//3964 4144//4144 4094//4094 -f 3964//3964 4094//4094 3962//3962 -f 3962//3962 4094//4094 4120//4120 -f 3962//3962 4120//4120 3856//3856 -f 3856//3856 4120//4120 4122//4122 -f 3856//3856 4122//4122 3932//3932 -f 3932//3932 4122//4122 4057//4057 -f 3932//3932 4057//4057 3893//3893 -f 3893//3893 4057//4057 4099//4099 -f 3893//3893 4099//4099 3891//3891 -f 3891//3891 4099//4099 4101//4101 -f 3891//3891 4101//4101 3945//3945 -f 3945//3945 4101//4101 4051//4051 -f 3945//3945 4051//4051 3866//3866 -f 3866//3866 4051//4051 4053//4053 -f 4157//4157 4158//4158 4159//4159 -f 4160//4160 4161//4161 4162//4162 -f 4163//4163 4164//4164 4165//4165 -f 4165//4165 4164//4164 4166//4166 -f 4165//4165 4166//4166 4167//4167 -f 4168//4168 4169//4169 4170//4170 -f 4170//4170 4169//4169 4171//4171 -f 4170//4170 4171//4171 4172//4172 -f 4173//4173 4174//4174 4175//4175 -f 4176//4176 4177//4177 4178//4178 -f 4179//4179 4157//4157 4180//4180 -f 4180//4180 4157//4157 4159//4159 -f 4180//4180 4159//4159 4181//4181 -f 4181//4181 4159//4159 4182//4182 -f 4183//4183 4184//4184 4185//4185 -f 4186//4186 4187//4187 4188//4188 -f 4189//4189 4173//4173 4190//4190 -f 4190//4190 4173//4173 4175//4175 -f 4190//4190 4175//4175 4191//4191 -f 4192//4192 4193//4193 4194//4194 -f 4194//4194 4193//4193 4195//4195 -f 4196//4196 4185//4185 4197//4197 -f 4197//4197 4185//4185 4198//4198 -f 4199//4199 4200//4200 4201//4201 -f 4166//4166 4202//4202 4167//4167 -f 4167//4167 4202//4202 4203//4203 -f 4167//4167 4203//4203 4195//4195 -f 4195//4195 4203//4203 4204//4204 -f 4195//4195 4204//4204 4194//4194 -f 4205//4205 4206//4206 4207//4207 -f 4191//4191 4175//4175 4208//4208 -f 4208//4208 4175//4175 4209//4209 -f 4208//4208 4209//4209 4188//4188 -f 4188//4188 4209//4209 4210//4210 -f 4188//4188 4210//4210 4186//4186 -f 4186//4186 4210//4210 4211//4211 -f 4186//4186 4211//4211 4212//4212 -f 4176//4176 4178//4178 4213//4213 -f 4183//4183 4185//4185 4214//4214 -f 4214//4214 4185//4185 4196//4196 -f 4214//4214 4196//4196 4215//4215 -f 4216//4216 4217//4217 4218//4218 -f 4218//4218 4217//4217 4219//4219 -f 4220//4220 4221//4221 4207//4207 -f 4207//4207 4221//4221 4222//4222 -f 4207//4207 4222//4222 4205//4205 -f 4223//4223 4224//4224 4225//4225 -f 4199//4199 4201//4201 4226//4226 -f 4196//4196 4227//4227 4215//4215 -f 4215//4215 4227//4227 4218//4218 -f 4215//4215 4218//4218 4228//4228 -f 4228//4228 4218//4218 4219//4219 -f 4229//4229 4230//4230 4231//4231 -f 4232//4232 4233//4233 4234//4234 -f 4235//4235 4236//4236 4230//4230 -f 4230//4230 4236//4236 4237//4237 -f 4238//4238 4239//4239 4240//4240 -f 4240//4240 4239//4239 4241//4241 -f 4240//4240 4241//4241 4242//4242 -f 4159//4159 4243//4243 4182//4182 -f 4182//4182 4243//4243 4235//4235 -f 4182//4182 4235//4235 4244//4244 -f 4244//4244 4235//4235 4230//4230 -f 4244//4244 4230//4230 4245//4245 -f 4246//4246 4185//4185 4247//4247 -f 4248//4248 4249//4249 4250//4250 -f 4251//4251 4252//4252 4253//4253 -f 4254//4254 4255//4255 4256//4256 -f 4257//4257 4237//4237 4258//4258 -f 4259//4259 4260//4260 4261//4261 -f 4261//4261 4260//4260 4262//4262 -f 4261//4261 4262//4262 4263//4263 -f 4263//4263 4262//4262 4264//4264 -f 4265//4265 4266//4266 4267//4267 -f 4267//4267 4266//4266 4268//4268 -f 4267//4267 4268//4268 4269//4269 -f 4237//4237 4257//4257 4230//4230 -f 4230//4230 4257//4257 4270//4270 -f 4230//4230 4270//4270 4231//4231 -f 4271//4271 4272//4272 4273//4273 -f 4273//4273 4272//4272 4274//4274 -f 4201//4201 4275//4275 4276//4276 -f 4223//4223 4225//4225 4277//4277 -f 4278//4278 4184//4184 4279//4279 -f 4220//4220 4207//4207 4280//4280 -f 4280//4280 4207//4207 4281//4281 -f 4280//4280 4281//4281 4253//4253 -f 4253//4253 4281//4281 4282//4282 -f 4253//4253 4282//4282 4251//4251 -f 4251//4251 4282//4282 4283//4283 -f 4251//4251 4283//4283 4284//4284 -f 4178//4178 4285//4285 4286//4286 -f 4248//4248 4250//4250 4287//4287 -f 4187//4187 4186//4186 4231//4231 -f 4231//4231 4186//4186 4288//4288 -f 4231//4231 4288//4288 4229//4229 -f 4261//4261 4289//4289 4259//4259 -f 4259//4259 4289//4289 4273//4273 -f 4259//4259 4273//4273 4290//4290 -f 4290//4290 4273//4273 4274//4274 -f 4260//4260 4291//4291 4262//4262 -f 4262//4262 4291//4291 4292//4292 -f 4262//4262 4292//4292 4293//4293 -f 4293//4293 4292//4292 4275//4275 -f 4293//4293 4275//4275 4294//4294 -f 4294//4294 4275//4275 4201//4201 -f 4295//4295 4160//4160 4296//4296 -f 4296//4296 4160//4160 4162//4162 -f 4296//4296 4162//4162 4297//4297 -f 4297//4297 4162//4162 4298//4298 -f 4297//4297 4298//4298 4299//4299 -f 4299//4299 4298//4298 4226//4226 -f 4299//4299 4226//4226 4300//4300 -f 4300//4300 4226//4226 4201//4201 -f 4300//4300 4201//4201 4224//4224 -f 4224//4224 4201//4201 4276//4276 -f 4224//4224 4276//4276 4225//4225 -f 4184//4184 4278//4278 4185//4185 -f 4185//4185 4278//4278 4301//4301 -f 4185//4185 4301//4301 4247//4247 -f 4168//4168 4170//4170 4302//4302 -f 4302//4302 4170//4170 4303//4303 -f 4302//4302 4303//4303 4304//4304 -f 4304//4304 4303//4303 4213//4213 -f 4304//4304 4213//4213 4305//4305 -f 4305//4305 4213//4213 4178//4178 -f 4305//4305 4178//4178 4249//4249 -f 4249//4249 4178//4178 4286//4286 -f 4249//4249 4286//4286 4250//4250 -f 4268//4268 4306//4306 4269//4269 -f 4269//4269 4306//4306 4307//4307 -f 4269//4269 4307//4307 4308//4308 -f 4308//4308 4307//4307 4309//4309 -f 4308//4308 4309//4309 4232//4232 -f 4232//4232 4309//4309 4310//4310 -f 4232//4232 4310//4310 4233//4233 -f 4233//4233 4310//4310 4311//4311 -f 4233//4233 4311//4311 4312//4312 -f 4312//4312 4311//4311 4257//4257 -f 4312//4312 4257//4257 4313//4313 -f 4313//4313 4257//4257 4258//4258 -f 4252//4252 4251//4251 4247//4247 -f 4247//4247 4251//4251 4314//4314 -f 4247//4247 4314//4314 4246//4246 -f 4204//4204 4315//4315 4194//4194 -f 4194//4194 4315//4315 4316//4316 -f 4194//4194 4316//4316 4317//4317 -f 4317//4317 4316//4316 4285//4285 -f 4317//4317 4285//4285 4318//4318 -f 4318//4318 4285//4285 4178//4178 -f 4241//4241 4319//4319 4242//4242 -f 4242//4242 4319//4319 4320//4320 -f 4242//4242 4320//4320 4321//4321 -f 4321//4321 4320//4320 4322//4322 -f 4321//4321 4322//4322 4267//4267 -f 4267//4267 4322//4322 4323//4323 -f 4267//4267 4323//4323 4265//4265 -f 4265//4265 4323//4323 4324//4324 -f 4265//4265 4324//4324 4225//4225 -f 4225//4225 4324//4324 4325//4325 -f 4225//4225 4325//4325 4277//4277 -f 4256//4256 4326//4326 4254//4254 -f 4254//4254 4326//4326 4327//4327 -f 4254//4254 4327//4327 4328//4328 -f 4328//4328 4327//4327 4329//4329 -f 4328//4328 4329//4329 4330//4330 -f 4330//4330 4329//4329 4331//4331 -f 4330//4330 4331//4331 4240//4240 -f 4240//4240 4331//4331 4332//4332 -f 4240//4240 4332//4332 4238//4238 -f 4238//4238 4332//4332 4333//4333 -f 4238//4238 4333//4333 4334//4334 -f 4334//4334 4333//4333 4278//4278 -f 4334//4334 4278//4278 4335//4335 -f 4335//4335 4278//4278 4279//4279 -f 4234//4234 4336//4336 4232//4232 -f 4232//4232 4336//4336 4337//4337 -f 4232//4232 4337//4337 4338//4338 -f 4338//4338 4337//4337 4339//4339 -f 4338//4338 4339//4339 4340//4340 -f 4340//4340 4339//4339 4341//4341 -f 4340//4340 4341//4341 4254//4254 -f 4254//4254 4341//4341 4342//4342 -f 4254//4254 4342//4342 4255//4255 -f 4255//4255 4342//4342 4343//4343 -f 4255//4255 4343//4343 4250//4250 -f 4250//4250 4343//4343 4344//4344 -f 4250//4250 4344//4344 4287//4287 -f 4345//4345 4346//4346 4347//4347 -f 4348//4348 4349//4349 4350//4350 -f 4351//4351 4352//4352 4353//4353 -f 4353//4353 4352//4352 4354//4354 -f 4355//4355 4356//4356 4357//4357 -f 4357//4357 4356//4356 4358//4358 -f 4357//4357 4358//4358 4359//4359 -f 4360//4360 4361//4361 4362//4362 -f 4363//4363 4348//4348 4364//4364 -f 4364//4364 4348//4348 4350//4350 -f 4364//4364 4350//4350 4365//4365 -f 4366//4366 3836//3836 3810//3810 -f 4367//4367 4368//4368 4369//4369 -f 4370//4370 4371//4371 4372//4372 -f 4354//4354 4373//4373 4353//4353 -f 4353//4353 4373//4373 4374//4374 -f 4353//4353 4374//4374 4375//4375 -f 4375//4375 4374//4374 4376//4376 -f 4375//4375 4376//4376 4377//4377 -f 4377//4377 4376//4376 4378//4378 -f 4377//4377 4378//4378 4379//4379 -f 4379//4379 4378//4378 4380//4380 -f 4381//4381 4382//4382 4383//4383 -f 4384//4384 4385//4385 4386//4386 -f 4386//4386 4385//4385 4387//4387 -f 4386//4386 4387//4387 4388//4388 -f 4365//4365 4350//4350 4389//4389 -f 4389//4389 4350//4350 4390//4390 -f 4389//4389 4390//4390 4369//4369 -f 4369//4369 4390//4390 4391//4391 -f 4369//4369 4391//4391 4367//4367 -f 4367//4367 4391//4391 4392//4392 -f 4367//4367 4392//4392 4393//4393 -f 4381//4381 4383//4383 4394//4394 -f 4395//4395 4396//4396 4397//4397 -f 4398//4398 4399//4399 4400//4400 -f 4366//4366 3810//3810 4401//4401 -f 4362//4362 4345//4345 4360//4360 -f 4360//4360 4345//4345 4347//4347 -f 4360//4360 4347//4347 4402//4402 -f 4402//4402 4347//4347 4394//4394 -f 4402//4402 4394//4394 4403//4403 -f 4403//4403 4394//4394 4383//4383 -f 4403//4403 4383//4383 4404//4404 -f 4404//4404 4383//4383 4405//4405 -f 4406//4406 4407//4407 3886//3886 -f 3886//3886 4407//4407 4408//4408 -f 4409//4409 4410//4410 4400//4400 -f 4400//4400 4410//4410 4411//4411 -f 4400//4400 4411//4411 4398//4398 -f 4412//4412 4370//4370 4413//4413 -f 4413//4413 4370//4370 4372//4372 -f 4413//4413 4372//4372 4414//4414 -f 4414//4414 4372//4372 4415//4415 -f 4372//4372 4416//4416 4415//4415 -f 4415//4415 4416//4416 4406//4406 -f 4415//4415 4406//4406 4417//4417 -f 4417//4417 4406//4406 3886//3886 -f 4417//4417 3886//3886 3888//3888 -f 4418//4418 4419//4419 4420//4420 -f 4421//4421 4422//4422 4423//4423 -f 4423//4423 4422//4422 4424//4424 -f 4423//4423 4424//4424 4425//4425 -f 4426//4426 4427//4427 4428//4428 -f 4429//4429 4430//4430 4431//4431 -f 4432//4432 4433//4433 4434//4434 -f 4435//4435 4383//4383 4436//4436 -f 4437//4437 4408//4408 4438//4438 -f 4409//4409 4400//4400 4439//4439 -f 4439//4439 4400//4400 4440//4440 -f 4439//4439 4440//4440 4441//4441 -f 4441//4441 4440//4440 4442//4442 -f 4441//4441 4442//4442 4443//4443 -f 4443//4443 4442//4442 4444//4444 -f 4443//4443 4444//4444 4445//4445 -f 4446//4446 4447//4447 4448//4448 -f 4448//4448 4447//4447 4449//4449 -f 4408//4408 4437//4437 3886//3886 -f 3886//3886 4437//4437 4450//4450 -f 3886//3886 4450//4450 4451//4451 -f 4452//4452 3886//3886 4453//4453 -f 4453//4453 3886//3886 4451//4451 -f 4453//4453 4451//4451 4443//4443 -f 4443//4443 4451//4451 4454//4454 -f 4443//4443 4454//4454 4441//4441 -f 4428//4428 4455//4455 4456//4456 -f 4432//4432 4434//4434 4457//4457 -f 4426//4426 4428//4428 4458//4458 -f 4387//4387 4459//4459 4388//4388 -f 4388//4388 4459//4459 4460//4460 -f 4388//4388 4460//4460 4449//4449 -f 4449//4449 4460//4460 4461//4461 -f 4449//4449 4461//4461 4448//4448 -f 4355//4355 4357//4357 4462//4462 -f 4462//4462 4357//4357 4463//4463 -f 4462//4462 4463//4463 4464//4464 -f 4464//4464 4463//4463 4458//4458 -f 4464//4464 4458//4458 4465//4465 -f 4465//4465 4458//4458 4428//4428 -f 4465//4465 4428//4428 4433//4433 -f 4433//4433 4428//4428 4456//4456 -f 4433//4433 4456//4456 4434//4434 -f 4466//4466 4467//4467 4468//4468 -f 4431//4431 4469//4469 4429//4429 -f 4429//4429 4469//4469 4470//4470 -f 4429//4429 4470//4470 4471//4471 -f 4471//4471 4470//4470 4472//4472 -f 4471//4471 4472//4472 4473//4473 -f 4473//4473 4472//4472 4474//4474 -f 4473//4473 4474//4474 4423//4423 -f 4423//4423 4474//4474 4475//4475 -f 4423//4423 4475//4475 4421//4421 -f 4421//4421 4475//4475 4476//4476 -f 4421//4421 4476//4476 4477//4477 -f 4477//4477 4476//4476 4437//4437 -f 4477//4477 4437//4437 4478//4478 -f 4478//4478 4437//4437 4438//4438 -f 4376//4376 4479//4479 4378//4378 -f 4378//4378 4479//4479 4480//4480 -f 4378//4378 4480//4480 4481//4481 -f 4481//4481 4480//4480 4455//4455 -f 4481//4481 4455//4455 4482//4482 -f 4482//4482 4455//4455 4428//4428 -f 4483//4483 4382//4382 4484//4484 -f 4485//4485 4486//4486 4487//4487 -f 4487//4487 4486//4486 4488//4488 -f 4487//4487 4488//4488 4489//4489 -f 4468//4468 4490//4490 4466//4466 -f 4466//4466 4490//4490 4491//4491 -f 4466//4466 4491//4491 4492//4492 -f 4492//4492 4491//4491 4493//4493 -f 4492//4492 4493//4493 4494//4494 -f 4494//4494 4493//4493 4495//4495 -f 4494//4494 4495//4495 4429//4429 -f 4429//4429 4495//4495 4496//4496 -f 4429//4429 4496//4496 4430//4430 -f 4430//4430 4496//4496 4497//4497 -f 4430//4430 4497//4497 4434//4434 -f 4434//4434 4497//4497 4498//4498 -f 4434//4434 4498//4498 4457//4457 -f 4382//4382 4483//4483 4383//4383 -f 4383//4383 4483//4483 4499//4499 -f 4383//4383 4499//4499 4436//4436 -f 3810//3810 4500//4500 4501//4501 -f 4418//4418 4420//4420 4502//4502 -f 4368//4368 4367//4367 4436//4436 -f 4436//4436 4367//4367 4503//4503 -f 4436//4436 4503//4503 4435//4435 -f 4461//4461 4504//4504 4448//4448 -f 4448//4448 4504//4504 4505//4505 -f 4448//4448 4505//4505 4506//4506 -f 4506//4506 4505//4505 4500//4500 -f 4506//4506 4500//4500 4507//4507 -f 4507//4507 4500//4500 3810//3810 -f 4508//4508 4395//4395 4509//4509 -f 4509//4509 4395//4395 4397//4397 -f 4509//4509 4397//4397 4510//4510 -f 4510//4510 4397//4397 4511//4511 -f 4510//4510 4511//4511 4512//4512 -f 4512//4512 4511//4511 4401//4401 -f 4512//4512 4401//4401 4513//4513 -f 4513//4513 4401//4401 3810//3810 -f 4513//4513 3810//3810 4419//4419 -f 4419//4419 3810//3810 4501//4501 -f 4419//4419 4501//4501 4420//4420 -f 4488//4488 4514//4514 4489//4489 -f 4489//4489 4514//4514 4515//4515 -f 4489//4489 4515//4515 4516//4516 -f 4516//4516 4515//4515 4517//4517 -f 4516//4516 4517//4517 4466//4466 -f 4466//4466 4517//4517 4518//4518 -f 4466//4466 4518//4518 4467//4467 -f 4467//4467 4518//4518 4519//4519 -f 4467//4467 4519//4519 4520//4520 -f 4520//4520 4519//4519 4483//4483 -f 4520//4520 4483//4483 4521//4521 -f 4521//4521 4483//4483 4484//4484 -f 4424//4424 4522//4522 4425//4425 -f 4425//4425 4522//4522 4523//4523 -f 4425//4425 4523//4523 4524//4524 -f 4524//4524 4523//4523 4525//4525 -f 4524//4524 4525//4525 4487//4487 -f 4487//4487 4525//4525 4526//4526 -f 4487//4487 4526//4526 4485//4485 -f 4485//4485 4526//4526 4527//4527 -f 4485//4485 4527//4527 4420//4420 -f 4420//4420 4527//4527 4528//4528 -f 4420//4420 4528//4528 4502//4502 -f 4217//4217 4216//4216 4395//4395 -f 4395//4395 4216//4216 4396//4396 -f 4217//4217 4395//4395 4508//4508 -f 4217//4217 4508//4508 4219//4219 -f 4219//4219 4508//4508 4509//4509 -f 4219//4219 4509//4509 4228//4228 -f 4228//4228 4509//4509 4510//4510 -f 4228//4228 4510//4510 4215//4215 -f 4214//4214 4215//4215 4512//4512 -f 4512//4512 4215//4215 4510//4510 -f 4214//4214 4512//4512 4183//4183 -f 4183//4183 4512//4512 4513//4513 -f 4183//4183 4513//4513 4184//4184 -f 4184//4184 4513//4513 4419//4419 -f 4184//4184 4419//4419 4279//4279 -f 4279//4279 4419//4419 4418//4418 -f 4335//4335 4279//4279 4502//4502 -f 4502//4502 4279//4279 4418//4418 -f 4335//4335 4502//4502 4334//4334 -f 4334//4334 4502//4502 4528//4528 -f 4334//4334 4528//4528 4238//4238 -f 4238//4238 4528//4528 4527//4527 -f 4239//4239 4238//4238 4526//4526 -f 4526//4526 4238//4238 4527//4527 -f 4239//4239 4526//4526 4241//4241 -f 4241//4241 4526//4526 4525//4525 -f 4241//4241 4525//4525 4319//4319 -f 4319//4319 4525//4525 4523//4523 -f 4320//4320 4319//4319 4522//4522 -f 4522//4522 4319//4319 4523//4523 -f 4320//4320 4522//4522 4322//4322 -f 4322//4322 4522//4522 4424//4424 -f 4322//4322 4424//4424 4323//4323 -f 4323//4323 4424//4424 4422//4422 -f 4324//4324 4323//4323 4421//4421 -f 4421//4421 4323//4323 4422//4422 -f 4324//4324 4421//4421 4325//4325 -f 4325//4325 4421//4421 4477//4477 -f 4325//4325 4477//4477 4277//4277 -f 4277//4277 4477//4477 4478//4478 -f 4223//4223 4277//4277 4438//4438 -f 4438//4438 4277//4277 4478//4478 -f 4223//4223 4438//4438 4224//4224 -f 4224//4224 4438//4438 4408//4408 -f 4224//4224 4408//4408 4300//4300 -f 4300//4300 4408//4408 4407//4407 -f 4300//4300 4407//4407 4299//4299 -f 4299//4299 4407//4407 4406//4406 -f 4297//4297 4299//4299 4416//4416 -f 4416//4416 4299//4299 4406//4406 -f 4297//4297 4416//4416 4372//4372 -f 4297//4297 4372//4372 4296//4296 -f 4296//4296 4372//4372 4371//4371 -f 4296//4296 4371//4371 4295//4295 -f 4295//4295 4371//4371 4370//4370 -f 4295//4295 4370//4370 4160//4160 -f 4161//4161 4160//4160 4412//4412 -f 4412//4412 4160//4160 4370//4370 -f 4162//4162 4161//4161 4413//4413 -f 4413//4413 4161//4161 4412//4412 -f 4162//4162 4413//4413 4298//4298 -f 4298//4298 4413//4413 4414//4414 -f 4298//4298 4414//4414 4226//4226 -f 4226//4226 4414//4414 4415//4415 -f 4226//4226 4415//4415 4199//4199 -f 4199//4199 4415//4415 4417//4417 -f 4200//4200 4199//4199 3888//3888 -f 3888//3888 4199//4199 4417//4417 -f 4201//4201 4200//4200 3886//3886 -f 3886//3886 4200//4200 3888//3888 -f 4201//4201 3886//3886 4452//4452 -f 4201//4201 4452//4452 4294//4294 -f 4294//4294 4452//4452 4453//4453 -f 4294//4294 4453//4453 4293//4293 -f 4293//4293 4453//4453 4443//4443 -f 4293//4293 4443//4443 4262//4262 -f 4264//4264 4262//4262 4445//4445 -f 4445//4445 4262//4262 4443//4443 -f 4263//4263 4264//4264 4444//4444 -f 4444//4444 4264//4264 4445//4445 -f 4263//4263 4444//4444 4261//4261 -f 4261//4261 4444//4444 4442//4442 -f 4261//4261 4442//4442 4289//4289 -f 4289//4289 4442//4442 4440//4440 -f 4289//4289 4440//4440 4273//4273 -f 4273//4273 4440//4440 4400//4400 -f 4271//4271 4273//4273 4399//4399 -f 4399//4399 4273//4273 4400//4400 -f 4272//4272 4271//4271 4398//4398 -f 4398//4398 4271//4271 4399//4399 -f 4272//4272 4398//4398 4411//4411 -f 4272//4272 4411//4411 4274//4274 -f 4274//4274 4411//4411 4410//4410 -f 4274//4274 4410//4410 4290//4290 -f 4290//4290 4410//4410 4409//4409 -f 4290//4290 4409//4409 4259//4259 -f 4260//4260 4259//4259 4439//4439 -f 4439//4439 4259//4259 4409//4409 -f 4260//4260 4439//4439 4291//4291 -f 4291//4291 4439//4439 4441//4441 -f 4291//4291 4441//4441 4292//4292 -f 4292//4292 4441//4441 4454//4454 -f 4292//4292 4454//4454 4275//4275 -f 4275//4275 4454//4454 4451//4451 -f 4276//4276 4275//4275 4450//4450 -f 4450//4450 4275//4275 4451//4451 -f 4276//4276 4450//4450 4225//4225 -f 4225//4225 4450//4450 4437//4437 -f 4225//4225 4437//4437 4265//4265 -f 4265//4265 4437//4437 4476//4476 -f 4266//4266 4265//4265 4475//4475 -f 4475//4475 4265//4265 4476//4476 -f 4266//4266 4475//4475 4268//4268 -f 4268//4268 4475//4475 4474//4474 -f 4268//4268 4474//4474 4306//4306 -f 4306//4306 4474//4474 4472//4472 -f 4307//4307 4306//4306 4470//4470 -f 4470//4470 4306//4306 4472//4472 -f 4307//4307 4470//4470 4309//4309 -f 4309//4309 4470//4470 4469//4469 -f 4309//4309 4469//4469 4310//4310 -f 4310//4310 4469//4469 4431//4431 -f 4311//4311 4310//4310 4430//4430 -f 4430//4430 4310//4310 4431//4431 -f 4311//4311 4430//4430 4257//4257 -f 4257//4257 4430//4430 4434//4434 -f 4257//4257 4434//4434 4270//4270 -f 4270//4270 4434//4434 4456//4456 -f 4231//4231 4270//4270 4455//4455 -f 4455//4455 4270//4270 4456//4456 -f 4231//4231 4455//4455 4187//4187 -f 4187//4187 4455//4455 4480//4480 -f 4187//4187 4480//4480 4188//4188 -f 4188//4188 4480//4480 4479//4479 -f 4188//4188 4479//4479 4208//4208 -f 4208//4208 4479//4479 4376//4376 -f 4191//4191 4208//4208 4374//4374 -f 4374//4374 4208//4208 4376//4376 -f 4191//4191 4374//4374 4373//4373 -f 4191//4191 4373//4373 4190//4190 -f 4190//4190 4373//4373 4354//4354 -f 4190//4190 4354//4354 4189//4189 -f 4189//4189 4354//4354 4352//4352 -f 4189//4189 4352//4352 4173//4173 -f 4174//4174 4173//4173 4351//4351 -f 4351//4351 4173//4173 4352//4352 -f 4175//4175 4174//4174 4353//4353 -f 4353//4353 4174//4174 4351//4351 -f 4175//4175 4353//4353 4209//4209 -f 4209//4209 4353//4353 4375//4375 -f 4209//4209 4375//4375 4210//4210 -f 4210//4210 4375//4375 4377//4377 -f 4210//4210 4377//4377 4211//4211 -f 4211//4211 4377//4377 4379//4379 -f 4212//4212 4211//4211 4380//4380 -f 4380//4380 4211//4211 4379//4379 -f 4186//4186 4212//4212 4378//4378 -f 4378//4378 4212//4212 4380//4380 -f 4186//4186 4378//4378 4481//4481 -f 4186//4186 4481//4481 4288//4288 -f 4288//4288 4481//4481 4482//4482 -f 4288//4288 4482//4482 4229//4229 -f 4229//4229 4482//4482 4428//4428 -f 4229//4229 4428//4428 4230//4230 -f 4245//4245 4230//4230 4427//4427 -f 4427//4427 4230//4230 4428//4428 -f 4244//4244 4245//4245 4426//4426 -f 4426//4426 4245//4245 4427//4427 -f 4244//4244 4426//4426 4182//4182 -f 4182//4182 4426//4426 4458//4458 -f 4182//4182 4458//4458 4181//4181 -f 4181//4181 4458//4458 4463//4463 -f 4181//4181 4463//4463 4180//4180 -f 4180//4180 4463//4463 4357//4357 -f 4179//4179 4180//4180 4359//4359 -f 4359//4359 4180//4180 4357//4357 -f 4157//4157 4179//4179 4358//4358 -f 4358//4358 4179//4179 4359//4359 -f 4157//4157 4358//4358 4356//4356 -f 4157//4157 4356//4356 4158//4158 -f 4158//4158 4356//4356 4355//4355 -f 4158//4158 4355//4355 4159//4159 -f 4159//4159 4355//4355 4462//4462 -f 4159//4159 4462//4462 4243//4243 -f 4235//4235 4243//4243 4464//4464 -f 4464//4464 4243//4243 4462//4462 -f 4235//4235 4464//4464 4236//4236 -f 4236//4236 4464//4464 4465//4465 -f 4236//4236 4465//4465 4237//4237 -f 4237//4237 4465//4465 4433//4433 -f 4237//4237 4433//4433 4258//4258 -f 4258//4258 4433//4433 4432//4432 -f 4313//4313 4258//4258 4457//4457 -f 4457//4457 4258//4258 4432//4432 -f 4313//4313 4457//4457 4312//4312 -f 4312//4312 4457//4457 4498//4498 -f 4312//4312 4498//4498 4233//4233 -f 4233//4233 4498//4498 4497//4497 -f 4234//4234 4233//4233 4496//4496 -f 4496//4496 4233//4233 4497//4497 -f 4234//4234 4496//4496 4336//4336 -f 4336//4336 4496//4496 4495//4495 -f 4336//4336 4495//4495 4337//4337 -f 4337//4337 4495//4495 4493//4493 -f 4339//4339 4337//4337 4491//4491 -f 4491//4491 4337//4337 4493//4493 -f 4339//4339 4491//4491 4341//4341 -f 4341//4341 4491//4491 4490//4490 -f 4341//4341 4490//4490 4342//4342 -f 4342//4342 4490//4490 4468//4468 -f 4343//4343 4342//4342 4467//4467 -f 4467//4467 4342//4342 4468//4468 -f 4343//4343 4467//4467 4344//4344 -f 4344//4344 4467//4467 4520//4520 -f 4344//4344 4520//4520 4287//4287 -f 4287//4287 4520//4520 4521//4521 -f 4248//4248 4287//4287 4484//4484 -f 4484//4484 4287//4287 4521//4521 -f 4248//4248 4484//4484 4249//4249 -f 4249//4249 4484//4484 4382//4382 -f 4249//4249 4382//4382 4305//4305 -f 4305//4305 4382//4382 4381//4381 -f 4305//4305 4381//4381 4304//4304 -f 4304//4304 4381//4381 4394//4394 -f 4302//4302 4304//4304 4347//4347 -f 4347//4347 4304//4304 4394//4394 -f 4302//4302 4347//4347 4346//4346 -f 4302//4302 4346//4346 4168//4168 -f 4168//4168 4346//4346 4345//4345 -f 4168//4168 4345//4345 4169//4169 -f 4169//4169 4345//4345 4362//4362 -f 4169//4169 4362//4362 4171//4171 -f 4172//4172 4171//4171 4361//4361 -f 4361//4361 4171//4171 4362//4362 -f 4170//4170 4172//4172 4360//4360 -f 4360//4360 4172//4172 4361//4361 -f 4170//4170 4360//4360 4303//4303 -f 4303//4303 4360//4360 4402//4402 -f 4303//4303 4402//4402 4213//4213 -f 4213//4213 4402//4402 4403//4403 -f 4213//4213 4403//4403 4176//4176 -f 4176//4176 4403//4403 4404//4404 -f 4177//4177 4176//4176 4405//4405 -f 4405//4405 4176//4176 4404//4404 -f 4178//4178 4177//4177 4383//4383 -f 4383//4383 4177//4177 4405//4405 -f 4178//4178 4383//4383 4435//4435 -f 4178//4178 4435//4435 4318//4318 -f 4318//4318 4435//4435 4503//4503 -f 4318//4318 4503//4503 4317//4317 -f 4317//4317 4503//4503 4367//4367 -f 4317//4317 4367//4367 4194//4194 -f 4192//4192 4194//4194 4393//4393 -f 4393//4393 4194//4194 4367//4367 -f 4193//4193 4192//4192 4392//4392 -f 4392//4392 4192//4192 4393//4393 -f 4193//4193 4392//4392 4195//4195 -f 4195//4195 4392//4392 4391//4391 -f 4195//4195 4391//4391 4167//4167 -f 4167//4167 4391//4391 4390//4390 -f 4167//4167 4390//4390 4165//4165 -f 4165//4165 4390//4390 4350//4350 -f 4163//4163 4165//4165 4349//4349 -f 4349//4349 4165//4165 4350//4350 -f 4164//4164 4163//4163 4348//4348 -f 4348//4348 4163//4163 4349//4349 -f 4164//4164 4348//4348 4363//4363 -f 4164//4164 4363//4363 4166//4166 -f 4166//4166 4363//4363 4364//4364 -f 4166//4166 4364//4364 4202//4202 -f 4202//4202 4364//4364 4365//4365 -f 4202//4202 4365//4365 4203//4203 -f 4204//4204 4203//4203 4389//4389 -f 4389//4389 4203//4203 4365//4365 -f 4204//4204 4389//4389 4315//4315 -f 4315//4315 4389//4389 4369//4369 -f 4315//4315 4369//4369 4316//4316 -f 4316//4316 4369//4369 4368//4368 -f 4316//4316 4368//4368 4285//4285 -f 4285//4285 4368//4368 4436//4436 -f 4286//4286 4285//4285 4499//4499 -f 4499//4499 4285//4285 4436//4436 -f 4286//4286 4499//4499 4250//4250 -f 4250//4250 4499//4499 4483//4483 -f 4250//4250 4483//4483 4255//4255 -f 4255//4255 4483//4483 4519//4519 -f 4256//4256 4255//4255 4518//4518 -f 4518//4518 4255//4255 4519//4519 -f 4256//4256 4518//4518 4326//4326 -f 4326//4326 4518//4518 4517//4517 -f 4326//4326 4517//4517 4327//4327 -f 4327//4327 4517//4517 4515//4515 -f 4329//4329 4327//4327 4514//4514 -f 4514//4514 4327//4327 4515//4515 -f 4329//4329 4514//4514 4331//4331 -f 4331//4331 4514//4514 4488//4488 -f 4331//4331 4488//4488 4332//4332 -f 4332//4332 4488//4488 4486//4486 -f 4333//4333 4332//4332 4485//4485 -f 4485//4485 4332//4332 4486//4486 -f 4333//4333 4485//4485 4278//4278 -f 4278//4278 4485//4485 4420//4420 -f 4278//4278 4420//4420 4301//4301 -f 4301//4301 4420//4420 4501//4501 -f 4247//4247 4301//4301 4500//4500 -f 4500//4500 4301//4301 4501//4501 -f 4247//4247 4500//4500 4252//4252 -f 4252//4252 4500//4500 4505//4505 -f 4252//4252 4505//4505 4253//4253 -f 4253//4253 4505//4505 4504//4504 -f 4253//4253 4504//4504 4280//4280 -f 4280//4280 4504//4504 4461//4461 -f 4220//4220 4280//4280 4460//4460 -f 4460//4460 4280//4280 4461//4461 -f 4220//4220 4460//4460 4459//4459 -f 4220//4220 4459//4459 4221//4221 -f 4221//4221 4459//4459 4387//4387 -f 4221//4221 4387//4387 4222//4222 -f 4222//4222 4387//4387 4385//4385 -f 4222//4222 4385//4385 4205//4205 -f 4206//4206 4205//4205 4384//4384 -f 4384//4384 4205//4205 4385//4385 -f 4207//4207 4206//4206 4386//4386 -f 4386//4386 4206//4206 4384//4384 -f 4207//4207 4386//4386 4281//4281 -f 4281//4281 4386//4386 4388//4388 -f 4281//4281 4388//4388 4282//4282 -f 4282//4282 4388//4388 4449//4449 -f 4282//4282 4449//4449 4283//4283 -f 4283//4283 4449//4449 4447//4447 -f 4284//4284 4283//4283 4446//4446 -f 4446//4446 4283//4283 4447//4447 -f 4251//4251 4284//4284 4448//4448 -f 4448//4448 4284//4284 4446//4446 -f 4251//4251 4448//4448 4506//4506 -f 4251//4251 4506//4506 4314//4314 -f 4314//4314 4506//4506 4507//4507 -f 4314//4314 4507//4507 4246//4246 -f 4246//4246 4507//4507 3810//3810 -f 4246//4246 3810//3810 4185//4185 -f 4198//4198 4185//4185 3836//3836 -f 3836//3836 4185//4185 3810//3810 -f 4197//4197 4198//4198 4366//4366 -f 4366//4366 4198//4198 3836//3836 -f 4197//4197 4366//4366 4196//4196 -f 4196//4196 4366//4366 4401//4401 -f 4196//4196 4401//4401 4227//4227 -f 4227//4227 4401//4401 4511//4511 -f 4227//4227 4511//4511 4218//4218 -f 4218//4218 4511//4511 4397//4397 -f 4216//4216 4218//4218 4396//4396 -f 4396//4396 4218//4218 4397//4397 -f 4242//4242 4425//4425 4240//4240 -f 4240//4240 4425//4425 4524//4524 -f 4240//4240 4524//4524 4330//4330 -f 4330//4330 4524//4524 4487//4487 -f 4330//4330 4487//4487 4328//4328 -f 4328//4328 4487//4487 4489//4489 -f 4328//4328 4489//4489 4254//4254 -f 4254//4254 4489//4489 4516//4516 -f 4254//4254 4516//4516 4340//4340 -f 4340//4340 4516//4516 4466//4466 -f 4340//4340 4466//4466 4338//4338 -f 4338//4338 4466//4466 4492//4492 -f 4338//4338 4492//4492 4232//4232 -f 4232//4232 4492//4492 4494//4494 -f 4232//4232 4494//4494 4308//4308 -f 4308//4308 4494//4494 4429//4429 -f 4308//4308 4429//4429 4269//4269 -f 4269//4269 4429//4429 4471//4471 -f 4269//4269 4471//4471 4267//4267 -f 4267//4267 4471//4471 4473//4473 -f 4267//4267 4473//4473 4321//4321 -f 4321//4321 4473//4473 4423//4423 -f 4321//4321 4423//4423 4242//4242 -f 4242//4242 4423//4423 4425//4425 -f 4529//4529 4530//4530 4531//4531 -f 4532//4532 4533//4533 4534//4534 -f 4535//4535 4536//4536 4537//4537 -f 4537//4537 4536//4536 4538//4538 -f 4537//4537 4538//4538 4539//4539 -f 4540//4540 4541//4541 4542//4542 -f 4542//4542 4541//4541 4543//4543 -f 4542//4542 4543//4543 4544//4544 -f 4545//4545 4546//4546 4547//4547 -f 4548//4548 4549//4549 4550//4550 -f 4551//4551 4529//4529 4552//4552 -f 4552//4552 4529//4529 4531//4531 -f 4552//4552 4531//4531 4553//4553 -f 4553//4553 4531//4531 4554//4554 -f 4555//4555 4556//4556 4557//4557 -f 4558//4558 4559//4559 4560//4560 -f 4561//4561 4545//4545 4562//4562 -f 4562//4562 4545//4545 4547//4547 -f 4562//4562 4547//4547 4563//4563 -f 4564//4564 4565//4565 4566//4566 -f 4566//4566 4565//4565 4567//4567 -f 4568//4568 4557//4557 4569//4569 -f 4569//4569 4557//4557 4570//4570 -f 4571//4571 4572//4572 4573//4573 -f 4538//4538 4574//4574 4539//4539 -f 4539//4539 4574//4574 4575//4575 -f 4539//4539 4575//4575 4567//4567 -f 4567//4567 4575//4575 4576//4576 -f 4567//4567 4576//4576 4566//4566 -f 4577//4577 4578//4578 4579//4579 -f 4563//4563 4547//4547 4580//4580 -f 4580//4580 4547//4547 4581//4581 -f 4580//4580 4581//4581 4560//4560 -f 4560//4560 4581//4581 4582//4582 -f 4560//4560 4582//4582 4558//4558 -f 4558//4558 4582//4582 4583//4583 -f 4558//4558 4583//4583 4584//4584 -f 4548//4548 4550//4550 4585//4585 -f 4555//4555 4557//4557 4586//4586 -f 4586//4586 4557//4557 4568//4568 -f 4586//4586 4568//4568 4587//4587 -f 4588//4588 4589//4589 4590//4590 -f 4590//4590 4589//4589 4591//4591 -f 4592//4592 4593//4593 4579//4579 -f 4579//4579 4593//4593 4594//4594 -f 4579//4579 4594//4594 4577//4577 -f 4595//4595 4596//4596 4597//4597 -f 4571//4571 4573//4573 4598//4598 -f 4568//4568 4599//4599 4587//4587 -f 4587//4587 4599//4599 4590//4590 -f 4587//4587 4590//4590 4600//4600 -f 4600//4600 4590//4590 4591//4591 -f 4601//4601 4602//4602 4603//4603 -f 4604//4604 4605//4605 4606//4606 -f 4607//4607 4608//4608 4602//4602 -f 4602//4602 4608//4608 4609//4609 -f 4610//4610 4611//4611 4612//4612 -f 4612//4612 4611//4611 4613//4613 -f 4612//4612 4613//4613 4614//4614 -f 4531//4531 4615//4615 4554//4554 -f 4554//4554 4615//4615 4607//4607 -f 4554//4554 4607//4607 4616//4616 -f 4616//4616 4607//4607 4602//4602 -f 4616//4616 4602//4602 4617//4617 -f 4618//4618 4557//4557 4619//4619 -f 4620//4620 4621//4621 4622//4622 -f 4623//4623 4624//4624 4625//4625 -f 4626//4626 4627//4627 4628//4628 -f 4629//4629 4609//4609 4630//4630 -f 4631//4631 4632//4632 4633//4633 -f 4633//4633 4632//4632 4634//4634 -f 4633//4633 4634//4634 4635//4635 -f 4635//4635 4634//4634 4636//4636 -f 4637//4637 4638//4638 4639//4639 -f 4639//4639 4638//4638 4640//4640 -f 4639//4639 4640//4640 4641//4641 -f 4609//4609 4629//4629 4602//4602 -f 4602//4602 4629//4629 4642//4642 -f 4602//4602 4642//4642 4603//4603 -f 4643//4643 4644//4644 4645//4645 -f 4645//4645 4644//4644 4646//4646 -f 4573//4573 4647//4647 4648//4648 -f 4595//4595 4597//4597 4649//4649 -f 4650//4650 4556//4556 4651//4651 -f 4592//4592 4579//4579 4652//4652 -f 4652//4652 4579//4579 4653//4653 -f 4652//4652 4653//4653 4625//4625 -f 4625//4625 4653//4653 4654//4654 -f 4625//4625 4654//4654 4623//4623 -f 4623//4623 4654//4654 4655//4655 -f 4623//4623 4655//4655 4656//4656 -f 4550//4550 4657//4657 4658//4658 -f 4620//4620 4622//4622 4659//4659 -f 4559//4559 4558//4558 4603//4603 -f 4603//4603 4558//4558 4660//4660 -f 4603//4603 4660//4660 4601//4601 -f 4633//4633 4661//4661 4631//4631 -f 4631//4631 4661//4661 4645//4645 -f 4631//4631 4645//4645 4662//4662 -f 4662//4662 4645//4645 4646//4646 -f 4632//4632 4663//4663 4634//4634 -f 4634//4634 4663//4663 4664//4664 -f 4634//4634 4664//4664 4665//4665 -f 4665//4665 4664//4664 4647//4647 -f 4665//4665 4647//4647 4666//4666 -f 4666//4666 4647//4647 4573//4573 -f 4667//4667 4532//4532 4668//4668 -f 4668//4668 4532//4532 4534//4534 -f 4668//4668 4534//4534 4669//4669 -f 4669//4669 4534//4534 4670//4670 -f 4669//4669 4670//4670 4671//4671 -f 4671//4671 4670//4670 4598//4598 -f 4671//4671 4598//4598 4672//4672 -f 4672//4672 4598//4598 4573//4573 -f 4672//4672 4573//4573 4596//4596 -f 4596//4596 4573//4573 4648//4648 -f 4596//4596 4648//4648 4597//4597 -f 4556//4556 4650//4650 4557//4557 -f 4557//4557 4650//4650 4673//4673 -f 4557//4557 4673//4673 4619//4619 -f 4540//4540 4542//4542 4674//4674 -f 4674//4674 4542//4542 4675//4675 -f 4674//4674 4675//4675 4676//4676 -f 4676//4676 4675//4675 4585//4585 -f 4676//4676 4585//4585 4677//4677 -f 4677//4677 4585//4585 4550//4550 -f 4677//4677 4550//4550 4621//4621 -f 4621//4621 4550//4550 4658//4658 -f 4621//4621 4658//4658 4622//4622 -f 4640//4640 4678//4678 4641//4641 -f 4641//4641 4678//4678 4679//4679 -f 4641//4641 4679//4679 4680//4680 -f 4680//4680 4679//4679 4681//4681 -f 4680//4680 4681//4681 4604//4604 -f 4604//4604 4681//4681 4682//4682 -f 4604//4604 4682//4682 4605//4605 -f 4605//4605 4682//4682 4683//4683 -f 4605//4605 4683//4683 4684//4684 -f 4684//4684 4683//4683 4629//4629 -f 4684//4684 4629//4629 4685//4685 -f 4685//4685 4629//4629 4630//4630 -f 4624//4624 4623//4623 4619//4619 -f 4619//4619 4623//4623 4686//4686 -f 4619//4619 4686//4686 4618//4618 -f 4576//4576 4687//4687 4566//4566 -f 4566//4566 4687//4687 4688//4688 -f 4566//4566 4688//4688 4689//4689 -f 4689//4689 4688//4688 4657//4657 -f 4689//4689 4657//4657 4690//4690 -f 4690//4690 4657//4657 4550//4550 -f 4613//4613 4691//4691 4614//4614 -f 4614//4614 4691//4691 4692//4692 -f 4614//4614 4692//4692 4693//4693 -f 4693//4693 4692//4692 4694//4694 -f 4693//4693 4694//4694 4639//4639 -f 4639//4639 4694//4694 4695//4695 -f 4639//4639 4695//4695 4637//4637 -f 4637//4637 4695//4695 4696//4696 -f 4637//4637 4696//4696 4597//4597 -f 4597//4597 4696//4696 4697//4697 -f 4597//4597 4697//4697 4649//4649 -f 4628//4628 4698//4698 4626//4626 -f 4626//4626 4698//4698 4699//4699 -f 4626//4626 4699//4699 4700//4700 -f 4700//4700 4699//4699 4701//4701 -f 4700//4700 4701//4701 4702//4702 -f 4702//4702 4701//4701 4703//4703 -f 4702//4702 4703//4703 4612//4612 -f 4612//4612 4703//4703 4704//4704 -f 4612//4612 4704//4704 4610//4610 -f 4610//4610 4704//4704 4705//4705 -f 4610//4610 4705//4705 4706//4706 -f 4706//4706 4705//4705 4650//4650 -f 4706//4706 4650//4650 4707//4707 -f 4707//4707 4650//4650 4651//4651 -f 4606//4606 4708//4708 4604//4604 -f 4604//4604 4708//4708 4709//4709 -f 4604//4604 4709//4709 4710//4710 -f 4710//4710 4709//4709 4711//4711 -f 4710//4710 4711//4711 4712//4712 -f 4712//4712 4711//4711 4713//4713 -f 4712//4712 4713//4713 4626//4626 -f 4626//4626 4713//4713 4714//4714 -f 4626//4626 4714//4714 4627//4627 -f 4627//4627 4714//4714 4715//4715 -f 4627//4627 4715//4715 4622//4622 -f 4622//4622 4715//4715 4716//4716 -f 4622//4622 4716//4716 4659//4659 -f 4717//4717 4718//4718 4719//4719 -f 4720//4720 4721//4721 4722//4722 -f 4723//4723 4724//4724 4725//4725 -f 4725//4725 4724//4724 4726//4726 -f 4727//4727 4728//4728 4729//4729 -f 4729//4729 4728//4728 4730//4730 -f 4729//4729 4730//4730 4731//4731 -f 4732//4732 4733//4733 4734//4734 -f 4735//4735 4720//4720 4736//4736 -f 4736//4736 4720//4720 4722//4722 -f 4736//4736 4722//4722 4737//4737 -f 4738//4738 4739//4739 4740//4740 -f 4741//4741 4742//4742 4743//4743 -f 4744//4744 4745//4745 4746//4746 -f 4726//4726 4747//4747 4725//4725 -f 4725//4725 4747//4747 4748//4748 -f 4725//4725 4748//4748 4749//4749 -f 4749//4749 4748//4748 4750//4750 -f 4749//4749 4750//4750 4751//4751 -f 4751//4751 4750//4750 4752//4752 -f 4751//4751 4752//4752 4753//4753 -f 4753//4753 4752//4752 4754//4754 -f 4755//4755 4756//4756 4004//4004 -f 4757//4757 4758//4758 4759//4759 -f 4759//4759 4758//4758 4760//4760 -f 4759//4759 4760//4760 4761//4761 -f 4737//4737 4722//4722 4762//4762 -f 4762//4762 4722//4722 4763//4763 -f 4762//4762 4763//4763 4743//4743 -f 4743//4743 4763//4763 4764//4764 -f 4743//4743 4764//4764 4741//4741 -f 4741//4741 4764//4764 4765//4765 -f 4741//4741 4765//4765 4766//4766 -f 4755//4755 4004//4004 4767//4767 -f 4768//4768 4769//4769 4770//4770 -f 4771//4771 4772//4772 4773//4773 -f 4738//4738 4740//4740 4774//4774 -f 4734//4734 4717//4717 4732//4732 -f 4732//4732 4717//4717 4719//4719 -f 4732//4732 4719//4719 4775//4775 -f 4775//4775 4719//4719 4767//4767 -f 4775//4775 4767//4767 4776//4776 -f 4776//4776 4767//4767 4004//4004 -f 4776//4776 4004//4004 4777//4777 -f 4777//4777 4004//4004 4006//4006 -f 4778//4778 4779//4779 4780//4780 -f 4780//4780 4779//4779 4781//4781 -f 4782//4782 4783//4783 4773//4773 -f 4773//4773 4783//4783 4784//4784 -f 4773//4773 4784//4784 4771//4771 -f 4785//4785 4744//4744 4786//4786 -f 4786//4786 4744//4744 4746//4746 -f 4786//4786 4746//4746 4787//4787 -f 4787//4787 4746//4746 4788//4788 -f 4746//4746 4789//4789 4788//4788 -f 4788//4788 4789//4789 4778//4778 -f 4788//4788 4778//4778 4790//4790 -f 4790//4790 4778//4778 4780//4780 -f 4790//4790 4780//4780 4791//4791 -f 4792//4792 4793//4793 4794//4794 -f 4795//4795 4796//4796 4797//4797 -f 4797//4797 4796//4796 4798//4798 -f 4797//4797 4798//4798 4799//4799 -f 4800//4800 4073//4073 4071//4071 -f 4801//4801 4802//4802 4803//4803 -f 4804//4804 4805//4805 4806//4806 -f 4807//4807 4004//4004 4808//4808 -f 4809//4809 4781//4781 4810//4810 -f 4782//4782 4773//4773 4811//4811 -f 4811//4811 4773//4773 4812//4812 -f 4811//4811 4812//4812 4813//4813 -f 4813//4813 4812//4812 4814//4814 -f 4813//4813 4814//4814 4815//4815 -f 4815//4815 4814//4814 4816//4816 -f 4815//4815 4816//4816 4817//4817 -f 4818//4818 4819//4819 4820//4820 -f 4820//4820 4819//4819 4821//4821 -f 4781//4781 4809//4809 4780//4780 -f 4780//4780 4809//4809 4822//4822 -f 4780//4780 4822//4822 4823//4823 -f 4824//4824 4780//4780 4825//4825 -f 4825//4825 4780//4780 4823//4823 -f 4825//4825 4823//4823 4815//4815 -f 4815//4815 4823//4823 4826//4826 -f 4815//4815 4826//4826 4813//4813 -f 4071//4071 4827//4827 4828//4828 -f 4804//4804 4806//4806 4829//4829 -f 4800//4800 4071//4071 4830//4830 -f 4760//4760 4831//4831 4761//4761 -f 4761//4761 4831//4831 4832//4832 -f 4761//4761 4832//4832 4821//4821 -f 4821//4821 4832//4832 4833//4833 -f 4821//4821 4833//4833 4820//4820 -f 4727//4727 4729//4729 4834//4834 -f 4834//4834 4729//4729 4835//4835 -f 4834//4834 4835//4835 4836//4836 -f 4836//4836 4835//4835 4830//4830 -f 4836//4836 4830//4830 4837//4837 -f 4837//4837 4830//4830 4071//4071 -f 4837//4837 4071//4071 4805//4805 -f 4805//4805 4071//4071 4828//4828 -f 4805//4805 4828//4828 4806//4806 -f 4838//4838 4839//4839 4840//4840 -f 4803//4803 4841//4841 4801//4801 -f 4801//4801 4841//4841 4842//4842 -f 4801//4801 4842//4842 4843//4843 -f 4843//4843 4842//4842 4844//4844 -f 4843//4843 4844//4844 4845//4845 -f 4845//4845 4844//4844 4846//4846 -f 4845//4845 4846//4846 4797//4797 -f 4797//4797 4846//4846 4847//4847 -f 4797//4797 4847//4847 4795//4795 -f 4795//4795 4847//4847 4848//4848 -f 4795//4795 4848//4848 4849//4849 -f 4849//4849 4848//4848 4809//4809 -f 4849//4849 4809//4809 4850//4850 -f 4850//4850 4809//4809 4810//4810 -f 4750//4750 4851//4851 4752//4752 -f 4752//4752 4851//4851 4852//4852 -f 4752//4752 4852//4852 4853//4853 -f 4853//4853 4852//4852 4827//4827 -f 4853//4853 4827//4827 4854//4854 -f 4854//4854 4827//4827 4071//4071 -f 4855//4855 4756//4756 4856//4856 -f 4857//4857 4858//4858 4859//4859 -f 4859//4859 4858//4858 4860//4860 -f 4859//4859 4860//4860 4861//4861 -f 4840//4840 4862//4862 4838//4838 -f 4838//4838 4862//4862 4863//4863 -f 4838//4838 4863//4863 4864//4864 -f 4864//4864 4863//4863 4865//4865 -f 4864//4864 4865//4865 4866//4866 -f 4866//4866 4865//4865 4867//4867 -f 4866//4866 4867//4867 4801//4801 -f 4801//4801 4867//4867 4868//4868 -f 4801//4801 4868//4868 4802//4802 -f 4802//4802 4868//4868 4869//4869 -f 4802//4802 4869//4869 4806//4806 -f 4806//4806 4869//4869 4870//4870 -f 4806//4806 4870//4870 4829//4829 -f 4756//4756 4855//4855 4004//4004 -f 4004//4004 4855//4855 4871//4871 -f 4004//4004 4871//4871 4808//4808 -f 4740//4740 4872//4872 4873//4873 -f 4792//4792 4794//4794 4874//4874 -f 4742//4742 4741//4741 4808//4808 -f 4808//4808 4741//4741 4875//4875 -f 4808//4808 4875//4875 4807//4807 -f 4833//4833 4876//4876 4820//4820 -f 4820//4820 4876//4876 4877//4877 -f 4820//4820 4877//4877 4878//4878 -f 4878//4878 4877//4877 4872//4872 -f 4878//4878 4872//4872 4879//4879 -f 4879//4879 4872//4872 4740//4740 -f 4880//4880 4768//4768 4881//4881 -f 4881//4881 4768//4768 4770//4770 -f 4881//4881 4770//4770 4882//4882 -f 4882//4882 4770//4770 4883//4883 -f 4882//4882 4883//4883 4884//4884 -f 4884//4884 4883//4883 4774//4774 -f 4884//4884 4774//4774 4885//4885 -f 4885//4885 4774//4774 4740//4740 -f 4885//4885 4740//4740 4793//4793 -f 4793//4793 4740//4740 4873//4873 -f 4793//4793 4873//4873 4794//4794 -f 4860//4860 4886//4886 4861//4861 -f 4861//4861 4886//4886 4887//4887 -f 4861//4861 4887//4887 4888//4888 -f 4888//4888 4887//4887 4889//4889 -f 4888//4888 4889//4889 4838//4838 -f 4838//4838 4889//4889 4890//4890 -f 4838//4838 4890//4890 4839//4839 -f 4839//4839 4890//4890 4891//4891 -f 4839//4839 4891//4891 4892//4892 -f 4892//4892 4891//4891 4855//4855 -f 4892//4892 4855//4855 4893//4893 -f 4893//4893 4855//4855 4856//4856 -f 4798//4798 4894//4894 4799//4799 -f 4799//4799 4894//4894 4895//4895 -f 4799//4799 4895//4895 4896//4896 -f 4896//4896 4895//4895 4897//4897 -f 4896//4896 4897//4897 4859//4859 -f 4859//4859 4897//4897 4898//4898 -f 4859//4859 4898//4898 4857//4857 -f 4857//4857 4898//4898 4899//4899 -f 4857//4857 4899//4899 4794//4794 -f 4794//4794 4899//4899 4900//4900 -f 4794//4794 4900//4900 4874//4874 -f 4589//4589 4588//4588 4768//4768 -f 4768//4768 4588//4588 4769//4769 -f 4589//4589 4768//4768 4880//4880 -f 4589//4589 4880//4880 4591//4591 -f 4591//4591 4880//4880 4881//4881 -f 4591//4591 4881//4881 4600//4600 -f 4600//4600 4881//4881 4882//4882 -f 4600//4600 4882//4882 4587//4587 -f 4586//4586 4587//4587 4884//4884 -f 4884//4884 4587//4587 4882//4882 -f 4586//4586 4884//4884 4555//4555 -f 4555//4555 4884//4884 4885//4885 -f 4555//4555 4885//4885 4556//4556 -f 4556//4556 4885//4885 4793//4793 -f 4556//4556 4793//4793 4651//4651 -f 4651//4651 4793//4793 4792//4792 -f 4707//4707 4651//4651 4874//4874 -f 4874//4874 4651//4651 4792//4792 -f 4707//4707 4874//4874 4706//4706 -f 4706//4706 4874//4874 4900//4900 -f 4706//4706 4900//4900 4610//4610 -f 4610//4610 4900//4900 4899//4899 -f 4611//4611 4610//4610 4898//4898 -f 4898//4898 4610//4610 4899//4899 -f 4611//4611 4898//4898 4613//4613 -f 4613//4613 4898//4898 4897//4897 -f 4613//4613 4897//4897 4691//4691 -f 4691//4691 4897//4897 4895//4895 -f 4692//4692 4691//4691 4894//4894 -f 4894//4894 4691//4691 4895//4895 -f 4692//4692 4894//4894 4694//4694 -f 4694//4694 4894//4894 4798//4798 -f 4694//4694 4798//4798 4695//4695 -f 4695//4695 4798//4798 4796//4796 -f 4696//4696 4695//4695 4795//4795 -f 4795//4795 4695//4695 4796//4796 -f 4696//4696 4795//4795 4697//4697 -f 4697//4697 4795//4795 4849//4849 -f 4697//4697 4849//4849 4649//4649 -f 4649//4649 4849//4849 4850//4850 -f 4595//4595 4649//4649 4810//4810 -f 4810//4810 4649//4649 4850//4850 -f 4595//4595 4810//4810 4596//4596 -f 4596//4596 4810//4810 4781//4781 -f 4596//4596 4781//4781 4672//4672 -f 4672//4672 4781//4781 4779//4779 -f 4672//4672 4779//4779 4671//4671 -f 4671//4671 4779//4779 4778//4778 -f 4669//4669 4671//4671 4789//4789 -f 4789//4789 4671//4671 4778//4778 -f 4669//4669 4789//4789 4746//4746 -f 4669//4669 4746//4746 4668//4668 -f 4668//4668 4746//4746 4745//4745 -f 4668//4668 4745//4745 4667//4667 -f 4667//4667 4745//4745 4744//4744 -f 4667//4667 4744//4744 4532//4532 -f 4533//4533 4532//4532 4785//4785 -f 4785//4785 4532//4532 4744//4744 -f 4534//4534 4533//4533 4786//4786 -f 4786//4786 4533//4533 4785//4785 -f 4534//4534 4786//4786 4670//4670 -f 4670//4670 4786//4786 4787//4787 -f 4670//4670 4787//4787 4598//4598 -f 4598//4598 4787//4787 4788//4788 -f 4598//4598 4788//4788 4571//4571 -f 4571//4571 4788//4788 4790//4790 -f 4572//4572 4571//4571 4791//4791 -f 4791//4791 4571//4571 4790//4790 -f 4573//4573 4572//4572 4780//4780 -f 4780//4780 4572//4572 4791//4791 -f 4573//4573 4780//4780 4824//4824 -f 4573//4573 4824//4824 4666//4666 -f 4666//4666 4824//4824 4825//4825 -f 4666//4666 4825//4825 4665//4665 -f 4665//4665 4825//4825 4815//4815 -f 4665//4665 4815//4815 4634//4634 -f 4636//4636 4634//4634 4817//4817 -f 4817//4817 4634//4634 4815//4815 -f 4635//4635 4636//4636 4816//4816 -f 4816//4816 4636//4636 4817//4817 -f 4635//4635 4816//4816 4633//4633 -f 4633//4633 4816//4816 4814//4814 -f 4633//4633 4814//4814 4661//4661 -f 4661//4661 4814//4814 4812//4812 -f 4661//4661 4812//4812 4645//4645 -f 4645//4645 4812//4812 4773//4773 -f 4643//4643 4645//4645 4772//4772 -f 4772//4772 4645//4645 4773//4773 -f 4644//4644 4643//4643 4771//4771 -f 4771//4771 4643//4643 4772//4772 -f 4644//4644 4771//4771 4784//4784 -f 4644//4644 4784//4784 4646//4646 -f 4646//4646 4784//4784 4783//4783 -f 4646//4646 4783//4783 4662//4662 -f 4662//4662 4783//4783 4782//4782 -f 4662//4662 4782//4782 4631//4631 -f 4632//4632 4631//4631 4811//4811 -f 4811//4811 4631//4631 4782//4782 -f 4632//4632 4811//4811 4663//4663 -f 4663//4663 4811//4811 4813//4813 -f 4663//4663 4813//4813 4664//4664 -f 4664//4664 4813//4813 4826//4826 -f 4664//4664 4826//4826 4647//4647 -f 4647//4647 4826//4826 4823//4823 -f 4648//4648 4647//4647 4822//4822 -f 4822//4822 4647//4647 4823//4823 -f 4648//4648 4822//4822 4597//4597 -f 4597//4597 4822//4822 4809//4809 -f 4597//4597 4809//4809 4637//4637 -f 4637//4637 4809//4809 4848//4848 -f 4638//4638 4637//4637 4847//4847 -f 4847//4847 4637//4637 4848//4848 -f 4638//4638 4847//4847 4640//4640 -f 4640//4640 4847//4847 4846//4846 -f 4640//4640 4846//4846 4678//4678 -f 4678//4678 4846//4846 4844//4844 -f 4679//4679 4678//4678 4842//4842 -f 4842//4842 4678//4678 4844//4844 -f 4679//4679 4842//4842 4681//4681 -f 4681//4681 4842//4842 4841//4841 -f 4681//4681 4841//4841 4682//4682 -f 4682//4682 4841//4841 4803//4803 -f 4683//4683 4682//4682 4802//4802 -f 4802//4802 4682//4682 4803//4803 -f 4683//4683 4802//4802 4629//4629 -f 4629//4629 4802//4802 4806//4806 -f 4629//4629 4806//4806 4642//4642 -f 4642//4642 4806//4806 4828//4828 -f 4603//4603 4642//4642 4827//4827 -f 4827//4827 4642//4642 4828//4828 -f 4603//4603 4827//4827 4559//4559 -f 4559//4559 4827//4827 4852//4852 -f 4559//4559 4852//4852 4560//4560 -f 4560//4560 4852//4852 4851//4851 -f 4560//4560 4851//4851 4580//4580 -f 4580//4580 4851//4851 4750//4750 -f 4563//4563 4580//4580 4748//4748 -f 4748//4748 4580//4580 4750//4750 -f 4563//4563 4748//4748 4747//4747 -f 4563//4563 4747//4747 4562//4562 -f 4562//4562 4747//4747 4726//4726 -f 4562//4562 4726//4726 4561//4561 -f 4561//4561 4726//4726 4724//4724 -f 4561//4561 4724//4724 4545//4545 -f 4546//4546 4545//4545 4723//4723 -f 4723//4723 4545//4545 4724//4724 -f 4547//4547 4546//4546 4725//4725 -f 4725//4725 4546//4546 4723//4723 -f 4547//4547 4725//4725 4581//4581 -f 4581//4581 4725//4725 4749//4749 -f 4581//4581 4749//4749 4582//4582 -f 4582//4582 4749//4749 4751//4751 -f 4582//4582 4751//4751 4583//4583 -f 4583//4583 4751//4751 4753//4753 -f 4584//4584 4583//4583 4754//4754 -f 4754//4754 4583//4583 4753//4753 -f 4558//4558 4584//4584 4752//4752 -f 4752//4752 4584//4584 4754//4754 -f 4558//4558 4752//4752 4853//4853 -f 4558//4558 4853//4853 4660//4660 -f 4660//4660 4853//4853 4854//4854 -f 4660//4660 4854//4854 4601//4601 -f 4601//4601 4854//4854 4071//4071 -f 4601//4601 4071//4071 4602//4602 -f 4617//4617 4602//4602 4073//4073 -f 4073//4073 4602//4602 4071//4071 -f 4616//4616 4617//4617 4800//4800 -f 4800//4800 4617//4617 4073//4073 -f 4616//4616 4800//4800 4554//4554 -f 4554//4554 4800//4800 4830//4830 -f 4554//4554 4830//4830 4553//4553 -f 4553//4553 4830//4830 4835//4835 -f 4553//4553 4835//4835 4552//4552 -f 4552//4552 4835//4835 4729//4729 -f 4551//4551 4552//4552 4731//4731 -f 4731//4731 4552//4552 4729//4729 -f 4529//4529 4551//4551 4730//4730 -f 4730//4730 4551//4551 4731//4731 -f 4529//4529 4730//4730 4728//4728 -f 4529//4529 4728//4728 4530//4530 -f 4530//4530 4728//4728 4727//4727 -f 4530//4530 4727//4727 4531//4531 -f 4531//4531 4727//4727 4834//4834 -f 4531//4531 4834//4834 4615//4615 -f 4607//4607 4615//4615 4836//4836 -f 4836//4836 4615//4615 4834//4834 -f 4607//4607 4836//4836 4608//4608 -f 4608//4608 4836//4836 4837//4837 -f 4608//4608 4837//4837 4609//4609 -f 4609//4609 4837//4837 4805//4805 -f 4609//4609 4805//4805 4630//4630 -f 4630//4630 4805//4805 4804//4804 -f 4685//4685 4630//4630 4829//4829 -f 4829//4829 4630//4630 4804//4804 -f 4685//4685 4829//4829 4684//4684 -f 4684//4684 4829//4829 4870//4870 -f 4684//4684 4870//4870 4605//4605 -f 4605//4605 4870//4870 4869//4869 -f 4606//4606 4605//4605 4868//4868 -f 4868//4868 4605//4605 4869//4869 -f 4606//4606 4868//4868 4708//4708 -f 4708//4708 4868//4868 4867//4867 -f 4708//4708 4867//4867 4709//4709 -f 4709//4709 4867//4867 4865//4865 -f 4711//4711 4709//4709 4863//4863 -f 4863//4863 4709//4709 4865//4865 -f 4711//4711 4863//4863 4713//4713 -f 4713//4713 4863//4863 4862//4862 -f 4713//4713 4862//4862 4714//4714 -f 4714//4714 4862//4862 4840//4840 -f 4715//4715 4714//4714 4839//4839 -f 4839//4839 4714//4714 4840//4840 -f 4715//4715 4839//4839 4716//4716 -f 4716//4716 4839//4839 4892//4892 -f 4716//4716 4892//4892 4659//4659 -f 4659//4659 4892//4892 4893//4893 -f 4620//4620 4659//4659 4856//4856 -f 4856//4856 4659//4659 4893//4893 -f 4620//4620 4856//4856 4621//4621 -f 4621//4621 4856//4856 4756//4756 -f 4621//4621 4756//4756 4677//4677 -f 4677//4677 4756//4756 4755//4755 -f 4677//4677 4755//4755 4676//4676 -f 4676//4676 4755//4755 4767//4767 -f 4674//4674 4676//4676 4719//4719 -f 4719//4719 4676//4676 4767//4767 -f 4674//4674 4719//4719 4718//4718 -f 4674//4674 4718//4718 4540//4540 -f 4540//4540 4718//4718 4717//4717 -f 4540//4540 4717//4717 4541//4541 -f 4541//4541 4717//4717 4734//4734 -f 4541//4541 4734//4734 4543//4543 -f 4544//4544 4543//4543 4733//4733 -f 4733//4733 4543//4543 4734//4734 -f 4542//4542 4544//4544 4732//4732 -f 4732//4732 4544//4544 4733//4733 -f 4542//4542 4732//4732 4675//4675 -f 4675//4675 4732//4732 4775//4775 -f 4675//4675 4775//4775 4585//4585 -f 4585//4585 4775//4775 4776//4776 -f 4585//4585 4776//4776 4548//4548 -f 4548//4548 4776//4776 4777//4777 -f 4549//4549 4548//4548 4006//4006 -f 4006//4006 4548//4548 4777//4777 -f 4550//4550 4549//4549 4004//4004 -f 4004//4004 4549//4549 4006//4006 -f 4550//4550 4004//4004 4807//4807 -f 4550//4550 4807//4807 4690//4690 -f 4690//4690 4807//4807 4875//4875 -f 4690//4690 4875//4875 4689//4689 -f 4689//4689 4875//4875 4741//4741 -f 4689//4689 4741//4741 4566//4566 -f 4564//4564 4566//4566 4766//4766 -f 4766//4766 4566//4566 4741//4741 -f 4565//4565 4564//4564 4765//4765 -f 4765//4765 4564//4564 4766//4766 -f 4565//4565 4765//4765 4567//4567 -f 4567//4567 4765//4765 4764//4764 -f 4567//4567 4764//4764 4539//4539 -f 4539//4539 4764//4764 4763//4763 -f 4539//4539 4763//4763 4537//4537 -f 4537//4537 4763//4763 4722//4722 -f 4535//4535 4537//4537 4721//4721 -f 4721//4721 4537//4537 4722//4722 -f 4536//4536 4535//4535 4720//4720 -f 4720//4720 4535//4535 4721//4721 -f 4536//4536 4720//4720 4735//4735 -f 4536//4536 4735//4735 4538//4538 -f 4538//4538 4735//4735 4736//4736 -f 4538//4538 4736//4736 4574//4574 -f 4574//4574 4736//4736 4737//4737 -f 4574//4574 4737//4737 4575//4575 -f 4576//4576 4575//4575 4762//4762 -f 4762//4762 4575//4575 4737//4737 -f 4576//4576 4762//4762 4687//4687 -f 4687//4687 4762//4762 4743//4743 -f 4687//4687 4743//4743 4688//4688 -f 4688//4688 4743//4743 4742//4742 -f 4688//4688 4742//4742 4657//4657 -f 4657//4657 4742//4742 4808//4808 -f 4658//4658 4657//4657 4871//4871 -f 4871//4871 4657//4657 4808//4808 -f 4658//4658 4871//4871 4622//4622 -f 4622//4622 4871//4871 4855//4855 -f 4622//4622 4855//4855 4627//4627 -f 4627//4627 4855//4855 4891//4891 -f 4628//4628 4627//4627 4890//4890 -f 4890//4890 4627//4627 4891//4891 -f 4628//4628 4890//4890 4698//4698 -f 4698//4698 4890//4890 4889//4889 -f 4698//4698 4889//4889 4699//4699 -f 4699//4699 4889//4889 4887//4887 -f 4701//4701 4699//4699 4886//4886 -f 4886//4886 4699//4699 4887//4887 -f 4701//4701 4886//4886 4703//4703 -f 4703//4703 4886//4886 4860//4860 -f 4703//4703 4860//4860 4704//4704 -f 4704//4704 4860//4860 4858//4858 -f 4705//4705 4704//4704 4857//4857 -f 4857//4857 4704//4704 4858//4858 -f 4705//4705 4857//4857 4650//4650 -f 4650//4650 4857//4857 4794//4794 -f 4650//4650 4794//4794 4673//4673 -f 4673//4673 4794//4794 4873//4873 -f 4619//4619 4673//4673 4872//4872 -f 4872//4872 4673//4673 4873//4873 -f 4619//4619 4872//4872 4624//4624 -f 4624//4624 4872//4872 4877//4877 -f 4624//4624 4877//4877 4625//4625 -f 4625//4625 4877//4877 4876//4876 -f 4625//4625 4876//4876 4652//4652 -f 4652//4652 4876//4876 4833//4833 -f 4592//4592 4652//4652 4832//4832 -f 4832//4832 4652//4652 4833//4833 -f 4592//4592 4832//4832 4831//4831 -f 4592//4592 4831//4831 4593//4593 -f 4593//4593 4831//4831 4760//4760 -f 4593//4593 4760//4760 4594//4594 -f 4594//4594 4760//4760 4758//4758 -f 4594//4594 4758//4758 4577//4577 -f 4578//4578 4577//4577 4757//4757 -f 4757//4757 4577//4577 4758//4758 -f 4579//4579 4578//4578 4759//4759 -f 4759//4759 4578//4578 4757//4757 -f 4579//4579 4759//4759 4653//4653 -f 4653//4653 4759//4759 4761//4761 -f 4653//4653 4761//4761 4654//4654 -f 4654//4654 4761//4761 4821//4821 -f 4654//4654 4821//4821 4655//4655 -f 4655//4655 4821//4821 4819//4819 -f 4656//4656 4655//4655 4818//4818 -f 4818//4818 4655//4655 4819//4819 -f 4623//4623 4656//4656 4820//4820 -f 4820//4820 4656//4656 4818//4818 -f 4623//4623 4820//4820 4878//4878 -f 4623//4623 4878//4878 4686//4686 -f 4686//4686 4878//4878 4879//4879 -f 4686//4686 4879//4879 4618//4618 -f 4618//4618 4879//4879 4740//4740 -f 4618//4618 4740//4740 4557//4557 -f 4570//4570 4557//4557 4739//4739 -f 4739//4739 4557//4557 4740//4740 -f 4569//4569 4570//4570 4738//4738 -f 4738//4738 4570//4570 4739//4739 -f 4569//4569 4738//4738 4568//4568 -f 4568//4568 4738//4738 4774//4774 -f 4568//4568 4774//4774 4599//4599 -f 4599//4599 4774//4774 4883//4883 -f 4599//4599 4883//4883 4590//4590 -f 4590//4590 4883//4883 4770//4770 -f 4588//4588 4590//4590 4769//4769 -f 4769//4769 4590//4590 4770//4770 -f 4614//4614 4799//4799 4612//4612 -f 4612//4612 4799//4799 4896//4896 -f 4612//4612 4896//4896 4702//4702 -f 4702//4702 4896//4896 4859//4859 -f 4702//4702 4859//4859 4700//4700 -f 4700//4700 4859//4859 4861//4861 -f 4700//4700 4861//4861 4626//4626 -f 4626//4626 4861//4861 4888//4888 -f 4626//4626 4888//4888 4712//4712 -f 4712//4712 4888//4888 4838//4838 -f 4712//4712 4838//4838 4710//4710 -f 4710//4710 4838//4838 4864//4864 -f 4710//4710 4864//4864 4604//4604 -f 4604//4604 4864//4864 4866//4866 -f 4604//4604 4866//4866 4680//4680 -f 4680//4680 4866//4866 4801//4801 -f 4680//4680 4801//4801 4641//4641 -f 4641//4641 4801//4801 4843//4843 -f 4641//4641 4843//4843 4639//4639 -f 4639//4639 4843//4843 4845//4845 -f 4639//4639 4845//4845 4693//4693 -f 4693//4693 4845//4845 4797//4797 -f 4693//4693 4797//4797 4614//4614 -f 4614//4614 4797//4797 4799//4799 -# 9848 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_crveno.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_crveno.obj deleted file mode 100644 index 762f93151..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_crveno.obj +++ /dev/null @@ -1,8460 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object robot-crveno.obj -# -# Vertices: 2074 -# Faces: 4296 -# -#### -vn 0.000000 -1.000000 0.000000 -v 0.035250 -0.148000 0.130850 -vn 0.707107 -0.707107 0.000000 -v 0.039000 -0.148000 0.130850 -vn 0.707107 -0.707107 0.000000 -v 0.039000 -0.148000 0.197900 -vn 0.071345 -0.685696 -0.724383 -v -0.053260 -0.148000 0.005000 -vn 0.285560 -0.665719 -0.689401 -v -0.049433 -0.148000 0.005761 -vn 0.527644 -0.665720 -0.527644 -v -0.046189 -0.148000 0.007929 -vn -0.552289 -0.770261 -0.318865 -v 0.031165 -0.148000 0.107050 -vn -0.637727 -0.770262 -0.000001 -v 0.031500 -0.148000 0.105800 -vn 0.527645 -0.665718 -0.527645 -v 0.036071 -0.148000 0.071947 -vn -0.552288 -0.770262 0.318865 -v 0.031165 -0.148000 0.104550 -vn -0.318864 -0.770261 0.552289 -v 0.030250 -0.148000 0.103635 -vn 0.285560 -0.665719 -0.689401 -v 0.032827 -0.148000 0.069780 -vn 0.000000 -0.770263 0.637727 -v 0.029000 -0.148000 0.103300 -vn 0.071346 -0.685696 -0.724383 -v 0.029000 -0.148000 0.069018 -vn 0.038914 -0.719948 -0.692936 -v 0.000740 -0.148000 0.069018 -vn 0.000000 -0.707107 0.707107 -v -0.025500 -0.148000 0.080800 -vn 0.290991 -0.731273 -0.616898 -v -0.018351 -0.148000 0.064661 -vn -0.301512 -0.904534 0.301511 -v -0.017500 -0.148000 0.080800 -vn 0.151318 -0.733198 -0.662966 -v -0.009051 -0.148000 0.067915 -vn 0.552289 -0.770262 -0.318863 -v 0.026835 -0.148000 0.107050 -vn -0.707107 -0.707106 -0.000000 -v -0.017500 -0.148000 0.130850 -vn 0.637728 -0.770262 -0.000000 -v 0.026500 -0.148000 0.105800 -vn 0.552288 -0.770262 0.318864 -v 0.026835 -0.148000 0.104550 -vn 0.318865 -0.770261 0.552289 -v 0.027750 -0.148000 0.103635 -vn 0.318864 -0.770262 -0.552288 -v 0.027750 -0.148000 0.107965 -vn 0.000000 -0.770261 -0.637729 -v 0.029000 -0.148000 0.108300 -vn -0.318863 -0.770262 -0.552288 -v 0.030250 -0.148000 0.107965 -vn -0.318865 -0.770261 0.552288 -v -0.078750 -0.148000 0.103635 -vn -0.000000 -0.770263 0.637727 -v -0.080000 -0.148000 0.103300 -vn -0.707105 -0.707108 -0.000000 -v -0.090000 -0.148000 0.060000 -vn 0.318865 -0.770262 0.552288 -v -0.081250 -0.148000 0.103635 -vn -0.637727 -0.770263 -0.000000 -v -0.077500 -0.148000 0.105800 -vn 0.301511 -0.904534 0.301511 -v -0.033500 -0.148000 0.080800 -vn -0.552290 -0.770261 -0.318864 -v -0.077835 -0.148000 0.107050 -vn 0.707106 -0.707107 0.000000 -v -0.033500 -0.148000 0.130850 -vn 0.428333 -0.708922 -0.560322 -v -0.025827 -0.148000 0.060093 -vn 0.389717 -0.718500 -0.576090 -v -0.025572 -0.148000 0.060284 -vn 0.552288 -0.770262 0.318865 -v -0.082165 -0.148000 0.104550 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 -0.148000 0.105800 -vn -0.707107 -0.707106 -0.000000 -v -0.090000 -0.148000 0.130850 -vn 0.552290 -0.770261 -0.318864 -v -0.082165 -0.148000 0.107050 -vn 0.318864 -0.770263 -0.552287 -v -0.081250 -0.148000 0.107965 -vn -0.000000 -0.770261 -0.637729 -v -0.080000 -0.148000 0.108300 -vn -0.318864 -0.770263 -0.552287 -v -0.078750 -0.148000 0.107965 -vn 0.318863 -0.770263 0.552287 -v -0.081250 -0.148000 0.012035 -vn 0.552290 -0.770261 0.318864 -v -0.082165 -0.148000 0.012950 -vn -0.609915 -0.670164 -0.422947 -v -0.088040 -0.148000 0.008254 -vn -0.318864 -0.770263 0.552287 -v -0.078750 -0.148000 0.012035 -vn -0.000000 -0.770261 0.637729 -v -0.080000 -0.148000 0.011700 -vn -0.552290 -0.770261 0.318864 -v -0.077835 -0.148000 0.012950 -vn 0.689401 -0.665719 -0.285560 -v -0.044021 -0.148000 0.011173 -vn -0.637727 -0.770263 0.000000 -v -0.077500 -0.148000 0.014200 -vn 0.724382 -0.685697 -0.071345 -v -0.043260 -0.148000 0.015000 -vn -0.552289 -0.770261 -0.318864 -v -0.077835 -0.148000 0.015450 -vn -0.000000 -0.770261 -0.637729 -v -0.080000 -0.148000 0.016700 -vn -0.318864 -0.770263 -0.552287 -v -0.078750 -0.148000 0.016365 -vn -0.693720 -0.673104 -0.256288 -v -0.089252 -0.148000 0.010404 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 -0.148000 0.014200 -vn -0.724277 -0.685873 -0.070725 -v -0.090000 -0.148000 0.014200 -vn 0.552289 -0.770261 -0.318865 -v -0.082165 -0.148000 0.015450 -vn 0.318863 -0.770263 -0.552288 -v -0.081250 -0.148000 0.016365 -vn -0.552288 -0.770262 0.318865 -v -0.077835 -0.148000 0.104550 -vn 0.458227 -0.721401 -0.519238 -v -0.026694 -0.148000 0.059419 -vn 0.531657 -0.733198 -0.423983 -v -0.033661 -0.148000 0.052452 -vn 0.692937 -0.719948 -0.038914 -v -0.043260 -0.148000 0.025018 -vn 0.662966 -0.733198 -0.151318 -v -0.042157 -0.148000 0.034809 -vn 0.612673 -0.733198 -0.295047 -v -0.038903 -0.148000 0.044109 -vn -0.224512 -0.646480 -0.729149 -v -0.083919 -0.148000 0.005000 -vn -0.490010 -0.678480 -0.547316 -v -0.087118 -0.148000 0.007176 -vn -0.637727 -0.770263 0.000000 -v -0.077500 -0.148000 0.239900 -vn -0.552290 -0.770261 0.318864 -v -0.077835 -0.148000 0.238650 -vn 0.724383 -0.685696 0.071346 -v -0.063500 -0.148000 0.237100 -vn 0.707107 -0.707107 0.000000 -v -0.063500 -0.148000 0.197900 -vn -0.318864 -0.770263 0.552287 -v -0.078750 -0.148000 0.237735 -vn -0.707107 -0.707106 0.000000 -v -0.090000 -0.148000 0.197900 -vn -0.000000 -0.770261 0.637729 -v -0.080000 -0.148000 0.237400 -vn 0.318863 -0.770263 0.552287 -v -0.081250 -0.148000 0.237735 -vn -0.724277 -0.685873 0.070725 -v -0.090000 -0.148000 0.237900 -vn 0.552290 -0.770261 0.318864 -v -0.082165 -0.148000 0.238650 -vn -0.690081 -0.666047 0.283144 -v -0.089252 -0.148000 0.241696 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 -0.148000 0.239900 -vn -0.530949 -0.666046 0.523905 -v -0.087118 -0.148000 0.244924 -vn 0.552290 -0.770261 -0.318864 -v -0.082165 -0.148000 0.241150 -vn -0.224511 -0.646480 0.729149 -v -0.083919 -0.148000 0.247100 -vn 0.689401 -0.665719 0.285560 -v -0.064261 -0.148000 0.240927 -vn 0.527645 -0.665719 0.527645 -v -0.066429 -0.148000 0.244171 -vn -0.552290 -0.770261 -0.318864 -v -0.077835 -0.148000 0.241150 -vn 0.285559 -0.665719 0.689402 -v -0.069673 -0.148000 0.246339 -vn -0.318868 -0.770261 -0.552287 -v -0.078750 -0.148000 0.242065 -vn 0.071345 -0.685697 0.724383 -v -0.073500 -0.148000 0.247100 -vn -0.000000 -0.770264 -0.637725 -v -0.080000 -0.148000 0.242400 -vn 0.318867 -0.770261 -0.552287 -v -0.081250 -0.148000 0.242065 -vn 0.692294 -0.667148 0.275031 -v -0.034207 -0.148000 0.143621 -vn 0.541839 -0.667148 0.511199 -v -0.036226 -0.148000 0.146792 -vn 0.723916 -0.686464 0.068643 -v -0.033500 -0.148000 0.139929 -vn 0.368152 -0.686464 0.627081 -v -0.039274 -0.148000 0.148992 -vn 0.346567 -0.728984 0.590316 -v -0.057726 -0.148000 0.157597 -vn -0.000000 -0.770261 0.637729 -v -0.080000 -0.148000 0.153400 -vn 0.318863 -0.770263 0.552287 -v -0.081250 -0.148000 0.153735 -vn -0.318864 -0.770263 0.552287 -v -0.078750 -0.148000 0.153735 -vn -0.552289 -0.770261 0.318864 -v -0.077835 -0.148000 0.154650 -vn 0.552290 -0.770261 -0.318864 -v -0.082165 -0.148000 0.157150 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 -0.148000 0.155900 -vn 0.552290 -0.770261 0.318864 -v -0.082165 -0.148000 0.154650 -vn 0.318863 -0.770263 -0.552287 -v -0.081250 -0.148000 0.158065 -vn -0.000000 -0.770261 -0.637729 -v -0.080000 -0.148000 0.158400 -vn -0.318864 -0.770263 -0.552287 -v -0.078750 -0.148000 0.158065 -vn 0.681474 -0.728984 0.064618 -v -0.063500 -0.148000 0.166660 -vn -0.552290 -0.770261 -0.318864 -v -0.077835 -0.148000 0.157150 -vn -0.637727 -0.770263 0.000000 -v -0.077500 -0.148000 0.155900 -vn 0.479491 -0.751960 0.452377 -v -0.060774 -0.148000 0.159798 -vn 0.612634 -0.751960 0.243384 -v -0.062793 -0.148000 0.162968 -vn -0.637727 -0.770262 0.000000 -v 0.031500 -0.148000 0.155900 -vn -0.552289 -0.770261 0.318864 -v 0.031165 -0.148000 0.154650 -vn -0.318863 -0.770262 0.552288 -v 0.030250 -0.148000 0.153735 -vn 0.000000 -0.770261 0.637729 -v 0.029000 -0.148000 0.153400 -vn 0.318864 -0.770262 -0.552288 -v 0.027750 -0.148000 0.158065 -vn 0.000000 -0.770261 -0.637729 -v 0.029000 -0.148000 0.158400 -vn 0.000000 -1.000000 0.000000 -v 0.035250 -0.148000 0.197900 -vn -0.318863 -0.770262 -0.552288 -v 0.030250 -0.148000 0.158065 -vn -0.552289 -0.770261 -0.318864 -v 0.031165 -0.148000 0.157150 -vn 0.318864 -0.770262 0.552288 -v 0.027750 -0.148000 0.153735 -vn 0.552289 -0.770262 0.318864 -v 0.026835 -0.148000 0.154650 -vn 0.637727 -0.770262 -0.000000 -v 0.026500 -0.148000 0.155900 -vn -0.368152 -0.686464 0.627081 -v -0.011726 -0.148000 0.148992 -vn -0.541839 -0.667148 0.511198 -v -0.014774 -0.148000 0.146792 -vn -0.692294 -0.667148 0.275031 -v -0.016793 -0.148000 0.143621 -vn -0.707107 -0.707107 -0.000000 -v 0.012500 -0.148000 0.197900 -vn -0.681474 -0.728984 0.064618 -v 0.012500 -0.148000 0.166660 -vn 0.552289 -0.770261 -0.318864 -v 0.026835 -0.148000 0.157150 -vn -0.612635 -0.751960 0.243384 -v 0.011793 -0.148000 0.162968 -vn -0.723916 -0.686464 0.068643 -v -0.017500 -0.148000 0.139929 -vn -0.346567 -0.728984 0.590316 -v 0.006726 -0.148000 0.157597 -vn -0.479491 -0.751960 0.452377 -v 0.009774 -0.148000 0.159798 -vn 0.530949 -0.666046 0.523905 -v 0.036118 -0.148000 0.244924 -vn 0.224511 -0.646480 0.729149 -v 0.032919 -0.148000 0.247100 -vn -0.071345 -0.685697 0.724383 -v 0.022500 -0.148000 0.247100 -vn -0.285559 -0.665719 0.689402 -v 0.018673 -0.148000 0.246339 -vn -0.527645 -0.665719 0.527645 -v 0.015429 -0.148000 0.244171 -vn -0.724383 -0.685696 0.071346 -v 0.012500 -0.148000 0.237100 -vn -0.689401 -0.665719 0.285560 -v 0.013261 -0.148000 0.240927 -vn 0.724383 -0.685696 -0.071345 -v 0.039000 -0.148000 0.079018 -vn 0.689402 -0.665719 -0.285559 -v 0.038239 -0.148000 0.075192 -vn 0.724277 -0.685873 0.070725 -v 0.039000 -0.148000 0.237900 -vn 0.690081 -0.666046 0.283145 -v 0.038252 -0.148000 0.241696 -vn 0.530949 0.666046 0.523905 -v 0.036118 -0.146000 0.244924 -vn 0.690081 0.666046 0.283145 -v 0.038252 -0.146000 0.241696 -vn 0.724277 0.685872 0.070725 -v 0.039000 -0.146000 0.237900 -vn 0.000000 1.000000 0.000000 -v 0.035250 -0.146000 0.197900 -vn -0.707107 0.707107 -0.000000 -v 0.012500 -0.146000 0.197900 -vn -0.724383 0.685696 0.071346 -v 0.012500 -0.146000 0.237100 -vn -0.689401 0.665719 0.285560 -v 0.013261 -0.146000 0.240927 -vn -0.527645 0.665719 0.527645 -v 0.015429 -0.146000 0.244171 -vn 0.224511 0.646480 0.729149 -v 0.032919 -0.146000 0.247100 -vn -0.071345 0.685697 0.724382 -v 0.022500 -0.146000 0.247100 -vn -0.285559 0.665719 0.689402 -v 0.018673 -0.146000 0.246339 -vn -0.318863 0.770262 -0.552288 -v 0.030250 -0.146000 0.158065 -vn 0.000000 0.770261 -0.637729 -v 0.029000 -0.146000 0.158400 -vn 0.318864 0.770262 -0.552288 -v 0.027750 -0.146000 0.158065 -vn -0.681474 0.728984 0.064618 -v 0.012500 -0.146000 0.166660 -vn 0.552289 0.770261 -0.318864 -v 0.026835 -0.146000 0.157150 -vn -0.612635 0.751960 0.243384 -v 0.011793 -0.146000 0.162968 -vn -0.692294 0.667148 0.275031 -v -0.016793 -0.146000 0.143621 -vn -0.541839 0.667148 0.511199 -v -0.014774 -0.146000 0.146792 -vn -0.723916 0.686464 0.068643 -v -0.017500 -0.146000 0.139929 -vn -0.368152 0.686464 0.627081 -v -0.011726 -0.146000 0.148992 -vn -0.707107 0.707107 -0.000000 -v -0.017500 -0.146000 0.130850 -vn -0.346567 0.728984 0.590316 -v 0.006726 -0.146000 0.157597 -vn -0.318863 0.770262 0.552288 -v 0.030250 -0.146000 0.153735 -vn -0.552289 0.770261 0.318864 -v 0.031165 -0.146000 0.154650 -vn 0.000000 1.000000 0.000000 -v 0.035250 -0.146000 0.130850 -vn -0.637727 0.770262 -0.000000 -v 0.031500 -0.146000 0.155900 -vn -0.552289 0.770261 -0.318864 -v 0.031165 -0.146000 0.157150 -vn -0.479491 0.751960 0.452376 -v 0.009774 -0.146000 0.159798 -vn 0.637727 0.770262 0.000000 -v 0.026500 -0.146000 0.155900 -vn 0.552289 0.770261 0.318864 -v 0.026835 -0.146000 0.154650 -vn 0.318864 0.770262 0.552288 -v 0.027750 -0.146000 0.153735 -vn 0.000000 0.770261 0.637729 -v 0.029000 -0.146000 0.153400 -vn -0.552289 0.770261 -0.318865 -v 0.031165 -0.146000 0.107050 -vn -0.637727 0.770262 -0.000001 -v 0.031500 -0.146000 0.105800 -vn 0.527645 0.665718 -0.527645 -v 0.036071 -0.146000 0.071947 -vn -0.301512 0.904534 0.301511 -v -0.017500 -0.146000 0.080800 -vn 0.552289 0.770262 -0.318863 -v 0.026835 -0.146000 0.107050 -vn 0.637728 0.770262 -0.000000 -v 0.026500 -0.146000 0.105800 -vn 0.552288 0.770262 0.318864 -v 0.026835 -0.146000 0.104550 -vn 0.038914 0.719948 -0.692936 -v 0.000740 -0.146000 0.069018 -vn 0.318865 0.770261 0.552289 -v 0.027750 -0.146000 0.103635 -vn 0.071346 0.685696 -0.724383 -v 0.029000 -0.146000 0.069018 -vn 0.000000 0.770263 0.637727 -v 0.029000 -0.146000 0.103300 -vn 0.285560 0.665719 -0.689401 -v 0.032827 -0.146000 0.069780 -vn -0.318864 0.770261 0.552289 -v 0.030250 -0.146000 0.103635 -vn -0.552288 0.770262 0.318865 -v 0.031165 -0.146000 0.104550 -vn -0.318863 0.770262 -0.552288 -v 0.030250 -0.146000 0.107965 -vn 0.000000 0.770261 -0.637729 -v 0.029000 -0.146000 0.108300 -vn 0.318864 0.770262 -0.552288 -v 0.027750 -0.146000 0.107965 -vn 0.552288 0.770262 0.318865 -v -0.082165 -0.146000 0.104550 -vn -0.707106 0.707108 -0.000000 -v -0.090000 -0.146000 0.060000 -vn 0.637727 0.770263 -0.000000 -v -0.082500 -0.146000 0.105800 -vn -0.707107 0.707106 -0.000000 -v -0.090000 -0.146000 0.130850 -vn 0.552290 0.770261 -0.318864 -v -0.082165 -0.146000 0.107050 -vn 0.318865 0.770262 0.552288 -v -0.081250 -0.146000 0.103635 -vn -0.000000 0.770263 0.637727 -v -0.080000 -0.146000 0.103300 -vn 0.301511 0.904534 0.301511 -v -0.033500 -0.146000 0.080800 -vn -0.318865 0.770261 0.552288 -v -0.078750 -0.146000 0.103635 -vn -0.552290 0.770261 -0.318864 -v -0.077835 -0.146000 0.107050 -vn 0.707107 0.707107 0.000000 -v -0.033500 -0.146000 0.130850 -vn -0.637727 0.770263 -0.000000 -v -0.077500 -0.146000 0.105800 -vn -0.552288 0.770262 0.318865 -v -0.077835 -0.146000 0.104550 -vn -0.318864 0.770263 -0.552287 -v -0.078750 -0.146000 0.107965 -vn -0.000000 0.770261 -0.637729 -v -0.080000 -0.146000 0.108300 -vn 0.318863 0.770263 -0.552287 -v -0.081250 -0.146000 0.107965 -vn 0.318863 0.770263 0.552287 -v -0.081250 -0.146000 0.153735 -vn -0.000000 0.770261 0.637729 -v -0.080000 -0.146000 0.153400 -vn 0.541839 0.667148 0.511198 -v -0.036226 -0.146000 0.146792 -vn 0.692294 0.667148 0.275031 -v -0.034207 -0.146000 0.143621 -vn 0.368152 0.686464 0.627081 -v -0.039274 -0.146000 0.148992 -vn 0.723916 0.686465 0.068643 -v -0.033500 -0.146000 0.139929 -vn 0.346567 0.728984 0.590316 -v -0.057726 -0.146000 0.157597 -vn 0.479491 0.751960 0.452377 -v -0.060774 -0.146000 0.159798 -vn -0.637727 0.770263 -0.000000 -v -0.077500 -0.146000 0.155900 -vn 0.612634 0.751960 0.243384 -v -0.062793 -0.146000 0.162968 -vn -0.552290 0.770261 -0.318864 -v -0.077835 -0.146000 0.157150 -vn 0.681474 0.728984 0.064618 -v -0.063500 -0.146000 0.166660 -vn 0.707107 0.707107 0.000000 -v -0.063500 -0.146000 0.197900 -vn -0.318864 0.770263 -0.552287 -v -0.078750 -0.146000 0.158065 -vn -0.707108 0.707106 0.000000 -v -0.090000 -0.146000 0.197900 -vn -0.000000 0.770261 -0.637729 -v -0.080000 -0.146000 0.158400 -vn 0.318863 0.770263 -0.552287 -v -0.081250 -0.146000 0.158065 -vn 0.552290 0.770261 -0.318864 -v -0.082165 -0.146000 0.157150 -vn 0.637727 0.770263 0.000000 -v -0.082500 -0.146000 0.155900 -vn 0.552290 0.770261 0.318864 -v -0.082165 -0.146000 0.154650 -vn -0.552290 0.770261 0.318864 -v -0.077835 -0.146000 0.154650 -vn -0.318864 0.770263 0.552287 -v -0.078750 -0.146000 0.153735 -vn -0.552290 0.770261 -0.318864 -v -0.077835 -0.146000 0.241150 -vn -0.318868 0.770261 -0.552287 -v -0.078750 -0.146000 0.242065 -vn 0.071345 0.685697 0.724382 -v -0.073500 -0.146000 0.247100 -vn -0.224511 0.646480 0.729149 -v -0.083919 -0.146000 0.247100 -vn -0.000000 0.770264 -0.637725 -v -0.080000 -0.146000 0.242400 -vn 0.318867 0.770261 -0.552287 -v -0.081250 -0.146000 0.242065 -vn -0.530949 0.666046 0.523905 -v -0.087118 -0.146000 0.244924 -vn 0.552290 0.770261 -0.318864 -v -0.082165 -0.146000 0.241150 -vn -0.690081 0.666046 0.283144 -v -0.089252 -0.146000 0.241696 -vn 0.637727 0.770263 0.000000 -v -0.082500 -0.146000 0.239900 -vn -0.724277 0.685872 0.070725 -v -0.090000 -0.146000 0.237900 -vn 0.552290 0.770261 0.318864 -v -0.082165 -0.146000 0.238650 -vn 0.285559 0.665718 0.689402 -v -0.069673 -0.146000 0.246339 -vn 0.527645 0.665719 0.527645 -v -0.066429 -0.146000 0.244171 -vn -0.637727 0.770263 -0.000000 -v -0.077500 -0.146000 0.239900 -vn 0.689401 0.665719 0.285560 -v -0.064261 -0.146000 0.240927 -vn -0.552290 0.770261 0.318864 -v -0.077835 -0.146000 0.238650 -vn 0.724383 0.685696 0.071346 -v -0.063500 -0.146000 0.237100 -vn -0.318864 0.770263 0.552287 -v -0.078750 -0.146000 0.237735 -vn -0.000000 0.770261 0.637729 -v -0.080000 -0.146000 0.237400 -vn 0.318863 0.770263 0.552287 -v -0.081250 -0.146000 0.237735 -vn -0.000000 0.770261 -0.637729 -v -0.080000 -0.146000 0.016700 -vn 0.318863 0.770263 -0.552288 -v -0.081250 -0.146000 0.016365 -vn -0.724277 0.685873 -0.070725 -v -0.090000 -0.146000 0.014200 -vn 0.552289 0.770261 -0.318865 -v -0.082165 -0.146000 0.015450 -vn 0.637727 0.770263 0.000000 -v -0.082500 -0.146000 0.014200 -vn -0.690102 0.672634 -0.267064 -v -0.089252 -0.146000 0.010404 -vn 0.552290 0.770261 0.318864 -v -0.082165 -0.146000 0.012950 -vn -0.512074 0.675568 -0.530460 -v -0.087118 -0.146000 0.007176 -vn 0.318864 0.770263 0.552287 -v -0.081250 -0.146000 0.012035 -vn -0.000000 0.770261 0.637729 -v -0.080000 -0.146000 0.011700 -vn -0.318864 0.770263 0.552287 -v -0.078750 -0.146000 0.012035 -vn 0.527645 0.665720 -0.527644 -v -0.046189 -0.146000 0.007929 -vn -0.552290 0.770261 0.318864 -v -0.077835 -0.146000 0.012950 -vn 0.689401 0.665719 -0.285560 -v -0.044021 -0.146000 0.011173 -vn -0.637727 0.770263 -0.000000 -v -0.077500 -0.146000 0.014200 -vn -0.552289 0.770261 -0.318864 -v -0.077835 -0.146000 0.015450 -vn 0.692936 0.719948 -0.038914 -v -0.043260 -0.146000 0.025018 -vn 0.724383 0.685696 -0.071345 -v -0.043260 -0.146000 0.015000 -vn -0.318864 0.770263 -0.552287 -v -0.078750 -0.146000 0.016365 -vn 0.458227 0.721401 -0.519238 -v -0.026694 -0.146000 0.059419 -vn 0.428333 0.708922 -0.560322 -v -0.025827 -0.146000 0.060093 -vn 0.389717 0.718500 -0.576090 -v -0.025572 -0.146000 0.060284 -vn 0.000000 0.707107 0.707107 -v -0.025500 -0.146000 0.080800 -vn 0.290991 0.731273 -0.616898 -v -0.018351 -0.146000 0.064661 -vn 0.151318 0.733198 -0.662966 -v -0.009051 -0.146000 0.067915 -vn 0.531657 0.733198 -0.423983 -v -0.033661 -0.146000 0.052452 -vn 0.612673 0.733198 -0.295048 -v -0.038903 -0.146000 0.044109 -vn 0.662966 0.733198 -0.151318 -v -0.042157 -0.146000 0.034809 -vn 0.285560 0.665719 -0.689401 -v -0.049433 -0.146000 0.005761 -vn 0.071345 0.685696 -0.724383 -v -0.053260 -0.146000 0.005000 -vn -0.224512 0.646480 -0.729149 -v -0.083919 -0.146000 0.005000 -vn 0.707107 0.707107 0.000000 -v 0.039000 -0.146000 0.197900 -vn 0.707107 0.707107 0.000000 -v 0.039000 -0.146000 0.130850 -vn 0.724383 0.685696 -0.071345 -v 0.039000 -0.146000 0.079018 -vn 0.689402 0.665719 -0.285559 -v 0.038239 -0.146000 0.075192 -vn 0.000000 -1.000000 0.000000 -v 0.035250 0.146000 0.130850 -vn 0.707107 -0.707107 0.000000 -v 0.039000 0.146000 0.130850 -vn 0.707107 -0.707107 0.000000 -v 0.039000 0.146000 0.197900 -vn 0.071345 -0.685696 -0.724383 -v -0.053260 0.146000 0.005000 -vn 0.285560 -0.665719 -0.689401 -v -0.049433 0.146000 0.005761 -vn 0.527644 -0.665720 -0.527644 -v -0.046189 0.146000 0.007929 -vn -0.552289 -0.770262 -0.318864 -v 0.031165 0.146000 0.107050 -vn -0.637728 -0.770262 -0.000001 -v 0.031500 0.146000 0.105800 -vn 0.527645 -0.665718 -0.527645 -v 0.036071 0.146000 0.071947 -vn -0.552288 -0.770262 0.318864 -v 0.031165 0.146000 0.104550 -vn -0.318864 -0.770261 0.552289 -v 0.030250 0.146000 0.103635 -vn 0.285560 -0.665719 -0.689401 -v 0.032827 0.146000 0.069780 -vn 0.000000 -0.770263 0.637727 -v 0.029000 0.146000 0.103300 -vn 0.071346 -0.685696 -0.724383 -v 0.029000 0.146000 0.069018 -vn 0.038914 -0.719948 -0.692936 -v 0.000740 0.146000 0.069018 -vn 0.000000 -0.707107 0.707107 -v -0.025500 0.146000 0.080800 -vn 0.290991 -0.731273 -0.616898 -v -0.018351 0.146000 0.064661 -vn -0.301512 -0.904534 0.301511 -v -0.017500 0.146000 0.080800 -vn 0.151318 -0.733198 -0.662966 -v -0.009051 0.146000 0.067915 -vn 0.552289 -0.770262 -0.318863 -v 0.026835 0.146000 0.107050 -vn -0.707107 -0.707106 -0.000000 -v -0.017500 0.146000 0.130850 -vn 0.637728 -0.770262 -0.000000 -v 0.026500 0.146000 0.105800 -vn 0.552288 -0.770262 0.318864 -v 0.026835 0.146000 0.104550 -vn 0.318865 -0.770261 0.552289 -v 0.027750 0.146000 0.103635 -vn 0.318864 -0.770262 -0.552288 -v 0.027750 0.146000 0.107965 -vn 0.000000 -0.770261 -0.637729 -v 0.029000 0.146000 0.108300 -vn -0.318863 -0.770262 -0.552288 -v 0.030250 0.146000 0.107965 -vn -0.318865 -0.770261 0.552288 -v -0.078750 0.146000 0.103635 -vn -0.000000 -0.770263 0.637727 -v -0.080000 0.146000 0.103300 -vn -0.707105 -0.707108 -0.000000 -v -0.090000 0.146000 0.060000 -vn 0.318865 -0.770262 0.552288 -v -0.081250 0.146000 0.103635 -vn -0.637727 -0.770263 -0.000000 -v -0.077500 0.146000 0.105800 -vn 0.301511 -0.904534 0.301511 -v -0.033500 0.146000 0.080800 -vn -0.552290 -0.770261 -0.318864 -v -0.077835 0.146000 0.107050 -vn 0.707106 -0.707107 0.000000 -v -0.033500 0.146000 0.130850 -vn 0.428333 -0.708922 -0.560322 -v -0.025827 0.146000 0.060093 -vn 0.389717 -0.718500 -0.576090 -v -0.025572 0.146000 0.060284 -vn 0.552288 -0.770262 0.318865 -v -0.082165 0.146000 0.104550 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 0.146000 0.105800 -vn -0.707107 -0.707106 -0.000000 -v -0.090000 0.146000 0.130850 -vn 0.552290 -0.770261 -0.318864 -v -0.082165 0.146000 0.107050 -vn 0.318864 -0.770263 -0.552287 -v -0.081250 0.146000 0.107965 -vn -0.000000 -0.770261 -0.637729 -v -0.080000 0.146000 0.108300 -vn -0.318864 -0.770263 -0.552287 -v -0.078750 0.146000 0.107965 -vn 0.318863 -0.770263 0.552287 -v -0.081250 0.146000 0.012035 -vn 0.552290 -0.770261 0.318864 -v -0.082165 0.146000 0.012950 -vn -0.609915 -0.670164 -0.422947 -v -0.088040 0.146000 0.008254 -vn -0.318864 -0.770263 0.552287 -v -0.078750 0.146000 0.012035 -vn -0.000000 -0.770261 0.637729 -v -0.080000 0.146000 0.011700 -vn -0.552290 -0.770261 0.318864 -v -0.077835 0.146000 0.012950 -vn 0.689401 -0.665719 -0.285560 -v -0.044021 0.146000 0.011173 -vn -0.637727 -0.770263 0.000000 -v -0.077500 0.146000 0.014200 -vn 0.724382 -0.685697 -0.071345 -v -0.043260 0.146000 0.015000 -vn -0.552289 -0.770261 -0.318864 -v -0.077835 0.146000 0.015450 -vn -0.000000 -0.770261 -0.637729 -v -0.080000 0.146000 0.016700 -vn -0.318864 -0.770263 -0.552287 -v -0.078750 0.146000 0.016365 -vn -0.693720 -0.673104 -0.256288 -v -0.089252 0.146000 0.010404 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 0.146000 0.014200 -vn -0.724277 -0.685873 -0.070725 -v -0.090000 0.146000 0.014200 -vn 0.552289 -0.770261 -0.318865 -v -0.082165 0.146000 0.015450 -vn 0.318863 -0.770263 -0.552288 -v -0.081250 0.146000 0.016365 -vn -0.552288 -0.770262 0.318865 -v -0.077835 0.146000 0.104550 -vn 0.458227 -0.721401 -0.519239 -v -0.026694 0.146000 0.059419 -vn 0.531657 -0.733198 -0.423983 -v -0.033661 0.146000 0.052452 -vn 0.692937 -0.719948 -0.038914 -v -0.043260 0.146000 0.025018 -vn 0.662966 -0.733198 -0.151318 -v -0.042157 0.146000 0.034809 -vn 0.612673 -0.733198 -0.295047 -v -0.038903 0.146000 0.044109 -vn -0.224512 -0.646480 -0.729149 -v -0.083919 0.146000 0.005000 -vn -0.490010 -0.678480 -0.547316 -v -0.087118 0.146000 0.007176 -vn -0.637727 -0.770263 0.000000 -v -0.077500 0.146000 0.239900 -vn -0.552290 -0.770261 0.318864 -v -0.077835 0.146000 0.238650 -vn 0.724383 -0.685696 0.071346 -v -0.063500 0.146000 0.237100 -vn 0.707107 -0.707107 0.000000 -v -0.063500 0.146000 0.197900 -vn -0.318864 -0.770263 0.552287 -v -0.078750 0.146000 0.237735 -vn -0.707107 -0.707106 0.000000 -v -0.090000 0.146000 0.197900 -vn -0.000000 -0.770261 0.637729 -v -0.080000 0.146000 0.237400 -vn 0.318863 -0.770263 0.552287 -v -0.081250 0.146000 0.237735 -vn -0.724277 -0.685873 0.070725 -v -0.090000 0.146000 0.237900 -vn 0.552290 -0.770261 0.318864 -v -0.082165 0.146000 0.238650 -vn -0.690081 -0.666047 0.283144 -v -0.089252 0.146000 0.241696 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 0.146000 0.239900 -vn -0.530949 -0.666046 0.523905 -v -0.087118 0.146000 0.244924 -vn 0.552290 -0.770261 -0.318864 -v -0.082165 0.146000 0.241150 -vn -0.224511 -0.646480 0.729149 -v -0.083919 0.146000 0.247100 -vn 0.689401 -0.665719 0.285560 -v -0.064261 0.146000 0.240927 -vn 0.527645 -0.665719 0.527645 -v -0.066429 0.146000 0.244171 -vn -0.552290 -0.770261 -0.318864 -v -0.077835 0.146000 0.241150 -vn 0.285559 -0.665719 0.689402 -v -0.069673 0.146000 0.246339 -vn -0.318868 -0.770261 -0.552287 -v -0.078750 0.146000 0.242065 -vn 0.071345 -0.685697 0.724383 -v -0.073500 0.146000 0.247100 -vn -0.000000 -0.770264 -0.637725 -v -0.080000 0.146000 0.242400 -vn 0.318867 -0.770261 -0.552287 -v -0.081250 0.146000 0.242065 -vn 0.692294 -0.667148 0.275031 -v -0.034207 0.146000 0.143621 -vn 0.541839 -0.667148 0.511199 -v -0.036226 0.146000 0.146792 -vn 0.723916 -0.686464 0.068643 -v -0.033500 0.146000 0.139929 -vn 0.368152 -0.686464 0.627081 -v -0.039274 0.146000 0.148992 -vn 0.346567 -0.728984 0.590316 -v -0.057726 0.146000 0.157597 -vn -0.000000 -0.770261 0.637729 -v -0.080000 0.146000 0.153400 -vn 0.318863 -0.770263 0.552287 -v -0.081250 0.146000 0.153735 -vn -0.318864 -0.770263 0.552287 -v -0.078750 0.146000 0.153735 -vn -0.552289 -0.770261 0.318864 -v -0.077835 0.146000 0.154650 -vn 0.552290 -0.770261 -0.318864 -v -0.082165 0.146000 0.157150 -vn 0.637727 -0.770263 -0.000000 -v -0.082500 0.146000 0.155900 -vn 0.552290 -0.770261 0.318864 -v -0.082165 0.146000 0.154650 -vn 0.318863 -0.770263 -0.552287 -v -0.081250 0.146000 0.158065 -vn -0.000000 -0.770261 -0.637729 -v -0.080000 0.146000 0.158400 -vn -0.318864 -0.770263 -0.552287 -v -0.078750 0.146000 0.158065 -vn 0.681474 -0.728984 0.064618 -v -0.063500 0.146000 0.166660 -vn -0.552290 -0.770261 -0.318864 -v -0.077835 0.146000 0.157150 -vn -0.637727 -0.770263 0.000000 -v -0.077500 0.146000 0.155900 -vn 0.479491 -0.751960 0.452377 -v -0.060774 0.146000 0.159798 -vn 0.612634 -0.751960 0.243384 -v -0.062793 0.146000 0.162968 -vn -0.637728 -0.770262 0.000000 -v 0.031500 0.146000 0.155900 -vn -0.552289 -0.770262 0.318863 -v 0.031165 0.146000 0.154650 -vn -0.318863 -0.770262 0.552288 -v 0.030250 0.146000 0.153735 -vn 0.000000 -0.770261 0.637729 -v 0.029000 0.146000 0.153400 -vn 0.318864 -0.770262 -0.552288 -v 0.027750 0.146000 0.158065 -vn 0.000000 -0.770261 -0.637729 -v 0.029000 0.146000 0.158400 -vn 0.000000 -1.000000 0.000000 -v 0.035250 0.146000 0.197900 -vn -0.318863 -0.770262 -0.552288 -v 0.030250 0.146000 0.158065 -vn -0.552289 -0.770262 -0.318863 -v 0.031165 0.146000 0.157150 -vn 0.318864 -0.770262 0.552288 -v 0.027750 0.146000 0.153735 -vn 0.552289 -0.770262 0.318864 -v 0.026835 0.146000 0.154650 -vn 0.637727 -0.770262 -0.000000 -v 0.026500 0.146000 0.155900 -vn -0.368152 -0.686464 0.627081 -v -0.011726 0.146000 0.148992 -vn -0.541839 -0.667148 0.511198 -v -0.014774 0.146000 0.146792 -vn -0.692294 -0.667148 0.275031 -v -0.016793 0.146000 0.143621 -vn -0.707107 -0.707107 -0.000000 -v 0.012500 0.146000 0.197900 -vn -0.681474 -0.728984 0.064618 -v 0.012500 0.146000 0.166660 -vn 0.552289 -0.770261 -0.318864 -v 0.026835 0.146000 0.157150 -vn -0.612634 -0.751960 0.243384 -v 0.011793 0.146000 0.162968 -vn -0.723916 -0.686464 0.068643 -v -0.017500 0.146000 0.139929 -vn -0.346567 -0.728984 0.590316 -v 0.006726 0.146000 0.157597 -vn -0.479491 -0.751960 0.452377 -v 0.009774 0.146000 0.159798 -vn 0.530949 -0.666046 0.523905 -v 0.036118 0.146000 0.244924 -vn 0.224511 -0.646480 0.729149 -v 0.032919 0.146000 0.247100 -vn -0.071345 -0.685697 0.724382 -v 0.022500 0.146000 0.247100 -vn -0.285559 -0.665719 0.689402 -v 0.018673 0.146000 0.246339 -vn -0.527645 -0.665719 0.527645 -v 0.015429 0.146000 0.244171 -vn -0.724383 -0.685696 0.071346 -v 0.012500 0.146000 0.237100 -vn -0.689401 -0.665719 0.285560 -v 0.013261 0.146000 0.240927 -vn 0.724383 -0.685696 -0.071345 -v 0.039000 0.146000 0.079018 -vn 0.689402 -0.665719 -0.285559 -v 0.038239 0.146000 0.075192 -vn 0.724277 -0.685873 0.070725 -v 0.039000 0.146000 0.237900 -vn 0.690081 -0.666046 0.283145 -v 0.038252 0.146000 0.241696 -vn 0.530949 0.666046 0.523905 -v 0.036118 0.148000 0.244924 -vn 0.690081 0.666046 0.283145 -v 0.038252 0.148000 0.241696 -vn 0.724277 0.685872 0.070725 -v 0.039000 0.148000 0.237900 -vn 0.000000 1.000000 0.000000 -v 0.035250 0.148000 0.197900 -vn -0.707107 0.707107 -0.000000 -v 0.012500 0.148000 0.197900 -vn -0.724383 0.685696 0.071346 -v 0.012500 0.148000 0.237100 -vn -0.689401 0.665719 0.285560 -v 0.013261 0.148000 0.240927 -vn -0.527645 0.665719 0.527645 -v 0.015429 0.148000 0.244171 -vn 0.224511 0.646480 0.729149 -v 0.032919 0.148000 0.247100 -vn -0.071345 0.685697 0.724382 -v 0.022500 0.148000 0.247100 -vn -0.285559 0.665719 0.689402 -v 0.018673 0.148000 0.246339 -vn -0.318863 0.770262 -0.552288 -v 0.030250 0.148000 0.158065 -vn 0.000000 0.770261 -0.637729 -v 0.029000 0.148000 0.158400 -vn 0.318864 0.770262 -0.552288 -v 0.027750 0.148000 0.158065 -vn -0.681474 0.728984 0.064618 -v 0.012500 0.148000 0.166660 -vn 0.552289 0.770261 -0.318864 -v 0.026835 0.148000 0.157150 -vn -0.612635 0.751960 0.243384 -v 0.011793 0.148000 0.162968 -vn -0.692294 0.667148 0.275031 -v -0.016793 0.148000 0.143621 -vn -0.541839 0.667148 0.511198 -v -0.014774 0.148000 0.146792 -vn -0.723916 0.686464 0.068643 -v -0.017500 0.148000 0.139929 -vn -0.368152 0.686464 0.627081 -v -0.011726 0.148000 0.148992 -vn -0.707107 0.707107 -0.000000 -v -0.017500 0.148000 0.130850 -vn -0.346567 0.728984 0.590316 -v 0.006726 0.148000 0.157597 -vn -0.318863 0.770262 0.552288 -v 0.030250 0.148000 0.153735 -vn -0.552289 0.770262 0.318863 -v 0.031165 0.148000 0.154650 -vn 0.000000 1.000000 0.000000 -v 0.035250 0.148000 0.130850 -vn -0.637728 0.770262 0.000000 -v 0.031500 0.148000 0.155900 -vn -0.552289 0.770262 -0.318863 -v 0.031165 0.148000 0.157150 -vn -0.479491 0.751960 0.452376 -v 0.009774 0.148000 0.159798 -vn 0.637727 0.770262 0.000000 -v 0.026500 0.148000 0.155900 -vn 0.552289 0.770261 0.318864 -v 0.026835 0.148000 0.154650 -vn 0.318864 0.770262 0.552288 -v 0.027750 0.148000 0.153735 -vn 0.000000 0.770261 0.637729 -v 0.029000 0.148000 0.153400 -vn -0.552289 0.770261 -0.318864 -v 0.031165 0.148000 0.107050 -vn -0.637728 0.770262 -0.000001 -v 0.031500 0.148000 0.105800 -vn 0.527645 0.665719 -0.527645 -v 0.036071 0.148000 0.071947 -vn -0.301512 0.904534 0.301511 -v -0.017500 0.148000 0.080800 -vn 0.552289 0.770262 -0.318863 -v 0.026835 0.148000 0.107050 -vn 0.637728 0.770262 -0.000000 -v 0.026500 0.148000 0.105800 -vn 0.552288 0.770262 0.318864 -v 0.026835 0.148000 0.104550 -vn 0.038914 0.719948 -0.692936 -v 0.000740 0.148000 0.069018 -vn 0.318865 0.770261 0.552289 -v 0.027750 0.148000 0.103635 -vn 0.071346 0.685696 -0.724383 -v 0.029000 0.148000 0.069018 -vn 0.000000 0.770263 0.637727 -v 0.029000 0.148000 0.103300 -vn 0.285560 0.665719 -0.689401 -v 0.032827 0.148000 0.069780 -vn -0.318864 0.770261 0.552289 -v 0.030250 0.148000 0.103635 -vn -0.552288 0.770262 0.318864 -v 0.031165 0.148000 0.104550 -vn -0.318863 0.770262 -0.552288 -v 0.030250 0.148000 0.107965 -vn 0.000000 0.770261 -0.637729 -v 0.029000 0.148000 0.108300 -vn 0.318864 0.770262 -0.552288 -v 0.027750 0.148000 0.107965 -vn 0.552288 0.770262 0.318865 -v -0.082165 0.148000 0.104550 -vn -0.707106 0.707108 -0.000000 -v -0.090000 0.148000 0.060000 -vn 0.637727 0.770263 -0.000000 -v -0.082500 0.148000 0.105800 -vn -0.707107 0.707106 -0.000000 -v -0.090000 0.148000 0.130850 -vn 0.552290 0.770261 -0.318864 -v -0.082165 0.148000 0.107050 -vn 0.318865 0.770262 0.552288 -v -0.081250 0.148000 0.103635 -vn -0.000000 0.770263 0.637727 -v -0.080000 0.148000 0.103300 -vn 0.301511 0.904534 0.301511 -v -0.033500 0.148000 0.080800 -vn -0.318865 0.770261 0.552288 -v -0.078750 0.148000 0.103635 -vn -0.552290 0.770261 -0.318864 -v -0.077835 0.148000 0.107050 -vn 0.707107 0.707107 0.000000 -v -0.033500 0.148000 0.130850 -vn -0.637727 0.770263 -0.000000 -v -0.077500 0.148000 0.105800 -vn -0.552288 0.770262 0.318865 -v -0.077835 0.148000 0.104550 -vn -0.318864 0.770263 -0.552287 -v -0.078750 0.148000 0.107965 -vn -0.000000 0.770261 -0.637729 -v -0.080000 0.148000 0.108300 -vn 0.318863 0.770263 -0.552287 -v -0.081250 0.148000 0.107965 -vn 0.318863 0.770263 0.552287 -v -0.081250 0.148000 0.153735 -vn -0.000000 0.770261 0.637729 -v -0.080000 0.148000 0.153400 -vn 0.541839 0.667148 0.511198 -v -0.036226 0.148000 0.146792 -vn 0.692294 0.667148 0.275031 -v -0.034207 0.148000 0.143621 -vn 0.368152 0.686464 0.627081 -v -0.039274 0.148000 0.148992 -vn 0.723916 0.686465 0.068643 -v -0.033500 0.148000 0.139929 -vn 0.346567 0.728984 0.590316 -v -0.057726 0.148000 0.157597 -vn 0.479491 0.751960 0.452377 -v -0.060774 0.148000 0.159798 -vn -0.637727 0.770263 -0.000000 -v -0.077500 0.148000 0.155900 -vn 0.612634 0.751960 0.243384 -v -0.062793 0.148000 0.162968 -vn -0.552290 0.770261 -0.318864 -v -0.077835 0.148000 0.157150 -vn 0.681474 0.728984 0.064618 -v -0.063500 0.148000 0.166660 -vn 0.707107 0.707107 0.000000 -v -0.063500 0.148000 0.197900 -vn -0.318864 0.770263 -0.552287 -v -0.078750 0.148000 0.158065 -vn -0.707108 0.707106 0.000000 -v -0.090000 0.148000 0.197900 -vn -0.000000 0.770261 -0.637729 -v -0.080000 0.148000 0.158400 -vn 0.318863 0.770263 -0.552287 -v -0.081250 0.148000 0.158065 -vn 0.552290 0.770261 -0.318864 -v -0.082165 0.148000 0.157150 -vn 0.637727 0.770263 0.000000 -v -0.082500 0.148000 0.155900 -vn 0.552290 0.770261 0.318864 -v -0.082165 0.148000 0.154650 -vn -0.552290 0.770261 0.318864 -v -0.077835 0.148000 0.154650 -vn -0.318864 0.770263 0.552287 -v -0.078750 0.148000 0.153735 -vn -0.552290 0.770261 -0.318864 -v -0.077835 0.148000 0.241150 -vn -0.318868 0.770261 -0.552287 -v -0.078750 0.148000 0.242065 -vn 0.071345 0.685697 0.724382 -v -0.073500 0.148000 0.247100 -vn -0.224511 0.646480 0.729149 -v -0.083919 0.148000 0.247100 -vn -0.000000 0.770264 -0.637725 -v -0.080000 0.148000 0.242400 -vn 0.318867 0.770261 -0.552287 -v -0.081250 0.148000 0.242065 -vn -0.530949 0.666046 0.523905 -v -0.087118 0.148000 0.244924 -vn 0.552290 0.770261 -0.318864 -v -0.082165 0.148000 0.241150 -vn -0.690081 0.666046 0.283144 -v -0.089252 0.148000 0.241696 -vn 0.637727 0.770263 0.000000 -v -0.082500 0.148000 0.239900 -vn -0.724277 0.685872 0.070725 -v -0.090000 0.148000 0.237900 -vn 0.552290 0.770261 0.318864 -v -0.082165 0.148000 0.238650 -vn 0.285559 0.665718 0.689402 -v -0.069673 0.148000 0.246339 -vn 0.527645 0.665719 0.527645 -v -0.066429 0.148000 0.244171 -vn -0.637727 0.770263 -0.000000 -v -0.077500 0.148000 0.239900 -vn 0.689401 0.665719 0.285560 -v -0.064261 0.148000 0.240927 -vn -0.552290 0.770261 0.318864 -v -0.077835 0.148000 0.238650 -vn 0.724383 0.685696 0.071346 -v -0.063500 0.148000 0.237100 -vn -0.318864 0.770263 0.552287 -v -0.078750 0.148000 0.237735 -vn -0.000000 0.770261 0.637729 -v -0.080000 0.148000 0.237400 -vn 0.318863 0.770263 0.552287 -v -0.081250 0.148000 0.237735 -vn -0.000000 0.770261 -0.637729 -v -0.080000 0.148000 0.016700 -vn 0.318863 0.770263 -0.552288 -v -0.081250 0.148000 0.016365 -vn -0.724277 0.685873 -0.070725 -v -0.090000 0.148000 0.014200 -vn 0.552289 0.770261 -0.318865 -v -0.082165 0.148000 0.015450 -vn 0.637727 0.770263 0.000000 -v -0.082500 0.148000 0.014200 -vn -0.690102 0.672634 -0.267064 -v -0.089252 0.148000 0.010404 -vn 0.552290 0.770261 0.318864 -v -0.082165 0.148000 0.012950 -vn -0.512074 0.675568 -0.530460 -v -0.087118 0.148000 0.007176 -vn 0.318864 0.770263 0.552287 -v -0.081250 0.148000 0.012035 -vn -0.000000 0.770261 0.637729 -v -0.080000 0.148000 0.011700 -vn -0.318864 0.770263 0.552287 -v -0.078750 0.148000 0.012035 -vn 0.527645 0.665720 -0.527644 -v -0.046189 0.148000 0.007929 -vn -0.552290 0.770261 0.318864 -v -0.077835 0.148000 0.012950 -vn 0.689401 0.665719 -0.285560 -v -0.044021 0.148000 0.011173 -vn -0.637727 0.770263 -0.000000 -v -0.077500 0.148000 0.014200 -vn -0.552289 0.770261 -0.318864 -v -0.077835 0.148000 0.015450 -vn 0.692936 0.719948 -0.038914 -v -0.043260 0.148000 0.025018 -vn 0.724383 0.685696 -0.071345 -v -0.043260 0.148000 0.015000 -vn -0.318864 0.770263 -0.552287 -v -0.078750 0.148000 0.016365 -vn 0.458227 0.721401 -0.519239 -v -0.026694 0.148000 0.059419 -vn 0.428333 0.708922 -0.560322 -v -0.025827 0.148000 0.060093 -vn 0.389717 0.718500 -0.576090 -v -0.025572 0.148000 0.060284 -vn 0.000000 0.707107 0.707107 -v -0.025500 0.148000 0.080800 -vn 0.290991 0.731273 -0.616898 -v -0.018351 0.148000 0.064661 -vn 0.151318 0.733198 -0.662966 -v -0.009051 0.148000 0.067915 -vn 0.531657 0.733198 -0.423983 -v -0.033661 0.148000 0.052452 -vn 0.612673 0.733198 -0.295048 -v -0.038903 0.148000 0.044109 -vn 0.662966 0.733198 -0.151318 -v -0.042157 0.148000 0.034809 -vn 0.285560 0.665719 -0.689401 -v -0.049433 0.148000 0.005761 -vn 0.071345 0.685696 -0.724383 -v -0.053260 0.148000 0.005000 -vn -0.224512 0.646480 -0.729149 -v -0.083919 0.148000 0.005000 -vn 0.707107 0.707107 0.000000 -v 0.039000 0.148000 0.197900 -vn 0.707107 0.707107 0.000000 -v 0.039000 0.148000 0.130850 -vn 0.724383 0.685696 -0.071345 -v 0.039000 0.148000 0.079018 -vn 0.689402 0.665719 -0.285559 -v 0.038239 0.148000 0.075192 -vn -0.577350 0.577350 0.577350 -v 0.011250 0.148000 0.299560 -vn -0.301511 0.904534 0.301512 -v 0.011250 0.148000 0.292060 -vn -0.577350 -0.577350 0.577350 -v 0.011250 0.146000 0.299560 -vn -0.301511 -0.904534 0.301511 -v 0.011250 0.146000 0.292060 -vn 0.577350 -0.577350 0.577350 -v -0.062750 0.146000 0.299560 -vn 0.301511 -0.904534 0.301512 -v -0.062750 0.146000 0.292060 -vn 0.577350 0.577350 0.577350 -v -0.062750 0.148000 0.299560 -vn 0.301511 0.904534 0.301511 -v -0.062750 0.148000 0.292060 -vn 0.084917 -0.681886 -0.726512 -v -0.074446 0.146000 0.247100 -vn -0.071346 -0.685696 -0.724383 -v -0.085250 0.146000 0.247100 -vn 0.084917 0.681886 -0.726512 -v -0.074446 0.148000 0.247100 -vn -0.071346 0.685696 -0.724383 -v -0.085250 0.148000 0.247100 -vn -0.724383 -0.685697 -0.071345 -v -0.090250 0.146000 0.252100 -vn -0.724383 0.685696 -0.071345 -v -0.090250 0.148000 0.252100 -vn -0.689401 0.665719 -0.285560 -v -0.089869 0.148000 0.250187 -vn -0.689401 -0.665719 -0.285560 -v -0.089869 0.146000 0.250187 -vn -0.527645 0.665719 -0.527645 -v -0.088786 0.148000 0.248564 -vn -0.527645 -0.665719 -0.527645 -v -0.088786 0.146000 0.248564 -vn -0.285561 0.665719 -0.689401 -v -0.087163 0.148000 0.247481 -vn -0.285561 -0.665719 -0.689401 -v -0.087163 0.146000 0.247481 -vn -0.084917 0.681886 -0.726512 -v 0.022945 0.148000 0.247100 -vn 0.071346 0.685696 -0.724383 -v 0.033750 0.148000 0.247100 -vn -0.084917 -0.681886 -0.726512 -v 0.022945 0.146000 0.247100 -vn 0.071346 -0.685696 -0.724383 -v 0.033750 0.146000 0.247100 -vn 0.285560 0.665719 -0.689401 -v 0.035663 0.148000 0.247481 -vn 0.285560 -0.665719 -0.689401 -v 0.035663 0.146000 0.247481 -vn 0.527644 0.665719 -0.527645 -v 0.037286 0.148000 0.248564 -vn 0.527644 -0.665719 -0.527645 -v 0.037286 0.146000 0.248564 -vn 0.689401 0.665718 -0.285560 -v 0.038369 0.148000 0.250187 -vn 0.689401 -0.665718 -0.285560 -v 0.038369 0.146000 0.250187 -vn 0.724382 0.685697 -0.071345 -v 0.038750 0.148000 0.252100 -vn 0.724382 -0.685697 -0.071345 -v 0.038750 0.146000 0.252100 -vn 0.724382 0.685697 0.071344 -v 0.038750 0.148000 0.334600 -vn 0.724382 -0.685697 0.071344 -v 0.038750 0.146000 0.334600 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.148000 0.320930 -vn 0.707107 -0.707107 0.000000 -v 0.038750 0.146000 0.320930 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.148000 0.318160 -vn 0.707107 -0.707107 0.000000 -v 0.038750 0.146000 0.318160 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.148000 0.303580 -vn 0.707107 -0.707107 0.000000 -v 0.038750 0.146000 0.303580 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.148000 0.290960 -vn 0.707107 -0.707107 0.000000 -v 0.038750 0.146000 0.290960 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.148000 0.274480 -vn 0.707107 -0.707107 0.000000 -v 0.038750 0.146000 0.274480 -vn 0.689402 0.665718 0.285559 -v 0.038369 0.148000 0.336513 -vn 0.689402 -0.665718 0.285559 -v 0.038369 0.146000 0.336513 -vn 0.527643 0.665719 0.527647 -v 0.037286 0.148000 0.338136 -vn 0.527643 -0.665719 0.527647 -v 0.037286 0.146000 0.338136 -vn 0.285558 0.665720 0.689401 -v 0.035663 0.148000 0.339219 -vn 0.285558 -0.665720 0.689401 -v 0.035663 0.146000 0.339219 -vn 0.071346 0.685696 0.724383 -v 0.033750 0.148000 0.339600 -vn 0.071346 -0.685696 0.724383 -v 0.033750 0.146000 0.339600 -vn -0.071346 0.685696 0.724383 -v -0.085250 0.148000 0.339600 -vn -0.071346 -0.685696 0.724383 -v -0.085250 0.146000 0.339600 -vn 0.000000 0.707107 0.707107 -v -0.072250 0.148000 0.339600 -vn 0.000000 -0.707107 0.707107 -v -0.072250 0.146000 0.339600 -vn 0.000000 0.707107 0.707106 -v -0.025750 0.148000 0.339600 -vn 0.000000 -0.707107 0.707107 -v -0.025750 0.146000 0.339600 -vn 0.000000 0.707106 0.707107 -v 0.014125 0.148000 0.339600 -vn 0.000000 -0.707107 0.707107 -v 0.014125 0.146000 0.339600 -vn 0.000000 0.707107 0.707107 -v 0.020750 0.148000 0.339600 -vn 0.000000 -0.707107 0.707107 -v 0.020750 0.146000 0.339600 -vn -0.285558 0.665719 0.689401 -v -0.087163 0.148000 0.339219 -vn -0.285558 -0.665719 0.689401 -v -0.087163 0.146000 0.339219 -vn -0.527643 0.665719 0.527647 -v -0.088786 0.148000 0.338136 -vn -0.527643 -0.665719 0.527647 -v -0.088786 0.146000 0.338136 -vn -0.689402 0.665718 0.285559 -v -0.089869 0.148000 0.336513 -vn -0.689402 -0.665718 0.285559 -v -0.089869 0.146000 0.336513 -vn -0.724382 0.685697 0.071344 -v -0.090250 0.148000 0.334600 -vn -0.724382 -0.685697 0.071344 -v -0.090250 0.146000 0.334600 -vn -0.707107 0.707107 -0.000000 -v -0.090250 0.148000 0.274480 -vn -0.707107 -0.707107 -0.000000 -v -0.090250 0.146000 0.274480 -vn -0.707107 0.707107 0.000000 -v -0.090250 0.148000 0.290960 -vn -0.707107 -0.707107 0.000000 -v -0.090250 0.146000 0.290960 -vn -0.707107 0.707107 0.000000 -v -0.090250 0.148000 0.303580 -vn -0.707107 -0.707107 0.000000 -v -0.090250 0.146000 0.303580 -vn -0.707107 0.707107 0.000000 -v -0.090250 0.148000 0.318160 -vn -0.707107 -0.707107 0.000000 -v -0.090250 0.146000 0.318160 -vn -0.707107 0.707107 0.000000 -v -0.090250 0.148000 0.320930 -vn -0.707107 -0.707107 0.000000 -v -0.090250 0.146000 0.320930 -vn -0.552296 -0.770258 -0.318860 -v 0.012833 0.146000 0.289235 -vn -0.637728 -0.770261 -0.000004 -v 0.013000 0.146000 0.288610 -vn 0.000000 -1.000000 0.000000 -v 0.014125 0.146000 0.290960 -vn 0.637728 -0.770261 0.000004 -v -0.064500 0.146000 0.320510 -vn 0.552286 -0.770264 -0.318863 -v -0.064333 0.146000 0.321135 -vn 0.000000 -1.000000 0.000000 -v -0.072250 0.146000 0.320930 -vn -0.650416 -0.734195 -0.194722 -v 0.017715 0.146000 0.252968 -vn -0.700729 -0.681886 -0.209786 -v 0.018021 0.146000 0.251232 -vn 0.000000 -1.000000 0.000000 -v 0.020750 0.146000 0.251850 -vn -0.552292 -0.770260 0.318863 -v -0.078085 0.146000 0.316350 -vn 0.000000 -1.000000 0.000000 -v -0.072250 0.146000 0.303580 -vn -0.637727 -0.770263 0.000000 -v -0.077750 0.146000 0.317600 -vn 0.000000 -1.000000 0.000000 -v -0.072250 0.146000 0.318160 -vn -0.552287 -0.770262 -0.318866 -v -0.078085 0.146000 0.318850 -vn -0.318862 -0.770265 0.552285 -v -0.079000 0.146000 0.315435 -vn -0.000000 -0.770258 0.637732 -v -0.080250 0.146000 0.315100 -vn 0.000000 -1.000000 0.000000 -v -0.086500 0.146000 0.303580 -vn 0.318861 -0.770265 0.552285 -v -0.081500 0.146000 0.315435 -vn 0.552292 -0.770260 0.318863 -v -0.082415 0.146000 0.316350 -vn 0.000000 -1.000000 0.000000 -v -0.086500 0.146000 0.318160 -vn 0.637727 -0.770263 -0.000000 -v -0.082750 0.146000 0.317600 -vn 0.000000 -1.000000 0.000000 -v -0.086500 0.146000 0.320930 -vn 0.552287 -0.770262 -0.318866 -v -0.082415 0.146000 0.318850 -vn 0.318866 -0.770260 -0.552289 -v -0.081500 0.146000 0.319765 -vn -0.000000 -0.770264 -0.637725 -v -0.080250 0.146000 0.320100 -vn -0.318866 -0.770260 -0.552289 -v -0.079000 0.146000 0.319765 -vn -0.318861 -0.770265 0.552286 -v 0.030000 0.146000 0.315435 -vn 0.000000 -0.770258 0.637732 -v 0.028750 0.146000 0.315100 -vn 0.000000 -1.000000 0.000000 -v 0.020750 0.146000 0.303580 -vn 0.318861 -0.770265 0.552286 -v 0.027500 0.146000 0.315435 -vn 0.552292 -0.770260 0.318862 -v 0.026585 0.146000 0.316350 -vn 0.000000 -1.000000 0.000000 -v 0.020750 0.146000 0.318160 -vn 0.637728 -0.770262 0.000000 -v 0.026250 0.146000 0.317600 -vn 0.000000 -1.000000 0.000000 -v 0.020750 0.146000 0.320930 -vn 0.552287 -0.770262 -0.318865 -v 0.026585 0.146000 0.318850 -vn 0.318866 -0.770260 -0.552290 -v 0.027500 0.146000 0.319765 -vn -0.552292 -0.770260 0.318862 -v 0.030915 0.146000 0.316350 -vn -0.637728 -0.770262 0.000000 -v 0.031250 0.146000 0.317600 -vn -0.552286 -0.770263 -0.318866 -v 0.030915 0.146000 0.318850 -vn -0.318865 -0.770260 -0.552290 -v 0.030000 0.146000 0.319765 -vn 0.000000 -0.770264 -0.637725 -v 0.028750 0.146000 0.320100 -vn 0.000000 -1.000000 0.000000 -v 0.014125 0.146000 0.274480 -vn -0.290167 -0.762882 -0.577766 -v 0.015035 0.146000 0.256568 -vn 0.000000 -1.000000 0.000000 -v 0.020750 0.146000 0.274480 -vn -0.518601 -0.762883 -0.386085 -v 0.016802 0.146000 0.255086 -vn 0.518602 -0.762883 -0.386085 -v -0.068302 0.146000 0.255086 -vn 0.000000 -1.000000 0.000000 -v -0.072250 0.146000 0.274480 -vn 0.650416 -0.734195 -0.194722 -v -0.069215 0.146000 0.252968 -vn 0.000000 -1.000000 0.000000 -v -0.072250 0.146000 0.251850 -vn 0.700729 -0.681886 -0.209786 -v -0.069521 0.146000 0.251232 -vn 0.290167 -0.762882 -0.577766 -v -0.066535 0.146000 0.256568 -vn 0.078822 -0.734196 -0.674347 -v -0.064291 0.146000 0.257100 -vn 0.000000 -1.000000 0.000000 -v -0.025750 0.146000 0.274480 -vn 0.000000 -0.707107 -0.707107 -v -0.025750 0.146000 0.257100 -vn -0.078822 -0.734196 -0.674347 -v 0.012791 0.146000 0.257100 -vn 0.603524 -0.658697 -0.449307 -v -0.070435 0.146000 0.249114 -vn 0.337683 -0.658696 -0.672377 -v -0.072202 0.146000 0.247632 -vn 0.000000 -1.000000 0.000000 -v -0.086500 0.146000 0.251850 -vn 0.000000 -1.000000 0.000000 -v -0.086500 0.146000 0.274480 -vn -0.552291 -0.770260 -0.318862 -v 0.030915 0.146000 0.260350 -vn 0.552287 -0.770263 0.318865 -v 0.026585 0.146000 0.257850 -vn 0.637728 -0.770262 0.000000 -v 0.026250 0.146000 0.259100 -vn -0.637728 -0.770262 0.000000 -v 0.031250 0.146000 0.259100 -vn -0.552287 -0.770262 0.318865 -v 0.030915 0.146000 0.257850 -vn 0.552292 -0.770260 -0.318862 -v 0.026585 0.146000 0.260350 -vn 0.318861 -0.770265 -0.552286 -v 0.027500 0.146000 0.261265 -vn 0.000000 -0.770258 -0.637732 -v 0.028750 0.146000 0.261600 -vn -0.318861 -0.770265 -0.552286 -v 0.030000 0.146000 0.261265 -vn -0.318866 -0.770260 0.552290 -v 0.030000 0.146000 0.256935 -vn 0.000000 -0.770264 0.637725 -v 0.028750 0.146000 0.256600 -vn 0.318866 -0.770260 0.552290 -v 0.027500 0.146000 0.256935 -vn -0.337682 -0.658696 -0.672377 -v 0.020701 0.146000 0.247632 -vn -0.603524 -0.658697 -0.449307 -v 0.018935 0.146000 0.249114 -vn 0.301511 -0.904534 0.301511 -v -0.066750 0.146000 0.299560 -vn 0.000000 -0.707107 0.707107 -v 0.014125 0.146000 0.299560 -vn 0.000000 -1.000000 0.000000 -v -0.025750 0.146000 0.290960 -vn -0.301511 -0.904534 0.301511 -v 0.015250 0.146000 0.299560 -vn 0.000000 -1.000000 0.000000 -v 0.020750 0.146000 0.290960 -vn -0.707107 -0.707107 -0.000000 -v 0.015250 0.146000 0.303580 -vn -0.301511 -0.904534 -0.301511 -v 0.015250 0.146000 0.309560 -vn 0.000000 -0.707107 -0.707107 -v 0.014125 0.146000 0.309560 -vn 0.000000 -0.707107 0.707107 -v -0.025750 0.146000 0.292060 -vn 0.000000 -1.000000 0.000000 -v -0.072250 0.146000 0.290960 -vn 0.707107 -0.707107 0.000000 -v -0.066750 0.146000 0.303580 -vn 0.301511 -0.904534 -0.301511 -v -0.066750 0.146000 0.309560 -vn -0.301511 -0.904534 -0.301512 -v 0.011250 0.146000 0.317060 -vn 0.000000 -1.000000 0.000000 -v 0.014125 0.146000 0.318160 -vn 0.000000 -0.707107 -0.707107 -v -0.025750 0.146000 0.317060 -vn 0.000000 -1.000000 0.000000 -v -0.025750 0.146000 0.318160 -vn 0.301511 -0.904534 -0.301511 -v -0.062750 0.146000 0.317060 -vn 0.577350 -0.577350 -0.577350 -v -0.062750 0.146000 0.309560 -vn 0.552286 -0.770262 0.318867 -v -0.064333 0.146000 0.319885 -vn -0.552287 -0.770261 0.318868 -v -0.062167 0.146000 0.319885 -vn -0.318874 -0.770257 0.552289 -v -0.062625 0.146000 0.319428 -vn -0.000000 -0.770270 0.637718 -v -0.063250 0.146000 0.319260 -vn 0.318873 -0.770257 0.552290 -v -0.063875 0.146000 0.319428 -vn 0.318858 -0.770262 -0.552291 -v -0.063875 0.146000 0.321593 -vn -0.000000 -0.770258 -0.637732 -v -0.063250 0.146000 0.321760 -vn -0.318858 -0.770263 -0.552290 -v -0.062625 0.146000 0.321593 -vn 0.000000 -1.000000 0.000000 -v -0.025750 0.146000 0.320930 -vn -0.552287 -0.770263 -0.318864 -v -0.062167 0.146000 0.321135 -vn -0.637727 -0.770263 0.000004 -v -0.062000 0.146000 0.320510 -vn 0.000000 -1.000000 0.000000 -v 0.014125 0.146000 0.320930 -vn -0.637728 -0.770261 0.000004 -v 0.013000 0.146000 0.320510 -vn -0.552286 -0.770262 0.318867 -v 0.012833 0.146000 0.319885 -vn 0.552287 -0.770261 0.318868 -v 0.010667 0.146000 0.319885 -vn -0.318873 -0.770257 0.552290 -v 0.012375 0.146000 0.319428 -vn -0.000000 -0.770270 0.637718 -v 0.011750 0.146000 0.319260 -vn 0.318874 -0.770258 0.552289 -v 0.011125 0.146000 0.319428 -vn -0.318858 -0.770262 -0.552291 -v 0.012375 0.146000 0.321593 -vn -0.552286 -0.770264 -0.318863 -v 0.012833 0.146000 0.321135 -vn 0.637727 -0.770263 0.000004 -v 0.010500 0.146000 0.320510 -vn 0.552287 -0.770263 -0.318864 -v 0.010667 0.146000 0.321135 -vn 0.318858 -0.770263 -0.552290 -v 0.011125 0.146000 0.321593 -vn -0.000000 -0.770258 -0.637732 -v 0.011750 0.146000 0.321760 -vn -0.577350 -0.577350 -0.577350 -v 0.011250 0.146000 0.309560 -vn 0.552287 -0.770263 0.318864 -v 0.010667 0.146000 0.287985 -vn 0.637727 -0.770263 -0.000004 -v 0.010500 0.146000 0.288610 -vn 0.552297 -0.770257 -0.318862 -v 0.010667 0.146000 0.289235 -vn -0.552287 -0.770264 0.318863 -v 0.012833 0.146000 0.287985 -vn 0.318864 -0.770267 -0.552281 -v 0.011125 0.146000 0.289693 -vn -0.000000 -0.770258 -0.637732 -v 0.011750 0.146000 0.289860 -vn -0.318864 -0.770267 -0.552282 -v 0.012375 0.146000 0.289693 -vn -0.318858 -0.770263 0.552291 -v 0.012375 0.146000 0.287528 -vn -0.000000 -0.770258 0.637732 -v 0.011750 0.146000 0.287360 -vn 0.318858 -0.770263 0.552290 -v 0.011125 0.146000 0.287528 -vn -0.552295 -0.770257 -0.318862 -v -0.062167 0.146000 0.289235 -vn -0.637727 -0.770263 -0.000004 -v -0.062000 0.146000 0.288610 -vn 0.552296 -0.770258 -0.318860 -v -0.064333 0.146000 0.289235 -vn 0.318864 -0.770267 -0.552282 -v -0.063875 0.146000 0.289693 -vn -0.000000 -0.770258 -0.637732 -v -0.063250 0.146000 0.289860 -vn -0.318864 -0.770267 -0.552282 -v -0.062625 0.146000 0.289693 -vn -0.552286 -0.770263 0.318865 -v -0.062167 0.146000 0.287985 -vn -0.318858 -0.770262 0.552291 -v -0.062625 0.146000 0.287528 -vn 0.000000 -0.770258 0.637732 -v -0.063250 0.146000 0.287360 -vn 0.318858 -0.770262 0.552291 -v -0.063875 0.146000 0.287528 -vn 0.552286 -0.770264 0.318863 -v -0.064333 0.146000 0.287985 -vn 0.637729 -0.770261 -0.000004 -v -0.064500 0.146000 0.288610 -vn 0.000000 -1.000000 0.000000 -v -0.086500 0.146000 0.290960 -vn -0.552287 -0.770262 0.318866 -v -0.078085 0.146000 0.257850 -vn -0.318866 -0.770260 0.552289 -v -0.079000 0.146000 0.256935 -vn -0.000000 -0.770264 0.637725 -v -0.080250 0.146000 0.256600 -vn 0.318866 -0.770260 0.552290 -v -0.081500 0.146000 0.256935 -vn 0.552287 -0.770262 0.318866 -v -0.082415 0.146000 0.257850 -vn 0.637727 -0.770263 -0.000000 -v -0.082750 0.146000 0.259100 -vn 0.552292 -0.770260 -0.318863 -v -0.082415 0.146000 0.260350 -vn 0.318861 -0.770265 -0.552285 -v -0.081500 0.146000 0.261265 -vn -0.000000 -0.770258 -0.637732 -v -0.080250 0.146000 0.261600 -vn -0.318862 -0.770265 -0.552285 -v -0.079000 0.146000 0.261265 -vn -0.552292 -0.770260 -0.318863 -v -0.078085 0.146000 0.260350 -vn -0.637727 -0.770263 0.000000 -v -0.077750 0.146000 0.259100 -vn 0.552296 0.770258 -0.318860 -v -0.064333 0.148000 0.289235 -vn 0.637728 0.770261 -0.000004 -v -0.064500 0.148000 0.288610 -vn 0.000000 1.000000 0.000000 -v -0.072250 0.148000 0.290960 -vn 0.552297 0.770257 -0.318862 -v 0.010667 0.148000 0.289235 -vn 0.637727 0.770263 -0.000004 -v 0.010500 0.148000 0.288610 -vn 0.000000 1.000000 0.000000 -v -0.025750 0.148000 0.290960 -vn 0.552287 0.770262 -0.318865 -v 0.026585 0.148000 0.318850 -vn 0.637728 0.770262 0.000000 -v 0.026250 0.148000 0.317600 -vn 0.000000 1.000000 0.000000 -v 0.020750 0.148000 0.318160 -vn 0.000000 1.000000 0.000000 -v -0.072250 0.148000 0.320930 -vn 0.000000 1.000000 0.000000 -v 0.020750 0.148000 0.320930 -vn -0.337682 0.658696 -0.672377 -v 0.020701 0.148000 0.247632 -vn 0.000000 1.000000 0.000000 -v 0.020750 0.148000 0.251850 -vn 0.552287 0.770263 0.318865 -v 0.026585 0.148000 0.257850 -vn 0.318866 0.770260 0.552290 -v 0.027500 0.148000 0.256935 -vn 0.000000 0.770264 0.637725 -v 0.028750 0.148000 0.256600 -vn -0.318866 0.770260 0.552290 -v 0.030000 0.148000 0.256935 -vn -0.552287 0.770263 0.318865 -v 0.030915 0.148000 0.257850 -vn -0.637728 0.770262 -0.000000 -v 0.031250 0.148000 0.259100 -vn -0.552291 0.770260 -0.318862 -v 0.030915 0.148000 0.260350 -vn -0.318861 0.770265 -0.552286 -v 0.030000 0.148000 0.261265 -vn 0.000000 0.770258 -0.637732 -v 0.028750 0.148000 0.261600 -vn 0.318861 0.770265 -0.552286 -v 0.027500 0.148000 0.261265 -vn 0.000000 1.000000 0.000000 -v 0.020750 0.148000 0.274480 -vn 0.552291 0.770260 -0.318862 -v 0.026585 0.148000 0.260350 -vn 0.637728 0.770262 0.000000 -v 0.026250 0.148000 0.259100 -vn 0.000000 1.000000 0.000000 -v -0.086500 0.148000 0.251850 -vn 0.000000 1.000000 0.000000 -v -0.072250 0.148000 0.251850 -vn 0.337683 0.658696 -0.672377 -v -0.072202 0.148000 0.247632 -vn 0.000000 1.000000 0.000000 -v -0.072250 0.148000 0.274480 -vn 0.518602 0.762883 -0.386085 -v -0.068302 0.148000 0.255086 -vn 0.603524 0.658697 -0.449307 -v -0.070435 0.148000 0.249114 -vn 0.700729 0.681886 -0.209786 -v -0.069521 0.148000 0.251232 -vn 0.650416 0.734195 -0.194721 -v -0.069215 0.148000 0.252968 -vn 0.000000 0.707107 -0.707107 -v -0.025750 0.148000 0.257100 -vn 0.078822 0.734196 -0.674347 -v -0.064291 0.148000 0.257100 -vn 0.290167 0.762882 -0.577766 -v -0.066535 0.148000 0.256568 -vn 0.000000 1.000000 0.000000 -v 0.014125 0.148000 0.274480 -vn -0.290167 0.762882 -0.577766 -v 0.015035 0.148000 0.256568 -vn -0.078822 0.734196 -0.674347 -v 0.012791 0.148000 0.257100 -vn 0.000000 1.000000 0.000000 -v -0.025750 0.148000 0.274480 -vn -0.518601 0.762883 -0.386085 -v 0.016802 0.148000 0.255086 -vn -0.650416 0.734195 -0.194722 -v 0.017715 0.148000 0.252968 -vn -0.700729 0.681886 -0.209786 -v 0.018021 0.148000 0.251232 -vn -0.603524 0.658697 -0.449307 -v 0.018935 0.148000 0.249114 -vn 0.000000 1.000000 0.000000 -v -0.086500 0.148000 0.303580 -vn 0.318861 0.770265 0.552285 -v -0.081500 0.148000 0.315435 -vn -0.000000 0.770258 0.637732 -v -0.080250 0.148000 0.315100 -vn -0.637727 0.770263 -0.000000 -v -0.077750 0.148000 0.317600 -vn 0.000000 1.000000 0.000000 -v -0.072250 0.148000 0.318160 -vn -0.552292 0.770260 0.318863 -v -0.078085 0.148000 0.316350 -vn 0.000000 1.000000 0.000000 -v -0.072250 0.148000 0.303580 -vn -0.318862 0.770265 0.552285 -v -0.079000 0.148000 0.315435 -vn -0.552287 0.770262 -0.318866 -v -0.078085 0.148000 0.318850 -vn -0.318866 0.770260 -0.552289 -v -0.079000 0.148000 0.319765 -vn -0.000000 0.770264 -0.637725 -v -0.080250 0.148000 0.320100 -vn 0.000000 1.000000 0.000000 -v -0.086500 0.148000 0.320930 -vn 0.318866 0.770260 -0.552289 -v -0.081500 0.148000 0.319765 -vn 0.552287 0.770262 -0.318866 -v -0.082415 0.148000 0.318850 -vn 0.000000 1.000000 0.000000 -v -0.086500 0.148000 0.318160 -vn 0.637727 0.770263 0.000000 -v -0.082750 0.148000 0.317600 -vn 0.552292 0.770260 0.318863 -v -0.082415 0.148000 0.316350 -vn 0.000000 1.000000 0.000000 -v 0.020750 0.148000 0.303580 -vn 0.552291 0.770260 0.318862 -v 0.026585 0.148000 0.316350 -vn 0.318861 0.770265 0.552286 -v 0.027500 0.148000 0.315435 -vn 0.000000 0.770258 0.637732 -v 0.028750 0.148000 0.315100 -vn -0.318861 0.770265 0.552286 -v 0.030000 0.148000 0.315435 -vn -0.552291 0.770260 0.318862 -v 0.030915 0.148000 0.316350 -vn -0.637728 0.770262 -0.000000 -v 0.031250 0.148000 0.317600 -vn -0.552286 0.770263 -0.318866 -v 0.030915 0.148000 0.318850 -vn -0.318865 0.770260 -0.552290 -v 0.030000 0.148000 0.319765 -vn 0.000000 0.770264 -0.637725 -v 0.028750 0.148000 0.320100 -vn 0.318866 0.770260 -0.552290 -v 0.027500 0.148000 0.319765 -vn 0.301511 0.904534 -0.301512 -v -0.062750 0.148000 0.317060 -vn 0.577350 0.577350 -0.577350 -v -0.062750 0.148000 0.309560 -vn 0.301511 0.904534 -0.301511 -v -0.066750 0.148000 0.309560 -vn 0.000000 1.000000 0.000000 -v 0.014125 0.148000 0.290960 -vn 0.000000 0.707107 0.707107 -v 0.014125 0.148000 0.299560 -vn 0.000000 1.000000 0.000000 -v 0.020750 0.148000 0.290960 -vn -0.301511 0.904534 0.301511 -v 0.015250 0.148000 0.299560 -vn -0.707107 0.707107 -0.000000 -v 0.015250 0.148000 0.303580 -vn -0.301511 0.904534 -0.301511 -v 0.015250 0.148000 0.309560 -vn 0.000000 1.000000 0.000000 -v 0.014125 0.148000 0.318160 -vn 0.000000 0.707107 -0.707107 -v 0.014125 0.148000 0.309560 -vn -0.577350 0.577350 -0.577350 -v 0.011250 0.148000 0.309560 -vn -0.301511 0.904534 -0.301511 -v 0.011250 0.148000 0.317060 -vn 0.000000 0.707107 -0.707107 -v -0.025750 0.148000 0.317060 -vn 0.000000 1.000000 0.000000 -v -0.025750 0.148000 0.318160 -vn 0.707107 0.707107 0.000000 -v -0.066750 0.148000 0.303580 -vn 0.301511 0.904534 0.301511 -v -0.066750 0.148000 0.299560 -vn 0.000000 0.707107 0.707107 -v -0.025750 0.148000 0.292060 -vn 0.637728 0.770261 0.000004 -v -0.064500 0.148000 0.320510 -vn 0.552286 0.770262 0.318867 -v -0.064333 0.148000 0.319885 -vn 0.318873 0.770257 0.552290 -v -0.063875 0.148000 0.319428 -vn 0.000000 0.770270 0.637718 -v -0.063250 0.148000 0.319260 -vn -0.318874 0.770257 0.552289 -v -0.062625 0.148000 0.319428 -vn -0.552287 0.770261 0.318868 -v -0.062167 0.148000 0.319885 -vn 0.318858 0.770262 -0.552291 -v -0.063875 0.148000 0.321593 -vn 0.552286 0.770264 -0.318863 -v -0.064333 0.148000 0.321135 -vn -0.637727 0.770263 0.000004 -v -0.062000 0.148000 0.320510 -vn 0.000000 1.000000 0.000000 -v -0.025750 0.148000 0.320930 -vn -0.552287 0.770263 -0.318864 -v -0.062167 0.148000 0.321135 -vn -0.318858 0.770263 -0.552290 -v -0.062625 0.148000 0.321593 -vn 0.000000 0.770258 -0.637732 -v -0.063250 0.148000 0.321760 -vn -0.552286 0.770262 0.318867 -v 0.012833 0.148000 0.319885 -vn -0.637728 0.770261 0.000004 -v 0.013000 0.148000 0.320510 -vn 0.000000 1.000000 0.000000 -v 0.014125 0.148000 0.320930 -vn 0.552287 0.770261 0.318868 -v 0.010667 0.148000 0.319885 -vn 0.318874 0.770257 0.552289 -v 0.011125 0.148000 0.319428 -vn -0.000000 0.770270 0.637718 -v 0.011750 0.148000 0.319260 -vn -0.318873 0.770257 0.552290 -v 0.012375 0.148000 0.319428 -vn 0.637727 0.770263 0.000004 -v 0.010500 0.148000 0.320510 -vn -0.552286 0.770264 -0.318863 -v 0.012833 0.148000 0.321135 -vn -0.318858 0.770262 -0.552291 -v 0.012375 0.148000 0.321593 -vn -0.000000 0.770258 -0.637732 -v 0.011750 0.148000 0.321760 -vn 0.318858 0.770263 -0.552290 -v 0.011125 0.148000 0.321593 -vn 0.552287 0.770263 -0.318864 -v 0.010667 0.148000 0.321135 -vn 0.637727 0.770263 0.000000 -v -0.082750 0.148000 0.259100 -vn 0.552287 0.770262 0.318866 -v -0.082415 0.148000 0.257850 -vn -0.000000 0.770258 -0.637732 -v -0.080250 0.148000 0.261600 -vn 0.318861 0.770265 -0.552285 -v -0.081500 0.148000 0.261265 -vn 0.000000 1.000000 0.000000 -v -0.086500 0.148000 0.274480 -vn 0.552292 0.770260 -0.318863 -v -0.082415 0.148000 0.260350 -vn -0.318866 0.770260 0.552289 -v -0.079000 0.148000 0.256935 -vn -0.000000 0.770264 0.637725 -v -0.080250 0.148000 0.256600 -vn 0.318866 0.770260 0.552290 -v -0.081500 0.148000 0.256935 -vn -0.552287 0.770262 0.318866 -v -0.078085 0.148000 0.257850 -vn -0.637727 0.770263 -0.000000 -v -0.077750 0.148000 0.259100 -vn -0.552292 0.770260 -0.318863 -v -0.078085 0.148000 0.260350 -vn -0.318862 0.770265 -0.552285 -v -0.079000 0.148000 0.261265 -vn -0.318858 0.770263 0.552291 -v 0.012375 0.148000 0.287528 -vn -0.552287 0.770264 0.318862 -v 0.012833 0.148000 0.287985 -vn -0.637728 0.770261 -0.000004 -v 0.013000 0.148000 0.288610 -vn -0.552296 0.770258 -0.318860 -v 0.012833 0.148000 0.289235 -vn -0.318864 0.770267 -0.552282 -v 0.012375 0.148000 0.289693 -vn -0.000000 0.770258 -0.637732 -v 0.011750 0.148000 0.289860 -vn 0.318864 0.770267 -0.552281 -v 0.011125 0.148000 0.289693 -vn 0.552287 0.770263 0.318864 -v 0.010667 0.148000 0.287985 -vn 0.318858 0.770263 0.552290 -v 0.011125 0.148000 0.287528 -vn -0.000000 0.770258 0.637732 -v 0.011750 0.148000 0.287360 -vn 0.552286 0.770264 0.318863 -v -0.064333 0.148000 0.287985 -vn 0.318858 0.770262 0.552291 -v -0.063875 0.148000 0.287528 -vn -0.000000 0.770258 0.637732 -v -0.063250 0.148000 0.287360 -vn -0.552295 0.770257 -0.318862 -v -0.062167 0.148000 0.289235 -vn -0.318864 0.770267 -0.552282 -v -0.062625 0.148000 0.289693 -vn 0.000000 0.770258 -0.637732 -v -0.063250 0.148000 0.289860 -vn 0.318864 0.770267 -0.552282 -v -0.063875 0.148000 0.289693 -vn -0.318858 0.770262 0.552291 -v -0.062625 0.148000 0.287528 -vn -0.552286 0.770263 0.318865 -v -0.062167 0.148000 0.287985 -vn -0.637727 0.770263 -0.000004 -v -0.062000 0.148000 0.288610 -vn 0.000000 1.000000 0.000000 -v -0.086500 0.148000 0.290960 -vn -0.577350 0.577350 0.577350 -v 0.008761 -0.146000 0.299560 -vn -0.301511 0.904534 0.301512 -v 0.008761 -0.146000 0.292060 -vn -0.577350 -0.577350 0.577350 -v 0.008761 -0.148000 0.299560 -vn -0.301511 -0.904534 0.301511 -v 0.008761 -0.148000 0.292060 -vn 0.577350 -0.577350 0.577350 -v -0.065239 -0.148000 0.299560 -vn 0.301511 -0.904534 0.301511 -v -0.065239 -0.148000 0.292060 -vn 0.577350 0.577350 0.577350 -v -0.065239 -0.146000 0.299560 -vn 0.301511 0.904534 0.301511 -v -0.065239 -0.146000 0.292060 -vn 0.084917 -0.681886 -0.726512 -v -0.076934 -0.148000 0.247100 -vn -0.071346 -0.685696 -0.724383 -v -0.087739 -0.148000 0.247100 -vn 0.084917 0.681886 -0.726512 -v -0.076934 -0.146000 0.247100 -vn -0.071346 0.685696 -0.724383 -v -0.087739 -0.146000 0.247100 -vn -0.724383 -0.685697 -0.071345 -v -0.092739 -0.148000 0.252100 -vn -0.724383 0.685696 -0.071345 -v -0.092739 -0.146000 0.252100 -vn -0.689401 0.665719 -0.285560 -v -0.092358 -0.146000 0.250187 -vn -0.689401 -0.665719 -0.285560 -v -0.092358 -0.148000 0.250187 -vn -0.527644 0.665719 -0.527645 -v -0.091274 -0.146000 0.248564 -vn -0.527644 -0.665719 -0.527645 -v -0.091274 -0.148000 0.248564 -vn -0.285560 0.665719 -0.689401 -v -0.089652 -0.146000 0.247481 -vn -0.285560 -0.665719 -0.689401 -v -0.089652 -0.148000 0.247481 -vn -0.084917 0.681886 -0.726512 -v 0.020457 -0.146000 0.247100 -vn 0.071346 0.685696 -0.724383 -v 0.031261 -0.146000 0.247100 -vn -0.084917 -0.681886 -0.726512 -v 0.020457 -0.148000 0.247100 -vn 0.071346 -0.685696 -0.724383 -v 0.031261 -0.148000 0.247100 -vn 0.285560 0.665719 -0.689401 -v 0.033175 -0.146000 0.247481 -vn 0.285560 -0.665719 -0.689401 -v 0.033175 -0.148000 0.247481 -vn 0.527644 0.665719 -0.527645 -v 0.034797 -0.146000 0.248564 -vn 0.527644 -0.665719 -0.527645 -v 0.034797 -0.148000 0.248564 -vn 0.689401 0.665719 -0.285560 -v 0.035881 -0.146000 0.250187 -vn 0.689401 -0.665719 -0.285560 -v 0.035881 -0.148000 0.250187 -vn 0.724383 0.685696 -0.071345 -v 0.036261 -0.146000 0.252100 -vn 0.724383 -0.685696 -0.071345 -v 0.036261 -0.148000 0.252100 -vn 0.724382 0.685697 0.071344 -v 0.036261 -0.146000 0.334600 -vn 0.724382 -0.685697 0.071344 -v 0.036261 -0.148000 0.334600 -vn 0.707107 0.707107 0.000000 -v 0.036261 -0.146000 0.320930 -vn 0.707107 -0.707107 0.000000 -v 0.036261 -0.148000 0.320930 -vn 0.707107 0.707107 0.000000 -v 0.036261 -0.146000 0.318160 -vn 0.707107 -0.707107 0.000000 -v 0.036261 -0.148000 0.318160 -vn 0.707107 0.707107 0.000000 -v 0.036261 -0.146000 0.303580 -vn 0.707107 -0.707107 0.000000 -v 0.036261 -0.148000 0.303580 -vn 0.707107 0.707107 0.000000 -v 0.036261 -0.146000 0.290960 -vn 0.707107 -0.707107 0.000000 -v 0.036261 -0.148000 0.290960 -vn 0.707107 0.707107 0.000000 -v 0.036261 -0.146000 0.274480 -vn 0.707107 -0.707107 0.000000 -v 0.036261 -0.148000 0.274480 -vn 0.689402 0.665718 0.285559 -v 0.035881 -0.146000 0.336513 -vn 0.689402 -0.665718 0.285559 -v 0.035881 -0.148000 0.336513 -vn 0.527643 0.665719 0.527647 -v 0.034797 -0.146000 0.338136 -vn 0.527643 -0.665719 0.527647 -v 0.034797 -0.148000 0.338136 -vn 0.285558 0.665720 0.689401 -v 0.033175 -0.146000 0.339219 -vn 0.285558 -0.665720 0.689401 -v 0.033175 -0.148000 0.339219 -vn 0.071346 0.685696 0.724383 -v 0.031261 -0.146000 0.339600 -vn 0.071346 -0.685696 0.724383 -v 0.031261 -0.148000 0.339600 -vn -0.071346 0.685696 0.724383 -v -0.087739 -0.146000 0.339600 -vn -0.071346 -0.685696 0.724383 -v -0.087739 -0.148000 0.339600 -vn 0.000000 0.707107 0.707107 -v -0.074739 -0.146000 0.339600 -vn 0.000000 -0.707107 0.707107 -v -0.074739 -0.148000 0.339600 -vn 0.000000 0.707107 0.707106 -v -0.028239 -0.146000 0.339600 -vn 0.000000 -0.707107 0.707107 -v -0.028239 -0.148000 0.339600 -vn 0.000000 0.707106 0.707107 -v 0.011636 -0.146000 0.339600 -vn 0.000000 -0.707107 0.707107 -v 0.011636 -0.148000 0.339600 -vn 0.000000 0.707107 0.707107 -v 0.018261 -0.146000 0.339600 -vn 0.000000 -0.707107 0.707107 -v 0.018261 -0.148000 0.339600 -vn -0.285558 0.665720 0.689401 -v -0.089652 -0.146000 0.339219 -vn -0.285558 -0.665720 0.689401 -v -0.089652 -0.148000 0.339219 -vn -0.527643 0.665719 0.527647 -v -0.091274 -0.146000 0.338136 -vn -0.527643 -0.665719 0.527647 -v -0.091274 -0.148000 0.338136 -vn -0.689402 0.665718 0.285559 -v -0.092358 -0.146000 0.336513 -vn -0.689402 -0.665718 0.285559 -v -0.092358 -0.148000 0.336513 -vn -0.724383 0.685697 0.071344 -v -0.092739 -0.146000 0.334600 -vn -0.724382 -0.685697 0.071344 -v -0.092739 -0.148000 0.334600 -vn -0.707107 0.707107 -0.000000 -v -0.092739 -0.146000 0.274480 -vn -0.707107 -0.707107 -0.000000 -v -0.092739 -0.148000 0.274480 -vn -0.707107 0.707107 0.000000 -v -0.092739 -0.146000 0.290960 -vn -0.707107 -0.707107 0.000000 -v -0.092739 -0.148000 0.290960 -vn -0.707107 0.707107 0.000000 -v -0.092739 -0.146000 0.303580 -vn -0.707107 -0.707107 0.000000 -v -0.092739 -0.148000 0.303580 -vn -0.707107 0.707107 0.000000 -v -0.092739 -0.146000 0.318160 -vn -0.707107 -0.707107 0.000000 -v -0.092739 -0.148000 0.318160 -vn -0.707107 0.707107 0.000000 -v -0.092739 -0.146000 0.320930 -vn -0.707107 -0.707107 0.000000 -v -0.092739 -0.148000 0.320930 -vn -0.552296 -0.770258 -0.318860 -v 0.010344 -0.148000 0.289235 -vn -0.637728 -0.770261 -0.000004 -v 0.010511 -0.148000 0.288610 -vn 0.000000 -1.000000 0.000000 -v 0.011636 -0.148000 0.290960 -vn 0.637728 -0.770261 0.000004 -v -0.066989 -0.148000 0.320510 -vn 0.552286 -0.770264 -0.318863 -v -0.066821 -0.148000 0.321135 -vn 0.000000 -1.000000 0.000000 -v -0.074739 -0.148000 0.320930 -vn -0.650416 -0.734195 -0.194722 -v 0.015227 -0.148000 0.252968 -vn -0.700729 -0.681886 -0.209786 -v 0.015533 -0.148000 0.251232 -vn 0.000000 -1.000000 0.000000 -v 0.018261 -0.148000 0.251850 -vn -0.552291 -0.770261 0.318862 -v -0.080574 -0.148000 0.316350 -vn 0.000000 -1.000000 0.000000 -v -0.074739 -0.148000 0.303580 -vn -0.637728 -0.770261 0.000000 -v -0.080239 -0.148000 0.317600 -vn 0.000000 -1.000000 0.000000 -v -0.074739 -0.148000 0.318160 -vn -0.552286 -0.770263 -0.318865 -v -0.080574 -0.148000 0.318850 -vn -0.318861 -0.770265 0.552286 -v -0.081489 -0.148000 0.315435 -vn 0.000000 -0.770258 0.637732 -v -0.082739 -0.148000 0.315100 -vn 0.000000 -1.000000 0.000000 -v -0.088989 -0.148000 0.303580 -vn 0.318861 -0.770265 0.552286 -v -0.083989 -0.148000 0.315435 -vn 0.552291 -0.770261 0.318862 -v -0.084904 -0.148000 0.316350 -vn 0.000000 -1.000000 0.000000 -v -0.088989 -0.148000 0.318160 -vn 0.637728 -0.770261 0.000000 -v -0.085239 -0.148000 0.317600 -vn 0.000000 -1.000000 0.000000 -v -0.088989 -0.148000 0.320930 -vn 0.552286 -0.770263 -0.318865 -v -0.084904 -0.148000 0.318850 -vn 0.318865 -0.770260 -0.552291 -v -0.083989 -0.148000 0.319765 -vn 0.000000 -0.770264 -0.637725 -v -0.082739 -0.148000 0.320100 -vn -0.318865 -0.770260 -0.552291 -v -0.081489 -0.148000 0.319765 -vn -0.318861 -0.770265 0.552286 -v 0.027511 -0.148000 0.315435 -vn 0.000000 -0.770258 0.637732 -v 0.026261 -0.148000 0.315100 -vn 0.000000 -1.000000 0.000000 -v 0.018261 -0.148000 0.303580 -vn 0.318861 -0.770265 0.552286 -v 0.025011 -0.148000 0.315435 -vn 0.552292 -0.770260 0.318862 -v 0.024096 -0.148000 0.316350 -vn 0.000000 -1.000000 0.000000 -v 0.018261 -0.148000 0.318160 -vn 0.637728 -0.770262 0.000000 -v 0.023761 -0.148000 0.317600 -vn 0.000000 -1.000000 0.000000 -v 0.018261 -0.148000 0.320930 -vn 0.552287 -0.770262 -0.318865 -v 0.024096 -0.148000 0.318850 -vn 0.318866 -0.770260 -0.552290 -v 0.025011 -0.148000 0.319765 -vn -0.552292 -0.770260 0.318862 -v 0.028426 -0.148000 0.316350 -vn -0.637728 -0.770262 0.000000 -v 0.028761 -0.148000 0.317600 -vn -0.552286 -0.770263 -0.318866 -v 0.028426 -0.148000 0.318850 -vn -0.318865 -0.770260 -0.552290 -v 0.027511 -0.148000 0.319765 -vn 0.000000 -0.770264 -0.637725 -v 0.026261 -0.148000 0.320100 -vn 0.000000 -1.000000 0.000000 -v 0.011636 -0.148000 0.274480 -vn -0.290167 -0.762882 -0.577766 -v 0.012546 -0.148000 0.256568 -vn 0.000000 -1.000000 0.000000 -v 0.018261 -0.148000 0.274480 -vn -0.518601 -0.762883 -0.386085 -v 0.014313 -0.148000 0.255086 -vn 0.518602 -0.762883 -0.386086 -v -0.070791 -0.148000 0.255086 -vn 0.000000 -1.000000 0.000000 -v -0.074739 -0.148000 0.274480 -vn 0.650416 -0.734195 -0.194722 -v -0.071704 -0.148000 0.252968 -vn 0.000000 -1.000000 0.000000 -v -0.074739 -0.148000 0.251850 -vn 0.700729 -0.681886 -0.209785 -v -0.072010 -0.148000 0.251232 -vn 0.290167 -0.762882 -0.577766 -v -0.069024 -0.148000 0.256568 -vn 0.078822 -0.734196 -0.674347 -v -0.066780 -0.148000 0.257100 -vn 0.000000 -1.000000 0.000000 -v -0.028239 -0.148000 0.274480 -vn 0.000000 -0.707107 -0.707107 -v -0.028239 -0.148000 0.257100 -vn -0.078822 -0.734196 -0.674347 -v 0.010302 -0.148000 0.257100 -vn 0.603525 -0.658697 -0.449307 -v -0.072924 -0.148000 0.249114 -vn 0.337682 -0.658696 -0.672377 -v -0.074690 -0.148000 0.247632 -vn 0.000000 -1.000000 0.000000 -v -0.088989 -0.148000 0.251850 -vn 0.000000 -1.000000 0.000000 -v -0.088989 -0.148000 0.274480 -vn -0.552291 -0.770260 -0.318862 -v 0.028426 -0.148000 0.260350 -vn 0.552287 -0.770263 0.318865 -v 0.024096 -0.148000 0.257850 -vn 0.637728 -0.770262 0.000000 -v 0.023761 -0.148000 0.259100 -vn -0.637728 -0.770262 0.000000 -v 0.028761 -0.148000 0.259100 -vn -0.552287 -0.770262 0.318865 -v 0.028426 -0.148000 0.257850 -vn 0.552292 -0.770260 -0.318862 -v 0.024096 -0.148000 0.260350 -vn 0.318861 -0.770265 -0.552286 -v 0.025011 -0.148000 0.261265 -vn 0.000000 -0.770258 -0.637732 -v 0.026261 -0.148000 0.261600 -vn -0.318861 -0.770265 -0.552286 -v 0.027511 -0.148000 0.261265 -vn -0.318866 -0.770260 0.552290 -v 0.027511 -0.148000 0.256935 -vn 0.000000 -0.770264 0.637725 -v 0.026261 -0.148000 0.256600 -vn 0.318866 -0.770260 0.552290 -v 0.025011 -0.148000 0.256935 -vn -0.337682 -0.658696 -0.672377 -v 0.018213 -0.148000 0.247632 -vn -0.603524 -0.658697 -0.449307 -v 0.016446 -0.148000 0.249114 -vn 0.301511 -0.904534 0.301511 -v -0.069239 -0.148000 0.299560 -vn 0.000000 -0.707107 0.707107 -v 0.011636 -0.148000 0.299560 -vn 0.000000 -1.000000 0.000000 -v -0.028239 -0.148000 0.290960 -vn -0.301511 -0.904534 0.301511 -v 0.012761 -0.148000 0.299560 -vn 0.000000 -1.000000 0.000000 -v 0.018261 -0.148000 0.290960 -vn -0.707107 -0.707107 -0.000000 -v 0.012761 -0.148000 0.303580 -vn -0.301511 -0.904534 -0.301511 -v 0.012761 -0.148000 0.309560 -vn 0.000000 -0.707107 -0.707107 -v 0.011636 -0.148000 0.309560 -vn 0.000000 -0.707107 0.707107 -v -0.028239 -0.148000 0.292060 -vn 0.000000 -1.000000 0.000000 -v -0.074739 -0.148000 0.290960 -vn 0.707107 -0.707107 0.000000 -v -0.069239 -0.148000 0.303580 -vn 0.301511 -0.904534 -0.301511 -v -0.069239 -0.148000 0.309560 -vn -0.301511 -0.904534 -0.301512 -v 0.008761 -0.148000 0.317060 -vn 0.000000 -1.000000 0.000000 -v 0.011636 -0.148000 0.318160 -vn 0.000000 -0.707107 -0.707107 -v -0.028239 -0.148000 0.317060 -vn 0.000000 -1.000000 0.000000 -v -0.028239 -0.148000 0.318160 -vn 0.301511 -0.904534 -0.301511 -v -0.065239 -0.148000 0.317060 -vn 0.577350 -0.577350 -0.577350 -v -0.065239 -0.148000 0.309560 -vn 0.552286 -0.770262 0.318867 -v -0.066821 -0.148000 0.319885 -vn -0.552288 -0.770260 0.318869 -v -0.064656 -0.148000 0.319885 -vn -0.318874 -0.770258 0.552288 -v -0.065114 -0.148000 0.319428 -vn 0.000001 -0.770269 0.637719 -v -0.065739 -0.148000 0.319260 -vn 0.318873 -0.770257 0.552290 -v -0.066364 -0.148000 0.319428 -vn 0.318858 -0.770262 -0.552291 -v -0.066364 -0.148000 0.321593 -vn 0.000001 -0.770258 -0.637732 -v -0.065739 -0.148000 0.321760 -vn -0.318858 -0.770264 -0.552289 -v -0.065114 -0.148000 0.321593 -vn 0.000000 -1.000000 0.000000 -v -0.028239 -0.148000 0.320930 -vn -0.552288 -0.770261 -0.318865 -v -0.064656 -0.148000 0.321135 -vn -0.637725 -0.770264 0.000004 -v -0.064489 -0.148000 0.320510 -vn 0.000000 -1.000000 0.000000 -v 0.011636 -0.148000 0.320930 -vn -0.637728 -0.770261 0.000004 -v 0.010511 -0.148000 0.320510 -vn -0.552286 -0.770262 0.318867 -v 0.010344 -0.148000 0.319885 -vn 0.552287 -0.770261 0.318868 -v 0.008179 -0.148000 0.319885 -vn -0.318873 -0.770257 0.552290 -v 0.009886 -0.148000 0.319428 -vn -0.000000 -0.770270 0.637718 -v 0.009261 -0.148000 0.319260 -vn 0.318874 -0.770258 0.552289 -v 0.008636 -0.148000 0.319428 -vn -0.318858 -0.770262 -0.552291 -v 0.009886 -0.148000 0.321593 -vn -0.552286 -0.770264 -0.318863 -v 0.010344 -0.148000 0.321135 -vn 0.637727 -0.770263 0.000004 -v 0.008011 -0.148000 0.320510 -vn 0.552287 -0.770263 -0.318864 -v 0.008179 -0.148000 0.321135 -vn 0.318858 -0.770263 -0.552290 -v 0.008636 -0.148000 0.321593 -vn -0.000000 -0.770258 -0.637732 -v 0.009261 -0.148000 0.321760 -vn -0.577350 -0.577350 -0.577350 -v 0.008761 -0.148000 0.309560 -vn 0.552287 -0.770263 0.318864 -v 0.008179 -0.148000 0.287985 -vn 0.637727 -0.770263 -0.000004 -v 0.008011 -0.148000 0.288610 -vn 0.552297 -0.770257 -0.318862 -v 0.008179 -0.148000 0.289235 -vn -0.552287 -0.770264 0.318863 -v 0.010344 -0.148000 0.287985 -vn 0.318864 -0.770267 -0.552281 -v 0.008636 -0.148000 0.289693 -vn -0.000000 -0.770258 -0.637732 -v 0.009261 -0.148000 0.289860 -vn -0.318864 -0.770267 -0.552282 -v 0.009886 -0.148000 0.289693 -vn -0.318858 -0.770263 0.552291 -v 0.009886 -0.148000 0.287528 -vn -0.000000 -0.770258 0.637732 -v 0.009261 -0.148000 0.287360 -vn 0.318858 -0.770263 0.552290 -v 0.008636 -0.148000 0.287528 -vn -0.552298 -0.770256 -0.318863 -v -0.064656 -0.148000 0.289235 -vn -0.637725 -0.770264 -0.000004 -v -0.064489 -0.148000 0.288610 -vn 0.552296 -0.770258 -0.318860 -v -0.066821 -0.148000 0.289235 -vn 0.318864 -0.770267 -0.552282 -v -0.066364 -0.148000 0.289693 -vn 0.000001 -0.770258 -0.637732 -v -0.065739 -0.148000 0.289860 -vn -0.318865 -0.770268 -0.552279 -v -0.065114 -0.148000 0.289693 -vn -0.552288 -0.770261 0.318865 -v -0.064656 -0.148000 0.287985 -vn -0.318858 -0.770264 0.552289 -v -0.065114 -0.148000 0.287528 -vn 0.000001 -0.770258 0.637732 -v -0.065739 -0.148000 0.287360 -vn 0.318858 -0.770262 0.552291 -v -0.066364 -0.148000 0.287528 -vn 0.552286 -0.770264 0.318863 -v -0.066821 -0.148000 0.287985 -vn 0.637728 -0.770261 -0.000004 -v -0.066989 -0.148000 0.288610 -vn 0.000000 -1.000000 0.000000 -v -0.088989 -0.148000 0.290960 -vn -0.552286 -0.770263 0.318865 -v -0.080574 -0.148000 0.257850 -vn -0.318865 -0.770260 0.552291 -v -0.081489 -0.148000 0.256935 -vn -0.000000 -0.770264 0.637725 -v -0.082739 -0.148000 0.256600 -vn 0.318865 -0.770260 0.552291 -v -0.083989 -0.148000 0.256935 -vn 0.552286 -0.770263 0.318865 -v -0.084904 -0.148000 0.257850 -vn 0.637728 -0.770261 0.000000 -v -0.085239 -0.148000 0.259100 -vn 0.552291 -0.770261 -0.318862 -v -0.084904 -0.148000 0.260350 -vn 0.318861 -0.770265 -0.552286 -v -0.083989 -0.148000 0.261265 -vn -0.000000 -0.770258 -0.637732 -v -0.082739 -0.148000 0.261600 -vn -0.318861 -0.770265 -0.552286 -v -0.081489 -0.148000 0.261265 -vn -0.552291 -0.770261 -0.318862 -v -0.080574 -0.148000 0.260350 -vn -0.637728 -0.770261 0.000000 -v -0.080239 -0.148000 0.259100 -vn 0.552296 0.770258 -0.318860 -v -0.066821 -0.146000 0.289235 -vn 0.637728 0.770261 -0.000004 -v -0.066989 -0.146000 0.288610 -vn 0.000000 1.000000 0.000000 -v -0.074739 -0.146000 0.290960 -vn 0.552297 0.770257 -0.318862 -v 0.008179 -0.146000 0.289235 -vn 0.637727 0.770263 -0.000004 -v 0.008011 -0.146000 0.288610 -vn 0.000000 1.000000 0.000000 -v -0.028239 -0.146000 0.290960 -vn 0.552287 0.770262 -0.318865 -v 0.024096 -0.146000 0.318850 -vn 0.637728 0.770262 0.000000 -v 0.023761 -0.146000 0.317600 -vn 0.000000 1.000000 0.000000 -v 0.018261 -0.146000 0.318160 -vn 0.000000 1.000000 0.000000 -v -0.074739 -0.146000 0.320930 -vn 0.000000 1.000000 0.000000 -v 0.018261 -0.146000 0.320930 -vn -0.337682 0.658696 -0.672377 -v 0.018213 -0.146000 0.247632 -vn 0.000000 1.000000 0.000000 -v 0.018261 -0.146000 0.251850 -vn 0.552287 0.770263 0.318865 -v 0.024096 -0.146000 0.257850 -vn 0.318866 0.770260 0.552290 -v 0.025011 -0.146000 0.256935 -vn 0.000000 0.770264 0.637725 -v 0.026261 -0.146000 0.256600 -vn -0.318866 0.770260 0.552290 -v 0.027511 -0.146000 0.256935 -vn -0.552287 0.770263 0.318865 -v 0.028426 -0.146000 0.257850 -vn -0.637728 0.770262 -0.000000 -v 0.028761 -0.146000 0.259100 -vn -0.552291 0.770260 -0.318862 -v 0.028426 -0.146000 0.260350 -vn -0.318861 0.770265 -0.552286 -v 0.027511 -0.146000 0.261265 -vn 0.000000 0.770258 -0.637732 -v 0.026261 -0.146000 0.261600 -vn 0.318861 0.770265 -0.552286 -v 0.025011 -0.146000 0.261265 -vn 0.000000 1.000000 0.000000 -v 0.018261 -0.146000 0.274480 -vn 0.552291 0.770260 -0.318862 -v 0.024096 -0.146000 0.260350 -vn 0.637728 0.770262 0.000000 -v 0.023761 -0.146000 0.259100 -vn 0.000000 1.000000 0.000000 -v -0.088989 -0.146000 0.251850 -vn 0.000000 1.000000 0.000000 -v -0.074739 -0.146000 0.251850 -vn 0.337682 0.658696 -0.672377 -v -0.074690 -0.146000 0.247632 -vn 0.000000 1.000000 0.000000 -v -0.074739 -0.146000 0.274480 -vn 0.518602 0.762883 -0.386086 -v -0.070791 -0.146000 0.255086 -vn 0.603525 0.658697 -0.449307 -v -0.072924 -0.146000 0.249114 -vn 0.700729 0.681886 -0.209785 -v -0.072010 -0.146000 0.251232 -vn 0.650416 0.734195 -0.194722 -v -0.071704 -0.146000 0.252968 -vn 0.000000 0.707107 -0.707107 -v -0.028239 -0.146000 0.257100 -vn 0.078822 0.734196 -0.674347 -v -0.066780 -0.146000 0.257100 -vn 0.290167 0.762882 -0.577766 -v -0.069024 -0.146000 0.256568 -vn 0.000000 1.000000 0.000000 -v 0.011636 -0.146000 0.274480 -vn -0.290167 0.762882 -0.577766 -v 0.012546 -0.146000 0.256568 -vn -0.078822 0.734196 -0.674347 -v 0.010302 -0.146000 0.257100 -vn 0.000000 1.000000 0.000000 -v -0.028239 -0.146000 0.274480 -vn -0.518601 0.762883 -0.386085 -v 0.014313 -0.146000 0.255086 -vn -0.650416 0.734195 -0.194722 -v 0.015227 -0.146000 0.252968 -vn -0.700729 0.681886 -0.209786 -v 0.015533 -0.146000 0.251232 -vn -0.603524 0.658697 -0.449307 -v 0.016446 -0.146000 0.249114 -vn 0.000000 1.000000 0.000000 -v -0.088989 -0.146000 0.303580 -vn 0.318861 0.770265 0.552286 -v -0.083989 -0.146000 0.315435 -vn -0.000000 0.770258 0.637732 -v -0.082739 -0.146000 0.315100 -vn -0.637729 0.770261 0.000000 -v -0.080239 -0.146000 0.317600 -vn 0.000000 1.000000 0.000000 -v -0.074739 -0.146000 0.318160 -vn -0.552291 0.770261 0.318862 -v -0.080574 -0.146000 0.316350 -vn 0.000000 1.000000 0.000000 -v -0.074739 -0.146000 0.303580 -vn -0.318861 0.770265 0.552286 -v -0.081489 -0.146000 0.315435 -vn -0.552286 0.770263 -0.318865 -v -0.080574 -0.146000 0.318850 -vn -0.318865 0.770260 -0.552291 -v -0.081489 -0.146000 0.319765 -vn 0.000000 0.770264 -0.637725 -v -0.082739 -0.146000 0.320100 -vn 0.000000 1.000000 0.000000 -v -0.088989 -0.146000 0.320930 -vn 0.318866 0.770260 -0.552291 -v -0.083989 -0.146000 0.319765 -vn 0.552286 0.770263 -0.318865 -v -0.084904 -0.146000 0.318850 -vn 0.000000 1.000000 0.000000 -v -0.088989 -0.146000 0.318160 -vn 0.637728 0.770261 0.000000 -v -0.085239 -0.146000 0.317600 -vn 0.552291 0.770261 0.318862 -v -0.084904 -0.146000 0.316350 -vn 0.000000 1.000000 0.000000 -v 0.018261 -0.146000 0.303580 -vn 0.552291 0.770260 0.318862 -v 0.024096 -0.146000 0.316350 -vn 0.318861 0.770265 0.552286 -v 0.025011 -0.146000 0.315435 -vn 0.000000 0.770258 0.637732 -v 0.026261 -0.146000 0.315100 -vn -0.318861 0.770265 0.552286 -v 0.027511 -0.146000 0.315435 -vn -0.552291 0.770260 0.318862 -v 0.028426 -0.146000 0.316350 -vn -0.637728 0.770262 -0.000000 -v 0.028761 -0.146000 0.317600 -vn -0.552286 0.770263 -0.318866 -v 0.028426 -0.146000 0.318850 -vn -0.318865 0.770260 -0.552290 -v 0.027511 -0.146000 0.319765 -vn 0.000000 0.770264 -0.637725 -v 0.026261 -0.146000 0.320100 -vn 0.318866 0.770260 -0.552290 -v 0.025011 -0.146000 0.319765 -vn 0.301511 0.904534 -0.301511 -v -0.065239 -0.146000 0.317060 -vn 0.577350 0.577350 -0.577350 -v -0.065239 -0.146000 0.309560 -vn 0.301511 0.904534 -0.301511 -v -0.069239 -0.146000 0.309560 -vn 0.000000 1.000000 0.000000 -v 0.011636 -0.146000 0.290960 -vn 0.000000 0.707107 0.707107 -v 0.011636 -0.146000 0.299560 -vn 0.000000 1.000000 0.000000 -v 0.018261 -0.146000 0.290960 -vn -0.301511 0.904534 0.301511 -v 0.012761 -0.146000 0.299560 -vn -0.707107 0.707107 -0.000000 -v 0.012761 -0.146000 0.303580 -vn -0.301511 0.904534 -0.301511 -v 0.012761 -0.146000 0.309560 -vn 0.000000 1.000000 0.000000 -v 0.011636 -0.146000 0.318160 -vn 0.000000 0.707107 -0.707107 -v 0.011636 -0.146000 0.309560 -vn -0.577350 0.577350 -0.577350 -v 0.008761 -0.146000 0.309560 -vn -0.301511 0.904534 -0.301511 -v 0.008761 -0.146000 0.317060 -vn 0.000000 0.707107 -0.707107 -v -0.028239 -0.146000 0.317060 -vn 0.000000 1.000000 0.000000 -v -0.028239 -0.146000 0.318160 -vn 0.707107 0.707107 0.000000 -v -0.069239 -0.146000 0.303580 -vn 0.301511 0.904534 0.301511 -v -0.069239 -0.146000 0.299560 -vn 0.000000 0.707107 0.707107 -v -0.028239 -0.146000 0.292060 -vn 0.637729 0.770261 0.000004 -v -0.066989 -0.146000 0.320510 -vn 0.552286 0.770262 0.318867 -v -0.066821 -0.146000 0.319885 -vn 0.318873 0.770257 0.552290 -v -0.066364 -0.146000 0.319428 -vn 0.000001 0.770269 0.637719 -v -0.065739 -0.146000 0.319260 -vn -0.318874 0.770258 0.552288 -v -0.065114 -0.146000 0.319428 -vn -0.552288 0.770260 0.318869 -v -0.064656 -0.146000 0.319885 -vn 0.318858 0.770262 -0.552291 -v -0.066364 -0.146000 0.321593 -vn 0.552286 0.770264 -0.318863 -v -0.066821 -0.146000 0.321135 -vn -0.637725 0.770264 0.000004 -v -0.064489 -0.146000 0.320510 -vn 0.000000 1.000000 0.000000 -v -0.028239 -0.146000 0.320930 -vn -0.552288 0.770261 -0.318865 -v -0.064656 -0.146000 0.321135 -vn -0.318858 0.770264 -0.552289 -v -0.065114 -0.146000 0.321593 -vn 0.000001 0.770258 -0.637732 -v -0.065739 -0.146000 0.321760 -vn -0.552286 0.770262 0.318867 -v 0.010344 -0.146000 0.319885 -vn -0.637728 0.770261 0.000004 -v 0.010511 -0.146000 0.320510 -vn 0.000000 1.000000 0.000000 -v 0.011636 -0.146000 0.320930 -vn 0.552287 0.770261 0.318868 -v 0.008179 -0.146000 0.319885 -vn 0.318874 0.770257 0.552289 -v 0.008636 -0.146000 0.319428 -vn -0.000000 0.770270 0.637718 -v 0.009261 -0.146000 0.319260 -vn -0.318873 0.770257 0.552290 -v 0.009886 -0.146000 0.319428 -vn 0.637727 0.770263 0.000004 -v 0.008011 -0.146000 0.320510 -vn -0.552286 0.770264 -0.318863 -v 0.010344 -0.146000 0.321135 -vn -0.318858 0.770262 -0.552291 -v 0.009886 -0.146000 0.321593 -vn -0.000000 0.770258 -0.637732 -v 0.009261 -0.146000 0.321760 -vn 0.318858 0.770263 -0.552290 -v 0.008636 -0.146000 0.321593 -vn 0.552287 0.770263 -0.318864 -v 0.008179 -0.146000 0.321135 -vn 0.637728 0.770261 0.000000 -v -0.085239 -0.146000 0.259100 -vn 0.552286 0.770263 0.318865 -v -0.084904 -0.146000 0.257850 -vn 0.000000 0.770258 -0.637732 -v -0.082739 -0.146000 0.261600 -vn 0.318861 0.770265 -0.552286 -v -0.083989 -0.146000 0.261265 -vn 0.000000 1.000000 0.000000 -v -0.088989 -0.146000 0.274480 -vn 0.552291 0.770261 -0.318862 -v -0.084904 -0.146000 0.260350 -vn -0.318866 0.770260 0.552291 -v -0.081489 -0.146000 0.256935 -vn 0.000000 0.770264 0.637725 -v -0.082739 -0.146000 0.256600 -vn 0.318865 0.770260 0.552291 -v -0.083989 -0.146000 0.256935 -vn -0.552286 0.770263 0.318865 -v -0.080574 -0.146000 0.257850 -vn -0.637728 0.770261 0.000000 -v -0.080239 -0.146000 0.259100 -vn -0.552291 0.770261 -0.318862 -v -0.080574 -0.146000 0.260350 -vn -0.318861 0.770265 -0.552286 -v -0.081489 -0.146000 0.261265 -vn -0.318858 0.770263 0.552291 -v 0.009886 -0.146000 0.287528 -vn -0.552287 0.770264 0.318862 -v 0.010344 -0.146000 0.287985 -vn -0.637728 0.770261 -0.000004 -v 0.010511 -0.146000 0.288610 -vn -0.552296 0.770258 -0.318860 -v 0.010344 -0.146000 0.289235 -vn -0.318864 0.770267 -0.552282 -v 0.009886 -0.146000 0.289693 -vn -0.000000 0.770258 -0.637732 -v 0.009261 -0.146000 0.289860 -vn 0.318864 0.770267 -0.552281 -v 0.008636 -0.146000 0.289693 -vn 0.552287 0.770263 0.318864 -v 0.008179 -0.146000 0.287985 -vn 0.318858 0.770263 0.552290 -v 0.008636 -0.146000 0.287528 -vn -0.000000 0.770258 0.637732 -v 0.009261 -0.146000 0.287360 -vn 0.552286 0.770264 0.318863 -v -0.066821 -0.146000 0.287985 -vn 0.318858 0.770262 0.552291 -v -0.066364 -0.146000 0.287528 -vn 0.000001 0.770258 0.637732 -v -0.065739 -0.146000 0.287360 -vn -0.552298 0.770256 -0.318863 -v -0.064656 -0.146000 0.289235 -vn -0.318865 0.770268 -0.552279 -v -0.065114 -0.146000 0.289693 -vn 0.000001 0.770258 -0.637732 -v -0.065739 -0.146000 0.289860 -vn 0.318864 0.770267 -0.552282 -v -0.066364 -0.146000 0.289693 -vn -0.318858 0.770264 0.552289 -v -0.065114 -0.146000 0.287528 -vn -0.552288 0.770261 0.318865 -v -0.064656 -0.146000 0.287985 -vn -0.637725 0.770264 -0.000004 -v -0.064489 -0.146000 0.288610 -vn 0.000000 1.000000 0.000000 -v -0.088989 -0.146000 0.290960 -vn -0.678874 0.095840 0.727973 -v -0.092000 -0.073412 0.165100 -vn -0.649522 -0.211527 0.730328 -v -0.092000 -0.140981 0.165100 -vn 0.678872 0.095840 0.727975 -v -0.090000 -0.073412 0.165100 -vn 0.649522 -0.211527 0.730327 -v -0.090000 -0.140981 0.165100 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 -0.134897 0.157150 -vn 0.770264 -0.637725 0.000000 -v -0.090000 -0.134562 0.155900 -vn 0.770262 0.552288 -0.318864 -v -0.090000 0.125215 0.078247 -vn 0.770263 0.318866 0.552286 -v -0.090000 0.133688 0.092635 -vn 0.770259 0.552291 0.318866 -v -0.090000 0.132773 0.093550 -vn 0.770262 0.552289 0.318863 -v -0.090000 0.126277 0.111347 -vn 0.737700 0.669353 0.088122 -v -0.090000 0.124938 0.116347 -vn 0.707106 -0.707107 -0.000000 -v -0.090000 0.053938 0.125350 -vn 0.770260 -0.552291 0.318866 -v -0.090000 0.137103 0.093550 -vn 0.678874 0.727973 -0.095840 -v -0.090000 0.144938 0.093247 -vn 0.770264 -0.637725 0.000000 -v -0.090000 0.137438 0.094800 -vn 0.678874 0.727973 0.095840 -v -0.090000 0.144938 0.096347 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 0.137103 0.096050 -vn 0.653227 0.655722 0.378581 -v -0.090000 0.143598 0.101347 -vn 0.770263 -0.318865 -0.552286 -v -0.090000 0.136188 0.096965 -vn 0.653227 0.378582 0.655721 -v -0.090000 0.139938 0.105007 -vn 0.770261 -0.000001 -0.637729 -v -0.090000 0.134938 0.097300 -vn 0.707107 0.183013 0.683013 -v -0.090000 0.134938 0.106347 -vn 0.770264 0.318864 -0.552286 -v -0.090000 0.133688 0.096965 -vn 0.770262 0.318864 0.552288 -v -0.090000 0.129938 0.107687 -vn 0.770262 0.318863 -0.552288 -v -0.090000 0.128875 0.081907 -vn 0.737701 0.088122 -0.669352 -v -0.090000 0.133875 0.083247 -vn 0.770262 -0.000001 0.637728 -v -0.090000 0.134938 0.092300 -vn 0.678875 0.095840 -0.727973 -v -0.090000 0.134938 0.083247 -vn 0.770262 -0.318867 0.552286 -v -0.090000 0.136188 0.092635 -vn 0.653227 0.378582 -0.655721 -v -0.090000 0.139938 0.084587 -vn 0.653227 0.655722 -0.378581 -v -0.090000 0.143598 0.088247 -vn 0.737700 0.669353 -0.088122 -v -0.090000 0.123875 0.073247 -vn 0.770262 -0.318864 0.552288 -v -0.090000 0.048938 0.091390 -vn 0.770262 -0.552288 0.318864 -v -0.090000 0.052598 0.095050 -vn 0.770264 0.637725 -0.000000 -v -0.090000 0.132438 0.094800 -vn 0.737700 -0.669353 0.088122 -v -0.090000 0.053938 0.100050 -vn 0.770260 0.552291 -0.318866 -v -0.090000 0.132773 0.096050 -vn 0.659607 0.744726 -0.101502 -v -0.090000 0.143737 0.157892 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 0.137103 0.157150 -vn 0.770264 -0.637725 0.000000 -v -0.090000 0.137438 0.155900 -vn 0.770260 -0.552291 0.318866 -v -0.090000 0.137103 0.154650 -vn 0.682384 0.435118 -0.587388 -v -0.090000 0.140792 0.153506 -vn 0.659607 0.623987 -0.418997 -v -0.090000 0.142773 0.155358 -vn 0.659607 0.713358 0.236725 -v -0.090000 0.143486 0.160592 -vn 0.662687 0.542691 0.516074 -v -0.090000 0.142073 0.162906 -vn 0.770263 -0.318865 -0.552286 -v -0.090000 0.136188 0.158065 -vn 0.646370 0.224984 0.729100 -v -0.090000 0.138857 0.165100 -vn 0.770261 -0.000001 -0.637729 -v -0.090000 0.134938 0.158400 -vn 0.707107 0.000000 0.707107 -v -0.090000 0.134938 0.165100 -vn 0.770263 0.318864 -0.552286 -v -0.090000 0.133688 0.158065 -vn 0.770260 0.552291 -0.318865 -v -0.090000 0.132773 0.157150 -vn 0.678875 -0.095840 0.727972 -v -0.090000 0.071287 0.165100 -vn 0.653227 -0.378581 0.655722 -v -0.090000 0.066287 0.163760 -vn 0.678874 -0.582523 0.446986 -v -0.090000 0.062627 0.160100 -vn 0.707107 0.707107 0.000000 -v -0.090000 0.124938 0.125350 -vn 0.737700 0.669353 -0.088121 -v -0.090000 0.124938 0.140889 -vn 0.770262 0.552288 -0.318863 -v -0.090000 0.125742 0.143889 -vn 0.770263 -0.318865 0.552286 -v -0.090000 0.136188 0.153735 -vn 0.770261 -0.000001 0.637729 -v -0.090000 0.134938 0.153400 -vn 0.737700 0.410992 -0.535615 -v -0.090000 0.127938 0.146085 -vn 0.770263 0.318864 0.552286 -v -0.090000 0.133688 0.153735 -vn 0.770260 0.552291 0.318865 -v -0.090000 0.132773 0.154650 -vn 0.770264 0.637725 -0.000000 -v -0.090000 0.132438 0.155900 -vn 0.678874 -0.678363 0.280987 -v -0.090000 0.055277 0.147370 -vn 0.678874 -0.727973 0.095839 -v -0.090000 0.053938 0.142370 -vn 0.682384 0.435118 0.587388 -v -0.090000 0.140792 0.016594 -vn 0.770260 -0.552290 -0.318866 -v -0.090000 0.137103 0.015450 -vn 0.659607 0.623988 0.418996 -v -0.090000 0.142773 0.014742 -vn 0.770264 -0.637725 0.000000 -v -0.090000 0.137438 0.014200 -vn 0.659607 0.744726 0.101502 -v -0.090000 0.143737 0.012208 -vn 0.770260 -0.552291 0.318865 -v -0.090000 0.137103 0.012950 -vn 0.659607 0.713358 -0.236725 -v -0.090000 0.143486 0.009508 -vn 0.662687 0.542691 -0.516074 -v -0.090000 0.142073 0.007194 -vn 0.770263 -0.318865 0.552286 -v -0.090000 0.136188 0.012035 -vn 0.770261 -0.000001 0.637729 -v -0.090000 0.134938 0.011700 -vn 1.000000 0.000000 0.000000 -v -0.090000 0.134938 0.008350 -vn 0.770263 0.318864 0.552286 -v -0.090000 0.133688 0.012035 -vn 1.000000 0.000000 -0.000000 -v -0.090000 -0.001062 0.008350 -vn 0.770260 0.552291 0.318865 -v -0.090000 0.132773 0.012950 -vn 0.707107 0.707107 0.000000 -v -0.090000 0.123875 0.054500 -vn 1.000000 0.000000 0.000000 -v -0.090000 -0.001062 0.054500 -vn 0.737701 0.669352 0.088123 -v -0.090000 0.123875 0.029824 -vn 0.770261 0.552289 0.318865 -v -0.090000 0.124679 0.026824 -vn 0.770264 0.637725 -0.000000 -v -0.090000 0.132438 0.014200 -vn 0.770260 0.552290 -0.318866 -v -0.090000 0.132773 0.015450 -vn 0.770263 0.318864 -0.552286 -v -0.090000 0.133688 0.016365 -vn 0.770261 -0.000001 -0.637729 -v -0.090000 0.134938 0.016700 -vn 0.737700 0.410993 0.535615 -v -0.090000 0.126875 0.024628 -vn 0.770263 -0.318865 -0.552286 -v -0.090000 0.136188 0.016365 -vn 0.672718 -0.490629 0.553835 -v -0.090000 -0.143693 0.163385 -vn 0.770260 0.552291 -0.318866 -v -0.090000 -0.139227 0.157150 -vn 0.770260 -0.552291 0.318865 -v -0.090000 -0.134897 0.154650 -vn 0.770264 -0.318864 0.552286 -v -0.090000 -0.135812 0.153735 -vn 0.707097 0.707117 0.000000 -v -0.090000 -0.056062 0.125350 -vn 0.770261 0.000001 0.637729 -v -0.090000 -0.137062 0.153400 -vn 0.770263 0.318865 0.552286 -v -0.090000 -0.138312 0.153735 -vn 0.770263 0.318865 -0.552286 -v -0.090000 -0.138312 0.158065 -vn 0.770261 0.000001 -0.637729 -v -0.090000 -0.137062 0.158400 -vn 0.770264 -0.318864 -0.552286 -v -0.090000 -0.135812 0.158065 -vn 0.653227 0.378581 0.655722 -v -0.090000 -0.068412 0.163760 -vn 0.678874 0.582523 0.446986 -v -0.090000 -0.064751 0.160100 -vn 0.678874 0.678363 0.280987 -v -0.090000 -0.057402 0.147370 -vn 0.678874 0.727973 0.095839 -v -0.090000 -0.056062 0.142370 -vn 0.770262 -0.552288 -0.318863 -v -0.090000 -0.127732 0.143966 -vn 0.737700 -0.410992 -0.535615 -v -0.090000 -0.129562 0.145796 -vn 0.678874 -0.446987 -0.582523 -v -0.090000 -0.143892 0.154070 -vn 0.770260 0.552291 0.318865 -v -0.090000 -0.139227 0.154650 -vn 0.770264 0.637725 -0.000000 -v -0.090000 -0.139562 0.155900 -vn 0.737700 -0.088122 0.669353 -v -0.090000 0.043938 0.090050 -vn 0.707107 0.000000 0.707107 -v -0.090000 -0.001062 0.090050 -vn 0.737700 0.088122 0.669353 -v -0.090000 -0.046062 0.090050 -vn 0.770260 -0.552291 0.318866 -v -0.090000 -0.134897 0.093550 -vn 0.770261 0.318864 0.552289 -v -0.090000 -0.051062 0.091390 -vn 0.770264 -0.637725 0.000000 -v -0.090000 -0.134562 0.094800 -vn 0.770262 0.552288 0.318863 -v -0.090000 -0.054723 0.095050 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 -0.134897 0.096050 -vn 0.770262 -0.318864 -0.552288 -v -0.090000 -0.131000 0.081907 -vn 0.770262 -0.552288 -0.318864 -v -0.090000 -0.127340 0.078247 -vn 0.737700 -0.669352 -0.088122 -v -0.090000 -0.126000 0.073247 -vn 0.737700 -0.669353 -0.088121 -v -0.090000 -0.127062 0.141466 -vn 0.707107 -0.707107 0.000000 -v -0.090000 -0.127062 0.125350 -vn 0.737701 0.669352 0.088122 -v -0.090000 -0.056062 0.100050 -vn 0.770261 0.000001 -0.637729 -v -0.090000 -0.137062 0.097300 -vn 0.770264 -0.318864 -0.552286 -v -0.090000 -0.135812 0.096965 -vn 0.770262 -0.318864 0.552288 -v -0.090000 -0.132062 0.107687 -vn 0.770262 -0.552289 0.318864 -v -0.090000 -0.128402 0.111347 -vn 0.737700 -0.669353 0.088122 -v -0.090000 -0.127062 0.116347 -vn 0.770263 -0.318866 0.552286 -v -0.090000 -0.135812 0.092635 -vn 0.770264 0.637725 -0.000000 -v -0.090000 -0.139562 0.094800 -vn 0.770260 0.552291 -0.318866 -v -0.090000 -0.139227 0.096050 -vn 0.665719 -0.527645 0.527646 -v -0.090000 -0.144133 0.103418 -vn 0.770263 0.318865 -0.552286 -v -0.090000 -0.138312 0.096965 -vn 0.665719 -0.285560 0.689401 -v -0.090000 -0.140889 0.105586 -vn 0.714546 -0.158860 0.681314 -v -0.090000 -0.137062 0.106347 -vn 0.770260 0.552291 0.318865 -v -0.090000 -0.139227 0.093550 -vn 0.653227 -0.655722 -0.378581 -v -0.090000 -0.145723 0.088247 -vn 0.770262 0.318867 0.552286 -v -0.090000 -0.138312 0.092635 -vn 0.666615 -0.355462 -0.655189 -v -0.090000 -0.142062 0.084587 -vn 0.770262 0.000001 0.637728 -v -0.090000 -0.137062 0.092300 -vn 0.678875 -0.095840 -0.727973 -v -0.090000 -0.137062 0.083247 -vn 0.737701 -0.088122 -0.669352 -v -0.090000 -0.136000 0.083247 -vn 0.707108 0.000000 -0.707106 -v -0.090000 0.134938 0.005000 -vn 0.646370 0.224984 -0.729100 -v -0.090000 0.138857 0.005000 -vn 1.000000 0.000000 -0.000000 -v -0.090000 -0.143312 0.008350 -vn 0.672719 -0.490629 -0.553835 -v -0.090000 -0.143693 0.006715 -vn 0.649522 -0.211527 -0.730327 -v -0.090000 -0.140981 0.005000 -vn 0.653227 -0.655721 0.378582 -v -0.090000 -0.145723 0.014200 -vn 0.653226 -0.757163 0.000000 -v -0.090000 -0.146392 0.011700 -vn 0.662776 -0.666513 -0.341305 -v -0.090000 -0.145723 0.009200 -vn 0.770260 -0.552290 -0.318865 -v -0.090000 -0.134897 0.015450 -vn 0.770264 -0.637725 0.000000 -v -0.090000 -0.134562 0.014200 -vn 0.770260 -0.552291 0.318865 -v -0.090000 -0.134897 0.012950 -vn 0.707107 -0.707107 0.000000 -v -0.090000 -0.126000 0.054500 -vn 0.770264 0.637725 -0.000000 -v -0.090000 -0.139562 0.014200 -vn 0.770260 0.552290 -0.318866 -v -0.090000 -0.139227 0.015450 -vn 0.678874 -0.446986 0.582523 -v -0.090000 -0.143892 0.016030 -vn 0.770263 0.318865 -0.552286 -v -0.090000 -0.138312 0.016365 -vn 0.737700 -0.410993 0.535615 -v -0.090000 -0.128500 0.024917 -vn 0.770261 0.000001 -0.637729 -v -0.090000 -0.137062 0.016700 -vn 0.770260 0.552291 0.318865 -v -0.090000 -0.139227 0.012950 -vn 0.770264 -0.318864 0.552286 -v -0.090000 -0.135812 0.012035 -vn 0.770261 0.000001 0.637729 -v -0.090000 -0.137062 0.011700 -vn 0.770263 0.318865 0.552286 -v -0.090000 -0.138312 0.012035 -vn 0.737701 -0.669352 0.088123 -v -0.090000 -0.126000 0.029247 -vn 0.770261 -0.552289 0.318864 -v -0.090000 -0.126670 0.026747 -vn 0.770263 -0.318864 -0.552286 -v -0.090000 -0.135812 0.016365 -vn 0.665719 -0.689402 0.285559 -v -0.090000 -0.146301 0.100174 -vn 0.685697 -0.724383 0.071345 -v -0.090000 -0.147062 0.096347 -vn 0.678874 -0.727973 -0.095840 -v -0.090000 -0.147062 0.093247 -vn 0.653226 -0.757163 0.000000 -v -0.090000 -0.146392 0.158400 -vn 0.653228 -0.655721 -0.378581 -v -0.090000 -0.145723 0.155900 -vn 0.662776 -0.666513 0.341305 -v -0.090000 -0.145723 0.160900 -vn 0.707107 0.000000 -0.707106 -v -0.090000 -0.001062 0.005000 -vn -0.770264 0.637725 0.000000 -v -0.092000 -0.139562 0.155900 -vn -0.770260 0.552291 0.318865 -v -0.092000 -0.139227 0.154650 -vn -0.707108 -0.353551 -0.612372 -v -0.092000 -0.143312 0.153735 -vn -0.770263 0.318865 0.552286 -v -0.092000 -0.138312 0.153735 -vn -0.737700 -0.410992 -0.535616 -v -0.092000 -0.129562 0.145796 -vn -0.653227 0.378581 0.655722 -v -0.092000 -0.068412 0.163760 -vn -0.678875 0.582523 0.446986 -v -0.092000 -0.064751 0.160100 -vn -0.770263 0.318865 -0.552286 -v -0.092000 -0.138312 0.158065 -vn -0.672719 -0.490629 0.553835 -v -0.092000 -0.143693 0.163385 -vn -0.770260 0.552291 -0.318865 -v -0.092000 -0.139227 0.157150 -vn -0.770260 -0.552291 0.318865 -v -0.092000 -0.134897 0.154650 -vn -0.770262 -0.552289 -0.318863 -v -0.092000 -0.127732 0.143966 -vn -0.770263 -0.318864 0.552286 -v -0.092000 -0.135812 0.153735 -vn -0.770261 0.000001 0.637729 -v -0.092000 -0.137062 0.153400 -vn -0.707107 0.707107 -0.000000 -v -0.092000 -0.056062 0.125350 -vn -0.707107 -0.707107 0.000000 -v -0.092000 -0.127062 0.125350 -vn -0.737700 -0.669353 -0.088121 -v -0.092000 -0.127062 0.141466 -vn -0.678875 0.678363 0.280987 -v -0.092000 -0.057402 0.147370 -vn -0.678874 0.727973 0.095839 -v -0.092000 -0.056062 0.142370 -vn -0.770264 -0.637725 0.000000 -v -0.092000 -0.134562 0.155900 -vn -0.770260 -0.552291 -0.318865 -v -0.092000 -0.134897 0.157150 -vn -0.770263 -0.318864 -0.552286 -v -0.092000 -0.135812 0.158065 -vn -0.770261 0.000001 -0.637729 -v -0.092000 -0.137062 0.158400 -vn -0.678873 -0.446985 -0.582525 -v -0.092000 -0.143892 0.154070 -vn -0.653228 -0.655721 -0.378581 -v -0.092000 -0.145723 0.155900 -vn -0.653226 -0.757163 -0.000000 -v -0.092000 -0.146392 0.158400 -vn -0.662776 -0.666513 0.341305 -v -0.092000 -0.145723 0.160900 -vn -0.770262 -0.318864 0.552288 -v -0.092000 -0.132062 0.107687 -vn -0.770262 -0.552289 0.318864 -v -0.092000 -0.128402 0.111347 -vn -0.770264 -0.318864 -0.552286 -v -0.092000 -0.135812 0.096965 -vn -0.770260 -0.552291 -0.318866 -v -0.092000 -0.134897 0.096050 -vn -1.000000 -0.000000 -0.000000 -v -0.092000 -0.001062 0.054500 -vn -0.770262 0.318864 0.552288 -v -0.092000 -0.051062 0.091390 -vn -0.770264 -0.637725 0.000000 -v -0.092000 -0.134562 0.094800 -vn -0.770260 -0.552291 0.318865 -v -0.092000 -0.134897 0.093550 -vn -0.714546 -0.158860 0.681314 -v -0.092000 -0.137062 0.106347 -vn -0.770261 0.000001 -0.637729 -v -0.092000 -0.137062 0.097300 -vn -0.665719 -0.285560 0.689401 -v -0.092000 -0.140889 0.105586 -vn -0.770263 0.318865 -0.552286 -v -0.092000 -0.138312 0.096965 -vn -0.665719 -0.527645 0.527645 -v -0.092000 -0.144133 0.103418 -vn -0.770260 0.552291 -0.318865 -v -0.092000 -0.139227 0.096050 -vn -0.770264 0.637725 0.000000 -v -0.092000 -0.139562 0.094800 -vn -0.615228 -0.567442 -0.547270 -v -0.092000 -0.143529 0.085620 -vn -0.770260 0.552291 0.318865 -v -0.092000 -0.139227 0.093550 -vn -0.669775 -0.314685 -0.672589 -v -0.092000 -0.142062 0.084587 -vn -0.770263 0.318867 0.552286 -v -0.092000 -0.138312 0.092635 -vn -0.678874 -0.095840 -0.727973 -v -0.092000 -0.137062 0.083247 -vn -0.770263 0.000001 0.637727 -v -0.092000 -0.137062 0.092300 -vn -0.737700 -0.088122 -0.669353 -v -0.092000 -0.136000 0.083247 -vn -0.770263 -0.318866 0.552286 -v -0.092000 -0.135812 0.092635 -vn -0.770261 -0.318864 -0.552289 -v -0.092000 -0.131000 0.081907 -vn -0.770262 -0.552288 -0.318865 -v -0.092000 -0.127340 0.078247 -vn -0.737700 -0.669352 -0.088122 -v -0.092000 -0.126000 0.073247 -vn -0.737700 -0.669353 0.088122 -v -0.092000 -0.127062 0.116347 -vn -0.737700 0.669352 0.088122 -v -0.092000 -0.056062 0.100050 -vn -0.770262 0.552289 0.318864 -v -0.092000 -0.054723 0.095050 -vn -0.665719 -0.689402 0.285559 -v -0.092000 -0.146301 0.100174 -vn -0.685697 -0.724383 0.071345 -v -0.092000 -0.147062 0.096347 -vn -0.678874 -0.727973 -0.095840 -v -0.092000 -0.147062 0.093247 -vn -0.652857 -0.659976 -0.371765 -v -0.092000 -0.145723 0.088247 -vn -0.678874 -0.446986 0.582523 -v -0.092000 -0.143892 0.016030 -vn -0.770264 0.637725 0.000000 -v -0.092000 -0.139562 0.014200 -vn -1.000000 -0.000000 0.000000 -v -0.092000 -0.143312 0.008350 -vn -0.770260 0.552291 0.318865 -v -0.092000 -0.139227 0.012950 -vn -0.770264 -0.637725 0.000000 -v -0.092000 -0.134562 0.014200 -vn -0.770260 -0.552290 -0.318866 -v -0.092000 -0.134897 0.015450 -vn -0.770261 -0.552289 0.318864 -v -0.092000 -0.126670 0.026747 -vn -0.737701 -0.669352 0.088123 -v -0.092000 -0.126000 0.029247 -vn -0.707107 -0.707107 0.000000 -v -0.092000 -0.126000 0.054500 -vn -0.770263 0.318865 0.552286 -v -0.092000 -0.138312 0.012035 -vn -0.770261 0.000001 0.637729 -v -0.092000 -0.137062 0.011700 -vn -1.000000 -0.000000 0.000000 -v -0.092000 -0.001062 0.008350 -vn -0.770263 -0.318864 0.552286 -v -0.092000 -0.135812 0.012035 -vn -0.770260 -0.552291 0.318865 -v -0.092000 -0.134897 0.012950 -vn -0.770263 -0.318864 -0.552286 -v -0.092000 -0.135812 0.016365 -vn -0.770260 0.000002 -0.637731 -v -0.092000 -0.137062 0.016700 -vn -0.770263 0.318865 -0.552286 -v -0.092000 -0.138312 0.016365 -vn -0.737701 -0.410993 0.535615 -v -0.092000 -0.128500 0.024917 -vn -0.770260 0.552290 -0.318866 -v -0.092000 -0.139227 0.015450 -vn -0.653227 -0.655721 0.378582 -v -0.092000 -0.145723 0.014200 -vn -0.653226 -0.757163 0.000000 -v -0.092000 -0.146392 0.011700 -vn -0.662776 -0.666513 -0.341305 -v -0.092000 -0.145723 0.009200 -vn -0.672719 -0.490629 -0.553835 -v -0.092000 -0.143693 0.006715 -vn -0.770264 -0.637725 0.000000 -v -0.092000 0.137438 0.014200 -vn -0.659607 0.744726 0.101502 -v -0.092000 0.143737 0.012208 -vn -0.770260 -0.552291 0.318865 -v -0.092000 0.137103 0.012950 -vn -0.659607 0.713358 -0.236725 -v -0.092000 0.143486 0.009508 -vn -0.770263 -0.318865 0.552286 -v -0.092000 0.136188 0.012035 -vn -0.662687 0.542691 -0.516074 -v -0.092000 0.142073 0.007194 -vn -0.770261 -0.000001 0.637729 -v -0.092000 0.134938 0.011700 -vn -1.000000 -0.000000 -0.000000 -v -0.092000 0.134938 0.008350 -vn -0.770260 -0.552290 -0.318866 -v -0.092000 0.137103 0.015450 -vn -0.682384 0.435118 0.587388 -v -0.092000 0.140792 0.016594 -vn -0.659607 0.623988 0.418996 -v -0.092000 0.142773 0.014742 -vn -0.770260 0.552290 -0.318866 -v -0.092000 0.132773 0.015450 -vn -0.770264 0.637725 0.000000 -v -0.092000 0.132438 0.014200 -vn -0.770260 0.552291 0.318865 -v -0.092000 0.132773 0.012950 -vn -0.770263 0.318864 0.552286 -v -0.092000 0.133688 0.012035 -vn -0.770261 0.552289 0.318864 -v -0.092000 0.124679 0.026824 -vn -0.737701 0.669352 0.088123 -v -0.092000 0.123875 0.029824 -vn -0.707107 0.707107 -0.000000 -v -0.092000 0.123875 0.054500 -vn -0.770263 0.318864 -0.552286 -v -0.092000 0.133688 0.016365 -vn -0.737700 0.410993 0.535615 -v -0.092000 0.126875 0.024628 -vn -0.770261 -0.000001 -0.637729 -v -0.092000 0.134938 0.016700 -vn -0.770263 -0.318865 -0.552286 -v -0.092000 0.136188 0.016365 -vn -0.737700 0.088122 0.669352 -v -0.092000 -0.046062 0.090050 -vn -0.707107 -0.000000 0.707107 -v -0.092000 -0.001062 0.090050 -vn -0.707107 -0.707107 -0.000000 -v -0.092000 0.053938 0.125350 -vn -0.737700 0.669353 0.088122 -v -0.092000 0.124938 0.116347 -vn -0.770262 0.552289 0.318863 -v -0.092000 0.126277 0.111347 -vn -0.770261 -0.318864 0.552289 -v -0.092000 0.048938 0.091390 -vn -0.770262 -0.552289 0.318864 -v -0.092000 0.052598 0.095050 -vn -0.770264 0.637725 0.000000 -v -0.092000 0.132438 0.094800 -vn -0.737700 -0.669352 0.088122 -v -0.092000 0.053938 0.100050 -vn -0.770260 0.552291 -0.318866 -v -0.092000 0.132773 0.096050 -vn -0.770261 0.318865 -0.552289 -v -0.092000 0.128875 0.081907 -vn -0.770262 0.552288 -0.318864 -v -0.092000 0.125215 0.078247 -vn -0.770263 0.318866 0.552286 -v -0.092000 0.133688 0.092635 -vn -0.770260 0.552291 0.318865 -v -0.092000 0.132773 0.093550 -vn -0.737700 -0.088122 0.669353 -v -0.092000 0.043938 0.090050 -vn -0.737700 0.669353 -0.088122 -v -0.092000 0.123875 0.073247 -vn -0.770264 0.318864 -0.552286 -v -0.092000 0.133688 0.096965 -vn -0.770262 0.318864 0.552288 -v -0.092000 0.129938 0.107687 -vn -0.770261 -0.000001 -0.637729 -v -0.092000 0.134938 0.097300 -vn -0.707107 0.183013 0.683013 -v -0.092000 0.134938 0.106347 -vn -0.770263 -0.318865 -0.552286 -v -0.092000 0.136188 0.096965 -vn -0.653227 0.378582 0.655721 -v -0.092000 0.139938 0.105007 -vn -0.770260 -0.552291 -0.318866 -v -0.092000 0.137103 0.096050 -vn -0.653227 0.655722 0.378581 -v -0.092000 0.143598 0.101347 -vn -0.770264 -0.637725 0.000000 -v -0.092000 0.137438 0.094800 -vn -0.678874 0.727973 0.095840 -v -0.092000 0.144938 0.096347 -vn -0.678874 0.727973 -0.095840 -v -0.092000 0.144938 0.093247 -vn -0.770260 -0.552291 0.318865 -v -0.092000 0.137103 0.093550 -vn -0.653227 0.655722 -0.378581 -v -0.092000 0.143598 0.088247 -vn -0.770263 -0.318867 0.552286 -v -0.092000 0.136188 0.092635 -vn -0.653226 0.378582 -0.655722 -v -0.092000 0.139938 0.084587 -vn -0.770263 -0.000001 0.637727 -v -0.092000 0.134938 0.092300 -vn -0.678874 0.095840 -0.727973 -v -0.092000 0.134938 0.083247 -vn -0.737700 0.088122 -0.669353 -v -0.092000 0.133875 0.083247 -vn -0.737700 0.410992 -0.535615 -v -0.092000 0.127938 0.146085 -vn -0.770262 0.552288 -0.318863 -v -0.092000 0.125742 0.143889 -vn -0.737700 0.669353 -0.088121 -v -0.092000 0.124938 0.140889 -vn -0.707107 0.707107 0.000000 -v -0.092000 0.124938 0.125350 -vn -0.770263 -0.318865 -0.552286 -v -0.092000 0.136188 0.158065 -vn -0.770261 -0.000001 -0.637729 -v -0.092000 0.134938 0.158400 -vn -0.707107 -0.000000 0.707107 -v -0.092000 0.134938 0.165100 -vn -0.770264 0.318864 -0.552286 -v -0.092000 0.133688 0.158065 -vn -0.678874 -0.095840 0.727973 -v -0.092000 0.071287 0.165100 -vn -0.770260 0.552291 -0.318865 -v -0.092000 0.132773 0.157150 -vn -0.770264 0.637725 0.000000 -v -0.092000 0.132438 0.155900 -vn -0.653227 -0.378581 0.655722 -v -0.092000 0.066287 0.163760 -vn -0.678874 -0.582523 0.446986 -v -0.092000 0.062627 0.160100 -vn -0.678874 -0.678363 0.280987 -v -0.092000 0.055277 0.147370 -vn -0.770260 0.552291 0.318865 -v -0.092000 0.132773 0.154650 -vn -0.678874 -0.727973 0.095839 -v -0.092000 0.053938 0.142370 -vn -0.682384 0.435118 -0.587388 -v -0.092000 0.140792 0.153506 -vn -0.770261 -0.000001 0.637729 -v -0.092000 0.134938 0.153400 -vn -0.770264 0.318864 0.552286 -v -0.092000 0.133688 0.153735 -vn -0.770263 -0.318865 0.552286 -v -0.092000 0.136188 0.153735 -vn -0.770260 -0.552291 0.318865 -v -0.092000 0.137103 0.154650 -vn -0.659607 0.623987 -0.418996 -v -0.092000 0.142773 0.155358 -vn -0.770264 -0.637725 0.000000 -v -0.092000 0.137438 0.155900 -vn -0.659607 0.744726 -0.101502 -v -0.092000 0.143737 0.157892 -vn -0.770260 -0.552291 -0.318865 -v -0.092000 0.137103 0.157150 -vn -0.646370 0.224984 0.729100 -v -0.092000 0.138857 0.165100 -vn -0.662687 0.542691 0.516074 -v -0.092000 0.142073 0.162906 -vn -0.659607 0.713358 0.236725 -v -0.092000 0.143486 0.160592 -vn -0.646370 0.224984 -0.729101 -v -0.092000 0.138857 0.005000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 0.134938 0.005000 -vn -0.707108 -0.000000 -0.707106 -v -0.092000 -0.001062 0.005000 -vn -0.649522 -0.211527 -0.730327 -v -0.092000 -0.140981 0.005000 -vn -0.770261 -0.552288 -0.318867 -v -0.092000 0.138165 0.330850 -vn -0.658993 0.720674 0.215306 -v -0.092000 0.145518 0.332666 -vn -0.770264 -0.637725 0.000000 -v -0.092000 0.138500 0.329600 -vn -0.654973 0.741583 -0.145138 -v -0.092000 0.145666 0.330173 -vn -0.770259 -0.552293 0.318864 -v -0.092000 0.138165 0.328350 -vn -0.679842 0.616655 -0.396928 -v -0.092000 0.144589 0.327919 -vn -0.770266 -0.318862 0.552284 -v -0.092000 0.137250 0.327435 -vn -0.727260 0.562235 -0.393680 -v -0.092000 0.127170 0.307159 -vn -0.770258 -0.000001 0.637732 -v -0.092000 0.136000 0.327100 -vn -0.770264 -0.000001 -0.637725 -v -0.092000 0.136000 0.332100 -vn -0.684274 0.076380 0.725214 -v -0.092000 0.136000 0.339600 -vn -0.770261 -0.318867 -0.552288 -v -0.092000 0.137250 0.331765 -vn -0.663084 0.305044 0.683569 -v -0.092000 0.140075 0.338732 -vn -0.663084 0.557131 0.499925 -v -0.092000 0.143443 0.336279 -vn -0.770261 0.552288 -0.318867 -v -0.092000 0.133835 0.330850 -vn -0.770264 0.637726 0.000000 -v -0.092000 0.133500 0.329600 -vn -0.770262 -0.637728 0.000000 -v -0.092000 -0.133500 0.329600 -vn -0.770258 -0.552293 0.318864 -v -0.092000 -0.133835 0.328350 -vn -0.684274 -0.076380 0.725214 -v -0.092000 -0.136000 0.339600 -vn -0.770261 -0.552288 -0.318867 -v -0.092000 -0.133835 0.330850 -vn -0.770261 0.318866 -0.552288 -v -0.092000 0.134750 0.331765 -vn -0.770261 0.552288 0.318867 -v -0.092000 -0.138165 0.257850 -vn -0.770261 0.318867 0.552288 -v -0.092000 -0.137250 0.256935 -vn -0.663084 -0.305043 -0.683570 -v -0.092000 -0.140075 0.249968 -vn -0.684274 -0.076380 -0.725214 -v -0.092000 -0.136000 0.249100 -vn -0.684273 0.076380 -0.725214 -v -0.092000 0.136000 0.249100 -vn -0.770260 0.552289 0.318867 -v -0.092000 0.133835 0.257850 -vn -0.770261 -0.318866 -0.552288 -v -0.092000 -0.134750 0.331765 -vn -0.770264 0.000001 -0.637725 -v -0.092000 -0.136000 0.332100 -vn -0.663084 -0.305044 0.683570 -v -0.092000 -0.140075 0.338732 -vn -0.770261 0.318867 -0.552288 -v -0.092000 -0.137250 0.331765 -vn -0.663084 -0.557131 0.499925 -v -0.092000 -0.143443 0.336279 -vn -0.770261 0.552288 -0.318867 -v -0.092000 -0.138165 0.330850 -vn -0.658993 -0.720674 0.215306 -v -0.092000 -0.145518 0.332666 -vn -0.770264 0.637725 0.000000 -v -0.092000 -0.138500 0.329600 -vn -0.770266 0.318862 0.552284 -v -0.092000 -0.137250 0.327435 -vn -0.727261 -0.562235 -0.393680 -v -0.092000 -0.127170 0.307159 -vn -0.770259 0.552293 0.318864 -v -0.092000 -0.138165 0.328350 -vn -0.679842 -0.616655 -0.396928 -v -0.092000 -0.144589 0.327919 -vn -0.654973 -0.741583 -0.145138 -v -0.092000 -0.145666 0.330173 -vn -0.727260 -0.562235 0.393680 -v -0.092000 -0.127170 0.281541 -vn -0.770266 0.318862 -0.552284 -v -0.092000 -0.137250 0.261265 -vn -0.679842 -0.616655 0.396928 -v -0.092000 -0.144589 0.260781 -vn -0.770259 0.552293 -0.318864 -v -0.092000 -0.138165 0.260350 -vn -0.654973 -0.741583 0.145138 -v -0.092000 -0.145666 0.258527 -vn -0.770264 0.637725 0.000000 -v -0.092000 -0.138500 0.259100 -vn -0.658994 -0.720674 -0.215306 -v -0.092000 -0.145518 0.256034 -vn -0.663083 -0.557130 -0.499926 -v -0.092000 -0.143443 0.252421 -vn -0.770264 -0.637725 0.000000 -v -0.092000 0.138500 0.259100 -vn -0.658994 0.720674 -0.215306 -v -0.092000 0.145518 0.256034 -vn -0.770261 -0.552288 0.318867 -v -0.092000 0.138165 0.257850 -vn -0.663083 0.557130 -0.499926 -v -0.092000 0.143443 0.252421 -vn -0.770261 -0.318867 0.552288 -v -0.092000 0.137250 0.256935 -vn -0.663084 0.305043 -0.683570 -v -0.092000 0.140075 0.249968 -vn -0.770264 -0.000001 0.637725 -v -0.092000 0.136000 0.256600 -vn -0.770262 0.318866 0.552288 -v -0.092000 0.134750 0.256935 -vn -0.770262 0.552290 0.318862 -v -0.092000 0.133835 0.328350 -vn -0.748360 -0.623291 -0.226859 -v -0.092000 -0.126302 0.305655 -vn -0.770266 -0.318861 0.552284 -v -0.092000 -0.134750 0.327435 -vn -0.770258 0.000001 0.637732 -v -0.092000 -0.136000 0.327100 -vn -0.748361 -0.623291 0.226859 -v -0.092000 -0.126302 0.283045 -vn -0.727260 -0.683750 0.059820 -v -0.092000 -0.126000 0.284755 -vn -0.727260 -0.683750 -0.059820 -v -0.092000 -0.126000 0.303945 -vn -0.770266 -0.318862 -0.552284 -v -0.092000 0.137250 0.261265 -vn -0.727261 0.562235 0.393680 -v -0.092000 0.127170 0.281541 -vn -0.770259 -0.552293 -0.318864 -v -0.092000 0.138165 0.260350 -vn -0.679842 0.616655 0.396928 -v -0.092000 0.144589 0.260781 -vn -0.654973 0.741583 0.145138 -v -0.092000 0.145666 0.258527 -vn -0.727260 0.683750 0.059820 -v -0.092000 0.126000 0.284755 -vn -0.748361 0.623291 0.226859 -v -0.092000 0.126302 0.283045 -vn -0.770268 -0.637721 0.000000 -v -0.092000 -0.133500 0.259100 -vn -0.770264 0.000001 0.637725 -v -0.092000 -0.136000 0.256600 -vn -0.770261 -0.318866 0.552288 -v -0.092000 -0.134750 0.256935 -vn -0.770260 -0.552289 0.318867 -v -0.092000 -0.133835 0.257850 -vn -0.770264 0.637726 0.000000 -v -0.092000 0.133500 0.259100 -vn -0.770259 0.552293 -0.318864 -v -0.092000 0.133835 0.260350 -vn -0.770266 0.318861 -0.552284 -v -0.092000 0.134750 0.261265 -vn -0.770258 -0.000001 -0.637732 -v -0.092000 0.136000 0.261600 -vn -0.770266 0.318861 0.552284 -v -0.092000 0.134750 0.327435 -vn -0.770259 -0.552293 -0.318864 -v -0.092000 -0.133835 0.260350 -vn -0.770266 -0.318861 -0.552284 -v -0.092000 -0.134750 0.261265 -vn -0.770258 0.000001 -0.637732 -v -0.092000 -0.136000 0.261600 -vn -0.748360 0.623291 -0.226859 -v -0.092000 0.126302 0.305655 -vn -0.727261 0.683750 -0.059820 -v -0.092000 0.126000 0.303945 -vn 0.770261 0.552288 0.318867 -v -0.090000 0.133835 0.257850 -vn 0.770255 0.000001 -0.637736 -v -0.090000 -0.136000 0.261600 -vn 0.770259 0.318867 0.552290 -v -0.090000 0.134750 0.256935 -vn 0.770265 -0.318862 -0.552286 -v -0.090000 -0.134750 0.261265 -vn 0.770261 -0.000001 0.637729 -v -0.090000 0.136000 0.256600 -vn 0.770259 -0.552293 -0.318864 -v -0.090000 -0.133835 0.260350 -vn 0.770264 -0.637725 0.000000 -v -0.090000 -0.133500 0.259100 -vn 0.770261 -0.552288 -0.318867 -v -0.090000 -0.133835 0.330850 -vn 0.770255 -0.000001 0.637736 -v -0.090000 0.136000 0.327100 -vn 0.770260 -0.318867 -0.552290 -v -0.090000 -0.134750 0.331765 -vn 0.770264 0.318862 0.552286 -v -0.090000 0.134750 0.327435 -vn 0.770261 0.000001 -0.637729 -v -0.090000 -0.136000 0.332100 -vn 0.770258 0.552293 0.318864 -v -0.090000 0.133835 0.328350 -vn 0.770264 0.637725 0.000000 -v -0.090000 0.133500 0.329600 -vn 0.770261 0.552288 -0.318867 -v -0.090000 -0.138165 0.330850 -vn 0.658993 -0.720674 0.215306 -v -0.090000 -0.145518 0.332666 -vn 0.770264 0.637725 0.000000 -v -0.090000 -0.138500 0.329600 -vn 0.654973 -0.741583 -0.145138 -v -0.090000 -0.145666 0.330173 -vn 0.770259 0.552293 0.318864 -v -0.090000 -0.138165 0.328350 -vn 0.679842 -0.616655 -0.396928 -v -0.090000 -0.144589 0.327919 -vn 0.770266 0.318862 0.552284 -v -0.090000 -0.137250 0.327435 -vn 0.727260 -0.562235 -0.393680 -v -0.090000 -0.127170 0.307159 -vn 0.770258 0.000001 0.637732 -v -0.090000 -0.136000 0.327100 -vn 0.770264 -0.637725 0.000000 -v -0.090000 0.138500 0.329600 -vn 0.658993 0.720674 0.215306 -v -0.090000 0.145518 0.332666 -vn 0.770261 -0.552288 -0.318867 -v -0.090000 0.138165 0.330850 -vn 0.663084 0.557131 0.499925 -v -0.090000 0.143443 0.336279 -vn 0.770261 -0.318867 -0.552288 -v -0.090000 0.137250 0.331765 -vn 0.663085 0.305044 0.683570 -v -0.090000 0.140075 0.338732 -vn 0.770264 -0.000001 -0.637725 -v -0.090000 0.136000 0.332100 -vn 0.684274 0.076380 0.725214 -v -0.090000 0.136000 0.339600 -vn 0.684274 -0.076380 -0.725214 -v -0.090000 -0.136000 0.249100 -vn 0.684275 0.076380 -0.725213 -v -0.090000 0.136000 0.249100 -vn 0.770261 -0.552288 0.318868 -v -0.090000 -0.133835 0.257850 -vn 0.770264 0.637725 0.000000 -v -0.090000 -0.138500 0.259100 -vn 0.658993 -0.720674 -0.215306 -v -0.090000 -0.145518 0.256034 -vn 0.770261 0.552288 0.318868 -v -0.090000 -0.138165 0.257850 -vn 0.663084 -0.557130 -0.499925 -v -0.090000 -0.143443 0.252421 -vn 0.770260 0.318867 0.552289 -v -0.090000 -0.137250 0.256935 -vn 0.663085 -0.305043 -0.683569 -v -0.090000 -0.140075 0.249968 -vn 0.770263 0.000001 0.637726 -v -0.090000 -0.136000 0.256600 -vn 0.770261 -0.318867 0.552289 -v -0.090000 -0.134750 0.256935 -vn 0.684274 -0.076380 0.725214 -v -0.090000 -0.136000 0.339600 -vn 0.770261 0.552288 -0.318867 -v -0.090000 0.133835 0.330850 -vn 0.770261 0.318866 -0.552288 -v -0.090000 0.134750 0.331765 -vn 0.770261 -0.552288 0.318868 -v -0.090000 0.138165 0.257850 -vn 0.658993 0.720674 -0.215306 -v -0.090000 0.145518 0.256034 -vn 0.770264 -0.637725 0.000000 -v -0.090000 0.138500 0.259100 -vn 0.654973 0.741583 0.145138 -v -0.090000 0.145666 0.258527 -vn 0.770259 -0.552293 -0.318864 -v -0.090000 0.138165 0.260350 -vn 0.679842 0.616655 0.396928 -v -0.090000 0.144589 0.260781 -vn 0.770266 -0.318862 -0.552284 -v -0.090000 0.137250 0.261265 -vn 0.727260 0.562235 0.393680 -v -0.090000 0.127170 0.281541 -vn 0.770258 -0.000001 -0.637732 -v -0.090000 0.136000 0.261600 -vn 0.770260 -0.318867 0.552289 -v -0.090000 0.137250 0.256935 -vn 0.663085 0.305043 -0.683570 -v -0.090000 0.140075 0.249968 -vn 0.663085 0.557130 -0.499925 -v -0.090000 0.143443 0.252421 -vn 0.770261 0.318867 -0.552288 -v -0.090000 -0.137250 0.331765 -vn 0.663084 -0.305044 0.683569 -v -0.090000 -0.140075 0.338732 -vn 0.663084 -0.557131 0.499925 -v -0.090000 -0.143443 0.336279 -vn 0.727260 0.683750 -0.059820 -v -0.090000 0.126000 0.303945 -vn 0.748360 0.623291 -0.226859 -v -0.090000 0.126302 0.305655 -vn 0.770269 -0.637719 0.000000 -v -0.090000 -0.133500 0.329600 -vn 0.727260 -0.683750 0.059820 -v -0.090000 -0.126000 0.284755 -vn 0.748361 -0.623291 0.226859 -v -0.090000 -0.126302 0.283045 -vn 0.770269 0.637719 0.000000 -v -0.090000 0.133500 0.259100 -vn 0.770259 0.552293 -0.318864 -v -0.090000 0.133835 0.260350 -vn 0.770266 0.318861 -0.552284 -v -0.090000 0.134750 0.261265 -vn 0.770267 -0.318862 0.552282 -v -0.090000 0.137250 0.327435 -vn 0.727261 0.562235 -0.393680 -v -0.090000 0.127170 0.307159 -vn 0.770259 -0.552293 0.318864 -v -0.090000 0.138165 0.328350 -vn 0.679842 0.616655 -0.396928 -v -0.090000 0.144589 0.327919 -vn 0.654973 0.741583 -0.145138 -v -0.090000 0.145666 0.330173 -vn 0.770259 -0.552293 0.318864 -v -0.090000 -0.133835 0.328350 -vn 0.770266 -0.318861 0.552284 -v -0.090000 -0.134750 0.327435 -vn 0.770267 0.318862 -0.552282 -v -0.090000 -0.137250 0.261265 -vn 0.727261 -0.562235 0.393680 -v -0.090000 -0.127170 0.281541 -vn 0.770259 0.552293 -0.318864 -v -0.090000 -0.138165 0.260350 -vn 0.679842 -0.616655 0.396928 -v -0.090000 -0.144589 0.260781 -vn 0.654973 -0.741583 0.145138 -v -0.090000 -0.145666 0.258527 -vn 0.748360 0.623291 0.226859 -v -0.090000 0.126302 0.283045 -vn 0.727260 0.683750 0.059820 -v -0.090000 0.126000 0.284755 -vn 0.748360 -0.623291 -0.226859 -v -0.090000 -0.126302 0.305655 -vn 0.727261 -0.683750 -0.059820 -v -0.090000 -0.126000 0.303945 -vn -0.678875 -0.095839 -0.727972 -v -0.092000 0.065000 0.167700 -vn -0.651083 0.204939 -0.730816 -v -0.092000 0.139919 0.167700 -vn 0.678876 -0.095839 -0.727971 -v -0.090000 0.065000 0.167700 -vn 0.651082 0.204939 -0.730816 -v -0.090000 0.139919 0.167700 -vn 0.770263 0.318865 -0.552286 -v -0.090000 -0.137250 0.179065 -vn 0.728985 -0.346567 0.590316 -v -0.090000 -0.128887 0.184880 -vn 0.683655 -0.377857 0.624372 -v -0.090000 -0.142263 0.178643 -vn 0.651082 -0.204938 -0.730816 -v -0.090000 -0.139919 0.167700 -vn 0.770263 0.318865 0.552286 -v -0.090000 -0.137250 0.174735 -vn 0.676170 -0.469474 -0.567792 -v -0.090000 -0.142372 0.169193 -vn 0.770260 0.552291 0.318865 -v -0.090000 -0.138165 0.175650 -vn 0.668958 -0.631386 -0.392234 -v -0.090000 -0.144300 0.171322 -vn 0.661941 -0.739961 -0.119547 -v -0.090000 -0.145086 0.173314 -vn 0.661942 -0.722124 0.200923 -v -0.090000 -0.144967 0.175451 -vn 0.661942 -0.571880 0.484547 -v -0.090000 -0.143965 0.177343 -vn 0.770264 0.637725 -0.000000 -v -0.090000 -0.138500 0.176900 -vn 0.770260 0.552291 -0.318865 -v -0.090000 -0.138165 0.178150 -vn 0.770260 0.552291 -0.318866 -v -0.090000 0.133835 0.240150 -vn 0.770263 0.318864 -0.552286 -v -0.090000 0.134750 0.241065 -vn 0.770262 -0.318864 -0.552288 -v -0.090000 -0.134750 0.241065 -vn 0.653226 0.378581 -0.655722 -v -0.090000 -0.060000 0.169040 -vn 0.653227 0.655722 -0.378581 -v -0.090000 -0.056340 0.172700 -vn 0.678875 0.095839 -0.727972 -v -0.090000 -0.065000 0.167700 -vn 0.678875 0.727972 -0.095839 -v -0.090000 -0.055000 0.177700 -vn 0.770261 0.000001 -0.637729 -v -0.090000 -0.136000 0.179400 -vn 0.770264 -0.318864 -0.552286 -v -0.090000 -0.134750 0.179065 -vn 0.751960 -0.479492 0.452375 -v -0.090000 -0.127363 0.185980 -vn 0.668958 -0.631386 0.392234 -v -0.090000 -0.144300 0.244478 -vn 0.770260 0.552291 -0.318866 -v -0.090000 -0.138165 0.240150 -vn 0.676170 -0.469474 0.567792 -v -0.090000 -0.142372 0.246607 -vn 0.770263 0.318865 -0.552286 -v -0.090000 -0.137250 0.241065 -vn 0.651082 -0.204939 0.730816 -v -0.090000 -0.139919 0.248100 -vn 0.661941 -0.739961 0.119547 -v -0.090000 -0.145086 0.242486 -vn 0.661942 -0.722124 -0.200921 -v -0.090000 -0.144967 0.240349 -vn 0.770264 0.637725 -0.000000 -v -0.090000 -0.138500 0.238900 -vn 0.661942 -0.571881 -0.484546 -v -0.090000 -0.143965 0.238457 -vn 0.770260 0.552291 0.318865 -v -0.090000 -0.138165 0.237650 -vn 0.683655 -0.377857 -0.624372 -v -0.090000 -0.142263 0.237157 -vn 0.770262 0.318869 0.552286 -v -0.090000 -0.137250 0.236735 -vn 0.728984 -0.346567 -0.590316 -v -0.090000 -0.128887 0.230920 -vn 0.770264 0.000001 0.637725 -v -0.090000 -0.136000 0.236400 -vn 0.770262 -0.318868 0.552286 -v -0.090000 -0.134750 0.236735 -vn 0.770263 0.637727 -0.000000 -v -0.090000 0.133500 0.238900 -vn 0.770261 0.000001 -0.637729 -v -0.090000 -0.136000 0.241400 -vn 0.651081 0.204939 0.730817 -v -0.090000 0.139919 0.248100 -vn 0.770261 -0.000001 -0.637729 -v -0.090000 0.136000 0.241400 -vn 0.770263 -0.318865 -0.552286 -v -0.090000 0.137250 0.241065 -vn 0.676170 0.469474 0.567792 -v -0.090000 0.142372 0.246607 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 0.138165 0.240150 -vn 0.668958 0.631386 0.392234 -v -0.090000 0.144300 0.244478 -vn 0.683655 0.377857 -0.624372 -v -0.090000 0.142263 0.237157 -vn 0.661942 0.571881 -0.484546 -v -0.090000 0.143965 0.238457 -vn 0.770264 -0.637725 0.000000 -v -0.090000 0.138500 0.238900 -vn 0.661942 0.722124 -0.200921 -v -0.090000 0.144967 0.240349 -vn 0.661941 0.739961 0.119547 -v -0.090000 0.145086 0.242486 -vn 0.737700 -0.535616 -0.410992 -v -0.090000 0.046311 0.227700 -vn 0.770264 0.637725 0.000000 -v -0.090000 0.133500 0.176900 -vn 0.770261 -0.318865 -0.552289 -v -0.090000 0.042651 0.231360 -vn 0.770260 0.552291 -0.318866 -v -0.090000 0.133835 0.178150 -vn 0.668958 0.631386 -0.392234 -v -0.090000 0.144300 0.171322 -vn 0.770260 -0.552291 0.318866 -v -0.090000 0.138165 0.175650 -vn 0.676170 0.469474 -0.567792 -v -0.090000 0.142372 0.169193 -vn 0.770263 -0.318865 0.552286 -v -0.090000 0.137250 0.174735 -vn 0.770261 -0.000001 0.637729 -v -0.090000 0.136000 0.174400 -vn 0.770263 0.318864 0.552286 -v -0.090000 0.134750 0.174735 -vn 0.770260 0.552291 0.318866 -v -0.090000 0.133835 0.175650 -vn 0.737700 -0.623737 -0.258360 -v -0.090000 0.053660 0.214970 -vn 0.737700 -0.669353 -0.088122 -v -0.090000 0.055000 0.209970 -vn 0.678874 -0.727973 -0.095839 -v -0.090000 0.055000 0.177700 -vn 0.770260 -0.552291 0.318865 -v -0.090000 0.138165 0.237650 -vn 0.770262 -0.318869 0.552286 -v -0.090000 0.137250 0.236735 -vn 0.728984 0.346567 -0.590316 -v -0.090000 0.128887 0.230920 -vn 0.661941 0.739961 -0.119547 -v -0.090000 0.145086 0.173314 -vn 0.661942 0.722124 0.200923 -v -0.090000 0.144967 0.175451 -vn 0.770264 -0.637725 0.000000 -v -0.090000 0.138500 0.176900 -vn 0.661942 0.571880 0.484547 -v -0.090000 0.143965 0.177343 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 0.138165 0.178150 -vn 0.683655 0.377857 0.624372 -v -0.090000 0.142263 0.178643 -vn 0.770263 -0.318865 -0.552286 -v -0.090000 0.137250 0.179065 -vn 0.728985 0.346567 0.590316 -v -0.090000 0.128887 0.184880 -vn 0.770261 -0.000001 -0.637729 -v -0.090000 0.136000 0.179400 -vn 0.770263 0.318864 -0.552286 -v -0.090000 0.134750 0.179065 -vn 0.770264 -0.000001 0.637725 -v -0.090000 0.136000 0.236400 -vn 0.770262 0.318868 0.552286 -v -0.090000 0.134750 0.236735 -vn 0.751961 0.479490 -0.452376 -v -0.090000 0.127363 0.229820 -vn 0.770260 0.552291 0.318865 -v -0.090000 0.133835 0.237650 -vn 0.653226 -0.378581 -0.655722 -v -0.090000 0.060000 0.169040 -vn 0.653227 -0.655722 -0.378581 -v -0.090000 0.056340 0.172700 -vn 0.770260 -0.552290 0.318865 -v -0.090000 -0.133835 0.237650 -vn 0.737699 0.669354 -0.088122 -v -0.090000 -0.055000 0.209970 -vn 0.770268 -0.637720 -0.000000 -v -0.090000 -0.133500 0.238900 -vn 0.737700 0.623737 -0.258360 -v -0.090000 -0.053660 0.214970 -vn 0.737700 0.535616 -0.410992 -v -0.090000 -0.046311 0.227700 -vn 0.728984 -0.681474 -0.064618 -v -0.090000 -0.126000 0.226388 -vn 0.728984 -0.681474 0.064618 -v -0.090000 -0.126000 0.189411 -vn 0.751959 -0.612635 0.243383 -v -0.090000 -0.126353 0.187565 -vn 0.751960 -0.479491 -0.452377 -v -0.090000 -0.127363 0.229820 -vn 0.751960 -0.612634 -0.243384 -v -0.090000 -0.126353 0.228235 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 -0.133835 0.178150 -vn 0.770264 -0.637725 -0.000000 -v -0.090000 -0.133500 0.176900 -vn 0.770260 -0.552291 0.318865 -v -0.090000 -0.133835 0.175650 -vn 0.770264 -0.318864 0.552286 -v -0.090000 -0.134750 0.174735 -vn 0.770261 0.000001 0.637729 -v -0.090000 -0.136000 0.174400 -vn 0.751960 0.479492 0.452376 -v -0.090000 0.127363 0.185980 -vn 0.751959 0.612635 0.243383 -v -0.090000 0.126353 0.187565 -vn 0.728984 0.681474 0.064618 -v -0.090000 0.126000 0.189411 -vn 0.770262 0.318864 -0.552288 -v -0.090000 -0.042651 0.231360 -vn 0.737700 0.088122 -0.669353 -v -0.090000 -0.037651 0.232700 -vn 0.737704 -0.088122 -0.669348 -v -0.090000 0.037651 0.232700 -vn 0.770260 -0.552291 -0.318865 -v -0.090000 -0.133835 0.240150 -vn 0.751961 0.612633 -0.243384 -v -0.090000 0.126353 0.228235 -vn 0.728984 0.681474 -0.064618 -v -0.090000 0.126000 0.226388 -vn -0.770262 0.318869 0.552286 -v -0.092000 -0.137250 0.236735 -vn -0.728984 -0.346567 -0.590316 -v -0.092000 -0.128887 0.230920 -vn -0.683655 -0.377857 -0.624372 -v -0.092000 -0.142263 0.237157 -vn -0.651082 -0.204938 0.730817 -v -0.092000 -0.139919 0.248100 -vn -0.770263 0.318865 -0.552286 -v -0.092000 -0.137250 0.241065 -vn -0.676170 -0.469474 0.567792 -v -0.092000 -0.142372 0.246607 -vn -0.770260 0.552291 -0.318865 -v -0.092000 -0.138165 0.240150 -vn -0.668958 -0.631386 0.392234 -v -0.092000 -0.144300 0.244478 -vn -0.661941 -0.739961 0.119547 -v -0.092000 -0.145086 0.242486 -vn -0.661942 -0.722124 -0.200921 -v -0.092000 -0.144967 0.240349 -vn -0.661942 -0.571881 -0.484546 -v -0.092000 -0.143965 0.238457 -vn -0.770264 0.637725 0.000000 -v -0.092000 -0.138500 0.238900 -vn -0.770260 0.552291 0.318865 -v -0.092000 -0.138165 0.237650 -vn -0.770263 -0.318864 -0.552286 -v -0.092000 -0.134750 0.179065 -vn -0.770261 0.000001 -0.637729 -v -0.092000 -0.136000 0.179400 -vn -0.728985 -0.346567 0.590316 -v -0.092000 -0.128887 0.184880 -vn -0.770263 0.318865 -0.552286 -v -0.092000 -0.137250 0.179065 -vn -0.683655 -0.377857 0.624372 -v -0.092000 -0.142263 0.178643 -vn -0.770260 0.552291 -0.318865 -v -0.092000 -0.138165 0.178150 -vn -0.661942 -0.571880 0.484547 -v -0.092000 -0.143965 0.177343 -vn -0.770264 0.637725 0.000000 -v -0.092000 -0.138500 0.176900 -vn -0.661942 -0.722124 0.200923 -v -0.092000 -0.144967 0.175451 -vn -0.770260 0.552291 0.318866 -v -0.092000 -0.138165 0.175650 -vn -0.661941 -0.739961 -0.119547 -v -0.092000 -0.145086 0.173314 -vn -0.678876 0.095838 -0.727971 -v -0.092000 -0.065000 0.167700 -vn -0.770263 -0.318864 0.552286 -v -0.092000 -0.134750 0.174735 -vn -0.770260 -0.552291 0.318866 -v -0.092000 -0.133835 0.175650 -vn -0.770261 0.000001 0.637729 -v -0.092000 -0.136000 0.174400 -vn -0.651082 -0.204939 -0.730816 -v -0.092000 -0.139919 0.167700 -vn -0.770263 0.318865 0.552286 -v -0.092000 -0.137250 0.174735 -vn -0.676170 -0.469474 -0.567792 -v -0.092000 -0.142372 0.169193 -vn -0.668958 -0.631386 -0.392234 -v -0.092000 -0.144300 0.171322 -vn -0.737700 0.623737 -0.258360 -v -0.092000 -0.053660 0.214970 -vn -0.737700 0.669353 -0.088122 -v -0.092000 -0.055000 0.209970 -vn -0.770264 -0.637726 0.000000 -v -0.092000 -0.133500 0.176900 -vn -0.678874 0.727973 -0.095839 -v -0.092000 -0.055000 0.177700 -vn -0.770260 -0.552291 0.318865 -v -0.092000 -0.133835 0.237650 -vn -0.770258 -0.000001 -0.637732 -v -0.092000 0.136000 0.241400 -vn -0.770261 -0.318869 0.552288 -v -0.092000 -0.134750 0.236735 -vn -0.770262 0.318865 -0.552288 -v -0.092000 0.134750 0.241065 -vn -0.770261 0.000001 0.637729 -v -0.092000 -0.136000 0.236400 -vn -0.770260 0.552291 -0.318865 -v -0.092000 0.133835 0.240150 -vn -0.770271 0.637717 0.000000 -v -0.092000 0.133500 0.238900 -vn -0.770261 -0.000001 0.637729 -v -0.092000 0.136000 0.174400 -vn -0.770263 -0.318865 0.552286 -v -0.092000 0.137250 0.174735 -vn -0.770264 -0.637725 0.000000 -v -0.092000 0.138500 0.176900 -vn -0.770260 -0.552291 -0.318865 -v -0.092000 0.138165 0.178150 -vn -0.683655 0.377857 0.624372 -v -0.092000 0.142263 0.178643 -vn -0.770263 -0.318865 -0.552286 -v -0.092000 0.137250 0.179065 -vn -0.728985 0.346567 0.590316 -v -0.092000 0.128887 0.184880 -vn -0.653226 0.378581 -0.655722 -v -0.092000 -0.060000 0.169040 -vn -0.653227 0.655722 -0.378581 -v -0.092000 -0.056340 0.172700 -vn -0.676170 0.469474 -0.567792 -v -0.092000 0.142372 0.169193 -vn -0.770260 -0.552291 0.318866 -v -0.092000 0.138165 0.175650 -vn -0.668958 0.631386 -0.392234 -v -0.092000 0.144300 0.171322 -vn -0.661942 0.571880 0.484547 -v -0.092000 0.143965 0.177343 -vn -0.661942 0.722124 0.200923 -v -0.092000 0.144967 0.175451 -vn -0.661941 0.739961 -0.119547 -v -0.092000 0.145086 0.173314 -vn -0.653226 -0.378581 -0.655722 -v -0.092000 0.060000 0.169040 -vn -0.653227 -0.655722 -0.378581 -v -0.092000 0.056340 0.172700 -vn -0.678875 -0.727972 -0.095839 -v -0.092000 0.055000 0.177700 -vn -0.668958 0.631386 0.392234 -v -0.092000 0.144300 0.244478 -vn -0.770260 -0.552291 -0.318866 -v -0.092000 0.138165 0.240150 -vn -0.676170 0.469474 0.567792 -v -0.092000 0.142372 0.246607 -vn -0.770263 -0.318865 -0.552286 -v -0.092000 0.137250 0.241065 -vn -0.651081 0.204939 0.730817 -v -0.092000 0.139919 0.248100 -vn -0.770264 -0.637725 0.000000 -v -0.092000 -0.133500 0.238900 -vn -0.770260 -0.552290 -0.318865 -v -0.092000 -0.133835 0.240150 -vn -0.770263 -0.318864 -0.552286 -v -0.092000 -0.134750 0.241065 -vn -0.770261 0.000001 -0.637729 -v -0.092000 -0.136000 0.241400 -vn -0.770264 0.318864 0.552286 -v -0.092000 0.134750 0.174735 -vn -0.770260 0.552291 0.318865 -v -0.092000 0.133835 0.175650 -vn -0.770264 0.637725 0.000000 -v -0.092000 0.133500 0.176900 -vn -0.737700 -0.669353 -0.088122 -v -0.092000 0.055000 0.209970 -vn -0.770259 0.552291 -0.318866 -v -0.092000 0.133835 0.178150 -vn -0.737700 -0.623737 -0.258360 -v -0.092000 0.053660 0.214970 -vn -0.737700 -0.535616 -0.410992 -v -0.092000 0.046311 0.227700 -vn -0.661941 0.739961 0.119547 -v -0.092000 0.145086 0.242486 -vn -0.661942 0.722124 -0.200921 -v -0.092000 0.144967 0.240349 -vn -0.770264 -0.637725 0.000000 -v -0.092000 0.138500 0.238900 -vn -0.661942 0.571881 -0.484546 -v -0.092000 0.143965 0.238457 -vn -0.770260 -0.552291 0.318865 -v -0.092000 0.138165 0.237650 -vn -0.683655 0.377857 -0.624372 -v -0.092000 0.142263 0.237157 -vn -0.770262 -0.318869 0.552286 -v -0.092000 0.137250 0.236735 -vn -0.728984 0.346567 -0.590316 -v -0.092000 0.128887 0.230920 -vn -0.770264 -0.000001 0.637725 -v -0.092000 0.136000 0.236400 -vn -0.770260 -0.552291 -0.318865 -v -0.092000 -0.133835 0.178150 -vn -0.770261 0.318865 -0.552289 -v -0.092000 -0.042651 0.231360 -vn -0.737700 0.535616 -0.410992 -v -0.092000 -0.046311 0.227700 -vn -0.770262 0.318868 0.552286 -v -0.092000 0.134750 0.236735 -vn -0.770262 -0.318864 -0.552288 -v -0.092000 0.042651 0.231360 -vn -0.770260 0.552291 0.318865 -v -0.092000 0.133835 0.237650 -vn -0.751960 0.479491 -0.452377 -v -0.092000 0.127363 0.229820 -vn -0.751960 0.612634 -0.243384 -v -0.092000 0.126353 0.228235 -vn -0.728984 0.681474 -0.064618 -v -0.092000 0.126000 0.226388 -vn -0.751960 0.479492 0.452375 -v -0.092000 0.127363 0.185980 -vn -0.770264 0.318864 -0.552286 -v -0.092000 0.134750 0.179065 -vn -0.770261 -0.000001 -0.637729 -v -0.092000 0.136000 0.179400 -vn -0.728984 0.681474 0.064618 -v -0.092000 0.126000 0.189411 -vn -0.751959 0.612635 0.243383 -v -0.092000 0.126353 0.187565 -vn -0.737700 -0.088122 -0.669353 -v -0.092000 0.037651 0.232700 -vn -0.737703 0.088122 -0.669350 -v -0.092000 -0.037651 0.232700 -vn -0.751960 -0.479492 0.452376 -v -0.092000 -0.127363 0.185980 -vn -0.751959 -0.612635 0.243383 -v -0.092000 -0.126353 0.187565 -vn -0.728984 -0.681474 0.064618 -v -0.092000 -0.126000 0.189411 -vn -0.751963 -0.479488 -0.452374 -v -0.092000 -0.127363 0.229820 -vn -0.751960 -0.612634 -0.243384 -v -0.092000 -0.126353 0.228235 -vn -0.728984 -0.681474 -0.064618 -v -0.092000 -0.126000 0.226388 -# 2074 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 7//7 8//8 1//1 -f 1//1 8//8 9//9 -f 8//8 10//10 9//9 -f 9//9 10//10 11//11 -f 9//9 11//11 12//12 -f 12//12 11//11 13//13 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 16//16 17//17 18//18 -f 18//18 17//17 19//19 -f 18//18 19//19 15//15 -f 20//20 21//21 22//22 -f 22//22 21//21 18//18 -f 22//22 18//18 23//23 -f 23//23 18//18 15//15 -f 23//23 15//15 24//24 -f 24//24 15//15 13//13 -f 25//25 26//26 1//1 -f 1//1 26//26 27//27 -f 1//1 27//27 7//7 -f 28//28 29//29 30//30 -f 30//30 29//29 31//31 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 33//33 36//36 16//16 -f 16//16 36//36 37//37 -f 16//16 37//37 17//17 -f 31//31 38//38 30//30 -f 30//30 38//38 39//39 -f 30//30 39//39 40//40 -f 40//40 39//39 41//41 -f 41//41 42//42 40//40 -f 40//40 42//42 43//43 -f 40//40 43//43 35//35 -f 35//35 43//43 44//44 -f 35//35 44//44 34//34 -f 45//45 46//46 47//47 -f 6//6 48//48 49//49 -f 48//48 6//6 50//50 -f 50//50 6//6 51//51 -f 50//50 51//51 52//52 -f 52//52 51//51 53//53 -f 52//52 53//53 54//54 -f 30//30 55//55 56//56 -f 47//47 46//46 57//57 -f 57//57 46//46 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 30//30 -f 30//30 60//60 61//61 -f 30//30 61//61 55//55 -f 32//32 62//62 33//33 -f 33//33 62//62 28//28 -f 33//33 28//28 36//36 -f 36//36 28//28 30//30 -f 36//36 30//30 63//63 -f 63//63 30//30 56//56 -f 63//63 56//56 64//64 -f 53//53 65//65 54//54 -f 54//54 65//65 66//66 -f 54//54 66//66 56//56 -f 56//56 66//66 67//67 -f 56//56 67//67 64//64 -f 68//68 4//4 69//69 -f 69//69 4//4 6//6 -f 69//69 6//6 47//47 -f 47//47 6//6 49//49 -f 47//47 49//49 45//45 -f 70//70 71//71 72//72 -f 72//72 71//71 73//73 -f 73//73 71//71 74//74 -f 73//73 74//74 75//75 -f 74//74 76//76 75//75 -f 75//75 76//76 77//77 -f 75//75 77//77 78//78 -f 78//78 77//77 79//79 -f 78//78 79//79 80//80 -f 80//80 79//79 81//81 -f 80//80 81//81 82//82 -f 82//82 81//81 83//83 -f 82//82 83//83 84//84 -f 72//72 85//85 70//70 -f 70//70 85//85 86//86 -f 70//70 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 84//84 -f 91//91 84//84 92//92 -f 92//92 84//84 83//83 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 40//40 98//98 99//99 -f 98//98 40//40 100//100 -f 100//100 40//40 35//35 -f 100//100 35//35 101//101 -f 102//102 75//75 103//103 -f 103//103 75//75 40//40 -f 103//103 40//40 104//104 -f 104//104 40//40 99//99 -f 102//102 105//105 75//75 -f 75//75 105//105 106//106 -f 75//75 106//106 73//73 -f 73//73 106//106 107//107 -f 73//73 107//107 108//108 -f 108//108 107//107 109//109 -f 35//35 95//95 101//101 -f 101//101 95//95 97//97 -f 101//101 97//97 110//110 -f 110//110 97//97 111//111 -f 110//110 111//111 109//109 -f 109//109 111//111 112//112 -f 109//109 112//112 108//108 -f 113//113 114//114 1//1 -f 1//1 114//114 115//115 -f 115//115 116//116 1//1 -f 1//1 116//116 21//21 -f 1//1 21//21 25//25 -f 25//25 21//21 20//20 -f 117//117 118//118 119//119 -f 118//118 120//120 119//119 -f 119//119 120//120 121//121 -f 119//119 121//121 113//113 -f 116//116 122//122 21//21 -f 21//21 122//122 123//123 -f 21//21 123//123 124//124 -f 125//125 126//126 127//127 -f 128//128 129//129 130//130 -f 130//130 129//129 131//131 -f 130//130 131//131 124//124 -f 127//127 132//132 125//125 -f 125//125 132//132 21//21 -f 125//125 21//21 133//133 -f 133//133 21//21 124//124 -f 133//133 124//124 134//134 -f 134//134 124//124 131//131 -f 135//135 136//136 119//119 -f 119//119 136//136 137//137 -f 137//137 138//138 139//139 -f 130//130 117//117 128//128 -f 128//128 117//117 119//119 -f 128//128 119//119 140//140 -f 140//140 119//119 137//137 -f 140//140 137//137 141//141 -f 141//141 137//137 139//139 -f 2//2 1//1 142//142 -f 142//142 1//1 9//9 -f 142//142 9//9 143//143 -f 113//113 1//1 119//119 -f 119//119 1//1 3//3 -f 119//119 3//3 135//135 -f 135//135 3//3 144//144 -f 135//135 144//144 145//145 -f 146//146 147//147 148//148 -f 149//149 150//150 146//146 -f 146//146 150//150 151//151 -f 151//151 152//152 153//153 -f 154//154 146//146 155//155 -f 155//155 146//146 151//151 -f 155//155 151//151 156//156 -f 156//156 151//151 153//153 -f 149//149 157//157 158//158 -f 149//149 158//158 150//150 -f 150//150 158//158 159//159 -f 150//150 159//159 160//160 -f 160//160 159//159 161//161 -f 160//160 161//161 162//162 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 149//149 -f 149//149 172//172 173//173 -f 149//149 173//173 157//157 -f 162//162 161//161 174//174 -f 174//174 161//161 175//175 -f 174//174 175//175 168//168 -f 168//168 175//175 176//176 -f 168//168 176//176 167//167 -f 167//167 176//176 177//177 -f 167//167 177//177 171//171 -f 171//171 177//177 178//178 -f 171//171 178//178 169//169 -f 179//179 171//171 180//180 -f 180//180 171//171 181//181 -f 182//182 167//167 183//183 -f 183//183 184//184 182//182 -f 182//182 184//184 185//185 -f 182//182 185//185 186//186 -f 186//186 185//185 187//187 -f 186//186 187//187 188//188 -f 188//188 187//187 189//189 -f 188//188 189//189 190//190 -f 190//190 189//189 191//191 -f 190//190 191//191 181//181 -f 181//181 191//191 192//192 -f 181//181 192//192 180//180 -f 179//179 193//193 171//171 -f 171//171 193//193 194//194 -f 171//171 194//194 167//167 -f 167//167 194//194 195//195 -f 167//167 195//195 183//183 -f 196//196 197//197 198//198 -f 198//198 197//197 199//199 -f 198//198 199//199 200//200 -f 196//196 201//201 197//197 -f 197//197 201//201 202//202 -f 197//197 202//202 203//203 -f 203//203 202//202 204//204 -f 205//205 206//206 207//207 -f 207//207 206//206 203//203 -f 207//207 203//203 208//208 -f 208//208 203//203 204//204 -f 209//209 210//210 199//199 -f 199//199 210//210 211//211 -f 199//199 211//211 200//200 -f 212//212 213//213 199//199 -f 199//199 213//213 206//206 -f 199//199 206//206 209//209 -f 209//209 206//206 205//205 -f 214//214 215//215 216//216 -f 216//216 215//215 217//217 -f 216//216 217//217 218//218 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 224//224 222//222 225//225 -f 224//224 225//225 226//226 -f 226//226 225//225 227//227 -f 226//226 227//227 228//228 -f 228//228 229//229 226//226 -f 226//226 229//229 230//230 -f 226//226 230//230 199//199 -f 199//199 230//230 231//231 -f 199//199 231//231 212//212 -f 219//219 218//218 220//220 -f 220//220 218//218 217//217 -f 220//220 217//217 232//232 -f 232//232 217//217 206//206 -f 232//232 206//206 233//233 -f 233//233 206//206 213//213 -f 234//234 235//235 236//236 -f 236//236 235//235 237//237 -f 235//235 238//238 237//237 -f 237//237 238//238 239//239 -f 237//237 239//239 240//240 -f 240//240 239//239 241//241 -f 240//240 241//241 242//242 -f 242//242 241//241 243//243 -f 242//242 243//243 244//244 -f 244//244 243//243 245//245 -f 244//244 245//245 226//226 -f 236//236 246//246 234//234 -f 234//234 246//246 247//247 -f 234//234 247//247 248//248 -f 248//248 247//247 249//249 -f 248//248 249//249 250//250 -f 250//250 249//249 251//251 -f 250//250 251//251 252//252 -f 252//252 251//251 224//224 -f 252//252 224//224 253//253 -f 253//253 224//224 226//226 -f 253//253 226//226 254//254 -f 254//254 226//226 245//245 -f 197//197 255//255 256//256 -f 197//197 256//256 257//257 -f 256//256 258//258 257//257 -f 257//257 258//258 259//259 -f 257//257 259//259 260//260 -f 260//260 259//259 261//261 -f 260//260 261//261 262//262 -f 262//262 261//261 263//263 -f 262//262 263//263 264//264 -f 264//264 265//265 266//266 -f 266//266 265//265 267//267 -f 266//266 267//267 268//268 -f 268//268 267//267 269//269 -f 270//270 271//271 269//269 -f 269//269 271//271 272//272 -f 269//269 272//272 268//268 -f 273//273 255//255 274//274 -f 274//274 255//255 197//197 -f 274//274 197//197 275//275 -f 275//275 197//197 203//203 -f 275//275 203//203 276//276 -f 276//276 203//203 277//277 -f 276//276 277//277 278//278 -f 278//278 277//277 182//182 -f 278//278 182//182 279//279 -f 279//279 182//182 186//186 -f 274//274 280//280 273//273 -f 273//273 280//280 281//281 -f 273//273 281//281 270//270 -f 270//270 281//281 282//282 -f 270//270 282//282 271//271 -f 266//266 283//283 284//284 -f 264//264 266//266 262//262 -f 262//262 266//266 284//284 -f 262//262 284//284 285//285 -f 146//146 148//148 149//149 -f 149//149 148//148 286//286 -f 149//149 286//286 171//171 -f 171//171 286//286 287//287 -f 171//171 287//287 181//181 -f 181//181 287//287 288//288 -f 181//181 288//288 289//289 -f 236//236 237//237 90//90 -f 90//90 237//237 84//84 -f 257//257 260//260 59//59 -f 59//59 260//260 57//57 -f 57//57 260//260 47//47 -f 47//47 260//260 262//262 -f 47//47 262//262 69//69 -f 69//69 262//262 285//285 -f 69//69 285//285 68//68 -f 144//144 148//148 147//147 -f 144//144 147//147 145//145 -f 145//145 147//147 146//146 -f 145//145 146//146 135//135 -f 135//135 146//146 154//154 -f 135//135 154//154 136//136 -f 84//84 237//237 240//240 -f 84//84 240//240 82//82 -f 82//82 240//240 242//242 -f 82//82 242//242 80//80 -f 80//80 242//242 244//244 -f 80//80 244//244 78//78 -f 257//257 59//59 197//197 -f 197//197 59//59 30//30 -f 197//197 30//30 199//199 -f 199//199 30//30 40//40 -f 199//199 40//40 226//226 -f 226//226 40//40 75//75 -f 226//226 75//75 244//244 -f 244//244 75//75 78//78 -f 142//142 288//288 2//2 -f 2//2 288//288 287//287 -f 2//2 287//287 3//3 -f 3//3 287//287 286//286 -f 3//3 286//286 144//144 -f 144//144 286//286 148//148 -f 58//58 259//259 60//60 -f 60//60 259//259 258//258 -f 60//60 258//258 61//61 -f 61//61 258//258 256//256 -f 61//61 256//256 55//55 -f 55//55 256//256 255//255 -f 55//55 255//255 56//56 -f 56//56 255//255 273//273 -f 56//56 273//273 54//54 -f 54//54 273//273 270//270 -f 54//54 270//270 52//52 -f 52//52 270//270 269//269 -f 52//52 269//269 50//50 -f 50//50 269//269 267//267 -f 50//50 267//267 48//48 -f 48//48 267//267 265//265 -f 48//48 265//265 49//49 -f 49//49 265//265 264//264 -f 49//49 264//264 45//45 -f 45//45 264//264 263//263 -f 45//45 263//263 46//46 -f 46//46 263//263 261//261 -f 46//46 261//261 58//58 -f 58//58 261//261 259//259 -f 39//39 198//198 41//41 -f 41//41 198//198 200//200 -f 41//41 200//200 42//42 -f 42//42 200//200 211//211 -f 42//42 211//211 43//43 -f 43//43 211//211 210//210 -f 43//43 210//210 44//44 -f 44//44 210//210 209//209 -f 44//44 209//209 34//34 -f 34//34 209//209 205//205 -f 34//34 205//205 32//32 -f 32//32 205//205 207//207 -f 32//32 207//207 62//62 -f 62//62 207//207 208//208 -f 62//62 208//208 28//28 -f 28//28 208//208 204//204 -f 28//28 204//204 29//29 -f 29//29 204//204 202//202 -f 29//29 202//202 31//31 -f 31//31 202//202 201//201 -f 31//31 201//201 38//38 -f 38//38 201//201 196//196 -f 38//38 196//196 39//39 -f 39//39 196//196 198//198 -f 103//103 230//230 102//102 -f 102//102 230//230 229//229 -f 102//102 229//229 105//105 -f 105//105 229//229 228//228 -f 105//105 228//228 106//106 -f 106//106 228//228 227//227 -f 106//106 227//227 107//107 -f 107//107 227//227 225//225 -f 107//107 225//225 109//109 -f 109//109 225//225 222//222 -f 109//109 222//222 110//110 -f 110//110 222//222 220//220 -f 110//110 220//220 101//101 -f 101//101 220//220 232//232 -f 101//101 232//232 100//100 -f 100//100 232//232 233//233 -f 100//100 233//233 98//98 -f 98//98 233//233 213//213 -f 98//98 213//213 99//99 -f 99//99 213//213 212//212 -f 99//99 212//212 104//104 -f 104//104 212//212 231//231 -f 104//104 231//231 103//103 -f 103//103 231//231 230//230 -f 81//81 243//243 83//83 -f 83//83 243//243 241//241 -f 83//83 241//241 92//92 -f 92//92 241//241 239//239 -f 92//92 239//239 91//91 -f 91//91 239//239 238//238 -f 91//91 238//238 89//89 -f 89//89 238//238 235//235 -f 89//89 235//235 87//87 -f 87//87 235//235 234//234 -f 87//87 234//234 70//70 -f 70//70 234//234 248//248 -f 70//70 248//248 71//71 -f 71//71 248//248 250//250 -f 71//71 250//250 74//74 -f 74//74 250//250 252//252 -f 74//74 252//252 76//76 -f 76//76 252//252 253//253 -f 76//76 253//253 77//77 -f 77//77 253//253 254//254 -f 77//77 254//254 79//79 -f 79//79 254//254 245//245 -f 79//79 245//245 81//81 -f 81//81 245//245 243//243 -f 22//22 184//184 20//20 -f 20//20 184//184 183//183 -f 20//20 183//183 25//25 -f 25//25 183//183 195//195 -f 25//25 195//195 26//26 -f 26//26 195//195 194//194 -f 26//26 194//194 27//27 -f 27//27 194//194 193//193 -f 27//27 193//193 7//7 -f 7//7 193//193 179//179 -f 7//7 179//179 8//8 -f 8//8 179//179 180//180 -f 8//8 180//180 10//10 -f 10//10 180//180 192//192 -f 10//10 192//192 11//11 -f 11//11 192//192 191//191 -f 11//11 191//191 13//13 -f 13//13 191//191 189//189 -f 13//13 189//189 24//24 -f 24//24 189//189 187//187 -f 24//24 187//187 23//23 -f 23//23 187//187 185//185 -f 23//23 185//185 22//22 -f 22//22 185//185 184//184 -f 124//124 175//175 130//130 -f 130//130 175//175 161//161 -f 130//130 161//161 117//117 -f 117//117 161//161 159//159 -f 117//117 159//159 118//118 -f 118//118 159//159 158//158 -f 118//118 158//158 120//120 -f 120//120 158//158 157//157 -f 120//120 157//157 121//121 -f 121//121 157//157 173//173 -f 121//121 173//173 113//113 -f 113//113 173//173 172//172 -f 113//113 172//172 114//114 -f 114//114 172//172 170//170 -f 114//114 170//170 115//115 -f 115//115 170//170 169//169 -f 115//115 169//169 116//116 -f 116//116 169//169 178//178 -f 116//116 178//178 122//122 -f 122//122 178//178 177//177 -f 122//122 177//177 123//123 -f 123//123 177//177 176//176 -f 123//123 176//176 124//124 -f 124//124 176//176 175//175 -f 137//137 136//136 155//155 -f 155//155 136//136 154//154 -f 4//4 68//68 284//284 -f 284//284 68//68 285//285 -f 132//132 165//165 21//21 -f 21//21 165//165 167//167 -f 21//21 167//167 18//18 -f 18//18 167//167 182//182 -f 217//217 95//95 206//206 -f 206//206 95//95 35//35 -f 206//206 35//35 203//203 -f 203//203 35//35 33//33 -f 97//97 96//96 218//218 -f 218//218 96//96 216//216 -f 251//251 72//72 224//224 -f 224//224 72//72 73//73 -f 224//224 73//73 223//223 -f 223//223 73//73 108//108 -f 168//168 166//166 133//133 -f 133//133 166//166 125//125 -f 140//140 151//151 128//128 -f 128//128 151//151 150//150 -f 128//128 150//150 129//129 -f 129//129 150//150 160//160 -f 151//151 140//140 141//141 -f 151//151 141//141 152//152 -f 152//152 141//141 139//139 -f 152//152 139//139 153//153 -f 153//153 139//139 138//138 -f 153//153 138//138 156//156 -f 156//156 138//138 137//137 -f 156//156 137//137 155//155 -f 72//72 251//251 249//249 -f 72//72 249//249 85//85 -f 85//85 249//249 247//247 -f 85//85 247//247 86//86 -f 86//86 247//247 246//246 -f 86//86 246//246 88//88 -f 88//88 246//246 236//236 -f 88//88 236//236 90//90 -f 129//129 160//160 131//131 -f 131//131 160//160 162//162 -f 131//131 162//162 134//134 -f 134//134 162//162 174//174 -f 134//134 174//174 133//133 -f 133//133 174//174 168//168 -f 97//97 218//218 111//111 -f 111//111 218//218 219//219 -f 111//111 219//219 112//112 -f 112//112 219//219 221//221 -f 112//112 221//221 108//108 -f 108//108 221//221 223//223 -f 165//165 132//132 127//127 -f 165//165 127//127 163//163 -f 163//163 127//127 126//126 -f 163//163 126//126 164//164 -f 164//164 126//126 125//125 -f 164//164 125//125 166//166 -f 95//95 217//217 215//215 -f 95//95 215//215 93//93 -f 93//93 215//215 214//214 -f 93//93 214//214 94//94 -f 94//94 214//214 216//216 -f 94//94 216//216 96//96 -f 203//203 33//33 277//277 -f 277//277 33//33 16//16 -f 277//277 16//16 182//182 -f 182//182 16//16 18//18 -f 65//65 271//271 66//66 -f 66//66 271//271 282//282 -f 66//66 282//282 67//67 -f 67//67 282//282 281//281 -f 67//67 281//281 64//64 -f 64//64 281//281 280//280 -f 64//64 280//280 63//63 -f 63//63 280//280 274//274 -f 63//63 274//274 36//36 -f 36//36 274//274 275//275 -f 36//36 275//275 37//37 -f 37//37 275//275 276//276 -f 37//37 276//276 17//17 -f 17//17 276//276 278//278 -f 17//17 278//278 19//19 -f 19//19 278//278 279//279 -f 19//19 279//279 15//15 -f 15//15 279//279 186//186 -f 272//272 271//271 53//53 -f 53//53 271//271 65//65 -f 14//14 15//15 188//188 -f 188//188 15//15 186//186 -f 14//14 188//188 190//190 -f 14//14 190//190 12//12 -f 12//12 190//190 181//181 -f 12//12 181//181 9//9 -f 9//9 181//181 289//289 -f 9//9 289//289 143//143 -f 143//143 289//289 288//288 -f 143//143 288//288 142//142 -f 272//272 53//53 51//51 -f 272//272 51//51 268//268 -f 268//268 51//51 6//6 -f 268//268 6//6 266//266 -f 266//266 6//6 5//5 -f 266//266 5//5 283//283 -f 283//283 5//5 4//4 -f 283//283 4//4 284//284 -f 290//290 291//291 292//292 -f 293//293 294//294 295//295 -f 296//296 297//297 290//290 -f 290//290 297//297 298//298 -f 297//297 299//299 298//298 -f 298//298 299//299 300//300 -f 298//298 300//300 301//301 -f 301//301 300//300 302//302 -f 301//301 302//302 303//303 -f 303//303 302//302 304//304 -f 305//305 306//306 307//307 -f 307//307 306//306 308//308 -f 307//307 308//308 304//304 -f 309//309 310//310 311//311 -f 311//311 310//310 307//307 -f 311//311 307//307 312//312 -f 312//312 307//307 304//304 -f 312//312 304//304 313//313 -f 313//313 304//304 302//302 -f 314//314 315//315 290//290 -f 290//290 315//315 316//316 -f 290//290 316//316 296//296 -f 317//317 318//318 319//319 -f 319//319 318//318 320//320 -f 321//321 322//322 323//323 -f 323//323 322//322 324//324 -f 322//322 325//325 305//305 -f 305//305 325//325 326//326 -f 305//305 326//326 306//306 -f 320//320 327//327 319//319 -f 319//319 327//327 328//328 -f 319//319 328//328 329//329 -f 329//329 328//328 330//330 -f 330//330 331//331 329//329 -f 329//329 331//331 332//332 -f 329//329 332//332 324//324 -f 324//324 332//332 333//333 -f 324//324 333//333 323//323 -f 334//334 335//335 336//336 -f 295//295 337//337 338//338 -f 337//337 295//295 339//339 -f 339//339 295//295 340//340 -f 339//339 340//340 341//341 -f 341//341 340//340 342//342 -f 341//341 342//342 343//343 -f 319//319 344//344 345//345 -f 336//336 335//335 346//346 -f 346//346 335//335 347//347 -f 346//346 347//347 348//348 -f 348//348 347//347 349//349 -f 348//348 349//349 319//319 -f 319//319 349//349 350//350 -f 319//319 350//350 344//344 -f 321//321 351//351 322//322 -f 322//322 351//351 317//317 -f 322//322 317//317 325//325 -f 325//325 317//317 319//319 -f 325//325 319//319 352//352 -f 352//352 319//319 345//345 -f 352//352 345//345 353//353 -f 342//342 354//354 343//343 -f 343//343 354//354 355//355 -f 343//343 355//355 345//345 -f 345//345 355//355 356//356 -f 345//345 356//356 353//353 -f 357//357 293//293 358//358 -f 358//358 293//293 295//295 -f 358//358 295//295 336//336 -f 336//336 295//295 338//338 -f 336//336 338//338 334//334 -f 359//359 360//360 361//361 -f 361//361 360//360 362//362 -f 362//362 360//360 363//363 -f 362//362 363//363 364//364 -f 363//363 365//365 364//364 -f 364//364 365//365 366//366 -f 364//364 366//366 367//367 -f 367//367 366//366 368//368 -f 367//367 368//368 369//369 -f 369//369 368//368 370//370 -f 369//369 370//370 371//371 -f 371//371 370//370 372//372 -f 371//371 372//372 373//373 -f 361//361 374//374 359//359 -f 359//359 374//374 375//375 -f 359//359 375//375 376//376 -f 376//376 375//375 377//377 -f 376//376 377//377 378//378 -f 378//378 377//377 379//379 -f 378//378 379//379 380//380 -f 380//380 379//379 373//373 -f 380//380 373//373 381//381 -f 381//381 373//373 372//372 -f 382//382 383//383 384//384 -f 384//384 383//383 385//385 -f 384//384 385//385 386//386 -f 329//329 387//387 388//388 -f 387//387 329//329 389//389 -f 389//389 329//329 324//324 -f 389//389 324//324 390//390 -f 391//391 364//364 392//392 -f 392//392 364//364 329//329 -f 392//392 329//329 393//393 -f 393//393 329//329 388//388 -f 391//391 394//394 364//364 -f 364//364 394//394 395//395 -f 364//364 395//395 362//362 -f 362//362 395//395 396//396 -f 362//362 396//396 397//397 -f 397//397 396//396 398//398 -f 324//324 384//384 390//390 -f 390//390 384//384 386//386 -f 390//390 386//386 399//399 -f 399//399 386//386 400//400 -f 399//399 400//400 398//398 -f 398//398 400//400 401//401 -f 398//398 401//401 397//397 -f 402//402 403//403 290//290 -f 290//290 403//403 404//404 -f 404//404 405//405 290//290 -f 290//290 405//405 310//310 -f 290//290 310//310 314//314 -f 314//314 310//310 309//309 -f 406//406 407//407 408//408 -f 407//407 409//409 408//408 -f 408//408 409//409 410//410 -f 408//408 410//410 402//402 -f 405//405 411//411 310//310 -f 310//310 411//411 412//412 -f 310//310 412//412 413//413 -f 414//414 415//415 416//416 -f 417//417 418//418 419//419 -f 419//419 418//418 420//420 -f 419//419 420//420 413//413 -f 416//416 421//421 414//414 -f 414//414 421//421 310//310 -f 414//414 310//310 422//422 -f 422//422 310//310 413//413 -f 422//422 413//413 423//423 -f 423//423 413//413 420//420 -f 424//424 425//425 408//408 -f 408//408 425//425 426//426 -f 426//426 427//427 428//428 -f 419//419 406//406 417//417 -f 417//417 406//406 408//408 -f 417//417 408//408 429//429 -f 429//429 408//408 426//426 -f 429//429 426//426 430//430 -f 430//430 426//426 428//428 -f 291//291 290//290 431//431 -f 431//431 290//290 298//298 -f 431//431 298//298 432//432 -f 402//402 290//290 408//408 -f 408//408 290//290 292//292 -f 408//408 292//292 424//424 -f 424//424 292//292 433//433 -f 424//424 433//433 434//434 -f 435//435 436//436 437//437 -f 438//438 439//439 435//435 -f 435//435 439//439 440//440 -f 440//440 441//441 442//442 -f 443//443 435//435 444//444 -f 444//444 435//435 440//440 -f 444//444 440//440 445//445 -f 445//445 440//440 442//442 -f 438//438 446//446 447//447 -f 438//438 447//447 439//439 -f 439//439 447//447 448//448 -f 439//439 448//448 449//449 -f 449//449 448//448 450//450 -f 449//449 450//450 451//451 -f 452//452 453//453 454//454 -f 454//454 453//453 455//455 -f 454//454 455//455 456//456 -f 456//456 455//455 457//457 -f 458//458 459//459 460//460 -f 460//460 459//459 461//461 -f 460//460 461//461 438//438 -f 438//438 461//461 462//462 -f 438//438 462//462 446//446 -f 451//451 450//450 463//463 -f 463//463 450//450 464//464 -f 463//463 464//464 457//457 -f 457//457 464//464 465//465 -f 457//457 465//465 456//456 -f 456//456 465//465 466//466 -f 456//456 466//466 460//460 -f 460//460 466//466 467//467 -f 460//460 467//467 458//458 -f 468//468 460//460 469//469 -f 469//469 460//460 470//470 -f 471//471 456//456 472//472 -f 472//472 473//473 471//471 -f 471//471 473//473 474//474 -f 471//471 474//474 475//475 -f 475//475 474//474 476//476 -f 475//475 476//476 477//477 -f 477//477 476//476 478//478 -f 477//477 478//478 479//479 -f 479//479 478//478 480//480 -f 479//479 480//480 470//470 -f 470//470 480//480 481//481 -f 470//470 481//481 469//469 -f 468//468 482//482 460//460 -f 460//460 482//482 483//483 -f 460//460 483//483 456//456 -f 456//456 483//483 484//484 -f 456//456 484//484 472//472 -f 485//485 486//486 487//487 -f 487//487 486//486 488//488 -f 487//487 488//488 489//489 -f 485//485 490//490 486//486 -f 486//486 490//490 491//491 -f 486//486 491//491 492//492 -f 492//492 491//491 493//493 -f 494//494 495//495 496//496 -f 496//496 495//495 492//492 -f 496//496 492//492 497//497 -f 497//497 492//492 493//493 -f 498//498 499//499 488//488 -f 488//488 499//499 500//500 -f 488//488 500//500 489//489 -f 501//501 502//502 488//488 -f 488//488 502//502 495//495 -f 488//488 495//495 498//498 -f 498//498 495//495 494//494 -f 503//503 504//504 505//505 -f 505//505 504//504 506//506 -f 505//505 506//506 507//507 -f 508//508 509//509 510//510 -f 510//510 509//509 511//511 -f 510//510 511//511 512//512 -f 512//512 511//511 513//513 -f 513//513 511//511 514//514 -f 513//513 514//514 515//515 -f 515//515 514//514 516//516 -f 515//515 516//516 517//517 -f 517//517 518//518 515//515 -f 515//515 518//518 519//519 -f 515//515 519//519 488//488 -f 488//488 519//519 520//520 -f 488//488 520//520 501//501 -f 508//508 507//507 509//509 -f 509//509 507//507 506//506 -f 509//509 506//506 521//521 -f 521//521 506//506 495//495 -f 521//521 495//495 522//522 -f 522//522 495//495 502//502 -f 523//523 524//524 525//525 -f 525//525 524//524 526//526 -f 524//524 527//527 526//526 -f 526//526 527//527 528//528 -f 526//526 528//528 529//529 -f 529//529 528//528 530//530 -f 529//529 530//530 531//531 -f 531//531 530//530 532//532 -f 531//531 532//532 533//533 -f 533//533 532//532 534//534 -f 533//533 534//534 515//515 -f 525//525 535//535 523//523 -f 523//523 535//535 536//536 -f 523//523 536//536 537//537 -f 537//537 536//536 538//538 -f 537//537 538//538 539//539 -f 539//539 538//538 540//540 -f 539//539 540//540 541//541 -f 541//541 540//540 513//513 -f 541//541 513//513 542//542 -f 542//542 513//513 515//515 -f 542//542 515//515 543//543 -f 543//543 515//515 534//534 -f 486//486 544//544 545//545 -f 486//486 545//545 546//546 -f 545//545 547//547 546//546 -f 546//546 547//547 548//548 -f 546//546 548//548 549//549 -f 549//549 548//548 550//550 -f 549//549 550//550 551//551 -f 551//551 550//550 552//552 -f 551//551 552//552 553//553 -f 553//553 554//554 555//555 -f 555//555 554//554 556//556 -f 555//555 556//556 557//557 -f 557//557 556//556 558//558 -f 559//559 560//560 558//558 -f 558//558 560//560 561//561 -f 558//558 561//561 557//557 -f 562//562 544//544 563//563 -f 563//563 544//544 486//486 -f 563//563 486//486 564//564 -f 564//564 486//486 492//492 -f 564//564 492//492 565//565 -f 565//565 492//492 566//566 -f 565//565 566//566 567//567 -f 567//567 566//566 471//471 -f 567//567 471//471 568//568 -f 568//568 471//471 475//475 -f 563//563 569//569 562//562 -f 562//562 569//569 570//570 -f 562//562 570//570 559//559 -f 559//559 570//570 571//571 -f 559//559 571//571 560//560 -f 555//555 572//572 573//573 -f 553//553 555//555 551//551 -f 551//551 555//555 573//573 -f 551//551 573//573 574//574 -f 435//435 437//437 438//438 -f 438//438 437//437 575//575 -f 438//438 575//575 460//460 -f 460//460 575//575 576//576 -f 460//460 576//576 470//470 -f 470//470 576//576 577//577 -f 470//470 577//577 578//578 -f 525//525 526//526 379//379 -f 379//379 526//526 373//373 -f 546//546 549//549 348//348 -f 348//348 549//549 346//346 -f 346//346 549//549 336//336 -f 336//336 549//549 551//551 -f 336//336 551//551 358//358 -f 358//358 551//551 574//574 -f 358//358 574//574 357//357 -f 433//433 437//437 436//436 -f 433//433 436//436 434//434 -f 434//434 436//436 435//435 -f 434//434 435//435 424//424 -f 424//424 435//435 443//443 -f 424//424 443//443 425//425 -f 373//373 526//526 529//529 -f 373//373 529//529 371//371 -f 371//371 529//529 531//531 -f 371//371 531//531 369//369 -f 369//369 531//531 533//533 -f 369//369 533//533 367//367 -f 546//546 348//348 486//486 -f 486//486 348//348 319//319 -f 486//486 319//319 488//488 -f 488//488 319//319 329//329 -f 488//488 329//329 515//515 -f 515//515 329//329 364//364 -f 515//515 364//364 533//533 -f 533//533 364//364 367//367 -f 431//431 577//577 291//291 -f 291//291 577//577 576//576 -f 291//291 576//576 292//292 -f 292//292 576//576 575//575 -f 292//292 575//575 433//433 -f 433//433 575//575 437//437 -f 347//347 548//548 349//349 -f 349//349 548//548 547//547 -f 349//349 547//547 350//350 -f 350//350 547//547 545//545 -f 350//350 545//545 344//344 -f 344//344 545//545 544//544 -f 344//344 544//544 345//345 -f 345//345 544//544 562//562 -f 345//345 562//562 343//343 -f 343//343 562//562 559//559 -f 343//343 559//559 341//341 -f 341//341 559//559 558//558 -f 341//341 558//558 339//339 -f 339//339 558//558 556//556 -f 339//339 556//556 337//337 -f 337//337 556//556 554//554 -f 337//337 554//554 338//338 -f 338//338 554//554 553//553 -f 338//338 553//553 334//334 -f 334//334 553//553 552//552 -f 334//334 552//552 335//335 -f 335//335 552//552 550//550 -f 335//335 550//550 347//347 -f 347//347 550//550 548//548 -f 328//328 487//487 330//330 -f 330//330 487//487 489//489 -f 330//330 489//489 331//331 -f 331//331 489//489 500//500 -f 331//331 500//500 332//332 -f 332//332 500//500 499//499 -f 332//332 499//499 333//333 -f 333//333 499//499 498//498 -f 333//333 498//498 323//323 -f 323//323 498//498 494//494 -f 323//323 494//494 321//321 -f 321//321 494//494 496//496 -f 321//321 496//496 351//351 -f 351//351 496//496 497//497 -f 351//351 497//497 317//317 -f 317//317 497//497 493//493 -f 317//317 493//493 318//318 -f 318//318 493//493 491//491 -f 318//318 491//491 320//320 -f 320//320 491//491 490//490 -f 320//320 490//490 327//327 -f 327//327 490//490 485//485 -f 327//327 485//485 328//328 -f 328//328 485//485 487//487 -f 392//392 519//519 391//391 -f 391//391 519//519 518//518 -f 391//391 518//518 394//394 -f 394//394 518//518 517//517 -f 394//394 517//517 395//395 -f 395//395 517//517 516//516 -f 395//395 516//516 396//396 -f 396//396 516//516 514//514 -f 396//396 514//514 398//398 -f 398//398 514//514 511//511 -f 398//398 511//511 399//399 -f 399//399 511//511 509//509 -f 399//399 509//509 390//390 -f 390//390 509//509 521//521 -f 390//390 521//521 389//389 -f 389//389 521//521 522//522 -f 389//389 522//522 387//387 -f 387//387 522//522 502//502 -f 387//387 502//502 388//388 -f 388//388 502//502 501//501 -f 388//388 501//501 393//393 -f 393//393 501//501 520//520 -f 393//393 520//520 392//392 -f 392//392 520//520 519//519 -f 370//370 532//532 372//372 -f 372//372 532//532 530//530 -f 372//372 530//530 381//381 -f 381//381 530//530 528//528 -f 381//381 528//528 380//380 -f 380//380 528//528 527//527 -f 380//380 527//527 378//378 -f 378//378 527//527 524//524 -f 378//378 524//524 376//376 -f 376//376 524//524 523//523 -f 376//376 523//523 359//359 -f 359//359 523//523 537//537 -f 359//359 537//537 360//360 -f 360//360 537//537 539//539 -f 360//360 539//539 363//363 -f 363//363 539//539 541//541 -f 363//363 541//541 365//365 -f 365//365 541//541 542//542 -f 365//365 542//542 366//366 -f 366//366 542//542 543//543 -f 366//366 543//543 368//368 -f 368//368 543//543 534//534 -f 368//368 534//534 370//370 -f 370//370 534//534 532//532 -f 311//311 473//473 309//309 -f 309//309 473//473 472//472 -f 309//309 472//472 314//314 -f 314//314 472//472 484//484 -f 314//314 484//484 315//315 -f 315//315 484//484 483//483 -f 315//315 483//483 316//316 -f 316//316 483//483 482//482 -f 316//316 482//482 296//296 -f 296//296 482//482 468//468 -f 296//296 468//468 297//297 -f 297//297 468//468 469//469 -f 297//297 469//469 299//299 -f 299//299 469//469 481//481 -f 299//299 481//481 300//300 -f 300//300 481//481 480//480 -f 300//300 480//480 302//302 -f 302//302 480//480 478//478 -f 302//302 478//478 313//313 -f 313//313 478//478 476//476 -f 313//313 476//476 312//312 -f 312//312 476//476 474//474 -f 312//312 474//474 311//311 -f 311//311 474//474 473//473 -f 413//413 464//464 419//419 -f 419//419 464//464 450//450 -f 419//419 450//450 406//406 -f 406//406 450//450 448//448 -f 406//406 448//448 407//407 -f 407//407 448//448 447//447 -f 407//407 447//447 409//409 -f 409//409 447//447 446//446 -f 409//409 446//446 410//410 -f 410//410 446//446 462//462 -f 410//410 462//462 402//402 -f 402//402 462//462 461//461 -f 402//402 461//461 403//403 -f 403//403 461//461 459//459 -f 403//403 459//459 404//404 -f 404//404 459//459 458//458 -f 404//404 458//458 405//405 -f 405//405 458//458 467//467 -f 405//405 467//467 411//411 -f 411//411 467//467 466//466 -f 411//411 466//466 412//412 -f 412//412 466//466 465//465 -f 412//412 465//465 413//413 -f 413//413 465//465 464//464 -f 426//426 425//425 444//444 -f 444//444 425//425 443//443 -f 293//293 357//357 573//573 -f 573//573 357//357 574//574 -f 421//421 454//454 310//310 -f 310//310 454//454 456//456 -f 310//310 456//456 307//307 -f 307//307 456//456 471//471 -f 506//506 384//384 495//495 -f 495//495 384//384 324//324 -f 495//495 324//324 492//492 -f 492//492 324//324 322//322 -f 386//386 385//385 507//507 -f 507//507 385//385 505//505 -f 540//540 361//361 513//513 -f 513//513 361//361 362//362 -f 513//513 362//362 512//512 -f 512//512 362//362 397//397 -f 457//457 455//455 422//422 -f 422//422 455//455 414//414 -f 429//429 440//440 417//417 -f 417//417 440//440 439//439 -f 417//417 439//439 418//418 -f 418//418 439//439 449//449 -f 440//440 429//429 430//430 -f 440//440 430//430 441//441 -f 441//441 430//430 428//428 -f 441//441 428//428 442//442 -f 442//442 428//428 427//427 -f 442//442 427//427 445//445 -f 445//445 427//427 426//426 -f 445//445 426//426 444//444 -f 361//361 540//540 538//538 -f 361//361 538//538 374//374 -f 374//374 538//538 536//536 -f 374//374 536//536 375//375 -f 375//375 536//536 535//535 -f 375//375 535//535 377//377 -f 377//377 535//535 525//525 -f 377//377 525//525 379//379 -f 418//418 449//449 420//420 -f 420//420 449//449 451//451 -f 420//420 451//451 423//423 -f 423//423 451//451 463//463 -f 423//423 463//463 422//422 -f 422//422 463//463 457//457 -f 386//386 507//507 400//400 -f 400//400 507//507 508//508 -f 400//400 508//508 401//401 -f 401//401 508//508 510//510 -f 401//401 510//510 397//397 -f 397//397 510//510 512//512 -f 454//454 421//421 416//416 -f 454//454 416//416 452//452 -f 452//452 416//416 415//415 -f 452//452 415//415 453//453 -f 453//453 415//415 414//414 -f 453//453 414//414 455//455 -f 384//384 506//506 504//504 -f 384//384 504//504 382//382 -f 382//382 504//504 503//503 -f 382//382 503//503 383//383 -f 383//383 503//503 505//505 -f 383//383 505//505 385//385 -f 492//492 322//322 566//566 -f 566//566 322//322 305//305 -f 566//566 305//305 471//471 -f 471//471 305//305 307//307 -f 354//354 560//560 355//355 -f 355//355 560//560 571//571 -f 355//355 571//571 356//356 -f 356//356 571//571 570//570 -f 356//356 570//570 353//353 -f 353//353 570//570 569//569 -f 353//353 569//569 352//352 -f 352//352 569//569 563//563 -f 352//352 563//563 325//325 -f 325//325 563//563 564//564 -f 325//325 564//564 326//326 -f 326//326 564//564 565//565 -f 326//326 565//565 306//306 -f 306//306 565//565 567//567 -f 306//306 567//567 308//308 -f 308//308 567//567 568//568 -f 308//308 568//568 304//304 -f 304//304 568//568 475//475 -f 561//561 560//560 342//342 -f 342//342 560//560 354//354 -f 303//303 304//304 477//477 -f 477//477 304//304 475//475 -f 303//303 477//477 479//479 -f 303//303 479//479 301//301 -f 301//301 479//479 470//470 -f 301//301 470//470 298//298 -f 298//298 470//470 578//578 -f 298//298 578//578 432//432 -f 432//432 578//578 577//577 -f 432//432 577//577 431//431 -f 561//561 342//342 340//340 -f 561//561 340//340 557//557 -f 557//557 340//340 295//295 -f 557//557 295//295 555//555 -f 555//555 295//295 294//294 -f 555//555 294//294 572//572 -f 572//572 294//294 293//293 -f 572//572 293//293 573//573 -f 579//579 580//580 581//581 -f 581//581 580//580 582//582 -f 583//583 584//584 585//585 -f 585//585 584//584 586//586 -f 587//587 588//588 589//589 -f 589//589 588//588 590//590 -f 591//591 592//592 593//593 -f 591//591 593//593 594//594 -f 594//594 593//593 595//595 -f 594//594 595//595 596//596 -f 596//596 595//595 597//597 -f 596//596 597//597 598//598 -f 598//598 597//597 590//590 -f 598//598 590//590 588//588 -f 599//599 600//600 601//601 -f 601//601 600//600 602//602 -f 602//602 600//600 603//603 -f 602//602 603//603 604//604 -f 604//604 603//603 605//605 -f 604//604 605//605 606//606 -f 606//606 605//605 607//607 -f 606//606 607//607 608//608 -f 608//608 607//607 609//609 -f 608//608 609//609 610//610 -f 611//611 612//612 613//613 -f 613//613 612//612 614//614 -f 613//613 614//614 615//615 -f 615//615 614//614 616//616 -f 615//615 616//616 617//617 -f 617//617 616//616 618//618 -f 617//617 618//618 619//619 -f 619//619 618//618 620//620 -f 619//619 620//620 621//621 -f 621//621 620//620 622//622 -f 621//621 622//622 609//609 -f 609//609 622//622 610//610 -f 612//612 611//611 623//623 -f 612//612 623//623 624//624 -f 624//624 623//623 625//625 -f 624//624 625//625 626//626 -f 626//626 625//625 627//627 -f 626//626 627//627 628//628 -f 628//628 627//627 629//629 -f 628//628 629//629 630//630 -f 631//631 632//632 633//633 -f 633//633 632//632 634//634 -f 633//633 634//634 635//635 -f 635//635 634//634 636//636 -f 635//635 636//636 637//637 -f 637//637 636//636 638//638 -f 637//637 638//638 639//639 -f 639//639 638//638 640//640 -f 639//639 640//640 629//629 -f 629//629 640//640 630//630 -f 632//632 631//631 641//641 -f 632//632 641//641 642//642 -f 642//642 641//641 643//643 -f 642//642 643//643 644//644 -f 644//644 643//643 645//645 -f 644//644 645//645 646//646 -f 646//646 645//645 647//647 -f 646//646 647//647 648//648 -f 592//592 591//591 649//649 -f 649//649 591//591 650//650 -f 649//649 650//650 651//651 -f 651//651 650//650 652//652 -f 651//651 652//652 653//653 -f 653//653 652//652 654//654 -f 653//653 654//654 655//655 -f 655//655 654//654 656//656 -f 655//655 656//656 657//657 -f 657//657 656//656 658//658 -f 657//657 658//658 647//647 -f 647//647 658//658 648//648 -f 659//659 660//660 661//661 -f 662//662 663//663 664//664 -f 665//665 666//666 667//667 -f 668//668 669//669 670//670 -f 670//670 669//669 671//671 -f 670//670 671//671 672//672 -f 673//673 674//674 675//675 -f 674//674 676//676 675//675 -f 675//675 676//676 677//677 -f 675//675 677//677 678//678 -f 678//678 677//677 679//679 -f 678//678 679//679 680//680 -f 680//680 679//679 681//681 -f 681//681 682//682 680//680 -f 680//680 682//682 683//683 -f 680//680 683//683 664//664 -f 664//664 683//683 684//684 -f 664//664 684//684 672//672 -f 685//685 686//686 687//687 -f 686//686 688//688 687//687 -f 687//687 688//688 689//689 -f 687//687 689//689 690//690 -f 690//690 689//689 691//691 -f 690//690 691//691 692//692 -f 692//692 691//691 693//693 -f 692//692 693//693 694//694 -f 695//695 618//618 696//696 -f 696//696 618//618 616//616 -f 696//696 616//616 697//697 -f 697//697 616//616 614//614 -f 697//697 614//614 698//698 -f 698//698 614//614 699//699 -f 700//700 701//701 702//702 -f 702//702 701//701 703//703 -f 665//665 667//667 703//703 -f 704//704 705//705 706//706 -f 706//706 705//705 707//707 -f 706//706 707//707 708//708 -f 704//704 709//709 705//705 -f 705//705 709//709 710//710 -f 705//705 710//710 711//711 -f 711//711 710//710 712//712 -f 711//711 712//712 700//700 -f 700//700 712//712 713//713 -f 700//700 713//713 701//701 -f 714//714 708//708 715//715 -f 715//715 708//708 707//707 -f 715//715 707//707 587//587 -f 587//587 707//707 716//716 -f 587//587 716//716 588//588 -f 588//588 716//716 598//598 -f 596//596 598//598 594//594 -f 594//594 598//598 716//716 -f 594//594 716//716 591//591 -f 591//591 716//716 717//717 -f 626//626 628//628 624//624 -f 624//624 628//628 630//630 -f 624//624 630//630 612//612 -f 612//612 630//630 640//640 -f 612//612 640//640 614//614 -f 614//614 640//640 692//692 -f 614//614 692//692 699//699 -f 699//699 692//692 694//694 -f 610//610 622//622 718//718 -f 667//667 719//719 720//720 -f 718//718 721//721 610//610 -f 610//610 721//721 722//722 -f 610//610 722//722 608//608 -f 703//703 667//667 702//702 -f 702//702 667//667 720//720 -f 702//702 720//720 723//723 -f 723//723 724//724 702//702 -f 702//702 724//724 725//725 -f 702//702 725//725 622//622 -f 622//622 725//725 726//726 -f 622//622 726//726 718//718 -f 722//722 727//727 608//608 -f 608//608 727//727 728//728 -f 608//608 728//728 667//667 -f 667//667 728//728 729//729 -f 667//667 729//729 719//719 -f 604//604 606//606 602//602 -f 602//602 606//606 608//608 -f 602//602 608//608 601//601 -f 601//601 608//608 667//667 -f 601//601 667//667 730//730 -f 730//730 667//667 666//666 -f 730//730 666//666 731//731 -f 584//584 583//583 732//732 -f 733//733 581//581 661//661 -f 661//661 581//581 582//582 -f 661//661 582//582 734//734 -f 733//733 661//661 735//735 -f 735//735 661//661 736//736 -f 735//735 736//736 737//737 -f 737//737 736//736 687//687 -f 737//737 687//687 738//738 -f 738//738 687//687 690//690 -f 738//738 690//690 739//739 -f 582//582 740//740 734//734 -f 734//734 740//740 584//584 -f 734//734 584//584 741//741 -f 741//741 584//584 732//732 -f 741//741 732//732 669//669 -f 669//669 732//732 742//742 -f 669//669 742//742 671//671 -f 671//671 742//742 743//743 -f 744//744 745//745 746//746 -f 746//746 745//745 747//747 -f 746//746 747//747 748//748 -f 748//748 747//747 671//671 -f 748//748 671//671 749//749 -f 749//749 671//671 743//743 -f 672//672 671//671 664//664 -f 664//664 671//671 750//750 -f 664//664 750//750 662//662 -f 751//751 752//752 747//747 -f 747//747 752//752 753//753 -f 747//747 753//753 671//671 -f 671//671 753//753 754//754 -f 671//671 754//754 750//750 -f 642//642 680//680 632//632 -f 632//632 680//680 664//664 -f 632//632 664//664 634//634 -f 634//634 664//664 663//663 -f 663//663 755//755 634//634 -f 634//634 755//755 756//756 -f 634//634 756//756 636//636 -f 636//636 756//756 757//757 -f 636//636 757//757 758//758 -f 758//758 757//757 759//759 -f 758//758 759//759 760//760 -f 761//761 762//762 745//745 -f 745//745 762//762 763//763 -f 764//764 758//758 747//747 -f 747//747 758//758 760//760 -f 747//747 760//760 751//751 -f 763//763 765//765 745//745 -f 745//745 765//765 766//766 -f 745//745 766//766 747//747 -f 747//747 766//766 767//767 -f 747//747 767//767 764//764 -f 638//638 768//768 761//761 -f 761//761 768//768 769//769 -f 761//761 769//769 762//762 -f 764//764 770//770 758//758 -f 758//758 770//770 771//771 -f 758//758 771//771 636//636 -f 636//636 771//771 772//772 -f 636//636 772//772 638//638 -f 638//638 772//772 773//773 -f 638//638 773//773 768//768 -f 640//640 638//638 692//692 -f 692//692 638//638 761//761 -f 692//692 761//761 690//690 -f 690//690 761//761 745//745 -f 690//690 745//745 739//739 -f 739//739 745//745 744//744 -f 739//739 744//744 774//774 -f 695//695 685//685 618//618 -f 618//618 685//685 687//687 -f 618//618 687//687 620//620 -f 620//620 687//687 736//736 -f 620//620 736//736 622//622 -f 775//775 776//776 734//734 -f 734//734 776//776 777//777 -f 622//622 736//736 702//702 -f 702//702 736//736 661//661 -f 702//702 661//661 700//700 -f 700//700 661//661 660//660 -f 700//700 660//660 778//778 -f 777//777 779//779 734//734 -f 734//734 779//779 780//780 -f 734//734 780//780 661//661 -f 661//661 780//780 781//781 -f 661//661 781//781 659//659 -f 778//778 782//782 700//700 -f 700//700 782//782 783//783 -f 700//700 783//783 711//711 -f 711//711 783//783 784//784 -f 785//785 786//786 734//734 -f 734//734 786//786 711//711 -f 734//734 711//711 775//775 -f 775//775 711//711 784//784 -f 787//787 788//788 741//741 -f 741//741 788//788 789//789 -f 741//741 789//789 734//734 -f 734//734 789//789 790//790 -f 734//734 790//790 785//785 -f 786//786 791//791 711//711 -f 711//711 791//791 792//792 -f 711//711 792//792 705//705 -f 705//705 792//792 793//793 -f 793//793 794//794 705//705 -f 705//705 794//794 795//795 -f 705//705 795//795 741//741 -f 741//741 795//795 796//796 -f 741//741 796//796 787//787 -f 644//644 646//646 642//642 -f 642//642 646//646 648//648 -f 642//642 648//648 680//680 -f 680//680 648//648 658//658 -f 680//680 658//658 678//678 -f 678//678 658//658 656//656 -f 678//678 656//656 675//675 -f 675//675 656//656 654//654 -f 675//675 654//654 797//797 -f 797//797 654//654 652//652 -f 797//797 652//652 717//717 -f 717//717 652//652 650//650 -f 717//717 650//650 591//591 -f 707//707 798//798 799//799 -f 707//707 799//799 716//716 -f 716//716 799//799 800//800 -f 716//716 800//800 801//801 -f 801//801 802//802 716//716 -f 716//716 802//802 803//803 -f 716//716 803//803 717//717 -f 717//717 803//803 804//804 -f 717//717 804//804 805//805 -f 805//805 806//806 717//717 -f 717//717 806//806 705//705 -f 717//717 705//705 797//797 -f 797//797 705//705 741//741 -f 797//797 741//741 675//675 -f 675//675 741//741 669//669 -f 675//675 669//669 673//673 -f 673//673 669//669 668//668 -f 806//806 807//807 705//705 -f 705//705 807//807 808//808 -f 705//705 808//808 707//707 -f 707//707 808//808 809//809 -f 707//707 809//809 798//798 -f 810//810 811//811 812//812 -f 813//813 814//814 815//815 -f 816//816 817//817 818//818 -f 631//631 633//633 819//819 -f 611//611 613//613 820//820 -f 599//599 821//821 822//822 -f 607//607 605//605 603//603 -f 599//599 822//822 600//600 -f 823//823 824//824 822//822 -f 822//822 824//824 607//607 -f 822//822 607//607 600//600 -f 600//600 607//607 603//603 -f 824//824 825//825 607//607 -f 607//607 825//825 826//826 -f 607//607 826//826 609//609 -f 826//826 827//827 609//609 -f 609//609 827//827 828//828 -f 609//609 828//828 621//621 -f 621//621 828//828 829//829 -f 621//621 829//829 830//830 -f 831//831 832//832 833//833 -f 833//833 832//832 834//834 -f 833//833 834//834 822//822 -f 822//822 834//834 835//835 -f 822//822 835//835 823//823 -f 629//629 627//627 625//625 -f 645//645 643//643 647//647 -f 647//647 643//643 641//641 -f 647//647 641//641 657//657 -f 590//590 597//597 836//836 -f 836//836 597//597 595//595 -f 836//836 595//595 593//593 -f 590//590 836//836 589//589 -f 589//589 836//836 837//837 -f 589//589 837//837 838//838 -f 837//837 839//839 840//840 -f 841//841 838//838 842//842 -f 842//842 838//838 837//837 -f 842//842 837//837 843//843 -f 843//843 837//837 840//840 -f 844//844 845//845 839//839 -f 839//839 845//845 846//846 -f 839//839 846//846 840//840 -f 847//847 848//848 849//849 -f 847//847 849//849 850//850 -f 848//848 847//847 851//851 -f 851//851 847//847 833//833 -f 851//851 833//833 852//852 -f 852//852 833//833 822//822 -f 852//852 822//822 853//853 -f 853//853 822//822 821//821 -f 853//853 821//821 854//854 -f 855//855 856//856 857//857 -f 858//858 859//859 860//860 -f 860//860 859//859 861//861 -f 860//860 861//861 862//862 -f 862//862 861//861 857//857 -f 863//863 864//864 819//819 -f 863//863 819//819 858//858 -f 864//864 865//865 819//819 -f 819//819 865//865 866//866 -f 819//819 866//866 631//631 -f 865//865 867//867 866//866 -f 866//866 867//867 868//868 -f 866//866 868//868 869//869 -f 869//869 868//868 870//870 -f 869//869 870//870 855//855 -f 855//855 870//870 871//871 -f 855//855 871//871 856//856 -f 818//818 817//817 872//872 -f 817//817 873//873 872//872 -f 872//872 873//873 874//874 -f 872//872 874//874 875//875 -f 875//875 876//876 617//617 -f 617//617 876//876 877//877 -f 617//617 877//877 615//615 -f 615//615 877//877 878//878 -f 615//615 878//878 613//613 -f 613//613 878//878 879//879 -f 879//879 880//880 613//613 -f 613//613 880//880 881//881 -f 613//613 881//881 820//820 -f 820//820 881//881 882//882 -f 883//883 884//884 885//885 -f 886//886 887//887 888//888 -f 888//888 887//887 889//889 -f 888//888 889//889 872//872 -f 872//872 889//889 890//890 -f 872//872 890//890 818//818 -f 818//818 890//890 891//891 -f 818//818 891//891 892//892 -f 892//892 891//891 893//893 -f 892//892 893//893 894//894 -f 895//895 896//896 897//897 -f 897//897 896//896 883//883 -f 897//897 883//883 859//859 -f 859//859 883//883 885//885 -f 859//859 885//885 861//861 -f 861//861 885//885 898//898 -f 861//861 898//898 812//812 -f 812//812 898//898 899//899 -f 579//579 887//887 580//580 -f 580//580 887//887 886//886 -f 580//580 886//886 900//900 -f 900//900 886//886 815//815 -f 900//900 815//815 586//586 -f 586//586 815//815 812//812 -f 586//586 812//812 585//585 -f 585//585 812//812 899//899 -f 858//858 819//819 859//859 -f 859//859 819//819 901//901 -f 859//859 901//901 902//902 -f 902//902 903//903 859//859 -f 859//859 903//903 904//904 -f 859//859 904//904 897//897 -f 897//897 904//904 905//905 -f 897//897 905//905 906//906 -f 633//633 907//907 819//819 -f 819//819 907//907 908//908 -f 819//819 908//908 901//901 -f 906//906 909//909 910//910 -f 910//910 909//909 911//911 -f 910//910 911//911 635//635 -f 635//635 911//911 912//912 -f 635//635 912//912 633//633 -f 633//633 912//912 913//913 -f 633//633 913//913 907//907 -f 914//914 915//915 916//916 -f 917//917 918//918 897//897 -f 919//919 920//920 892//892 -f 906//906 910//910 897//897 -f 897//897 910//910 921//921 -f 897//897 921//921 917//917 -f 894//894 895//895 892//892 -f 892//892 895//895 897//897 -f 892//892 897//897 919//919 -f 919//919 897//897 918//918 -f 922//922 923//923 637//637 -f 637//637 923//923 924//924 -f 637//637 924//924 635//635 -f 635//635 924//924 925//925 -f 635//635 925//925 910//910 -f 910//910 925//925 926//926 -f 910//910 926//926 921//921 -f 836//836 927//927 928//928 -f 929//929 930//930 931//931 -f 931//931 930//930 932//932 -f 593//593 592//592 836//836 -f 836//836 592//592 931//931 -f 836//836 931//931 927//927 -f 927//927 931//931 932//932 -f 933//933 837//837 934//934 -f 934//934 837//837 836//836 -f 934//934 836//836 935//935 -f 935//935 836//836 928//928 -f 933//933 936//936 837//837 -f 837//837 936//936 937//937 -f 837//837 937//937 839//839 -f 839//839 937//937 938//938 -f 839//839 938//938 939//939 -f 847//847 940//940 941//941 -f 886//886 942//942 943//943 -f 815//815 814//814 850//850 -f 888//888 833//833 886//886 -f 886//886 833//833 847//847 -f 886//886 847//847 942//942 -f 942//942 847//847 941//941 -f 943//943 944//944 886//886 -f 886//886 944//944 945//945 -f 886//886 945//945 815//815 -f 815//815 945//945 946//946 -f 815//815 946//946 813//813 -f 814//814 947//947 850//850 -f 850//850 947//947 948//948 -f 850//850 948//948 847//847 -f 847//847 948//948 949//949 -f 847//847 949//949 940//940 -f 812//812 811//811 839//839 -f 839//839 811//811 950//950 -f 839//839 950//950 951//951 -f 951//951 952//952 839//839 -f 839//839 952//952 850//850 -f 839//839 850//850 844//844 -f 844//844 850//850 849//849 -f 953//953 954//954 815//815 -f 815//815 954//954 955//955 -f 815//815 955//955 812//812 -f 812//812 955//955 956//956 -f 812//812 956//956 810//810 -f 952//952 957//957 850//850 -f 850//850 957//957 958//958 -f 850//850 958//958 815//815 -f 815//815 958//958 959//959 -f 815//815 959//959 953//953 -f 875//875 617//617 872//872 -f 872//872 617//617 619//619 -f 872//872 619//619 888//888 -f 888//888 619//619 621//621 -f 888//888 621//621 833//833 -f 833//833 621//621 830//830 -f 833//833 830//830 831//831 -f 857//857 861//861 855//855 -f 855//855 861//861 812//812 -f 855//855 812//812 960//960 -f 960//960 812//812 839//839 -f 960//960 839//839 931//931 -f 931//931 839//839 939//939 -f 931//931 939//939 929//929 -f 920//920 914//914 892//892 -f 892//892 914//914 916//916 -f 892//892 916//916 818//818 -f 818//818 916//916 820//820 -f 818//818 820//820 816//816 -f 816//816 820//820 882//882 -f 592//592 649//649 931//931 -f 931//931 649//649 651//651 -f 931//931 651//651 960//960 -f 960//960 651//651 653//653 -f 960//960 653//653 855//855 -f 855//855 653//653 655//655 -f 855//855 655//655 869//869 -f 869//869 655//655 657//657 -f 869//869 657//657 866//866 -f 866//866 657//657 641//641 -f 866//866 641//641 631//631 -f 915//915 922//922 916//916 -f 916//916 922//922 637//637 -f 916//916 637//637 820//820 -f 820//820 637//637 639//639 -f 820//820 639//639 611//611 -f 611//611 639//639 629//629 -f 611//611 629//629 623//623 -f 623//623 629//629 625//625 -f 858//858 670//670 863//863 -f 863//863 670//670 672//672 -f 863//863 672//672 864//864 -f 864//864 672//672 684//684 -f 864//864 684//684 865//865 -f 865//865 684//684 683//683 -f 865//865 683//683 867//867 -f 867//867 683//683 682//682 -f 867//867 682//682 868//868 -f 868//868 682//682 681//681 -f 868//868 681//681 870//870 -f 870//870 681//681 679//679 -f 870//870 679//679 871//871 -f 871//871 679//679 677//677 -f 871//871 677//677 856//856 -f 856//856 677//677 676//676 -f 856//856 676//676 857//857 -f 857//857 676//676 674//674 -f 857//857 674//674 862//862 -f 862//862 674//674 673//673 -f 862//862 673//673 860//860 -f 860//860 673//673 668//668 -f 860//860 668//668 858//858 -f 858//858 668//668 670//670 -f 937//937 809//809 938//938 -f 938//938 809//809 808//808 -f 938//938 808//808 939//939 -f 939//939 808//808 807//807 -f 939//939 807//807 929//929 -f 929//929 807//807 806//806 -f 929//929 806//806 930//930 -f 930//930 806//806 805//805 -f 930//930 805//805 932//932 -f 932//932 805//805 804//804 -f 932//932 804//804 927//927 -f 927//927 804//804 803//803 -f 927//927 803//803 928//928 -f 928//928 803//803 802//802 -f 928//928 802//802 935//935 -f 935//935 802//802 801//801 -f 935//935 801//801 934//934 -f 934//934 801//801 800//800 -f 934//934 800//800 933//933 -f 933//933 800//800 799//799 -f 933//933 799//799 936//936 -f 936//936 799//799 798//798 -f 936//936 798//798 937//937 -f 937//937 798//798 809//809 -f 828//828 721//721 829//829 -f 829//829 721//721 718//718 -f 829//829 718//718 830//830 -f 830//830 718//718 726//726 -f 830//830 726//726 831//831 -f 831//831 726//726 725//725 -f 831//831 725//725 832//832 -f 832//832 725//725 724//724 -f 832//832 724//724 834//834 -f 834//834 724//724 723//723 -f 834//834 723//723 835//835 -f 835//835 723//723 720//720 -f 835//835 720//720 823//823 -f 823//823 720//720 719//719 -f 823//823 719//719 824//824 -f 824//824 719//719 729//729 -f 824//824 729//729 825//825 -f 825//825 729//729 728//728 -f 825//825 728//728 826//826 -f 826//826 728//728 727//727 -f 826//826 727//727 827//827 -f 827//827 727//727 722//722 -f 827//827 722//722 828//828 -f 828//828 722//722 721//721 -f 878//878 696//696 879//879 -f 879//879 696//696 697//697 -f 879//879 697//697 880//880 -f 880//880 697//697 698//698 -f 880//880 698//698 881//881 -f 881//881 698//698 699//699 -f 881//881 699//699 882//882 -f 882//882 699//699 694//694 -f 882//882 694//694 816//816 -f 816//816 694//694 693//693 -f 816//816 693//693 817//817 -f 817//817 693//693 691//691 -f 817//817 691//691 873//873 -f 873//873 691//691 689//689 -f 873//873 689//689 874//874 -f 874//874 689//689 688//688 -f 874//874 688//688 875//875 -f 875//875 688//688 686//686 -f 875//875 686//686 876//876 -f 876//876 686//686 685//685 -f 876//876 685//685 877//877 -f 877//877 685//685 695//695 -f 877//877 695//695 878//878 -f 878//878 695//695 696//696 -f 706//706 708//708 843//843 -f 843//843 708//708 842//842 -f 849//849 713//713 844//844 -f 844//844 713//713 712//712 -f 844//844 712//712 845//845 -f 845//845 712//712 710//710 -f 852//852 853//853 665//665 -f 665//665 853//853 666//666 -f 713//713 849//849 701//701 -f 701//701 849//849 848//848 -f 701//701 848//848 703//703 -f 703//703 848//848 851//851 -f 703//703 851//851 665//665 -f 665//665 851//851 852//852 -f 599//599 601//601 730//730 -f 599//599 730//730 821//821 -f 821//821 730//730 731//731 -f 821//821 731//731 854//854 -f 854//854 731//731 666//666 -f 854//854 666//666 853//853 -f 706//706 843//843 704//704 -f 704//704 843//843 840//840 -f 704//704 840//840 709//709 -f 709//709 840//840 846//846 -f 709//709 846//846 710//710 -f 710//710 846//846 845//845 -f 842//842 708//708 714//714 -f 842//842 714//714 841//841 -f 841//841 714//714 715//715 -f 841//841 715//715 838//838 -f 838//838 715//715 587//587 -f 838//838 587//587 589//589 -f 774//774 744//744 894//894 -f 894//894 744//744 895//895 -f 582//582 580//580 740//740 -f 740//740 580//580 900//900 -f 740//740 900//900 584//584 -f 584//584 900//900 586//586 -f 884//884 883//883 749//749 -f 749//749 883//883 748//748 -f 748//748 883//883 746//746 -f 746//746 883//883 896//896 -f 746//746 896//896 744//744 -f 744//744 896//896 895//895 -f 732//732 583//583 899//899 -f 899//899 583//583 585//585 -f 885//885 884//884 743//743 -f 743//743 884//884 749//749 -f 732//732 899//899 742//742 -f 742//742 899//899 898//898 -f 742//742 898//898 743//743 -f 743//743 898//898 885//885 -f 735//735 889//889 733//733 -f 733//733 889//889 887//887 -f 733//733 887//887 581//581 -f 581//581 887//887 579//579 -f 891//891 738//738 893//893 -f 893//893 738//738 739//739 -f 893//893 739//739 894//894 -f 894//894 739//739 774//774 -f 738//738 891//891 737//737 -f 737//737 891//891 890//890 -f 737//737 890//890 735//735 -f 735//735 890//890 889//889 -f 909//909 760//760 911//911 -f 911//911 760//760 759//759 -f 911//911 759//759 912//912 -f 912//912 759//759 757//757 -f 912//912 757//757 913//913 -f 913//913 757//757 756//756 -f 913//913 756//756 907//907 -f 907//907 756//756 755//755 -f 907//907 755//755 908//908 -f 908//908 755//755 663//663 -f 908//908 663//663 901//901 -f 901//901 663//663 662//662 -f 901//901 662//662 902//902 -f 902//902 662//662 750//750 -f 902//902 750//750 903//903 -f 903//903 750//750 754//754 -f 903//903 754//754 904//904 -f 904//904 754//754 753//753 -f 904//904 753//753 905//905 -f 905//905 753//753 752//752 -f 905//905 752//752 906//906 -f 906//906 752//752 751//751 -f 906//906 751//751 909//909 -f 909//909 751//751 760//760 -f 915//915 762//762 922//922 -f 922//922 762//762 769//769 -f 922//922 769//769 923//923 -f 923//923 769//769 768//768 -f 923//923 768//768 924//924 -f 924//924 768//768 773//773 -f 924//924 773//773 925//925 -f 925//925 773//773 772//772 -f 925//925 772//772 926//926 -f 926//926 772//772 771//771 -f 926//926 771//771 921//921 -f 921//921 771//771 770//770 -f 921//921 770//770 917//917 -f 917//917 770//770 764//764 -f 917//917 764//764 918//918 -f 918//918 764//764 767//767 -f 918//918 767//767 919//919 -f 919//919 767//767 766//766 -f 919//919 766//766 920//920 -f 920//920 766//766 765//765 -f 920//920 765//765 914//914 -f 914//914 765//765 763//763 -f 914//914 763//763 915//915 -f 915//915 763//763 762//762 -f 942//942 660//660 943//943 -f 943//943 660//660 659//659 -f 943//943 659//659 944//944 -f 944//944 659//659 781//781 -f 944//944 781//781 945//945 -f 945//945 781//781 780//780 -f 945//945 780//780 946//946 -f 946//946 780//780 779//779 -f 946//946 779//779 813//813 -f 813//813 779//779 777//777 -f 813//813 777//777 814//814 -f 814//814 777//777 776//776 -f 814//814 776//776 947//947 -f 947//947 776//776 775//775 -f 947//947 775//775 948//948 -f 948//948 775//775 784//784 -f 948//948 784//784 949//949 -f 949//949 784//784 783//783 -f 949//949 783//783 940//940 -f 940//940 783//783 782//782 -f 940//940 782//782 941//941 -f 941//941 782//782 778//778 -f 941//941 778//778 942//942 -f 942//942 778//778 660//660 -f 959//959 786//786 953//953 -f 953//953 786//786 785//785 -f 953//953 785//785 954//954 -f 954//954 785//785 790//790 -f 954//954 790//790 955//955 -f 955//955 790//790 789//789 -f 955//955 789//789 956//956 -f 956//956 789//789 788//788 -f 956//956 788//788 810//810 -f 810//810 788//788 787//787 -f 810//810 787//787 811//811 -f 811//811 787//787 796//796 -f 811//811 796//796 950//950 -f 950//950 796//796 795//795 -f 950//950 795//795 951//951 -f 951//951 795//795 794//794 -f 951//951 794//794 952//952 -f 952//952 794//794 793//793 -f 952//952 793//793 957//957 -f 957//957 793//793 792//792 -f 957//957 792//792 958//958 -f 958//958 792//792 791//791 -f 958//958 791//791 959//959 -f 959//959 791//791 786//786 -f 961//961 962//962 963//963 -f 963//963 962//962 964//964 -f 965//965 966//966 967//967 -f 967//967 966//966 968//968 -f 969//969 970//970 971//971 -f 971//971 970//970 972//972 -f 973//973 974//974 975//975 -f 973//973 975//975 976//976 -f 976//976 975//975 977//977 -f 976//976 977//977 978//978 -f 978//978 977//977 979//979 -f 978//978 979//979 980//980 -f 980//980 979//979 972//972 -f 980//980 972//972 970//970 -f 981//981 982//982 983//983 -f 983//983 982//982 984//984 -f 984//984 982//982 985//985 -f 984//984 985//985 986//986 -f 986//986 985//985 987//987 -f 986//986 987//987 988//988 -f 988//988 987//987 989//989 -f 988//988 989//989 990//990 -f 990//990 989//989 991//991 -f 990//990 991//991 992//992 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 997//997 -f 997//997 996//996 998//998 -f 997//997 998//998 999//999 -f 999//999 998//998 1000//1000 -f 999//999 1000//1000 1001//1001 -f 1001//1001 1000//1000 1002//1002 -f 1001//1001 1002//1002 1003//1003 -f 1003//1003 1002//1002 1004//1004 -f 1003//1003 1004//1004 991//991 -f 991//991 1004//1004 992//992 -f 994//994 993//993 1005//1005 -f 994//994 1005//1005 1006//1006 -f 1006//1006 1005//1005 1007//1007 -f 1006//1006 1007//1007 1008//1008 -f 1008//1008 1007//1007 1009//1009 -f 1008//1008 1009//1009 1010//1010 -f 1010//1010 1009//1009 1011//1011 -f 1010//1010 1011//1011 1012//1012 -f 1013//1013 1014//1014 1015//1015 -f 1015//1015 1014//1014 1016//1016 -f 1015//1015 1016//1016 1017//1017 -f 1017//1017 1016//1016 1018//1018 -f 1017//1017 1018//1018 1019//1019 -f 1019//1019 1018//1018 1020//1020 -f 1019//1019 1020//1020 1021//1021 -f 1021//1021 1020//1020 1022//1022 -f 1021//1021 1022//1022 1011//1011 -f 1011//1011 1022//1022 1012//1012 -f 1014//1014 1013//1013 1023//1023 -f 1014//1014 1023//1023 1024//1024 -f 1024//1024 1023//1023 1025//1025 -f 1024//1024 1025//1025 1026//1026 -f 1026//1026 1025//1025 1027//1027 -f 1026//1026 1027//1027 1028//1028 -f 1028//1028 1027//1027 1029//1029 -f 1028//1028 1029//1029 1030//1030 -f 974//974 973//973 1031//1031 -f 1031//1031 973//973 1032//1032 -f 1031//1031 1032//1032 1033//1033 -f 1033//1033 1032//1032 1034//1034 -f 1033//1033 1034//1034 1035//1035 -f 1035//1035 1034//1034 1036//1036 -f 1035//1035 1036//1036 1037//1037 -f 1037//1037 1036//1036 1038//1038 -f 1037//1037 1038//1038 1039//1039 -f 1039//1039 1038//1038 1040//1040 -f 1039//1039 1040//1040 1029//1029 -f 1029//1029 1040//1040 1030//1030 -f 1041//1041 1042//1042 1043//1043 -f 1044//1044 1045//1045 1046//1046 -f 1047//1047 1048//1048 1049//1049 -f 1050//1050 1051//1051 1052//1052 -f 1052//1052 1051//1051 1053//1053 -f 1052//1052 1053//1053 1054//1054 -f 1055//1055 1056//1056 1057//1057 -f 1056//1056 1058//1058 1057//1057 -f 1057//1057 1058//1058 1059//1059 -f 1057//1057 1059//1059 1060//1060 -f 1060//1060 1059//1059 1061//1061 -f 1060//1060 1061//1061 1062//1062 -f 1062//1062 1061//1061 1063//1063 -f 1063//1063 1064//1064 1062//1062 -f 1062//1062 1064//1064 1065//1065 -f 1062//1062 1065//1065 1046//1046 -f 1046//1046 1065//1065 1066//1066 -f 1046//1046 1066//1066 1054//1054 -f 1067//1067 1068//1068 1069//1069 -f 1068//1068 1070//1070 1069//1069 -f 1069//1069 1070//1070 1071//1071 -f 1069//1069 1071//1071 1072//1072 -f 1072//1072 1071//1071 1073//1073 -f 1072//1072 1073//1073 1074//1074 -f 1074//1074 1073//1073 1075//1075 -f 1074//1074 1075//1075 1076//1076 -f 1077//1077 1000//1000 1078//1078 -f 1078//1078 1000//1000 998//998 -f 1078//1078 998//998 1079//1079 -f 1079//1079 998//998 996//996 -f 1079//1079 996//996 1080//1080 -f 1080//1080 996//996 1081//1081 -f 1082//1082 1083//1083 1084//1084 -f 1084//1084 1083//1083 1085//1085 -f 1047//1047 1049//1049 1085//1085 -f 1086//1086 1087//1087 1088//1088 -f 1088//1088 1087//1087 1089//1089 -f 1088//1088 1089//1089 1090//1090 -f 1086//1086 1091//1091 1087//1087 -f 1087//1087 1091//1091 1092//1092 -f 1087//1087 1092//1092 1093//1093 -f 1093//1093 1092//1092 1094//1094 -f 1093//1093 1094//1094 1082//1082 -f 1082//1082 1094//1094 1095//1095 -f 1082//1082 1095//1095 1083//1083 -f 1096//1096 1090//1090 1097//1097 -f 1097//1097 1090//1090 1089//1089 -f 1097//1097 1089//1089 969//969 -f 969//969 1089//1089 1098//1098 -f 969//969 1098//1098 970//970 -f 970//970 1098//1098 980//980 -f 978//978 980//980 976//976 -f 976//976 980//980 1098//1098 -f 976//976 1098//1098 973//973 -f 973//973 1098//1098 1099//1099 -f 1008//1008 1010//1010 1006//1006 -f 1006//1006 1010//1010 1012//1012 -f 1006//1006 1012//1012 994//994 -f 994//994 1012//1012 1022//1022 -f 994//994 1022//1022 996//996 -f 996//996 1022//1022 1074//1074 -f 996//996 1074//1074 1081//1081 -f 1081//1081 1074//1074 1076//1076 -f 992//992 1004//1004 1100//1100 -f 1049//1049 1101//1101 1102//1102 -f 1100//1100 1103//1103 992//992 -f 992//992 1103//1103 1104//1104 -f 992//992 1104//1104 990//990 -f 1085//1085 1049//1049 1084//1084 -f 1084//1084 1049//1049 1102//1102 -f 1084//1084 1102//1102 1105//1105 -f 1105//1105 1106//1106 1084//1084 -f 1084//1084 1106//1106 1107//1107 -f 1084//1084 1107//1107 1004//1004 -f 1004//1004 1107//1107 1108//1108 -f 1004//1004 1108//1108 1100//1100 -f 1104//1104 1109//1109 990//990 -f 990//990 1109//1109 1110//1110 -f 990//990 1110//1110 1049//1049 -f 1049//1049 1110//1110 1111//1111 -f 1049//1049 1111//1111 1101//1101 -f 986//986 988//988 984//984 -f 984//984 988//988 990//990 -f 984//984 990//990 983//983 -f 983//983 990//990 1049//1049 -f 983//983 1049//1049 1112//1112 -f 1112//1112 1049//1049 1048//1048 -f 1112//1112 1048//1048 1113//1113 -f 966//966 965//965 1114//1114 -f 1115//1115 963//963 1043//1043 -f 1043//1043 963//963 964//964 -f 1043//1043 964//964 1116//1116 -f 1115//1115 1043//1043 1117//1117 -f 1117//1117 1043//1043 1118//1118 -f 1117//1117 1118//1118 1119//1119 -f 1119//1119 1118//1118 1069//1069 -f 1119//1119 1069//1069 1120//1120 -f 1120//1120 1069//1069 1072//1072 -f 1120//1120 1072//1072 1121//1121 -f 964//964 1122//1122 1116//1116 -f 1116//1116 1122//1122 966//966 -f 1116//1116 966//966 1123//1123 -f 1123//1123 966//966 1114//1114 -f 1123//1123 1114//1114 1051//1051 -f 1051//1051 1114//1114 1124//1124 -f 1051//1051 1124//1124 1053//1053 -f 1053//1053 1124//1124 1125//1125 -f 1126//1126 1127//1127 1128//1128 -f 1128//1128 1127//1127 1129//1129 -f 1128//1128 1129//1129 1130//1130 -f 1130//1130 1129//1129 1053//1053 -f 1130//1130 1053//1053 1131//1131 -f 1131//1131 1053//1053 1125//1125 -f 1054//1054 1053//1053 1046//1046 -f 1046//1046 1053//1053 1132//1132 -f 1046//1046 1132//1132 1044//1044 -f 1133//1133 1134//1134 1129//1129 -f 1129//1129 1134//1134 1135//1135 -f 1129//1129 1135//1135 1053//1053 -f 1053//1053 1135//1135 1136//1136 -f 1053//1053 1136//1136 1132//1132 -f 1024//1024 1062//1062 1014//1014 -f 1014//1014 1062//1062 1046//1046 -f 1014//1014 1046//1046 1016//1016 -f 1016//1016 1046//1046 1045//1045 -f 1045//1045 1137//1137 1016//1016 -f 1016//1016 1137//1137 1138//1138 -f 1016//1016 1138//1138 1018//1018 -f 1018//1018 1138//1138 1139//1139 -f 1018//1018 1139//1139 1140//1140 -f 1140//1140 1139//1139 1141//1141 -f 1140//1140 1141//1141 1142//1142 -f 1143//1143 1144//1144 1127//1127 -f 1127//1127 1144//1144 1145//1145 -f 1146//1146 1140//1140 1129//1129 -f 1129//1129 1140//1140 1142//1142 -f 1129//1129 1142//1142 1133//1133 -f 1145//1145 1147//1147 1127//1127 -f 1127//1127 1147//1147 1148//1148 -f 1127//1127 1148//1148 1129//1129 -f 1129//1129 1148//1148 1149//1149 -f 1129//1129 1149//1149 1146//1146 -f 1020//1020 1150//1150 1143//1143 -f 1143//1143 1150//1150 1151//1151 -f 1143//1143 1151//1151 1144//1144 -f 1146//1146 1152//1152 1140//1140 -f 1140//1140 1152//1152 1153//1153 -f 1140//1140 1153//1153 1018//1018 -f 1018//1018 1153//1153 1154//1154 -f 1018//1018 1154//1154 1020//1020 -f 1020//1020 1154//1154 1155//1155 -f 1020//1020 1155//1155 1150//1150 -f 1022//1022 1020//1020 1074//1074 -f 1074//1074 1020//1020 1143//1143 -f 1074//1074 1143//1143 1072//1072 -f 1072//1072 1143//1143 1127//1127 -f 1072//1072 1127//1127 1121//1121 -f 1121//1121 1127//1127 1126//1126 -f 1121//1121 1126//1126 1156//1156 -f 1077//1077 1067//1067 1000//1000 -f 1000//1000 1067//1067 1069//1069 -f 1000//1000 1069//1069 1002//1002 -f 1002//1002 1069//1069 1118//1118 -f 1002//1002 1118//1118 1004//1004 -f 1157//1157 1158//1158 1116//1116 -f 1116//1116 1158//1158 1159//1159 -f 1004//1004 1118//1118 1084//1084 -f 1084//1084 1118//1118 1043//1043 -f 1084//1084 1043//1043 1082//1082 -f 1082//1082 1043//1043 1042//1042 -f 1082//1082 1042//1042 1160//1160 -f 1159//1159 1161//1161 1116//1116 -f 1116//1116 1161//1161 1162//1162 -f 1116//1116 1162//1162 1043//1043 -f 1043//1043 1162//1162 1163//1163 -f 1043//1043 1163//1163 1041//1041 -f 1160//1160 1164//1164 1082//1082 -f 1082//1082 1164//1164 1165//1165 -f 1082//1082 1165//1165 1093//1093 -f 1093//1093 1165//1165 1166//1166 -f 1167//1167 1168//1168 1116//1116 -f 1116//1116 1168//1168 1093//1093 -f 1116//1116 1093//1093 1157//1157 -f 1157//1157 1093//1093 1166//1166 -f 1169//1169 1170//1170 1123//1123 -f 1123//1123 1170//1170 1171//1171 -f 1123//1123 1171//1171 1116//1116 -f 1116//1116 1171//1171 1172//1172 -f 1116//1116 1172//1172 1167//1167 -f 1168//1168 1173//1173 1093//1093 -f 1093//1093 1173//1173 1174//1174 -f 1093//1093 1174//1174 1087//1087 -f 1087//1087 1174//1174 1175//1175 -f 1175//1175 1176//1176 1087//1087 -f 1087//1087 1176//1176 1177//1177 -f 1087//1087 1177//1177 1123//1123 -f 1123//1123 1177//1177 1178//1178 -f 1123//1123 1178//1178 1169//1169 -f 1026//1026 1028//1028 1024//1024 -f 1024//1024 1028//1028 1030//1030 -f 1024//1024 1030//1030 1062//1062 -f 1062//1062 1030//1030 1040//1040 -f 1062//1062 1040//1040 1060//1060 -f 1060//1060 1040//1040 1038//1038 -f 1060//1060 1038//1038 1057//1057 -f 1057//1057 1038//1038 1036//1036 -f 1057//1057 1036//1036 1179//1179 -f 1179//1179 1036//1036 1034//1034 -f 1179//1179 1034//1034 1099//1099 -f 1099//1099 1034//1034 1032//1032 -f 1099//1099 1032//1032 973//973 -f 1089//1089 1180//1180 1181//1181 -f 1089//1089 1181//1181 1098//1098 -f 1098//1098 1181//1181 1182//1182 -f 1098//1098 1182//1182 1183//1183 -f 1183//1183 1184//1184 1098//1098 -f 1098//1098 1184//1184 1185//1185 -f 1098//1098 1185//1185 1099//1099 -f 1099//1099 1185//1185 1186//1186 -f 1099//1099 1186//1186 1187//1187 -f 1187//1187 1188//1188 1099//1099 -f 1099//1099 1188//1188 1087//1087 -f 1099//1099 1087//1087 1179//1179 -f 1179//1179 1087//1087 1123//1123 -f 1179//1179 1123//1123 1057//1057 -f 1057//1057 1123//1123 1051//1051 -f 1057//1057 1051//1051 1055//1055 -f 1055//1055 1051//1051 1050//1050 -f 1188//1188 1189//1189 1087//1087 -f 1087//1087 1189//1189 1190//1190 -f 1087//1087 1190//1190 1089//1089 -f 1089//1089 1190//1190 1191//1191 -f 1089//1089 1191//1191 1180//1180 -f 1192//1192 1193//1193 1194//1194 -f 1195//1195 1196//1196 1197//1197 -f 1198//1198 1199//1199 1200//1200 -f 1013//1013 1015//1015 1201//1201 -f 993//993 995//995 1202//1202 -f 981//981 1203//1203 1204//1204 -f 989//989 987//987 985//985 -f 981//981 1204//1204 982//982 -f 1205//1205 1206//1206 1204//1204 -f 1204//1204 1206//1206 989//989 -f 1204//1204 989//989 982//982 -f 982//982 989//989 985//985 -f 1206//1206 1207//1207 989//989 -f 989//989 1207//1207 1208//1208 -f 989//989 1208//1208 991//991 -f 1208//1208 1209//1209 991//991 -f 991//991 1209//1209 1210//1210 -f 991//991 1210//1210 1003//1003 -f 1003//1003 1210//1210 1211//1211 -f 1003//1003 1211//1211 1212//1212 -f 1213//1213 1214//1214 1215//1215 -f 1215//1215 1214//1214 1216//1216 -f 1215//1215 1216//1216 1204//1204 -f 1204//1204 1216//1216 1217//1217 -f 1204//1204 1217//1217 1205//1205 -f 1011//1011 1009//1009 1007//1007 -f 1027//1027 1025//1025 1029//1029 -f 1029//1029 1025//1025 1023//1023 -f 1029//1029 1023//1023 1039//1039 -f 972//972 979//979 1218//1218 -f 1218//1218 979//979 977//977 -f 1218//1218 977//977 975//975 -f 972//972 1218//1218 971//971 -f 971//971 1218//1218 1219//1219 -f 971//971 1219//1219 1220//1220 -f 1219//1219 1221//1221 1222//1222 -f 1223//1223 1220//1220 1224//1224 -f 1224//1224 1220//1220 1219//1219 -f 1224//1224 1219//1219 1225//1225 -f 1225//1225 1219//1219 1222//1222 -f 1226//1226 1227//1227 1221//1221 -f 1221//1221 1227//1227 1228//1228 -f 1221//1221 1228//1228 1222//1222 -f 1229//1229 1230//1230 1231//1231 -f 1229//1229 1231//1231 1232//1232 -f 1230//1230 1229//1229 1233//1233 -f 1233//1233 1229//1229 1215//1215 -f 1233//1233 1215//1215 1234//1234 -f 1234//1234 1215//1215 1204//1204 -f 1234//1234 1204//1204 1235//1235 -f 1235//1235 1204//1204 1203//1203 -f 1235//1235 1203//1203 1236//1236 -f 1237//1237 1238//1238 1239//1239 -f 1240//1240 1241//1241 1242//1242 -f 1242//1242 1241//1241 1243//1243 -f 1242//1242 1243//1243 1244//1244 -f 1244//1244 1243//1243 1239//1239 -f 1245//1245 1246//1246 1201//1201 -f 1245//1245 1201//1201 1240//1240 -f 1246//1246 1247//1247 1201//1201 -f 1201//1201 1247//1247 1248//1248 -f 1201//1201 1248//1248 1013//1013 -f 1247//1247 1249//1249 1248//1248 -f 1248//1248 1249//1249 1250//1250 -f 1248//1248 1250//1250 1251//1251 -f 1251//1251 1250//1250 1252//1252 -f 1251//1251 1252//1252 1237//1237 -f 1237//1237 1252//1252 1253//1253 -f 1237//1237 1253//1253 1238//1238 -f 1200//1200 1199//1199 1254//1254 -f 1199//1199 1255//1255 1254//1254 -f 1254//1254 1255//1255 1256//1256 -f 1254//1254 1256//1256 1257//1257 -f 1257//1257 1258//1258 999//999 -f 999//999 1258//1258 1259//1259 -f 999//999 1259//1259 997//997 -f 997//997 1259//1259 1260//1260 -f 997//997 1260//1260 995//995 -f 995//995 1260//1260 1261//1261 -f 1261//1261 1262//1262 995//995 -f 995//995 1262//1262 1263//1263 -f 995//995 1263//1263 1202//1202 -f 1202//1202 1263//1263 1264//1264 -f 1265//1265 1266//1266 1267//1267 -f 1268//1268 1269//1269 1270//1270 -f 1270//1270 1269//1269 1271//1271 -f 1270//1270 1271//1271 1254//1254 -f 1254//1254 1271//1271 1272//1272 -f 1254//1254 1272//1272 1200//1200 -f 1200//1200 1272//1272 1273//1273 -f 1200//1200 1273//1273 1274//1274 -f 1274//1274 1273//1273 1275//1275 -f 1274//1274 1275//1275 1276//1276 -f 1277//1277 1278//1278 1279//1279 -f 1279//1279 1278//1278 1265//1265 -f 1279//1279 1265//1265 1241//1241 -f 1241//1241 1265//1265 1267//1267 -f 1241//1241 1267//1267 1243//1243 -f 1243//1243 1267//1267 1280//1280 -f 1243//1243 1280//1280 1194//1194 -f 1194//1194 1280//1280 1281//1281 -f 961//961 1269//1269 962//962 -f 962//962 1269//1269 1268//1268 -f 962//962 1268//1268 1282//1282 -f 1282//1282 1268//1268 1197//1197 -f 1282//1282 1197//1197 968//968 -f 968//968 1197//1197 1194//1194 -f 968//968 1194//1194 967//967 -f 967//967 1194//1194 1281//1281 -f 1240//1240 1201//1201 1241//1241 -f 1241//1241 1201//1201 1283//1283 -f 1241//1241 1283//1283 1284//1284 -f 1284//1284 1285//1285 1241//1241 -f 1241//1241 1285//1285 1286//1286 -f 1241//1241 1286//1286 1279//1279 -f 1279//1279 1286//1286 1287//1287 -f 1279//1279 1287//1287 1288//1288 -f 1015//1015 1289//1289 1201//1201 -f 1201//1201 1289//1289 1290//1290 -f 1201//1201 1290//1290 1283//1283 -f 1288//1288 1291//1291 1292//1292 -f 1292//1292 1291//1291 1293//1293 -f 1292//1292 1293//1293 1017//1017 -f 1017//1017 1293//1293 1294//1294 -f 1017//1017 1294//1294 1015//1015 -f 1015//1015 1294//1294 1295//1295 -f 1015//1015 1295//1295 1289//1289 -f 1296//1296 1297//1297 1298//1298 -f 1299//1299 1300//1300 1279//1279 -f 1301//1301 1302//1302 1274//1274 -f 1288//1288 1292//1292 1279//1279 -f 1279//1279 1292//1292 1303//1303 -f 1279//1279 1303//1303 1299//1299 -f 1276//1276 1277//1277 1274//1274 -f 1274//1274 1277//1277 1279//1279 -f 1274//1274 1279//1279 1301//1301 -f 1301//1301 1279//1279 1300//1300 -f 1304//1304 1305//1305 1019//1019 -f 1019//1019 1305//1305 1306//1306 -f 1019//1019 1306//1306 1017//1017 -f 1017//1017 1306//1306 1307//1307 -f 1017//1017 1307//1307 1292//1292 -f 1292//1292 1307//1307 1308//1308 -f 1292//1292 1308//1308 1303//1303 -f 1218//1218 1309//1309 1310//1310 -f 1311//1311 1312//1312 1313//1313 -f 1313//1313 1312//1312 1314//1314 -f 975//975 974//974 1218//1218 -f 1218//1218 974//974 1313//1313 -f 1218//1218 1313//1313 1309//1309 -f 1309//1309 1313//1313 1314//1314 -f 1315//1315 1219//1219 1316//1316 -f 1316//1316 1219//1219 1218//1218 -f 1316//1316 1218//1218 1317//1317 -f 1317//1317 1218//1218 1310//1310 -f 1315//1315 1318//1318 1219//1219 -f 1219//1219 1318//1318 1319//1319 -f 1219//1219 1319//1319 1221//1221 -f 1221//1221 1319//1319 1320//1320 -f 1221//1221 1320//1320 1321//1321 -f 1229//1229 1322//1322 1323//1323 -f 1268//1268 1324//1324 1325//1325 -f 1197//1197 1196//1196 1232//1232 -f 1270//1270 1215//1215 1268//1268 -f 1268//1268 1215//1215 1229//1229 -f 1268//1268 1229//1229 1324//1324 -f 1324//1324 1229//1229 1323//1323 -f 1325//1325 1326//1326 1268//1268 -f 1268//1268 1326//1326 1327//1327 -f 1268//1268 1327//1327 1197//1197 -f 1197//1197 1327//1327 1328//1328 -f 1197//1197 1328//1328 1195//1195 -f 1196//1196 1329//1329 1232//1232 -f 1232//1232 1329//1329 1330//1330 -f 1232//1232 1330//1330 1229//1229 -f 1229//1229 1330//1330 1331//1331 -f 1229//1229 1331//1331 1322//1322 -f 1194//1194 1193//1193 1221//1221 -f 1221//1221 1193//1193 1332//1332 -f 1221//1221 1332//1332 1333//1333 -f 1333//1333 1334//1334 1221//1221 -f 1221//1221 1334//1334 1232//1232 -f 1221//1221 1232//1232 1226//1226 -f 1226//1226 1232//1232 1231//1231 -f 1335//1335 1336//1336 1197//1197 -f 1197//1197 1336//1336 1337//1337 -f 1197//1197 1337//1337 1194//1194 -f 1194//1194 1337//1337 1338//1338 -f 1194//1194 1338//1338 1192//1192 -f 1334//1334 1339//1339 1232//1232 -f 1232//1232 1339//1339 1340//1340 -f 1232//1232 1340//1340 1197//1197 -f 1197//1197 1340//1340 1341//1341 -f 1197//1197 1341//1341 1335//1335 -f 1257//1257 999//999 1254//1254 -f 1254//1254 999//999 1001//1001 -f 1254//1254 1001//1001 1270//1270 -f 1270//1270 1001//1001 1003//1003 -f 1270//1270 1003//1003 1215//1215 -f 1215//1215 1003//1003 1212//1212 -f 1215//1215 1212//1212 1213//1213 -f 1239//1239 1243//1243 1237//1237 -f 1237//1237 1243//1243 1194//1194 -f 1237//1237 1194//1194 1342//1342 -f 1342//1342 1194//1194 1221//1221 -f 1342//1342 1221//1221 1313//1313 -f 1313//1313 1221//1221 1321//1321 -f 1313//1313 1321//1321 1311//1311 -f 1302//1302 1296//1296 1274//1274 -f 1274//1274 1296//1296 1298//1298 -f 1274//1274 1298//1298 1200//1200 -f 1200//1200 1298//1298 1202//1202 -f 1200//1200 1202//1202 1198//1198 -f 1198//1198 1202//1202 1264//1264 -f 974//974 1031//1031 1313//1313 -f 1313//1313 1031//1031 1033//1033 -f 1313//1313 1033//1033 1342//1342 -f 1342//1342 1033//1033 1035//1035 -f 1342//1342 1035//1035 1237//1237 -f 1237//1237 1035//1035 1037//1037 -f 1237//1237 1037//1037 1251//1251 -f 1251//1251 1037//1037 1039//1039 -f 1251//1251 1039//1039 1248//1248 -f 1248//1248 1039//1039 1023//1023 -f 1248//1248 1023//1023 1013//1013 -f 1297//1297 1304//1304 1298//1298 -f 1298//1298 1304//1304 1019//1019 -f 1298//1298 1019//1019 1202//1202 -f 1202//1202 1019//1019 1021//1021 -f 1202//1202 1021//1021 993//993 -f 993//993 1021//1021 1011//1011 -f 993//993 1011//1011 1005//1005 -f 1005//1005 1011//1011 1007//1007 -f 1240//1240 1052//1052 1245//1245 -f 1245//1245 1052//1052 1054//1054 -f 1245//1245 1054//1054 1246//1246 -f 1246//1246 1054//1054 1066//1066 -f 1246//1246 1066//1066 1247//1247 -f 1247//1247 1066//1066 1065//1065 -f 1247//1247 1065//1065 1249//1249 -f 1249//1249 1065//1065 1064//1064 -f 1249//1249 1064//1064 1250//1250 -f 1250//1250 1064//1064 1063//1063 -f 1250//1250 1063//1063 1252//1252 -f 1252//1252 1063//1063 1061//1061 -f 1252//1252 1061//1061 1253//1253 -f 1253//1253 1061//1061 1059//1059 -f 1253//1253 1059//1059 1238//1238 -f 1238//1238 1059//1059 1058//1058 -f 1238//1238 1058//1058 1239//1239 -f 1239//1239 1058//1058 1056//1056 -f 1239//1239 1056//1056 1244//1244 -f 1244//1244 1056//1056 1055//1055 -f 1244//1244 1055//1055 1242//1242 -f 1242//1242 1055//1055 1050//1050 -f 1242//1242 1050//1050 1240//1240 -f 1240//1240 1050//1050 1052//1052 -f 1319//1319 1191//1191 1320//1320 -f 1320//1320 1191//1191 1190//1190 -f 1320//1320 1190//1190 1321//1321 -f 1321//1321 1190//1190 1189//1189 -f 1321//1321 1189//1189 1311//1311 -f 1311//1311 1189//1189 1188//1188 -f 1311//1311 1188//1188 1312//1312 -f 1312//1312 1188//1188 1187//1187 -f 1312//1312 1187//1187 1314//1314 -f 1314//1314 1187//1187 1186//1186 -f 1314//1314 1186//1186 1309//1309 -f 1309//1309 1186//1186 1185//1185 -f 1309//1309 1185//1185 1310//1310 -f 1310//1310 1185//1185 1184//1184 -f 1310//1310 1184//1184 1317//1317 -f 1317//1317 1184//1184 1183//1183 -f 1317//1317 1183//1183 1316//1316 -f 1316//1316 1183//1183 1182//1182 -f 1316//1316 1182//1182 1315//1315 -f 1315//1315 1182//1182 1181//1181 -f 1315//1315 1181//1181 1318//1318 -f 1318//1318 1181//1181 1180//1180 -f 1318//1318 1180//1180 1319//1319 -f 1319//1319 1180//1180 1191//1191 -f 1210//1210 1103//1103 1211//1211 -f 1211//1211 1103//1103 1100//1100 -f 1211//1211 1100//1100 1212//1212 -f 1212//1212 1100//1100 1108//1108 -f 1212//1212 1108//1108 1213//1213 -f 1213//1213 1108//1108 1107//1107 -f 1213//1213 1107//1107 1214//1214 -f 1214//1214 1107//1107 1106//1106 -f 1214//1214 1106//1106 1216//1216 -f 1216//1216 1106//1106 1105//1105 -f 1216//1216 1105//1105 1217//1217 -f 1217//1217 1105//1105 1102//1102 -f 1217//1217 1102//1102 1205//1205 -f 1205//1205 1102//1102 1101//1101 -f 1205//1205 1101//1101 1206//1206 -f 1206//1206 1101//1101 1111//1111 -f 1206//1206 1111//1111 1207//1207 -f 1207//1207 1111//1111 1110//1110 -f 1207//1207 1110//1110 1208//1208 -f 1208//1208 1110//1110 1109//1109 -f 1208//1208 1109//1109 1209//1209 -f 1209//1209 1109//1109 1104//1104 -f 1209//1209 1104//1104 1210//1210 -f 1210//1210 1104//1104 1103//1103 -f 1260//1260 1078//1078 1261//1261 -f 1261//1261 1078//1078 1079//1079 -f 1261//1261 1079//1079 1262//1262 -f 1262//1262 1079//1079 1080//1080 -f 1262//1262 1080//1080 1263//1263 -f 1263//1263 1080//1080 1081//1081 -f 1263//1263 1081//1081 1264//1264 -f 1264//1264 1081//1081 1076//1076 -f 1264//1264 1076//1076 1198//1198 -f 1198//1198 1076//1076 1075//1075 -f 1198//1198 1075//1075 1199//1199 -f 1199//1199 1075//1075 1073//1073 -f 1199//1199 1073//1073 1255//1255 -f 1255//1255 1073//1073 1071//1071 -f 1255//1255 1071//1071 1256//1256 -f 1256//1256 1071//1071 1070//1070 -f 1256//1256 1070//1070 1257//1257 -f 1257//1257 1070//1070 1068//1068 -f 1257//1257 1068//1068 1258//1258 -f 1258//1258 1068//1068 1067//1067 -f 1258//1258 1067//1067 1259//1259 -f 1259//1259 1067//1067 1077//1077 -f 1259//1259 1077//1077 1260//1260 -f 1260//1260 1077//1077 1078//1078 -f 1088//1088 1090//1090 1225//1225 -f 1225//1225 1090//1090 1224//1224 -f 1231//1231 1095//1095 1226//1226 -f 1226//1226 1095//1095 1094//1094 -f 1226//1226 1094//1094 1227//1227 -f 1227//1227 1094//1094 1092//1092 -f 1234//1234 1235//1235 1047//1047 -f 1047//1047 1235//1235 1048//1048 -f 1095//1095 1231//1231 1083//1083 -f 1083//1083 1231//1231 1230//1230 -f 1083//1083 1230//1230 1085//1085 -f 1085//1085 1230//1230 1233//1233 -f 1085//1085 1233//1233 1047//1047 -f 1047//1047 1233//1233 1234//1234 -f 981//981 983//983 1112//1112 -f 981//981 1112//1112 1203//1203 -f 1203//1203 1112//1112 1113//1113 -f 1203//1203 1113//1113 1236//1236 -f 1236//1236 1113//1113 1048//1048 -f 1236//1236 1048//1048 1235//1235 -f 1088//1088 1225//1225 1086//1086 -f 1086//1086 1225//1225 1222//1222 -f 1086//1086 1222//1222 1091//1091 -f 1091//1091 1222//1222 1228//1228 -f 1091//1091 1228//1228 1092//1092 -f 1092//1092 1228//1228 1227//1227 -f 1224//1224 1090//1090 1096//1096 -f 1224//1224 1096//1096 1223//1223 -f 1223//1223 1096//1096 1097//1097 -f 1223//1223 1097//1097 1220//1220 -f 1220//1220 1097//1097 969//969 -f 1220//1220 969//969 971//971 -f 1156//1156 1126//1126 1276//1276 -f 1276//1276 1126//1126 1277//1277 -f 964//964 962//962 1122//1122 -f 1122//1122 962//962 1282//1282 -f 1122//1122 1282//1282 966//966 -f 966//966 1282//1282 968//968 -f 1266//1266 1265//1265 1131//1131 -f 1131//1131 1265//1265 1130//1130 -f 1130//1130 1265//1265 1128//1128 -f 1128//1128 1265//1265 1278//1278 -f 1128//1128 1278//1278 1126//1126 -f 1126//1126 1278//1278 1277//1277 -f 1114//1114 965//965 1281//1281 -f 1281//1281 965//965 967//967 -f 1267//1267 1266//1266 1125//1125 -f 1125//1125 1266//1266 1131//1131 -f 1114//1114 1281//1281 1124//1124 -f 1124//1124 1281//1281 1280//1280 -f 1124//1124 1280//1280 1125//1125 -f 1125//1125 1280//1280 1267//1267 -f 1117//1117 1271//1271 1115//1115 -f 1115//1115 1271//1271 1269//1269 -f 1115//1115 1269//1269 963//963 -f 963//963 1269//1269 961//961 -f 1273//1273 1120//1120 1275//1275 -f 1275//1275 1120//1120 1121//1121 -f 1275//1275 1121//1121 1276//1276 -f 1276//1276 1121//1121 1156//1156 -f 1120//1120 1273//1273 1119//1119 -f 1119//1119 1273//1273 1272//1272 -f 1119//1119 1272//1272 1117//1117 -f 1117//1117 1272//1272 1271//1271 -f 1291//1291 1142//1142 1293//1293 -f 1293//1293 1142//1142 1141//1141 -f 1293//1293 1141//1141 1294//1294 -f 1294//1294 1141//1141 1139//1139 -f 1294//1294 1139//1139 1295//1295 -f 1295//1295 1139//1139 1138//1138 -f 1295//1295 1138//1138 1289//1289 -f 1289//1289 1138//1138 1137//1137 -f 1289//1289 1137//1137 1290//1290 -f 1290//1290 1137//1137 1045//1045 -f 1290//1290 1045//1045 1283//1283 -f 1283//1283 1045//1045 1044//1044 -f 1283//1283 1044//1044 1284//1284 -f 1284//1284 1044//1044 1132//1132 -f 1284//1284 1132//1132 1285//1285 -f 1285//1285 1132//1132 1136//1136 -f 1285//1285 1136//1136 1286//1286 -f 1286//1286 1136//1136 1135//1135 -f 1286//1286 1135//1135 1287//1287 -f 1287//1287 1135//1135 1134//1134 -f 1287//1287 1134//1134 1288//1288 -f 1288//1288 1134//1134 1133//1133 -f 1288//1288 1133//1133 1291//1291 -f 1291//1291 1133//1133 1142//1142 -f 1297//1297 1144//1144 1304//1304 -f 1304//1304 1144//1144 1151//1151 -f 1304//1304 1151//1151 1305//1305 -f 1305//1305 1151//1151 1150//1150 -f 1305//1305 1150//1150 1306//1306 -f 1306//1306 1150//1150 1155//1155 -f 1306//1306 1155//1155 1307//1307 -f 1307//1307 1155//1155 1154//1154 -f 1307//1307 1154//1154 1308//1308 -f 1308//1308 1154//1154 1153//1153 -f 1308//1308 1153//1153 1303//1303 -f 1303//1303 1153//1153 1152//1152 -f 1303//1303 1152//1152 1299//1299 -f 1299//1299 1152//1152 1146//1146 -f 1299//1299 1146//1146 1300//1300 -f 1300//1300 1146//1146 1149//1149 -f 1300//1300 1149//1149 1301//1301 -f 1301//1301 1149//1149 1148//1148 -f 1301//1301 1148//1148 1302//1302 -f 1302//1302 1148//1148 1147//1147 -f 1302//1302 1147//1147 1296//1296 -f 1296//1296 1147//1147 1145//1145 -f 1296//1296 1145//1145 1297//1297 -f 1297//1297 1145//1145 1144//1144 -f 1324//1324 1042//1042 1325//1325 -f 1325//1325 1042//1042 1041//1041 -f 1325//1325 1041//1041 1326//1326 -f 1326//1326 1041//1041 1163//1163 -f 1326//1326 1163//1163 1327//1327 -f 1327//1327 1163//1163 1162//1162 -f 1327//1327 1162//1162 1328//1328 -f 1328//1328 1162//1162 1161//1161 -f 1328//1328 1161//1161 1195//1195 -f 1195//1195 1161//1161 1159//1159 -f 1195//1195 1159//1159 1196//1196 -f 1196//1196 1159//1159 1158//1158 -f 1196//1196 1158//1158 1329//1329 -f 1329//1329 1158//1158 1157//1157 -f 1329//1329 1157//1157 1330//1330 -f 1330//1330 1157//1157 1166//1166 -f 1330//1330 1166//1166 1331//1331 -f 1331//1331 1166//1166 1165//1165 -f 1331//1331 1165//1165 1322//1322 -f 1322//1322 1165//1165 1164//1164 -f 1322//1322 1164//1164 1323//1323 -f 1323//1323 1164//1164 1160//1160 -f 1323//1323 1160//1160 1324//1324 -f 1324//1324 1160//1160 1042//1042 -f 1341//1341 1168//1168 1335//1335 -f 1335//1335 1168//1168 1167//1167 -f 1335//1335 1167//1167 1336//1336 -f 1336//1336 1167//1167 1172//1172 -f 1336//1336 1172//1172 1337//1337 -f 1337//1337 1172//1172 1171//1171 -f 1337//1337 1171//1171 1338//1338 -f 1338//1338 1171//1171 1170//1170 -f 1338//1338 1170//1170 1192//1192 -f 1192//1192 1170//1170 1169//1169 -f 1192//1192 1169//1169 1193//1193 -f 1193//1193 1169//1169 1178//1178 -f 1193//1193 1178//1178 1332//1332 -f 1332//1332 1178//1178 1177//1177 -f 1332//1332 1177//1177 1333//1333 -f 1333//1333 1177//1177 1176//1176 -f 1333//1333 1176//1176 1334//1334 -f 1334//1334 1176//1176 1175//1175 -f 1334//1334 1175//1175 1339//1339 -f 1339//1339 1175//1175 1174//1174 -f 1339//1339 1174//1174 1340//1340 -f 1340//1340 1174//1174 1173//1173 -f 1340//1340 1173//1173 1341//1341 -f 1341//1341 1173//1173 1168//1168 -f 1343//1343 1344//1344 1345//1345 -f 1345//1345 1344//1344 1346//1346 -f 1345//1345 1347//1347 1348//1348 -f 1349//1349 1350//1350 1351//1351 -f 1352//1352 1353//1353 1354//1354 -f 1355//1355 1356//1356 1357//1357 -f 1357//1357 1356//1356 1358//1358 -f 1357//1357 1358//1358 1359//1359 -f 1359//1359 1358//1358 1360//1360 -f 1359//1359 1360//1360 1361//1361 -f 1361//1361 1360//1360 1362//1362 -f 1361//1361 1362//1362 1363//1363 -f 1363//1363 1362//1362 1364//1364 -f 1363//1363 1364//1364 1365//1365 -f 1365//1365 1364//1364 1366//1366 -f 1349//1349 1367//1367 1350//1350 -f 1350//1350 1367//1367 1368//1368 -f 1350//1350 1368//1368 1369//1369 -f 1369//1369 1368//1368 1370//1370 -f 1369//1369 1370//1370 1371//1371 -f 1371//1371 1370//1370 1372//1372 -f 1371//1371 1372//1372 1355//1355 -f 1355//1355 1372//1372 1373//1373 -f 1355//1355 1373//1373 1356//1356 -f 1374//1374 1349//1349 1375//1375 -f 1375//1375 1349//1349 1351//1351 -f 1375//1375 1351//1351 1376//1376 -f 1376//1376 1351//1351 1377//1377 -f 1376//1376 1377//1377 1378//1378 -f 1378//1378 1377//1377 1354//1354 -f 1366//1366 1352//1352 1365//1365 -f 1365//1365 1352//1352 1354//1354 -f 1365//1365 1354//1354 1379//1379 -f 1379//1379 1354//1354 1377//1377 -f 1380//1380 1381//1381 1382//1382 -f 1383//1383 1384//1384 1382//1382 -f 1382//1382 1384//1384 1385//1385 -f 1382//1382 1385//1385 1380//1380 -f 1380//1380 1386//1386 1381//1381 -f 1381//1381 1386//1386 1387//1387 -f 1381//1381 1387//1387 1388//1388 -f 1388//1388 1387//1387 1389//1389 -f 1388//1388 1389//1389 1390//1390 -f 1390//1390 1389//1389 1391//1391 -f 1390//1390 1391//1391 1392//1392 -f 1392//1392 1391//1391 1393//1393 -f 1394//1394 1395//1395 1396//1396 -f 1353//1353 1397//1397 1354//1354 -f 1354//1354 1397//1397 1398//1398 -f 1354//1354 1398//1398 1399//1399 -f 1383//1383 1400//1400 1384//1384 -f 1384//1384 1400//1400 1401//1401 -f 1384//1384 1401//1401 1402//1402 -f 1402//1402 1401//1401 1403//1403 -f 1402//1402 1403//1403 1399//1399 -f 1399//1399 1403//1403 1404//1404 -f 1399//1399 1404//1404 1354//1354 -f 1391//1391 1394//1394 1393//1393 -f 1393//1393 1394//1394 1396//1396 -f 1393//1393 1396//1396 1405//1405 -f 1405//1405 1396//1396 1406//1406 -f 1405//1405 1406//1406 1404//1404 -f 1404//1404 1406//1406 1407//1407 -f 1404//1404 1407//1407 1354//1354 -f 1408//1408 1409//1409 1410//1410 -f 1410//1410 1409//1409 1411//1411 -f 1410//1410 1411//1411 1412//1412 -f 1412//1412 1411//1411 1413//1413 -f 1412//1412 1413//1413 1414//1414 -f 1414//1414 1413//1413 1415//1415 -f 1416//1416 1417//1417 1418//1418 -f 1418//1418 1417//1417 1419//1419 -f 1418//1418 1419//1419 1420//1420 -f 1420//1420 1419//1419 1421//1421 -f 1422//1422 1423//1423 1424//1424 -f 1424//1424 1423//1423 1425//1425 -f 1426//1426 1427//1427 1423//1423 -f 1423//1423 1427//1427 1428//1428 -f 1423//1423 1428//1428 1429//1429 -f 1425//1425 1423//1423 1430//1430 -f 1430//1430 1423//1423 1429//1429 -f 1430//1430 1429//1429 1408//1408 -f 1408//1408 1429//1429 1431//1431 -f 1408//1408 1431//1431 1409//1409 -f 1346//1346 1432//1432 1433//1433 -f 1434//1434 1435//1435 1436//1436 -f 1436//1436 1435//1435 1437//1437 -f 1436//1436 1437//1437 1438//1438 -f 1433//1433 1439//1439 1346//1346 -f 1346//1346 1439//1439 1440//1440 -f 1346//1346 1440//1440 1345//1345 -f 1345//1345 1440//1440 1441//1441 -f 1345//1345 1441//1441 1347//1347 -f 1442//1442 1345//1345 1443//1443 -f 1443//1443 1345//1345 1348//1348 -f 1443//1443 1348//1348 1444//1444 -f 1444//1444 1348//1348 1434//1434 -f 1444//1444 1434//1434 1445//1445 -f 1445//1445 1434//1434 1436//1436 -f 1446//1446 1436//1436 1447//1447 -f 1447//1447 1436//1436 1438//1438 -f 1447//1447 1438//1438 1448//1448 -f 1448//1448 1438//1438 1449//1449 -f 1448//1448 1449//1449 1450//1450 -f 1374//1374 1375//1375 1422//1422 -f 1422//1422 1375//1375 1451//1451 -f 1422//1422 1451//1451 1423//1423 -f 1423//1423 1451//1451 1452//1452 -f 1423//1423 1452//1452 1453//1453 -f 1454//1454 1455//1455 1456//1456 -f 1456//1456 1455//1455 1457//1457 -f 1456//1456 1457//1457 1458//1458 -f 1459//1459 1460//1460 1423//1423 -f 1423//1423 1460//1460 1461//1461 -f 1446//1446 1462//1462 1436//1436 -f 1436//1436 1462//1462 1463//1463 -f 1436//1436 1463//1463 1464//1464 -f 1465//1465 1466//1466 1467//1467 -f 1467//1467 1466//1466 1468//1468 -f 1463//1463 1469//1469 1464//1464 -f 1464//1464 1469//1469 1468//1468 -f 1464//1464 1468//1468 1457//1457 -f 1457//1457 1468//1468 1466//1466 -f 1457//1457 1466//1466 1458//1458 -f 1453//1453 1455//1455 1423//1423 -f 1423//1423 1455//1455 1454//1454 -f 1423//1423 1454//1454 1459//1459 -f 1459//1459 1454//1454 1470//1470 -f 1471//1471 1472//1472 1473//1473 -f 1473//1473 1472//1472 1474//1474 -f 1473//1473 1474//1474 1475//1475 -f 1475//1475 1474//1474 1465//1465 -f 1475//1475 1465//1465 1476//1476 -f 1476//1476 1465//1465 1467//1467 -f 1477//1477 1478//1478 1479//1479 -f 1479//1479 1478//1478 1480//1480 -f 1479//1479 1480//1480 1481//1481 -f 1481//1481 1480//1480 1482//1482 -f 1481//1481 1482//1482 1470//1470 -f 1470//1470 1482//1482 1483//1483 -f 1470//1470 1483//1483 1459//1459 -f 1484//1484 1485//1485 1415//1415 -f 1486//1486 1487//1487 1488//1488 -f 1486//1486 1488//1488 1420//1420 -f 1489//1489 1490//1490 1486//1486 -f 1486//1486 1490//1490 1491//1491 -f 1486//1486 1491//1491 1487//1487 -f 1492//1492 1493//1493 1420//1420 -f 1420//1420 1493//1493 1494//1494 -f 1461//1461 1495//1495 1423//1423 -f 1423//1423 1495//1495 1420//1420 -f 1423//1423 1420//1420 1426//1426 -f 1426//1426 1420//1420 1421//1421 -f 1496//1496 1497//1497 1498//1498 -f 1498//1498 1497//1497 1499//1499 -f 1498//1498 1499//1499 1500//1500 -f 1500//1500 1499//1499 1501//1501 -f 1489//1489 1486//1486 1498//1498 -f 1498//1498 1486//1486 1502//1502 -f 1498//1498 1502//1502 1496//1496 -f 1494//1494 1503//1503 1420//1420 -f 1420//1420 1503//1503 1504//1504 -f 1420//1420 1504//1504 1486//1486 -f 1486//1486 1504//1504 1505//1505 -f 1486//1486 1505//1505 1502//1502 -f 1495//1495 1506//1506 1420//1420 -f 1420//1420 1506//1506 1507//1507 -f 1420//1420 1507//1507 1492//1492 -f 1492//1492 1507//1507 1500//1500 -f 1492//1492 1500//1500 1508//1508 -f 1508//1508 1500//1500 1501//1501 -f 1473//1473 1509//1509 1510//1510 -f 1477//1477 1471//1471 1478//1478 -f 1478//1478 1471//1471 1473//1473 -f 1478//1478 1473//1473 1511//1511 -f 1511//1511 1473//1473 1510//1510 -f 1512//1512 1513//1513 1514//1514 -f 1514//1514 1513//1513 1448//1448 -f 1514//1514 1448//1448 1432//1432 -f 1432//1432 1448//1448 1450//1450 -f 1432//1432 1450//1450 1433//1433 -f 1488//1488 1515//1515 1420//1420 -f 1420//1420 1515//1515 1484//1484 -f 1420//1420 1484//1484 1418//1418 -f 1418//1418 1484//1484 1415//1415 -f 1418//1418 1415//1415 1416//1416 -f 1416//1416 1415//1415 1413//1413 -f 1516//1516 1517//1517 1518//1518 -f 1518//1518 1517//1517 1519//1519 -f 1518//1518 1519//1519 1520//1520 -f 1343//1343 1521//1521 1522//1522 -f 1344//1344 1523//1523 1524//1524 -f 1524//1524 1523//1523 1525//1525 -f 1526//1526 1527//1527 1528//1528 -f 1528//1528 1527//1527 1520//1520 -f 1528//1528 1520//1520 1529//1529 -f 1529//1529 1520//1520 1519//1519 -f 1530//1530 1531//1531 1532//1532 -f 1522//1522 1533//1533 1526//1526 -f 1532//1532 1527//1527 1530//1530 -f 1530//1530 1527//1527 1526//1526 -f 1530//1530 1526//1526 1534//1534 -f 1534//1534 1526//1526 1533//1533 -f 1526//1526 1535//1535 1522//1522 -f 1522//1522 1535//1535 1536//1536 -f 1522//1522 1536//1536 1343//1343 -f 1343//1343 1536//1536 1537//1537 -f 1343//1343 1537//1537 1344//1344 -f 1344//1344 1537//1537 1538//1538 -f 1344//1344 1538//1538 1523//1523 -f 1539//1539 1540//1540 1541//1541 -f 1541//1541 1542//1542 1539//1539 -f 1539//1539 1542//1542 1524//1524 -f 1539//1539 1524//1524 1518//1518 -f 1518//1518 1524//1524 1525//1525 -f 1518//1518 1525//1525 1516//1516 -f 1543//1543 1544//1544 1545//1545 -f 1545//1545 1544//1544 1546//1546 -f 1547//1547 1544//1544 1548//1548 -f 1546//1546 1544//1544 1549//1549 -f 1549//1549 1544//1544 1547//1547 -f 1549//1549 1547//1547 1550//1550 -f 1543//1543 1545//1545 1551//1551 -f 1551//1551 1545//1545 1552//1552 -f 1551//1551 1552//1552 1553//1553 -f 1553//1553 1552//1552 1554//1554 -f 1553//1553 1554//1554 1555//1555 -f 1554//1554 1556//1556 1555//1555 -f 1555//1555 1556//1556 1557//1557 -f 1555//1555 1557//1557 1558//1558 -f 1558//1558 1557//1557 1559//1559 -f 1558//1558 1559//1559 1560//1560 -f 1560//1560 1559//1559 1561//1561 -f 1560//1560 1561//1561 1562//1562 -f 1562//1562 1561//1561 1563//1563 -f 1562//1562 1563//1563 1564//1564 -f 1564//1564 1563//1563 1565//1565 -f 1564//1564 1565//1565 1566//1566 -f 1566//1566 1565//1565 1550//1550 -f 1566//1566 1550//1550 1567//1567 -f 1567//1567 1550//1550 1547//1547 -f 1567//1567 1547//1547 1568//1568 -f 1531//1531 1530//1530 1569//1569 -f 1569//1569 1530//1530 1570//1570 -f 1569//1569 1570//1570 1544//1544 -f 1544//1544 1570//1570 1571//1571 -f 1544//1544 1571//1571 1548//1548 -f 1572//1572 1555//1555 1573//1573 -f 1573//1573 1555//1555 1558//1558 -f 1573//1573 1558//1558 1574//1574 -f 1574//1574 1558//1558 1575//1575 -f 1576//1576 1577//1577 1578//1578 -f 1578//1578 1577//1577 1579//1579 -f 1580//1580 1581//1581 1547//1547 -f 1582//1582 1583//1583 1547//1547 -f 1547//1547 1583//1583 1584//1584 -f 1547//1547 1584//1584 1568//1568 -f 1579//1579 1585//1585 1578//1578 -f 1578//1578 1585//1585 1586//1586 -f 1578//1578 1586//1586 1587//1587 -f 1587//1587 1586//1586 1588//1588 -f 1587//1587 1588//1588 1589//1589 -f 1581//1581 1590//1590 1547//1547 -f 1547//1547 1590//1590 1591//1591 -f 1547//1547 1591//1591 1592//1592 -f 1582//1582 1547//1547 1593//1593 -f 1593//1593 1547//1547 1592//1592 -f 1593//1593 1592//1592 1576//1576 -f 1576//1576 1592//1592 1594//1594 -f 1576//1576 1594//1594 1577//1577 -f 1595//1595 1576//1576 1596//1596 -f 1596//1596 1576//1576 1578//1578 -f 1596//1596 1578//1578 1597//1597 -f 1597//1597 1578//1578 1598//1598 -f 1599//1599 1600//1600 1601//1601 -f 1601//1601 1600//1600 1602//1602 -f 1601//1601 1602//1602 1603//1603 -f 1603//1603 1602//1602 1604//1604 -f 1603//1603 1604//1604 1605//1605 -f 1605//1605 1604//1604 1606//1606 -f 1607//1607 1608//1608 1599//1599 -f 1599//1599 1608//1608 1609//1609 -f 1599//1599 1609//1609 1600//1600 -f 1610//1610 1611//1611 1587//1587 -f 1587//1587 1611//1611 1612//1612 -f 1587//1587 1612//1612 1606//1606 -f 1606//1606 1612//1612 1613//1613 -f 1606//1606 1613//1613 1605//1605 -f 1614//1614 1547//1547 1615//1615 -f 1615//1615 1547//1547 1616//1616 -f 1589//1589 1580//1580 1587//1587 -f 1587//1587 1580//1580 1547//1547 -f 1587//1587 1547//1547 1610//1610 -f 1610//1610 1547//1547 1614//1614 -f 1610//1610 1614//1614 1617//1617 -f 1617//1617 1614//1614 1618//1618 -f 1617//1617 1618//1618 1619//1619 -f 1619//1619 1618//1618 1608//1608 -f 1619//1619 1608//1608 1620//1620 -f 1620//1620 1608//1608 1607//1607 -f 1548//1548 1621//1621 1547//1547 -f 1547//1547 1621//1621 1622//1622 -f 1547//1547 1622//1622 1616//1616 -f 1623//1623 1624//1624 1625//1625 -f 1626//1626 1627//1627 1628//1628 -f 1628//1628 1627//1627 1629//1629 -f 1628//1628 1629//1629 1630//1630 -f 1631//1631 1632//1632 1633//1633 -f 1633//1633 1632//1632 1626//1626 -f 1633//1633 1626//1626 1634//1634 -f 1634//1634 1626//1626 1628//1628 -f 1622//1622 1635//1635 1616//1616 -f 1616//1616 1635//1635 1626//1626 -f 1616//1616 1626//1626 1636//1636 -f 1636//1636 1626//1626 1632//1632 -f 1629//1629 1623//1623 1630//1630 -f 1630//1630 1623//1623 1625//1625 -f 1630//1630 1625//1625 1637//1637 -f 1637//1637 1625//1625 1638//1638 -f 1637//1637 1638//1638 1639//1639 -f 1639//1639 1638//1638 1640//1640 -f 1639//1639 1640//1640 1641//1641 -f 1641//1641 1640//1640 1642//1642 -f 1641//1641 1642//1642 1643//1643 -f 1643//1643 1642//1642 1644//1644 -f 1643//1643 1644//1644 1645//1645 -f 1644//1644 1646//1646 1645//1645 -f 1645//1645 1646//1646 1647//1647 -f 1645//1645 1647//1647 1648//1648 -f 1648//1648 1647//1647 1649//1649 -f 1648//1648 1649//1649 1650//1650 -f 1650//1650 1649//1649 1651//1651 -f 1650//1650 1651//1651 1652//1652 -f 1652//1652 1651//1651 1653//1653 -f 1652//1652 1653//1653 1633//1633 -f 1633//1633 1653//1653 1654//1654 -f 1633//1633 1654//1654 1631//1631 -f 1655//1655 1656//1656 1623//1623 -f 1656//1656 1657//1657 1623//1623 -f 1623//1623 1657//1657 1658//1658 -f 1623//1623 1658//1658 1624//1624 -f 1659//1659 1660//1660 1661//1661 -f 1661//1661 1660//1660 1662//1662 -f 1661//1661 1662//1662 1663//1663 -f 1663//1663 1662//1662 1664//1664 -f 1663//1663 1664//1664 1665//1665 -f 1666//1666 1663//1663 1667//1667 -f 1667//1667 1663//1663 1665//1665 -f 1667//1667 1665//1665 1668//1668 -f 1668//1668 1665//1665 1669//1669 -f 1668//1668 1669//1669 1670//1670 -f 1670//1670 1669//1669 1623//1623 -f 1671//1671 1655//1655 1672//1672 -f 1672//1672 1655//1655 1623//1623 -f 1672//1672 1623//1623 1673//1673 -f 1673//1673 1623//1623 1669//1669 -f 1672//1672 1674//1674 1671//1671 -f 1671//1671 1674//1674 1675//1675 -f 1671//1671 1675//1675 1676//1676 -f 1676//1676 1675//1675 1677//1677 -f 1676//1676 1677//1677 1678//1678 -f 1678//1678 1677//1677 1679//1679 -f 1661//1661 1680//1680 1659//1659 -f 1659//1659 1680//1680 1681//1681 -f 1659//1659 1681//1681 1679//1679 -f 1679//1679 1681//1681 1682//1682 -f 1679//1679 1682//1682 1678//1678 -f 1604//1604 1683//1683 1606//1606 -f 1606//1606 1683//1683 1684//1684 -f 1606//1606 1684//1684 1587//1587 -f 1587//1587 1684//1684 1685//1685 -f 1587//1587 1685//1685 1578//1578 -f 1578//1578 1685//1685 1686//1686 -f 1578//1578 1686//1686 1598//1598 -f 1683//1683 1604//1604 1485//1485 -f 1485//1485 1604//1604 1415//1415 -f 1491//1491 1597//1597 1598//1598 -f 1491//1491 1598//1598 1487//1487 -f 1487//1487 1598//1598 1686//1686 -f 1487//1487 1686//1686 1488//1488 -f 1511//1511 1510//1510 1574//1574 -f 1574//1574 1510//1510 1573//1573 -f 1647//1647 1646//1646 1356//1356 -f 1356//1356 1646//1646 1358//1358 -f 1681//1681 1680//1680 1387//1387 -f 1387//1387 1680//1680 1389//1389 -f 1346//1346 1344//1344 1524//1524 -f 1346//1346 1524//1524 1432//1432 -f 1432//1432 1524//1524 1542//1542 -f 1432//1432 1542//1542 1514//1514 -f 1450//1450 1516//1516 1433//1433 -f 1433//1433 1516//1516 1525//1525 -f 1433//1433 1525//1525 1439//1439 -f 1439//1439 1525//1525 1523//1523 -f 1439//1439 1523//1523 1440//1440 -f 1440//1440 1523//1523 1538//1538 -f 1440//1440 1538//1538 1441//1441 -f 1441//1441 1538//1538 1537//1537 -f 1441//1441 1537//1537 1347//1347 -f 1347//1347 1537//1537 1536//1536 -f 1347//1347 1536//1536 1348//1348 -f 1348//1348 1536//1536 1535//1535 -f 1348//1348 1535//1535 1434//1434 -f 1434//1434 1535//1535 1526//1526 -f 1434//1434 1526//1526 1435//1435 -f 1435//1435 1526//1526 1528//1528 -f 1435//1435 1528//1528 1437//1437 -f 1437//1437 1528//1528 1529//1529 -f 1437//1437 1529//1529 1438//1438 -f 1438//1438 1529//1529 1519//1519 -f 1438//1438 1519//1519 1449//1449 -f 1449//1449 1519//1519 1517//1517 -f 1449//1449 1517//1517 1450//1450 -f 1450//1450 1517//1517 1516//1516 -f 1496//1496 1577//1577 1497//1497 -f 1497//1497 1577//1577 1594//1594 -f 1497//1497 1594//1594 1499//1499 -f 1499//1499 1594//1594 1592//1592 -f 1499//1499 1592//1592 1501//1501 -f 1501//1501 1592//1592 1591//1591 -f 1501//1501 1591//1591 1508//1508 -f 1508//1508 1591//1591 1590//1590 -f 1508//1508 1590//1590 1492//1492 -f 1492//1492 1590//1590 1581//1581 -f 1492//1492 1581//1581 1493//1493 -f 1493//1493 1581//1581 1580//1580 -f 1493//1493 1580//1580 1494//1494 -f 1494//1494 1580//1580 1589//1589 -f 1494//1494 1589//1589 1503//1503 -f 1503//1503 1589//1589 1588//1588 -f 1503//1503 1588//1588 1504//1504 -f 1504//1504 1588//1588 1586//1586 -f 1504//1504 1586//1586 1505//1505 -f 1505//1505 1586//1586 1585//1585 -f 1505//1505 1585//1585 1502//1502 -f 1502//1502 1585//1585 1579//1579 -f 1502//1502 1579//1579 1496//1496 -f 1496//1496 1579//1579 1577//1577 -f 1426//1426 1611//1611 1427//1427 -f 1427//1427 1611//1611 1610//1610 -f 1427//1427 1610//1610 1428//1428 -f 1428//1428 1610//1610 1617//1617 -f 1428//1428 1617//1617 1429//1429 -f 1429//1429 1617//1617 1619//1619 -f 1429//1429 1619//1619 1431//1431 -f 1431//1431 1619//1619 1620//1620 -f 1431//1431 1620//1620 1409//1409 -f 1409//1409 1620//1620 1607//1607 -f 1409//1409 1607//1607 1411//1411 -f 1411//1411 1607//1607 1599//1599 -f 1411//1411 1599//1599 1413//1413 -f 1413//1413 1599//1599 1601//1601 -f 1413//1413 1601//1601 1416//1416 -f 1416//1416 1601//1601 1603//1603 -f 1416//1416 1603//1603 1417//1417 -f 1417//1417 1603//1603 1605//1605 -f 1417//1417 1605//1605 1419//1419 -f 1419//1419 1605//1605 1613//1613 -f 1419//1419 1613//1613 1421//1421 -f 1421//1421 1613//1613 1612//1612 -f 1421//1421 1612//1612 1426//1426 -f 1426//1426 1612//1612 1611//1611 -f 1405//1405 1665//1665 1393//1393 -f 1393//1393 1665//1665 1664//1664 -f 1393//1393 1664//1664 1392//1392 -f 1392//1392 1664//1664 1662//1662 -f 1392//1392 1662//1662 1390//1390 -f 1390//1390 1662//1662 1660//1660 -f 1390//1390 1660//1660 1388//1388 -f 1388//1388 1660//1660 1659//1659 -f 1388//1388 1659//1659 1381//1381 -f 1381//1381 1659//1659 1679//1679 -f 1381//1381 1679//1679 1382//1382 -f 1382//1382 1679//1679 1677//1677 -f 1382//1382 1677//1677 1383//1383 -f 1383//1383 1677//1677 1675//1675 -f 1383//1383 1675//1675 1400//1400 -f 1400//1400 1675//1675 1674//1674 -f 1400//1400 1674//1674 1401//1401 -f 1401//1401 1674//1674 1672//1672 -f 1401//1401 1672//1672 1403//1403 -f 1403//1403 1672//1672 1673//1673 -f 1403//1403 1673//1673 1404//1404 -f 1404//1404 1673//1673 1669//1669 -f 1404//1404 1669//1669 1405//1405 -f 1405//1405 1669//1669 1665//1665 -f 1471//1471 1557//1557 1472//1472 -f 1472//1472 1557//1557 1556//1556 -f 1472//1472 1556//1556 1474//1474 -f 1474//1474 1556//1556 1554//1554 -f 1474//1474 1554//1554 1465//1465 -f 1465//1465 1554//1554 1552//1552 -f 1465//1465 1552//1552 1466//1466 -f 1466//1466 1552//1552 1545//1545 -f 1466//1466 1545//1545 1458//1458 -f 1458//1458 1545//1545 1546//1546 -f 1458//1458 1546//1546 1456//1456 -f 1456//1456 1546//1546 1549//1549 -f 1456//1456 1549//1549 1454//1454 -f 1454//1454 1549//1549 1550//1550 -f 1454//1454 1550//1550 1470//1470 -f 1470//1470 1550//1550 1565//1565 -f 1470//1470 1565//1565 1481//1481 -f 1481//1481 1565//1565 1563//1563 -f 1481//1481 1563//1563 1479//1479 -f 1479//1479 1563//1563 1561//1561 -f 1479//1479 1561//1561 1477//1477 -f 1477//1477 1561//1561 1559//1559 -f 1477//1477 1559//1559 1471//1471 -f 1471//1471 1559//1559 1557//1557 -f 1377//1377 1628//1628 1379//1379 -f 1379//1379 1628//1628 1630//1630 -f 1379//1379 1630//1630 1365//1365 -f 1365//1365 1630//1630 1637//1637 -f 1365//1365 1637//1637 1363//1363 -f 1363//1363 1637//1637 1639//1639 -f 1363//1363 1639//1639 1361//1361 -f 1361//1361 1639//1639 1641//1641 -f 1361//1361 1641//1641 1359//1359 -f 1359//1359 1641//1641 1643//1643 -f 1359//1359 1643//1643 1357//1357 -f 1357//1357 1643//1643 1645//1645 -f 1357//1357 1645//1645 1355//1355 -f 1355//1355 1645//1645 1648//1648 -f 1355//1355 1648//1648 1371//1371 -f 1371//1371 1648//1648 1650//1650 -f 1371//1371 1650//1650 1369//1369 -f 1369//1369 1650//1650 1652//1652 -f 1369//1369 1652//1652 1350//1350 -f 1350//1350 1652//1652 1633//1633 -f 1350//1350 1633//1633 1351//1351 -f 1351//1351 1633//1633 1634//1634 -f 1351//1351 1634//1634 1377//1377 -f 1377//1377 1634//1634 1628//1628 -f 1655//1655 1671//1671 1402//1402 -f 1402//1402 1671//1671 1384//1384 -f 1353//1353 1624//1624 1397//1397 -f 1397//1397 1624//1624 1658//1658 -f 1397//1397 1658//1658 1398//1398 -f 1398//1398 1658//1658 1657//1657 -f 1654//1654 1653//1653 1368//1368 -f 1368//1368 1653//1653 1370//1370 -f 1636//1636 1374//1374 1616//1616 -f 1616//1616 1374//1374 1422//1422 -f 1616//1616 1422//1422 1615//1615 -f 1615//1615 1422//1422 1424//1424 -f 1608//1608 1618//1618 1408//1408 -f 1408//1408 1618//1618 1430//1430 -f 1415//1415 1604//1604 1602//1602 -f 1415//1415 1602//1602 1414//1414 -f 1414//1414 1602//1602 1600//1600 -f 1414//1414 1600//1600 1412//1412 -f 1412//1412 1600//1600 1609//1609 -f 1412//1412 1609//1609 1410//1410 -f 1410//1410 1609//1609 1608//1608 -f 1410//1410 1608//1608 1408//1408 -f 1615//1615 1424//1424 1614//1614 -f 1614//1614 1424//1424 1425//1425 -f 1614//1614 1425//1425 1618//1618 -f 1618//1618 1425//1425 1430//1430 -f 1655//1655 1402//1402 1656//1656 -f 1656//1656 1402//1402 1399//1399 -f 1656//1656 1399//1399 1657//1657 -f 1657//1657 1399//1399 1398//1398 -f 1384//1384 1671//1671 1676//1676 -f 1384//1384 1676//1676 1385//1385 -f 1385//1385 1676//1676 1678//1678 -f 1385//1385 1678//1678 1380//1380 -f 1380//1380 1678//1678 1682//1682 -f 1380//1380 1682//1682 1386//1386 -f 1386//1386 1682//1682 1681//1681 -f 1386//1386 1681//1681 1387//1387 -f 1654//1654 1368//1368 1631//1631 -f 1631//1631 1368//1368 1367//1367 -f 1631//1631 1367//1367 1632//1632 -f 1632//1632 1367//1367 1349//1349 -f 1632//1632 1349//1349 1636//1636 -f 1636//1636 1349//1349 1374//1374 -f 1370//1370 1653//1653 1651//1651 -f 1370//1370 1651//1651 1372//1372 -f 1372//1372 1651//1651 1649//1649 -f 1372//1372 1649//1649 1373//1373 -f 1373//1373 1649//1649 1647//1647 -f 1373//1373 1647//1647 1356//1356 -f 1624//1624 1353//1353 1625//1625 -f 1625//1625 1353//1353 1352//1352 -f 1625//1625 1352//1352 1638//1638 -f 1638//1638 1352//1352 1366//1366 -f 1638//1638 1366//1366 1640//1640 -f 1640//1640 1366//1366 1364//1364 -f 1358//1358 1646//1646 1644//1644 -f 1358//1358 1644//1644 1360//1360 -f 1360//1360 1644//1644 1642//1642 -f 1360//1360 1642//1642 1362//1362 -f 1362//1362 1642//1642 1640//1640 -f 1362//1362 1640//1640 1364//1364 -f 1593//1593 1576//1576 1500//1500 -f 1500//1500 1576//1576 1498//1498 -f 1583//1583 1506//1506 1584//1584 -f 1584//1584 1506//1506 1495//1495 -f 1584//1584 1495//1495 1568//1568 -f 1568//1568 1495//1495 1461//1461 -f 1483//1483 1482//1482 1564//1564 -f 1564//1564 1482//1482 1562//1562 -f 1462//1462 1532//1532 1463//1463 -f 1463//1463 1532//1532 1531//1531 -f 1463//1463 1531//1531 1469//1469 -f 1469//1469 1531//1531 1569//1569 -f 1520//1520 1447//1447 1518//1518 -f 1518//1518 1447//1447 1448//1448 -f 1518//1518 1448//1448 1539//1539 -f 1568//1568 1461//1461 1567//1567 -f 1567//1567 1461//1461 1460//1460 -f 1567//1567 1460//1460 1566//1566 -f 1566//1566 1460//1460 1459//1459 -f 1566//1566 1459//1459 1564//1564 -f 1564//1564 1459//1459 1483//1483 -f 1562//1562 1482//1482 1480//1480 -f 1575//1575 1558//1558 1480//1480 -f 1480//1480 1558//1558 1560//1560 -f 1480//1480 1560//1560 1562//1562 -f 1480//1480 1478//1478 1575//1575 -f 1575//1575 1478//1478 1511//1511 -f 1575//1575 1511//1511 1574//1574 -f 1551//1551 1476//1476 1543//1543 -f 1543//1543 1476//1476 1467//1467 -f 1543//1543 1467//1467 1544//1544 -f 1544//1544 1467//1467 1468//1468 -f 1544//1544 1468//1468 1569//1569 -f 1569//1569 1468//1468 1469//1469 -f 1573//1573 1510//1510 1509//1509 -f 1573//1573 1509//1509 1572//1572 -f 1572//1572 1509//1509 1473//1473 -f 1572//1572 1473//1473 1555//1555 -f 1555//1555 1473//1473 1475//1475 -f 1555//1555 1475//1475 1553//1553 -f 1553//1553 1475//1475 1476//1476 -f 1553//1553 1476//1476 1551//1551 -f 1593//1593 1500//1500 1582//1582 -f 1582//1582 1500//1500 1507//1507 -f 1582//1582 1507//1507 1583//1583 -f 1583//1583 1507//1507 1506//1506 -f 1498//1498 1576//1576 1595//1595 -f 1498//1498 1595//1595 1489//1489 -f 1489//1489 1595//1595 1596//1596 -f 1489//1489 1596//1596 1490//1490 -f 1490//1490 1596//1596 1597//1597 -f 1490//1490 1597//1597 1491//1491 -f 1532//1532 1462//1462 1527//1527 -f 1527//1527 1462//1462 1446//1446 -f 1527//1527 1446//1446 1520//1520 -f 1520//1520 1446//1446 1447//1447 -f 1514//1514 1542//1542 1541//1541 -f 1514//1514 1541//1541 1512//1512 -f 1512//1512 1541//1541 1540//1540 -f 1512//1512 1540//1540 1513//1513 -f 1513//1513 1540//1540 1539//1539 -f 1513//1513 1539//1539 1448//1448 -f 1663//1663 1394//1394 1661//1661 -f 1661//1661 1394//1394 1391//1391 -f 1661//1661 1391//1391 1680//1680 -f 1680//1680 1391//1391 1389//1389 -f 1488//1488 1686//1686 1515//1515 -f 1515//1515 1686//1686 1685//1685 -f 1515//1515 1685//1685 1484//1484 -f 1484//1484 1685//1685 1684//1684 -f 1484//1484 1684//1684 1485//1485 -f 1485//1485 1684//1684 1683//1683 -f 1534//1534 1445//1445 1530//1530 -f 1530//1530 1445//1445 1436//1436 -f 1530//1530 1436//1436 1570//1570 -f 1570//1570 1436//1436 1464//1464 -f 1621//1621 1453//1453 1622//1622 -f 1622//1622 1453//1453 1452//1452 -f 1622//1622 1452//1452 1635//1635 -f 1635//1635 1452//1452 1451//1451 -f 1407//1407 1670//1670 1354//1354 -f 1354//1354 1670//1670 1623//1623 -f 1354//1354 1623//1623 1378//1378 -f 1378//1378 1623//1623 1629//1629 -f 1443//1443 1444//1444 1522//1522 -f 1522//1522 1444//1444 1533//1533 -f 1667//1667 1668//1668 1396//1396 -f 1396//1396 1668//1668 1406//1406 -f 1443//1443 1522//1522 1521//1521 -f 1443//1443 1521//1521 1442//1442 -f 1442//1442 1521//1521 1343//1343 -f 1442//1442 1343//1343 1345//1345 -f 1394//1394 1663//1663 1666//1666 -f 1394//1394 1666//1666 1395//1395 -f 1395//1395 1666//1666 1667//1667 -f 1395//1395 1667//1667 1396//1396 -f 1668//1668 1670//1670 1406//1406 -f 1406//1406 1670//1670 1407//1407 -f 1534//1534 1533//1533 1445//1445 -f 1445//1445 1533//1533 1444//1444 -f 1570//1570 1464//1464 1571//1571 -f 1571//1571 1464//1464 1457//1457 -f 1571//1571 1457//1457 1548//1548 -f 1548//1548 1457//1457 1455//1455 -f 1548//1548 1455//1455 1621//1621 -f 1621//1621 1455//1455 1453//1453 -f 1635//1635 1451//1451 1626//1626 -f 1626//1626 1451//1451 1375//1375 -f 1626//1626 1375//1375 1627//1627 -f 1627//1627 1375//1375 1376//1376 -f 1627//1627 1376//1376 1629//1629 -f 1629//1629 1376//1376 1378//1378 -f 1687//1687 1688//1688 1689//1689 -f 1689//1689 1688//1688 1690//1690 -f 1689//1689 1690//1690 1691//1691 -f 1691//1691 1690//1690 1692//1692 -f 1691//1691 1692//1692 1693//1693 -f 1693//1693 1692//1692 1694//1694 -f 1693//1693 1694//1694 1695//1695 -f 1696//1696 1697//1697 1698//1698 -f 1698//1698 1697//1697 1699//1699 -f 1698//1698 1699//1699 1687//1687 -f 1687//1687 1699//1699 1700//1700 -f 1687//1687 1700//1700 1688//1688 -f 1701//1701 1702//1702 1703//1703 -f 1703//1703 1702//1702 1704//1704 -f 1705//1705 1697//1697 1706//1706 -f 1706//1706 1697//1697 1696//1696 -f 1706//1706 1696//1696 1703//1703 -f 1703//1703 1696//1696 1707//1707 -f 1703//1703 1707//1707 1701//1701 -f 1708//1708 1709//1709 1710//1710 -f 1710//1710 1709//1709 1711//1711 -f 1712//1712 1711//1711 1713//1713 -f 1706//1706 1714//1714 1705//1705 -f 1705//1705 1714//1714 1715//1715 -f 1705//1705 1715//1715 1716//1716 -f 1716//1716 1715//1715 1717//1717 -f 1716//1716 1717//1717 1718//1718 -f 1718//1718 1717//1717 1719//1719 -f 1718//1718 1719//1719 1720//1720 -f 1720//1720 1719//1719 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1724//1724 1723//1723 1725//1725 -f 1724//1724 1725//1725 1721//1721 -f 1721//1721 1725//1725 1726//1726 -f 1721//1721 1726//1726 1720//1720 -f 1727//1727 1728//1728 1729//1729 -f 1729//1729 1728//1728 1730//1730 -f 1729//1729 1730//1730 1731//1731 -f 1731//1731 1730//1730 1732//1732 -f 1731//1731 1732//1732 1733//1733 -f 1733//1733 1732//1732 1708//1708 -f 1733//1733 1708//1708 1734//1734 -f 1734//1734 1708//1708 1710//1710 -f 1735//1735 1736//1736 1737//1737 -f 1737//1737 1736//1736 1738//1738 -f 1737//1737 1738//1738 1739//1739 -f 1739//1739 1738//1738 1740//1740 -f 1739//1739 1740//1740 1741//1741 -f 1741//1741 1740//1740 1712//1712 -f 1741//1741 1712//1712 1742//1742 -f 1742//1742 1712//1712 1713//1713 -f 1702//1702 1743//1743 1704//1704 -f 1704//1704 1743//1743 1744//1744 -f 1704//1704 1744//1744 1745//1745 -f 1745//1745 1744//1744 1723//1723 -f 1745//1745 1723//1723 1746//1746 -f 1746//1746 1723//1723 1722//1722 -f 1747//1747 1748//1748 1743//1743 -f 1743//1743 1748//1748 1749//1749 -f 1743//1743 1749//1749 1744//1744 -f 1750//1750 1751//1751 1752//1752 -f 1752//1752 1751//1751 1753//1753 -f 1752//1752 1753//1753 1735//1735 -f 1735//1735 1753//1753 1754//1754 -f 1735//1735 1754//1754 1736//1736 -f 1755//1755 1756//1756 1757//1757 -f 1709//1709 1758//1758 1711//1711 -f 1711//1711 1758//1758 1759//1759 -f 1711//1711 1759//1759 1713//1713 -f 1713//1713 1759//1759 1760//1760 -f 1713//1713 1760//1760 1761//1761 -f 1761//1761 1760//1760 1757//1757 -f 1761//1761 1757//1757 1762//1762 -f 1762//1762 1757//1757 1756//1756 -f 1762//1762 1756//1756 1763//1763 -f 1763//1763 1756//1756 1751//1751 -f 1763//1763 1751//1751 1764//1764 -f 1764//1764 1751//1751 1750//1750 -f 1765//1765 1757//1757 1743//1743 -f 1743//1743 1757//1757 1766//1766 -f 1743//1743 1766//1766 1747//1747 -f 1747//1747 1766//1766 1767//1767 -f 1747//1747 1767//1767 1727//1727 -f 1727//1727 1767//1767 1768//1768 -f 1727//1727 1768//1768 1728//1728 -f 1695//1695 1694//1694 1765//1765 -f 1765//1765 1694//1694 1769//1769 -f 1765//1765 1769//1769 1757//1757 -f 1757//1757 1769//1769 1770//1770 -f 1757//1757 1770//1770 1755//1755 -f 1771//1771 1772//1772 1773//1773 -f 1773//1773 1772//1772 1774//1774 -f 1773//1773 1774//1774 1775//1775 -f 1775//1775 1774//1774 1776//1776 -f 1775//1775 1776//1776 1777//1777 -f 1778//1778 1779//1779 1780//1780 -f 1780//1780 1779//1779 1781//1781 -f 1780//1780 1781//1781 1782//1782 -f 1782//1782 1781//1781 1783//1783 -f 1782//1782 1783//1783 1784//1784 -f 1785//1785 1786//1786 1787//1787 -f 1787//1787 1786//1786 1788//1788 -f 1787//1787 1788//1788 1789//1789 -f 1789//1789 1788//1788 1790//1790 -f 1789//1789 1790//1790 1791//1791 -f 1791//1791 1790//1790 1792//1792 -f 1791//1791 1792//1792 1793//1793 -f 1794//1794 1795//1795 1796//1796 -f 1796//1796 1795//1795 1797//1797 -f 1796//1796 1797//1797 1798//1798 -f 1798//1798 1797//1797 1799//1799 -f 1798//1798 1799//1799 1800//1800 -f 1800//1800 1799//1799 1801//1801 -f 1802//1802 1803//1803 1804//1804 -f 1805//1805 1806//1806 1807//1807 -f 1807//1807 1806//1806 1808//1808 -f 1807//1807 1808//1808 1809//1809 -f 1809//1809 1808//1808 1810//1810 -f 1809//1809 1810//1810 1811//1811 -f 1811//1811 1810//1810 1802//1802 -f 1811//1811 1802//1802 1812//1812 -f 1812//1812 1802//1802 1804//1804 -f 1813//1813 1814//1814 1801//1801 -f 1801//1801 1814//1814 1815//1815 -f 1801//1801 1815//1815 1800//1800 -f 1816//1816 1817//1817 1818//1818 -f 1818//1818 1817//1817 1819//1819 -f 1818//1818 1819//1819 1820//1820 -f 1820//1820 1819//1819 1821//1821 -f 1820//1820 1821//1821 1822//1822 -f 1822//1822 1821//1821 1823//1823 -f 1822//1822 1823//1823 1824//1824 -f 1777//1777 1804//1804 1775//1775 -f 1775//1775 1804//1804 1803//1803 -f 1775//1775 1803//1803 1825//1825 -f 1825//1825 1803//1803 1826//1826 -f 1825//1825 1826//1826 1816//1816 -f 1816//1816 1826//1826 1827//1827 -f 1816//1816 1827//1827 1817//1817 -f 1784//1784 1814//1814 1782//1782 -f 1782//1782 1814//1814 1813//1813 -f 1782//1782 1813//1813 1828//1828 -f 1828//1828 1813//1813 1829//1829 -f 1828//1828 1829//1829 1785//1785 -f 1785//1785 1829//1829 1830//1830 -f 1785//1785 1830//1830 1786//1786 -f 1831//1831 1832//1832 1833//1833 -f 1834//1834 1835//1835 1836//1836 -f 1833//1833 1837//1837 1838//1838 -f 1778//1778 1833//1833 1779//1779 -f 1779//1779 1833//1833 1832//1832 -f 1779//1779 1832//1832 1839//1839 -f 1839//1839 1832//1832 1840//1840 -f 1839//1839 1840//1840 1841//1841 -f 1841//1841 1840//1840 1842//1842 -f 1841//1841 1842//1842 1794//1794 -f 1794//1794 1842//1842 1843//1843 -f 1794//1794 1843//1843 1795//1795 -f 1837//1837 1833//1833 1836//1836 -f 1836//1836 1833//1833 1844//1844 -f 1836//1836 1844//1844 1845//1845 -f 1771//1771 1836//1836 1772//1772 -f 1772//1772 1836//1836 1835//1835 -f 1772//1772 1835//1835 1846//1846 -f 1846//1846 1835//1835 1847//1847 -f 1846//1846 1847//1847 1848//1848 -f 1848//1848 1847//1847 1849//1849 -f 1848//1848 1849//1849 1805//1805 -f 1805//1805 1849//1849 1850//1850 -f 1805//1805 1850//1850 1806//1806 -f 1824//1824 1823//1823 1838//1838 -f 1838//1838 1823//1823 1851//1851 -f 1838//1838 1851//1851 1833//1833 -f 1833//1833 1851//1851 1852//1852 -f 1833//1833 1852//1852 1831//1831 -f 1793//1793 1792//1792 1845//1845 -f 1845//1845 1792//1792 1853//1853 -f 1845//1845 1853//1853 1836//1836 -f 1836//1836 1853//1853 1854//1854 -f 1836//1836 1854//1854 1834//1834 -f 1736//1736 1817//1817 1827//1827 -f 1736//1736 1827//1827 1738//1738 -f 1738//1738 1827//1827 1826//1826 -f 1738//1738 1826//1826 1740//1740 -f 1740//1740 1826//1826 1803//1803 -f 1740//1740 1803//1803 1712//1712 -f 1711//1711 1712//1712 1802//1802 -f 1802//1802 1712//1712 1803//1803 -f 1711//1711 1802//1802 1810//1810 -f 1711//1711 1810//1810 1710//1710 -f 1710//1710 1810//1810 1808//1808 -f 1710//1710 1808//1808 1734//1734 -f 1734//1734 1808//1808 1806//1806 -f 1734//1734 1806//1806 1733//1733 -f 1720//1720 1786//1786 1830//1830 -f 1720//1720 1830//1830 1718//1718 -f 1718//1718 1830//1830 1829//1829 -f 1718//1718 1829//1829 1716//1716 -f 1716//1716 1829//1829 1813//1813 -f 1716//1716 1813//1813 1705//1705 -f 1697//1697 1705//1705 1801//1801 -f 1801//1801 1705//1705 1813//1813 -f 1697//1697 1801//1801 1799//1799 -f 1697//1697 1799//1799 1699//1699 -f 1699//1699 1799//1799 1797//1797 -f 1699//1699 1797//1797 1700//1700 -f 1700//1700 1797//1797 1795//1795 -f 1700//1700 1795//1795 1688//1688 -f 1732//1732 1805//1805 1708//1708 -f 1708//1708 1805//1805 1807//1807 -f 1708//1708 1807//1807 1709//1709 -f 1709//1709 1807//1807 1809//1809 -f 1709//1709 1809//1809 1758//1758 -f 1758//1758 1809//1809 1811//1811 -f 1758//1758 1811//1811 1759//1759 -f 1759//1759 1811//1811 1812//1812 -f 1759//1759 1812//1812 1760//1760 -f 1760//1760 1812//1812 1804//1804 -f 1760//1760 1804//1804 1757//1757 -f 1757//1757 1804//1804 1777//1777 -f 1757//1757 1777//1777 1766//1766 -f 1766//1766 1777//1777 1776//1776 -f 1766//1766 1776//1776 1767//1767 -f 1767//1767 1776//1776 1774//1774 -f 1767//1767 1774//1774 1768//1768 -f 1768//1768 1774//1774 1772//1772 -f 1768//1768 1772//1772 1728//1728 -f 1728//1728 1772//1772 1846//1846 -f 1728//1728 1846//1846 1730//1730 -f 1730//1730 1846//1846 1848//1848 -f 1730//1730 1848//1848 1732//1732 -f 1732//1732 1848//1848 1805//1805 -f 1721//1721 1787//1787 1724//1724 -f 1724//1724 1787//1787 1789//1789 -f 1724//1724 1789//1789 1722//1722 -f 1722//1722 1789//1789 1791//1791 -f 1722//1722 1791//1791 1746//1746 -f 1746//1746 1791//1791 1793//1793 -f 1746//1746 1793//1793 1745//1745 -f 1745//1745 1793//1793 1845//1845 -f 1745//1745 1845//1845 1704//1704 -f 1704//1704 1845//1845 1844//1844 -f 1704//1704 1844//1844 1703//1703 -f 1703//1703 1844//1844 1833//1833 -f 1703//1703 1833//1833 1706//1706 -f 1706//1706 1833//1833 1778//1778 -f 1706//1706 1778//1778 1714//1714 -f 1714//1714 1778//1778 1780//1780 -f 1714//1714 1780//1780 1715//1715 -f 1715//1715 1780//1780 1782//1782 -f 1715//1715 1782//1782 1717//1717 -f 1717//1717 1782//1782 1828//1828 -f 1717//1717 1828//1828 1719//1719 -f 1719//1719 1828//1828 1785//1785 -f 1719//1719 1785//1785 1721//1721 -f 1721//1721 1785//1785 1787//1787 -f 1761//1761 1836//1836 1713//1713 -f 1713//1713 1836//1836 1771//1771 -f 1713//1713 1771//1771 1742//1742 -f 1742//1742 1771//1771 1773//1773 -f 1742//1742 1773//1773 1741//1741 -f 1741//1741 1773//1773 1775//1775 -f 1741//1741 1775//1775 1739//1739 -f 1739//1739 1775//1775 1825//1825 -f 1739//1739 1825//1825 1737//1737 -f 1737//1737 1825//1825 1816//1816 -f 1737//1737 1816//1816 1735//1735 -f 1735//1735 1816//1816 1818//1818 -f 1735//1735 1818//1818 1752//1752 -f 1752//1752 1818//1818 1820//1820 -f 1752//1752 1820//1820 1750//1750 -f 1750//1750 1820//1820 1822//1822 -f 1750//1750 1822//1822 1764//1764 -f 1764//1764 1822//1822 1824//1824 -f 1764//1764 1824//1824 1763//1763 -f 1763//1763 1824//1824 1838//1838 -f 1763//1763 1838//1838 1762//1762 -f 1762//1762 1838//1838 1837//1837 -f 1762//1762 1837//1837 1761//1761 -f 1761//1761 1837//1837 1836//1836 -f 1702//1702 1784//1784 1743//1743 -f 1743//1743 1784//1784 1783//1783 -f 1743//1743 1783//1783 1765//1765 -f 1765//1765 1783//1783 1781//1781 -f 1765//1765 1781//1781 1695//1695 -f 1695//1695 1781//1781 1779//1779 -f 1695//1695 1779//1779 1693//1693 -f 1693//1693 1779//1779 1839//1839 -f 1693//1693 1839//1839 1691//1691 -f 1691//1691 1839//1839 1841//1841 -f 1691//1691 1841//1841 1689//1689 -f 1689//1689 1841//1841 1794//1794 -f 1689//1689 1794//1794 1687//1687 -f 1687//1687 1794//1794 1796//1796 -f 1687//1687 1796//1796 1698//1698 -f 1698//1698 1796//1796 1798//1798 -f 1698//1698 1798//1798 1696//1696 -f 1696//1696 1798//1798 1800//1800 -f 1696//1696 1800//1800 1707//1707 -f 1707//1707 1800//1800 1815//1815 -f 1707//1707 1815//1815 1701//1701 -f 1701//1701 1815//1815 1814//1814 -f 1701//1701 1814//1814 1702//1702 -f 1702//1702 1814//1814 1784//1784 -f 1823//1823 1821//1821 1751//1751 -f 1751//1751 1821//1821 1753//1753 -f 1831//1831 1852//1852 1770//1770 -f 1770//1770 1852//1852 1755//1755 -f 1842//1842 1840//1840 1692//1692 -f 1692//1692 1840//1840 1694//1694 -f 1688//1688 1795//1795 1843//1843 -f 1688//1688 1843//1843 1690//1690 -f 1690//1690 1843//1843 1842//1842 -f 1690//1690 1842//1842 1692//1692 -f 1831//1831 1770//1770 1832//1832 -f 1832//1832 1770//1770 1769//1769 -f 1832//1832 1769//1769 1840//1840 -f 1840//1840 1769//1769 1694//1694 -f 1755//1755 1852//1852 1756//1756 -f 1756//1756 1852//1852 1851//1851 -f 1756//1756 1851//1851 1751//1751 -f 1751//1751 1851//1851 1823//1823 -f 1753//1753 1821//1821 1819//1819 -f 1753//1753 1819//1819 1754//1754 -f 1754//1754 1819//1819 1817//1817 -f 1754//1754 1817//1817 1736//1736 -f 1725//1725 1723//1723 1790//1790 -f 1790//1790 1723//1723 1792//1792 -f 1749//1749 1748//1748 1854//1854 -f 1854//1854 1748//1748 1834//1834 -f 1727//1727 1729//1729 1847//1847 -f 1847//1847 1729//1729 1849//1849 -f 1725//1725 1790//1790 1788//1788 -f 1725//1725 1788//1788 1726//1726 -f 1726//1726 1788//1788 1786//1786 -f 1726//1726 1786//1786 1720//1720 -f 1792//1792 1723//1723 1853//1853 -f 1853//1853 1723//1723 1744//1744 -f 1853//1853 1744//1744 1854//1854 -f 1854//1854 1744//1744 1749//1749 -f 1727//1727 1847//1847 1747//1747 -f 1747//1747 1847//1847 1835//1835 -f 1747//1747 1835//1835 1748//1748 -f 1748//1748 1835//1835 1834//1834 -f 1733//1733 1806//1806 1850//1850 -f 1733//1733 1850//1850 1731//1731 -f 1731//1731 1850//1850 1849//1849 -f 1731//1731 1849//1849 1729//1729 -f 1855//1855 1856//1856 1857//1857 -f 1857//1857 1856//1856 1858//1858 -f 1859//1859 1860//1860 1861//1861 -f 1862//1862 1863//1863 1864//1864 -f 1864//1864 1863//1863 1865//1865 -f 1864//1864 1865//1865 1866//1866 -f 1867//1867 1866//1866 1868//1868 -f 1868//1868 1866//1866 1865//1865 -f 1868//1868 1865//1865 1869//1869 -f 1869//1869 1865//1865 1870//1870 -f 1869//1869 1870//1870 1861//1861 -f 1861//1861 1870//1870 1871//1871 -f 1861//1861 1871//1871 1859//1859 -f 1872//1872 1873//1873 1874//1874 -f 1875//1875 1876//1876 1877//1877 -f 1877//1877 1876//1876 1878//1878 -f 1859//1859 1879//1879 1860//1860 -f 1860//1860 1879//1879 1880//1880 -f 1860//1860 1880//1880 1881//1881 -f 1882//1882 1883//1883 1884//1884 -f 1884//1884 1883//1883 1885//1885 -f 1884//1884 1885//1885 1886//1886 -f 1882//1882 1887//1887 1883//1883 -f 1883//1883 1887//1887 1888//1888 -f 1883//1883 1888//1888 1889//1889 -f 1889//1889 1888//1888 1890//1890 -f 1889//1889 1890//1890 1891//1891 -f 1891//1891 1890//1890 1892//1892 -f 1891//1891 1892//1892 1893//1893 -f 1893//1893 1892//1892 1894//1894 -f 1893//1893 1894//1894 1895//1895 -f 1895//1895 1894//1894 1896//1896 -f 1872//1872 1874//1874 1897//1897 -f 1885//1885 1898//1898 1886//1886 -f 1886//1886 1898//1898 1874//1874 -f 1886//1886 1874//1874 1899//1899 -f 1899//1899 1874//1874 1873//1873 -f 1873//1873 1900//1900 1899//1899 -f 1899//1899 1900//1900 1901//1901 -f 1899//1899 1901//1901 1902//1902 -f 1902//1902 1901//1901 1903//1903 -f 1902//1902 1903//1903 1904//1904 -f 1905//1905 1906//1906 1907//1907 -f 1907//1907 1906//1906 1908//1908 -f 1907//1907 1908//1908 1903//1903 -f 1903//1903 1908//1908 1909//1909 -f 1903//1903 1909//1909 1904//1904 -f 1910//1910 1911//1911 1912//1912 -f 1912//1912 1911//1911 1913//1913 -f 1914//1914 1915//1915 1916//1916 -f 1916//1916 1915//1915 1917//1917 -f 1916//1916 1917//1917 1858//1858 -f 1858//1858 1917//1917 1918//1918 -f 1858//1858 1918//1918 1857//1857 -f 1857//1857 1918//1918 1919//1919 -f 1857//1857 1919//1919 1920//1920 -f 1910//1910 1921//1921 1911//1911 -f 1911//1911 1921//1921 1922//1922 -f 1911//1911 1922//1922 1923//1923 -f 1907//1907 1924//1924 1905//1905 -f 1905//1905 1924//1924 1925//1925 -f 1905//1905 1925//1925 1926//1926 -f 1914//1914 1927//1927 1915//1915 -f 1915//1915 1927//1927 1928//1928 -f 1915//1915 1928//1928 1929//1929 -f 1929//1929 1928//1928 1930//1930 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1935//1935 -f 1935//1935 1934//1934 1936//1936 -f 1925//1925 1937//1937 1926//1926 -f 1926//1926 1937//1937 1938//1938 -f 1926//1926 1938//1938 1939//1939 -f 1939//1939 1938//1938 1940//1940 -f 1939//1939 1940//1940 1897//1897 -f 1920//1920 1911//1911 1857//1857 -f 1857//1857 1911//1911 1923//1923 -f 1857//1857 1923//1923 1941//1941 -f 1941//1941 1923//1923 1942//1942 -f 1943//1943 1878//1878 1944//1944 -f 1943//1943 1944//1944 1945//1945 -f 1945//1945 1944//1944 1946//1946 -f 1945//1945 1946//1946 1947//1947 -f 1948//1948 1949//1949 1878//1878 -f 1878//1878 1949//1949 1950//1950 -f 1878//1878 1950//1950 1881//1881 -f 1896//1896 1894//1894 1943//1943 -f 1943//1943 1894//1894 1951//1951 -f 1943//1943 1951//1951 1878//1878 -f 1878//1878 1951//1951 1952//1952 -f 1878//1878 1952//1952 1948//1948 -f 1880//1880 1953//1953 1881//1881 -f 1881//1881 1953//1953 1954//1954 -f 1881//1881 1954//1954 1878//1878 -f 1878//1878 1954//1954 1955//1955 -f 1878//1878 1955//1955 1877//1877 -f 1877//1877 1955//1955 1956//1956 -f 1877//1877 1956//1956 1862//1862 -f 1862//1862 1956//1956 1957//1957 -f 1862//1862 1957//1957 1863//1863 -f 1936//1936 1934//1934 1913//1913 -f 1913//1913 1934//1934 1958//1958 -f 1913//1913 1958//1958 1912//1912 -f 1912//1912 1958//1958 1959//1959 -f 1912//1912 1959//1959 1960//1960 -f 1947//1947 1961//1961 1945//1945 -f 1945//1945 1961//1961 1962//1962 -f 1945//1945 1962//1962 1963//1963 -f 1874//1874 1964//1964 1897//1897 -f 1897//1897 1964//1964 1945//1945 -f 1897//1897 1945//1945 1939//1939 -f 1939//1939 1945//1945 1963//1963 -f 1939//1939 1963//1963 1965//1965 -f 1965//1965 1963//1963 1912//1912 -f 1965//1965 1912//1912 1966//1966 -f 1966//1966 1912//1912 1960//1960 -f 1967//1967 1968//1968 1969//1969 -f 1970//1970 1971//1971 1972//1972 -f 1972//1972 1971//1971 1973//1973 -f 1972//1972 1973//1973 1974//1974 -f 1975//1975 1974//1974 1976//1976 -f 1976//1976 1974//1974 1973//1973 -f 1976//1976 1973//1973 1977//1977 -f 1977//1977 1973//1973 1978//1978 -f 1977//1977 1978//1978 1969//1969 -f 1969//1969 1978//1978 1979//1979 -f 1969//1969 1979//1979 1967//1967 -f 1980//1980 1981//1981 1982//1982 -f 1982//1982 1981//1981 1983//1983 -f 1982//1982 1983//1983 1984//1984 -f 1984//1984 1983//1983 1985//1985 -f 1984//1984 1985//1985 1986//1986 -f 1986//1986 1985//1985 1987//1987 -f 1986//1986 1987//1987 1988//1988 -f 1988//1988 1987//1987 1989//1989 -f 1988//1988 1989//1989 1990//1990 -f 1991//1991 1992//1992 1993//1993 -f 1992//1992 1991//1991 1994//1994 -f 1994//1994 1991//1991 1995//1995 -f 1994//1994 1995//1995 1996//1996 -f 1996//1996 1995//1995 1997//1997 -f 1996//1996 1997//1997 1989//1989 -f 1989//1989 1997//1997 1998//1998 -f 1989//1989 1998//1998 1990//1990 -f 1999//1999 2000//2000 2001//2001 -f 2001//2001 2000//2000 2002//2002 -f 2003//2003 2004//2004 2005//2005 -f 2005//2005 2004//2004 2006//2006 -f 2005//2005 2006//2006 2007//2007 -f 2007//2007 2006//2006 2008//2008 -f 2007//2007 2008//2008 2009//2009 -f 1856//1856 2010//2010 2011//2011 -f 2012//2012 2013//2013 2014//2014 -f 2014//2014 2013//2013 2015//2015 -f 2014//2014 2015//2015 2016//2016 -f 1993//1993 2001//2001 1991//1991 -f 1991//1991 2001//2001 2002//2002 -f 1991//1991 2002//2002 2017//2017 -f 2017//2017 2002//2002 2018//2018 -f 1856//1856 2011//2011 2019//2019 -f 2019//2019 2011//2011 2020//2020 -f 2019//2019 2020//2020 2021//2021 -f 2014//2014 2022//2022 2012//2012 -f 2012//2012 2022//2022 2023//2023 -f 2012//2012 2023//2023 2020//2020 -f 2020//2020 2023//2023 2024//2024 -f 2020//2020 2024//2024 2021//2021 -f 2025//2025 2026//2026 1855//1855 -f 1855//1855 2026//2026 2027//2027 -f 2028//2028 2029//2029 2030//2030 -f 2030//2030 2029//2029 2031//2031 -f 2030//2030 2031//2031 2032//2032 -f 2032//2032 2031//2031 2004//2004 -f 2003//2003 2033//2033 2004//2004 -f 2004//2004 2033//2033 2034//2034 -f 2004//2004 2034//2034 2032//2032 -f 2032//2032 2034//2034 2035//2035 -f 2032//2032 2035//2035 1970//1970 -f 1970//1970 2035//2035 2036//2036 -f 1970//1970 2036//2036 1971//1971 -f 2010//2010 1856//1856 2037//2037 -f 2037//2037 1856//1856 1855//1855 -f 2037//2037 1855//1855 2038//2038 -f 2038//2038 1855//1855 2027//2027 -f 2038//2038 2027//2027 2039//2039 -f 2039//2039 2027//2027 2040//2040 -f 2039//2039 2040//2040 2041//2041 -f 2041//2041 2040//2040 2042//2042 -f 2041//2041 2042//2042 2043//2043 -f 2028//2028 2044//2044 2029//2029 -f 2029//2029 2044//2044 2045//2045 -f 2029//2029 2045//2045 2046//2046 -f 2046//2046 2045//2045 2047//2047 -f 2046//2046 2047//2047 2048//2048 -f 2048//2048 2047//2047 2049//2049 -f 2048//2048 2049//2049 2050//2050 -f 2050//2050 2049//2049 2051//2051 -f 2050//2050 2051//2051 2052//2052 -f 2053//2053 2054//2054 2001//2001 -f 2001//2001 2054//2054 2055//2055 -f 2001//2001 2055//2055 1999//1999 -f 2052//2052 2051//2051 2056//2056 -f 2056//2056 2051//2051 2057//2057 -f 2056//2056 2057//2057 2058//2058 -f 2051//2051 2059//2059 2057//2057 -f 2057//2057 2059//2059 2060//2060 -f 2057//2057 2060//2060 2061//2061 -f 2043//2043 2057//2057 2041//2041 -f 2041//2041 2057//2057 2062//2062 -f 2041//2041 2062//2062 2063//2063 -f 2063//2063 2062//2062 2016//2016 -f 2063//2063 2016//2016 2064//2064 -f 2064//2064 2016//2016 2015//2015 -f 2061//2061 2065//2065 2057//2057 -f 2057//2057 2065//2065 2066//2066 -f 2057//2057 2066//2066 2062//2062 -f 2058//2058 2057//2057 2009//2009 -f 2009//2009 2057//2057 2067//2067 -f 2009//2009 2067//2067 2068//2068 -f 1980//1980 1982//1982 2053//2053 -f 2053//2053 1982//1982 2069//2069 -f 2053//2053 2069//2069 2054//2054 -f 2054//2054 2069//2069 2070//2070 -f 2054//2054 2070//2070 2071//2071 -f 1967//1967 2007//2007 1968//1968 -f 1968//1968 2007//2007 2009//2009 -f 1968//1968 2009//2009 2072//2072 -f 2072//2072 2009//2009 2068//2068 -f 2072//2072 2068//2068 2073//2073 -f 2073//2073 2068//2068 2054//2054 -f 2073//2073 2054//2054 2074//2074 -f 2074//2074 2054//2054 2071//2071 -f 1904//1904 2028//2028 2030//2030 -f 1904//1904 2030//2030 1902//1902 -f 1902//1902 2030//2030 2032//2032 -f 1902//1902 2032//2032 1899//1899 -f 1886//1886 1970//1970 1972//1972 -f 1886//1886 1972//1972 1884//1884 -f 1884//1884 1972//1972 1974//1974 -f 1884//1884 1974//1974 1882//1882 -f 1866//1866 1998//1998 1997//1997 -f 1866//1866 1997//1997 1864//1864 -f 1864//1864 1997//1997 1995//1995 -f 1864//1864 1995//1995 1862//1862 -f 1858//1858 1856//1856 2019//2019 -f 1858//1858 2019//2019 1916//1916 -f 1916//1916 2019//2019 2021//2021 -f 1916//1916 2021//2021 1914//1914 -f 1889//1889 1978//1978 1883//1883 -f 1883//1883 1978//1978 1973//1973 -f 1883//1883 1973//1973 1885//1885 -f 1885//1885 1973//1973 1971//1971 -f 1885//1885 1971//1971 1898//1898 -f 1898//1898 1971//1971 2036//2036 -f 1898//1898 2036//2036 1874//1874 -f 1874//1874 2036//2036 2035//2035 -f 1874//1874 2035//2035 1964//1964 -f 1964//1964 2035//2035 2034//2034 -f 1964//1964 2034//2034 1945//1945 -f 1945//1945 2034//2034 2033//2033 -f 1945//1945 2033//2033 1943//1943 -f 1943//1943 2033//2033 2003//2003 -f 1943//1943 2003//2003 1896//1896 -f 1896//1896 2003//2003 2005//2005 -f 1896//1896 2005//2005 1895//1895 -f 1895//1895 2005//2005 2007//2007 -f 1895//1895 2007//2007 1893//1893 -f 1893//1893 2007//2007 1967//1967 -f 1893//1893 1967//1967 1891//1891 -f 1891//1891 1967//1967 1979//1979 -f 1891//1891 1979//1979 1889//1889 -f 1889//1889 1979//1979 1978//1978 -f 1870//1870 1987//1987 1871//1871 -f 1871//1871 1987//1987 1985//1985 -f 1871//1871 1985//1985 1859//1859 -f 1859//1859 1985//1985 1983//1983 -f 1859//1859 1983//1983 1879//1879 -f 1879//1879 1983//1983 1981//1981 -f 1879//1879 1981//1981 1880//1880 -f 1880//1880 1981//1981 1980//1980 -f 1880//1880 1980//1980 1953//1953 -f 1953//1953 1980//1980 2053//2053 -f 1953//1953 2053//2053 1954//1954 -f 1954//1954 2053//2053 2001//2001 -f 1954//1954 2001//2001 1955//1955 -f 1955//1955 2001//2001 1993//1993 -f 1955//1955 1993//1993 1956//1956 -f 1956//1956 1993//1993 1992//1992 -f 1956//1956 1992//1992 1957//1957 -f 1957//1957 1992//1992 1994//1994 -f 1957//1957 1994//1994 1863//1863 -f 1863//1863 1994//1994 1996//1996 -f 1863//1863 1996//1996 1865//1865 -f 1865//1865 1996//1996 1989//1989 -f 1865//1865 1989//1989 1870//1870 -f 1870//1870 1989//1989 1987//1987 -f 1897//1897 2009//2009 1872//1872 -f 1872//1872 2009//2009 2008//2008 -f 1872//1872 2008//2008 1873//1873 -f 1873//1873 2008//2008 2006//2006 -f 1873//1873 2006//2006 1900//1900 -f 1900//1900 2006//2006 2004//2004 -f 1900//1900 2004//2004 1901//1901 -f 1901//1901 2004//2004 2031//2031 -f 1901//1901 2031//2031 1903//1903 -f 1903//1903 2031//2031 2029//2029 -f 1903//1903 2029//2029 1907//1907 -f 1907//1907 2029//2029 2046//2046 -f 1907//1907 2046//2046 1924//1924 -f 1924//1924 2046//2046 2048//2048 -f 1924//1924 2048//2048 1925//1925 -f 1925//1925 2048//2048 2050//2050 -f 1925//1925 2050//2050 1937//1937 -f 1937//1937 2050//2050 2052//2052 -f 1937//1937 2052//2052 1938//1938 -f 1938//1938 2052//2052 2056//2056 -f 1938//1938 2056//2056 1940//1940 -f 1940//1940 2056//2056 2058//2058 -f 1940//1940 2058//2058 1897//1897 -f 1897//1897 2058//2058 2009//2009 -f 1911//1911 2039//2039 1913//1913 -f 1913//1913 2039//2039 2041//2041 -f 1913//1913 2041//2041 1936//1936 -f 1936//1936 2041//2041 2063//2063 -f 1936//1936 2063//2063 1935//1935 -f 1935//1935 2063//2063 2064//2064 -f 1935//1935 2064//2064 1933//1933 -f 1933//1933 2064//2064 2015//2015 -f 1933//1933 2015//2015 1931//1931 -f 1931//1931 2015//2015 2013//2013 -f 1931//1931 2013//2013 1929//1929 -f 1929//1929 2013//2013 2012//2012 -f 1929//1929 2012//2012 1915//1915 -f 1915//1915 2012//2012 2020//2020 -f 1915//1915 2020//2020 1917//1917 -f 1917//1917 2020//2020 2011//2011 -f 1917//1917 2011//2011 1918//1918 -f 1918//1918 2011//2011 2010//2010 -f 1918//1918 2010//2010 1919//1919 -f 1919//1919 2010//2010 2037//2037 -f 1919//1919 2037//2037 1920//1920 -f 1920//1920 2037//2037 2038//2038 -f 1920//1920 2038//2038 1911//1911 -f 1911//1911 2038//2038 2039//2039 -f 1877//1877 1862//1862 1991//1991 -f 1991//1991 1862//1862 1995//1995 -f 1886//1886 1899//1899 1970//1970 -f 1970//1970 1899//1899 2032//2032 -f 1894//1894 1892//1892 1968//1968 -f 1968//1968 1892//1892 1969//1969 -f 1949//1949 1948//1948 2071//2071 -f 2071//2071 1948//1948 2074//2074 -f 1861//1861 1860//1860 1984//1984 -f 1984//1984 1860//1860 1982//1982 -f 1861//1861 1984//1984 1986//1986 -f 1861//1861 1986//1986 1869//1869 -f 1869//1869 1986//1986 1988//1988 -f 1869//1869 1988//1988 1868//1868 -f 1868//1868 1988//1988 1990//1990 -f 1868//1868 1990//1990 1867//1867 -f 1867//1867 1990//1990 1998//1998 -f 1867//1867 1998//1998 1866//1866 -f 1949//1949 2071//2071 1950//1950 -f 1950//1950 2071//2071 2070//2070 -f 1950//1950 2070//2070 1881//1881 -f 1881//1881 2070//2070 2069//2069 -f 1881//1881 2069//2069 1860//1860 -f 1860//1860 2069//2069 1982//1982 -f 1894//1894 1968//1968 1951//1951 -f 1951//1951 1968//1968 2072//2072 -f 1951//1951 2072//2072 1952//1952 -f 1952//1952 2072//2072 2073//2073 -f 1952//1952 2073//2073 1948//1948 -f 1948//1948 2073//2073 2074//2074 -f 1882//1882 1974//1974 1975//1975 -f 1882//1882 1975//1975 1887//1887 -f 1887//1887 1975//1975 1976//1976 -f 1887//1887 1976//1976 1888//1888 -f 1888//1888 1976//1976 1977//1977 -f 1888//1888 1977//1977 1890//1890 -f 1890//1890 1977//1977 1969//1969 -f 1890//1890 1969//1969 1892//1892 -f 2014//2014 2016//2016 1932//1932 -f 1932//1932 2016//2016 1934//1934 -f 2065//2065 2061//2061 1960//1960 -f 1960//1960 2061//2061 1966//1966 -f 2051//2051 2049//2049 1926//1926 -f 1926//1926 2049//2049 1905//1905 -f 1914//1914 2021//2021 2024//2024 -f 1914//1914 2024//2024 1927//1927 -f 1927//1927 2024//2024 2023//2023 -f 1927//1927 2023//2023 1928//1928 -f 1928//1928 2023//2023 2022//2022 -f 1928//1928 2022//2022 1930//1930 -f 1930//1930 2022//2022 2014//2014 -f 1930//1930 2014//2014 1932//1932 -f 1934//1934 2016//2016 1958//1958 -f 1958//1958 2016//2016 2062//2062 -f 1958//1958 2062//2062 1959//1959 -f 1959//1959 2062//2062 2066//2066 -f 1959//1959 2066//2066 1960//1960 -f 1960//1960 2066//2066 2065//2065 -f 1966//1966 2061//2061 1965//1965 -f 1965//1965 2061//2061 2060//2060 -f 1965//1965 2060//2060 1939//1939 -f 1939//1939 2060//2060 2059//2059 -f 1939//1939 2059//2059 1926//1926 -f 1926//1926 2059//2059 2051//2051 -f 1905//1905 2049//2049 2047//2047 -f 1905//1905 2047//2047 1906//1906 -f 1906//1906 2047//2047 2045//2045 -f 1906//1906 2045//2045 1908//1908 -f 1908//1908 2045//2045 2044//2044 -f 1908//1908 2044//2044 1909//1909 -f 1909//1909 2044//2044 2028//2028 -f 1909//1909 2028//2028 1904//1904 -f 1923//1923 1922//1922 2027//2027 -f 2027//2027 1922//1922 2040//2040 -f 1921//1921 2042//2042 1922//1922 -f 1922//1922 2042//2042 2040//2040 -f 1921//1921 1910//1910 2042//2042 -f 2042//2042 1910//1910 2043//2043 -f 1963//1963 2067//2067 1912//1912 -f 1912//1912 2067//2067 2057//2057 -f 1912//1912 2057//2057 1910//1910 -f 1910//1910 2057//2057 2043//2043 -f 1963//1963 1962//1962 2067//2067 -f 2067//2067 1962//1962 2068//2068 -f 1947//1947 2055//2055 1961//1961 -f 1961//1961 2055//2055 2054//2054 -f 1961//1961 2054//2054 1962//1962 -f 1962//1962 2054//2054 2068//2068 -f 1947//1947 1946//1946 2055//2055 -f 2055//2055 1946//1946 1999//1999 -f 1944//1944 2000//2000 1946//1946 -f 1946//1946 2000//2000 1999//1999 -f 2002//2002 2000//2000 1878//1878 -f 1878//1878 2000//2000 1944//1944 -f 2002//2002 1878//1878 1876//1876 -f 2002//2002 1876//1876 2018//2018 -f 2018//2018 1876//1876 1875//1875 -f 2018//2018 1875//1875 2017//2017 -f 2017//2017 1875//1875 1877//1877 -f 2017//2017 1877//1877 1991//1991 -f 1923//1923 2027//2027 2026//2026 -f 1923//1923 2026//2026 1942//1942 -f 1942//1942 2026//2026 2025//2025 -f 1942//1942 2025//2025 1941//1941 -f 1941//1941 2025//2025 1855//1855 -f 1941//1941 1855//1855 1857//1857 -# 4296 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_motori.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_motori.obj deleted file mode 100644 index a5858563d..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_motori.obj +++ /dev/null @@ -1,75548 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object robot_motori.obj -# -# Vertices: 18574 -# Faces: 38384 -# -#### -vn -0.577350 0.577350 0.577350 -v -0.011250 -0.092500 0.145450 -vn -0.577350 0.577350 -0.577350 -v -0.011250 -0.092500 0.133950 -vn -0.904534 0.301511 0.301511 -v -0.011250 -0.094000 0.145450 -vn -0.904534 0.301511 -0.301511 -v -0.011250 -0.094000 0.133950 -vn -0.678875 0.727973 -0.095839 -v -0.011250 -0.094000 0.127700 -vn -0.770262 -0.637727 0.000002 -v -0.011250 -0.095500 0.129300 -vn -0.770265 0.552286 -0.318861 -v -0.011250 -0.097366 0.129800 -vn -0.770262 0.000002 0.637728 -v -0.011250 -0.138500 0.129450 -vn -0.770261 0.318862 -0.552290 -v -0.011250 -0.097000 0.130166 -vn -0.770268 -0.318868 0.552278 -v -0.011250 -0.138000 0.129584 -vn -0.770261 0.000000 -0.637728 -v -0.011250 -0.096500 0.130300 -vn -0.770263 0.000002 -0.637727 -v -0.011250 -0.138500 0.149950 -vn -0.770260 0.637730 0.000002 -v -0.011250 -0.097500 0.150100 -vn -0.770264 -0.318864 -0.552286 -v -0.011250 -0.138000 0.149816 -vn -0.770262 -0.552288 -0.318864 -v -0.011250 -0.137634 0.149450 -vn -0.770263 -0.552286 -0.318865 -v -0.011250 -0.095634 0.129800 -vn -0.770260 -0.318864 -0.552291 -v -0.011250 -0.096000 0.130166 -vn -0.770264 -0.637726 0.000002 -v -0.011250 -0.137500 0.148950 -vn -0.770261 0.552292 0.318859 -v -0.011250 -0.097366 0.149600 -vn -0.770266 0.318857 0.552286 -v -0.011250 -0.097000 0.149234 -vn -0.678874 0.727973 0.095842 -v -0.011250 -0.094000 0.151700 -vn -0.770263 -0.552286 -0.318865 -v -0.011250 -0.095634 0.150600 -vn -0.653228 0.655721 0.378579 -v -0.011250 -0.094134 0.152200 -vn -0.770260 -0.318864 -0.552291 -v -0.011250 -0.096000 0.150966 -vn -0.653226 0.378586 0.655720 -v -0.011250 -0.094500 0.152566 -vn -0.678874 0.095840 0.727973 -v -0.011250 -0.095000 0.152700 -vn -0.770262 0.000000 -0.637727 -v -0.011250 -0.096500 0.151100 -vn -0.770260 0.318863 -0.552292 -v -0.011250 -0.097000 0.150966 -vn -0.689865 -0.056801 0.721707 -v -0.011250 -0.136000 0.152700 -vn -0.770265 0.552286 -0.318861 -v -0.011250 -0.097366 0.150600 -vn -0.673533 -0.597992 0.434464 -v -0.011250 -0.140045 0.150639 -vn -0.770265 0.552283 -0.318868 -v -0.011250 -0.139366 0.149450 -vn -0.673534 -0.702980 0.228411 -v -0.011250 -0.140755 0.149245 -vn -0.770263 0.637727 0.000002 -v -0.011250 -0.139500 0.148950 -vn -0.689866 -0.721705 0.056800 -v -0.011250 -0.141000 0.147700 -vn -0.770261 0.552288 0.318866 -v -0.011250 -0.139366 0.148450 -vn -0.689866 -0.721705 -0.056800 -v -0.011250 -0.141000 0.131700 -vn -0.770261 0.318866 0.552288 -v -0.011250 -0.139000 0.148084 -vn -0.673533 -0.434466 0.597990 -v -0.011250 -0.138939 0.151745 -vn -0.770258 0.318862 -0.552294 -v -0.011250 -0.139000 0.149816 -vn -0.673534 -0.228413 0.702979 -v -0.011250 -0.137545 0.152455 -vn -0.653228 0.378578 -0.655722 -v -0.011250 -0.094500 0.126834 -vn -0.678874 0.095840 -0.727973 -v -0.011250 -0.095000 0.126700 -vn -0.653226 0.655721 -0.378585 -v -0.011250 -0.094134 0.127200 -vn -0.770263 -0.318867 0.552285 -v -0.011250 -0.096000 0.128434 -vn -0.770260 -0.552292 0.318863 -v -0.011250 -0.095634 0.128800 -vn -0.770258 -0.552294 0.318862 -v -0.011250 -0.137634 0.129950 -vn -0.770263 -0.637727 0.000002 -v -0.011250 -0.137500 0.130450 -vn -0.770262 -0.552288 -0.318864 -v -0.011250 -0.137634 0.130950 -vn -0.770265 -0.318868 0.552282 -v -0.011250 -0.138000 0.148084 -vn -0.770262 -0.318864 -0.552288 -v -0.011250 -0.138000 0.131316 -vn -0.770262 0.000002 0.637727 -v -0.011250 -0.138500 0.147950 -vn -0.770263 0.000002 -0.637727 -v -0.011250 -0.138500 0.131450 -vn -0.770258 0.318862 -0.552294 -v -0.011250 -0.139000 0.131316 -vn -0.770265 0.552283 -0.318868 -v -0.011250 -0.139366 0.130950 -vn -0.673534 -0.702980 -0.228411 -v -0.011250 -0.140755 0.130155 -vn -0.770263 0.637727 0.000002 -v -0.011250 -0.139500 0.130450 -vn -0.673533 -0.597992 -0.434464 -v -0.011250 -0.140045 0.128761 -vn -0.770255 -0.000000 0.637736 -v -0.011250 -0.096500 0.149100 -vn -0.770258 -0.552294 0.318862 -v -0.011250 -0.137634 0.148450 -vn -0.770266 -0.318858 0.552286 -v -0.011250 -0.096000 0.149234 -vn -0.770260 -0.552291 0.318864 -v -0.011250 -0.095634 0.149600 -vn -0.770262 -0.637727 0.000002 -v -0.011250 -0.095500 0.150100 -vn -0.770259 0.637731 0.000002 -v -0.011250 -0.097500 0.129300 -vn -0.770261 0.552292 0.318859 -v -0.011250 -0.097366 0.128800 -vn -0.689866 -0.056801 -0.721706 -v -0.011250 -0.136000 0.126700 -vn -0.770263 0.318867 0.552286 -v -0.011250 -0.097000 0.128434 -vn -0.770262 0.000000 0.637727 -v -0.011250 -0.096500 0.128300 -vn -0.770261 0.552288 0.318866 -v -0.011250 -0.139366 0.129950 -vn -0.770261 0.318866 0.552288 -v -0.011250 -0.139000 0.129584 -vn -0.673532 -0.434464 -0.597993 -v -0.011250 -0.138939 0.127655 -vn -0.673535 -0.228410 -0.702979 -v -0.011250 -0.137545 0.126945 -vn 0.904534 0.301511 0.301511 -v 0.010750 -0.094000 0.145450 -vn 0.678874 0.727973 0.095842 -v 0.010750 -0.094000 0.151700 -vn 0.770263 -0.637727 0.000002 -v 0.010750 -0.095500 0.150100 -vn 0.577350 0.577350 -0.577350 -v 0.010750 -0.092500 0.133950 -vn 0.577350 0.577350 0.577350 -v 0.010750 -0.092500 0.145450 -vn 0.904534 0.301512 -0.301511 -v 0.010750 -0.094000 0.133950 -vn 0.770263 -0.000000 -0.637727 -v 0.010750 -0.096500 0.151100 -vn 0.770260 -0.318862 -0.552291 -v 0.010750 -0.096000 0.150966 -vn 0.678874 0.095841 0.727973 -v 0.010750 -0.095000 0.152700 -vn 0.770263 -0.318866 0.552285 -v 0.010750 -0.096000 0.128434 -vn 0.770263 -0.000000 0.637727 -v 0.010750 -0.096500 0.128300 -vn 0.678874 0.095840 -0.727973 -v 0.010750 -0.095000 0.126700 -vn 0.770263 0.318867 0.552285 -v 0.010750 -0.097000 0.128434 -vn -0.003385 -0.076048 -0.997098 -v 0.010750 -0.136000 0.126700 -vn 0.770262 0.552292 0.318859 -v 0.010750 -0.097366 0.128800 -vn 0.770260 0.637730 0.000002 -v 0.010750 -0.097500 0.129300 -vn 0.770260 0.637730 0.000002 -v 0.010750 -0.097500 0.150100 -vn 0.770262 -0.552289 -0.318864 -v 0.010750 -0.137634 0.149450 -vn 0.770263 -0.637727 0.000002 -v 0.010750 -0.137500 0.148950 -vn 0.770267 -0.318856 0.552286 -v 0.010750 -0.096000 0.149234 -vn 0.770255 0.000000 0.637735 -v 0.010750 -0.096500 0.149100 -vn 0.770261 -0.318862 -0.552291 -v 0.010750 -0.096000 0.130166 -vn 0.770263 -0.552285 -0.318866 -v 0.010750 -0.095634 0.129800 -vn 0.653226 0.378586 0.655720 -v 0.010750 -0.094500 0.152566 -vn 0.653228 0.655721 0.378579 -v 0.010750 -0.094134 0.152200 -vn 0.770263 -0.552285 -0.318866 -v 0.010750 -0.095634 0.150600 -vn 0.770258 -0.552294 0.318862 -v 0.010750 -0.137634 0.148450 -vn 0.770264 -0.318867 0.552283 -v 0.010750 -0.138000 0.148084 -vn 0.770262 -0.552288 -0.318864 -v 0.010750 -0.137634 0.130950 -vn 0.770262 -0.637727 0.000002 -v 0.010750 -0.137500 0.130450 -vn 0.770258 -0.552294 0.318862 -v 0.010750 -0.137634 0.129950 -vn 0.678874 0.727973 -0.095839 -v 0.010750 -0.094000 0.127700 -vn 0.770263 -0.637727 0.000002 -v 0.010750 -0.095500 0.129300 -vn 0.770260 -0.552291 0.318865 -v 0.010750 -0.095634 0.128800 -vn 0.653226 0.655721 -0.378585 -v 0.010750 -0.094134 0.127200 -vn 0.653228 0.378578 -0.655722 -v 0.010750 -0.094500 0.126834 -vn -0.006827 -0.808999 -0.587770 -v 0.010750 -0.140045 0.128761 -vn -0.006826 -0.587768 -0.809000 -v 0.010750 -0.138939 0.127655 -vn 0.770263 0.000003 0.637727 -v 0.010750 -0.138500 0.129450 -vn -0.006827 -0.309008 -0.951035 -v 0.010750 -0.137545 0.126945 -vn 0.770263 -0.318867 0.552286 -v 0.010750 -0.138000 0.129584 -vn -0.003384 -0.997099 -0.076047 -v 0.010750 -0.141000 0.131700 -vn 0.770261 0.318866 0.552288 -v 0.010750 -0.139000 0.148084 -vn -0.003384 -0.997099 0.076047 -v 0.010750 -0.141000 0.147700 -vn 0.770261 0.552288 0.318866 -v 0.010750 -0.139366 0.148450 -vn -0.006828 -0.951035 0.309009 -v 0.010750 -0.140755 0.149245 -vn 0.770262 0.637727 0.000002 -v 0.010750 -0.139500 0.148950 -vn -0.006827 -0.808999 0.587770 -v 0.010750 -0.140045 0.150639 -vn 0.770260 -0.552291 0.318864 -v 0.010750 -0.095634 0.149600 -vn 0.770263 0.000000 -0.637727 -v 0.010750 -0.096500 0.130300 -vn 0.770260 0.318863 -0.552291 -v 0.010750 -0.097000 0.130166 -vn 0.770265 0.318858 0.552287 -v 0.010750 -0.097000 0.149234 -vn 0.770265 0.552286 -0.318861 -v 0.010750 -0.097366 0.129800 -vn 0.770261 0.552292 0.318860 -v 0.010750 -0.097366 0.149600 -vn 0.770260 0.318863 -0.552291 -v 0.010750 -0.097000 0.150966 -vn -0.003385 -0.076048 0.997098 -v 0.010750 -0.136000 0.152700 -vn 0.770265 0.552286 -0.318861 -v 0.010750 -0.097366 0.150600 -vn 0.770263 0.000003 -0.637727 -v 0.010750 -0.138500 0.149950 -vn 0.770260 -0.318863 -0.552292 -v 0.010750 -0.138000 0.149816 -vn 0.770265 0.552283 -0.318868 -v 0.010750 -0.139366 0.149450 -vn 0.770258 0.318862 -0.552294 -v 0.010750 -0.139000 0.149816 -vn -0.006827 -0.587771 0.808998 -v 0.010750 -0.138939 0.151745 -vn -0.006826 -0.309012 0.951034 -v 0.010750 -0.137545 0.152455 -vn 0.770261 0.318866 0.552288 -v 0.010750 -0.139000 0.129584 -vn 0.770261 0.552288 0.318866 -v 0.010750 -0.139366 0.129950 -vn -0.006827 -0.951035 -0.309009 -v 0.010750 -0.140755 0.130155 -vn 0.770262 0.637727 0.000002 -v 0.010750 -0.139500 0.130450 -vn 0.770265 0.552283 -0.318868 -v 0.010750 -0.139366 0.130950 -vn 0.770259 0.318862 -0.552294 -v 0.010750 -0.139000 0.131316 -vn 0.770263 0.000003 0.637727 -v 0.010750 -0.138500 0.147950 -vn 0.770263 0.000003 -0.637727 -v 0.010750 -0.138500 0.131450 -vn 0.770262 -0.318863 -0.552289 -v 0.010750 -0.138000 0.131316 -vn -1.000000 0.000000 0.000000 -v -0.016250 -0.092125 0.128950 -vn -0.923880 0.382683 0.000000 -v -0.016250 -0.092000 0.128950 -vn -0.717284 0.297108 -0.630263 -v -0.016250 -0.092000 0.128450 -vn -0.995906 -0.003465 -0.090328 -v -0.016250 -0.136000 0.128200 -vn -0.913025 -0.400396 -0.077894 -v -0.016250 -0.136522 0.128239 -vn -0.913686 -0.406422 0.000000 -v -0.016250 -0.136522 0.128950 -vn -0.774230 0.173282 -0.608722 -v -0.016250 -0.098472 0.129700 -vn -0.487327 0.619596 -0.615316 -v -0.016250 -0.098398 0.129746 -vn -0.940157 0.336739 0.052067 -v -0.016250 -0.098436 0.129070 -vn -0.770264 -0.637725 0.000000 -v -0.016250 -0.097500 0.153200 -vn -0.770262 -0.552286 -0.318869 -v -0.016250 -0.097667 0.153825 -vn -1.000000 0.000000 0.000000 -v -0.016250 -0.096125 0.154575 -vn -0.707107 -0.707107 0.000000 -v -0.016250 -0.102000 0.154575 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.099833 0.153825 -vn -0.973781 -0.131340 0.185743 -v -0.016250 -0.102000 0.152700 -vn -0.770261 0.637728 0.000000 -v -0.016250 -0.100000 0.153200 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.099833 0.152575 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.099375 0.152117 -vn -0.539748 0.229382 0.809973 -v -0.016250 -0.098409 0.149700 -vn -0.770258 0.000000 0.637732 -v -0.016250 -0.098750 0.151950 -vn -0.770260 -0.318865 -0.552291 -v -0.016250 -0.098125 0.154283 -vn -0.770264 -0.000000 -0.637725 -v -0.016250 -0.098750 0.154450 -vn -0.770260 0.318865 -0.552291 -v -0.016250 -0.099375 0.154283 -vn -0.942584 -0.085437 -0.322855 -v -0.016250 -0.096109 0.152010 -vn -0.934101 0.003453 -0.356991 -v -0.016250 -0.096393 0.152047 -vn -0.770260 -0.552291 0.318865 -v -0.016250 -0.097667 0.152575 -vn -0.940629 0.147418 -0.305754 -v -0.016250 -0.097371 0.151845 -vn -0.770265 -0.318861 0.552287 -v -0.016250 -0.098125 0.152117 -vn -0.940310 0.279987 -0.193454 -v -0.016250 -0.098120 0.151185 -vn -0.939229 0.340984 -0.039744 -v -0.016250 -0.098445 0.150242 -vn -0.707107 0.707107 0.000000 -v -0.016250 -0.095500 0.154575 -vn -0.973781 0.131340 0.185743 -v -0.016250 -0.095500 0.152700 -vn -0.939245 -0.197236 -0.280921 -v -0.016250 -0.095443 0.151739 -vn -0.816496 0.408249 0.408249 -v -0.016250 -0.094000 0.152700 -vn -0.941720 -0.299945 -0.152302 -v -0.016250 -0.094771 0.151001 -vn -0.973781 0.185743 0.131340 -v -0.016250 -0.094000 0.150950 -vn -0.770262 -0.637728 -0.000000 -v -0.016250 -0.092250 0.147700 -vn -0.770258 -0.552294 -0.318864 -v -0.016250 -0.092417 0.148325 -vn -0.707107 -0.000000 0.707106 -v -0.016250 -0.092125 0.150950 -vn -0.770266 -0.318862 -0.552284 -v -0.016250 -0.092875 0.148783 -vn -0.770258 0.000001 -0.637733 -v -0.016250 -0.093500 0.148950 -vn -0.770265 0.318862 -0.552284 -v -0.016250 -0.094125 0.148783 -vn -0.770259 0.552293 -0.318864 -v -0.016250 -0.094583 0.148325 -vn -0.770264 0.637725 -0.000000 -v -0.016250 -0.094750 0.147700 -vn -0.945218 -0.156016 0.286744 -v -0.016250 -0.095568 0.148387 -vn -0.939543 -0.015344 0.342087 -v -0.016250 -0.096538 0.148150 -vn -0.770261 0.552288 0.318867 -v -0.016250 -0.094583 0.147075 -vn -0.770261 0.318867 0.552288 -v -0.016250 -0.094125 0.146617 -vn -0.973781 0.185743 -0.131340 -v -0.016250 -0.094000 0.144450 -vn -0.770264 0.000001 0.637725 -v -0.016250 -0.093500 0.146450 -vn -0.707107 -0.000000 -0.707107 -v -0.016250 -0.092125 0.144450 -vn -0.770261 -0.318866 0.552288 -v -0.016250 -0.092875 0.146617 -vn -0.770261 -0.552288 0.318867 -v -0.016250 -0.092417 0.147075 -vn -0.943022 -0.280565 0.178867 -v -0.016250 -0.094843 0.149073 -vn -0.942134 -0.334870 0.015656 -v -0.016250 -0.094551 0.150028 -vn -0.525314 0.818472 0.232701 -v -0.016250 -0.097000 0.148215 -vn -0.707107 0.707107 0.000000 -v -0.016250 -0.097000 0.139700 -vn -1.000000 0.000000 0.000000 -v -0.016250 -0.096125 0.139700 -vn -0.766703 0.622391 -0.157466 -v -0.016250 -0.097000 0.131274 -vn -0.938469 -0.035310 -0.343553 -v -0.016250 -0.096385 0.131247 -vn -0.465176 0.661095 -0.588698 -v -0.016250 -0.097057 0.131169 -vn -0.923879 0.382684 0.000000 -v -0.016250 -0.094000 0.139700 -vn -0.973781 0.185743 0.131340 -v -0.016250 -0.094000 0.134950 -vn -0.770264 0.000001 0.637726 -v -0.016250 -0.093500 0.130450 -vn -0.770261 -0.318866 0.552288 -v -0.016250 -0.092875 0.130617 -vn -0.770261 -0.552288 0.318867 -v -0.016250 -0.092417 0.131075 -vn -0.770258 0.000001 -0.637732 -v -0.016250 -0.093500 0.132950 -vn -0.770266 -0.318861 -0.552284 -v -0.016250 -0.092875 0.132783 -vn -0.707107 0.000000 0.707107 -v -0.016250 -0.092125 0.134950 -vn -0.770259 -0.552293 -0.318864 -v -0.016250 -0.092417 0.132325 -vn -0.770264 -0.637725 0.000000 -v -0.016250 -0.092250 0.131700 -vn -0.717284 0.630263 -0.297108 -v -0.016250 -0.095500 0.124700 -vn -0.923880 -0.000000 -0.382683 -v -0.016250 -0.096125 0.124700 -vn -0.973781 0.131340 -0.185743 -v -0.016250 -0.095500 0.126700 -vn -0.949432 -0.094214 0.299504 -v -0.016250 -0.096110 0.127389 -vn -0.816496 0.408249 -0.408249 -v -0.016250 -0.094000 0.126700 -vn -0.942337 -0.183411 0.279931 -v -0.016250 -0.095459 0.127651 -vn -0.940882 -0.289295 0.176209 -v -0.016250 -0.094792 0.128358 -vn -0.973781 0.185743 -0.131340 -v -0.016250 -0.094000 0.128450 -vn -0.945657 -0.316743 0.073529 -v -0.016250 -0.094584 0.128936 -vn -0.707107 0.000000 -0.707107 -v -0.016250 -0.092125 0.128450 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.099833 0.125575 -vn -0.717284 -0.630262 -0.297108 -v -0.016250 -0.102000 0.124700 -vn -0.770261 0.637729 -0.000000 -v -0.016250 -0.100000 0.126200 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 -0.102000 0.126700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.099833 0.126825 -vn -0.770260 0.318865 -0.552291 -v -0.016250 -0.099375 0.127283 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.099375 0.125117 -vn -0.770258 -0.000000 0.637732 -v -0.016250 -0.098750 0.124950 -vn -0.770264 0.000000 -0.637725 -v -0.016250 -0.098750 0.127450 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 -0.098125 0.127283 -vn -0.940955 0.270862 0.203071 -v -0.016250 -0.098085 0.128163 -vn -0.770262 -0.552286 -0.318869 -v -0.016250 -0.097667 0.126825 -vn -0.770265 -0.318861 0.552286 -v -0.016250 -0.098125 0.125117 -vn -0.770260 -0.552291 0.318865 -v -0.016250 -0.097667 0.125575 -vn -0.770264 -0.637725 -0.000000 -v -0.016250 -0.097500 0.126200 -vn -0.934277 0.003696 0.356529 -v -0.016250 -0.096385 0.127353 -vn -0.941338 0.139683 0.307200 -v -0.016250 -0.097339 0.127540 -vn -0.707107 -0.000000 -0.707107 -v -0.016250 -0.102750 0.129700 -vn -1.000000 -0.000000 0.000000 -v -0.016250 -0.102750 0.128950 -vn -0.707107 -0.000000 -0.707107 -v -0.016250 -0.110750 0.129700 -vn -1.000000 -0.000000 -0.000000 -v -0.016250 -0.110750 0.128950 -vn -0.707107 0.000000 -0.707107 -v -0.016250 -0.118750 0.129700 -vn -1.000000 0.000000 0.000000 -v -0.016250 -0.118750 0.128950 -vn -0.534582 -0.237790 -0.810974 -v -0.016250 -0.136522 0.129700 -vn -0.997107 -0.040621 -0.064243 -v -0.016250 -0.127500 0.128200 -vn -0.973781 0.131340 -0.185743 -v -0.016250 -0.119500 0.126700 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 -0.121667 0.126825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 -0.122125 0.127283 -vn -0.770264 0.000000 -0.637725 -v -0.016250 -0.122750 0.127450 -vn -0.717283 -0.630262 -0.297109 -v -0.016250 -0.127500 0.126700 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 -0.126000 0.126700 -vn -0.770260 0.318865 -0.552291 -v -0.016250 -0.123375 0.127283 -vn -0.717284 0.630262 -0.297108 -v -0.016250 -0.119500 0.124700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 -0.121667 0.125575 -vn -0.770261 -0.637728 -0.000000 -v -0.016250 -0.121500 0.126200 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.123833 0.126825 -vn -0.770261 0.637728 0.000000 -v -0.016250 -0.124000 0.126200 -vn -0.717284 -0.630262 -0.297108 -v -0.016250 -0.126000 0.124700 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.123833 0.125575 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.123375 0.125117 -vn -0.770258 0.000000 0.637732 -v -0.016250 -0.122750 0.124950 -vn -0.770265 -0.318861 0.552286 -v -0.016250 -0.122125 0.125117 -vn -0.973781 0.131340 -0.185743 -v -0.016250 -0.111500 0.126700 -vn -0.717284 0.630263 -0.297108 -v -0.016250 -0.111500 0.124700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 -0.113667 0.125575 -vn -0.770261 -0.637728 -0.000000 -v -0.016250 -0.113500 0.126200 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 -0.113667 0.126825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 -0.114125 0.127283 -vn -0.770264 -0.000000 -0.637725 -v -0.016250 -0.114750 0.127450 -vn -0.770260 0.318866 -0.552291 -v -0.016250 -0.115375 0.127283 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 -0.118000 0.126700 -vn -0.923879 0.000000 -0.382684 -v -0.016250 -0.118750 0.126700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.115833 0.126825 -vn -0.770261 0.637728 0.000000 -v -0.016250 -0.116000 0.126200 -vn -0.717284 -0.630263 -0.297108 -v -0.016250 -0.118000 0.124700 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.115833 0.125575 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.115375 0.125117 -vn -0.770258 0.000000 0.637732 -v -0.016250 -0.114750 0.124950 -vn -0.770265 -0.318861 0.552286 -v -0.016250 -0.114125 0.125117 -vn -0.973781 0.131340 -0.185743 -v -0.016250 -0.103500 0.126700 -vn -0.717284 0.630263 -0.297108 -v -0.016250 -0.103500 0.124700 -vn -0.770259 -0.552293 0.318864 -v -0.016250 -0.105667 0.125575 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.107833 0.125575 -vn -0.717284 -0.630263 -0.297108 -v -0.016250 -0.110000 0.124700 -vn -0.770261 0.637728 0.000000 -v -0.016250 -0.108000 0.126200 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 -0.110000 0.126700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.107833 0.126825 -vn -0.770259 0.318866 -0.552292 -v -0.016250 -0.107375 0.127283 -vn -0.923879 0.000000 -0.382684 -v -0.016250 -0.102750 0.126700 -vn -0.770264 -0.637725 -0.000000 -v -0.016250 -0.105500 0.126200 -vn -0.770261 -0.552288 -0.318867 -v -0.016250 -0.105667 0.126825 -vn -0.770262 -0.318867 -0.552286 -v -0.016250 -0.106125 0.127283 -vn -0.770262 0.000001 -0.637727 -v -0.016250 -0.106750 0.127450 -vn -0.923879 0.000000 -0.382684 -v -0.016250 -0.110750 0.126700 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.107375 0.125117 -vn -0.770257 0.000001 0.637734 -v -0.016250 -0.106750 0.124950 -vn -0.770268 -0.318863 0.552281 -v -0.016250 -0.106125 0.125117 -vn -0.770266 0.318862 -0.552284 -v -0.016250 -0.094125 0.132783 -vn -0.770259 0.552293 -0.318864 -v -0.016250 -0.094583 0.132325 -vn -0.770264 0.637725 0.000000 -v -0.016250 -0.094750 0.131700 -vn -0.942081 -0.183376 -0.280815 -v -0.016250 -0.095459 0.130949 -vn -0.770261 0.552288 0.318867 -v -0.016250 -0.094583 0.131075 -vn -0.944677 -0.287243 -0.158357 -v -0.016250 -0.094792 0.130241 -vn -0.770261 0.318867 0.552288 -v -0.016250 -0.094125 0.130617 -vn -0.938161 -0.345266 -0.025409 -v -0.016250 -0.094550 0.129300 -vn -0.717284 0.297108 0.630263 -v -0.016250 -0.092000 0.134950 -vn -0.717284 0.297108 0.630262 -v -0.016250 -0.092000 0.150950 -vn -0.717284 0.297108 -0.630262 -v -0.016250 -0.092000 0.144450 -vn -0.717284 0.630263 0.297108 -v -0.016250 -0.095500 0.154700 -vn -0.923880 -0.000000 0.382683 -v -0.016250 -0.096125 0.154700 -vn -0.717284 -0.630262 0.297108 -v -0.016250 -0.102000 0.154700 -vn -0.770259 -0.552293 0.318864 -v -0.016250 -0.105667 0.152575 -vn -0.770264 -0.637725 0.000000 -v -0.016250 -0.105500 0.153200 -vn -0.707107 -0.000000 0.707107 -v -0.016250 -0.102750 0.149700 -vn -0.707106 0.707107 0.000000 -v -0.016250 -0.103500 0.154575 -vn -0.770263 -0.318867 -0.552285 -v -0.016250 -0.106125 0.154283 -vn -0.770261 0.000001 -0.637728 -v -0.016250 -0.106750 0.154450 -vn -0.973781 -0.131340 0.185743 -v -0.016250 -0.110000 0.152700 -vn -0.707107 -0.707107 -0.000000 -v -0.016250 -0.110000 0.154575 -vn -0.770260 0.318865 -0.552291 -v -0.016250 -0.107375 0.154283 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.107833 0.152575 -vn -0.707107 -0.000000 0.707107 -v -0.016250 -0.110750 0.149700 -vn -0.770261 0.637728 0.000000 -v -0.016250 -0.108000 0.153200 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.107833 0.153825 -vn -0.923879 0.000000 0.382684 -v -0.016250 -0.102750 0.152700 -vn -0.973781 0.131340 0.185743 -v -0.016250 -0.103500 0.152700 -vn -0.770261 -0.552288 -0.318867 -v -0.016250 -0.105667 0.153825 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.107375 0.152117 -vn -0.770258 0.000000 0.637733 -v -0.016250 -0.106750 0.151950 -vn -0.770267 -0.318863 0.552283 -v -0.016250 -0.106125 0.152117 -vn -0.717283 -0.630263 0.297108 -v -0.016250 -0.110000 0.154700 -vn -0.717284 0.630262 0.297108 -v -0.016250 -0.103500 0.154700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 -0.113667 0.152575 -vn -0.770261 -0.637728 -0.000000 -v -0.016250 -0.113500 0.153200 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 -0.113667 0.153825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 -0.114125 0.154283 -vn -0.707106 0.707107 0.000000 -v -0.016250 -0.111500 0.154575 -vn -0.770264 0.000000 -0.637725 -v -0.016250 -0.114750 0.154450 -vn -0.973781 -0.131340 0.185743 -v -0.016250 -0.118000 0.152700 -vn -0.707107 -0.707107 0.000000 -v -0.016250 -0.118000 0.154575 -vn -0.770260 0.318866 -0.552291 -v -0.016250 -0.115375 0.154283 -vn -0.973781 0.131340 0.185743 -v -0.016250 -0.111500 0.152700 -vn -0.923879 0.000000 0.382684 -v -0.016250 -0.110750 0.152700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.115833 0.153825 -vn -0.770261 0.637728 0.000000 -v -0.016250 -0.116000 0.153200 -vn -0.707107 0.000000 0.707107 -v -0.016250 -0.118750 0.149700 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.115833 0.152575 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.115375 0.152117 -vn -0.770258 0.000000 0.637732 -v -0.016250 -0.114750 0.151950 -vn -0.770265 -0.318861 0.552286 -v -0.016250 -0.114125 0.152117 -vn -0.717283 -0.630263 0.297108 -v -0.016250 -0.118000 0.154700 -vn -0.717284 0.630262 0.297108 -v -0.016250 -0.111500 0.154700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 -0.121667 0.152575 -vn -0.770261 -0.637728 0.000000 -v -0.016250 -0.121500 0.153200 -vn -0.997107 -0.040620 0.064242 -v -0.016250 -0.127500 0.151200 -vn -0.717283 -0.630262 0.297109 -v -0.016250 -0.127500 0.152700 -vn -0.973781 -0.131340 0.185743 -v -0.016250 -0.126000 0.152700 -vn -0.925077 -0.379320 0.018699 -v -0.016250 -0.136550 0.151156 -vn -0.996376 0.004468 0.084938 -v -0.016250 -0.136000 0.151200 -vn -0.549135 -0.227456 0.804186 -v -0.016250 -0.136550 0.149700 -vn -0.770260 0.318865 -0.552290 -v -0.016250 -0.123375 0.154283 -vn -0.770263 0.552286 -0.318865 -v -0.016250 -0.123833 0.153825 -vn -0.770261 0.637728 -0.000000 -v -0.016250 -0.124000 0.153200 -vn -0.770261 0.552291 0.318862 -v -0.016250 -0.123833 0.152575 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 -0.121667 0.153825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 -0.122125 0.154283 -vn -0.707106 0.707107 0.000000 -v -0.016250 -0.119500 0.154575 -vn -0.770264 0.000000 -0.637725 -v -0.016250 -0.122750 0.154450 -vn -0.707107 -0.707107 0.000000 -v -0.016250 -0.126000 0.154575 -vn -0.770265 0.318861 0.552286 -v -0.016250 -0.123375 0.152117 -vn -0.770258 -0.000000 0.637732 -v -0.016250 -0.122750 0.151950 -vn -0.770265 -0.318861 0.552286 -v -0.016250 -0.122125 0.152117 -vn -0.973781 0.131340 0.185743 -v -0.016250 -0.119500 0.152700 -vn -0.923879 0.000000 0.382684 -v -0.016250 -0.118750 0.152700 -vn -0.717283 -0.630263 0.297108 -v -0.016250 -0.126000 0.154700 -vn -0.717284 0.630263 0.297108 -v -0.016250 -0.119500 0.154700 -vn -0.511561 0.726534 0.458753 -v -0.016245 -0.098404 0.149700 -vn -0.328056 0.331545 0.884566 -v -0.019050 -0.098404 0.149700 -vn -0.297113 -0.717283 0.630261 -v -0.016300 -0.136750 0.149700 -vn -0.185744 -0.973781 0.131342 -v -0.016050 -0.136750 0.149700 -vn -0.717284 -0.297105 0.630263 -v -0.016500 -0.136550 0.149700 -vn -0.131340 -0.185742 0.973781 -v -0.016500 -0.120550 0.149700 -vn -0.341589 -0.341586 0.875577 -v -0.019050 -0.120550 0.149700 -vn -0.325839 0.886089 0.329658 -v -0.019050 -0.097000 0.148223 -vn -0.523659 0.485121 0.700314 -v -0.016243 -0.097000 0.148223 -vn -0.333461 0.921917 -0.197161 -v -0.019050 -0.097000 0.131274 -vn -0.939710 0.253757 -0.229245 -v -0.019250 -0.097916 0.130641 -vn -0.849416 0.276504 -0.449486 -v -0.019250 -0.098355 0.129900 -vn -0.875576 -0.341581 -0.341598 -v -0.019250 -0.120550 0.129900 -vn -0.932050 -0.319830 0.170271 -v -0.019250 -0.119404 0.134298 -vn -0.932220 -0.346282 0.105143 -v -0.019250 -0.118544 0.136373 -vn -0.938930 0.242887 0.243753 -v -0.019250 -0.097916 0.148759 -vn -0.932221 -0.360144 0.035503 -v -0.019250 -0.118105 0.138577 -vn -0.932221 -0.360143 -0.035503 -v -0.019250 -0.118105 0.140823 -vn -0.848127 0.296913 0.438774 -v -0.019250 -0.098355 0.149500 -vn -0.842676 0.453567 0.290128 -v -0.019250 -0.097200 0.148280 -vn -0.844519 0.463103 -0.268930 -v -0.019250 -0.097200 0.131120 -vn -0.904944 -0.408556 0.118990 -v -0.019250 -0.120550 0.132559 -vn -0.904816 -0.408621 -0.119739 -v -0.019250 -0.120550 0.146841 -vn -0.875581 -0.341583 0.341583 -v -0.019250 -0.120550 0.149500 -vn -0.931922 -0.320350 -0.169993 -v -0.019250 -0.119404 0.145102 -vn -0.932218 -0.346287 -0.105142 -v -0.019250 -0.118544 0.143027 -vn 0.690457 -0.721220 -0.055784 -v -0.011250 -0.141000 0.131700 -vn 0.689866 -0.721705 0.056800 -v -0.011250 -0.141000 0.147700 -vn -0.110051 -0.987815 0.110051 -v -0.014550 -0.141000 0.147000 -vn -0.375127 -0.924492 0.067783 -v -0.014550 -0.141000 0.147700 -vn -0.375938 -0.924209 -0.067148 -v -0.014550 -0.141000 0.131700 -vn -0.110051 -0.987815 -0.110051 -v -0.014550 -0.141000 0.132400 -vn -0.118633 -0.921349 -0.370194 -v -0.015000 -0.141000 0.132400 -vn -0.118633 -0.921348 0.370194 -v -0.015000 -0.141000 0.147000 -vn -0.804186 -0.549133 0.227458 -v -0.016500 -0.120750 0.149500 -vn -0.934292 -0.353779 0.044031 -v -0.016500 -0.136550 0.148950 -vn -0.735270 0.658079 -0.162202 -v -0.016500 -0.138336 0.141878 -vn -0.735271 0.677773 0.000000 -v -0.016500 -0.138600 0.139700 -vn -0.934292 -0.044031 0.353780 -v -0.016500 -0.138500 0.147000 -vn -0.777812 -0.602021 0.180497 -v -0.016500 -0.120750 0.132629 -vn -0.735271 -0.507320 0.449448 -v -0.016500 -0.122689 0.133666 -vn -0.685652 -0.644141 0.339063 -v -0.016500 -0.119550 0.134450 -vn -0.735271 -0.600138 0.314977 -v -0.016500 -0.121442 0.135471 -vn -0.685531 -0.697354 0.209153 -v -0.016500 -0.118724 0.136469 -vn -0.735270 -0.658079 0.162202 -v -0.016500 -0.120664 0.137522 -vn -0.685729 -0.724414 0.070714 -v -0.016500 -0.118303 0.138609 -vn -0.735271 -0.677773 -0.000000 -v -0.016500 -0.120400 0.139700 -vn -0.685922 -0.724270 -0.070315 -v -0.016500 -0.118303 0.140791 -vn -0.686109 -0.696940 -0.208637 -v -0.016500 -0.118724 0.142931 -vn -0.735270 0.658079 0.162202 -v -0.016500 -0.138336 0.137522 -vn -0.735271 0.600138 0.314977 -v -0.016500 -0.137558 0.135471 -vn -0.945442 -0.162896 -0.282143 -v -0.016500 -0.137525 0.132139 -vn -0.735271 0.507320 0.449448 -v -0.016500 -0.136311 0.133666 -vn -0.945442 -0.282143 -0.162894 -v -0.016500 -0.136811 0.131425 -vn -0.735271 0.385019 0.557797 -v -0.016500 -0.134669 0.132211 -vn -0.934292 -0.353778 -0.044033 -v -0.016500 -0.136550 0.130450 -vn -0.735270 0.240343 0.633729 -v -0.016500 -0.132727 0.131191 -vn -0.735271 0.081698 0.672831 -v -0.016500 -0.130597 0.130666 -vn -0.804191 -0.549123 -0.227466 -v -0.016500 -0.120750 0.129900 -vn -0.717284 -0.297105 -0.630264 -v -0.016500 -0.136550 0.129700 -vn -0.131333 -0.185735 -0.973783 -v -0.016500 -0.120550 0.129700 -vn -0.735271 -0.081698 0.672831 -v -0.016500 -0.128403 0.130666 -vn -0.735270 -0.240344 0.633729 -v -0.016500 -0.126273 0.131191 -vn -0.735270 -0.385019 0.557797 -v -0.016500 -0.124331 0.132211 -vn -0.934292 -0.044032 -0.353780 -v -0.016500 -0.138500 0.132400 -vn -0.921350 -0.118638 -0.370189 -v -0.016500 -0.139500 0.132400 -vn -0.921350 -0.118638 0.370189 -v -0.016500 -0.139500 0.147000 -vn -0.735270 0.081696 -0.672833 -v -0.016500 -0.130597 0.148734 -vn -0.735271 0.240341 -0.633729 -v -0.016500 -0.132727 0.148209 -vn -0.945444 -0.282135 0.162894 -v -0.016500 -0.136811 0.147975 -vn -0.735271 0.385020 -0.557795 -v -0.016500 -0.134669 0.147189 -vn -0.945447 -0.162886 0.282132 -v -0.016500 -0.137525 0.147261 -vn -0.735270 0.507322 -0.449447 -v -0.016500 -0.136311 0.145734 -vn -0.735271 0.600138 -0.314977 -v -0.016500 -0.137558 0.143929 -vn -0.735270 -0.658079 -0.162202 -v -0.016500 -0.120664 0.141878 -vn -0.778046 -0.601628 -0.180799 -v -0.016500 -0.120750 0.146771 -vn -0.686287 -0.643461 -0.339068 -v -0.016500 -0.119550 0.144950 -vn -0.735271 -0.600138 -0.314976 -v -0.016500 -0.121442 0.143929 -vn -0.735271 -0.507321 -0.449447 -v -0.016500 -0.122689 0.145734 -vn -0.735271 -0.385020 -0.557796 -v -0.016500 -0.124331 0.147189 -vn -0.735271 -0.240341 -0.633729 -v -0.016500 -0.126273 0.148209 -vn -0.735270 -0.081696 -0.672833 -v -0.016500 -0.128403 0.148734 -vn 0.674748 -0.702483 0.226345 -v -0.011250 -0.140755 0.149245 -vn -0.370453 -0.889761 0.266628 -v -0.014550 -0.140787 0.149144 -vn -0.375402 -0.802107 0.464432 -v -0.014550 -0.140166 0.150465 -vn 0.676755 -0.595995 0.432196 -v -0.011250 -0.140045 0.150639 -vn -0.392618 -0.711817 0.582381 -v -0.014550 -0.140045 0.150639 -vn -0.375025 -0.623805 0.685729 -v -0.014550 -0.139190 0.151550 -vn 0.677718 -0.432618 0.594593 -v -0.011250 -0.138939 0.151745 -vn -0.400471 -0.503030 0.765888 -v -0.014550 -0.138939 0.151745 -vn -0.374930 -0.390451 0.840818 -v -0.014550 -0.137943 0.152307 -vn 0.678575 -0.227468 0.698423 -v -0.011250 -0.137545 0.152455 -vn -0.397508 -0.258898 0.880317 -v -0.014550 -0.137545 0.152455 -vn -0.088068 -0.028561 0.995705 -v -0.014750 -0.136000 0.152700 -vn -0.081115 -0.426414 0.900884 -v -0.014750 -0.136573 0.152667 -vn -0.089207 -0.226910 0.969822 -v -0.014550 -0.136573 0.152667 -vn 0.692644 -0.052669 0.719354 -v -0.011250 -0.136000 0.152700 -vn 0.301511 0.301511 0.904534 -v -0.014250 -0.124750 0.155700 -vn 0.770260 0.318866 -0.552291 -v -0.014250 -0.123375 0.154283 -vn 0.770264 -0.000000 -0.637725 -v -0.014250 -0.122750 0.154450 -vn 0.609995 -0.000001 0.792405 -v -0.014250 -0.122750 0.150891 -vn 0.770258 0.000000 0.637732 -v -0.014250 -0.122750 0.151950 -vn 0.770265 0.318861 0.552286 -v -0.014250 -0.123375 0.152117 -vn 0.301511 -0.301511 0.904534 -v -0.014250 -0.120750 0.155700 -vn 0.770260 -0.318865 -0.552291 -v -0.014250 -0.122125 0.154283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 -0.121667 0.153825 -vn 0.609994 -0.686243 0.396204 -v -0.014250 -0.120750 0.152045 -vn 0.609994 0.686243 0.396205 -v -0.014250 -0.124750 0.152045 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.123833 0.152575 -vn 0.770261 0.637728 0.000000 -v -0.014250 -0.124000 0.153200 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.123833 0.153825 -vn 0.770261 -0.637729 -0.000000 -v -0.014250 -0.121500 0.153200 -vn 0.770261 -0.552291 0.318862 -v -0.014250 -0.121667 0.152575 -vn 0.770265 -0.318861 0.552286 -v -0.014250 -0.122125 0.152117 -vn 0.609994 -0.686243 0.396204 -v -0.014250 -0.112750 0.152045 -vn 0.770261 -0.552291 0.318862 -v -0.014250 -0.113667 0.152575 -vn 0.609995 -0.000001 0.792405 -v -0.014250 -0.114750 0.150891 -vn 0.770265 -0.318861 0.552286 -v -0.014250 -0.114125 0.152117 -vn 0.609994 0.686243 0.396205 -v -0.014250 -0.116750 0.152045 -vn 0.770261 0.637728 -0.000000 -v -0.014250 -0.116000 0.153200 -vn 0.301511 0.301511 0.904534 -v -0.014250 -0.116750 0.155700 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.115833 0.153825 -vn 0.770260 0.318866 -0.552291 -v -0.014250 -0.115375 0.154283 -vn 0.770264 0.000000 -0.637725 -v -0.014250 -0.114750 0.154450 -vn 0.301511 -0.301511 0.904534 -v -0.014250 -0.112750 0.155700 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 -0.114125 0.154283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 -0.113667 0.153825 -vn 0.770261 -0.637729 0.000000 -v -0.014250 -0.113500 0.153200 -vn 0.770258 0.000000 0.637732 -v -0.014250 -0.114750 0.151950 -vn 0.770265 0.318861 0.552286 -v -0.014250 -0.115375 0.152117 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.115833 0.152575 -vn 0.609994 0.686243 0.396204 -v -0.014250 -0.108750 0.152045 -vn 0.770261 0.637728 -0.000000 -v -0.014250 -0.108000 0.153200 -vn 0.301511 0.301511 0.904534 -v -0.014250 -0.108750 0.155700 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.107833 0.153825 -vn 0.609995 0.000001 0.792405 -v -0.014250 -0.106750 0.150891 -vn 0.770265 0.318861 0.552286 -v -0.014250 -0.107375 0.152117 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.107833 0.152575 -vn 0.770260 0.318866 -0.552291 -v -0.014250 -0.107375 0.154283 -vn 0.770264 0.000001 -0.637726 -v -0.014250 -0.106750 0.154450 -vn 0.301511 -0.301511 0.904534 -v -0.014250 -0.104750 0.155700 -vn 0.770264 -0.637725 -0.000000 -v -0.014250 -0.105500 0.153200 -vn 0.609994 -0.686243 0.396205 -v -0.014250 -0.104750 0.152045 -vn 0.770261 -0.552288 -0.318867 -v -0.014250 -0.105667 0.153825 -vn 0.770261 -0.318866 -0.552288 -v -0.014250 -0.106125 0.154283 -vn 0.770259 -0.552293 0.318864 -v -0.014250 -0.105667 0.152575 -vn 0.770266 -0.318861 0.552284 -v -0.014250 -0.106125 0.152117 -vn 0.770258 0.000001 0.637732 -v -0.014250 -0.106750 0.151950 -vn 0.717284 0.297108 -0.630263 -v -0.011250 -0.092000 0.128450 -vn 0.741788 0.427644 0.516597 -v -0.011250 -0.092000 0.129700 -vn 0.904534 0.301511 -0.301511 -v -0.011250 -0.092500 0.128450 -vn 0.846478 0.452906 0.279911 -v -0.011250 -0.094000 0.130700 -vn 0.846478 0.279911 0.452907 -v -0.011250 -0.123750 0.152700 -vn 0.741788 0.516596 0.427644 -v -0.011250 -0.124750 0.154700 -vn 0.717284 -0.630263 0.297108 -v -0.011250 -0.126000 0.154700 -vn 0.770265 0.552283 -0.318868 -v -0.011250 -0.139366 0.149450 -vn 0.770258 0.318862 -0.552294 -v -0.011250 -0.139000 0.149816 -vn 0.717284 -0.630263 -0.297108 -v -0.011250 -0.126000 0.124700 -vn 0.741788 0.516596 -0.427644 -v -0.011250 -0.124750 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 -0.126000 0.125200 -vn 0.846478 0.279911 -0.452907 -v -0.011250 -0.123750 0.126700 -vn 0.770263 0.000003 -0.637727 -v -0.011250 -0.138500 0.149950 -vn 0.717284 -0.630262 -0.297108 -v -0.011250 -0.118000 0.124700 -vn 0.741787 0.516596 -0.427644 -v -0.011250 -0.116750 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 -0.118000 0.125200 -vn 0.846478 0.279911 -0.452908 -v -0.011250 -0.115750 0.126700 -vn 0.717284 -0.630263 -0.297108 -v -0.011250 -0.110000 0.124700 -vn 0.741788 0.516596 -0.427644 -v -0.011250 -0.108750 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 -0.110000 0.125200 -vn 0.846478 0.279911 -0.452907 -v -0.011250 -0.107750 0.126700 -vn 0.904534 0.301511 -0.301511 -v -0.011250 -0.111500 0.125200 -vn 0.904534 0.301512 -0.301511 -v -0.011250 -0.095500 0.125200 -vn 0.577350 0.577350 -0.577350 -v -0.011250 -0.094000 0.125200 -vn 0.904534 0.301511 -0.301511 -v -0.011250 -0.094000 0.126700 -vn 0.741787 -0.516597 -0.427643 -v -0.011250 -0.120750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 -0.119500 0.124700 -vn 0.846479 -0.279911 -0.452906 -v -0.011250 -0.121750 0.126700 -vn 0.904534 0.301511 -0.301511 -v -0.011250 -0.119500 0.125200 -vn 0.846478 -0.279911 -0.452907 -v -0.011250 -0.113750 0.126700 -vn 0.741788 -0.516596 -0.427644 -v -0.011250 -0.112750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 -0.111500 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 -0.127500 0.126700 -vn 0.770260 0.637729 0.000002 -v -0.011250 -0.097500 0.129300 -vn 0.770263 0.000003 0.637727 -v -0.011250 -0.138500 0.129450 -vn 0.741788 0.516596 0.427644 -v -0.011250 -0.100750 0.154700 -vn 0.717284 -0.630263 0.297108 -v -0.011250 -0.102000 0.154700 -vn 0.846478 0.279911 0.452907 -v -0.011250 -0.099750 0.152700 -vn 0.904534 -0.301511 0.301511 -v -0.011250 -0.102000 0.154200 -vn 0.676638 -0.596072 -0.432273 -v -0.011250 -0.140045 0.128761 -vn 0.677585 -0.432684 -0.594696 -v -0.011250 -0.138939 0.127655 -vn 0.741788 -0.516596 -0.427644 -v -0.011250 -0.104750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 -0.103500 0.124700 -vn 0.846478 -0.279911 -0.452907 -v -0.011250 -0.105750 0.126700 -vn 0.904534 0.301511 -0.301511 -v -0.011250 -0.103500 0.125200 -vn 0.770263 -0.318866 0.552285 -v -0.011250 -0.096000 0.128434 -vn 0.846478 0.279911 -0.452907 -v -0.011250 -0.099750 0.126700 -vn 0.846478 -0.279911 -0.452907 -v -0.011250 -0.097750 0.126700 -vn 0.717284 0.630263 0.297108 -v -0.011250 -0.103500 0.154700 -vn 0.741788 -0.516596 0.427644 -v -0.011250 -0.104750 0.154700 -vn 0.904534 0.301511 0.301511 -v -0.011250 -0.103500 0.154200 -vn 0.846478 -0.279911 0.452907 -v -0.011250 -0.105750 0.152700 -vn 0.741788 0.516596 0.427644 -v -0.011250 -0.108750 0.154700 -vn 0.717284 -0.630263 0.297108 -v -0.011250 -0.110000 0.154700 -vn 0.846478 0.279911 0.452907 -v -0.011250 -0.107750 0.152700 -vn 0.904534 -0.301511 0.301511 -v -0.011250 -0.110000 0.154200 -vn 0.675966 -0.224546 -0.701889 -v -0.011250 -0.137545 0.126945 -vn 0.690737 -0.056392 -0.720904 -v -0.011250 -0.136000 0.126700 -vn 0.717284 0.630263 0.297108 -v -0.011250 -0.111500 0.154700 -vn 0.741788 -0.516596 0.427644 -v -0.011250 -0.112750 0.154700 -vn 0.904534 0.301511 0.301511 -v -0.011250 -0.111500 0.154200 -vn 0.846478 -0.279911 0.452907 -v -0.011250 -0.113750 0.152700 -vn 0.770266 -0.318856 0.552287 -v -0.011250 -0.096000 0.149234 -vn 0.770260 -0.552291 0.318864 -v -0.011250 -0.095634 0.149600 -vn 0.770264 -0.637726 0.000002 -v -0.011250 -0.095500 0.150100 -vn 0.577350 -0.577350 -0.577350 -v -0.011250 -0.127500 0.125200 -vn 0.717284 -0.630263 -0.297108 -v -0.011250 -0.102000 0.124700 -vn 0.741788 0.516596 -0.427644 -v -0.011250 -0.100750 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 -0.102000 0.125200 -vn 0.770263 -0.000000 0.637727 -v -0.011250 -0.096500 0.128300 -vn 0.741788 -0.516596 -0.427644 -v -0.011250 -0.096750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 -0.095500 0.124700 -vn 0.770260 -0.552291 0.318865 -v -0.011250 -0.095634 0.128800 -vn 0.717283 0.630263 0.297108 -v -0.011250 -0.095500 0.154700 -vn 0.741788 -0.516596 0.427644 -v -0.011250 -0.096750 0.154700 -vn 0.904534 0.301512 0.301511 -v -0.011250 -0.095500 0.154200 -vn 0.846478 -0.279911 0.452907 -v -0.011250 -0.097750 0.152700 -vn 0.770261 -0.318862 -0.552291 -v -0.011250 -0.138000 0.149816 -vn 0.770265 0.552286 -0.318861 -v -0.011250 -0.097366 0.129800 -vn 0.770259 0.318864 -0.552293 -v -0.011250 -0.097000 0.130166 -vn 0.770261 0.552292 0.318859 -v -0.011250 -0.097366 0.128800 -vn 0.770263 0.318867 0.552285 -v -0.011250 -0.097000 0.128434 -vn 0.770266 0.318857 0.552286 -v -0.011250 -0.097000 0.149234 -vn 0.770255 -0.000000 0.637736 -v -0.011250 -0.096500 0.149100 -vn 0.770263 0.000000 -0.637727 -v -0.011250 -0.096500 0.130300 -vn 0.770258 0.637733 0.000002 -v -0.011250 -0.097500 0.150100 -vn 0.770261 0.552292 0.318859 -v -0.011250 -0.097366 0.149600 -vn 0.770262 -0.552289 -0.318864 -v -0.011250 -0.137634 0.149450 -vn 0.770263 -0.637727 0.000002 -v -0.011250 -0.137500 0.148950 -vn 0.741787 0.516596 0.427644 -v -0.011250 -0.116750 0.154700 -vn 0.717284 -0.630262 0.297108 -v -0.011250 -0.118000 0.154700 -vn 0.846478 0.279911 0.452908 -v -0.011250 -0.115750 0.152700 -vn 0.904534 -0.301511 0.301511 -v -0.011250 -0.118000 0.154200 -vn 0.904534 0.301511 0.301511 -v -0.011250 -0.119500 0.154200 -vn 0.770261 -0.318861 -0.552291 -v -0.011250 -0.096000 0.130166 -vn 0.770263 -0.552285 -0.318866 -v -0.011250 -0.095634 0.129800 -vn 0.770263 -0.637727 0.000002 -v -0.011250 -0.095500 0.129300 -vn 0.770263 -0.637727 0.000002 -v -0.011250 -0.137500 0.130450 -vn 0.770258 -0.552294 0.318862 -v -0.011250 -0.137634 0.129950 -vn 0.770263 -0.318867 0.552286 -v -0.011250 -0.138000 0.129584 -vn 0.770259 0.318862 -0.552294 -v -0.011250 -0.139000 0.131316 -vn 0.770265 0.552283 -0.318868 -v -0.011250 -0.139366 0.130950 -vn 0.770263 0.637727 0.000002 -v -0.011250 -0.139500 0.130450 -vn 0.675264 -0.701711 -0.227201 -v -0.011250 -0.140755 0.130155 -vn 0.770261 0.552288 0.318866 -v -0.011250 -0.139366 0.129950 -vn 0.770261 0.318866 0.552288 -v -0.011250 -0.139000 0.129584 -vn 0.904534 -0.301511 0.301511 -v -0.011250 -0.126000 0.154200 -vn 0.577350 -0.577350 0.577350 -v -0.011250 -0.127500 0.154200 -vn 0.904534 -0.301511 0.301511 -v -0.011250 -0.127500 0.152700 -vn 0.846478 0.452907 0.279911 -v -0.011250 -0.094000 0.146700 -vn 0.846478 0.452906 -0.279911 -v -0.011250 -0.094000 0.148700 -vn 0.770262 -0.552288 -0.318864 -v -0.011250 -0.137634 0.130950 -vn 0.770263 -0.318868 0.552284 -v -0.011250 -0.138000 0.148084 -vn 0.770258 -0.552294 0.318862 -v -0.011250 -0.137634 0.148450 -vn 0.770263 0.637727 0.000002 -v -0.011250 -0.139500 0.148950 -vn 0.770261 0.552288 0.318866 -v -0.011250 -0.139366 0.148450 -vn 0.770261 0.318866 0.552288 -v -0.011250 -0.139000 0.148084 -vn 0.770263 0.000003 0.637727 -v -0.011250 -0.138500 0.147950 -vn 0.770263 0.000003 -0.637727 -v -0.011250 -0.138500 0.131450 -vn 0.770262 -0.318863 -0.552289 -v -0.011250 -0.138000 0.131316 -vn 0.741788 0.427644 -0.516597 -v -0.011250 -0.092000 0.133700 -vn 0.717284 0.297108 0.630263 -v -0.011250 -0.092000 0.134950 -vn 0.846478 0.452906 -0.279911 -v -0.011250 -0.094000 0.132700 -vn 0.904534 0.301511 0.301511 -v -0.011250 -0.092500 0.134950 -vn 0.904534 0.301511 -0.301511 -v -0.011250 -0.092500 0.144450 -vn 0.717284 0.297108 -0.630263 -v -0.011250 -0.092000 0.144450 -vn 0.741788 0.427644 0.516597 -v -0.011250 -0.092000 0.145700 -vn 0.577350 0.577350 -0.577350 -v -0.011250 -0.092500 0.126700 -vn 0.770260 0.318863 -0.552291 -v -0.011250 -0.097000 0.150966 -vn 0.770263 -0.000000 -0.637727 -v -0.011250 -0.096500 0.151100 -vn 0.770260 -0.318862 -0.552292 -v -0.011250 -0.096000 0.150966 -vn 0.770265 0.552286 -0.318861 -v -0.011250 -0.097366 0.150600 -vn 0.741788 0.427644 -0.516597 -v -0.011250 -0.092000 0.149700 -vn 0.717284 0.297108 0.630263 -v -0.011250 -0.092000 0.150950 -vn 0.904534 0.301511 0.301511 -v -0.011250 -0.092500 0.150950 -vn 0.577350 0.577350 0.577350 -v -0.011250 -0.092500 0.152700 -vn 0.577350 0.577350 0.577350 -v -0.011250 -0.094000 0.154200 -vn 0.904534 0.301511 0.301512 -v -0.011250 -0.094000 0.152700 -vn 0.770263 -0.552285 -0.318866 -v -0.011250 -0.095634 0.150600 -vn 0.846479 -0.279911 0.452906 -v -0.011250 -0.121750 0.152700 -vn 0.741787 -0.516597 0.427643 -v -0.011250 -0.120750 0.154700 -vn 0.717284 0.630263 0.297108 -v -0.011250 -0.119500 0.154700 -vn -0.075085 -0.990667 0.113762 -v -0.012750 -0.120750 0.154700 -vn -0.609994 -0.686243 0.396204 -v -0.012750 -0.120750 0.152045 -vn -0.846478 -0.279911 0.452906 -v -0.012750 -0.121750 0.152700 -vn -0.609995 -0.000001 0.792405 -v -0.012750 -0.122750 0.150891 -vn -0.846478 0.279911 0.452907 -v -0.012750 -0.123750 0.152700 -vn -0.609994 0.686243 0.396205 -v -0.012750 -0.124750 0.152045 -vn -0.075085 0.990667 0.113763 -v -0.012750 -0.124750 0.154700 -vn -0.075085 -0.990667 0.113763 -v -0.012750 -0.112750 0.154700 -vn -0.609994 -0.686243 0.396204 -v -0.012750 -0.112750 0.152045 -vn -0.846478 -0.279911 0.452907 -v -0.012750 -0.113750 0.152700 -vn -0.609995 -0.000001 0.792405 -v -0.012750 -0.114750 0.150891 -vn -0.846478 0.279911 0.452907 -v -0.012750 -0.115750 0.152700 -vn -0.609994 0.686243 0.396205 -v -0.012750 -0.116750 0.152045 -vn -0.075085 0.990667 0.113763 -v -0.012750 -0.116750 0.154700 -vn -0.075085 -0.990667 0.113763 -v -0.012750 -0.104750 0.154700 -vn -0.609994 -0.686243 0.396205 -v -0.012750 -0.104750 0.152045 -vn -0.846478 -0.279911 0.452907 -v -0.012750 -0.105750 0.152700 -vn -0.609995 0.000001 0.792405 -v -0.012750 -0.106750 0.150891 -vn -0.846478 0.279911 0.452907 -v -0.012750 -0.107750 0.152700 -vn -0.609994 0.686243 0.396204 -v -0.012750 -0.108750 0.152045 -vn -0.075085 0.990667 0.113763 -v -0.012750 -0.108750 0.154700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.120750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.119500 0.155700 -vn -0.297109 0.630262 0.717283 -v -0.015250 -0.119500 0.155700 -vn -0.297109 -0.630262 0.717283 -v -0.015250 -0.126000 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.124750 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.126000 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.112750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.111500 0.155700 -vn -0.297109 0.630262 0.717283 -v -0.015250 -0.111500 0.155700 -vn -0.297109 -0.630262 0.717284 -v -0.015250 -0.118000 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.116750 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.118000 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.104750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.103500 0.155700 -vn -0.297109 0.630262 0.717284 -v -0.015250 -0.103500 0.155700 -vn -0.297109 -0.630262 0.717283 -v -0.015250 -0.110000 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.108750 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.110000 0.155700 -vn 0.609994 0.686243 0.396204 -v -0.014250 -0.100750 0.152045 -vn 0.770261 0.637728 0.000000 -v -0.014250 -0.100000 0.153200 -vn 0.301511 0.301511 0.904534 -v -0.014250 -0.100750 0.155700 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.099833 0.153825 -vn 0.609994 -0.686243 0.396205 -v -0.014250 -0.096750 0.152045 -vn 0.301511 -0.301511 0.904534 -v -0.014250 -0.096750 0.155700 -vn 0.770262 -0.552286 -0.318869 -v -0.014250 -0.097667 0.153825 -vn 0.770265 -0.318861 0.552286 -v -0.014250 -0.098125 0.152117 -vn 0.609995 0.000001 0.792405 -v -0.014250 -0.098750 0.150891 -vn 0.770260 -0.552291 0.318866 -v -0.014250 -0.097667 0.152575 -vn 0.770264 -0.637725 -0.000000 -v -0.014250 -0.097500 0.153200 -vn 0.770258 0.000000 0.637732 -v -0.014250 -0.098750 0.151950 -vn 0.770265 0.318861 0.552287 -v -0.014250 -0.099375 0.152117 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.099833 0.152575 -vn 0.770260 0.318865 -0.552291 -v -0.014250 -0.099375 0.154283 -vn 0.770264 0.000000 -0.637725 -v -0.014250 -0.098750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 -0.098125 0.154283 -vn 0.301511 0.904534 0.301511 -v -0.014250 -0.091000 0.145700 -vn 0.301511 0.904534 -0.301511 -v -0.014250 -0.091000 0.149700 -vn 0.770264 -0.637725 -0.000000 -v -0.014250 -0.092250 0.147700 -vn 0.770259 -0.552293 -0.318864 -v -0.014250 -0.092417 0.148325 -vn 0.770259 0.552293 -0.318864 -v -0.014250 -0.094583 0.148325 -vn 0.609994 0.396203 -0.686243 -v -0.014250 -0.094655 0.149700 -vn 0.770264 0.637725 0.000000 -v -0.014250 -0.094750 0.147700 -vn 0.609994 0.792406 -0.000000 -v -0.014250 -0.095809 0.147700 -vn 0.770261 0.552288 0.318867 -v -0.014250 -0.094583 0.147075 -vn 0.609994 0.396203 0.686243 -v -0.014250 -0.094655 0.145700 -vn 0.770261 0.318867 0.552288 -v -0.014250 -0.094125 0.146617 -vn 0.770261 -0.552288 0.318867 -v -0.014250 -0.092417 0.147075 -vn 0.770261 -0.318866 0.552288 -v -0.014250 -0.092875 0.146617 -vn 0.770264 0.000001 0.637725 -v -0.014250 -0.093500 0.146450 -vn 0.770266 0.318862 -0.552284 -v -0.014250 -0.094125 0.148783 -vn 0.770258 0.000001 -0.637732 -v -0.014250 -0.093500 0.148950 -vn 0.770266 -0.318861 -0.552284 -v -0.014250 -0.092875 0.148783 -vn -0.075085 -0.990667 0.113763 -v -0.012750 -0.096750 0.154700 -vn -0.609994 -0.686243 0.396205 -v -0.012750 -0.096750 0.152045 -vn -0.846478 -0.279911 0.452907 -v -0.012750 -0.097750 0.152700 -vn -0.609995 0.000001 0.792405 -v -0.012750 -0.098750 0.150891 -vn -0.846478 0.279911 0.452907 -v -0.012750 -0.099750 0.152700 -vn -0.609994 0.686243 0.396204 -v -0.012750 -0.100750 0.152045 -vn -0.075085 0.990667 0.113763 -v -0.012750 -0.100750 0.154700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.096750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.095500 0.155700 -vn -0.297109 0.630262 0.717284 -v -0.015250 -0.095500 0.155700 -vn -0.297109 -0.630262 0.717284 -v -0.015250 -0.102000 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 -0.100750 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 -0.102000 0.155700 -vn -0.846478 0.452907 0.279911 -v -0.012750 -0.094000 0.146700 -vn -0.075085 0.113763 0.990667 -v -0.012750 -0.092000 0.145700 -vn -0.609994 0.396204 0.686243 -v -0.012750 -0.094655 0.145700 -vn -0.609994 0.396204 -0.686243 -v -0.012750 -0.094655 0.149700 -vn -0.075085 0.113763 -0.990667 -v -0.012750 -0.092000 0.149700 -vn -0.846478 0.452906 -0.279911 -v -0.012750 -0.094000 0.148700 -vn -0.609995 0.792406 0.000000 -v -0.012750 -0.095809 0.147700 -vn 0.297109 0.717283 0.630262 -v -0.012250 -0.091000 0.145700 -vn 0.297109 0.717283 -0.630262 -v -0.012250 -0.091000 0.144450 -vn -0.297109 0.717283 -0.630262 -v -0.015250 -0.091000 0.144450 -vn -0.297109 0.717284 0.630262 -v -0.015250 -0.091000 0.150950 -vn 0.297109 0.717283 -0.630262 -v -0.012250 -0.091000 0.149700 -vn 0.297109 0.717283 0.630262 -v -0.012250 -0.091000 0.150950 -vn -0.087119 -0.736839 -0.670431 -v -0.014750 -0.127500 0.126700 -vn -0.081892 -0.019677 -0.996447 -v -0.014750 -0.136000 0.126700 -vn -0.087124 -0.736841 0.670428 -v -0.014750 -0.127500 0.152700 -vn -0.297108 -0.630263 0.717284 -v -0.014750 -0.127500 0.154200 -vn -0.319810 -0.768477 0.554224 -v -0.015500 -0.127500 0.152499 -vn -0.554221 -0.768481 0.319807 -v -0.016049 -0.127500 0.151950 -vn -0.227458 -0.804186 0.549133 -v -0.014750 -0.126000 0.154200 -vn -0.227458 0.804186 0.549133 -v -0.014750 -0.119500 0.154200 -vn -0.227458 -0.804186 0.549133 -v -0.014750 -0.118000 0.154200 -vn -0.227458 0.804186 0.549133 -v -0.014750 -0.111500 0.154200 -vn -0.227458 -0.804186 0.549133 -v -0.014750 -0.110000 0.154200 -vn -0.227458 0.804186 0.549133 -v -0.014750 -0.103500 0.154200 -vn -0.227458 -0.804186 0.549133 -v -0.014750 -0.102000 0.154200 -vn -0.227458 0.804186 0.549133 -v -0.014750 -0.095500 0.154200 -vn -0.297108 0.630263 0.717284 -v -0.014750 -0.094000 0.154200 -vn -0.297108 0.717284 0.630263 -v -0.014750 -0.092500 0.152700 -vn -0.227458 0.549133 0.804186 -v -0.014750 -0.092500 0.150950 -vn -0.227458 0.549133 -0.804186 -v -0.014750 -0.092500 0.144450 -vn -0.227458 0.549133 0.804186 -v -0.014750 -0.092500 0.134950 -vn -0.297109 0.717283 0.630262 -v -0.015250 -0.091000 0.134950 -vn 0.297109 0.717283 0.630262 -v -0.012250 -0.091000 0.134950 -vn 0.297109 0.717283 0.630262 -v -0.012250 -0.091000 0.129700 -vn 0.297109 0.717283 -0.630262 -v -0.012250 -0.091000 0.128450 -vn 0.301511 0.904534 0.301511 -v -0.014250 -0.091000 0.129700 -vn -0.297109 0.717283 -0.630262 -v -0.015250 -0.091000 0.128450 -vn 0.301511 0.904534 -0.301511 -v -0.014250 -0.091000 0.133700 -vn 0.297109 0.717283 -0.630262 -v -0.012250 -0.091000 0.133700 -vn -0.227458 0.549133 -0.804186 -v -0.014750 -0.092500 0.128450 -vn -0.297108 0.717284 -0.630263 -v -0.014750 -0.092500 0.126700 -vn -0.297108 0.630263 -0.717284 -v -0.014750 -0.094000 0.125200 -vn -0.227458 0.804186 -0.549133 -v -0.014750 -0.095500 0.125200 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.095500 0.123700 -vn -0.297109 0.630262 -0.717283 -v -0.015250 -0.095500 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.100750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 -0.102000 0.123700 -vn 0.301511 0.301511 -0.904534 -v -0.014250 -0.100750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v -0.015250 -0.102000 0.123700 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 -0.096750 0.123700 -vn 0.297109 -0.630262 -0.717284 -v -0.012250 -0.096750 0.123700 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 -0.102000 0.125200 -vn -0.227458 0.804186 -0.549133 -v -0.014750 -0.103500 0.125200 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.103500 0.123700 -vn -0.297109 0.630262 -0.717284 -v -0.015250 -0.103500 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.108750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 -0.110000 0.123700 -vn 0.301511 0.301511 -0.904534 -v -0.014250 -0.108750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v -0.015250 -0.110000 0.123700 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 -0.104750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 -0.104750 0.123700 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 -0.110000 0.125200 -vn -0.227458 0.804186 -0.549133 -v -0.014750 -0.111500 0.125200 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.111500 0.123700 -vn -0.297109 0.630262 -0.717283 -v -0.015250 -0.111500 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.116750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 -0.118000 0.123700 -vn 0.301511 0.301511 -0.904534 -v -0.014250 -0.116750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v -0.015250 -0.118000 0.123700 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 -0.112750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 -0.112750 0.123700 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 -0.118000 0.125200 -vn -0.227458 0.804186 -0.549133 -v -0.014750 -0.119500 0.125200 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.119500 0.123700 -vn -0.297109 0.630262 -0.717283 -v -0.015250 -0.119500 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 -0.124750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 -0.126000 0.123700 -vn 0.301511 0.301511 -0.904534 -v -0.014250 -0.124750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v -0.015250 -0.126000 0.123700 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 -0.120750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 -0.120750 0.123700 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 -0.126000 0.125200 -vn -0.297108 -0.630263 -0.717284 -v -0.014750 -0.127500 0.125200 -vn -0.554225 -0.768479 -0.319806 -v -0.016049 -0.127500 0.127450 -vn -0.319806 -0.768482 -0.554220 -v -0.015500 -0.127500 0.126901 -vn -0.174809 -0.977022 -0.121937 -v -0.015997 -0.136750 0.129700 -vn -0.297112 -0.717283 -0.630262 -v -0.016300 -0.136750 0.129700 -vn -0.332588 0.226214 -0.915539 -v -0.019050 -0.098472 0.129700 -vn -0.341577 -0.341572 -0.875588 -v -0.019050 -0.120550 0.129700 -vn -0.341588 -0.875572 -0.341601 -v -0.019050 -0.120750 0.129900 -vn -0.371678 -0.888584 0.268838 -v -0.019050 -0.120750 0.132629 -vn -0.391739 -0.812014 0.432637 -v -0.019050 -0.119581 0.134392 -vn -0.391668 -0.880350 0.267545 -v -0.019050 -0.118735 0.136431 -vn -0.391403 -0.915764 0.090445 -v -0.019050 -0.118304 0.138596 -vn -0.391145 -0.915900 -0.090179 -v -0.019050 -0.118304 0.140804 -vn -0.390889 -0.880749 -0.267369 -v -0.019050 -0.118735 0.142968 -vn -0.391243 -0.812382 -0.432394 -v -0.019050 -0.119581 0.145007 -vn -0.371668 -0.888352 -0.269617 -v -0.019050 -0.120750 0.146771 -vn -0.341590 -0.875577 0.341585 -v -0.019050 -0.120750 0.149500 -vn -0.609994 0.396204 -0.686243 -v -0.012750 -0.094655 0.133700 -vn 0.609994 0.396203 -0.686243 -v -0.014250 -0.094655 0.133700 -vn -0.075085 0.113763 -0.990667 -v -0.012750 -0.092000 0.133700 -vn 0.770264 -0.637725 -0.000000 -v -0.014250 -0.092250 0.131700 -vn 0.770259 -0.552293 -0.318864 -v -0.014250 -0.092417 0.132325 -vn 0.770264 0.000001 0.637725 -v -0.014250 -0.093500 0.130450 -vn 0.609994 0.396202 0.686244 -v -0.014250 -0.094655 0.129700 -vn 0.770261 -0.318866 0.552288 -v -0.014250 -0.092875 0.130617 -vn 0.770261 -0.552288 0.318867 -v -0.014250 -0.092417 0.131075 -vn 0.770261 0.318867 0.552288 -v -0.014250 -0.094125 0.130617 -vn 0.770261 0.552288 0.318867 -v -0.014250 -0.094583 0.131075 -vn 0.609994 0.792406 0.000001 -v -0.014250 -0.095809 0.131700 -vn 0.770264 0.637725 0.000000 -v -0.014250 -0.094750 0.131700 -vn 0.770259 0.552293 -0.318864 -v -0.014250 -0.094583 0.132325 -vn 0.770266 0.318862 -0.552284 -v -0.014250 -0.094125 0.132783 -vn 0.770258 0.000001 -0.637732 -v -0.014250 -0.093500 0.132950 -vn 0.770266 -0.318861 -0.552284 -v -0.014250 -0.092875 0.132783 -vn -0.075085 0.113763 0.990667 -v -0.012750 -0.092000 0.129700 -vn -0.609994 0.396202 0.686244 -v -0.012750 -0.094655 0.129700 -vn -0.609994 0.792406 0.000001 -v -0.012750 -0.095809 0.131700 -vn -0.846478 0.452906 0.279911 -v -0.012750 -0.094000 0.130700 -vn -0.846478 0.452907 -0.279911 -v -0.012750 -0.094000 0.132700 -vn -0.609994 -0.686244 -0.396203 -v -0.012750 -0.096750 0.127355 -vn 0.609994 -0.686244 -0.396203 -v -0.014250 -0.096750 0.127355 -vn -0.075085 -0.990667 -0.113763 -v -0.012750 -0.096750 0.124700 -vn 0.609995 0.686244 -0.396202 -v -0.014250 -0.100750 0.127355 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.099833 0.125575 -vn 0.770261 0.637728 0.000000 -v -0.014250 -0.100000 0.126200 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.099833 0.126825 -vn 0.609994 0.000001 -0.792406 -v -0.014250 -0.098750 0.128509 -vn 0.770260 0.318866 -0.552291 -v -0.014250 -0.099375 0.127283 -vn 0.770264 -0.637725 0.000000 -v -0.014250 -0.097500 0.126200 -vn 0.770260 -0.552291 0.318866 -v -0.014250 -0.097667 0.125575 -vn 0.770265 -0.318861 0.552286 -v -0.014250 -0.098125 0.125117 -vn 0.770258 0.000000 0.637732 -v -0.014250 -0.098750 0.124950 -vn 0.770265 0.318861 0.552286 -v -0.014250 -0.099375 0.125117 -vn 0.770264 -0.000000 -0.637725 -v -0.014250 -0.098750 0.127450 -vn 0.770260 -0.318865 -0.552291 -v -0.014250 -0.098125 0.127283 -vn 0.770262 -0.552286 -0.318869 -v -0.014250 -0.097667 0.126825 -vn -0.075085 0.990667 -0.113763 -v -0.012750 -0.100750 0.124700 -vn -0.609995 0.686244 -0.396202 -v -0.012750 -0.100750 0.127355 -vn -0.609994 0.000001 -0.792406 -v -0.012750 -0.098750 0.128509 -vn -0.846478 0.279911 -0.452907 -v -0.012750 -0.099750 0.126700 -vn -0.846478 -0.279911 -0.452907 -v -0.012750 -0.097750 0.126700 -vn -0.609994 -0.686244 -0.396203 -v -0.012750 -0.104750 0.127355 -vn 0.609994 -0.686244 -0.396203 -v -0.014250 -0.104750 0.127355 -vn -0.075085 -0.990667 -0.113763 -v -0.012750 -0.104750 0.124700 -vn 0.609995 0.686244 -0.396202 -v -0.014250 -0.108750 0.127355 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.107833 0.125575 -vn 0.770261 0.637728 -0.000000 -v -0.014250 -0.108000 0.126200 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.107833 0.126825 -vn 0.609994 0.000001 -0.792406 -v -0.014250 -0.106750 0.128509 -vn 0.770260 0.318865 -0.552291 -v -0.014250 -0.107375 0.127283 -vn 0.770259 -0.552293 0.318864 -v -0.014250 -0.105667 0.125575 -vn 0.770264 -0.637725 0.000000 -v -0.014250 -0.105500 0.126200 -vn 0.770264 0.000001 -0.637726 -v -0.014250 -0.106750 0.127450 -vn 0.770261 -0.318866 -0.552288 -v -0.014250 -0.106125 0.127283 -vn 0.770261 -0.552288 -0.318867 -v -0.014250 -0.105667 0.126825 -vn 0.770266 -0.318861 0.552284 -v -0.014250 -0.106125 0.125117 -vn 0.770258 0.000001 0.637732 -v -0.014250 -0.106750 0.124950 -vn 0.770265 0.318861 0.552287 -v -0.014250 -0.107375 0.125117 -vn -0.075085 0.990667 -0.113763 -v -0.012750 -0.108750 0.124700 -vn -0.609995 0.686244 -0.396202 -v -0.012750 -0.108750 0.127355 -vn -0.609995 -0.686244 -0.396202 -v -0.012750 -0.112750 0.127355 -vn 0.609995 -0.686244 -0.396202 -v -0.014250 -0.112750 0.127355 -vn -0.075085 -0.990667 -0.113763 -v -0.012750 -0.112750 0.124700 -vn 0.770261 -0.552291 0.318862 -v -0.014250 -0.113667 0.125575 -vn 0.770261 -0.637728 0.000000 -v -0.014250 -0.113500 0.126200 -vn 0.770265 -0.318861 0.552286 -v -0.014250 -0.114125 0.125117 -vn 0.770258 -0.000000 0.637732 -v -0.014250 -0.114750 0.124950 -vn 0.770260 0.318865 -0.552291 -v -0.014250 -0.115375 0.127283 -vn 0.609994 -0.000001 -0.792406 -v -0.014250 -0.114750 0.128509 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.115833 0.126825 -vn 0.609994 0.686244 -0.396202 -v -0.014250 -0.116750 0.127355 -vn 0.770264 0.000000 -0.637725 -v -0.014250 -0.114750 0.127450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 -0.114125 0.127283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 -0.113667 0.126825 -vn 0.770265 0.318861 0.552286 -v -0.014250 -0.115375 0.125117 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.115833 0.125575 -vn 0.770261 0.637728 -0.000000 -v -0.014250 -0.116000 0.126200 -vn -0.075085 0.990667 -0.113763 -v -0.012750 -0.116750 0.124700 -vn -0.609994 0.686244 -0.396203 -v -0.012750 -0.116750 0.127355 -vn -0.609995 -0.686244 -0.396202 -v -0.012750 -0.120750 0.127355 -vn 0.609995 -0.686244 -0.396202 -v -0.014250 -0.120750 0.127355 -vn -0.075085 -0.990667 -0.113762 -v -0.012750 -0.120750 0.124700 -vn 0.770264 0.000000 -0.637725 -v -0.014250 -0.122750 0.127450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 -0.122125 0.127283 -vn 0.609994 -0.000001 -0.792406 -v -0.014250 -0.122750 0.128509 -vn 0.609994 0.686244 -0.396202 -v -0.014250 -0.124750 0.127355 -vn 0.770261 0.552291 0.318862 -v -0.014250 -0.123833 0.125575 -vn 0.770261 0.637728 -0.000000 -v -0.014250 -0.124000 0.126200 -vn 0.770263 0.552286 -0.318865 -v -0.014250 -0.123833 0.126825 -vn 0.770260 0.318866 -0.552291 -v -0.014250 -0.123375 0.127283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 -0.121667 0.126825 -vn 0.770261 -0.637728 0.000000 -v -0.014250 -0.121500 0.126200 -vn 0.770261 -0.552291 0.318862 -v -0.014250 -0.121667 0.125575 -vn 0.770265 -0.318861 0.552286 -v -0.014250 -0.122125 0.125117 -vn 0.770258 0.000000 0.637732 -v -0.014250 -0.122750 0.124950 -vn 0.770265 0.318861 0.552286 -v -0.014250 -0.123375 0.125117 -vn -0.075085 0.990667 -0.113763 -v -0.012750 -0.124750 0.124700 -vn -0.609994 0.686244 -0.396203 -v -0.012750 -0.124750 0.127355 -vn -0.609994 0.000001 -0.792406 -v -0.012750 -0.106750 0.128509 -vn -0.846478 0.279911 -0.452907 -v -0.012750 -0.107750 0.126700 -vn -0.846478 -0.279911 -0.452907 -v -0.012750 -0.105750 0.126700 -vn -0.609994 -0.000001 -0.792406 -v -0.012750 -0.114750 0.128509 -vn -0.846478 0.279911 -0.452907 -v -0.012750 -0.115750 0.126700 -vn -0.846478 -0.279911 -0.452907 -v -0.012750 -0.113750 0.126700 -vn -0.609994 -0.000001 -0.792406 -v -0.012750 -0.122750 0.128509 -vn -0.846478 0.279911 -0.452907 -v -0.012750 -0.123750 0.126700 -vn -0.846478 -0.279911 -0.452906 -v -0.012750 -0.121750 0.126700 -vn -0.034159 -0.454645 -0.890017 -v -0.014750 -0.136550 0.126730 -vn -0.091616 -0.237885 -0.966963 -v -0.014550 -0.136550 0.126730 -vn -0.414899 -0.237231 -0.878396 -v -0.014550 -0.137545 0.126945 -vn -0.377856 -0.392572 -0.838518 -v -0.014550 -0.137925 0.127086 -vn -0.408210 -0.494299 -0.767485 -v -0.014550 -0.138939 0.127655 -vn -0.375042 -0.622836 -0.686599 -v -0.014550 -0.139179 0.127841 -vn -0.391910 -0.711427 -0.583333 -v -0.014550 -0.140045 0.128761 -vn -0.375405 -0.801580 -0.465340 -v -0.014550 -0.140161 0.128928 -vn -0.371280 -0.888943 -0.268200 -v -0.014550 -0.140786 0.130252 -vn -0.407593 -0.057150 -0.911373 -v -0.016300 -0.139500 0.132200 -vn -0.392038 -0.123373 -0.911639 -v -0.016300 -0.138500 0.132200 -vn -0.678875 -0.095838 -0.727972 -v -0.014750 -0.138500 0.132200 -vn -0.376177 -0.217184 -0.900734 -v -0.016126 -0.140150 0.132200 -vn -0.217185 -0.376171 -0.900736 -v -0.015650 -0.140626 0.132200 -vn -0.057147 -0.407588 -0.911376 -v -0.015000 -0.140800 0.132200 -vn -0.578889 -0.574264 -0.578885 -v -0.014750 -0.140800 0.132200 -vn -0.797132 -0.566906 -0.207842 -v -0.014750 -0.136750 0.126982 -vn -0.393456 -0.593620 -0.702003 -v -0.014750 -0.136729 0.126956 -vn -0.915141 -0.166939 -0.366946 -v -0.014750 -0.137848 0.127270 -vn -0.770262 0.000002 0.637727 -v -0.014750 -0.138500 0.129450 -vn -0.770265 -0.318868 0.552282 -v -0.014750 -0.138000 0.129584 -vn -0.770258 -0.552294 0.318862 -v -0.014750 -0.137634 0.129950 -vn -0.678875 -0.727973 -0.095838 -v -0.014750 -0.136750 0.130450 -vn -0.770263 -0.637727 0.000002 -v -0.014750 -0.137500 0.130450 -vn -0.653226 -0.655723 -0.378580 -v -0.014750 -0.136984 0.131325 -vn -0.770262 -0.552289 -0.318864 -v -0.014750 -0.137634 0.130950 -vn -0.653226 -0.378580 -0.655723 -v -0.014750 -0.137625 0.131966 -vn -0.770262 -0.318864 -0.552288 -v -0.014750 -0.138000 0.131316 -vn -0.770262 0.000002 -0.637727 -v -0.014750 -0.138500 0.131450 -vn -0.770258 0.318862 -0.552294 -v -0.014750 -0.139000 0.131316 -vn -0.917198 -0.397282 -0.030260 -v -0.014750 -0.140800 0.131700 -vn -0.770265 0.552283 -0.318868 -v -0.014750 -0.139366 0.130950 -vn -0.911014 -0.394698 -0.119448 -v -0.014750 -0.140594 0.130310 -vn -0.770263 0.637727 0.000002 -v -0.014750 -0.139500 0.130450 -vn -0.915050 -0.341600 -0.214460 -v -0.014750 -0.139995 0.129038 -vn -0.770261 0.552288 0.318866 -v -0.014750 -0.139366 0.129950 -vn -0.916106 -0.260379 -0.304880 -v -0.014750 -0.139052 0.127995 -vn -0.770261 0.318866 0.552288 -v -0.014750 -0.139000 0.129584 -vn -0.392036 -0.911639 -0.123376 -v -0.016300 -0.136750 0.130450 -vn -0.376086 -0.925873 -0.036324 -v -0.015997 -0.136750 0.128239 -vn -0.075598 -0.934780 -0.347089 -v -0.014940 -0.136750 0.126996 -vn -0.358782 -0.923540 -0.135458 -v -0.015912 -0.136750 0.127782 -vn -0.279265 -0.928830 -0.243485 -v -0.015665 -0.136750 0.127384 -vn -0.178106 -0.931066 -0.318426 -v -0.015372 -0.136750 0.127149 -vn -0.406952 -0.456728 -0.791069 -v -0.016300 -0.137625 0.131966 -vn -0.406950 -0.791071 -0.456725 -v -0.016300 -0.136984 0.131325 -vn -0.057148 -0.407588 0.911376 -v -0.015000 -0.140800 0.147200 -vn -0.578889 -0.574264 0.578885 -v -0.014750 -0.140800 0.147200 -vn -0.678875 -0.095838 0.727972 -v -0.014750 -0.138500 0.147200 -vn -0.217184 -0.376171 0.900737 -v -0.015650 -0.140626 0.147200 -vn -0.376177 -0.217183 0.900734 -v -0.016126 -0.140150 0.147200 -vn -0.407593 -0.057150 0.911373 -v -0.016300 -0.139500 0.147200 -vn -0.392038 -0.123373 0.911639 -v -0.016300 -0.138500 0.147200 -vn -0.770263 -0.637727 0.000002 -v -0.014750 -0.137500 0.148950 -vn -0.770262 -0.552289 -0.318864 -v -0.014750 -0.137634 0.149450 -vn -0.503527 -0.830929 0.236680 -v -0.014750 -0.136750 0.152441 -vn -0.770262 -0.318864 -0.552288 -v -0.014750 -0.138000 0.149816 -vn -0.916752 -0.164414 0.364051 -v -0.014750 -0.137865 0.152123 -vn -0.770262 0.000002 -0.637727 -v -0.014750 -0.138500 0.149950 -vn -0.916343 -0.262570 0.302280 -v -0.014750 -0.139063 0.151396 -vn -0.770258 0.318862 -0.552294 -v -0.014750 -0.139000 0.149816 -vn -0.915128 -0.341979 0.213522 -v -0.014750 -0.139999 0.150354 -vn -0.770265 0.552283 -0.318868 -v -0.014750 -0.139366 0.149450 -vn -0.911050 -0.394732 0.119058 -v -0.014750 -0.140595 0.149086 -vn -0.770263 0.637727 0.000002 -v -0.014750 -0.139500 0.148950 -vn -0.917220 -0.397238 0.030157 -v -0.014750 -0.140800 0.147700 -vn -0.770261 0.552288 0.318866 -v -0.014750 -0.139366 0.148450 -vn -0.770261 0.318866 0.552288 -v -0.014750 -0.139000 0.148084 -vn -0.770262 0.000002 0.637727 -v -0.014750 -0.138500 0.147950 -vn -0.653226 -0.378580 0.655723 -v -0.014750 -0.137625 0.147434 -vn -0.770265 -0.318868 0.552282 -v -0.014750 -0.138000 0.148084 -vn -0.653227 -0.655722 0.378581 -v -0.014750 -0.136984 0.148075 -vn -0.770258 -0.552294 0.318862 -v -0.014750 -0.137634 0.148450 -vn -0.678874 -0.727973 0.095840 -v -0.014750 -0.136750 0.148950 -vn -0.392038 -0.911638 0.123374 -v -0.016300 -0.136750 0.148950 -vn -0.406960 -0.791067 0.456724 -v -0.016300 -0.136984 0.148075 -vn -0.406966 -0.456723 0.791064 -v -0.016300 -0.137625 0.147434 -vn -0.141903 -0.919681 0.366129 -v -0.015215 -0.136750 0.152382 -vn -0.036080 -0.926994 0.373338 -v -0.014750 -0.136750 0.152468 -vn -0.451015 -0.527996 0.719587 -v -0.014723 -0.136750 0.152468 -vn -0.386589 -0.922213 0.008518 -v -0.016050 -0.136750 0.151156 -vn -0.396285 -0.915774 0.065702 -v -0.016043 -0.136750 0.151289 -vn -0.267267 -0.918050 0.292836 -v -0.015622 -0.136750 0.152130 -vn -0.361084 -0.915021 0.179874 -v -0.015908 -0.136750 0.151753 -vn -0.133422 0.907512 -0.398272 -v -0.016050 -0.098142 0.129904 -vn -0.658765 0.652396 -0.374710 -v -0.014750 -0.098016 0.130175 -vn -0.344940 0.934450 -0.088428 -v -0.016050 -0.098250 0.129300 -vn -0.658698 0.752369 -0.007636 -v -0.014750 -0.098250 0.129300 -vn -0.390795 0.901666 0.185144 -v -0.016050 -0.098238 0.129093 -vn -0.662042 0.648876 0.375046 -v -0.014750 -0.098016 0.128425 -vn -0.660767 0.374856 0.650284 -v -0.014750 -0.097375 0.127784 -vn -0.391314 0.695175 0.602997 -v -0.016050 -0.097922 0.128280 -vn -0.344691 0.856594 0.383973 -v -0.016050 -0.098016 0.128425 -vn -0.659325 -0.000676 0.751858 -v -0.014750 -0.096500 0.127550 -vn -0.391812 0.310547 0.866051 -v -0.016050 -0.097253 0.127720 -vn -0.356523 0.551757 0.753960 -v -0.016050 -0.097375 0.127784 -vn -0.657712 -0.377402 0.651907 -v -0.014750 -0.095625 0.127784 -vn -0.407743 -0.138306 0.902561 -v -0.016050 -0.096397 0.127553 -vn -0.367161 0.105669 0.924136 -v -0.016050 -0.096500 0.127550 -vn -0.654709 -0.655784 -0.375905 -v -0.014750 -0.094984 0.130175 -vn -0.422285 -0.906198 -0.021917 -v -0.016050 -0.094750 0.129300 -vn -0.653967 -0.756522 -0.001406 -v -0.014750 -0.094750 0.129300 -vn -0.415225 -0.789485 0.451997 -v -0.016050 -0.094967 0.128455 -vn -0.655411 -0.654563 0.376808 -v -0.014750 -0.094984 0.128425 -vn -0.393184 -0.579373 0.713956 -v -0.016050 -0.095566 0.127820 -vn -0.376620 -0.364534 0.851629 -v -0.016050 -0.095625 0.127784 -vn -0.657715 -0.377403 -0.651903 -v -0.014750 -0.095625 0.130816 -vn -0.393173 -0.579423 -0.713922 -v -0.016050 -0.095566 0.130780 -vn -0.406166 -0.801280 -0.439294 -v -0.016050 -0.094967 0.130145 -vn -0.660325 -0.002347 -0.750976 -v -0.014750 -0.096500 0.131050 -vn -0.394650 -0.149701 -0.906554 -v -0.016050 -0.096396 0.131047 -vn -0.380445 -0.368057 -0.848408 -v -0.016050 -0.095625 0.130816 -vn -0.660892 0.378744 -0.647900 -v -0.014750 -0.097375 0.130816 -vn -0.126314 0.444721 -0.886717 -v -0.016050 -0.097200 0.130904 -vn -0.388736 0.076507 -0.918167 -v -0.016050 -0.096500 0.131050 -vn -0.322672 0.635231 -0.701687 -v -0.019050 -0.097200 0.130904 -vn -0.352524 0.505455 -0.787555 -v -0.019050 -0.097375 0.130816 -vn -0.383270 0.674653 -0.630831 -v -0.019050 -0.097771 0.130503 -vn -0.274664 0.808500 -0.520468 -v -0.019050 -0.098016 0.130175 -vn -0.323519 0.727336 -0.605242 -v -0.019050 -0.098142 0.129904 -vn -0.770261 0.552292 0.318859 -v -0.014750 -0.097366 0.128800 -vn -0.770259 0.637731 0.000002 -v -0.014750 -0.097500 0.129300 -vn -0.770265 0.552286 -0.318861 -v -0.014750 -0.097366 0.129800 -vn -0.770260 0.318863 -0.552291 -v -0.014750 -0.097000 0.130166 -vn -0.770262 -0.000000 -0.637727 -v -0.014750 -0.096500 0.130300 -vn -0.770260 -0.318864 -0.552291 -v -0.014750 -0.096000 0.130166 -vn -0.770263 -0.552286 -0.318865 -v -0.014750 -0.095634 0.129800 -vn -0.770263 -0.637727 0.000002 -v -0.014750 -0.095500 0.129300 -vn -0.770260 -0.552292 0.318863 -v -0.014750 -0.095634 0.128800 -vn -0.770262 -0.318867 0.552286 -v -0.014750 -0.096000 0.128434 -vn -0.770262 -0.000000 0.637727 -v -0.014750 -0.096500 0.128300 -vn -0.770263 0.318867 0.552285 -v -0.014750 -0.097000 0.128434 -vn -0.660918 0.750456 -0.001532 -v -0.014750 -0.098250 0.150100 -vn -0.660948 0.647848 0.378736 -v -0.014750 -0.098016 0.149225 -vn -0.090475 0.901120 0.424024 -v -0.016050 -0.098104 0.149400 -vn -0.081886 0.464696 0.881676 -v -0.016050 -0.097344 0.148567 -vn -0.656889 0.375510 0.653827 -v -0.014750 -0.097375 0.148584 -vn -0.420598 -0.009040 0.907202 -v -0.016050 -0.096534 0.148350 -vn -0.653090 -0.003254 0.757274 -v -0.014750 -0.096500 0.148350 -vn -0.653676 -0.375682 0.656941 -v -0.014750 -0.095625 0.148584 -vn -0.656507 -0.653208 0.377251 -v -0.014750 -0.094984 0.149225 -vn -0.392615 -0.715791 0.577492 -v -0.016050 -0.095013 0.149178 -vn -0.406960 -0.434095 0.803707 -v -0.016050 -0.095664 0.148563 -vn -0.657037 -0.753858 0.000057 -v -0.014750 -0.094750 0.150100 -vn -0.393743 -0.908508 0.139926 -v -0.016050 -0.094751 0.150035 -vn -0.382807 -0.850127 0.361583 -v -0.016050 -0.094984 0.149225 -vn -0.657551 -0.652476 -0.376698 -v -0.014750 -0.094984 0.150975 -vn -0.393993 -0.857625 -0.330528 -v -0.016050 -0.094948 0.150909 -vn -0.380927 -0.918052 -0.109886 -v -0.016050 -0.094750 0.150100 -vn -0.658050 -0.376455 -0.652114 -v -0.014750 -0.095625 0.151616 -vn -0.394239 -0.579463 -0.713301 -v -0.016050 -0.095552 0.151571 -vn -0.379018 -0.742064 -0.552890 -v -0.016050 -0.094984 0.150975 -vn -0.658535 0.000078 -0.752551 -v -0.014750 -0.096500 0.151850 -vn -0.409687 -0.129597 -0.902974 -v -0.016050 -0.096404 0.151847 -vn -0.391924 -0.379826 -0.837931 -v -0.016050 -0.095625 0.151616 -vn -0.659003 0.376171 -0.651315 -v -0.014750 -0.097375 0.151616 -vn -0.394719 0.322964 -0.860169 -v -0.016050 -0.097281 0.151666 -vn -0.375119 0.103443 -0.921187 -v -0.016050 -0.096500 0.151850 -vn -0.659455 0.651104 -0.375744 -v -0.014750 -0.098016 0.150975 -vn -0.394945 0.707985 -0.585470 -v -0.016050 -0.097954 0.151074 -vn -0.373133 0.548761 -0.748086 -v -0.016050 -0.097375 0.151616 -vn -0.339313 0.939541 0.046135 -v -0.016050 -0.098250 0.150100 -vn -0.385324 0.911942 -0.141019 -v -0.016050 -0.098245 0.150227 -vn -0.371148 0.849019 -0.376054 -v -0.016050 -0.098016 0.150975 -vn -0.322203 0.782883 0.532239 -v -0.019050 -0.098104 0.149400 -vn -0.343795 0.801454 0.489363 -v -0.019050 -0.098016 0.149225 -vn -0.386040 0.651026 0.653558 -v -0.019050 -0.097771 0.148897 -vn -0.306497 0.546604 0.779284 -v -0.019050 -0.097375 0.148584 -vn -0.324453 0.549392 0.769999 -v -0.019050 -0.097344 0.148567 -vn -0.770261 0.552292 0.318859 -v -0.014750 -0.097366 0.149600 -vn -0.770259 0.637731 0.000002 -v -0.014750 -0.097500 0.150100 -vn -0.770265 0.552286 -0.318861 -v -0.014750 -0.097366 0.150600 -vn -0.770260 0.318863 -0.552291 -v -0.014750 -0.097000 0.150966 -vn -0.770262 -0.000000 -0.637727 -v -0.014750 -0.096500 0.151100 -vn -0.770260 -0.318864 -0.552291 -v -0.014750 -0.096000 0.150966 -vn -0.770263 -0.552286 -0.318865 -v -0.014750 -0.095634 0.150600 -vn -0.770263 -0.637727 0.000002 -v -0.014750 -0.095500 0.150100 -vn -0.770260 -0.552292 0.318863 -v -0.014750 -0.095634 0.149600 -vn -0.770266 -0.318858 0.552287 -v -0.014750 -0.096000 0.149234 -vn -0.770255 -0.000000 0.637736 -v -0.014750 -0.096500 0.149100 -vn -0.770266 0.318857 0.552286 -v -0.014750 -0.097000 0.149234 -vn -0.301576 -0.027693 0.953040 -v -0.015269 -0.136000 0.152607 -vn -0.517919 -0.028992 0.854939 -v -0.015500 -0.136000 0.152499 -vn -0.709493 -0.023719 0.704313 -v -0.015811 -0.136000 0.152261 -vn -0.851021 -0.021423 0.524694 -v -0.016049 -0.136000 0.151950 -vn -0.951519 -0.009598 0.307439 -v -0.016157 -0.136000 0.151719 -vn -0.913756 -0.381674 0.139195 -v -0.016242 -0.136553 0.151309 -vn -0.817783 -0.405547 0.408366 -v -0.016086 -0.136562 0.151843 -vn -0.615727 -0.417649 0.668169 -v -0.015756 -0.136568 0.152278 -vn -0.322013 -0.424822 0.846070 -v -0.015287 -0.136572 0.152567 -vn -0.307935 -0.026108 -0.951049 -v -0.015269 -0.136000 0.126793 -vn -0.520711 -0.026791 -0.853312 -v -0.015500 -0.136000 0.126901 -vn -0.702647 -0.023041 -0.711165 -v -0.015811 -0.136000 0.127139 -vn -0.952564 -0.010426 -0.304158 -v -0.016157 -0.136000 0.127681 -vn -0.854005 -0.020963 -0.519842 -v -0.016049 -0.136000 0.127450 -vn -0.177913 -0.446635 -0.876849 -v -0.014979 -0.136550 0.126748 -vn -0.445571 -0.445008 -0.776810 -v -0.015498 -0.136547 0.126931 -vn -0.671643 -0.437031 -0.598247 -v -0.015850 -0.136543 0.127213 -vn -0.850368 -0.422554 -0.313564 -v -0.016148 -0.136534 0.127691 -vn -0.807283 -0.466083 -0.362024 -v -0.016299 -0.140250 0.132400 -vn -0.807283 -0.466082 0.362024 -v -0.016299 -0.140250 0.147000 -vn -0.466085 -0.807280 -0.362028 -v -0.015750 -0.140799 0.132400 -vn -0.466084 -0.807280 0.362028 -v -0.015750 -0.140799 0.147000 -vn -0.680956 -0.732325 0.000000 -v -0.015750 -0.120400 0.139700 -vn -0.680957 -0.711043 0.175257 -v -0.015750 -0.120664 0.137522 -vn -0.680956 -0.648441 0.340328 -v -0.015750 -0.121442 0.135471 -vn -0.680956 -0.548152 0.485622 -v -0.015750 -0.122689 0.133666 -vn -0.680957 -0.416007 0.602691 -v -0.015750 -0.124331 0.132211 -vn -0.680957 -0.259687 0.684734 -v -0.015750 -0.126273 0.131191 -vn -0.680956 -0.088274 0.726985 -v -0.015750 -0.128403 0.130666 -vn -0.680956 0.088274 0.726985 -v -0.015750 -0.130597 0.130666 -vn -0.680957 0.259687 0.684734 -v -0.015750 -0.132727 0.131191 -vn -0.680956 0.416007 0.602691 -v -0.015750 -0.134669 0.132211 -vn -0.680957 0.548151 0.485622 -v -0.015750 -0.136311 0.133666 -vn -0.680956 0.648441 0.340329 -v -0.015750 -0.137558 0.135471 -vn -0.680957 0.711043 0.175257 -v -0.015750 -0.138336 0.137522 -vn -0.680956 0.732325 -0.000000 -v -0.015750 -0.138600 0.139700 -vn -0.680957 0.711043 -0.175257 -v -0.015750 -0.138336 0.141878 -vn -0.680956 0.648441 -0.340329 -v -0.015750 -0.137558 0.143929 -vn -0.680957 0.548152 -0.485620 -v -0.015750 -0.136311 0.145734 -vn -0.680956 0.416009 -0.602691 -v -0.015750 -0.134669 0.147189 -vn -0.680956 0.259685 -0.684735 -v -0.015750 -0.132727 0.148209 -vn -0.680957 0.088271 -0.726984 -v -0.015750 -0.130597 0.148734 -vn -0.680957 -0.088271 -0.726985 -v -0.015750 -0.128403 0.148734 -vn -0.680956 -0.259685 -0.684735 -v -0.015750 -0.126273 0.148209 -vn -0.680956 -0.416008 -0.602690 -v -0.015750 -0.124331 0.147189 -vn -0.680957 -0.548153 -0.485620 -v -0.015750 -0.122689 0.145734 -vn -0.680956 -0.648441 -0.340328 -v -0.015750 -0.121442 0.143929 -vn -0.680957 -0.711043 -0.175257 -v -0.015750 -0.120664 0.141878 -vn -0.740588 0.440042 0.507832 -v -0.015750 -0.125112 0.144764 -vn -0.740585 0.565292 0.363289 -v -0.015750 -0.123864 0.143322 -vn -0.740587 0.644741 0.189313 -v -0.015750 -0.123071 0.141588 -vn -0.740586 0.671961 -0.000000 -v -0.015750 -0.122800 0.139700 -vn -0.740587 0.644742 -0.189313 -v -0.015750 -0.123071 0.137812 -vn -0.740586 0.565291 -0.363289 -v -0.015750 -0.123864 0.136078 -vn -0.740585 -0.565292 0.363289 -v -0.015750 -0.135136 0.143322 -vn -0.740588 -0.440042 0.507832 -v -0.015750 -0.133888 0.144764 -vn -0.740587 -0.279141 0.611238 -v -0.015750 -0.132283 0.145795 -vn -0.740586 -0.095629 0.665122 -v -0.015750 -0.130453 0.146332 -vn -0.740586 0.095629 0.665122 -v -0.015750 -0.128546 0.146332 -vn -0.740587 0.279141 0.611238 -v -0.015750 -0.126717 0.145795 -vn -0.740587 0.440041 -0.507834 -v -0.015750 -0.125112 0.134636 -vn -0.740586 0.279144 -0.611238 -v -0.015750 -0.126717 0.133605 -vn -0.740587 0.095631 -0.665121 -v -0.015750 -0.128546 0.133068 -vn -0.740587 -0.095631 -0.665121 -v -0.015750 -0.130453 0.133068 -vn -0.740586 -0.279144 -0.611238 -v -0.015750 -0.132283 0.133605 -vn -0.740587 -0.440041 -0.507833 -v -0.015750 -0.133888 0.134636 -vn -0.740586 -0.565291 -0.363289 -v -0.015750 -0.135136 0.136078 -vn -0.740587 -0.644742 -0.189313 -v -0.015750 -0.135929 0.137812 -vn -0.740586 -0.671961 -0.000000 -v -0.015750 -0.136200 0.139700 -vn -0.740587 -0.644741 0.189313 -v -0.015750 -0.135929 0.141588 -vn -0.676434 0.736503 -0.000000 -v -0.016500 -0.122800 0.139700 -vn -0.676434 0.706670 -0.207497 -v -0.016500 -0.123071 0.137812 -vn -0.676434 0.619587 -0.398183 -v -0.016500 -0.123864 0.136078 -vn -0.676433 0.482308 -0.556612 -v -0.016500 -0.125112 0.134636 -vn -0.676434 0.305955 -0.669946 -v -0.016500 -0.126717 0.133605 -vn -0.676433 0.104817 -0.729007 -v -0.016500 -0.128546 0.133068 -vn -0.676434 -0.104817 -0.729007 -v -0.016500 -0.130453 0.133068 -vn -0.676434 -0.305955 -0.669946 -v -0.016500 -0.132283 0.133605 -vn -0.676433 -0.482308 -0.556612 -v -0.016500 -0.133888 0.134636 -vn -0.676434 -0.619587 -0.398183 -v -0.016500 -0.135136 0.136078 -vn -0.676434 -0.706670 -0.207497 -v -0.016500 -0.135929 0.137812 -vn -0.676434 -0.736503 -0.000000 -v -0.016500 -0.136200 0.139700 -vn -0.676433 -0.706670 0.207497 -v -0.016500 -0.135929 0.141588 -vn -0.676435 -0.619586 0.398182 -v -0.016500 -0.135136 0.143322 -vn -0.676433 -0.482310 0.556611 -v -0.016500 -0.133888 0.144764 -vn -0.676433 -0.305953 0.669948 -v -0.016500 -0.132283 0.145795 -vn -0.676434 -0.104814 0.729007 -v -0.016500 -0.130453 0.146332 -vn -0.676434 0.104814 0.729007 -v -0.016500 -0.128546 0.146332 -vn -0.676433 0.305953 0.669948 -v -0.016500 -0.126717 0.145795 -vn -0.676433 0.482310 0.556611 -v -0.016500 -0.125112 0.144764 -vn -0.676435 0.619586 0.398182 -v -0.016500 -0.123864 0.143322 -vn -0.676433 0.706670 0.207497 -v -0.016500 -0.123071 0.141588 -vn -0.746099 -0.163456 -0.645460 -v -0.016500 -0.128334 0.144305 -vn -0.746098 -0.364178 -0.557415 -v -0.016500 -0.126902 0.143677 -vn -0.746098 -0.525436 -0.408967 -v -0.016500 -0.125752 0.142617 -vn -0.746101 -0.629757 -0.216194 -v -0.016500 -0.125007 0.141242 -vn -0.746096 -0.665838 0.000001 -v -0.016500 -0.124750 0.139700 -vn -0.746100 -0.629758 0.216193 -v -0.016500 -0.125007 0.138158 -vn -0.746099 -0.525437 0.408966 -v -0.016500 -0.125752 0.136782 -vn -0.746098 -0.364178 0.557415 -v -0.016500 -0.126902 0.135723 -vn -0.746099 0.656754 -0.109592 -v -0.016500 -0.134185 0.140482 -vn -0.746099 0.585585 -0.316902 -v -0.016500 -0.133677 0.141961 -vn -0.746099 0.450958 -0.489871 -v -0.016500 -0.132717 0.143195 -vn -0.746099 0.267463 -0.609754 -v -0.016500 -0.131408 0.144050 -vn -0.746100 0.054982 -0.663560 -v -0.016500 -0.129892 0.144434 -vn -0.746100 -0.163452 0.645460 -v -0.016500 -0.128334 0.135095 -vn -0.746098 0.054986 0.663561 -v -0.016500 -0.129892 0.134966 -vn -0.746099 0.267463 0.609754 -v -0.016500 -0.131408 0.135350 -vn -0.746099 0.450958 0.489871 -v -0.016500 -0.132717 0.136205 -vn -0.746099 0.585585 0.316902 -v -0.016500 -0.133677 0.137439 -vn -0.746099 0.656754 0.109592 -v -0.016500 -0.134185 0.138918 -vn -0.671871 -0.740669 0.000000 -v -0.014000 -0.124750 0.139700 -vn -0.671867 -0.700541 0.240493 -v -0.014000 -0.125007 0.138158 -vn -0.671869 -0.584492 0.454931 -v -0.014000 -0.125752 0.136782 -vn -0.671869 -0.405108 0.620064 -v -0.014000 -0.126902 0.135723 -vn -0.671868 -0.181824 0.718007 -v -0.014000 -0.128334 0.135095 -vn -0.671869 0.061165 0.738140 -v -0.014000 -0.129892 0.134966 -vn -0.671869 0.297524 0.678286 -v -0.014000 -0.131408 0.135350 -vn -0.671869 0.501643 0.544929 -v -0.014000 -0.132717 0.136205 -vn -0.671869 0.651401 0.352519 -v -0.014000 -0.133677 0.137439 -vn -0.671869 0.730569 0.121909 -v -0.014000 -0.134185 0.138918 -vn -0.671869 0.730569 -0.121910 -v -0.014000 -0.134185 0.140482 -vn -0.671868 0.651401 -0.352519 -v -0.014000 -0.133677 0.141961 -vn -0.671869 0.501643 -0.544929 -v -0.014000 -0.132717 0.143195 -vn -0.671868 0.297524 -0.678286 -v -0.014000 -0.131408 0.144050 -vn -0.671868 0.061162 -0.738141 -v -0.014000 -0.129892 0.144434 -vn -0.671869 -0.181827 -0.718005 -v -0.014000 -0.128334 0.144305 -vn -0.671869 -0.405108 -0.620064 -v -0.014000 -0.126902 0.143677 -vn -0.671869 -0.584491 -0.454932 -v -0.014000 -0.125752 0.142617 -vn -0.671867 -0.700541 -0.240494 -v -0.014000 -0.125007 0.141242 -vn -1.000000 0.000000 -0.000000 -v -0.014000 -0.129500 0.139700 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 -0.113667 0.153825 -vn 0.770261 -0.637728 -0.000000 -v 0.015750 -0.113500 0.153200 -vn 0.923880 0.000000 0.382683 -v 0.015750 -0.112250 0.154700 -vn 0.987815 0.110050 0.110050 -v 0.015750 -0.117500 0.129900 -vn 0.923879 0.382686 0.000000 -v 0.015750 -0.117500 0.130575 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.130575 -vn 0.991004 -0.005386 -0.133723 -v 0.015750 -0.136000 0.127700 -vn 0.997001 -0.041898 -0.065064 -v 0.015750 -0.127500 0.127700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.129700 0.129800 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 -0.126000 0.126700 -vn 0.707107 -0.707107 0.000000 -v 0.015750 -0.126000 0.124825 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.124825 -vn 0.973781 0.131340 0.185743 -v 0.015750 -0.095500 0.152700 -vn 0.717284 0.630263 0.297108 -v 0.015750 -0.095500 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 -0.095875 0.154700 -vn 0.945446 -0.162886 -0.282136 -v 0.015750 -0.136500 0.134566 -vn 0.736823 -0.642995 -0.208922 -v 0.015750 -0.134636 0.138031 -vn 0.945449 -0.000000 -0.325770 -v 0.015750 -0.137000 0.134700 -vn 0.736825 -0.676083 0.000000 -v 0.015750 -0.134900 0.139700 -vn 0.945451 0.162881 -0.282120 -v 0.015750 -0.137500 0.134566 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.129700 0.130575 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.129700 0.133625 -vn 0.945437 -0.325804 -0.000003 -v 0.015750 -0.136000 0.133700 -vn 0.945447 -0.282132 0.162887 -v 0.015750 -0.136134 0.133200 -vn 0.945447 -0.162887 0.282132 -v 0.015750 -0.136500 0.132834 -vn 0.990581 -0.130229 -0.042314 -v 0.015750 -0.139804 0.130464 -vn 0.945449 -0.000001 0.325771 -v 0.015750 -0.137000 0.132700 -vn 0.945453 0.162885 0.282113 -v 0.015750 -0.137500 0.132834 -vn 0.945444 0.282138 -0.162894 -v 0.015750 -0.137866 0.134200 -vn 0.991445 -0.130527 0.000000 -v 0.015750 -0.140000 0.139700 -vn 0.945448 0.325774 -0.000002 -v 0.015750 -0.138000 0.133700 -vn 0.991445 -0.130527 0.000000 -v 0.015750 -0.140000 0.133625 -vn 0.945438 0.282151 0.162903 -v 0.015750 -0.137866 0.133200 -vn 0.991004 -0.133726 -0.005386 -v 0.015750 -0.140000 0.131700 -vn 0.990581 -0.135244 -0.021420 -v 0.015750 -0.139951 0.131074 -vn 0.770260 -0.318865 -0.552291 -v 0.015750 -0.122125 0.127283 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 -0.121667 0.126825 -vn 0.973781 0.131340 -0.185743 -v 0.015750 -0.119500 0.126700 -vn 0.770261 -0.637729 -0.000000 -v 0.015750 -0.121500 0.126200 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.119500 0.124825 -vn 0.770261 -0.552291 0.318862 -v 0.015750 -0.121667 0.125575 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.124825 -vn 0.770265 -0.318861 0.552286 -v 0.015750 -0.122125 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.015750 -0.122750 0.124950 -vn 0.770265 0.318861 0.552286 -v 0.015750 -0.123375 0.125117 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.123833 0.125575 -vn 0.770264 -0.000000 -0.637725 -v 0.015750 -0.122750 0.127450 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.129800 -vn 0.770260 0.318866 -0.552291 -v 0.015750 -0.123375 0.127283 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.129800 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.123833 0.126825 -vn 0.770261 0.637728 0.000000 -v 0.015750 -0.124000 0.126200 -vn 0.770261 -0.318865 -0.552289 -v 0.015750 -0.106125 0.127283 -vn 0.973781 0.131340 -0.185743 -v 0.015750 -0.103500 0.126700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.106250 0.129800 -vn 0.770266 -0.318854 -0.552289 -v 0.015750 -0.103850 0.129740 -vn 0.770258 -0.552288 -0.318875 -v 0.015750 -0.103960 0.129850 -vn 0.770261 -0.552288 -0.318867 -v 0.015750 -0.105667 0.126825 -vn 0.770264 -0.637725 0.000000 -v 0.015750 -0.105500 0.126200 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.103500 0.124825 -vn 0.770258 -0.552293 0.318864 -v 0.015750 -0.105667 0.125575 -vn 1.000000 0.000001 -0.000001 -v 0.015750 -0.106250 0.124825 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 -0.110000 0.126700 -vn 0.707107 -0.707107 -0.000000 -v 0.015750 -0.110000 0.124825 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.107833 0.125575 -vn 0.770261 0.637728 0.000000 -v 0.015750 -0.108000 0.126200 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.107833 0.126825 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.110000 0.129800 -vn 0.770260 0.318866 -0.552290 -v 0.015750 -0.107375 0.127283 -vn 0.770264 0.000002 -0.637725 -v 0.015750 -0.106750 0.127450 -vn 0.770266 -0.318861 0.552284 -v 0.015750 -0.106125 0.125117 -vn 0.770262 0.000002 0.637727 -v 0.015750 -0.106750 0.124950 -vn 0.770265 0.318861 0.552287 -v 0.015750 -0.107375 0.125117 -vn 0.770264 0.637725 -0.000000 -v 0.015750 -0.094750 0.131700 -vn 0.770259 0.552293 -0.318864 -v 0.015750 -0.094583 0.132325 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.095875 0.133625 -vn 0.770266 0.318862 -0.552284 -v 0.015750 -0.094125 0.132783 -vn 0.770258 0.000001 -0.637732 -v 0.015750 -0.093500 0.132950 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.092000 0.133625 -vn 0.770266 -0.318861 -0.552284 -v 0.015750 -0.092875 0.132783 -vn 0.770259 -0.552293 -0.318864 -v 0.015750 -0.092417 0.132325 -vn 0.770264 -0.637725 0.000000 -v 0.015750 -0.092250 0.131700 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.092000 0.130575 -vn 0.770261 -0.552288 0.318867 -v 0.015750 -0.092417 0.131075 -vn 0.770261 -0.318866 0.552288 -v 0.015750 -0.092875 0.130617 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.092000 0.129800 -vn 0.770264 0.000001 0.637725 -v 0.015750 -0.093500 0.130450 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.095875 0.129800 -vn 0.770261 0.318867 0.552288 -v 0.015750 -0.094125 0.130617 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.095875 0.130575 -vn 0.770261 0.552288 0.318867 -v 0.015750 -0.094583 0.131075 -vn 0.923880 0.000000 0.382683 -v 0.015750 -0.116750 0.154700 -vn 0.717284 -0.630263 0.297108 -v 0.015750 -0.118000 0.154700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.150825 -vn 0.973781 -0.131340 0.185743 -v 0.015750 -0.118000 0.152700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.150825 -vn 0.973781 0.131340 0.185743 -v 0.015750 -0.119500 0.152700 -vn 0.770261 -0.552291 0.318862 -v 0.015750 -0.121667 0.152575 -vn 0.770265 -0.318861 0.552286 -v 0.015750 -0.122125 0.152117 -vn 0.770258 0.000000 0.637732 -v 0.015750 -0.122750 0.151950 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.150825 -vn 0.923880 0.000000 0.382683 -v 0.015750 -0.124050 0.154700 -vn 0.770261 0.637728 -0.000000 -v 0.015750 -0.124000 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.123833 0.153825 -vn 0.770265 0.318861 0.552286 -v 0.015750 -0.123375 0.152117 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.123833 0.152575 -vn 0.770260 0.318866 -0.552291 -v 0.015750 -0.123375 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.015750 -0.122750 0.154450 -vn 0.923880 0.000000 0.382683 -v 0.015750 -0.122000 0.154700 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 -0.122125 0.154283 -vn 0.717284 0.630263 0.297108 -v 0.015750 -0.119500 0.154700 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 -0.121667 0.153825 -vn 0.770261 -0.637728 0.000000 -v 0.015750 -0.121500 0.153200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.102000 0.150825 -vn 0.973781 -0.131340 0.185743 -v 0.015750 -0.102000 0.152700 -vn 1.000000 0.000000 -0.000000 -v 0.015750 -0.106250 0.150825 -vn 0.973781 0.131340 0.185743 -v 0.015750 -0.103500 0.152700 -vn 0.770259 -0.552293 0.318864 -v 0.015750 -0.105667 0.152575 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.107833 0.153825 -vn 0.717284 -0.630262 0.297108 -v 0.015750 -0.110000 0.154700 -vn 0.770261 0.637729 0.000000 -v 0.015750 -0.108000 0.153200 -vn 0.973781 -0.131340 0.185743 -v 0.015750 -0.110000 0.152700 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.107833 0.152575 -vn 0.770260 0.318866 -0.552291 -v 0.015750 -0.107375 0.154283 -vn 0.770266 0.000002 -0.637723 -v 0.015750 -0.106750 0.154450 -vn 0.923880 0.000001 0.382683 -v 0.015750 -0.106250 0.154700 -vn 0.770261 -0.318866 -0.552289 -v 0.015750 -0.106125 0.154283 -vn 0.717284 0.630263 0.297108 -v 0.015750 -0.103500 0.154700 -vn 0.770261 -0.552288 -0.318867 -v 0.015750 -0.105667 0.153825 -vn 0.770264 -0.637725 -0.000000 -v 0.015750 -0.105500 0.153200 -vn 0.770265 0.318861 0.552286 -v 0.015750 -0.107375 0.152117 -vn 1.000000 0.000000 -0.000000 -v 0.015750 -0.110000 0.150825 -vn 0.770259 0.000002 0.637732 -v 0.015750 -0.106750 0.151950 -vn 0.770266 -0.318861 0.552285 -v 0.015750 -0.106125 0.152117 -vn 1.000000 -0.000000 0.000000 -v 0.015750 -0.095875 0.149600 -vn 0.770267 0.552290 0.318849 -v 0.015750 -0.097040 0.149550 -vn 0.737695 0.669360 0.088109 -v 0.015750 -0.097000 0.149400 -vn 1.000000 -0.000000 0.000000 -v 0.015750 -0.095875 0.145775 -vn 0.770261 -0.552288 0.318866 -v 0.015750 -0.103960 0.149550 -vn 0.770266 -0.318854 0.552289 -v 0.015750 -0.103850 0.149660 -vn 0.737697 -0.088113 0.669358 -v 0.015750 -0.103700 0.149700 -vn 0.707107 0.000000 0.707107 -v 0.015750 -0.102000 0.149700 -vn 0.737697 0.088113 0.669358 -v 0.015750 -0.097300 0.149700 -vn 0.707107 -0.707107 0.000000 -v 0.015750 -0.104000 0.145775 -vn 0.737701 -0.669352 0.088124 -v 0.015750 -0.104000 0.149400 -vn 1.000000 0.000001 0.000001 -v 0.015750 -0.106250 0.149600 -vn 0.707107 0.000000 -0.707107 -v 0.015750 -0.102000 0.143700 -vn 0.737697 -0.088113 -0.669358 -v 0.015750 -0.103700 0.143700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.106250 0.139700 -vn 0.770266 -0.318854 -0.552289 -v 0.015750 -0.103850 0.143740 -vn 0.770258 -0.552288 -0.318875 -v 0.015750 -0.103960 0.143850 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.106250 0.144200 -vn 0.737704 -0.669347 -0.088131 -v 0.015750 -0.104000 0.144000 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.097000 0.145775 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.097000 0.144200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.095875 0.144200 -vn 0.737698 0.669356 -0.088117 -v 0.015750 -0.097000 0.144000 -vn 0.717284 0.630263 0.297108 -v 0.015750 -0.111500 0.154700 -vn 0.973781 0.131340 0.185743 -v 0.015750 -0.111500 0.152700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.112250 0.150825 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.092000 0.150825 -vn 0.717284 0.297108 0.630263 -v 0.015750 -0.092000 0.150950 -vn 0.973781 0.185743 0.131340 -v 0.015750 -0.094000 0.150950 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.095875 0.150825 -vn 0.816496 0.408249 0.408249 -v 0.015750 -0.094000 0.152700 -vn 0.717284 0.297108 -0.630262 -v 0.015750 -0.092000 0.144450 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.092000 0.145775 -vn 0.973781 0.185743 -0.131340 -v 0.015750 -0.094000 0.144450 -vn 0.923879 0.382684 0.000000 -v 0.015750 -0.094000 0.144200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.095875 0.139700 -vn 0.770264 0.552289 -0.318858 -v 0.015750 -0.097040 0.143850 -vn 0.717284 0.297108 0.630263 -v 0.015750 -0.092000 0.134950 -vn 0.973781 0.185743 0.131340 -v 0.015750 -0.094000 0.134950 -vn 0.923879 0.382684 0.000000 -v 0.015750 -0.094000 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.095875 0.124825 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.095500 0.124825 -vn 0.973781 0.131340 -0.185743 -v 0.015750 -0.095500 0.126700 -vn 0.717284 0.297108 -0.630263 -v 0.015750 -0.092000 0.128450 -vn 0.973781 0.185743 -0.131340 -v 0.015750 -0.094000 0.128450 -vn 0.816496 0.408249 -0.408249 -v 0.015750 -0.094000 0.126700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.112250 0.124825 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.111500 0.124825 -vn 0.973781 0.131340 -0.185743 -v 0.015750 -0.111500 0.126700 -vn 0.717284 0.630262 -0.297108 -v 0.015750 -0.111500 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 -0.112250 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 -0.116750 0.124700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.129800 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 -0.118000 0.126700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.124825 -vn 0.707107 -0.707107 0.000000 -v 0.015750 -0.118000 0.124825 -vn 0.717284 -0.630263 -0.297108 -v 0.015750 -0.118000 0.124700 -vn 0.717283 -0.630262 -0.297109 -v 0.015750 -0.127500 0.126700 -vn 0.990581 -0.122005 -0.062166 -v 0.015750 -0.139564 0.129884 -vn 0.990581 -0.110778 -0.080484 -v 0.015750 -0.139236 0.129349 -vn 0.990581 -0.021420 -0.135241 -v 0.015750 -0.136626 0.127749 -vn 0.990581 -0.042315 -0.130229 -v 0.015750 -0.137236 0.127896 -vn 0.990581 -0.096822 -0.096822 -v 0.015750 -0.138828 0.128872 -vn 0.990581 -0.080483 -0.110776 -v 0.015750 -0.138351 0.128464 -vn 0.990581 -0.062165 -0.122004 -v 0.015750 -0.137816 0.128136 -vn 0.945437 -0.325804 -0.000003 -v 0.015750 -0.136000 0.145700 -vn 1.000000 -0.000000 0.000000 -v 0.015750 -0.129700 0.145775 -vn 0.945453 -0.282119 -0.162876 -v 0.015750 -0.136134 0.146200 -vn 1.000000 -0.000000 0.000000 -v 0.015750 -0.129700 0.149600 -vn 0.945438 -0.162897 -0.282156 -v 0.015750 -0.136500 0.146566 -vn 0.945448 -0.000004 -0.325773 -v 0.015750 -0.137000 0.146700 -vn 0.990581 -0.080484 0.110777 -v 0.015750 -0.138351 0.150936 -vn 0.990581 -0.096824 0.096823 -v 0.015750 -0.138828 0.150528 -vn 0.945443 0.162897 -0.282138 -v 0.015750 -0.137500 0.146566 -vn 0.990581 -0.122003 0.062165 -v 0.015750 -0.139564 0.149516 -vn 0.990581 -0.110779 0.080485 -v 0.015750 -0.139236 0.150051 -vn 0.991004 -0.005386 0.133726 -v 0.015750 -0.136000 0.151700 -vn 0.990581 -0.021421 0.135244 -v 0.015750 -0.136626 0.151651 -vn 0.990581 -0.042314 0.130224 -v 0.015750 -0.137236 0.151504 -vn 0.717284 -0.630263 0.297108 -v 0.015750 -0.126000 0.154700 -vn 0.973781 -0.131340 0.185743 -v 0.015750 -0.126000 0.152700 -vn 0.717283 -0.630262 0.297109 -v 0.015750 -0.127500 0.152700 -vn 0.997001 -0.041899 0.065065 -v 0.015750 -0.127500 0.151700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.129700 0.150825 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 -0.102000 0.126700 -vn 0.707107 -0.707107 0.000000 -v 0.015750 -0.102000 0.124825 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.099833 0.125575 -vn 0.770261 0.637728 -0.000000 -v 0.015750 -0.100000 0.126200 -vn 0.707107 0.000000 -0.707107 -v 0.015750 -0.102000 0.129700 -vn 0.737697 -0.088113 -0.669358 -v 0.015750 -0.103700 0.129700 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.099833 0.126825 -vn 0.770260 0.318866 -0.552291 -v 0.015750 -0.099375 0.127283 -vn 0.737697 0.088113 -0.669358 -v 0.015750 -0.097300 0.129700 -vn 0.770264 0.000000 -0.637725 -v 0.015750 -0.098750 0.127450 -vn 0.770265 0.318854 -0.552289 -v 0.015750 -0.097150 0.129740 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 -0.098125 0.127283 -vn 0.770262 -0.552286 -0.318869 -v 0.015750 -0.097667 0.126825 -vn 0.770264 -0.637725 0.000000 -v 0.015750 -0.097500 0.126200 -vn 0.770260 -0.552291 0.318866 -v 0.015750 -0.097667 0.125575 -vn 0.770265 -0.318861 0.552286 -v 0.015750 -0.098125 0.125117 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.097250 0.124825 -vn 0.770258 0.000000 0.637732 -v 0.015750 -0.098750 0.124950 -vn 0.770265 0.318861 0.552286 -v 0.015750 -0.099375 0.125117 -vn 0.770264 0.552289 -0.318858 -v 0.015750 -0.097040 0.129850 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.097000 0.130575 -vn 0.737698 0.669356 -0.088117 -v 0.015750 -0.097000 0.130000 -vn 0.737697 0.088113 0.669358 -v 0.015750 -0.097300 0.135700 -vn 0.770266 0.318854 0.552289 -v 0.015750 -0.097150 0.135660 -vn 0.770267 0.552290 0.318849 -v 0.015750 -0.097040 0.135550 -vn 0.737695 0.669360 0.088109 -v 0.015750 -0.097000 0.135400 -vn 0.707107 0.707107 0.000000 -v 0.015750 -0.097000 0.133625 -vn 0.737697 -0.088113 0.669358 -v 0.015750 -0.103700 0.135700 -vn 0.707107 0.000000 0.707107 -v 0.015750 -0.102000 0.135700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.102000 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.097250 0.139700 -vn 0.770266 0.318854 -0.552289 -v 0.015750 -0.097150 0.143740 -vn 0.770266 -0.318854 0.552289 -v 0.015750 -0.103850 0.135660 -vn 0.737697 0.088113 -0.669358 -v 0.015750 -0.097300 0.143700 -vn 0.737704 -0.669347 -0.088131 -v 0.015750 -0.104000 0.130000 -vn 0.707107 -0.707107 0.000000 -v 0.015750 -0.104000 0.130575 -vn 1.000000 0.000001 -0.000000 -v 0.015750 -0.106250 0.130575 -vn 0.707107 -0.707107 0.000000 -v 0.015750 -0.104000 0.133625 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.106250 0.133625 -vn 0.737701 -0.669352 0.088124 -v 0.015750 -0.104000 0.135400 -vn 0.770261 -0.552288 0.318866 -v 0.015750 -0.103960 0.135550 -vn 0.973781 0.185742 0.131340 -v 0.015750 -0.117500 0.140200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.144200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.110000 0.145775 -vn 0.923880 -0.382683 0.000000 -v 0.015750 -0.111000 0.145775 -vn 0.923880 -0.382683 0.000000 -v 0.015750 -0.111000 0.144200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.112250 0.149600 -vn 0.923881 0.000000 -0.382680 -v 0.015750 -0.112250 0.149500 -vn 0.987815 -0.110050 -0.110050 -v 0.015750 -0.111000 0.149500 -vn 1.000000 -0.000000 0.000000 -v 0.015750 -0.110000 0.149600 -vn 0.923881 0.000000 -0.382679 -v 0.015750 -0.116750 0.149500 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.149600 -vn 0.987815 0.110049 -0.110050 -v 0.015750 -0.117500 0.149500 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.133625 -vn 0.923880 0.382683 -0.000000 -v 0.015750 -0.117500 0.133625 -vn 0.973781 0.185742 -0.131340 -v 0.015750 -0.117500 0.139200 -vn 0.707107 0.000000 -0.707107 -v 0.015750 -0.116750 0.139200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.112250 0.139700 -vn 0.707107 0.000000 -0.707107 -v 0.015750 -0.112250 0.139200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.110000 0.139700 -vn 0.973781 -0.185743 -0.131340 -v 0.015750 -0.111000 0.139200 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.110000 0.133625 -vn 0.923880 -0.382683 -0.000000 -v 0.015750 -0.111000 0.133625 -vn 0.923878 -0.382686 0.000000 -v 0.015750 -0.111000 0.130575 -vn 0.736824 0.546965 -0.397391 -v 0.015750 -0.125131 0.136526 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.133625 -vn 0.736824 0.642995 -0.208922 -v 0.015750 -0.124364 0.138031 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.139700 -vn 0.736824 0.397392 -0.546965 -v 0.015750 -0.126326 0.135331 -vn 0.736823 0.208922 -0.642996 -v 0.015750 -0.127831 0.134564 -vn 0.736825 0.000000 -0.676083 -v 0.015750 -0.129500 0.134300 -vn 0.736823 -0.208922 -0.642996 -v 0.015750 -0.131169 0.134564 -vn 0.945453 -0.282115 -0.162877 -v 0.015750 -0.136134 0.134200 -vn 0.736824 -0.397392 -0.546965 -v 0.015750 -0.132674 0.135331 -vn 0.736824 -0.546965 -0.397392 -v 0.015750 -0.133869 0.136526 -vn 0.736823 0.397393 0.546965 -v 0.015750 -0.126326 0.144069 -vn 0.736826 0.546962 0.397391 -v 0.015750 -0.125131 0.142874 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.144200 -vn 0.736823 0.642996 0.208920 -v 0.015750 -0.124364 0.141369 -vn 0.736824 0.676085 0.000000 -v 0.015750 -0.124100 0.139700 -vn 0.945448 -0.162882 0.282131 -v 0.015750 -0.136500 0.144834 -vn 0.945446 -0.000001 0.325778 -v 0.015750 -0.137000 0.144700 -vn 0.736823 -0.397393 0.546965 -v 0.015750 -0.132674 0.144069 -vn 0.991445 -0.130528 0.000000 -v 0.015750 -0.140000 0.144200 -vn 0.736826 -0.546962 0.397392 -v 0.015750 -0.133869 0.142874 -vn 0.736825 0.208922 0.642993 -v 0.015750 -0.127831 0.144836 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.145775 -vn 0.736822 0.000000 0.676086 -v 0.015750 -0.129500 0.145100 -vn 0.736825 -0.208922 0.642993 -v 0.015750 -0.131169 0.144836 -vn 0.945447 -0.282132 0.162887 -v 0.015750 -0.136134 0.145200 -vn 0.990581 -0.130228 0.042316 -v 0.015750 -0.139804 0.148936 -vn 0.990581 -0.135245 0.021421 -v 0.015750 -0.139951 0.148326 -vn 0.945444 0.282138 -0.162894 -v 0.015750 -0.137866 0.146200 -vn 0.991004 -0.133727 0.005386 -v 0.015750 -0.140000 0.147700 -vn 0.945448 0.325774 -0.000002 -v 0.015750 -0.138000 0.145700 -vn 0.991445 -0.130528 0.000000 -v 0.015750 -0.140000 0.145775 -vn 0.945438 0.282151 0.162903 -v 0.015750 -0.137866 0.145200 -vn 0.945454 0.162879 0.282113 -v 0.015750 -0.137500 0.144834 -vn 0.736823 -0.642996 0.208921 -v 0.015750 -0.134636 0.141369 -vn 0.945443 -0.325787 -0.000001 -v 0.015750 -0.122500 0.131700 -vn 0.945447 -0.282132 0.162887 -v 0.015750 -0.122634 0.131200 -vn 0.945438 -0.162897 -0.282156 -v 0.015750 -0.123000 0.132566 -vn 0.945452 -0.282119 -0.162879 -v 0.015750 -0.122634 0.132200 -vn 0.945448 0.325773 -0.000001 -v 0.015750 -0.124500 0.131700 -vn 0.945448 0.282125 -0.162889 -v 0.015750 -0.124366 0.132200 -vn 0.945441 0.162900 -0.282145 -v 0.015750 -0.124000 0.132566 -vn 0.945448 -0.000004 -0.325773 -v 0.015750 -0.123500 0.132700 -vn 0.945448 -0.162882 0.282131 -v 0.015750 -0.123000 0.130834 -vn 0.945437 -0.000004 0.325805 -v 0.015750 -0.123500 0.130700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.124050 0.130575 -vn 0.945450 0.162885 0.282123 -v 0.015750 -0.124000 0.130834 -vn 0.945442 0.282142 0.162895 -v 0.015750 -0.124366 0.131200 -vn 0.945447 -0.282132 0.162887 -v 0.015750 -0.122634 0.147200 -vn 0.945447 -0.162887 0.282132 -v 0.015750 -0.123000 0.146834 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.145775 -vn 0.945443 -0.325786 -0.000001 -v 0.015750 -0.122500 0.147700 -vn 1.000000 -0.000000 0.000001 -v 0.015750 -0.124050 0.149600 -vn 0.945449 -0.000000 -0.325769 -v 0.015750 -0.123500 0.148700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.122000 0.149600 -vn 0.945446 -0.162886 -0.282135 -v 0.015750 -0.123000 0.148566 -vn 0.945453 -0.282115 -0.162880 -v 0.015750 -0.122634 0.148200 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.117500 0.145775 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.117500 0.144200 -vn 0.945448 0.282125 -0.162889 -v 0.015750 -0.124366 0.148200 -vn 0.945449 0.162883 -0.282125 -v 0.015750 -0.124000 0.148566 -vn 0.945449 -0.000001 0.325771 -v 0.015750 -0.123500 0.146700 -vn 0.945450 0.162886 0.282123 -v 0.015750 -0.124000 0.146834 -vn 0.945442 0.282141 0.162895 -v 0.015750 -0.124366 0.147200 -vn 0.945448 0.325772 -0.000001 -v 0.015750 -0.124500 0.147700 -vn 0.717284 0.630263 -0.297108 -v 0.015750 -0.119500 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 -0.122000 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 -0.124050 0.124700 -vn 0.717284 -0.630263 -0.297108 -v 0.015750 -0.126000 0.124700 -vn 0.717284 0.630263 -0.297108 -v 0.015750 -0.103500 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 -0.106250 0.124700 -vn 0.717284 -0.630262 -0.297108 -v 0.015750 -0.110000 0.124700 -vn 0.717284 0.630263 -0.297108 -v 0.015750 -0.095500 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 -0.095875 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 -0.097250 0.124700 -vn 0.717284 -0.630263 -0.297108 -v 0.015750 -0.102000 0.124700 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.112250 0.129800 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 -0.113667 0.126825 -vn 0.770261 -0.637728 -0.000000 -v 0.015750 -0.113500 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.015750 -0.113667 0.125575 -vn 0.770265 -0.318861 0.552286 -v 0.015750 -0.114125 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.015750 -0.114750 0.124950 -vn 0.770265 0.318861 0.552286 -v 0.015750 -0.115375 0.125117 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.115833 0.126825 -vn 0.770261 0.637728 0.000000 -v 0.015750 -0.116000 0.126200 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.115833 0.125575 -vn 0.770260 0.318865 -0.552291 -v 0.015750 -0.115375 0.127283 -vn 0.770264 0.000000 -0.637725 -v 0.015750 -0.114750 0.127450 -vn 0.770260 -0.318865 -0.552291 -v 0.015750 -0.114125 0.127283 -vn 1.000000 0.000000 -0.000000 -v 0.015750 -0.110000 0.130575 -vn 0.945449 -0.325770 0.000003 -v 0.015750 -0.107000 0.131700 -vn 0.945442 -0.282143 0.162892 -v 0.015750 -0.107134 0.131200 -vn 0.945447 0.282132 0.162885 -v 0.015750 -0.108866 0.131200 -vn 0.945443 0.325788 0.000003 -v 0.015750 -0.109000 0.131700 -vn 0.945451 -0.162879 0.282124 -v 0.015750 -0.107500 0.130834 -vn 0.945438 -0.000003 0.325801 -v 0.015750 -0.108000 0.130700 -vn 0.945450 0.162885 0.282123 -v 0.015750 -0.108500 0.130834 -vn 0.987815 -0.110050 0.110051 -v 0.015750 -0.111000 0.129900 -vn 0.923881 0.000000 0.382681 -v 0.015750 -0.112250 0.129900 -vn 0.923881 0.000000 0.382680 -v 0.015750 -0.116750 0.129900 -vn 0.945452 0.282115 -0.162883 -v 0.015750 -0.108866 0.132200 -vn 0.945441 0.162901 -0.282143 -v 0.015750 -0.108500 0.132566 -vn 0.945448 -0.000003 -0.325773 -v 0.015750 -0.108000 0.132700 -vn 0.945448 -0.282128 -0.162889 -v 0.015750 -0.107134 0.132200 -vn 0.945441 -0.162895 -0.282146 -v 0.015750 -0.107500 0.132566 -vn 1.000000 0.000000 -0.000000 -v 0.015750 -0.106250 0.145775 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.110000 0.144200 -vn 0.973781 -0.185742 0.131340 -v 0.015750 -0.111000 0.140200 -vn 0.707107 0.000000 0.707107 -v 0.015750 -0.112250 0.140200 -vn 0.707107 0.000000 0.707107 -v 0.015750 -0.116750 0.140200 -vn 0.945449 -0.325770 0.000002 -v 0.015750 -0.107000 0.147700 -vn 0.945442 -0.282144 0.162892 -v 0.015750 -0.107134 0.147200 -vn 0.945449 -0.282124 -0.162890 -v 0.015750 -0.107134 0.148200 -vn 0.707107 -0.707107 0.000000 -v 0.015750 -0.104000 0.144200 -vn 0.945450 0.162886 0.282123 -v 0.015750 -0.108500 0.146834 -vn 0.945449 -0.000000 0.325770 -v 0.015750 -0.108000 0.146700 -vn 0.945449 -0.162884 0.282125 -v 0.015750 -0.107500 0.146834 -vn 0.945447 0.282132 0.162885 -v 0.015750 -0.108866 0.147200 -vn 0.945443 0.325788 0.000003 -v 0.015750 -0.109000 0.147700 -vn 0.945453 0.282115 -0.162883 -v 0.015750 -0.108866 0.148200 -vn 0.945450 0.162884 -0.282124 -v 0.015750 -0.108500 0.148566 -vn 0.945449 0.000001 -0.325769 -v 0.015750 -0.108000 0.148700 -vn 0.945449 -0.162884 -0.282125 -v 0.015750 -0.107500 0.148566 -vn 0.770261 -0.552288 0.318867 -v 0.015750 -0.092417 0.147075 -vn 0.770265 -0.637724 0.000000 -v 0.015750 -0.092250 0.147700 -vn 0.923880 0.382683 0.000000 -v 0.015750 -0.092000 0.149600 -vn 0.770259 -0.552292 -0.318864 -v 0.015750 -0.092417 0.148325 -vn 0.770267 -0.318861 -0.552283 -v 0.015750 -0.092875 0.148783 -vn 0.770261 0.318867 0.552288 -v 0.015750 -0.094125 0.146617 -vn 0.770264 0.000001 0.637725 -v 0.015750 -0.093500 0.146450 -vn 0.770261 -0.318866 0.552288 -v 0.015750 -0.092875 0.146617 -vn 0.770266 0.318862 -0.552283 -v 0.015750 -0.094125 0.148783 -vn 0.770259 0.000001 -0.637731 -v 0.015750 -0.093500 0.148950 -vn 0.770261 0.552288 0.318867 -v 0.015750 -0.094583 0.147075 -vn 0.770264 0.637725 0.000000 -v 0.015750 -0.094750 0.147700 -vn 0.770259 0.552293 -0.318864 -v 0.015750 -0.094583 0.148325 -vn 0.990581 -0.062164 0.122007 -v 0.015750 -0.137816 0.151264 -vn 0.770258 0.000000 0.637732 -v 0.015750 -0.114750 0.151950 -vn 0.770265 0.318861 0.552286 -v 0.015750 -0.115375 0.152117 -vn 0.770261 -0.552291 0.318862 -v 0.015750 -0.113667 0.152575 -vn 0.770265 -0.318861 0.552286 -v 0.015750 -0.114125 0.152117 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.115833 0.152575 -vn 0.770261 0.637728 0.000000 -v 0.015750 -0.116000 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.115833 0.153825 -vn 0.770260 0.318866 -0.552291 -v 0.015750 -0.115375 0.154283 -vn 0.770264 -0.000000 -0.637725 -v 0.015750 -0.114750 0.154450 -vn 0.770260 -0.318865 -0.552291 -v 0.015750 -0.114125 0.154283 -vn 0.770263 0.552286 -0.318865 -v 0.015750 -0.099833 0.153825 -vn 0.717284 -0.630262 0.297108 -v 0.015750 -0.102000 0.154700 -vn 0.770261 0.637728 -0.000000 -v 0.015750 -0.100000 0.153200 -vn 0.770261 0.552291 0.318862 -v 0.015750 -0.099833 0.152575 -vn 0.770265 0.318861 0.552286 -v 0.015750 -0.099375 0.152117 -vn 0.770260 0.318866 -0.552291 -v 0.015750 -0.099375 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.015750 -0.098750 0.154450 -vn 0.923880 0.000000 0.382683 -v 0.015750 -0.097250 0.154700 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 -0.098125 0.154283 -vn 0.770262 -0.552286 -0.318869 -v 0.015750 -0.097667 0.153825 -vn 0.770264 -0.637725 -0.000000 -v 0.015750 -0.097500 0.153200 -vn 0.770260 -0.552291 0.318866 -v 0.015750 -0.097667 0.152575 -vn 1.000000 0.000000 0.000000 -v 0.015750 -0.097250 0.150825 -vn 0.770265 -0.318861 0.552286 -v 0.015750 -0.098125 0.152117 -vn 0.770258 -0.000000 0.637732 -v 0.015750 -0.098750 0.151950 -vn 0.770266 0.318854 0.552289 -v 0.015750 -0.097150 0.149660 -vn -0.301511 0.301511 -0.904534 -v 0.013750 -0.124750 0.123700 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.123375 0.125117 -vn -0.770258 -0.000000 0.637732 -v 0.013750 -0.122750 0.124950 -vn -0.609994 -0.000001 -0.792406 -v 0.013750 -0.122750 0.128509 -vn -0.770264 0.000000 -0.637725 -v 0.013750 -0.122750 0.127450 -vn -0.770260 0.318865 -0.552291 -v 0.013750 -0.123375 0.127283 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 -0.120750 0.123700 -vn -0.770265 -0.318861 0.552286 -v 0.013750 -0.122125 0.125117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 -0.121667 0.125575 -vn -0.609995 -0.686244 -0.396202 -v 0.013750 -0.120750 0.127355 -vn -0.609994 0.686244 -0.396202 -v 0.013750 -0.124750 0.127355 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.123833 0.126825 -vn -0.770261 0.637728 -0.000000 -v 0.013750 -0.124000 0.126200 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.123833 0.125575 -vn -0.770261 -0.637729 0.000000 -v 0.013750 -0.121500 0.126200 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 -0.121667 0.126825 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 -0.122125 0.127283 -vn -0.609995 -0.686244 -0.396202 -v 0.013750 -0.112750 0.127355 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 -0.113667 0.126825 -vn -0.609994 -0.000001 -0.792406 -v 0.013750 -0.114750 0.128509 -vn -0.770260 -0.318865 -0.552291 -v 0.013750 -0.114125 0.127283 -vn -0.609994 0.686244 -0.396202 -v 0.013750 -0.116750 0.127355 -vn -0.770261 0.637728 -0.000000 -v 0.013750 -0.116000 0.126200 -vn -0.301511 0.301511 -0.904534 -v 0.013750 -0.116750 0.123700 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.115833 0.125575 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.115375 0.125117 -vn -0.770258 0.000000 0.637732 -v 0.013750 -0.114750 0.124950 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 -0.112750 0.123700 -vn -0.770265 -0.318861 0.552287 -v 0.013750 -0.114125 0.125117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 -0.113667 0.125575 -vn -0.770261 -0.637728 0.000000 -v 0.013750 -0.113500 0.126200 -vn -0.770264 -0.000000 -0.637725 -v 0.013750 -0.114750 0.127450 -vn -0.770260 0.318866 -0.552291 -v 0.013750 -0.115375 0.127283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.115833 0.126825 -vn -0.609995 0.686244 -0.396202 -v 0.013750 -0.108750 0.127355 -vn -0.770261 0.637728 -0.000000 -v 0.013750 -0.108000 0.126200 -vn -0.301511 0.301511 -0.904534 -v 0.013750 -0.108750 0.123700 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.107833 0.125575 -vn -0.609994 0.000001 -0.792406 -v 0.013750 -0.106750 0.128509 -vn -0.770260 0.318866 -0.552291 -v 0.013750 -0.107375 0.127283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.107833 0.126825 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.107375 0.125117 -vn -0.770258 0.000001 0.637732 -v 0.013750 -0.106750 0.124950 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 -0.104750 0.123700 -vn -0.770264 -0.637725 0.000000 -v 0.013750 -0.105500 0.126200 -vn -0.609994 -0.686244 -0.396203 -v 0.013750 -0.104750 0.127355 -vn -0.770259 -0.552293 0.318864 -v 0.013750 -0.105667 0.125575 -vn -0.770266 -0.318861 0.552284 -v 0.013750 -0.106125 0.125117 -vn -0.770261 -0.552288 -0.318867 -v 0.013750 -0.105667 0.126825 -vn -0.770261 -0.318866 -0.552288 -v 0.013750 -0.106125 0.127283 -vn -0.770264 0.000001 -0.637726 -v 0.013750 -0.106750 0.127450 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.136850 0.128975 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.102000 0.154200 -vn -0.717284 -0.630263 0.297108 -v 0.010750 -0.102000 0.154700 -vn -0.741788 0.516596 0.427644 -v 0.010750 -0.100750 0.154700 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.111500 0.125200 -vn -0.717284 0.630263 -0.297108 -v 0.010750 -0.111500 0.124700 -vn -0.741788 -0.516596 -0.427644 -v 0.010750 -0.112750 0.124700 -vn -0.741788 0.516596 -0.427644 -v 0.010750 -0.124750 0.124700 -vn -0.717284 -0.630263 -0.297108 -v 0.010750 -0.126000 0.124700 -vn -0.846478 0.279911 -0.452907 -v 0.010750 -0.123750 0.126700 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.126000 0.125200 -vn -0.707107 0.000000 -0.707107 -v 0.010750 -0.126325 0.125200 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.128975 -vn -0.846478 -0.279911 -0.452906 -v 0.010750 -0.121750 0.126700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.119550 0.128975 -vn -0.741787 -0.516597 -0.427643 -v 0.010750 -0.120750 0.124700 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.119500 0.125200 -vn -0.717284 0.630263 -0.297108 -v 0.010750 -0.119500 0.124700 -vn -0.923880 0.000000 -0.382683 -v 0.010750 -0.119550 0.124700 -vn -0.846478 0.279911 -0.452907 -v 0.010750 -0.115750 0.126700 -vn -0.741788 0.516596 -0.427644 -v 0.010750 -0.116750 0.124700 -vn -0.717284 -0.630263 -0.297108 -v 0.010750 -0.118000 0.124700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.110450 0.128975 -vn -0.846478 -0.279911 -0.452907 -v 0.010750 -0.113750 0.126700 -vn -0.904534 -0.301511 -0.301512 -v 0.010750 -0.118000 0.125200 -vn -0.846478 0.279911 -0.452907 -v 0.010750 -0.107750 0.126700 -vn -0.741788 0.516596 -0.427644 -v 0.010750 -0.108750 0.124700 -vn -0.717284 -0.630263 -0.297108 -v 0.010750 -0.110000 0.124700 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.102250 0.128975 -vn -0.707107 0.000000 -0.707107 -v 0.010750 -0.102250 0.125200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.103500 0.125200 -vn -0.846478 -0.279911 -0.452907 -v 0.010750 -0.105750 0.126700 -vn -0.707107 0.000000 -0.707107 -v 0.010750 -0.110450 0.125200 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.110000 0.125200 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.102000 0.125200 -vn -0.846478 -0.279911 -0.452907 -v 0.010750 -0.097750 0.126700 -vn -0.846478 0.279911 -0.452907 -v 0.010750 -0.099750 0.126700 -vn -0.976005 0.188574 0.108876 -v 0.010750 -0.097279 0.128850 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.094000 0.126700 -vn -0.577350 0.577350 -0.577350 -v 0.010750 -0.094000 0.125200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.095500 0.125200 -vn -0.976004 0.108878 0.188579 -v 0.010750 -0.096950 0.128521 -vn -0.741787 -0.516596 -0.427644 -v 0.010750 -0.096750 0.124700 -vn -0.717284 0.630262 -0.297108 -v 0.010750 -0.095500 0.124700 -vn -0.976005 -0.188574 0.108873 -v 0.010750 -0.095721 0.128850 -vn -0.976003 -0.108878 0.188582 -v 0.010750 -0.096050 0.128521 -vn -0.976003 0.000000 0.217755 -v 0.010750 -0.096500 0.128400 -vn -0.577350 0.577350 -0.577350 -v 0.010750 -0.092500 0.126700 -vn -0.707107 0.000000 -0.707107 -v 0.010750 -0.093800 0.126700 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.092500 0.128450 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.093800 0.128975 -vn -0.717284 0.297108 -0.630263 -v 0.010750 -0.092000 0.128450 -vn -0.923880 0.382683 0.000000 -v 0.010750 -0.092000 0.128975 -vn -0.717284 0.297108 0.630263 -v 0.010750 -0.092000 0.134950 -vn -0.741788 0.427644 -0.516597 -v 0.010750 -0.092000 0.133700 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.092500 0.134950 -vn -0.846478 0.452906 -0.279911 -v 0.010750 -0.094000 0.132700 -vn -0.707107 0.707107 -0.000000 -v 0.010750 -0.092500 0.136525 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.093800 0.136525 -vn -0.707107 0.707107 -0.000000 -v 0.010750 -0.092500 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.093800 0.139700 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.092500 0.142875 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.093800 0.142875 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.092500 0.144450 -vn -0.846478 0.452906 0.279911 -v 0.010750 -0.094000 0.146700 -vn -0.717284 0.297108 -0.630263 -v 0.010750 -0.092000 0.144450 -vn -0.741788 0.427644 0.516597 -v 0.010750 -0.092000 0.145700 -vn -0.846478 0.452906 -0.279911 -v 0.010750 -0.094000 0.148700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.093800 0.148900 -vn -0.741788 0.427644 -0.516596 -v 0.010750 -0.092000 0.149700 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.092500 0.150950 -vn -0.717284 0.297108 0.630263 -v 0.010750 -0.092000 0.150950 -vn -0.846478 0.279911 0.452907 -v 0.010750 -0.099750 0.152700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.102250 0.148900 -vn -0.707107 0.000000 0.707107 -v 0.010750 -0.102250 0.154200 -vn -0.976003 -0.217757 0.000001 -v 0.010750 -0.095600 0.150100 -vn -0.976002 -0.188589 -0.108876 -v 0.010750 -0.095721 0.150550 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.095500 0.154200 -vn -0.976004 -0.108875 -0.188579 -v 0.010750 -0.096050 0.150879 -vn -0.975997 -0.000003 -0.217784 -v 0.010750 -0.096500 0.151000 -vn -0.976005 0.188574 0.108876 -v 0.010750 -0.097279 0.149650 -vn -0.976004 0.108878 0.188579 -v 0.010750 -0.096950 0.149321 -vn -0.976003 0.000000 0.217756 -v 0.010750 -0.096500 0.149200 -vn -0.976003 -0.108878 0.188582 -v 0.010750 -0.096050 0.149321 -vn -0.976005 -0.188574 0.108873 -v 0.010750 -0.095721 0.149650 -vn -0.717284 0.630262 0.297108 -v 0.010750 -0.095500 0.154700 -vn -0.741787 -0.516596 0.427644 -v 0.010750 -0.096750 0.154700 -vn -0.846478 -0.279911 0.452907 -v 0.010750 -0.097750 0.152700 -vn -0.976004 0.108878 -0.188578 -v 0.010750 -0.096950 0.150879 -vn -0.976002 0.188589 -0.108879 -v 0.010750 -0.097279 0.150550 -vn -0.976003 0.217755 0.000000 -v 0.010750 -0.097400 0.150100 -vn -0.577350 0.577350 0.577350 -v 0.010750 -0.094000 0.154200 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.094000 0.152700 -vn -0.707107 0.000000 0.707107 -v 0.010750 -0.093800 0.152700 -vn -0.577350 0.577350 0.577350 -v 0.010750 -0.092500 0.152700 -vn -0.707107 0.000000 0.707107 -v 0.010750 -0.110450 0.154200 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.110000 0.154200 -vn -0.741788 -0.516596 0.427644 -v 0.010750 -0.104750 0.154700 -vn -0.717284 0.630263 0.297108 -v 0.010750 -0.103500 0.154700 -vn -0.846478 -0.279911 0.452907 -v 0.010750 -0.105750 0.152700 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.103500 0.154200 -vn -0.846478 0.279911 0.452907 -v 0.010750 -0.107750 0.152700 -vn -0.741788 0.516596 0.427644 -v 0.010750 -0.108750 0.154700 -vn -0.717284 -0.630263 0.297108 -v 0.010750 -0.110000 0.154700 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.112000 0.147425 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.112000 0.148900 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.110450 0.148900 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.112000 0.149200 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.119500 0.154200 -vn -0.904534 -0.301512 0.301511 -v 0.010750 -0.118000 0.154200 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.119550 0.148900 -vn -0.923880 0.000000 0.382683 -v 0.010750 -0.119550 0.154700 -vn -0.717284 0.630263 0.297108 -v 0.010750 -0.119500 0.154700 -vn -0.741788 -0.516596 0.427644 -v 0.010750 -0.112750 0.154700 -vn -0.717284 0.630263 0.297108 -v 0.010750 -0.111500 0.154700 -vn -0.846478 -0.279911 0.452907 -v 0.010750 -0.113750 0.152700 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.111500 0.154200 -vn -0.717283 -0.630263 0.297108 -v 0.010750 -0.118000 0.154700 -vn -0.741788 0.516596 0.427644 -v 0.010750 -0.116750 0.154700 -vn -0.846479 0.279910 0.452906 -v 0.010750 -0.115750 0.152700 -vn -0.707107 0.000000 0.707107 -v 0.010750 -0.126325 0.154200 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.126000 0.154200 -vn -0.741787 -0.516597 0.427643 -v 0.010750 -0.120750 0.154700 -vn -0.846478 -0.279911 0.452906 -v 0.010750 -0.121750 0.152700 -vn -0.846478 0.279911 0.452907 -v 0.010750 -0.123750 0.152700 -vn -0.741788 0.516596 0.427644 -v 0.010750 -0.124750 0.154700 -vn -0.717284 -0.630263 0.297108 -v 0.010750 -0.126000 0.154700 -vn -0.707107 0.000000 0.707107 -v 0.010750 -0.133425 0.152700 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.127500 0.152700 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.148900 -vn -0.975997 -0.108893 -0.188606 -v 0.010750 -0.138050 0.149729 -vn -0.976003 0.000001 -0.217758 -v 0.010750 -0.138500 0.149850 -vn -0.976000 0.108886 -0.188592 -v 0.010750 -0.138950 0.149729 -vn -0.976002 0.188587 -0.108879 -v 0.010750 -0.139279 0.149400 -vn -0.976003 0.217755 0.000000 -v 0.010750 -0.139400 0.148950 -vn -0.976005 0.188574 0.108876 -v 0.010750 -0.139279 0.148500 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.141000 0.147425 -vn -0.976005 0.108876 0.188574 -v 0.010750 -0.138950 0.148171 -vn -0.976004 0.000000 0.217755 -v 0.010750 -0.138500 0.148050 -vn -0.976002 -0.108879 0.188589 -v 0.010750 -0.138050 0.148171 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.136850 0.147425 -vn -0.976006 -0.188573 0.108872 -v 0.010750 -0.137721 0.148500 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.136850 0.148900 -vn -0.976002 -0.217760 0.000000 -v 0.010750 -0.137600 0.148950 -vn -0.976003 -0.188584 -0.108876 -v 0.010750 -0.137721 0.149400 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.136850 0.130500 -vn -0.976002 -0.217760 0.000000 -v 0.010750 -0.137600 0.130450 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.136850 0.131975 -vn -0.976003 -0.188584 -0.108876 -v 0.010750 -0.137721 0.130900 -vn -0.975997 -0.108893 -0.188605 -v 0.010750 -0.138050 0.131229 -vn -0.976003 0.000002 -0.217758 -v 0.010750 -0.138500 0.131350 -vn -0.976000 0.108886 -0.188592 -v 0.010750 -0.138950 0.131229 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 -0.141000 0.131975 -vn -0.976002 0.188587 -0.108879 -v 0.010750 -0.139279 0.130900 -vn -0.976003 0.217755 0.000000 -v 0.010750 -0.139400 0.130450 -vn -0.976005 0.188574 0.108876 -v 0.010750 -0.139279 0.130000 -vn -0.976005 0.108876 0.188574 -v 0.010750 -0.138950 0.129671 -vn -0.976004 0.000000 0.217754 -v 0.010750 -0.138500 0.129550 -vn -0.976002 -0.108879 0.188589 -v 0.010750 -0.138050 0.129671 -vn -0.976006 -0.188573 0.108872 -v 0.010750 -0.137721 0.130000 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.128975 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 -0.127500 0.125200 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.127500 0.126700 -vn -0.707107 0.000000 -0.707107 -v 0.010750 -0.133425 0.126700 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.116500 0.140200 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.119550 0.139700 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.116500 0.142875 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.119550 0.142875 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.116500 0.146700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.119550 0.146700 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.116500 0.147425 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.119550 0.147425 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.116500 0.148900 -vn -1.000000 0.000000 -0.000000 -v 0.010750 -0.110450 0.139700 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.112000 0.140200 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.110450 0.142875 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.112000 0.142875 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.110450 0.146700 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.112000 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.110450 0.147425 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.112000 0.130500 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.110450 0.130500 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.112000 0.130200 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.116500 0.130200 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.116500 0.130500 -vn -1.000000 0.000000 -0.000000 -v 0.010750 -0.110450 0.136525 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 -0.112000 0.136525 -vn -0.904534 -0.301511 -0.301512 -v 0.010750 -0.112000 0.139200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.116500 0.139200 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.116500 0.131975 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.119550 0.131975 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.116500 0.132700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.119550 0.132700 -vn -0.707107 0.707107 -0.000000 -v 0.010750 -0.116500 0.136525 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.119550 0.136525 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.112000 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.110450 0.132700 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.112000 0.131975 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.110450 0.131975 -vn -0.976003 -0.188586 -0.108877 -v 0.010750 -0.095721 0.129750 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.093800 0.130500 -vn -0.976003 -0.217757 0.000001 -v 0.010750 -0.095600 0.129300 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.102250 0.130500 -vn -0.976002 0.188586 -0.108880 -v 0.010750 -0.097279 0.129750 -vn -0.741788 0.516596 -0.427644 -v 0.010750 -0.100750 0.124700 -vn -0.717284 -0.630263 -0.297108 -v 0.010750 -0.102000 0.124700 -vn -0.976003 0.217755 0.000000 -v 0.010750 -0.097400 0.129300 -vn -0.976003 -0.108877 -0.188583 -v 0.010750 -0.096050 0.130079 -vn -0.976003 -0.000000 -0.217756 -v 0.010750 -0.096500 0.130200 -vn -0.976004 0.108878 -0.188581 -v 0.010750 -0.096950 0.130079 -vn -0.770264 -0.000000 0.637725 -v 0.010750 -0.129500 0.138450 -vn -0.770259 -0.318864 0.552292 -v 0.010750 -0.128875 0.138617 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.126325 0.136525 -vn -0.770266 -0.552284 0.318862 -v 0.010750 -0.128417 0.139075 -vn -1.000000 0.000000 -0.000000 -v 0.010750 -0.126325 0.139700 -vn -0.770258 -0.637732 0.000000 -v 0.010750 -0.128250 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.142875 -vn -0.770263 -0.552289 -0.318859 -v 0.010750 -0.128417 0.140325 -vn -0.770263 -0.318859 -0.552289 -v 0.010750 -0.128875 0.140783 -vn -0.770258 -0.000000 -0.637732 -v 0.010750 -0.129500 0.140950 -vn -0.770266 0.318862 -0.552284 -v 0.010750 -0.130125 0.140783 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.142875 -vn -0.770258 0.552293 -0.318864 -v 0.010750 -0.130583 0.140325 -vn -1.000000 0.000000 -0.000000 -v 0.010750 -0.133425 0.139700 -vn -0.770264 0.637725 -0.000000 -v 0.010750 -0.130750 0.139700 -vn -1.000000 0.000000 -0.000000 -v 0.010750 -0.133425 0.136525 -vn -0.770261 0.552288 0.318867 -v 0.010750 -0.130583 0.139075 -vn -0.770261 0.318868 0.552287 -v 0.010750 -0.130125 0.138617 -vn -0.770263 -0.000000 0.637726 -v 0.010750 -0.137000 0.132800 -vn -0.770261 -0.318866 0.552288 -v 0.010750 -0.136550 0.132921 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.132700 -vn -0.770261 -0.552288 0.318866 -v 0.010750 -0.136221 0.133250 -vn -0.770263 -0.637726 -0.000000 -v 0.010750 -0.136100 0.133700 -vn -0.770261 -0.552288 -0.318866 -v 0.010750 -0.136221 0.134150 -vn -0.770263 -0.000000 -0.637726 -v 0.010750 -0.137000 0.134600 -vn -0.770258 0.318862 -0.552295 -v 0.010750 -0.137450 0.134479 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 -0.141000 0.136525 -vn -0.770268 0.552282 -0.318860 -v 0.010750 -0.137779 0.134150 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 -0.141000 0.132700 -vn -0.770256 0.637735 0.000000 -v 0.010750 -0.137900 0.133700 -vn -0.770268 0.552282 0.318860 -v 0.010750 -0.137779 0.133250 -vn -0.770264 0.552285 0.318863 -v 0.010750 -0.124279 0.131250 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.130500 -vn -0.770259 0.637731 -0.000000 -v 0.010750 -0.124400 0.131700 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.131975 -vn -0.770262 0.552292 -0.318858 -v 0.010750 -0.124279 0.132150 -vn -0.770261 -0.552288 0.318866 -v 0.010750 -0.122721 0.131250 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.119550 0.130500 -vn -0.770260 0.318864 0.552292 -v 0.010750 -0.123950 0.130921 -vn -0.770263 -0.000000 0.637726 -v 0.010750 -0.123500 0.130800 -vn -0.770261 -0.318866 0.552288 -v 0.010750 -0.123050 0.130921 -vn -0.770263 -0.637726 -0.000000 -v 0.010750 -0.122600 0.131700 -vn -0.770258 -0.552295 -0.318862 -v 0.010750 -0.122721 0.132150 -vn -0.770268 -0.318860 -0.552282 -v 0.010750 -0.123050 0.132479 -vn -0.770266 0.318857 -0.552286 -v 0.010750 -0.123950 0.132479 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.132700 -vn -0.770256 0.000000 -0.637735 -v 0.010750 -0.123500 0.132600 -vn -0.770261 0.552288 0.318866 -v 0.010750 -0.108779 0.131250 -vn -0.770261 0.318866 0.552288 -v 0.010750 -0.108450 0.130921 -vn -0.770263 -0.000000 0.637726 -v 0.010750 -0.108000 0.130800 -vn -0.770260 -0.318864 0.552292 -v 0.010750 -0.107550 0.130921 -vn -0.770264 -0.552285 0.318863 -v 0.010750 -0.107221 0.131250 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.102250 0.131975 -vn -0.770263 0.637726 0.000000 -v 0.010750 -0.108900 0.131700 -vn -0.770259 -0.637731 0.000000 -v 0.010750 -0.107100 0.131700 -vn -0.770262 -0.552292 -0.318858 -v 0.010750 -0.107221 0.132150 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.102250 0.132700 -vn -0.770266 -0.318857 -0.552286 -v 0.010750 -0.107550 0.132479 -vn -0.770256 0.000000 -0.637735 -v 0.010750 -0.108000 0.132600 -vn -0.770268 0.318860 -0.552282 -v 0.010750 -0.108450 0.132479 -vn -0.770258 0.552295 -0.318862 -v 0.010750 -0.108779 0.132150 -vn -0.770256 -0.000000 0.637735 -v 0.010750 -0.137000 0.144800 -vn -0.770265 -0.318855 0.552289 -v 0.010750 -0.136550 0.144921 -vn -0.770261 -0.552288 0.318866 -v 0.010750 -0.136221 0.145250 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.146700 -vn -0.770263 -0.637726 -0.000000 -v 0.010750 -0.136100 0.145700 -vn -0.770258 -0.552295 -0.318862 -v 0.010750 -0.136221 0.146150 -vn -0.770256 -0.000000 -0.637735 -v 0.010750 -0.137000 0.146600 -vn -0.770265 0.318855 -0.552289 -v 0.010750 -0.137450 0.146479 -vn -0.707107 -0.707107 0.000000 -v 0.010750 -0.141000 0.146700 -vn -0.770265 0.552289 -0.318855 -v 0.010750 -0.137779 0.146150 -vn -0.770256 0.637735 0.000000 -v 0.010750 -0.137900 0.145700 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 -0.141000 0.142875 -vn -0.770268 0.552282 0.318860 -v 0.010750 -0.137779 0.145250 -vn -0.770264 -0.552285 -0.318863 -v 0.010750 -0.107221 0.148150 -vn -0.770260 -0.318864 -0.552292 -v 0.010750 -0.107550 0.148479 -vn -0.770263 0.000000 -0.637726 -v 0.010750 -0.108000 0.148600 -vn -0.770261 0.318866 -0.552288 -v 0.010750 -0.108450 0.148479 -vn -0.770261 0.552288 -0.318866 -v 0.010750 -0.108779 0.148150 -vn -0.770259 -0.637731 0.000000 -v 0.010750 -0.107100 0.147700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.102250 0.147425 -vn -0.770264 -0.552285 0.318863 -v 0.010750 -0.107221 0.147250 -vn -0.770263 0.637726 0.000000 -v 0.010750 -0.108900 0.147700 -vn -0.770261 0.552288 0.318866 -v 0.010750 -0.108779 0.147250 -vn -0.770261 0.318866 0.552288 -v 0.010750 -0.108450 0.146921 -vn -0.770259 -0.318864 0.552292 -v 0.010750 -0.107550 0.146921 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.102250 0.146700 -vn -0.770263 0.000000 0.637726 -v 0.010750 -0.108000 0.146800 -vn -0.770263 -0.637726 -0.000000 -v 0.010750 -0.122600 0.147700 -vn -0.770261 -0.552288 -0.318866 -v 0.010750 -0.122721 0.148150 -vn -0.770261 -0.318866 -0.552288 -v 0.010750 -0.123050 0.148479 -vn -0.770261 -0.552288 0.318866 -v 0.010750 -0.122721 0.147250 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.116500 0.149200 -vn -0.770263 0.000000 -0.637726 -v 0.010750 -0.123500 0.148600 -vn -0.770260 0.318864 -0.552292 -v 0.010750 -0.123950 0.148479 -vn -0.770264 0.552285 -0.318863 -v 0.010750 -0.124279 0.148150 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.147425 -vn -0.577350 -0.577350 0.577350 -v 0.010750 -0.127500 0.154200 -vn -0.770261 -0.318866 0.552288 -v 0.010750 -0.123050 0.146921 -vn -0.770263 -0.000000 0.637726 -v 0.010750 -0.123500 0.146800 -vn -0.770259 0.637731 -0.000000 -v 0.010750 -0.124400 0.147700 -vn -0.770264 0.552285 0.318863 -v 0.010750 -0.124279 0.147250 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.126325 0.146700 -vn -0.770260 0.318864 0.552292 -v 0.010750 -0.123950 0.146921 -vn -1.000000 -0.000000 0.000000 -v 0.010750 -0.136850 0.146700 -vn -0.770268 -0.318860 -0.552283 -v 0.010750 -0.136550 0.146479 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.148900 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.147425 -vn -0.770262 0.318851 0.552296 -v 0.010750 -0.137450 0.144921 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.136850 0.142875 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 -0.141000 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.136850 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.136850 0.136525 -vn -0.770261 -0.318866 -0.552288 -v 0.010750 -0.136550 0.134479 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.102250 0.142875 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.102250 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.102250 0.136525 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.094000 0.147425 -vn -0.741788 0.427644 0.516596 -v 0.010750 -0.092000 0.129700 -vn -0.846478 0.452906 0.279911 -v 0.010750 -0.094000 0.130700 -vn -0.707107 0.707107 0.000000 -v 0.010750 -0.094000 0.131975 -vn -0.770258 0.318861 0.552295 -v 0.010750 -0.137450 0.132921 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 -0.136850 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.131975 -vn -1.000000 0.000000 0.000000 -v 0.010750 -0.133425 0.130500 -vn -0.741788 -0.516596 -0.427644 -v 0.010750 -0.104750 0.124700 -vn -0.717284 0.630263 -0.297108 -v 0.010750 -0.103500 0.124700 -vn 0.075085 -0.990667 -0.113762 -v 0.012250 -0.120750 0.124700 -vn 0.609995 -0.686244 -0.396202 -v 0.012250 -0.120750 0.127355 -vn 0.846478 -0.279911 -0.452906 -v 0.012250 -0.121750 0.126700 -vn 0.609994 -0.000001 -0.792406 -v 0.012250 -0.122750 0.128509 -vn 0.846478 0.279911 -0.452907 -v 0.012250 -0.123750 0.126700 -vn 0.609994 0.686244 -0.396203 -v 0.012250 -0.124750 0.127355 -vn 0.075085 0.990667 -0.113763 -v 0.012250 -0.124750 0.124700 -vn 0.075085 -0.990667 -0.113763 -v 0.012250 -0.112750 0.124700 -vn 0.609995 -0.686244 -0.396202 -v 0.012250 -0.112750 0.127355 -vn 0.846478 -0.279911 -0.452907 -v 0.012250 -0.113750 0.126700 -vn 0.609994 -0.000001 -0.792406 -v 0.012250 -0.114750 0.128509 -vn 0.846478 0.279911 -0.452907 -v 0.012250 -0.115750 0.126700 -vn 0.609994 0.686244 -0.396203 -v 0.012250 -0.116750 0.127355 -vn 0.075085 0.990667 -0.113763 -v 0.012250 -0.116750 0.124700 -vn 0.075085 -0.990667 -0.113763 -v 0.012250 -0.104750 0.124700 -vn 0.609994 -0.686244 -0.396203 -v 0.012250 -0.104750 0.127355 -vn 0.846478 -0.279911 -0.452907 -v 0.012250 -0.105750 0.126700 -vn 0.609994 0.000001 -0.792406 -v 0.012250 -0.106750 0.128509 -vn 0.846478 0.279911 -0.452907 -v 0.012250 -0.107750 0.126700 -vn 0.609995 0.686244 -0.396202 -v 0.012250 -0.108750 0.127355 -vn 0.075085 0.990667 -0.113763 -v 0.012250 -0.108750 0.124700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.120750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 -0.119500 0.123700 -vn 0.297109 0.630262 -0.717284 -v 0.014750 -0.119500 0.123700 -vn 0.297109 -0.630262 -0.717283 -v 0.014750 -0.126000 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 -0.124750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.126000 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.112750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 -0.111500 0.123700 -vn 0.297109 0.630262 -0.717284 -v 0.014750 -0.111500 0.123700 -vn 0.297109 -0.630262 -0.717283 -v 0.014750 -0.118000 0.123700 -vn -0.297109 0.630262 -0.717284 -v 0.011750 -0.116750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.118000 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.104750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 -0.103500 0.123700 -vn 0.297109 0.630262 -0.717283 -v 0.014750 -0.103500 0.123700 -vn 0.297109 -0.630262 -0.717284 -v 0.014750 -0.110000 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 -0.108750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.110000 0.123700 -vn -0.609995 0.686244 -0.396202 -v 0.013750 -0.100750 0.127355 -vn -0.770261 0.637728 0.000000 -v 0.013750 -0.100000 0.126200 -vn -0.301511 0.301511 -0.904534 -v 0.013750 -0.100750 0.123700 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.099833 0.125575 -vn -0.609994 -0.686244 -0.396203 -v 0.013750 -0.096750 0.127355 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 -0.096750 0.123700 -vn -0.770260 -0.552291 0.318865 -v 0.013750 -0.097667 0.125575 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 -0.098125 0.127283 -vn -0.609994 0.000001 -0.792406 -v 0.013750 -0.098750 0.128509 -vn -0.770262 -0.552286 -0.318869 -v 0.013750 -0.097667 0.126825 -vn -0.770264 -0.637725 0.000000 -v 0.013750 -0.097500 0.126200 -vn -0.770264 0.000000 -0.637725 -v 0.013750 -0.098750 0.127450 -vn -0.770260 0.318866 -0.552291 -v 0.013750 -0.099375 0.127283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.099833 0.126825 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.099375 0.125117 -vn -0.770258 0.000000 0.637732 -v 0.013750 -0.098750 0.124950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 -0.098125 0.125117 -vn -0.301511 0.904534 -0.301511 -v 0.013750 -0.091000 0.133700 -vn -0.301511 0.904534 0.301511 -v 0.013750 -0.091000 0.129700 -vn -0.770264 -0.637725 -0.000000 -v 0.013750 -0.092250 0.131700 -vn -0.770261 -0.552288 0.318867 -v 0.013750 -0.092417 0.131075 -vn -0.770261 0.552288 0.318867 -v 0.013750 -0.094583 0.131075 -vn -0.609995 0.396202 0.686244 -v 0.013750 -0.094655 0.129700 -vn -0.770264 0.637725 0.000000 -v 0.013750 -0.094750 0.131700 -vn -0.609994 0.792406 0.000001 -v 0.013750 -0.095809 0.131700 -vn -0.770259 0.552293 -0.318864 -v 0.013750 -0.094583 0.132325 -vn -0.609994 0.396203 -0.686243 -v 0.013750 -0.094655 0.133700 -vn -0.770266 0.318862 -0.552284 -v 0.013750 -0.094125 0.132783 -vn -0.770259 -0.552293 -0.318864 -v 0.013750 -0.092417 0.132325 -vn -0.770266 -0.318861 -0.552284 -v 0.013750 -0.092875 0.132783 -vn -0.770258 0.000001 -0.637732 -v 0.013750 -0.093500 0.132950 -vn -0.770261 0.318867 0.552288 -v 0.013750 -0.094125 0.130617 -vn -0.770264 0.000001 0.637725 -v 0.013750 -0.093500 0.130450 -vn -0.770261 -0.318866 0.552288 -v 0.013750 -0.092875 0.130617 -vn 0.075085 -0.990667 -0.113763 -v 0.012250 -0.096750 0.124700 -vn 0.609994 -0.686244 -0.396203 -v 0.012250 -0.096750 0.127355 -vn 0.846478 -0.279911 -0.452907 -v 0.012250 -0.097750 0.126700 -vn 0.609994 0.000001 -0.792406 -v 0.012250 -0.098750 0.128509 -vn 0.846478 0.279911 -0.452907 -v 0.012250 -0.099750 0.126700 -vn 0.609995 0.686244 -0.396202 -v 0.012250 -0.100750 0.127355 -vn 0.075085 0.990667 -0.113763 -v 0.012250 -0.100750 0.124700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.096750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 -0.095500 0.123700 -vn 0.297109 0.630262 -0.717283 -v 0.014750 -0.095500 0.123700 -vn 0.297109 -0.630262 -0.717283 -v 0.014750 -0.102000 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 -0.100750 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 -0.102000 0.123700 -vn 0.846478 0.452906 -0.279911 -v 0.012250 -0.094000 0.132700 -vn 0.075085 0.113763 -0.990667 -v 0.012250 -0.092000 0.133700 -vn 0.609994 0.396204 -0.686243 -v 0.012250 -0.094655 0.133700 -vn 0.609994 0.396202 0.686244 -v 0.012250 -0.094655 0.129700 -vn 0.075085 0.113763 0.990667 -v 0.012250 -0.092000 0.129700 -vn 0.846478 0.452906 0.279911 -v 0.012250 -0.094000 0.130700 -vn 0.609994 0.792406 0.000001 -v 0.012250 -0.095809 0.131700 -vn -0.297109 0.717283 -0.630262 -v 0.011750 -0.091000 0.133700 -vn -0.297109 0.717283 0.630262 -v 0.011750 -0.091000 0.134950 -vn 0.297109 0.717283 0.630262 -v 0.014750 -0.091000 0.134950 -vn 0.297109 0.717283 -0.630262 -v 0.014750 -0.091000 0.128450 -vn -0.297109 0.717283 0.630262 -v 0.011750 -0.091000 0.129700 -vn -0.297109 0.717283 -0.630262 -v 0.011750 -0.091000 0.128450 -vn 0.088123 -0.737701 0.669352 -v 0.014750 -0.127500 0.152700 -vn 0.130014 -0.038813 0.990752 -v 0.014750 -0.136000 0.152700 -vn 0.130013 -0.990753 0.038803 -v 0.014750 -0.141000 0.147700 -vn 0.130014 -0.990753 -0.038804 -v 0.014750 -0.141000 0.131700 -vn 0.088123 -0.737701 -0.669352 -v 0.014750 -0.127500 0.126700 -vn 0.130013 -0.038803 -0.990753 -v 0.014750 -0.136000 0.126700 -vn 0.297108 -0.630263 -0.717284 -v 0.014250 -0.127500 0.125200 -vn 0.318863 -0.770260 -0.552292 -v 0.015250 -0.127500 0.126834 -vn 0.552285 -0.770264 -0.318865 -v 0.015616 -0.127500 0.127200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 -0.126000 0.125200 -vn 0.227458 0.804186 -0.549133 -v 0.014250 -0.119500 0.125200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 -0.118000 0.125200 -vn 0.227458 0.804186 -0.549133 -v 0.014250 -0.111500 0.125200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 -0.110000 0.125200 -vn 0.227458 0.804186 -0.549133 -v 0.014250 -0.103500 0.125200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 -0.102000 0.125200 -vn 0.227458 0.804186 -0.549133 -v 0.014250 -0.095500 0.125200 -vn 0.297108 0.630263 -0.717284 -v 0.014250 -0.094000 0.125200 -vn 0.297108 0.717284 -0.630263 -v 0.014250 -0.092500 0.126700 -vn 0.227458 0.549133 -0.804186 -v 0.014250 -0.092500 0.128450 -vn 0.227458 0.549133 0.804186 -v 0.014250 -0.092500 0.134950 -vn 0.227458 0.549133 -0.804186 -v 0.014250 -0.092500 0.144450 -vn 0.297109 0.717284 -0.630262 -v 0.014750 -0.091000 0.144450 -vn -0.297109 0.717283 -0.630262 -v 0.011750 -0.091000 0.144450 -vn -0.297109 0.717283 -0.630262 -v 0.011750 -0.091000 0.149700 -vn -0.297109 0.717283 0.630262 -v 0.011750 -0.091000 0.150950 -vn -0.301511 0.904534 -0.301511 -v 0.013750 -0.091000 0.149700 -vn 0.297109 0.717283 0.630262 -v 0.014750 -0.091000 0.150950 -vn -0.301511 0.904534 0.301511 -v 0.013750 -0.091000 0.145700 -vn -0.297109 0.717283 0.630262 -v 0.011750 -0.091000 0.145700 -vn 0.227458 0.549133 0.804186 -v 0.014250 -0.092500 0.150950 -vn 0.297108 0.717284 0.630263 -v 0.014250 -0.092500 0.152700 -vn 0.297108 0.630263 0.717284 -v 0.014250 -0.094000 0.154200 -vn 0.227458 0.804186 0.549133 -v 0.014250 -0.095500 0.154200 -vn 0.297109 0.630262 0.717283 -v 0.014750 -0.095500 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 -0.095500 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 -0.100750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.102000 0.155700 -vn -0.301511 0.301511 0.904534 -v 0.013750 -0.100750 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 -0.102000 0.155700 -vn -0.301511 -0.301511 0.904534 -v 0.013750 -0.096750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.096750 0.155700 -vn 0.227458 -0.804186 0.549133 -v 0.014250 -0.102000 0.154200 -vn 0.227458 0.804186 0.549133 -v 0.014250 -0.103500 0.154200 -vn 0.297109 0.630262 0.717283 -v 0.014750 -0.103500 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 -0.103500 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 -0.108750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.110000 0.155700 -vn -0.301511 0.301511 0.904534 -v 0.013750 -0.108750 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 -0.110000 0.155700 -vn -0.301511 -0.301511 0.904534 -v 0.013750 -0.104750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.104750 0.155700 -vn 0.227458 -0.804186 0.549133 -v 0.014250 -0.110000 0.154200 -vn 0.227458 0.804186 0.549133 -v 0.014250 -0.111500 0.154200 -vn 0.297109 0.630262 0.717284 -v 0.014750 -0.111500 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 -0.111500 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 -0.116750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.118000 0.155700 -vn -0.301511 0.301511 0.904534 -v 0.013750 -0.116750 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 -0.118000 0.155700 -vn -0.301511 -0.301511 0.904534 -v 0.013750 -0.112750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.112750 0.155700 -vn 0.227458 -0.804186 0.549133 -v 0.014250 -0.118000 0.154200 -vn 0.227458 0.804186 0.549133 -v 0.014250 -0.119500 0.154200 -vn 0.297109 0.630262 0.717283 -v 0.014750 -0.119500 0.155700 -vn -0.297109 0.630262 0.717284 -v 0.011750 -0.119500 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 -0.124750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.126000 0.155700 -vn -0.301511 0.301511 0.904534 -v 0.013750 -0.124750 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 -0.126000 0.155700 -vn -0.301511 -0.301511 0.904534 -v 0.013750 -0.120750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 -0.120750 0.155700 -vn 0.227458 -0.804186 0.549133 -v 0.014250 -0.126000 0.154200 -vn 0.297108 -0.630263 0.717284 -v 0.014250 -0.127500 0.154200 -vn 0.552291 -0.770261 0.318863 -v 0.015616 -0.127500 0.152200 -vn 0.318867 -0.770263 0.552286 -v 0.015250 -0.127500 0.152566 -vn 0.128136 0.983445 0.128129 -v 0.018450 -0.097000 0.149400 -vn 0.128141 0.983442 -0.128145 -v 0.018450 -0.097000 0.144000 -vn 0.128141 0.128139 0.983443 -v 0.018450 -0.097300 0.149700 -vn 0.128136 -0.128135 0.983444 -v 0.018450 -0.103700 0.149700 -vn 0.128158 -0.983438 -0.128162 -v 0.018450 -0.104000 0.144000 -vn 0.128158 -0.983439 0.128150 -v 0.018450 -0.104000 0.149400 -vn 0.128136 0.128135 -0.983444 -v 0.018450 -0.097300 0.143700 -vn 0.128139 -0.128138 -0.983443 -v 0.018450 -0.103700 0.143700 -vn 0.988107 0.108729 -0.108735 -v 0.018750 -0.097300 0.144000 -vn 0.988108 0.108730 0.108724 -v 0.018750 -0.097300 0.149400 -vn 0.988107 -0.108726 -0.108733 -v 0.018750 -0.103700 0.144000 -vn 0.988108 -0.108728 0.108722 -v 0.018750 -0.103700 0.149400 -vn 0.128136 0.128135 -0.983444 -v 0.018450 -0.097300 0.129700 -vn 0.128139 -0.128138 -0.983443 -v 0.018450 -0.103700 0.129700 -vn 0.128141 0.983442 -0.128145 -v 0.018450 -0.097000 0.130000 -vn 0.128136 0.983445 0.128129 -v 0.018450 -0.097000 0.135400 -vn 0.128141 0.128139 0.983443 -v 0.018450 -0.097300 0.135700 -vn 0.128136 -0.128135 0.983444 -v 0.018450 -0.103700 0.135700 -vn 0.128158 -0.983439 0.128150 -v 0.018450 -0.104000 0.135400 -vn 0.128158 -0.983438 -0.128162 -v 0.018450 -0.104000 0.130000 -vn 0.988107 -0.108726 -0.108733 -v 0.018750 -0.103700 0.130000 -vn 0.988107 0.108729 -0.108735 -v 0.018750 -0.097300 0.130000 -vn 0.988108 -0.108728 0.108722 -v 0.018750 -0.103700 0.135400 -vn 0.988108 0.108730 0.108724 -v 0.018750 -0.097300 0.135400 -vn 0.609994 0.396204 0.686243 -v 0.012250 -0.094655 0.145700 -vn -0.609994 0.396203 0.686243 -v 0.013750 -0.094655 0.145700 -vn 0.075085 0.113763 0.990667 -v 0.012250 -0.092000 0.145700 -vn -0.770264 -0.637725 0.000000 -v 0.013750 -0.092250 0.147700 -vn -0.770261 -0.552288 0.318867 -v 0.013750 -0.092417 0.147075 -vn -0.770258 0.000001 -0.637732 -v 0.013750 -0.093500 0.148950 -vn -0.609994 0.396203 -0.686243 -v 0.013750 -0.094655 0.149700 -vn -0.770266 -0.318861 -0.552284 -v 0.013750 -0.092875 0.148783 -vn -0.770259 -0.552293 -0.318864 -v 0.013750 -0.092417 0.148325 -vn -0.770266 0.318862 -0.552284 -v 0.013750 -0.094125 0.148783 -vn -0.770259 0.552293 -0.318864 -v 0.013750 -0.094583 0.148325 -vn -0.609994 0.792406 0.000000 -v 0.013750 -0.095809 0.147700 -vn -0.770264 0.637725 -0.000000 -v 0.013750 -0.094750 0.147700 -vn -0.770261 0.552288 0.318867 -v 0.013750 -0.094583 0.147075 -vn -0.770261 0.318867 0.552288 -v 0.013750 -0.094125 0.146617 -vn -0.770264 0.000001 0.637726 -v 0.013750 -0.093500 0.146450 -vn -0.770261 -0.318866 0.552288 -v 0.013750 -0.092875 0.146617 -vn 0.075085 0.113763 -0.990667 -v 0.012250 -0.092000 0.149700 -vn 0.609994 0.396204 -0.686243 -v 0.012250 -0.094655 0.149700 -vn 0.609995 0.792406 -0.000000 -v 0.012250 -0.095809 0.147700 -vn 0.846478 0.452906 -0.279911 -v 0.012250 -0.094000 0.148700 -vn 0.846478 0.452907 0.279911 -v 0.012250 -0.094000 0.146700 -vn 0.609994 -0.686243 0.396205 -v 0.012250 -0.096750 0.152045 -vn -0.609994 -0.686243 0.396205 -v 0.013750 -0.096750 0.152045 -vn 0.075085 -0.990667 0.113763 -v 0.012250 -0.096750 0.154700 -vn -0.609994 0.686243 0.396204 -v 0.013750 -0.100750 0.152045 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.099833 0.153825 -vn -0.770261 0.637729 0.000000 -v 0.013750 -0.100000 0.153200 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.099833 0.152575 -vn -0.609995 0.000001 0.792405 -v 0.013750 -0.098750 0.150891 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.099375 0.152117 -vn -0.770264 -0.637725 0.000000 -v 0.013750 -0.097500 0.153200 -vn -0.770262 -0.552286 -0.318869 -v 0.013750 -0.097667 0.153825 -vn -0.770260 -0.318865 -0.552291 -v 0.013750 -0.098125 0.154283 -vn -0.770264 -0.000000 -0.637725 -v 0.013750 -0.098750 0.154450 -vn -0.770260 0.318866 -0.552291 -v 0.013750 -0.099375 0.154283 -vn -0.770258 0.000000 0.637732 -v 0.013750 -0.098750 0.151950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 -0.098125 0.152117 -vn -0.770260 -0.552291 0.318865 -v 0.013750 -0.097667 0.152575 -vn 0.075085 0.990667 0.113763 -v 0.012250 -0.100750 0.154700 -vn 0.609994 0.686243 0.396204 -v 0.012250 -0.100750 0.152045 -vn 0.609995 0.000001 0.792405 -v 0.012250 -0.098750 0.150891 -vn 0.846478 0.279911 0.452907 -v 0.012250 -0.099750 0.152700 -vn 0.846478 -0.279911 0.452907 -v 0.012250 -0.097750 0.152700 -vn 0.609994 -0.686243 0.396205 -v 0.012250 -0.104750 0.152045 -vn -0.609994 -0.686243 0.396205 -v 0.013750 -0.104750 0.152045 -vn 0.075085 -0.990667 0.113763 -v 0.012250 -0.104750 0.154700 -vn -0.609994 0.686243 0.396204 -v 0.013750 -0.108750 0.152045 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.107833 0.153825 -vn -0.770261 0.637729 -0.000000 -v 0.013750 -0.108000 0.153200 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.107833 0.152575 -vn -0.609995 0.000001 0.792405 -v 0.013750 -0.106750 0.150891 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.107375 0.152117 -vn -0.770261 -0.552288 -0.318867 -v 0.013750 -0.105667 0.153825 -vn -0.770264 -0.637725 0.000000 -v 0.013750 -0.105500 0.153200 -vn -0.770258 0.000001 0.637732 -v 0.013750 -0.106750 0.151950 -vn -0.770266 -0.318861 0.552284 -v 0.013750 -0.106125 0.152117 -vn -0.770259 -0.552293 0.318864 -v 0.013750 -0.105667 0.152575 -vn -0.770261 -0.318866 -0.552288 -v 0.013750 -0.106125 0.154283 -vn -0.770264 0.000001 -0.637726 -v 0.013750 -0.106750 0.154450 -vn -0.770260 0.318865 -0.552291 -v 0.013750 -0.107375 0.154283 -vn 0.075085 0.990667 0.113763 -v 0.012250 -0.108750 0.154700 -vn 0.609994 0.686243 0.396204 -v 0.012250 -0.108750 0.152045 -vn 0.609994 -0.686243 0.396204 -v 0.012250 -0.112750 0.152045 -vn -0.609994 -0.686243 0.396204 -v 0.013750 -0.112750 0.152045 -vn 0.075085 -0.990667 0.113763 -v 0.012250 -0.112750 0.154700 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 -0.113667 0.153825 -vn -0.770261 -0.637729 0.000000 -v 0.013750 -0.113500 0.153200 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 -0.114125 0.154283 -vn -0.770264 0.000000 -0.637725 -v 0.013750 -0.114750 0.154450 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.115375 0.152117 -vn -0.609995 -0.000001 0.792405 -v 0.013750 -0.114750 0.150891 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.115833 0.152575 -vn -0.609994 0.686243 0.396205 -v 0.013750 -0.116750 0.152045 -vn -0.770258 -0.000000 0.637732 -v 0.013750 -0.114750 0.151950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 -0.114125 0.152117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 -0.113667 0.152575 -vn -0.770260 0.318866 -0.552291 -v 0.013750 -0.115375 0.154283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.115833 0.153825 -vn -0.770261 0.637729 -0.000000 -v 0.013750 -0.116000 0.153200 -vn 0.075085 0.990667 0.113763 -v 0.012250 -0.116750 0.154700 -vn 0.609994 0.686243 0.396205 -v 0.012250 -0.116750 0.152045 -vn 0.609994 -0.686243 0.396204 -v 0.012250 -0.120750 0.152045 -vn -0.609994 -0.686243 0.396204 -v 0.013750 -0.120750 0.152045 -vn 0.075085 -0.990667 0.113762 -v 0.012250 -0.120750 0.154700 -vn -0.770258 0.000000 0.637732 -v 0.013750 -0.122750 0.151950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 -0.122125 0.152117 -vn -0.609995 -0.000001 0.792405 -v 0.013750 -0.122750 0.150891 -vn -0.609994 0.686243 0.396205 -v 0.013750 -0.124750 0.152045 -vn -0.770263 0.552286 -0.318865 -v 0.013750 -0.123833 0.153825 -vn -0.770261 0.637728 0.000000 -v 0.013750 -0.124000 0.153200 -vn -0.770261 0.552291 0.318862 -v 0.013750 -0.123833 0.152575 -vn -0.770265 0.318861 0.552286 -v 0.013750 -0.123375 0.152117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 -0.121667 0.152575 -vn -0.770261 -0.637728 -0.000000 -v 0.013750 -0.121500 0.153200 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 -0.121667 0.153825 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 -0.122125 0.154283 -vn -0.770264 0.000000 -0.637725 -v 0.013750 -0.122750 0.154450 -vn -0.770260 0.318866 -0.552291 -v 0.013750 -0.123375 0.154283 -vn 0.075085 0.990667 0.113763 -v 0.012250 -0.124750 0.154700 -vn 0.609994 0.686243 0.396205 -v 0.012250 -0.124750 0.152045 -vn 0.609995 0.000001 0.792405 -v 0.012250 -0.106750 0.150891 -vn 0.846478 0.279911 0.452907 -v 0.012250 -0.107750 0.152700 -vn 0.846478 -0.279911 0.452907 -v 0.012250 -0.105750 0.152700 -vn 0.609995 -0.000001 0.792405 -v 0.012250 -0.114750 0.150891 -vn 0.846478 0.279911 0.452907 -v 0.012250 -0.115750 0.152700 -vn 0.846478 -0.279911 0.452907 -v 0.012250 -0.113750 0.152700 -vn 0.609995 -0.000001 0.792405 -v 0.012250 -0.122750 0.150891 -vn 0.846478 0.279911 0.452907 -v 0.012250 -0.123750 0.152700 -vn 0.846478 -0.279911 0.452906 -v 0.012250 -0.121750 0.152700 -vn 0.128742 -0.979469 -0.155133 -v 0.014750 -0.140938 0.130918 -vn 0.129694 -0.943024 -0.306408 -v 0.014750 -0.140755 0.130155 -vn 0.128747 -0.883593 -0.450208 -v 0.014750 -0.140455 0.129430 -vn 0.129695 -0.802179 -0.582828 -v 0.014750 -0.140045 0.128761 -vn 0.128738 -0.701225 -0.701221 -v 0.014750 -0.139536 0.128164 -vn 0.129692 -0.582821 -0.802184 -v 0.014750 -0.138939 0.127655 -vn 0.128742 -0.450206 -0.883595 -v 0.014750 -0.138270 0.127245 -vn 0.129690 -0.306407 -0.943025 -v 0.014750 -0.137545 0.126945 -vn 0.128742 -0.155137 -0.979468 -v 0.014750 -0.136782 0.126762 -vn 0.128742 -0.155135 0.979469 -v 0.014750 -0.136782 0.152638 -vn 0.129690 -0.306408 0.943024 -v 0.014750 -0.137545 0.152455 -vn 0.128741 -0.450211 0.883593 -v 0.014750 -0.138270 0.152155 -vn 0.129693 -0.582819 0.802186 -v 0.014750 -0.138939 0.151745 -vn 0.128745 -0.701220 0.701224 -v 0.014750 -0.139536 0.151236 -vn 0.129694 -0.802184 0.582821 -v 0.014750 -0.140045 0.150639 -vn 0.128747 -0.883593 0.450209 -v 0.014750 -0.140455 0.149970 -vn 0.129691 -0.943024 0.306408 -v 0.014750 -0.140755 0.149245 -vn 0.128743 -0.979468 0.155136 -v 0.014750 -0.140938 0.148482 -vn 0.227459 -0.549132 -0.804187 -v 0.014750 -0.112000 0.149200 -vn 0.227458 -0.549133 0.804186 -v 0.014750 -0.112000 0.140200 -vn 0.227458 0.549133 0.804187 -v 0.014750 -0.116500 0.140200 -vn 0.227459 0.549132 -0.804187 -v 0.014750 -0.116500 0.149200 -vn 0.765315 -0.483793 -0.424543 -v 0.015450 -0.111300 0.149200 -vn 0.765316 0.483792 -0.424543 -v 0.015450 -0.117200 0.149200 -vn 0.765315 0.483793 0.424544 -v 0.015450 -0.117200 0.130200 -vn 0.765315 -0.483793 0.424544 -v 0.015450 -0.111300 0.130200 -vn 0.227459 -0.549132 0.804187 -v 0.014750 -0.112000 0.130200 -vn 0.227459 0.549132 0.804187 -v 0.014750 -0.116500 0.130200 -vn 0.227458 0.549133 -0.804186 -v 0.014750 -0.116500 0.139200 -vn 0.227458 -0.549133 -0.804186 -v 0.014750 -0.112000 0.139200 -vn 0.126935 -0.979699 -0.155170 -v 0.018250 -0.134833 0.138855 -vn 0.126914 -0.883804 -0.450315 -v 0.018250 -0.134311 0.137248 -vn 0.129686 -0.943025 -0.306408 -v 0.018250 -0.134636 0.138031 -vn 0.126949 -0.701383 -0.701389 -v 0.018250 -0.133318 0.135882 -vn 0.129673 -0.802189 -0.582819 -v 0.018250 -0.133869 0.136526 -vn 0.126970 -0.450311 -0.883798 -v 0.018250 -0.131952 0.134889 -vn 0.129676 -0.582825 -0.802184 -v 0.018250 -0.132674 0.135331 -vn 0.126933 -0.155173 -0.979699 -v 0.018250 -0.130345 0.134366 -vn 0.129688 -0.306408 -0.943024 -v 0.018250 -0.131169 0.134564 -vn 0.126935 0.155170 -0.979699 -v 0.018250 -0.128655 0.134366 -vn 0.129721 0.000003 -0.991551 -v 0.018250 -0.129500 0.134300 -vn 0.126970 0.450319 -0.883794 -v 0.018250 -0.127048 0.134889 -vn 0.129673 0.306403 -0.943028 -v 0.018250 -0.127831 0.134564 -vn 0.126949 0.701387 -0.701385 -v 0.018250 -0.125682 0.135882 -vn 0.129677 0.582819 -0.802188 -v 0.018250 -0.126326 0.135331 -vn 0.126914 0.883803 -0.450317 -v 0.018250 -0.124689 0.137248 -vn 0.129676 0.802189 -0.582818 -v 0.018250 -0.125131 0.136526 -vn 0.126934 0.979699 -0.155171 -v 0.018250 -0.124166 0.138855 -vn 0.129705 0.943022 -0.306408 -v 0.018250 -0.124364 0.138031 -vn 0.126934 0.979699 0.155168 -v 0.018250 -0.124166 0.140545 -vn 0.129700 0.991553 0.000001 -v 0.018250 -0.124100 0.139700 -vn 0.126934 0.883802 0.450314 -v 0.018250 -0.124689 0.142152 -vn 0.129693 0.943024 0.306407 -v 0.018250 -0.124364 0.141369 -vn 0.126921 0.701386 0.701391 -v 0.018250 -0.125682 0.143518 -vn 0.129700 0.802184 0.582820 -v 0.018250 -0.125131 0.142874 -vn 0.126933 0.450324 0.883797 -v 0.018250 -0.127048 0.144511 -vn 0.129674 0.582822 0.802186 -v 0.018250 -0.126326 0.144069 -vn 0.126934 0.155167 0.979699 -v 0.018250 -0.128655 0.145034 -vn 0.129714 0.306407 0.943021 -v 0.018250 -0.127831 0.144836 -vn 0.126932 -0.155166 0.979700 -v 0.018250 -0.130345 0.145034 -vn 0.129678 0.000001 0.991556 -v 0.018250 -0.129500 0.145100 -vn 0.126936 -0.450322 0.883797 -v 0.018250 -0.131952 0.144511 -vn 0.129727 -0.306414 0.943017 -v 0.018250 -0.131169 0.144836 -vn 0.126919 -0.701385 0.701392 -v 0.018250 -0.133318 0.143518 -vn 0.129675 -0.582821 0.802187 -v 0.018250 -0.132674 0.144069 -vn 0.126934 -0.883801 0.450314 -v 0.018250 -0.134311 0.142152 -vn 0.129699 -0.802183 0.582821 -v 0.018250 -0.133869 0.142874 -vn 0.129721 -0.991551 -0.000003 -v 0.018250 -0.134900 0.139700 -vn 0.126932 -0.979699 0.155172 -v 0.018250 -0.134833 0.140545 -vn 0.129673 -0.943028 0.306405 -v 0.018250 -0.134636 0.141369 -vn 0.990582 0.130223 -0.042312 -v 0.018550 -0.124650 0.138124 -vn 0.990581 0.135242 -0.021420 -v 0.018550 -0.124463 0.138902 -vn 0.750900 -0.615819 0.238573 -v 0.018550 -0.125770 0.138255 -vn 0.750899 -0.660417 -0.000000 -v 0.018550 -0.125500 0.139700 -vn 0.990581 0.096823 0.096823 -v 0.018550 -0.125894 0.143306 -vn 0.990580 0.080490 0.110784 -v 0.018550 -0.126502 0.143826 -vn 0.750898 -0.488055 -0.444921 -v 0.018550 -0.126544 0.142395 -vn 0.750899 -0.294375 -0.591180 -v 0.018550 -0.127717 0.143281 -vn 0.750900 0.180732 0.635205 -v 0.018550 -0.130595 0.135853 -vn 0.750898 0.397991 0.527024 -v 0.018550 -0.131911 0.136508 -vn 0.990581 -0.062162 -0.122002 -v 0.018550 -0.131815 0.135156 -vn 0.750898 0.561497 0.347667 -v 0.018550 -0.132901 0.137594 -vn 0.990581 -0.096824 -0.096824 -v 0.018550 -0.133106 0.136094 -vn 0.990581 -0.080482 -0.110776 -v 0.018550 -0.132498 0.135574 -vn 0.990582 -0.135235 -0.021419 -v 0.018550 -0.134537 0.138902 -vn 0.750900 0.649171 0.121353 -v 0.018550 -0.133432 0.138965 -vn 0.990580 -0.136933 0.000001 -v 0.018550 -0.134600 0.139700 -vn 0.750900 0.649171 -0.121353 -v 0.018550 -0.133432 0.140435 -vn 0.990582 -0.135236 0.021418 -v 0.018550 -0.134537 0.140498 -vn 0.990581 -0.042314 0.130225 -v 0.018550 -0.131076 0.144550 -vn 0.990581 -0.062163 0.122002 -v 0.018550 -0.131815 0.144244 -vn 0.750898 0.180735 -0.635206 -v 0.018550 -0.130595 0.143547 -vn 0.750898 0.397991 -0.527024 -v 0.018550 -0.131911 0.142892 -vn 0.990581 0.062165 0.122007 -v 0.018550 -0.127185 0.144244 -vn 0.990581 0.042313 0.130226 -v 0.018550 -0.127924 0.144550 -vn 0.750900 -0.060934 -0.657599 -v 0.018550 -0.129131 0.143683 -vn 0.990580 0.136934 -0.000001 -v 0.018550 -0.124400 0.139700 -vn 0.990581 0.135242 0.021420 -v 0.018550 -0.124463 0.140498 -vn 0.750899 -0.615820 -0.238572 -v 0.018550 -0.125770 0.141145 -vn 0.750897 -0.488054 0.444923 -v 0.018550 -0.126544 0.137005 -vn 0.990581 0.110776 -0.080482 -v 0.018550 -0.125374 0.136702 -vn 0.990581 0.122001 -0.062163 -v 0.018550 -0.124956 0.137385 -vn 0.990582 0.021421 -0.135238 -v 0.018550 -0.128702 0.134663 -vn 0.990579 0.042317 -0.130238 -v 0.018550 -0.127924 0.134850 -vn 0.750899 -0.060937 0.657600 -v 0.018550 -0.129131 0.135717 -vn 0.750899 -0.294375 0.591180 -v 0.018550 -0.127717 0.136119 -vn 0.990582 -0.130223 -0.042311 -v 0.018550 -0.134350 0.138124 -vn 0.990580 -0.122007 -0.062165 -v 0.018550 -0.134044 0.137385 -vn 0.990581 -0.110775 -0.080483 -v 0.018550 -0.133626 0.136702 -vn 0.990582 -0.130222 0.042311 -v 0.018550 -0.134350 0.141276 -vn 0.750898 0.561497 -0.347667 -v 0.018550 -0.132901 0.141806 -vn 0.990580 -0.122007 0.062166 -v 0.018550 -0.134044 0.142015 -vn 0.990580 -0.080488 0.110785 -v 0.018550 -0.132498 0.143826 -vn 0.990581 -0.096823 0.096823 -v 0.018550 -0.133106 0.143306 -vn 0.990581 -0.110776 0.080484 -v 0.018550 -0.133626 0.142698 -vn 0.990580 0.021423 0.135250 -v 0.018550 -0.128702 0.144737 -vn 0.990580 -0.000000 0.136934 -v 0.018550 -0.129500 0.144800 -vn 0.990580 -0.021421 0.135248 -v 0.018550 -0.130298 0.144737 -vn 0.990582 0.130222 0.042312 -v 0.018550 -0.124650 0.141276 -vn 0.990581 0.122002 0.062163 -v 0.018550 -0.124956 0.142015 -vn 0.990581 0.110776 0.080484 -v 0.018550 -0.125374 0.142698 -vn 0.990581 0.062165 -0.122006 -v 0.018550 -0.127185 0.135156 -vn 0.990581 0.080484 -0.110776 -v 0.018550 -0.126502 0.135574 -vn 0.990581 0.096824 -0.096823 -v 0.018550 -0.125894 0.136094 -vn 0.990579 -0.042319 -0.130237 -v 0.018550 -0.131076 0.134850 -vn 0.990582 -0.021418 -0.135236 -v 0.018550 -0.130298 0.134663 -vn 0.990580 -0.000001 -0.136934 -v 0.018550 -0.129500 0.134600 -vn 0.667992 -0.744168 0.000000 -v 0.017950 -0.125500 0.139700 -vn 0.667992 -0.693915 -0.268826 -v 0.017950 -0.125770 0.141145 -vn 0.667993 -0.549946 -0.501342 -v 0.017950 -0.126544 0.142395 -vn 0.667992 -0.331706 -0.666151 -v 0.017950 -0.127717 0.143281 -vn 0.667992 -0.068661 -0.740994 -v 0.017950 -0.129131 0.143683 -vn 0.667993 0.203655 -0.715758 -v 0.017950 -0.130595 0.143547 -vn 0.667993 0.448462 -0.593858 -v 0.017950 -0.131911 0.142892 -vn 0.667993 0.632703 -0.391756 -v 0.017950 -0.132901 0.141806 -vn 0.667992 0.731497 -0.136743 -v 0.017950 -0.133432 0.140435 -vn 0.667992 0.731497 0.136743 -v 0.017950 -0.133432 0.138965 -vn 0.667993 0.632703 0.391756 -v 0.017950 -0.132901 0.137594 -vn 0.667993 0.448462 0.593858 -v 0.017950 -0.131911 0.136508 -vn 0.667992 0.203652 0.715760 -v 0.017950 -0.130595 0.135853 -vn 0.667993 -0.068665 0.740993 -v 0.017950 -0.129131 0.135717 -vn 0.667992 -0.331706 0.666151 -v 0.017950 -0.127717 0.136119 -vn 0.667994 -0.549945 0.501344 -v 0.017950 -0.126544 0.137005 -vn 0.667992 -0.693915 0.268828 -v 0.017950 -0.125770 0.138255 -vn 0.976004 -0.108877 0.188581 -v 0.017950 -0.128737 0.138379 -vn 0.976001 -0.188593 0.108882 -v 0.017950 -0.128179 0.138937 -vn 0.976002 -0.217762 0.000001 -v 0.017950 -0.127975 0.139700 -vn 0.976002 -0.188587 -0.108882 -v 0.017950 -0.128179 0.140462 -vn 0.976003 0.108879 0.188585 -v 0.017950 -0.130262 0.138379 -vn 0.976002 -0.000000 0.217760 -v 0.017950 -0.129500 0.138175 -vn 0.976004 0.188579 -0.108878 -v 0.017950 -0.130821 0.140462 -vn 0.976002 0.217760 0.000001 -v 0.017950 -0.131025 0.139700 -vn 0.976003 0.188585 0.108879 -v 0.017950 -0.130821 0.138937 -vn 0.976002 -0.000000 -0.217762 -v 0.017950 -0.129500 0.141225 -vn 0.976001 0.108884 -0.188591 -v 0.017950 -0.130262 0.141021 -vn 0.976002 -0.108881 -0.188587 -v 0.017950 -0.128737 0.141021 -vn -1.000000 0.000002 0.000003 -v 0.015731 -0.138500 0.130450 -vn -0.460550 0.768712 -0.443820 -v 0.015250 -0.139193 0.130850 -vn -0.460549 0.443809 -0.768718 -v 0.015250 -0.138900 0.131143 -vn -0.460548 0.887635 0.000004 -v 0.015250 -0.139300 0.130450 -vn -0.460550 -0.443807 -0.768719 -v 0.015250 -0.138100 0.131143 -vn -0.460550 -0.768719 -0.443806 -v 0.015250 -0.137807 0.130850 -vn -0.460552 0.000004 -0.887633 -v 0.015250 -0.138500 0.131250 -vn -0.460549 -0.768718 0.443810 -v 0.015250 -0.137807 0.130050 -vn -0.460549 -0.443820 0.768712 -v 0.015250 -0.138100 0.129757 -vn -0.460551 -0.887633 0.000004 -v 0.015250 -0.137700 0.130450 -vn -0.460548 0.443823 0.768711 -v 0.015250 -0.138900 0.129757 -vn -0.460548 0.768711 0.443823 -v 0.015250 -0.139193 0.130050 -vn -0.460548 0.000004 0.887635 -v 0.015250 -0.138500 0.129650 -vn -0.539406 0.842046 0.000003 -v 0.010808 -0.139300 0.130450 -vn -0.539398 0.729234 -0.421031 -v 0.010808 -0.139193 0.130850 -vn -0.539388 0.421015 -0.729251 -v 0.010808 -0.138900 0.131143 -vn -0.539397 0.000008 -0.842051 -v 0.010808 -0.138500 0.131250 -vn -0.539376 -0.421027 -0.729253 -v 0.010808 -0.138100 0.131143 -vn -0.539399 -0.729240 -0.421021 -v 0.010808 -0.137807 0.130850 -vn -0.539399 -0.842050 0.000004 -v 0.010808 -0.137700 0.130450 -vn -0.539415 -0.729234 0.421009 -v 0.010808 -0.137807 0.130050 -vn -0.539400 -0.421028 0.729235 -v 0.010808 -0.138100 0.129757 -vn -0.539405 0.000003 0.842046 -v 0.010808 -0.138500 0.129650 -vn -0.539412 0.421023 0.729228 -v 0.010808 -0.138900 0.129757 -vn -0.539413 0.729227 0.421024 -v 0.010808 -0.139193 0.130050 -vn -1.000000 0.000002 0.000003 -v 0.015731 -0.138500 0.148950 -vn -0.460549 0.768712 -0.443820 -v 0.015250 -0.139193 0.149350 -vn -0.460549 0.443810 -0.768718 -v 0.015250 -0.138900 0.149643 -vn -0.460548 0.887635 0.000004 -v 0.015250 -0.139300 0.148950 -vn -0.460550 -0.443807 -0.768720 -v 0.015250 -0.138100 0.149643 -vn -0.460550 -0.768720 -0.443806 -v 0.015250 -0.137807 0.149350 -vn -0.460552 0.000004 -0.887633 -v 0.015250 -0.138500 0.149750 -vn -0.460549 -0.768718 0.443810 -v 0.015250 -0.137807 0.148550 -vn -0.460549 -0.443820 0.768712 -v 0.015250 -0.138100 0.148257 -vn -0.460551 -0.887633 0.000004 -v 0.015250 -0.137700 0.148950 -vn -0.460548 0.443823 0.768711 -v 0.015250 -0.138900 0.148257 -vn -0.460548 0.768711 0.443823 -v 0.015250 -0.139193 0.148550 -vn -0.460548 0.000004 0.887635 -v 0.015250 -0.138500 0.148150 -vn -0.539406 0.842046 0.000003 -v 0.010808 -0.139300 0.148950 -vn -0.539398 0.729234 -0.421031 -v 0.010808 -0.139193 0.149350 -vn -0.539388 0.421015 -0.729251 -v 0.010808 -0.138900 0.149643 -vn -0.539397 0.000008 -0.842051 -v 0.010808 -0.138500 0.149750 -vn -0.539376 -0.421027 -0.729253 -v 0.010808 -0.138100 0.149643 -vn -0.539399 -0.729240 -0.421021 -v 0.010808 -0.137807 0.149350 -vn -0.539399 -0.842050 0.000004 -v 0.010808 -0.137700 0.148950 -vn -0.539415 -0.729234 0.421009 -v 0.010808 -0.137807 0.148550 -vn -0.539400 -0.421028 0.729235 -v 0.010808 -0.138100 0.148257 -vn -0.539405 0.000003 0.842046 -v 0.010808 -0.138500 0.148150 -vn -0.539412 0.421023 0.729228 -v 0.010808 -0.138900 0.148257 -vn -0.539413 0.729227 0.421024 -v 0.010808 -0.139193 0.148550 -vn -1.000000 0.000001 0.000001 -v 0.015731 -0.096500 0.129300 -vn -0.460549 0.768710 -0.443824 -v 0.015250 -0.097193 0.129700 -vn -0.460550 0.443816 -0.768714 -v 0.015250 -0.096900 0.129993 -vn -0.460548 0.887635 0.000004 -v 0.015250 -0.097300 0.129300 -vn -0.460551 -0.443812 -0.768716 -v 0.015250 -0.096100 0.129993 -vn -0.460548 -0.768711 -0.443822 -v 0.015250 -0.095807 0.129700 -vn -0.460548 0.000000 -0.887635 -v 0.015250 -0.096500 0.130100 -vn -0.460548 -0.768715 0.443816 -v 0.015250 -0.095807 0.128900 -vn -0.460549 -0.443821 0.768711 -v 0.015250 -0.096100 0.128607 -vn -0.460550 -0.887634 0.000004 -v 0.015250 -0.095700 0.129300 -vn -0.460548 0.443826 0.768709 -v 0.015250 -0.096900 0.128607 -vn -0.460549 0.768713 0.443818 -v 0.015250 -0.097193 0.128900 -vn -0.460548 -0.000000 0.887635 -v 0.015250 -0.096500 0.128500 -vn -0.539406 0.842046 0.000003 -v 0.010808 -0.097300 0.129300 -vn -0.539399 0.729231 -0.421036 -v 0.010808 -0.097193 0.129700 -vn -0.539403 0.421025 -0.729234 -v 0.010808 -0.096900 0.129993 -vn -0.539406 -0.000001 -0.842046 -v 0.010808 -0.096500 0.130100 -vn -0.539403 -0.421019 -0.729238 -v 0.010808 -0.096100 0.129993 -vn -0.539403 -0.729231 -0.421030 -v 0.010808 -0.095807 0.129700 -vn -0.539402 -0.842048 0.000004 -v 0.010808 -0.095700 0.129300 -vn -0.539414 -0.729232 0.421015 -v 0.010808 -0.095807 0.128900 -vn -0.539406 -0.421026 0.729231 -v 0.010808 -0.096100 0.128607 -vn -0.539406 0.000001 0.842046 -v 0.010808 -0.096500 0.128500 -vn -0.539406 0.421032 0.729228 -v 0.010808 -0.096900 0.128607 -vn -0.539411 0.729230 0.421021 -v 0.010808 -0.097193 0.128900 -vn -1.000000 0.000001 0.000004 -v 0.015731 -0.096500 0.150100 -vn -0.460551 0.768714 -0.443815 -v 0.015250 -0.097193 0.150500 -vn -0.460551 0.443825 -0.768708 -v 0.015250 -0.096900 0.150793 -vn -0.460548 0.887635 0.000004 -v 0.015250 -0.097300 0.150100 -vn -0.460552 -0.443820 -0.768710 -v 0.015250 -0.096100 0.150793 -vn -0.460550 -0.768716 -0.443813 -v 0.015250 -0.095807 0.150500 -vn -0.460552 0.000000 -0.887633 -v 0.015250 -0.096500 0.150900 -vn -0.460549 -0.768715 0.443816 -v 0.015250 -0.095807 0.149700 -vn -0.460550 -0.443821 0.768711 -v 0.015250 -0.096100 0.149407 -vn -0.460550 -0.887634 0.000004 -v 0.015250 -0.095700 0.150100 -vn -0.460549 0.443826 0.768709 -v 0.015250 -0.096900 0.149407 -vn -0.460550 0.768713 0.443818 -v 0.015250 -0.097193 0.149700 -vn -0.460548 -0.000000 0.887635 -v 0.015250 -0.096500 0.149300 -vn -0.539406 0.842046 0.000003 -v 0.010808 -0.097300 0.150100 -vn -0.539397 0.729238 -0.421027 -v 0.010808 -0.097193 0.150500 -vn -0.539406 0.421034 -0.729227 -v 0.010808 -0.096900 0.150793 -vn -0.539376 -0.000006 -0.842065 -v 0.010808 -0.096500 0.150900 -vn -0.539403 -0.421024 -0.729235 -v 0.010808 -0.096100 0.150793 -vn -0.539401 -0.729238 -0.421022 -v 0.010808 -0.095807 0.150500 -vn -0.539402 -0.842048 0.000004 -v 0.010808 -0.095700 0.150100 -vn -0.539414 -0.729232 0.421015 -v 0.010808 -0.095807 0.149700 -vn -0.539406 -0.421026 0.729231 -v 0.010808 -0.096100 0.149407 -vn -0.539406 0.000001 0.842046 -v 0.010808 -0.096500 0.149300 -vn -0.539406 0.421032 0.729228 -v 0.010808 -0.096900 0.149407 -vn -0.539411 0.729230 0.421021 -v 0.010808 -0.097193 0.149700 -vn 0.539395 -0.842053 0.000002 -v 0.017791 -0.128250 0.139700 -vn 0.539398 -0.729241 -0.421020 -v 0.017791 -0.128417 0.140325 -vn 0.539397 -0.421019 -0.729242 -v 0.017791 -0.128875 0.140783 -vn 0.539395 -0.000001 -0.842053 -v 0.017791 -0.129500 0.140950 -vn 0.539394 0.421030 -0.729238 -v 0.017791 -0.130125 0.140783 -vn 0.539402 0.729235 -0.421025 -v 0.017791 -0.130583 0.140325 -vn 0.539401 0.842049 0.000002 -v 0.017791 -0.130750 0.139700 -vn 0.539399 0.729235 0.421029 -v 0.017791 -0.130583 0.139075 -vn 0.539400 0.421030 0.729234 -v 0.017791 -0.130125 0.138617 -vn 0.539400 -0.000001 0.842050 -v 0.017791 -0.129500 0.138450 -vn 0.539403 -0.421019 0.729238 -v 0.017791 -0.128875 0.138617 -vn 0.539395 -0.729240 0.421024 -v 0.017791 -0.128417 0.139075 -vn 0.406938 -0.913456 -0.000005 -v 0.015650 -0.136100 0.133700 -vn 0.406981 -0.791063 -0.456712 -v 0.015650 -0.136221 0.134150 -vn 0.406968 -0.456724 -0.791063 -v 0.015650 -0.136550 0.134479 -vn 0.406973 -0.000000 -0.913440 -v 0.015650 -0.137000 0.134600 -vn 0.406983 0.456707 -0.791065 -v 0.015650 -0.137450 0.134479 -vn 0.406957 0.791075 -0.456712 -v 0.015650 -0.137779 0.134150 -vn 0.406967 0.913443 -0.000005 -v 0.015650 -0.137900 0.133700 -vn 0.406939 0.791073 0.456732 -v 0.015650 -0.137779 0.133250 -vn 0.406979 0.456716 0.791061 -v 0.015650 -0.137450 0.132921 -vn 0.406974 -0.000001 0.913440 -v 0.015650 -0.137000 0.132800 -vn 0.406966 -0.456728 0.791062 -v 0.015650 -0.136550 0.132921 -vn 0.406966 -0.791062 0.456728 -v 0.015650 -0.136221 0.133250 -vn 0.406955 -0.913448 -0.000003 -v 0.015650 -0.122600 0.131700 -vn 0.406982 -0.791067 -0.456705 -v 0.015650 -0.122721 0.132150 -vn 0.406940 -0.456719 -0.791080 -v 0.015650 -0.123050 0.132479 -vn 0.406966 -0.000006 -0.913443 -v 0.015650 -0.123500 0.132600 -vn 0.406947 0.456722 -0.791075 -v 0.015650 -0.123950 0.132479 -vn 0.406966 0.791071 -0.456712 -v 0.015650 -0.124279 0.132150 -vn 0.406971 0.913441 -0.000002 -v 0.015650 -0.124400 0.131700 -vn 0.406952 0.791067 0.456730 -v 0.015650 -0.124279 0.131250 -vn 0.406972 0.456722 0.791061 -v 0.015650 -0.123950 0.130921 -vn 0.406938 -0.000006 0.913456 -v 0.015650 -0.123500 0.130800 -vn 0.406963 -0.456724 0.791066 -v 0.015650 -0.123050 0.130921 -vn 0.406966 -0.791062 0.456728 -v 0.015650 -0.122721 0.131250 -vn 0.406970 -0.913442 0.000003 -v 0.015650 -0.107100 0.131700 -vn 0.406970 -0.791071 -0.456709 -v 0.015650 -0.107221 0.132150 -vn 0.406947 -0.456713 -0.791080 -v 0.015650 -0.107550 0.132479 -vn 0.406967 -0.000005 -0.913443 -v 0.015650 -0.108000 0.132600 -vn 0.406948 0.456726 -0.791072 -v 0.015650 -0.108450 0.132479 -vn 0.406980 0.791062 -0.456714 -v 0.015650 -0.108779 0.132150 -vn 0.406956 0.913448 0.000004 -v 0.015650 -0.108900 0.131700 -vn 0.406964 0.791064 0.456726 -v 0.015650 -0.108779 0.131250 -vn 0.406974 0.456725 0.791059 -v 0.015650 -0.108450 0.130921 -vn 0.406938 -0.000006 0.913456 -v 0.015650 -0.108000 0.130800 -vn 0.406971 -0.456713 0.791067 -v 0.015650 -0.107550 0.130921 -vn 0.406953 -0.791071 0.456723 -v 0.015650 -0.107221 0.131250 -vn 0.406938 -0.913456 -0.000005 -v 0.015650 -0.136100 0.145700 -vn 0.406980 -0.791069 -0.456703 -v 0.015650 -0.136221 0.146150 -vn 0.406940 -0.456719 -0.791080 -v 0.015650 -0.136550 0.146479 -vn 0.406966 -0.000006 -0.913443 -v 0.015650 -0.137000 0.146600 -vn 0.406956 0.456711 -0.791076 -v 0.015650 -0.137450 0.146479 -vn 0.406953 0.791080 -0.456708 -v 0.015650 -0.137779 0.146150 -vn 0.406967 0.913443 -0.000005 -v 0.015650 -0.137900 0.145700 -vn 0.406939 0.791073 0.456732 -v 0.015650 -0.137779 0.145250 -vn 0.406981 0.456703 0.791068 -v 0.015650 -0.137450 0.144921 -vn 0.406971 -0.000001 0.913441 -v 0.015650 -0.137000 0.144800 -vn 0.406968 -0.456715 0.791068 -v 0.015650 -0.136550 0.144921 -vn 0.406966 -0.791062 0.456728 -v 0.015650 -0.136221 0.145250 -vn 0.406970 -0.913442 0.000003 -v 0.015650 -0.107100 0.147700 -vn 0.406971 -0.791065 -0.456718 -v 0.015650 -0.107221 0.148150 -vn 0.406975 -0.456718 -0.791063 -v 0.015650 -0.107550 0.148479 -vn 0.406973 0.000001 -0.913440 -v 0.015650 -0.108000 0.148600 -vn 0.406975 0.456722 -0.791060 -v 0.015650 -0.108450 0.148479 -vn 0.406984 0.791057 -0.456719 -v 0.015650 -0.108779 0.148150 -vn 0.406956 0.913448 0.000004 -v 0.015650 -0.108900 0.147700 -vn 0.406964 0.791064 0.456726 -v 0.015650 -0.108779 0.147250 -vn 0.406974 0.456725 0.791059 -v 0.015650 -0.108450 0.146921 -vn 0.406973 -0.000001 0.913440 -v 0.015650 -0.108000 0.146800 -vn 0.406975 -0.456717 0.791063 -v 0.015650 -0.107550 0.146921 -vn 0.406953 -0.791071 0.456723 -v 0.015650 -0.107221 0.147250 -vn 0.406955 -0.913448 -0.000003 -v 0.015650 -0.122600 0.147700 -vn 0.406983 -0.791061 -0.456714 -v 0.015650 -0.122721 0.148150 -vn 0.406968 -0.456724 -0.791063 -v 0.015650 -0.123050 0.148479 -vn 0.406973 -0.000000 -0.913440 -v 0.015650 -0.123500 0.148600 -vn 0.406975 0.456717 -0.791063 -v 0.015650 -0.123950 0.148479 -vn 0.406970 0.791066 -0.456717 -v 0.015650 -0.124279 0.148150 -vn 0.406971 0.913441 -0.000002 -v 0.015650 -0.124400 0.147700 -vn 0.406952 0.791067 0.456730 -v 0.015650 -0.124279 0.147250 -vn 0.406972 0.456722 0.791061 -v 0.015650 -0.123950 0.146921 -vn 0.406973 -0.000001 0.913440 -v 0.015650 -0.123500 0.146800 -vn 0.406966 -0.456728 0.791061 -v 0.015650 -0.123050 0.146921 -vn 0.406966 -0.791062 0.456728 -v 0.015650 -0.122721 0.147250 -vn 0.496973 -0.033951 -0.867102 -v 0.015250 -0.136000 0.126834 -vn 0.863074 -0.019976 -0.504683 -v 0.015616 -0.136000 0.127200 -vn 0.863078 -0.504675 -0.019974 -v 0.015616 -0.140500 0.131700 -vn 0.860427 -0.503300 -0.079715 -v 0.015616 -0.140445 0.130996 -vn 0.496980 -0.867098 -0.033951 -v 0.015250 -0.140866 0.131700 -vn 0.494486 -0.858484 -0.135973 -v 0.015250 -0.140806 0.130939 -vn 0.494484 -0.826646 -0.268592 -v 0.015250 -0.140628 0.130196 -vn 0.494488 -0.774450 -0.394599 -v 0.015250 -0.140336 0.129491 -vn 0.494488 -0.703184 -0.510895 -v 0.015250 -0.139937 0.128840 -vn 0.494475 -0.614615 -0.614608 -v 0.015250 -0.139441 0.128259 -vn 0.494482 -0.510894 -0.703189 -v 0.015250 -0.138860 0.127763 -vn 0.494477 -0.394601 -0.774457 -v 0.015250 -0.138209 0.127364 -vn 0.494478 -0.268595 -0.826648 -v 0.015250 -0.137504 0.127072 -vn 0.494477 -0.135976 -0.858489 -v 0.015250 -0.136761 0.126894 -vn 0.860421 -0.484643 -0.157468 -v 0.015616 -0.140280 0.130309 -vn 0.860428 -0.454031 -0.231344 -v 0.015616 -0.140010 0.129657 -vn 0.860426 -0.412257 -0.299519 -v 0.015616 -0.139641 0.129055 -vn 0.860423 -0.360330 -0.360325 -v 0.015616 -0.139182 0.128518 -vn 0.860424 -0.299523 -0.412259 -v 0.015616 -0.138645 0.128059 -vn 0.860424 -0.231341 -0.454040 -v 0.015616 -0.138043 0.127690 -vn 0.860422 -0.157472 -0.484641 -v 0.015616 -0.137391 0.127420 -vn 0.860423 -0.079716 -0.503307 -v 0.015616 -0.136704 0.127255 -vn 0.863077 -0.504677 0.019975 -v 0.015616 -0.140500 0.147700 -vn 0.496981 -0.867097 0.033951 -v 0.015250 -0.140866 0.147700 -vn 0.863077 -0.019977 0.504677 -v 0.015616 -0.136000 0.152200 -vn 0.860423 -0.079714 0.503308 -v 0.015616 -0.136704 0.152145 -vn 0.496979 -0.033959 0.867098 -v 0.015250 -0.136000 0.152566 -vn 0.494480 -0.135973 0.858488 -v 0.015250 -0.136761 0.152506 -vn 0.494478 -0.268595 0.826649 -v 0.015250 -0.137504 0.152328 -vn 0.494478 -0.394606 0.774453 -v 0.015250 -0.138209 0.152036 -vn 0.494483 -0.510895 0.703188 -v 0.015250 -0.138860 0.151637 -vn 0.494481 -0.614609 0.614609 -v 0.015250 -0.139441 0.151141 -vn 0.494489 -0.703186 0.510891 -v 0.015250 -0.139937 0.150560 -vn 0.494486 -0.774451 0.394600 -v 0.015250 -0.140336 0.149909 -vn 0.494481 -0.826646 0.268598 -v 0.015250 -0.140628 0.149204 -vn 0.494485 -0.858485 0.135970 -v 0.015250 -0.140806 0.148461 -vn 0.860422 -0.157470 0.484642 -v 0.015616 -0.137391 0.151980 -vn 0.860423 -0.231346 0.454038 -v 0.015616 -0.138043 0.151710 -vn 0.860422 -0.299523 0.412261 -v 0.015616 -0.138645 0.151341 -vn 0.860424 -0.360329 0.360325 -v 0.015616 -0.139182 0.150882 -vn 0.860426 -0.412256 0.299519 -v 0.015616 -0.139641 0.150345 -vn 0.860425 -0.454035 0.231345 -v 0.015616 -0.140010 0.149743 -vn 0.860423 -0.484639 0.157471 -v 0.015616 -0.140280 0.149091 -vn 0.860427 -0.503301 0.079713 -v 0.015616 -0.140445 0.148404 -vn 0.127823 -0.495888 0.858927 -v 0.018450 -0.103850 0.149660 -vn 0.127833 -0.858920 0.495898 -v 0.018450 -0.103960 0.149550 -vn 0.854928 0.069833 0.514025 -v 0.018710 -0.097300 0.149550 -vn 0.854932 -0.069820 0.514021 -v 0.018710 -0.103700 0.149550 -vn 0.488319 0.112932 0.865327 -v 0.018600 -0.097300 0.149660 -vn 0.488321 -0.112919 0.865328 -v 0.018600 -0.103700 0.149660 -vn 0.127833 0.858927 0.495886 -v 0.018450 -0.097040 0.149550 -vn 0.127838 0.495887 0.858926 -v 0.018450 -0.097150 0.149660 -vn 0.488337 -0.865318 0.112921 -v 0.018600 -0.103960 0.149400 -vn 0.482350 -0.758628 0.437975 -v 0.018600 -0.103925 0.149530 -vn 0.847440 -0.265473 0.459749 -v 0.018710 -0.103775 0.149530 -vn 0.847437 -0.459783 0.265425 -v 0.018710 -0.103830 0.149475 -vn 0.482345 -0.438004 0.758614 -v 0.018600 -0.103830 0.149625 -vn 0.854929 -0.514026 0.069807 -v 0.018710 -0.103850 0.149400 -vn 0.482354 0.437989 0.758618 -v 0.018600 -0.097170 0.149625 -vn 0.854929 0.514025 0.069825 -v 0.018710 -0.097150 0.149400 -vn 0.847442 0.459758 0.265451 -v 0.018710 -0.097170 0.149475 -vn 0.847435 0.265480 0.459754 -v 0.018710 -0.097225 0.149530 -vn 0.482358 0.758614 0.437990 -v 0.018600 -0.097075 0.149530 -vn 0.488322 0.865327 0.112917 -v 0.018600 -0.097040 0.149400 -vn 0.127838 -0.858911 -0.495912 -v 0.018450 -0.103960 0.143850 -vn 0.127831 -0.495888 -0.858926 -v 0.018450 -0.103850 0.143740 -vn 0.854927 -0.514030 -0.069813 -v 0.018710 -0.103850 0.144000 -vn 0.488336 -0.865317 -0.112934 -v 0.018600 -0.103960 0.144000 -vn 0.854925 0.514030 -0.069834 -v 0.018710 -0.097150 0.144000 -vn 0.488318 0.865327 -0.112937 -v 0.018600 -0.097040 0.144000 -vn 0.127833 0.495891 -0.858924 -v 0.018450 -0.097150 0.143740 -vn 0.127838 0.858923 -0.495892 -v 0.018450 -0.097040 0.143850 -vn 0.488319 -0.112925 -0.865328 -v 0.018600 -0.103700 0.143740 -vn 0.482335 -0.438002 -0.758622 -v 0.018600 -0.103830 0.143775 -vn 0.847427 -0.459781 -0.265460 -v 0.018710 -0.103830 0.143925 -vn 0.847436 -0.265441 -0.459775 -v 0.018710 -0.103775 0.143870 -vn 0.482337 -0.758628 -0.437989 -v 0.018600 -0.103925 0.143870 -vn 0.854923 -0.069827 -0.514034 -v 0.018710 -0.103700 0.143850 -vn 0.482348 0.758619 -0.437994 -v 0.018600 -0.097075 0.143870 -vn 0.854925 0.069827 -0.514031 -v 0.018710 -0.097300 0.143850 -vn 0.847435 0.265460 -0.459767 -v 0.018710 -0.097225 0.143870 -vn 0.847428 0.459761 -0.265490 -v 0.018710 -0.097170 0.143925 -vn 0.482353 0.437994 -0.758615 -v 0.018600 -0.097170 0.143775 -vn 0.488322 0.112923 -0.865327 -v 0.018600 -0.097300 0.143740 -vn 0.127833 0.858927 0.495886 -v 0.018450 -0.097040 0.135550 -vn 0.127838 0.495887 0.858926 -v 0.018450 -0.097150 0.135660 -vn 0.488322 0.865327 0.112917 -v 0.018600 -0.097040 0.135400 -vn 0.488318 0.865327 -0.112937 -v 0.018600 -0.097040 0.130000 -vn 0.854929 0.514025 0.069825 -v 0.018710 -0.097150 0.135400 -vn 0.854925 0.514030 -0.069834 -v 0.018710 -0.097150 0.130000 -vn 0.127833 0.495891 -0.858924 -v 0.018450 -0.097150 0.129740 -vn 0.127838 0.858923 -0.495892 -v 0.018450 -0.097040 0.129850 -vn 0.488319 0.112932 0.865327 -v 0.018600 -0.097300 0.135660 -vn 0.482354 0.437989 0.758618 -v 0.018600 -0.097170 0.135625 -vn 0.847442 0.459758 0.265451 -v 0.018710 -0.097170 0.135475 -vn 0.847435 0.265480 0.459754 -v 0.018710 -0.097225 0.135530 -vn 0.482358 0.758614 0.437990 -v 0.018600 -0.097075 0.135530 -vn 0.854928 0.069833 0.514025 -v 0.018710 -0.097300 0.135550 -vn 0.482348 0.758619 -0.437994 -v 0.018600 -0.097075 0.129870 -vn 0.854925 0.069827 -0.514031 -v 0.018710 -0.097300 0.129850 -vn 0.847435 0.265460 -0.459767 -v 0.018710 -0.097225 0.129870 -vn 0.847428 0.459761 -0.265490 -v 0.018710 -0.097170 0.129925 -vn 0.482353 0.437994 -0.758615 -v 0.018600 -0.097170 0.129775 -vn 0.488322 0.112923 -0.865327 -v 0.018600 -0.097300 0.129740 -vn 0.127823 -0.495888 0.858927 -v 0.018450 -0.103850 0.135660 -vn 0.127833 -0.858920 0.495898 -v 0.018450 -0.103960 0.135550 -vn 0.488321 -0.112919 0.865328 -v 0.018600 -0.103700 0.135660 -vn 0.854932 -0.069820 0.514021 -v 0.018710 -0.103700 0.135550 -vn 0.488319 -0.112925 -0.865328 -v 0.018600 -0.103700 0.129740 -vn 0.854923 -0.069827 -0.514034 -v 0.018710 -0.103700 0.129850 -vn 0.127838 -0.858911 -0.495912 -v 0.018450 -0.103960 0.129850 -vn 0.127831 -0.495888 -0.858926 -v 0.018450 -0.103850 0.129740 -vn 0.488337 -0.865318 0.112921 -v 0.018600 -0.103960 0.135400 -vn 0.482350 -0.758628 0.437975 -v 0.018600 -0.103925 0.135530 -vn 0.847440 -0.265473 0.459749 -v 0.018710 -0.103775 0.135530 -vn 0.847437 -0.459783 0.265425 -v 0.018710 -0.103830 0.135475 -vn 0.482345 -0.438004 0.758614 -v 0.018600 -0.103830 0.135625 -vn 0.854929 -0.514026 0.069807 -v 0.018710 -0.103850 0.135400 -vn 0.482335 -0.438002 -0.758622 -v 0.018600 -0.103830 0.129775 -vn 0.854927 -0.514030 -0.069813 -v 0.018710 -0.103850 0.130000 -vn 0.847427 -0.459781 -0.265460 -v 0.018710 -0.103830 0.129925 -vn 0.847436 -0.265441 -0.459775 -v 0.018710 -0.103775 0.129870 -vn 0.482337 -0.758628 -0.437989 -v 0.018600 -0.103925 0.129870 -vn 0.488336 -0.865317 -0.112934 -v 0.018600 -0.103960 0.130000 -vn 0.860426 0.503302 0.079717 -v 0.018510 -0.124315 0.140521 -vn 0.860420 0.484645 0.157470 -v 0.018510 -0.124507 0.141322 -vn 0.860425 0.454037 0.231343 -v 0.018510 -0.124822 0.142083 -vn 0.860426 0.412255 0.299520 -v 0.018510 -0.125253 0.142786 -vn 0.860432 0.360316 0.360318 -v 0.018510 -0.125788 0.143412 -vn 0.860421 0.299528 0.412260 -v 0.018510 -0.126414 0.143947 -vn 0.860421 0.231346 0.454042 -v 0.018510 -0.127117 0.144378 -vn 0.860424 0.157467 0.484638 -v 0.018510 -0.127878 0.144693 -vn 0.860434 0.079712 0.503289 -v 0.018510 -0.128679 0.144885 -vn 0.860422 0.000002 0.509582 -v 0.018510 -0.129500 0.144950 -vn 0.860434 -0.079717 0.503287 -v 0.018510 -0.130321 0.144885 -vn 0.860418 -0.157469 0.484649 -v 0.018510 -0.131122 0.144693 -vn 0.860425 -0.231345 0.454036 -v 0.018510 -0.131883 0.144378 -vn 0.860433 -0.299515 0.412246 -v 0.018510 -0.132586 0.143947 -vn 0.860431 -0.360317 0.360319 -v 0.018510 -0.133212 0.143412 -vn 0.860426 -0.412254 0.299523 -v 0.018510 -0.133747 0.142786 -vn 0.860422 -0.454041 0.231348 -v 0.018510 -0.134178 0.142083 -vn 0.860419 -0.484646 0.157471 -v 0.018510 -0.134493 0.141322 -vn 0.860420 -0.503311 0.079715 -v 0.018510 -0.134685 0.140521 -vn 0.860423 -0.509581 -0.000000 -v 0.018510 -0.134750 0.139700 -vn 0.860422 -0.503308 -0.079713 -v 0.018510 -0.134685 0.138879 -vn 0.860420 -0.484645 -0.157468 -v 0.018510 -0.134493 0.138078 -vn 0.860430 -0.454029 -0.231339 -v 0.018510 -0.134178 0.137317 -vn 0.860436 -0.412241 -0.299512 -v 0.018510 -0.133747 0.136614 -vn 0.860420 -0.360333 -0.360330 -v 0.018510 -0.133212 0.135988 -vn 0.860436 -0.299507 -0.412245 -v 0.018510 -0.132586 0.135453 -vn 0.860425 -0.231344 -0.454036 -v 0.018510 -0.131883 0.135022 -vn 0.860429 -0.157467 -0.484629 -v 0.018510 -0.131122 0.134707 -vn 0.860422 -0.079716 -0.503308 -v 0.018510 -0.130321 0.134515 -vn 0.860423 -0.000000 -0.509581 -v 0.018510 -0.129500 0.134450 -vn 0.860422 0.079714 -0.503309 -v 0.018510 -0.128679 0.134515 -vn 0.860435 0.157466 -0.484620 -v 0.018510 -0.127878 0.134707 -vn 0.860422 0.231343 -0.454042 -v 0.018510 -0.127117 0.135022 -vn 0.860425 0.299522 -0.412257 -v 0.018510 -0.126414 0.135453 -vn 0.860420 0.360330 -0.360332 -v 0.018510 -0.125788 0.135988 -vn 0.860436 0.412244 -0.299507 -v 0.018510 -0.125253 0.136614 -vn 0.860432 0.454028 -0.231335 -v 0.018510 -0.124822 0.137317 -vn 0.860420 0.484644 -0.157473 -v 0.018510 -0.124507 0.138078 -vn 0.860429 0.503297 -0.079712 -v 0.018510 -0.124315 0.138879 -vn 0.860422 0.509582 -0.000001 -v 0.018510 -0.124250 0.139700 -vn 0.494482 0.858487 0.135968 -v 0.018400 -0.124206 0.140538 -vn 0.494474 0.826650 0.268597 -v 0.018400 -0.124403 0.141356 -vn 0.494478 0.774457 0.394598 -v 0.018400 -0.124724 0.142133 -vn 0.494490 0.703187 0.510890 -v 0.018400 -0.125164 0.142850 -vn 0.494478 0.614609 0.614611 -v 0.018400 -0.125710 0.143490 -vn 0.494470 0.510900 0.703193 -v 0.018400 -0.126350 0.144036 -vn 0.494479 0.394603 0.774454 -v 0.018400 -0.127067 0.144476 -vn 0.494501 0.268595 0.826635 -v 0.018400 -0.127844 0.144797 -vn 0.494498 0.135969 0.858478 -v 0.018400 -0.128662 0.144994 -vn 0.494472 0.000003 0.869193 -v 0.018400 -0.129500 0.145060 -vn 0.494500 -0.135972 0.858476 -v 0.018400 -0.130338 0.144994 -vn 0.494506 -0.268593 0.826632 -v 0.018400 -0.131156 0.144797 -vn 0.494476 -0.394601 0.774457 -v 0.018400 -0.131933 0.144476 -vn 0.494484 -0.510896 0.703186 -v 0.018400 -0.132650 0.144036 -vn 0.494481 -0.614607 0.614611 -v 0.018400 -0.133290 0.143490 -vn 0.494493 -0.703185 0.510889 -v 0.018400 -0.133836 0.142850 -vn 0.494477 -0.774457 0.394600 -v 0.018400 -0.134276 0.142133 -vn 0.494456 -0.826661 0.268599 -v 0.018400 -0.134597 0.141356 -vn 0.494470 -0.858494 0.135969 -v 0.018400 -0.134794 0.140538 -vn 0.494509 -0.869173 -0.000004 -v 0.018400 -0.134860 0.139700 -vn 0.494472 -0.858493 -0.135969 -v 0.018400 -0.134794 0.138862 -vn 0.494467 -0.826656 -0.268593 -v 0.018400 -0.134597 0.138044 -vn 0.494471 -0.774458 -0.394604 -v 0.018400 -0.134276 0.137267 -vn 0.494486 -0.703185 -0.510896 -v 0.018400 -0.133836 0.136550 -vn 0.494488 -0.614608 -0.614604 -v 0.018400 -0.133290 0.135910 -vn 0.494485 -0.510895 -0.703186 -v 0.018400 -0.132650 0.135364 -vn 0.494514 -0.394589 -0.774439 -v 0.018400 -0.131933 0.134924 -vn 0.494493 -0.268592 -0.826641 -v 0.018400 -0.131156 0.134603 -vn 0.494475 -0.135974 -0.858490 -v 0.018400 -0.130338 0.134406 -vn 0.494509 0.000004 -0.869173 -v 0.018400 -0.129500 0.134340 -vn 0.494472 0.135968 -0.858493 -v 0.018400 -0.128662 0.134406 -vn 0.494491 0.268596 -0.826641 -v 0.018400 -0.127844 0.134603 -vn 0.494514 0.394595 -0.774436 -v 0.018400 -0.127067 0.134924 -vn 0.494469 0.510896 -0.703197 -v 0.018400 -0.126350 0.135364 -vn 0.494488 0.614610 -0.614602 -v 0.018400 -0.125710 0.135910 -vn 0.494483 0.703189 -0.510894 -v 0.018400 -0.125164 0.136550 -vn 0.494474 0.774457 -0.394603 -v 0.018400 -0.124724 0.137267 -vn 0.494487 0.826644 -0.268592 -v 0.018400 -0.124403 0.138044 -vn 0.494485 0.858485 -0.135971 -v 0.018400 -0.124206 0.138862 -vn 0.494491 0.869183 0.000001 -v 0.018400 -0.124140 0.139700 -vn -0.673142 0.513711 0.531960 -v -0.019750 -0.131410 0.137722 -vn -0.674184 0.313585 0.668685 -v -0.019750 -0.130664 0.137209 -vn -0.389849 0.465122 0.794783 -v -0.020950 -0.130706 0.137228 -vn -0.675656 0.079095 0.732962 -v -0.019750 -0.129792 0.136966 -vn -0.390519 0.189292 0.900924 -v -0.020950 -0.129883 0.136977 -vn -0.386440 0.328927 0.861668 -v -0.020950 -0.130664 0.137209 -vn -0.676926 -0.163110 0.717751 -v -0.019750 -0.128889 0.137019 -vn -0.397981 -0.113050 0.910401 -v -0.020950 -0.129022 0.136992 -vn -0.392171 0.046101 0.918736 -v -0.020950 -0.129792 0.136966 -vn -0.678007 -0.386934 0.624971 -v -0.019750 -0.128051 0.137363 -vn -0.391664 -0.390168 0.833288 -v -0.020950 -0.128209 0.137272 -vn -0.381569 -0.256504 0.888038 -v -0.020950 -0.128889 0.137019 -vn -0.678900 -0.568335 0.464855 -v -0.019750 -0.127371 0.137960 -vn -0.392139 -0.634077 0.666463 -v -0.020950 -0.127522 0.137790 -vn -0.379255 -0.525295 0.761729 -v -0.020950 -0.128051 0.137363 -vn -0.679608 -0.687893 0.254826 -v -0.019750 -0.126921 0.138745 -vn -0.392536 -0.812507 0.430984 -v -0.020950 -0.127028 0.138494 -vn -0.377173 -0.740182 0.556660 -v -0.020950 -0.127371 0.137960 -vn -0.680132 -0.732879 0.017593 -v -0.019750 -0.126751 0.139634 -vn -0.392843 -0.907100 0.151142 -v -0.020950 -0.126777 0.139317 -vn -0.375402 -0.878980 0.294053 -v -0.020950 -0.126921 0.138745 -vn -0.680486 -0.698555 -0.221267 -v -0.019750 -0.126878 0.140531 -vn -0.393069 -0.908120 -0.144275 -v -0.020950 -0.126792 0.140178 -vn -0.374008 -0.927425 0.001005 -v -0.020950 -0.126751 0.139634 -vn -0.680657 -0.588714 -0.436029 -v -0.019750 -0.127290 0.141337 -vn -0.393202 -0.815470 -0.424737 -v -0.020950 -0.127072 0.140991 -vn -0.373051 -0.880547 -0.292352 -v -0.020950 -0.126878 0.140531 -vn -0.680659 -0.415217 -0.603572 -v -0.019750 -0.127941 0.141966 -vn -0.385463 -0.632560 -0.671778 -v -0.020950 -0.127590 0.141678 -vn -0.372557 -0.743184 -0.555769 -v -0.020950 -0.127290 0.141337 -vn -0.680481 -0.196758 -0.705855 -v -0.019750 -0.128761 0.142349 -vn -0.386234 -0.387939 -0.836855 -v -0.020950 -0.128294 0.142172 -vn -0.340447 -0.551224 -0.761741 -v -0.020950 -0.127941 0.141966 -vn -0.680134 0.043159 -0.731816 -v -0.019750 -0.129662 0.142445 -vn -0.396399 -0.116061 -0.910713 -v -0.020950 -0.129117 0.142423 -vn -0.347411 -0.279398 -0.895121 -v -0.020950 -0.128761 0.142349 -vn -0.679607 0.278678 -0.678582 -v -0.019750 -0.130544 0.142244 -vn -0.387548 0.190752 -0.901898 -v -0.020950 -0.129978 0.142408 -vn -0.388765 0.039227 -0.920502 -v -0.020950 -0.129662 0.142445 -vn -0.678898 0.484413 -0.551763 -v -0.019750 -0.131314 0.141767 -vn -0.388089 0.465629 -0.795347 -v -0.020950 -0.130791 0.142128 -vn -0.360371 0.316062 -0.877632 -v -0.020950 -0.130544 0.142244 -vn -0.678012 0.638090 -0.364886 -v -0.019750 -0.131887 0.141066 -vn -0.388559 0.692766 -0.607534 -v -0.020950 -0.131478 0.141610 -vn -0.366265 0.577849 -0.729343 -v -0.020950 -0.131314 0.141767 -vn -0.676928 0.723003 -0.137967 -v -0.019750 -0.132201 0.140217 -vn -0.388968 0.848952 -0.357749 -v -0.020950 -0.131972 0.140906 -vn -0.371751 0.778404 -0.505855 -v -0.020950 -0.131887 0.141066 -vn -0.675654 0.729757 0.104623 -v -0.019750 -0.132223 0.139312 -vn -0.397710 0.913961 -0.080633 -v -0.020950 -0.132223 0.140083 -vn -0.376779 0.897147 -0.230576 -v -0.020950 -0.132201 0.140217 -vn -0.674181 0.657335 0.336734 -v -0.019750 -0.131949 0.138449 -vn -0.389591 0.893836 0.221983 -v -0.020950 -0.132208 0.139222 -vn -0.395231 0.915196 0.078800 -v -0.020950 -0.132223 0.139312 -vn -0.396859 0.637619 0.660262 -v -0.020950 -0.131410 0.137722 -vn -0.389824 0.777976 0.492738 -v -0.020950 -0.131928 0.138409 -vn -0.385335 0.850567 0.357845 -v -0.020950 -0.131949 0.138449 -vn -0.916684 -0.374753 0.138744 -v -0.021250 -0.139534 0.143415 -vn -0.916684 -0.346807 0.198534 -v -0.021250 -0.138786 0.145016 -vn -0.934356 0.356309 -0.004726 -v -0.021250 -0.132549 0.139778 -vn -0.976003 0.151267 0.156644 -v -0.021250 -0.124457 0.133405 -vn -0.976002 0.052682 0.211294 -v -0.021250 -0.123993 0.133148 -vn -0.911766 0.242088 -0.331778 -v -0.021250 -0.123364 0.130934 -vn -0.976003 -0.060021 0.209321 -v -0.021250 -0.123463 0.133157 -vn -0.930603 -0.005099 -0.365995 -v -0.021250 -0.129422 0.142749 -vn -0.915898 0.206176 0.344416 -v -0.021250 -0.123673 0.148674 -vn -0.976002 0.156646 -0.151272 -v -0.021250 -0.124680 0.146167 -vn -0.933409 -0.014962 0.358503 -v -0.021250 -0.129316 0.136656 -vn -0.976002 0.211292 -0.052681 -v -0.021250 -0.124740 0.134391 -vn -0.976002 0.209326 0.060024 -v -0.021250 -0.124731 0.133860 -vn -0.976002 -0.209326 -0.060024 -v -0.021250 -0.122760 0.134425 -vn -0.916684 0.346807 -0.198533 -v -0.021250 -0.120214 0.134384 -vn -0.976002 -0.211291 0.052682 -v -0.021250 -0.122751 0.133895 -vn -0.916688 0.309391 -0.252904 -v -0.021250 -0.121216 0.132928 -vn -0.976003 -0.156643 0.151268 -v -0.021250 -0.123008 0.133431 -vn -0.976003 -0.151267 -0.156644 -v -0.021250 -0.123033 0.134880 -vn -0.916684 0.392480 -0.075168 -v -0.021250 -0.118991 0.137687 -vn -0.916684 0.374754 -0.138743 -v -0.021250 -0.119466 0.135985 -vn -0.976002 0.211292 -0.052681 -v -0.021250 -0.124937 0.145703 -vn -0.976002 0.209328 0.060023 -v -0.021250 -0.124928 0.145172 -vn -0.930828 -0.064055 -0.359800 -v -0.021250 -0.129076 0.142720 -vn -0.917897 0.265985 -0.294476 -v -0.021250 -0.122443 0.131657 -vn -0.916687 0.355886 0.181744 -v -0.021250 -0.119971 0.144566 -vn -0.916685 0.380950 0.120691 -v -0.021250 -0.119300 0.142932 -vn -0.976000 -0.052687 -0.211302 -v -0.021250 -0.123497 0.135137 -vn -0.916686 0.395617 0.056341 -v -0.021250 -0.118907 0.141209 -vn -0.916686 0.399494 -0.009543 -v -0.021250 -0.118803 0.139444 -vn -0.976001 0.060025 -0.209332 -v -0.021250 -0.124028 0.135128 -vn -0.976002 0.052680 0.211291 -v -0.021250 -0.124191 0.144460 -vn -0.976000 -0.060025 0.209334 -v -0.021250 -0.123660 0.144469 -vn -0.932766 -0.356717 0.051969 -v -0.021250 -0.126480 0.139276 -vn -0.933026 -0.322409 0.159734 -v -0.021250 -0.126759 0.138363 -vn -0.933382 -0.256418 0.251092 -v -0.021250 -0.127306 0.137581 -vn -0.976001 0.156647 -0.151272 -v -0.021250 -0.124483 0.134855 -vn -0.933857 -0.165621 0.316987 -v -0.021250 -0.128068 0.137007 -vn -0.930829 -0.076189 0.357426 -v -0.021250 -0.128970 0.136696 -vn -0.932593 -0.355667 -0.061417 -v -0.021250 -0.126496 0.140230 -vn -0.932491 -0.319223 -0.168987 -v -0.021250 -0.126807 0.141132 -vn -0.976001 0.151277 0.156646 -v -0.021250 -0.124655 0.144717 -vn -0.934774 -0.242178 -0.259899 -v -0.021250 -0.127381 0.141894 -vn -0.935149 -0.151817 -0.320076 -v -0.021250 -0.128163 0.142441 -vn -0.976002 -0.156645 0.151270 -v -0.021250 -0.123205 0.144743 -vn -0.976002 -0.211294 0.052680 -v -0.021250 -0.122948 0.145207 -vn -0.916687 0.321117 0.237841 -v -0.021250 -0.120902 0.146069 -vn -0.976002 -0.209328 -0.060023 -v -0.021250 -0.122957 0.145737 -vn -0.916685 0.277592 0.287456 -v -0.021250 -0.122067 0.147397 -vn -0.976003 -0.151266 -0.156642 -v -0.021250 -0.123231 0.146192 -vn -0.919658 0.233913 0.315458 -v -0.021250 -0.123435 0.148515 -vn -0.976002 -0.052682 -0.211295 -v -0.021250 -0.123695 0.146449 -vn -0.976003 0.060022 -0.209320 -v -0.021250 -0.124225 0.146440 -vn -0.976000 -0.151276 -0.156649 -v -0.021250 -0.134543 0.145995 -vn -0.976002 -0.052680 -0.211292 -v -0.021250 -0.135007 0.146252 -vn -0.916685 -0.151737 0.369681 -v -0.021250 -0.133563 0.149599 -vn -0.916685 -0.309397 0.252908 -v -0.021250 -0.137784 0.146472 -vn -0.916681 -0.263559 0.300389 -v -0.021250 -0.136557 0.147743 -vn -0.976000 0.060025 -0.209334 -v -0.021250 -0.135537 0.146243 -vn -0.931356 0.358168 -0.065520 -v -0.021250 -0.132520 0.140124 -vn -0.976003 -0.060021 0.209321 -v -0.021250 -0.134972 0.144272 -vn -0.916688 -0.210510 0.339660 -v -0.021250 -0.135137 0.148795 -vn -0.976000 0.151276 0.156651 -v -0.021250 -0.135967 0.144520 -vn -0.976002 0.052683 0.211293 -v -0.021250 -0.135503 0.144263 -vn -0.976002 -0.211294 0.052682 -v -0.021250 -0.134260 0.145009 -vn -0.976003 -0.209319 -0.060022 -v -0.021250 -0.134269 0.145540 -vn -0.917266 0.166151 0.361963 -v -0.021250 -0.124969 0.149393 -vn -0.916686 0.107322 0.384928 -v -0.021250 -0.126626 0.150007 -vn -0.976001 0.156645 -0.151275 -v -0.021250 -0.135992 0.145969 -vn -0.976002 0.211295 -0.052679 -v -0.021250 -0.136249 0.145505 -vn -0.976001 0.209330 0.060027 -v -0.021250 -0.136240 0.144975 -vn -0.933541 0.074590 -0.350624 -v -0.021250 -0.130030 0.142704 -vn -0.935068 0.169550 -0.311288 -v -0.021250 -0.130932 0.142393 -vn -0.976003 -0.156643 0.151267 -v -0.021250 -0.134517 0.144545 -vn -0.935158 0.257041 -0.243740 -v -0.021250 -0.131694 0.141819 -vn -0.935333 0.319165 -0.152597 -v -0.021250 -0.132241 0.141037 -vn -0.916685 -0.088818 0.389615 -v -0.021250 -0.131878 0.150132 -vn -0.916681 -0.023481 0.398929 -v -0.021250 -0.130129 0.150382 -vn -0.916688 0.042502 0.397336 -v -0.021250 -0.128362 0.150339 -vn -0.932526 0.360726 0.016492 -v -0.021250 -0.132544 0.139516 -vn -0.916687 -0.355886 -0.181743 -v -0.021250 -0.139029 0.134834 -vn -0.916687 -0.380945 -0.120688 -v -0.021250 -0.139700 0.136468 -vn -0.916682 -0.395625 -0.056345 -v -0.021250 -0.140093 0.138191 -vn -0.916686 -0.399494 0.009544 -v -0.021250 -0.140197 0.139956 -vn -0.916684 -0.392480 0.075169 -v -0.021250 -0.140009 0.141713 -vn -0.936219 0.155499 0.315141 -v -0.021250 -0.130837 0.136959 -vn -0.933462 0.060408 0.353554 -v -0.021250 -0.129924 0.136680 -vn -0.976003 -0.209321 -0.060021 -v -0.021250 -0.134072 0.134228 -vn -0.976002 -0.211294 0.052682 -v -0.021250 -0.134063 0.133697 -vn -0.937084 0.242509 0.251124 -v -0.021250 -0.131619 0.137506 -vn -0.976003 -0.151267 -0.156643 -v -0.021250 -0.134345 0.134683 -vn -0.936468 0.309337 0.165345 -v -0.021250 -0.132193 0.138268 -vn -0.976002 -0.052682 -0.211294 -v -0.021250 -0.134809 0.134940 -vn -0.932373 0.352396 0.080607 -v -0.021250 -0.132504 0.139170 -vn -0.976003 0.060021 -0.209321 -v -0.021250 -0.135340 0.134931 -vn -0.976003 0.156643 -0.151267 -v -0.021250 -0.135795 0.134657 -vn -0.976002 0.211294 -0.052682 -v -0.021250 -0.136052 0.134193 -vn -0.916689 -0.321114 -0.237839 -v -0.021250 -0.138098 0.133331 -vn -0.976003 0.209321 0.060021 -v -0.021250 -0.136043 0.133663 -vn -0.916684 -0.277594 -0.287458 -v -0.021250 -0.136933 0.132003 -vn -0.976003 0.151267 0.156643 -v -0.021250 -0.135769 0.133208 -vn -0.916683 -0.226495 -0.329230 -v -0.021250 -0.135565 0.130885 -vn -0.976002 0.052682 0.211294 -v -0.021250 -0.135305 0.132951 -vn -0.916689 -0.169213 -0.362005 -v -0.021250 -0.134031 0.130007 -vn -0.976003 -0.060021 0.209321 -v -0.021250 -0.134775 0.132960 -vn -0.916686 -0.107321 -0.384928 -v -0.021250 -0.132374 0.129393 -vn -0.976003 -0.156643 0.151267 -v -0.021250 -0.134320 0.133233 -vn -0.919039 0.198167 -0.340731 -v -0.021250 -0.123863 0.130605 -vn -0.916685 0.151736 -0.369681 -v -0.021250 -0.125437 0.129801 -vn -0.916686 0.088819 -0.389614 -v -0.021250 -0.127122 0.129268 -vn -0.916686 0.023479 -0.398918 -v -0.021250 -0.128871 0.129018 -vn -0.916684 -0.042500 -0.397347 -v -0.021250 -0.130638 0.129061 -vn 0.375745 -0.643755 -0.666630 -v -0.017050 -0.137141 0.131787 -vn -0.375745 -0.525254 -0.763495 -v -0.020950 -0.135735 0.130637 -vn 0.375744 -0.525256 -0.763494 -v -0.017050 -0.135735 0.130637 -vn -0.375755 -0.392424 -0.839531 -v -0.020950 -0.134158 0.129735 -vn 0.375755 -0.392422 -0.839532 -v -0.017050 -0.134158 0.129735 -vn -0.375748 -0.248885 -0.892676 -v -0.020950 -0.132454 0.129104 -vn 0.375749 -0.248885 -0.892675 -v -0.017050 -0.132454 0.129104 -vn -0.375745 -0.098562 -0.921467 -v -0.020950 -0.130670 0.128762 -vn 0.375744 -0.098563 -0.921467 -v -0.017050 -0.130670 0.128762 -vn -0.375749 0.054450 -0.925120 -v -0.020950 -0.128854 0.128719 -vn 0.375749 0.054451 -0.925121 -v -0.017050 -0.128854 0.128719 -vn -0.375748 0.205979 -0.903541 -v -0.020950 -0.127055 0.128975 -vn 0.375748 0.205978 -0.903541 -v -0.017050 -0.127055 0.128975 -vn -0.375747 0.351885 -0.857316 -v -0.020950 -0.125323 0.129524 -vn 0.375747 0.351885 -0.857316 -v -0.017050 -0.125323 0.129524 -vn -0.370878 0.484075 -0.792541 -v -0.020950 -0.123705 0.130350 -vn 0.375744 0.488198 -0.787705 -v -0.017050 -0.123705 0.130350 -vn -0.373008 0.614878 -0.694832 -v -0.020950 -0.122245 0.131431 -vn 0.375742 0.611190 -0.696609 -v -0.017050 -0.122245 0.131431 -vn -0.375753 0.717509 -0.586507 -v -0.020950 -0.120983 0.132738 -vn 0.375752 0.717511 -0.586505 -v -0.017050 -0.120983 0.132738 -vn -0.375745 0.804264 -0.460409 -v -0.020950 -0.119954 0.134235 -vn 0.372879 0.804238 -0.462777 -v -0.017050 -0.119954 0.134235 -vn -0.375745 0.869074 -0.321753 -v -0.020950 -0.119184 0.135881 -vn 0.375745 0.869074 -0.321753 -v -0.017050 -0.119184 0.135881 -vn -0.375745 0.910180 -0.174319 -v -0.020950 -0.118696 0.137631 -vn 0.375745 0.910180 -0.174320 -v -0.017050 -0.118696 0.137631 -vn -0.375749 0.926457 -0.022132 -v -0.020950 -0.118503 0.139437 -vn 0.375749 0.926457 -0.022132 -v -0.017050 -0.118503 0.139437 -vn -0.375748 0.917465 0.130661 -v -0.020950 -0.118610 0.141251 -vn 0.375748 0.917464 0.130661 -v -0.017050 -0.118610 0.141251 -vn -0.375747 0.883446 0.279887 -v -0.020950 -0.119014 0.143022 -vn 0.375747 0.883447 0.279886 -v -0.017050 -0.119014 0.143022 -vn -0.375751 0.825328 0.421480 -v -0.020950 -0.119704 0.144703 -vn 0.375751 0.825328 0.421480 -v -0.017050 -0.119704 0.144703 -vn -0.375751 0.744698 0.551576 -v -0.020950 -0.120661 0.146247 -vn 0.375752 0.744698 0.551576 -v -0.017050 -0.120661 0.146247 -vn -0.375748 0.643755 0.666628 -v -0.020950 -0.121859 0.147613 -vn 0.375748 0.643756 0.666627 -v -0.017050 -0.121859 0.147613 -vn -0.371091 0.530223 0.762336 -v -0.020950 -0.123265 0.148763 -vn 0.375752 0.525249 0.763495 -v -0.017050 -0.123265 0.148763 -vn -0.374420 0.390853 0.840859 -v -0.020950 -0.124842 0.149665 -vn 0.375743 0.392422 0.839537 -v -0.017050 -0.124842 0.149665 -vn -0.375749 0.248889 0.892674 -v -0.020950 -0.126546 0.150296 -vn 0.375748 0.248889 0.892675 -v -0.017050 -0.126546 0.150296 -vn -0.375752 0.098563 0.921464 -v -0.020950 -0.128330 0.150638 -vn 0.375753 0.098561 0.921464 -v -0.017050 -0.128330 0.150638 -vn -0.375740 -0.054451 0.925124 -v -0.020950 -0.130146 0.150681 -vn 0.375740 -0.054449 0.925124 -v -0.017050 -0.130146 0.150681 -vn -0.375748 -0.205975 0.903542 -v -0.020950 -0.131945 0.150425 -vn 0.375747 -0.205976 0.903542 -v -0.017050 -0.131945 0.150425 -vn -0.375748 -0.351885 0.857316 -v -0.020950 -0.133677 0.149876 -vn 0.375747 -0.351884 0.857316 -v -0.017050 -0.133677 0.149876 -vn -0.375751 -0.488196 0.787703 -v -0.020950 -0.135295 0.149050 -vn 0.375752 -0.488197 0.787702 -v -0.017050 -0.135295 0.149050 -vn -0.375739 -0.611195 0.696607 -v -0.020950 -0.136755 0.147969 -vn 0.375739 -0.611193 0.696609 -v -0.017050 -0.136755 0.147969 -vn -0.375746 -0.717512 0.586508 -v -0.020950 -0.138017 0.146662 -vn 0.375746 -0.717513 0.586507 -v -0.017050 -0.138017 0.146662 -vn -0.375745 -0.804263 0.460410 -v -0.020950 -0.139046 0.145165 -vn 0.375745 -0.804262 0.460411 -v -0.017050 -0.139046 0.145165 -vn -0.375745 -0.869074 0.321755 -v -0.020950 -0.139816 0.143519 -vn 0.375745 -0.869074 0.321755 -v -0.017050 -0.139816 0.143519 -vn -0.375745 -0.910180 0.174321 -v -0.020950 -0.140304 0.141769 -vn 0.375745 -0.910180 0.174322 -v -0.017050 -0.140304 0.141769 -vn -0.375748 -0.926458 0.022131 -v -0.020950 -0.140497 0.139963 -vn 0.375749 -0.926457 0.022130 -v -0.017050 -0.140497 0.139963 -vn -0.375742 -0.917467 -0.130662 -v -0.020950 -0.140390 0.138149 -vn 0.375742 -0.917467 -0.130660 -v -0.017050 -0.140390 0.138149 -vn -0.375752 -0.883445 -0.279884 -v -0.020950 -0.139986 0.136378 -vn 0.375751 -0.883445 -0.279886 -v -0.017050 -0.139986 0.136378 -vn -0.375752 -0.825328 -0.421478 -v -0.020950 -0.139296 0.134697 -vn 0.371560 -0.828955 -0.418064 -v -0.017050 -0.139296 0.134697 -vn -0.375755 -0.744696 -0.551576 -v -0.020950 -0.138339 0.133153 -vn 0.375755 -0.744695 -0.551577 -v -0.017050 -0.138339 0.133153 -vn -0.375744 -0.643754 -0.666631 -v -0.020950 -0.137141 0.131787 -vn 0.976003 -0.156641 0.151265 -v -0.016750 -0.134320 0.133233 -vn 0.976004 -0.060020 0.209318 -v -0.016750 -0.134775 0.132960 -vn 0.916689 -0.169210 -0.362006 -v -0.016750 -0.134031 0.130007 -vn 0.916684 -0.226496 -0.329228 -v -0.016750 -0.135565 0.130885 -vn 0.976003 0.052681 0.211291 -v -0.016750 -0.135305 0.132951 -vn 0.916684 -0.277596 -0.287458 -v -0.016750 -0.136933 0.132003 -vn 0.976003 0.151265 0.156641 -v -0.016750 -0.135769 0.133208 -vn 0.916691 -0.320524 -0.238626 -v -0.016750 -0.138098 0.133331 -vn 0.976004 0.209318 0.060020 -v -0.016750 -0.136043 0.133663 -vn 0.899799 -0.365683 -0.237987 -v -0.016750 -0.138673 0.134191 -vn 0.976003 0.211291 -0.052681 -v -0.016750 -0.136052 0.134193 -vn 0.976003 0.156641 -0.151265 -v -0.016750 -0.135795 0.134657 -vn 0.976004 0.060020 -0.209318 -v -0.016750 -0.135340 0.134931 -vn 0.722336 -0.683397 -0.105825 -v -0.016750 -0.133958 0.139088 -vn 0.976003 -0.052681 -0.211291 -v -0.016750 -0.134809 0.134940 -vn 0.728539 -0.651016 -0.213094 -v -0.016750 -0.133799 0.138369 -vn 0.976004 -0.209318 -0.060020 -v -0.016750 -0.134072 0.134228 -vn 0.731170 0.160411 -0.663067 -v -0.016750 -0.128442 0.135326 -vn 0.731171 -0.009525 -0.682128 -v -0.016750 -0.129563 0.135200 -vn 0.916685 -0.107322 -0.384929 -v -0.016750 -0.132374 0.129393 -vn 0.916684 -0.042501 -0.397347 -v -0.016750 -0.130638 0.129061 -vn 0.916686 0.023480 -0.398918 -v -0.016750 -0.128871 0.129018 -vn 0.976003 -0.211291 0.052681 -v -0.016750 -0.134063 0.133697 -vn 0.976003 0.209323 0.060024 -v -0.016750 -0.124731 0.133860 -vn 0.976003 0.211290 -0.052681 -v -0.016750 -0.124740 0.134391 -vn 0.731173 -0.178865 -0.658326 -v -0.016750 -0.130680 0.135357 -vn 0.731173 -0.336965 -0.593162 -v -0.016750 -0.131723 0.135787 -vn 0.976003 -0.151265 -0.156641 -v -0.016750 -0.134345 0.134683 -vn 0.731173 -0.473890 -0.490728 -v -0.016750 -0.132626 0.136463 -vn 0.731173 -0.581043 -0.357456 -v -0.016750 -0.133333 0.137342 -vn 0.719460 0.686827 -0.103179 -v -0.016750 -0.125025 0.139229 -vn 0.730066 0.645646 -0.223929 -v -0.016750 -0.125240 0.138250 -vn 0.976002 0.060024 -0.209327 -v -0.016750 -0.124028 0.135128 -vn 0.731169 0.570835 -0.373549 -v -0.016750 -0.125735 0.137236 -vn 0.976002 0.156644 -0.151269 -v -0.016750 -0.124483 0.134855 -vn 0.731172 0.460006 -0.503768 -v -0.016750 -0.126466 0.136377 -vn 0.731173 0.320270 -0.602340 -v -0.016750 -0.127387 0.135727 -vn 0.976000 -0.052684 -0.211302 -v -0.016750 -0.123497 0.135137 -vn 0.976003 -0.151268 -0.156642 -v -0.016750 -0.123033 0.134880 -vn 0.917636 0.355737 -0.177186 -v -0.016750 -0.120143 0.134510 -vn 0.976003 -0.209323 -0.060024 -v -0.016750 -0.122760 0.134425 -vn 0.976003 0.151266 0.156641 -v -0.016750 -0.124457 0.133405 -vn 0.916685 0.088819 -0.389614 -v -0.016750 -0.127122 0.129268 -vn 0.976003 0.052681 0.211291 -v -0.016750 -0.123993 0.133148 -vn 0.916683 0.263553 -0.300387 -v -0.016750 -0.122443 0.131657 -vn 0.916688 0.309393 -0.252901 -v -0.016750 -0.121216 0.132928 -vn 0.976003 -0.211290 0.052681 -v -0.016750 -0.122751 0.133895 -vn 0.919930 0.332469 -0.207830 -v -0.016750 -0.120214 0.134384 -vn 0.976003 -0.156641 0.151267 -v -0.016750 -0.123008 0.133431 -vn 0.976004 -0.060020 0.209318 -v -0.016750 -0.123463 0.133157 -vn 0.916683 0.210517 -0.339669 -v -0.016750 -0.123863 0.130605 -vn 0.916685 0.151736 -0.369681 -v -0.016750 -0.125437 0.129801 -vn 0.976002 0.209326 0.060022 -v -0.016750 -0.124928 0.145172 -vn 0.976003 0.211290 -0.052681 -v -0.016750 -0.124937 0.145703 -vn 0.731171 0.094943 0.675555 -v -0.016750 -0.128874 0.144156 -vn 0.731171 -0.076043 0.677942 -v -0.016750 -0.130002 0.144172 -vn 0.976002 0.156644 -0.151269 -v -0.016750 -0.124680 0.146167 -vn 0.916682 0.169219 0.362020 -v -0.016750 -0.124969 0.149393 -vn 0.976004 0.060020 -0.209318 -v -0.016750 -0.124225 0.146440 -vn 0.916687 0.226489 0.329222 -v -0.016750 -0.123435 0.148515 -vn 0.976002 -0.052680 -0.211293 -v -0.016750 -0.123695 0.146449 -vn 0.916685 0.277593 0.287455 -v -0.016750 -0.122067 0.147397 -vn 0.976003 -0.151265 -0.156640 -v -0.016750 -0.123231 0.146192 -vn 0.916687 0.321117 0.237842 -v -0.016750 -0.120902 0.146069 -vn 0.976002 -0.209325 -0.060023 -v -0.016750 -0.122957 0.145737 -vn 0.916687 0.355885 0.181744 -v -0.016750 -0.119971 0.144566 -vn 0.976003 -0.211291 0.052680 -v -0.016750 -0.122948 0.145207 -vn 0.916685 0.380950 0.120690 -v -0.016750 -0.119300 0.142932 -vn 0.976003 -0.156642 0.151268 -v -0.016750 -0.123205 0.144743 -vn 0.916686 0.395618 0.056341 -v -0.016750 -0.118907 0.141209 -vn 0.720500 0.693208 -0.018539 -v -0.016750 -0.125013 0.139355 -vn 0.731172 0.671829 0.118462 -v -0.016750 -0.125068 0.140481 -vn 0.916686 0.399494 -0.009543 -v -0.016750 -0.118803 0.139444 -vn 0.976001 -0.060026 0.209331 -v -0.016750 -0.123660 0.144469 -vn 0.916684 0.392479 -0.075168 -v -0.016750 -0.118991 0.137687 -vn 0.731174 0.259962 0.630717 -v -0.016750 -0.127785 0.143860 -vn 0.731171 0.408653 0.546253 -v -0.016750 -0.126804 0.143303 -vn 0.976001 0.151273 0.156645 -v -0.016750 -0.124655 0.144717 -vn 0.731171 0.531662 0.427464 -v -0.016750 -0.125993 0.142520 -vn 0.976003 0.052681 0.211288 -v -0.016750 -0.124191 0.144460 -vn 0.731170 0.621264 0.281819 -v -0.016750 -0.125402 0.141559 -vn 0.916684 0.374821 -0.138563 -v -0.016750 -0.119466 0.135985 -vn 0.916686 0.107322 0.384928 -v -0.016750 -0.126626 0.150007 -vn 0.916688 0.042500 0.397338 -v -0.016750 -0.128362 0.150339 -vn 0.916681 -0.023478 0.398930 -v -0.016750 -0.130129 0.150382 -vn 0.916685 -0.088819 0.389614 -v -0.016750 -0.131878 0.150132 -vn 0.916685 -0.151736 0.369682 -v -0.016750 -0.133563 0.149599 -vn 0.976001 0.151273 0.156648 -v -0.016750 -0.135967 0.144520 -vn 0.976001 0.209328 0.060028 -v -0.016750 -0.136240 0.144975 -vn 0.916684 -0.374753 0.138744 -v -0.016750 -0.139534 0.143415 -vn 0.916681 -0.263557 0.300391 -v -0.016750 -0.136557 0.147743 -vn 0.916685 -0.309397 0.252906 -v -0.016750 -0.137784 0.146472 -vn 0.976002 0.211293 -0.052679 -v -0.016750 -0.136249 0.145505 -vn 0.731170 -0.242251 0.637734 -v -0.016750 -0.131098 0.143907 -vn 0.976003 -0.211291 0.052681 -v -0.016750 -0.134260 0.145009 -vn 0.916688 -0.380944 -0.120689 -v -0.016750 -0.139700 0.136468 -vn 0.918772 -0.355943 -0.170771 -v -0.016750 -0.139029 0.134834 -vn 0.976003 0.052683 0.211289 -v -0.016750 -0.135503 0.144263 -vn 0.916684 -0.346807 0.198535 -v -0.016750 -0.138786 0.145016 -vn 0.724822 -0.688854 -0.010661 -v -0.016750 -0.133995 0.139480 -vn 0.731174 -0.668258 0.137173 -v -0.016750 -0.133908 0.140605 -vn 0.976002 0.156644 -0.151273 -v -0.016750 -0.135992 0.145969 -vn 0.976000 0.060025 -0.209333 -v -0.016750 -0.135537 0.146243 -vn 0.916688 -0.210512 0.339659 -v -0.016750 -0.135137 0.148795 -vn 0.976003 -0.052681 -0.211288 -v -0.016750 -0.135007 0.146252 -vn 0.976001 -0.151273 -0.156648 -v -0.016750 -0.134543 0.145995 -vn 0.976004 -0.209318 -0.060020 -v -0.016750 -0.134269 0.145540 -vn 0.976004 -0.060020 0.209318 -v -0.016750 -0.134972 0.144272 -vn 0.731174 -0.613150 0.299053 -v -0.016750 -0.133545 0.141673 -vn 0.976003 -0.156641 0.151265 -v -0.016750 -0.134517 0.144545 -vn 0.731174 -0.519513 0.442144 -v -0.016750 -0.132927 0.142617 -vn 0.731172 -0.393236 0.557452 -v -0.016750 -0.132094 0.143377 -vn 0.916684 -0.392479 0.075169 -v -0.016750 -0.140009 0.141713 -vn 0.916686 -0.399495 0.009542 -v -0.016750 -0.140197 0.139956 -vn 0.916682 -0.395625 -0.056342 -v -0.016750 -0.140093 0.138191 -vn 0.375772 -0.722223 -0.580681 -v -0.014850 -0.133007 0.136880 -vn 0.411991 -0.782166 -0.467418 -v -0.014850 -0.133333 0.137342 -vn 0.381720 -0.838229 -0.389437 -v -0.014850 -0.133598 0.137841 -vn 0.410696 -0.874746 -0.257192 -v -0.014850 -0.133799 0.138369 -vn 0.381694 -0.908513 -0.170039 -v -0.014850 -0.133932 0.138919 -vn 0.411985 -0.910600 -0.032798 -v -0.014850 -0.133995 0.139480 -vn 0.381729 -0.922156 0.062545 -v -0.014850 -0.133987 0.140045 -vn 0.411998 -0.890140 0.194702 -v -0.014850 -0.133908 0.140605 -vn 0.381722 -0.877633 0.289910 -v -0.014850 -0.133760 0.141150 -vn 0.390742 -0.827342 0.403518 -v -0.014850 -0.133545 0.141673 -vn 0.375767 -0.775440 0.507437 -v -0.014850 -0.133265 0.142164 -vn 0.390742 -0.700993 0.596598 -v -0.014850 -0.132927 0.142617 -vn 0.375765 -0.624882 0.684341 -v -0.014850 -0.132534 0.143023 -vn 0.411985 -0.515618 0.751270 -v -0.014850 -0.132094 0.143377 -vn 0.381718 -0.441303 0.812123 -v -0.014850 -0.131613 0.143673 -vn 0.411978 -0.312583 0.855901 -v -0.014850 -0.131098 0.143907 -vn 0.381718 -0.225474 0.896355 -v -0.014850 -0.130558 0.144074 -vn 0.411981 -0.089908 0.906746 -v -0.014850 -0.130002 0.144172 -vn 0.381724 0.004526 0.924265 -v -0.014850 -0.129437 0.144200 -vn 0.411988 0.138423 0.900614 -v -0.014850 -0.128874 0.144156 -vn 0.381722 0.234230 0.894105 -v -0.014850 -0.128320 0.144043 -vn 0.411991 0.358036 0.837898 -v -0.014850 -0.127785 0.143860 -vn 0.381725 0.449236 0.807758 -v -0.014850 -0.127277 0.143613 -vn 0.390744 0.551401 0.737073 -v -0.014850 -0.126804 0.143303 -vn 0.375770 0.643751 0.666620 -v -0.014850 -0.126374 0.142937 -vn 0.411982 0.717416 0.561770 -v -0.014850 -0.125993 0.142520 -vn 0.381720 0.782809 0.491426 -v -0.014850 -0.125667 0.142058 -vn 0.390742 0.838284 0.380264 -v -0.014850 -0.125402 0.141559 -vn 0.375772 0.885267 0.274040 -v -0.014850 -0.125201 0.141031 -vn 0.390742 0.906517 0.159835 -v -0.014850 -0.125068 0.140481 -vn 0.375762 0.925610 0.045271 -v -0.014850 -0.125005 0.139920 -vn 0.412696 0.907262 -0.080985 -v -0.014850 -0.125013 0.139355 -vn 0.382863 0.906472 -0.178112 -v -0.014850 -0.125092 0.138795 -vn 0.411995 0.858724 -0.304718 -v -0.014850 -0.125240 0.138250 -vn 0.381724 0.834370 -0.397635 -v -0.014850 -0.125455 0.137727 -vn 0.411981 0.755966 -0.508712 -v -0.014850 -0.125735 0.137236 -vn 0.381721 0.709278 -0.592633 -v -0.014850 -0.126073 0.136783 -vn 0.411986 0.605708 -0.680724 -v -0.014850 -0.126466 0.136377 -vn 0.381720 0.539616 -0.750403 -v -0.014850 -0.126906 0.136023 -vn 0.411985 0.417394 -0.809970 -v -0.014850 -0.127387 0.135727 -vn 0.381728 0.336033 -0.861026 -v -0.014850 -0.127902 0.135493 -vn 0.390748 0.216445 -0.894688 -v -0.014850 -0.128442 0.135326 -vn 0.375775 0.103299 -0.920936 -v -0.014850 -0.128998 0.135228 -vn 0.411989 -0.024446 -0.910861 -v -0.014850 -0.129563 0.135200 -vn 0.381725 -0.120325 -0.916410 -v -0.014850 -0.130126 0.135244 -vn 0.411992 -0.250211 -0.876160 -v -0.014850 -0.130680 0.135357 -vn 0.381721 -0.344451 -0.857696 -v -0.014850 -0.131215 0.135540 -vn 0.390739 -0.454675 -0.800371 -v -0.014850 -0.131723 0.135787 -vn 0.375762 -0.555124 -0.742051 -v -0.014850 -0.132196 0.136097 -vn 0.377379 -0.643293 -0.666153 -v -0.014850 -0.132626 0.136463 -vn 0.917913 -0.313913 -0.242680 -v -0.014550 -0.132773 0.137068 -vn 0.746099 0.462528 0.478962 -v -0.014550 -0.131410 0.137722 -vn 0.746099 0.592985 0.302828 -v -0.014550 -0.131949 0.138449 -vn 0.746096 0.577852 -0.330797 -v -0.014550 -0.131887 0.141066 -vn 0.915382 -0.383616 0.122124 -v -0.014550 -0.133476 0.141053 -vn 0.746100 0.653948 -0.125249 -v -0.014550 -0.132201 0.140217 -vn 0.915181 -0.402247 0.025318 -v -0.014550 -0.133688 0.140022 -vn 0.746099 0.659184 0.093877 -v -0.014550 -0.132223 0.139312 -vn 0.915178 -0.395913 -0.075513 -v -0.014550 -0.133636 0.138971 -vn 0.915175 -0.364701 -0.171605 -v -0.014550 -0.133325 0.137965 -vn 0.746098 0.039124 -0.664685 -v -0.014550 -0.129662 0.142445 -vn 0.915176 -0.100224 0.390394 -v -0.014550 -0.130488 0.143782 -vn 0.746098 0.252824 -0.615969 -v -0.014550 -0.130544 0.142244 -vn 0.915174 -0.194168 0.353207 -v -0.014550 -0.131472 0.143408 -vn 0.746101 0.439130 -0.500498 -v -0.014550 -0.131314 0.141767 -vn 0.917663 -0.266170 0.295040 -v -0.014550 -0.132332 0.142801 -vn 0.917884 -0.332069 0.217301 -v -0.014550 -0.133014 0.142000 -vn 0.746101 -0.535053 -0.396298 -v -0.014550 -0.127290 0.141337 -vn 0.917664 0.277743 0.284168 -v -0.014550 -0.126582 0.142721 -vn 0.746097 -0.377388 -0.548560 -v -0.014550 -0.127941 0.141966 -vn 0.915385 0.191845 0.353931 -v -0.014550 -0.127425 0.143352 -vn 0.746101 -0.178822 -0.641371 -v -0.014550 -0.128761 0.142349 -vn 0.915177 0.100242 0.390388 -v -0.014550 -0.128399 0.143753 -vn 0.915179 0.000013 0.403048 -v -0.014550 -0.129441 0.143900 -vn 0.918427 -0.274803 -0.284563 -v -0.014550 -0.132418 0.136679 -vn 0.918140 -0.233202 -0.320369 -v -0.014550 -0.132016 0.136337 -vn 0.746099 0.281949 0.603193 -v -0.014550 -0.130664 0.137209 -vn 0.915382 -0.145973 -0.375190 -v -0.014550 -0.131100 0.135817 -vn 0.746098 0.070819 0.662059 -v -0.014550 -0.129792 0.136966 -vn 0.915178 -0.050524 -0.399870 -v -0.014550 -0.130085 0.135541 -vn 0.746100 -0.147988 0.649180 -v -0.014550 -0.128889 0.137019 -vn 0.746097 -0.624418 0.231175 -v -0.014550 -0.126921 0.138745 -vn 0.915181 0.395903 -0.075532 -v -0.014550 -0.125386 0.138855 -vn 0.746101 -0.665643 0.015901 -v -0.014550 -0.126751 0.139634 -vn 0.917661 0.396999 0.017023 -v -0.014550 -0.125305 0.139905 -vn 0.746097 -0.634744 -0.201096 -v -0.014550 -0.126878 0.140531 -vn 0.917885 0.379098 0.117352 -v -0.014550 -0.125488 0.140942 -vn 0.915384 0.338625 0.217728 -v -0.014550 -0.125923 0.141901 -vn 0.917667 0.041916 -0.395135 -v -0.014550 -0.129032 0.135526 -vn 0.915388 0.150414 -0.373417 -v -0.014550 -0.128009 0.135774 -vn 0.746100 -0.350762 0.565952 -v -0.014550 -0.128051 0.137363 -vn 0.915176 0.236904 -0.326083 -v -0.014550 -0.127079 0.136268 -vn 0.746099 -0.515523 0.421393 -v -0.014550 -0.127371 0.137960 -vn 0.915177 0.310550 -0.256923 -v -0.014550 -0.126302 0.136978 -vn 0.915176 0.364690 -0.171620 -v -0.014550 -0.125725 0.137859 -vn 0.671869 0.514512 0.532794 -v -0.018250 -0.131410 0.137722 -vn 0.671869 0.313638 0.670987 -v -0.018250 -0.130664 0.137209 -vn 0.671869 0.078778 0.736468 -v -0.018250 -0.129792 0.136966 -vn 0.671868 -0.164621 0.722145 -v -0.018250 -0.128889 0.137019 -vn 0.671868 -0.390186 0.629562 -v -0.018250 -0.128051 0.137363 -vn 0.671868 -0.573465 0.468755 -v -0.018250 -0.127371 0.137960 -vn 0.671870 -0.694595 0.257156 -v -0.018250 -0.126921 0.138745 -vn 0.671867 -0.740461 0.017688 -v -0.018250 -0.126751 0.139634 -vn 0.671870 -0.706081 -0.223697 -v -0.018250 -0.126878 0.140531 -vn 0.671867 -0.595192 -0.440842 -v -0.018250 -0.127290 0.141337 -vn 0.671870 -0.419801 -0.610211 -v -0.018250 -0.127941 0.141966 -vn 0.671867 -0.198922 -0.713460 -v -0.018250 -0.128761 0.142349 -vn 0.671869 0.043521 -0.739390 -v -0.018250 -0.129662 0.142445 -vn 0.671869 0.281239 -0.685198 -v -0.018250 -0.130544 0.142244 -vn 0.671867 0.488488 -0.556753 -v -0.018250 -0.131314 0.141767 -vn 0.671871 0.642795 -0.367974 -v -0.018250 -0.131887 0.141066 -vn 0.671868 0.727449 -0.139327 -v -0.018250 -0.132201 0.140217 -vn 0.671868 0.733272 0.104428 -v -0.018250 -0.132223 0.139312 -vn 0.671868 0.659633 0.336864 -v -0.018250 -0.131949 0.138449 -vn 0.765146 0.635239 -0.104993 -v -0.018250 -0.130733 0.139904 -vn 0.765148 0.611265 0.202247 -v -0.018250 -0.130687 0.139307 -vn 0.765143 0.447265 0.463153 -v -0.018250 -0.130368 0.138801 -vn 0.765149 0.180792 0.617949 -v -0.018250 -0.129851 0.138500 -vn 0.765146 -0.323424 -0.556730 -v -0.018250 -0.128872 0.140781 -vn 0.765144 -0.027657 -0.643265 -v -0.018250 -0.129446 0.140949 -vn 0.765151 0.274455 -0.582425 -v -0.018250 -0.130033 0.140831 -vn 0.765142 0.513694 -0.388171 -v -0.018250 -0.130497 0.140454 -vn 0.765146 -0.641906 -0.050085 -v -0.018250 -0.128254 0.139797 -vn 0.765146 -0.545104 -0.342657 -v -0.018250 -0.128442 0.140365 -vn 0.765150 -0.405861 0.499822 -v -0.018250 -0.128712 0.138730 -vn 0.765144 -0.591660 0.253956 -v -0.018250 -0.128351 0.139207 -vn 0.765142 -0.127093 0.631193 -v -0.018250 -0.129253 0.138475 -vn -0.765143 0.447265 0.463153 -v -0.019750 -0.130368 0.138801 -vn -0.765149 0.180792 0.617949 -v -0.019750 -0.129851 0.138500 -vn -0.765142 -0.127093 0.631193 -v -0.019750 -0.129253 0.138475 -vn -0.765150 -0.405861 0.499822 -v -0.019750 -0.128712 0.138730 -vn -0.765144 -0.591660 0.253956 -v -0.019750 -0.128351 0.139207 -vn -0.765146 -0.641906 -0.050085 -v -0.019750 -0.128254 0.139797 -vn -0.765146 -0.545104 -0.342657 -v -0.019750 -0.128442 0.140365 -vn -0.765146 -0.323424 -0.556730 -v -0.019750 -0.128872 0.140781 -vn -0.765144 -0.027657 -0.643265 -v -0.019750 -0.129446 0.140949 -vn -0.765151 0.274455 -0.582425 -v -0.019750 -0.130033 0.140831 -vn -0.765142 0.513694 -0.388171 -v -0.019750 -0.130497 0.140454 -vn -0.765146 0.635239 -0.104993 -v -0.019750 -0.130733 0.139904 -vn -0.765148 0.611265 0.202247 -v -0.019750 -0.130687 0.139307 -vn 0.539401 0.203709 0.817037 -v -0.016880 -0.135251 0.133169 -vn 0.539405 -0.232097 0.809428 -v -0.016880 -0.134837 0.133176 -vn 0.539404 -0.605717 0.584936 -v -0.016880 -0.134482 0.133390 -vn 0.539401 -0.817037 0.203709 -v -0.016880 -0.134281 0.133752 -vn 0.539405 -0.809428 -0.232097 -v -0.016880 -0.134288 0.134166 -vn 0.539404 -0.584936 -0.605717 -v -0.016880 -0.134502 0.134521 -vn 0.539401 -0.203709 -0.817037 -v -0.016880 -0.134864 0.134722 -vn 0.539405 0.232097 -0.809428 -v -0.016880 -0.135278 0.134714 -vn 0.539404 0.605717 -0.584936 -v -0.016880 -0.135633 0.134501 -vn 0.539401 0.817037 -0.203709 -v -0.016880 -0.135833 0.134139 -vn 0.539405 0.809428 0.232097 -v -0.016880 -0.135826 0.133725 -vn 0.539404 0.584936 0.605717 -v -0.016880 -0.135613 0.133370 -vn -0.539400 -0.584937 -0.605719 -v -0.021120 -0.134502 0.134521 -vn -0.539402 -0.809429 -0.232100 -v -0.021120 -0.134288 0.134166 -vn -0.539398 -0.817038 0.203711 -v -0.021120 -0.134281 0.133752 -vn -0.539400 -0.605719 0.584937 -v -0.021120 -0.134482 0.133390 -vn -0.539402 -0.232100 0.809429 -v -0.021120 -0.134837 0.133176 -vn -0.539398 0.203711 0.817038 -v -0.021120 -0.135251 0.133169 -vn -0.539400 0.584937 0.605719 -v -0.021120 -0.135613 0.133370 -vn -0.539402 0.809429 0.232100 -v -0.021120 -0.135826 0.133725 -vn -0.539398 0.817038 -0.203711 -v -0.021120 -0.135833 0.134139 -vn -0.539400 0.605719 -0.584937 -v -0.021120 -0.135633 0.134501 -vn -0.539402 0.232100 -0.809429 -v -0.021120 -0.135278 0.134714 -vn -0.539398 -0.203711 -0.817038 -v -0.021120 -0.134864 0.134722 -vn 0.539399 0.203712 0.817037 -v -0.016880 -0.135448 0.144481 -vn 0.539405 -0.232097 0.809428 -v -0.016880 -0.135034 0.144488 -vn 0.539404 -0.605717 0.584936 -v -0.016880 -0.134679 0.144702 -vn 0.539401 -0.817037 0.203709 -v -0.016880 -0.134478 0.145064 -vn 0.539405 -0.809428 -0.232097 -v -0.016880 -0.134486 0.145478 -vn 0.539395 -0.584936 -0.605725 -v -0.016880 -0.134699 0.145833 -vn 0.539399 -0.203712 -0.817037 -v -0.016880 -0.135061 0.146033 -vn 0.539392 0.232094 -0.809437 -v -0.016880 -0.135475 0.146026 -vn 0.539395 0.605717 -0.584944 -v -0.016880 -0.135830 0.145813 -vn 0.539397 0.817038 -0.203714 -v -0.016880 -0.136031 0.145451 -vn 0.539396 0.809429 0.232114 -v -0.016880 -0.136024 0.145037 -vn 0.539390 0.584932 0.605734 -v -0.016880 -0.135810 0.144682 -vn -0.539392 -0.584942 -0.605722 -v -0.021120 -0.134699 0.145833 -vn -0.539401 -0.809429 -0.232102 -v -0.021120 -0.134486 0.145478 -vn -0.539398 -0.817038 0.203712 -v -0.021120 -0.134478 0.145064 -vn -0.539400 -0.605719 0.584937 -v -0.021120 -0.134679 0.144702 -vn -0.539402 -0.232100 0.809429 -v -0.021120 -0.135034 0.144488 -vn -0.539398 0.203711 0.817038 -v -0.021120 -0.135448 0.144481 -vn -0.539389 0.584933 0.605733 -v -0.021120 -0.135810 0.144682 -vn -0.539392 0.809432 0.232111 -v -0.021120 -0.136024 0.145037 -vn -0.539393 0.817042 -0.203712 -v -0.021120 -0.136031 0.145451 -vn -0.539392 0.605718 -0.584946 -v -0.021120 -0.135830 0.145813 -vn -0.539388 0.232093 -0.809441 -v -0.021120 -0.135475 0.146026 -vn -0.539396 -0.203708 -0.817040 -v -0.021120 -0.135061 0.146033 -vn 0.539399 0.203712 0.817037 -v -0.016880 -0.124136 0.144678 -vn 0.539393 -0.232102 0.809434 -v -0.016880 -0.123722 0.144686 -vn 0.539399 -0.605724 0.584933 -v -0.016880 -0.123367 0.144899 -vn 0.539398 -0.817040 0.203704 -v -0.016880 -0.123166 0.145261 -vn 0.539399 -0.809431 -0.232099 -v -0.016880 -0.123174 0.145675 -vn 0.539403 -0.584937 -0.605717 -v -0.016880 -0.123387 0.146030 -vn 0.539400 -0.203710 -0.817038 -v -0.016880 -0.123749 0.146231 -vn 0.539405 0.232097 -0.809428 -v -0.016880 -0.124163 0.146224 -vn 0.539400 0.605721 -0.584936 -v -0.016880 -0.124518 0.146010 -vn 0.539400 0.817037 -0.203710 -v -0.016880 -0.124719 0.145648 -vn 0.539398 0.809434 0.232092 -v -0.016880 -0.124712 0.145234 -vn 0.539396 0.584943 0.605718 -v -0.016880 -0.124498 0.144879 -vn -0.539400 -0.584937 -0.605720 -v -0.021120 -0.123387 0.146030 -vn -0.539396 -0.809433 -0.232099 -v -0.021120 -0.123174 0.145675 -vn -0.539396 -0.817042 0.203702 -v -0.021120 -0.123166 0.145261 -vn -0.539398 -0.605725 0.584934 -v -0.021120 -0.123367 0.144899 -vn -0.539390 -0.232099 0.809437 -v -0.021120 -0.123722 0.144686 -vn -0.539396 0.203708 0.817040 -v -0.021120 -0.124136 0.144678 -vn -0.539393 0.584947 0.605716 -v -0.021120 -0.124498 0.144879 -vn -0.539393 0.809436 0.232094 -v -0.021120 -0.124712 0.145234 -vn -0.539397 0.817039 -0.203710 -v -0.021120 -0.124719 0.145648 -vn -0.539396 0.605721 -0.584940 -v -0.021120 -0.124518 0.146010 -vn -0.539402 0.232101 -0.809429 -v -0.021120 -0.124163 0.146224 -vn -0.539397 -0.203713 -0.817039 -v -0.021120 -0.123749 0.146231 -vn 0.539401 0.203709 0.817037 -v -0.016880 -0.123939 0.133366 -vn 0.539405 -0.232097 0.809428 -v -0.016880 -0.123525 0.133374 -vn 0.539403 -0.605713 0.584941 -v -0.016880 -0.123170 0.133587 -vn 0.539402 -0.817034 0.203715 -v -0.016880 -0.122969 0.133949 -vn 0.539400 -0.809428 -0.232106 -v -0.016880 -0.122976 0.134363 -vn 0.539399 -0.584945 -0.605713 -v -0.016880 -0.123190 0.134718 -vn 0.539392 -0.203718 -0.817040 -v -0.016880 -0.123552 0.134919 -vn 0.539393 0.232107 -0.809433 -v -0.016880 -0.123966 0.134912 -vn 0.539396 0.605727 -0.584934 -v -0.016880 -0.124321 0.134698 -vn 0.539400 0.817037 -0.203710 -v -0.016880 -0.124522 0.134336 -vn 0.539400 0.809428 0.232106 -v -0.016880 -0.124514 0.133922 -vn 0.539402 0.584933 0.605722 -v -0.016880 -0.124301 0.133567 -vn -0.539394 -0.584942 -0.605720 -v -0.021120 -0.123190 0.134718 -vn -0.539398 -0.809430 -0.232105 -v -0.021120 -0.122976 0.134363 -vn -0.539398 -0.817037 0.203716 -v -0.021120 -0.122969 0.133949 -vn -0.539399 -0.605715 0.584943 -v -0.021120 -0.123170 0.133587 -vn -0.539402 -0.232100 0.809429 -v -0.021120 -0.123525 0.133374 -vn -0.539398 0.203711 0.817038 -v -0.021120 -0.123939 0.133366 -vn -0.539399 0.584933 0.605725 -v -0.021120 -0.124301 0.133567 -vn -0.539398 0.809430 0.232105 -v -0.021120 -0.124514 0.133922 -vn -0.539397 0.817039 -0.203710 -v -0.021120 -0.124522 0.134336 -vn -0.539394 0.605728 -0.584933 -v -0.021120 -0.124321 0.134698 -vn -0.539392 0.232107 -0.809434 -v -0.021120 -0.123966 0.134912 -vn -0.539387 -0.203726 -0.817042 -v -0.021120 -0.123552 0.134919 -vn 0.577350 0.577350 -0.577350 -v -0.040000 -0.092500 0.111450 -vn 0.577350 0.577350 0.577350 -v -0.040000 -0.092500 0.122950 -vn 0.904534 0.301512 -0.301512 -v -0.040000 -0.094000 0.111450 -vn 0.904534 0.301511 0.301512 -v -0.040000 -0.094000 0.122950 -vn 0.678874 0.727973 0.095839 -v -0.040000 -0.094000 0.129200 -vn 0.000000 -1.000000 0.000001 -v -0.040000 -0.095500 0.127600 -vn 0.000000 0.866030 0.499992 -v -0.040000 -0.097366 0.127100 -vn -0.000002 0.000004 -1.000000 -v -0.040000 -0.138500 0.127450 -vn 0.000004 0.500006 0.866022 -v -0.040000 -0.097000 0.126734 -vn 0.000002 -0.500008 -0.866021 -v -0.040000 -0.138000 0.127316 -vn -0.000002 0.000000 1.000000 -v -0.040000 -0.096500 0.126600 -vn -0.000000 0.000004 1.000000 -v -0.040000 -0.138500 0.106950 -vn 0.000000 1.000000 0.000000 -v -0.040000 -0.097500 0.106800 -vn -0.000000 -0.500004 0.866023 -v -0.040000 -0.138000 0.107084 -vn 0.000000 -0.866027 0.499997 -v -0.040000 -0.137634 0.107450 -vn -0.000000 -0.866027 0.499998 -v -0.040000 -0.095634 0.127100 -vn -0.000000 -0.500006 0.866022 -v -0.040000 -0.096000 0.126734 -vn 0.000002 -1.000000 0.000000 -v -0.040000 -0.137500 0.107950 -vn -0.000000 0.866028 -0.499995 -v -0.040000 -0.097366 0.107300 -vn 0.000000 0.500001 -0.866025 -v -0.040000 -0.097000 0.107666 -vn 0.678874 0.727973 -0.095840 -v -0.040000 -0.094000 0.105200 -vn -0.000000 -0.866025 0.500001 -v -0.040000 -0.095634 0.106300 -vn 0.653227 0.655721 -0.378582 -v -0.040000 -0.094134 0.104700 -vn 0.000000 -0.499995 0.866028 -v -0.040000 -0.096000 0.105934 -vn 0.653227 0.378582 -0.655721 -v -0.040000 -0.094500 0.104334 -vn 0.678874 0.095840 -0.727973 -v -0.040000 -0.095000 0.104200 -vn 0.000000 0.000000 1.000000 -v -0.040000 -0.096500 0.105800 -vn 0.000000 0.499995 0.866028 -v -0.040000 -0.097000 0.105934 -vn -0.003865 -0.075740 -0.997120 -v -0.040000 -0.136000 0.104200 -vn -0.000000 0.866028 0.499995 -v -0.040000 -0.097366 0.106300 -vn -0.004459 -0.809274 -0.587414 -v -0.040000 -0.140045 0.106261 -vn -0.000000 0.866022 0.500006 -v -0.040000 -0.139366 0.107450 -vn -0.001694 -0.951434 -0.307848 -v -0.040000 -0.140755 0.107655 -vn 0.000000 1.000000 -0.000000 -v -0.040000 -0.139500 0.107950 -vn 0.000000 -0.996917 -0.078460 -v -0.040000 -0.141000 0.109200 -vn 0.000000 0.866022 -0.500006 -v -0.040000 -0.139366 0.108450 -vn -0.000828 -0.996970 0.077788 -v -0.040000 -0.141000 0.125200 -vn 0.000000 0.499992 -0.866030 -v -0.040000 -0.139000 0.108816 -vn -0.005793 -0.588051 -0.808803 -v -0.040000 -0.138939 0.105155 -vn 0.000000 0.499998 0.866026 -v -0.040000 -0.139000 0.107084 -vn -0.006980 -0.309339 -0.950926 -v -0.040000 -0.137545 0.104445 -vn 0.653228 0.378578 0.655722 -v -0.040000 -0.094500 0.130066 -vn 0.678874 0.095840 0.727973 -v -0.040000 -0.095000 0.130200 -vn 0.653226 0.655721 0.378585 -v -0.040000 -0.094134 0.129700 -vn -0.000001 -0.500006 -0.866022 -v -0.040000 -0.096000 0.128466 -vn 0.000000 -0.866026 -0.499999 -v -0.040000 -0.095634 0.128100 -vn 0.000000 -0.866029 -0.499994 -v -0.040000 -0.137634 0.126950 -vn 0.000000 -1.000000 -0.000004 -v -0.040000 -0.137500 0.126450 -vn 0.000000 -0.866026 0.500000 -v -0.040000 -0.137634 0.125950 -vn 0.000001 -0.499998 -0.866027 -v -0.040000 -0.138000 0.108816 -vn 0.000000 -0.500000 0.866026 -v -0.040000 -0.138000 0.125584 -vn -0.000000 0.000004 -1.000000 -v -0.040000 -0.138500 0.108950 -vn 0.000000 0.000004 1.000000 -v -0.040000 -0.138500 0.125450 -vn -0.000000 0.499994 0.866029 -v -0.040000 -0.139000 0.125584 -vn -0.000000 0.866021 0.500008 -v -0.040000 -0.139366 0.125950 -vn -0.002423 -0.951213 0.308526 -v -0.040000 -0.140755 0.126745 -vn 0.000000 1.000000 -0.000003 -v -0.040000 -0.139500 0.126450 -vn -0.004298 -0.809268 0.587424 -v -0.040000 -0.140045 0.128139 -vn -0.000000 0.000000 -1.000000 -v -0.040000 -0.096500 0.107800 -vn 0.000000 -0.866027 -0.499997 -v -0.040000 -0.137634 0.108450 -vn 0.000001 -0.500001 -0.866025 -v -0.040000 -0.096000 0.107666 -vn -0.000000 -0.866025 -0.500001 -v -0.040000 -0.095634 0.107300 -vn -0.000002 -1.000000 0.000000 -v -0.040000 -0.095500 0.106800 -vn -0.000003 1.000000 0.000000 -v -0.040000 -0.097500 0.127600 -vn -0.000000 0.866030 -0.499993 -v -0.040000 -0.097366 0.128100 -vn -0.001162 -0.078224 0.996935 -v -0.040000 -0.136000 0.130200 -vn 0.000000 0.500006 -0.866022 -v -0.040000 -0.097000 0.128466 -vn -0.000000 -0.000000 -1.000000 -v -0.040000 -0.096500 0.128600 -vn 0.000000 0.866023 -0.500004 -v -0.040000 -0.139366 0.126950 -vn 0.000000 0.500003 -0.866024 -v -0.040000 -0.139000 0.127316 -vn -0.005609 -0.588047 0.808807 -v -0.040000 -0.138939 0.129245 -vn -0.003335 -0.306858 0.951750 -v -0.040000 -0.137545 0.129955 -vn -0.904534 0.301511 -0.301511 -v -0.062000 -0.094000 0.111450 -vn -0.678874 0.727973 -0.095840 -v -0.062000 -0.094000 0.105200 -vn -0.770263 -0.637727 -0.000000 -v -0.062000 -0.095500 0.106800 -vn -0.577350 0.577350 0.577350 -v -0.062000 -0.092500 0.122950 -vn -0.577350 0.577350 -0.577350 -v -0.062000 -0.092500 0.111450 -vn -0.904534 0.301511 0.301511 -v -0.062000 -0.094000 0.122950 -vn -0.770259 -0.000000 0.637731 -v -0.062000 -0.096500 0.105800 -vn -0.770263 -0.318860 0.552289 -v -0.062000 -0.096000 0.105934 -vn -0.678874 0.095840 -0.727973 -v -0.062000 -0.095000 0.104200 -vn -0.770263 -0.318867 -0.552285 -v -0.062000 -0.096000 0.128466 -vn -0.770263 0.000000 -0.637727 -v -0.062000 -0.096500 0.128600 -vn -0.678874 0.095840 0.727973 -v -0.062000 -0.095000 0.130200 -vn -0.770263 0.318867 -0.552285 -v -0.062000 -0.097000 0.128466 -vn 0.003385 -0.076048 0.997098 -v -0.062000 -0.136000 0.130200 -vn -0.770262 0.552290 -0.318861 -v -0.062000 -0.097366 0.128100 -vn -0.770260 0.637730 -0.000003 -v -0.062000 -0.097500 0.127600 -vn -0.770260 0.637730 0.000000 -v -0.062000 -0.097500 0.106800 -vn -0.770260 -0.552291 0.318863 -v -0.062000 -0.137634 0.107450 -vn -0.770263 -0.637727 -0.000000 -v -0.062000 -0.137500 0.107950 -vn -0.770262 -0.318865 -0.552288 -v -0.062000 -0.096000 0.107666 -vn -0.770263 0.000000 -0.637727 -v -0.062000 -0.096500 0.107800 -vn -0.770263 -0.318867 0.552285 -v -0.062000 -0.096000 0.126734 -vn -0.770259 -0.552292 0.318864 -v -0.062000 -0.095634 0.127100 -vn -0.653227 0.378582 -0.655721 -v -0.062000 -0.094500 0.104334 -vn -0.653227 0.655721 -0.378582 -v -0.062000 -0.094134 0.104700 -vn -0.770262 -0.552288 0.318865 -v -0.062000 -0.095634 0.106300 -vn -0.770260 -0.552291 -0.318863 -v -0.062000 -0.137634 0.108450 -vn -0.770265 -0.318861 -0.552286 -v -0.062000 -0.138000 0.108816 -vn -0.770262 -0.552288 0.318863 -v -0.062000 -0.137634 0.125950 -vn -0.770262 -0.637727 -0.000002 -v -0.062000 -0.137500 0.126450 -vn -0.770258 -0.552294 -0.318862 -v -0.062000 -0.137634 0.126950 -vn -0.678875 0.727973 0.095839 -v -0.062000 -0.094000 0.129200 -vn -0.770262 -0.637727 -0.000001 -v -0.062000 -0.095500 0.127600 -vn -0.770261 -0.552289 -0.318867 -v -0.062000 -0.095634 0.128100 -vn -0.653226 0.655721 0.378585 -v -0.062000 -0.094134 0.129700 -vn -0.653228 0.378578 0.655722 -v -0.062000 -0.094500 0.130066 -vn 0.006827 -0.808999 0.587770 -v -0.062000 -0.140045 0.128139 -vn 0.006826 -0.587769 0.809000 -v -0.062000 -0.138939 0.129245 -vn -0.770262 0.000003 -0.637728 -v -0.062000 -0.138500 0.127450 -vn 0.006827 -0.309008 0.951035 -v -0.062000 -0.137545 0.129955 -vn -0.770264 -0.318868 -0.552283 -v -0.062000 -0.138000 0.127316 -vn 0.003384 -0.997099 0.076047 -v -0.062000 -0.141000 0.125200 -vn -0.770261 0.318859 -0.552292 -v -0.062000 -0.139000 0.108816 -vn 0.003384 -0.997099 -0.076047 -v -0.062000 -0.141000 0.109200 -vn -0.770263 0.552285 -0.318867 -v -0.062000 -0.139366 0.108450 -vn 0.006828 -0.951035 -0.309009 -v -0.062000 -0.140755 0.107655 -vn -0.770263 0.637727 0.000000 -v -0.062000 -0.139500 0.107950 -vn 0.006827 -0.808999 -0.587770 -v -0.062000 -0.140045 0.106261 -vn -0.770262 -0.552288 -0.318865 -v -0.062000 -0.095634 0.107300 -vn -0.770263 -0.000000 0.637727 -v -0.062000 -0.096500 0.126600 -vn -0.770263 0.318867 0.552285 -v -0.062000 -0.097000 0.126734 -vn -0.770260 0.318866 -0.552290 -v -0.062000 -0.097000 0.107666 -vn -0.770261 0.552292 0.318859 -v -0.062000 -0.097366 0.127100 -vn -0.770263 0.552289 -0.318860 -v -0.062000 -0.097366 0.107300 -vn -0.770263 0.318860 0.552289 -v -0.062000 -0.097000 0.105934 -vn 0.003385 -0.076048 -0.997098 -v -0.062000 -0.136000 0.104200 -vn -0.770263 0.552289 0.318860 -v -0.062000 -0.097366 0.106300 -vn -0.770263 0.000002 0.637727 -v -0.062000 -0.138500 0.106950 -vn -0.770263 -0.318866 0.552286 -v -0.062000 -0.138000 0.107084 -vn -0.770263 0.552285 0.318867 -v -0.062000 -0.139366 0.107450 -vn -0.770260 0.318864 0.552291 -v -0.062000 -0.139000 0.107084 -vn 0.006826 -0.587770 -0.808999 -v -0.062000 -0.138939 0.105155 -vn 0.006827 -0.309010 -0.951034 -v -0.062000 -0.137545 0.104445 -vn -0.770260 0.318867 -0.552290 -v -0.062000 -0.139000 0.127316 -vn -0.770260 0.552289 -0.318867 -v -0.062000 -0.139366 0.126950 -vn 0.006827 -0.951035 0.309009 -v -0.062000 -0.140755 0.126745 -vn -0.770262 0.637727 -0.000002 -v -0.062000 -0.139500 0.126450 -vn -0.770265 0.552283 0.318868 -v -0.062000 -0.139366 0.125950 -vn -0.770259 0.318862 0.552294 -v -0.062000 -0.139000 0.125584 -vn -0.770259 0.000002 -0.637731 -v -0.062000 -0.138500 0.108950 -vn -0.770263 0.000002 0.637727 -v -0.062000 -0.138500 0.125450 -vn -0.770262 -0.318864 0.552288 -v -0.062000 -0.138000 0.125584 -vn 1.000000 0.000000 0.000001 -v -0.035000 -0.092125 0.127950 -vn 0.923880 0.382682 0.000000 -v -0.035000 -0.092000 0.127950 -vn 0.717284 0.297108 0.630263 -v -0.035000 -0.092000 0.128450 -vn 0.995906 -0.003465 0.090326 -v -0.035000 -0.136000 0.128700 -vn 0.913025 -0.400398 0.077893 -v -0.035000 -0.136522 0.128661 -vn 0.913686 -0.406421 0.000003 -v -0.035000 -0.136522 0.127950 -vn 0.774230 0.173282 0.608722 -v -0.035000 -0.098472 0.127200 -vn 0.487327 0.619596 0.615316 -v -0.035000 -0.098398 0.127154 -vn 0.940157 0.336740 -0.052064 -v -0.035000 -0.098436 0.127830 -vn 0.770264 -0.637725 0.000000 -v -0.035000 -0.097500 0.103700 -vn 0.770261 -0.552288 0.318867 -v -0.035000 -0.097667 0.103075 -vn 1.000000 0.000000 0.000000 -v -0.035000 -0.096125 0.102325 -vn 0.707107 -0.707107 0.000000 -v -0.035000 -0.102000 0.102325 -vn 0.770262 0.552289 0.318863 -v -0.035000 -0.099833 0.103075 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 -0.102000 0.104200 -vn 0.770261 0.637728 0.000000 -v -0.035000 -0.100000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.035000 -0.099833 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.035000 -0.099375 0.104783 -vn 0.539748 0.229382 -0.809973 -v -0.035000 -0.098409 0.107200 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 -0.098750 0.104950 -vn 0.770262 -0.318863 0.552289 -v -0.035000 -0.098125 0.102617 -vn 0.770261 -0.000000 0.637728 -v -0.035000 -0.098750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.035000 -0.099375 0.102617 -vn 0.942584 -0.085435 0.322855 -v -0.035000 -0.096109 0.104890 -vn 0.934097 0.003457 0.357003 -v -0.035000 -0.096393 0.104853 -vn 0.770261 -0.552288 -0.318867 -v -0.035000 -0.097667 0.104325 -vn 0.940627 0.147418 0.305758 -v -0.035000 -0.097371 0.105055 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 -0.098125 0.104783 -vn 0.940311 0.279985 0.193451 -v -0.035000 -0.098120 0.105715 -vn 0.939229 0.340984 0.039743 -v -0.035000 -0.098445 0.106658 -vn 0.707107 0.707107 0.000000 -v -0.035000 -0.095500 0.102325 -vn 0.973781 0.131340 -0.185743 -v -0.035000 -0.095500 0.104200 -vn 0.939245 -0.197237 0.280920 -v -0.035000 -0.095443 0.105161 -vn 0.816496 0.408249 -0.408249 -v -0.035000 -0.094000 0.104200 -vn 0.941720 -0.299946 0.152303 -v -0.035000 -0.094771 0.105899 -vn 0.973781 0.185743 -0.131340 -v -0.035000 -0.094000 0.105950 -vn 0.770264 -0.637725 0.000000 -v -0.035000 -0.092250 0.109200 -vn 0.770260 -0.552291 0.318865 -v -0.035000 -0.092417 0.108575 -vn 0.707107 0.000000 -0.707107 -v -0.035000 -0.092125 0.105950 -vn 0.770263 -0.318864 0.552286 -v -0.035000 -0.092875 0.108117 -vn 0.770261 0.000001 0.637729 -v -0.035000 -0.093500 0.107950 -vn 0.770263 0.318865 0.552286 -v -0.035000 -0.094125 0.108117 -vn 0.770260 0.552291 0.318866 -v -0.035000 -0.094583 0.108575 -vn 0.770264 0.637725 -0.000000 -v -0.035000 -0.094750 0.109200 -vn 0.945218 -0.156016 -0.286745 -v -0.035000 -0.095568 0.108513 -vn 0.939547 -0.015343 -0.342077 -v -0.035000 -0.096538 0.108750 -vn 0.770260 0.552291 -0.318865 -v -0.035000 -0.094583 0.109825 -vn 0.770263 0.318865 -0.552286 -v -0.035000 -0.094125 0.110283 -vn 0.973781 0.185743 0.131340 -v -0.035000 -0.094000 0.112450 -vn 0.770261 0.000001 -0.637729 -v -0.035000 -0.093500 0.110450 -vn 0.707107 0.000000 0.707107 -v -0.035000 -0.092125 0.112450 -vn 0.770263 -0.318864 -0.552286 -v -0.035000 -0.092875 0.110283 -vn 0.770260 -0.552291 -0.318866 -v -0.035000 -0.092417 0.109825 -vn 0.943023 -0.280561 -0.178866 -v -0.035000 -0.094843 0.107827 -vn 0.942133 -0.334875 -0.015657 -v -0.035000 -0.094551 0.106872 -vn 0.525230 0.818505 -0.232771 -v -0.035000 -0.097000 0.108685 -vn 0.707107 0.707107 0.000000 -v -0.035000 -0.097000 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.035000 -0.096125 0.117200 -vn 0.766703 0.622391 0.157466 -v -0.035000 -0.097000 0.125626 -vn 0.938472 -0.035306 0.343545 -v -0.035000 -0.096385 0.125653 -vn 0.465181 0.661092 0.588697 -v -0.035000 -0.097057 0.125731 -vn 0.923879 0.382684 0.000000 -v -0.035000 -0.094000 0.117200 -vn 0.973781 0.185743 -0.131340 -v -0.035000 -0.094000 0.121950 -vn 0.770265 0.000001 -0.637725 -v -0.035000 -0.093500 0.126450 -vn 0.770262 -0.318866 -0.552288 -v -0.035000 -0.092875 0.126283 -vn 0.770262 -0.552287 -0.318867 -v -0.035000 -0.092417 0.125825 -vn 0.770264 0.000001 0.637726 -v -0.035000 -0.093500 0.123950 -vn 0.770261 -0.318866 0.552288 -v -0.035000 -0.092875 0.124117 -vn 0.707107 0.000000 -0.707107 -v -0.035000 -0.092125 0.121950 -vn 0.770261 -0.552288 0.318867 -v -0.035000 -0.092417 0.124575 -vn 0.770269 -0.637719 0.000000 -v -0.035000 -0.092250 0.125200 -vn 0.717284 0.630263 0.297108 -v -0.035000 -0.095500 0.132200 -vn 0.923880 0.000000 0.382683 -v -0.035000 -0.096125 0.132200 -vn 0.973781 0.131340 0.185743 -v -0.035000 -0.095500 0.130200 -vn 0.949432 -0.094214 -0.299504 -v -0.035000 -0.096110 0.129511 -vn 0.816496 0.408248 0.408249 -v -0.035000 -0.094000 0.130200 -vn 0.942337 -0.183411 -0.279933 -v -0.035000 -0.095459 0.129249 -vn 0.940885 -0.289287 -0.176205 -v -0.035000 -0.094792 0.128542 -vn 0.973781 0.185743 0.131340 -v -0.035000 -0.094000 0.128450 -vn 0.945658 -0.316741 -0.073525 -v -0.035000 -0.094584 0.127964 -vn 0.707107 0.000000 0.707107 -v -0.035000 -0.092125 0.128450 -vn 0.770263 0.552286 -0.318865 -v -0.035000 -0.099833 0.131325 -vn 0.717284 -0.630262 0.297108 -v -0.035000 -0.102000 0.132200 -vn 0.770261 0.637729 -0.000002 -v -0.035000 -0.100000 0.130700 -vn 0.973781 -0.131340 0.185743 -v -0.035000 -0.102000 0.130200 -vn 0.770264 0.552286 0.318863 -v -0.035000 -0.099833 0.130075 -vn 0.770259 0.318866 0.552292 -v -0.035000 -0.099375 0.129617 -vn 0.770260 0.318866 -0.552291 -v -0.035000 -0.099375 0.131783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 -0.098750 0.131950 -vn 0.770263 0.000000 0.637726 -v -0.035000 -0.098750 0.129450 -vn 0.770259 -0.318865 0.552291 -v -0.035000 -0.098125 0.129617 -vn 0.940958 0.270856 -0.203066 -v -0.035000 -0.098085 0.128737 -vn 0.770262 -0.552286 0.318867 -v -0.035000 -0.097667 0.130075 -vn 0.770260 -0.318865 -0.552291 -v -0.035000 -0.098125 0.131783 -vn 0.770262 -0.552286 -0.318869 -v -0.035000 -0.097667 0.131325 -vn 0.770263 -0.637726 -0.000002 -v -0.035000 -0.097500 0.130700 -vn 0.934275 0.003691 -0.356535 -v -0.035000 -0.096385 0.129547 -vn 0.941334 0.139690 -0.307207 -v -0.035000 -0.097339 0.129360 -vn 0.707105 -0.000000 0.707108 -v -0.035000 -0.102750 0.127200 -vn 1.000000 -0.000000 0.000003 -v -0.035000 -0.102750 0.127950 -vn 0.707105 0.000000 0.707108 -v -0.035000 -0.110750 0.127200 -vn 1.000000 0.000000 0.000002 -v -0.035000 -0.110750 0.127950 -vn 0.707105 0.000000 0.707109 -v -0.035000 -0.118750 0.127200 -vn 1.000000 0.000000 0.000003 -v -0.035000 -0.118750 0.127950 -vn 0.534580 -0.237789 0.810975 -v -0.035000 -0.136522 0.127200 -vn 0.997107 -0.040621 0.064245 -v -0.035000 -0.127500 0.128700 -vn 0.973781 0.131340 0.185743 -v -0.035000 -0.119500 0.130200 -vn 0.770264 -0.552286 0.318863 -v -0.035000 -0.121667 0.130075 -vn 0.770260 -0.318866 0.552291 -v -0.035000 -0.122125 0.129617 -vn 0.770264 0.000000 0.637725 -v -0.035000 -0.122750 0.129450 -vn 0.717283 -0.630262 0.297109 -v -0.035000 -0.127500 0.130200 -vn 0.973781 -0.131340 0.185743 -v -0.035000 -0.126000 0.130200 -vn 0.770260 0.318865 0.552291 -v -0.035000 -0.123375 0.129617 -vn 0.717284 0.630262 0.297108 -v -0.035000 -0.119500 0.132200 -vn 0.770263 -0.552286 -0.318865 -v -0.035000 -0.121667 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.035000 -0.121500 0.130700 -vn 0.770264 0.552286 0.318863 -v -0.035000 -0.123833 0.130075 -vn 0.770261 0.637729 -0.000002 -v -0.035000 -0.124000 0.130700 -vn 0.717284 -0.630262 0.297108 -v -0.035000 -0.126000 0.132200 -vn 0.770263 0.552286 -0.318865 -v -0.035000 -0.123833 0.131325 -vn 0.770260 0.318866 -0.552291 -v -0.035000 -0.123375 0.131783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 -0.122750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.035000 -0.122125 0.131783 -vn 0.973781 0.131340 0.185743 -v -0.035000 -0.111500 0.130200 -vn 0.717284 0.630262 0.297108 -v -0.035000 -0.111500 0.132200 -vn 0.770263 -0.552286 -0.318865 -v -0.035000 -0.113667 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.035000 -0.113500 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.035000 -0.113667 0.130075 -vn 0.770260 -0.318866 0.552291 -v -0.035000 -0.114125 0.129617 -vn 0.770264 0.000000 0.637725 -v -0.035000 -0.114750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.035000 -0.115375 0.129617 -vn 0.973781 -0.131340 0.185743 -v -0.035000 -0.118000 0.130200 -vn 0.923879 0.000000 0.382684 -v -0.035000 -0.118750 0.130200 -vn 0.770264 0.552286 0.318863 -v -0.035000 -0.115833 0.130075 -vn 0.770261 0.637729 -0.000002 -v -0.035000 -0.116000 0.130700 -vn 0.717284 -0.630263 0.297108 -v -0.035000 -0.118000 0.132200 -vn 0.770263 0.552286 -0.318865 -v -0.035000 -0.115833 0.131325 -vn 0.770260 0.318866 -0.552291 -v -0.035000 -0.115375 0.131783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 -0.114750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.035000 -0.114125 0.131783 -vn 0.973781 0.131340 0.185743 -v -0.035000 -0.103500 0.130200 -vn 0.717284 0.630263 0.297108 -v -0.035000 -0.103500 0.132200 -vn 0.770261 -0.552288 -0.318867 -v -0.035000 -0.105667 0.131325 -vn 0.770263 0.552286 -0.318865 -v -0.035000 -0.107833 0.131325 -vn 0.717284 -0.630262 0.297108 -v -0.035000 -0.110000 0.132200 -vn 0.770261 0.637729 -0.000002 -v -0.035000 -0.108000 0.130700 -vn 0.973781 -0.131340 0.185743 -v -0.035000 -0.110000 0.130200 -vn 0.770264 0.552286 0.318863 -v -0.035000 -0.107833 0.130075 -vn 0.770260 0.318865 0.552291 -v -0.035000 -0.107375 0.129617 -vn 0.923879 0.000000 0.382684 -v -0.035000 -0.102750 0.130200 -vn 0.770263 -0.637726 -0.000002 -v -0.035000 -0.105500 0.130700 -vn 0.770261 -0.552288 0.318865 -v -0.035000 -0.105667 0.130075 -vn 0.770261 -0.318866 0.552288 -v -0.035000 -0.106125 0.129617 -vn 0.770264 0.000001 0.637726 -v -0.035000 -0.106750 0.129450 -vn 0.923879 0.000000 0.382684 -v -0.035000 -0.110750 0.130200 -vn 0.770260 0.318866 -0.552291 -v -0.035000 -0.107375 0.131783 -vn 0.770264 0.000001 -0.637725 -v -0.035000 -0.106750 0.131950 -vn 0.770261 -0.318866 -0.552288 -v -0.035000 -0.106125 0.131783 -vn 0.770261 0.318867 0.552288 -v -0.035000 -0.094125 0.124117 -vn 0.770261 0.552288 0.318867 -v -0.035000 -0.094583 0.124575 -vn 0.770264 0.637725 -0.000000 -v -0.035000 -0.094750 0.125200 -vn 0.942083 -0.183368 0.280812 -v -0.035000 -0.095459 0.125951 -vn 0.770261 0.552288 -0.318867 -v -0.035000 -0.094583 0.125825 -vn 0.944677 -0.287243 0.158357 -v -0.035000 -0.094792 0.126659 -vn 0.770261 0.318867 -0.552288 -v -0.035000 -0.094125 0.126283 -vn 0.938163 -0.345260 0.025416 -v -0.035000 -0.094550 0.127600 -vn 0.717284 0.297108 -0.630262 -v -0.035000 -0.092000 0.121950 -vn 0.717284 0.297108 -0.630263 -v -0.035000 -0.092000 0.105950 -vn 0.717284 0.297108 0.630262 -v -0.035000 -0.092000 0.112450 -vn 0.717284 0.630263 -0.297108 -v -0.035000 -0.095500 0.102200 -vn 0.923880 0.000000 -0.382683 -v -0.035000 -0.096125 0.102200 -vn 0.717284 -0.630263 -0.297108 -v -0.035000 -0.102000 0.102200 -vn 0.770260 -0.552291 -0.318866 -v -0.035000 -0.105667 0.104325 -vn 0.770264 -0.637725 0.000000 -v -0.035000 -0.105500 0.103700 -vn 0.707107 0.000000 -0.707107 -v -0.035000 -0.102750 0.107200 -vn 0.707107 0.707107 0.000000 -v -0.035000 -0.103500 0.102325 -vn 0.770263 -0.318864 0.552286 -v -0.035000 -0.106125 0.102617 -vn 0.770261 0.000001 0.637729 -v -0.035000 -0.106750 0.102450 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 -0.110000 0.104200 -vn 0.707107 -0.707107 0.000000 -v -0.035000 -0.110000 0.102325 -vn 0.770262 0.318863 0.552289 -v -0.035000 -0.107375 0.102617 -vn 0.770262 0.552289 -0.318863 -v -0.035000 -0.107833 0.104325 -vn 0.707107 0.000000 -0.707107 -v -0.035000 -0.110750 0.107200 -vn 0.770261 0.637728 0.000000 -v -0.035000 -0.108000 0.103700 -vn 0.770262 0.552289 0.318863 -v -0.035000 -0.107833 0.103075 -vn 0.923879 0.000000 -0.382684 -v -0.035000 -0.102750 0.104200 -vn 0.973781 0.131340 -0.185743 -v -0.035000 -0.103500 0.104200 -vn 0.770260 -0.552291 0.318865 -v -0.035000 -0.105667 0.103075 -vn 0.770261 0.318867 -0.552288 -v -0.035000 -0.107375 0.104783 -vn 0.770264 0.000001 -0.637725 -v -0.035000 -0.106750 0.104950 -vn 0.770262 -0.318868 -0.552286 -v -0.035000 -0.106125 0.104783 -vn 0.717284 -0.630262 -0.297108 -v -0.035000 -0.110000 0.102200 -vn 0.717284 0.630263 -0.297108 -v -0.035000 -0.103500 0.102200 -vn 0.770262 -0.552289 -0.318863 -v -0.035000 -0.113667 0.104325 -vn 0.770261 -0.637728 -0.000000 -v -0.035000 -0.113500 0.103700 -vn 0.770262 -0.552289 0.318863 -v -0.035000 -0.113667 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.035000 -0.114125 0.102617 -vn 0.707107 0.707107 0.000000 -v -0.035000 -0.111500 0.102325 -vn 0.770261 -0.000000 0.637728 -v -0.035000 -0.114750 0.102450 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 -0.118000 0.104200 -vn 0.707107 -0.707107 0.000000 -v -0.035000 -0.118000 0.102325 -vn 0.770262 0.318863 0.552289 -v -0.035000 -0.115375 0.102617 -vn 0.973781 0.131340 -0.185743 -v -0.035000 -0.111500 0.104200 -vn 0.923879 0.000000 -0.382684 -v -0.035000 -0.110750 0.104200 -vn 0.770262 0.552289 0.318863 -v -0.035000 -0.115833 0.103075 -vn 0.770261 0.637728 0.000000 -v -0.035000 -0.116000 0.103700 -vn 0.707107 0.000000 -0.707106 -v -0.035000 -0.118750 0.107200 -vn 0.770262 0.552289 -0.318863 -v -0.035000 -0.115833 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.035000 -0.115375 0.104783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 -0.114750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 -0.114125 0.104783 -vn 0.717284 -0.630262 -0.297108 -v -0.035000 -0.118000 0.102200 -vn 0.717284 0.630263 -0.297108 -v -0.035000 -0.111500 0.102200 -vn 0.770262 -0.552289 -0.318863 -v -0.035000 -0.121667 0.104325 -vn 0.770261 -0.637728 -0.000000 -v -0.035000 -0.121500 0.103700 -vn 0.997107 -0.040620 -0.064243 -v -0.035000 -0.127500 0.105700 -vn 0.717283 -0.630262 -0.297109 -v -0.035000 -0.127500 0.104200 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 -0.126000 0.104200 -vn 0.925077 -0.379320 -0.018700 -v -0.035000 -0.136550 0.105743 -vn 0.996376 0.004468 -0.084937 -v -0.035000 -0.136000 0.105700 -vn 0.549135 -0.227456 -0.804186 -v -0.035000 -0.136550 0.107200 -vn 0.770262 0.318863 0.552289 -v -0.035000 -0.123375 0.102617 -vn 0.770262 0.552288 0.318863 -v -0.035000 -0.123833 0.103075 -vn 0.770261 0.637728 0.000000 -v -0.035000 -0.124000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.035000 -0.123833 0.104325 -vn 0.770262 -0.552289 0.318863 -v -0.035000 -0.121667 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.035000 -0.122125 0.102617 -vn 0.707107 0.707107 0.000000 -v -0.035000 -0.119500 0.102325 -vn 0.770261 -0.000000 0.637728 -v -0.035000 -0.122750 0.102450 -vn 0.707107 -0.707107 0.000000 -v -0.035000 -0.126000 0.102325 -vn 0.770261 0.318867 -0.552288 -v -0.035000 -0.123375 0.104783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 -0.122750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 -0.122125 0.104783 -vn 0.973781 0.131340 -0.185743 -v -0.035000 -0.119500 0.104200 -vn 0.923879 0.000000 -0.382684 -v -0.035000 -0.118750 0.104200 -vn 0.717284 -0.630262 -0.297108 -v -0.035000 -0.126000 0.102200 -vn 0.717284 0.630263 -0.297108 -v -0.035000 -0.119500 0.102200 -vn 0.511562 0.726536 -0.458748 -v -0.035005 -0.098404 0.107200 -vn 0.328055 0.331550 -0.884565 -v -0.032200 -0.098404 0.107200 -vn 0.297112 -0.717283 -0.630262 -v -0.034950 -0.136750 0.107200 -vn 0.185744 -0.973781 -0.131342 -v -0.035200 -0.136750 0.107200 -vn 0.717284 -0.297105 -0.630264 -v -0.034750 -0.136550 0.107200 -vn 0.131340 -0.185742 -0.973781 -v -0.034750 -0.120550 0.107200 -vn 0.341589 -0.341586 -0.875577 -v -0.032200 -0.120550 0.107200 -vn 0.325836 0.886093 -0.329651 -v -0.032200 -0.097000 0.108677 -vn 0.523578 0.484972 -0.700477 -v -0.035007 -0.097000 0.108677 -vn 0.333461 0.921917 0.197161 -v -0.032200 -0.097000 0.125626 -vn 0.939710 0.253754 0.229246 -v -0.032000 -0.097916 0.126259 -vn 0.849416 0.276504 0.449486 -v -0.032000 -0.098355 0.127000 -vn 0.875576 -0.341581 0.341598 -v -0.032000 -0.120550 0.127000 -vn 0.932050 -0.319830 -0.170271 -v -0.032000 -0.119404 0.122602 -vn 0.932219 -0.346284 -0.105143 -v -0.032000 -0.118544 0.120527 -vn 0.938931 0.242884 -0.243753 -v -0.032000 -0.097916 0.108141 -vn 0.932221 -0.360145 -0.035502 -v -0.032000 -0.118105 0.118323 -vn 0.932221 -0.360144 0.035503 -v -0.032000 -0.118105 0.116077 -vn 0.848125 0.296917 -0.438776 -v -0.032000 -0.098355 0.107400 -vn 0.842668 0.453575 -0.290139 -v -0.032000 -0.097200 0.108620 -vn 0.844520 0.463104 0.268925 -v -0.032000 -0.097200 0.125780 -vn 0.904944 -0.408556 -0.118990 -v -0.032000 -0.120550 0.124341 -vn 0.904818 -0.408617 0.119733 -v -0.032000 -0.120550 0.110059 -vn 0.875581 -0.341583 -0.341583 -v -0.032000 -0.120550 0.107400 -vn 0.931923 -0.320347 0.169991 -v -0.032000 -0.119404 0.111798 -vn 0.932219 -0.346284 0.105142 -v -0.032000 -0.118544 0.113873 -vn 0.110053 -0.987814 -0.110052 -v -0.036700 -0.141000 0.109900 -vn 0.375127 -0.924492 -0.067783 -v -0.036700 -0.141000 0.109200 -vn 0.375938 -0.924209 0.067148 -v -0.036700 -0.141000 0.125200 -vn 0.110051 -0.987815 0.110051 -v -0.036700 -0.141000 0.124500 -vn 0.118633 -0.921348 0.370193 -v -0.036250 -0.141000 0.124500 -vn 0.118633 -0.921345 -0.370202 -v -0.036250 -0.141000 0.109900 -vn 0.804186 -0.549133 -0.227458 -v -0.034750 -0.120750 0.107400 -vn 0.934292 -0.353779 -0.044032 -v -0.034750 -0.136550 0.107950 -vn 0.735270 0.658079 0.162202 -v -0.034750 -0.138336 0.115022 -vn 0.735272 0.677773 -0.000000 -v -0.034750 -0.138600 0.117200 -vn 0.934289 -0.044032 -0.353788 -v -0.034750 -0.138500 0.109900 -vn 0.777812 -0.602021 -0.180497 -v -0.034750 -0.120750 0.124271 -vn 0.735270 -0.507321 -0.449447 -v -0.034750 -0.122689 0.123234 -vn 0.685652 -0.644141 -0.339063 -v -0.034750 -0.119550 0.122450 -vn 0.735271 -0.600138 -0.314977 -v -0.034750 -0.121442 0.121429 -vn 0.685531 -0.697354 -0.209153 -v -0.034750 -0.118724 0.120431 -vn 0.735270 -0.658079 -0.162202 -v -0.034750 -0.120664 0.119378 -vn 0.685729 -0.724414 -0.070714 -v -0.034750 -0.118303 0.118291 -vn 0.735271 -0.677773 -0.000000 -v -0.034750 -0.120400 0.117200 -vn 0.685922 -0.724270 0.070315 -v -0.034750 -0.118303 0.116109 -vn 0.686109 -0.696940 0.208637 -v -0.034750 -0.118724 0.113969 -vn 0.735270 0.658079 -0.162202 -v -0.034750 -0.138336 0.119378 -vn 0.735272 0.600137 -0.314977 -v -0.034750 -0.137558 0.121429 -vn 0.945444 -0.162891 0.282138 -v -0.034750 -0.137525 0.124761 -vn 0.735270 0.507321 -0.449448 -v -0.034750 -0.136311 0.123234 -vn 0.945445 -0.282134 0.162893 -v -0.034750 -0.136811 0.125475 -vn 0.735271 0.385020 -0.557795 -v -0.034750 -0.134669 0.124689 -vn 0.934292 -0.353778 0.044034 -v -0.034750 -0.136550 0.126450 -vn 0.735271 0.240341 -0.633730 -v -0.034750 -0.132727 0.125709 -vn 0.735272 0.081696 -0.672831 -v -0.034750 -0.130597 0.126234 -vn 0.804191 -0.549123 0.227466 -v -0.034750 -0.120750 0.127000 -vn 0.717284 -0.297105 0.630264 -v -0.034750 -0.136550 0.127200 -vn 0.131333 -0.185735 0.973783 -v -0.034750 -0.120550 0.127200 -vn 0.735272 -0.081696 -0.672830 -v -0.034750 -0.128403 0.126234 -vn 0.735270 -0.240341 -0.633731 -v -0.034750 -0.126273 0.125709 -vn 0.735271 -0.385020 -0.557796 -v -0.034750 -0.124331 0.124689 -vn 0.934292 -0.044031 0.353780 -v -0.034750 -0.138500 0.124500 -vn 0.921350 -0.118637 0.370190 -v -0.034750 -0.139500 0.124500 -vn 0.921347 -0.118636 -0.370197 -v -0.034750 -0.139500 0.109900 -vn 0.735272 0.081696 0.672831 -v -0.034750 -0.130597 0.108166 -vn 0.735271 0.240342 0.633729 -v -0.034750 -0.132727 0.108691 -vn 0.945444 -0.282136 -0.162894 -v -0.034750 -0.136811 0.108925 -vn 0.735271 0.385020 0.557796 -v -0.034750 -0.134669 0.109711 -vn 0.945445 -0.162889 -0.282137 -v -0.034750 -0.137525 0.109639 -vn 0.735270 0.507321 0.449448 -v -0.034750 -0.136311 0.111166 -vn 0.735271 0.600138 0.314977 -v -0.034750 -0.137558 0.112971 -vn 0.735270 -0.658079 0.162202 -v -0.034750 -0.120664 0.115022 -vn 0.778046 -0.601628 0.180799 -v -0.034750 -0.120750 0.110129 -vn 0.686287 -0.643461 0.339069 -v -0.034750 -0.119550 0.111950 -vn 0.735271 -0.600138 0.314977 -v -0.034750 -0.121442 0.112971 -vn 0.735271 -0.507321 0.449447 -v -0.034750 -0.122689 0.111166 -vn 0.735270 -0.385020 0.557796 -v -0.034750 -0.124331 0.109711 -vn 0.735270 -0.240341 0.633730 -v -0.034750 -0.126273 0.108691 -vn 0.735272 -0.081696 0.672830 -v -0.034750 -0.128403 0.108166 -vn 0.370453 -0.889761 -0.266627 -v -0.036700 -0.140787 0.107756 -vn 0.375402 -0.802108 -0.464432 -v -0.036700 -0.140166 0.106435 -vn 0.392619 -0.711817 -0.582381 -v -0.036700 -0.140045 0.106261 -vn 0.375031 -0.623803 -0.685727 -v -0.036700 -0.139190 0.105350 -vn 0.400477 -0.503030 -0.765884 -v -0.036700 -0.138939 0.105155 -vn 0.374936 -0.390438 -0.840822 -v -0.036700 -0.137943 0.104593 -vn 0.397508 -0.258892 -0.880320 -v -0.036700 -0.137545 0.104445 -vn 0.088068 -0.028549 -0.995705 -v -0.036500 -0.136000 0.104200 -vn 0.081123 -0.426411 -0.900884 -v -0.036500 -0.136573 0.104233 -vn 0.089208 -0.226906 -0.969822 -v -0.036700 -0.136573 0.104233 -vn -0.301511 0.301511 -0.904534 -v -0.037000 -0.124750 0.101200 -vn -0.770262 0.318863 0.552289 -v -0.037000 -0.123375 0.102617 -vn -0.770261 0.000000 0.637729 -v -0.037000 -0.122750 0.102450 -vn -0.609994 -0.000001 -0.792406 -v -0.037000 -0.122750 0.106009 -vn -0.770264 0.000000 -0.637725 -v -0.037000 -0.122750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.037000 -0.123375 0.104783 -vn -0.301512 -0.301511 -0.904534 -v -0.037000 -0.120750 0.101200 -vn -0.770262 -0.318863 0.552289 -v -0.037000 -0.122125 0.102617 -vn -0.770262 -0.552289 0.318863 -v -0.037000 -0.121667 0.103075 -vn -0.609995 -0.686243 -0.396203 -v -0.037000 -0.120750 0.104855 -vn -0.609994 0.686243 -0.396203 -v -0.037000 -0.124750 0.104855 -vn -0.770262 0.552289 -0.318863 -v -0.037000 -0.123833 0.104325 -vn -0.770261 0.637728 -0.000000 -v -0.037000 -0.124000 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.037000 -0.123833 0.103075 -vn -0.770261 -0.637729 0.000000 -v -0.037000 -0.121500 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.037000 -0.121667 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 -0.122125 0.104783 -vn -0.609995 -0.686243 -0.396203 -v -0.037000 -0.112750 0.104855 -vn -0.770262 -0.552289 -0.318863 -v -0.037000 -0.113667 0.104325 -vn -0.609994 -0.000001 -0.792406 -v -0.037000 -0.114750 0.106009 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 -0.114125 0.104783 -vn -0.609994 0.686243 -0.396203 -v -0.037000 -0.116750 0.104855 -vn -0.770261 0.637728 -0.000000 -v -0.037000 -0.116000 0.103700 -vn -0.301511 0.301511 -0.904534 -v -0.037000 -0.116750 0.101200 -vn -0.770262 0.552289 0.318863 -v -0.037000 -0.115833 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.037000 -0.115375 0.102617 -vn -0.770261 0.000000 0.637729 -v -0.037000 -0.114750 0.102450 -vn -0.301512 -0.301511 -0.904534 -v -0.037000 -0.112750 0.101200 -vn -0.770262 -0.318863 0.552289 -v -0.037000 -0.114125 0.102617 -vn -0.770262 -0.552289 0.318863 -v -0.037000 -0.113667 0.103075 -vn -0.770261 -0.637729 0.000000 -v -0.037000 -0.113500 0.103700 -vn -0.770264 0.000000 -0.637725 -v -0.037000 -0.114750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.037000 -0.115375 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.037000 -0.115833 0.104325 -vn -0.609994 0.686244 -0.396203 -v -0.037000 -0.108750 0.104855 -vn -0.770261 0.637728 -0.000000 -v -0.037000 -0.108000 0.103700 -vn -0.301512 0.301511 -0.904534 -v -0.037000 -0.108750 0.101200 -vn -0.770262 0.552289 0.318863 -v -0.037000 -0.107833 0.103075 -vn -0.609994 0.000001 -0.792406 -v -0.037000 -0.106750 0.106009 -vn -0.770261 0.318867 -0.552288 -v -0.037000 -0.107375 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.037000 -0.107833 0.104325 -vn -0.770262 0.318863 0.552289 -v -0.037000 -0.107375 0.102617 -vn -0.770261 0.000001 0.637729 -v -0.037000 -0.106750 0.102450 -vn -0.301511 -0.301511 -0.904534 -v -0.037000 -0.104750 0.101200 -vn -0.770264 -0.637725 -0.000000 -v -0.037000 -0.105500 0.103700 -vn -0.609994 -0.686243 -0.396204 -v -0.037000 -0.104750 0.104855 -vn -0.770260 -0.552291 0.318866 -v -0.037000 -0.105667 0.103075 -vn -0.770263 -0.318864 0.552286 -v -0.037000 -0.106125 0.102617 -vn -0.770260 -0.552291 -0.318866 -v -0.037000 -0.105667 0.104325 -vn -0.770262 -0.318868 -0.552286 -v -0.037000 -0.106125 0.104783 -vn -0.770264 0.000001 -0.637726 -v -0.037000 -0.106750 0.104950 -vn -0.717285 0.297108 0.630262 -v -0.040000 -0.092000 0.128450 -vn -0.741786 0.427642 -0.516599 -v -0.040000 -0.092000 0.127200 -vn -0.904535 0.301511 0.301510 -v -0.040000 -0.092500 0.128450 -vn -0.846476 0.452910 -0.279912 -v -0.040000 -0.094000 0.126200 -vn -0.846478 0.279911 -0.452906 -v -0.040000 -0.123750 0.104200 -vn -0.741788 0.516597 -0.427644 -v -0.040000 -0.124750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 -0.126000 0.102200 -vn -0.717284 -0.630263 0.297108 -v -0.040000 -0.126000 0.132200 -vn -0.741787 0.516597 0.427643 -v -0.040000 -0.124750 0.132200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 -0.126000 0.131700 -vn -0.846479 0.279911 0.452905 -v -0.040000 -0.123750 0.130200 -vn -0.717284 -0.630263 0.297108 -v -0.040000 -0.118000 0.132200 -vn -0.741788 0.516597 0.427643 -v -0.040000 -0.116750 0.132200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 -0.118000 0.131700 -vn -0.846479 0.279911 0.452905 -v -0.040000 -0.115750 0.130200 -vn -0.717284 -0.630263 0.297108 -v -0.040000 -0.110000 0.132200 -vn -0.741788 0.516597 0.427643 -v -0.040000 -0.108750 0.132200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 -0.110000 0.131700 -vn -0.846479 0.279911 0.452905 -v -0.040000 -0.107750 0.130200 -vn -0.904534 0.301511 0.301511 -v -0.040000 -0.111500 0.131700 -vn -0.904534 0.301511 0.301511 -v -0.040000 -0.095500 0.131700 -vn -0.577350 0.577350 0.577350 -v -0.040000 -0.094000 0.131700 -vn -0.904535 0.301511 0.301510 -v -0.040000 -0.094000 0.130200 -vn -0.741787 -0.516598 0.427643 -v -0.040000 -0.120750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 -0.119500 0.132200 -vn -0.846479 -0.279912 0.452904 -v -0.040000 -0.121750 0.130200 -vn -0.904534 0.301511 0.301511 -v -0.040000 -0.119500 0.131700 -vn -0.846479 -0.279912 0.452905 -v -0.040000 -0.113750 0.130200 -vn -0.741788 -0.516597 0.427643 -v -0.040000 -0.112750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 -0.111500 0.132200 -vn -0.904534 -0.301512 0.301510 -v -0.040000 -0.127500 0.130200 -vn -0.741788 0.516597 -0.427644 -v -0.040000 -0.100750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 -0.102000 0.102200 -vn -0.846478 0.279911 -0.452907 -v -0.040000 -0.099750 0.104200 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 -0.102000 0.102700 -vn -0.741788 -0.516597 0.427643 -v -0.040000 -0.104750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 -0.103500 0.132200 -vn -0.846479 -0.279912 0.452905 -v -0.040000 -0.105750 0.130200 -vn -0.904534 0.301511 0.301511 -v -0.040000 -0.103500 0.131700 -vn -0.846478 0.279911 0.452906 -v -0.040000 -0.099750 0.130200 -vn -0.846478 -0.279911 0.452906 -v -0.040000 -0.097750 0.130200 -vn -0.717284 0.630263 -0.297108 -v -0.040000 -0.103500 0.102200 -vn -0.741788 -0.516597 -0.427644 -v -0.040000 -0.104750 0.102200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 -0.103500 0.102700 -vn -0.846478 -0.279911 -0.452906 -v -0.040000 -0.105750 0.104200 -vn -0.741788 0.516597 -0.427644 -v -0.040000 -0.108750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 -0.110000 0.102200 -vn -0.846478 0.279911 -0.452907 -v -0.040000 -0.107750 0.104200 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 -0.110000 0.102700 -vn -0.717284 0.630263 -0.297108 -v -0.040000 -0.111500 0.102200 -vn -0.741788 -0.516597 -0.427644 -v -0.040000 -0.112750 0.102200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 -0.111500 0.102700 -vn -0.846478 -0.279911 -0.452907 -v -0.040000 -0.113750 0.104200 -vn -0.577350 -0.577350 0.577350 -v -0.040000 -0.127500 0.131700 -vn -0.717284 -0.630263 0.297108 -v -0.040000 -0.102000 0.132200 -vn -0.741788 0.516597 0.427643 -v -0.040000 -0.100750 0.132200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 -0.102000 0.131700 -vn -0.741788 -0.516597 0.427643 -v -0.040000 -0.096750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 -0.095500 0.132200 -vn -0.717284 0.630263 -0.297108 -v -0.040000 -0.095500 0.102200 -vn -0.741788 -0.516597 -0.427644 -v -0.040000 -0.096750 0.102200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 -0.095500 0.102700 -vn -0.846478 -0.279911 -0.452906 -v -0.040000 -0.097750 0.104200 -vn -0.741788 0.516597 -0.427644 -v -0.040000 -0.116750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 -0.118000 0.102200 -vn -0.846478 0.279911 -0.452907 -v -0.040000 -0.115750 0.104200 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 -0.118000 0.102700 -vn -0.904534 0.301511 -0.301511 -v -0.040000 -0.119500 0.102700 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 -0.126000 0.102700 -vn -0.577350 -0.577350 -0.577350 -v -0.040000 -0.127500 0.102700 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 -0.127500 0.104200 -vn -0.846479 0.452906 -0.279911 -v -0.040000 -0.094000 0.110200 -vn -0.846478 0.452906 0.279911 -v -0.040000 -0.094000 0.108200 -vn -0.741788 0.427644 0.516597 -v -0.040000 -0.092000 0.123200 -vn -0.717284 0.297108 -0.630263 -v -0.040000 -0.092000 0.121950 -vn -0.846478 0.452906 0.279911 -v -0.040000 -0.094000 0.124200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 -0.092500 0.121950 -vn -0.904534 0.301511 0.301511 -v -0.040000 -0.092500 0.112450 -vn -0.717284 0.297108 0.630263 -v -0.040000 -0.092000 0.112450 -vn -0.741787 0.427643 -0.516598 -v -0.040000 -0.092000 0.111200 -vn -0.577350 0.577350 0.577350 -v -0.040000 -0.092500 0.130200 -vn -0.741788 0.427644 0.516597 -v -0.040000 -0.092000 0.107200 -vn -0.717284 0.297108 -0.630263 -v -0.040000 -0.092000 0.105950 -vn -0.904534 0.301511 -0.301511 -v -0.040000 -0.092500 0.105950 -vn -0.577350 0.577350 -0.577350 -v -0.040000 -0.092500 0.104200 -vn -0.577350 0.577350 -0.577350 -v -0.040000 -0.094000 0.102700 -vn -0.904534 0.301511 -0.301511 -v -0.040000 -0.094000 0.104200 -vn -0.846479 -0.279912 -0.452906 -v -0.040000 -0.121750 0.104200 -vn -0.741787 -0.516598 -0.427643 -v -0.040000 -0.120750 0.102200 -vn -0.717284 0.630263 -0.297108 -v -0.040000 -0.119500 0.102200 -vn 0.075085 -0.990667 -0.113762 -v -0.038500 -0.120750 0.102200 -vn 0.609994 -0.686244 -0.396203 -v -0.038500 -0.120750 0.104855 -vn 0.846479 -0.279911 -0.452906 -v -0.038500 -0.121750 0.104200 -vn 0.609994 -0.000001 -0.792406 -v -0.038500 -0.122750 0.106009 -vn 0.846478 0.279911 -0.452907 -v -0.038500 -0.123750 0.104200 -vn 0.609994 0.686243 -0.396204 -v -0.038500 -0.124750 0.104855 -vn 0.075085 0.990667 -0.113763 -v -0.038500 -0.124750 0.102200 -vn 0.075085 -0.990667 -0.113763 -v -0.038500 -0.112750 0.102200 -vn 0.609994 -0.686244 -0.396203 -v -0.038500 -0.112750 0.104855 -vn 0.846478 -0.279911 -0.452907 -v -0.038500 -0.113750 0.104200 -vn 0.609994 -0.000001 -0.792406 -v -0.038500 -0.114750 0.106009 -vn 0.846478 0.279911 -0.452907 -v -0.038500 -0.115750 0.104200 -vn 0.609994 0.686243 -0.396204 -v -0.038500 -0.116750 0.104855 -vn 0.075085 0.990667 -0.113763 -v -0.038500 -0.116750 0.102200 -vn 0.075085 -0.990667 -0.113763 -v -0.038500 -0.104750 0.102200 -vn 0.609994 -0.686243 -0.396203 -v -0.038500 -0.104750 0.104855 -vn 0.846478 -0.279911 -0.452906 -v -0.038500 -0.105750 0.104200 -vn 0.609994 0.000001 -0.792406 -v -0.038500 -0.106750 0.106009 -vn 0.846478 0.279911 -0.452907 -v -0.038500 -0.107750 0.104200 -vn 0.609994 0.686244 -0.396203 -v -0.038500 -0.108750 0.104855 -vn 0.075085 0.990667 -0.113763 -v -0.038500 -0.108750 0.102200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.120750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.119500 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 -0.119500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 -0.126000 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.124750 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.126000 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.112750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.111500 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 -0.111500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 -0.118000 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.116750 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.118000 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.104750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.103500 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 -0.103500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 -0.110000 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.108750 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.110000 0.101200 -vn -0.609994 0.686244 -0.396203 -v -0.037000 -0.100750 0.104855 -vn -0.770261 0.637728 -0.000000 -v -0.037000 -0.100000 0.103700 -vn -0.301512 0.301511 -0.904534 -v -0.037000 -0.100750 0.101200 -vn -0.770262 0.552289 0.318863 -v -0.037000 -0.099833 0.103075 -vn -0.609994 -0.686243 -0.396204 -v -0.037000 -0.096750 0.104855 -vn -0.301511 -0.301511 -0.904534 -v -0.037000 -0.096750 0.101200 -vn -0.770261 -0.552288 0.318867 -v -0.037000 -0.097667 0.103075 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 -0.098125 0.104783 -vn -0.609994 0.000001 -0.792406 -v -0.037000 -0.098750 0.106009 -vn -0.770261 -0.552288 -0.318867 -v -0.037000 -0.097667 0.104325 -vn -0.770264 -0.637725 -0.000000 -v -0.037000 -0.097500 0.103700 -vn -0.770264 0.000000 -0.637725 -v -0.037000 -0.098750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.037000 -0.099375 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.037000 -0.099833 0.104325 -vn -0.770262 0.318863 0.552289 -v -0.037000 -0.099375 0.102617 -vn -0.770261 0.000000 0.637729 -v -0.037000 -0.098750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.037000 -0.098125 0.102617 -vn -0.301511 0.904534 -0.301511 -v -0.037000 -0.091000 0.111200 -vn -0.301511 0.904534 0.301511 -v -0.037000 -0.091000 0.107200 -vn -0.770264 -0.637725 -0.000000 -v -0.037000 -0.092250 0.109200 -vn -0.770260 -0.552291 0.318866 -v -0.037000 -0.092417 0.108575 -vn -0.770260 0.552291 0.318866 -v -0.037000 -0.094583 0.108575 -vn -0.609994 0.396203 0.686243 -v -0.037000 -0.094655 0.107200 -vn -0.770264 0.637725 0.000000 -v -0.037000 -0.094750 0.109200 -vn -0.609994 0.792406 -0.000001 -v -0.037000 -0.095809 0.109200 -vn -0.770260 0.552291 -0.318866 -v -0.037000 -0.094583 0.109825 -vn -0.609994 0.396203 -0.686244 -v -0.037000 -0.094655 0.111200 -vn -0.770263 0.318865 -0.552286 -v -0.037000 -0.094125 0.110283 -vn -0.770260 -0.552291 -0.318865 -v -0.037000 -0.092417 0.109825 -vn -0.770263 -0.318864 -0.552286 -v -0.037000 -0.092875 0.110283 -vn -0.770261 0.000001 -0.637729 -v -0.037000 -0.093500 0.110450 -vn -0.770263 0.318865 0.552286 -v -0.037000 -0.094125 0.108117 -vn -0.770261 0.000001 0.637729 -v -0.037000 -0.093500 0.107950 -vn -0.770263 -0.318864 0.552286 -v -0.037000 -0.092875 0.108117 -vn 0.075085 -0.990667 -0.113763 -v -0.038500 -0.096750 0.102200 -vn 0.609994 -0.686243 -0.396203 -v -0.038500 -0.096750 0.104855 -vn 0.846478 -0.279911 -0.452906 -v -0.038500 -0.097750 0.104200 -vn 0.609994 0.000001 -0.792406 -v -0.038500 -0.098750 0.106009 -vn 0.846478 0.279911 -0.452907 -v -0.038500 -0.099750 0.104200 -vn 0.609994 0.686244 -0.396203 -v -0.038500 -0.100750 0.104855 -vn 0.075085 0.990667 -0.113763 -v -0.038500 -0.100750 0.102200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.096750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.095500 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 -0.095500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 -0.102000 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 -0.100750 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 -0.102000 0.101200 -vn 0.846479 0.452906 -0.279912 -v -0.038500 -0.094000 0.110200 -vn 0.075085 0.113762 -0.990667 -v -0.038500 -0.092000 0.111200 -vn 0.609994 0.396203 -0.686244 -v -0.038500 -0.094655 0.111200 -vn 0.609994 0.396204 0.686243 -v -0.038500 -0.094655 0.107200 -vn 0.075085 0.113763 0.990667 -v -0.038500 -0.092000 0.107200 -vn 0.846478 0.452906 0.279911 -v -0.038500 -0.094000 0.108200 -vn 0.609994 0.792406 -0.000001 -v -0.038500 -0.095809 0.109200 -vn -0.297109 0.717283 -0.630262 -v -0.039000 -0.091000 0.111200 -vn -0.297109 0.717283 0.630262 -v -0.039000 -0.091000 0.112450 -vn 0.297109 0.717283 0.630262 -v -0.036000 -0.091000 0.112450 -vn 0.297109 0.717283 -0.630262 -v -0.036000 -0.091000 0.105950 -vn -0.297109 0.717283 0.630262 -v -0.039000 -0.091000 0.107200 -vn -0.297109 0.717283 -0.630262 -v -0.039000 -0.091000 0.105950 -vn 0.087119 -0.736839 0.670431 -v -0.036500 -0.127500 0.130200 -vn 0.081892 -0.019677 0.996447 -v -0.036500 -0.136000 0.130200 -vn 0.087122 -0.736840 -0.670430 -v -0.036500 -0.127500 0.104200 -vn 0.297108 -0.630262 -0.717284 -v -0.036500 -0.127500 0.102700 -vn 0.319808 -0.768479 -0.554223 -v -0.035750 -0.127500 0.104401 -vn 0.554223 -0.768480 -0.319807 -v -0.035201 -0.127500 0.104950 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 -0.126000 0.102700 -vn 0.227458 0.804186 -0.549133 -v -0.036500 -0.119500 0.102700 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 -0.118000 0.102700 -vn 0.227458 0.804186 -0.549133 -v -0.036500 -0.111500 0.102700 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 -0.110000 0.102700 -vn 0.227458 0.804186 -0.549133 -v -0.036500 -0.103500 0.102700 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 -0.102000 0.102700 -vn 0.227458 0.804186 -0.549133 -v -0.036500 -0.095500 0.102700 -vn 0.297108 0.630263 -0.717284 -v -0.036500 -0.094000 0.102700 -vn 0.297108 0.717284 -0.630263 -v -0.036500 -0.092500 0.104200 -vn 0.227458 0.549133 -0.804186 -v -0.036500 -0.092500 0.105950 -vn 0.227458 0.549133 0.804186 -v -0.036500 -0.092500 0.112450 -vn 0.227458 0.549133 -0.804186 -v -0.036500 -0.092500 0.121950 -vn 0.297109 0.717283 -0.630262 -v -0.036000 -0.091000 0.121950 -vn -0.297109 0.717283 -0.630262 -v -0.039000 -0.091000 0.121950 -vn -0.297109 0.717283 -0.630263 -v -0.039000 -0.091000 0.127200 -vn -0.297110 0.717284 0.630262 -v -0.039000 -0.091000 0.128450 -vn -0.301511 0.904534 -0.301511 -v -0.037000 -0.091000 0.127200 -vn 0.297109 0.717283 0.630262 -v -0.036000 -0.091000 0.128450 -vn -0.301511 0.904534 0.301511 -v -0.037000 -0.091000 0.123200 -vn -0.297109 0.717283 0.630262 -v -0.039000 -0.091000 0.123200 -vn 0.227458 0.549133 0.804186 -v -0.036500 -0.092500 0.128450 -vn 0.297108 0.717284 0.630263 -v -0.036500 -0.092500 0.130200 -vn 0.297108 0.630263 0.717284 -v -0.036500 -0.094000 0.131700 -vn 0.227458 0.804186 0.549133 -v -0.036500 -0.095500 0.131700 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.095500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 -0.095500 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.100750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.102000 0.133200 -vn -0.301511 0.301511 0.904534 -v -0.037000 -0.100750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.036000 -0.102000 0.133200 -vn -0.301511 -0.301511 0.904534 -v -0.037000 -0.096750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.096750 0.133200 -vn 0.227458 -0.804186 0.549133 -v -0.036500 -0.102000 0.131700 -vn 0.227458 0.804186 0.549133 -v -0.036500 -0.103500 0.131700 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.103500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 -0.103500 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.108750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.110000 0.133200 -vn -0.301511 0.301511 0.904534 -v -0.037000 -0.108750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.036000 -0.110000 0.133200 -vn -0.301511 -0.301511 0.904534 -v -0.037000 -0.104750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.104750 0.133200 -vn 0.227458 -0.804186 0.549133 -v -0.036500 -0.110000 0.131700 -vn 0.227458 0.804186 0.549133 -v -0.036500 -0.111500 0.131700 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.111500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 -0.111500 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.116750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.118000 0.133200 -vn -0.301511 0.301511 0.904534 -v -0.037000 -0.116750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.036000 -0.118000 0.133200 -vn -0.301511 -0.301511 0.904534 -v -0.037000 -0.112750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.112750 0.133200 -vn 0.227458 -0.804186 0.549133 -v -0.036500 -0.118000 0.131700 -vn 0.227458 0.804186 0.549133 -v -0.036500 -0.119500 0.131700 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.119500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 -0.119500 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 -0.124750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.126000 0.133200 -vn -0.301511 0.301511 0.904534 -v -0.037000 -0.124750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.036000 -0.126000 0.133200 -vn -0.301511 -0.301511 0.904534 -v -0.037000 -0.120750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 -0.120750 0.133200 -vn 0.227458 -0.804186 0.549133 -v -0.036500 -0.126000 0.131700 -vn 0.297108 -0.630263 0.717284 -v -0.036500 -0.127500 0.131700 -vn 0.554224 -0.768479 0.319806 -v -0.035201 -0.127500 0.129450 -vn 0.319806 -0.768481 0.554221 -v -0.035750 -0.127500 0.129999 -vn 0.174809 -0.977023 0.121937 -v -0.035253 -0.136750 0.127200 -vn 0.297112 -0.717283 0.630262 -v -0.034950 -0.136750 0.127200 -vn 0.332588 0.226214 0.915539 -v -0.032200 -0.098472 0.127200 -vn 0.341577 -0.341572 0.875588 -v -0.032200 -0.120550 0.127200 -vn 0.341588 -0.875572 0.341601 -v -0.032200 -0.120750 0.127000 -vn 0.371678 -0.888584 -0.268838 -v -0.032200 -0.120750 0.124271 -vn 0.391739 -0.812014 -0.432637 -v -0.032200 -0.119581 0.122508 -vn 0.391666 -0.880350 -0.267547 -v -0.032200 -0.118735 0.120468 -vn 0.391402 -0.915764 -0.090446 -v -0.032200 -0.118304 0.118304 -vn 0.391145 -0.915900 0.090179 -v -0.032200 -0.118304 0.116096 -vn 0.390891 -0.880749 0.267368 -v -0.032200 -0.118735 0.113931 -vn 0.391248 -0.812380 0.432393 -v -0.032200 -0.119581 0.111892 -vn 0.371672 -0.888350 0.269619 -v -0.032200 -0.120750 0.110129 -vn 0.341590 -0.875577 -0.341585 -v -0.032200 -0.120750 0.107400 -vn 0.609994 0.396203 0.686244 -v -0.038500 -0.094655 0.123200 -vn -0.609994 0.396203 0.686244 -v -0.037000 -0.094655 0.123200 -vn 0.075085 0.113763 0.990667 -v -0.038500 -0.092000 0.123200 -vn -0.770264 -0.637725 -0.000000 -v -0.037000 -0.092250 0.125200 -vn -0.770261 -0.552288 0.318867 -v -0.037000 -0.092417 0.124575 -vn -0.770264 0.000001 -0.637725 -v -0.037000 -0.093500 0.126450 -vn -0.609994 0.396202 -0.686244 -v -0.037000 -0.094655 0.127200 -vn -0.770261 -0.318866 -0.552288 -v -0.037000 -0.092875 0.126283 -vn -0.770261 -0.552288 -0.318867 -v -0.037000 -0.092417 0.125825 -vn -0.770261 0.318867 -0.552288 -v -0.037000 -0.094125 0.126283 -vn -0.770261 0.552288 -0.318867 -v -0.037000 -0.094583 0.125825 -vn -0.609994 0.792406 -0.000001 -v -0.037000 -0.095809 0.125200 -vn -0.770264 0.637725 0.000000 -v -0.037000 -0.094750 0.125200 -vn -0.770261 0.552288 0.318867 -v -0.037000 -0.094583 0.124575 -vn -0.770261 0.318867 0.552288 -v -0.037000 -0.094125 0.124117 -vn -0.770264 0.000001 0.637725 -v -0.037000 -0.093500 0.123950 -vn -0.770261 -0.318866 0.552288 -v -0.037000 -0.092875 0.124117 -vn 0.075084 0.113761 -0.990667 -v -0.038500 -0.092000 0.127200 -vn 0.609994 0.396202 -0.686244 -v -0.038500 -0.094655 0.127200 -vn 0.609994 0.792406 -0.000001 -v -0.038500 -0.095809 0.125200 -vn 0.846479 0.452905 -0.279912 -v -0.038500 -0.094000 0.126200 -vn 0.846478 0.452907 0.279911 -v -0.038500 -0.094000 0.124200 -vn 0.609994 -0.686244 0.396202 -v -0.038500 -0.096750 0.129545 -vn -0.609994 -0.686244 0.396202 -v -0.037000 -0.096750 0.129545 -vn 0.075085 -0.990667 0.113762 -v -0.038500 -0.096750 0.132200 -vn -0.609995 0.686244 0.396202 -v -0.037000 -0.100750 0.129545 -vn -0.770263 0.552286 -0.318865 -v -0.037000 -0.099833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.037000 -0.100000 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.037000 -0.099833 0.130075 -vn -0.609994 0.000001 0.792406 -v -0.037000 -0.098750 0.128391 -vn -0.770260 0.318866 0.552291 -v -0.037000 -0.099375 0.129617 -vn -0.770263 -0.637726 -0.000002 -v -0.037000 -0.097500 0.130700 -vn -0.770262 -0.552286 -0.318869 -v -0.037000 -0.097667 0.131325 -vn -0.770260 -0.318866 -0.552291 -v -0.037000 -0.098125 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.037000 -0.098750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.037000 -0.099375 0.131783 -vn -0.770264 -0.000000 0.637725 -v -0.037000 -0.098750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.037000 -0.098125 0.129617 -vn -0.770262 -0.552286 0.318867 -v -0.037000 -0.097667 0.130075 -vn 0.075085 0.990667 0.113762 -v -0.038500 -0.100750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 -0.100750 0.129545 -vn 0.609994 0.000001 0.792406 -v -0.038500 -0.098750 0.128391 -vn 0.846478 0.279911 0.452906 -v -0.038500 -0.099750 0.130200 -vn 0.846478 -0.279911 0.452906 -v -0.038500 -0.097750 0.130200 -vn 0.609994 -0.686244 0.396202 -v -0.038500 -0.104750 0.129545 -vn -0.609994 -0.686244 0.396202 -v -0.037000 -0.104750 0.129545 -vn 0.075085 -0.990667 0.113762 -v -0.038500 -0.104750 0.132200 -vn -0.609995 0.686244 0.396202 -v -0.037000 -0.108750 0.129545 -vn -0.770263 0.552286 -0.318865 -v -0.037000 -0.107833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.037000 -0.108000 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.037000 -0.107833 0.130075 -vn -0.609994 0.000001 0.792406 -v -0.037000 -0.106750 0.128391 -vn -0.770260 0.318866 0.552291 -v -0.037000 -0.107375 0.129617 -vn -0.770261 -0.552288 -0.318867 -v -0.037000 -0.105667 0.131325 -vn -0.770263 -0.637726 -0.000002 -v -0.037000 -0.105500 0.130700 -vn -0.770264 0.000001 0.637725 -v -0.037000 -0.106750 0.129450 -vn -0.770261 -0.318866 0.552288 -v -0.037000 -0.106125 0.129617 -vn -0.770261 -0.552288 0.318865 -v -0.037000 -0.105667 0.130075 -vn -0.770261 -0.318866 -0.552288 -v -0.037000 -0.106125 0.131783 -vn -0.770264 0.000001 -0.637726 -v -0.037000 -0.106750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.037000 -0.107375 0.131783 -vn 0.075085 0.990667 0.113762 -v -0.038500 -0.108750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 -0.108750 0.129545 -vn 0.609995 -0.686244 0.396202 -v -0.038500 -0.112750 0.129545 -vn -0.609995 -0.686244 0.396202 -v -0.037000 -0.112750 0.129545 -vn 0.075085 -0.990667 0.113762 -v -0.038500 -0.112750 0.132200 -vn -0.770263 -0.552286 -0.318865 -v -0.037000 -0.113667 0.131325 -vn -0.770261 -0.637729 -0.000002 -v -0.037000 -0.113500 0.130700 -vn -0.770260 -0.318866 -0.552291 -v -0.037000 -0.114125 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.037000 -0.114750 0.131950 -vn -0.770260 0.318866 0.552291 -v -0.037000 -0.115375 0.129617 -vn -0.609994 -0.000001 0.792406 -v -0.037000 -0.114750 0.128391 -vn -0.770264 0.552286 0.318863 -v -0.037000 -0.115833 0.130075 -vn -0.609994 0.686244 0.396203 -v -0.037000 -0.116750 0.129545 -vn -0.770264 -0.000000 0.637725 -v -0.037000 -0.114750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.037000 -0.114125 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.037000 -0.113667 0.130075 -vn -0.770260 0.318866 -0.552291 -v -0.037000 -0.115375 0.131783 -vn -0.770263 0.552286 -0.318865 -v -0.037000 -0.115833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.037000 -0.116000 0.130700 -vn 0.075085 0.990667 0.113762 -v -0.038500 -0.116750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 -0.116750 0.129545 -vn 0.609995 -0.686244 0.396202 -v -0.038500 -0.120750 0.129545 -vn -0.609995 -0.686244 0.396202 -v -0.037000 -0.120750 0.129545 -vn 0.075084 -0.990667 0.113762 -v -0.038500 -0.120750 0.132200 -vn -0.770264 -0.000000 0.637725 -v -0.037000 -0.122750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.037000 -0.122125 0.129617 -vn -0.609994 -0.000001 0.792406 -v -0.037000 -0.122750 0.128391 -vn -0.609994 0.686244 0.396203 -v -0.037000 -0.124750 0.129545 -vn -0.770263 0.552286 -0.318865 -v -0.037000 -0.123833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.037000 -0.124000 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.037000 -0.123833 0.130075 -vn -0.770260 0.318866 0.552291 -v -0.037000 -0.123375 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.037000 -0.121667 0.130075 -vn -0.770261 -0.637729 -0.000002 -v -0.037000 -0.121500 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.037000 -0.121667 0.131325 -vn -0.770260 -0.318866 -0.552291 -v -0.037000 -0.122125 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.037000 -0.122750 0.131950 -vn -0.770260 0.318866 -0.552291 -v -0.037000 -0.123375 0.131783 -vn 0.075085 0.990667 0.113762 -v -0.038500 -0.124750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 -0.124750 0.129545 -vn 0.609994 0.000001 0.792406 -v -0.038500 -0.106750 0.128391 -vn 0.846478 0.279911 0.452906 -v -0.038500 -0.107750 0.130200 -vn 0.846478 -0.279911 0.452906 -v -0.038500 -0.105750 0.130200 -vn 0.609994 -0.000001 0.792406 -v -0.038500 -0.114750 0.128391 -vn 0.846478 0.279911 0.452906 -v -0.038500 -0.115750 0.130200 -vn 0.846479 -0.279911 0.452906 -v -0.038500 -0.113750 0.130200 -vn 0.609994 -0.000001 0.792406 -v -0.038500 -0.122750 0.128391 -vn 0.846478 0.279911 0.452906 -v -0.038500 -0.123750 0.130200 -vn 0.846479 -0.279912 0.452905 -v -0.038500 -0.121750 0.130200 -vn 0.034159 -0.454645 0.890017 -v -0.036500 -0.136550 0.130170 -vn 0.091616 -0.237885 0.966963 -v -0.036700 -0.136550 0.130170 -vn 0.414899 -0.237231 0.878396 -v -0.036700 -0.137545 0.129955 -vn 0.377856 -0.392572 0.838518 -v -0.036700 -0.137925 0.129814 -vn 0.408211 -0.494299 0.767485 -v -0.036700 -0.138939 0.129245 -vn 0.375042 -0.622836 0.686599 -v -0.036700 -0.139179 0.129059 -vn 0.391910 -0.711427 0.583333 -v -0.036700 -0.140045 0.128139 -vn 0.375405 -0.801580 0.465340 -v -0.036700 -0.140161 0.127972 -vn 0.371280 -0.888943 0.268200 -v -0.036700 -0.140786 0.126648 -vn 0.407594 -0.057151 0.911373 -v -0.034950 -0.139500 0.124700 -vn 0.392038 -0.123373 0.911639 -v -0.034950 -0.138500 0.124700 -vn 0.678875 -0.095838 0.727973 -v -0.036500 -0.138500 0.124700 -vn 0.376173 -0.217182 0.900736 -v -0.035124 -0.140150 0.124700 -vn 0.217186 -0.376171 0.900736 -v -0.035600 -0.140626 0.124700 -vn 0.057147 -0.407588 0.911376 -v -0.036250 -0.140800 0.124700 -vn 0.578889 -0.574264 0.578885 -v -0.036500 -0.140800 0.124700 -vn 0.797132 -0.566906 0.207843 -v -0.036500 -0.136750 0.129918 -vn 0.393456 -0.593620 0.702003 -v -0.036500 -0.136729 0.129944 -vn 0.915140 -0.166939 0.366947 -v -0.036500 -0.137848 0.129630 -vn 0.770263 0.000002 -0.637726 -v -0.036500 -0.138500 0.127450 -vn 0.770265 -0.318867 -0.552282 -v -0.036500 -0.138000 0.127316 -vn 0.770259 -0.552294 -0.318862 -v -0.036500 -0.137634 0.126950 -vn 0.678874 -0.727973 0.095840 -v -0.036500 -0.136750 0.126450 -vn 0.770263 -0.637727 -0.000002 -v -0.036500 -0.137500 0.126450 -vn 0.653227 -0.655722 0.378581 -v -0.036500 -0.136984 0.125575 -vn 0.770262 -0.552289 0.318864 -v -0.036500 -0.137634 0.125950 -vn 0.653226 -0.378580 0.655723 -v -0.036500 -0.137625 0.124934 -vn 0.770262 -0.318864 0.552289 -v -0.036500 -0.138000 0.125584 -vn 0.770263 0.000002 0.637727 -v -0.036500 -0.138500 0.125450 -vn 0.770258 0.318862 0.552294 -v -0.036500 -0.139000 0.125584 -vn 0.917198 -0.397282 0.030260 -v -0.036500 -0.140800 0.125200 -vn 0.770265 0.552283 0.318868 -v -0.036500 -0.139366 0.125950 -vn 0.911014 -0.394698 0.119449 -v -0.036500 -0.140594 0.126590 -vn 0.770263 0.637727 -0.000002 -v -0.036500 -0.139500 0.126450 -vn 0.915050 -0.341600 0.214461 -v -0.036500 -0.139995 0.127862 -vn 0.770262 0.552287 -0.318866 -v -0.036500 -0.139366 0.126950 -vn 0.916106 -0.260379 0.304881 -v -0.036500 -0.139052 0.128904 -vn 0.770262 0.318865 -0.552287 -v -0.036500 -0.139000 0.127316 -vn 0.392037 -0.911639 0.123377 -v -0.034950 -0.136750 0.126450 -vn 0.376084 -0.925873 0.036324 -v -0.035253 -0.136750 0.128661 -vn 0.075599 -0.934780 0.347089 -v -0.036310 -0.136750 0.129904 -vn 0.358781 -0.923541 0.135456 -v -0.035338 -0.136750 0.129118 -vn 0.279266 -0.928830 0.243485 -v -0.035585 -0.136750 0.129516 -vn 0.178106 -0.931066 0.318426 -v -0.035878 -0.136750 0.129751 -vn 0.406959 -0.456726 0.791066 -v -0.034950 -0.137625 0.124934 -vn 0.406959 -0.791068 0.456723 -v -0.034950 -0.136984 0.125575 -vn 0.057146 -0.407579 -0.911380 -v -0.036250 -0.140800 0.109700 -vn 0.578888 -0.574259 -0.578892 -v -0.036500 -0.140800 0.109700 -vn 0.678875 -0.095838 -0.727973 -v -0.036500 -0.138500 0.109700 -vn 0.217181 -0.376164 -0.900740 -v -0.035600 -0.140626 0.109700 -vn 0.376164 -0.217178 -0.900741 -v -0.035124 -0.140150 0.109700 -vn 0.407584 -0.057148 -0.911378 -v -0.034950 -0.139500 0.109700 -vn 0.392029 -0.123374 -0.911643 -v -0.034950 -0.138500 0.109700 -vn 0.770262 -0.637727 -0.000000 -v -0.036500 -0.137500 0.107950 -vn 0.770260 -0.552291 0.318863 -v -0.036500 -0.137634 0.107450 -vn 0.503522 -0.830931 -0.236684 -v -0.036500 -0.136750 0.104459 -vn 0.770263 -0.318866 0.552286 -v -0.036500 -0.138000 0.107084 -vn 0.916754 -0.164410 -0.364048 -v -0.036500 -0.137865 0.104777 -vn 0.770263 0.000002 0.637727 -v -0.036500 -0.138500 0.106950 -vn 0.916346 -0.262566 -0.302274 -v -0.036500 -0.139063 0.105504 -vn 0.770260 0.318864 0.552291 -v -0.036500 -0.139000 0.107084 -vn 0.915128 -0.341979 -0.213522 -v -0.036500 -0.139999 0.106546 -vn 0.770263 0.552285 0.318867 -v -0.036500 -0.139366 0.107450 -vn 0.911050 -0.394732 -0.119057 -v -0.036500 -0.140595 0.107814 -vn 0.770262 0.637727 0.000000 -v -0.036500 -0.139500 0.107950 -vn 0.917220 -0.397238 -0.030157 -v -0.036500 -0.140800 0.109200 -vn 0.770263 0.552285 -0.318867 -v -0.036500 -0.139366 0.108450 -vn 0.770261 0.318859 -0.552292 -v -0.036500 -0.139000 0.108816 -vn 0.770259 0.000002 -0.637731 -v -0.036500 -0.138500 0.108950 -vn 0.653226 -0.378582 -0.655722 -v -0.036500 -0.137625 0.109466 -vn 0.770265 -0.318861 -0.552286 -v -0.036500 -0.138000 0.108816 -vn 0.653227 -0.655722 -0.378579 -v -0.036500 -0.136984 0.108825 -vn 0.770260 -0.552291 -0.318863 -v -0.036500 -0.137634 0.108450 -vn 0.678874 -0.727973 -0.095840 -v -0.036500 -0.136750 0.107950 -vn 0.392038 -0.911638 -0.123375 -v -0.034950 -0.136750 0.107950 -vn 0.406960 -0.791068 -0.456721 -v -0.034950 -0.136984 0.108825 -vn 0.406959 -0.456726 -0.791066 -v -0.034950 -0.137625 0.109466 -vn 0.141904 -0.919683 -0.366124 -v -0.036035 -0.136750 0.104518 -vn 0.036082 -0.926997 -0.373330 -v -0.036500 -0.136750 0.104432 -vn 0.451017 -0.528002 -0.719582 -v -0.036527 -0.136750 0.104432 -vn 0.386589 -0.922213 -0.008518 -v -0.035200 -0.136750 0.105743 -vn 0.396286 -0.915773 -0.065704 -v -0.035207 -0.136750 0.105611 -vn 0.267265 -0.918050 -0.292838 -v -0.035628 -0.136750 0.104770 -vn 0.361088 -0.915019 -0.179875 -v -0.035342 -0.136750 0.105147 -vn 0.133422 0.907512 0.398272 -v -0.035200 -0.098142 0.126996 -vn 0.658764 0.652395 0.374714 -v -0.036500 -0.098016 0.126725 -vn 0.344940 0.934450 0.088428 -v -0.035200 -0.098250 0.127600 -vn 0.658697 0.752369 0.007637 -v -0.036500 -0.098250 0.127600 -vn 0.390796 0.901666 -0.185142 -v -0.035200 -0.098238 0.127807 -vn 0.662043 0.648876 -0.375045 -v -0.036500 -0.098016 0.128475 -vn 0.660770 0.374862 -0.650278 -v -0.036500 -0.097375 0.129116 -vn 0.391325 0.695171 -0.602994 -v -0.035200 -0.097922 0.128620 -vn 0.344697 0.856593 -0.383970 -v -0.035200 -0.098016 0.128475 -vn 0.659321 -0.000680 -0.751861 -v -0.036500 -0.096500 0.129350 -vn 0.391801 0.310589 -0.866041 -v -0.035200 -0.097253 0.129180 -vn 0.356511 0.551790 -0.753942 -v -0.035200 -0.097375 0.129116 -vn 0.657713 -0.377405 -0.651905 -v -0.036500 -0.095625 0.129116 -vn 0.407734 -0.138372 -0.902555 -v -0.035200 -0.096397 0.129347 -vn 0.367157 0.105612 -0.924144 -v -0.035200 -0.096500 0.129350 -vn 0.654708 -0.655783 0.375907 -v -0.036500 -0.094984 0.126725 -vn 0.422286 -0.906198 0.021919 -v -0.035200 -0.094750 0.127600 -vn 0.653966 -0.756522 0.001407 -v -0.036500 -0.094750 0.127600 -vn 0.415234 -0.789484 -0.451991 -v -0.035200 -0.094967 0.128445 -vn 0.655412 -0.654563 -0.376807 -v -0.036500 -0.094984 0.128475 -vn 0.393185 -0.579371 -0.713957 -v -0.035200 -0.095566 0.129080 -vn 0.376620 -0.364534 -0.851629 -v -0.035200 -0.095625 0.129116 -vn 0.657719 -0.377397 0.651902 -v -0.036500 -0.095625 0.126084 -vn 0.393185 -0.579354 0.713971 -v -0.035200 -0.095566 0.126120 -vn 0.406166 -0.801280 0.439294 -v -0.035200 -0.094967 0.126755 -vn 0.660328 -0.002347 0.750973 -v -0.036500 -0.096500 0.125850 -vn 0.394661 -0.149643 0.906559 -v -0.035200 -0.096396 0.125853 -vn 0.380443 -0.367991 0.848437 -v -0.035200 -0.095625 0.126084 -vn 0.660895 0.378740 0.647899 -v -0.036500 -0.097375 0.126084 -vn 0.126318 0.444746 0.886705 -v -0.035200 -0.097200 0.125996 -vn 0.388736 0.076559 0.918163 -v -0.035200 -0.096500 0.125850 -vn 0.322667 0.635257 0.701666 -v -0.032200 -0.097200 0.125996 -vn 0.352529 0.505468 0.787544 -v -0.032200 -0.097375 0.126084 -vn 0.383271 0.674645 0.630839 -v -0.032200 -0.097771 0.126397 -vn 0.274664 0.808500 0.520468 -v -0.032200 -0.098016 0.126725 -vn 0.323519 0.727336 0.605242 -v -0.032200 -0.098142 0.126996 -vn 0.770261 0.552294 -0.318857 -v -0.036500 -0.097366 0.128100 -vn 0.770260 0.637730 0.000002 -v -0.036500 -0.097500 0.127600 -vn 0.770261 0.552292 0.318859 -v -0.036500 -0.097366 0.127100 -vn 0.770263 0.318867 0.552285 -v -0.036500 -0.097000 0.126734 -vn 0.770262 -0.000000 0.637727 -v -0.036500 -0.096500 0.126600 -vn 0.770263 -0.318867 0.552285 -v -0.036500 -0.096000 0.126734 -vn 0.770260 -0.552291 0.318864 -v -0.036500 -0.095634 0.127100 -vn 0.770264 -0.637725 0.000003 -v -0.036500 -0.095500 0.127600 -vn 0.770259 -0.552293 -0.318862 -v -0.036500 -0.095634 0.128100 -vn 0.770263 -0.318867 -0.552285 -v -0.036500 -0.096000 0.128466 -vn 0.770262 0.000000 -0.637727 -v -0.036500 -0.096500 0.128600 -vn 0.770263 0.318867 -0.552285 -v -0.036500 -0.097000 0.128466 -vn 0.660918 0.750457 0.001536 -v -0.036500 -0.098250 0.106800 -vn 0.660949 0.647848 -0.378735 -v -0.036500 -0.098016 0.107675 -vn 0.090475 0.901118 -0.424029 -v -0.035200 -0.098104 0.107500 -vn 0.081888 0.464698 -0.881675 -v -0.035200 -0.097344 0.108333 -vn 0.656889 0.375510 -0.653827 -v -0.036500 -0.097375 0.108316 -vn 0.420605 -0.009040 -0.907199 -v -0.035200 -0.096534 0.108550 -vn 0.653089 -0.003253 -0.757274 -v -0.036500 -0.096500 0.108550 -vn 0.653676 -0.375681 -0.656941 -v -0.036500 -0.095625 0.108316 -vn 0.656507 -0.653208 -0.377251 -v -0.036500 -0.094984 0.107675 -vn 0.392618 -0.715790 -0.577491 -v -0.035200 -0.095013 0.107722 -vn 0.406960 -0.434094 -0.803708 -v -0.035200 -0.095664 0.108337 -vn 0.657038 -0.753858 -0.000054 -v -0.036500 -0.094750 0.106800 -vn 0.393740 -0.908509 -0.139927 -v -0.035200 -0.094751 0.106865 -vn 0.382807 -0.850127 -0.361583 -v -0.035200 -0.094984 0.107675 -vn 0.657552 -0.652476 0.376697 -v -0.036500 -0.094984 0.105925 -vn 0.393993 -0.857617 0.330550 -v -0.035200 -0.094948 0.105991 -vn 0.380926 -0.918052 0.109889 -v -0.035200 -0.094750 0.106800 -vn 0.658050 -0.376456 0.652113 -v -0.036500 -0.095625 0.105284 -vn 0.394239 -0.579466 0.713299 -v -0.035200 -0.095552 0.105329 -vn 0.379013 -0.742055 0.552905 -v -0.035200 -0.094984 0.105925 -vn 0.658534 0.000080 0.752551 -v -0.036500 -0.096500 0.105050 -vn 0.409680 -0.129594 0.902977 -v -0.035200 -0.096404 0.105053 -vn 0.391924 -0.379826 0.837931 -v -0.035200 -0.095625 0.105284 -vn 0.659002 0.376170 0.651316 -v -0.036500 -0.097375 0.105284 -vn 0.394715 0.322942 0.860179 -v -0.035200 -0.097281 0.105234 -vn 0.375110 0.103446 0.921190 -v -0.035200 -0.096500 0.105050 -vn 0.659456 0.651104 0.375741 -v -0.036500 -0.098016 0.105925 -vn 0.394950 0.708001 0.585447 -v -0.035200 -0.097954 0.105826 -vn 0.373134 0.548737 0.748103 -v -0.035200 -0.097375 0.105284 -vn 0.339310 0.939543 -0.046131 -v -0.035200 -0.098250 0.106800 -vn 0.385323 0.911943 0.141021 -v -0.035200 -0.098245 0.106673 -vn 0.371147 0.849031 0.376027 -v -0.035200 -0.098016 0.105925 -vn 0.322197 0.782883 -0.532243 -v -0.032200 -0.098104 0.107500 -vn 0.343793 0.801454 -0.489365 -v -0.032200 -0.098016 0.107675 -vn 0.386042 0.651024 -0.653559 -v -0.032200 -0.097771 0.108003 -vn 0.306492 0.546599 -0.779290 -v -0.032200 -0.097375 0.108316 -vn 0.324444 0.549397 -0.770000 -v -0.032200 -0.097344 0.108333 -vn 0.770263 0.552289 -0.318860 -v -0.036500 -0.097366 0.107300 -vn 0.770259 0.637731 0.000000 -v -0.036500 -0.097500 0.106800 -vn 0.770263 0.552289 0.318860 -v -0.036500 -0.097366 0.106300 -vn 0.770263 0.318860 0.552289 -v -0.036500 -0.097000 0.105934 -vn 0.770259 -0.000000 0.637731 -v -0.036500 -0.096500 0.105800 -vn 0.770263 -0.318860 0.552289 -v -0.036500 -0.096000 0.105934 -vn 0.770261 -0.552288 0.318865 -v -0.036500 -0.095634 0.106300 -vn 0.770262 -0.637727 -0.000000 -v -0.036500 -0.095500 0.106800 -vn 0.770261 -0.552288 -0.318865 -v -0.036500 -0.095634 0.107300 -vn 0.770261 -0.318865 -0.552288 -v -0.036500 -0.096000 0.107666 -vn 0.770262 0.000000 -0.637727 -v -0.036500 -0.096500 0.107800 -vn 0.770261 0.318865 -0.552288 -v -0.036500 -0.097000 0.107666 -vn 0.301568 -0.027690 -0.953043 -v -0.035981 -0.136000 0.104293 -vn 0.517908 -0.028993 -0.854945 -v -0.035750 -0.136000 0.104401 -vn 0.709497 -0.023718 -0.704309 -v -0.035439 -0.136000 0.104639 -vn 0.851023 -0.021423 -0.524691 -v -0.035201 -0.136000 0.104950 -vn 0.951518 -0.009600 -0.307442 -v -0.035093 -0.136000 0.105181 -vn 0.913756 -0.381674 -0.139195 -v -0.035008 -0.136553 0.105591 -vn 0.817787 -0.405544 -0.408362 -v -0.035164 -0.136562 0.105057 -vn 0.615727 -0.417648 -0.668169 -v -0.035494 -0.136568 0.104622 -vn 0.322017 -0.424825 -0.846067 -v -0.035963 -0.136572 0.104333 -vn 0.307936 -0.026108 0.951049 -v -0.035981 -0.136000 0.130107 -vn 0.520711 -0.026791 0.853312 -v -0.035750 -0.136000 0.129999 -vn 0.702646 -0.023041 0.711166 -v -0.035439 -0.136000 0.129761 -vn 0.952564 -0.010427 0.304160 -v -0.035093 -0.136000 0.129219 -vn 0.854004 -0.020963 0.519844 -v -0.035201 -0.136000 0.129450 -vn 0.177913 -0.446635 0.876849 -v -0.036271 -0.136550 0.130152 -vn 0.445571 -0.445007 0.776811 -v -0.035752 -0.136547 0.129969 -vn 0.671642 -0.437031 0.598248 -v -0.035400 -0.136543 0.129687 -vn 0.850367 -0.422556 0.313564 -v -0.035102 -0.136534 0.129209 -vn 0.807282 -0.466082 0.362027 -v -0.034951 -0.140250 0.124500 -vn 0.807279 -0.466081 -0.362034 -v -0.034951 -0.140250 0.109900 -vn 0.466084 -0.807281 0.362028 -v -0.035500 -0.140799 0.124500 -vn 0.466082 -0.807278 -0.362036 -v -0.035500 -0.140799 0.109900 -vn 0.680956 -0.732325 -0.000000 -v -0.035500 -0.120400 0.117200 -vn 0.680957 -0.711043 -0.175257 -v -0.035500 -0.120664 0.119378 -vn 0.680956 -0.648441 -0.340328 -v -0.035500 -0.121442 0.121429 -vn 0.680957 -0.548152 -0.485620 -v -0.035500 -0.122689 0.123234 -vn 0.680956 -0.416008 -0.602690 -v -0.035500 -0.124331 0.124689 -vn 0.680956 -0.259685 -0.684735 -v -0.035500 -0.126273 0.125709 -vn 0.680956 -0.088271 -0.726985 -v -0.035500 -0.128403 0.126234 -vn 0.680957 0.088271 -0.726984 -v -0.035500 -0.130597 0.126234 -vn 0.680956 0.259685 -0.684735 -v -0.035500 -0.132727 0.125709 -vn 0.680956 0.416009 -0.602691 -v -0.035500 -0.134669 0.124689 -vn 0.680957 0.548151 -0.485620 -v -0.035500 -0.136311 0.123234 -vn 0.680956 0.648441 -0.340329 -v -0.035500 -0.137558 0.121429 -vn 0.680957 0.711043 -0.175257 -v -0.035500 -0.138336 0.119378 -vn 0.680956 0.732325 -0.000000 -v -0.035500 -0.138600 0.117200 -vn 0.680957 0.711044 0.175257 -v -0.035500 -0.138336 0.115022 -vn 0.680956 0.648441 0.340329 -v -0.035500 -0.137558 0.112971 -vn 0.680957 0.548152 0.485621 -v -0.035500 -0.136311 0.111166 -vn 0.680956 0.416009 0.602690 -v -0.035500 -0.134669 0.109711 -vn 0.680956 0.259686 0.684735 -v -0.035500 -0.132727 0.108691 -vn 0.680956 0.088271 0.726985 -v -0.035500 -0.130597 0.108166 -vn 0.680956 -0.088271 0.726985 -v -0.035500 -0.128403 0.108166 -vn 0.680956 -0.259686 0.684735 -v -0.035500 -0.126273 0.108691 -vn 0.680957 -0.416008 0.602690 -v -0.035500 -0.124331 0.109711 -vn 0.680956 -0.548152 0.485621 -v -0.035500 -0.122689 0.111166 -vn 0.680956 -0.648441 0.340328 -v -0.035500 -0.121442 0.112971 -vn 0.680957 -0.711043 0.175257 -v -0.035500 -0.120664 0.115022 -vn 0.740587 0.440041 -0.507833 -v -0.035500 -0.125112 0.112136 -vn 0.740586 0.565291 -0.363289 -v -0.035500 -0.123864 0.113578 -vn 0.740587 0.644742 -0.189313 -v -0.035500 -0.123071 0.115312 -vn 0.740586 0.671961 0.000000 -v -0.035500 -0.122800 0.117200 -vn 0.740587 0.644742 0.189313 -v -0.035500 -0.123071 0.119088 -vn 0.740586 0.565290 0.363289 -v -0.035500 -0.123864 0.120822 -vn 0.740586 -0.565291 -0.363289 -v -0.035500 -0.135136 0.113578 -vn 0.740587 -0.440041 -0.507833 -v -0.035500 -0.133888 0.112136 -vn 0.740586 -0.279142 -0.611238 -v -0.035500 -0.132283 0.111105 -vn 0.740586 -0.095630 -0.665122 -v -0.035500 -0.130453 0.110568 -vn 0.740586 0.095631 -0.665122 -v -0.035500 -0.128546 0.110568 -vn 0.740587 0.279143 -0.611237 -v -0.035500 -0.126717 0.111105 -vn 0.740587 0.440041 0.507833 -v -0.035500 -0.125112 0.122264 -vn 0.740587 0.279143 0.611237 -v -0.035500 -0.126717 0.123295 -vn 0.740586 0.095631 0.665122 -v -0.035500 -0.128546 0.123832 -vn 0.740586 -0.095630 0.665122 -v -0.035500 -0.130453 0.123832 -vn 0.740586 -0.279142 0.611238 -v -0.035500 -0.132283 0.123295 -vn 0.740587 -0.440041 0.507834 -v -0.035500 -0.133888 0.122264 -vn 0.740586 -0.565290 0.363289 -v -0.035500 -0.135136 0.120822 -vn 0.740587 -0.644742 0.189313 -v -0.035500 -0.135929 0.119088 -vn 0.740586 -0.671961 0.000000 -v -0.035500 -0.136200 0.117200 -vn 0.740587 -0.644742 -0.189313 -v -0.035500 -0.135929 0.115312 -vn 0.676434 0.736503 0.000000 -v -0.034750 -0.122800 0.117200 -vn 0.676434 0.706670 0.207497 -v -0.034750 -0.123071 0.119088 -vn 0.676434 0.619587 0.398183 -v -0.034750 -0.123864 0.120822 -vn 0.676433 0.482308 0.556612 -v -0.034750 -0.125112 0.122264 -vn 0.676433 0.305955 0.669947 -v -0.034750 -0.126717 0.123295 -vn 0.676434 0.104816 0.729007 -v -0.034750 -0.128546 0.123832 -vn 0.676434 -0.104815 0.729007 -v -0.034750 -0.130453 0.123832 -vn 0.676434 -0.305954 0.669947 -v -0.034750 -0.132283 0.123295 -vn 0.676433 -0.482308 0.556612 -v -0.034750 -0.133888 0.122264 -vn 0.676434 -0.619587 0.398183 -v -0.034750 -0.135136 0.120822 -vn 0.676434 -0.706670 0.207497 -v -0.034750 -0.135929 0.119088 -vn 0.676434 -0.736503 0.000000 -v -0.034750 -0.136200 0.117200 -vn 0.676434 -0.706670 -0.207497 -v -0.034750 -0.135929 0.115312 -vn 0.676434 -0.619586 -0.398182 -v -0.034750 -0.135136 0.113578 -vn 0.676433 -0.482309 -0.556612 -v -0.034750 -0.133888 0.112136 -vn 0.676434 -0.305954 -0.669947 -v -0.034750 -0.132283 0.111105 -vn 0.676434 -0.104815 -0.729007 -v -0.034750 -0.130453 0.110568 -vn 0.676434 0.104816 -0.729007 -v -0.034750 -0.128546 0.110568 -vn 0.676433 0.305955 -0.669947 -v -0.034750 -0.126717 0.111105 -vn 0.676433 0.482309 -0.556612 -v -0.034750 -0.125112 0.112136 -vn 0.676434 0.619586 -0.398182 -v -0.034750 -0.123864 0.113578 -vn 0.676433 0.706670 -0.207497 -v -0.034750 -0.123071 0.115312 -vn 0.746099 -0.163452 0.645461 -v -0.034750 -0.128334 0.112595 -vn 0.746099 -0.364177 0.557415 -v -0.034750 -0.126902 0.113223 -vn 0.746098 -0.525437 0.408966 -v -0.034750 -0.125752 0.114282 -vn 0.746101 -0.629757 0.216193 -v -0.034750 -0.125007 0.115658 -vn 0.746096 -0.665838 0.000000 -v -0.034750 -0.124750 0.117200 -vn 0.746101 -0.629757 -0.216194 -v -0.034750 -0.125007 0.118742 -vn 0.746098 -0.525437 -0.408967 -v -0.034750 -0.125752 0.120118 -vn 0.746098 -0.364178 -0.557415 -v -0.034750 -0.126902 0.121177 -vn 0.746099 0.656754 0.109592 -v -0.034750 -0.134185 0.116418 -vn 0.746099 0.585585 0.316902 -v -0.034750 -0.133677 0.114939 -vn 0.746099 0.450958 0.489871 -v -0.034750 -0.132717 0.113705 -vn 0.746099 0.267463 0.609754 -v -0.034750 -0.131408 0.112850 -vn 0.746099 0.054984 0.663561 -v -0.034750 -0.129892 0.112466 -vn 0.746100 -0.163451 -0.645460 -v -0.034750 -0.128334 0.121805 -vn 0.746098 0.054984 -0.663562 -v -0.034750 -0.129892 0.121934 -vn 0.746100 0.267461 -0.609754 -v -0.034750 -0.131408 0.121550 -vn 0.746099 0.450958 -0.489870 -v -0.034750 -0.132717 0.120695 -vn 0.746099 0.585586 -0.316901 -v -0.034750 -0.133677 0.119461 -vn 0.746099 0.656754 -0.109592 -v -0.034750 -0.134185 0.117982 -vn 0.671871 -0.740668 -0.000000 -v -0.037250 -0.124750 0.117200 -vn 0.671867 -0.700541 -0.240494 -v -0.037250 -0.125007 0.118742 -vn 0.671870 -0.584491 -0.454930 -v -0.037250 -0.125752 0.120118 -vn 0.671869 -0.405109 -0.620063 -v -0.037250 -0.126902 0.121177 -vn 0.671868 -0.181823 -0.718007 -v -0.037250 -0.128334 0.121805 -vn 0.671869 0.061164 -0.738140 -v -0.037250 -0.129892 0.121934 -vn 0.671868 0.297523 -0.678287 -v -0.037250 -0.131408 0.121550 -vn 0.671868 0.501644 -0.544928 -v -0.037250 -0.132717 0.120695 -vn 0.671869 0.651401 -0.352518 -v -0.037250 -0.133677 0.119461 -vn 0.671869 0.730569 -0.121910 -v -0.037250 -0.134185 0.117982 -vn 0.671869 0.730569 0.121910 -v -0.037250 -0.134185 0.116418 -vn 0.671868 0.651401 0.352519 -v -0.037250 -0.133677 0.114939 -vn 0.671869 0.501643 0.544929 -v -0.037250 -0.132717 0.113705 -vn 0.671869 0.297524 0.678286 -v -0.037250 -0.131408 0.112850 -vn 0.671868 0.061164 0.738141 -v -0.037250 -0.129892 0.112466 -vn 0.671869 -0.181823 0.718006 -v -0.037250 -0.128334 0.112595 -vn 0.671869 -0.405108 0.620065 -v -0.037250 -0.126902 0.113223 -vn 0.671869 -0.584492 0.454930 -v -0.037250 -0.125752 0.114282 -vn 0.671867 -0.700541 0.240493 -v -0.037250 -0.125007 0.115658 -vn 1.000000 0.000000 0.000000 -v -0.037250 -0.129500 0.117200 -vn -0.770262 -0.552289 0.318863 -v -0.067000 -0.113667 0.103075 -vn -0.770261 -0.637728 -0.000000 -v -0.067000 -0.113500 0.103700 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.112250 0.102200 -vn -0.987814 0.110051 -0.110052 -v -0.067000 -0.117500 0.127000 -vn -0.923877 0.382689 0.000000 -v -0.067000 -0.117500 0.126325 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.126325 -vn -0.991004 -0.005386 0.133725 -v -0.067000 -0.136000 0.129200 -vn -0.997001 -0.041898 0.065065 -v -0.067000 -0.127500 0.129200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.129700 0.127100 -vn -0.973781 -0.131340 0.185743 -v -0.067000 -0.126000 0.130200 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.126000 0.132075 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.132075 -vn -0.973781 0.131340 -0.185743 -v -0.067000 -0.095500 0.104200 -vn -0.717284 0.630262 -0.297109 -v -0.067000 -0.095500 0.102200 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.095875 0.102200 -vn -0.945445 -0.162889 0.282137 -v -0.067000 -0.136500 0.122334 -vn -0.736823 -0.642995 0.208922 -v -0.067000 -0.134636 0.118869 -vn -0.945448 -0.000000 0.325774 -v -0.067000 -0.137000 0.122200 -vn -0.736825 -0.676083 0.000000 -v -0.067000 -0.134900 0.117200 -vn -0.945450 0.162883 0.282123 -v -0.067000 -0.137500 0.122334 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.129700 0.126325 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.129700 0.123275 -vn -0.945436 -0.325809 0.000004 -v -0.067000 -0.136000 0.123200 -vn -0.945448 -0.282126 -0.162887 -v -0.067000 -0.136134 0.123700 -vn -0.945445 -0.162889 -0.282136 -v -0.067000 -0.136500 0.124066 -vn -0.990580 -0.130231 0.042315 -v -0.067000 -0.139804 0.126436 -vn -0.945447 -0.000001 -0.325775 -v -0.067000 -0.137000 0.124200 -vn -0.945451 0.162886 -0.282118 -v -0.067000 -0.137500 0.124066 -vn -0.945439 0.282150 0.162897 -v -0.067000 -0.137866 0.122700 -vn -0.991444 -0.130529 0.000000 -v -0.067000 -0.140000 0.117200 -vn -0.945446 0.325778 0.000003 -v -0.067000 -0.138000 0.123200 -vn -0.991444 -0.130529 0.000000 -v -0.067000 -0.140000 0.123275 -vn -0.945440 0.282146 -0.162903 -v -0.067000 -0.137866 0.123700 -vn -0.991003 -0.133729 0.005386 -v -0.067000 -0.140000 0.125200 -vn -0.990580 -0.135247 0.021420 -v -0.067000 -0.139951 0.125826 -vn -0.770260 -0.318865 0.552291 -v -0.067000 -0.122125 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.067000 -0.121667 0.130075 -vn -0.973781 0.131340 0.185743 -v -0.067000 -0.119500 0.130200 -vn -0.770261 -0.637729 -0.000002 -v -0.067000 -0.121500 0.130700 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.119500 0.132075 -vn -0.770263 -0.552286 -0.318865 -v -0.067000 -0.121667 0.131325 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.132075 -vn -0.770260 -0.318865 -0.552291 -v -0.067000 -0.122125 0.131783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 -0.122750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.067000 -0.123375 0.131783 -vn -0.770263 0.552286 -0.318865 -v -0.067000 -0.123833 0.131325 -vn -0.770264 0.000000 0.637725 -v -0.067000 -0.122750 0.129450 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.127100 -vn -0.770260 0.318865 0.552291 -v -0.067000 -0.123375 0.129617 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.127100 -vn -0.770264 0.552286 0.318863 -v -0.067000 -0.123833 0.130075 -vn -0.770261 0.637729 -0.000002 -v -0.067000 -0.124000 0.130700 -vn -0.770261 -0.318866 0.552288 -v -0.067000 -0.106125 0.129617 -vn -0.973781 0.131340 0.185743 -v -0.067000 -0.103500 0.130200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.127100 -vn -0.770266 -0.318854 0.552289 -v -0.067000 -0.103850 0.127160 -vn -0.770258 -0.552288 0.318875 -v -0.067000 -0.103960 0.127050 -vn -0.770261 -0.552288 0.318865 -v -0.067000 -0.105667 0.130075 -vn -0.770263 -0.637726 -0.000002 -v -0.067000 -0.105500 0.130700 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.103500 0.132075 -vn -0.770261 -0.552288 -0.318867 -v -0.067000 -0.105667 0.131325 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.132075 -vn -0.973781 -0.131340 0.185743 -v -0.067000 -0.110000 0.130200 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.110000 0.132075 -vn -0.770263 0.552286 -0.318865 -v -0.067000 -0.107833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.067000 -0.108000 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.067000 -0.107833 0.130075 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.127100 -vn -0.770260 0.318865 0.552291 -v -0.067000 -0.107375 0.129617 -vn -0.770264 0.000001 0.637726 -v -0.067000 -0.106750 0.129450 -vn -0.770261 -0.318866 -0.552288 -v -0.067000 -0.106125 0.131783 -vn -0.770264 0.000001 -0.637726 -v -0.067000 -0.106750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.067000 -0.107375 0.131783 -vn -0.770264 0.637725 -0.000000 -v -0.067000 -0.094750 0.125200 -vn -0.770261 0.552288 0.318867 -v -0.067000 -0.094583 0.124575 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.123275 -vn -0.770261 0.318867 0.552288 -v -0.067000 -0.094125 0.124117 -vn -0.770264 0.000001 0.637726 -v -0.067000 -0.093500 0.123950 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.092000 0.123275 -vn -0.770261 -0.318866 0.552288 -v -0.067000 -0.092875 0.124117 -vn -0.770261 -0.552288 0.318867 -v -0.067000 -0.092417 0.124575 -vn -0.770264 -0.637725 0.000000 -v -0.067000 -0.092250 0.125200 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.092000 0.126325 -vn -0.770261 -0.552288 -0.318867 -v -0.067000 -0.092417 0.125825 -vn -0.770261 -0.318866 -0.552288 -v -0.067000 -0.092875 0.126283 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.092000 0.127100 -vn -0.770264 0.000001 -0.637726 -v -0.067000 -0.093500 0.126450 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.127100 -vn -0.770261 0.318867 -0.552288 -v -0.067000 -0.094125 0.126283 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.126325 -vn -0.770261 0.552288 -0.318867 -v -0.067000 -0.094583 0.125825 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.116750 0.102200 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 -0.118000 0.102200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.106075 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 -0.118000 0.104200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.106075 -vn -0.973781 0.131340 -0.185743 -v -0.067000 -0.119500 0.104200 -vn -0.770262 -0.552289 -0.318863 -v -0.067000 -0.121667 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 -0.122125 0.104783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 -0.122750 0.104950 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.106075 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.124050 0.102200 -vn -0.770261 0.637728 0.000000 -v -0.067000 -0.124000 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.067000 -0.123833 0.103075 -vn -0.770261 0.318867 -0.552288 -v -0.067000 -0.123375 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.067000 -0.123833 0.104325 -vn -0.770262 0.318863 0.552289 -v -0.067000 -0.123375 0.102617 -vn -0.770261 -0.000000 0.637728 -v -0.067000 -0.122750 0.102450 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.122000 0.102200 -vn -0.770262 -0.318863 0.552289 -v -0.067000 -0.122125 0.102617 -vn -0.717284 0.630263 -0.297109 -v -0.067000 -0.119500 0.102200 -vn -0.770262 -0.552289 0.318863 -v -0.067000 -0.121667 0.103075 -vn -0.770261 -0.637728 -0.000000 -v -0.067000 -0.121500 0.103700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.102000 0.106075 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 -0.102000 0.104200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.106075 -vn -0.973781 0.131340 -0.185743 -v -0.067000 -0.103500 0.104200 -vn -0.770260 -0.552291 -0.318865 -v -0.067000 -0.105667 0.104325 -vn -0.770262 0.552289 0.318863 -v -0.067000 -0.107833 0.103075 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 -0.110000 0.102200 -vn -0.770261 0.637728 0.000000 -v -0.067000 -0.108000 0.103700 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 -0.110000 0.104200 -vn -0.770262 0.552289 -0.318863 -v -0.067000 -0.107833 0.104325 -vn -0.770262 0.318863 0.552289 -v -0.067000 -0.107375 0.102617 -vn -0.770261 0.000001 0.637729 -v -0.067000 -0.106750 0.102450 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.106250 0.102200 -vn -0.770263 -0.318864 0.552286 -v -0.067000 -0.106125 0.102617 -vn -0.717283 0.630263 -0.297109 -v -0.067000 -0.103500 0.102200 -vn -0.770260 -0.552291 0.318865 -v -0.067000 -0.105667 0.103075 -vn -0.770264 -0.637725 0.000000 -v -0.067000 -0.105500 0.103700 -vn -0.770261 0.318867 -0.552288 -v -0.067000 -0.107375 0.104783 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.106075 -vn -0.770264 0.000001 -0.637726 -v -0.067000 -0.106750 0.104950 -vn -0.770262 -0.318868 -0.552286 -v -0.067000 -0.106125 0.104783 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.107300 -vn -0.770266 0.552289 -0.318854 -v -0.067000 -0.097040 0.107350 -vn -0.737697 0.669358 -0.088113 -v -0.067000 -0.097000 0.107500 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.111125 -vn -0.770260 -0.552288 -0.318870 -v -0.067000 -0.103960 0.107350 -vn -0.770260 -0.318870 -0.552288 -v -0.067000 -0.103850 0.107240 -vn -0.737702 -0.088128 -0.669350 -v -0.067000 -0.103700 0.107200 -vn -0.707107 0.000000 -0.707107 -v -0.067000 -0.102000 0.107200 -vn -0.737703 0.088127 -0.669349 -v -0.067000 -0.097300 0.107200 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.104000 0.111125 -vn -0.737703 -0.669349 -0.088127 -v -0.067000 -0.104000 0.107500 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.107300 -vn -0.707107 0.000000 0.707107 -v -0.067000 -0.102000 0.113200 -vn -0.737702 -0.088127 0.669349 -v -0.067000 -0.103700 0.113200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.117200 -vn -0.770260 -0.318870 0.552288 -v -0.067000 -0.103850 0.113160 -vn -0.770260 -0.552288 0.318870 -v -0.067000 -0.103960 0.113050 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.112700 -vn -0.737702 -0.669350 0.088128 -v -0.067000 -0.104000 0.112900 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.097000 0.111125 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.097000 0.112700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.112700 -vn -0.737697 0.669358 0.088113 -v -0.067000 -0.097000 0.112900 -vn -0.717284 0.630262 -0.297109 -v -0.067000 -0.111500 0.102200 -vn -0.973781 0.131340 -0.185743 -v -0.067000 -0.111500 0.104200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.106075 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.092000 0.106075 -vn -0.717284 0.297109 -0.630262 -v -0.067000 -0.092000 0.105950 -vn -0.973781 0.185743 -0.131340 -v -0.067000 -0.094000 0.105950 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.106075 -vn -0.816496 0.408249 -0.408249 -v -0.067000 -0.094000 0.104200 -vn -0.717284 0.297109 0.630262 -v -0.067000 -0.092000 0.112450 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.092000 0.111125 -vn -0.973781 0.185743 0.131340 -v -0.067000 -0.094000 0.112450 -vn -0.923879 0.382685 0.000000 -v -0.067000 -0.094000 0.112700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.117200 -vn -0.770266 0.552289 0.318854 -v -0.067000 -0.097040 0.113050 -vn -0.717284 0.297109 -0.630262 -v -0.067000 -0.092000 0.121950 -vn -0.973781 0.185743 -0.131340 -v -0.067000 -0.094000 0.121950 -vn -0.923879 0.382685 0.000000 -v -0.067000 -0.094000 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.095875 0.132075 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.095500 0.132075 -vn -0.973781 0.131340 0.185743 -v -0.067000 -0.095500 0.130200 -vn -0.717284 0.297109 0.630262 -v -0.067000 -0.092000 0.128450 -vn -0.973781 0.185743 0.131340 -v -0.067000 -0.094000 0.128450 -vn -0.816496 0.408249 0.408249 -v -0.067000 -0.094000 0.130200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.132075 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.111500 0.132075 -vn -0.973781 0.131340 0.185743 -v -0.067000 -0.111500 0.130200 -vn -0.717284 0.630262 0.297109 -v -0.067000 -0.111500 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 -0.112250 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 -0.116750 0.132200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.127100 -vn -0.973781 -0.131340 0.185743 -v -0.067000 -0.118000 0.130200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.132075 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.118000 0.132075 -vn -0.717284 -0.630262 0.297109 -v -0.067000 -0.118000 0.132200 -vn -0.717283 -0.630262 0.297110 -v -0.067000 -0.127500 0.130200 -vn -0.990580 -0.122008 0.062167 -v -0.067000 -0.139564 0.127016 -vn -0.990581 -0.110780 0.080486 -v -0.067000 -0.139236 0.127551 -vn -0.990581 -0.021420 0.135243 -v -0.067000 -0.136626 0.129151 -vn -0.990580 -0.042315 0.130230 -v -0.067000 -0.137236 0.129004 -vn -0.990581 -0.096824 0.096823 -v -0.067000 -0.138828 0.128028 -vn -0.990580 -0.080487 0.110781 -v -0.067000 -0.138351 0.128436 -vn -0.990581 -0.062164 0.122005 -v -0.067000 -0.137816 0.128764 -vn -0.945436 -0.325809 0.000004 -v -0.067000 -0.136000 0.111200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.129700 0.111125 -vn -0.945449 -0.282127 0.162882 -v -0.067000 -0.136134 0.110700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.129700 0.107300 -vn -0.945445 -0.162888 0.282137 -v -0.067000 -0.136500 0.110334 -vn -0.945442 0.000001 0.325791 -v -0.067000 -0.137000 0.110200 -vn -0.990580 -0.080487 -0.110780 -v -0.067000 -0.138351 0.105964 -vn -0.990581 -0.096825 -0.096824 -v -0.067000 -0.138828 0.106372 -vn -0.945451 0.162881 0.282123 -v -0.067000 -0.137500 0.110334 -vn -0.990580 -0.122007 -0.062166 -v -0.067000 -0.139564 0.107384 -vn -0.990580 -0.110780 -0.080486 -v -0.067000 -0.139236 0.106849 -vn -0.991004 -0.005386 -0.133727 -v -0.067000 -0.136000 0.105200 -vn -0.990581 -0.021421 -0.135245 -v -0.067000 -0.136626 0.105249 -vn -0.990580 -0.042314 -0.130231 -v -0.067000 -0.137236 0.105396 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 -0.126000 0.102200 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 -0.126000 0.104200 -vn -0.717283 -0.630262 -0.297110 -v -0.067000 -0.127500 0.104200 -vn -0.997001 -0.041899 -0.065066 -v -0.067000 -0.127500 0.105200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.129700 0.106075 -vn -0.973781 -0.131340 0.185743 -v -0.067000 -0.102000 0.130200 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.102000 0.132075 -vn -0.770263 0.552286 -0.318865 -v -0.067000 -0.099833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.067000 -0.100000 0.130700 -vn -0.707107 0.000000 0.707107 -v -0.067000 -0.102000 0.127200 -vn -0.737697 -0.088113 0.669358 -v -0.067000 -0.103700 0.127200 -vn -0.770264 0.552286 0.318863 -v -0.067000 -0.099833 0.130075 -vn -0.770260 0.318865 0.552291 -v -0.067000 -0.099375 0.129617 -vn -0.737697 0.088113 0.669358 -v -0.067000 -0.097300 0.127200 -vn -0.770264 0.000000 0.637725 -v -0.067000 -0.098750 0.129450 -vn -0.770266 0.318854 0.552289 -v -0.067000 -0.097150 0.127160 -vn -0.770260 -0.318865 0.552291 -v -0.067000 -0.098125 0.129617 -vn -0.770262 -0.552286 0.318867 -v -0.067000 -0.097667 0.130075 -vn -0.770263 -0.637726 -0.000002 -v -0.067000 -0.097500 0.130700 -vn -0.770262 -0.552286 -0.318869 -v -0.067000 -0.097667 0.131325 -vn -0.770260 -0.318865 -0.552291 -v -0.067000 -0.098125 0.131783 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.097250 0.132075 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 -0.098750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.067000 -0.099375 0.131783 -vn -0.770264 0.552289 0.318858 -v -0.067000 -0.097040 0.127050 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.097000 0.126325 -vn -0.737698 0.669355 0.088117 -v -0.067000 -0.097000 0.126900 -vn -0.737697 0.088113 -0.669358 -v -0.067000 -0.097300 0.121200 -vn -0.770266 0.318854 -0.552289 -v -0.067000 -0.097150 0.121240 -vn -0.770266 0.552289 -0.318854 -v -0.067000 -0.097040 0.121350 -vn -0.737697 0.669358 -0.088113 -v -0.067000 -0.097000 0.121500 -vn -0.707107 0.707107 0.000000 -v -0.067000 -0.097000 0.123275 -vn -0.737697 -0.088113 -0.669358 -v -0.067000 -0.103700 0.121200 -vn -0.707107 0.000000 -0.707107 -v -0.067000 -0.102000 0.121200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.102000 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.097250 0.117200 -vn -0.770260 0.318870 0.552288 -v -0.067000 -0.097150 0.113160 -vn -0.770266 -0.318854 -0.552289 -v -0.067000 -0.103850 0.121240 -vn -0.737702 0.088128 0.669350 -v -0.067000 -0.097300 0.113200 -vn -0.737704 -0.669347 0.088131 -v -0.067000 -0.104000 0.126900 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.104000 0.126325 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.126325 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.104000 0.123275 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.123275 -vn -0.737703 -0.669349 -0.088127 -v -0.067000 -0.104000 0.121500 -vn -0.770260 -0.552288 -0.318870 -v -0.067000 -0.103960 0.121350 -vn -0.973781 0.185742 -0.131340 -v -0.067000 -0.117500 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.112700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.111125 -vn -0.923880 -0.382683 -0.000000 -v -0.067000 -0.111000 0.111125 -vn -0.923880 -0.382683 0.000000 -v -0.067000 -0.111000 0.112700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.107300 -vn -0.923877 0.000000 0.382689 -v -0.067000 -0.112250 0.107400 -vn -0.987814 -0.110052 0.110052 -v -0.067000 -0.111000 0.107400 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.107300 -vn -0.923877 0.000000 0.382689 -v -0.067000 -0.116750 0.107400 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.107300 -vn -0.987814 0.110052 0.110052 -v -0.067000 -0.117500 0.107400 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.123275 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.117500 0.123275 -vn -0.973781 0.185742 0.131340 -v -0.067000 -0.117500 0.117700 -vn -0.707107 0.000000 0.707107 -v -0.067000 -0.116750 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.117200 -vn -0.707107 0.000000 0.707107 -v -0.067000 -0.112250 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.117200 -vn -0.973781 -0.185743 0.131340 -v -0.067000 -0.111000 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.123275 -vn -0.923880 -0.382683 0.000000 -v -0.067000 -0.111000 0.123275 -vn -0.923877 -0.382689 0.000000 -v -0.067000 -0.111000 0.126325 -vn -0.736824 0.546965 0.397391 -v -0.067000 -0.125131 0.120374 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.123275 -vn -0.736824 0.642995 0.208921 -v -0.067000 -0.124364 0.118869 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.117200 -vn -0.736824 0.397392 0.546965 -v -0.067000 -0.126326 0.121569 -vn -0.736823 0.208921 0.642996 -v -0.067000 -0.127831 0.122336 -vn -0.736824 0.000000 0.676085 -v -0.067000 -0.129500 0.122600 -vn -0.736823 -0.208921 0.642996 -v -0.067000 -0.131169 0.122336 -vn -0.945449 -0.282127 0.162882 -v -0.067000 -0.136134 0.122700 -vn -0.736824 -0.397392 0.546965 -v -0.067000 -0.132674 0.121569 -vn -0.736824 -0.546965 0.397392 -v -0.067000 -0.133869 0.120374 -vn -0.736823 0.397393 -0.546965 -v -0.067000 -0.126326 0.112831 -vn -0.736825 0.546963 -0.397391 -v -0.067000 -0.125131 0.114026 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.112700 -vn -0.736824 0.642996 -0.208921 -v -0.067000 -0.124364 0.115531 -vn -0.736824 0.676085 0.000000 -v -0.067000 -0.124100 0.117200 -vn -0.945441 -0.162897 -0.282145 -v -0.067000 -0.136500 0.112066 -vn -0.945447 0.000001 -0.325776 -v -0.067000 -0.137000 0.112200 -vn -0.736823 -0.397393 -0.546965 -v -0.067000 -0.132674 0.112831 -vn -0.991444 -0.130529 0.000000 -v -0.067000 -0.140000 0.112700 -vn -0.736825 -0.546963 -0.397392 -v -0.067000 -0.133869 0.114026 -vn -0.736824 0.208922 -0.642995 -v -0.067000 -0.127831 0.112064 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.111125 -vn -0.736824 0.000000 -0.676085 -v -0.067000 -0.129500 0.111800 -vn -0.736824 -0.208922 -0.642995 -v -0.067000 -0.131169 0.112064 -vn -0.945448 -0.282126 -0.162887 -v -0.067000 -0.136134 0.111700 -vn -0.990580 -0.130231 -0.042315 -v -0.067000 -0.139804 0.107964 -vn -0.990580 -0.135247 -0.021421 -v -0.067000 -0.139951 0.108574 -vn -0.945439 0.282150 0.162897 -v -0.067000 -0.137866 0.110700 -vn -0.991003 -0.133729 -0.005386 -v -0.067000 -0.140000 0.109200 -vn -0.945446 0.325778 0.000003 -v -0.067000 -0.138000 0.111200 -vn -0.991444 -0.130529 0.000000 -v -0.067000 -0.140000 0.111125 -vn -0.945439 0.282148 -0.162902 -v -0.067000 -0.137866 0.111700 -vn -0.945447 0.162891 -0.282129 -v -0.067000 -0.137500 0.112066 -vn -0.736823 -0.642996 -0.208921 -v -0.067000 -0.134636 0.115531 -vn -0.945442 -0.325791 0.000002 -v -0.067000 -0.122500 0.125200 -vn -0.945445 -0.282136 -0.162889 -v -0.067000 -0.122634 0.125700 -vn -0.945441 -0.162894 0.282148 -v -0.067000 -0.123000 0.124334 -vn -0.945448 -0.282129 0.162884 -v -0.067000 -0.122634 0.124700 -vn -0.945447 0.325776 0.000002 -v -0.067000 -0.124500 0.125200 -vn -0.945444 0.282138 0.162893 -v -0.067000 -0.124366 0.124700 -vn -0.945443 0.162894 0.282139 -v -0.067000 -0.124000 0.124334 -vn -0.945447 -0.000002 0.325776 -v -0.067000 -0.123500 0.124200 -vn -0.945445 -0.162889 -0.282135 -v -0.067000 -0.123000 0.126066 -vn -0.945448 -0.000001 -0.325775 -v -0.067000 -0.123500 0.126200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.126325 -vn -0.945448 0.162888 -0.282126 -v -0.067000 -0.124000 0.126066 -vn -0.945441 0.282145 -0.162897 -v -0.067000 -0.124366 0.125700 -vn -0.945448 -0.282126 -0.162887 -v -0.067000 -0.122634 0.109700 -vn -0.945445 -0.162889 -0.282136 -v -0.067000 -0.123000 0.110066 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.111125 -vn -0.945442 -0.325792 0.000002 -v -0.067000 -0.122500 0.109200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.124050 0.107300 -vn -0.945447 -0.000002 0.325776 -v -0.067000 -0.123500 0.108200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.122000 0.107300 -vn -0.945441 -0.162894 0.282148 -v -0.067000 -0.123000 0.108334 -vn -0.945448 -0.282129 0.162884 -v -0.067000 -0.122634 0.108700 -vn -0.923880 0.382683 -0.000000 -v -0.067000 -0.117500 0.111125 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.117500 0.112700 -vn -0.945444 0.282138 0.162893 -v -0.067000 -0.124366 0.108700 -vn -0.945443 0.162894 0.282139 -v -0.067000 -0.124000 0.108334 -vn -0.945448 -0.000001 -0.325775 -v -0.067000 -0.123500 0.110200 -vn -0.945448 0.162887 -0.282128 -v -0.067000 -0.124000 0.110066 -vn -0.945444 0.282137 -0.162895 -v -0.067000 -0.124366 0.109700 -vn -0.945447 0.325776 0.000001 -v -0.067000 -0.124500 0.109200 -vn -0.717284 0.630262 0.297109 -v -0.067000 -0.119500 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 -0.122000 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 -0.124050 0.132200 -vn -0.717284 -0.630263 0.297109 -v -0.067000 -0.126000 0.132200 -vn -0.717284 0.630262 0.297109 -v -0.067000 -0.103500 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 -0.106250 0.132200 -vn -0.717284 -0.630262 0.297109 -v -0.067000 -0.110000 0.132200 -vn -0.717284 0.630262 0.297109 -v -0.067000 -0.095500 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 -0.095875 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 -0.097250 0.132200 -vn -0.717284 -0.630262 0.297109 -v -0.067000 -0.102000 0.132200 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.127100 -vn -0.770264 -0.552286 0.318863 -v -0.067000 -0.113667 0.130075 -vn -0.770261 -0.637729 -0.000002 -v -0.067000 -0.113500 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.067000 -0.113667 0.131325 -vn -0.770260 -0.318865 -0.552291 -v -0.067000 -0.114125 0.131783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 -0.114750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.067000 -0.115375 0.131783 -vn -0.770264 0.552286 0.318863 -v -0.067000 -0.115833 0.130075 -vn -0.770261 0.637729 -0.000002 -v -0.067000 -0.116000 0.130700 -vn -0.770263 0.552286 -0.318865 -v -0.067000 -0.115833 0.131325 -vn -0.770260 0.318865 0.552291 -v -0.067000 -0.115375 0.129617 -vn -0.770264 0.000000 0.637725 -v -0.067000 -0.114750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.067000 -0.114125 0.129617 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.126325 -vn -0.945447 -0.325775 -0.000001 -v -0.067000 -0.107000 0.125200 -vn -0.945441 -0.282148 -0.162894 -v -0.067000 -0.107134 0.125700 -vn -0.945446 0.282135 -0.162887 -v -0.067000 -0.108866 0.125700 -vn -0.945442 0.325791 -0.000002 -v -0.067000 -0.109000 0.125200 -vn -0.945448 -0.162886 -0.282129 -v -0.067000 -0.107500 0.126066 -vn -0.945448 -0.000000 -0.325775 -v -0.067000 -0.108000 0.126200 -vn -0.945448 0.162888 -0.282126 -v -0.067000 -0.108500 0.126066 -vn -0.987814 -0.110051 -0.110052 -v -0.067000 -0.111000 0.127000 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.112250 0.127000 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.116750 0.127000 -vn -0.945448 0.282128 0.162887 -v -0.067000 -0.108866 0.124700 -vn -0.945444 0.162895 0.282137 -v -0.067000 -0.108500 0.124334 -vn -0.945447 -0.000001 0.325776 -v -0.067000 -0.108000 0.124200 -vn -0.945443 -0.282139 0.162895 -v -0.067000 -0.107134 0.124700 -vn -0.945444 -0.162893 0.282138 -v -0.067000 -0.107500 0.124334 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.106250 0.111125 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.110000 0.112700 -vn -0.973781 -0.185742 -0.131340 -v -0.067000 -0.111000 0.116700 -vn -0.707107 0.000000 -0.707107 -v -0.067000 -0.112250 0.116700 -vn -0.707107 0.000000 -0.707107 -v -0.067000 -0.116750 0.116700 -vn -0.945447 -0.325776 -0.000001 -v -0.067000 -0.107000 0.109200 -vn -0.945444 -0.282138 -0.162893 -v -0.067000 -0.107134 0.109700 -vn -0.945443 -0.282139 0.162894 -v -0.067000 -0.107134 0.108700 -vn -0.707107 -0.707107 0.000000 -v -0.067000 -0.104000 0.112700 -vn -0.945448 0.162887 -0.282128 -v -0.067000 -0.108500 0.110066 -vn -0.945448 -0.000000 -0.325775 -v -0.067000 -0.108000 0.110200 -vn -0.945448 -0.162886 -0.282129 -v -0.067000 -0.107500 0.110066 -vn -0.945449 0.282127 -0.162884 -v -0.067000 -0.108866 0.109700 -vn -0.945442 0.325792 -0.000002 -v -0.067000 -0.109000 0.109200 -vn -0.945448 0.282128 0.162887 -v -0.067000 -0.108866 0.108700 -vn -0.945444 0.162895 0.282137 -v -0.067000 -0.108500 0.108334 -vn -0.945447 -0.000001 0.325776 -v -0.067000 -0.108000 0.108200 -vn -0.945444 -0.162893 0.282138 -v -0.067000 -0.107500 0.108334 -vn -0.770260 -0.552291 -0.318865 -v -0.067000 -0.092417 0.109825 -vn -0.770264 -0.637725 0.000000 -v -0.067000 -0.092250 0.109200 -vn -0.923880 0.382683 0.000000 -v -0.067000 -0.092000 0.107300 -vn -0.770260 -0.552291 0.318865 -v -0.067000 -0.092417 0.108575 -vn -0.770263 -0.318864 0.552286 -v -0.067000 -0.092875 0.108117 -vn -0.770263 0.318865 -0.552286 -v -0.067000 -0.094125 0.110283 -vn -0.770261 0.000001 -0.637729 -v -0.067000 -0.093500 0.110450 -vn -0.770264 -0.318864 -0.552286 -v -0.067000 -0.092875 0.110283 -vn -0.770263 0.318865 0.552286 -v -0.067000 -0.094125 0.108117 -vn -0.770261 0.000001 0.637729 -v -0.067000 -0.093500 0.107950 -vn -0.770260 0.552291 -0.318865 -v -0.067000 -0.094583 0.109825 -vn -0.770264 0.637725 -0.000000 -v -0.067000 -0.094750 0.109200 -vn -0.770260 0.552291 0.318865 -v -0.067000 -0.094583 0.108575 -vn -0.990580 -0.062166 -0.122008 -v -0.067000 -0.137816 0.105636 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 -0.114750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.067000 -0.115375 0.104783 -vn -0.770262 -0.552289 -0.318863 -v -0.067000 -0.113667 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 -0.114125 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.067000 -0.115833 0.104325 -vn -0.770261 0.637728 0.000000 -v -0.067000 -0.116000 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.067000 -0.115833 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.067000 -0.115375 0.102617 -vn -0.770261 -0.000000 0.637728 -v -0.067000 -0.114750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.067000 -0.114125 0.102617 -vn -0.770262 0.552289 0.318863 -v -0.067000 -0.099833 0.103075 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 -0.102000 0.102200 -vn -0.770261 0.637728 0.000000 -v -0.067000 -0.100000 0.103700 -vn -0.770262 0.552289 -0.318863 -v -0.067000 -0.099833 0.104325 -vn -0.770261 0.318867 -0.552288 -v -0.067000 -0.099375 0.104783 -vn -0.770262 0.318863 0.552289 -v -0.067000 -0.099375 0.102617 -vn -0.770261 -0.000000 0.637728 -v -0.067000 -0.098750 0.102450 -vn -0.923880 0.000000 -0.382683 -v -0.067000 -0.097250 0.102200 -vn -0.770262 -0.318863 0.552289 -v -0.067000 -0.098125 0.102617 -vn -0.770261 -0.552288 0.318867 -v -0.067000 -0.097667 0.103075 -vn -0.770264 -0.637725 0.000000 -v -0.067000 -0.097500 0.103700 -vn -0.770261 -0.552288 -0.318867 -v -0.067000 -0.097667 0.104325 -vn -1.000000 0.000000 0.000000 -v -0.067000 -0.097250 0.106075 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 -0.098125 0.104783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 -0.098750 0.104950 -vn -0.770260 0.318870 -0.552288 -v -0.067000 -0.097150 0.107240 -vn 0.301511 0.301511 0.904534 -v -0.065000 -0.124750 0.133200 -vn 0.770260 0.318865 -0.552291 -v -0.065000 -0.123375 0.131783 -vn 0.770264 0.000000 -0.637725 -v -0.065000 -0.122750 0.131950 -vn 0.609994 -0.000001 0.792406 -v -0.065000 -0.122750 0.128391 -vn 0.770264 -0.000000 0.637725 -v -0.065000 -0.122750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.065000 -0.123375 0.129617 -vn 0.301511 -0.301511 0.904534 -v -0.065000 -0.120750 0.133200 -vn 0.770260 -0.318865 -0.552291 -v -0.065000 -0.122125 0.131783 -vn 0.770263 -0.552286 -0.318865 -v -0.065000 -0.121667 0.131325 -vn 0.609995 -0.686244 0.396202 -v -0.065000 -0.120750 0.129545 -vn 0.609994 0.686244 0.396203 -v -0.065000 -0.124750 0.129545 -vn 0.770264 0.552286 0.318863 -v -0.065000 -0.123833 0.130075 -vn 0.770261 0.637729 -0.000002 -v -0.065000 -0.124000 0.130700 -vn 0.770263 0.552286 -0.318865 -v -0.065000 -0.123833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.065000 -0.121500 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.065000 -0.121667 0.130075 -vn 0.770260 -0.318865 0.552291 -v -0.065000 -0.122125 0.129617 -vn 0.609995 -0.686244 0.396202 -v -0.065000 -0.112750 0.129545 -vn 0.770264 -0.552286 0.318863 -v -0.065000 -0.113667 0.130075 -vn 0.609994 -0.000001 0.792406 -v -0.065000 -0.114750 0.128391 -vn 0.770260 -0.318865 0.552291 -v -0.065000 -0.114125 0.129617 -vn 0.609994 0.686244 0.396202 -v -0.065000 -0.116750 0.129545 -vn 0.770261 0.637729 -0.000002 -v -0.065000 -0.116000 0.130700 -vn 0.301511 0.301511 0.904534 -v -0.065000 -0.116750 0.133200 -vn 0.770263 0.552286 -0.318865 -v -0.065000 -0.115833 0.131325 -vn 0.770260 0.318865 -0.552291 -v -0.065000 -0.115375 0.131783 -vn 0.770264 0.000000 -0.637725 -v -0.065000 -0.114750 0.131950 -vn 0.301511 -0.301511 0.904534 -v -0.065000 -0.112750 0.133200 -vn 0.770260 -0.318865 -0.552291 -v -0.065000 -0.114125 0.131783 -vn 0.770263 -0.552286 -0.318865 -v -0.065000 -0.113667 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.065000 -0.113500 0.130700 -vn 0.770264 -0.000000 0.637725 -v -0.065000 -0.114750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.065000 -0.115375 0.129617 -vn 0.770264 0.552286 0.318863 -v -0.065000 -0.115833 0.130075 -vn 0.609995 0.686244 0.396202 -v -0.065000 -0.108750 0.129545 -vn 0.770261 0.637729 -0.000002 -v -0.065000 -0.108000 0.130700 -vn 0.301511 0.301511 0.904534 -v -0.065000 -0.108750 0.133200 -vn 0.770263 0.552286 -0.318865 -v -0.065000 -0.107833 0.131325 -vn 0.609994 0.000001 0.792406 -v -0.065000 -0.106750 0.128391 -vn 0.770260 0.318865 0.552291 -v -0.065000 -0.107375 0.129617 -vn 0.770264 0.552286 0.318863 -v -0.065000 -0.107833 0.130075 -vn 0.770260 0.318865 -0.552291 -v -0.065000 -0.107375 0.131783 -vn 0.770264 0.000001 -0.637726 -v -0.065000 -0.106750 0.131950 -vn 0.301511 -0.301511 0.904534 -v -0.065000 -0.104750 0.133200 -vn 0.770263 -0.637726 -0.000002 -v -0.065000 -0.105500 0.130700 -vn 0.609994 -0.686244 0.396202 -v -0.065000 -0.104750 0.129545 -vn 0.770261 -0.552288 -0.318867 -v -0.065000 -0.105667 0.131325 -vn 0.770261 -0.318866 -0.552288 -v -0.065000 -0.106125 0.131783 -vn 0.770261 -0.552288 0.318865 -v -0.065000 -0.105667 0.130075 -vn 0.770261 -0.318866 0.552288 -v -0.065000 -0.106125 0.129617 -vn 0.770264 0.000001 0.637726 -v -0.065000 -0.106750 0.129450 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.136850 0.127925 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.102000 0.102700 -vn 0.717284 -0.630262 -0.297109 -v -0.062000 -0.102000 0.102200 -vn 0.741787 0.516596 -0.427644 -v -0.062000 -0.100750 0.102200 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.111500 0.131700 -vn 0.717284 0.630263 0.297108 -v -0.062000 -0.111500 0.132200 -vn 0.741788 -0.516597 0.427643 -v -0.062000 -0.112750 0.132200 -vn 0.741787 0.516597 0.427643 -v -0.062000 -0.124750 0.132200 -vn 0.717284 -0.630263 0.297108 -v -0.062000 -0.126000 0.132200 -vn 0.846478 0.279911 0.452906 -v -0.062000 -0.123750 0.130200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.126000 0.131700 -vn 0.707107 0.000000 0.707107 -v -0.062000 -0.126325 0.131700 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.126325 0.127925 -vn 0.846479 -0.279912 0.452905 -v -0.062000 -0.121750 0.130200 -vn 1.000000 -0.000000 0.000001 -v -0.062000 -0.119550 0.127925 -vn 0.741787 -0.516598 0.427643 -v -0.062000 -0.120750 0.132200 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.119500 0.131700 -vn 0.717284 0.630263 0.297108 -v -0.062000 -0.119500 0.132200 -vn 0.923880 0.000000 0.382683 -v -0.062000 -0.119550 0.132200 -vn 0.846478 0.279911 0.452906 -v -0.062000 -0.115750 0.130200 -vn 0.741787 0.516597 0.427643 -v -0.062000 -0.116750 0.132200 -vn 0.717284 -0.630263 0.297108 -v -0.062000 -0.118000 0.132200 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.110450 0.127925 -vn 0.846478 -0.279911 0.452906 -v -0.062000 -0.113750 0.130200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.118000 0.131700 -vn 0.846478 0.279911 0.452906 -v -0.062000 -0.107750 0.130200 -vn 0.741787 0.516597 0.427643 -v -0.062000 -0.108750 0.132200 -vn 0.717284 -0.630263 0.297108 -v -0.062000 -0.110000 0.132200 -vn 1.000000 -0.000000 0.000001 -v -0.062000 -0.102250 0.127925 -vn 0.707107 0.000000 0.707107 -v -0.062000 -0.102250 0.131700 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.103500 0.131700 -vn 0.846478 -0.279911 0.452906 -v -0.062000 -0.105750 0.130200 -vn 0.707107 0.000000 0.707107 -v -0.062000 -0.110450 0.131700 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.110000 0.131700 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.102000 0.131700 -vn 0.846479 -0.279911 0.452906 -v -0.062000 -0.097750 0.130200 -vn 0.846478 0.279911 0.452906 -v -0.062000 -0.099750 0.130200 -vn 0.976002 0.188588 -0.108876 -v -0.062000 -0.097279 0.128050 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.094000 0.130200 -vn 0.577350 0.577350 0.577350 -v -0.062000 -0.094000 0.131700 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.095500 0.131700 -vn 0.976003 0.108877 -0.188582 -v -0.062000 -0.096950 0.128379 -vn 0.741788 -0.516597 0.427643 -v -0.062000 -0.096750 0.132200 -vn 0.717284 0.630263 0.297108 -v -0.062000 -0.095500 0.132200 -vn 0.976003 -0.188585 -0.108875 -v -0.062000 -0.095721 0.128050 -vn 0.976003 -0.108877 -0.188582 -v -0.062000 -0.096050 0.128379 -vn 0.976004 0.000000 -0.217755 -v -0.062000 -0.096500 0.128500 -vn 0.577350 0.577350 0.577350 -v -0.062000 -0.092500 0.130200 -vn 0.707107 0.000000 0.707107 -v -0.062000 -0.093800 0.130200 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.092500 0.128450 -vn 1.000000 0.000000 0.000002 -v -0.062000 -0.093800 0.127925 -vn 0.717284 0.297108 0.630263 -v -0.062000 -0.092000 0.128450 -vn 0.923880 0.382683 0.000002 -v -0.062000 -0.092000 0.127925 -vn 0.717284 0.297109 -0.630262 -v -0.062000 -0.092000 0.121950 -vn 0.741787 0.427644 0.516596 -v -0.062000 -0.092000 0.123200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.092500 0.121950 -vn 0.846478 0.452906 0.279911 -v -0.062000 -0.094000 0.124200 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.092500 0.120375 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.093800 0.120375 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.092500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.093800 0.117200 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.092500 0.114025 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.093800 0.114025 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.092500 0.112450 -vn 0.846479 0.452906 -0.279912 -v -0.062000 -0.094000 0.110200 -vn 0.717284 0.297109 0.630262 -v -0.062000 -0.092000 0.112450 -vn 0.741787 0.427644 -0.516597 -v -0.062000 -0.092000 0.111200 -vn 0.846478 0.452907 0.279911 -v -0.062000 -0.094000 0.108200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.093800 0.108000 -vn 0.741788 0.427644 0.516596 -v -0.062000 -0.092000 0.107200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.092500 0.105950 -vn 0.717284 0.297109 -0.630262 -v -0.062000 -0.092000 0.105950 -vn 0.846478 0.279911 -0.452907 -v -0.062000 -0.099750 0.104200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.108000 -vn 0.707107 0.000000 -0.707107 -v -0.062000 -0.102250 0.102700 -vn 0.976003 -0.217757 -0.000000 -v -0.062000 -0.095600 0.106800 -vn 0.976004 -0.188579 0.108876 -v -0.062000 -0.095721 0.106350 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.095500 0.102700 -vn 0.976003 -0.108877 0.188582 -v -0.062000 -0.096050 0.106021 -vn 0.976004 -0.000000 0.217755 -v -0.062000 -0.096500 0.105900 -vn 0.976003 0.188582 -0.108877 -v -0.062000 -0.097279 0.107250 -vn 0.976004 0.108876 -0.188579 -v -0.062000 -0.096950 0.107579 -vn 0.976003 0.000000 -0.217757 -v -0.062000 -0.096500 0.107700 -vn 0.976004 -0.108876 -0.188580 -v -0.062000 -0.096050 0.107579 -vn 0.976004 -0.188580 -0.108876 -v -0.062000 -0.095721 0.107250 -vn 0.717284 0.630262 -0.297109 -v -0.062000 -0.095500 0.102200 -vn 0.741787 -0.516596 -0.427644 -v -0.062000 -0.096750 0.102200 -vn 0.846478 -0.279911 -0.452907 -v -0.062000 -0.097750 0.104200 -vn 0.976004 0.108878 0.188581 -v -0.062000 -0.096950 0.106021 -vn 0.976004 0.188580 0.108877 -v -0.062000 -0.097279 0.106350 -vn 0.976004 0.217755 0.000000 -v -0.062000 -0.097400 0.106800 -vn 0.577350 0.577350 -0.577350 -v -0.062000 -0.094000 0.102700 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.094000 0.104200 -vn 0.707107 0.000000 -0.707107 -v -0.062000 -0.093800 0.104200 -vn 0.577350 0.577350 -0.577350 -v -0.062000 -0.092500 0.104200 -vn 0.707107 0.000000 -0.707107 -v -0.062000 -0.110450 0.102700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.110000 0.102700 -vn 0.741787 -0.516596 -0.427644 -v -0.062000 -0.104750 0.102200 -vn 0.717284 0.630262 -0.297109 -v -0.062000 -0.103500 0.102200 -vn 0.846478 -0.279911 -0.452907 -v -0.062000 -0.105750 0.104200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.103500 0.102700 -vn 0.846478 0.279911 -0.452906 -v -0.062000 -0.107750 0.104200 -vn 0.741787 0.516596 -0.427644 -v -0.062000 -0.108750 0.102200 -vn 0.717284 -0.630262 -0.297109 -v -0.062000 -0.110000 0.102200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.109475 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.108000 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.108000 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.112000 0.107700 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.119500 0.102700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.118000 0.102700 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.108000 -vn 0.923880 0.000000 -0.382683 -v -0.062000 -0.119550 0.102200 -vn 0.717284 0.630262 -0.297109 -v -0.062000 -0.119500 0.102200 -vn 0.741787 -0.516596 -0.427644 -v -0.062000 -0.112750 0.102200 -vn 0.717284 0.630262 -0.297109 -v -0.062000 -0.111500 0.102200 -vn 0.846478 -0.279911 -0.452907 -v -0.062000 -0.113750 0.104200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.111500 0.102700 -vn 0.717284 -0.630262 -0.297109 -v -0.062000 -0.118000 0.102200 -vn 0.741787 0.516596 -0.427644 -v -0.062000 -0.116750 0.102200 -vn 0.846478 0.279911 -0.452907 -v -0.062000 -0.115750 0.104200 -vn 0.707107 0.000000 -0.707107 -v -0.062000 -0.126325 0.102700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.126000 0.102700 -vn 0.741787 -0.516597 -0.427644 -v -0.062000 -0.120750 0.102200 -vn 0.846479 -0.279912 -0.452906 -v -0.062000 -0.121750 0.104200 -vn 0.846478 0.279911 -0.452907 -v -0.062000 -0.123750 0.104200 -vn 0.741787 0.516596 -0.427644 -v -0.062000 -0.124750 0.102200 -vn 0.717284 -0.630262 -0.297109 -v -0.062000 -0.126000 0.102200 -vn 0.707107 0.000000 -0.707107 -v -0.062000 -0.133425 0.104200 -vn 0.904534 -0.301511 -0.301512 -v -0.062000 -0.127500 0.104200 -vn 1.000000 0.000000 -0.000000 -v -0.062000 -0.126325 0.108000 -vn 0.976002 -0.108877 0.188587 -v -0.062000 -0.138050 0.107171 -vn 0.976003 0.000000 0.217758 -v -0.062000 -0.138500 0.107050 -vn 0.976005 0.108875 0.188572 -v -0.062000 -0.138950 0.107171 -vn 0.976004 0.188581 0.108877 -v -0.062000 -0.139279 0.107500 -vn 0.976004 0.217755 0.000000 -v -0.062000 -0.139400 0.107950 -vn 0.976004 0.188581 -0.108878 -v -0.062000 -0.139279 0.108400 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.141000 0.109475 -vn 0.976005 0.108875 -0.188575 -v -0.062000 -0.138950 0.108729 -vn 0.976004 0.000001 -0.217754 -v -0.062000 -0.138500 0.108850 -vn 0.976002 -0.108878 -0.188590 -v -0.062000 -0.138050 0.108729 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.109475 -vn 0.976004 -0.188578 -0.108874 -v -0.062000 -0.137721 0.108400 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.108000 -vn 0.976002 -0.217760 -0.000000 -v -0.062000 -0.137600 0.107950 -vn 0.976004 -0.188578 0.108874 -v -0.062000 -0.137721 0.107500 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.136850 0.126400 -vn 0.976002 -0.217760 -0.000000 -v -0.062000 -0.137600 0.126450 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.124925 -vn 0.976003 -0.188584 0.108876 -v -0.062000 -0.137721 0.126000 -vn 0.975997 -0.108892 0.188607 -v -0.062000 -0.138050 0.125671 -vn 0.976003 0.000003 0.217758 -v -0.062000 -0.138500 0.125550 -vn 0.976000 0.108886 0.188592 -v -0.062000 -0.138950 0.125671 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.141000 0.124925 -vn 0.976002 0.188587 0.108879 -v -0.062000 -0.139279 0.126000 -vn 0.976004 0.217755 0.000000 -v -0.062000 -0.139400 0.126450 -vn 0.976005 0.188572 -0.108876 -v -0.062000 -0.139279 0.126900 -vn 0.976005 0.108875 -0.188572 -v -0.062000 -0.138950 0.127229 -vn 0.976004 0.000001 -0.217752 -v -0.062000 -0.138500 0.127350 -vn 0.976002 -0.108878 -0.188588 -v -0.062000 -0.138050 0.127229 -vn 0.976006 -0.188572 -0.108871 -v -0.062000 -0.137721 0.126900 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.133425 0.127925 -vn 0.577350 -0.577350 0.577350 -v -0.062000 -0.127500 0.131700 -vn 0.904534 -0.301511 0.301512 -v -0.062000 -0.127500 0.130200 -vn 0.707107 0.000000 0.707107 -v -0.062000 -0.133425 0.130200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.116500 0.116700 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.117200 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.114025 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.114025 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.109475 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.109475 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.108000 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.117200 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.112000 0.116700 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.114025 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.114025 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.110200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.109475 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.126400 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.110450 0.126400 -vn 0.904535 -0.301511 -0.301510 -v -0.062000 -0.112000 0.126700 -vn 0.904535 0.301511 -0.301510 -v -0.062000 -0.116500 0.126700 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.126400 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.120375 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.120375 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.112000 0.117700 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.116500 0.117700 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.124925 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.124925 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.124200 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.116500 0.120375 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.119550 0.120375 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.112000 0.124925 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.110450 0.124925 -vn 0.976003 -0.188585 0.108878 -v -0.062000 -0.095721 0.127150 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.093800 0.126400 -vn 0.976003 -0.217757 0.000004 -v -0.062000 -0.095600 0.127600 -vn 1.000000 -0.000000 0.000001 -v -0.062000 -0.102250 0.126400 -vn 0.976002 0.188586 0.108880 -v -0.062000 -0.097279 0.127150 -vn 0.741787 0.516597 0.427643 -v -0.062000 -0.100750 0.132200 -vn 0.717284 -0.630263 0.297108 -v -0.062000 -0.102000 0.132200 -vn 0.976004 0.217755 0.000004 -v -0.062000 -0.097400 0.127600 -vn 0.976003 -0.108877 0.188583 -v -0.062000 -0.096050 0.126821 -vn 0.976004 -0.000000 0.217755 -v -0.062000 -0.096500 0.126700 -vn 0.976004 0.108878 0.188581 -v -0.062000 -0.096950 0.126821 -vn 0.770262 0.000000 -0.637728 -v -0.062000 -0.129500 0.118450 -vn 0.770262 -0.318861 -0.552290 -v -0.062000 -0.128875 0.118283 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.126325 0.120375 -vn 0.770265 -0.552286 -0.318861 -v -0.062000 -0.128417 0.117825 -vn 1.000000 0.000001 0.000000 -v -0.062000 -0.126325 0.117200 -vn 0.770259 -0.637731 0.000000 -v -0.062000 -0.128250 0.117200 -vn 1.000000 0.000000 -0.000000 -v -0.062000 -0.126325 0.114025 -vn 0.770265 -0.552286 0.318861 -v -0.062000 -0.128417 0.116575 -vn 0.770262 -0.318861 0.552290 -v -0.062000 -0.128875 0.116117 -vn 0.770262 0.000000 0.637728 -v -0.062000 -0.129500 0.115950 -vn 0.770263 0.318865 0.552286 -v -0.062000 -0.130125 0.116117 -vn 1.000000 0.000000 -0.000000 -v -0.062000 -0.133425 0.114025 -vn 0.770260 0.552291 0.318865 -v -0.062000 -0.130583 0.116575 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.133425 0.117200 -vn 0.770264 0.637725 0.000000 -v -0.062000 -0.130750 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.133425 0.120375 -vn 0.770260 0.552291 -0.318865 -v -0.062000 -0.130583 0.117825 -vn 0.770263 0.318865 -0.552286 -v -0.062000 -0.130125 0.118283 -vn 0.770263 -0.000000 -0.637726 -v -0.062000 -0.137000 0.124100 -vn 0.770261 -0.318866 -0.552288 -v -0.062000 -0.136550 0.123979 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.133425 0.124200 -vn 0.770261 -0.552288 -0.318866 -v -0.062000 -0.136221 0.123650 -vn 0.770263 -0.637726 0.000000 -v -0.062000 -0.136100 0.123200 -vn 0.770261 -0.552288 0.318866 -v -0.062000 -0.136221 0.122750 -vn 0.770263 0.000000 0.637726 -v -0.062000 -0.137000 0.122300 -vn 0.770258 0.318862 0.552295 -v -0.062000 -0.137450 0.122421 -vn 0.707107 -0.707106 0.000000 -v -0.062000 -0.141000 0.120375 -vn 0.770268 0.552282 0.318860 -v -0.062000 -0.137779 0.122750 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.141000 0.124200 -vn 0.770256 0.637735 -0.000000 -v -0.062000 -0.137900 0.123200 -vn 0.770268 0.552282 -0.318860 -v -0.062000 -0.137779 0.123650 -vn 0.770264 0.552285 -0.318863 -v -0.062000 -0.124279 0.125650 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.126325 0.126400 -vn 0.770260 0.637730 0.000001 -v -0.062000 -0.124400 0.125200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.126325 0.124925 -vn 0.770262 0.552289 0.318862 -v -0.062000 -0.124279 0.124750 -vn 0.770261 -0.552288 -0.318866 -v -0.062000 -0.122721 0.125650 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.119550 0.126400 -vn 0.770260 0.318864 -0.552292 -v -0.062000 -0.123950 0.125979 -vn 0.770263 -0.000000 -0.637726 -v -0.062000 -0.123500 0.126100 -vn 0.770261 -0.318866 -0.552288 -v -0.062000 -0.123050 0.125979 -vn 0.770264 -0.637725 0.000001 -v -0.062000 -0.122600 0.125200 -vn 0.770259 -0.552292 0.318865 -v -0.062000 -0.122721 0.124750 -vn 0.770264 -0.318863 0.552285 -v -0.062000 -0.123050 0.124421 -vn 0.770263 0.318861 0.552289 -v -0.062000 -0.123950 0.124421 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.126325 0.124200 -vn 0.770259 -0.000000 0.637731 -v -0.062000 -0.123500 0.124300 -vn 0.770261 0.552288 -0.318866 -v -0.062000 -0.108779 0.125650 -vn 0.770261 0.318866 -0.552288 -v -0.062000 -0.108450 0.125979 -vn 0.770263 -0.000000 -0.637726 -v -0.062000 -0.108000 0.126100 -vn 0.770260 -0.318864 -0.552292 -v -0.062000 -0.107550 0.125979 -vn 0.770264 -0.552285 -0.318863 -v -0.062000 -0.107221 0.125650 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.124925 -vn 0.770264 0.637725 0.000001 -v -0.062000 -0.108900 0.125200 -vn 0.770260 -0.637730 0.000001 -v -0.062000 -0.107100 0.125200 -vn 0.770262 -0.552289 0.318862 -v -0.062000 -0.107221 0.124750 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.124200 -vn 0.770263 -0.318861 0.552289 -v -0.062000 -0.107550 0.124421 -vn 0.770259 -0.000000 0.637731 -v -0.062000 -0.108000 0.124300 -vn 0.770264 0.318863 0.552285 -v -0.062000 -0.108450 0.124421 -vn 0.770259 0.552292 0.318865 -v -0.062000 -0.108779 0.124750 -vn 0.770259 0.000000 -0.637731 -v -0.062000 -0.137000 0.112100 -vn 0.770264 -0.318863 -0.552286 -v -0.062000 -0.136550 0.111979 -vn 0.770260 -0.552292 -0.318864 -v -0.062000 -0.136221 0.111650 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.133425 0.110200 -vn 0.770263 -0.637726 0.000000 -v -0.062000 -0.136100 0.111200 -vn 0.770261 -0.552288 0.318866 -v -0.062000 -0.136221 0.110750 -vn 0.770263 0.000000 0.637726 -v -0.062000 -0.137000 0.110300 -vn 0.770258 0.318862 0.552295 -v -0.062000 -0.137450 0.110421 -vn 0.707107 -0.707106 0.000000 -v -0.062000 -0.141000 0.110200 -vn 0.770268 0.552282 0.318860 -v -0.062000 -0.137779 0.110750 -vn 0.770256 0.637735 -0.000000 -v -0.062000 -0.137900 0.111200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.141000 0.114025 -vn 0.770266 0.552286 -0.318857 -v -0.062000 -0.137779 0.111650 -vn 0.770263 -0.552289 0.318861 -v -0.062000 -0.107221 0.108750 -vn 0.770263 -0.318861 0.552289 -v -0.062000 -0.107550 0.108421 -vn 0.770259 -0.000000 0.637731 -v -0.062000 -0.108000 0.108300 -vn 0.770264 0.318863 0.552285 -v -0.062000 -0.108450 0.108421 -vn 0.770260 0.552292 0.318864 -v -0.062000 -0.108779 0.108750 -vn 0.770259 -0.637731 -0.000000 -v -0.062000 -0.107100 0.109200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.109475 -vn 0.770264 -0.552285 -0.318863 -v -0.062000 -0.107221 0.109650 -vn 0.770263 0.637726 -0.000000 -v -0.062000 -0.108900 0.109200 -vn 0.770261 0.552288 -0.318866 -v -0.062000 -0.108779 0.109650 -vn 0.770261 0.318866 -0.552288 -v -0.062000 -0.108450 0.109979 -vn 0.770259 -0.318864 -0.552292 -v -0.062000 -0.107550 0.109979 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.110200 -vn 0.770263 -0.000000 -0.637726 -v -0.062000 -0.108000 0.110100 -vn 0.770263 -0.637726 0.000000 -v -0.062000 -0.122600 0.109200 -vn 0.770260 -0.552292 0.318864 -v -0.062000 -0.122721 0.108750 -vn 0.770264 -0.318863 0.552285 -v -0.062000 -0.123050 0.108421 -vn 0.770261 -0.552288 -0.318866 -v -0.062000 -0.122721 0.109650 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.116500 0.107700 -vn 0.770259 -0.000000 0.637731 -v -0.062000 -0.123500 0.108300 -vn 0.770263 0.318861 0.552289 -v -0.062000 -0.123950 0.108421 -vn 0.770263 0.552289 0.318861 -v -0.062000 -0.124279 0.108750 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.126325 0.109475 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 -0.127500 0.102700 -vn 0.770261 -0.318866 -0.552288 -v -0.062000 -0.123050 0.109979 -vn 0.770263 -0.000000 -0.637726 -v -0.062000 -0.123500 0.110100 -vn 0.770259 0.637731 0.000000 -v -0.062000 -0.124400 0.109200 -vn 0.770264 0.552285 -0.318863 -v -0.062000 -0.124279 0.109650 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.126325 0.110200 -vn 0.770260 0.318864 -0.552292 -v -0.062000 -0.123950 0.109979 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.110200 -vn 0.770261 -0.318866 0.552288 -v -0.062000 -0.136550 0.110421 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.133425 0.108000 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.133425 0.109475 -vn 0.770262 0.318858 -0.552292 -v -0.062000 -0.137450 0.111979 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.114025 -vn 0.707107 -0.707107 0.000000 -v -0.062000 -0.141000 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.120375 -vn 0.770261 -0.318866 0.552288 -v -0.062000 -0.136550 0.122421 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.114025 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.102250 0.120375 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.094000 0.109475 -vn 0.741788 0.427643 -0.516596 -v -0.062000 -0.092000 0.127200 -vn 0.846479 0.452905 -0.279912 -v -0.062000 -0.094000 0.126200 -vn 0.707107 0.707107 0.000000 -v -0.062000 -0.094000 0.124925 -vn 0.770258 0.318862 -0.552295 -v -0.062000 -0.137450 0.123979 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.136850 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.062000 -0.133425 0.124925 -vn 1.000000 0.000000 0.000001 -v -0.062000 -0.133425 0.126400 -vn 0.741788 -0.516597 0.427643 -v -0.062000 -0.104750 0.132200 -vn 0.717284 0.630263 0.297108 -v -0.062000 -0.103500 0.132200 -vn -0.075084 -0.990667 0.113762 -v -0.063500 -0.120750 0.132200 -vn -0.609995 -0.686244 0.396202 -v -0.063500 -0.120750 0.129545 -vn -0.846479 -0.279912 0.452905 -v -0.063500 -0.121750 0.130200 -vn -0.609994 -0.000001 0.792406 -v -0.063500 -0.122750 0.128391 -vn -0.846478 0.279911 0.452906 -v -0.063500 -0.123750 0.130200 -vn -0.609994 0.686244 0.396202 -v -0.063500 -0.124750 0.129545 -vn -0.075085 0.990667 0.113762 -v -0.063500 -0.124750 0.132200 -vn -0.075085 -0.990667 0.113762 -v -0.063500 -0.112750 0.132200 -vn -0.609995 -0.686244 0.396202 -v -0.063500 -0.112750 0.129545 -vn -0.846478 -0.279911 0.452906 -v -0.063500 -0.113750 0.130200 -vn -0.609994 -0.000001 0.792406 -v -0.063500 -0.114750 0.128391 -vn -0.846478 0.279911 0.452906 -v -0.063500 -0.115750 0.130200 -vn -0.609994 0.686244 0.396202 -v -0.063500 -0.116750 0.129545 -vn -0.075085 0.990667 0.113762 -v -0.063500 -0.116750 0.132200 -vn -0.075085 -0.990667 0.113762 -v -0.063500 -0.104750 0.132200 -vn -0.609994 -0.686244 0.396203 -v -0.063500 -0.104750 0.129545 -vn -0.846478 -0.279911 0.452906 -v -0.063500 -0.105750 0.130200 -vn -0.609994 0.000001 0.792406 -v -0.063500 -0.106750 0.128391 -vn -0.846478 0.279911 0.452906 -v -0.063500 -0.107750 0.130200 -vn -0.609995 0.686244 0.396202 -v -0.063500 -0.108750 0.129545 -vn -0.075085 0.990667 0.113762 -v -0.063500 -0.108750 0.132200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.120750 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.119500 0.133200 -vn -0.297109 0.630263 0.717283 -v -0.066000 -0.119500 0.133200 -vn -0.297109 -0.630262 0.717284 -v -0.066000 -0.126000 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.124750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.126000 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.112750 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.111500 0.133200 -vn -0.297109 0.630263 0.717283 -v -0.066000 -0.111500 0.133200 -vn -0.297109 -0.630262 0.717284 -v -0.066000 -0.118000 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.116750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.118000 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.104750 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.103500 0.133200 -vn -0.297109 0.630263 0.717283 -v -0.066000 -0.103500 0.133200 -vn -0.297109 -0.630262 0.717284 -v -0.066000 -0.110000 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.108750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.110000 0.133200 -vn 0.609995 0.686244 0.396202 -v -0.065000 -0.100750 0.129545 -vn 0.770261 0.637729 -0.000002 -v -0.065000 -0.100000 0.130700 -vn 0.301511 0.301511 0.904534 -v -0.065000 -0.100750 0.133200 -vn 0.770263 0.552286 -0.318865 -v -0.065000 -0.099833 0.131325 -vn 0.609994 -0.686244 0.396203 -v -0.065000 -0.096750 0.129545 -vn 0.301511 -0.301511 0.904534 -v -0.065000 -0.096750 0.133200 -vn 0.770262 -0.552286 -0.318869 -v -0.065000 -0.097667 0.131325 -vn 0.770260 -0.318865 0.552291 -v -0.065000 -0.098125 0.129617 -vn 0.609994 0.000001 0.792406 -v -0.065000 -0.098750 0.128391 -vn 0.770262 -0.552286 0.318867 -v -0.065000 -0.097667 0.130075 -vn 0.770263 -0.637726 -0.000002 -v -0.065000 -0.097500 0.130700 -vn 0.770264 -0.000000 0.637725 -v -0.065000 -0.098750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.065000 -0.099375 0.129617 -vn 0.770264 0.552286 0.318863 -v -0.065000 -0.099833 0.130075 -vn 0.770260 0.318865 -0.552291 -v -0.065000 -0.099375 0.131783 -vn 0.770264 0.000000 -0.637725 -v -0.065000 -0.098750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.065000 -0.098125 0.131783 -vn 0.301511 0.904534 0.301511 -v -0.065000 -0.091000 0.123200 -vn 0.301511 0.904534 -0.301511 -v -0.065000 -0.091000 0.127200 -vn 0.770264 -0.637725 -0.000000 -v -0.065000 -0.092250 0.125200 -vn 0.770261 -0.552288 -0.318867 -v -0.065000 -0.092417 0.125825 -vn 0.770261 0.552288 -0.318867 -v -0.065000 -0.094583 0.125825 -vn 0.609995 0.396202 -0.686244 -v -0.065000 -0.094655 0.127200 -vn 0.770264 0.637725 0.000000 -v -0.065000 -0.094750 0.125200 -vn 0.609994 0.792406 -0.000001 -v -0.065000 -0.095809 0.125200 -vn 0.770261 0.552288 0.318867 -v -0.065000 -0.094583 0.124575 -vn 0.609994 0.396203 0.686244 -v -0.065000 -0.094655 0.123200 -vn 0.770261 0.318867 0.552288 -v -0.065000 -0.094125 0.124117 -vn 0.770261 -0.552288 0.318867 -v -0.065000 -0.092417 0.124575 -vn 0.770261 -0.318866 0.552288 -v -0.065000 -0.092875 0.124117 -vn 0.770264 0.000001 0.637726 -v -0.065000 -0.093500 0.123950 -vn 0.770261 0.318867 -0.552288 -v -0.065000 -0.094125 0.126283 -vn 0.770264 0.000001 -0.637726 -v -0.065000 -0.093500 0.126450 -vn 0.770261 -0.318866 -0.552288 -v -0.065000 -0.092875 0.126283 -vn -0.075085 -0.990667 0.113762 -v -0.063500 -0.096750 0.132200 -vn -0.609994 -0.686244 0.396203 -v -0.063500 -0.096750 0.129545 -vn -0.846478 -0.279911 0.452906 -v -0.063500 -0.097750 0.130200 -vn -0.609994 0.000001 0.792406 -v -0.063500 -0.098750 0.128391 -vn -0.846478 0.279911 0.452906 -v -0.063500 -0.099750 0.130200 -vn -0.609995 0.686244 0.396202 -v -0.063500 -0.100750 0.129545 -vn -0.075085 0.990667 0.113762 -v -0.063500 -0.100750 0.132200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.096750 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.095500 0.133200 -vn -0.297109 0.630262 0.717284 -v -0.066000 -0.095500 0.133200 -vn -0.297109 -0.630262 0.717284 -v -0.066000 -0.102000 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.063000 -0.100750 0.133200 -vn 0.297109 -0.630262 0.717283 -v -0.063000 -0.102000 0.133200 -vn -0.846478 0.452907 0.279911 -v -0.063500 -0.094000 0.124200 -vn -0.075085 0.113763 0.990667 -v -0.063500 -0.092000 0.123200 -vn -0.609994 0.396203 0.686244 -v -0.063500 -0.094655 0.123200 -vn -0.609994 0.396202 -0.686244 -v -0.063500 -0.094655 0.127200 -vn -0.075084 0.113761 -0.990667 -v -0.063500 -0.092000 0.127200 -vn -0.846479 0.452905 -0.279912 -v -0.063500 -0.094000 0.126200 -vn -0.609994 0.792406 -0.000001 -v -0.063500 -0.095809 0.125200 -vn 0.297109 0.717284 0.630262 -v -0.063000 -0.091000 0.123200 -vn 0.297109 0.717284 -0.630262 -v -0.063000 -0.091000 0.121950 -vn -0.297109 0.717284 -0.630262 -v -0.066000 -0.091000 0.121950 -vn -0.297109 0.717284 0.630262 -v -0.066000 -0.091000 0.128450 -vn 0.297109 0.717283 -0.630262 -v -0.063000 -0.091000 0.127200 -vn 0.297109 0.717283 0.630262 -v -0.063000 -0.091000 0.128450 -vn -0.088123 -0.737701 -0.669352 -v -0.066000 -0.127500 0.104200 -vn -0.130014 -0.038804 -0.990753 -v -0.066000 -0.136000 0.104200 -vn -0.130013 -0.990753 -0.038802 -v -0.066000 -0.141000 0.109200 -vn -0.130014 -0.990753 0.038804 -v -0.066000 -0.141000 0.125200 -vn -0.088123 -0.737701 0.669352 -v -0.066000 -0.127500 0.130200 -vn -0.130013 -0.038803 0.990753 -v -0.066000 -0.136000 0.130200 -vn -0.297108 -0.630263 0.717284 -v -0.065500 -0.127500 0.131700 -vn -0.318863 -0.770260 0.552291 -v -0.066500 -0.127500 0.130066 -vn -0.552285 -0.770263 0.318866 -v -0.066866 -0.127500 0.129700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 -0.126000 0.131700 -vn -0.227458 0.804186 0.549134 -v -0.065500 -0.119500 0.131700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 -0.118000 0.131700 -vn -0.227458 0.804186 0.549134 -v -0.065500 -0.111500 0.131700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 -0.110000 0.131700 -vn -0.227458 0.804186 0.549134 -v -0.065500 -0.103500 0.131700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 -0.102000 0.131700 -vn -0.227458 0.804186 0.549134 -v -0.065500 -0.095500 0.131700 -vn -0.297108 0.630263 0.717284 -v -0.065500 -0.094000 0.131700 -vn -0.297108 0.717284 0.630263 -v -0.065500 -0.092500 0.130200 -vn -0.227458 0.549134 0.804186 -v -0.065500 -0.092500 0.128450 -vn -0.227458 0.549134 -0.804186 -v -0.065500 -0.092500 0.121950 -vn -0.227458 0.549133 0.804186 -v -0.065500 -0.092500 0.112450 -vn -0.297109 0.717284 0.630262 -v -0.066000 -0.091000 0.112450 -vn 0.297109 0.717284 0.630262 -v -0.063000 -0.091000 0.112450 -vn 0.297109 0.717284 0.630262 -v -0.063000 -0.091000 0.107200 -vn 0.297109 0.717284 -0.630262 -v -0.063000 -0.091000 0.105950 -vn 0.301511 0.904534 0.301511 -v -0.065000 -0.091000 0.107200 -vn -0.297109 0.717284 -0.630262 -v -0.066000 -0.091000 0.105950 -vn 0.301511 0.904534 -0.301511 -v -0.065000 -0.091000 0.111200 -vn 0.297109 0.717284 -0.630262 -v -0.063000 -0.091000 0.111200 -vn -0.227458 0.549134 -0.804186 -v -0.065500 -0.092500 0.105950 -vn -0.297108 0.717284 -0.630263 -v -0.065500 -0.092500 0.104200 -vn -0.297108 0.630263 -0.717284 -v -0.065500 -0.094000 0.102700 -vn -0.227458 0.804186 -0.549133 -v -0.065500 -0.095500 0.102700 -vn -0.297109 0.630262 -0.717284 -v -0.066000 -0.095500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.095500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.100750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.102000 0.101200 -vn 0.301512 0.301511 -0.904534 -v -0.065000 -0.100750 0.101200 -vn -0.297109 -0.630262 -0.717284 -v -0.066000 -0.102000 0.101200 -vn 0.301511 -0.301511 -0.904534 -v -0.065000 -0.096750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.096750 0.101200 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 -0.102000 0.102700 -vn -0.227458 0.804186 -0.549134 -v -0.065500 -0.103500 0.102700 -vn -0.297109 0.630262 -0.717284 -v -0.066000 -0.103500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.103500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.108750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.110000 0.101200 -vn 0.301512 0.301511 -0.904534 -v -0.065000 -0.108750 0.101200 -vn -0.297109 -0.630262 -0.717284 -v -0.066000 -0.110000 0.101200 -vn 0.301511 -0.301511 -0.904534 -v -0.065000 -0.104750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.104750 0.101200 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 -0.110000 0.102700 -vn -0.227458 0.804186 -0.549133 -v -0.065500 -0.111500 0.102700 -vn -0.297109 0.630262 -0.717284 -v -0.066000 -0.111500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.111500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.116750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.118000 0.101200 -vn 0.301511 0.301511 -0.904534 -v -0.065000 -0.116750 0.101200 -vn -0.297109 -0.630262 -0.717284 -v -0.066000 -0.118000 0.101200 -vn 0.301512 -0.301511 -0.904534 -v -0.065000 -0.112750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.112750 0.101200 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 -0.118000 0.102700 -vn -0.227458 0.804186 -0.549133 -v -0.065500 -0.119500 0.102700 -vn -0.297109 0.630262 -0.717284 -v -0.066000 -0.119500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.119500 0.101200 -vn 0.297109 0.630262 -0.717284 -v -0.063000 -0.124750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.126000 0.101200 -vn 0.301511 0.301511 -0.904534 -v -0.065000 -0.124750 0.101200 -vn -0.297109 -0.630262 -0.717284 -v -0.066000 -0.126000 0.101200 -vn 0.301512 -0.301511 -0.904534 -v -0.065000 -0.120750 0.101200 -vn 0.297109 -0.630262 -0.717284 -v -0.063000 -0.120750 0.101200 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 -0.126000 0.102700 -vn -0.297108 -0.630263 -0.717284 -v -0.065500 -0.127500 0.102700 -vn -0.552288 -0.770262 -0.318865 -v -0.066866 -0.127500 0.104700 -vn -0.318865 -0.770262 -0.552288 -v -0.066500 -0.127500 0.104334 -vn -0.128141 0.983444 -0.128135 -v -0.069700 -0.097000 0.107500 -vn -0.128144 0.983443 0.128138 -v -0.069700 -0.097000 0.112900 -vn -0.128162 0.128156 -0.983438 -v -0.069700 -0.097300 0.107200 -vn -0.128163 -0.128156 -0.983438 -v -0.069700 -0.103700 0.107200 -vn -0.128163 -0.983438 0.128156 -v -0.069700 -0.104000 0.112900 -vn -0.128161 -0.983438 -0.128155 -v -0.069700 -0.104000 0.107500 -vn -0.128163 0.128156 0.983438 -v -0.069700 -0.097300 0.113200 -vn -0.128161 -0.128155 0.983438 -v -0.069700 -0.103700 0.113200 -vn -0.988105 0.108737 0.108737 -v -0.070000 -0.097300 0.112900 -vn -0.988106 0.108737 -0.108737 -v -0.070000 -0.097300 0.107500 -vn -0.988106 -0.108735 0.108735 -v -0.070000 -0.103700 0.112900 -vn -0.988106 -0.108735 -0.108735 -v -0.070000 -0.103700 0.107500 -vn -0.128141 0.128135 0.983444 -v -0.069700 -0.097300 0.127200 -vn -0.128144 -0.128138 0.983443 -v -0.069700 -0.103700 0.127200 -vn -0.128143 0.983442 0.128142 -v -0.069700 -0.097000 0.126900 -vn -0.128141 0.983444 -0.128135 -v -0.069700 -0.097000 0.121500 -vn -0.128145 0.128139 -0.983442 -v -0.069700 -0.097300 0.121200 -vn -0.128141 -0.128135 -0.983444 -v -0.069700 -0.103700 0.121200 -vn -0.128162 -0.983438 -0.128156 -v -0.069700 -0.104000 0.121500 -vn -0.128162 -0.983437 0.128162 -v -0.069700 -0.104000 0.126900 -vn -0.988106 -0.108734 0.108740 -v -0.070000 -0.103700 0.126900 -vn -0.988105 0.108736 0.108742 -v -0.070000 -0.097300 0.126900 -vn -0.988106 -0.108737 -0.108737 -v -0.070000 -0.103700 0.121500 -vn -0.988105 0.108739 -0.108739 -v -0.070000 -0.097300 0.121500 -vn -0.609994 0.396203 -0.686244 -v -0.063500 -0.094655 0.111200 -vn 0.609994 0.396203 -0.686244 -v -0.065000 -0.094655 0.111200 -vn -0.075085 0.113762 -0.990667 -v -0.063500 -0.092000 0.111200 -vn 0.770264 -0.637725 -0.000000 -v -0.065000 -0.092250 0.109200 -vn 0.770260 -0.552291 -0.318865 -v -0.065000 -0.092417 0.109825 -vn 0.770261 0.000001 0.637729 -v -0.065000 -0.093500 0.107950 -vn 0.609994 0.396204 0.686243 -v -0.065000 -0.094655 0.107200 -vn 0.770263 -0.318864 0.552286 -v -0.065000 -0.092875 0.108117 -vn 0.770260 -0.552291 0.318865 -v -0.065000 -0.092417 0.108575 -vn 0.770263 0.318865 0.552286 -v -0.065000 -0.094125 0.108117 -vn 0.770260 0.552291 0.318865 -v -0.065000 -0.094583 0.108575 -vn 0.609994 0.792406 -0.000001 -v -0.065000 -0.095809 0.109200 -vn 0.770264 0.637725 0.000000 -v -0.065000 -0.094750 0.109200 -vn 0.770260 0.552291 -0.318865 -v -0.065000 -0.094583 0.109825 -vn 0.770263 0.318865 -0.552286 -v -0.065000 -0.094125 0.110283 -vn 0.770261 0.000001 -0.637729 -v -0.065000 -0.093500 0.110450 -vn 0.770263 -0.318864 -0.552286 -v -0.065000 -0.092875 0.110283 -vn -0.075085 0.113763 0.990667 -v -0.063500 -0.092000 0.107200 -vn -0.609994 0.396204 0.686243 -v -0.063500 -0.094655 0.107200 -vn -0.609994 0.792406 -0.000001 -v -0.063500 -0.095809 0.109200 -vn -0.846478 0.452906 0.279911 -v -0.063500 -0.094000 0.108200 -vn -0.846479 0.452906 -0.279912 -v -0.063500 -0.094000 0.110200 -vn -0.609994 -0.686243 -0.396204 -v -0.063500 -0.096750 0.104855 -vn 0.609994 -0.686243 -0.396203 -v -0.065000 -0.096750 0.104855 -vn -0.075085 -0.990667 -0.113763 -v -0.063500 -0.096750 0.102200 -vn 0.609995 0.686243 -0.396203 -v -0.065000 -0.100750 0.104855 -vn 0.770262 0.552289 0.318863 -v -0.065000 -0.099833 0.103075 -vn 0.770261 0.637729 -0.000000 -v -0.065000 -0.100000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.065000 -0.099833 0.104325 -vn 0.609994 0.000001 -0.792406 -v -0.065000 -0.098750 0.106009 -vn 0.770261 0.318867 -0.552288 -v -0.065000 -0.099375 0.104783 -vn 0.770264 -0.637725 -0.000000 -v -0.065000 -0.097500 0.103700 -vn 0.770261 -0.552288 0.318867 -v -0.065000 -0.097667 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.065000 -0.098125 0.102617 -vn 0.770261 0.000000 0.637728 -v -0.065000 -0.098750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.065000 -0.099375 0.102617 -vn 0.770264 0.000000 -0.637725 -v -0.065000 -0.098750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 -0.098125 0.104783 -vn 0.770261 -0.552288 -0.318867 -v -0.065000 -0.097667 0.104325 -vn -0.075085 0.990667 -0.113763 -v -0.063500 -0.100750 0.102200 -vn -0.609994 0.686244 -0.396203 -v -0.063500 -0.100750 0.104855 -vn -0.609994 0.000001 -0.792406 -v -0.063500 -0.098750 0.106009 -vn -0.846478 0.279911 -0.452907 -v -0.063500 -0.099750 0.104200 -vn -0.846478 -0.279911 -0.452907 -v -0.063500 -0.097750 0.104200 -vn -0.609994 -0.686243 -0.396204 -v -0.063500 -0.104750 0.104855 -vn 0.609994 -0.686243 -0.396204 -v -0.065000 -0.104750 0.104855 -vn -0.075085 -0.990667 -0.113763 -v -0.063500 -0.104750 0.102200 -vn 0.609995 0.686243 -0.396203 -v -0.065000 -0.108750 0.104855 -vn 0.770262 0.552289 0.318863 -v -0.065000 -0.107833 0.103075 -vn 0.770261 0.637729 -0.000000 -v -0.065000 -0.108000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.065000 -0.107833 0.104325 -vn 0.609994 0.000001 -0.792406 -v -0.065000 -0.106750 0.106009 -vn 0.770261 0.318867 -0.552288 -v -0.065000 -0.107375 0.104783 -vn 0.770260 -0.552291 0.318865 -v -0.065000 -0.105667 0.103075 -vn 0.770264 -0.637725 -0.000000 -v -0.065000 -0.105500 0.103700 -vn 0.770264 0.000001 -0.637726 -v -0.065000 -0.106750 0.104950 -vn 0.770262 -0.318868 -0.552286 -v -0.065000 -0.106125 0.104783 -vn 0.770260 -0.552291 -0.318865 -v -0.065000 -0.105667 0.104325 -vn 0.770263 -0.318864 0.552286 -v -0.065000 -0.106125 0.102617 -vn 0.770261 0.000001 0.637729 -v -0.065000 -0.106750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.065000 -0.107375 0.102617 -vn -0.075085 0.990667 -0.113763 -v -0.063500 -0.108750 0.102200 -vn -0.609994 0.686244 -0.396203 -v -0.063500 -0.108750 0.104855 -vn -0.609994 -0.686244 -0.396203 -v -0.063500 -0.112750 0.104855 -vn 0.609994 -0.686244 -0.396203 -v -0.065000 -0.112750 0.104855 -vn -0.075085 -0.990667 -0.113763 -v -0.063500 -0.112750 0.102200 -vn 0.770262 -0.552289 0.318863 -v -0.065000 -0.113667 0.103075 -vn 0.770261 -0.637728 0.000000 -v -0.065000 -0.113500 0.103700 -vn 0.770262 -0.318863 0.552289 -v -0.065000 -0.114125 0.102617 -vn 0.770261 0.000000 0.637728 -v -0.065000 -0.114750 0.102450 -vn 0.770261 0.318867 -0.552288 -v -0.065000 -0.115375 0.104783 -vn 0.609994 -0.000001 -0.792406 -v -0.065000 -0.114750 0.106009 -vn 0.770262 0.552289 -0.318863 -v -0.065000 -0.115833 0.104325 -vn 0.609994 0.686243 -0.396204 -v -0.065000 -0.116750 0.104855 -vn 0.770264 0.000000 -0.637725 -v -0.065000 -0.114750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 -0.114125 0.104783 -vn 0.770262 -0.552289 -0.318863 -v -0.065000 -0.113667 0.104325 -vn 0.770262 0.318863 0.552289 -v -0.065000 -0.115375 0.102617 -vn 0.770262 0.552289 0.318863 -v -0.065000 -0.115833 0.103075 -vn 0.770261 0.637728 -0.000000 -v -0.065000 -0.116000 0.103700 -vn -0.075085 0.990667 -0.113763 -v -0.063500 -0.116750 0.102200 -vn -0.609994 0.686243 -0.396204 -v -0.063500 -0.116750 0.104855 -vn -0.609994 -0.686244 -0.396203 -v -0.063500 -0.120750 0.104855 -vn 0.609994 -0.686244 -0.396203 -v -0.065000 -0.120750 0.104855 -vn -0.075085 -0.990667 -0.113762 -v -0.063500 -0.120750 0.102200 -vn 0.770264 0.000000 -0.637725 -v -0.065000 -0.122750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 -0.122125 0.104783 -vn 0.609994 -0.000001 -0.792406 -v -0.065000 -0.122750 0.106009 -vn 0.609994 0.686243 -0.396204 -v -0.065000 -0.124750 0.104855 -vn 0.770262 0.552289 0.318863 -v -0.065000 -0.123833 0.103075 -vn 0.770261 0.637728 -0.000000 -v -0.065000 -0.124000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.065000 -0.123833 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.065000 -0.123375 0.104783 -vn 0.770262 -0.552289 -0.318863 -v -0.065000 -0.121667 0.104325 -vn 0.770261 -0.637728 0.000000 -v -0.065000 -0.121500 0.103700 -vn 0.770262 -0.552289 0.318863 -v -0.065000 -0.121667 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.065000 -0.122125 0.102617 -vn 0.770261 0.000000 0.637728 -v -0.065000 -0.122750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.065000 -0.123375 0.102617 -vn -0.075085 0.990667 -0.113763 -v -0.063500 -0.124750 0.102200 -vn -0.609994 0.686243 -0.396204 -v -0.063500 -0.124750 0.104855 -vn -0.609994 0.000001 -0.792406 -v -0.063500 -0.106750 0.106009 -vn -0.846478 0.279911 -0.452907 -v -0.063500 -0.107750 0.104200 -vn -0.846478 -0.279911 -0.452907 -v -0.063500 -0.105750 0.104200 -vn -0.609994 -0.000001 -0.792406 -v -0.063500 -0.114750 0.106009 -vn -0.846478 0.279911 -0.452907 -v -0.063500 -0.115750 0.104200 -vn -0.846478 -0.279911 -0.452907 -v -0.063500 -0.113750 0.104200 -vn -0.609994 -0.000001 -0.792406 -v -0.063500 -0.122750 0.106009 -vn -0.846478 0.279911 -0.452906 -v -0.063500 -0.123750 0.104200 -vn -0.846479 -0.279911 -0.452906 -v -0.063500 -0.121750 0.104200 -vn -0.128742 -0.979469 0.155133 -v -0.066000 -0.140938 0.125982 -vn -0.129693 -0.943024 0.306408 -v -0.066000 -0.140755 0.126745 -vn -0.128747 -0.883593 0.450208 -v -0.066000 -0.140455 0.127470 -vn -0.129694 -0.802179 0.582828 -v -0.066000 -0.140045 0.128139 -vn -0.128738 -0.701225 0.701221 -v -0.066000 -0.139536 0.128736 -vn -0.129692 -0.582821 0.802184 -v -0.066000 -0.138939 0.129245 -vn -0.128742 -0.450206 0.883595 -v -0.066000 -0.138270 0.129655 -vn -0.129680 -0.306410 0.943025 -v -0.066000 -0.137545 0.129955 -vn -0.128739 -0.155134 0.979469 -v -0.066000 -0.136782 0.130138 -vn -0.128747 -0.155136 -0.979468 -v -0.066000 -0.136782 0.104262 -vn -0.129686 -0.306410 -0.943024 -v -0.066000 -0.137545 0.104445 -vn -0.128735 -0.450208 -0.883595 -v -0.066000 -0.138270 0.104745 -vn -0.129688 -0.582823 -0.802184 -v -0.066000 -0.138939 0.105155 -vn -0.128740 -0.701221 -0.701224 -v -0.066000 -0.139536 0.105664 -vn -0.129690 -0.802183 -0.582824 -v -0.066000 -0.140045 0.106261 -vn -0.128746 -0.883593 -0.450208 -v -0.066000 -0.140455 0.106930 -vn -0.129693 -0.943024 -0.306407 -v -0.066000 -0.140755 0.107655 -vn -0.128743 -0.979468 -0.155137 -v -0.066000 -0.140938 0.108418 -vn -0.227459 -0.549132 0.804187 -v -0.066000 -0.112000 0.107700 -vn -0.227458 -0.549133 -0.804186 -v -0.066000 -0.112000 0.116700 -vn -0.227458 0.549133 -0.804186 -v -0.066000 -0.116500 0.116700 -vn -0.227459 0.549132 0.804187 -v -0.066000 -0.116500 0.107700 -vn -0.765310 -0.483795 0.424551 -v -0.066700 -0.111300 0.107700 -vn -0.765310 0.483795 0.424551 -v -0.066700 -0.117200 0.107700 -vn -0.765313 0.483795 -0.424546 -v -0.066700 -0.117200 0.126700 -vn -0.765312 -0.483795 -0.424546 -v -0.066700 -0.111300 0.126700 -vn -0.227459 -0.549132 -0.804187 -v -0.066000 -0.112000 0.126700 -vn -0.227459 0.549132 -0.804187 -v -0.066000 -0.116500 0.126700 -vn -0.227458 0.549133 0.804187 -v -0.066000 -0.116500 0.117700 -vn -0.227458 -0.549133 0.804186 -v -0.066000 -0.112000 0.117700 -vn -0.126934 -0.979699 0.155171 -v -0.069500 -0.134833 0.118045 -vn -0.126922 -0.883802 0.450317 -v -0.069500 -0.134311 0.119652 -vn -0.129678 -0.943027 0.306405 -v -0.069500 -0.134636 0.118869 -vn -0.126933 -0.701387 0.701388 -v -0.069500 -0.133318 0.121018 -vn -0.129685 -0.802185 0.582821 -v -0.069500 -0.133869 0.120374 -vn -0.126951 -0.450315 0.883798 -v -0.069500 -0.131952 0.122011 -vn -0.129691 -0.582821 0.802185 -v -0.069500 -0.132674 0.121569 -vn -0.126931 -0.155169 0.979700 -v -0.069500 -0.130345 0.122534 -vn -0.129686 -0.306407 0.943025 -v -0.069500 -0.131169 0.122336 -vn -0.126931 0.155170 0.979699 -v -0.069500 -0.128655 0.122534 -vn -0.129677 -0.000001 0.991556 -v -0.069500 -0.129500 0.122600 -vn -0.126950 0.450319 0.883797 -v -0.069500 -0.127048 0.122011 -vn -0.129671 0.306403 0.943029 -v -0.069500 -0.127831 0.122336 -vn -0.126933 0.701387 0.701388 -v -0.069500 -0.125682 0.121018 -vn -0.129692 0.582820 0.802185 -v -0.069500 -0.126326 0.121569 -vn -0.126922 0.883801 0.450318 -v -0.069500 -0.124689 0.119652 -vn -0.129686 0.802188 0.582817 -v -0.069500 -0.125131 0.120374 -vn -0.126932 0.979699 0.155170 -v -0.069500 -0.124166 0.118045 -vn -0.129698 0.943024 0.306407 -v -0.069500 -0.124364 0.118869 -vn -0.126932 0.979700 -0.155168 -v -0.069500 -0.124166 0.116355 -vn -0.129698 0.991554 -0.000001 -v -0.069500 -0.124100 0.117200 -vn -0.126933 0.883801 -0.450315 -v -0.069500 -0.124689 0.114748 -vn -0.129698 0.943023 -0.306408 -v -0.069500 -0.124364 0.115531 -vn -0.126918 0.701387 -0.701390 -v -0.069500 -0.125682 0.113382 -vn -0.129686 0.802186 -0.582820 -v -0.069500 -0.125131 0.114026 -vn -0.126931 0.450320 -0.883799 -v -0.069500 -0.127048 0.112389 -vn -0.129672 0.582823 -0.802186 -v -0.069500 -0.126326 0.112831 -vn -0.126932 0.155170 -0.979699 -v -0.069500 -0.128655 0.111866 -vn -0.129692 0.306406 -0.943025 -v -0.069500 -0.127831 0.112064 -vn -0.126932 -0.155168 -0.979699 -v -0.069500 -0.130345 0.111866 -vn -0.129698 -0.000001 -0.991554 -v -0.069500 -0.129500 0.111800 -vn -0.126933 -0.450320 -0.883799 -v -0.069500 -0.131952 0.112389 -vn -0.129705 -0.306409 -0.943022 -v -0.069500 -0.131169 0.112064 -vn -0.126917 -0.701387 -0.701391 -v -0.069500 -0.133318 0.113382 -vn -0.129673 -0.582821 -0.802187 -v -0.069500 -0.132674 0.112831 -vn -0.126931 -0.883801 -0.450316 -v -0.069500 -0.134311 0.114748 -vn -0.129685 -0.802185 -0.582822 -v -0.069500 -0.133869 0.114026 -vn -0.129719 -0.991551 0.000003 -v -0.069500 -0.134900 0.117200 -vn -0.126931 -0.979699 -0.155173 -v -0.069500 -0.134833 0.116355 -vn -0.129678 -0.943027 -0.306405 -v -0.069500 -0.134636 0.115531 -vn -0.990583 0.130213 0.042309 -v -0.069800 -0.124650 0.118776 -vn -0.990583 0.135231 0.021419 -v -0.069800 -0.124463 0.117998 -vn -0.750899 -0.615819 -0.238572 -v -0.069800 -0.125770 0.118645 -vn -0.750899 -0.660417 0.000000 -v -0.069800 -0.125500 0.117200 -vn -0.990583 0.096816 -0.096814 -v -0.069800 -0.125894 0.113594 -vn -0.990583 0.080477 -0.110766 -v -0.069800 -0.126502 0.113074 -vn -0.750899 -0.488053 0.444922 -v -0.069800 -0.126544 0.114505 -vn -0.750898 -0.294374 0.591182 -v -0.069800 -0.127717 0.113619 -vn -0.750900 0.180732 -0.635206 -v -0.069800 -0.130595 0.121047 -vn -0.750898 0.397991 -0.527024 -v -0.069800 -0.131911 0.120392 -vn -0.990583 -0.062157 0.121991 -v -0.069800 -0.131815 0.121744 -vn -0.750898 0.561498 -0.347667 -v -0.069800 -0.132901 0.119306 -vn -0.990583 -0.096815 0.096815 -v -0.069800 -0.133106 0.120806 -vn -0.990583 -0.080476 0.110766 -v -0.069800 -0.132498 0.121326 -vn -0.990584 -0.135224 0.021418 -v -0.069800 -0.134537 0.117998 -vn -0.750899 0.649172 -0.121353 -v -0.069800 -0.133432 0.117935 -vn -0.990582 -0.136921 -0.000001 -v -0.069800 -0.134600 0.117200 -vn -0.750900 0.649171 0.121353 -v -0.069800 -0.133432 0.116465 -vn -0.990584 -0.135224 -0.021416 -v -0.069800 -0.134537 0.116402 -vn -0.990583 -0.042309 -0.130215 -v -0.069800 -0.131076 0.112350 -vn -0.990583 -0.062157 -0.121991 -v -0.069800 -0.131815 0.112656 -vn -0.750898 0.180732 0.635207 -v -0.069800 -0.130595 0.113353 -vn -0.750899 0.397990 0.527024 -v -0.069800 -0.131911 0.114008 -vn -0.990582 0.062160 -0.121996 -v -0.069800 -0.127185 0.112656 -vn -0.990583 0.042309 -0.130215 -v -0.069800 -0.127924 0.112350 -vn -0.750899 -0.060935 0.657600 -v -0.069800 -0.129131 0.113217 -vn -0.990582 0.136922 0.000001 -v -0.069800 -0.124400 0.117200 -vn -0.990583 0.135230 -0.021418 -v -0.069800 -0.124463 0.116402 -vn -0.750899 -0.615820 0.238572 -v -0.069800 -0.125770 0.115755 -vn -0.750898 -0.488055 -0.444922 -v -0.069800 -0.126544 0.119895 -vn -0.990583 0.110767 0.080476 -v -0.069800 -0.125374 0.120198 -vn -0.990583 0.121991 0.062157 -v -0.069800 -0.124956 0.119515 -vn -0.990582 0.021420 0.135238 -v -0.069800 -0.128702 0.122237 -vn -0.990582 0.042311 0.130220 -v -0.069800 -0.127924 0.122050 -vn -0.750898 -0.060935 -0.657601 -v -0.069800 -0.129131 0.121183 -vn -0.750900 -0.294373 -0.591181 -v -0.069800 -0.127717 0.120781 -vn -0.990583 -0.130213 0.042308 -v -0.069800 -0.134350 0.118776 -vn -0.990582 -0.121997 0.062160 -v -0.069800 -0.134044 0.119515 -vn -0.990583 -0.110765 0.080476 -v -0.069800 -0.133626 0.120198 -vn -0.990583 -0.130213 -0.042308 -v -0.069800 -0.134350 0.115624 -vn -0.750898 0.561498 0.347667 -v -0.069800 -0.132901 0.115094 -vn -0.990583 -0.121994 -0.062159 -v -0.069800 -0.134044 0.114885 -vn -0.990583 -0.080476 -0.110766 -v -0.069800 -0.132498 0.113074 -vn -0.990583 -0.096815 -0.096815 -v -0.069800 -0.133106 0.113594 -vn -0.990583 -0.110766 -0.080476 -v -0.069800 -0.133626 0.114202 -vn -0.990582 0.021419 -0.135232 -v -0.069800 -0.128702 0.112163 -vn -0.990582 0.000000 -0.136922 -v -0.069800 -0.129500 0.112100 -vn -0.990583 -0.021418 -0.135230 -v -0.069800 -0.130298 0.112163 -vn -0.990583 0.130213 -0.042309 -v -0.069800 -0.124650 0.115624 -vn -0.990583 0.121988 -0.062156 -v -0.069800 -0.124956 0.114885 -vn -0.990583 0.110767 -0.080476 -v -0.069800 -0.125374 0.114202 -vn -0.990582 0.062160 0.121996 -v -0.069800 -0.127185 0.121744 -vn -0.990583 0.080477 0.110766 -v -0.069800 -0.126502 0.121326 -vn -0.990583 0.096815 0.096815 -v -0.069800 -0.125894 0.120806 -vn -0.990582 -0.042312 0.130221 -v -0.069800 -0.131076 0.122050 -vn -0.990582 -0.021419 0.135236 -v -0.069800 -0.130298 0.122237 -vn -0.990583 0.000001 0.136915 -v -0.069800 -0.129500 0.122300 -vn -0.667992 -0.744168 -0.000000 -v -0.069200 -0.125500 0.117200 -vn -0.667992 -0.693915 0.268826 -v -0.069200 -0.125770 0.115755 -vn -0.667993 -0.549945 0.501344 -v -0.069200 -0.126544 0.114505 -vn -0.667993 -0.331704 0.666151 -v -0.069200 -0.127717 0.113619 -vn -0.667992 -0.068663 0.740994 -v -0.069200 -0.129131 0.113217 -vn -0.667993 0.203651 0.715759 -v -0.069200 -0.130595 0.113353 -vn -0.667992 0.448462 0.593859 -v -0.069200 -0.131911 0.114008 -vn -0.667993 0.632703 0.391755 -v -0.069200 -0.132901 0.115094 -vn -0.667992 0.731497 0.136743 -v -0.069200 -0.133432 0.116465 -vn -0.667992 0.731497 -0.136742 -v -0.069200 -0.133432 0.117935 -vn -0.667993 0.632703 -0.391756 -v -0.069200 -0.132901 0.119306 -vn -0.667993 0.448462 -0.593858 -v -0.069200 -0.131911 0.120392 -vn -0.667992 0.203652 -0.715760 -v -0.069200 -0.130595 0.121047 -vn -0.667993 -0.068663 -0.740993 -v -0.069200 -0.129131 0.121183 -vn -0.667992 -0.331704 -0.666152 -v -0.069200 -0.127717 0.120781 -vn -0.667994 -0.549945 -0.501343 -v -0.069200 -0.126544 0.119895 -vn -0.667992 -0.693915 -0.268827 -v -0.069200 -0.125770 0.118645 -vn -0.976003 -0.108879 -0.188584 -v -0.069200 -0.128737 0.118521 -vn -0.976001 -0.188590 -0.108881 -v -0.069200 -0.128179 0.117962 -vn -0.976002 -0.217762 -0.000001 -v -0.069200 -0.127975 0.117200 -vn -0.976001 -0.188589 0.108883 -v -0.069200 -0.128179 0.116437 -vn -0.976002 0.108881 -0.188589 -v -0.069200 -0.130262 0.118521 -vn -0.976002 0.000000 -0.217761 -v -0.069200 -0.129500 0.118725 -vn -0.976003 0.188582 0.108879 -v -0.069200 -0.130821 0.116437 -vn -0.976002 0.217760 -0.000001 -v -0.069200 -0.131025 0.117200 -vn -0.976003 0.188583 -0.108878 -v -0.069200 -0.130821 0.117962 -vn -0.976002 0.000000 0.217761 -v -0.069200 -0.129500 0.115675 -vn -0.976002 0.108881 0.188588 -v -0.069200 -0.130262 0.115879 -vn -0.976003 -0.108880 0.188583 -v -0.069200 -0.128737 0.115879 -vn 1.000000 0.000003 -0.000003 -v -0.066981 -0.138500 0.126450 -vn 0.460549 0.768712 0.443820 -v -0.066500 -0.139193 0.126050 -vn 0.460549 0.443810 0.768718 -v -0.066500 -0.138900 0.125757 -vn 0.460547 0.887635 -0.000004 -v -0.066500 -0.139300 0.126450 -vn 0.460550 -0.443806 0.768720 -v -0.066500 -0.138100 0.125757 -vn 0.460550 -0.768720 0.443806 -v -0.066500 -0.137807 0.126050 -vn 0.460551 0.000004 0.887633 -v -0.066500 -0.138500 0.125650 -vn 0.460549 -0.768718 -0.443810 -v -0.066500 -0.137807 0.126850 -vn 0.460549 -0.443820 -0.768712 -v -0.066500 -0.138100 0.127143 -vn 0.460551 -0.887633 -0.000004 -v -0.066500 -0.137700 0.126450 -vn 0.460548 0.443823 -0.768711 -v -0.066500 -0.138900 0.127143 -vn 0.460548 0.768711 -0.443823 -v -0.066500 -0.139193 0.126850 -vn 0.460547 0.000004 -0.887635 -v -0.066500 -0.138500 0.127250 -vn 0.539406 0.842046 -0.000003 -v -0.062058 -0.139300 0.126450 -vn 0.539398 0.729234 0.421031 -v -0.062058 -0.139193 0.126050 -vn 0.539389 0.421015 0.729251 -v -0.062058 -0.138900 0.125757 -vn 0.539398 0.000008 0.842051 -v -0.062058 -0.138500 0.125650 -vn 0.539376 -0.421026 0.729253 -v -0.062058 -0.138100 0.125757 -vn 0.539399 -0.729240 0.421021 -v -0.062058 -0.137807 0.126050 -vn 0.539399 -0.842050 -0.000003 -v -0.062058 -0.137700 0.126450 -vn 0.539416 -0.729234 -0.421009 -v -0.062058 -0.137807 0.126850 -vn 0.539400 -0.421028 -0.729235 -v -0.062058 -0.138100 0.127143 -vn 0.539405 0.000004 -0.842046 -v -0.062058 -0.138500 0.127250 -vn 0.539412 0.421023 -0.729228 -v -0.062058 -0.138900 0.127143 -vn 0.539413 0.729227 -0.421024 -v -0.062058 -0.139193 0.126850 -vn 1.000000 0.000003 -0.000001 -v -0.066981 -0.138500 0.107950 -vn 0.460548 0.768712 0.443821 -v -0.066500 -0.139193 0.107550 -vn 0.460548 0.443816 0.768715 -v -0.066500 -0.138900 0.107257 -vn 0.460547 0.887635 0.000000 -v -0.066500 -0.139300 0.107950 -vn 0.460549 -0.443813 0.768716 -v -0.066500 -0.138100 0.107257 -vn 0.460549 -0.768719 0.443808 -v -0.066500 -0.137807 0.107550 -vn 0.460549 0.000004 0.887634 -v -0.066500 -0.138500 0.107150 -vn 0.460549 -0.768717 -0.443813 -v -0.066500 -0.137807 0.108350 -vn 0.460550 -0.443815 -0.768715 -v -0.066500 -0.138100 0.108643 -vn 0.460551 -0.887633 0.000000 -v -0.066500 -0.137700 0.107950 -vn 0.460549 0.443818 -0.768714 -v -0.066500 -0.138900 0.108643 -vn 0.460548 0.768709 -0.443826 -v -0.066500 -0.139193 0.108350 -vn 0.460547 0.000004 -0.887635 -v -0.066500 -0.138500 0.108750 -vn 0.539406 0.842046 0.000001 -v -0.062058 -0.139300 0.107950 -vn 0.539405 0.729231 0.421027 -v -0.062058 -0.139193 0.107550 -vn 0.539414 0.421018 0.729230 -v -0.062058 -0.138900 0.107257 -vn 0.539403 0.000003 0.842048 -v -0.062058 -0.138500 0.107150 -vn 0.539400 -0.421024 0.729237 -v -0.062058 -0.138100 0.107257 -vn 0.539407 -0.729237 0.421015 -v -0.062058 -0.137807 0.107550 -vn 0.539400 -0.842050 -0.000000 -v -0.062058 -0.137700 0.107950 -vn 0.539409 -0.729234 -0.421018 -v -0.062058 -0.137807 0.108350 -vn 0.539398 -0.421025 -0.729238 -v -0.062058 -0.138100 0.108643 -vn 0.539405 0.000004 -0.842046 -v -0.062058 -0.138500 0.108750 -vn 0.539411 0.421018 -0.729232 -v -0.062058 -0.138900 0.108643 -vn 0.539408 0.729228 -0.421030 -v -0.062058 -0.139193 0.108350 -vn 1.000000 0.000001 -0.000000 -v -0.066981 -0.096500 0.127600 -vn 0.460548 0.768710 0.443825 -v -0.066500 -0.097193 0.127200 -vn 0.460549 0.443816 0.768714 -v -0.066500 -0.096900 0.126907 -vn 0.460548 0.887635 -0.000000 -v -0.066500 -0.097300 0.127600 -vn 0.460550 -0.443812 0.768717 -v -0.066500 -0.096100 0.126907 -vn 0.460548 -0.768711 0.443823 -v -0.066500 -0.095807 0.127200 -vn 0.460547 0.000000 0.887635 -v -0.066500 -0.096500 0.126800 -vn 0.460548 -0.768711 -0.443823 -v -0.066500 -0.095807 0.128000 -vn 0.460550 -0.443812 -0.768717 -v -0.066500 -0.096100 0.128293 -vn 0.460550 -0.887634 0.000000 -v -0.066500 -0.095700 0.127600 -vn 0.460549 0.443816 -0.768714 -v -0.066500 -0.096900 0.128293 -vn 0.460548 0.768710 -0.443825 -v -0.066500 -0.097193 0.128000 -vn 0.460547 -0.000000 -0.887635 -v -0.066500 -0.096500 0.128400 -vn 0.539405 0.842046 0.000002 -v -0.062058 -0.097300 0.127600 -vn 0.539399 0.729231 0.421036 -v -0.062058 -0.097193 0.127200 -vn 0.539403 0.421025 0.729234 -v -0.062058 -0.096900 0.126907 -vn 0.539406 -0.000001 0.842046 -v -0.062058 -0.096500 0.126800 -vn 0.539403 -0.421018 0.729238 -v -0.062058 -0.096100 0.126907 -vn 0.539403 -0.729231 0.421031 -v -0.062058 -0.095807 0.127200 -vn 0.539403 -0.842048 0.000003 -v -0.062058 -0.095700 0.127600 -vn 0.539401 -0.729232 -0.421032 -v -0.062058 -0.095807 0.128000 -vn 0.539402 -0.421021 -0.729237 -v -0.062058 -0.096100 0.128293 -vn 0.539406 0.000001 -0.842046 -v -0.062058 -0.096500 0.128400 -vn 0.539404 0.421022 -0.729235 -v -0.062058 -0.096900 0.128293 -vn 0.539399 0.729233 -0.421032 -v -0.062058 -0.097193 0.128000 -vn 1.000000 0.000001 0.000001 -v -0.066981 -0.096500 0.106800 -vn 0.460548 0.768712 0.443821 -v -0.066500 -0.097193 0.106400 -vn 0.460548 0.443821 0.768712 -v -0.066500 -0.096900 0.106107 -vn 0.460547 0.887635 -0.000000 -v -0.066500 -0.097300 0.106800 -vn 0.460549 -0.443816 0.768714 -v -0.066500 -0.096100 0.106107 -vn 0.460548 -0.768713 0.443820 -v -0.066500 -0.095807 0.106400 -vn 0.460547 0.000000 0.887635 -v -0.066500 -0.096500 0.106000 -vn 0.460549 -0.768716 -0.443815 -v -0.066500 -0.095807 0.107200 -vn 0.460549 -0.443815 -0.768715 -v -0.066500 -0.096100 0.107493 -vn 0.460549 -0.887634 0.000000 -v -0.066500 -0.095700 0.106800 -vn 0.460548 0.443820 -0.768713 -v -0.066500 -0.096900 0.107493 -vn 0.460549 0.768714 -0.443816 -v -0.066500 -0.097193 0.107200 -vn 0.460549 -0.000000 -0.887634 -v -0.066500 -0.096500 0.107600 -vn 0.539406 0.842046 0.000001 -v -0.062058 -0.097300 0.106800 -vn 0.539405 0.729231 0.421027 -v -0.062058 -0.097193 0.106400 -vn 0.539405 0.421028 0.729231 -v -0.062058 -0.096900 0.106107 -vn 0.539406 -0.000001 0.842046 -v -0.062058 -0.096500 0.106000 -vn 0.539404 -0.421023 0.729235 -v -0.062058 -0.096100 0.106107 -vn 0.539408 -0.729231 0.421025 -v -0.062058 -0.095807 0.106400 -vn 0.539403 -0.842048 -0.000000 -v -0.062058 -0.095700 0.106800 -vn 0.539407 -0.729234 -0.421020 -v -0.062058 -0.095807 0.107200 -vn 0.539407 -0.421020 -0.729234 -v -0.062058 -0.096100 0.107493 -vn 0.539403 0.000000 -0.842048 -v -0.062058 -0.096500 0.107600 -vn 0.539408 0.421025 -0.729231 -v -0.062058 -0.096900 0.107493 -vn 0.539404 0.729234 -0.421023 -v -0.062058 -0.097193 0.107200 -vn -0.539395 -0.842053 -0.000002 -v -0.069041 -0.128250 0.117200 -vn -0.539396 -0.729239 0.421025 -v -0.069041 -0.128417 0.116575 -vn -0.539399 -0.421022 0.729239 -v -0.069041 -0.128875 0.116117 -vn -0.539398 0.000000 0.842051 -v -0.069041 -0.129500 0.115950 -vn -0.539396 0.421030 0.729236 -v -0.069041 -0.130125 0.116117 -vn -0.539401 0.729234 0.421028 -v -0.069041 -0.130583 0.116575 -vn -0.539400 0.842049 -0.000002 -v -0.069041 -0.130750 0.117200 -vn -0.539401 0.729236 -0.421024 -v -0.069041 -0.130583 0.117825 -vn -0.539397 0.421027 -0.729237 -v -0.069041 -0.130125 0.118283 -vn -0.539398 0.000000 -0.842051 -v -0.069041 -0.129500 0.118450 -vn -0.539400 -0.421019 -0.729239 -v -0.069041 -0.128875 0.118283 -vn -0.539396 -0.729241 -0.421022 -v -0.069041 -0.128417 0.117825 -vn -0.406933 -0.913458 0.000006 -v -0.066900 -0.136100 0.123200 -vn -0.406967 -0.791066 0.456719 -v -0.066900 -0.136221 0.122750 -vn -0.406962 -0.456727 0.791064 -v -0.066900 -0.136550 0.122421 -vn -0.406968 -0.000000 0.913442 -v -0.066900 -0.137000 0.122300 -vn -0.406978 0.456708 0.791067 -v -0.066900 -0.137450 0.122421 -vn -0.406944 0.791079 0.456717 -v -0.066900 -0.137779 0.122750 -vn -0.406962 0.913445 0.000005 -v -0.066900 -0.137900 0.123200 -vn -0.406943 0.791074 -0.456727 -v -0.066900 -0.137779 0.123650 -vn -0.406975 0.456715 -0.791064 -v -0.066900 -0.137450 0.123979 -vn -0.406969 -0.000001 -0.913442 -v -0.066900 -0.137000 0.124100 -vn -0.406961 -0.456729 -0.791063 -v -0.066900 -0.136550 0.123979 -vn -0.406970 -0.791061 -0.456726 -v -0.066900 -0.136221 0.123650 -vn -0.406951 -0.913450 0.000005 -v -0.066900 -0.122600 0.125200 -vn -0.406968 -0.791066 0.456718 -v -0.066900 -0.122721 0.124750 -vn -0.406948 -0.456724 0.791073 -v -0.066900 -0.123050 0.124421 -vn -0.406965 -0.000003 0.913444 -v -0.066900 -0.123500 0.124300 -vn -0.406956 0.456721 0.791071 -v -0.066900 -0.123950 0.124421 -vn -0.406955 0.791072 0.456721 -v -0.066900 -0.124279 0.124750 -vn -0.406966 0.913444 0.000004 -v -0.066900 -0.124400 0.125200 -vn -0.406948 0.791069 -0.456731 -v -0.066900 -0.124279 0.125650 -vn -0.406968 0.456723 -0.791063 -v -0.066900 -0.123950 0.125979 -vn -0.406969 -0.000001 -0.913442 -v -0.066900 -0.123500 0.126100 -vn -0.406961 -0.456729 -0.791063 -v -0.066900 -0.123050 0.125979 -vn -0.406961 -0.791063 -0.456729 -v -0.066900 -0.122721 0.125650 -vn -0.406965 -0.913444 -0.000001 -v -0.066900 -0.107100 0.125200 -vn -0.406956 -0.791070 0.456722 -v -0.066900 -0.107221 0.124750 -vn -0.406955 -0.456719 0.791073 -v -0.066900 -0.107550 0.124421 -vn -0.406965 -0.000002 0.913444 -v -0.066900 -0.108000 0.124300 -vn -0.406957 0.456725 0.791068 -v -0.066900 -0.108450 0.124421 -vn -0.406969 0.791063 0.456723 -v -0.066900 -0.108779 0.124750 -vn -0.406951 0.913450 -0.000002 -v -0.066900 -0.108900 0.125200 -vn -0.406960 0.791065 -0.456727 -v -0.066900 -0.108779 0.125650 -vn -0.406970 0.456726 -0.791061 -v -0.066900 -0.108450 0.125979 -vn -0.406969 -0.000001 -0.913442 -v -0.066900 -0.108000 0.126100 -vn -0.406970 -0.456719 -0.791065 -v -0.066900 -0.107550 0.125979 -vn -0.406948 -0.791073 -0.456724 -v -0.066900 -0.107221 0.125650 -vn -0.406933 -0.913458 0.000006 -v -0.066900 -0.136100 0.111200 -vn -0.406967 -0.791066 0.456719 -v -0.066900 -0.136221 0.110750 -vn -0.406962 -0.456727 0.791064 -v -0.066900 -0.136550 0.110421 -vn -0.406951 0.000003 0.913450 -v -0.066900 -0.137000 0.110300 -vn -0.406977 0.456706 0.791069 -v -0.066900 -0.137450 0.110421 -vn -0.406944 0.791079 0.456717 -v -0.066900 -0.137779 0.110750 -vn -0.406962 0.913445 0.000005 -v -0.066900 -0.137900 0.111200 -vn -0.406943 0.791077 -0.456723 -v -0.066900 -0.137779 0.111650 -vn -0.406961 0.456713 -0.791072 -v -0.066900 -0.137450 0.111979 -vn -0.406966 0.000002 -0.913443 -v -0.066900 -0.137000 0.112100 -vn -0.406948 -0.456731 -0.791069 -v -0.066900 -0.136550 0.111979 -vn -0.406968 -0.791063 -0.456723 -v -0.066900 -0.136221 0.111650 -vn -0.406965 -0.913444 -0.000002 -v -0.066900 -0.107100 0.109200 -vn -0.406956 -0.791071 0.456721 -v -0.066900 -0.107221 0.108750 -vn -0.406955 -0.456719 0.791073 -v -0.066900 -0.107550 0.108421 -vn -0.406965 -0.000002 0.913444 -v -0.066900 -0.108000 0.108300 -vn -0.406957 0.456725 0.791068 -v -0.066900 -0.108450 0.108421 -vn -0.406969 0.791064 0.456721 -v -0.066900 -0.108779 0.108750 -vn -0.406951 0.913450 -0.000003 -v -0.066900 -0.108900 0.109200 -vn -0.406969 0.791064 -0.456721 -v -0.066900 -0.108779 0.109650 -vn -0.406971 0.456724 -0.791062 -v -0.066900 -0.108450 0.109979 -vn -0.406969 -0.000001 -0.913442 -v -0.066900 -0.108000 0.110100 -vn -0.406970 -0.456719 -0.791065 -v -0.066900 -0.107550 0.109979 -vn -0.406957 -0.791070 -0.456721 -v -0.066900 -0.107221 0.109650 -vn -0.406951 -0.913450 0.000003 -v -0.066900 -0.122600 0.109200 -vn -0.406968 -0.791067 0.456716 -v -0.066900 -0.122721 0.108750 -vn -0.406948 -0.456724 0.791073 -v -0.066900 -0.123050 0.108421 -vn -0.406965 -0.000003 0.913444 -v -0.066900 -0.123500 0.108300 -vn -0.406956 0.456721 0.791071 -v -0.066900 -0.123950 0.108421 -vn -0.406955 0.791073 0.456719 -v -0.066900 -0.124279 0.108750 -vn -0.406965 0.913444 0.000002 -v -0.066900 -0.124400 0.109200 -vn -0.406957 0.791068 -0.456725 -v -0.066900 -0.124279 0.109650 -vn -0.406969 0.456721 -0.791064 -v -0.066900 -0.123950 0.109979 -vn -0.406969 -0.000001 -0.913442 -v -0.066900 -0.123500 0.110100 -vn -0.406961 -0.456729 -0.791063 -v -0.066900 -0.123050 0.109979 -vn -0.406970 -0.791061 -0.456726 -v -0.066900 -0.122721 0.109650 -vn -0.496973 -0.033951 0.867102 -v -0.066500 -0.136000 0.130066 -vn -0.863073 -0.019976 0.504684 -v -0.066866 -0.136000 0.129700 -vn -0.863077 -0.504677 0.019974 -v -0.066866 -0.140500 0.125200 -vn -0.860426 -0.503302 0.079716 -v -0.066866 -0.140445 0.125904 -vn -0.496980 -0.867098 0.033951 -v -0.066500 -0.140866 0.125200 -vn -0.494486 -0.858484 0.135973 -v -0.066500 -0.140806 0.125961 -vn -0.494484 -0.826646 0.268592 -v -0.066500 -0.140628 0.126704 -vn -0.494488 -0.774450 0.394599 -v -0.066500 -0.140336 0.127409 -vn -0.494488 -0.703184 0.510895 -v -0.066500 -0.139937 0.128060 -vn -0.494475 -0.614615 0.614608 -v -0.066500 -0.139441 0.128641 -vn -0.494482 -0.510894 0.703189 -v -0.066500 -0.138860 0.129137 -vn -0.494475 -0.394606 0.774455 -v -0.066500 -0.138209 0.129536 -vn -0.494475 -0.268597 0.826650 -v -0.066500 -0.137504 0.129828 -vn -0.494479 -0.135969 0.858489 -v -0.066500 -0.136761 0.130006 -vn -0.860420 -0.484645 0.157468 -v -0.066866 -0.140280 0.126591 -vn -0.860427 -0.454032 0.231345 -v -0.066866 -0.140010 0.127243 -vn -0.860425 -0.412258 0.299520 -v -0.066866 -0.139641 0.127845 -vn -0.860422 -0.360331 0.360326 -v -0.066866 -0.139182 0.128382 -vn -0.860421 -0.299526 0.412261 -v -0.066866 -0.138645 0.128841 -vn -0.860424 -0.231343 0.454039 -v -0.066866 -0.138043 0.129210 -vn -0.860425 -0.157468 0.484636 -v -0.066866 -0.137391 0.129480 -vn -0.860423 -0.079717 0.503307 -v -0.066866 -0.136704 0.129645 -vn -0.863077 -0.504678 -0.019975 -v -0.066866 -0.140500 0.109200 -vn -0.496982 -0.867097 -0.033950 -v -0.066500 -0.140866 0.109200 -vn -0.863075 -0.019976 -0.504681 -v -0.066866 -0.136000 0.104700 -vn -0.860423 -0.079715 -0.503307 -v -0.066866 -0.136704 0.104755 -vn -0.496977 -0.033954 -0.867099 -v -0.066500 -0.136000 0.104334 -vn -0.494483 -0.135973 -0.858486 -v -0.066500 -0.136761 0.104394 -vn -0.494476 -0.268593 -0.826651 -v -0.066500 -0.137504 0.104572 -vn -0.494476 -0.394603 -0.774456 -v -0.066500 -0.138209 0.104864 -vn -0.494481 -0.510898 -0.703187 -v -0.066500 -0.138860 0.105263 -vn -0.494478 -0.614610 -0.614611 -v -0.066500 -0.139441 0.105759 -vn -0.494486 -0.703187 -0.510894 -v -0.066500 -0.139937 0.106340 -vn -0.494488 -0.774451 -0.394597 -v -0.066500 -0.140336 0.106991 -vn -0.494483 -0.826645 -0.268597 -v -0.066500 -0.140628 0.107696 -vn -0.494485 -0.858485 -0.135972 -v -0.066500 -0.140806 0.108439 -vn -0.860423 -0.157469 -0.484640 -v -0.066866 -0.137391 0.104920 -vn -0.860424 -0.231344 -0.454038 -v -0.066866 -0.138043 0.105190 -vn -0.860423 -0.299524 -0.412260 -v -0.066866 -0.138645 0.105559 -vn -0.860423 -0.360329 -0.360327 -v -0.066866 -0.139182 0.106018 -vn -0.860426 -0.412257 -0.299519 -v -0.066866 -0.139641 0.106555 -vn -0.860425 -0.454036 -0.231343 -v -0.066866 -0.140010 0.107157 -vn -0.860421 -0.484641 -0.157473 -v -0.066866 -0.140280 0.107809 -vn -0.860427 -0.503300 -0.079711 -v -0.066866 -0.140445 0.108496 -vn -0.127833 -0.495903 -0.858917 -v -0.069700 -0.103850 0.107240 -vn -0.127831 -0.858917 -0.495904 -v -0.069700 -0.103960 0.107350 -vn -0.854926 0.069808 -0.514032 -v -0.069960 -0.097300 0.107350 -vn -0.854925 -0.069806 -0.514034 -v -0.069960 -0.103700 0.107350 -vn -0.488343 0.112926 -0.865314 -v -0.069850 -0.097300 0.107240 -vn -0.488344 -0.112924 -0.865314 -v -0.069850 -0.103700 0.107240 -vn -0.127828 0.858927 -0.495888 -v -0.069700 -0.097040 0.107350 -vn -0.127838 0.495903 -0.858916 -v -0.069700 -0.097150 0.107240 -vn -0.488343 -0.865315 -0.112920 -v -0.069850 -0.103960 0.107500 -vn -0.482342 -0.758621 -0.437996 -v -0.069850 -0.103925 0.107370 -vn -0.847426 -0.265446 -0.459790 -v -0.069960 -0.103775 0.107370 -vn -0.847429 -0.459785 -0.265448 -v -0.069960 -0.103830 0.107425 -vn -0.482343 -0.437992 -0.758623 -v -0.069850 -0.103830 0.107275 -vn -0.854927 -0.514031 -0.069801 -v -0.069960 -0.103850 0.107500 -vn -0.482355 0.437979 -0.758622 -v -0.069850 -0.097170 0.107275 -vn -0.854925 0.514031 -0.069822 -v -0.069960 -0.097150 0.107500 -vn -0.847434 0.459763 -0.265469 -v -0.069960 -0.097170 0.107425 -vn -0.847428 0.265454 -0.459784 -v -0.069960 -0.097225 0.107370 -vn -0.482353 0.758611 -0.438002 -v -0.069850 -0.097075 0.107370 -vn -0.488328 0.865324 -0.112918 -v -0.069850 -0.097040 0.107500 -vn -0.127833 -0.858917 0.495903 -v -0.069700 -0.103960 0.113050 -vn -0.127831 -0.495904 0.858917 -v -0.069700 -0.103850 0.113160 -vn -0.854925 -0.514034 0.069806 -v -0.069960 -0.103850 0.112900 -vn -0.488344 -0.865314 0.112924 -v -0.069850 -0.103960 0.112900 -vn -0.854923 0.514035 0.069827 -v -0.069960 -0.097150 0.112900 -vn -0.488327 0.865323 0.112925 -v -0.069850 -0.097040 0.112900 -vn -0.127842 0.495906 0.858914 -v -0.069700 -0.097150 0.113160 -vn -0.127835 0.858926 0.495888 -v -0.069700 -0.097040 0.113050 -vn -0.488343 -0.112920 0.865315 -v -0.069850 -0.103700 0.113160 -vn -0.482342 -0.437996 0.758621 -v -0.069850 -0.103830 0.113125 -vn -0.847426 -0.459790 0.265446 -v -0.069960 -0.103830 0.112975 -vn -0.847429 -0.265448 0.459785 -v -0.069960 -0.103775 0.113030 -vn -0.482343 -0.758623 0.437992 -v -0.069850 -0.103925 0.113030 -vn -0.854927 -0.069801 0.514031 -v -0.069960 -0.103700 0.113050 -vn -0.482346 0.758615 0.438001 -v -0.069850 -0.097075 0.113030 -vn -0.854924 0.069812 0.514034 -v -0.069960 -0.097300 0.113050 -vn -0.847428 0.265446 0.459787 -v -0.069960 -0.097225 0.113030 -vn -0.847433 0.459769 0.265460 -v -0.069960 -0.097170 0.112975 -vn -0.482350 0.437983 0.758623 -v -0.069850 -0.097170 0.113125 -vn -0.488344 0.112928 0.865313 -v -0.069850 -0.097300 0.113160 -vn -0.127837 0.858924 -0.495891 -v -0.069700 -0.097040 0.121350 -vn -0.127842 0.495887 -0.858925 -v -0.069700 -0.097150 0.121240 -vn -0.488329 0.865323 -0.112922 -v -0.069850 -0.097040 0.121500 -vn -0.488328 0.865323 0.112926 -v -0.069850 -0.097040 0.126900 -vn -0.854925 0.514031 -0.069827 -v -0.069960 -0.097150 0.121500 -vn -0.854921 0.514036 0.069834 -v -0.069960 -0.097150 0.126900 -vn -0.127837 0.495891 0.858924 -v -0.069700 -0.097150 0.127160 -vn -0.127829 0.858923 0.495895 -v -0.069700 -0.097040 0.127050 -vn -0.488327 0.112931 -0.865323 -v -0.069850 -0.097300 0.121240 -vn -0.482358 0.437985 -0.758617 -v -0.069850 -0.097170 0.121275 -vn -0.847435 0.459760 -0.265469 -v -0.069960 -0.097170 0.121425 -vn -0.847432 0.265465 -0.459768 -v -0.069960 -0.097225 0.121370 -vn -0.482360 0.758612 -0.437992 -v -0.069850 -0.097075 0.121370 -vn -0.854921 0.069834 -0.514036 -v -0.069960 -0.097300 0.121350 -vn -0.482337 0.758610 0.438021 -v -0.069850 -0.097075 0.127030 -vn -0.854921 0.069796 0.514042 -v -0.069960 -0.097300 0.127050 -vn -0.847419 0.265435 0.459810 -v -0.069960 -0.097225 0.127030 -vn -0.847439 0.459771 0.265439 -v -0.069960 -0.097170 0.126975 -vn -0.482340 0.437973 0.758635 -v -0.069850 -0.097170 0.127125 -vn -0.488329 0.112922 0.865323 -v -0.069850 -0.097300 0.127160 -vn -0.127828 -0.495888 -0.858927 -v -0.069700 -0.103850 0.121240 -vn -0.127838 -0.858916 -0.495903 -v -0.069700 -0.103960 0.121350 -vn -0.488328 -0.112918 -0.865324 -v -0.069850 -0.103700 0.121240 -vn -0.854925 -0.069822 -0.514031 -v -0.069960 -0.103700 0.121350 -vn -0.488319 -0.112917 0.865329 -v -0.069850 -0.103700 0.127160 -vn -0.854929 -0.069775 0.514031 -v -0.069960 -0.103700 0.127050 -vn -0.127823 -0.858918 0.495905 -v -0.069700 -0.103960 0.127050 -vn -0.127827 -0.495882 0.858931 -v -0.069700 -0.103850 0.127160 -vn -0.488343 -0.865314 -0.112926 -v -0.069850 -0.103960 0.121500 -vn -0.482355 -0.758622 -0.437979 -v -0.069850 -0.103925 0.121370 -vn -0.847434 -0.265469 -0.459763 -v -0.069960 -0.103775 0.121370 -vn -0.847428 -0.459784 -0.265454 -v -0.069960 -0.103830 0.121425 -vn -0.482353 -0.438002 -0.758611 -v -0.069850 -0.103830 0.121275 -vn -0.854926 -0.514032 -0.069808 -v -0.069960 -0.103850 0.121500 -vn -0.482332 -0.437983 0.758635 -v -0.069850 -0.103830 0.127125 -vn -0.854925 -0.514033 0.069810 -v -0.069960 -0.103850 0.126900 -vn -0.847428 -0.459790 0.265441 -v -0.069960 -0.103830 0.126975 -vn -0.847419 -0.265457 0.459797 -v -0.069960 -0.103775 0.127030 -vn -0.482341 -0.758614 0.438009 -v -0.069850 -0.103925 0.127030 -vn -0.488342 -0.865315 0.112926 -v -0.069850 -0.103960 0.126900 -vn -0.860433 0.503291 -0.079715 -v -0.069760 -0.124315 0.116379 -vn -0.860425 0.484638 -0.157467 -v -0.069760 -0.124507 0.115578 -vn -0.860432 0.454026 -0.231338 -v -0.069760 -0.124822 0.114817 -vn -0.860437 0.412240 -0.299509 -v -0.069760 -0.125253 0.114114 -vn -0.860437 0.360311 -0.360310 -v -0.069760 -0.125788 0.113488 -vn -0.860424 0.299525 -0.412256 -v -0.069760 -0.126414 0.112953 -vn -0.860428 0.231341 -0.454033 -v -0.069760 -0.127117 0.112522 -vn -0.860429 0.157463 -0.484631 -v -0.069760 -0.127878 0.112207 -vn -0.860434 0.079711 -0.503289 -v -0.069760 -0.128679 0.112015 -vn -0.860428 0.000001 -0.509572 -v -0.069760 -0.129500 0.111950 -vn -0.860434 -0.079714 -0.503288 -v -0.069760 -0.130321 0.112015 -vn -0.860424 -0.157466 -0.484639 -v -0.069760 -0.131122 0.112207 -vn -0.860430 -0.231340 -0.454029 -v -0.069760 -0.131883 0.112522 -vn -0.860435 -0.299511 -0.412243 -v -0.069760 -0.132586 0.112953 -vn -0.860438 -0.360311 -0.360310 -v -0.069760 -0.133212 0.113488 -vn -0.860437 -0.412241 -0.299510 -v -0.069760 -0.133747 0.114114 -vn -0.860428 -0.454031 -0.231343 -v -0.069760 -0.134178 0.114817 -vn -0.860424 -0.484638 -0.157468 -v -0.069760 -0.134493 0.115578 -vn -0.860427 -0.503300 -0.079712 -v -0.069760 -0.134685 0.116379 -vn -0.860428 -0.509572 0.000000 -v -0.069760 -0.134750 0.117200 -vn -0.860428 -0.503299 0.079711 -v -0.069760 -0.134685 0.118021 -vn -0.860427 -0.484634 0.157464 -v -0.069760 -0.134493 0.118822 -vn -0.860431 -0.454027 0.231339 -v -0.069760 -0.134178 0.119583 -vn -0.860432 -0.412247 0.299516 -v -0.069760 -0.133747 0.120286 -vn -0.860431 -0.360317 0.360319 -v -0.069760 -0.133212 0.120912 -vn -0.860435 -0.299510 0.412245 -v -0.069760 -0.132586 0.121447 -vn -0.860430 -0.231341 0.454028 -v -0.069760 -0.131883 0.121878 -vn -0.860430 -0.157465 0.484629 -v -0.069760 -0.131122 0.122193 -vn -0.860432 -0.079714 0.503292 -v -0.069760 -0.130321 0.122385 -vn -0.860430 -0.000000 0.509569 -v -0.069760 -0.129500 0.122450 -vn -0.860431 0.079713 0.503293 -v -0.069760 -0.128679 0.122385 -vn -0.860434 0.157462 0.484623 -v -0.069760 -0.127878 0.122193 -vn -0.860427 0.231341 0.454034 -v -0.069760 -0.127117 0.121878 -vn -0.860424 0.299522 0.412258 -v -0.069760 -0.126414 0.121447 -vn -0.860431 0.360318 0.360317 -v -0.069760 -0.125788 0.120912 -vn -0.860431 0.412248 0.299515 -v -0.069760 -0.125253 0.120286 -vn -0.860434 0.454024 0.231334 -v -0.069760 -0.124822 0.119583 -vn -0.860428 0.484632 0.157467 -v -0.069760 -0.124507 0.118822 -vn -0.860434 0.503289 0.079711 -v -0.069760 -0.124315 0.118021 -vn -0.860428 0.509572 0.000001 -v -0.069760 -0.124250 0.117200 -vn -0.494483 0.858487 -0.135970 -v -0.069650 -0.124206 0.116362 -vn -0.494479 0.826648 -0.268595 -v -0.069650 -0.124403 0.115544 -vn -0.494476 0.774458 -0.394598 -v -0.069650 -0.124724 0.114767 -vn -0.494486 0.703188 -0.510892 -v -0.069650 -0.125164 0.114050 -vn -0.494478 0.614610 -0.614611 -v -0.069650 -0.125710 0.113410 -vn -0.494458 0.510906 -0.703198 -v -0.069650 -0.126350 0.112864 -vn -0.494476 0.394601 -0.774457 -v -0.069650 -0.127067 0.112424 -vn -0.494481 0.268597 -0.826646 -v -0.069650 -0.127844 0.112103 -vn -0.494484 0.135970 -0.858485 -v -0.069650 -0.128662 0.111906 -vn -0.494489 -0.000001 -0.869184 -v -0.069650 -0.129500 0.111840 -vn -0.494485 -0.135971 -0.858485 -v -0.069650 -0.130338 0.111906 -vn -0.494486 -0.268592 -0.826645 -v -0.069650 -0.131156 0.112103 -vn -0.494475 -0.394601 -0.774458 -v -0.069650 -0.131933 0.112424 -vn -0.494472 -0.510900 -0.703192 -v -0.069650 -0.132650 0.112864 -vn -0.494478 -0.614610 -0.614611 -v -0.069650 -0.133290 0.113410 -vn -0.494488 -0.703186 -0.510892 -v -0.069650 -0.133836 0.114050 -vn -0.494477 -0.774457 -0.394601 -v -0.069650 -0.134276 0.114767 -vn -0.494461 -0.826659 -0.268596 -v -0.069650 -0.134597 0.115544 -vn -0.494470 -0.858494 -0.135971 -v -0.069650 -0.134794 0.116362 -vn -0.494508 -0.869173 0.000004 -v -0.069650 -0.134860 0.117200 -vn -0.494471 -0.858494 0.135969 -v -0.069650 -0.134794 0.118038 -vn -0.494464 -0.826658 0.268594 -v -0.069650 -0.134597 0.118856 -vn -0.494473 -0.774457 0.394604 -v -0.069650 -0.134276 0.119633 -vn -0.494479 -0.703190 0.510896 -v -0.069650 -0.133836 0.120350 -vn -0.494482 -0.614610 0.614608 -v -0.069650 -0.133290 0.120990 -vn -0.494489 -0.510894 0.703184 -v -0.069650 -0.132650 0.121536 -vn -0.494494 -0.394597 0.774448 -v -0.069650 -0.131933 0.121976 -vn -0.494479 -0.268592 0.826649 -v -0.069650 -0.131156 0.122297 -vn -0.494484 -0.135971 0.858486 -v -0.069650 -0.130338 0.122494 -vn -0.494469 -0.000002 0.869195 -v -0.069650 -0.129500 0.122560 -vn -0.494484 0.135972 0.858485 -v -0.069650 -0.128662 0.122494 -vn -0.494477 0.268595 0.826650 -v -0.069650 -0.127844 0.122297 -vn -0.494495 0.394600 0.774445 -v -0.069650 -0.127067 0.121976 -vn -0.494472 0.510898 0.703193 -v -0.069650 -0.126350 0.121536 -vn -0.494481 0.614611 0.614607 -v -0.069650 -0.125710 0.120990 -vn -0.494479 0.703192 0.510893 -v -0.069650 -0.125164 0.120350 -vn -0.494475 0.774457 0.394603 -v -0.069650 -0.124724 0.119633 -vn -0.494483 0.826646 0.268594 -v -0.069650 -0.124403 0.118856 -vn -0.494484 0.858486 0.135971 -v -0.069650 -0.124206 0.118038 -vn -0.494489 0.869184 -0.000001 -v -0.069650 -0.124140 0.117200 -vn 0.673140 0.513710 -0.531962 -v -0.031500 -0.131410 0.119178 -vn 0.674182 0.313587 -0.668687 -v -0.031500 -0.130664 0.119691 -vn 0.389835 0.465237 -0.794722 -v -0.030300 -0.130706 0.119672 -vn 0.675655 0.079095 -0.732963 -v -0.031500 -0.129792 0.119934 -vn 0.390512 0.189325 -0.900920 -v -0.030300 -0.129883 0.119923 -vn 0.386455 0.329045 -0.861616 -v -0.030300 -0.130664 0.119691 -vn 0.676929 -0.163112 -0.717748 -v -0.031500 -0.128889 0.119881 -vn 0.397983 -0.113075 -0.910397 -v -0.030300 -0.129022 0.119908 -vn 0.392172 0.046138 -0.918734 -v -0.030300 -0.129792 0.119934 -vn 0.678007 -0.386935 -0.624971 -v -0.031500 -0.128051 0.119537 -vn 0.391666 -0.390178 -0.833282 -v -0.030300 -0.128209 0.119628 -vn 0.381567 -0.256523 -0.888033 -v -0.030300 -0.128889 0.119881 -vn 0.678901 -0.568332 -0.464857 -v -0.031500 -0.127371 0.118940 -vn 0.392140 -0.634073 -0.666467 -v -0.030300 -0.127522 0.119110 -vn 0.379254 -0.525310 -0.761719 -v -0.030300 -0.128051 0.119537 -vn 0.679608 -0.687893 -0.254827 -v -0.031500 -0.126921 0.118155 -vn 0.392531 -0.812507 -0.430990 -v -0.030300 -0.127028 0.118406 -vn 0.377173 -0.740178 -0.556666 -v -0.030300 -0.127371 0.118940 -vn 0.680133 -0.732878 -0.017592 -v -0.031500 -0.126751 0.117266 -vn 0.392841 -0.907101 -0.151141 -v -0.030300 -0.126777 0.117583 -vn 0.375399 -0.878980 -0.294058 -v -0.030300 -0.126921 0.118155 -vn 0.680487 -0.698554 0.221268 -v -0.031500 -0.126878 0.116369 -vn 0.393067 -0.908120 0.144276 -v -0.030300 -0.126792 0.116722 -vn 0.374007 -0.927426 -0.001004 -v -0.030300 -0.126751 0.117266 -vn 0.680659 -0.588714 0.436027 -v -0.031500 -0.127290 0.115563 -vn 0.393201 -0.815470 0.424737 -v -0.030300 -0.127072 0.115909 -vn 0.373049 -0.880548 0.292352 -v -0.030300 -0.126878 0.116369 -vn 0.680658 -0.415216 0.603573 -v -0.031500 -0.127941 0.114934 -vn 0.385462 -0.632564 0.671775 -v -0.030300 -0.127590 0.115222 -vn 0.372556 -0.743187 0.555765 -v -0.030300 -0.127290 0.115563 -vn 0.680482 -0.196755 0.705855 -v -0.031500 -0.128761 0.114551 -vn 0.386235 -0.387935 0.836857 -v -0.030300 -0.128294 0.114728 -vn 0.340445 -0.551224 0.761741 -v -0.030300 -0.127941 0.114934 -vn 0.680135 0.043155 0.731815 -v -0.031500 -0.129662 0.114455 -vn 0.396402 -0.116059 0.910712 -v -0.030300 -0.129117 0.114477 -vn 0.347420 -0.279389 0.895121 -v -0.030300 -0.128761 0.114551 -vn 0.679606 0.278677 0.678583 -v -0.031500 -0.130544 0.114656 -vn 0.387542 0.190742 0.901903 -v -0.030300 -0.129978 0.114492 -vn 0.388760 0.039218 0.920504 -v -0.030300 -0.129662 0.114455 -vn 0.678897 0.484412 0.551764 -v -0.031500 -0.131314 0.115133 -vn 0.388085 0.465635 0.795345 -v -0.030300 -0.130791 0.114772 -vn 0.360366 0.316071 0.877631 -v -0.030300 -0.130544 0.114656 -vn 0.678011 0.638091 0.364885 -v -0.031500 -0.131887 0.115834 -vn 0.388561 0.692766 0.607532 -v -0.030300 -0.131478 0.115290 -vn 0.366267 0.577844 0.729345 -v -0.030300 -0.131314 0.115133 -vn 0.676928 0.723003 0.137967 -v -0.031500 -0.132201 0.116683 -vn 0.388967 0.848956 0.357740 -v -0.030300 -0.131972 0.115994 -vn 0.371752 0.778408 0.505848 -v -0.030300 -0.131887 0.115834 -vn 0.675655 0.729757 -0.104621 -v -0.031500 -0.132223 0.117588 -vn 0.397708 0.913962 0.080633 -v -0.030300 -0.132223 0.116817 -vn 0.376777 0.897148 0.230576 -v -0.030300 -0.132201 0.116683 -vn 0.674181 0.657336 -0.336733 -v -0.031500 -0.131949 0.118451 -vn 0.389590 0.893838 -0.221978 -v -0.030300 -0.132208 0.117678 -vn 0.395229 0.915197 -0.078794 -v -0.030300 -0.132223 0.117588 -vn 0.396851 0.637618 -0.660267 -v -0.030300 -0.131410 0.119178 -vn 0.389819 0.777977 -0.492740 -v -0.030300 -0.131928 0.118491 -vn 0.385332 0.850568 -0.357846 -v -0.030300 -0.131949 0.118451 -vn 0.916684 -0.374754 -0.138744 -v -0.030000 -0.139534 0.113485 -vn 0.916685 -0.346806 -0.198533 -v -0.030000 -0.138786 0.111884 -vn 0.934356 0.356311 0.004726 -v -0.030000 -0.132549 0.117122 -vn 0.976002 0.151268 -0.156644 -v -0.030000 -0.124457 0.123495 -vn 0.976002 0.052682 -0.211291 -v -0.030000 -0.123993 0.123752 -vn 0.911762 0.242091 0.331786 -v -0.030000 -0.123364 0.125966 -vn 0.976002 -0.060024 -0.209326 -v -0.030000 -0.123463 0.123743 -vn 0.930602 -0.005096 0.365997 -v -0.030000 -0.129422 0.114151 -vn 0.915896 0.206179 -0.344421 -v -0.030000 -0.123673 0.108226 -vn 0.976001 0.156647 0.151272 -v -0.030000 -0.124680 0.110733 -vn 0.933408 -0.014961 -0.358504 -v -0.030000 -0.129316 0.120244 -vn 0.976002 0.211293 0.052681 -v -0.030000 -0.124740 0.122509 -vn 0.976002 0.209326 -0.060024 -v -0.030000 -0.124731 0.123040 -vn 0.976002 -0.209326 0.060024 -v -0.030000 -0.122760 0.122475 -vn 0.916683 0.346809 0.198534 -v -0.030000 -0.120214 0.122516 -vn 0.976002 -0.211291 -0.052682 -v -0.030000 -0.122751 0.123005 -vn 0.916686 0.309395 0.252907 -v -0.030000 -0.121216 0.123972 -vn 0.976002 -0.156644 -0.151268 -v -0.030000 -0.123008 0.123469 -vn 0.976002 -0.151268 0.156644 -v -0.030000 -0.123033 0.122020 -vn 0.916683 0.392481 0.075168 -v -0.030000 -0.118991 0.119213 -vn 0.916684 0.374755 0.138743 -v -0.030000 -0.119466 0.120915 -vn 0.976002 0.211292 0.052681 -v -0.030000 -0.124937 0.111197 -vn 0.976002 0.209328 -0.060023 -v -0.030000 -0.124928 0.111728 -vn 0.930830 -0.064050 0.359795 -v -0.030000 -0.129076 0.114180 -vn 0.917901 0.265980 0.294469 -v -0.030000 -0.122443 0.125243 -vn 0.916685 0.355889 -0.181746 -v -0.030000 -0.119971 0.112334 -vn 0.916685 0.380950 -0.120690 -v -0.030000 -0.119300 0.113968 -vn 0.976002 -0.052682 0.211291 -v -0.030000 -0.123497 0.121763 -vn 0.916685 0.395619 -0.056341 -v -0.030000 -0.118907 0.115691 -vn 0.916685 0.399496 0.009544 -v -0.030000 -0.118803 0.117456 -vn 0.976002 0.060024 0.209326 -v -0.030000 -0.124028 0.121772 -vn 0.976002 0.052682 -0.211291 -v -0.030000 -0.124191 0.112440 -vn 0.976002 -0.060024 -0.209326 -v -0.030000 -0.123660 0.112431 -vn 0.932765 -0.356719 -0.051969 -v -0.030000 -0.126480 0.117624 -vn 0.933024 -0.322413 -0.159736 -v -0.030000 -0.126759 0.118537 -vn 0.933383 -0.256417 -0.251091 -v -0.030000 -0.127306 0.119319 -vn 0.976002 0.156646 0.151272 -v -0.030000 -0.124483 0.122045 -vn 0.933858 -0.165621 -0.316985 -v -0.030000 -0.128068 0.119893 -vn 0.930829 -0.076191 -0.357425 -v -0.030000 -0.128970 0.120204 -vn 0.932592 -0.355668 0.061418 -v -0.030000 -0.126496 0.116670 -vn 0.932491 -0.319224 0.168987 -v -0.030000 -0.126807 0.115768 -vn 0.976003 0.151268 -0.156642 -v -0.030000 -0.124655 0.112183 -vn 0.934774 -0.242179 0.259898 -v -0.030000 -0.127381 0.115006 -vn 0.935148 -0.151817 0.320077 -v -0.030000 -0.128163 0.114459 -vn 0.976001 -0.156647 -0.151272 -v -0.030000 -0.123205 0.112157 -vn 0.976002 -0.211292 -0.052681 -v -0.030000 -0.122948 0.111693 -vn 0.916686 0.321118 -0.237843 -v -0.030000 -0.120902 0.110831 -vn 0.976002 -0.209328 0.060023 -v -0.030000 -0.122957 0.111163 -vn 0.916685 0.277593 -0.287457 -v -0.030000 -0.122067 0.109503 -vn 0.976002 -0.151271 0.156644 -v -0.030000 -0.123231 0.110708 -vn 0.919656 0.233916 -0.315463 -v -0.030000 -0.123435 0.108385 -vn 0.976002 -0.052681 0.211294 -v -0.030000 -0.123695 0.110451 -vn 0.976002 0.060024 0.209326 -v -0.030000 -0.124225 0.110460 -vn 0.976002 -0.151272 0.156646 -v -0.030000 -0.134543 0.110905 -vn 0.976002 -0.052681 0.211292 -v -0.030000 -0.135007 0.110648 -vn 0.916682 -0.151740 -0.369688 -v -0.030000 -0.133563 0.107301 -vn 0.916687 -0.309393 -0.252904 -v -0.030000 -0.137784 0.110428 -vn 0.916682 -0.263557 -0.300387 -v -0.030000 -0.136557 0.109157 -vn 0.976002 0.060023 0.209328 -v -0.030000 -0.135537 0.110657 -vn 0.931355 0.358169 0.065520 -v -0.030000 -0.132520 0.116776 -vn 0.976002 -0.060023 -0.209328 -v -0.030000 -0.134972 0.112628 -vn 0.916685 -0.210514 -0.339666 -v -0.030000 -0.135137 0.108105 -vn 0.976001 0.151272 -0.156648 -v -0.030000 -0.135967 0.112380 -vn 0.976002 0.052681 -0.211292 -v -0.030000 -0.135503 0.112637 -vn 0.976002 -0.211294 -0.052682 -v -0.030000 -0.134260 0.111891 -vn 0.976003 -0.209320 0.060022 -v -0.030000 -0.134269 0.111360 -vn 0.917268 0.166148 -0.361959 -v -0.030000 -0.124969 0.107507 -vn 0.916685 0.107323 -0.384930 -v -0.030000 -0.126626 0.106893 -vn 0.976001 0.156646 0.151277 -v -0.030000 -0.135992 0.110931 -vn 0.976002 0.211291 0.052680 -v -0.030000 -0.136249 0.111395 -vn 0.976001 0.209331 -0.060027 -v -0.030000 -0.136240 0.111925 -vn 0.933539 0.074589 0.350629 -v -0.030000 -0.130030 0.114196 -vn 0.935066 0.169552 0.311292 -v -0.030000 -0.130932 0.114507 -vn 0.976003 -0.156642 -0.151267 -v -0.030000 -0.134517 0.112355 -vn 0.935160 0.257038 0.243738 -v -0.030000 -0.131694 0.115081 -vn 0.935333 0.319166 0.152596 -v -0.030000 -0.132241 0.115863 -vn 0.916685 -0.088819 -0.389614 -v -0.030000 -0.131878 0.106768 -vn 0.916686 -0.023479 -0.398919 -v -0.030000 -0.130129 0.106518 -vn 0.916686 0.042502 -0.397343 -v -0.030000 -0.128362 0.106561 -vn 0.932525 0.360728 -0.016492 -v -0.030000 -0.132544 0.117384 -vn 0.916685 -0.355889 0.181746 -v -0.030000 -0.139029 0.122066 -vn 0.916687 -0.380945 0.120687 -v -0.030000 -0.139700 0.120432 -vn 0.916682 -0.395625 0.056345 -v -0.030000 -0.140093 0.118709 -vn 0.916685 -0.399496 -0.009544 -v -0.030000 -0.140197 0.116944 -vn 0.916683 -0.392481 -0.075169 -v -0.030000 -0.140009 0.115187 -vn 0.936218 0.155502 -0.315143 -v -0.030000 -0.130837 0.119941 -vn 0.933459 0.060411 -0.353559 -v -0.030000 -0.129924 0.120220 -vn 0.976003 -0.209320 0.060022 -v -0.030000 -0.134072 0.122672 -vn 0.976002 -0.211294 -0.052682 -v -0.030000 -0.134063 0.123203 -vn 0.937080 0.242517 -0.251130 -v -0.030000 -0.131619 0.119394 -vn 0.976002 -0.151272 0.156646 -v -0.030000 -0.134345 0.122217 -vn 0.936466 0.309340 -0.165347 -v -0.030000 -0.132193 0.118632 -vn 0.976002 -0.052681 0.211292 -v -0.030000 -0.134809 0.121960 -vn 0.932373 0.352397 -0.080607 -v -0.030000 -0.132504 0.117730 -vn 0.976002 0.060023 0.209328 -v -0.030000 -0.135340 0.121969 -vn 0.976003 0.156642 0.151267 -v -0.030000 -0.135795 0.122243 -vn 0.976002 0.211294 0.052682 -v -0.030000 -0.136052 0.122707 -vn 0.916687 -0.321117 0.237842 -v -0.030000 -0.138098 0.123569 -vn 0.976003 0.209320 -0.060022 -v -0.030000 -0.136043 0.123237 -vn 0.916681 -0.277597 0.287463 -v -0.030000 -0.136933 0.124897 -vn 0.976002 0.151272 -0.156646 -v -0.030000 -0.135769 0.123692 -vn 0.916682 -0.226496 0.329231 -v -0.030000 -0.135565 0.126015 -vn 0.976002 0.052681 -0.211292 -v -0.030000 -0.135305 0.123949 -vn 0.916689 -0.169214 0.362007 -v -0.030000 -0.134031 0.126893 -vn 0.976002 -0.060023 -0.209328 -v -0.030000 -0.134775 0.123940 -vn 0.916685 -0.107322 0.384930 -v -0.030000 -0.132374 0.127507 -vn 0.976003 -0.156642 -0.151267 -v -0.030000 -0.134320 0.123667 -vn 0.919039 0.198163 0.340733 -v -0.030000 -0.123863 0.126295 -vn 0.916685 0.151736 0.369683 -v -0.030000 -0.125437 0.127099 -vn 0.916685 0.088820 0.389615 -v -0.030000 -0.127122 0.127632 -vn 0.916685 0.023479 0.398919 -v -0.030000 -0.128871 0.127881 -vn 0.916683 -0.042500 0.397349 -v -0.030000 -0.130638 0.127839 -vn -0.375742 -0.643755 0.666631 -v -0.034200 -0.137141 0.125113 -vn 0.375743 -0.525255 0.763495 -v -0.030300 -0.135735 0.126263 -vn -0.375745 -0.525255 0.763494 -v -0.034200 -0.135735 0.126263 -vn 0.375754 -0.392424 0.839531 -v -0.030300 -0.134158 0.127165 -vn -0.375756 -0.392421 0.839531 -v -0.034200 -0.134158 0.127165 -vn 0.375746 -0.248885 0.892676 -v -0.030300 -0.132454 0.127796 -vn -0.375750 -0.248885 0.892675 -v -0.034200 -0.132454 0.127796 -vn 0.375743 -0.098562 0.921468 -v -0.030300 -0.130670 0.128138 -vn -0.375746 -0.098563 0.921466 -v -0.034200 -0.130670 0.128138 -vn 0.375748 0.054450 0.925121 -v -0.030300 -0.128854 0.128181 -vn -0.375750 0.054450 0.925120 -v -0.034200 -0.128854 0.128181 -vn 0.375747 0.205979 0.903542 -v -0.030300 -0.127055 0.127925 -vn -0.375753 0.205978 0.903539 -v -0.034200 -0.127055 0.127925 -vn 0.375746 0.351885 0.857317 -v -0.030300 -0.125323 0.127376 -vn -0.375749 0.351885 0.857315 -v -0.034200 -0.125323 0.127376 -vn 0.370875 0.484071 0.792544 -v -0.030300 -0.123705 0.126550 -vn -0.375745 0.488195 0.787706 -v -0.034200 -0.123705 0.126550 -vn 0.373012 0.614876 0.694831 -v -0.030300 -0.122245 0.125469 -vn -0.375751 0.611187 0.696607 -v -0.034200 -0.122245 0.125469 -vn 0.375748 0.717511 0.586508 -v -0.030300 -0.120983 0.124162 -vn -0.375751 0.717510 0.586506 -v -0.034200 -0.120983 0.124162 -vn 0.375743 0.804264 0.460409 -v -0.030300 -0.119954 0.122665 -vn -0.372880 0.804237 0.462777 -v -0.034200 -0.119954 0.122665 -vn 0.375744 0.869075 0.321753 -v -0.030300 -0.119184 0.121019 -vn -0.375747 0.869074 0.321753 -v -0.034200 -0.119184 0.121019 -vn 0.375744 0.910181 0.174320 -v -0.030300 -0.118696 0.119269 -vn -0.375747 0.910180 0.174320 -v -0.034200 -0.118696 0.119269 -vn 0.375748 0.926458 0.022132 -v -0.030300 -0.118503 0.117463 -vn -0.375750 0.926457 0.022132 -v -0.034200 -0.118503 0.117463 -vn 0.375747 0.917465 -0.130661 -v -0.030300 -0.118610 0.115649 -vn -0.375750 0.917464 -0.130660 -v -0.034200 -0.118610 0.115649 -vn 0.375747 0.883446 -0.279888 -v -0.030300 -0.119014 0.113878 -vn -0.375750 0.883445 -0.279887 -v -0.034200 -0.119014 0.113878 -vn 0.375748 0.825329 -0.421480 -v -0.030300 -0.119704 0.112197 -vn -0.375750 0.825328 -0.421479 -v -0.034200 -0.119704 0.112197 -vn 0.375750 0.744698 -0.551577 -v -0.030300 -0.120661 0.110653 -vn -0.375753 0.744697 -0.551577 -v -0.034200 -0.120661 0.110653 -vn 0.375747 0.643755 -0.666629 -v -0.030300 -0.121859 0.109287 -vn -0.375749 0.643755 -0.666628 -v -0.034200 -0.121859 0.109287 -vn 0.371085 0.530225 -0.762337 -v -0.030300 -0.123265 0.108137 -vn -0.375749 0.525252 -0.763494 -v -0.034200 -0.123265 0.108137 -vn 0.374422 0.390854 -0.840858 -v -0.030300 -0.124842 0.107235 -vn -0.375748 0.392422 -0.839535 -v -0.034200 -0.124842 0.107235 -vn 0.375747 0.248888 -0.892675 -v -0.030300 -0.126546 0.106604 -vn -0.375750 0.248887 -0.892674 -v -0.034200 -0.126546 0.106604 -vn 0.375748 0.098564 -0.921465 -v -0.030300 -0.128330 0.106262 -vn -0.375750 0.098563 -0.921465 -v -0.034200 -0.128330 0.106262 -vn 0.375748 -0.054450 -0.925121 -v -0.030300 -0.130146 0.106219 -vn -0.375751 -0.054450 -0.925120 -v -0.034200 -0.130146 0.106219 -vn 0.375748 -0.205978 -0.903541 -v -0.030300 -0.131945 0.106475 -vn -0.375750 -0.205978 -0.903540 -v -0.034200 -0.131945 0.106475 -vn 0.375741 -0.351887 -0.857318 -v -0.030300 -0.133677 0.107024 -vn -0.375744 -0.351885 -0.857318 -v -0.034200 -0.133677 0.107024 -vn 0.375746 -0.488196 -0.787705 -v -0.030300 -0.135295 0.107850 -vn -0.375749 -0.488197 -0.787703 -v -0.034200 -0.135295 0.107850 -vn 0.375742 -0.611192 -0.696608 -v -0.030300 -0.136755 0.108931 -vn -0.375744 -0.611190 -0.696608 -v -0.034200 -0.136755 0.108931 -vn 0.375752 -0.717510 -0.586507 -v -0.030300 -0.138017 0.110238 -vn -0.375754 -0.717510 -0.586505 -v -0.034200 -0.138017 0.110238 -vn 0.375746 -0.804263 -0.460409 -v -0.030300 -0.139046 0.111735 -vn -0.375749 -0.804261 -0.460409 -v -0.034200 -0.139046 0.111735 -vn 0.375744 -0.869074 -0.321755 -v -0.030300 -0.139816 0.113381 -vn -0.375747 -0.869073 -0.321754 -v -0.034200 -0.139816 0.113381 -vn 0.375744 -0.910181 -0.174322 -v -0.030300 -0.140304 0.115131 -vn -0.375746 -0.910179 -0.174322 -v -0.034200 -0.140304 0.115131 -vn 0.375747 -0.926458 -0.022131 -v -0.030300 -0.140497 0.116937 -vn -0.375750 -0.926457 -0.022129 -v -0.034200 -0.140497 0.116937 -vn 0.375742 -0.917467 0.130662 -v -0.030300 -0.140390 0.118751 -vn -0.375744 -0.917466 0.130660 -v -0.034200 -0.140390 0.118751 -vn 0.375752 -0.883445 0.279885 -v -0.030300 -0.139986 0.120522 -vn -0.375754 -0.883444 0.279886 -v -0.034200 -0.139986 0.120522 -vn 0.375748 -0.825329 0.421480 -v -0.030300 -0.139296 0.122203 -vn -0.371560 -0.828954 0.418065 -v -0.034200 -0.139296 0.122203 -vn 0.375750 -0.744697 0.551578 -v -0.030300 -0.138339 0.123747 -vn -0.375754 -0.744695 0.551578 -v -0.034200 -0.138339 0.123747 -vn 0.375739 -0.643755 0.666633 -v -0.030300 -0.137141 0.125113 -vn -0.976003 -0.156642 -0.151267 -v -0.034500 -0.134320 0.123667 -vn -0.976002 -0.060023 -0.209327 -v -0.034500 -0.134775 0.123940 -vn -0.916690 -0.169210 0.362005 -v -0.034500 -0.134031 0.126893 -vn -0.916684 -0.226494 0.329227 -v -0.034500 -0.135565 0.126015 -vn -0.976002 0.052682 -0.211292 -v -0.034500 -0.135305 0.123949 -vn -0.916682 -0.277597 0.287460 -v -0.034500 -0.136933 0.124897 -vn -0.976002 0.151271 -0.156647 -v -0.034500 -0.135769 0.123692 -vn -0.916690 -0.320525 0.238627 -v -0.034500 -0.138098 0.123569 -vn -0.976003 0.209321 -0.060021 -v -0.034500 -0.136043 0.123237 -vn -0.899800 -0.365682 0.237986 -v -0.034500 -0.138673 0.122709 -vn -0.976002 0.211293 0.052681 -v -0.034500 -0.136052 0.122707 -vn -0.976003 0.156642 0.151267 -v -0.034500 -0.135795 0.122243 -vn -0.976002 0.060023 0.209327 -v -0.034500 -0.135340 0.121969 -vn -0.722336 -0.683398 0.105824 -v -0.034500 -0.133958 0.117812 -vn -0.976002 -0.052682 0.211292 -v -0.034500 -0.134809 0.121960 -vn -0.728539 -0.651016 0.213094 -v -0.034500 -0.133799 0.118531 -vn -0.976003 -0.209321 0.060021 -v -0.034500 -0.134072 0.122672 -vn -0.731173 0.160410 0.663064 -v -0.034500 -0.128442 0.121574 -vn -0.731173 -0.009526 0.682126 -v -0.034500 -0.129563 0.121700 -vn -0.916685 -0.107323 0.384928 -v -0.034500 -0.132374 0.127507 -vn -0.916684 -0.042501 0.397345 -v -0.034500 -0.130638 0.127839 -vn -0.916687 0.023479 0.398916 -v -0.034500 -0.128871 0.127881 -vn -0.976002 -0.211294 -0.052681 -v -0.034500 -0.134063 0.123203 -vn -0.976002 0.209325 -0.060024 -v -0.034500 -0.124731 0.123040 -vn -0.976002 0.211292 0.052682 -v -0.034500 -0.124740 0.122509 -vn -0.731172 -0.178865 0.658328 -v -0.034500 -0.130680 0.121543 -vn -0.731173 -0.336964 0.593162 -v -0.034500 -0.131723 0.121113 -vn -0.976002 -0.151271 0.156647 -v -0.034500 -0.134345 0.122217 -vn -0.731173 -0.473893 0.490727 -v -0.034500 -0.132626 0.120437 -vn -0.731173 -0.581042 0.357457 -v -0.034500 -0.133333 0.119558 -vn -0.719459 0.686827 0.103181 -v -0.034500 -0.125025 0.117671 -vn -0.730066 0.645646 0.223929 -v -0.034500 -0.125240 0.118650 -vn -0.976002 0.060024 0.209326 -v -0.034500 -0.124028 0.121772 -vn -0.731170 0.570834 0.373548 -v -0.034500 -0.125735 0.119664 -vn -0.976002 0.156646 0.151271 -v -0.034500 -0.124483 0.122045 -vn -0.731171 0.460006 0.503770 -v -0.034500 -0.126466 0.120523 -vn -0.731171 0.320270 0.602342 -v -0.034500 -0.127387 0.121173 -vn -0.976002 -0.052682 0.211292 -v -0.034500 -0.123497 0.121763 -vn -0.976002 -0.151269 0.156643 -v -0.034500 -0.123033 0.122020 -vn -0.917637 0.355736 0.177185 -v -0.034500 -0.120143 0.122390 -vn -0.976002 -0.209326 0.060024 -v -0.034500 -0.122760 0.122475 -vn -0.976002 0.151269 -0.156643 -v -0.034500 -0.124457 0.123495 -vn -0.916687 0.088819 0.389610 -v -0.034500 -0.127122 0.127632 -vn -0.976002 0.052682 -0.211292 -v -0.034500 -0.123993 0.123752 -vn -0.916687 0.263547 0.300379 -v -0.034500 -0.122443 0.125243 -vn -0.916687 0.309394 0.252905 -v -0.034500 -0.121216 0.123972 -vn -0.976002 -0.211292 -0.052682 -v -0.034500 -0.122751 0.123005 -vn -0.919930 0.332468 0.207830 -v -0.034500 -0.120214 0.122516 -vn -0.976002 -0.156643 -0.151269 -v -0.034500 -0.123008 0.123469 -vn -0.976002 -0.060024 -0.209326 -v -0.034500 -0.123463 0.123743 -vn -0.916684 0.210514 0.339668 -v -0.034500 -0.123863 0.126295 -vn -0.916686 0.151736 0.369680 -v -0.034500 -0.125437 0.127099 -vn -0.976002 0.209327 -0.060023 -v -0.034500 -0.124928 0.111728 -vn -0.976002 0.211292 0.052682 -v -0.034500 -0.124937 0.111197 -vn -0.731172 0.094942 -0.675554 -v -0.034500 -0.128874 0.112744 -vn -0.731172 -0.076043 -0.677941 -v -0.034500 -0.130002 0.112728 -vn -0.976002 0.156647 0.151271 -v -0.034500 -0.124680 0.110733 -vn -0.916686 0.169215 -0.362013 -v -0.034500 -0.124969 0.107507 -vn -0.976002 0.060025 0.209326 -v -0.034500 -0.124225 0.110460 -vn -0.916686 0.226492 -0.329224 -v -0.034500 -0.123435 0.108385 -vn -0.976002 -0.052681 0.211294 -v -0.034500 -0.123695 0.110451 -vn -0.916686 0.277591 -0.287454 -v -0.034500 -0.122067 0.109503 -vn -0.976002 -0.151271 0.156644 -v -0.034500 -0.123231 0.110708 -vn -0.916688 0.321115 -0.237842 -v -0.034500 -0.120902 0.110831 -vn -0.976002 -0.209328 0.060023 -v -0.034500 -0.122957 0.111163 -vn -0.916686 0.355886 -0.181744 -v -0.034500 -0.119971 0.112334 -vn -0.976002 -0.211292 -0.052682 -v -0.034500 -0.122948 0.111693 -vn -0.916686 0.380947 -0.120689 -v -0.034500 -0.119300 0.113968 -vn -0.976002 -0.156647 -0.151271 -v -0.034500 -0.123205 0.112157 -vn -0.916686 0.395616 -0.056341 -v -0.034500 -0.118907 0.115691 -vn -0.720500 0.693207 0.018541 -v -0.034500 -0.125013 0.117545 -vn -0.731172 0.671829 -0.118461 -v -0.034500 -0.125068 0.116419 -vn -0.916687 0.399493 0.009543 -v -0.034500 -0.118803 0.117456 -vn -0.976002 -0.060025 -0.209326 -v -0.034500 -0.123660 0.112431 -vn -0.916685 0.392478 0.075168 -v -0.034500 -0.118991 0.119213 -vn -0.731171 0.259963 -0.630721 -v -0.034500 -0.127785 0.113040 -vn -0.731172 0.408651 -0.546253 -v -0.034500 -0.126804 0.113597 -vn -0.976003 0.151269 -0.156642 -v -0.034500 -0.124655 0.112183 -vn -0.731171 0.531660 -0.427465 -v -0.034500 -0.125993 0.114380 -vn -0.976002 0.052682 -0.211292 -v -0.034500 -0.124191 0.112440 -vn -0.731171 0.621263 -0.281819 -v -0.034500 -0.125402 0.115341 -vn -0.916685 0.374819 0.138562 -v -0.034500 -0.119466 0.120915 -vn -0.916686 0.107321 -0.384927 -v -0.034500 -0.126626 0.106893 -vn -0.916686 0.042500 -0.397341 -v -0.034500 -0.128362 0.106561 -vn -0.916687 -0.023479 -0.398917 -v -0.034500 -0.130129 0.106518 -vn -0.916686 -0.088819 -0.389612 -v -0.034500 -0.131878 0.106768 -vn -0.916683 -0.151737 -0.369686 -v -0.034500 -0.133563 0.107301 -vn -0.976002 0.151271 -0.156647 -v -0.034500 -0.135967 0.112380 -vn -0.976001 0.209330 -0.060029 -v -0.034500 -0.136240 0.111925 -vn -0.916685 -0.374752 -0.138743 -v -0.034500 -0.139534 0.113485 -vn -0.916683 -0.263553 -0.300386 -v -0.034500 -0.136557 0.109157 -vn -0.916689 -0.309391 -0.252900 -v -0.034500 -0.137784 0.110428 -vn -0.976002 0.211291 0.052682 -v -0.034500 -0.136249 0.111395 -vn -0.731172 -0.242252 -0.637732 -v -0.034500 -0.131098 0.112993 -vn -0.976002 -0.211293 -0.052681 -v -0.034500 -0.134260 0.111891 -vn -0.916689 -0.380941 0.120688 -v -0.034500 -0.139700 0.120432 -vn -0.918771 -0.355944 0.170772 -v -0.034500 -0.139029 0.122066 -vn -0.976002 0.052682 -0.211292 -v -0.034500 -0.135503 0.112637 -vn -0.916686 -0.346803 -0.198532 -v -0.034500 -0.138786 0.111884 -vn -0.724822 -0.688854 0.010661 -v -0.034500 -0.133995 0.117420 -vn -0.731173 -0.668258 -0.137172 -v -0.034500 -0.133908 0.116295 -vn -0.976001 0.156647 0.151275 -v -0.034500 -0.135992 0.110931 -vn -0.976001 0.060023 0.209329 -v -0.034500 -0.135537 0.110657 -vn -0.916686 -0.210514 -0.339662 -v -0.034500 -0.135137 0.108105 -vn -0.976002 -0.052682 0.211292 -v -0.034500 -0.135007 0.110648 -vn -0.976002 -0.151271 0.156647 -v -0.034500 -0.134543 0.110905 -vn -0.976003 -0.209321 0.060021 -v -0.034500 -0.134269 0.111360 -vn -0.976002 -0.060023 -0.209327 -v -0.034500 -0.134972 0.112628 -vn -0.731174 -0.613150 -0.299053 -v -0.034500 -0.133545 0.115227 -vn -0.976003 -0.156642 -0.151267 -v -0.034500 -0.134517 0.112355 -vn -0.731174 -0.519513 -0.442145 -v -0.034500 -0.132927 0.114283 -vn -0.731170 -0.393237 -0.557454 -v -0.034500 -0.132094 0.113523 -vn -0.916685 -0.392478 -0.075169 -v -0.034500 -0.140009 0.115187 -vn -0.916686 -0.399493 -0.009542 -v -0.034500 -0.140197 0.116944 -vn -0.916683 -0.395622 0.056342 -v -0.034500 -0.140093 0.118709 -vn -0.375769 -0.722223 0.580682 -v -0.036400 -0.133007 0.120020 -vn -0.411990 -0.782165 0.467421 -v -0.036400 -0.133333 0.119558 -vn -0.381722 -0.838228 0.389439 -v -0.036400 -0.133598 0.119059 -vn -0.410699 -0.874745 0.257191 -v -0.036400 -0.133799 0.118531 -vn -0.381696 -0.908513 0.170038 -v -0.036400 -0.133932 0.117981 -vn -0.411986 -0.910600 0.032798 -v -0.036400 -0.133995 0.117420 -vn -0.381730 -0.922155 -0.062544 -v -0.036400 -0.133987 0.116855 -vn -0.411999 -0.890140 -0.194700 -v -0.036400 -0.133908 0.116295 -vn -0.381725 -0.877632 -0.289912 -v -0.036400 -0.133760 0.115750 -vn -0.390744 -0.827340 -0.403519 -v -0.036400 -0.133545 0.115227 -vn -0.375769 -0.775440 -0.507436 -v -0.036400 -0.133265 0.114736 -vn -0.390745 -0.700995 -0.596594 -v -0.036400 -0.132927 0.114283 -vn -0.375769 -0.624877 -0.684344 -v -0.036400 -0.132534 0.113877 -vn -0.411985 -0.515612 -0.751274 -v -0.036400 -0.132094 0.113523 -vn -0.381719 -0.441306 -0.812120 -v -0.036400 -0.131613 0.113227 -vn -0.411985 -0.312579 -0.855899 -v -0.036400 -0.131098 0.112993 -vn -0.381722 -0.225476 -0.896353 -v -0.036400 -0.130558 0.112826 -vn -0.411988 -0.089906 -0.906743 -v -0.036400 -0.130002 0.112728 -vn -0.381723 0.004523 -0.924266 -v -0.036400 -0.129437 0.112700 -vn -0.411985 0.138412 -0.900617 -v -0.036400 -0.128874 0.112744 -vn -0.381725 0.234236 -0.894103 -v -0.036400 -0.128320 0.112857 -vn -0.411994 0.358044 -0.837894 -v -0.036400 -0.127785 0.113040 -vn -0.381726 0.449232 -0.807760 -v -0.036400 -0.127277 0.113287 -vn -0.390745 0.551399 -0.737073 -v -0.036400 -0.126804 0.113597 -vn -0.375768 0.643752 -0.666620 -v -0.036400 -0.126374 0.113963 -vn -0.411984 0.717415 -0.561769 -v -0.036400 -0.125993 0.114380 -vn -0.381720 0.782808 -0.491428 -v -0.036400 -0.125667 0.114842 -vn -0.390744 0.838282 -0.380266 -v -0.036400 -0.125402 0.115341 -vn -0.375775 0.885266 -0.274038 -v -0.036400 -0.125201 0.115869 -vn -0.390745 0.906516 -0.159835 -v -0.036400 -0.125068 0.116419 -vn -0.375764 0.925609 -0.045271 -v -0.036400 -0.125005 0.116980 -vn -0.412697 0.907261 0.080985 -v -0.036400 -0.125013 0.117545 -vn -0.382864 0.906472 0.178114 -v -0.036400 -0.125092 0.118105 -vn -0.411996 0.858723 0.304722 -v -0.036400 -0.125240 0.118650 -vn -0.381724 0.834371 0.397631 -v -0.036400 -0.125455 0.119173 -vn -0.411983 0.755968 0.508707 -v -0.036400 -0.125735 0.119664 -vn -0.381722 0.709275 0.592635 -v -0.036400 -0.126073 0.120117 -vn -0.411983 0.605710 0.680724 -v -0.036400 -0.126466 0.120523 -vn -0.381723 0.539613 0.750403 -v -0.036400 -0.126906 0.120877 -vn -0.411990 0.417387 0.809970 -v -0.036400 -0.127387 0.121173 -vn -0.381726 0.336039 0.861025 -v -0.036400 -0.127902 0.121407 -vn -0.390745 0.216441 0.894691 -v -0.036400 -0.128442 0.121574 -vn -0.375768 0.103299 0.920938 -v -0.036400 -0.128998 0.121672 -vn -0.411990 -0.024444 0.910861 -v -0.036400 -0.129563 0.121700 -vn -0.381728 -0.120330 0.916409 -v -0.036400 -0.130126 0.121656 -vn -0.411991 -0.250204 0.876163 -v -0.036400 -0.130680 0.121543 -vn -0.381725 -0.344447 0.857696 -v -0.036400 -0.131215 0.121360 -vn -0.390747 -0.454674 0.800368 -v -0.036400 -0.131723 0.121113 -vn -0.375772 -0.555125 0.742045 -v -0.036400 -0.132196 0.120803 -vn -0.377383 -0.643296 0.666147 -v -0.036400 -0.132626 0.120437 -vn -0.917911 -0.313916 0.242687 -v -0.036700 -0.132773 0.119832 -vn -0.746099 0.462528 -0.478962 -v -0.036700 -0.131410 0.119178 -vn -0.746099 0.592985 -0.302827 -v -0.036700 -0.131949 0.118451 -vn -0.746097 0.577852 0.330796 -v -0.036700 -0.131887 0.115834 -vn -0.915384 -0.383613 -0.122123 -v -0.036700 -0.133476 0.115846 -vn -0.746099 0.653949 0.125248 -v -0.036700 -0.132201 0.116683 -vn -0.915182 -0.402245 -0.025318 -v -0.036700 -0.133688 0.116878 -vn -0.746099 0.659184 -0.093876 -v -0.036700 -0.132223 0.117588 -vn -0.915179 -0.395911 0.075512 -v -0.036700 -0.133636 0.117929 -vn -0.915176 -0.364699 0.171604 -v -0.036700 -0.133325 0.118935 -vn -0.746097 0.039121 0.664686 -v -0.036700 -0.129662 0.114455 -vn -0.915177 -0.100225 -0.390391 -v -0.036700 -0.130488 0.113118 -vn -0.746099 0.252821 0.615969 -v -0.036700 -0.130544 0.114656 -vn -0.915175 -0.194166 -0.353204 -v -0.036700 -0.131472 0.113492 -vn -0.746101 0.439130 0.500498 -v -0.036700 -0.131314 0.115133 -vn -0.917664 -0.266167 -0.295039 -v -0.036700 -0.132332 0.114098 -vn -0.917884 -0.332068 -0.217300 -v -0.036700 -0.133014 0.114900 -vn -0.746100 -0.535055 0.396296 -v -0.036700 -0.127290 0.115563 -vn -0.917664 0.277743 -0.284169 -v -0.036700 -0.126582 0.114179 -vn -0.746097 -0.377388 0.548559 -v -0.036700 -0.127941 0.114934 -vn -0.915386 0.191841 -0.353928 -v -0.036700 -0.127425 0.113548 -vn -0.746099 -0.178821 0.641373 -v -0.036700 -0.128761 0.114551 -vn -0.915179 0.100242 -0.390383 -v -0.036700 -0.128399 0.113147 -vn -0.915177 0.000009 -0.403052 -v -0.036700 -0.129441 0.113000 -vn -0.918426 -0.274802 0.284565 -v -0.036700 -0.132418 0.120221 -vn -0.918144 -0.233197 0.320360 -v -0.036700 -0.132016 0.120563 -vn -0.746099 0.281949 -0.603193 -v -0.036700 -0.130664 0.119691 -vn -0.915385 -0.145971 0.375183 -v -0.036700 -0.131100 0.121083 -vn -0.746099 0.070816 -0.662058 -v -0.036700 -0.129792 0.119934 -vn -0.915179 -0.050525 0.399868 -v -0.036700 -0.130085 0.121359 -vn -0.746099 -0.147991 -0.649181 -v -0.036700 -0.128889 0.119881 -vn -0.746098 -0.624416 -0.231176 -v -0.036700 -0.126921 0.118155 -vn -0.915181 0.395902 0.075533 -v -0.036700 -0.125386 0.118045 -vn -0.746101 -0.665643 -0.015900 -v -0.036700 -0.126751 0.117266 -vn -0.917662 0.396997 -0.017023 -v -0.036700 -0.125305 0.116995 -vn -0.746097 -0.634744 0.201096 -v -0.036700 -0.126878 0.116369 -vn -0.917887 0.379095 -0.117350 -v -0.036700 -0.125488 0.115958 -vn -0.915384 0.338625 -0.217729 -v -0.036700 -0.125923 0.114999 -vn -0.917664 0.041916 0.395140 -v -0.036700 -0.129032 0.121374 -vn -0.915387 0.150417 0.373419 -v -0.036700 -0.128009 0.121126 -vn -0.746099 -0.350764 -0.565951 -v -0.036700 -0.128051 0.119537 -vn -0.915179 0.236897 0.326079 -v -0.036700 -0.127079 0.120632 -vn -0.746099 -0.515524 -0.421393 -v -0.036700 -0.127371 0.118940 -vn -0.915177 0.310549 0.256923 -v -0.036700 -0.126302 0.119922 -vn -0.915176 0.364690 0.171620 -v -0.036700 -0.125725 0.119041 -vn -0.671869 0.514512 -0.532794 -v -0.033000 -0.131410 0.119178 -vn -0.671869 0.313638 -0.670987 -v -0.033000 -0.130664 0.119691 -vn -0.671869 0.078775 -0.736469 -v -0.033000 -0.129792 0.119934 -vn -0.671869 -0.164624 -0.722144 -v -0.033000 -0.128889 0.119881 -vn -0.671868 -0.390187 -0.629561 -v -0.033000 -0.128051 0.119537 -vn -0.671868 -0.573465 -0.468755 -v -0.033000 -0.127371 0.118940 -vn -0.671869 -0.694595 -0.257158 -v -0.033000 -0.126921 0.118155 -vn -0.671866 -0.740461 -0.017687 -v -0.033000 -0.126751 0.117266 -vn -0.671869 -0.706082 0.223697 -v -0.033000 -0.126878 0.116369 -vn -0.671867 -0.595194 0.440839 -v -0.033000 -0.127290 0.115563 -vn -0.671869 -0.419802 0.610211 -v -0.033000 -0.127941 0.114934 -vn -0.671868 -0.198919 0.713460 -v -0.033000 -0.128761 0.114551 -vn -0.671870 0.043518 0.739390 -v -0.033000 -0.129662 0.114455 -vn -0.671868 0.281236 0.685200 -v -0.033000 -0.130544 0.114656 -vn -0.671867 0.488488 0.556753 -v -0.033000 -0.131314 0.115133 -vn -0.671870 0.642795 0.367973 -v -0.033000 -0.131887 0.115834 -vn -0.671868 0.727449 0.139326 -v -0.033000 -0.132201 0.116683 -vn -0.671868 0.733272 -0.104427 -v -0.033000 -0.132223 0.117588 -vn -0.671868 0.659633 -0.336863 -v -0.033000 -0.131949 0.118451 -vn -0.765145 0.635240 0.104991 -v -0.033000 -0.130733 0.116996 -vn -0.765147 0.611267 -0.202246 -v -0.033000 -0.130687 0.117593 -vn -0.765145 0.447262 -0.463152 -v -0.033000 -0.130368 0.118099 -vn -0.765146 0.180794 -0.617953 -v -0.033000 -0.129851 0.118400 -vn -0.765143 -0.323427 0.556732 -v -0.033000 -0.128872 0.116119 -vn -0.765147 -0.027657 0.643261 -v -0.033000 -0.129446 0.115951 -vn -0.765148 0.274457 0.582428 -v -0.033000 -0.130033 0.116069 -vn -0.765144 0.513691 0.388171 -v -0.033000 -0.130497 0.116446 -vn -0.765144 -0.641908 0.050084 -v -0.033000 -0.128254 0.117103 -vn -0.765147 -0.545102 0.342658 -v -0.033000 -0.128442 0.116535 -vn -0.765145 -0.405867 -0.499825 -v -0.033000 -0.128712 0.118170 -vn -0.765145 -0.591657 -0.253960 -v -0.033000 -0.128351 0.117693 -vn -0.765147 -0.127095 -0.631187 -v -0.033000 -0.129253 0.118425 -vn 0.765145 0.447262 -0.463152 -v -0.031500 -0.130368 0.118099 -vn 0.765146 0.180794 -0.617953 -v -0.031500 -0.129851 0.118400 -vn 0.765147 -0.127095 -0.631187 -v -0.031500 -0.129253 0.118425 -vn 0.765146 -0.405865 -0.499826 -v -0.031500 -0.128712 0.118170 -vn 0.765146 -0.591655 -0.253960 -v -0.031500 -0.128351 0.117693 -vn 0.765146 -0.641906 0.050084 -v -0.031500 -0.128254 0.117103 -vn 0.765148 -0.545100 0.342658 -v -0.031500 -0.128442 0.116535 -vn 0.765143 -0.323427 0.556733 -v -0.031500 -0.128872 0.116119 -vn 0.765147 -0.027657 0.643261 -v -0.031500 -0.129446 0.115951 -vn 0.765148 0.274457 0.582428 -v -0.031500 -0.130033 0.116069 -vn 0.765144 0.513691 0.388171 -v -0.031500 -0.130497 0.116446 -vn 0.765145 0.635240 0.104991 -v -0.031500 -0.130733 0.116996 -vn 0.765147 0.611267 -0.202246 -v -0.031500 -0.130687 0.117593 -vn -0.539397 0.203711 -0.817039 -v -0.034370 -0.135251 0.123731 -vn -0.539396 -0.232100 -0.809433 -v -0.034370 -0.134837 0.123724 -vn -0.539400 -0.605718 -0.584939 -v -0.034370 -0.134482 0.123510 -vn -0.539398 -0.817039 -0.203709 -v -0.034370 -0.134281 0.123148 -vn -0.539402 -0.809430 0.232097 -v -0.034370 -0.134288 0.122734 -vn -0.539397 -0.584937 0.605722 -v -0.034370 -0.134502 0.122379 -vn -0.539397 -0.203711 0.817039 -v -0.034370 -0.134864 0.122178 -vn -0.539396 0.232100 0.809433 -v -0.034370 -0.135278 0.122186 -vn -0.539400 0.605718 0.584939 -v -0.034370 -0.135633 0.122399 -vn -0.539398 0.817039 0.203709 -v -0.034370 -0.135833 0.122761 -vn -0.539402 0.809430 -0.232097 -v -0.034370 -0.135826 0.123175 -vn -0.539397 0.584937 -0.605722 -v -0.034370 -0.135613 0.123530 -vn 0.539396 -0.584939 0.605721 -v -0.030130 -0.134502 0.122379 -vn 0.539402 -0.809429 0.232101 -v -0.030130 -0.134288 0.122734 -vn 0.539398 -0.817038 -0.203711 -v -0.030130 -0.134281 0.123148 -vn 0.539400 -0.605719 -0.584937 -v -0.030130 -0.134482 0.123510 -vn 0.539396 -0.232099 -0.809433 -v -0.030130 -0.134837 0.123724 -vn 0.539397 0.203710 -0.817039 -v -0.030130 -0.135251 0.123731 -vn 0.539396 0.584939 -0.605721 -v -0.030130 -0.135613 0.123530 -vn 0.539402 0.809429 -0.232101 -v -0.030130 -0.135826 0.123175 -vn 0.539398 0.817038 0.203711 -v -0.030130 -0.135833 0.122761 -vn 0.539400 0.605719 0.584937 -v -0.030130 -0.135633 0.122399 -vn 0.539396 0.232099 0.809433 -v -0.030130 -0.135278 0.122186 -vn 0.539397 -0.203710 0.817039 -v -0.030130 -0.134864 0.122178 -vn -0.539397 0.203711 -0.817039 -v -0.034370 -0.135448 0.112419 -vn -0.539396 -0.232100 -0.809433 -v -0.034370 -0.135034 0.112412 -vn -0.539400 -0.605718 -0.584939 -v -0.034370 -0.134679 0.112198 -vn -0.539398 -0.817039 -0.203709 -v -0.034370 -0.134478 0.111836 -vn -0.539402 -0.809430 0.232097 -v -0.034370 -0.134486 0.111422 -vn -0.539397 -0.584937 0.605722 -v -0.034370 -0.134699 0.111067 -vn -0.539397 -0.203711 0.817039 -v -0.034370 -0.135061 0.110866 -vn -0.539395 0.232092 0.809436 -v -0.034370 -0.135475 0.110874 -vn -0.539393 0.605719 0.584944 -v -0.034370 -0.135830 0.111087 -vn -0.539396 0.817039 0.203713 -v -0.034370 -0.136031 0.111449 -vn -0.539393 0.809431 -0.232115 -v -0.034370 -0.136024 0.111863 -vn -0.539392 0.584933 -0.605731 -v -0.034370 -0.135810 0.112218 -vn 0.539396 -0.584939 0.605721 -v -0.030130 -0.134699 0.111067 -vn 0.539402 -0.809429 0.232101 -v -0.030130 -0.134486 0.111422 -vn 0.539398 -0.817038 -0.203711 -v -0.030130 -0.134478 0.111836 -vn 0.539400 -0.605719 -0.584937 -v -0.030130 -0.134679 0.112198 -vn 0.539396 -0.232099 -0.809433 -v -0.030130 -0.135034 0.112412 -vn 0.539397 0.203710 -0.817039 -v -0.030130 -0.135448 0.112419 -vn 0.539394 0.584931 -0.605732 -v -0.030130 -0.135810 0.112218 -vn 0.539393 0.809432 -0.232110 -v -0.030130 -0.136024 0.111863 -vn 0.539396 0.817040 0.203708 -v -0.030130 -0.136031 0.111449 -vn 0.539393 0.605716 0.584947 -v -0.030130 -0.135830 0.111087 -vn 0.539393 0.232094 0.809436 -v -0.030130 -0.135475 0.110874 -vn 0.539397 -0.203710 0.817039 -v -0.030130 -0.135061 0.110866 -vn -0.539399 0.203715 -0.817036 -v -0.034370 -0.124136 0.112222 -vn -0.539397 -0.232106 -0.809430 -v -0.034370 -0.123722 0.112214 -vn -0.539394 -0.605727 -0.584935 -v -0.034370 -0.123367 0.112001 -vn -0.539397 -0.817039 -0.203711 -v -0.034370 -0.123166 0.111639 -vn -0.539395 -0.809435 0.232096 -v -0.034370 -0.123174 0.111225 -vn -0.539397 -0.584941 0.605718 -v -0.034370 -0.123387 0.110870 -vn -0.539396 -0.203712 0.817040 -v -0.034370 -0.123749 0.110669 -vn -0.539397 0.232106 0.809430 -v -0.034370 -0.124163 0.110676 -vn -0.539394 0.605727 0.584935 -v -0.034370 -0.124518 0.110890 -vn -0.539397 0.817039 0.203711 -v -0.034370 -0.124719 0.111252 -vn -0.539396 0.809433 -0.232100 -v -0.034370 -0.124712 0.111666 -vn -0.539399 0.584944 -0.605714 -v -0.034370 -0.124498 0.112021 -vn 0.539396 -0.584942 0.605718 -v -0.030130 -0.123387 0.110870 -vn 0.539395 -0.809435 0.232096 -v -0.030130 -0.123174 0.111225 -vn 0.539397 -0.817039 -0.203710 -v -0.030130 -0.123166 0.111639 -vn 0.539395 -0.605726 -0.584935 -v -0.030130 -0.123367 0.112001 -vn 0.539397 -0.232106 -0.809430 -v -0.030130 -0.123722 0.112214 -vn 0.539398 0.203716 -0.817037 -v -0.030130 -0.124136 0.112222 -vn 0.539399 0.584943 -0.605715 -v -0.030130 -0.124498 0.112021 -vn 0.539396 0.809433 -0.232099 -v -0.030130 -0.124712 0.111666 -vn 0.539397 0.817039 0.203710 -v -0.030130 -0.124719 0.111252 -vn 0.539395 0.605726 0.584935 -v -0.030130 -0.124518 0.110890 -vn 0.539397 0.232106 0.809430 -v -0.030130 -0.124163 0.110676 -vn 0.539396 -0.203712 0.817040 -v -0.030130 -0.123749 0.110669 -vn -0.539399 0.203715 -0.817036 -v -0.034370 -0.123939 0.123534 -vn -0.539397 -0.232106 -0.809430 -v -0.034370 -0.123525 0.123526 -vn -0.539398 -0.605719 -0.584940 -v -0.034370 -0.123170 0.123313 -vn -0.539399 -0.817036 -0.203715 -v -0.034370 -0.122969 0.122951 -vn -0.539397 -0.809430 0.232106 -v -0.034370 -0.122976 0.122537 -vn -0.539398 -0.584940 0.605719 -v -0.034370 -0.123190 0.122182 -vn -0.539399 -0.203715 0.817036 -v -0.034370 -0.123552 0.121981 -vn -0.539396 0.232102 0.809432 -v -0.034370 -0.123966 0.121988 -vn -0.539395 0.605724 0.584937 -v -0.034370 -0.124321 0.122202 -vn -0.539397 0.817039 0.203711 -v -0.034370 -0.124522 0.122564 -vn -0.539397 0.809430 -0.232106 -v -0.034370 -0.124514 0.122978 -vn -0.539398 0.584940 -0.605719 -v -0.034370 -0.124301 0.123333 -vn 0.539397 -0.584938 0.605721 -v -0.030130 -0.123190 0.122182 -vn 0.539398 -0.809430 0.232105 -v -0.030130 -0.122976 0.122537 -vn 0.539399 -0.817037 -0.203716 -v -0.030130 -0.122969 0.122951 -vn 0.539397 -0.605721 -0.584938 -v -0.030130 -0.123170 0.123313 -vn 0.539398 -0.232105 -0.809430 -v -0.030130 -0.123525 0.123526 -vn 0.539398 0.203716 -0.817037 -v -0.030130 -0.123939 0.123534 -vn 0.539397 0.584938 -0.605721 -v -0.030130 -0.124301 0.123333 -vn 0.539398 0.809430 -0.232105 -v -0.030130 -0.124514 0.122978 -vn 0.539397 0.817039 0.203710 -v -0.030130 -0.124522 0.122564 -vn 0.539396 0.605723 0.584938 -v -0.030130 -0.124321 0.122202 -vn 0.539396 0.232102 0.809432 -v -0.030130 -0.123966 0.121988 -vn 0.539398 -0.203716 0.817037 -v -0.030130 -0.123552 0.121981 -vn -0.577350 -0.577350 -0.577350 -v -0.011250 0.092500 0.133950 -vn -0.577350 -0.577350 0.577350 -v -0.011250 0.092500 0.145450 -vn -0.904534 -0.301512 -0.301512 -v -0.011250 0.094000 0.133950 -vn -0.904534 -0.301511 0.301511 -v -0.011250 0.094000 0.145450 -vn -0.678874 -0.727973 0.095842 -v -0.011250 0.094000 0.151700 -vn -0.770263 0.637727 0.000002 -v -0.011250 0.095500 0.150100 -vn -0.770262 -0.552292 0.318859 -v -0.011250 0.097366 0.149600 -vn -0.770262 -0.000003 -0.637728 -v -0.011250 0.138500 0.149950 -vn -0.770267 -0.318856 0.552285 -v -0.011250 0.097000 0.149234 -vn -0.770261 0.318862 -0.552291 -v -0.011250 0.138000 0.149816 -vn -0.770254 -0.000000 0.637737 -v -0.011250 0.096500 0.149100 -vn -0.770263 -0.000003 0.637727 -v -0.011250 0.138500 0.129450 -vn -0.770260 -0.637730 0.000002 -v -0.011250 0.097500 0.129300 -vn -0.770263 0.318867 0.552286 -v -0.011250 0.138000 0.129584 -vn -0.770258 0.552294 0.318862 -v -0.011250 0.137634 0.129950 -vn -0.770260 0.552291 0.318865 -v -0.011250 0.095634 0.149600 -vn -0.770267 0.318856 0.552286 -v -0.011250 0.096000 0.149234 -vn -0.770264 0.637726 0.000002 -v -0.011250 0.137500 0.130450 -vn -0.770265 -0.552286 -0.318861 -v -0.011250 0.097366 0.129800 -vn -0.770260 -0.318863 -0.552291 -v -0.011250 0.097000 0.130166 -vn -0.678874 -0.727973 -0.095839 -v -0.011250 0.094000 0.127700 -vn -0.770260 0.552291 0.318865 -v -0.011250 0.095634 0.128800 -vn -0.653226 -0.655721 -0.378585 -v -0.011250 0.094134 0.127200 -vn -0.770263 0.318866 0.552285 -v -0.011250 0.096000 0.128434 -vn -0.653228 -0.378578 -0.655722 -v -0.011250 0.094500 0.126834 -vn -0.678874 -0.095840 -0.727973 -v -0.011250 0.095000 0.126700 -vn -0.770263 0.000000 0.637727 -v -0.011250 0.096500 0.128300 -vn -0.770263 -0.318867 0.552285 -v -0.011250 0.097000 0.128434 -vn -0.689865 0.056801 -0.721706 -v -0.011250 0.136000 0.126700 -vn -0.770262 -0.552292 0.318859 -v -0.011250 0.097366 0.128800 -vn -0.673533 0.597992 -0.434464 -v -0.011250 0.140045 0.128761 -vn -0.770261 -0.552288 0.318866 -v -0.011250 0.139366 0.129950 -vn -0.673534 0.702980 -0.228411 -v -0.011250 0.140755 0.130155 -vn -0.770262 -0.637727 0.000002 -v -0.011250 0.139500 0.130450 -vn -0.689866 0.721705 -0.056800 -v -0.011250 0.141000 0.131700 -vn -0.770265 -0.552283 -0.318868 -v -0.011250 0.139366 0.130950 -vn -0.689866 0.721705 0.056800 -v -0.011250 0.141000 0.147700 -vn -0.770258 -0.318862 -0.552294 -v -0.011250 0.139000 0.131316 -vn -0.673533 0.434463 -0.597993 -v -0.011250 0.138939 0.127655 -vn -0.770261 -0.318866 0.552288 -v -0.011250 0.139000 0.129584 -vn -0.673535 0.228410 -0.702979 -v -0.011250 0.137545 0.126945 -vn -0.653226 -0.378586 0.655720 -v -0.011250 0.094500 0.152566 -vn -0.678874 -0.095841 0.727973 -v -0.011250 0.095000 0.152700 -vn -0.653228 -0.655721 0.378579 -v -0.011250 0.094134 0.152200 -vn -0.770260 0.318862 -0.552291 -v -0.011250 0.096000 0.150966 -vn -0.770263 0.552285 -0.318866 -v -0.011250 0.095634 0.150600 -vn -0.770262 0.552289 -0.318864 -v -0.011250 0.137634 0.149450 -vn -0.770263 0.637727 0.000002 -v -0.011250 0.137500 0.148950 -vn -0.770258 0.552294 0.318862 -v -0.011250 0.137634 0.148450 -vn -0.770262 0.318863 -0.552289 -v -0.011250 0.138000 0.131316 -vn -0.770265 0.318867 0.552283 -v -0.011250 0.138000 0.148084 -vn -0.770263 -0.000003 -0.637727 -v -0.011250 0.138500 0.131450 -vn -0.770263 -0.000003 0.637726 -v -0.011250 0.138500 0.147950 -vn -0.770261 -0.318866 0.552288 -v -0.011250 0.139000 0.148084 -vn -0.770261 -0.552288 0.318866 -v -0.011250 0.139366 0.148450 -vn -0.673534 0.702980 0.228411 -v -0.011250 0.140755 0.149245 -vn -0.770262 -0.637727 0.000002 -v -0.011250 0.139500 0.148950 -vn -0.673533 0.597992 0.434465 -v -0.011250 0.140045 0.150639 -vn -0.770263 0.000000 -0.637727 -v -0.011250 0.096500 0.130300 -vn -0.770262 0.552289 -0.318864 -v -0.011250 0.137634 0.130950 -vn -0.770261 0.318862 -0.552291 -v -0.011250 0.096000 0.130166 -vn -0.770263 0.552285 -0.318866 -v -0.011250 0.095634 0.129800 -vn -0.770263 0.637727 0.000002 -v -0.011250 0.095500 0.129300 -vn -0.770259 -0.637731 0.000002 -v -0.011250 0.097500 0.150100 -vn -0.770265 -0.552286 -0.318861 -v -0.011250 0.097366 0.150600 -vn -0.689865 0.056801 0.721706 -v -0.011250 0.136000 0.152700 -vn -0.770260 -0.318863 -0.552291 -v -0.011250 0.097000 0.150966 -vn -0.770263 0.000000 -0.637727 -v -0.011250 0.096500 0.151100 -vn -0.770265 -0.552283 -0.318868 -v -0.011250 0.139366 0.149450 -vn -0.770258 -0.318862 -0.552294 -v -0.011250 0.139000 0.149816 -vn -0.673533 0.434465 0.597990 -v -0.011250 0.138939 0.151745 -vn -0.673534 0.228413 0.702979 -v -0.011250 0.137545 0.152455 -vn 0.904534 -0.301511 -0.301511 -v 0.010750 0.094000 0.133950 -vn 0.678875 -0.727973 -0.095839 -v 0.010750 0.094000 0.127700 -vn 0.770262 0.637727 0.000002 -v 0.010750 0.095500 0.129300 -vn 0.577350 -0.577350 0.577350 -v 0.010750 0.092500 0.145450 -vn 0.577350 -0.577350 -0.577350 -v 0.010750 0.092500 0.133950 -vn 0.904534 -0.301511 0.301512 -v 0.010750 0.094000 0.145450 -vn 0.770262 -0.000000 0.637727 -v 0.010750 0.096500 0.128300 -vn 0.770263 0.318867 0.552285 -v 0.010750 0.096000 0.128434 -vn 0.678874 -0.095840 -0.727973 -v 0.010750 0.095000 0.126700 -vn 0.770260 0.318864 -0.552291 -v 0.010750 0.096000 0.150966 -vn 0.770262 -0.000000 -0.637727 -v 0.010750 0.096500 0.151100 -vn 0.678874 -0.095840 0.727973 -v 0.010750 0.095000 0.152700 -vn 0.770260 -0.318863 -0.552292 -v 0.010750 0.097000 0.150966 -vn -0.003385 0.076048 0.997098 -v 0.010750 0.136000 0.152700 -vn 0.770265 -0.552286 -0.318861 -v 0.010750 0.097366 0.150600 -vn 0.770260 -0.637730 0.000002 -v 0.010750 0.097500 0.150100 -vn 0.770260 -0.637729 0.000002 -v 0.010750 0.097500 0.129300 -vn 0.770258 0.552294 0.318862 -v 0.010750 0.137634 0.129950 -vn 0.770262 0.637727 0.000002 -v 0.010750 0.137500 0.130450 -vn 0.770260 0.318864 -0.552291 -v 0.010750 0.096000 0.130166 -vn 0.770263 -0.000000 -0.637727 -v 0.010750 0.096500 0.130300 -vn 0.770266 0.318858 0.552286 -v 0.010750 0.096000 0.149234 -vn 0.770260 0.552291 0.318864 -v 0.010750 0.095634 0.149600 -vn 0.653228 -0.378578 -0.655722 -v 0.010750 0.094500 0.126834 -vn 0.653226 -0.655721 -0.378585 -v 0.010750 0.094134 0.127200 -vn 0.770260 0.552292 0.318863 -v 0.010750 0.095634 0.128800 -vn 0.770262 0.552288 -0.318864 -v 0.010750 0.137634 0.130950 -vn 0.770262 0.318864 -0.552288 -v 0.010750 0.138000 0.131316 -vn 0.770258 0.552294 0.318862 -v 0.010750 0.137634 0.148450 -vn 0.770262 0.637727 0.000002 -v 0.010750 0.137500 0.148950 -vn 0.770262 0.552288 -0.318864 -v 0.010750 0.137634 0.149450 -vn 0.678874 -0.727973 0.095842 -v 0.010750 0.094000 0.151700 -vn 0.770262 0.637727 0.000002 -v 0.010750 0.095500 0.150100 -vn 0.770263 0.552286 -0.318865 -v 0.010750 0.095634 0.150600 -vn 0.653228 -0.655721 0.378579 -v 0.010750 0.094134 0.152200 -vn 0.653226 -0.378586 0.655720 -v 0.010750 0.094500 0.152566 -vn -0.006827 0.808999 0.587770 -v 0.010750 0.140045 0.150639 -vn -0.006827 0.587771 0.808998 -v 0.010750 0.138939 0.151745 -vn 0.770263 -0.000002 -0.637727 -v 0.010750 0.138500 0.149950 -vn -0.006826 0.309012 0.951034 -v 0.010750 0.137545 0.152455 -vn 0.770264 0.318864 -0.552286 -v 0.010750 0.138000 0.149816 -vn -0.003384 0.997099 0.076047 -v 0.010750 0.141000 0.147700 -vn 0.770258 -0.318862 -0.552294 -v 0.010750 0.139000 0.131316 -vn -0.003384 0.997099 -0.076047 -v 0.010750 0.141000 0.131700 -vn 0.770265 -0.552283 -0.318868 -v 0.010750 0.139366 0.130950 -vn -0.006827 0.951035 -0.309009 -v 0.010750 0.140755 0.130155 -vn 0.770263 -0.637727 0.000002 -v 0.010750 0.139500 0.130450 -vn -0.006827 0.808999 -0.587770 -v 0.010750 0.140045 0.128761 -vn 0.770263 0.552286 -0.318865 -v 0.010750 0.095634 0.129800 -vn 0.770255 0.000000 0.637736 -v 0.010750 0.096500 0.149100 -vn 0.770266 -0.318857 0.552286 -v 0.010750 0.097000 0.149234 -vn 0.770259 -0.318864 -0.552293 -v 0.010750 0.097000 0.130166 -vn 0.770261 -0.552292 0.318859 -v 0.010750 0.097366 0.149600 -vn 0.770265 -0.552286 -0.318861 -v 0.010750 0.097366 0.129800 -vn 0.770263 -0.318867 0.552286 -v 0.010750 0.097000 0.128434 -vn -0.003385 0.076048 -0.997098 -v 0.010750 0.136000 0.126700 -vn 0.770261 -0.552292 0.318859 -v 0.010750 0.097366 0.128800 -vn 0.770263 -0.000002 0.637727 -v 0.010750 0.138500 0.129450 -vn 0.770266 0.318868 0.552279 -v 0.010750 0.138000 0.129584 -vn 0.770261 -0.552288 0.318866 -v 0.010750 0.139366 0.129950 -vn 0.770261 -0.318866 0.552288 -v 0.010750 0.139000 0.129584 -vn -0.006826 0.587768 -0.809000 -v 0.010750 0.138939 0.127655 -vn -0.006827 0.309008 -0.951035 -v 0.010750 0.137545 0.126945 -vn 0.770258 -0.318862 -0.552294 -v 0.010750 0.139000 0.149816 -vn 0.770265 -0.552283 -0.318868 -v 0.010750 0.139366 0.149450 -vn -0.006828 0.951035 0.309009 -v 0.010750 0.140755 0.149245 -vn 0.770263 -0.637727 0.000002 -v 0.010750 0.139500 0.148950 -vn 0.770261 -0.552288 0.318866 -v 0.010750 0.139366 0.148450 -vn 0.770261 -0.318866 0.552288 -v 0.010750 0.139000 0.148084 -vn 0.770263 -0.000002 -0.637727 -v 0.010750 0.138500 0.131450 -vn 0.770262 -0.000002 0.637727 -v 0.010750 0.138500 0.147950 -vn 0.770265 0.318868 0.552282 -v 0.010750 0.138000 0.148084 -vn -1.000000 0.000000 -0.000000 -v -0.016250 0.092125 0.150450 -vn -0.923880 -0.382683 -0.000000 -v -0.016250 0.092000 0.150450 -vn -0.717284 -0.297108 0.630263 -v -0.016250 0.092000 0.150950 -vn -0.995906 0.003464 0.090324 -v -0.016250 0.136000 0.151200 -vn -0.913025 0.400396 0.077895 -v -0.016250 0.136522 0.151161 -vn -0.913686 0.406421 0.000000 -v -0.016250 0.136522 0.150450 -vn -0.774248 -0.173320 0.608687 -v -0.016250 0.098472 0.149700 -vn -0.487300 -0.619622 0.615311 -v -0.016250 0.098398 0.149654 -vn -0.940157 -0.336739 -0.052067 -v -0.016250 0.098436 0.150330 -vn -0.770264 0.637725 -0.000000 -v -0.016250 0.097500 0.126200 -vn -0.770260 0.552291 0.318865 -v -0.016250 0.097667 0.125575 -vn -1.000000 0.000000 0.000000 -v -0.016250 0.096125 0.124825 -vn -0.707107 0.707107 0.000000 -v -0.016250 0.102000 0.124825 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.099833 0.125575 -vn -0.973781 0.131340 -0.185743 -v -0.016250 0.102000 0.126700 -vn -0.770261 -0.637728 -0.000000 -v -0.016250 0.100000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.099833 0.126825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 0.099375 0.127283 -vn -0.539748 -0.229382 -0.809973 -v -0.016250 0.098409 0.129700 -vn -0.770264 -0.000000 -0.637725 -v -0.016250 0.098750 0.127450 -vn -0.770265 0.318861 0.552286 -v -0.016250 0.098125 0.125117 -vn -0.770258 0.000000 0.637732 -v -0.016250 0.098750 0.124950 -vn -0.770265 -0.318861 0.552287 -v -0.016250 0.099375 0.125117 -vn -0.942584 0.085436 0.322856 -v -0.016250 0.096109 0.127390 -vn -0.934101 -0.003453 0.356991 -v -0.016250 0.096393 0.127353 -vn -0.770262 0.552286 -0.318869 -v -0.016250 0.097667 0.126825 -vn -0.940629 -0.147417 0.305755 -v -0.016250 0.097371 0.127555 -vn -0.770260 0.318866 -0.552291 -v -0.016250 0.098125 0.127283 -vn -0.940311 -0.279984 0.193452 -v -0.016250 0.098120 0.128215 -vn -0.939229 -0.340984 0.039744 -v -0.016250 0.098445 0.129158 -vn -0.707107 -0.707107 0.000000 -v -0.016250 0.095500 0.124825 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 0.095500 0.126700 -vn -0.939248 0.197227 0.280917 -v -0.016250 0.095443 0.127661 -vn -0.816496 -0.408249 -0.408249 -v -0.016250 0.094000 0.126700 -vn -0.941719 0.299948 0.152303 -v -0.016250 0.094771 0.128399 -vn -0.973781 -0.185743 -0.131340 -v -0.016250 0.094000 0.128450 -vn -0.770264 0.637725 0.000000 -v -0.016250 0.092250 0.131700 -vn -0.770261 0.552288 0.318867 -v -0.016250 0.092417 0.131075 -vn -0.707107 0.000000 -0.707107 -v -0.016250 0.092125 0.128450 -vn -0.770261 0.318866 0.552288 -v -0.016250 0.092875 0.130617 -vn -0.770264 -0.000001 0.637726 -v -0.016250 0.093500 0.130450 -vn -0.770261 -0.318867 0.552288 -v -0.016250 0.094125 0.130617 -vn -0.770261 -0.552288 0.318867 -v -0.016250 0.094583 0.131075 -vn -0.770264 -0.637725 0.000000 -v -0.016250 0.094750 0.131700 -vn -0.945213 0.156023 -0.286757 -v -0.016250 0.095568 0.131013 -vn -0.939545 0.015341 -0.342082 -v -0.016250 0.096538 0.131250 -vn -0.770259 -0.552293 -0.318864 -v -0.016250 0.094583 0.132325 -vn -0.770266 -0.318862 -0.552284 -v -0.016250 0.094125 0.132783 -vn -0.973781 -0.185743 0.131340 -v -0.016250 0.094000 0.134950 -vn -0.770258 -0.000001 -0.637732 -v -0.016250 0.093500 0.132950 -vn -0.707107 0.000000 0.707107 -v -0.016250 0.092125 0.134950 -vn -0.770266 0.318861 -0.552284 -v -0.016250 0.092875 0.132783 -vn -0.770259 0.552293 -0.318864 -v -0.016250 0.092417 0.132325 -vn -0.943022 0.280564 -0.178865 -v -0.016250 0.094843 0.130327 -vn -0.942133 0.334875 -0.015657 -v -0.016250 0.094551 0.129372 -vn -0.525142 -0.818541 -0.232842 -v -0.016250 0.097000 0.131185 -vn -0.707107 -0.707107 0.000000 -v -0.016250 0.097000 0.139700 -vn -1.000000 0.000000 0.000000 -v -0.016250 0.096125 0.139700 -vn -0.766703 -0.622392 0.157466 -v -0.016250 0.097000 0.148126 -vn -0.938469 0.035312 0.343555 -v -0.016250 0.096385 0.148153 -vn -0.465187 -0.661099 0.588684 -v -0.016250 0.097057 0.148231 -vn -0.923879 -0.382684 0.000000 -v -0.016250 0.094000 0.139700 -vn -0.973781 -0.185743 -0.131340 -v -0.016250 0.094000 0.144450 -vn -0.770258 -0.000001 -0.637733 -v -0.016250 0.093500 0.148950 -vn -0.770266 0.318862 -0.552284 -v -0.016250 0.092875 0.148783 -vn -0.770258 0.552294 -0.318864 -v -0.016250 0.092417 0.148325 -vn -0.770264 -0.000001 0.637726 -v -0.016250 0.093500 0.146450 -vn -0.770261 0.318866 0.552288 -v -0.016250 0.092875 0.146617 -vn -0.707107 0.000000 -0.707107 -v -0.016250 0.092125 0.144450 -vn -0.770261 0.552288 0.318867 -v -0.016250 0.092417 0.147075 -vn -0.770262 0.637728 -0.000000 -v -0.016250 0.092250 0.147700 -vn -0.717284 -0.630263 0.297108 -v -0.016250 0.095500 0.154700 -vn -0.923880 -0.000000 0.382683 -v -0.016250 0.096125 0.154700 -vn -0.973781 -0.131340 0.185743 -v -0.016250 0.095500 0.152700 -vn -0.949430 0.094217 -0.299510 -v -0.016250 0.096110 0.152011 -vn -0.816496 -0.408249 0.408249 -v -0.016250 0.094000 0.152700 -vn -0.942338 0.183408 -0.279931 -v -0.016250 0.095459 0.151749 -vn -0.940885 0.289289 -0.176205 -v -0.016250 0.094792 0.151042 -vn -0.973781 -0.185743 0.131340 -v -0.016250 0.094000 0.150950 -vn -0.945658 0.316741 -0.073529 -v -0.016250 0.094584 0.150464 -vn -0.707107 0.000000 0.707107 -v -0.016250 0.092125 0.150950 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.099833 0.153825 -vn -0.717284 0.630262 0.297108 -v -0.016250 0.102000 0.154700 -vn -0.770261 -0.637728 -0.000000 -v -0.016250 0.100000 0.153200 -vn -0.973781 0.131340 0.185743 -v -0.016250 0.102000 0.152700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.099833 0.152575 -vn -0.770265 -0.318861 0.552286 -v -0.016250 0.099375 0.152117 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 0.099375 0.154283 -vn -0.770264 0.000000 -0.637725 -v -0.016250 0.098750 0.154450 -vn -0.770258 0.000000 0.637732 -v -0.016250 0.098750 0.151950 -vn -0.770265 0.318861 0.552286 -v -0.016250 0.098125 0.152117 -vn -0.940958 -0.270852 -0.203070 -v -0.016250 0.098085 0.151237 -vn -0.770260 0.552291 0.318866 -v -0.016250 0.097667 0.152575 -vn -0.770260 0.318866 -0.552291 -v -0.016250 0.098125 0.154283 -vn -0.770262 0.552286 -0.318869 -v -0.016250 0.097667 0.153825 -vn -0.770264 0.637725 0.000000 -v -0.016250 0.097500 0.153200 -vn -0.934283 -0.003682 -0.356512 -v -0.016250 0.096385 0.152047 -vn -0.941332 -0.139692 -0.307213 -v -0.016250 0.097339 0.151860 -vn -0.707107 -0.000000 0.707107 -v -0.016250 0.102750 0.149700 -vn -1.000000 -0.000000 0.000000 -v -0.016250 0.102750 0.150450 -vn -0.707107 -0.000000 0.707107 -v -0.016250 0.110750 0.149700 -vn -1.000000 -0.000000 -0.000000 -v -0.016250 0.110750 0.150450 -vn -0.707107 0.000000 0.707107 -v -0.016250 0.118750 0.149700 -vn -1.000000 0.000000 0.000000 -v -0.016250 0.118750 0.150450 -vn -0.534582 0.237790 0.810974 -v -0.016250 0.136522 0.149700 -vn -0.997107 0.040620 0.064242 -v -0.016250 0.127500 0.151200 -vn -0.973781 -0.131340 0.185743 -v -0.016250 0.119500 0.152700 -vn -0.770261 0.552291 0.318862 -v -0.016250 0.121667 0.152575 -vn -0.770265 0.318861 0.552286 -v -0.016250 0.122125 0.152117 -vn -0.770258 -0.000000 0.637732 -v -0.016250 0.122750 0.151950 -vn -0.717283 0.630262 0.297109 -v -0.016250 0.127500 0.152700 -vn -0.973781 0.131340 0.185743 -v -0.016250 0.126000 0.152700 -vn -0.770265 -0.318861 0.552287 -v -0.016250 0.123375 0.152117 -vn -0.717284 -0.630262 0.297108 -v -0.016250 0.119500 0.154700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 0.121667 0.153825 -vn -0.770261 0.637728 -0.000000 -v -0.016250 0.121500 0.153200 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.123833 0.152575 -vn -0.770261 -0.637728 0.000000 -v -0.016250 0.124000 0.153200 -vn -0.717284 0.630262 0.297108 -v -0.016250 0.126000 0.154700 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.123833 0.153825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 0.123375 0.154283 -vn -0.770264 0.000000 -0.637725 -v -0.016250 0.122750 0.154450 -vn -0.770260 0.318865 -0.552291 -v -0.016250 0.122125 0.154283 -vn -0.973781 -0.131340 0.185743 -v -0.016250 0.111500 0.152700 -vn -0.717284 -0.630262 0.297108 -v -0.016250 0.111500 0.154700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 0.113667 0.153825 -vn -0.770261 0.637728 -0.000000 -v -0.016250 0.113500 0.153200 -vn -0.770261 0.552291 0.318862 -v -0.016250 0.113667 0.152575 -vn -0.770265 0.318861 0.552286 -v -0.016250 0.114125 0.152117 -vn -0.770258 0.000000 0.637732 -v -0.016250 0.114750 0.151950 -vn -0.770264 -0.318861 0.552287 -v -0.016250 0.115375 0.152117 -vn -0.973781 0.131340 0.185743 -v -0.016250 0.118000 0.152700 -vn -0.923879 0.000000 0.382684 -v -0.016250 0.118750 0.152700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.115833 0.152575 -vn -0.770261 -0.637728 0.000000 -v -0.016250 0.116000 0.153200 -vn -0.717284 0.630263 0.297108 -v -0.016250 0.118000 0.154700 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.115833 0.153825 -vn -0.770260 -0.318865 -0.552291 -v -0.016250 0.115375 0.154283 -vn -0.770264 -0.000000 -0.637725 -v -0.016250 0.114750 0.154450 -vn -0.770260 0.318865 -0.552291 -v -0.016250 0.114125 0.154283 -vn -0.973781 -0.131340 0.185743 -v -0.016250 0.103500 0.152700 -vn -0.717284 -0.630263 0.297108 -v -0.016250 0.103500 0.154700 -vn -0.770261 0.552288 -0.318867 -v -0.016250 0.105667 0.153825 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.107833 0.153825 -vn -0.717284 0.630262 0.297108 -v -0.016250 0.110000 0.154700 -vn -0.770261 -0.637729 0.000000 -v -0.016250 0.108000 0.153200 -vn -0.973781 0.131340 0.185743 -v -0.016250 0.110000 0.152700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.107833 0.152575 -vn -0.770265 -0.318861 0.552285 -v -0.016250 0.107375 0.152117 -vn -0.923879 0.000000 0.382684 -v -0.016250 0.102750 0.152700 -vn -0.770264 0.637725 0.000000 -v -0.016250 0.105500 0.153200 -vn -0.770259 0.552293 0.318864 -v -0.016250 0.105667 0.152575 -vn -0.770265 0.318860 0.552286 -v -0.016250 0.106125 0.152117 -vn -0.770259 -0.000001 0.637731 -v -0.016250 0.106750 0.151950 -vn -0.923879 0.000000 0.382684 -v -0.016250 0.110750 0.152700 -vn -0.770260 -0.318865 -0.552291 -v -0.016250 0.107375 0.154283 -vn -0.770265 -0.000001 -0.637724 -v -0.016250 0.106750 0.154450 -vn -0.770259 0.318865 -0.552292 -v -0.016250 0.106125 0.154283 -vn -0.770261 -0.318867 0.552288 -v -0.016250 0.094125 0.146617 -vn -0.770261 -0.552288 0.318867 -v -0.016250 0.094583 0.147075 -vn -0.770264 -0.637725 0.000000 -v -0.016250 0.094750 0.147700 -vn -0.942086 0.183366 0.280804 -v -0.016250 0.095459 0.148451 -vn -0.770258 -0.552293 -0.318865 -v -0.016250 0.094583 0.148325 -vn -0.944677 0.287244 0.158355 -v -0.016250 0.094792 0.149159 -vn -0.770265 -0.318863 -0.552285 -v -0.016250 0.094125 0.148783 -vn -0.938162 0.345263 0.025412 -v -0.016250 0.094550 0.150100 -vn -0.717284 -0.297108 -0.630263 -v -0.016250 0.092000 0.144450 -vn -0.717284 -0.297108 -0.630263 -v -0.016250 0.092000 0.128450 -vn -0.717284 -0.297108 0.630262 -v -0.016250 0.092000 0.134950 -vn -0.717284 -0.630263 -0.297108 -v -0.016250 0.095500 0.124700 -vn -0.923880 -0.000000 -0.382683 -v -0.016250 0.096125 0.124700 -vn -0.717284 0.630263 -0.297108 -v -0.016250 0.102000 0.124700 -vn -0.770261 0.552288 -0.318867 -v -0.016250 0.105667 0.126825 -vn -0.770264 0.637725 -0.000000 -v -0.016250 0.105500 0.126200 -vn -0.707107 -0.000000 -0.707107 -v -0.016250 0.102750 0.129700 -vn -0.707107 -0.707107 0.000000 -v -0.016250 0.103500 0.124825 -vn -0.770264 0.318860 0.552288 -v -0.016250 0.106125 0.125117 -vn -0.770261 -0.000001 0.637729 -v -0.016250 0.106750 0.124950 -vn -0.973781 0.131340 -0.185743 -v -0.016250 0.110000 0.126700 -vn -0.707107 0.707107 -0.000000 -v -0.016250 0.110000 0.124825 -vn -0.770265 -0.318861 0.552287 -v -0.016250 0.107375 0.125117 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.107833 0.126825 -vn -0.707107 -0.000000 -0.707107 -v -0.016250 0.110750 0.129700 -vn -0.770261 -0.637728 0.000000 -v -0.016250 0.108000 0.126200 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.107833 0.125575 -vn -0.923879 0.000000 -0.382684 -v -0.016250 0.102750 0.126700 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 0.103500 0.126700 -vn -0.770259 0.552293 0.318864 -v -0.016250 0.105667 0.125575 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 0.107375 0.127283 -vn -0.770264 -0.000002 -0.637725 -v -0.016250 0.106750 0.127450 -vn -0.770260 0.318865 -0.552290 -v -0.016250 0.106125 0.127283 -vn -0.717284 0.630262 -0.297108 -v -0.016250 0.110000 0.124700 -vn -0.717284 -0.630263 -0.297108 -v -0.016250 0.103500 0.124700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 0.113667 0.126825 -vn -0.770261 0.637728 -0.000000 -v -0.016250 0.113500 0.126200 -vn -0.770261 0.552291 0.318862 -v -0.016250 0.113667 0.125575 -vn -0.770265 0.318861 0.552286 -v -0.016250 0.114125 0.125117 -vn -0.707107 -0.707107 0.000000 -v -0.016250 0.111500 0.124825 -vn -0.770258 -0.000000 0.637732 -v -0.016250 0.114750 0.124950 -vn -0.973781 0.131340 -0.185743 -v -0.016250 0.118000 0.126700 -vn -0.707107 0.707107 0.000000 -v -0.016250 0.118000 0.124825 -vn -0.770265 -0.318861 0.552286 -v -0.016250 0.115375 0.125117 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 0.111500 0.126700 -vn -0.923879 0.000000 -0.382684 -v -0.016250 0.110750 0.126700 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.115833 0.125575 -vn -0.770261 -0.637728 0.000000 -v -0.016250 0.116000 0.126200 -vn -0.707107 0.000000 -0.707106 -v -0.016250 0.118750 0.129700 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.115833 0.126825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 0.115375 0.127283 -vn -0.770264 0.000000 -0.637725 -v -0.016250 0.114750 0.127450 -vn -0.770260 0.318865 -0.552291 -v -0.016250 0.114125 0.127283 -vn -0.717284 0.630262 -0.297108 -v -0.016250 0.118000 0.124700 -vn -0.717284 -0.630263 -0.297108 -v -0.016250 0.111500 0.124700 -vn -0.770263 0.552286 -0.318865 -v -0.016250 0.121667 0.126825 -vn -0.770261 0.637728 0.000000 -v -0.016250 0.121500 0.126200 -vn -0.997107 0.040621 -0.064243 -v -0.016250 0.127500 0.128200 -vn -0.717283 0.630262 -0.297109 -v -0.016250 0.127500 0.126700 -vn -0.973781 0.131340 -0.185743 -v -0.016250 0.126000 0.126700 -vn -0.925077 0.379320 -0.018699 -v -0.016250 0.136550 0.128243 -vn -0.996376 -0.004467 -0.084941 -v -0.016250 0.136000 0.128200 -vn -0.549135 0.227456 -0.804186 -v -0.016250 0.136550 0.129700 -vn -0.770265 -0.318861 0.552286 -v -0.016250 0.123375 0.125117 -vn -0.770261 -0.552291 0.318862 -v -0.016250 0.123833 0.125575 -vn -0.770261 -0.637728 -0.000000 -v -0.016250 0.124000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v -0.016250 0.123833 0.126825 -vn -0.770261 0.552291 0.318862 -v -0.016250 0.121667 0.125575 -vn -0.770265 0.318861 0.552286 -v -0.016250 0.122125 0.125117 -vn -0.707107 -0.707107 0.000000 -v -0.016250 0.119500 0.124825 -vn -0.770258 0.000000 0.637732 -v -0.016250 0.122750 0.124950 -vn -0.707107 0.707107 0.000000 -v -0.016250 0.126000 0.124825 -vn -0.770260 -0.318866 -0.552291 -v -0.016250 0.123375 0.127283 -vn -0.770264 0.000000 -0.637725 -v -0.016250 0.122750 0.127450 -vn -0.770260 0.318866 -0.552291 -v -0.016250 0.122125 0.127283 -vn -0.973781 -0.131340 -0.185743 -v -0.016250 0.119500 0.126700 -vn -0.923879 0.000000 -0.382684 -v -0.016250 0.118750 0.126700 -vn -0.717284 0.630262 -0.297108 -v -0.016250 0.126000 0.124700 -vn -0.717284 -0.630263 -0.297108 -v -0.016250 0.119500 0.124700 -vn -0.511562 -0.726533 -0.458752 -v -0.016245 0.098404 0.129700 -vn -0.328039 -0.331546 -0.884572 -v -0.019050 0.098404 0.129700 -vn -0.297112 0.717283 -0.630262 -v -0.016300 0.136750 0.129700 -vn -0.185744 0.973781 -0.131342 -v -0.016050 0.136750 0.129700 -vn -0.717284 0.297105 -0.630264 -v -0.016500 0.136550 0.129700 -vn -0.131333 0.185734 -0.973784 -v -0.016500 0.120550 0.129700 -vn -0.341576 0.341573 -0.875588 -v -0.019050 0.120550 0.129700 -vn -0.325836 -0.886095 -0.329647 -v -0.019050 0.097000 0.131177 -vn -0.523491 -0.484833 -0.700638 -v -0.016243 0.097000 0.131177 -vn -0.333462 -0.921918 0.197154 -v -0.019050 0.097000 0.148126 -vn -0.939709 -0.253758 0.229246 -v -0.019250 0.097916 0.148759 -vn -0.849429 -0.276498 0.449466 -v -0.019250 0.098355 0.149500 -vn -0.875581 0.341583 0.341582 -v -0.019250 0.120550 0.149500 -vn -0.932050 0.319831 -0.170271 -v -0.019250 0.119404 0.145102 -vn -0.932218 0.346286 -0.105143 -v -0.019250 0.118544 0.143027 -vn -0.938932 -0.242884 -0.243751 -v -0.019250 0.097916 0.130641 -vn -0.932221 0.360144 -0.035503 -v -0.019250 0.118105 0.140823 -vn -0.932221 0.360143 0.035503 -v -0.019250 0.118105 0.138577 -vn -0.848116 -0.296919 -0.438793 -v -0.019250 0.098355 0.129900 -vn -0.842670 -0.453573 -0.290136 -v -0.019250 0.097200 0.131120 -vn -0.844524 -0.463101 0.268918 -v -0.019250 0.097200 0.148280 -vn -0.904941 0.408560 -0.118996 -v -0.019250 0.120550 0.146841 -vn -0.904818 0.408617 0.119734 -v -0.019250 0.120550 0.132559 -vn -0.875576 0.341581 -0.341598 -v -0.019250 0.120550 0.129900 -vn -0.931922 0.320350 0.169992 -v -0.019250 0.119404 0.134298 -vn -0.932220 0.346282 0.105142 -v -0.019250 0.118544 0.136373 -vn 0.690457 0.721220 0.055784 -v -0.011250 0.141000 0.147700 -vn 0.689866 0.721705 -0.056800 -v -0.011250 0.141000 0.131700 -vn -0.110051 0.987815 -0.110051 -v -0.014550 0.141000 0.132400 -vn -0.375127 0.924492 -0.067783 -v -0.014550 0.141000 0.131700 -vn -0.375938 0.924209 0.067148 -v -0.014550 0.141000 0.147700 -vn -0.110051 0.987815 0.110051 -v -0.014550 0.141000 0.147000 -vn -0.118633 0.921348 0.370193 -v -0.015000 0.141000 0.147000 -vn -0.118633 0.921348 -0.370194 -v -0.015000 0.141000 0.132400 -vn -0.804191 0.549123 -0.227466 -v -0.016500 0.120750 0.129900 -vn -0.934292 0.353780 -0.044032 -v -0.016500 0.136550 0.130450 -vn -0.735270 -0.658079 0.162202 -v -0.016500 0.138336 0.137522 -vn -0.735271 -0.677773 -0.000000 -v -0.016500 0.138600 0.139700 -vn -0.934292 0.044033 -0.353778 -v -0.016500 0.138500 0.132400 -vn -0.777812 0.602022 -0.180496 -v -0.016500 0.120750 0.146771 -vn -0.735271 0.507321 -0.449447 -v -0.016500 0.122689 0.145734 -vn -0.685653 0.644141 -0.339061 -v -0.016500 0.119550 0.144950 -vn -0.735271 0.600138 -0.314977 -v -0.016500 0.121442 0.143929 -vn -0.685531 0.697354 -0.209153 -v -0.016500 0.118724 0.142931 -vn -0.735270 0.658079 -0.162202 -v -0.016500 0.120664 0.141878 -vn -0.685729 0.724413 -0.070714 -v -0.016500 0.118303 0.140791 -vn -0.735271 0.677773 0.000000 -v -0.016500 0.120400 0.139700 -vn -0.685922 0.724270 0.070315 -v -0.016500 0.118303 0.138609 -vn -0.686109 0.696940 0.208637 -v -0.016500 0.118724 0.136469 -vn -0.735270 -0.658079 -0.162202 -v -0.016500 0.138336 0.141878 -vn -0.735271 -0.600138 -0.314977 -v -0.016500 0.137558 0.143929 -vn -0.945447 0.162886 0.282132 -v -0.016500 0.137525 0.147261 -vn -0.735270 -0.507322 -0.449447 -v -0.016500 0.136311 0.145734 -vn -0.945445 0.282135 0.162892 -v -0.016500 0.136811 0.147975 -vn -0.735271 -0.385020 -0.557795 -v -0.016500 0.134669 0.147189 -vn -0.934292 0.353778 0.044032 -v -0.016500 0.136550 0.148950 -vn -0.735271 -0.240341 -0.633730 -v -0.016500 0.132727 0.148209 -vn -0.735270 -0.081696 -0.672833 -v -0.016500 0.130597 0.148734 -vn -0.804186 0.549133 0.227458 -v -0.016500 0.120750 0.149500 -vn -0.717285 0.297105 0.630263 -v -0.016500 0.136550 0.149700 -vn -0.131340 0.185743 0.973781 -v -0.016500 0.120550 0.149700 -vn -0.735270 0.081696 -0.672833 -v -0.016500 0.128403 0.148734 -vn -0.735271 0.240341 -0.633729 -v -0.016500 0.126273 0.148209 -vn -0.735271 0.385020 -0.557796 -v -0.016500 0.124331 0.147189 -vn -0.934292 0.044031 0.353780 -v -0.016500 0.138500 0.147000 -vn -0.921350 0.118638 0.370189 -v -0.016500 0.139500 0.147000 -vn -0.921350 0.118638 -0.370189 -v -0.016500 0.139500 0.132400 -vn -0.735271 -0.081698 0.672831 -v -0.016500 0.130597 0.130666 -vn -0.735270 -0.240343 0.633729 -v -0.016500 0.132727 0.131191 -vn -0.945442 0.282143 -0.162896 -v -0.016500 0.136811 0.131425 -vn -0.735271 -0.385019 0.557797 -v -0.016500 0.134669 0.132211 -vn -0.945442 0.162894 -0.282143 -v -0.016500 0.137525 0.132139 -vn -0.735271 -0.507320 0.449448 -v -0.016500 0.136311 0.133666 -vn -0.735271 -0.600138 0.314977 -v -0.016500 0.137558 0.135471 -vn -0.735270 0.658079 0.162202 -v -0.016500 0.120664 0.137522 -vn -0.778046 0.601627 0.180800 -v -0.016500 0.120750 0.132629 -vn -0.686287 0.643461 0.339069 -v -0.016500 0.119550 0.134450 -vn -0.735271 0.600138 0.314976 -v -0.016500 0.121442 0.135471 -vn -0.735271 0.507320 0.449448 -v -0.016500 0.122689 0.133666 -vn -0.735270 0.385019 0.557797 -v -0.016500 0.124331 0.132211 -vn -0.735270 0.240344 0.633729 -v -0.016500 0.126273 0.131191 -vn -0.735271 0.081698 0.672831 -v -0.016500 0.128403 0.130666 -vn 0.674748 0.702484 -0.226345 -v -0.011250 0.140755 0.130155 -vn -0.370454 0.889761 -0.266627 -v -0.014550 0.140787 0.130256 -vn -0.375410 0.802104 -0.464431 -v -0.014550 0.140166 0.128935 -vn 0.676755 0.595995 -0.432196 -v -0.011250 0.140045 0.128761 -vn -0.392628 0.711814 -0.582378 -v -0.014550 0.140045 0.128761 -vn -0.375037 0.623801 -0.685725 -v -0.014550 0.139190 0.127850 -vn 0.677717 0.432616 -0.594594 -v -0.011250 0.138939 0.127655 -vn -0.400481 0.503029 -0.765883 -v -0.014550 0.138939 0.127655 -vn -0.374929 0.390437 -0.840825 -v -0.014550 0.137943 0.127093 -vn 0.678577 0.227465 -0.698422 -v -0.011250 0.137545 0.126945 -vn -0.397501 0.258893 -0.880323 -v -0.014550 0.137545 0.126945 -vn -0.088068 0.028549 -0.995705 -v -0.014750 0.136000 0.126700 -vn -0.081124 0.426404 -0.900887 -v -0.014750 0.136573 0.126733 -vn -0.089205 0.226903 -0.969824 -v -0.014550 0.136573 0.126733 -vn 0.692645 0.052668 -0.719353 -v -0.011250 0.136000 0.126700 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 0.124750 0.123700 -vn 0.770265 -0.318861 0.552286 -v -0.014250 0.123375 0.125117 -vn 0.770258 0.000000 0.637732 -v -0.014250 0.122750 0.124950 -vn 0.609994 0.000001 -0.792406 -v -0.014250 0.122750 0.128509 -vn 0.770264 0.000000 -0.637725 -v -0.014250 0.122750 0.127450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 0.123375 0.127283 -vn 0.301511 0.301511 -0.904534 -v -0.014250 0.120750 0.123700 -vn 0.770265 0.318861 0.552286 -v -0.014250 0.122125 0.125117 -vn 0.770261 0.552291 0.318862 -v -0.014250 0.121667 0.125575 -vn 0.609995 0.686244 -0.396202 -v -0.014250 0.120750 0.127355 -vn 0.609994 -0.686244 -0.396202 -v -0.014250 0.124750 0.127355 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.123833 0.126825 -vn 0.770261 -0.637728 0.000000 -v -0.014250 0.124000 0.126200 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.123833 0.125575 -vn 0.770261 0.637728 -0.000000 -v -0.014250 0.121500 0.126200 -vn 0.770263 0.552286 -0.318865 -v -0.014250 0.121667 0.126825 -vn 0.770260 0.318866 -0.552291 -v -0.014250 0.122125 0.127283 -vn 0.609995 0.686244 -0.396202 -v -0.014250 0.112750 0.127355 -vn 0.770263 0.552286 -0.318865 -v -0.014250 0.113667 0.126825 -vn 0.609994 0.000001 -0.792406 -v -0.014250 0.114750 0.128509 -vn 0.770260 0.318866 -0.552291 -v -0.014250 0.114125 0.127283 -vn 0.609994 -0.686244 -0.396202 -v -0.014250 0.116750 0.127355 -vn 0.770261 -0.637728 -0.000000 -v -0.014250 0.116000 0.126200 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 0.116750 0.123700 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.115833 0.125575 -vn 0.770265 -0.318861 0.552286 -v -0.014250 0.115375 0.125117 -vn 0.770258 0.000000 0.637732 -v -0.014250 0.114750 0.124950 -vn 0.301511 0.301511 -0.904534 -v -0.014250 0.112750 0.123700 -vn 0.770265 0.318861 0.552286 -v -0.014250 0.114125 0.125117 -vn 0.770261 0.552291 0.318862 -v -0.014250 0.113667 0.125575 -vn 0.770261 0.637729 0.000000 -v -0.014250 0.113500 0.126200 -vn 0.770264 -0.000000 -0.637725 -v -0.014250 0.114750 0.127450 -vn 0.770260 -0.318865 -0.552291 -v -0.014250 0.115375 0.127283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.115833 0.126825 -vn 0.609995 -0.686244 -0.396202 -v -0.014250 0.108750 0.127355 -vn 0.770261 -0.637728 -0.000000 -v -0.014250 0.108000 0.126200 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 0.108750 0.123700 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.107833 0.125575 -vn 0.609994 -0.000001 -0.792406 -v -0.014250 0.106750 0.128509 -vn 0.770260 -0.318865 -0.552291 -v -0.014250 0.107375 0.127283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.107833 0.126825 -vn 0.770265 -0.318861 0.552287 -v -0.014250 0.107375 0.125117 -vn 0.770258 -0.000001 0.637732 -v -0.014250 0.106750 0.124950 -vn 0.301511 0.301511 -0.904534 -v -0.014250 0.104750 0.123700 -vn 0.770264 0.637725 0.000000 -v -0.014250 0.105500 0.126200 -vn 0.609994 0.686244 -0.396203 -v -0.014250 0.104750 0.127355 -vn 0.770259 0.552293 0.318864 -v -0.014250 0.105667 0.125575 -vn 0.770266 0.318861 0.552284 -v -0.014250 0.106125 0.125117 -vn 0.770261 0.552288 -0.318867 -v -0.014250 0.105667 0.126825 -vn 0.770261 0.318866 -0.552288 -v -0.014250 0.106125 0.127283 -vn 0.770264 -0.000001 -0.637726 -v -0.014250 0.106750 0.127450 -vn 0.717284 -0.297108 0.630263 -v -0.011250 0.092000 0.150950 -vn 0.741788 -0.427644 -0.516597 -v -0.011250 0.092000 0.149700 -vn 0.904534 -0.301511 0.301511 -v -0.011250 0.092500 0.150950 -vn 0.846478 -0.452907 -0.279911 -v -0.011250 0.094000 0.148700 -vn 0.846478 -0.279911 -0.452907 -v -0.011250 0.123750 0.126700 -vn 0.741788 -0.516596 -0.427644 -v -0.011250 0.124750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 0.126000 0.124700 -vn 0.770261 -0.552288 0.318866 -v -0.011250 0.139366 0.129950 -vn 0.770261 -0.318866 0.552288 -v -0.011250 0.139000 0.129584 -vn 0.717284 0.630263 0.297108 -v -0.011250 0.126000 0.154700 -vn 0.741788 -0.516596 0.427644 -v -0.011250 0.124750 0.154700 -vn 0.904534 0.301511 0.301511 -v -0.011250 0.126000 0.154200 -vn 0.846478 -0.279911 0.452907 -v -0.011250 0.123750 0.152700 -vn 0.770263 -0.000002 0.637727 -v -0.011250 0.138500 0.129450 -vn 0.717283 0.630263 0.297108 -v -0.011250 0.118000 0.154700 -vn 0.741788 -0.516596 0.427644 -v -0.011250 0.116750 0.154700 -vn 0.904534 0.301512 0.301512 -v -0.011250 0.118000 0.154200 -vn 0.846478 -0.279911 0.452907 -v -0.011250 0.115750 0.152700 -vn 0.717284 0.630263 0.297108 -v -0.011250 0.110000 0.154700 -vn 0.741788 -0.516596 0.427644 -v -0.011250 0.108750 0.154700 -vn 0.904534 0.301511 0.301511 -v -0.011250 0.110000 0.154200 -vn 0.846478 -0.279911 0.452907 -v -0.011250 0.107750 0.152700 -vn 0.904534 -0.301511 0.301511 -v -0.011250 0.111500 0.154200 -vn 0.904534 -0.301511 0.301511 -v -0.011250 0.095500 0.154200 -vn 0.577350 -0.577350 0.577350 -v -0.011250 0.094000 0.154200 -vn 0.904534 -0.301511 0.301511 -v -0.011250 0.094000 0.152700 -vn 0.741787 0.516597 0.427643 -v -0.011250 0.120750 0.154700 -vn 0.717284 -0.630263 0.297108 -v -0.011250 0.119500 0.154700 -vn 0.846478 0.279911 0.452906 -v -0.011250 0.121750 0.152700 -vn 0.904534 -0.301511 0.301511 -v -0.011250 0.119500 0.154200 -vn 0.846478 0.279911 0.452907 -v -0.011250 0.113750 0.152700 -vn 0.741788 0.516596 0.427644 -v -0.011250 0.112750 0.154700 -vn 0.717284 -0.630263 0.297108 -v -0.011250 0.111500 0.154700 -vn 0.904534 0.301511 0.301511 -v -0.011250 0.127500 0.152700 -vn 0.770259 -0.637731 0.000002 -v -0.011250 0.097500 0.150100 -vn 0.770263 -0.000002 -0.637727 -v -0.011250 0.138500 0.149950 -vn 0.741788 -0.516596 -0.427644 -v -0.011250 0.100750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 0.102000 0.124700 -vn 0.846478 -0.279911 -0.452907 -v -0.011250 0.099750 0.126700 -vn 0.904534 0.301511 -0.301511 -v -0.011250 0.102000 0.125200 -vn 0.676639 0.596071 0.432272 -v -0.011250 0.140045 0.150639 -vn 0.677586 0.432686 0.594693 -v -0.011250 0.138939 0.151745 -vn 0.741788 0.516596 0.427644 -v -0.011250 0.104750 0.154700 -vn 0.717284 -0.630263 0.297108 -v -0.011250 0.103500 0.154700 -vn 0.846478 0.279911 0.452907 -v -0.011250 0.105750 0.152700 -vn 0.904534 -0.301511 0.301511 -v -0.011250 0.103500 0.154200 -vn 0.770260 0.318863 -0.552291 -v -0.011250 0.096000 0.150966 -vn 0.846478 -0.279911 0.452907 -v -0.011250 0.099750 0.152700 -vn 0.846478 0.279911 0.452907 -v -0.011250 0.097750 0.152700 -vn 0.717284 -0.630263 -0.297108 -v -0.011250 0.103500 0.124700 -vn 0.741788 0.516596 -0.427644 -v -0.011250 0.104750 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 0.103500 0.125200 -vn 0.846478 0.279911 -0.452907 -v -0.011250 0.105750 0.126700 -vn 0.741788 -0.516596 -0.427644 -v -0.011250 0.108750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 0.110000 0.124700 -vn 0.846478 -0.279911 -0.452907 -v -0.011250 0.107750 0.126700 -vn 0.904534 0.301511 -0.301511 -v -0.011250 0.110000 0.125200 -vn 0.675966 0.224549 0.701889 -v -0.011250 0.137545 0.152455 -vn 0.690737 0.056392 0.720904 -v -0.011250 0.136000 0.152700 -vn 0.717284 -0.630263 -0.297108 -v -0.011250 0.111500 0.124700 -vn 0.741788 0.516596 -0.427644 -v -0.011250 0.112750 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 0.111500 0.125200 -vn 0.846478 0.279911 -0.452907 -v -0.011250 0.113750 0.126700 -vn 0.770259 0.318864 -0.552292 -v -0.011250 0.096000 0.130166 -vn 0.770263 0.552286 -0.318865 -v -0.011250 0.095634 0.129800 -vn 0.770263 0.637726 0.000002 -v -0.011250 0.095500 0.129300 -vn 0.577350 0.577350 0.577350 -v -0.011250 0.127500 0.154200 -vn 0.717284 0.630263 0.297108 -v -0.011250 0.102000 0.154700 -vn 0.741788 -0.516596 0.427644 -v -0.011250 0.100750 0.154700 -vn 0.904534 0.301511 0.301511 -v -0.011250 0.102000 0.154200 -vn 0.770263 0.000000 -0.637727 -v -0.011250 0.096500 0.151100 -vn 0.741787 0.516596 0.427644 -v -0.011250 0.096750 0.154700 -vn 0.717284 -0.630262 0.297108 -v -0.011250 0.095500 0.154700 -vn 0.770263 0.552286 -0.318865 -v -0.011250 0.095634 0.150600 -vn 0.717284 -0.630262 -0.297108 -v -0.011250 0.095500 0.124700 -vn 0.741787 0.516596 -0.427644 -v -0.011250 0.096750 0.124700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 0.095500 0.125200 -vn 0.846478 0.279911 -0.452907 -v -0.011250 0.097750 0.126700 -vn 0.770266 0.318868 0.552280 -v -0.011250 0.138000 0.129584 -vn 0.770261 -0.552292 0.318859 -v -0.011250 0.097366 0.149600 -vn 0.770265 -0.318858 0.552287 -v -0.011250 0.097000 0.149234 -vn 0.770265 -0.552286 -0.318861 -v -0.011250 0.097366 0.150600 -vn 0.770260 -0.318863 -0.552291 -v -0.011250 0.097000 0.150966 -vn 0.770260 -0.318863 -0.552291 -v -0.011250 0.097000 0.130166 -vn 0.770263 0.000000 -0.637727 -v -0.011250 0.096500 0.130300 -vn 0.770255 -0.000000 0.637736 -v -0.011250 0.096500 0.149100 -vn 0.770260 -0.637730 0.000002 -v -0.011250 0.097500 0.129300 -vn 0.770265 -0.552286 -0.318861 -v -0.011250 0.097366 0.129800 -vn 0.770258 0.552294 0.318862 -v -0.011250 0.137634 0.129950 -vn 0.770263 0.637727 0.000002 -v -0.011250 0.137500 0.130450 -vn 0.741788 -0.516596 -0.427644 -v -0.011250 0.116750 0.124700 -vn 0.717284 0.630263 -0.297108 -v -0.011250 0.118000 0.124700 -vn 0.846478 -0.279911 -0.452907 -v -0.011250 0.115750 0.126700 -vn 0.904534 0.301511 -0.301512 -v -0.011250 0.118000 0.125200 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 0.119500 0.125200 -vn 0.770266 0.318858 0.552286 -v -0.011250 0.096000 0.149234 -vn 0.770260 0.552291 0.318864 -v -0.011250 0.095634 0.149600 -vn 0.770263 0.637727 0.000002 -v -0.011250 0.095500 0.150100 -vn 0.770263 0.637727 0.000002 -v -0.011250 0.137500 0.148950 -vn 0.770262 0.552289 -0.318864 -v -0.011250 0.137634 0.149450 -vn 0.770264 0.318864 -0.552285 -v -0.011250 0.138000 0.149816 -vn 0.770261 -0.318866 0.552288 -v -0.011250 0.139000 0.148084 -vn 0.770261 -0.552288 0.318866 -v -0.011250 0.139366 0.148450 -vn 0.770263 -0.637727 0.000002 -v -0.011250 0.139500 0.148950 -vn 0.675264 0.701711 0.227201 -v -0.011250 0.140755 0.149245 -vn 0.770265 -0.552283 -0.318868 -v -0.011250 0.139366 0.149450 -vn 0.770258 -0.318862 -0.552294 -v -0.011250 0.139000 0.149816 -vn 0.904534 0.301511 -0.301511 -v -0.011250 0.126000 0.125200 -vn 0.577350 0.577350 -0.577350 -v -0.011250 0.127500 0.125200 -vn 0.904534 0.301511 -0.301511 -v -0.011250 0.127500 0.126700 -vn 0.846478 -0.452906 -0.279911 -v -0.011250 0.094000 0.132700 -vn 0.846478 -0.452906 0.279911 -v -0.011250 0.094000 0.130700 -vn 0.770258 0.552294 0.318862 -v -0.011250 0.137634 0.148450 -vn 0.770262 0.318864 -0.552288 -v -0.011250 0.138000 0.131316 -vn 0.770262 0.552289 -0.318864 -v -0.011250 0.137634 0.130950 -vn 0.770263 -0.637727 0.000002 -v -0.011250 0.139500 0.130450 -vn 0.770265 -0.552283 -0.318868 -v -0.011250 0.139366 0.130950 -vn 0.770258 -0.318862 -0.552294 -v -0.011250 0.139000 0.131316 -vn 0.770263 -0.000002 -0.637727 -v -0.011250 0.138500 0.131450 -vn 0.770262 -0.000002 0.637727 -v -0.011250 0.138500 0.147950 -vn 0.770265 0.318868 0.552282 -v -0.011250 0.138000 0.148084 -vn 0.741788 -0.427644 0.516597 -v -0.011250 0.092000 0.145700 -vn 0.717284 -0.297108 -0.630263 -v -0.011250 0.092000 0.144450 -vn 0.846478 -0.452907 0.279911 -v -0.011250 0.094000 0.146700 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 0.092500 0.144450 -vn 0.904534 -0.301511 0.301511 -v -0.011250 0.092500 0.134950 -vn 0.717284 -0.297108 0.630263 -v -0.011250 0.092000 0.134950 -vn 0.741788 -0.427644 -0.516597 -v -0.011250 0.092000 0.133700 -vn 0.577350 -0.577350 0.577350 -v -0.011250 0.092500 0.152700 -vn 0.770263 -0.318867 0.552285 -v -0.011250 0.097000 0.128434 -vn 0.770262 -0.000000 0.637727 -v -0.011250 0.096500 0.128300 -vn 0.770263 0.318867 0.552285 -v -0.011250 0.096000 0.128434 -vn 0.770261 -0.552292 0.318859 -v -0.011250 0.097366 0.128800 -vn 0.741788 -0.427644 0.516597 -v -0.011250 0.092000 0.129700 -vn 0.717284 -0.297108 -0.630263 -v -0.011250 0.092000 0.128450 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 0.092500 0.128450 -vn 0.577350 -0.577350 -0.577350 -v -0.011250 0.092500 0.126700 -vn 0.577350 -0.577350 -0.577350 -v -0.011250 0.094000 0.125200 -vn 0.904534 -0.301511 -0.301511 -v -0.011250 0.094000 0.126700 -vn 0.770260 0.552292 0.318863 -v -0.011250 0.095634 0.128800 -vn 0.846478 0.279911 -0.452906 -v -0.011250 0.121750 0.126700 -vn 0.741787 0.516597 -0.427643 -v -0.011250 0.120750 0.124700 -vn 0.717284 -0.630263 -0.297108 -v -0.011250 0.119500 0.124700 -vn -0.075085 0.990667 -0.113762 -v -0.012750 0.120750 0.124700 -vn -0.609995 0.686244 -0.396202 -v -0.012750 0.120750 0.127355 -vn -0.846478 0.279911 -0.452906 -v -0.012750 0.121750 0.126700 -vn -0.609994 0.000001 -0.792406 -v -0.012750 0.122750 0.128509 -vn -0.846478 -0.279911 -0.452907 -v -0.012750 0.123750 0.126700 -vn -0.609994 -0.686244 -0.396203 -v -0.012750 0.124750 0.127355 -vn -0.075085 -0.990667 -0.113763 -v -0.012750 0.124750 0.124700 -vn -0.075085 0.990667 -0.113763 -v -0.012750 0.112750 0.124700 -vn -0.609995 0.686244 -0.396202 -v -0.012750 0.112750 0.127355 -vn -0.846478 0.279911 -0.452907 -v -0.012750 0.113750 0.126700 -vn -0.609994 0.000001 -0.792406 -v -0.012750 0.114750 0.128509 -vn -0.846478 -0.279911 -0.452907 -v -0.012750 0.115750 0.126700 -vn -0.609994 -0.686244 -0.396203 -v -0.012750 0.116750 0.127355 -vn -0.075085 -0.990667 -0.113763 -v -0.012750 0.116750 0.124700 -vn -0.075085 0.990667 -0.113763 -v -0.012750 0.104750 0.124700 -vn -0.609994 0.686244 -0.396203 -v -0.012750 0.104750 0.127355 -vn -0.846478 0.279911 -0.452907 -v -0.012750 0.105750 0.126700 -vn -0.609994 -0.000001 -0.792406 -v -0.012750 0.106750 0.128509 -vn -0.846478 -0.279911 -0.452907 -v -0.012750 0.107750 0.126700 -vn -0.609995 -0.686244 -0.396202 -v -0.012750 0.108750 0.127355 -vn -0.075085 -0.990667 -0.113763 -v -0.012750 0.108750 0.124700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.120750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 0.119500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v -0.015250 0.119500 0.123700 -vn -0.297109 0.630262 -0.717283 -v -0.015250 0.126000 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 0.124750 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.126000 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.112750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 0.111500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v -0.015250 0.111500 0.123700 -vn -0.297109 0.630262 -0.717283 -v -0.015250 0.118000 0.123700 -vn 0.297109 -0.630262 -0.717284 -v -0.012250 0.116750 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.118000 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.104750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 0.103500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v -0.015250 0.103500 0.123700 -vn -0.297109 0.630262 -0.717284 -v -0.015250 0.110000 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 0.108750 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.110000 0.123700 -vn 0.609995 -0.686244 -0.396202 -v -0.014250 0.100750 0.127355 -vn 0.770261 -0.637728 0.000000 -v -0.014250 0.100000 0.126200 -vn 0.301511 -0.301511 -0.904534 -v -0.014250 0.100750 0.123700 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.099833 0.125575 -vn 0.609994 0.686244 -0.396203 -v -0.014250 0.096750 0.127355 -vn 0.301511 0.301511 -0.904534 -v -0.014250 0.096750 0.123700 -vn 0.770260 0.552291 0.318865 -v -0.014250 0.097667 0.125575 -vn 0.770260 0.318865 -0.552291 -v -0.014250 0.098125 0.127283 -vn 0.609994 -0.000001 -0.792406 -v -0.014250 0.098750 0.128509 -vn 0.770262 0.552286 -0.318869 -v -0.014250 0.097667 0.126825 -vn 0.770264 0.637725 0.000000 -v -0.014250 0.097500 0.126200 -vn 0.770264 0.000000 -0.637725 -v -0.014250 0.098750 0.127450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 0.099375 0.127283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.099833 0.126825 -vn 0.770265 -0.318861 0.552286 -v -0.014250 0.099375 0.125117 -vn 0.770258 -0.000000 0.637732 -v -0.014250 0.098750 0.124950 -vn 0.770265 0.318861 0.552286 -v -0.014250 0.098125 0.125117 -vn 0.301511 -0.904534 -0.301511 -v -0.014250 0.091000 0.133700 -vn 0.301511 -0.904534 0.301511 -v -0.014250 0.091000 0.129700 -vn 0.770264 0.637725 0.000000 -v -0.014250 0.092250 0.131700 -vn 0.770261 0.552288 0.318867 -v -0.014250 0.092417 0.131075 -vn 0.770261 -0.552288 0.318867 -v -0.014250 0.094583 0.131075 -vn 0.609995 -0.396202 0.686244 -v -0.014250 0.094655 0.129700 -vn 0.770264 -0.637725 0.000000 -v -0.014250 0.094750 0.131700 -vn 0.609994 -0.792406 0.000001 -v -0.014250 0.095809 0.131700 -vn 0.770259 -0.552293 -0.318864 -v -0.014250 0.094583 0.132325 -vn 0.609994 -0.396203 -0.686243 -v -0.014250 0.094655 0.133700 -vn 0.770266 -0.318862 -0.552284 -v -0.014250 0.094125 0.132783 -vn 0.770259 0.552293 -0.318864 -v -0.014250 0.092417 0.132325 -vn 0.770266 0.318861 -0.552284 -v -0.014250 0.092875 0.132783 -vn 0.770258 -0.000001 -0.637732 -v -0.014250 0.093500 0.132950 -vn 0.770261 -0.318867 0.552288 -v -0.014250 0.094125 0.130617 -vn 0.770264 -0.000001 0.637726 -v -0.014250 0.093500 0.130450 -vn 0.770261 0.318866 0.552288 -v -0.014250 0.092875 0.130617 -vn -0.075085 0.990667 -0.113763 -v -0.012750 0.096750 0.124700 -vn -0.609994 0.686244 -0.396203 -v -0.012750 0.096750 0.127355 -vn -0.846478 0.279911 -0.452907 -v -0.012750 0.097750 0.126700 -vn -0.609994 -0.000001 -0.792406 -v -0.012750 0.098750 0.128509 -vn -0.846478 -0.279911 -0.452907 -v -0.012750 0.099750 0.126700 -vn -0.609995 -0.686244 -0.396202 -v -0.012750 0.100750 0.127355 -vn -0.075085 -0.990667 -0.113763 -v -0.012750 0.100750 0.124700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.096750 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 0.095500 0.123700 -vn -0.297109 -0.630262 -0.717284 -v -0.015250 0.095500 0.123700 -vn -0.297109 0.630262 -0.717283 -v -0.015250 0.102000 0.123700 -vn 0.297109 -0.630262 -0.717283 -v -0.012250 0.100750 0.123700 -vn 0.297109 0.630262 -0.717283 -v -0.012250 0.102000 0.123700 -vn -0.846478 -0.452906 -0.279911 -v -0.012750 0.094000 0.132700 -vn -0.075085 -0.113763 -0.990667 -v -0.012750 0.092000 0.133700 -vn -0.609994 -0.396204 -0.686243 -v -0.012750 0.094655 0.133700 -vn -0.609994 -0.396202 0.686244 -v -0.012750 0.094655 0.129700 -vn -0.075085 -0.113763 0.990667 -v -0.012750 0.092000 0.129700 -vn -0.846478 -0.452906 0.279911 -v -0.012750 0.094000 0.130700 -vn -0.609994 -0.792406 0.000001 -v -0.012750 0.095809 0.131700 -vn 0.297109 -0.717283 -0.630262 -v -0.012250 0.091000 0.133700 -vn 0.297109 -0.717283 0.630262 -v -0.012250 0.091000 0.134950 -vn -0.297109 -0.717283 0.630262 -v -0.015250 0.091000 0.134950 -vn -0.297109 -0.717283 -0.630262 -v -0.015250 0.091000 0.128450 -vn 0.297109 -0.717283 0.630262 -v -0.012250 0.091000 0.129700 -vn 0.297109 -0.717283 -0.630262 -v -0.012250 0.091000 0.128450 -vn -0.087124 0.736841 0.670428 -v -0.014750 0.127500 0.152700 -vn -0.081892 0.019690 0.996447 -v -0.014750 0.136000 0.152700 -vn -0.087119 0.736839 -0.670431 -v -0.014750 0.127500 0.126700 -vn -0.297108 0.630263 -0.717284 -v -0.014750 0.127500 0.125200 -vn -0.319806 0.768482 -0.554220 -v -0.015500 0.127500 0.126901 -vn -0.554225 0.768479 -0.319806 -v -0.016049 0.127500 0.127450 -vn -0.227458 0.804186 -0.549133 -v -0.014750 0.126000 0.125200 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 0.119500 0.125200 -vn -0.227458 0.804186 -0.549133 -v -0.014750 0.118000 0.125200 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 0.111500 0.125200 -vn -0.227458 0.804186 -0.549133 -v -0.014750 0.110000 0.125200 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 0.103500 0.125200 -vn -0.227458 0.804186 -0.549133 -v -0.014750 0.102000 0.125200 -vn -0.227458 -0.804186 -0.549133 -v -0.014750 0.095500 0.125200 -vn -0.297108 -0.630263 -0.717284 -v -0.014750 0.094000 0.125200 -vn -0.297108 -0.717284 -0.630263 -v -0.014750 0.092500 0.126700 -vn -0.227458 -0.549133 -0.804186 -v -0.014750 0.092500 0.128450 -vn -0.227458 -0.549133 0.804186 -v -0.014750 0.092500 0.134950 -vn -0.227458 -0.549133 -0.804186 -v -0.014750 0.092500 0.144450 -vn -0.297109 -0.717283 -0.630262 -v -0.015250 0.091000 0.144450 -vn 0.297109 -0.717283 -0.630262 -v -0.012250 0.091000 0.144450 -vn 0.297109 -0.717283 -0.630262 -v -0.012250 0.091000 0.149700 -vn 0.297109 -0.717283 0.630262 -v -0.012250 0.091000 0.150950 -vn 0.301511 -0.904534 -0.301511 -v -0.014250 0.091000 0.149700 -vn -0.297109 -0.717284 0.630262 -v -0.015250 0.091000 0.150950 -vn 0.301511 -0.904534 0.301511 -v -0.014250 0.091000 0.145700 -vn 0.297109 -0.717283 0.630262 -v -0.012250 0.091000 0.145700 -vn -0.227458 -0.549133 0.804186 -v -0.014750 0.092500 0.150950 -vn -0.297108 -0.717284 0.630263 -v -0.014750 0.092500 0.152700 -vn -0.297108 -0.630263 0.717284 -v -0.014750 0.094000 0.154200 -vn -0.227458 -0.804186 0.549133 -v -0.014750 0.095500 0.154200 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.095500 0.155700 -vn -0.297109 -0.630262 0.717284 -v -0.015250 0.095500 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.100750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.102000 0.155700 -vn 0.301511 -0.301511 0.904534 -v -0.014250 0.100750 0.155700 -vn -0.297109 0.630262 0.717283 -v -0.015250 0.102000 0.155700 -vn 0.301511 0.301511 0.904534 -v -0.014250 0.096750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.096750 0.155700 -vn -0.227458 0.804186 0.549133 -v -0.014750 0.102000 0.154200 -vn -0.227458 -0.804186 0.549133 -v -0.014750 0.103500 0.154200 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.103500 0.155700 -vn -0.297109 -0.630262 0.717283 -v -0.015250 0.103500 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.108750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.110000 0.155700 -vn 0.301511 -0.301511 0.904534 -v -0.014250 0.108750 0.155700 -vn -0.297109 0.630262 0.717284 -v -0.015250 0.110000 0.155700 -vn 0.301511 0.301511 0.904534 -v -0.014250 0.104750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.104750 0.155700 -vn -0.227458 0.804186 0.549133 -v -0.014750 0.110000 0.154200 -vn -0.227458 -0.804186 0.549133 -v -0.014750 0.111500 0.154200 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.111500 0.155700 -vn -0.297109 -0.630262 0.717284 -v -0.015250 0.111500 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.116750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.118000 0.155700 -vn 0.301511 -0.301511 0.904534 -v -0.014250 0.116750 0.155700 -vn -0.297109 0.630262 0.717284 -v -0.015250 0.118000 0.155700 -vn 0.301511 0.301511 0.904534 -v -0.014250 0.112750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.112750 0.155700 -vn -0.227458 0.804186 0.549133 -v -0.014750 0.118000 0.154200 -vn -0.227458 -0.804186 0.549133 -v -0.014750 0.119500 0.154200 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.119500 0.155700 -vn -0.297109 -0.630262 0.717284 -v -0.015250 0.119500 0.155700 -vn 0.297109 -0.630262 0.717283 -v -0.012250 0.124750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.126000 0.155700 -vn 0.301511 -0.301511 0.904534 -v -0.014250 0.124750 0.155700 -vn -0.297109 0.630262 0.717283 -v -0.015250 0.126000 0.155700 -vn 0.301511 0.301511 0.904534 -v -0.014250 0.120750 0.155700 -vn 0.297109 0.630262 0.717283 -v -0.012250 0.120750 0.155700 -vn -0.227458 0.804186 0.549133 -v -0.014750 0.126000 0.154200 -vn -0.297108 0.630263 0.717284 -v -0.014750 0.127500 0.154200 -vn -0.554221 0.768481 0.319807 -v -0.016049 0.127500 0.151950 -vn -0.319810 0.768477 0.554224 -v -0.015500 0.127500 0.152499 -vn -0.174809 0.977022 0.121937 -v -0.015997 0.136750 0.149700 -vn -0.297113 0.717283 0.630261 -v -0.016300 0.136750 0.149700 -vn -0.332605 -0.226215 0.915533 -v -0.019050 0.098472 0.149700 -vn -0.341590 0.341585 0.875577 -v -0.019050 0.120550 0.149700 -vn -0.341590 0.875577 0.341585 -v -0.019050 0.120750 0.149500 -vn -0.371675 0.888586 -0.268835 -v -0.019050 0.120750 0.146771 -vn -0.391738 0.812015 -0.432636 -v -0.019050 0.119581 0.145007 -vn -0.391664 0.880350 -0.267549 -v -0.019050 0.118735 0.142968 -vn -0.391403 0.915764 -0.090445 -v -0.019050 0.118304 0.140804 -vn -0.391145 0.915900 0.090179 -v -0.019050 0.118304 0.138596 -vn -0.390893 0.880748 0.267367 -v -0.019050 0.118735 0.136431 -vn -0.391244 0.812381 0.432394 -v -0.019050 0.119581 0.134392 -vn -0.371672 0.888350 0.269620 -v -0.019050 0.120750 0.132629 -vn -0.341588 0.875572 -0.341601 -v -0.019050 0.120750 0.129900 -vn -0.609994 -0.396204 0.686243 -v -0.012750 0.094655 0.145700 -vn 0.609994 -0.396203 0.686243 -v -0.014250 0.094655 0.145700 -vn -0.075085 -0.113763 0.990667 -v -0.012750 0.092000 0.145700 -vn 0.770264 0.637725 0.000000 -v -0.014250 0.092250 0.147700 -vn 0.770261 0.552288 0.318867 -v -0.014250 0.092417 0.147075 -vn 0.770258 -0.000001 -0.637732 -v -0.014250 0.093500 0.148950 -vn 0.609994 -0.396203 -0.686243 -v -0.014250 0.094655 0.149700 -vn 0.770266 0.318861 -0.552284 -v -0.014250 0.092875 0.148783 -vn 0.770259 0.552293 -0.318864 -v -0.014250 0.092417 0.148325 -vn 0.770266 -0.318863 -0.552284 -v -0.014250 0.094125 0.148783 -vn 0.770259 -0.552293 -0.318864 -v -0.014250 0.094583 0.148325 -vn 0.609994 -0.792406 0.000000 -v -0.014250 0.095809 0.147700 -vn 0.770264 -0.637725 -0.000000 -v -0.014250 0.094750 0.147700 -vn 0.770261 -0.552288 0.318867 -v -0.014250 0.094583 0.147075 -vn 0.770261 -0.318867 0.552288 -v -0.014250 0.094125 0.146617 -vn 0.770264 -0.000001 0.637726 -v -0.014250 0.093500 0.146450 -vn 0.770261 0.318866 0.552288 -v -0.014250 0.092875 0.146617 -vn -0.075085 -0.113763 -0.990667 -v -0.012750 0.092000 0.149700 -vn -0.609994 -0.396204 -0.686243 -v -0.012750 0.094655 0.149700 -vn -0.609995 -0.792406 -0.000000 -v -0.012750 0.095809 0.147700 -vn -0.846478 -0.452906 -0.279911 -v -0.012750 0.094000 0.148700 -vn -0.846478 -0.452907 0.279911 -v -0.012750 0.094000 0.146700 -vn -0.609994 0.686243 0.396205 -v -0.012750 0.096750 0.152045 -vn 0.609994 0.686243 0.396205 -v -0.014250 0.096750 0.152045 -vn -0.075085 0.990667 0.113763 -v -0.012750 0.096750 0.154700 -vn 0.609994 -0.686243 0.396204 -v -0.014250 0.100750 0.152045 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.099833 0.153825 -vn 0.770261 -0.637729 0.000000 -v -0.014250 0.100000 0.153200 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.099833 0.152575 -vn 0.609995 -0.000001 0.792405 -v -0.014250 0.098750 0.150891 -vn 0.770265 -0.318861 0.552286 -v -0.014250 0.099375 0.152117 -vn 0.770264 0.637725 0.000000 -v -0.014250 0.097500 0.153200 -vn 0.770262 0.552286 -0.318869 -v -0.014250 0.097667 0.153825 -vn 0.770260 0.318866 -0.552291 -v -0.014250 0.098125 0.154283 -vn 0.770264 0.000000 -0.637725 -v -0.014250 0.098750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 0.099375 0.154283 -vn 0.770258 0.000000 0.637732 -v -0.014250 0.098750 0.151950 -vn 0.770265 0.318861 0.552286 -v -0.014250 0.098125 0.152117 -vn 0.770260 0.552291 0.318865 -v -0.014250 0.097667 0.152575 -vn -0.075085 -0.990667 0.113763 -v -0.012750 0.100750 0.154700 -vn -0.609994 -0.686243 0.396204 -v -0.012750 0.100750 0.152045 -vn -0.609995 -0.000001 0.792405 -v -0.012750 0.098750 0.150891 -vn -0.846478 -0.279911 0.452907 -v -0.012750 0.099750 0.152700 -vn -0.846478 0.279911 0.452907 -v -0.012750 0.097750 0.152700 -vn -0.609994 0.686243 0.396205 -v -0.012750 0.104750 0.152045 -vn 0.609994 0.686243 0.396205 -v -0.014250 0.104750 0.152045 -vn -0.075085 0.990667 0.113763 -v -0.012750 0.104750 0.154700 -vn 0.609994 -0.686243 0.396204 -v -0.014250 0.108750 0.152045 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.107833 0.153825 -vn 0.770261 -0.637729 -0.000000 -v -0.014250 0.108000 0.153200 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.107833 0.152575 -vn 0.609995 -0.000001 0.792405 -v -0.014250 0.106750 0.150891 -vn 0.770265 -0.318861 0.552286 -v -0.014250 0.107375 0.152117 -vn 0.770261 0.552288 -0.318867 -v -0.014250 0.105667 0.153825 -vn 0.770264 0.637725 0.000000 -v -0.014250 0.105500 0.153200 -vn 0.770258 -0.000001 0.637732 -v -0.014250 0.106750 0.151950 -vn 0.770266 0.318861 0.552284 -v -0.014250 0.106125 0.152117 -vn 0.770259 0.552293 0.318864 -v -0.014250 0.105667 0.152575 -vn 0.770261 0.318866 -0.552288 -v -0.014250 0.106125 0.154283 -vn 0.770264 -0.000001 -0.637726 -v -0.014250 0.106750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 0.107375 0.154283 -vn -0.075085 -0.990667 0.113763 -v -0.012750 0.108750 0.154700 -vn -0.609994 -0.686243 0.396204 -v -0.012750 0.108750 0.152045 -vn -0.609994 0.686243 0.396204 -v -0.012750 0.112750 0.152045 -vn 0.609994 0.686243 0.396204 -v -0.014250 0.112750 0.152045 -vn -0.075085 0.990667 0.113763 -v -0.012750 0.112750 0.154700 -vn 0.770263 0.552286 -0.318865 -v -0.014250 0.113667 0.153825 -vn 0.770261 0.637728 0.000000 -v -0.014250 0.113500 0.153200 -vn 0.770260 0.318865 -0.552291 -v -0.014250 0.114125 0.154283 -vn 0.770264 0.000000 -0.637725 -v -0.014250 0.114750 0.154450 -vn 0.770265 -0.318861 0.552286 -v -0.014250 0.115375 0.152117 -vn 0.609995 0.000001 0.792405 -v -0.014250 0.114750 0.150891 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.115833 0.152575 -vn 0.609994 -0.686243 0.396205 -v -0.014250 0.116750 0.152045 -vn 0.770258 0.000000 0.637732 -v -0.014250 0.114750 0.151950 -vn 0.770265 0.318861 0.552287 -v -0.014250 0.114125 0.152117 -vn 0.770261 0.552291 0.318862 -v -0.014250 0.113667 0.152575 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 0.115375 0.154283 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.115833 0.153825 -vn 0.770261 -0.637729 -0.000000 -v -0.014250 0.116000 0.153200 -vn -0.075085 -0.990667 0.113763 -v -0.012750 0.116750 0.154700 -vn -0.609994 -0.686243 0.396205 -v -0.012750 0.116750 0.152045 -vn -0.609994 0.686243 0.396204 -v -0.012750 0.120750 0.152045 -vn 0.609994 0.686243 0.396204 -v -0.014250 0.120750 0.152045 -vn -0.075085 0.990667 0.113762 -v -0.012750 0.120750 0.154700 -vn 0.770258 0.000000 0.637732 -v -0.014250 0.122750 0.151950 -vn 0.770265 0.318861 0.552286 -v -0.014250 0.122125 0.152117 -vn 0.609995 0.000001 0.792405 -v -0.014250 0.122750 0.150891 -vn 0.609994 -0.686243 0.396205 -v -0.014250 0.124750 0.152045 -vn 0.770263 -0.552286 -0.318865 -v -0.014250 0.123833 0.153825 -vn 0.770261 -0.637729 -0.000000 -v -0.014250 0.124000 0.153200 -vn 0.770261 -0.552291 0.318862 -v -0.014250 0.123833 0.152575 -vn 0.770265 -0.318861 0.552286 -v -0.014250 0.123375 0.152117 -vn 0.770261 0.552291 0.318862 -v -0.014250 0.121667 0.152575 -vn 0.770261 0.637729 0.000000 -v -0.014250 0.121500 0.153200 -vn 0.770263 0.552286 -0.318865 -v -0.014250 0.121667 0.153825 -vn 0.770260 0.318866 -0.552291 -v -0.014250 0.122125 0.154283 -vn 0.770264 -0.000000 -0.637725 -v -0.014250 0.122750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v -0.014250 0.123375 0.154283 -vn -0.075085 -0.990667 0.113763 -v -0.012750 0.124750 0.154700 -vn -0.609994 -0.686243 0.396205 -v -0.012750 0.124750 0.152045 -vn -0.609995 -0.000001 0.792405 -v -0.012750 0.106750 0.150891 -vn -0.846478 -0.279911 0.452907 -v -0.012750 0.107750 0.152700 -vn -0.846478 0.279911 0.452907 -v -0.012750 0.105750 0.152700 -vn -0.609995 0.000001 0.792405 -v -0.012750 0.114750 0.150891 -vn -0.846478 -0.279911 0.452907 -v -0.012750 0.115750 0.152700 -vn -0.846478 0.279911 0.452907 -v -0.012750 0.113750 0.152700 -vn -0.609995 0.000001 0.792405 -v -0.012750 0.122750 0.150891 -vn -0.846478 -0.279911 0.452907 -v -0.012750 0.123750 0.152700 -vn -0.846478 0.279911 0.452906 -v -0.012750 0.121750 0.152700 -vn -0.034163 0.454648 0.890016 -v -0.014750 0.136550 0.152670 -vn -0.091615 0.237889 0.966962 -v -0.014550 0.136550 0.152670 -vn -0.414915 0.237223 0.878391 -v -0.014550 0.137545 0.152455 -vn -0.377869 0.392572 0.838512 -v -0.014550 0.137925 0.152314 -vn -0.408214 0.494291 0.767488 -v -0.014550 0.138939 0.151745 -vn -0.375052 0.622823 0.686606 -v -0.014550 0.139179 0.151559 -vn -0.391907 0.711419 0.583346 -v -0.014550 0.140045 0.150639 -vn -0.375403 0.801571 0.465355 -v -0.014550 0.140161 0.150472 -vn -0.371280 0.888944 0.268198 -v -0.014550 0.140786 0.149148 -vn -0.407593 0.057150 0.911373 -v -0.016300 0.139500 0.147200 -vn -0.392038 0.123373 0.911639 -v -0.016300 0.138500 0.147200 -vn -0.678875 0.095838 0.727973 -v -0.014750 0.138500 0.147200 -vn -0.376177 0.217184 0.900734 -v -0.016126 0.140150 0.147200 -vn -0.217185 0.376171 0.900737 -v -0.015650 0.140626 0.147200 -vn -0.057147 0.407588 0.911376 -v -0.015000 0.140800 0.147200 -vn -0.578889 0.574264 0.578885 -v -0.014750 0.140800 0.147200 -vn -0.797140 0.566893 0.207848 -v -0.014750 0.136750 0.152418 -vn -0.393460 0.593606 0.702012 -v -0.014750 0.136729 0.152444 -vn -0.915147 0.166932 0.366932 -v -0.014750 0.137848 0.152130 -vn -0.770263 -0.000003 -0.637727 -v -0.014750 0.138500 0.149950 -vn -0.770262 0.318863 -0.552289 -v -0.014750 0.138000 0.149816 -vn -0.770262 0.552288 -0.318864 -v -0.014750 0.137634 0.149450 -vn -0.678874 0.727973 0.095840 -v -0.014750 0.136750 0.148950 -vn -0.770263 0.637727 0.000002 -v -0.014750 0.137500 0.148950 -vn -0.653227 0.655722 0.378581 -v -0.014750 0.136984 0.148075 -vn -0.770258 0.552294 0.318862 -v -0.014750 0.137634 0.148450 -vn -0.653226 0.378580 0.655723 -v -0.014750 0.137625 0.147434 -vn -0.770264 0.318867 0.552283 -v -0.014750 0.138000 0.148084 -vn -0.770263 -0.000003 0.637727 -v -0.014750 0.138500 0.147950 -vn -0.770261 -0.318866 0.552288 -v -0.014750 0.139000 0.148084 -vn -0.917198 0.397282 0.030260 -v -0.014750 0.140800 0.147700 -vn -0.770261 -0.552288 0.318866 -v -0.014750 0.139366 0.148450 -vn -0.911014 0.394698 0.119447 -v -0.014750 0.140594 0.149090 -vn -0.770263 -0.637727 0.000002 -v -0.014750 0.139500 0.148950 -vn -0.915048 0.341601 0.214465 -v -0.014750 0.139995 0.150362 -vn -0.770265 -0.552283 -0.318868 -v -0.014750 0.139366 0.149450 -vn -0.916111 0.260371 0.304874 -v -0.014750 0.139052 0.151404 -vn -0.770258 -0.318862 -0.552294 -v -0.014750 0.139000 0.149816 -vn -0.392037 0.911639 0.123377 -v -0.016300 0.136750 0.148950 -vn -0.376087 0.925872 0.036325 -v -0.015997 0.136750 0.151161 -vn -0.075601 0.934782 0.347084 -v -0.014940 0.136750 0.152404 -vn -0.358781 0.923541 0.135455 -v -0.015912 0.136750 0.151618 -vn -0.279268 0.928830 0.243484 -v -0.015665 0.136750 0.152016 -vn -0.178102 0.931065 0.318431 -v -0.015372 0.136750 0.152251 -vn -0.406967 0.456724 0.791064 -v -0.016300 0.137625 0.147434 -vn -0.406959 0.791068 0.456722 -v -0.016300 0.136984 0.148075 -vn -0.057148 0.407588 -0.911376 -v -0.015000 0.140800 0.132200 -vn -0.578889 0.574264 -0.578885 -v -0.014750 0.140800 0.132200 -vn -0.678875 0.095838 -0.727973 -v -0.014750 0.138500 0.132200 -vn -0.217184 0.376171 -0.900737 -v -0.015650 0.140626 0.132200 -vn -0.376177 0.217183 -0.900734 -v -0.016126 0.140150 0.132200 -vn -0.407593 0.057150 -0.911373 -v -0.016300 0.139500 0.132200 -vn -0.392036 0.123376 -0.911639 -v -0.016300 0.138500 0.132200 -vn -0.770263 0.637727 0.000002 -v -0.014750 0.137500 0.130450 -vn -0.770258 0.552294 0.318862 -v -0.014750 0.137634 0.129950 -vn -0.503524 0.830930 -0.236681 -v -0.014750 0.136750 0.126959 -vn -0.770265 0.318867 0.552283 -v -0.014750 0.138000 0.129584 -vn -0.916751 0.164411 -0.364055 -v -0.014750 0.137865 0.127277 -vn -0.770263 -0.000003 0.637727 -v -0.014750 0.138500 0.129450 -vn -0.916349 0.262562 -0.302269 -v -0.014750 0.139063 0.128004 -vn -0.770261 -0.318866 0.552288 -v -0.014750 0.139000 0.129584 -vn -0.915132 0.341972 -0.213516 -v -0.014750 0.139999 0.129046 -vn -0.770261 -0.552288 0.318866 -v -0.014750 0.139366 0.129950 -vn -0.911050 0.394731 -0.119057 -v -0.014750 0.140595 0.130314 -vn -0.770263 -0.637727 0.000002 -v -0.014750 0.139500 0.130450 -vn -0.917220 0.397238 -0.030157 -v -0.014750 0.140800 0.131700 -vn -0.770265 -0.552283 -0.318868 -v -0.014750 0.139366 0.130950 -vn -0.770258 -0.318862 -0.552294 -v -0.014750 0.139000 0.131316 -vn -0.770263 -0.000003 -0.637727 -v -0.014750 0.138500 0.131450 -vn -0.653227 0.378580 -0.655723 -v -0.014750 0.137625 0.131966 -vn -0.770262 0.318863 -0.552289 -v -0.014750 0.138000 0.131316 -vn -0.653226 0.655723 -0.378580 -v -0.014750 0.136984 0.131325 -vn -0.770262 0.552288 -0.318864 -v -0.014750 0.137634 0.130950 -vn -0.678875 0.727973 -0.095838 -v -0.014750 0.136750 0.130450 -vn -0.392038 0.911639 -0.123373 -v -0.016300 0.136750 0.130450 -vn -0.406952 0.791069 -0.456728 -v -0.016300 0.136984 0.131325 -vn -0.406950 0.456725 -0.791071 -v -0.016300 0.137625 0.131966 -vn -0.141908 0.919682 -0.366124 -v -0.015215 0.136750 0.127018 -vn -0.036086 0.926992 -0.373341 -v -0.014750 0.136750 0.126932 -vn -0.451010 0.528002 -0.719586 -v -0.014723 0.136750 0.126932 -vn -0.386588 0.922213 -0.008517 -v -0.016050 0.136750 0.128243 -vn -0.396288 0.915772 -0.065703 -v -0.016043 0.136750 0.128111 -vn -0.267255 0.918055 -0.292831 -v -0.015622 0.136750 0.127270 -vn -0.361089 0.915018 -0.179877 -v -0.015908 0.136750 0.127647 -vn -0.133425 -0.907514 0.398267 -v -0.016050 0.098142 0.149496 -vn -0.658764 -0.652395 0.374715 -v -0.014750 0.098016 0.149225 -vn -0.344934 -0.934452 0.088433 -v -0.016050 0.098250 0.150100 -vn -0.658699 -0.752368 0.007638 -v -0.014750 0.098250 0.150100 -vn -0.390795 -0.901666 -0.185142 -v -0.016050 0.098238 0.150307 -vn -0.662041 -0.648877 -0.375048 -v -0.014750 0.098016 0.150975 -vn -0.660766 -0.374858 -0.650284 -v -0.014750 0.097375 0.151616 -vn -0.391319 -0.695162 -0.603009 -v -0.016050 0.097922 0.151120 -vn -0.344697 -0.856585 -0.383988 -v -0.016050 0.098016 0.150975 -vn -0.659322 0.000678 -0.751860 -v -0.014750 0.096500 0.151850 -vn -0.391796 -0.310551 -0.866057 -v -0.016050 0.097253 0.151680 -vn -0.356504 -0.551768 -0.753961 -v -0.016050 0.097375 0.151616 -vn -0.657711 0.377400 -0.651909 -v -0.014750 0.095625 0.151616 -vn -0.407744 0.138371 -0.902551 -v -0.016050 0.096397 0.151847 -vn -0.367177 -0.105610 -0.924136 -v -0.016050 0.096500 0.151850 -vn -0.654706 0.655784 0.375909 -v -0.014750 0.094984 0.149225 -vn -0.422287 0.906197 0.021913 -v -0.016050 0.094750 0.150100 -vn -0.653967 0.756522 0.001408 -v -0.014750 0.094750 0.150100 -vn -0.415232 0.789487 -0.451988 -v -0.016050 0.094967 0.150945 -vn -0.655410 0.654565 -0.376807 -v -0.014750 0.094984 0.150975 -vn -0.393185 0.579374 -0.713955 -v -0.016050 0.095566 0.151580 -vn -0.376620 0.364525 -0.851633 -v -0.016050 0.095625 0.151616 -vn -0.657717 0.377398 0.651905 -v -0.014750 0.095625 0.148584 -vn -0.393186 0.579420 0.713917 -v -0.016050 0.095566 0.148620 -vn -0.406165 0.801282 0.439291 -v -0.016050 0.094967 0.149255 -vn -0.660325 0.002347 0.750976 -v -0.014750 0.096500 0.148350 -vn -0.394650 0.149701 0.906554 -v -0.016050 0.096396 0.148353 -vn -0.380460 0.368052 0.848403 -v -0.016050 0.095625 0.148584 -vn -0.660893 -0.378740 0.647902 -v -0.014750 0.097375 0.148584 -vn -0.126319 -0.444726 0.886714 -v -0.016050 0.097200 0.148496 -vn -0.388740 -0.076502 0.918166 -v -0.016050 0.096500 0.148350 -vn -0.322685 -0.635233 0.701679 -v -0.019050 0.097200 0.148496 -vn -0.352535 -0.505456 0.787549 -v -0.019050 0.097375 0.148584 -vn -0.383267 -0.674648 0.630838 -v -0.019050 0.097771 0.148897 -vn -0.274655 -0.808499 0.520475 -v -0.019050 0.098016 0.149225 -vn -0.323530 -0.727338 0.605234 -v -0.019050 0.098142 0.149496 -vn -0.770265 -0.552286 -0.318861 -v -0.014750 0.097366 0.150600 -vn -0.770259 -0.637731 0.000002 -v -0.014750 0.097500 0.150100 -vn -0.770261 -0.552292 0.318859 -v -0.014750 0.097366 0.149600 -vn -0.770266 -0.318857 0.552286 -v -0.014750 0.097000 0.149234 -vn -0.770255 0.000000 0.637736 -v -0.014750 0.096500 0.149100 -vn -0.770267 0.318856 0.552286 -v -0.014750 0.096000 0.149234 -vn -0.770260 0.552291 0.318864 -v -0.014750 0.095634 0.149600 -vn -0.770263 0.637727 0.000002 -v -0.014750 0.095500 0.150100 -vn -0.770263 0.552285 -0.318866 -v -0.014750 0.095634 0.150600 -vn -0.770261 0.318862 -0.552291 -v -0.014750 0.096000 0.150966 -vn -0.770263 -0.000000 -0.637727 -v -0.014750 0.096500 0.151100 -vn -0.770260 -0.318863 -0.552291 -v -0.014750 0.097000 0.150966 -vn -0.660918 -0.750457 0.001535 -v -0.014750 0.098250 0.129300 -vn -0.660950 -0.647848 -0.378731 -v -0.014750 0.098016 0.130175 -vn -0.090476 -0.901114 -0.424038 -v -0.016050 0.098104 0.130000 -vn -0.081883 -0.464543 -0.881757 -v -0.016050 0.097344 0.130833 -vn -0.656887 -0.375514 -0.653826 -v -0.014750 0.097375 0.130816 -vn -0.420594 0.009037 -0.907204 -v -0.016050 0.096534 0.131050 -vn -0.653089 0.003253 -0.757274 -v -0.014750 0.096500 0.131050 -vn -0.653676 0.375683 -0.656939 -v -0.014750 0.095625 0.130816 -vn -0.656510 0.653208 -0.377245 -v -0.014750 0.094984 0.130175 -vn -0.392622 0.715829 -0.577440 -v -0.016050 0.095013 0.130222 -vn -0.406944 0.434095 -0.803715 -v -0.016050 0.095664 0.130837 -vn -0.657037 0.753858 -0.000055 -v -0.014750 0.094750 0.129300 -vn -0.393740 0.908509 -0.139928 -v -0.016050 0.094751 0.129365 -vn -0.382798 0.850155 -0.361529 -v -0.016050 0.094984 0.130175 -vn -0.657553 0.652475 0.376698 -v -0.014750 0.094984 0.128425 -vn -0.393993 0.857609 0.330570 -v -0.016050 0.094948 0.128491 -vn -0.380926 0.918052 0.109889 -v -0.016050 0.094750 0.129300 -vn -0.658052 0.376451 0.652113 -v -0.014750 0.095625 0.127784 -vn -0.394249 0.579412 0.713337 -v -0.016050 0.095552 0.127829 -vn -0.379008 0.742046 0.552919 -v -0.016050 0.094984 0.128425 -vn -0.658534 -0.000079 0.752551 -v -0.014750 0.096500 0.127550 -vn -0.409687 0.129597 0.902974 -v -0.016050 0.096404 0.127553 -vn -0.391923 0.379767 0.837958 -v -0.016050 0.095625 0.127784 -vn -0.659004 -0.376169 0.651315 -v -0.014750 0.097375 0.127784 -vn -0.394719 -0.322964 0.860169 -v -0.016050 0.097281 0.127734 -vn -0.375119 -0.103443 0.921187 -v -0.016050 0.096500 0.127550 -vn -0.659456 -0.651103 0.375743 -v -0.014750 0.098016 0.128425 -vn -0.394950 -0.707999 0.585450 -v -0.016050 0.097954 0.128326 -vn -0.373134 -0.548756 0.748090 -v -0.016050 0.097375 0.127784 -vn -0.339310 -0.939543 -0.046130 -v -0.016050 0.098250 0.129300 -vn -0.385323 -0.911943 0.141021 -v -0.016050 0.098245 0.129173 -vn -0.371147 -0.849031 0.376027 -v -0.016050 0.098016 0.128425 -vn -0.322188 -0.782879 -0.532256 -v -0.019050 0.098104 0.130000 -vn -0.343791 -0.801454 -0.489366 -v -0.019050 0.098016 0.130175 -vn -0.386041 -0.651031 -0.653553 -v -0.019050 0.097771 0.130503 -vn -0.306528 -0.546494 -0.779349 -v -0.019050 0.097375 0.130816 -vn -0.324538 -0.549218 -0.770087 -v -0.019050 0.097344 0.130833 -vn -0.770265 -0.552286 -0.318861 -v -0.014750 0.097366 0.129800 -vn -0.770259 -0.637731 0.000002 -v -0.014750 0.097500 0.129300 -vn -0.770261 -0.552292 0.318859 -v -0.014750 0.097366 0.128800 -vn -0.770263 -0.318867 0.552285 -v -0.014750 0.097000 0.128434 -vn -0.770262 0.000000 0.637727 -v -0.014750 0.096500 0.128300 -vn -0.770263 0.318866 0.552285 -v -0.014750 0.096000 0.128434 -vn -0.770260 0.552291 0.318864 -v -0.014750 0.095634 0.128800 -vn -0.770263 0.637727 0.000002 -v -0.014750 0.095500 0.129300 -vn -0.770263 0.552285 -0.318866 -v -0.014750 0.095634 0.129800 -vn -0.770261 0.318862 -0.552291 -v -0.014750 0.096000 0.130166 -vn -0.770263 -0.000000 -0.637727 -v -0.014750 0.096500 0.130300 -vn -0.770260 -0.318863 -0.552291 -v -0.014750 0.097000 0.130166 -vn -0.301554 0.027690 -0.953047 -v -0.015269 0.136000 0.126793 -vn -0.517907 0.028992 -0.854946 -v -0.015500 0.136000 0.126901 -vn -0.709505 0.023711 -0.704301 -v -0.015811 0.136000 0.127139 -vn -0.851022 0.021420 -0.524692 -v -0.016049 0.136000 0.127450 -vn -0.951519 0.009599 -0.307441 -v -0.016157 0.136000 0.127681 -vn -0.913757 0.381673 -0.139193 -v -0.016242 0.136553 0.128091 -vn -0.817790 0.405540 -0.408359 -v -0.016086 0.136562 0.127557 -vn -0.615722 0.417654 -0.668170 -v -0.015756 0.136568 0.127122 -vn -0.322013 0.424829 -0.846066 -v -0.015287 0.136572 0.126833 -vn -0.307953 0.026109 0.951043 -v -0.015269 0.136000 0.152607 -vn -0.520724 0.026783 0.853305 -v -0.015500 0.136000 0.152499 -vn -0.702636 0.023042 0.711177 -v -0.015811 0.136000 0.152261 -vn -0.952564 0.010429 0.304158 -v -0.016157 0.136000 0.151719 -vn -0.854006 0.020966 0.519840 -v -0.016049 0.136000 0.151950 -vn -0.177904 0.446646 0.876845 -v -0.014979 0.136550 0.152652 -vn -0.445567 0.445003 0.776816 -v -0.015498 0.136547 0.152469 -vn -0.671644 0.437030 0.598247 -v -0.015850 0.136543 0.152187 -vn -0.850368 0.422558 0.313559 -v -0.016148 0.136534 0.151709 -vn -0.807283 0.466083 0.362024 -v -0.016299 0.140250 0.147000 -vn -0.807283 0.466082 -0.362024 -v -0.016299 0.140250 0.132400 -vn -0.466085 0.807280 0.362028 -v -0.015750 0.140799 0.147000 -vn -0.466084 0.807280 -0.362028 -v -0.015750 0.140799 0.132400 -vn -0.680956 0.732325 -0.000000 -v -0.015750 0.120400 0.139700 -vn -0.680957 0.711043 -0.175257 -v -0.015750 0.120664 0.141878 -vn -0.680956 0.648441 -0.340328 -v -0.015750 0.121442 0.143929 -vn -0.680957 0.548153 -0.485620 -v -0.015750 0.122689 0.145734 -vn -0.680956 0.416008 -0.602690 -v -0.015750 0.124331 0.147189 -vn -0.680956 0.259685 -0.684735 -v -0.015750 0.126273 0.148209 -vn -0.680957 0.088271 -0.726984 -v -0.015750 0.128403 0.148734 -vn -0.680957 -0.088271 -0.726985 -v -0.015750 0.130597 0.148734 -vn -0.680956 -0.259685 -0.684735 -v -0.015750 0.132727 0.148209 -vn -0.680956 -0.416009 -0.602691 -v -0.015750 0.134669 0.147189 -vn -0.680957 -0.548152 -0.485620 -v -0.015750 0.136311 0.145734 -vn -0.680956 -0.648441 -0.340329 -v -0.015750 0.137558 0.143929 -vn -0.680957 -0.711044 -0.175257 -v -0.015750 0.138336 0.141878 -vn -0.680956 -0.732325 0.000000 -v -0.015750 0.138600 0.139700 -vn -0.680957 -0.711043 0.175257 -v -0.015750 0.138336 0.137522 -vn -0.680956 -0.648441 0.340329 -v -0.015750 0.137558 0.135471 -vn -0.680957 -0.548151 0.485622 -v -0.015750 0.136311 0.133666 -vn -0.680956 -0.416007 0.602691 -v -0.015750 0.134669 0.132211 -vn -0.680957 -0.259687 0.684734 -v -0.015750 0.132727 0.131191 -vn -0.680956 -0.088274 0.726985 -v -0.015750 0.130597 0.130666 -vn -0.680956 0.088274 0.726985 -v -0.015750 0.128403 0.130666 -vn -0.680957 0.259687 0.684734 -v -0.015750 0.126273 0.131191 -vn -0.680957 0.416007 0.602691 -v -0.015750 0.124331 0.132211 -vn -0.680956 0.548152 0.485622 -v -0.015750 0.122689 0.133666 -vn -0.680956 0.648441 0.340328 -v -0.015750 0.121442 0.135471 -vn -0.680957 0.711043 0.175257 -v -0.015750 0.120664 0.137522 -vn -0.740587 -0.440041 -0.507833 -v -0.015750 0.125112 0.134636 -vn -0.740586 -0.565291 -0.363289 -v -0.015750 0.123864 0.136078 -vn -0.740587 -0.644742 -0.189313 -v -0.015750 0.123071 0.137812 -vn -0.740586 -0.671961 -0.000000 -v -0.015750 0.122800 0.139700 -vn -0.740587 -0.644741 0.189313 -v -0.015750 0.123071 0.141588 -vn -0.740585 -0.565292 0.363289 -v -0.015750 0.123864 0.143322 -vn -0.740586 0.565291 -0.363289 -v -0.015750 0.135136 0.136078 -vn -0.740587 0.440041 -0.507834 -v -0.015750 0.133888 0.134636 -vn -0.740586 0.279144 -0.611238 -v -0.015750 0.132283 0.133605 -vn -0.740587 0.095631 -0.665121 -v -0.015750 0.130453 0.133068 -vn -0.740587 -0.095631 -0.665121 -v -0.015750 0.128546 0.133068 -vn -0.740586 -0.279144 -0.611238 -v -0.015750 0.126717 0.133605 -vn -0.740588 -0.440042 0.507832 -v -0.015750 0.125112 0.144764 -vn -0.740587 -0.279141 0.611238 -v -0.015750 0.126717 0.145795 -vn -0.740586 -0.095629 0.665122 -v -0.015750 0.128546 0.146332 -vn -0.740586 0.095629 0.665122 -v -0.015750 0.130453 0.146332 -vn -0.740587 0.279141 0.611238 -v -0.015750 0.132283 0.145795 -vn -0.740588 0.440042 0.507832 -v -0.015750 0.133888 0.144764 -vn -0.740585 0.565292 0.363289 -v -0.015750 0.135136 0.143322 -vn -0.740587 0.644741 0.189313 -v -0.015750 0.135929 0.141588 -vn -0.740586 0.671961 -0.000000 -v -0.015750 0.136200 0.139700 -vn -0.740587 0.644742 -0.189313 -v -0.015750 0.135929 0.137812 -vn -0.676434 -0.736503 -0.000000 -v -0.016500 0.122800 0.139700 -vn -0.676433 -0.706670 0.207497 -v -0.016500 0.123071 0.141588 -vn -0.676435 -0.619586 0.398182 -v -0.016500 0.123864 0.143322 -vn -0.676433 -0.482310 0.556611 -v -0.016500 0.125112 0.144764 -vn -0.676433 -0.305953 0.669948 -v -0.016500 0.126717 0.145795 -vn -0.676434 -0.104814 0.729007 -v -0.016500 0.128546 0.146332 -vn -0.676434 0.104814 0.729007 -v -0.016500 0.130453 0.146332 -vn -0.676433 0.305953 0.669948 -v -0.016500 0.132283 0.145795 -vn -0.676433 0.482310 0.556611 -v -0.016500 0.133888 0.144764 -vn -0.676435 0.619586 0.398182 -v -0.016500 0.135136 0.143322 -vn -0.676433 0.706670 0.207497 -v -0.016500 0.135929 0.141588 -vn -0.676434 0.736503 -0.000000 -v -0.016500 0.136200 0.139700 -vn -0.676434 0.706670 -0.207497 -v -0.016500 0.135929 0.137812 -vn -0.676434 0.619587 -0.398183 -v -0.016500 0.135136 0.136078 -vn -0.676433 0.482308 -0.556612 -v -0.016500 0.133888 0.134636 -vn -0.676434 0.305955 -0.669946 -v -0.016500 0.132283 0.133605 -vn -0.676433 0.104817 -0.729007 -v -0.016500 0.130453 0.133068 -vn -0.676433 -0.104817 -0.729007 -v -0.016500 0.128546 0.133068 -vn -0.676434 -0.305955 -0.669946 -v -0.016500 0.126717 0.133605 -vn -0.676433 -0.482308 -0.556612 -v -0.016500 0.125112 0.134636 -vn -0.676434 -0.619587 -0.398183 -v -0.016500 0.123864 0.136078 -vn -0.676434 -0.706670 -0.207497 -v -0.016500 0.123071 0.137812 -vn -0.746100 0.163452 0.645460 -v -0.016500 0.128334 0.135095 -vn -0.746098 0.364178 0.557415 -v -0.016500 0.126902 0.135723 -vn -0.746099 0.525436 0.408966 -v -0.016500 0.125752 0.136782 -vn -0.746100 0.629758 0.216193 -v -0.016500 0.125007 0.138158 -vn -0.746096 0.665838 0.000001 -v -0.016500 0.124750 0.139700 -vn -0.746101 0.629757 -0.216194 -v -0.016500 0.125007 0.141242 -vn -0.746098 0.525436 -0.408967 -v -0.016500 0.125752 0.142617 -vn -0.746098 0.364178 -0.557415 -v -0.016500 0.126902 0.143677 -vn -0.746099 -0.656754 0.109592 -v -0.016500 0.134185 0.138918 -vn -0.746099 -0.585585 0.316902 -v -0.016500 0.133677 0.137439 -vn -0.746099 -0.450958 0.489871 -v -0.016500 0.132717 0.136205 -vn -0.746099 -0.267463 0.609754 -v -0.016500 0.131408 0.135350 -vn -0.746098 -0.054986 0.663562 -v -0.016500 0.129892 0.134966 -vn -0.746099 0.163456 -0.645460 -v -0.016500 0.128334 0.144305 -vn -0.746100 -0.054982 -0.663560 -v -0.016500 0.129892 0.144434 -vn -0.746099 -0.267463 -0.609754 -v -0.016500 0.131408 0.144050 -vn -0.746099 -0.450958 -0.489871 -v -0.016500 0.132717 0.143195 -vn -0.746099 -0.585585 -0.316902 -v -0.016500 0.133677 0.141961 -vn -0.746099 -0.656754 -0.109592 -v -0.016500 0.134185 0.140482 -vn -0.671871 0.740669 0.000000 -v -0.014000 0.124750 0.139700 -vn -0.671867 0.700541 -0.240494 -v -0.014000 0.125007 0.141242 -vn -0.671869 0.584491 -0.454932 -v -0.014000 0.125752 0.142617 -vn -0.671869 0.405108 -0.620064 -v -0.014000 0.126902 0.143677 -vn -0.671869 0.181827 -0.718005 -v -0.014000 0.128334 0.144305 -vn -0.671868 -0.061162 -0.738141 -v -0.014000 0.129892 0.144434 -vn -0.671868 -0.297524 -0.678286 -v -0.014000 0.131408 0.144050 -vn -0.671869 -0.501643 -0.544929 -v -0.014000 0.132717 0.143195 -vn -0.671868 -0.651401 -0.352519 -v -0.014000 0.133677 0.141961 -vn -0.671869 -0.730569 -0.121910 -v -0.014000 0.134185 0.140482 -vn -0.671869 -0.730569 0.121909 -v -0.014000 0.134185 0.138918 -vn -0.671869 -0.651401 0.352519 -v -0.014000 0.133677 0.137439 -vn -0.671869 -0.501643 0.544929 -v -0.014000 0.132717 0.136205 -vn -0.671869 -0.297524 0.678286 -v -0.014000 0.131408 0.135350 -vn -0.671869 -0.061165 0.738140 -v -0.014000 0.129892 0.134966 -vn -0.671868 0.181824 0.718007 -v -0.014000 0.128334 0.135095 -vn -0.671869 0.405108 0.620064 -v -0.014000 0.126902 0.135723 -vn -0.671869 0.584492 0.454930 -v -0.014000 0.125752 0.136782 -vn -0.671867 0.700541 0.240493 -v -0.014000 0.125007 0.138158 -vn -1.000000 -0.000000 -0.000000 -v -0.014000 0.129500 0.139700 -vn 0.770261 0.552291 0.318862 -v 0.015750 0.113667 0.125575 -vn 0.770261 0.637728 -0.000000 -v 0.015750 0.113500 0.126200 -vn 0.923880 0.000000 -0.382683 -v 0.015750 0.112250 0.124700 -vn 0.987815 -0.110050 -0.110049 -v 0.015750 0.117500 0.149500 -vn 0.923879 -0.382686 0.000001 -v 0.015750 0.117500 0.148825 -vn 1.000000 -0.000000 0.000001 -v 0.015750 0.122000 0.148825 -vn 0.991004 0.005386 0.133726 -v 0.015750 0.136000 0.151700 -vn 0.997001 0.041899 0.065065 -v 0.015750 0.127500 0.151700 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.129700 0.149600 -vn 0.973781 0.131340 0.185743 -v 0.015750 0.126000 0.152700 -vn 0.707107 0.707107 0.000000 -v 0.015750 0.126000 0.154575 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.124050 0.154575 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 0.095500 0.126700 -vn 0.717284 -0.630263 -0.297108 -v 0.015750 0.095500 0.124700 -vn 0.923880 0.000000 -0.382683 -v 0.015750 0.095875 0.124700 -vn 0.945448 0.162882 0.282131 -v 0.015750 0.136500 0.144834 -vn 0.736823 0.642996 0.208921 -v 0.015750 0.134636 0.141369 -vn 0.945447 0.000001 0.325777 -v 0.015750 0.137000 0.144700 -vn 0.736825 0.676083 -0.000000 -v 0.015750 0.134900 0.139700 -vn 0.945452 -0.162876 0.282119 -v 0.015750 0.137500 0.144834 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.129700 0.148825 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.129700 0.145775 -vn 0.945437 0.325805 0.000004 -v 0.015750 0.136000 0.145700 -vn 0.945453 0.282114 -0.162884 -v 0.015750 0.136134 0.146200 -vn 0.945438 0.162903 -0.282151 -v 0.015750 0.136500 0.146566 -vn 0.990580 0.130230 0.042316 -v 0.015750 0.139804 0.148936 -vn 0.945448 -0.000002 -0.325774 -v 0.015750 0.137000 0.146700 -vn 0.945444 -0.162894 -0.282138 -v 0.015750 0.137500 0.146566 -vn 0.945438 -0.282156 0.162897 -v 0.015750 0.137866 0.145200 -vn 0.991445 0.130529 0.000000 -v 0.015750 0.140000 0.139700 -vn 0.945448 -0.325773 0.000004 -v 0.015750 0.138000 0.145700 -vn 0.991444 0.130529 0.000000 -v 0.015750 0.140000 0.145775 -vn 0.945443 -0.282138 -0.162897 -v 0.015750 0.137866 0.146200 -vn 0.991003 0.133729 0.005386 -v 0.015750 0.140000 0.147700 -vn 0.990580 0.135247 0.021421 -v 0.015750 0.139951 0.148326 -vn 0.770265 0.318861 0.552286 -v 0.015750 0.122125 0.152117 -vn 0.770261 0.552291 0.318862 -v 0.015750 0.121667 0.152575 -vn 0.973781 -0.131340 0.185743 -v 0.015750 0.119500 0.152700 -vn 0.770261 0.637728 -0.000000 -v 0.015750 0.121500 0.153200 -vn 0.707107 -0.707107 0.000000 -v 0.015750 0.119500 0.154575 -vn 0.770263 0.552286 -0.318865 -v 0.015750 0.121667 0.153825 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.122000 0.154575 -vn 0.770260 0.318866 -0.552291 -v 0.015750 0.122125 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.015750 0.122750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 0.123375 0.154283 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.123833 0.153825 -vn 0.770258 0.000000 0.637732 -v 0.015750 0.122750 0.151950 -vn 1.000000 -0.000000 0.000001 -v 0.015750 0.122000 0.149600 -vn 0.770265 -0.318861 0.552286 -v 0.015750 0.123375 0.152117 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.124050 0.149600 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.123833 0.152575 -vn 0.770261 -0.637728 0.000000 -v 0.015750 0.124000 0.153200 -vn 0.770266 0.318862 0.552284 -v 0.015750 0.106125 0.152117 -vn 0.973781 -0.131340 0.185743 -v 0.015750 0.103500 0.152700 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.106250 0.149600 -vn 0.770266 0.318854 0.552289 -v 0.015750 0.103850 0.149660 -vn 0.770261 0.552288 0.318866 -v 0.015750 0.103960 0.149550 -vn 0.770259 0.552293 0.318864 -v 0.015750 0.105667 0.152575 -vn 0.770264 0.637725 -0.000000 -v 0.015750 0.105500 0.153200 -vn 0.707107 -0.707107 0.000000 -v 0.015750 0.103500 0.154575 -vn 0.770261 0.552288 -0.318867 -v 0.015750 0.105667 0.153825 -vn 1.000000 0.000001 -0.000001 -v 0.015750 0.106250 0.154575 -vn 0.973781 0.131340 0.185743 -v 0.015750 0.110000 0.152700 -vn 0.707107 0.707107 -0.000000 -v 0.015750 0.110000 0.154575 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.107833 0.153825 -vn 0.770261 -0.637728 0.000000 -v 0.015750 0.108000 0.153200 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.107833 0.152575 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.110000 0.149600 -vn 0.770264 -0.318861 0.552287 -v 0.015750 0.107375 0.152117 -vn 0.770258 0.000000 0.637733 -v 0.015750 0.106750 0.151950 -vn 0.770261 0.318867 -0.552288 -v 0.015750 0.106125 0.154283 -vn 0.770260 -0.000000 -0.637730 -v 0.015750 0.106750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 0.107375 0.154283 -vn 0.770264 -0.637725 -0.000000 -v 0.015750 0.094750 0.147700 -vn 0.770261 -0.552288 0.318867 -v 0.015750 0.094583 0.147075 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.095875 0.145775 -vn 0.770261 -0.318867 0.552288 -v 0.015750 0.094125 0.146617 -vn 0.770264 -0.000001 0.637726 -v 0.015750 0.093500 0.146450 -vn 0.923880 -0.382683 0.000000 -v 0.015750 0.092000 0.145775 -vn 0.770261 0.318866 0.552288 -v 0.015750 0.092875 0.146617 -vn 0.770261 0.552288 0.318867 -v 0.015750 0.092417 0.147075 -vn 0.770264 0.637725 0.000000 -v 0.015750 0.092250 0.147700 -vn 0.923880 -0.382683 0.000001 -v 0.015750 0.092000 0.148825 -vn 0.770259 0.552293 -0.318864 -v 0.015750 0.092417 0.148325 -vn 0.770267 0.318861 -0.552283 -v 0.015750 0.092875 0.148783 -vn 0.923880 -0.382682 0.000001 -v 0.015750 0.092000 0.149600 -vn 0.770259 -0.000001 -0.637731 -v 0.015750 0.093500 0.148950 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.095875 0.149600 -vn 0.770266 -0.318862 -0.552283 -v 0.015750 0.094125 0.148783 -vn 1.000000 -0.000000 0.000001 -v 0.015750 0.095875 0.148825 -vn 0.770259 -0.552293 -0.318864 -v 0.015750 0.094583 0.148325 -vn 0.923880 0.000000 -0.382683 -v 0.015750 0.116750 0.124700 -vn 0.717284 0.630263 -0.297108 -v 0.015750 0.118000 0.124700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.128575 -vn 0.973781 0.131340 -0.185743 -v 0.015750 0.118000 0.126700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.122000 0.128575 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 0.119500 0.126700 -vn 0.770263 0.552286 -0.318865 -v 0.015750 0.121667 0.126825 -vn 0.770260 0.318866 -0.552291 -v 0.015750 0.122125 0.127283 -vn 0.770264 -0.000000 -0.637725 -v 0.015750 0.122750 0.127450 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.124050 0.128575 -vn 0.923880 0.000000 -0.382683 -v 0.015750 0.124050 0.124700 -vn 0.770261 -0.637729 -0.000000 -v 0.015750 0.124000 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.123833 0.125575 -vn 0.770260 -0.318865 -0.552291 -v 0.015750 0.123375 0.127283 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.123833 0.126825 -vn 0.770265 -0.318861 0.552286 -v 0.015750 0.123375 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.015750 0.122750 0.124950 -vn 0.923880 0.000000 -0.382683 -v 0.015750 0.122000 0.124700 -vn 0.770265 0.318861 0.552286 -v 0.015750 0.122125 0.125117 -vn 0.717284 -0.630263 -0.297108 -v 0.015750 0.119500 0.124700 -vn 0.770261 0.552291 0.318862 -v 0.015750 0.121667 0.125575 -vn 0.770261 0.637728 0.000000 -v 0.015750 0.121500 0.126200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.102000 0.128575 -vn 0.973781 0.131340 -0.185743 -v 0.015750 0.102000 0.126700 -vn 1.000000 0.000000 -0.000000 -v 0.015750 0.106250 0.128575 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 0.103500 0.126700 -vn 0.770261 0.552288 -0.318867 -v 0.015750 0.105667 0.126825 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.107833 0.125575 -vn 0.717284 0.630262 -0.297108 -v 0.015750 0.110000 0.124700 -vn 0.770261 -0.637728 0.000000 -v 0.015750 0.108000 0.126200 -vn 0.973781 0.131340 -0.185743 -v 0.015750 0.110000 0.126700 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.107833 0.126825 -vn 0.770265 -0.318861 0.552286 -v 0.015750 0.107375 0.125117 -vn 0.770256 -0.000000 0.637735 -v 0.015750 0.106750 0.124950 -vn 0.923880 0.000001 -0.382683 -v 0.015750 0.106250 0.124700 -vn 0.770266 0.318862 0.552284 -v 0.015750 0.106125 0.125117 -vn 0.717284 -0.630263 -0.297108 -v 0.015750 0.103500 0.124700 -vn 0.770259 0.552293 0.318864 -v 0.015750 0.105667 0.125575 -vn 0.770264 0.637725 0.000000 -v 0.015750 0.105500 0.126200 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 0.107375 0.127283 -vn 1.000000 0.000000 -0.000000 -v 0.015750 0.110000 0.128575 -vn 0.770263 0.000000 -0.637726 -v 0.015750 0.106750 0.127450 -vn 0.770261 0.318867 -0.552288 -v 0.015750 0.106125 0.127283 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.095875 0.129800 -vn 0.770264 -0.552289 -0.318858 -v 0.015750 0.097040 0.129850 -vn 0.737698 -0.669355 -0.088117 -v 0.015750 0.097000 0.130000 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.095875 0.133625 -vn 0.770258 0.552288 -0.318874 -v 0.015750 0.103960 0.129850 -vn 0.770266 0.318854 -0.552289 -v 0.015750 0.103850 0.129740 -vn 0.737697 0.088113 -0.669358 -v 0.015750 0.103700 0.129700 -vn 0.707107 0.000000 -0.707107 -v 0.015750 0.102000 0.129700 -vn 0.737697 -0.088113 -0.669358 -v 0.015750 0.097300 0.129700 -vn 0.707107 0.707107 0.000000 -v 0.015750 0.104000 0.133625 -vn 0.737704 0.669347 -0.088131 -v 0.015750 0.104000 0.130000 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.106250 0.129800 -vn 0.707107 0.000000 0.707107 -v 0.015750 0.102000 0.135700 -vn 0.737697 0.088113 0.669358 -v 0.015750 0.103700 0.135700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.106250 0.139700 -vn 0.770266 0.318854 0.552289 -v 0.015750 0.103850 0.135660 -vn 0.770261 0.552288 0.318866 -v 0.015750 0.103960 0.135550 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.106250 0.135200 -vn 0.737701 0.669352 0.088124 -v 0.015750 0.104000 0.135400 -vn 0.707107 -0.707107 0.000000 -v 0.015750 0.097000 0.133625 -vn 0.707107 -0.707107 0.000000 -v 0.015750 0.097000 0.135200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.095875 0.135200 -vn 0.737695 -0.669360 0.088109 -v 0.015750 0.097000 0.135400 -vn 0.717284 -0.630263 -0.297108 -v 0.015750 0.111500 0.124700 -vn 0.973781 -0.131340 -0.185743 -v 0.015750 0.111500 0.126700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.112250 0.128575 -vn 0.923880 -0.382683 0.000000 -v 0.015750 0.092000 0.128575 -vn 0.717284 -0.297108 -0.630263 -v 0.015750 0.092000 0.128450 -vn 0.973781 -0.185743 -0.131340 -v 0.015750 0.094000 0.128450 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.095875 0.128575 -vn 0.816496 -0.408249 -0.408249 -v 0.015750 0.094000 0.126700 -vn 0.717284 -0.297108 0.630263 -v 0.015750 0.092000 0.134950 -vn 0.923880 -0.382683 0.000000 -v 0.015750 0.092000 0.133625 -vn 0.973781 -0.185743 0.131340 -v 0.015750 0.094000 0.134950 -vn 0.923879 -0.382684 0.000000 -v 0.015750 0.094000 0.135200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.095875 0.139700 -vn 0.770267 -0.552290 0.318849 -v 0.015750 0.097040 0.135550 -vn 0.717284 -0.297108 -0.630262 -v 0.015750 0.092000 0.144450 -vn 0.973781 -0.185743 -0.131340 -v 0.015750 0.094000 0.144450 -vn 0.923879 -0.382684 0.000000 -v 0.015750 0.094000 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.095875 0.154575 -vn 0.707107 -0.707107 0.000000 -v 0.015750 0.095500 0.154575 -vn 0.973781 -0.131340 0.185743 -v 0.015750 0.095500 0.152700 -vn 0.717284 -0.297108 0.630263 -v 0.015750 0.092000 0.150950 -vn 0.973781 -0.185743 0.131340 -v 0.015750 0.094000 0.150950 -vn 0.816496 -0.408249 0.408248 -v 0.015750 0.094000 0.152700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.112250 0.154575 -vn 0.707107 -0.707107 0.000000 -v 0.015750 0.111500 0.154575 -vn 0.973781 -0.131340 0.185743 -v 0.015750 0.111500 0.152700 -vn 0.717284 -0.630263 0.297108 -v 0.015750 0.111500 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 0.112250 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 0.116750 0.154700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.149600 -vn 0.973781 0.131340 0.185743 -v 0.015750 0.118000 0.152700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.154575 -vn 0.707107 0.707107 0.000000 -v 0.015750 0.118000 0.154575 -vn 0.717284 0.630263 0.297108 -v 0.015750 0.118000 0.154700 -vn 0.717283 0.630262 0.297109 -v 0.015750 0.127500 0.152700 -vn 0.990581 0.122004 0.062167 -v 0.015750 0.139564 0.149516 -vn 0.990580 0.110781 0.080486 -v 0.015750 0.139236 0.150051 -vn 0.990581 0.021422 0.135245 -v 0.015750 0.136626 0.151651 -vn 0.990581 0.042312 0.130225 -v 0.015750 0.137236 0.151504 -vn 0.990581 0.096825 0.096825 -v 0.015750 0.138828 0.150528 -vn 0.990581 0.080485 0.110779 -v 0.015750 0.138351 0.150936 -vn 0.990581 0.062166 0.122006 -v 0.015750 0.137816 0.151264 -vn 0.945437 0.325805 0.000004 -v 0.015750 0.136000 0.133700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.129700 0.133625 -vn 0.945448 0.282131 0.162882 -v 0.015750 0.136134 0.133200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.129700 0.129800 -vn 0.945447 0.162887 0.282132 -v 0.015750 0.136500 0.132834 -vn 0.945449 0.000000 0.325770 -v 0.015750 0.137000 0.132700 -vn 0.990581 0.080484 -0.110776 -v 0.015750 0.138351 0.128464 -vn 0.990581 0.096824 -0.096823 -v 0.015750 0.138828 0.128872 -vn 0.945451 -0.162881 0.282119 -v 0.015750 0.137500 0.132834 -vn 0.990580 0.122007 -0.062167 -v 0.015750 0.139564 0.129884 -vn 0.990581 0.110780 -0.080486 -v 0.015750 0.139236 0.129349 -vn 0.991004 0.005386 -0.133723 -v 0.015750 0.136000 0.127700 -vn 0.990581 0.021421 -0.135242 -v 0.015750 0.136626 0.127749 -vn 0.990581 0.042313 -0.130229 -v 0.015750 0.137236 0.127896 -vn 0.717284 0.630263 -0.297108 -v 0.015750 0.126000 0.124700 -vn 0.973781 0.131340 -0.185743 -v 0.015750 0.126000 0.126700 -vn 0.717283 0.630262 -0.297109 -v 0.015750 0.127500 0.126700 -vn 0.997001 0.041898 -0.065064 -v 0.015750 0.127500 0.127700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.129700 0.128575 -vn 0.973781 0.131340 0.185743 -v 0.015750 0.102000 0.152700 -vn 0.707107 0.707107 0.000000 -v 0.015750 0.102000 0.154575 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.099833 0.153825 -vn 0.770261 -0.637729 -0.000000 -v 0.015750 0.100000 0.153200 -vn 0.707107 0.000000 0.707107 -v 0.015750 0.102000 0.149700 -vn 0.737697 0.088113 0.669358 -v 0.015750 0.103700 0.149700 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.099833 0.152575 -vn 0.770265 -0.318861 0.552286 -v 0.015750 0.099375 0.152117 -vn 0.737697 -0.088113 0.669358 -v 0.015750 0.097300 0.149700 -vn 0.770258 0.000000 0.637732 -v 0.015750 0.098750 0.151950 -vn 0.770265 -0.318854 0.552289 -v 0.015750 0.097150 0.149660 -vn 0.770265 0.318861 0.552286 -v 0.015750 0.098125 0.152117 -vn 0.770260 0.552291 0.318865 -v 0.015750 0.097667 0.152575 -vn 0.770264 0.637725 -0.000000 -v 0.015750 0.097500 0.153200 -vn 0.770262 0.552286 -0.318869 -v 0.015750 0.097667 0.153825 -vn 0.770260 0.318866 -0.552291 -v 0.015750 0.098125 0.154283 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.097250 0.154575 -vn 0.770264 -0.000000 -0.637725 -v 0.015750 0.098750 0.154450 -vn 0.770260 -0.318865 -0.552291 -v 0.015750 0.099375 0.154283 -vn 0.770267 -0.552290 0.318849 -v 0.015750 0.097040 0.149550 -vn 0.707107 -0.707107 0.000001 -v 0.015750 0.097000 0.148825 -vn 0.737696 -0.669359 0.088110 -v 0.015750 0.097000 0.149400 -vn 0.737697 -0.088113 -0.669358 -v 0.015750 0.097300 0.143700 -vn 0.770266 -0.318854 -0.552289 -v 0.015750 0.097150 0.143740 -vn 0.770264 -0.552289 -0.318858 -v 0.015750 0.097040 0.143850 -vn 0.737698 -0.669355 -0.088117 -v 0.015750 0.097000 0.144000 -vn 0.707107 -0.707107 0.000000 -v 0.015750 0.097000 0.145775 -vn 0.737697 0.088113 -0.669358 -v 0.015750 0.103700 0.143700 -vn 0.707107 0.000000 -0.707107 -v 0.015750 0.102000 0.143700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.102000 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.097250 0.139700 -vn 0.770265 -0.318854 0.552289 -v 0.015750 0.097150 0.135660 -vn 0.770266 0.318854 -0.552289 -v 0.015750 0.103850 0.143740 -vn 0.737697 -0.088113 0.669358 -v 0.015750 0.097300 0.135700 -vn 0.737701 0.669351 0.088125 -v 0.015750 0.104000 0.149400 -vn 0.707106 0.707107 0.000001 -v 0.015750 0.104000 0.148825 -vn 1.000000 0.000001 0.000001 -v 0.015750 0.106250 0.148825 -vn 0.707107 0.707107 0.000000 -v 0.015750 0.104000 0.145775 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.106250 0.145775 -vn 0.737704 0.669347 -0.088131 -v 0.015750 0.104000 0.144000 -vn 0.770258 0.552288 -0.318874 -v 0.015750 0.103960 0.143850 -vn 0.973781 -0.185742 -0.131340 -v 0.015750 0.117500 0.139200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.122000 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.122000 0.135200 -vn 1.000000 0.000000 -0.000000 -v 0.015750 0.110000 0.133625 -vn 0.923880 0.382683 -0.000000 -v 0.015750 0.111000 0.133625 -vn 0.923880 0.382683 0.000000 -v 0.015750 0.111000 0.135200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.112250 0.129800 -vn 0.923881 0.000000 0.382679 -v 0.015750 0.112250 0.129900 -vn 0.987815 0.110049 0.110050 -v 0.015750 0.111000 0.129900 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.110000 0.129800 -vn 0.923881 0.000000 0.382680 -v 0.015750 0.116750 0.129900 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.129800 -vn 0.987815 -0.110050 0.110050 -v 0.015750 0.117500 0.129900 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.122000 0.145775 -vn 0.923880 -0.382683 0.000000 -v 0.015750 0.117500 0.145775 -vn 0.973781 -0.185742 0.131340 -v 0.015750 0.117500 0.140200 -vn 0.707107 0.000000 0.707107 -v 0.015750 0.116750 0.140200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.112250 0.139700 -vn 0.707107 0.000000 0.707107 -v 0.015750 0.112250 0.140200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.110000 0.139700 -vn 0.973781 0.185742 0.131340 -v 0.015750 0.111000 0.140200 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.110000 0.145775 -vn 0.923880 0.382683 0.000000 -v 0.015750 0.111000 0.145775 -vn 0.923879 0.382685 0.000001 -v 0.015750 0.111000 0.148825 -vn 0.736826 -0.546962 0.397391 -v 0.015750 0.125131 0.142874 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.124050 0.145775 -vn 0.736823 -0.642996 0.208920 -v 0.015750 0.124364 0.141369 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.124050 0.139700 -vn 0.736823 -0.397393 0.546965 -v 0.015750 0.126326 0.144069 -vn 0.736825 -0.208922 0.642993 -v 0.015750 0.127831 0.144836 -vn 0.736822 0.000000 0.676086 -v 0.015750 0.129500 0.145100 -vn 0.736825 0.208922 0.642993 -v 0.015750 0.131169 0.144836 -vn 0.945448 0.282131 0.162882 -v 0.015750 0.136134 0.145200 -vn 0.736823 0.397393 0.546965 -v 0.015750 0.132674 0.144069 -vn 0.736826 0.546962 0.397392 -v 0.015750 0.133869 0.142874 -vn 0.736824 -0.397392 -0.546965 -v 0.015750 0.126326 0.135331 -vn 0.736825 -0.546965 -0.397391 -v 0.015750 0.125131 0.136526 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.124050 0.135200 -vn 0.736824 -0.642995 -0.208922 -v 0.015750 0.124364 0.138031 -vn 0.736824 -0.676085 0.000000 -v 0.015750 0.124100 0.139700 -vn 0.945446 0.162887 -0.282133 -v 0.015750 0.136500 0.134566 -vn 0.945449 0.000001 -0.325771 -v 0.015750 0.137000 0.134700 -vn 0.736824 0.397392 -0.546965 -v 0.015750 0.132674 0.135331 -vn 0.991445 0.130529 0.000000 -v 0.015750 0.140000 0.135200 -vn 0.736824 0.546964 -0.397392 -v 0.015750 0.133869 0.136526 -vn 0.736823 -0.208922 -0.642996 -v 0.015750 0.127831 0.134564 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.124050 0.133625 -vn 0.736825 0.000000 -0.676083 -v 0.015750 0.129500 0.134300 -vn 0.736823 0.208922 -0.642996 -v 0.015750 0.131169 0.134564 -vn 0.945453 0.282114 -0.162884 -v 0.015750 0.136134 0.134200 -vn 0.990580 0.130230 -0.042314 -v 0.015750 0.139804 0.130464 -vn 0.990580 0.135246 -0.021420 -v 0.015750 0.139951 0.131074 -vn 0.945438 -0.282156 0.162897 -v 0.015750 0.137866 0.133200 -vn 0.991003 0.133728 -0.005386 -v 0.015750 0.140000 0.131700 -vn 0.945448 -0.325773 0.000004 -v 0.015750 0.138000 0.133700 -vn 0.991445 0.130529 0.000000 -v 0.015750 0.140000 0.133625 -vn 0.945444 -0.282135 -0.162899 -v 0.015750 0.137866 0.134200 -vn 0.945452 -0.162883 -0.282117 -v 0.015750 0.137500 0.134566 -vn 0.736823 0.642995 -0.208922 -v 0.015750 0.134636 0.138031 -vn 0.945443 0.325788 0.000003 -v 0.015750 0.122500 0.147700 -vn 0.945453 0.282113 -0.162884 -v 0.015750 0.122634 0.148200 -vn 0.945447 0.162887 0.282132 -v 0.015750 0.123000 0.146834 -vn 0.945447 0.282132 0.162885 -v 0.015750 0.122634 0.147200 -vn 0.945448 -0.325772 0.000002 -v 0.015750 0.124500 0.147700 -vn 0.945442 -0.282144 0.162892 -v 0.015750 0.124366 0.147200 -vn 0.945449 -0.162884 0.282126 -v 0.015750 0.124000 0.146834 -vn 0.945449 0.000000 0.325770 -v 0.015750 0.123500 0.146700 -vn 0.945446 0.162887 -0.282133 -v 0.015750 0.123000 0.148566 -vn 0.945449 0.000001 -0.325771 -v 0.015750 0.123500 0.148700 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.124050 0.148825 -vn 0.945449 -0.162885 -0.282126 -v 0.015750 0.124000 0.148566 -vn 0.945448 -0.282126 -0.162891 -v 0.015750 0.124366 0.148200 -vn 0.945453 0.282113 -0.162884 -v 0.015750 0.122634 0.132200 -vn 0.945438 0.162903 -0.282151 -v 0.015750 0.123000 0.132566 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.122000 0.133625 -vn 0.945443 0.325788 0.000003 -v 0.015750 0.122500 0.131700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.124050 0.129800 -vn 0.945437 -0.000003 0.325804 -v 0.015750 0.123500 0.130700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.122000 0.129800 -vn 0.945447 0.162887 0.282132 -v 0.015750 0.123000 0.130834 -vn 0.945447 0.282132 0.162885 -v 0.015750 0.122634 0.131200 -vn 0.923880 -0.382683 -0.000000 -v 0.015750 0.117500 0.133625 -vn 0.923880 -0.382683 0.000000 -v 0.015750 0.117500 0.135200 -vn 0.945442 -0.282144 0.162892 -v 0.015750 0.124366 0.131200 -vn 0.945450 -0.162879 0.282125 -v 0.015750 0.124000 0.130834 -vn 0.945448 -0.000003 -0.325774 -v 0.015750 0.123500 0.132700 -vn 0.945441 -0.162895 -0.282147 -v 0.015750 0.124000 0.132566 -vn 0.945447 -0.282129 -0.162889 -v 0.015750 0.124366 0.132200 -vn 0.945448 -0.325772 0.000002 -v 0.015750 0.124500 0.131700 -vn 0.717284 -0.630263 0.297108 -v 0.015750 0.119500 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 0.122000 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 0.124050 0.154700 -vn 0.717284 0.630263 0.297108 -v 0.015750 0.126000 0.154700 -vn 0.717284 -0.630263 0.297108 -v 0.015750 0.103500 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 0.106250 0.154700 -vn 0.717284 0.630263 0.297108 -v 0.015750 0.110000 0.154700 -vn 0.717284 -0.630263 0.297108 -v 0.015750 0.095500 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 0.095875 0.154700 -vn 0.923880 0.000000 0.382683 -v 0.015750 0.097250 0.154700 -vn 0.717284 0.630262 0.297108 -v 0.015750 0.102000 0.154700 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.112250 0.149600 -vn 0.770261 0.552291 0.318862 -v 0.015750 0.113667 0.152575 -vn 0.770261 0.637728 -0.000000 -v 0.015750 0.113500 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.015750 0.113667 0.153825 -vn 0.770260 0.318866 -0.552291 -v 0.015750 0.114125 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.015750 0.114750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 0.115375 0.154283 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.115833 0.152575 -vn 0.770261 -0.637728 0.000000 -v 0.015750 0.116000 0.153200 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.115833 0.153825 -vn 0.770265 -0.318861 0.552286 -v 0.015750 0.115375 0.152117 -vn 0.770258 -0.000000 0.637732 -v 0.015750 0.114750 0.151950 -vn 0.770265 0.318861 0.552287 -v 0.015750 0.114125 0.152117 -vn 1.000000 0.000000 0.000001 -v 0.015750 0.110000 0.148825 -vn 0.945447 0.325775 -0.000000 -v 0.015750 0.107000 0.147700 -vn 0.945448 0.282126 -0.162890 -v 0.015750 0.107134 0.148200 -vn 0.945453 -0.282116 -0.162880 -v 0.015750 0.108866 0.148200 -vn 0.945443 -0.325787 -0.000001 -v 0.015750 0.109000 0.147700 -vn 0.945448 0.162884 -0.282128 -v 0.015750 0.107500 0.148566 -vn 0.945448 0.000001 -0.325775 -v 0.015750 0.108000 0.148700 -vn 0.945449 -0.162885 -0.282126 -v 0.015750 0.108500 0.148566 -vn 0.987815 0.110050 -0.110049 -v 0.015750 0.111000 0.149500 -vn 0.923882 0.000000 -0.382678 -v 0.015750 0.112250 0.149500 -vn 0.923881 0.000000 -0.382679 -v 0.015750 0.116750 0.149500 -vn 0.945446 -0.282134 0.162886 -v 0.015750 0.108866 0.147200 -vn 0.945449 -0.162885 0.282124 -v 0.015750 0.108500 0.146834 -vn 0.945449 -0.000000 0.325771 -v 0.015750 0.108000 0.146700 -vn 0.945442 0.282143 0.162896 -v 0.015750 0.107134 0.147200 -vn 0.945449 0.162886 0.282123 -v 0.015750 0.107500 0.146834 -vn 1.000000 0.000000 -0.000000 -v 0.015750 0.106250 0.133625 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.110000 0.135200 -vn 0.973781 0.185742 -0.131340 -v 0.015750 0.111000 0.139200 -vn 0.707107 0.000000 -0.707107 -v 0.015750 0.112250 0.139200 -vn 0.707107 0.000000 -0.707107 -v 0.015750 0.116750 0.139200 -vn 0.945448 0.325774 -0.000001 -v 0.015750 0.107000 0.131700 -vn 0.945448 0.282126 -0.162890 -v 0.015750 0.107134 0.132200 -vn 0.945442 0.282142 0.162896 -v 0.015750 0.107134 0.131200 -vn 0.707107 0.707107 0.000000 -v 0.015750 0.104000 0.135200 -vn 0.945441 -0.162895 -0.282147 -v 0.015750 0.108500 0.132566 -vn 0.945448 -0.000003 -0.325774 -v 0.015750 0.108000 0.132700 -vn 0.945440 0.162901 -0.282145 -v 0.015750 0.107500 0.132566 -vn 0.945452 -0.282119 -0.162879 -v 0.015750 0.108866 0.132200 -vn 0.945443 -0.325787 -0.000001 -v 0.015750 0.109000 0.131700 -vn 0.945446 -0.282134 0.162886 -v 0.015750 0.108866 0.131200 -vn 0.945450 -0.162880 0.282123 -v 0.015750 0.108500 0.130834 -vn 0.945437 -0.000003 0.325805 -v 0.015750 0.108000 0.130700 -vn 0.945449 0.162885 0.282124 -v 0.015750 0.107500 0.130834 -vn 0.770259 0.552293 -0.318864 -v 0.015750 0.092417 0.132325 -vn 0.770264 0.637725 -0.000000 -v 0.015750 0.092250 0.131700 -vn 0.923880 -0.382683 0.000000 -v 0.015750 0.092000 0.129800 -vn 0.770261 0.552288 0.318867 -v 0.015750 0.092417 0.131075 -vn 0.770261 0.318866 0.552288 -v 0.015750 0.092875 0.130617 -vn 0.770266 -0.318862 -0.552284 -v 0.015750 0.094125 0.132783 -vn 0.770258 -0.000001 -0.637732 -v 0.015750 0.093500 0.132950 -vn 0.770266 0.318861 -0.552284 -v 0.015750 0.092875 0.132783 -vn 0.770261 -0.318867 0.552288 -v 0.015750 0.094125 0.130617 -vn 0.770264 -0.000001 0.637725 -v 0.015750 0.093500 0.130450 -vn 0.770259 -0.552293 -0.318864 -v 0.015750 0.094583 0.132325 -vn 0.770264 -0.637725 0.000000 -v 0.015750 0.094750 0.131700 -vn 0.770261 -0.552288 0.318867 -v 0.015750 0.094583 0.131075 -vn 0.990581 0.062165 -0.122003 -v 0.015750 0.137816 0.128136 -vn 0.770264 0.000000 -0.637725 -v 0.015750 0.114750 0.127450 -vn 0.770260 -0.318866 -0.552291 -v 0.015750 0.115375 0.127283 -vn 0.770263 0.552286 -0.318865 -v 0.015750 0.113667 0.126825 -vn 0.770260 0.318866 -0.552291 -v 0.015750 0.114125 0.127283 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.115833 0.126825 -vn 0.770261 -0.637728 0.000000 -v 0.015750 0.116000 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.115833 0.125575 -vn 0.770265 -0.318861 0.552286 -v 0.015750 0.115375 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.015750 0.114750 0.124950 -vn 0.770265 0.318861 0.552286 -v 0.015750 0.114125 0.125117 -vn 0.770261 -0.552291 0.318862 -v 0.015750 0.099833 0.125575 -vn 0.717284 0.630262 -0.297108 -v 0.015750 0.102000 0.124700 -vn 0.770261 -0.637729 0.000000 -v 0.015750 0.100000 0.126200 -vn 0.770263 -0.552286 -0.318865 -v 0.015750 0.099833 0.126825 -vn 0.770260 -0.318865 -0.552291 -v 0.015750 0.099375 0.127283 -vn 0.770265 -0.318861 0.552286 -v 0.015750 0.099375 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.015750 0.098750 0.124950 -vn 0.923880 0.000000 -0.382683 -v 0.015750 0.097250 0.124700 -vn 0.770265 0.318861 0.552287 -v 0.015750 0.098125 0.125117 -vn 0.770260 0.552291 0.318865 -v 0.015750 0.097667 0.125575 -vn 0.770264 0.637725 0.000000 -v 0.015750 0.097500 0.126200 -vn 0.770262 0.552286 -0.318869 -v 0.015750 0.097667 0.126825 -vn 1.000000 0.000000 0.000000 -v 0.015750 0.097250 0.128575 -vn 0.770260 0.318865 -0.552291 -v 0.015750 0.098125 0.127283 -vn 0.770264 0.000000 -0.637725 -v 0.015750 0.098750 0.127450 -vn 0.770266 -0.318854 -0.552289 -v 0.015750 0.097150 0.129740 -vn -0.301511 -0.301511 0.904534 -v 0.013750 0.124750 0.155700 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 0.123375 0.154283 -vn -0.770264 0.000000 -0.637725 -v 0.013750 0.122750 0.154450 -vn -0.609995 0.000001 0.792405 -v 0.013750 0.122750 0.150891 -vn -0.770258 0.000000 0.637732 -v 0.013750 0.122750 0.151950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 0.123375 0.152117 -vn -0.301511 0.301511 0.904534 -v 0.013750 0.120750 0.155700 -vn -0.770260 0.318866 -0.552291 -v 0.013750 0.122125 0.154283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 0.121667 0.153825 -vn -0.609994 0.686243 0.396204 -v 0.013750 0.120750 0.152045 -vn -0.609994 -0.686243 0.396205 -v 0.013750 0.124750 0.152045 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.123833 0.152575 -vn -0.770261 -0.637728 -0.000000 -v 0.013750 0.124000 0.153200 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.123833 0.153825 -vn -0.770261 0.637729 0.000000 -v 0.013750 0.121500 0.153200 -vn -0.770261 0.552291 0.318862 -v 0.013750 0.121667 0.152575 -vn -0.770265 0.318861 0.552286 -v 0.013750 0.122125 0.152117 -vn -0.609994 0.686243 0.396204 -v 0.013750 0.112750 0.152045 -vn -0.770261 0.552291 0.318862 -v 0.013750 0.113667 0.152575 -vn -0.609995 0.000001 0.792405 -v 0.013750 0.114750 0.150891 -vn -0.770265 0.318861 0.552286 -v 0.013750 0.114125 0.152117 -vn -0.609994 -0.686243 0.396205 -v 0.013750 0.116750 0.152045 -vn -0.770261 -0.637728 -0.000000 -v 0.013750 0.116000 0.153200 -vn -0.301511 -0.301511 0.904534 -v 0.013750 0.116750 0.155700 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.115833 0.153825 -vn -0.770260 -0.318865 -0.552291 -v 0.013750 0.115375 0.154283 -vn -0.770264 -0.000000 -0.637725 -v 0.013750 0.114750 0.154450 -vn -0.301511 0.301511 0.904534 -v 0.013750 0.112750 0.155700 -vn -0.770260 0.318866 -0.552291 -v 0.013750 0.114125 0.154283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 0.113667 0.153825 -vn -0.770261 0.637729 0.000000 -v 0.013750 0.113500 0.153200 -vn -0.770258 0.000000 0.637732 -v 0.013750 0.114750 0.151950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 0.115375 0.152117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.115833 0.152575 -vn -0.609994 -0.686243 0.396204 -v 0.013750 0.108750 0.152045 -vn -0.770261 -0.637728 -0.000000 -v 0.013750 0.108000 0.153200 -vn -0.301511 -0.301511 0.904534 -v 0.013750 0.108750 0.155700 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.107833 0.153825 -vn -0.609995 -0.000001 0.792405 -v 0.013750 0.106750 0.150891 -vn -0.770265 -0.318861 0.552287 -v 0.013750 0.107375 0.152117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.107833 0.152575 -vn -0.770260 -0.318865 -0.552291 -v 0.013750 0.107375 0.154283 -vn -0.770264 -0.000001 -0.637726 -v 0.013750 0.106750 0.154450 -vn -0.301511 0.301511 0.904534 -v 0.013750 0.104750 0.155700 -vn -0.770264 0.637725 0.000000 -v 0.013750 0.105500 0.153200 -vn -0.609994 0.686243 0.396205 -v 0.013750 0.104750 0.152045 -vn -0.770261 0.552288 -0.318867 -v 0.013750 0.105667 0.153825 -vn -0.770261 0.318866 -0.552288 -v 0.013750 0.106125 0.154283 -vn -0.770259 0.552293 0.318864 -v 0.013750 0.105667 0.152575 -vn -0.770266 0.318861 0.552284 -v 0.013750 0.106125 0.152117 -vn -0.770258 -0.000001 0.637732 -v 0.013750 0.106750 0.151950 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.136850 0.150425 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.102000 0.125200 -vn -0.717284 0.630263 -0.297108 -v 0.010750 0.102000 0.124700 -vn -0.741788 -0.516596 -0.427644 -v 0.010750 0.100750 0.124700 -vn -0.904534 -0.301511 0.301511 -v 0.010750 0.111500 0.154200 -vn -0.717284 -0.630263 0.297108 -v 0.010750 0.111500 0.154700 -vn -0.741788 0.516596 0.427644 -v 0.010750 0.112750 0.154700 -vn -0.741788 -0.516596 0.427644 -v 0.010750 0.124750 0.154700 -vn -0.717284 0.630263 0.297108 -v 0.010750 0.126000 0.154700 -vn -0.846478 -0.279911 0.452907 -v 0.010750 0.123750 0.152700 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.126000 0.154200 -vn -0.707107 0.000000 0.707107 -v 0.010750 0.126325 0.154200 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.150425 -vn -0.846478 0.279911 0.452906 -v 0.010750 0.121750 0.152700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.119550 0.150425 -vn -0.741787 0.516597 0.427643 -v 0.010750 0.120750 0.154700 -vn -0.904534 -0.301511 0.301511 -v 0.010750 0.119500 0.154200 -vn -0.717284 -0.630263 0.297108 -v 0.010750 0.119500 0.154700 -vn -0.923880 0.000000 0.382683 -v 0.010750 0.119550 0.154700 -vn -0.846478 -0.279911 0.452907 -v 0.010750 0.115750 0.152700 -vn -0.741787 -0.516596 0.427644 -v 0.010750 0.116750 0.154700 -vn -0.717284 0.630262 0.297108 -v 0.010750 0.118000 0.154700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.110450 0.150425 -vn -0.846478 0.279911 0.452907 -v 0.010750 0.113750 0.152700 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.118000 0.154200 -vn -0.846478 -0.279911 0.452907 -v 0.010750 0.107750 0.152700 -vn -0.741788 -0.516596 0.427644 -v 0.010750 0.108750 0.154700 -vn -0.717284 0.630263 0.297108 -v 0.010750 0.110000 0.154700 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.102250 0.150425 -vn -0.707107 0.000000 0.707107 -v 0.010750 0.102250 0.154200 -vn -0.904534 -0.301511 0.301511 -v 0.010750 0.103500 0.154200 -vn -0.846478 0.279911 0.452907 -v 0.010750 0.105750 0.152700 -vn -0.707107 0.000000 0.707107 -v 0.010750 0.110450 0.154200 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.110000 0.154200 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.102000 0.154200 -vn -0.846478 0.279911 0.452907 -v 0.010750 0.097750 0.152700 -vn -0.846478 -0.279911 0.452907 -v 0.010750 0.099750 0.152700 -vn -0.976002 -0.188590 -0.108878 -v 0.010750 0.097279 0.150550 -vn -0.904534 -0.301511 0.301511 -v 0.010750 0.094000 0.152700 -vn -0.577350 -0.577350 0.577350 -v 0.010750 0.094000 0.154200 -vn -0.904534 -0.301512 0.301511 -v 0.010750 0.095500 0.154200 -vn -0.976004 -0.108874 -0.188578 -v 0.010750 0.096950 0.150879 -vn -0.741788 0.516596 0.427644 -v 0.010750 0.096750 0.154700 -vn -0.717284 -0.630263 0.297108 -v 0.010750 0.095500 0.154700 -vn -0.976002 0.188586 -0.108878 -v 0.010750 0.095721 0.150550 -vn -0.976004 0.108877 -0.188580 -v 0.010750 0.096050 0.150879 -vn -0.975997 -0.000003 -0.217784 -v 0.010750 0.096500 0.151000 -vn -0.577350 -0.577350 0.577350 -v 0.010750 0.092500 0.152700 -vn -0.707107 0.000000 0.707107 -v 0.010750 0.093800 0.152700 -vn -0.904534 -0.301511 0.301511 -v 0.010750 0.092500 0.150950 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.093800 0.150425 -vn -0.717284 -0.297108 0.630263 -v 0.010750 0.092000 0.150950 -vn -0.923880 -0.382683 0.000000 -v 0.010750 0.092000 0.150425 -vn -0.717284 -0.297108 -0.630263 -v 0.010750 0.092000 0.144450 -vn -0.741788 -0.427644 0.516597 -v 0.010750 0.092000 0.145700 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 0.092500 0.144450 -vn -0.846478 -0.452906 0.279911 -v 0.010750 0.094000 0.146700 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.092500 0.142875 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.093800 0.142875 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 0.092500 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.093800 0.139700 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 0.092500 0.136525 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.093800 0.136525 -vn -0.904534 -0.301511 0.301511 -v 0.010750 0.092500 0.134950 -vn -0.846478 -0.452907 -0.279911 -v 0.010750 0.094000 0.132700 -vn -0.717284 -0.297108 0.630263 -v 0.010750 0.092000 0.134950 -vn -0.741788 -0.427644 -0.516597 -v 0.010750 0.092000 0.133700 -vn -0.846478 -0.452907 0.279911 -v 0.010750 0.094000 0.130700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.093800 0.130500 -vn -0.741788 -0.427644 0.516596 -v 0.010750 0.092000 0.129700 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 0.092500 0.128450 -vn -0.717284 -0.297108 -0.630263 -v 0.010750 0.092000 0.128450 -vn -0.846478 -0.279911 -0.452907 -v 0.010750 0.099750 0.126700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.102250 0.130500 -vn -0.707107 0.000000 -0.707107 -v 0.010750 0.102250 0.125200 -vn -0.976003 0.217758 0.000000 -v 0.010750 0.095600 0.129300 -vn -0.976006 0.188572 0.108875 -v 0.010750 0.095721 0.128850 -vn -0.904534 -0.301512 -0.301511 -v 0.010750 0.095500 0.125200 -vn -0.976004 0.108876 0.188581 -v 0.010750 0.096050 0.128521 -vn -0.976004 0.000000 0.217755 -v 0.010750 0.096500 0.128400 -vn -0.976002 -0.188587 -0.108879 -v 0.010750 0.097279 0.129750 -vn -0.976003 -0.108877 -0.188582 -v 0.010750 0.096950 0.130079 -vn -0.976004 -0.000000 -0.217754 -v 0.010750 0.096500 0.130200 -vn -0.976003 0.108877 -0.188582 -v 0.010750 0.096050 0.130079 -vn -0.976003 0.188584 -0.108879 -v 0.010750 0.095721 0.129750 -vn -0.717283 -0.630263 -0.297108 -v 0.010750 0.095500 0.124700 -vn -0.741788 0.516596 -0.427644 -v 0.010750 0.096750 0.124700 -vn -0.846478 0.279911 -0.452907 -v 0.010750 0.097750 0.126700 -vn -0.976004 -0.108878 0.188581 -v 0.010750 0.096950 0.128521 -vn -0.976005 -0.188575 0.108875 -v 0.010750 0.097279 0.128850 -vn -0.976004 -0.217754 0.000001 -v 0.010750 0.097400 0.129300 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 0.094000 0.125200 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 0.094000 0.126700 -vn -0.707107 0.000000 -0.707107 -v 0.010750 0.093800 0.126700 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 0.092500 0.126700 -vn -0.707107 0.000000 -0.707107 -v 0.010750 0.110450 0.125200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.110000 0.125200 -vn -0.741788 0.516596 -0.427644 -v 0.010750 0.104750 0.124700 -vn -0.717284 -0.630263 -0.297108 -v 0.010750 0.103500 0.124700 -vn -0.846478 0.279911 -0.452907 -v 0.010750 0.105750 0.126700 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 0.103500 0.125200 -vn -0.846478 -0.279911 -0.452907 -v 0.010750 0.107750 0.126700 -vn -0.741788 -0.516596 -0.427644 -v 0.010750 0.108750 0.124700 -vn -0.717284 0.630263 -0.297108 -v 0.010750 0.110000 0.124700 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.112000 0.131975 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.112000 0.130500 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.110450 0.130500 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.112000 0.130200 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 0.119500 0.125200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.118000 0.125200 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.119550 0.130500 -vn -0.923880 0.000000 -0.382683 -v 0.010750 0.119550 0.124700 -vn -0.717284 -0.630263 -0.297108 -v 0.010750 0.119500 0.124700 -vn -0.741788 0.516596 -0.427644 -v 0.010750 0.112750 0.124700 -vn -0.717284 -0.630263 -0.297108 -v 0.010750 0.111500 0.124700 -vn -0.846478 0.279911 -0.452907 -v 0.010750 0.113750 0.126700 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 0.111500 0.125200 -vn -0.717284 0.630262 -0.297108 -v 0.010750 0.118000 0.124700 -vn -0.741787 -0.516596 -0.427644 -v 0.010750 0.116750 0.124700 -vn -0.846477 -0.279912 -0.452908 -v 0.010750 0.115750 0.126700 -vn -0.707107 0.000000 -0.707107 -v 0.010750 0.126325 0.125200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.126000 0.125200 -vn -0.741787 0.516597 -0.427643 -v 0.010750 0.120750 0.124700 -vn -0.846478 0.279911 -0.452906 -v 0.010750 0.121750 0.126700 -vn -0.846478 -0.279911 -0.452907 -v 0.010750 0.123750 0.126700 -vn -0.741788 -0.516596 -0.427644 -v 0.010750 0.124750 0.124700 -vn -0.717284 0.630263 -0.297108 -v 0.010750 0.126000 0.124700 -vn -0.707107 0.000000 -0.707107 -v 0.010750 0.133425 0.126700 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.127500 0.126700 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.130500 -vn -0.976002 0.108878 0.188588 -v 0.010750 0.138050 0.129671 -vn -0.976003 -0.000001 0.217755 -v 0.010750 0.138500 0.129550 -vn -0.976005 -0.108876 0.188574 -v 0.010750 0.138950 0.129671 -vn -0.976005 -0.188574 0.108876 -v 0.010750 0.139279 0.130000 -vn -0.976004 -0.217754 0.000001 -v 0.010750 0.139400 0.130450 -vn -0.976002 -0.188587 -0.108879 -v 0.010750 0.139279 0.130900 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.141000 0.131975 -vn -0.976000 -0.108889 -0.188593 -v 0.010750 0.138950 0.131229 -vn -0.976003 0.000001 -0.217757 -v 0.010750 0.138500 0.131350 -vn -0.975997 0.108887 -0.188609 -v 0.010750 0.138050 0.131229 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.136850 0.131975 -vn -0.976003 0.188586 -0.108876 -v 0.010750 0.137721 0.130900 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.136850 0.130500 -vn -0.976002 0.217760 0.000000 -v 0.010750 0.137600 0.130450 -vn -0.976006 0.188571 0.108873 -v 0.010750 0.137721 0.130000 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.136850 0.148900 -vn -0.976002 0.217760 0.000000 -v 0.010750 0.137600 0.148950 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.136850 0.147425 -vn -0.976006 0.188571 0.108873 -v 0.010750 0.137721 0.148500 -vn -0.976002 0.108878 0.188589 -v 0.010750 0.138050 0.148171 -vn -0.976003 -0.000001 0.217755 -v 0.010750 0.138500 0.148050 -vn -0.976005 -0.108876 0.188574 -v 0.010750 0.138950 0.148171 -vn -0.707107 0.707107 -0.000000 -v 0.010750 0.141000 0.147425 -vn -0.976005 -0.188574 0.108876 -v 0.010750 0.139279 0.148500 -vn -0.976004 -0.217754 0.000001 -v 0.010750 0.139400 0.148950 -vn -0.976002 -0.188587 -0.108879 -v 0.010750 0.139279 0.149400 -vn -0.976000 -0.108889 -0.188593 -v 0.010750 0.138950 0.149729 -vn -0.976003 0.000001 -0.217757 -v 0.010750 0.138500 0.149850 -vn -0.975997 0.108887 -0.188609 -v 0.010750 0.138050 0.149729 -vn -0.976003 0.188586 -0.108876 -v 0.010750 0.137721 0.149400 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.150425 -vn -0.577350 0.577350 0.577350 -v 0.010750 0.127500 0.154200 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.127500 0.152700 -vn -0.707107 0.000000 0.707107 -v 0.010750 0.133425 0.152700 -vn -0.904534 -0.301511 -0.301512 -v 0.010750 0.116500 0.139200 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.119550 0.139700 -vn -0.707107 -0.707107 -0.000000 -v 0.010750 0.116500 0.136525 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.119550 0.136525 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.116500 0.132700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.119550 0.132700 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.116500 0.131975 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.119550 0.131975 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.116500 0.130500 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.110450 0.139700 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.112000 0.139200 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.110450 0.136525 -vn -0.707107 0.707107 -0.000000 -v 0.010750 0.112000 0.136525 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.110450 0.132700 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.112000 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.110450 0.131975 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.112000 0.148900 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.110450 0.148900 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.112000 0.149200 -vn -0.904534 -0.301511 -0.301512 -v 0.010750 0.116500 0.149200 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.116500 0.148900 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.110450 0.142875 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.112000 0.142875 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.112000 0.140200 -vn -0.904534 -0.301511 0.301512 -v 0.010750 0.116500 0.140200 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.116500 0.147425 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.119550 0.147425 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.116500 0.146700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.119550 0.146700 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.116500 0.142875 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.119550 0.142875 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.112000 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.110450 0.146700 -vn -0.707107 0.707107 0.000000 -v 0.010750 0.112000 0.147425 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.110450 0.147425 -vn -0.976005 0.188572 0.108876 -v 0.010750 0.095721 0.149650 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.093800 0.148900 -vn -0.976003 0.217758 0.000000 -v 0.010750 0.095600 0.150100 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.102250 0.148900 -vn -0.976005 -0.188575 0.108875 -v 0.010750 0.097279 0.149650 -vn -0.741788 -0.516596 0.427644 -v 0.010750 0.100750 0.154700 -vn -0.717284 0.630263 0.297108 -v 0.010750 0.102000 0.154700 -vn -0.976004 -0.217754 0.000001 -v 0.010750 0.097400 0.150100 -vn -0.976004 0.108877 0.188581 -v 0.010750 0.096050 0.149321 -vn -0.976004 0.000000 0.217754 -v 0.010750 0.096500 0.149200 -vn -0.976004 -0.108878 0.188581 -v 0.010750 0.096950 0.149321 -vn -0.770258 -0.000000 -0.637732 -v 0.010750 0.129500 0.140950 -vn -0.770263 0.318859 -0.552289 -v 0.010750 0.128875 0.140783 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.142875 -vn -0.770264 0.552289 -0.318859 -v 0.010750 0.128417 0.140325 -vn -1.000000 0.000000 -0.000000 -v 0.010750 0.126325 0.139700 -vn -0.770258 0.637732 -0.000000 -v 0.010750 0.128250 0.139700 -vn -1.000000 0.000000 -0.000000 -v 0.010750 0.126325 0.136525 -vn -0.770266 0.552284 0.318862 -v 0.010750 0.128417 0.139075 -vn -0.770259 0.318864 0.552292 -v 0.010750 0.128875 0.138617 -vn -0.770264 0.000000 0.637725 -v 0.010750 0.129500 0.138450 -vn -0.770261 -0.318868 0.552287 -v 0.010750 0.130125 0.138617 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.133425 0.136525 -vn -0.770261 -0.552288 0.318867 -v 0.010750 0.130583 0.139075 -vn -1.000000 0.000000 -0.000000 -v 0.010750 0.133425 0.139700 -vn -0.770264 -0.637725 0.000000 -v 0.010750 0.130750 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.142875 -vn -0.770258 -0.552293 -0.318864 -v 0.010750 0.130583 0.140325 -vn -0.770266 -0.318863 -0.552284 -v 0.010750 0.130125 0.140783 -vn -0.770256 0.000000 -0.637735 -v 0.010750 0.137000 0.146600 -vn -0.770268 0.318860 -0.552282 -v 0.010750 0.136550 0.146479 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.146700 -vn -0.770258 0.552295 -0.318862 -v 0.010750 0.136221 0.146150 -vn -0.770263 0.637726 0.000000 -v 0.010750 0.136100 0.145700 -vn -0.770261 0.552288 0.318866 -v 0.010750 0.136221 0.145250 -vn -0.770256 -0.000000 0.637735 -v 0.010750 0.137000 0.144800 -vn -0.770262 -0.318851 0.552296 -v 0.010750 0.137450 0.144921 -vn -0.707107 0.707106 0.000000 -v 0.010750 0.141000 0.142875 -vn -0.770268 -0.552283 0.318860 -v 0.010750 0.137779 0.145250 -vn -0.707107 0.707107 -0.000000 -v 0.010750 0.141000 0.146700 -vn -0.770256 -0.637735 -0.000000 -v 0.010750 0.137900 0.145700 -vn -0.770265 -0.552289 -0.318855 -v 0.010750 0.137779 0.146150 -vn -0.770264 -0.552285 -0.318863 -v 0.010750 0.124279 0.148150 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.148900 -vn -0.770259 -0.637731 0.000000 -v 0.010750 0.124400 0.147700 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.147425 -vn -0.770264 -0.552285 0.318863 -v 0.010750 0.124279 0.147250 -vn -0.770261 0.552288 -0.318866 -v 0.010750 0.122721 0.148150 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.119550 0.148900 -vn -0.770260 -0.318864 -0.552292 -v 0.010750 0.123950 0.148479 -vn -0.770263 0.000000 -0.637726 -v 0.010750 0.123500 0.148600 -vn -0.770261 0.318866 -0.552288 -v 0.010750 0.123050 0.148479 -vn -0.770263 0.637726 0.000000 -v 0.010750 0.122600 0.147700 -vn -0.770261 0.552288 0.318866 -v 0.010750 0.122721 0.147250 -vn -0.770261 0.318866 0.552288 -v 0.010750 0.123050 0.146921 -vn -0.770260 -0.318864 0.552292 -v 0.010750 0.123950 0.146921 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.146700 -vn -0.770263 -0.000000 0.637726 -v 0.010750 0.123500 0.146800 -vn -0.770261 -0.552288 -0.318866 -v 0.010750 0.108779 0.148150 -vn -0.770261 -0.318866 -0.552288 -v 0.010750 0.108450 0.148479 -vn -0.770263 0.000000 -0.637726 -v 0.010750 0.108000 0.148600 -vn -0.770260 0.318864 -0.552292 -v 0.010750 0.107550 0.148479 -vn -0.770264 0.552285 -0.318863 -v 0.010750 0.107221 0.148150 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.102250 0.147425 -vn -0.770263 -0.637726 -0.000000 -v 0.010750 0.108900 0.147700 -vn -0.770259 0.637731 -0.000000 -v 0.010750 0.107100 0.147700 -vn -0.770264 0.552285 0.318863 -v 0.010750 0.107221 0.147250 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.102250 0.146700 -vn -0.770260 0.318864 0.552292 -v 0.010750 0.107550 0.146921 -vn -0.770263 -0.000000 0.637726 -v 0.010750 0.108000 0.146800 -vn -0.770261 -0.318866 0.552288 -v 0.010750 0.108450 0.146921 -vn -0.770261 -0.552288 0.318866 -v 0.010750 0.108779 0.147250 -vn -0.770263 0.000000 -0.637726 -v 0.010750 0.137000 0.134600 -vn -0.770261 0.318866 -0.552288 -v 0.010750 0.136550 0.134479 -vn -0.770261 0.552288 -0.318866 -v 0.010750 0.136221 0.134150 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.132700 -vn -0.770263 0.637726 0.000000 -v 0.010750 0.136100 0.133700 -vn -0.770261 0.552288 0.318866 -v 0.010750 0.136221 0.133250 -vn -0.770263 -0.000000 0.637726 -v 0.010750 0.137000 0.132800 -vn -0.770258 -0.318862 0.552295 -v 0.010750 0.137450 0.132921 -vn -0.707107 0.707106 0.000000 -v 0.010750 0.141000 0.132700 -vn -0.770268 -0.552283 0.318860 -v 0.010750 0.137779 0.133250 -vn -0.770255 -0.637735 -0.000000 -v 0.010750 0.137900 0.133700 -vn -0.707107 0.707107 -0.000000 -v 0.010750 0.141000 0.136525 -vn -0.770268 -0.552283 -0.318860 -v 0.010750 0.137779 0.134150 -vn -0.770264 0.552285 0.318863 -v 0.010750 0.107221 0.131250 -vn -0.770260 0.318864 0.552292 -v 0.010750 0.107550 0.130921 -vn -0.770263 0.000000 0.637726 -v 0.010750 0.108000 0.130800 -vn -0.770261 -0.318866 0.552288 -v 0.010750 0.108450 0.130921 -vn -0.770261 -0.552288 0.318866 -v 0.010750 0.108779 0.131250 -vn -0.770259 0.637731 -0.000000 -v 0.010750 0.107100 0.131700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.102250 0.131975 -vn -0.770262 0.552292 -0.318858 -v 0.010750 0.107221 0.132150 -vn -0.770263 -0.637726 0.000000 -v 0.010750 0.108900 0.131700 -vn -0.770258 -0.552295 -0.318862 -v 0.010750 0.108779 0.132150 -vn -0.770268 -0.318860 -0.552283 -v 0.010750 0.108450 0.132479 -vn -0.770266 0.318857 -0.552286 -v 0.010750 0.107550 0.132479 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.102250 0.132700 -vn -0.770256 0.000000 -0.637735 -v 0.010750 0.108000 0.132600 -vn -0.770263 0.637726 0.000000 -v 0.010750 0.122600 0.131700 -vn -0.770261 0.552288 0.318866 -v 0.010750 0.122721 0.131250 -vn -0.770261 0.318866 0.552288 -v 0.010750 0.123050 0.130921 -vn -0.770258 0.552295 -0.318862 -v 0.010750 0.122721 0.132150 -vn -0.904534 -0.301512 0.301511 -v 0.010750 0.116500 0.130200 -vn -0.770263 -0.000000 0.637726 -v 0.010750 0.123500 0.130800 -vn -0.770260 -0.318864 0.552292 -v 0.010750 0.123950 0.130921 -vn -0.770264 -0.552285 0.318863 -v 0.010750 0.124279 0.131250 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.131975 -vn -0.577350 0.577350 -0.577350 -v 0.010750 0.127500 0.125200 -vn -0.770268 0.318860 -0.552282 -v 0.010750 0.123050 0.132479 -vn -0.770256 0.000000 -0.637735 -v 0.010750 0.123500 0.132600 -vn -0.770259 -0.637731 0.000000 -v 0.010750 0.124400 0.131700 -vn -0.770262 -0.552292 -0.318858 -v 0.010750 0.124279 0.132150 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.126325 0.132700 -vn -0.770266 -0.318857 -0.552286 -v 0.010750 0.123950 0.132479 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.136850 0.132700 -vn -0.770261 0.318866 0.552288 -v 0.010750 0.136550 0.132921 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.130500 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.131975 -vn -0.770258 -0.318862 -0.552295 -v 0.010750 0.137450 0.134479 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.136850 0.136525 -vn -0.707107 0.707107 -0.000000 -v 0.010750 0.141000 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.136850 0.139700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.136850 0.142875 -vn -0.770265 0.318855 0.552289 -v 0.010750 0.136550 0.144921 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.102250 0.136525 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.102250 0.139700 -vn -1.000000 -0.000000 0.000000 -v 0.010750 0.102250 0.142875 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.094000 0.131975 -vn -0.741788 -0.427644 -0.516596 -v 0.010750 0.092000 0.149700 -vn -0.846478 -0.452907 -0.279911 -v 0.010750 0.094000 0.148700 -vn -0.707107 -0.707107 0.000000 -v 0.010750 0.094000 0.147425 -vn -0.770265 -0.318855 -0.552289 -v 0.010750 0.137450 0.146479 -vn -1.000000 -0.000000 -0.000000 -v 0.010750 0.136850 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.147425 -vn -1.000000 0.000000 0.000000 -v 0.010750 0.133425 0.148900 -vn -0.741788 0.516596 0.427644 -v 0.010750 0.104750 0.154700 -vn -0.717284 -0.630263 0.297108 -v 0.010750 0.103500 0.154700 -vn 0.075085 0.990667 0.113762 -v 0.012250 0.120750 0.154700 -vn 0.609994 0.686243 0.396204 -v 0.012250 0.120750 0.152045 -vn 0.846478 0.279911 0.452906 -v 0.012250 0.121750 0.152700 -vn 0.609995 0.000001 0.792405 -v 0.012250 0.122750 0.150891 -vn 0.846478 -0.279911 0.452907 -v 0.012250 0.123750 0.152700 -vn 0.609994 -0.686243 0.396205 -v 0.012250 0.124750 0.152045 -vn 0.075085 -0.990667 0.113763 -v 0.012250 0.124750 0.154700 -vn 0.075085 0.990667 0.113763 -v 0.012250 0.112750 0.154700 -vn 0.609994 0.686243 0.396204 -v 0.012250 0.112750 0.152045 -vn 0.846478 0.279911 0.452907 -v 0.012250 0.113750 0.152700 -vn 0.609995 0.000001 0.792405 -v 0.012250 0.114750 0.150891 -vn 0.846478 -0.279911 0.452907 -v 0.012250 0.115750 0.152700 -vn 0.609994 -0.686243 0.396205 -v 0.012250 0.116750 0.152045 -vn 0.075085 -0.990667 0.113763 -v 0.012250 0.116750 0.154700 -vn 0.075085 0.990667 0.113763 -v 0.012250 0.104750 0.154700 -vn 0.609994 0.686243 0.396205 -v 0.012250 0.104750 0.152045 -vn 0.846478 0.279911 0.452907 -v 0.012250 0.105750 0.152700 -vn 0.609995 -0.000001 0.792405 -v 0.012250 0.106750 0.150891 -vn 0.846478 -0.279911 0.452907 -v 0.012250 0.107750 0.152700 -vn 0.609994 -0.686243 0.396204 -v 0.012250 0.108750 0.152045 -vn 0.075085 -0.990667 0.113763 -v 0.012250 0.108750 0.154700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.120750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.119500 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 0.119500 0.155700 -vn 0.297109 0.630262 0.717283 -v 0.014750 0.126000 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.124750 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.126000 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.112750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.111500 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 0.111500 0.155700 -vn 0.297109 0.630262 0.717283 -v 0.014750 0.118000 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.116750 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.118000 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.104750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.103500 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 0.103500 0.155700 -vn 0.297109 0.630262 0.717283 -v 0.014750 0.110000 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.108750 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.110000 0.155700 -vn -0.609994 -0.686243 0.396204 -v 0.013750 0.100750 0.152045 -vn -0.770261 -0.637728 0.000000 -v 0.013750 0.100000 0.153200 -vn -0.301511 -0.301511 0.904534 -v 0.013750 0.100750 0.155700 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.099833 0.153825 -vn -0.609994 0.686243 0.396205 -v 0.013750 0.096750 0.152045 -vn -0.301511 0.301511 0.904534 -v 0.013750 0.096750 0.155700 -vn -0.770262 0.552286 -0.318869 -v 0.013750 0.097667 0.153825 -vn -0.770265 0.318861 0.552286 -v 0.013750 0.098125 0.152117 -vn -0.609995 -0.000001 0.792405 -v 0.013750 0.098750 0.150891 -vn -0.770260 0.552291 0.318865 -v 0.013750 0.097667 0.152575 -vn -0.770264 0.637725 0.000000 -v 0.013750 0.097500 0.153200 -vn -0.770258 -0.000000 0.637732 -v 0.013750 0.098750 0.151950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 0.099375 0.152117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.099833 0.152575 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 0.099375 0.154283 -vn -0.770264 0.000000 -0.637725 -v 0.013750 0.098750 0.154450 -vn -0.770260 0.318866 -0.552291 -v 0.013750 0.098125 0.154283 -vn -0.301511 -0.904534 0.301511 -v 0.013750 0.091000 0.145700 -vn -0.301511 -0.904534 -0.301511 -v 0.013750 0.091000 0.149700 -vn -0.770264 0.637725 -0.000000 -v 0.013750 0.092250 0.147700 -vn -0.770259 0.552293 -0.318864 -v 0.013750 0.092417 0.148325 -vn -0.770259 -0.552293 -0.318864 -v 0.013750 0.094583 0.148325 -vn -0.609994 -0.396203 -0.686243 -v 0.013750 0.094655 0.149700 -vn -0.770264 -0.637725 0.000000 -v 0.013750 0.094750 0.147700 -vn -0.609994 -0.792406 -0.000000 -v 0.013750 0.095809 0.147700 -vn -0.770261 -0.552288 0.318867 -v 0.013750 0.094583 0.147075 -vn -0.609994 -0.396203 0.686243 -v 0.013750 0.094655 0.145700 -vn -0.770261 -0.318867 0.552288 -v 0.013750 0.094125 0.146617 -vn -0.770261 0.552288 0.318867 -v 0.013750 0.092417 0.147075 -vn -0.770261 0.318866 0.552288 -v 0.013750 0.092875 0.146617 -vn -0.770264 -0.000001 0.637725 -v 0.013750 0.093500 0.146450 -vn -0.770266 -0.318862 -0.552284 -v 0.013750 0.094125 0.148783 -vn -0.770258 -0.000001 -0.637732 -v 0.013750 0.093500 0.148950 -vn -0.770266 0.318861 -0.552284 -v 0.013750 0.092875 0.148783 -vn 0.075085 0.990667 0.113763 -v 0.012250 0.096750 0.154700 -vn 0.609994 0.686243 0.396205 -v 0.012250 0.096750 0.152045 -vn 0.846478 0.279911 0.452907 -v 0.012250 0.097750 0.152700 -vn 0.609995 -0.000001 0.792405 -v 0.012250 0.098750 0.150891 -vn 0.846478 -0.279911 0.452907 -v 0.012250 0.099750 0.152700 -vn 0.609994 -0.686243 0.396204 -v 0.012250 0.100750 0.152045 -vn 0.075085 -0.990667 0.113763 -v 0.012250 0.100750 0.154700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.096750 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.095500 0.155700 -vn 0.297109 -0.630262 0.717283 -v 0.014750 0.095500 0.155700 -vn 0.297109 0.630262 0.717283 -v 0.014750 0.102000 0.155700 -vn -0.297109 -0.630262 0.717283 -v 0.011750 0.100750 0.155700 -vn -0.297109 0.630262 0.717283 -v 0.011750 0.102000 0.155700 -vn 0.846478 -0.452906 0.279911 -v 0.012250 0.094000 0.146700 -vn 0.075085 -0.113763 0.990667 -v 0.012250 0.092000 0.145700 -vn 0.609994 -0.396204 0.686243 -v 0.012250 0.094655 0.145700 -vn 0.609994 -0.396204 -0.686243 -v 0.012250 0.094655 0.149700 -vn 0.075085 -0.113763 -0.990667 -v 0.012250 0.092000 0.149700 -vn 0.846478 -0.452906 -0.279911 -v 0.012250 0.094000 0.148700 -vn 0.609995 -0.792406 0.000000 -v 0.012250 0.095809 0.147700 -vn -0.297109 -0.717283 0.630262 -v 0.011750 0.091000 0.145700 -vn -0.297109 -0.717283 -0.630262 -v 0.011750 0.091000 0.144450 -vn 0.297109 -0.717284 -0.630262 -v 0.014750 0.091000 0.144450 -vn 0.297109 -0.717283 0.630262 -v 0.014750 0.091000 0.150950 -vn -0.297109 -0.717283 -0.630262 -v 0.011750 0.091000 0.149700 -vn -0.297109 -0.717283 0.630262 -v 0.011750 0.091000 0.150950 -vn 0.088123 0.737701 -0.669352 -v 0.014750 0.127500 0.126700 -vn 0.130014 0.038804 -0.990753 -v 0.014750 0.136000 0.126700 -vn 0.130013 0.990753 -0.038803 -v 0.014750 0.141000 0.131700 -vn 0.130014 0.990753 0.038803 -v 0.014750 0.141000 0.147700 -vn 0.088123 0.737701 0.669352 -v 0.014750 0.127500 0.152700 -vn 0.130013 0.038812 0.990752 -v 0.014750 0.136000 0.152700 -vn 0.297108 0.630263 0.717284 -v 0.014250 0.127500 0.154200 -vn 0.318867 0.770263 0.552286 -v 0.015250 0.127500 0.152566 -vn 0.552291 0.770261 0.318862 -v 0.015616 0.127500 0.152200 -vn 0.227458 0.804186 0.549133 -v 0.014250 0.126000 0.154200 -vn 0.227458 -0.804186 0.549133 -v 0.014250 0.119500 0.154200 -vn 0.227458 0.804186 0.549133 -v 0.014250 0.118000 0.154200 -vn 0.227458 -0.804186 0.549133 -v 0.014250 0.111500 0.154200 -vn 0.227458 0.804186 0.549133 -v 0.014250 0.110000 0.154200 -vn 0.227458 -0.804186 0.549133 -v 0.014250 0.103500 0.154200 -vn 0.227458 0.804186 0.549133 -v 0.014250 0.102000 0.154200 -vn 0.227458 -0.804186 0.549133 -v 0.014250 0.095500 0.154200 -vn 0.297108 -0.630263 0.717284 -v 0.014250 0.094000 0.154200 -vn 0.297108 -0.717284 0.630263 -v 0.014250 0.092500 0.152700 -vn 0.227458 -0.549133 0.804186 -v 0.014250 0.092500 0.150950 -vn 0.227458 -0.549133 -0.804186 -v 0.014250 0.092500 0.144450 -vn 0.227458 -0.549133 0.804186 -v 0.014250 0.092500 0.134950 -vn 0.297109 -0.717283 0.630262 -v 0.014750 0.091000 0.134950 -vn -0.297109 -0.717283 0.630262 -v 0.011750 0.091000 0.134950 -vn -0.297109 -0.717283 0.630262 -v 0.011750 0.091000 0.129700 -vn -0.297109 -0.717283 -0.630262 -v 0.011750 0.091000 0.128450 -vn -0.301511 -0.904534 0.301511 -v 0.013750 0.091000 0.129700 -vn 0.297109 -0.717283 -0.630262 -v 0.014750 0.091000 0.128450 -vn -0.301511 -0.904534 -0.301511 -v 0.013750 0.091000 0.133700 -vn -0.297109 -0.717283 -0.630262 -v 0.011750 0.091000 0.133700 -vn 0.227458 -0.549133 -0.804186 -v 0.014250 0.092500 0.128450 -vn 0.297108 -0.717284 -0.630263 -v 0.014250 0.092500 0.126700 -vn 0.297108 -0.630263 -0.717284 -v 0.014250 0.094000 0.125200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 0.095500 0.125200 -vn 0.297109 -0.630262 -0.717284 -v 0.014750 0.095500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 0.095500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 0.100750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 0.102000 0.123700 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 0.100750 0.123700 -vn 0.297109 0.630262 -0.717284 -v 0.014750 0.102000 0.123700 -vn -0.301511 0.301511 -0.904534 -v 0.013750 0.096750 0.123700 -vn -0.297109 0.630262 -0.717284 -v 0.011750 0.096750 0.123700 -vn 0.227458 0.804186 -0.549133 -v 0.014250 0.102000 0.125200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 0.103500 0.125200 -vn 0.297109 -0.630262 -0.717284 -v 0.014750 0.103500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 0.103500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 0.108750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 0.110000 0.123700 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 0.108750 0.123700 -vn 0.297109 0.630262 -0.717283 -v 0.014750 0.110000 0.123700 -vn -0.301511 0.301511 -0.904534 -v 0.013750 0.104750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 0.104750 0.123700 -vn 0.227458 0.804186 -0.549133 -v 0.014250 0.110000 0.125200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 0.111500 0.125200 -vn 0.297109 -0.630262 -0.717283 -v 0.014750 0.111500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 0.111500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 0.116750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 0.118000 0.123700 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 0.116750 0.123700 -vn 0.297109 0.630262 -0.717284 -v 0.014750 0.118000 0.123700 -vn -0.301511 0.301511 -0.904534 -v 0.013750 0.112750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 0.112750 0.123700 -vn 0.227458 0.804186 -0.549133 -v 0.014250 0.118000 0.125200 -vn 0.227458 -0.804186 -0.549133 -v 0.014250 0.119500 0.125200 -vn 0.297109 -0.630262 -0.717284 -v 0.014750 0.119500 0.123700 -vn -0.297109 -0.630262 -0.717284 -v 0.011750 0.119500 0.123700 -vn -0.297109 -0.630262 -0.717283 -v 0.011750 0.124750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 0.126000 0.123700 -vn -0.301511 -0.301511 -0.904534 -v 0.013750 0.124750 0.123700 -vn 0.297109 0.630262 -0.717283 -v 0.014750 0.126000 0.123700 -vn -0.301511 0.301511 -0.904534 -v 0.013750 0.120750 0.123700 -vn -0.297109 0.630262 -0.717283 -v 0.011750 0.120750 0.123700 -vn 0.227458 0.804186 -0.549133 -v 0.014250 0.126000 0.125200 -vn 0.297108 0.630263 -0.717284 -v 0.014250 0.127500 0.125200 -vn 0.552285 0.770264 -0.318865 -v 0.015616 0.127500 0.127200 -vn 0.318863 0.770260 -0.552292 -v 0.015250 0.127500 0.126834 -vn 0.128136 -0.983443 -0.128141 -v 0.018450 0.097000 0.130000 -vn 0.128141 -0.983444 0.128133 -v 0.018450 0.097000 0.135400 -vn 0.128141 -0.128139 -0.983443 -v 0.018450 0.097300 0.129700 -vn 0.128136 0.128135 -0.983444 -v 0.018450 0.103700 0.129700 -vn 0.128158 0.983439 0.128150 -v 0.018450 0.104000 0.135400 -vn 0.128158 0.983438 -0.128163 -v 0.018450 0.104000 0.130000 -vn 0.128136 -0.128135 0.983444 -v 0.018450 0.097300 0.135700 -vn 0.128139 0.128138 0.983443 -v 0.018450 0.103700 0.135700 -vn 0.988108 -0.108730 0.108724 -v 0.018750 0.097300 0.135400 -vn 0.988107 -0.108728 -0.108735 -v 0.018750 0.097300 0.130000 -vn 0.988108 0.108728 0.108722 -v 0.018750 0.103700 0.135400 -vn 0.988107 0.108726 -0.108733 -v 0.018750 0.103700 0.130000 -vn 0.128136 -0.128135 0.983444 -v 0.018450 0.097300 0.149700 -vn 0.128139 0.128138 0.983443 -v 0.018450 0.103700 0.149700 -vn 0.128141 -0.983444 0.128133 -v 0.018450 0.097000 0.149400 -vn 0.128136 -0.983443 -0.128141 -v 0.018450 0.097000 0.144000 -vn 0.128141 -0.128139 -0.983443 -v 0.018450 0.097300 0.143700 -vn 0.128136 0.128135 -0.983444 -v 0.018450 0.103700 0.143700 -vn 0.128158 0.983438 -0.128163 -v 0.018450 0.104000 0.144000 -vn 0.128158 0.983439 0.128150 -v 0.018450 0.104000 0.149400 -vn 0.988108 0.108728 0.108722 -v 0.018750 0.103700 0.149400 -vn 0.988108 -0.108730 0.108724 -v 0.018750 0.097300 0.149400 -vn 0.988107 0.108726 -0.108733 -v 0.018750 0.103700 0.144000 -vn 0.988107 -0.108728 -0.108735 -v 0.018750 0.097300 0.144000 -vn 0.609994 -0.396204 -0.686243 -v 0.012250 0.094655 0.133700 -vn -0.609994 -0.396203 -0.686243 -v 0.013750 0.094655 0.133700 -vn 0.075085 -0.113763 -0.990667 -v 0.012250 0.092000 0.133700 -vn -0.770264 0.637725 0.000000 -v 0.013750 0.092250 0.131700 -vn -0.770259 0.552293 -0.318864 -v 0.013750 0.092417 0.132325 -vn -0.770264 -0.000001 0.637725 -v 0.013750 0.093500 0.130450 -vn -0.609994 -0.396202 0.686244 -v 0.013750 0.094655 0.129700 -vn -0.770261 0.318866 0.552288 -v 0.013750 0.092875 0.130617 -vn -0.770261 0.552288 0.318867 -v 0.013750 0.092417 0.131075 -vn -0.770261 -0.318867 0.552288 -v 0.013750 0.094125 0.130617 -vn -0.770261 -0.552288 0.318867 -v 0.013750 0.094583 0.131075 -vn -0.609994 -0.792406 0.000001 -v 0.013750 0.095809 0.131700 -vn -0.770264 -0.637725 -0.000000 -v 0.013750 0.094750 0.131700 -vn -0.770259 -0.552293 -0.318864 -v 0.013750 0.094583 0.132325 -vn -0.770266 -0.318863 -0.552284 -v 0.013750 0.094125 0.132783 -vn -0.770258 -0.000001 -0.637732 -v 0.013750 0.093500 0.132950 -vn -0.770266 0.318861 -0.552284 -v 0.013750 0.092875 0.132783 -vn 0.075085 -0.113763 0.990667 -v 0.012250 0.092000 0.129700 -vn 0.609994 -0.396202 0.686244 -v 0.012250 0.094655 0.129700 -vn 0.609994 -0.792406 0.000001 -v 0.012250 0.095809 0.131700 -vn 0.846478 -0.452906 0.279911 -v 0.012250 0.094000 0.130700 -vn 0.846478 -0.452907 -0.279911 -v 0.012250 0.094000 0.132700 -vn 0.609994 0.686244 -0.396203 -v 0.012250 0.096750 0.127355 -vn -0.609994 0.686244 -0.396203 -v 0.013750 0.096750 0.127355 -vn 0.075085 0.990667 -0.113763 -v 0.012250 0.096750 0.124700 -vn -0.609995 -0.686244 -0.396202 -v 0.013750 0.100750 0.127355 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.099833 0.125575 -vn -0.770261 -0.637728 0.000000 -v 0.013750 0.100000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.099833 0.126825 -vn -0.609994 -0.000001 -0.792406 -v 0.013750 0.098750 0.128509 -vn -0.770260 -0.318865 -0.552291 -v 0.013750 0.099375 0.127283 -vn -0.770264 0.637725 -0.000000 -v 0.013750 0.097500 0.126200 -vn -0.770260 0.552291 0.318866 -v 0.013750 0.097667 0.125575 -vn -0.770265 0.318861 0.552286 -v 0.013750 0.098125 0.125117 -vn -0.770258 0.000000 0.637732 -v 0.013750 0.098750 0.124950 -vn -0.770265 -0.318861 0.552287 -v 0.013750 0.099375 0.125117 -vn -0.770264 -0.000000 -0.637725 -v 0.013750 0.098750 0.127450 -vn -0.770260 0.318866 -0.552291 -v 0.013750 0.098125 0.127283 -vn -0.770262 0.552286 -0.318869 -v 0.013750 0.097667 0.126825 -vn 0.075085 -0.990667 -0.113763 -v 0.012250 0.100750 0.124700 -vn 0.609995 -0.686244 -0.396202 -v 0.012250 0.100750 0.127355 -vn 0.609994 -0.000001 -0.792406 -v 0.012250 0.098750 0.128509 -vn 0.846478 -0.279911 -0.452907 -v 0.012250 0.099750 0.126700 -vn 0.846478 0.279911 -0.452907 -v 0.012250 0.097750 0.126700 -vn 0.609994 0.686244 -0.396203 -v 0.012250 0.104750 0.127355 -vn -0.609994 0.686244 -0.396203 -v 0.013750 0.104750 0.127355 -vn 0.075085 0.990667 -0.113763 -v 0.012250 0.104750 0.124700 -vn -0.609995 -0.686244 -0.396202 -v 0.013750 0.108750 0.127355 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.107833 0.125575 -vn -0.770261 -0.637728 -0.000000 -v 0.013750 0.108000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.107833 0.126825 -vn -0.609994 -0.000001 -0.792406 -v 0.013750 0.106750 0.128509 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 0.107375 0.127283 -vn -0.770259 0.552293 0.318864 -v 0.013750 0.105667 0.125575 -vn -0.770264 0.637725 -0.000000 -v 0.013750 0.105500 0.126200 -vn -0.770264 -0.000001 -0.637726 -v 0.013750 0.106750 0.127450 -vn -0.770261 0.318866 -0.552288 -v 0.013750 0.106125 0.127283 -vn -0.770261 0.552288 -0.318867 -v 0.013750 0.105667 0.126825 -vn -0.770266 0.318861 0.552284 -v 0.013750 0.106125 0.125117 -vn -0.770258 -0.000001 0.637732 -v 0.013750 0.106750 0.124950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 0.107375 0.125117 -vn 0.075085 -0.990667 -0.113763 -v 0.012250 0.108750 0.124700 -vn 0.609995 -0.686244 -0.396202 -v 0.012250 0.108750 0.127355 -vn 0.609995 0.686244 -0.396202 -v 0.012250 0.112750 0.127355 -vn -0.609995 0.686244 -0.396202 -v 0.013750 0.112750 0.127355 -vn 0.075085 0.990667 -0.113763 -v 0.012250 0.112750 0.124700 -vn -0.770261 0.552291 0.318862 -v 0.013750 0.113667 0.125575 -vn -0.770261 0.637728 0.000000 -v 0.013750 0.113500 0.126200 -vn -0.770265 0.318861 0.552286 -v 0.013750 0.114125 0.125117 -vn -0.770258 0.000000 0.637732 -v 0.013750 0.114750 0.124950 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 0.115375 0.127283 -vn -0.609994 0.000001 -0.792406 -v 0.013750 0.114750 0.128509 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.115833 0.126825 -vn -0.609994 -0.686244 -0.396202 -v 0.013750 0.116750 0.127355 -vn -0.770264 0.000000 -0.637725 -v 0.013750 0.114750 0.127450 -vn -0.770260 0.318866 -0.552291 -v 0.013750 0.114125 0.127283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 0.113667 0.126825 -vn -0.770265 -0.318861 0.552286 -v 0.013750 0.115375 0.125117 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.115833 0.125575 -vn -0.770261 -0.637728 -0.000000 -v 0.013750 0.116000 0.126200 -vn 0.075085 -0.990667 -0.113763 -v 0.012250 0.116750 0.124700 -vn 0.609994 -0.686244 -0.396203 -v 0.012250 0.116750 0.127355 -vn 0.609995 0.686244 -0.396202 -v 0.012250 0.120750 0.127355 -vn -0.609995 0.686244 -0.396202 -v 0.013750 0.120750 0.127355 -vn 0.075085 0.990667 -0.113762 -v 0.012250 0.120750 0.124700 -vn -0.770264 0.000000 -0.637725 -v 0.013750 0.122750 0.127450 -vn -0.770260 0.318865 -0.552291 -v 0.013750 0.122125 0.127283 -vn -0.609994 0.000001 -0.792406 -v 0.013750 0.122750 0.128509 -vn -0.609994 -0.686244 -0.396202 -v 0.013750 0.124750 0.127355 -vn -0.770261 -0.552291 0.318862 -v 0.013750 0.123833 0.125575 -vn -0.770261 -0.637729 0.000000 -v 0.013750 0.124000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v 0.013750 0.123833 0.126825 -vn -0.770260 -0.318866 -0.552291 -v 0.013750 0.123375 0.127283 -vn -0.770263 0.552286 -0.318865 -v 0.013750 0.121667 0.126825 -vn -0.770261 0.637729 -0.000000 -v 0.013750 0.121500 0.126200 -vn -0.770261 0.552291 0.318862 -v 0.013750 0.121667 0.125575 -vn -0.770265 0.318861 0.552287 -v 0.013750 0.122125 0.125117 -vn -0.770258 -0.000000 0.637732 -v 0.013750 0.122750 0.124950 -vn -0.770265 -0.318861 0.552286 -v 0.013750 0.123375 0.125117 -vn 0.075085 -0.990667 -0.113763 -v 0.012250 0.124750 0.124700 -vn 0.609994 -0.686244 -0.396203 -v 0.012250 0.124750 0.127355 -vn 0.609994 -0.000001 -0.792406 -v 0.012250 0.106750 0.128509 -vn 0.846478 -0.279911 -0.452907 -v 0.012250 0.107750 0.126700 -vn 0.846478 0.279911 -0.452907 -v 0.012250 0.105750 0.126700 -vn 0.609994 0.000001 -0.792406 -v 0.012250 0.114750 0.128509 -vn 0.846478 -0.279911 -0.452907 -v 0.012250 0.115750 0.126700 -vn 0.846478 0.279911 -0.452907 -v 0.012250 0.113750 0.126700 -vn 0.609994 0.000001 -0.792406 -v 0.012250 0.122750 0.128509 -vn 0.846478 -0.279911 -0.452907 -v 0.012250 0.123750 0.126700 -vn 0.846478 0.279911 -0.452906 -v 0.012250 0.121750 0.126700 -vn 0.128744 0.979468 0.155135 -v 0.014750 0.140938 0.148482 -vn 0.129691 0.943024 0.306408 -v 0.014750 0.140755 0.149245 -vn 0.128746 0.883593 0.450209 -v 0.014750 0.140455 0.149970 -vn 0.129695 0.802183 0.582823 -v 0.014750 0.140045 0.150639 -vn 0.128746 0.701222 0.701222 -v 0.014750 0.139536 0.151236 -vn 0.129694 0.582817 0.802187 -v 0.014750 0.138939 0.151745 -vn 0.128743 0.450213 0.883591 -v 0.014750 0.138270 0.152155 -vn 0.129690 0.306406 0.943025 -v 0.014750 0.137545 0.152455 -vn 0.128742 0.155137 0.979468 -v 0.014750 0.136782 0.152638 -vn 0.128742 0.155135 -0.979469 -v 0.014750 0.136782 0.126762 -vn 0.129690 0.306408 -0.943024 -v 0.014750 0.137545 0.126945 -vn 0.128741 0.450203 -0.883596 -v 0.014750 0.138270 0.127245 -vn 0.129693 0.582825 -0.802181 -v 0.014750 0.138939 0.127655 -vn 0.128738 0.701221 -0.701225 -v 0.014750 0.139536 0.128164 -vn 0.129692 0.802182 -0.582825 -v 0.014750 0.140045 0.128761 -vn 0.128747 0.883593 -0.450209 -v 0.014750 0.140455 0.129430 -vn 0.129695 0.943025 -0.306405 -v 0.014750 0.140755 0.130155 -vn 0.128743 0.979468 -0.155135 -v 0.014750 0.140938 0.130918 -vn 0.227459 0.549132 0.804187 -v 0.014750 0.112000 0.130200 -vn 0.227458 0.549133 -0.804187 -v 0.014750 0.112000 0.139200 -vn 0.227459 -0.549133 -0.804187 -v 0.014750 0.116500 0.139200 -vn 0.227459 -0.549132 0.804187 -v 0.014750 0.116500 0.130200 -vn 0.765316 0.483792 0.424543 -v 0.015450 0.111300 0.130200 -vn 0.765315 -0.483792 0.424544 -v 0.015450 0.117200 0.130200 -vn 0.765316 -0.483793 -0.424543 -v 0.015450 0.117200 0.149200 -vn 0.765316 0.483792 -0.424542 -v 0.015450 0.111300 0.149200 -vn 0.227459 0.549132 -0.804187 -v 0.014750 0.112000 0.149200 -vn 0.227459 -0.549132 -0.804187 -v 0.014750 0.116500 0.149200 -vn 0.227458 -0.549133 0.804187 -v 0.014750 0.116500 0.140200 -vn 0.227458 0.549133 0.804187 -v 0.014750 0.112000 0.140200 -vn 0.126935 0.979699 0.155170 -v 0.018250 0.134833 0.140545 -vn 0.126932 0.883801 0.450315 -v 0.018250 0.134311 0.142152 -vn 0.129673 0.943028 0.306403 -v 0.018250 0.134636 0.141369 -vn 0.126921 0.701386 0.701391 -v 0.018250 0.133318 0.143518 -vn 0.129700 0.802181 0.582823 -v 0.018250 0.133869 0.142874 -vn 0.126933 0.450324 0.883797 -v 0.018250 0.131952 0.144511 -vn 0.129674 0.582822 0.802186 -v 0.018250 0.132674 0.144069 -vn 0.126935 0.155168 0.979699 -v 0.018250 0.130345 0.145034 -vn 0.129727 0.306407 0.943020 -v 0.018250 0.131169 0.144836 -vn 0.126932 -0.155166 0.979700 -v 0.018250 0.128655 0.145034 -vn 0.129678 0.000001 0.991556 -v 0.018250 0.129500 0.145100 -vn 0.126935 -0.450323 0.883797 -v 0.018250 0.127048 0.144511 -vn 0.129713 -0.306411 0.943020 -v 0.018250 0.127831 0.144836 -vn 0.126919 -0.701385 0.701392 -v 0.018250 0.125682 0.143518 -vn 0.129675 -0.582821 0.802187 -v 0.018250 0.126326 0.144069 -vn 0.126934 -0.883801 0.450315 -v 0.018250 0.124689 0.142152 -vn 0.129699 -0.802185 0.582818 -v 0.018250 0.125131 0.142874 -vn 0.126933 -0.979699 0.155170 -v 0.018250 0.124166 0.140545 -vn 0.129693 -0.943024 0.306406 -v 0.018250 0.124364 0.141369 -vn 0.126934 -0.979699 -0.155168 -v 0.018250 0.124166 0.138855 -vn 0.129700 -0.991553 -0.000001 -v 0.018250 0.124100 0.139700 -vn 0.126916 -0.883804 -0.450313 -v 0.018250 0.124689 0.137248 -vn 0.129706 -0.943021 -0.306412 -v 0.018250 0.124364 0.138031 -vn 0.126949 -0.701383 -0.701389 -v 0.018250 0.125682 0.135882 -vn 0.129673 -0.802191 -0.582816 -v 0.018250 0.125131 0.136526 -vn 0.126970 -0.450311 -0.883798 -v 0.018250 0.127048 0.134889 -vn 0.129676 -0.582825 -0.802184 -v 0.018250 0.126326 0.135331 -vn 0.126932 -0.155172 -0.979699 -v 0.018250 0.128655 0.134366 -vn 0.129675 -0.306408 -0.943026 -v 0.018250 0.127831 0.134564 -vn 0.126935 0.155170 -0.979699 -v 0.018250 0.130345 0.134366 -vn 0.129721 0.000003 -0.991551 -v 0.018250 0.129500 0.134300 -vn 0.126971 0.450318 -0.883794 -v 0.018250 0.131952 0.134889 -vn 0.129686 0.306405 -0.943026 -v 0.018250 0.131169 0.134564 -vn 0.126949 0.701387 -0.701385 -v 0.018250 0.133318 0.135882 -vn 0.129677 0.582819 -0.802188 -v 0.018250 0.132674 0.135331 -vn 0.126913 0.883803 -0.450317 -v 0.018250 0.134311 0.137248 -vn 0.129676 0.802187 -0.582821 -v 0.018250 0.133869 0.136526 -vn 0.129721 0.991551 0.000003 -v 0.018250 0.134900 0.139700 -vn 0.126933 0.979699 -0.155173 -v 0.018250 0.134833 0.138855 -vn 0.129685 0.943025 -0.306407 -v 0.018250 0.134636 0.138031 -vn 0.990582 -0.130223 0.042312 -v 0.018550 0.124650 0.141276 -vn 0.990581 -0.135242 0.021420 -v 0.018550 0.124463 0.140498 -vn 0.750899 0.615820 -0.238572 -v 0.018550 0.125770 0.141145 -vn 0.750899 0.660417 0.000000 -v 0.018550 0.125500 0.139700 -vn 0.990581 -0.096824 -0.096823 -v 0.018550 0.125894 0.136094 -vn 0.990581 -0.080483 -0.110777 -v 0.018550 0.126502 0.135574 -vn 0.750897 0.488054 0.444923 -v 0.018550 0.126544 0.137005 -vn 0.750899 0.294375 0.591180 -v 0.018550 0.127717 0.136119 -vn 0.750898 -0.180735 -0.635206 -v 0.018550 0.130595 0.143547 -vn 0.750898 -0.397991 -0.527024 -v 0.018550 0.131911 0.142892 -vn 0.990581 0.062162 0.122002 -v 0.018550 0.131815 0.144244 -vn 0.750898 -0.561497 -0.347667 -v 0.018550 0.132901 0.141806 -vn 0.990581 0.096823 0.096824 -v 0.018550 0.133106 0.143306 -vn 0.990580 0.080490 0.110784 -v 0.018550 0.132498 0.143826 -vn 0.990582 0.135235 0.021419 -v 0.018550 0.134537 0.140498 -vn 0.750900 -0.649171 -0.121353 -v 0.018550 0.133432 0.140435 -vn 0.990580 0.136933 -0.000001 -v 0.018550 0.134600 0.139700 -vn 0.750900 -0.649171 0.121353 -v 0.018550 0.133432 0.138965 -vn 0.990582 0.135236 -0.021418 -v 0.018550 0.134537 0.138902 -vn 0.990579 0.042316 -0.130238 -v 0.018550 0.131076 0.134850 -vn 0.990581 0.062163 -0.122001 -v 0.018550 0.131815 0.135156 -vn 0.750900 -0.180732 0.635205 -v 0.018550 0.130595 0.135853 -vn 0.750898 -0.397991 0.527024 -v 0.018550 0.131911 0.136508 -vn 0.990581 -0.062165 -0.122007 -v 0.018550 0.127185 0.135156 -vn 0.990579 -0.042319 -0.130237 -v 0.018550 0.127924 0.134850 -vn 0.750899 0.060937 0.657600 -v 0.018550 0.129131 0.135717 -vn 0.990580 -0.136934 0.000000 -v 0.018550 0.124400 0.139700 -vn 0.990581 -0.135241 -0.021420 -v 0.018550 0.124463 0.138902 -vn 0.750900 0.615819 0.238573 -v 0.018550 0.125770 0.138255 -vn 0.750898 0.488055 -0.444921 -v 0.018550 0.126544 0.142395 -vn 0.990581 -0.110776 0.080483 -v 0.018550 0.125374 0.142698 -vn 0.990581 -0.122001 0.062163 -v 0.018550 0.124956 0.142015 -vn 0.990580 -0.021422 0.135250 -v 0.018550 0.128702 0.144737 -vn 0.990581 -0.042314 0.130225 -v 0.018550 0.127924 0.144550 -vn 0.750900 0.060934 -0.657599 -v 0.018550 0.129131 0.143683 -vn 0.750899 0.294375 -0.591180 -v 0.018550 0.127717 0.143281 -vn 0.990582 0.130223 0.042311 -v 0.018550 0.134350 0.141276 -vn 0.990580 0.122007 0.062165 -v 0.018550 0.134044 0.142015 -vn 0.990581 0.110775 0.080484 -v 0.018550 0.133626 0.142698 -vn 0.990582 0.130222 -0.042311 -v 0.018550 0.134350 0.138124 -vn 0.750898 -0.561497 0.347667 -v 0.018550 0.132901 0.137594 -vn 0.990580 0.122007 -0.062166 -v 0.018550 0.134044 0.137385 -vn 0.990581 0.080483 -0.110776 -v 0.018550 0.132498 0.135574 -vn 0.990581 0.096824 -0.096824 -v 0.018550 0.133106 0.136094 -vn 0.990581 0.110776 -0.080483 -v 0.018550 0.133626 0.136702 -vn 0.990582 -0.021419 -0.135238 -v 0.018550 0.128702 0.134663 -vn 0.990580 -0.000001 -0.136933 -v 0.018550 0.129500 0.134600 -vn 0.990582 0.021420 -0.135236 -v 0.018550 0.130298 0.134663 -vn 0.990582 -0.130222 -0.042312 -v 0.018550 0.124650 0.138124 -vn 0.990581 -0.122002 -0.062163 -v 0.018550 0.124956 0.137385 -vn 0.990581 -0.110776 -0.080483 -v 0.018550 0.125374 0.136702 -vn 0.990580 -0.062165 0.122007 -v 0.018550 0.127185 0.144244 -vn 0.990580 -0.080489 0.110785 -v 0.018550 0.126502 0.143826 -vn 0.990581 -0.096823 0.096822 -v 0.018550 0.125894 0.143306 -vn 0.990581 0.042313 0.130226 -v 0.018550 0.131076 0.144550 -vn 0.990580 0.021422 0.135248 -v 0.018550 0.130298 0.144737 -vn 0.990580 -0.000000 0.136934 -v 0.018550 0.129500 0.144800 -vn 0.667992 0.744168 -0.000000 -v 0.017950 0.125500 0.139700 -vn 0.667992 0.693915 0.268828 -v 0.017950 0.125770 0.138255 -vn 0.667994 0.549945 0.501344 -v 0.017950 0.126544 0.137005 -vn 0.667992 0.331706 0.666151 -v 0.017950 0.127717 0.136119 -vn 0.667993 0.068665 0.740993 -v 0.017950 0.129131 0.135717 -vn 0.667992 -0.203652 0.715760 -v 0.017950 0.130595 0.135853 -vn 0.667993 -0.448462 0.593858 -v 0.017950 0.131911 0.136508 -vn 0.667993 -0.632703 0.391756 -v 0.017950 0.132901 0.137594 -vn 0.667992 -0.731497 0.136743 -v 0.017950 0.133432 0.138965 -vn 0.667992 -0.731497 -0.136743 -v 0.017950 0.133432 0.140435 -vn 0.667993 -0.632703 -0.391756 -v 0.017950 0.132901 0.141806 -vn 0.667993 -0.448462 -0.593858 -v 0.017950 0.131911 0.142892 -vn 0.667993 -0.203655 -0.715758 -v 0.017950 0.130595 0.143547 -vn 0.667992 0.068661 -0.740994 -v 0.017950 0.129131 0.143683 -vn 0.667992 0.331706 -0.666151 -v 0.017950 0.127717 0.143281 -vn 0.667993 0.549946 -0.501342 -v 0.017950 0.126544 0.142395 -vn 0.667992 0.693915 -0.268826 -v 0.017950 0.125770 0.141145 -vn 0.976002 0.108881 -0.188587 -v 0.017950 0.128737 0.141021 -vn 0.976002 0.188587 -0.108881 -v 0.017950 0.128179 0.140462 -vn 0.976002 0.217762 -0.000000 -v 0.017950 0.127975 0.139700 -vn 0.976001 0.188591 0.108884 -v 0.017950 0.128179 0.138937 -vn 0.976001 -0.108882 -0.188593 -v 0.017950 0.130262 0.141021 -vn 0.976002 -0.000001 -0.217762 -v 0.017950 0.129500 0.141225 -vn 0.976002 -0.188585 0.108879 -v 0.017950 0.130821 0.138937 -vn 0.976002 -0.217760 -0.000000 -v 0.017950 0.131025 0.139700 -vn 0.976004 -0.188581 -0.108877 -v 0.017950 0.130821 0.140462 -vn 0.976002 -0.000001 0.217760 -v 0.017950 0.129500 0.138175 -vn 0.976003 -0.108879 0.188585 -v 0.017950 0.130262 0.138379 -vn 0.976004 0.108878 0.188579 -v 0.017950 0.128737 0.138379 -vn -1.000000 -0.000003 0.000003 -v 0.015731 0.138500 0.148950 -vn -0.460547 -0.768711 0.443823 -v 0.015250 0.139193 0.148550 -vn -0.460547 -0.443823 0.768711 -v 0.015250 0.138900 0.148257 -vn -0.460547 -0.887635 0.000004 -v 0.015250 0.139300 0.148950 -vn -0.460549 0.443819 0.768713 -v 0.015250 0.138100 0.148257 -vn -0.460549 0.768718 0.443810 -v 0.015250 0.137807 0.148550 -vn -0.460547 -0.000004 0.887635 -v 0.015250 0.138500 0.148150 -vn -0.460550 0.768720 -0.443806 -v 0.015250 0.137807 0.149350 -vn -0.460550 0.443806 -0.768720 -v 0.015250 0.138100 0.149643 -vn -0.460551 0.887633 0.000004 -v 0.015250 0.137700 0.148950 -vn -0.460548 -0.443810 -0.768719 -v 0.015250 0.138900 0.149643 -vn -0.460549 -0.768713 -0.443820 -v 0.015250 0.139193 0.149350 -vn -0.460551 -0.000004 -0.887633 -v 0.015250 0.138500 0.149750 -vn -0.539405 -0.842046 0.000004 -v 0.010808 0.139300 0.148950 -vn -0.539412 -0.729228 0.421023 -v 0.010808 0.139193 0.148550 -vn -0.539413 -0.421024 0.729227 -v 0.010808 0.138900 0.148257 -vn -0.539406 -0.000003 0.842046 -v 0.010808 0.138500 0.148150 -vn -0.539398 0.421031 0.729235 -v 0.010808 0.138100 0.148257 -vn -0.539414 0.729233 0.421013 -v 0.010808 0.137807 0.148550 -vn -0.539400 0.842050 0.000003 -v 0.010808 0.137700 0.148950 -vn -0.539401 0.729240 -0.421017 -v 0.010808 0.137807 0.149350 -vn -0.539375 0.421018 -0.729259 -v 0.010808 0.138100 0.149643 -vn -0.539397 0.000001 -0.842052 -v 0.010808 0.138500 0.149750 -vn -0.539390 -0.421018 -0.729248 -v 0.010808 0.138900 0.149643 -vn -0.539398 -0.729234 -0.421031 -v 0.010808 0.139193 0.149350 -vn -1.000000 -0.000003 0.000003 -v 0.015731 0.138500 0.130450 -vn -0.460548 -0.768711 0.443823 -v 0.015250 0.139193 0.130050 -vn -0.460548 -0.443823 0.768711 -v 0.015250 0.138900 0.129757 -vn -0.460547 -0.887635 0.000004 -v 0.015250 0.139300 0.130450 -vn -0.460550 0.443819 0.768712 -v 0.015250 0.138100 0.129757 -vn -0.460549 0.768718 0.443810 -v 0.015250 0.137807 0.130050 -vn -0.460547 -0.000004 0.887635 -v 0.015250 0.138500 0.129650 -vn -0.460550 0.768720 -0.443806 -v 0.015250 0.137807 0.130850 -vn -0.460550 0.443806 -0.768720 -v 0.015250 0.138100 0.131143 -vn -0.460551 0.887633 0.000004 -v 0.015250 0.137700 0.130450 -vn -0.460549 -0.443810 -0.768718 -v 0.015250 0.138900 0.131143 -vn -0.460549 -0.768713 -0.443820 -v 0.015250 0.139193 0.130850 -vn -0.460551 -0.000004 -0.887633 -v 0.015250 0.138500 0.131250 -vn -0.539405 -0.842046 0.000004 -v 0.010808 0.139300 0.130450 -vn -0.539412 -0.729228 0.421023 -v 0.010808 0.139193 0.130050 -vn -0.539413 -0.421024 0.729227 -v 0.010808 0.138900 0.129757 -vn -0.539406 -0.000003 0.842046 -v 0.010808 0.138500 0.129650 -vn -0.539398 0.421031 0.729235 -v 0.010808 0.138100 0.129757 -vn -0.539414 0.729233 0.421013 -v 0.010808 0.137807 0.130050 -vn -0.539400 0.842050 0.000003 -v 0.010808 0.137700 0.130450 -vn -0.539401 0.729240 -0.421017 -v 0.010808 0.137807 0.130850 -vn -0.539375 0.421018 -0.729259 -v 0.010808 0.138100 0.131143 -vn -0.539397 0.000001 -0.842052 -v 0.010808 0.138500 0.131250 -vn -0.539390 -0.421018 -0.729248 -v 0.010808 0.138900 0.131143 -vn -0.539398 -0.729234 -0.421031 -v 0.010808 0.139193 0.130850 -vn -1.000000 -0.000001 0.000004 -v 0.015731 0.096500 0.150100 -vn -0.460549 -0.768713 0.443818 -v 0.015250 0.097193 0.149700 -vn -0.460548 -0.443826 0.768709 -v 0.015250 0.096900 0.149407 -vn -0.460548 -0.887635 0.000004 -v 0.015250 0.097300 0.150100 -vn -0.460548 0.443821 0.768712 -v 0.015250 0.096100 0.149407 -vn -0.460549 0.768714 0.443816 -v 0.015250 0.095807 0.149700 -vn -0.460548 -0.000000 0.887635 -v 0.015250 0.096500 0.149300 -vn -0.460550 0.768715 -0.443813 -v 0.015250 0.095807 0.150500 -vn -0.460551 0.443820 -0.768711 -v 0.015250 0.096100 0.150793 -vn -0.460550 0.887634 0.000004 -v 0.015250 0.095700 0.150100 -vn -0.460551 -0.443825 -0.768708 -v 0.015250 0.096900 0.150793 -vn -0.460550 -0.768715 -0.443815 -v 0.015250 0.097193 0.150500 -vn -0.460551 0.000000 -0.887633 -v 0.015250 0.096500 0.150900 -vn -0.539405 -0.842046 0.000004 -v 0.010808 0.097300 0.150100 -vn -0.539411 -0.729232 0.421018 -v 0.010808 0.097193 0.149700 -vn -0.539407 -0.421030 0.729228 -v 0.010808 0.096900 0.149407 -vn -0.539406 0.000001 0.842046 -v 0.010808 0.096500 0.149300 -vn -0.539405 0.421026 0.729231 -v 0.010808 0.096100 0.149407 -vn -0.539413 0.729230 0.421019 -v 0.010808 0.095807 0.149700 -vn -0.539403 0.842048 0.000003 -v 0.010808 0.095700 0.150100 -vn -0.539399 0.729237 -0.421025 -v 0.010808 0.095807 0.150500 -vn -0.539405 0.421029 -0.729231 -v 0.010808 0.096100 0.150793 -vn -0.539376 -0.000006 -0.842065 -v 0.010808 0.096500 0.150900 -vn -0.539404 -0.421028 -0.729232 -v 0.010808 0.096900 0.150793 -vn -0.539398 -0.729238 -0.421025 -v 0.010808 0.097193 0.150500 -vn -1.000000 -0.000001 0.000001 -v 0.015731 0.096500 0.129300 -vn -0.460549 -0.768714 0.443818 -v 0.015250 0.097193 0.128900 -vn -0.460548 -0.443826 0.768709 -v 0.015250 0.096900 0.128607 -vn -0.460547 -0.887635 0.000004 -v 0.015250 0.097300 0.129300 -vn -0.460548 0.443821 0.768712 -v 0.015250 0.096100 0.128607 -vn -0.460549 0.768714 0.443817 -v 0.015250 0.095807 0.128900 -vn -0.460547 -0.000000 0.887635 -v 0.015250 0.096500 0.128500 -vn -0.460548 0.768711 -0.443823 -v 0.015250 0.095807 0.129700 -vn -0.460549 0.443811 -0.768717 -v 0.015250 0.096100 0.129993 -vn -0.460550 0.887634 0.000004 -v 0.015250 0.095700 0.129300 -vn -0.460549 -0.443816 -0.768714 -v 0.015250 0.096900 0.129993 -vn -0.460548 -0.768710 -0.443825 -v 0.015250 0.097193 0.129700 -vn -0.460547 0.000000 -0.887635 -v 0.015250 0.096500 0.130100 -vn -0.539405 -0.842046 0.000004 -v 0.010808 0.097300 0.129300 -vn -0.539411 -0.729232 0.421018 -v 0.010808 0.097193 0.128900 -vn -0.539407 -0.421030 0.729228 -v 0.010808 0.096900 0.128607 -vn -0.539406 0.000001 0.842046 -v 0.010808 0.096500 0.128500 -vn -0.539405 0.421026 0.729231 -v 0.010808 0.096100 0.128607 -vn -0.539413 0.729230 0.421019 -v 0.010808 0.095807 0.128900 -vn -0.539403 0.842048 0.000003 -v 0.010808 0.095700 0.129300 -vn -0.539401 0.729230 -0.421034 -v 0.010808 0.095807 0.129700 -vn -0.539403 0.421020 -0.729237 -v 0.010808 0.096100 0.129993 -vn -0.539406 -0.000001 -0.842046 -v 0.010808 0.096500 0.130100 -vn -0.539404 -0.421022 -0.729235 -v 0.010808 0.096900 0.129993 -vn -0.539400 -0.729231 -0.421034 -v 0.010808 0.097193 0.129700 -vn 0.539395 0.842053 -0.000001 -v 0.017791 0.128250 0.139700 -vn 0.539394 0.729238 0.421030 -v 0.017791 0.128417 0.139075 -vn 0.539402 0.421025 0.729235 -v 0.017791 0.128875 0.138617 -vn 0.539401 -0.000002 0.842049 -v 0.017791 0.129500 0.138450 -vn 0.539399 -0.421029 0.729235 -v 0.017791 0.130125 0.138617 -vn 0.539400 -0.729234 0.421030 -v 0.017791 0.130583 0.139075 -vn 0.539400 -0.842050 -0.000001 -v 0.017791 0.130750 0.139700 -vn 0.539403 -0.729238 -0.421019 -v 0.017791 0.130583 0.140325 -vn 0.539395 -0.421024 -0.729240 -v 0.017791 0.130125 0.140783 -vn 0.539395 -0.000002 -0.842053 -v 0.017791 0.129500 0.140950 -vn 0.539398 0.421020 -0.729241 -v 0.017791 0.128875 0.140783 -vn 0.539397 0.729242 -0.421019 -v 0.017791 0.128417 0.140325 -vn 0.406939 0.913456 0.000007 -v 0.015650 0.136100 0.145700 -vn 0.406963 0.791066 0.456724 -v 0.015650 0.136221 0.145250 -vn 0.406967 0.456715 0.791068 -v 0.015650 0.136550 0.144921 -vn 0.406970 0.000001 0.913442 -v 0.015650 0.137000 0.144800 -vn 0.406985 -0.456694 0.791071 -v 0.015650 0.137450 0.144921 -vn 0.406940 -0.791080 0.456719 -v 0.015650 0.137779 0.145250 -vn 0.406966 -0.913443 0.000006 -v 0.015650 0.137900 0.145700 -vn 0.406956 -0.791076 -0.456711 -v 0.015650 0.137779 0.146150 -vn 0.406953 -0.456708 -0.791080 -v 0.015650 0.137450 0.146479 -vn 0.406967 -0.000005 -0.913443 -v 0.015650 0.137000 0.146600 -vn 0.406939 0.456732 -0.791073 -v 0.015650 0.136550 0.146479 -vn 0.406979 0.791061 -0.456716 -v 0.015650 0.136221 0.146150 -vn 0.406956 0.913448 0.000004 -v 0.015650 0.122600 0.147700 -vn 0.406964 0.791064 0.456726 -v 0.015650 0.122721 0.147250 -vn 0.406966 0.456728 0.791062 -v 0.015650 0.123050 0.146921 -vn 0.406973 0.000000 0.913440 -v 0.015650 0.123500 0.146800 -vn 0.406975 -0.456717 0.791063 -v 0.015650 0.123950 0.146921 -vn 0.406953 -0.791071 0.456723 -v 0.015650 0.124279 0.147250 -vn 0.406970 -0.913442 0.000003 -v 0.015650 0.124400 0.147700 -vn 0.406971 -0.791065 -0.456718 -v 0.015650 0.124279 0.148150 -vn 0.406975 -0.456718 -0.791063 -v 0.015650 0.123950 0.148479 -vn 0.406973 0.000001 -0.913440 -v 0.015650 0.123500 0.148600 -vn 0.406966 0.456728 -0.791061 -v 0.015650 0.123050 0.148479 -vn 0.406983 0.791057 -0.456721 -v 0.015650 0.122721 0.148150 -vn 0.406971 0.913441 -0.000002 -v 0.015650 0.107100 0.147700 -vn 0.406952 0.791067 0.456730 -v 0.015650 0.107221 0.147250 -vn 0.406972 0.456722 0.791061 -v 0.015650 0.107550 0.146921 -vn 0.406973 -0.000001 0.913440 -v 0.015650 0.108000 0.146800 -vn 0.406975 -0.456722 0.791060 -v 0.015650 0.108450 0.146921 -vn 0.406967 -0.791062 0.456726 -v 0.015650 0.108779 0.147250 -vn 0.406955 -0.913448 -0.000003 -v 0.015650 0.108900 0.147700 -vn 0.406983 -0.791061 -0.456714 -v 0.015650 0.108779 0.148150 -vn 0.406977 -0.456721 -0.791060 -v 0.015650 0.108450 0.148479 -vn 0.406973 0.000001 -0.913440 -v 0.015650 0.108000 0.148600 -vn 0.406975 0.456717 -0.791063 -v 0.015650 0.107550 0.148479 -vn 0.406970 0.791066 -0.456717 -v 0.015650 0.107221 0.148150 -vn 0.406939 0.913456 0.000007 -v 0.015650 0.136100 0.133700 -vn 0.406963 0.791066 0.456724 -v 0.015650 0.136221 0.133250 -vn 0.406966 0.456728 0.791062 -v 0.015650 0.136550 0.132921 -vn 0.406973 0.000000 0.913440 -v 0.015650 0.137000 0.132800 -vn 0.406983 -0.456707 0.791065 -v 0.015650 0.137450 0.132921 -vn 0.406940 -0.791080 0.456719 -v 0.015650 0.137779 0.133250 -vn 0.406966 -0.913443 0.000006 -v 0.015650 0.137900 0.133700 -vn 0.406957 -0.791070 -0.456720 -v 0.015650 0.137779 0.134150 -vn 0.406981 -0.456712 -0.791062 -v 0.015650 0.137450 0.134479 -vn 0.406974 0.000001 -0.913440 -v 0.015650 0.137000 0.134600 -vn 0.406966 0.456728 -0.791062 -v 0.015650 0.136550 0.134479 -vn 0.406983 0.791057 -0.456721 -v 0.015650 0.136221 0.134150 -vn 0.406971 0.913441 -0.000002 -v 0.015650 0.107100 0.131700 -vn 0.406952 0.791067 0.456730 -v 0.015650 0.107221 0.131250 -vn 0.406972 0.456722 0.791061 -v 0.015650 0.107550 0.130921 -vn 0.406938 -0.000006 0.913456 -v 0.015650 0.108000 0.130800 -vn 0.406972 -0.456718 0.791064 -v 0.015650 0.108450 0.130921 -vn 0.406967 -0.791062 0.456726 -v 0.015650 0.108779 0.131250 -vn 0.406955 -0.913448 -0.000003 -v 0.015650 0.108900 0.131700 -vn 0.406982 -0.791067 -0.456705 -v 0.015650 0.108779 0.132150 -vn 0.406949 -0.456716 -0.791077 -v 0.015650 0.108450 0.132479 -vn 0.406967 -0.000005 -0.913443 -v 0.015650 0.108000 0.132600 -vn 0.406947 0.456722 -0.791075 -v 0.015650 0.107550 0.132479 -vn 0.406966 0.791071 -0.456712 -v 0.015650 0.107221 0.132150 -vn 0.406956 0.913448 0.000004 -v 0.015650 0.122600 0.131700 -vn 0.406964 0.791064 0.456726 -v 0.015650 0.122721 0.131250 -vn 0.406966 0.456728 0.791062 -v 0.015650 0.123050 0.130921 -vn 0.406938 -0.000005 0.913456 -v 0.015650 0.123500 0.130800 -vn 0.406971 -0.456713 0.791067 -v 0.015650 0.123950 0.130921 -vn 0.406953 -0.791071 0.456723 -v 0.015650 0.124279 0.131250 -vn 0.406970 -0.913442 0.000003 -v 0.015650 0.124400 0.131700 -vn 0.406970 -0.791071 -0.456709 -v 0.015650 0.124279 0.132150 -vn 0.406947 -0.456713 -0.791080 -v 0.015650 0.123950 0.132479 -vn 0.406967 -0.000005 -0.913443 -v 0.015650 0.123500 0.132600 -vn 0.406939 0.456732 -0.791073 -v 0.015650 0.123050 0.132479 -vn 0.406979 0.791061 -0.456716 -v 0.015650 0.122721 0.132150 -vn 0.496979 0.033957 0.867098 -v 0.015250 0.136000 0.152566 -vn 0.863078 0.019975 0.504676 -v 0.015616 0.136000 0.152200 -vn 0.863077 0.504678 0.019974 -v 0.015616 0.140500 0.147700 -vn 0.860425 0.503303 0.079716 -v 0.015616 0.140445 0.148404 -vn 0.496980 0.867098 0.033951 -v 0.015250 0.140866 0.147700 -vn 0.494486 0.858485 0.135972 -v 0.015250 0.140806 0.148461 -vn 0.494483 0.826646 0.268595 -v 0.015250 0.140628 0.149204 -vn 0.494485 0.774451 0.394601 -v 0.015250 0.140336 0.149909 -vn 0.494489 0.703184 0.510894 -v 0.015250 0.139937 0.150560 -vn 0.494482 0.614611 0.614607 -v 0.015250 0.139441 0.151141 -vn 0.494482 0.510894 0.703189 -v 0.015250 0.138860 0.151637 -vn 0.494477 0.394608 0.774452 -v 0.015250 0.138209 0.152036 -vn 0.494477 0.268595 0.826649 -v 0.015250 0.137504 0.152328 -vn 0.494478 0.135976 0.858488 -v 0.015250 0.136761 0.152506 -vn 0.860421 0.484643 0.157468 -v 0.015616 0.140280 0.149091 -vn 0.860425 0.454034 0.231346 -v 0.015616 0.140010 0.149743 -vn 0.860425 0.412257 0.299521 -v 0.015616 0.139641 0.150345 -vn 0.860422 0.360332 0.360327 -v 0.015616 0.139182 0.150882 -vn 0.860422 0.299526 0.412261 -v 0.015616 0.138645 0.151341 -vn 0.860423 0.231347 0.454039 -v 0.015616 0.138043 0.151710 -vn 0.860422 0.157471 0.484642 -v 0.015616 0.137391 0.151980 -vn 0.860424 0.079715 0.503305 -v 0.015616 0.136704 0.152145 -vn 0.863077 0.504678 -0.019975 -v 0.015616 0.140500 0.131700 -vn 0.496981 0.867097 -0.033951 -v 0.015250 0.140866 0.131700 -vn 0.863074 0.019974 -0.504682 -v 0.015616 0.136000 0.127200 -vn 0.860423 0.079719 -0.503306 -v 0.015616 0.136704 0.127255 -vn 0.496971 0.033951 -0.867103 -v 0.015250 0.136000 0.126834 -vn 0.494477 0.135975 -0.858489 -v 0.015250 0.136761 0.126894 -vn 0.494479 0.268596 -0.826648 -v 0.015250 0.137504 0.127072 -vn 0.494477 0.394600 -0.774457 -v 0.015250 0.138209 0.127364 -vn 0.494481 0.510898 -0.703187 -v 0.015250 0.138860 0.127763 -vn 0.494473 0.614610 -0.614614 -v 0.015250 0.139441 0.128259 -vn 0.494489 0.703186 -0.510891 -v 0.015250 0.139937 0.128840 -vn 0.494490 0.774450 -0.394597 -v 0.015250 0.140336 0.129491 -vn 0.494483 0.826646 -0.268595 -v 0.015250 0.140628 0.130196 -vn 0.494484 0.858486 -0.135973 -v 0.015250 0.140806 0.130939 -vn 0.860422 0.157469 -0.484642 -v 0.015616 0.137391 0.127420 -vn 0.860423 0.231344 -0.454040 -v 0.015616 0.138043 0.127690 -vn 0.860423 0.299524 -0.412260 -v 0.015616 0.138645 0.128059 -vn 0.860424 0.360329 -0.360325 -v 0.015616 0.139182 0.128518 -vn 0.860426 0.412257 -0.299518 -v 0.015616 0.139641 0.129055 -vn 0.860426 0.454035 -0.231342 -v 0.015616 0.140010 0.129657 -vn 0.860421 0.484643 -0.157474 -v 0.015616 0.140280 0.130309 -vn 0.860427 0.503300 -0.079711 -v 0.015616 0.140445 0.130996 -vn 0.127823 0.495888 -0.858927 -v 0.018450 0.103850 0.129740 -vn 0.127834 0.858914 -0.495909 -v 0.018450 0.103960 0.129850 -vn 0.854922 -0.069834 -0.514035 -v 0.018710 0.097300 0.129850 -vn 0.854926 0.069822 -0.514030 -v 0.018710 0.103700 0.129850 -vn 0.488319 -0.112932 -0.865327 -v 0.018600 0.097300 0.129740 -vn 0.488321 0.112919 -0.865328 -v 0.018600 0.103700 0.129740 -vn 0.127833 -0.858921 -0.495897 -v 0.018450 0.097040 0.129850 -vn 0.127838 -0.495887 -0.858926 -v 0.018450 0.097150 0.129740 -vn 0.488334 0.865319 -0.112932 -v 0.018600 0.103960 0.130000 -vn 0.482344 0.758624 -0.437988 -v 0.018600 0.103925 0.129870 -vn 0.847433 0.265459 -0.459770 -v 0.018710 0.103775 0.129870 -vn 0.847424 0.459777 -0.265478 -v 0.018710 0.103830 0.129925 -vn 0.482345 0.438004 -0.758614 -v 0.018600 0.103830 0.129775 -vn 0.854929 0.514026 -0.069807 -v 0.018710 0.103850 0.130000 -vn 0.482347 -0.437985 -0.758624 -v 0.018600 0.097170 0.129775 -vn 0.854927 -0.514027 -0.069829 -v 0.018710 0.097150 0.130000 -vn 0.847434 -0.459754 -0.265483 -v 0.018710 0.097170 0.129925 -vn 0.847435 -0.265447 -0.459774 -v 0.018710 0.097225 0.129870 -vn 0.482347 -0.758616 -0.437999 -v 0.018600 0.097075 0.129870 -vn 0.488321 -0.865326 -0.112929 -v 0.018600 0.097040 0.130000 -vn 0.127838 0.858918 0.495901 -v 0.018450 0.103960 0.135550 -vn 0.127831 0.495888 0.858926 -v 0.018450 0.103850 0.135660 -vn 0.854928 0.514028 0.069809 -v 0.018710 0.103850 0.135400 -vn 0.488337 0.865318 0.112922 -v 0.018600 0.103960 0.135400 -vn 0.854925 -0.514030 0.069834 -v 0.018710 0.097150 0.135400 -vn 0.488321 -0.865327 0.112926 -v 0.018600 0.097040 0.135400 -vn 0.127833 -0.495891 0.858924 -v 0.018450 0.097150 0.135660 -vn 0.127838 -0.858929 0.495882 -v 0.018450 0.097040 0.135550 -vn 0.488319 0.112925 0.865328 -v 0.018600 0.103700 0.135660 -vn 0.482341 0.438005 0.758616 -v 0.018600 0.103830 0.135625 -vn 0.847435 0.459786 0.265428 -v 0.018710 0.103830 0.135475 -vn 0.847436 0.265474 0.459756 -v 0.018710 0.103775 0.135530 -vn 0.482348 0.758626 0.437980 -v 0.018600 0.103925 0.135530 -vn 0.854929 0.069826 0.514024 -v 0.018710 0.103700 0.135550 -vn 0.482354 -0.758623 0.437980 -v 0.018600 0.097075 0.135530 -vn 0.854931 -0.069826 0.514021 -v 0.018710 0.097300 0.135550 -vn 0.847442 -0.265474 0.459746 -v 0.018710 0.097225 0.135530 -vn 0.847442 -0.459767 0.265437 -v 0.018710 0.097170 0.135475 -vn 0.482353 -0.437994 0.758615 -v 0.018600 0.097170 0.135625 -vn 0.488322 -0.112923 0.865327 -v 0.018600 0.097300 0.135660 -vn 0.127833 -0.858921 -0.495897 -v 0.018450 0.097040 0.143850 -vn 0.127838 -0.495887 -0.858926 -v 0.018450 0.097150 0.143740 -vn 0.488321 -0.865326 -0.112929 -v 0.018600 0.097040 0.144000 -vn 0.488321 -0.865327 0.112926 -v 0.018600 0.097040 0.149400 -vn 0.854927 -0.514027 -0.069828 -v 0.018710 0.097150 0.144000 -vn 0.854925 -0.514030 0.069834 -v 0.018710 0.097150 0.149400 -vn 0.127833 -0.495891 0.858924 -v 0.018450 0.097150 0.149660 -vn 0.127838 -0.858929 0.495882 -v 0.018450 0.097040 0.149550 -vn 0.488319 -0.112932 -0.865327 -v 0.018600 0.097300 0.143740 -vn 0.482347 -0.437985 -0.758624 -v 0.018600 0.097170 0.143775 -vn 0.847434 -0.459754 -0.265483 -v 0.018710 0.097170 0.143925 -vn 0.847435 -0.265447 -0.459774 -v 0.018710 0.097225 0.143870 -vn 0.482347 -0.758616 -0.437999 -v 0.018600 0.097075 0.143870 -vn 0.854922 -0.069834 -0.514035 -v 0.018710 0.097300 0.143850 -vn 0.482354 -0.758623 0.437980 -v 0.018600 0.097075 0.149530 -vn 0.854931 -0.069826 0.514021 -v 0.018710 0.097300 0.149550 -vn 0.847442 -0.265474 0.459746 -v 0.018710 0.097225 0.149530 -vn 0.847442 -0.459767 0.265437 -v 0.018710 0.097170 0.149475 -vn 0.482353 -0.437994 0.758615 -v 0.018600 0.097170 0.149625 -vn 0.488322 -0.112923 0.865327 -v 0.018600 0.097300 0.149660 -vn 0.127823 0.495888 -0.858927 -v 0.018450 0.103850 0.143740 -vn 0.127834 0.858914 -0.495909 -v 0.018450 0.103960 0.143850 -vn 0.488321 0.112919 -0.865328 -v 0.018600 0.103700 0.143740 -vn 0.854926 0.069822 -0.514030 -v 0.018710 0.103700 0.143850 -vn 0.488319 0.112925 0.865328 -v 0.018600 0.103700 0.149660 -vn 0.854929 0.069826 0.514024 -v 0.018710 0.103700 0.149550 -vn 0.127838 0.858918 0.495901 -v 0.018450 0.103960 0.149550 -vn 0.127831 0.495888 0.858926 -v 0.018450 0.103850 0.149660 -vn 0.488334 0.865319 -0.112932 -v 0.018600 0.103960 0.144000 -vn 0.482344 0.758624 -0.437988 -v 0.018600 0.103925 0.143870 -vn 0.847433 0.265459 -0.459770 -v 0.018710 0.103775 0.143870 -vn 0.847424 0.459777 -0.265478 -v 0.018710 0.103830 0.143925 -vn 0.482345 0.438004 -0.758614 -v 0.018600 0.103830 0.143775 -vn 0.854929 0.514026 -0.069807 -v 0.018710 0.103850 0.144000 -vn 0.482341 0.438005 0.758616 -v 0.018600 0.103830 0.149625 -vn 0.854928 0.514028 0.069810 -v 0.018710 0.103850 0.149400 -vn 0.847435 0.459786 0.265428 -v 0.018710 0.103830 0.149475 -vn 0.847436 0.265474 0.459756 -v 0.018710 0.103775 0.149530 -vn 0.482348 0.758626 0.437980 -v 0.018600 0.103925 0.149530 -vn 0.488337 0.865318 0.112922 -v 0.018600 0.103960 0.149400 -vn 0.860428 -0.503298 -0.079715 -v 0.018510 0.124315 0.138879 -vn 0.860420 -0.484645 -0.157469 -v 0.018510 0.124507 0.138078 -vn 0.860433 -0.454025 -0.231335 -v 0.018510 0.124822 0.137317 -vn 0.860436 -0.412243 -0.299510 -v 0.018510 0.125253 0.136614 -vn 0.860420 -0.360334 -0.360330 -v 0.018510 0.125788 0.135988 -vn 0.860425 -0.299520 -0.412257 -v 0.018510 0.126414 0.135453 -vn 0.860423 -0.231345 -0.454039 -v 0.018510 0.127117 0.135022 -vn 0.860435 -0.157462 -0.484622 -v 0.018510 0.127878 0.134707 -vn 0.860421 -0.079716 -0.503310 -v 0.018510 0.128679 0.134515 -vn 0.860422 -0.000000 -0.509581 -v 0.018510 0.129500 0.134450 -vn 0.860423 0.079715 -0.503307 -v 0.018510 0.130321 0.134515 -vn 0.860430 0.157469 -0.484628 -v 0.018510 0.131122 0.134707 -vn 0.860425 0.231342 -0.454037 -v 0.018510 0.131883 0.135022 -vn 0.860436 0.299511 -0.412242 -v 0.018510 0.132586 0.135453 -vn 0.860420 0.360328 -0.360334 -v 0.018510 0.133212 0.135988 -vn 0.860437 0.412242 -0.299508 -v 0.018510 0.133747 0.136614 -vn 0.860429 0.454031 -0.231339 -v 0.018510 0.134178 0.137317 -vn 0.860419 0.484646 -0.157471 -v 0.018510 0.134493 0.138078 -vn 0.860423 0.503307 -0.079712 -v 0.018510 0.134685 0.138879 -vn 0.860422 0.509581 -0.000000 -v 0.018510 0.134750 0.139700 -vn 0.860420 0.503312 0.079715 -v 0.018510 0.134685 0.140521 -vn 0.860420 0.484645 0.157470 -v 0.018510 0.134493 0.141322 -vn 0.860422 0.454040 0.231347 -v 0.018510 0.134178 0.142083 -vn 0.860426 0.412254 0.299522 -v 0.018510 0.133747 0.142786 -vn 0.860432 0.360315 0.360318 -v 0.018510 0.133212 0.143412 -vn 0.860432 0.299515 0.412248 -v 0.018510 0.132586 0.143947 -vn 0.860423 0.231346 0.454038 -v 0.018510 0.131883 0.144378 -vn 0.860419 0.157473 0.484646 -v 0.018510 0.131122 0.144693 -vn 0.860435 0.079712 0.503287 -v 0.018510 0.130321 0.144885 -vn 0.860422 0.000002 0.509582 -v 0.018510 0.129500 0.144950 -vn 0.860434 -0.079716 0.503289 -v 0.018510 0.128679 0.144885 -vn 0.860423 -0.157466 0.484641 -v 0.018510 0.127878 0.144693 -vn 0.860422 -0.231346 0.454041 -v 0.018510 0.127117 0.144378 -vn 0.860422 -0.299526 0.412260 -v 0.018510 0.126414 0.143947 -vn 0.860432 -0.360319 0.360316 -v 0.018510 0.125788 0.143412 -vn 0.860425 -0.412256 0.299522 -v 0.018510 0.125253 0.142786 -vn 0.860424 -0.454038 0.231343 -v 0.018510 0.124822 0.142083 -vn 0.860420 -0.484644 0.157472 -v 0.018510 0.124507 0.141322 -vn 0.860426 -0.503301 0.079715 -v 0.018510 0.124315 0.140521 -vn 0.860422 -0.509582 0.000001 -v 0.018510 0.124250 0.139700 -vn 0.494486 -0.858484 -0.135970 -v 0.018400 0.124206 0.138862 -vn 0.494486 -0.826644 -0.268594 -v 0.018400 0.124403 0.138044 -vn 0.494471 -0.774460 -0.394601 -v 0.018400 0.124724 0.137267 -vn 0.494486 -0.703187 -0.510894 -v 0.018400 0.125164 0.136550 -vn 0.494488 -0.614608 -0.614604 -v 0.018400 0.125710 0.135910 -vn 0.494470 -0.510901 -0.703193 -v 0.018400 0.126350 0.135364 -vn 0.494512 -0.394589 -0.774440 -v 0.018400 0.127067 0.134924 -vn 0.494489 -0.268597 -0.826642 -v 0.018400 0.127844 0.134603 -vn 0.494476 -0.135973 -0.858490 -v 0.018400 0.128662 0.134406 -vn 0.494509 0.000004 -0.869173 -v 0.018400 0.129500 0.134340 -vn 0.494472 0.135969 -0.858493 -v 0.018400 0.130338 0.134406 -vn 0.494494 0.268591 -0.826640 -v 0.018400 0.131156 0.134603 -vn 0.494513 0.394594 -0.774437 -v 0.018400 0.131933 0.134924 -vn 0.494485 0.510893 -0.703188 -v 0.018400 0.132650 0.135364 -vn 0.494489 0.614609 -0.614603 -v 0.018400 0.133290 0.135910 -vn 0.494483 0.703187 -0.510896 -v 0.018400 0.133836 0.136550 -vn 0.494473 0.774457 -0.394605 -v 0.018400 0.134276 0.137267 -vn 0.494469 0.826655 -0.268593 -v 0.018400 0.134597 0.138044 -vn 0.494474 0.858492 -0.135972 -v 0.018400 0.134794 0.138862 -vn 0.494509 0.869173 0.000004 -v 0.018400 0.134860 0.139700 -vn 0.494467 0.858496 0.135967 -v 0.018400 0.134794 0.140538 -vn 0.494455 0.826662 0.268596 -v 0.018400 0.134597 0.141356 -vn 0.494478 0.774456 0.394601 -v 0.018400 0.134276 0.142133 -vn 0.494490 0.703184 0.510892 -v 0.018400 0.133836 0.142850 -vn 0.494478 0.614609 0.614611 -v 0.018400 0.133290 0.143490 -vn 0.494485 0.510895 0.703186 -v 0.018400 0.132650 0.144036 -vn 0.494481 0.394603 0.774453 -v 0.018400 0.131933 0.144476 -vn 0.494505 0.268590 0.826634 -v 0.018400 0.131156 0.144797 -vn 0.494497 0.135970 0.858478 -v 0.018400 0.130338 0.144994 -vn 0.494472 0.000003 0.869193 -v 0.018400 0.129500 0.145060 -vn 0.494500 -0.135971 0.858476 -v 0.018400 0.128662 0.144994 -vn 0.494503 -0.268598 0.826633 -v 0.018400 0.127844 0.144797 -vn 0.494477 -0.394602 0.774456 -v 0.018400 0.127067 0.144476 -vn 0.494468 -0.510899 0.703195 -v 0.018400 0.126350 0.144036 -vn 0.494480 -0.614609 0.614610 -v 0.018400 0.125710 0.143490 -vn 0.494492 -0.703187 0.510887 -v 0.018400 0.125164 0.142850 -vn 0.494478 -0.774457 0.394599 -v 0.018400 0.124724 0.142133 -vn 0.494474 -0.826650 0.268597 -v 0.018400 0.124403 0.141356 -vn 0.494481 -0.858487 0.135969 -v 0.018400 0.124206 0.140538 -vn 0.494491 -0.869183 -0.000001 -v 0.018400 0.124140 0.139700 -vn -0.673140 -0.513710 -0.531962 -v -0.019750 0.131410 0.141678 -vn -0.674182 -0.313588 -0.668686 -v -0.019750 0.130664 0.142191 -vn -0.389832 -0.465237 -0.794724 -v -0.020950 0.130706 0.142172 -vn -0.675655 -0.079091 -0.732963 -v -0.019750 0.129792 0.142434 -vn -0.390507 -0.189293 -0.900929 -v -0.020950 0.129883 0.142423 -vn -0.386450 -0.329048 -0.861617 -v -0.020950 0.130664 0.142191 -vn -0.676931 0.163115 -0.717745 -v -0.019750 0.128889 0.142381 -vn -0.397988 0.113099 -0.910392 -v -0.020950 0.129022 0.142408 -vn -0.392163 -0.046105 -0.918740 -v -0.020950 0.129792 0.142434 -vn -0.678009 0.386932 -0.624969 -v -0.019750 0.128051 0.142037 -vn -0.391670 0.390188 -0.833275 -v -0.020950 0.128209 0.142128 -vn -0.381567 0.256541 -0.888027 -v -0.020950 0.128889 0.142381 -vn -0.678898 0.568332 -0.464861 -v -0.019750 0.127371 0.141440 -vn -0.392136 0.634063 -0.666478 -v -0.020950 0.127522 0.141610 -vn -0.379255 0.525321 -0.761711 -v -0.020950 0.128051 0.142037 -vn -0.679608 0.687893 -0.254826 -v -0.019750 0.126921 0.140655 -vn -0.392530 0.812509 -0.430986 -v -0.020950 0.127028 0.140906 -vn -0.377171 0.740173 -0.556675 -v -0.020950 0.127371 0.141440 -vn -0.680132 0.732879 -0.017593 -v -0.019750 0.126751 0.139766 -vn -0.392843 0.907100 -0.151142 -v -0.020950 0.126777 0.140083 -vn -0.375400 0.878981 -0.294054 -v -0.020950 0.126921 0.140655 -vn -0.680486 0.698555 0.221267 -v -0.019750 0.126878 0.138869 -vn -0.393069 0.908120 0.144275 -v -0.020950 0.126792 0.139222 -vn -0.374008 0.927425 -0.001005 -v -0.020950 0.126751 0.139766 -vn -0.680658 0.588716 0.436026 -v -0.019750 0.127290 0.138063 -vn -0.393202 0.815470 0.424737 -v -0.020950 0.127072 0.138409 -vn -0.373051 0.880547 0.292352 -v -0.020950 0.126878 0.138869 -vn -0.680656 0.415219 0.603573 -v -0.019750 0.127941 0.137434 -vn -0.385468 0.632565 0.671771 -v -0.020950 0.127590 0.137722 -vn -0.372560 0.743184 0.555766 -v -0.020950 0.127290 0.138063 -vn -0.680484 0.196751 0.705855 -v -0.019750 0.128761 0.137051 -vn -0.386239 0.387931 0.836857 -v -0.020950 0.128294 0.137228 -vn -0.340438 0.551238 0.761734 -v -0.020950 0.127941 0.137434 -vn -0.680134 -0.043159 0.731816 -v -0.019750 0.129662 0.136955 -vn -0.396408 0.116057 0.910710 -v -0.020950 0.129117 0.136977 -vn -0.347432 0.279380 0.895119 -v -0.020950 0.128761 0.137051 -vn -0.679607 -0.278678 0.678582 -v -0.019750 0.130544 0.137156 -vn -0.387548 -0.190752 0.901898 -v -0.020950 0.129978 0.136992 -vn -0.388765 -0.039227 0.920502 -v -0.020950 0.129662 0.136955 -vn -0.678900 -0.484407 0.551765 -v -0.019750 0.131314 0.137633 -vn -0.388090 -0.465627 0.795347 -v -0.020950 0.130791 0.137272 -vn -0.360371 -0.316062 0.877632 -v -0.020950 0.130544 0.137156 -vn -0.678010 -0.638091 0.364887 -v -0.019750 0.131887 0.138334 -vn -0.388562 -0.692751 0.607549 -v -0.020950 0.131478 0.137790 -vn -0.366270 -0.577833 0.729352 -v -0.020950 0.131314 0.137633 -vn -0.676928 -0.723003 0.137966 -v -0.019750 0.132201 0.139183 -vn -0.388970 -0.848959 0.357731 -v -0.020950 0.131972 0.138494 -vn -0.371755 -0.778411 0.505841 -v -0.020950 0.131887 0.138334 -vn -0.675656 -0.729756 -0.104620 -v -0.019750 0.132223 0.140088 -vn -0.397710 -0.913961 0.080633 -v -0.020950 0.132223 0.139317 -vn -0.376779 -0.897147 0.230576 -v -0.020950 0.132201 0.139183 -vn -0.674181 -0.657336 -0.336733 -v -0.019750 0.131949 0.140951 -vn -0.389592 -0.893838 -0.221972 -v -0.020950 0.132208 0.140178 -vn -0.395230 -0.915197 -0.078788 -v -0.020950 0.132223 0.140088 -vn -0.396852 -0.637617 -0.660268 -v -0.020950 0.131410 0.141678 -vn -0.389823 -0.777975 -0.492739 -v -0.020950 0.131928 0.140991 -vn -0.385335 -0.850567 -0.357845 -v -0.020950 0.131949 0.140951 -vn -0.916684 0.374753 -0.138744 -v -0.021250 0.139534 0.135985 -vn -0.916684 0.346807 -0.198533 -v -0.021250 0.138786 0.134384 -vn -0.934356 -0.356309 0.004726 -v -0.021250 0.132549 0.139622 -vn -0.976000 -0.151276 -0.156650 -v -0.021250 0.124457 0.145995 -vn -0.976002 -0.052680 -0.211291 -v -0.021250 0.123993 0.146252 -vn -0.911766 -0.242087 0.331779 -v -0.021250 0.123364 0.148466 -vn -0.976000 0.060025 -0.209334 -v -0.021250 0.123463 0.146243 -vn -0.930602 0.005094 0.365997 -v -0.021250 0.129422 0.136651 -vn -0.915900 -0.206171 -0.344415 -v -0.021250 0.123673 0.130726 -vn -0.976002 -0.156646 0.151272 -v -0.021250 0.124680 0.133233 -vn -0.933409 0.014960 -0.358502 -v -0.021250 0.129316 0.142744 -vn -0.976002 -0.211293 0.052681 -v -0.021250 0.124740 0.145009 -vn -0.976002 -0.209325 -0.060025 -v -0.021250 0.124731 0.145540 -vn -0.976002 0.209325 0.060025 -v -0.021250 0.122760 0.144975 -vn -0.916684 -0.346807 0.198534 -v -0.021250 0.120214 0.145016 -vn -0.976002 0.211295 -0.052680 -v -0.021250 0.122751 0.145505 -vn -0.916685 -0.309397 0.252908 -v -0.021250 0.121216 0.146472 -vn -0.976003 0.156642 -0.151267 -v -0.021250 0.123008 0.145969 -vn -0.976000 0.151276 0.156650 -v -0.021250 0.123033 0.144520 -vn -0.916684 -0.392479 0.075168 -v -0.021250 0.118991 0.141713 -vn -0.916684 -0.374754 0.138743 -v -0.021250 0.119466 0.143415 -vn -0.976002 -0.211292 0.052681 -v -0.021250 0.124937 0.133697 -vn -0.976002 -0.209328 -0.060023 -v -0.021250 0.124928 0.134228 -vn -0.930834 0.064044 0.359787 -v -0.021250 0.129076 0.136680 -vn -0.917897 -0.265985 0.294476 -v -0.021250 0.122443 0.147743 -vn -0.916687 -0.355886 -0.181743 -v -0.021250 0.119971 0.134834 -vn -0.916685 -0.380950 -0.120691 -v -0.021250 0.119300 0.136468 -vn -0.976002 0.052683 0.211293 -v -0.021250 0.123497 0.144263 -vn -0.916685 -0.395619 -0.056342 -v -0.021250 0.118907 0.138191 -vn -0.916686 -0.399495 0.009544 -v -0.021250 0.118803 0.139956 -vn -0.976003 -0.060021 0.209321 -v -0.021250 0.124028 0.144272 -vn -0.976002 -0.052682 -0.211294 -v -0.021250 0.124191 0.134940 -vn -0.976003 0.060022 -0.209320 -v -0.021250 0.123660 0.134931 -vn -0.932766 0.356717 -0.051969 -v -0.021250 0.126480 0.140124 -vn -0.933024 0.322414 -0.159736 -v -0.021250 0.126759 0.141037 -vn -0.933381 0.256419 -0.251095 -v -0.021250 0.127306 0.141819 -vn -0.976002 -0.156645 0.151272 -v -0.021250 0.124483 0.144545 -vn -0.933859 0.165620 -0.316981 -v -0.021250 0.128068 0.142393 -vn -0.930830 0.076192 -0.357421 -v -0.021250 0.128970 0.142704 -vn -0.932593 0.355667 0.061417 -v -0.021250 0.126496 0.139170 -vn -0.932491 0.319223 0.168986 -v -0.021250 0.126807 0.138268 -vn -0.976003 -0.151267 -0.156642 -v -0.021250 0.124655 0.134683 -vn -0.934777 0.242172 0.259893 -v -0.021250 0.127381 0.137506 -vn -0.935149 0.151818 0.320075 -v -0.021250 0.128163 0.136959 -vn -0.976002 0.156646 -0.151272 -v -0.021250 0.123205 0.134657 -vn -0.976002 0.211292 -0.052681 -v -0.021250 0.122948 0.134193 -vn -0.916687 -0.321118 -0.237842 -v -0.021250 0.120902 0.133331 -vn -0.976002 0.209328 0.060023 -v -0.021250 0.122957 0.133663 -vn -0.916686 -0.277592 -0.287455 -v -0.021250 0.122067 0.132003 -vn -0.976003 0.151266 0.156642 -v -0.021250 0.123231 0.133208 -vn -0.919652 -0.233914 -0.315474 -v -0.021250 0.123435 0.130885 -vn -0.976002 0.052682 0.211295 -v -0.021250 0.123695 0.132951 -vn -0.976003 -0.060022 0.209320 -v -0.021250 0.124225 0.132960 -vn -0.976003 0.151267 0.156643 -v -0.021250 0.134543 0.133405 -vn -0.976002 0.052682 0.211294 -v -0.021250 0.135007 0.133148 -vn -0.916685 0.151735 -0.369681 -v -0.021250 0.133563 0.129801 -vn -0.916688 0.309391 -0.252904 -v -0.021250 0.137784 0.132928 -vn -0.916681 0.263559 -0.300388 -v -0.021250 0.136557 0.131657 -vn -0.976003 -0.060021 0.209321 -v -0.021250 0.135537 0.133157 -vn -0.931355 -0.358168 0.065520 -v -0.021250 0.132520 0.139276 -vn -0.976001 0.060025 -0.209332 -v -0.021250 0.134972 0.135128 -vn -0.916683 0.210516 -0.339669 -v -0.021250 0.135137 0.130605 -vn -0.976002 -0.151267 -0.156645 -v -0.021250 0.135967 0.134880 -vn -0.976000 -0.052687 -0.211302 -v -0.021250 0.135503 0.135137 -vn -0.976002 0.211294 -0.052682 -v -0.021250 0.134260 0.134391 -vn -0.976003 0.209321 0.060021 -v -0.021250 0.134269 0.133860 -vn -0.917271 -0.166147 -0.361952 -v -0.021250 0.124969 0.130007 -vn -0.916685 -0.107322 -0.384928 -v -0.021250 0.126626 0.129393 -vn -0.976001 -0.156646 0.151277 -v -0.021250 0.135992 0.133431 -vn -0.976002 -0.211291 0.052680 -v -0.021250 0.136249 0.133895 -vn -0.976001 -0.209332 -0.060026 -v -0.021250 0.136240 0.134425 -vn -0.933541 -0.074590 0.350624 -v -0.021250 0.130030 0.136696 -vn -0.935068 -0.169549 0.311290 -v -0.021250 0.130932 0.137007 -vn -0.976002 0.156645 -0.151267 -v -0.021250 0.134517 0.134855 -vn -0.935159 -0.257036 0.243740 -v -0.021250 0.131694 0.137581 -vn -0.935334 -0.319164 0.152594 -v -0.021250 0.132241 0.138363 -vn -0.916686 0.088819 -0.389614 -v -0.021250 0.131878 0.129268 -vn -0.916686 0.023479 -0.398918 -v -0.021250 0.130129 0.129018 -vn -0.916683 -0.042500 -0.397349 -v -0.021250 0.128362 0.129061 -vn -0.932526 -0.360727 -0.016491 -v -0.021250 0.132544 0.139884 -vn -0.916687 0.355886 0.181744 -v -0.021250 0.139029 0.144566 -vn -0.916687 0.380945 0.120688 -v -0.021250 0.139700 0.142932 -vn -0.916683 0.395623 0.056343 -v -0.021250 0.140093 0.141209 -vn -0.916686 0.399495 -0.009543 -v -0.021250 0.140197 0.139444 -vn -0.916684 0.392480 -0.075169 -v -0.021250 0.140009 0.137687 -vn -0.936217 -0.155504 -0.315146 -v -0.021250 0.130837 0.142441 -vn -0.933457 -0.060414 -0.353566 -v -0.021250 0.129924 0.142720 -vn -0.976003 0.209321 0.060021 -v -0.021250 0.134072 0.145172 -vn -0.976002 0.211294 -0.052682 -v -0.021250 0.134063 0.145703 -vn -0.937081 -0.242515 -0.251130 -v -0.021250 0.131619 0.141894 -vn -0.976001 0.151277 0.156646 -v -0.021250 0.134345 0.144717 -vn -0.936468 -0.309336 -0.165346 -v -0.021250 0.132193 0.141132 -vn -0.976002 0.052680 0.211291 -v -0.021250 0.134809 0.144460 -vn -0.932373 -0.352396 -0.080606 -v -0.021250 0.132504 0.140230 -vn -0.976000 -0.060025 0.209334 -v -0.021250 0.135340 0.144469 -vn -0.976003 -0.156642 0.151265 -v -0.021250 0.135795 0.144743 -vn -0.976002 -0.211295 0.052681 -v -0.021250 0.136052 0.145207 -vn -0.916689 0.321113 0.237838 -v -0.021250 0.138098 0.146069 -vn -0.976003 -0.209321 -0.060021 -v -0.021250 0.136043 0.145737 -vn -0.916683 0.277594 0.287459 -v -0.021250 0.136933 0.147397 -vn -0.976003 -0.151267 -0.156643 -v -0.021250 0.135769 0.146192 -vn -0.916688 0.226491 0.329220 -v -0.021250 0.135565 0.148515 -vn -0.976002 -0.052682 -0.211294 -v -0.021250 0.135305 0.146449 -vn -0.916685 0.169215 0.362016 -v -0.021250 0.134031 0.149393 -vn -0.976003 0.060021 -0.209321 -v -0.021250 0.134775 0.146440 -vn -0.916686 0.107321 0.384928 -v -0.021250 0.132374 0.150007 -vn -0.976003 0.156643 -0.151267 -v -0.021250 0.134320 0.146167 -vn -0.919044 -0.198158 0.340722 -v -0.021250 0.123863 0.148795 -vn -0.916685 -0.151738 0.369681 -v -0.021250 0.125437 0.149599 -vn -0.916685 -0.088818 0.389615 -v -0.021250 0.127122 0.150132 -vn -0.916681 -0.023481 0.398929 -v -0.021250 0.128871 0.150382 -vn -0.916689 0.042502 0.397335 -v -0.021250 0.130638 0.150339 -vn 0.375745 0.643756 0.666629 -v -0.017050 0.137141 0.147613 -vn -0.375752 0.525252 0.763493 -v -0.020950 0.135735 0.148763 -vn 0.375752 0.525250 0.763494 -v -0.017050 0.135735 0.148763 -vn -0.375747 0.392422 0.839535 -v -0.020950 0.134158 0.149665 -vn 0.375747 0.392422 0.839535 -v -0.017050 0.134158 0.149665 -vn -0.375749 0.248887 0.892675 -v -0.020950 0.132454 0.150296 -vn 0.375748 0.248888 0.892675 -v -0.017050 0.132454 0.150296 -vn -0.375753 0.098564 0.921463 -v -0.020950 0.130670 0.150638 -vn 0.375754 0.098561 0.921463 -v -0.017050 0.130670 0.150638 -vn -0.375740 -0.054451 0.925124 -v -0.020950 0.128854 0.150681 -vn 0.375740 -0.054449 0.925124 -v -0.017050 0.128854 0.150681 -vn -0.375748 -0.205975 0.903542 -v -0.020950 0.127055 0.150425 -vn 0.375747 -0.205976 0.903542 -v -0.017050 0.127055 0.150425 -vn -0.375748 -0.351886 0.857315 -v -0.020950 0.125323 0.149876 -vn 0.375747 -0.351885 0.857316 -v -0.017050 0.125323 0.149876 -vn -0.370885 -0.484071 0.792540 -v -0.020950 0.123705 0.149050 -vn 0.375753 -0.488197 0.787702 -v -0.017050 0.123705 0.149050 -vn -0.373007 -0.614879 0.694831 -v -0.020950 0.122245 0.147969 -vn 0.375742 -0.611192 0.696608 -v -0.017050 0.122245 0.147969 -vn -0.375746 -0.717512 0.586508 -v -0.020950 0.120983 0.146662 -vn 0.375746 -0.717513 0.586507 -v -0.017050 0.120983 0.146662 -vn -0.375745 -0.804263 0.460410 -v -0.020950 0.119954 0.145165 -vn 0.372879 -0.804237 0.462779 -v -0.017050 0.119954 0.145165 -vn -0.375745 -0.869074 0.321753 -v -0.020950 0.119184 0.143519 -vn 0.375745 -0.869074 0.321753 -v -0.017050 0.119184 0.143519 -vn -0.375745 -0.910180 0.174319 -v -0.020950 0.118696 0.141769 -vn 0.375745 -0.910180 0.174320 -v -0.017050 0.118696 0.141769 -vn -0.375749 -0.926457 0.022132 -v -0.020950 0.118503 0.139963 -vn 0.375749 -0.926457 0.022132 -v -0.017050 0.118503 0.139963 -vn -0.375747 -0.917465 -0.130660 -v -0.020950 0.118610 0.138149 -vn 0.375747 -0.917465 -0.130660 -v -0.017050 0.118610 0.138149 -vn -0.375747 -0.883446 -0.279887 -v -0.020950 0.119014 0.136378 -vn 0.375747 -0.883447 -0.279887 -v -0.017050 0.119014 0.136378 -vn -0.375751 -0.825329 -0.421478 -v -0.020950 0.119704 0.134697 -vn 0.375751 -0.825329 -0.421478 -v -0.017050 0.119704 0.134697 -vn -0.375751 -0.744698 -0.551577 -v -0.020950 0.120661 0.133153 -vn 0.375751 -0.744697 -0.551577 -v -0.017050 0.120661 0.133153 -vn -0.375748 -0.643754 -0.666629 -v -0.020950 0.121859 0.131787 -vn 0.375748 -0.643754 -0.666629 -v -0.017050 0.121859 0.131787 -vn -0.371085 -0.530224 -0.762337 -v -0.020950 0.123265 0.130637 -vn 0.375744 -0.525255 -0.763495 -v -0.017050 0.123265 0.130637 -vn -0.374428 -0.390855 -0.840855 -v -0.020950 0.124842 0.129735 -vn 0.375751 -0.392422 -0.839533 -v -0.017050 0.124842 0.129735 -vn -0.375747 -0.248886 -0.892675 -v -0.020950 0.126546 0.129104 -vn 0.375748 -0.248886 -0.892675 -v -0.017050 0.126546 0.129104 -vn -0.375743 -0.098561 -0.921468 -v -0.020950 0.128330 0.128762 -vn 0.375743 -0.098563 -0.921468 -v -0.017050 0.128330 0.128762 -vn -0.375749 0.054450 -0.925120 -v -0.020950 0.130146 0.128719 -vn 0.375749 0.054451 -0.925121 -v -0.017050 0.130146 0.128719 -vn -0.375748 0.205979 -0.903541 -v -0.020950 0.131945 0.128975 -vn 0.375748 0.205978 -0.903541 -v -0.017050 0.131945 0.128975 -vn -0.375747 0.351884 -0.857316 -v -0.020950 0.133677 0.129524 -vn 0.375748 0.351885 -0.857316 -v -0.017050 0.133677 0.129524 -vn -0.375743 0.488198 -0.787705 -v -0.020950 0.135295 0.130350 -vn 0.375743 0.488198 -0.787705 -v -0.017050 0.135295 0.130350 -vn -0.375739 0.611193 -0.696608 -v -0.020950 0.136755 0.131431 -vn 0.375739 0.611192 -0.696610 -v -0.017050 0.136755 0.131431 -vn -0.375753 0.717509 -0.586507 -v -0.020950 0.138017 0.132738 -vn 0.375752 0.717511 -0.586505 -v -0.017050 0.138017 0.132738 -vn -0.375745 0.804264 -0.460409 -v -0.020950 0.139046 0.134235 -vn 0.375745 0.804263 -0.460409 -v -0.017050 0.139046 0.134235 -vn -0.375745 0.869074 -0.321755 -v -0.020950 0.139816 0.135881 -vn 0.375745 0.869074 -0.321755 -v -0.017050 0.139816 0.135881 -vn -0.375745 0.910180 -0.174321 -v -0.020950 0.140304 0.137631 -vn 0.375745 0.910180 -0.174322 -v -0.017050 0.140304 0.137631 -vn -0.375748 0.926458 -0.022131 -v -0.020950 0.140497 0.139437 -vn 0.375749 0.926457 -0.022130 -v -0.017050 0.140497 0.139437 -vn -0.375744 0.917466 0.130662 -v -0.020950 0.140390 0.141251 -vn 0.375744 0.917466 0.130660 -v -0.017050 0.140390 0.141251 -vn -0.375752 0.883445 0.279884 -v -0.020950 0.139986 0.143022 -vn 0.375751 0.883445 0.279885 -v -0.017050 0.139986 0.143022 -vn -0.375752 0.825328 0.421480 -v -0.020950 0.139296 0.144703 -vn 0.371561 0.828953 0.418066 -v -0.017050 0.139296 0.144703 -vn -0.375755 0.744696 0.551575 -v -0.020950 0.138339 0.146247 -vn 0.375756 0.744695 0.551576 -v -0.017050 0.138339 0.146247 -vn -0.375745 0.643755 0.666630 -v -0.020950 0.137141 0.147613 -vn 0.976003 0.156641 -0.151265 -v -0.016750 0.134320 0.146167 -vn 0.976004 0.060019 -0.209318 -v -0.016750 0.134775 0.146440 -vn 0.916684 0.169216 0.362016 -v -0.016750 0.134031 0.149393 -vn 0.916688 0.226488 0.329221 -v -0.016750 0.135565 0.148515 -vn 0.976003 -0.052681 -0.211291 -v -0.016750 0.135305 0.146449 -vn 0.916683 0.277597 0.287458 -v -0.016750 0.136933 0.147397 -vn 0.976003 -0.151265 -0.156641 -v -0.016750 0.135769 0.146192 -vn 0.916691 0.320524 0.238625 -v -0.016750 0.138098 0.146069 -vn 0.976004 -0.209318 -0.060020 -v -0.016750 0.136043 0.145737 -vn 0.899803 0.365676 0.237983 -v -0.016750 0.138673 0.145209 -vn 0.976002 -0.211292 0.052680 -v -0.016750 0.136052 0.145207 -vn 0.976004 -0.156639 0.151264 -v -0.016750 0.135795 0.144743 -vn 0.976001 -0.060026 0.209331 -v -0.016750 0.135340 0.144469 -vn 0.722335 0.683398 0.105823 -v -0.016750 0.133958 0.140312 -vn 0.976003 0.052681 0.211288 -v -0.016750 0.134809 0.144460 -vn 0.728540 0.651016 0.213093 -v -0.016750 0.133799 0.141031 -vn 0.976004 0.209320 0.060019 -v -0.016750 0.134072 0.145172 -vn 0.731173 -0.160410 0.663065 -v -0.016750 0.128442 0.144074 -vn 0.731174 0.009528 0.682125 -v -0.016750 0.129563 0.144200 -vn 0.916686 0.107322 0.384928 -v -0.016750 0.132374 0.150007 -vn 0.916688 0.042499 0.397337 -v -0.016750 0.130638 0.150339 -vn 0.916681 -0.023478 0.398930 -v -0.016750 0.128871 0.150382 -vn 0.976003 0.211291 -0.052681 -v -0.016750 0.134063 0.145703 -vn 0.976003 -0.209323 -0.060024 -v -0.016750 0.124731 0.145540 -vn 0.976003 -0.211290 0.052681 -v -0.016750 0.124740 0.145009 -vn 0.731170 0.178865 0.658329 -v -0.016750 0.130680 0.144043 -vn 0.731173 0.336962 0.593163 -v -0.016750 0.131723 0.143613 -vn 0.976001 0.151273 0.156646 -v -0.016750 0.134345 0.144717 -vn 0.731174 0.473891 0.490727 -v -0.016750 0.132626 0.142937 -vn 0.731174 0.581042 0.357456 -v -0.016750 0.133333 0.142058 -vn 0.719459 -0.686828 0.103183 -v -0.016750 0.125025 0.140171 -vn 0.730066 -0.645647 0.223929 -v -0.016750 0.125240 0.141150 -vn 0.976004 -0.060019 0.209319 -v -0.016750 0.124028 0.144272 -vn 0.731171 -0.570834 0.373548 -v -0.016750 0.125735 0.142164 -vn 0.976002 -0.156644 0.151269 -v -0.016750 0.124483 0.144545 -vn 0.731169 -0.460009 0.503770 -v -0.016750 0.126466 0.143023 -vn 0.731175 -0.320271 0.602337 -v -0.016750 0.127387 0.143673 -vn 0.976003 0.052683 0.211289 -v -0.016750 0.123497 0.144263 -vn 0.976001 0.151273 0.156648 -v -0.016750 0.123033 0.144520 -vn 0.917636 -0.355737 0.177186 -v -0.016750 0.120143 0.144890 -vn 0.976003 0.209323 0.060024 -v -0.016750 0.122760 0.144975 -vn 0.976001 -0.151273 -0.156648 -v -0.016750 0.124457 0.145995 -vn 0.916685 -0.088819 0.389614 -v -0.016750 0.127122 0.150132 -vn 0.976003 -0.052681 -0.211288 -v -0.016750 0.123993 0.146252 -vn 0.916682 -0.263554 0.300388 -v -0.016750 0.122443 0.147743 -vn 0.916685 -0.309397 0.252907 -v -0.016750 0.121216 0.146472 -vn 0.976002 0.211294 -0.052679 -v -0.016750 0.122751 0.145505 -vn 0.919930 -0.332469 0.207830 -v -0.016750 0.120214 0.145016 -vn 0.976003 0.156639 -0.151267 -v -0.016750 0.123008 0.145969 -vn 0.976001 0.060026 -0.209331 -v -0.016750 0.123463 0.146243 -vn 0.916688 -0.210512 0.339659 -v -0.016750 0.123863 0.148795 -vn 0.916685 -0.151736 0.369682 -v -0.016750 0.125437 0.149599 -vn 0.976002 -0.209325 -0.060023 -v -0.016750 0.124928 0.134228 -vn 0.976003 -0.211290 0.052681 -v -0.016750 0.124937 0.133697 -vn 0.731173 -0.094944 -0.675553 -v -0.016750 0.128874 0.135244 -vn 0.731173 0.076043 -0.677940 -v -0.016750 0.130002 0.135228 -vn 0.976002 -0.156645 0.151269 -v -0.016750 0.124680 0.133233 -vn 0.916687 -0.169213 -0.362010 -v -0.016750 0.124969 0.130007 -vn 0.976004 -0.060020 0.209318 -v -0.016750 0.124225 0.132960 -vn 0.916683 -0.226496 -0.329228 -v -0.016750 0.123435 0.130885 -vn 0.976002 0.052680 0.211293 -v -0.016750 0.123695 0.132951 -vn 0.916685 -0.277592 -0.287455 -v -0.016750 0.122067 0.132003 -vn 0.976003 0.151265 0.156640 -v -0.016750 0.123231 0.133208 -vn 0.916687 -0.321118 -0.237843 -v -0.016750 0.120902 0.133331 -vn 0.976002 0.209325 0.060023 -v -0.016750 0.122957 0.133663 -vn 0.916687 -0.355885 -0.181743 -v -0.016750 0.119971 0.134834 -vn 0.976003 0.211290 -0.052681 -v -0.016750 0.122948 0.134193 -vn 0.916685 -0.380950 -0.120690 -v -0.016750 0.119300 0.136468 -vn 0.976002 0.156645 -0.151269 -v -0.016750 0.123205 0.134657 -vn 0.916685 -0.395619 -0.056342 -v -0.016750 0.118907 0.138191 -vn 0.720501 -0.693206 0.018543 -v -0.016750 0.125013 0.140045 -vn 0.731173 -0.671829 -0.118462 -v -0.016750 0.125068 0.138919 -vn 0.916686 -0.399494 0.009543 -v -0.016750 0.118803 0.139956 -vn 0.976004 0.060020 -0.209318 -v -0.016750 0.123660 0.134931 -vn 0.916684 -0.392479 0.075168 -v -0.016750 0.118991 0.141713 -vn 0.731172 -0.259968 -0.630717 -v -0.016750 0.127785 0.135540 -vn 0.731170 -0.408651 -0.546255 -v -0.016750 0.126804 0.136097 -vn 0.976003 -0.151266 -0.156640 -v -0.016750 0.124655 0.134683 -vn 0.731173 -0.531658 -0.427465 -v -0.016750 0.125993 0.136880 -vn 0.976003 -0.052681 -0.211291 -v -0.016750 0.124191 0.134940 -vn 0.731170 -0.621263 -0.281819 -v -0.016750 0.125402 0.137841 -vn 0.916684 -0.374821 0.138563 -v -0.016750 0.119466 0.143415 -vn 0.916685 -0.107322 -0.384929 -v -0.016750 0.126626 0.129393 -vn 0.916683 -0.042502 -0.397348 -v -0.016750 0.128362 0.129061 -vn 0.916686 0.023480 -0.398918 -v -0.016750 0.130129 0.129018 -vn 0.916686 0.088819 -0.389614 -v -0.016750 0.131878 0.129268 -vn 0.916685 0.151736 -0.369681 -v -0.016750 0.133563 0.129801 -vn 0.976003 -0.151268 -0.156642 -v -0.016750 0.135967 0.134880 -vn 0.976001 -0.209328 -0.060028 -v -0.016750 0.136240 0.134425 -vn 0.916684 0.374753 -0.138744 -v -0.016750 0.139534 0.135985 -vn 0.916681 0.263556 -0.300390 -v -0.016750 0.136557 0.131657 -vn 0.916688 0.309393 -0.252901 -v -0.016750 0.137784 0.132928 -vn 0.976003 -0.211288 0.052681 -v -0.016750 0.136249 0.133895 -vn 0.731173 0.242253 -0.637730 -v -0.016750 0.131098 0.135493 -vn 0.976003 0.211291 -0.052681 -v -0.016750 0.134260 0.134391 -vn 0.916688 0.380944 0.120689 -v -0.016750 0.139700 0.142932 -vn 0.918772 0.355943 0.170773 -v -0.016750 0.139029 0.144566 -vn 0.976000 -0.052684 -0.211302 -v -0.016750 0.135503 0.135137 -vn 0.916684 0.346807 -0.198535 -v -0.016750 0.138786 0.134384 -vn 0.724822 0.688854 0.010661 -v -0.016750 0.133995 0.139920 -vn 0.731173 0.668259 -0.137171 -v -0.016750 0.133908 0.138795 -vn 0.976001 -0.156646 0.151273 -v -0.016750 0.135992 0.133431 -vn 0.976004 -0.060019 0.209320 -v -0.016750 0.135537 0.133157 -vn 0.916683 0.210517 -0.339669 -v -0.016750 0.135137 0.130605 -vn 0.976003 0.052681 0.211291 -v -0.016750 0.135007 0.133148 -vn 0.976003 0.151265 0.156641 -v -0.016750 0.134543 0.133405 -vn 0.976004 0.209318 0.060020 -v -0.016750 0.134269 0.133860 -vn 0.976002 0.060024 -0.209327 -v -0.016750 0.134972 0.135128 -vn 0.731175 0.613147 -0.299054 -v -0.016750 0.133545 0.137727 -vn 0.976003 0.156641 -0.151265 -v -0.016750 0.134517 0.134855 -vn 0.731172 0.519514 -0.442146 -v -0.016750 0.132927 0.136783 -vn 0.731170 0.393239 -0.557452 -v -0.016750 0.132094 0.136023 -vn 0.916684 0.392479 -0.075169 -v -0.016750 0.140009 0.137687 -vn 0.916686 0.399495 -0.009542 -v -0.016750 0.140197 0.139444 -vn 0.916683 0.395623 0.056341 -v -0.016750 0.140093 0.141209 -vn 0.375770 0.722222 0.580683 -v -0.014850 0.133007 0.142520 -vn 0.411992 0.782166 0.467417 -v -0.014850 0.133333 0.142058 -vn 0.381718 0.838230 0.389437 -v -0.014850 0.133598 0.141559 -vn 0.410695 0.874746 0.257193 -v -0.014850 0.133799 0.141031 -vn 0.381695 0.908513 0.170037 -v -0.014850 0.133932 0.140481 -vn 0.411985 0.910600 0.032798 -v -0.014850 0.133995 0.139920 -vn 0.381728 0.922156 -0.062544 -v -0.014850 0.133987 0.139355 -vn 0.411994 0.890142 -0.194698 -v -0.014850 0.133908 0.138795 -vn 0.381721 0.877634 -0.289908 -v -0.014850 0.133760 0.138250 -vn 0.390743 0.827339 -0.403523 -v -0.014850 0.133545 0.137727 -vn 0.375768 0.775437 -0.507441 -v -0.014850 0.133265 0.137236 -vn 0.390741 0.700999 -0.596592 -v -0.014850 0.132927 0.136783 -vn 0.375763 0.624882 -0.684343 -v -0.014850 0.132534 0.136377 -vn 0.411980 0.515613 -0.751276 -v -0.014850 0.132094 0.136023 -vn 0.381718 0.441311 -0.812118 -v -0.014850 0.131613 0.135727 -vn 0.411989 0.312577 -0.855898 -v -0.014850 0.131098 0.135493 -vn 0.381724 0.225478 -0.896352 -v -0.014850 0.130558 0.135326 -vn 0.411992 0.089903 -0.906741 -v -0.014850 0.130002 0.135228 -vn 0.381729 -0.004523 -0.924263 -v -0.014850 0.129437 0.135200 -vn 0.411993 -0.138413 -0.900613 -v -0.014850 0.128874 0.135244 -vn 0.381722 -0.234240 -0.894103 -v -0.014850 0.128320 0.135357 -vn 0.411985 -0.358046 -0.837897 -v -0.014850 0.127785 0.135540 -vn 0.381724 -0.449238 -0.807758 -v -0.014850 0.127277 0.135787 -vn 0.390740 -0.551400 -0.737075 -v -0.014850 0.126804 0.136097 -vn 0.375763 -0.643747 -0.666627 -v -0.014850 0.126374 0.136463 -vn 0.411983 -0.717416 -0.561768 -v -0.014850 0.125993 0.136880 -vn 0.381717 -0.782810 -0.491427 -v -0.014850 0.125667 0.137342 -vn 0.390741 -0.838284 -0.380264 -v -0.014850 0.125402 0.137841 -vn 0.375773 -0.885267 -0.274039 -v -0.014850 0.125201 0.138369 -vn 0.390743 -0.906516 -0.159837 -v -0.014850 0.125068 0.138919 -vn 0.375763 -0.925610 -0.045272 -v -0.014850 0.125005 0.139480 -vn 0.412695 -0.907262 0.080985 -v -0.014850 0.125013 0.140045 -vn 0.382862 -0.906472 0.178116 -v -0.014850 0.125092 0.140605 -vn 0.411992 -0.858725 0.304721 -v -0.014850 0.125240 0.141150 -vn 0.381720 -0.834374 0.397630 -v -0.014850 0.125455 0.141673 -vn 0.411979 -0.755969 0.508708 -v -0.014850 0.125735 0.142164 -vn 0.381720 -0.709273 0.592640 -v -0.014850 0.126073 0.142617 -vn 0.411977 -0.605714 0.680724 -v -0.014850 0.126466 0.143023 -vn 0.381717 -0.539622 0.750400 -v -0.014850 0.126906 0.143377 -vn 0.411989 -0.417382 0.809974 -v -0.014850 0.127387 0.143673 -vn 0.381723 -0.336038 0.861026 -v -0.014850 0.127902 0.143907 -vn 0.390742 -0.216446 0.894691 -v -0.014850 0.128442 0.144074 -vn 0.375767 -0.103299 0.920939 -v -0.014850 0.128998 0.144172 -vn 0.411991 0.024451 0.910860 -v -0.014850 0.129563 0.144200 -vn 0.381728 0.120336 0.916408 -v -0.014850 0.130126 0.144156 -vn 0.411988 0.250199 0.876166 -v -0.014850 0.130680 0.144043 -vn 0.381727 0.344443 0.857697 -v -0.014850 0.131215 0.143860 -vn 0.390748 0.454673 0.800368 -v -0.014850 0.131723 0.143613 -vn 0.375771 0.555122 0.742048 -v -0.014850 0.132196 0.143303 -vn 0.377387 0.643296 0.666145 -v -0.014850 0.132626 0.142937 -vn 0.917910 0.313916 0.242690 -v -0.014550 0.132773 0.142332 -vn 0.746099 -0.462528 -0.478962 -v -0.014550 0.131410 0.141678 -vn 0.746100 -0.592985 -0.302826 -v -0.014550 0.131949 0.140951 -vn 0.746098 -0.577849 0.330798 -v -0.014550 0.131887 0.138334 -vn 0.915382 0.383616 -0.122124 -v -0.014550 0.133476 0.138346 -vn 0.746099 -0.653949 0.125248 -v -0.014550 0.132201 0.139183 -vn 0.915181 0.402247 -0.025318 -v -0.014550 0.133688 0.139378 -vn 0.746099 -0.659185 -0.093875 -v -0.014550 0.132223 0.140088 -vn 0.915178 0.395912 0.075512 -v -0.014550 0.133636 0.140429 -vn 0.915173 0.364704 0.171609 -v -0.014550 0.133325 0.141435 -vn 0.746098 -0.039124 0.664685 -v -0.014550 0.129662 0.136955 -vn 0.915177 0.100226 -0.390392 -v -0.014550 0.130488 0.135618 -vn 0.746098 -0.252824 0.615969 -v -0.014550 0.130544 0.137156 -vn 0.915175 0.194166 -0.353204 -v -0.014550 0.131472 0.135992 -vn 0.746100 -0.439129 0.500501 -v -0.014550 0.131314 0.137633 -vn 0.917661 0.266172 -0.295043 -v -0.014550 0.132332 0.136598 -vn 0.917884 0.332067 -0.217301 -v -0.014550 0.133014 0.137400 -vn 0.746099 0.535056 0.396296 -v -0.014550 0.127290 0.138063 -vn 0.917661 -0.277746 -0.284175 -v -0.014550 0.126582 0.136679 -vn 0.746100 0.377385 0.548558 -v -0.014550 0.127941 0.137434 -vn 0.915385 -0.191846 -0.353928 -v -0.014550 0.127425 0.136048 -vn 0.746099 0.178818 0.641374 -v -0.014550 0.128761 0.137051 -vn 0.915175 -0.100243 -0.390391 -v -0.014550 0.128399 0.135647 -vn 0.915180 -0.000009 -0.403046 -v -0.014550 0.129441 0.135500 -vn 0.918430 0.274798 0.284557 -v -0.014550 0.132418 0.142721 -vn 0.918144 0.233197 0.320361 -v -0.014550 0.132016 0.143063 -vn 0.746099 -0.281949 -0.603193 -v -0.014550 0.130664 0.142191 -vn 0.915387 0.145969 0.375179 -v -0.014550 0.131100 0.143583 -vn 0.746100 -0.070813 -0.662058 -v -0.014550 0.129792 0.142434 -vn 0.915179 0.050526 0.399868 -v -0.014550 0.130085 0.143859 -vn 0.746098 0.147994 -0.649181 -v -0.014550 0.128889 0.142381 -vn 0.746097 0.624417 -0.231175 -v -0.014550 0.126921 0.140655 -vn 0.915181 -0.395903 0.075533 -v -0.014550 0.125386 0.140545 -vn 0.746101 0.665643 -0.015901 -v -0.014550 0.126751 0.139766 -vn 0.917662 -0.396998 -0.017022 -v -0.014550 0.125305 0.139495 -vn 0.746097 0.634744 0.201097 -v -0.014550 0.126878 0.138869 -vn 0.917886 -0.379097 -0.117350 -v -0.014550 0.125488 0.138458 -vn 0.915381 -0.338629 -0.217732 -v -0.014550 0.125923 0.137499 -vn 0.917663 -0.041915 0.395142 -v -0.014550 0.129032 0.143874 -vn 0.915384 -0.150420 0.373424 -v -0.014550 0.128009 0.143626 -vn 0.746098 0.350759 -0.565955 -v -0.014550 0.128051 0.142037 -vn 0.915176 -0.236903 0.326083 -v -0.014550 0.127079 0.143132 -vn 0.746100 0.515520 -0.421395 -v -0.014550 0.127371 0.141440 -vn 0.915177 -0.310550 0.256925 -v -0.014550 0.126302 0.142422 -vn 0.915175 -0.364694 0.171622 -v -0.014550 0.125725 0.141541 -vn 0.671869 -0.514512 -0.532794 -v -0.018250 0.131410 0.141678 -vn 0.671869 -0.313638 -0.670987 -v -0.018250 0.130664 0.142191 -vn 0.671868 -0.078772 -0.736471 -v -0.018250 0.129792 0.142434 -vn 0.671870 0.164626 -0.722142 -v -0.018250 0.128889 0.142381 -vn 0.671869 0.390182 -0.629564 -v -0.018250 0.128051 0.142037 -vn 0.671867 0.573463 -0.468759 -v -0.018250 0.127371 0.141440 -vn 0.671870 0.694595 -0.257156 -v -0.018250 0.126921 0.140655 -vn 0.671867 0.740461 -0.017688 -v -0.018250 0.126751 0.139766 -vn 0.671870 0.706081 0.223697 -v -0.018250 0.126878 0.138869 -vn 0.671868 0.595194 0.440837 -v -0.018250 0.127290 0.138063 -vn 0.671868 0.419801 0.610214 -v -0.018250 0.127941 0.137434 -vn 0.671869 0.198916 0.713460 -v -0.018250 0.128761 0.137051 -vn 0.671869 -0.043521 0.739390 -v -0.018250 0.129662 0.136955 -vn 0.671869 -0.281239 0.685198 -v -0.018250 0.130544 0.137156 -vn 0.671868 -0.488485 0.556755 -v -0.018250 0.131314 0.137633 -vn 0.671869 -0.642795 0.367977 -v -0.018250 0.131887 0.138334 -vn 0.671869 -0.727449 0.139325 -v -0.018250 0.132201 0.139183 -vn 0.671869 -0.733272 -0.104426 -v -0.018250 0.132223 0.140088 -vn 0.671868 -0.659634 -0.336863 -v -0.018250 0.131949 0.140951 -vn 0.765145 -0.635241 0.104990 -v -0.018250 0.130733 0.139496 -vn 0.765148 -0.611265 -0.202247 -v -0.018250 0.130687 0.140093 -vn 0.765146 -0.447257 -0.463155 -v -0.018250 0.130368 0.140599 -vn 0.765143 -0.180795 -0.617956 -v -0.018250 0.129851 0.140900 -vn 0.765146 0.323424 0.556730 -v -0.018250 0.128872 0.138619 -vn 0.765144 0.027657 0.643265 -v -0.018250 0.129446 0.138451 -vn 0.765148 -0.274450 0.582431 -v -0.018250 0.130033 0.138569 -vn 0.765145 -0.513688 0.388171 -v -0.018250 0.130497 0.138946 -vn 0.765146 0.641906 0.050085 -v -0.018250 0.128254 0.139603 -vn 0.765146 0.545104 0.342657 -v -0.018250 0.128442 0.139035 -vn 0.765145 0.405866 -0.499825 -v -0.018250 0.128712 0.140670 -vn 0.765145 0.591656 -0.253960 -v -0.018250 0.128351 0.140193 -vn 0.765148 0.127091 -0.631186 -v -0.018250 0.129253 0.140925 -vn -0.765146 -0.447257 -0.463155 -v -0.019750 0.130368 0.140599 -vn -0.765143 -0.180795 -0.617956 -v -0.019750 0.129851 0.140900 -vn -0.765148 0.127091 -0.631186 -v -0.019750 0.129253 0.140925 -vn -0.765145 0.405866 -0.499825 -v -0.019750 0.128712 0.140670 -vn -0.765145 0.591656 -0.253960 -v -0.019750 0.128351 0.140193 -vn -0.765146 0.641906 0.050085 -v -0.019750 0.128254 0.139603 -vn -0.765146 0.545104 0.342657 -v -0.019750 0.128442 0.139035 -vn -0.765146 0.323424 0.556730 -v -0.019750 0.128872 0.138619 -vn -0.765144 0.027657 0.643265 -v -0.019750 0.129446 0.138451 -vn -0.765148 -0.274450 0.582431 -v -0.019750 0.130033 0.138569 -vn -0.765145 -0.513688 0.388171 -v -0.019750 0.130497 0.138946 -vn -0.765145 -0.635241 0.104990 -v -0.019750 0.130733 0.139496 -vn -0.765148 -0.611265 -0.202247 -v -0.019750 0.130687 0.140093 -vn 0.539401 -0.203709 -0.817037 -v -0.016880 0.135251 0.146231 -vn 0.539405 0.232097 -0.809428 -v -0.016880 0.134837 0.146224 -vn 0.539404 0.605717 -0.584936 -v -0.016880 0.134482 0.146010 -vn 0.539401 0.817037 -0.203709 -v -0.016880 0.134281 0.145648 -vn 0.539403 0.809431 0.232089 -v -0.016880 0.134288 0.145234 -vn 0.539397 0.584941 0.605718 -v -0.016880 0.134502 0.144879 -vn 0.539399 0.203712 0.817037 -v -0.016880 0.134864 0.144678 -vn 0.539393 -0.232102 0.809434 -v -0.016880 0.135278 0.144686 -vn 0.539404 -0.605721 0.584933 -v -0.016880 0.135633 0.144899 -vn 0.539399 -0.817040 0.203702 -v -0.016880 0.135833 0.145261 -vn 0.539405 -0.809428 -0.232097 -v -0.016880 0.135826 0.145675 -vn 0.539404 -0.584936 -0.605717 -v -0.016880 0.135613 0.146030 -vn -0.539393 0.584947 0.605716 -v -0.021120 0.134502 0.144879 -vn -0.539399 0.809432 0.232095 -v -0.021120 0.134288 0.145234 -vn -0.539398 0.817038 -0.203711 -v -0.021120 0.134281 0.145648 -vn -0.539400 0.605719 -0.584937 -v -0.021120 0.134482 0.146010 -vn -0.539402 0.232100 -0.809429 -v -0.021120 0.134837 0.146224 -vn -0.539398 -0.203711 -0.817038 -v -0.021120 0.135251 0.146231 -vn -0.539400 -0.584937 -0.605719 -v -0.021120 0.135613 0.146030 -vn -0.539402 -0.809429 -0.232100 -v -0.021120 0.135826 0.145675 -vn -0.539397 -0.817041 0.203704 -v -0.021120 0.135833 0.145261 -vn -0.539402 -0.605723 0.584931 -v -0.021120 0.135633 0.144899 -vn -0.539390 -0.232098 0.809437 -v -0.021120 0.135278 0.144686 -vn -0.539396 0.203708 0.817040 -v -0.021120 0.134864 0.144678 -vn 0.539392 -0.203718 -0.817040 -v -0.016880 0.135448 0.134919 -vn 0.539394 0.232111 -0.809431 -v -0.016880 0.135034 0.134912 -vn 0.539399 0.605726 -0.584931 -v -0.016880 0.134679 0.134698 -vn 0.539401 0.817037 -0.203709 -v -0.016880 0.134478 0.134336 -vn 0.539405 0.809428 0.232097 -v -0.016880 0.134486 0.133922 -vn 0.539404 0.584936 0.605717 -v -0.016880 0.134699 0.133567 -vn 0.539401 0.203709 0.817037 -v -0.016880 0.135061 0.133366 -vn 0.539403 -0.232089 0.809431 -v -0.016880 0.135475 0.133374 -vn 0.539397 -0.605718 0.584941 -v -0.016880 0.135830 0.133587 -vn 0.539399 -0.817037 0.203712 -v -0.016880 0.136031 0.133949 -vn 0.539396 -0.809429 -0.232115 -v -0.016880 0.136024 0.134363 -vn 0.539397 -0.584942 -0.605718 -v -0.016880 0.135810 0.134718 -vn -0.539400 0.584937 0.605719 -v -0.021120 0.134699 0.133567 -vn -0.539402 0.809429 0.232100 -v -0.021120 0.134486 0.133922 -vn -0.539398 0.817038 -0.203711 -v -0.021120 0.134478 0.134336 -vn -0.539398 0.605730 -0.584929 -v -0.021120 0.134679 0.134698 -vn -0.539393 0.232110 -0.809432 -v -0.021120 0.135034 0.134912 -vn -0.539387 -0.203726 -0.817042 -v -0.021120 0.135448 0.134919 -vn -0.539393 -0.584938 -0.605725 -v -0.021120 0.135810 0.134718 -vn -0.539393 -0.809432 -0.232110 -v -0.021120 0.136024 0.134363 -vn -0.539396 -0.817040 0.203708 -v -0.021120 0.136031 0.133949 -vn -0.539393 -0.605716 0.584947 -v -0.021120 0.135830 0.133587 -vn -0.539399 -0.232095 0.809432 -v -0.021120 0.135475 0.133374 -vn -0.539398 0.203711 0.817038 -v -0.021120 0.135061 0.133366 -vn 0.539401 -0.203709 -0.817037 -v -0.016880 0.124136 0.134722 -vn 0.539405 0.232097 -0.809428 -v -0.016880 0.123722 0.134714 -vn 0.539400 0.605721 -0.584936 -v -0.016880 0.123367 0.134501 -vn 0.539400 0.817037 -0.203710 -v -0.016880 0.123166 0.134139 -vn 0.539399 0.809431 0.232099 -v -0.016880 0.123174 0.133725 -vn 0.539403 0.584937 0.605717 -v -0.016880 0.123387 0.133370 -vn 0.539400 0.203710 0.817038 -v -0.016880 0.123749 0.133169 -vn 0.539405 -0.232097 0.809428 -v -0.016880 0.124163 0.133176 -vn 0.539400 -0.605721 0.584936 -v -0.016880 0.124518 0.133390 -vn 0.539400 -0.817037 0.203710 -v -0.016880 0.124719 0.133752 -vn 0.539399 -0.809431 -0.232099 -v -0.016880 0.124712 0.134166 -vn 0.539403 -0.584937 -0.605717 -v -0.016880 0.124498 0.134521 -vn -0.539400 0.584937 0.605720 -v -0.021120 0.123387 0.133370 -vn -0.539396 0.809433 0.232099 -v -0.021120 0.123174 0.133725 -vn -0.539397 0.817039 -0.203710 -v -0.021120 0.123166 0.134139 -vn -0.539396 0.605721 -0.584940 -v -0.021120 0.123367 0.134501 -vn -0.539402 0.232101 -0.809429 -v -0.021120 0.123722 0.134714 -vn -0.539398 -0.203711 -0.817038 -v -0.021120 0.124136 0.134722 -vn -0.539400 -0.584937 -0.605719 -v -0.021120 0.124498 0.134521 -vn -0.539396 -0.809433 -0.232099 -v -0.021120 0.124712 0.134166 -vn -0.539397 -0.817039 0.203710 -v -0.021120 0.124719 0.133752 -vn -0.539396 -0.605721 0.584940 -v -0.021120 0.124518 0.133390 -vn -0.539402 -0.232101 0.809429 -v -0.021120 0.124163 0.133176 -vn -0.539397 0.203713 0.817039 -v -0.021120 0.123749 0.133169 -vn 0.539399 -0.203712 -0.817037 -v -0.016880 0.123939 0.146033 -vn 0.539393 0.232102 -0.809434 -v -0.016880 0.123525 0.146026 -vn 0.539401 0.605711 -0.584944 -v -0.016880 0.123170 0.145813 -vn 0.539400 0.817035 -0.203717 -v -0.016880 0.122969 0.145451 -vn 0.539400 0.809428 0.232106 -v -0.016880 0.122976 0.145037 -vn 0.539393 0.584934 0.605729 -v -0.016880 0.123190 0.144682 -vn 0.539399 0.203712 0.817037 -v -0.016880 0.123552 0.144481 -vn 0.539404 -0.232093 0.809430 -v -0.016880 0.123966 0.144488 -vn 0.539401 -0.605718 0.584938 -v -0.016880 0.124321 0.144702 -vn 0.539400 -0.817037 0.203711 -v -0.016880 0.124522 0.145064 -vn 0.539400 -0.809428 -0.232105 -v -0.016880 0.124514 0.145478 -vn 0.539393 -0.584934 -0.605729 -v -0.016880 0.124301 0.145833 -vn -0.539391 0.584937 0.605728 -v -0.021120 0.123190 0.144682 -vn -0.539397 0.809431 0.232106 -v -0.021120 0.122976 0.145037 -vn -0.539395 0.817038 -0.203721 -v -0.021120 0.122969 0.145451 -vn -0.539398 0.605717 -0.584942 -v -0.021120 0.123170 0.145813 -vn -0.539390 0.232098 -0.809437 -v -0.021120 0.123525 0.146026 -vn -0.539396 -0.203708 -0.817040 -v -0.021120 0.123939 0.146033 -vn -0.539391 -0.584937 -0.605728 -v -0.021120 0.124301 0.145833 -vn -0.539397 -0.809431 -0.232106 -v -0.021120 0.124514 0.145478 -vn -0.539397 -0.817039 0.203710 -v -0.021120 0.124522 0.145064 -vn -0.539397 -0.605718 0.584942 -v -0.021120 0.124321 0.144702 -vn -0.539401 -0.232097 0.809431 -v -0.021120 0.123966 0.144488 -vn -0.539398 0.203711 0.817038 -v -0.021120 0.123552 0.144481 -vn 0.577350 -0.577350 0.577350 -v -0.040000 0.092500 0.122950 -vn 0.577350 -0.577350 -0.577350 -v -0.040000 0.092500 0.111450 -vn 0.904534 -0.301512 0.301512 -v -0.040000 0.094000 0.122950 -vn 0.904534 -0.301511 -0.301511 -v -0.040000 0.094000 0.111450 -vn 0.678874 -0.727973 -0.095840 -v -0.040000 0.094000 0.105200 -vn 0.000000 1.000000 -0.000000 -v -0.040000 0.095500 0.106800 -vn 0.000000 -0.866028 -0.499995 -v -0.040000 0.097366 0.107300 -vn -0.000002 -0.000004 1.000000 -v -0.040000 0.138500 0.106950 -vn 0.000004 -0.500001 -0.866025 -v -0.040000 0.097000 0.107666 -vn 0.000002 0.500004 0.866023 -v -0.040000 0.138000 0.107084 -vn -0.000002 0.000000 -1.000000 -v -0.040000 0.096500 0.107800 -vn -0.000000 -0.000004 -1.000000 -v -0.040000 0.138500 0.127450 -vn -0.000000 -1.000000 0.000002 -v -0.040000 0.097500 0.127600 -vn -0.000000 0.500008 -0.866021 -v -0.040000 0.138000 0.127316 -vn -0.000000 0.866029 -0.499994 -v -0.040000 0.137634 0.126950 -vn 0.000000 0.866025 -0.500001 -v -0.040000 0.095634 0.107300 -vn 0.000000 0.500001 -0.866025 -v -0.040000 0.096000 0.107666 -vn 0.000002 1.000000 -0.000004 -v -0.040000 0.137500 0.126450 -vn 0.000000 -0.866030 0.499992 -v -0.040000 0.097366 0.127100 -vn -0.000000 -0.500006 0.866022 -v -0.040000 0.097000 0.126734 -vn 0.678874 -0.727973 0.095839 -v -0.040000 0.094000 0.129200 -vn 0.000000 0.866026 -0.499998 -v -0.040000 0.095634 0.128100 -vn 0.653226 -0.655721 0.378585 -v -0.040000 0.094134 0.129700 -vn -0.000000 0.500006 -0.866022 -v -0.040000 0.096000 0.128466 -vn 0.653228 -0.378578 0.655722 -v -0.040000 0.094500 0.130066 -vn 0.678874 -0.095840 0.727973 -v -0.040000 0.095000 0.130200 -vn 0.000000 -0.000000 -1.000000 -v -0.040000 0.096500 0.128600 -vn -0.000000 -0.500006 -0.866022 -v -0.040000 0.097000 0.128466 -vn -0.003865 0.075740 0.997120 -v -0.040000 0.136000 0.130200 -vn 0.000000 -0.866028 -0.499995 -v -0.040000 0.097366 0.128100 -vn -0.004459 0.809274 0.587414 -v -0.040000 0.140045 0.128139 -vn 0.000000 -0.866024 -0.500002 -v -0.040000 0.139366 0.126950 -vn -0.001694 0.951434 0.307848 -v -0.040000 0.140755 0.126745 -vn 0.000000 -1.000000 -0.000004 -v -0.040000 0.139500 0.126450 -vn -0.000000 0.996917 0.078460 -v -0.040000 0.141000 0.125200 -vn 0.000000 -0.866021 0.500008 -v -0.040000 0.139366 0.125950 -vn -0.000829 0.996970 -0.077788 -v -0.040000 0.141000 0.109200 -vn 0.000000 -0.499994 0.866029 -v -0.040000 0.139000 0.125584 -vn -0.005793 0.588049 0.808805 -v -0.040000 0.138939 0.129245 -vn 0.000000 -0.500003 -0.866024 -v -0.040000 0.139000 0.127316 -vn -0.006980 0.309337 0.950927 -v -0.040000 0.137545 0.129955 -vn 0.653227 -0.378582 -0.655721 -v -0.040000 0.094500 0.104334 -vn 0.678874 -0.095840 -0.727973 -v -0.040000 0.095000 0.104200 -vn 0.653227 -0.655721 -0.378582 -v -0.040000 0.094134 0.104700 -vn -0.000001 0.499995 0.866028 -v -0.040000 0.096000 0.105934 -vn 0.000000 0.866025 0.500001 -v -0.040000 0.095634 0.106300 -vn 0.000000 0.866027 0.499997 -v -0.040000 0.137634 0.107450 -vn 0.000000 1.000000 -0.000000 -v -0.040000 0.137500 0.107950 -vn -0.000000 0.866027 -0.499997 -v -0.040000 0.137634 0.108450 -vn 0.000002 0.500000 0.866026 -v -0.040000 0.138000 0.125584 -vn 0.000000 0.499998 -0.866027 -v -0.040000 0.138000 0.108816 -vn -0.000000 -0.000004 1.000000 -v -0.040000 0.138500 0.125450 -vn 0.000000 -0.000004 -1.000000 -v -0.040000 0.138500 0.108950 -vn -0.000000 -0.499992 -0.866030 -v -0.040000 0.139000 0.108816 -vn -0.000000 -0.866022 -0.500006 -v -0.040000 0.139366 0.108450 -vn -0.002423 0.951213 -0.308526 -v -0.040000 0.140755 0.107655 -vn -0.000000 -1.000000 0.000000 -v -0.040000 0.139500 0.107950 -vn -0.004298 0.809268 -0.587424 -v -0.040000 0.140045 0.106261 -vn -0.000000 0.000000 1.000000 -v -0.040000 0.096500 0.126600 -vn -0.000000 0.866026 0.500000 -v -0.040000 0.137634 0.125950 -vn 0.000001 0.500006 0.866022 -v -0.040000 0.096000 0.126734 -vn 0.000000 0.866026 0.499999 -v -0.040000 0.095634 0.127100 -vn -0.000002 1.000000 -0.000001 -v -0.040000 0.095500 0.127600 -vn -0.000004 -1.000000 0.000000 -v -0.040000 0.097500 0.106800 -vn -0.000000 -0.866028 0.499995 -v -0.040000 0.097366 0.106300 -vn -0.001161 0.078223 -0.996935 -v -0.040000 0.136000 0.104200 -vn 0.000000 -0.499995 0.866028 -v -0.040000 0.097000 0.105934 -vn 0.000000 0.000000 1.000000 -v -0.040000 0.096500 0.105800 -vn 0.000000 -0.866022 0.500006 -v -0.040000 0.139366 0.107450 -vn 0.000000 -0.499998 0.866026 -v -0.040000 0.139000 0.107084 -vn -0.005610 0.588049 -0.808806 -v -0.040000 0.138939 0.105155 -vn -0.003336 0.306859 -0.951749 -v -0.040000 0.137545 0.104445 -vn -0.904534 -0.301511 0.301511 -v -0.062000 0.094000 0.122950 -vn -0.678875 -0.727973 0.095839 -v -0.062000 0.094000 0.129200 -vn -0.770263 0.637727 -0.000002 -v -0.062000 0.095500 0.127600 -vn -0.577350 -0.577350 -0.577350 -v -0.062000 0.092500 0.111450 -vn -0.577350 -0.577350 0.577350 -v -0.062000 0.092500 0.122950 -vn -0.904534 -0.301512 -0.301512 -v -0.062000 0.094000 0.111450 -vn -0.770263 0.000000 -0.637727 -v -0.062000 0.096500 0.128600 -vn -0.770263 0.318867 -0.552285 -v -0.062000 0.096000 0.128466 -vn -0.678874 -0.095840 0.727973 -v -0.062000 0.095000 0.130200 -vn -0.770263 0.318860 0.552289 -v -0.062000 0.096000 0.105934 -vn -0.770259 -0.000000 0.637731 -v -0.062000 0.096500 0.105800 -vn -0.678874 -0.095840 -0.727973 -v -0.062000 0.095000 0.104200 -vn -0.770263 -0.318860 0.552289 -v -0.062000 0.097000 0.105934 -vn 0.003384 0.076048 -0.997098 -v -0.062000 0.136000 0.104200 -vn -0.770263 -0.552289 0.318860 -v -0.062000 0.097366 0.106300 -vn -0.770260 -0.637730 -0.000000 -v -0.062000 0.097500 0.106800 -vn -0.770261 -0.637729 -0.000003 -v -0.062000 0.097500 0.127600 -vn -0.770258 0.552294 -0.318862 -v -0.062000 0.137634 0.126950 -vn -0.770263 0.637727 -0.000002 -v -0.062000 0.137500 0.126450 -vn -0.770263 0.318867 0.552285 -v -0.062000 0.096000 0.126734 -vn -0.770263 -0.000000 0.637727 -v -0.062000 0.096500 0.126600 -vn -0.770262 0.318865 -0.552288 -v -0.062000 0.096000 0.107666 -vn -0.770262 0.552288 -0.318865 -v -0.062000 0.095634 0.107300 -vn -0.653228 -0.378578 0.655722 -v -0.062000 0.094500 0.130066 -vn -0.653226 -0.655721 0.378585 -v -0.062000 0.094134 0.129700 -vn -0.770261 0.552289 -0.318867 -v -0.062000 0.095634 0.128100 -vn -0.770262 0.552288 0.318864 -v -0.062000 0.137634 0.125950 -vn -0.770262 0.318864 0.552289 -v -0.062000 0.138000 0.125584 -vn -0.770260 0.552291 -0.318863 -v -0.062000 0.137634 0.108450 -vn -0.770262 0.637728 0.000000 -v -0.062000 0.137500 0.107950 -vn -0.770260 0.552291 0.318863 -v -0.062000 0.137634 0.107450 -vn -0.678874 -0.727973 -0.095840 -v -0.062000 0.094000 0.105200 -vn -0.770263 0.637727 0.000000 -v -0.062000 0.095500 0.106800 -vn -0.770261 0.552288 0.318865 -v -0.062000 0.095634 0.106300 -vn -0.653227 -0.655721 -0.378582 -v -0.062000 0.094134 0.104700 -vn -0.653227 -0.378582 -0.655721 -v -0.062000 0.094500 0.104334 -vn 0.006827 0.808999 -0.587770 -v -0.062000 0.140045 0.106261 -vn 0.006827 0.587770 -0.808999 -v -0.062000 0.138939 0.105155 -vn -0.770263 -0.000002 0.637727 -v -0.062000 0.138500 0.106950 -vn 0.006827 0.309010 -0.951034 -v -0.062000 0.137545 0.104445 -vn -0.770263 0.318866 0.552285 -v -0.062000 0.138000 0.107084 -vn 0.003384 0.997099 -0.076047 -v -0.062000 0.141000 0.109200 -vn -0.770258 -0.318862 0.552294 -v -0.062000 0.139000 0.125584 -vn 0.003384 0.997099 0.076047 -v -0.062000 0.141000 0.125200 -vn -0.770265 -0.552283 0.318868 -v -0.062000 0.139366 0.125950 -vn 0.006827 0.951035 0.309009 -v -0.062000 0.140755 0.126745 -vn -0.770262 -0.637727 -0.000003 -v -0.062000 0.139500 0.126450 -vn 0.006827 0.808999 0.587770 -v -0.062000 0.140045 0.128139 -vn -0.770260 0.552291 0.318864 -v -0.062000 0.095634 0.127100 -vn -0.770263 0.000000 -0.637727 -v -0.062000 0.096500 0.107800 -vn -0.770262 -0.318865 -0.552288 -v -0.062000 0.097000 0.107666 -vn -0.770262 -0.318868 0.552287 -v -0.062000 0.097000 0.126734 -vn -0.770263 -0.552289 -0.318860 -v -0.062000 0.097366 0.107300 -vn -0.770261 -0.552292 0.318860 -v -0.062000 0.097366 0.127100 -vn -0.770263 -0.318867 -0.552285 -v -0.062000 0.097000 0.128466 -vn 0.003385 0.076048 0.997098 -v -0.062000 0.136000 0.130200 -vn -0.770262 -0.552291 -0.318861 -v -0.062000 0.097366 0.128100 -vn -0.770262 -0.000003 -0.637727 -v -0.062000 0.138500 0.127450 -vn -0.770265 0.318868 -0.552282 -v -0.062000 0.138000 0.127316 -vn -0.770260 -0.552290 -0.318867 -v -0.062000 0.139366 0.126950 -vn -0.770260 -0.318867 -0.552289 -v -0.062000 0.139000 0.127316 -vn 0.006826 0.587768 0.809000 -v -0.062000 0.138939 0.129245 -vn 0.006827 0.309008 0.951035 -v -0.062000 0.137545 0.129955 -vn -0.770260 -0.318864 0.552291 -v -0.062000 0.139000 0.107084 -vn -0.770263 -0.552285 0.318867 -v -0.062000 0.139366 0.107450 -vn 0.006828 0.951035 -0.309009 -v -0.062000 0.140755 0.107655 -vn -0.770263 -0.637727 -0.000000 -v -0.062000 0.139500 0.107950 -vn -0.770263 -0.552285 -0.318867 -v -0.062000 0.139366 0.108450 -vn -0.770262 -0.318859 -0.552291 -v -0.062000 0.139000 0.108816 -vn -0.770263 -0.000002 0.637727 -v -0.062000 0.138500 0.125450 -vn -0.770259 -0.000002 -0.637731 -v -0.062000 0.138500 0.108950 -vn -0.770265 0.318861 -0.552286 -v -0.062000 0.138000 0.108816 -vn 1.000000 0.000000 0.000000 -v -0.035000 0.092125 0.106450 -vn 0.923880 -0.382683 0.000000 -v -0.035000 0.092000 0.106450 -vn 0.717284 -0.297108 -0.630263 -v -0.035000 0.092000 0.105950 -vn 0.995906 0.003465 -0.090324 -v -0.035000 0.136000 0.105700 -vn 0.913025 0.400398 -0.077893 -v -0.035000 0.136522 0.105739 -vn 0.913685 0.406423 -0.000000 -v -0.035000 0.136522 0.106450 -vn 0.774248 -0.173320 -0.608687 -v -0.035000 0.098472 0.107200 -vn 0.487300 -0.619622 -0.615311 -v -0.035000 0.098398 0.107246 -vn 0.940157 -0.336739 0.052066 -v -0.035000 0.098436 0.106570 -vn 0.770263 0.637726 -0.000002 -v -0.035000 0.097500 0.130700 -vn 0.770262 0.552286 -0.318869 -v -0.035000 0.097667 0.131325 -vn 1.000000 0.000000 0.000000 -v -0.035000 0.096125 0.132075 -vn 0.707107 0.707107 0.000000 -v -0.035000 0.102000 0.132075 -vn 0.770263 -0.552286 -0.318865 -v -0.035000 0.099833 0.131325 -vn 0.973781 0.131340 0.185743 -v -0.035000 0.102000 0.130200 -vn 0.770261 -0.637729 -0.000002 -v -0.035000 0.100000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.035000 0.099833 0.130075 -vn 0.770258 -0.318867 0.552292 -v -0.035000 0.099375 0.129617 -vn 0.539748 -0.229382 0.809973 -v -0.035000 0.098409 0.127200 -vn 0.770264 -0.000000 0.637726 -v -0.035000 0.098750 0.129450 -vn 0.770260 0.318866 -0.552291 -v -0.035000 0.098125 0.131783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 0.098750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.035000 0.099375 0.131783 -vn 0.942586 0.085434 -0.322850 -v -0.035000 0.096109 0.129510 -vn 0.934093 -0.003462 -0.357014 -v -0.035000 0.096393 0.129547 -vn 0.770262 0.552286 0.318867 -v -0.035000 0.097667 0.130075 -vn 0.940628 -0.147419 -0.305756 -v -0.035000 0.097371 0.129345 -vn 0.770260 0.318865 0.552291 -v -0.035000 0.098125 0.129617 -vn 0.940311 -0.279986 -0.193450 -v -0.035000 0.098120 0.128685 -vn 0.939232 -0.340976 -0.039743 -v -0.035000 0.098445 0.127742 -vn 0.707107 -0.707107 0.000000 -v -0.035000 0.095500 0.132075 -vn 0.973781 -0.131340 0.185743 -v -0.035000 0.095500 0.130200 -vn 0.939248 0.197230 -0.280916 -v -0.035000 0.095443 0.129239 -vn 0.816496 -0.408249 0.408249 -v -0.035000 0.094000 0.130200 -vn 0.941719 0.299948 -0.152302 -v -0.035000 0.094771 0.128501 -vn 0.973781 -0.185743 0.131341 -v -0.035000 0.094000 0.128450 -vn 0.770269 0.637719 0.000000 -v -0.035000 0.092250 0.125200 -vn 0.770262 0.552287 -0.318867 -v -0.035000 0.092417 0.125825 -vn 0.707107 -0.000000 0.707107 -v -0.035000 0.092125 0.128450 -vn 0.770262 0.318866 -0.552288 -v -0.035000 0.092875 0.126283 -vn 0.770264 -0.000001 -0.637725 -v -0.035000 0.093500 0.126450 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 0.094125 0.126283 -vn 0.770261 -0.552288 -0.318867 -v -0.035000 0.094583 0.125825 -vn 0.770264 -0.637725 0.000000 -v -0.035000 0.094750 0.125200 -vn 0.945217 0.156015 0.286746 -v -0.035000 0.095568 0.125887 -vn 0.939551 0.015341 0.342066 -v -0.035000 0.096538 0.125650 -vn 0.770261 -0.552288 0.318867 -v -0.035000 0.094583 0.124575 -vn 0.770261 -0.318867 0.552288 -v -0.035000 0.094125 0.124117 -vn 0.973781 -0.185743 -0.131340 -v -0.035000 0.094000 0.121950 -vn 0.770264 -0.000001 0.637725 -v -0.035000 0.093500 0.123950 -vn 0.707107 -0.000000 -0.707107 -v -0.035000 0.092125 0.121950 -vn 0.770261 0.318866 0.552288 -v -0.035000 0.092875 0.124117 -vn 0.770261 0.552288 0.318867 -v -0.035000 0.092417 0.124575 -vn 0.943025 0.280557 0.178865 -v -0.035000 0.094843 0.126573 -vn 0.942135 0.334868 0.015656 -v -0.035000 0.094551 0.127528 -vn 0.525147 -0.818539 0.232841 -v -0.035000 0.097000 0.125715 -vn 0.707107 -0.707107 0.000000 -v -0.035000 0.097000 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.035000 0.096125 0.117200 -vn 0.766706 -0.622386 -0.157474 -v -0.035000 0.097000 0.108774 -vn 0.938472 0.035310 -0.343546 -v -0.035000 0.096385 0.108747 -vn 0.465178 -0.661092 -0.588699 -v -0.035000 0.097057 0.108669 -vn 0.923879 -0.382684 0.000000 -v -0.035000 0.094000 0.117200 -vn 0.973781 -0.185743 0.131340 -v -0.035000 0.094000 0.112450 -vn 0.770261 -0.000001 0.637729 -v -0.035000 0.093500 0.107950 -vn 0.770263 0.318864 0.552286 -v -0.035000 0.092875 0.108117 -vn 0.770260 0.552291 0.318866 -v -0.035000 0.092417 0.108575 -vn 0.770261 -0.000001 -0.637729 -v -0.035000 0.093500 0.110450 -vn 0.770263 0.318864 -0.552286 -v -0.035000 0.092875 0.110283 -vn 0.707107 0.000000 0.707107 -v -0.035000 0.092125 0.112450 -vn 0.770260 0.552291 -0.318865 -v -0.035000 0.092417 0.109825 -vn 0.770264 0.637725 -0.000000 -v -0.035000 0.092250 0.109200 -vn 0.717284 -0.630263 -0.297108 -v -0.035000 0.095500 0.102200 -vn 0.923880 0.000000 -0.382682 -v -0.035000 0.096125 0.102200 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 0.095500 0.104200 -vn 0.949429 0.094218 0.299513 -v -0.035000 0.096110 0.104889 -vn 0.816496 -0.408249 -0.408249 -v -0.035000 0.094000 0.104200 -vn 0.942336 0.183413 0.279933 -v -0.035000 0.095459 0.105151 -vn 0.940884 0.289291 0.176207 -v -0.035000 0.094792 0.105858 -vn 0.973781 -0.185743 -0.131340 -v -0.035000 0.094000 0.105950 -vn 0.945657 0.316744 0.073529 -v -0.035000 0.094584 0.106436 -vn 0.707107 0.000000 -0.707107 -v -0.035000 0.092125 0.105950 -vn 0.770262 -0.552289 0.318863 -v -0.035000 0.099833 0.103075 -vn 0.717284 0.630263 -0.297108 -v -0.035000 0.102000 0.102200 -vn 0.770261 -0.637728 -0.000000 -v -0.035000 0.100000 0.103700 -vn 0.973781 0.131340 -0.185743 -v -0.035000 0.102000 0.104200 -vn 0.770262 -0.552289 -0.318863 -v -0.035000 0.099833 0.104325 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 0.099375 0.104783 -vn 0.770262 -0.318863 0.552289 -v -0.035000 0.099375 0.102617 -vn 0.770261 -0.000000 0.637729 -v -0.035000 0.098750 0.102450 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 0.098750 0.104950 -vn 0.770261 0.318867 -0.552288 -v -0.035000 0.098125 0.104783 -vn 0.940958 -0.270852 0.203069 -v -0.035000 0.098085 0.105663 -vn 0.770261 0.552288 -0.318867 -v -0.035000 0.097667 0.104325 -vn 0.770262 0.318863 0.552289 -v -0.035000 0.098125 0.102617 -vn 0.770261 0.552288 0.318867 -v -0.035000 0.097667 0.103075 -vn 0.770264 0.637725 -0.000000 -v -0.035000 0.097500 0.103700 -vn 0.934277 -0.003689 0.356529 -v -0.035000 0.096385 0.104853 -vn 0.941333 -0.139691 0.307212 -v -0.035000 0.097339 0.105040 -vn 0.707107 0.000000 -0.707107 -v -0.035000 0.102750 0.107200 -vn 1.000000 0.000000 0.000000 -v -0.035000 0.102750 0.106450 -vn 0.707107 0.000000 -0.707107 -v -0.035000 0.110750 0.107200 -vn 1.000000 0.000000 0.000000 -v -0.035000 0.110750 0.106450 -vn 0.707107 0.000000 -0.707107 -v -0.035000 0.118750 0.107200 -vn 1.000000 0.000000 0.000000 -v -0.035000 0.118750 0.106450 -vn 0.534580 0.237791 -0.810975 -v -0.035000 0.136522 0.107200 -vn 0.997107 0.040621 -0.064242 -v -0.035000 0.127500 0.105700 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 0.119500 0.104200 -vn 0.770262 0.552289 -0.318863 -v -0.035000 0.121667 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.035000 0.122125 0.104783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 0.122750 0.104950 -vn 0.717283 0.630262 -0.297109 -v -0.035000 0.127500 0.104200 -vn 0.973781 0.131340 -0.185743 -v -0.035000 0.126000 0.104200 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 0.123375 0.104783 -vn 0.717284 -0.630263 -0.297108 -v -0.035000 0.119500 0.102200 -vn 0.770262 0.552289 0.318863 -v -0.035000 0.121667 0.103075 -vn 0.770261 0.637728 0.000000 -v -0.035000 0.121500 0.103700 -vn 0.770262 -0.552289 -0.318863 -v -0.035000 0.123833 0.104325 -vn 0.770261 -0.637728 -0.000000 -v -0.035000 0.124000 0.103700 -vn 0.717284 0.630263 -0.297108 -v -0.035000 0.126000 0.102200 -vn 0.770262 -0.552289 0.318863 -v -0.035000 0.123833 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.035000 0.123375 0.102617 -vn 0.770261 -0.000000 0.637728 -v -0.035000 0.122750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.035000 0.122125 0.102617 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 0.111500 0.104200 -vn 0.717284 -0.630263 -0.297108 -v -0.035000 0.111500 0.102200 -vn 0.770262 0.552289 0.318863 -v -0.035000 0.113667 0.103075 -vn 0.770261 0.637728 0.000000 -v -0.035000 0.113500 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.035000 0.113667 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.035000 0.114125 0.104783 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 0.114750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 0.115375 0.104783 -vn 0.973781 0.131340 -0.185743 -v -0.035000 0.118000 0.104200 -vn 0.923879 0.000000 -0.382684 -v -0.035000 0.118750 0.104200 -vn 0.770262 -0.552289 -0.318863 -v -0.035000 0.115833 0.104325 -vn 0.770261 -0.637728 -0.000000 -v -0.035000 0.116000 0.103700 -vn 0.717284 0.630263 -0.297108 -v -0.035000 0.118000 0.102200 -vn 0.770262 -0.552289 0.318863 -v -0.035000 0.115833 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.035000 0.115375 0.102617 -vn 0.770261 -0.000000 0.637728 -v -0.035000 0.114750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.035000 0.114125 0.102617 -vn 0.973781 -0.131340 -0.185743 -v -0.035000 0.103500 0.104200 -vn 0.717284 -0.630263 -0.297108 -v -0.035000 0.103500 0.102200 -vn 0.770260 0.552291 0.318866 -v -0.035000 0.105667 0.103075 -vn 0.770262 -0.552289 0.318863 -v -0.035000 0.107833 0.103075 -vn 0.717284 0.630263 -0.297108 -v -0.035000 0.110000 0.102200 -vn 0.770261 -0.637728 -0.000000 -v -0.035000 0.108000 0.103700 -vn 0.973781 0.131340 -0.185743 -v -0.035000 0.110000 0.104200 -vn 0.770262 -0.552289 -0.318863 -v -0.035000 0.107833 0.104325 -vn 0.770261 -0.318867 -0.552288 -v -0.035000 0.107375 0.104783 -vn 0.923879 0.000000 -0.382684 -v -0.035000 0.102750 0.104200 -vn 0.770264 0.637725 -0.000000 -v -0.035000 0.105500 0.103700 -vn 0.770260 0.552291 -0.318865 -v -0.035000 0.105667 0.104325 -vn 0.770262 0.318868 -0.552286 -v -0.035000 0.106125 0.104783 -vn 0.770264 -0.000001 -0.637726 -v -0.035000 0.106750 0.104950 -vn 0.923879 0.000000 -0.382684 -v -0.035000 0.110750 0.104200 -vn 0.770262 -0.318863 0.552289 -v -0.035000 0.107375 0.102617 -vn 0.770261 -0.000001 0.637729 -v -0.035000 0.106750 0.102450 -vn 0.770263 0.318864 0.552286 -v -0.035000 0.106125 0.102617 -vn 0.770263 -0.318865 -0.552286 -v -0.035000 0.094125 0.110283 -vn 0.770260 -0.552291 -0.318866 -v -0.035000 0.094583 0.109825 -vn 0.770264 -0.637725 0.000000 -v -0.035000 0.094750 0.109200 -vn 0.942086 0.183366 -0.280805 -v -0.035000 0.095459 0.108449 -vn 0.770260 -0.552291 0.318865 -v -0.035000 0.094583 0.108575 -vn 0.944677 0.287244 -0.158356 -v -0.035000 0.094792 0.107741 -vn 0.770263 -0.318865 0.552286 -v -0.035000 0.094125 0.108117 -vn 0.938161 0.345264 -0.025411 -v -0.035000 0.094550 0.106800 -vn 0.717284 -0.297108 0.630263 -v -0.035000 0.092000 0.112450 -vn 0.717284 -0.297108 0.630263 -v -0.035000 0.092000 0.128450 -vn 0.717284 -0.297108 -0.630262 -v -0.035000 0.092000 0.121950 -vn 0.717284 -0.630263 0.297108 -v -0.035000 0.095500 0.132200 -vn 0.923880 0.000000 0.382683 -v -0.035000 0.096125 0.132200 -vn 0.717283 0.630263 0.297108 -v -0.035000 0.102000 0.132200 -vn 0.770261 0.552289 0.318865 -v -0.035000 0.105667 0.130075 -vn 0.770263 0.637726 -0.000002 -v -0.035000 0.105500 0.130700 -vn 0.707107 0.000000 0.707107 -v -0.035000 0.102750 0.127200 -vn 0.707107 -0.707107 0.000000 -v -0.035000 0.103500 0.132075 -vn 0.770261 0.318866 -0.552288 -v -0.035000 0.106125 0.131783 -vn 0.770264 -0.000001 -0.637725 -v -0.035000 0.106750 0.131950 -vn 0.973781 0.131340 0.185744 -v -0.035000 0.110000 0.130200 -vn 0.707107 0.707107 0.000000 -v -0.035000 0.110000 0.132075 -vn 0.770260 -0.318865 -0.552291 -v -0.035000 0.107375 0.131783 -vn 0.770264 -0.552287 0.318863 -v -0.035000 0.107833 0.130075 -vn 0.707107 0.000000 0.707107 -v -0.035000 0.110750 0.127200 -vn 0.770260 -0.637730 -0.000002 -v -0.035000 0.108000 0.130700 -vn 0.770263 -0.552286 -0.318865 -v -0.035000 0.107833 0.131325 -vn 0.923879 0.000000 0.382685 -v -0.035000 0.102750 0.130200 -vn 0.973781 -0.131340 0.185743 -v -0.035000 0.103500 0.130200 -vn 0.770261 0.552288 -0.318867 -v -0.035000 0.105667 0.131325 -vn 0.770259 -0.318866 0.552291 -v -0.035000 0.107375 0.129617 -vn 0.770263 -0.000001 0.637726 -v -0.035000 0.106750 0.129450 -vn 0.770261 0.318866 0.552289 -v -0.035000 0.106125 0.129617 -vn 0.717284 0.630263 0.297108 -v -0.035000 0.110000 0.132200 -vn 0.717284 -0.630263 0.297108 -v -0.035000 0.103500 0.132200 -vn 0.770263 0.552287 0.318863 -v -0.035000 0.113667 0.130075 -vn 0.770260 0.637729 -0.000002 -v -0.035000 0.113500 0.130700 -vn 0.770263 0.552286 -0.318865 -v -0.035000 0.113667 0.131325 -vn 0.770260 0.318866 -0.552291 -v -0.035000 0.114125 0.131783 -vn 0.707107 -0.707107 0.000000 -v -0.035000 0.111500 0.132075 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 0.114750 0.131950 -vn 0.973781 0.131340 0.185743 -v -0.035000 0.118000 0.130200 -vn 0.707107 0.707107 0.000000 -v -0.035000 0.118000 0.132075 -vn 0.770260 -0.318865 -0.552291 -v -0.035000 0.115375 0.131783 -vn 0.973781 -0.131340 0.185743 -v -0.035000 0.111500 0.130200 -vn 0.923879 0.000000 0.382685 -v -0.035000 0.110750 0.130200 -vn 0.770263 -0.552286 -0.318865 -v -0.035000 0.115833 0.131325 -vn 0.770260 -0.637730 -0.000002 -v -0.035000 0.116000 0.130700 -vn 0.707107 0.000000 0.707107 -v -0.035000 0.118750 0.127200 -vn 0.770264 -0.552287 0.318863 -v -0.035000 0.115833 0.130075 -vn 0.770259 -0.318866 0.552291 -v -0.035000 0.115375 0.129617 -vn 0.770264 0.000000 0.637726 -v -0.035000 0.114750 0.129450 -vn 0.770259 0.318866 0.552291 -v -0.035000 0.114125 0.129617 -vn 0.717284 0.630263 0.297108 -v -0.035000 0.118000 0.132200 -vn 0.717284 -0.630263 0.297108 -v -0.035000 0.111500 0.132200 -vn 0.770263 0.552287 0.318863 -v -0.035000 0.121667 0.130075 -vn 0.770260 0.637729 -0.000002 -v -0.035000 0.121500 0.130700 -vn 0.997107 0.040621 0.064244 -v -0.035000 0.127500 0.128700 -vn 0.717283 0.630262 0.297109 -v -0.035000 0.127500 0.130200 -vn 0.973781 0.131340 0.185743 -v -0.035000 0.126000 0.130200 -vn 0.925077 0.379320 0.018702 -v -0.035000 0.136550 0.128657 -vn 0.996376 -0.004467 0.084940 -v -0.035000 0.136000 0.128700 -vn 0.549134 0.227456 0.804186 -v -0.035000 0.136550 0.127200 -vn 0.770260 -0.318865 -0.552291 -v -0.035000 0.123375 0.131783 -vn 0.770263 -0.552286 -0.318865 -v -0.035000 0.123833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.035000 0.124000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.035000 0.123833 0.130075 -vn 0.770263 0.552286 -0.318865 -v -0.035000 0.121667 0.131325 -vn 0.770260 0.318866 -0.552291 -v -0.035000 0.122125 0.131783 -vn 0.707107 -0.707107 0.000000 -v -0.035000 0.119500 0.132075 -vn 0.770264 -0.000000 -0.637725 -v -0.035000 0.122750 0.131950 -vn 0.707107 0.707107 0.000000 -v -0.035000 0.126000 0.132075 -vn 0.770260 -0.318866 0.552291 -v -0.035000 0.123375 0.129617 -vn 0.770264 0.000000 0.637726 -v -0.035000 0.122750 0.129450 -vn 0.770259 0.318866 0.552291 -v -0.035000 0.122125 0.129617 -vn 0.973781 -0.131340 0.185743 -v -0.035000 0.119500 0.130200 -vn 0.923879 0.000000 0.382685 -v -0.035000 0.118750 0.130200 -vn 0.717284 0.630263 0.297108 -v -0.035000 0.126000 0.132200 -vn 0.717284 -0.630263 0.297108 -v -0.035000 0.119500 0.132200 -vn 0.511562 -0.726533 0.458752 -v -0.035005 0.098404 0.127200 -vn 0.328039 -0.331546 0.884572 -v -0.032200 0.098404 0.127200 -vn 0.297112 0.717283 0.630262 -v -0.034950 0.136750 0.127200 -vn 0.185745 0.973780 0.131342 -v -0.035200 0.136750 0.127200 -vn 0.717284 0.297105 0.630264 -v -0.034750 0.136550 0.127200 -vn 0.131333 0.185735 0.973784 -v -0.034750 0.120550 0.127200 -vn 0.341576 0.341573 0.875588 -v -0.032200 0.120550 0.127200 -vn 0.325836 -0.886095 0.329646 -v -0.032200 0.097000 0.125723 -vn 0.523497 -0.484824 0.700640 -v -0.035008 0.097000 0.125723 -vn 0.333461 -0.921917 -0.197161 -v -0.032200 0.097000 0.108774 -vn 0.939710 -0.253755 -0.229246 -v -0.032000 0.097916 0.108141 -vn 0.849428 -0.276498 -0.449467 -v -0.032000 0.098355 0.107400 -vn 0.875581 0.341583 -0.341583 -v -0.032000 0.120550 0.107400 -vn 0.932051 0.319827 0.170269 -v -0.032000 0.119404 0.111798 -vn 0.932219 0.346284 0.105143 -v -0.032000 0.118544 0.113873 -vn 0.938932 -0.242884 0.243751 -v -0.032000 0.097916 0.126259 -vn 0.932221 0.360144 0.035503 -v -0.032000 0.118105 0.116077 -vn 0.932221 0.360144 -0.035503 -v -0.032000 0.118105 0.118323 -vn 0.848116 -0.296919 0.438793 -v -0.032000 0.098355 0.127000 -vn 0.842670 -0.453574 0.290135 -v -0.032000 0.097200 0.125780 -vn 0.844520 -0.463103 -0.268928 -v -0.032000 0.097200 0.108620 -vn 0.904944 0.408556 0.118990 -v -0.032000 0.120550 0.110059 -vn 0.904818 0.408617 -0.119734 -v -0.032000 0.120550 0.124341 -vn 0.875576 0.341581 0.341598 -v -0.032000 0.120550 0.127000 -vn 0.931922 0.320350 -0.169992 -v -0.032000 0.119404 0.122602 -vn 0.932219 0.346284 -0.105142 -v -0.032000 0.118544 0.120527 -vn 0.110051 0.987815 0.110051 -v -0.036700 0.141000 0.124500 -vn 0.375127 0.924492 0.067783 -v -0.036700 0.141000 0.125200 -vn 0.375938 0.924209 -0.067148 -v -0.036700 0.141000 0.109200 -vn 0.110053 0.987814 -0.110052 -v -0.036700 0.141000 0.109900 -vn 0.118633 0.921345 -0.370202 -v -0.036250 0.141000 0.109900 -vn 0.118634 0.921348 0.370194 -v -0.036250 0.141000 0.124500 -vn 0.804191 0.549123 0.227466 -v -0.034750 0.120750 0.127000 -vn 0.934292 0.353779 0.044032 -v -0.034750 0.136550 0.126450 -vn 0.735270 -0.658079 -0.162202 -v -0.034750 0.138336 0.119378 -vn 0.735272 -0.677773 -0.000000 -v -0.034750 0.138600 0.117200 -vn 0.934292 0.044032 0.353779 -v -0.034750 0.138500 0.124500 -vn 0.777812 0.602021 0.180497 -v -0.034750 0.120750 0.110129 -vn 0.735271 0.507321 0.449447 -v -0.034750 0.122689 0.111166 -vn 0.685652 0.644141 0.339062 -v -0.034750 0.119550 0.111950 -vn 0.735271 0.600138 0.314977 -v -0.034750 0.121442 0.112971 -vn 0.685531 0.697354 0.209153 -v -0.034750 0.118724 0.113969 -vn 0.735270 0.658079 0.162202 -v -0.034750 0.120664 0.115022 -vn 0.685729 0.724414 0.070714 -v -0.034750 0.118303 0.116109 -vn 0.735272 0.677773 -0.000000 -v -0.034750 0.120400 0.117200 -vn 0.685922 0.724270 -0.070315 -v -0.034750 0.118303 0.118291 -vn 0.686109 0.696940 -0.208637 -v -0.034750 0.118724 0.120431 -vn 0.735270 -0.658079 0.162202 -v -0.034750 0.138336 0.115022 -vn 0.735271 -0.600138 0.314977 -v -0.034750 0.137558 0.112971 -vn 0.945445 0.162890 -0.282137 -v -0.034750 0.137525 0.109639 -vn 0.735270 -0.507321 0.449448 -v -0.034750 0.136311 0.111166 -vn 0.945445 0.282135 -0.162892 -v -0.034750 0.136811 0.108925 -vn 0.735271 -0.385020 0.557796 -v -0.034750 0.134669 0.109711 -vn 0.934292 0.353778 -0.044033 -v -0.034750 0.136550 0.107950 -vn 0.735271 -0.240342 0.633729 -v -0.034750 0.132727 0.108691 -vn 0.735269 -0.081696 0.672833 -v -0.034750 0.130597 0.108166 -vn 0.804186 0.549133 -0.227459 -v -0.034750 0.120750 0.107400 -vn 0.717284 0.297105 -0.630264 -v -0.034750 0.136550 0.107200 -vn 0.131340 0.185742 -0.973781 -v -0.034750 0.120550 0.107200 -vn 0.735269 0.081696 0.672834 -v -0.034750 0.128403 0.108166 -vn 0.735273 0.240343 0.633727 -v -0.034750 0.126273 0.108691 -vn 0.735270 0.385020 0.557796 -v -0.034750 0.124331 0.109711 -vn 0.934289 0.044032 -0.353788 -v -0.034750 0.138500 0.109900 -vn 0.921346 0.118637 -0.370198 -v -0.034750 0.139500 0.109900 -vn 0.921350 0.118637 0.370189 -v -0.034750 0.139500 0.124500 -vn 0.735270 -0.081696 -0.672833 -v -0.034750 0.130597 0.126234 -vn 0.735271 -0.240341 -0.633729 -v -0.034750 0.132727 0.125709 -vn 0.945444 0.282135 0.162894 -v -0.034750 0.136811 0.125475 -vn 0.735272 -0.385020 -0.557795 -v -0.034750 0.134669 0.124689 -vn 0.945444 0.162889 0.282138 -v -0.034750 0.137525 0.124761 -vn 0.735270 -0.507321 -0.449448 -v -0.034750 0.136311 0.123234 -vn 0.735272 -0.600137 -0.314977 -v -0.034750 0.137558 0.121429 -vn 0.735270 0.658079 -0.162202 -v -0.034750 0.120664 0.119378 -vn 0.778046 0.601627 -0.180800 -v -0.034750 0.120750 0.124271 -vn 0.686287 0.643461 -0.339069 -v -0.034750 0.119550 0.122450 -vn 0.735272 0.600138 -0.314977 -v -0.034750 0.121442 0.121429 -vn 0.735270 0.507321 -0.449447 -v -0.034750 0.122689 0.123234 -vn 0.735271 0.385020 -0.557796 -v -0.034750 0.124331 0.124689 -vn 0.735272 0.240342 -0.633727 -v -0.034750 0.126273 0.125709 -vn 0.735269 0.081696 -0.672834 -v -0.034750 0.128403 0.126234 -vn 0.370454 0.889761 0.266627 -v -0.036700 0.140787 0.126644 -vn 0.375402 0.802108 0.464431 -v -0.036700 0.140166 0.127965 -vn 0.392620 0.711816 0.582381 -v -0.036700 0.140045 0.128139 -vn 0.375037 0.623801 0.685725 -v -0.036700 0.139190 0.129050 -vn 0.400481 0.503029 0.765883 -v -0.036700 0.138939 0.129245 -vn 0.374929 0.390437 0.840825 -v -0.036700 0.137943 0.129807 -vn 0.397501 0.258893 0.880323 -v -0.036700 0.137545 0.129955 -vn 0.088068 0.028549 0.995705 -v -0.036500 0.136000 0.130200 -vn 0.081124 0.426404 0.900887 -v -0.036500 0.136573 0.130167 -vn 0.089205 0.226903 0.969823 -v -0.036700 0.136573 0.130167 -vn -0.301511 -0.301511 0.904534 -v -0.037000 0.124750 0.133200 -vn -0.770260 -0.318866 -0.552291 -v -0.037000 0.123375 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.037000 0.122750 0.131950 -vn -0.609994 0.000001 0.792406 -v -0.037000 0.122750 0.128391 -vn -0.770264 -0.000000 0.637725 -v -0.037000 0.122750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.037000 0.123375 0.129617 -vn -0.301511 0.301511 0.904534 -v -0.037000 0.120750 0.133200 -vn -0.770260 0.318865 -0.552291 -v -0.037000 0.122125 0.131783 -vn -0.770263 0.552286 -0.318865 -v -0.037000 0.121667 0.131325 -vn -0.609995 0.686244 0.396202 -v -0.037000 0.120750 0.129545 -vn -0.609994 -0.686244 0.396202 -v -0.037000 0.124750 0.129545 -vn -0.770264 -0.552286 0.318863 -v -0.037000 0.123833 0.130075 -vn -0.770261 -0.637729 -0.000002 -v -0.037000 0.124000 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.037000 0.123833 0.131325 -vn -0.770260 0.637729 -0.000002 -v -0.037000 0.121500 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.037000 0.121667 0.130075 -vn -0.770260 0.318866 0.552291 -v -0.037000 0.122125 0.129617 -vn -0.609995 0.686244 0.396202 -v -0.037000 0.112750 0.129545 -vn -0.770264 0.552286 0.318863 -v -0.037000 0.113667 0.130075 -vn -0.609994 0.000001 0.792406 -v -0.037000 0.114750 0.128391 -vn -0.770260 0.318866 0.552291 -v -0.037000 0.114125 0.129617 -vn -0.609994 -0.686244 0.396202 -v -0.037000 0.116750 0.129545 -vn -0.770261 -0.637729 -0.000002 -v -0.037000 0.116000 0.130700 -vn -0.301511 -0.301511 0.904534 -v -0.037000 0.116750 0.133200 -vn -0.770263 -0.552286 -0.318865 -v -0.037000 0.115833 0.131325 -vn -0.770260 -0.318866 -0.552291 -v -0.037000 0.115375 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.037000 0.114750 0.131950 -vn -0.301511 0.301511 0.904534 -v -0.037000 0.112750 0.133200 -vn -0.770260 0.318865 -0.552291 -v -0.037000 0.114125 0.131783 -vn -0.770263 0.552286 -0.318865 -v -0.037000 0.113667 0.131325 -vn -0.770260 0.637729 -0.000002 -v -0.037000 0.113500 0.130700 -vn -0.770264 -0.000000 0.637725 -v -0.037000 0.114750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.037000 0.115375 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.037000 0.115833 0.130075 -vn -0.609995 -0.686244 0.396202 -v -0.037000 0.108750 0.129545 -vn -0.770261 -0.637729 -0.000002 -v -0.037000 0.108000 0.130700 -vn -0.301511 -0.301511 0.904534 -v -0.037000 0.108750 0.133200 -vn -0.770263 -0.552286 -0.318865 -v -0.037000 0.107833 0.131325 -vn -0.609994 -0.000001 0.792406 -v -0.037000 0.106750 0.128391 -vn -0.770260 -0.318865 0.552291 -v -0.037000 0.107375 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.037000 0.107833 0.130075 -vn -0.770260 -0.318866 -0.552291 -v -0.037000 0.107375 0.131783 -vn -0.770264 -0.000001 -0.637725 -v -0.037000 0.106750 0.131950 -vn -0.301511 0.301511 0.904534 -v -0.037000 0.104750 0.133200 -vn -0.770263 0.637726 -0.000002 -v -0.037000 0.105500 0.130700 -vn -0.609994 0.686244 0.396202 -v -0.037000 0.104750 0.129545 -vn -0.770261 0.552288 -0.318867 -v -0.037000 0.105667 0.131325 -vn -0.770261 0.318866 -0.552288 -v -0.037000 0.106125 0.131783 -vn -0.770261 0.552288 0.318865 -v -0.037000 0.105667 0.130075 -vn -0.770261 0.318866 0.552288 -v -0.037000 0.106125 0.129617 -vn -0.770264 -0.000001 0.637726 -v -0.037000 0.106750 0.129450 -vn -0.717284 -0.297108 -0.630263 -v -0.040000 0.092000 0.105950 -vn -0.741788 -0.427644 0.516597 -v -0.040000 0.092000 0.107200 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 0.092500 0.105950 -vn -0.846478 -0.452907 0.279911 -v -0.040000 0.094000 0.108200 -vn -0.846479 -0.279911 0.452905 -v -0.040000 0.123750 0.130200 -vn -0.741787 -0.516597 0.427643 -v -0.040000 0.124750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 0.126000 0.132200 -vn -0.717284 0.630263 -0.297108 -v -0.040000 0.126000 0.102200 -vn -0.741788 -0.516597 -0.427644 -v -0.040000 0.124750 0.102200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 0.126000 0.102700 -vn -0.846478 -0.279911 -0.452907 -v -0.040000 0.123750 0.104200 -vn -0.717284 0.630263 -0.297108 -v -0.040000 0.118000 0.102200 -vn -0.741788 -0.516597 -0.427644 -v -0.040000 0.116750 0.102200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 0.118000 0.102700 -vn -0.846478 -0.279911 -0.452907 -v -0.040000 0.115750 0.104200 -vn -0.717284 0.630263 -0.297108 -v -0.040000 0.110000 0.102200 -vn -0.741788 -0.516597 -0.427644 -v -0.040000 0.108750 0.102200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 0.110000 0.102700 -vn -0.846478 -0.279911 -0.452907 -v -0.040000 0.107750 0.104200 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 0.111500 0.102700 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 0.095500 0.102700 -vn -0.577350 -0.577350 -0.577350 -v -0.040000 0.094000 0.102700 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 0.094000 0.104200 -vn -0.741787 0.516598 -0.427643 -v -0.040000 0.120750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 0.119500 0.102200 -vn -0.846479 0.279912 -0.452906 -v -0.040000 0.121750 0.104200 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 0.119500 0.102700 -vn -0.846478 0.279911 -0.452906 -v -0.040000 0.113750 0.104200 -vn -0.741788 0.516597 -0.427644 -v -0.040000 0.112750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 0.111500 0.102200 -vn -0.904534 0.301511 -0.301512 -v -0.040000 0.127500 0.104200 -vn -0.741787 -0.516597 0.427643 -v -0.040000 0.100750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 0.102000 0.132200 -vn -0.846479 -0.279911 0.452905 -v -0.040000 0.099750 0.130200 -vn -0.904534 0.301511 0.301511 -v -0.040000 0.102000 0.131700 -vn -0.741788 0.516597 -0.427644 -v -0.040000 0.104750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 0.103500 0.102200 -vn -0.846478 0.279911 -0.452907 -v -0.040000 0.105750 0.104200 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 0.103500 0.102700 -vn -0.846478 -0.279911 -0.452907 -v -0.040000 0.099750 0.104200 -vn -0.846478 0.279911 -0.452906 -v -0.040000 0.097750 0.104200 -vn -0.717284 -0.630263 0.297108 -v -0.040000 0.103500 0.132200 -vn -0.741788 0.516597 0.427643 -v -0.040000 0.104750 0.132200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 0.103500 0.131700 -vn -0.846479 0.279911 0.452905 -v -0.040000 0.105750 0.130200 -vn -0.741787 -0.516597 0.427643 -v -0.040000 0.108750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 0.110000 0.132200 -vn -0.846479 -0.279911 0.452905 -v -0.040000 0.107750 0.130200 -vn -0.904534 0.301511 0.301511 -v -0.040000 0.110000 0.131700 -vn -0.717284 -0.630263 0.297108 -v -0.040000 0.111500 0.132200 -vn -0.741788 0.516597 0.427643 -v -0.040000 0.112750 0.132200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 0.111500 0.131700 -vn -0.846479 0.279911 0.452905 -v -0.040000 0.113750 0.130200 -vn -0.577350 0.577350 -0.577350 -v -0.040000 0.127500 0.102700 -vn -0.717284 0.630263 -0.297108 -v -0.040000 0.102000 0.102200 -vn -0.741788 -0.516597 -0.427644 -v -0.040000 0.100750 0.102200 -vn -0.904534 0.301511 -0.301511 -v -0.040000 0.102000 0.102700 -vn -0.741788 0.516597 -0.427644 -v -0.040000 0.096750 0.102200 -vn -0.717284 -0.630263 -0.297108 -v -0.040000 0.095500 0.102200 -vn -0.717284 -0.630263 0.297108 -v -0.040000 0.095500 0.132200 -vn -0.741788 0.516597 0.427643 -v -0.040000 0.096750 0.132200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 0.095500 0.131700 -vn -0.846479 0.279912 0.452906 -v -0.040000 0.097750 0.130200 -vn -0.741787 -0.516597 0.427643 -v -0.040000 0.116750 0.132200 -vn -0.717284 0.630263 0.297108 -v -0.040000 0.118000 0.132200 -vn -0.846479 -0.279911 0.452905 -v -0.040000 0.115750 0.130200 -vn -0.904534 0.301511 0.301511 -v -0.040000 0.118000 0.131700 -vn -0.904534 -0.301511 0.301511 -v -0.040000 0.119500 0.131700 -vn -0.904534 0.301511 0.301511 -v -0.040000 0.126000 0.131700 -vn -0.577350 0.577350 0.577350 -v -0.040000 0.127500 0.131700 -vn -0.904534 0.301511 0.301511 -v -0.040000 0.127500 0.130200 -vn -0.846478 -0.452906 0.279911 -v -0.040000 0.094000 0.124200 -vn -0.846479 -0.452904 -0.279912 -v -0.040000 0.094000 0.126200 -vn -0.741787 -0.427643 -0.516598 -v -0.040000 0.092000 0.111200 -vn -0.717284 -0.297108 0.630263 -v -0.040000 0.092000 0.112450 -vn -0.846479 -0.452906 -0.279911 -v -0.040000 0.094000 0.110200 -vn -0.904534 -0.301511 0.301511 -v -0.040000 0.092500 0.112450 -vn -0.904534 -0.301511 -0.301511 -v -0.040000 0.092500 0.121950 -vn -0.717284 -0.297108 -0.630263 -v -0.040000 0.092000 0.121950 -vn -0.741788 -0.427644 0.516597 -v -0.040000 0.092000 0.123200 -vn -0.577350 -0.577350 -0.577350 -v -0.040000 0.092500 0.104200 -vn -0.741786 -0.427642 -0.516600 -v -0.040000 0.092000 0.127200 -vn -0.717284 -0.297108 0.630262 -v -0.040000 0.092000 0.128450 -vn -0.904534 -0.301511 0.301511 -v -0.040000 0.092500 0.128450 -vn -0.577350 -0.577350 0.577350 -v -0.040000 0.092500 0.130200 -vn -0.577350 -0.577350 0.577350 -v -0.040000 0.094000 0.131700 -vn -0.904534 -0.301511 0.301511 -v -0.040000 0.094000 0.130200 -vn -0.846479 0.279912 0.452904 -v -0.040000 0.121750 0.130200 -vn -0.741787 0.516598 0.427643 -v -0.040000 0.120750 0.132200 -vn -0.717284 -0.630263 0.297108 -v -0.040000 0.119500 0.132200 -vn 0.075084 0.990667 0.113762 -v -0.038500 0.120750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 0.120750 0.129545 -vn 0.846479 0.279912 0.452905 -v -0.038500 0.121750 0.130200 -vn 0.609994 0.000001 0.792406 -v -0.038500 0.122750 0.128391 -vn 0.846478 -0.279911 0.452906 -v -0.038500 0.123750 0.130200 -vn 0.609994 -0.686244 0.396202 -v -0.038500 0.124750 0.129545 -vn 0.075085 -0.990667 0.113762 -v -0.038500 0.124750 0.132200 -vn 0.075085 0.990667 0.113762 -v -0.038500 0.112750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 0.112750 0.129545 -vn 0.846478 0.279911 0.452906 -v -0.038500 0.113750 0.130200 -vn 0.609994 0.000001 0.792406 -v -0.038500 0.114750 0.128391 -vn 0.846478 -0.279911 0.452906 -v -0.038500 0.115750 0.130200 -vn 0.609994 -0.686244 0.396202 -v -0.038500 0.116750 0.129545 -vn 0.075085 -0.990667 0.113762 -v -0.038500 0.116750 0.132200 -vn 0.075085 0.990667 0.113762 -v -0.038500 0.104750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 0.104750 0.129545 -vn 0.846478 0.279911 0.452906 -v -0.038500 0.105750 0.130200 -vn 0.609994 -0.000001 0.792406 -v -0.038500 0.106750 0.128391 -vn 0.846478 -0.279911 0.452906 -v -0.038500 0.107750 0.130200 -vn 0.609995 -0.686244 0.396202 -v -0.038500 0.108750 0.129545 -vn 0.075085 -0.990667 0.113762 -v -0.038500 0.108750 0.132200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.120750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.119500 0.133200 -vn 0.297109 -0.630263 0.717283 -v -0.036000 0.119500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 0.126000 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.124750 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.126000 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.112750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.111500 0.133200 -vn 0.297109 -0.630263 0.717283 -v -0.036000 0.111500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 0.118000 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.116750 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.118000 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.104750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.103500 0.133200 -vn 0.297109 -0.630263 0.717283 -v -0.036000 0.103500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 0.110000 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.108750 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.110000 0.133200 -vn -0.609995 -0.686244 0.396202 -v -0.037000 0.100750 0.129545 -vn -0.770261 -0.637729 -0.000002 -v -0.037000 0.100000 0.130700 -vn -0.301511 -0.301511 0.904534 -v -0.037000 0.100750 0.133200 -vn -0.770263 -0.552286 -0.318865 -v -0.037000 0.099833 0.131325 -vn -0.609994 0.686244 0.396203 -v -0.037000 0.096750 0.129545 -vn -0.301511 0.301511 0.904534 -v -0.037000 0.096750 0.133200 -vn -0.770262 0.552286 -0.318869 -v -0.037000 0.097667 0.131325 -vn -0.770260 0.318866 0.552291 -v -0.037000 0.098125 0.129617 -vn -0.609994 -0.000001 0.792406 -v -0.037000 0.098750 0.128391 -vn -0.770262 0.552286 0.318867 -v -0.037000 0.097667 0.130075 -vn -0.770263 0.637726 -0.000002 -v -0.037000 0.097500 0.130700 -vn -0.770264 -0.000000 0.637725 -v -0.037000 0.098750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.037000 0.099375 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.037000 0.099833 0.130075 -vn -0.770260 -0.318866 -0.552291 -v -0.037000 0.099375 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.037000 0.098750 0.131950 -vn -0.770260 0.318866 -0.552291 -v -0.037000 0.098125 0.131783 -vn -0.301511 -0.904534 0.301511 -v -0.037000 0.091000 0.123200 -vn -0.301511 -0.904534 -0.301511 -v -0.037000 0.091000 0.127200 -vn -0.770264 0.637725 0.000000 -v -0.037000 0.092250 0.125200 -vn -0.770261 0.552288 -0.318867 -v -0.037000 0.092417 0.125825 -vn -0.770261 -0.552288 -0.318867 -v -0.037000 0.094583 0.125825 -vn -0.609995 -0.396202 -0.686244 -v -0.037000 0.094655 0.127200 -vn -0.770264 -0.637725 -0.000000 -v -0.037000 0.094750 0.125200 -vn -0.609994 -0.792406 -0.000001 -v -0.037000 0.095809 0.125200 -vn -0.770261 -0.552288 0.318867 -v -0.037000 0.094583 0.124575 -vn -0.609994 -0.396203 0.686244 -v -0.037000 0.094655 0.123200 -vn -0.770261 -0.318867 0.552288 -v -0.037000 0.094125 0.124117 -vn -0.770261 0.552288 0.318867 -v -0.037000 0.092417 0.124575 -vn -0.770261 0.318866 0.552288 -v -0.037000 0.092875 0.124117 -vn -0.770264 -0.000001 0.637725 -v -0.037000 0.093500 0.123950 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 0.094125 0.126283 -vn -0.770264 -0.000001 -0.637725 -v -0.037000 0.093500 0.126450 -vn -0.770261 0.318866 -0.552288 -v -0.037000 0.092875 0.126283 -vn 0.075085 0.990667 0.113762 -v -0.038500 0.096750 0.132200 -vn 0.609994 0.686244 0.396202 -v -0.038500 0.096750 0.129545 -vn 0.846478 0.279911 0.452906 -v -0.038500 0.097750 0.130200 -vn 0.609994 -0.000001 0.792406 -v -0.038500 0.098750 0.128391 -vn 0.846478 -0.279911 0.452906 -v -0.038500 0.099750 0.130200 -vn 0.609995 -0.686244 0.396202 -v -0.038500 0.100750 0.129545 -vn 0.075085 -0.990667 0.113762 -v -0.038500 0.100750 0.132200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.096750 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.095500 0.133200 -vn 0.297109 -0.630263 0.717283 -v -0.036000 0.095500 0.133200 -vn 0.297109 0.630262 0.717283 -v -0.036000 0.102000 0.133200 -vn -0.297109 -0.630262 0.717283 -v -0.039000 0.100750 0.133200 -vn -0.297109 0.630262 0.717283 -v -0.039000 0.102000 0.133200 -vn 0.846478 -0.452906 0.279911 -v -0.038500 0.094000 0.124200 -vn 0.075085 -0.113763 0.990667 -v -0.038500 0.092000 0.123200 -vn 0.609994 -0.396203 0.686244 -v -0.038500 0.094655 0.123200 -vn 0.609994 -0.396202 -0.686244 -v -0.038500 0.094655 0.127200 -vn 0.075084 -0.113761 -0.990667 -v -0.038500 0.092000 0.127200 -vn 0.846479 -0.452905 -0.279912 -v -0.038500 0.094000 0.126200 -vn 0.609994 -0.792406 -0.000001 -v -0.038500 0.095809 0.125200 -vn -0.297109 -0.717283 0.630262 -v -0.039000 0.091000 0.123200 -vn -0.297109 -0.717283 -0.630262 -v -0.039000 0.091000 0.121950 -vn 0.297109 -0.717283 -0.630262 -v -0.036000 0.091000 0.121950 -vn 0.297109 -0.717283 0.630262 -v -0.036000 0.091000 0.128450 -vn -0.297109 -0.717283 -0.630263 -v -0.039000 0.091000 0.127200 -vn -0.297110 -0.717284 0.630262 -v -0.039000 0.091000 0.128450 -vn 0.087122 0.736841 -0.670429 -v -0.036500 0.127500 0.104200 -vn 0.081892 0.019684 -0.996447 -v -0.036500 0.136000 0.104200 -vn 0.087119 0.736840 0.670431 -v -0.036500 0.127500 0.130200 -vn 0.297108 0.630263 0.717284 -v -0.036500 0.127500 0.131700 -vn 0.319806 0.768481 0.554220 -v -0.035750 0.127500 0.129999 -vn 0.554224 0.768479 0.319806 -v -0.035201 0.127500 0.129450 -vn 0.227458 0.804186 0.549133 -v -0.036500 0.126000 0.131700 -vn 0.227458 -0.804186 0.549133 -v -0.036500 0.119500 0.131700 -vn 0.227458 0.804186 0.549133 -v -0.036500 0.118000 0.131700 -vn 0.227458 -0.804186 0.549133 -v -0.036500 0.111500 0.131700 -vn 0.227458 0.804186 0.549133 -v -0.036500 0.110000 0.131700 -vn 0.227458 -0.804186 0.549133 -v -0.036500 0.103500 0.131700 -vn 0.227458 0.804186 0.549133 -v -0.036500 0.102000 0.131700 -vn 0.227458 -0.804186 0.549133 -v -0.036500 0.095500 0.131700 -vn 0.297108 -0.630263 0.717284 -v -0.036500 0.094000 0.131700 -vn 0.297108 -0.717284 0.630263 -v -0.036500 0.092500 0.130200 -vn 0.227458 -0.549133 0.804186 -v -0.036500 0.092500 0.128450 -vn 0.227458 -0.549133 -0.804186 -v -0.036500 0.092500 0.121950 -vn 0.227458 -0.549133 0.804186 -v -0.036500 0.092500 0.112450 -vn 0.297109 -0.717283 0.630262 -v -0.036000 0.091000 0.112450 -vn -0.297109 -0.717283 0.630262 -v -0.039000 0.091000 0.112450 -vn -0.297109 -0.717283 0.630262 -v -0.039000 0.091000 0.107200 -vn -0.297109 -0.717283 -0.630262 -v -0.039000 0.091000 0.105950 -vn -0.301511 -0.904534 0.301511 -v -0.037000 0.091000 0.107200 -vn 0.297109 -0.717283 -0.630262 -v -0.036000 0.091000 0.105950 -vn -0.301511 -0.904534 -0.301511 -v -0.037000 0.091000 0.111200 -vn -0.297109 -0.717283 -0.630262 -v -0.039000 0.091000 0.111200 -vn 0.227458 -0.549133 -0.804186 -v -0.036500 0.092500 0.105950 -vn 0.297108 -0.717284 -0.630263 -v -0.036500 0.092500 0.104200 -vn 0.297108 -0.630263 -0.717284 -v -0.036500 0.094000 0.102700 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 0.095500 0.102700 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.095500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 0.095500 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.100750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.102000 0.101200 -vn -0.301512 -0.301511 -0.904534 -v -0.037000 0.100750 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 0.102000 0.101200 -vn -0.301511 0.301511 -0.904534 -v -0.037000 0.096750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.096750 0.101200 -vn 0.227458 0.804186 -0.549133 -v -0.036500 0.102000 0.102700 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 0.103500 0.102700 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.103500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 0.103500 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.108750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.110000 0.101200 -vn -0.301512 -0.301511 -0.904534 -v -0.037000 0.108750 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 0.110000 0.101200 -vn -0.301511 0.301511 -0.904534 -v -0.037000 0.104750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.104750 0.101200 -vn 0.227458 0.804186 -0.549133 -v -0.036500 0.110000 0.102700 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 0.111500 0.102700 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.111500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 0.111500 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.116750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.118000 0.101200 -vn -0.301511 -0.301511 -0.904534 -v -0.037000 0.116750 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 0.118000 0.101200 -vn -0.301512 0.301511 -0.904534 -v -0.037000 0.112750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.112750 0.101200 -vn 0.227458 0.804186 -0.549133 -v -0.036500 0.118000 0.102700 -vn 0.227458 -0.804186 -0.549133 -v -0.036500 0.119500 0.102700 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.119500 0.101200 -vn 0.297109 -0.630262 -0.717283 -v -0.036000 0.119500 0.101200 -vn -0.297109 -0.630262 -0.717283 -v -0.039000 0.124750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.126000 0.101200 -vn -0.301511 -0.301511 -0.904534 -v -0.037000 0.124750 0.101200 -vn 0.297109 0.630262 -0.717283 -v -0.036000 0.126000 0.101200 -vn -0.301512 0.301511 -0.904534 -v -0.037000 0.120750 0.101200 -vn -0.297109 0.630262 -0.717283 -v -0.039000 0.120750 0.101200 -vn 0.227458 0.804186 -0.549133 -v -0.036500 0.126000 0.102700 -vn 0.297108 0.630263 -0.717284 -v -0.036500 0.127500 0.102700 -vn 0.554223 0.768480 -0.319807 -v -0.035201 0.127500 0.104950 -vn 0.319808 0.768479 -0.554223 -v -0.035750 0.127500 0.104401 -vn 0.174809 0.977023 -0.121937 -v -0.035253 0.136750 0.107200 -vn 0.297112 0.717283 -0.630262 -v -0.034950 0.136750 0.107200 -vn 0.332605 -0.226215 -0.915533 -v -0.032200 0.098472 0.107200 -vn 0.341590 0.341585 -0.875577 -v -0.032200 0.120550 0.107200 -vn 0.341590 0.875577 -0.341585 -v -0.032200 0.120750 0.107400 -vn 0.371679 0.888584 0.268838 -v -0.032200 0.120750 0.110129 -vn 0.391743 0.812013 0.432635 -v -0.032200 0.119581 0.111892 -vn 0.391666 0.880350 0.267547 -v -0.032200 0.118735 0.113931 -vn 0.391403 0.915764 0.090445 -v -0.032200 0.118304 0.116096 -vn 0.391144 0.915901 -0.090180 -v -0.032200 0.118304 0.118304 -vn 0.390891 0.880749 -0.267368 -v -0.032200 0.118735 0.120468 -vn 0.391244 0.812381 -0.432394 -v -0.032200 0.119581 0.122508 -vn 0.371672 0.888350 -0.269620 -v -0.032200 0.120750 0.124271 -vn 0.341588 0.875572 0.341601 -v -0.032200 0.120750 0.127000 -vn 0.609994 -0.396203 -0.686244 -v -0.038500 0.094655 0.111200 -vn -0.609994 -0.396203 -0.686244 -v -0.037000 0.094655 0.111200 -vn 0.075085 -0.113762 -0.990667 -v -0.038500 0.092000 0.111200 -vn -0.770264 0.637725 0.000000 -v -0.037000 0.092250 0.109200 -vn -0.770260 0.552291 -0.318866 -v -0.037000 0.092417 0.109825 -vn -0.770261 -0.000001 0.637729 -v -0.037000 0.093500 0.107950 -vn -0.609994 -0.396204 0.686243 -v -0.037000 0.094655 0.107200 -vn -0.770263 0.318864 0.552286 -v -0.037000 0.092875 0.108117 -vn -0.770260 0.552291 0.318866 -v -0.037000 0.092417 0.108575 -vn -0.770263 -0.318865 0.552286 -v -0.037000 0.094125 0.108117 -vn -0.770260 -0.552291 0.318866 -v -0.037000 0.094583 0.108575 -vn -0.609994 -0.792406 -0.000001 -v -0.037000 0.095809 0.109200 -vn -0.770264 -0.637725 -0.000000 -v -0.037000 0.094750 0.109200 -vn -0.770260 -0.552291 -0.318866 -v -0.037000 0.094583 0.109825 -vn -0.770263 -0.318865 -0.552286 -v -0.037000 0.094125 0.110283 -vn -0.770261 -0.000001 -0.637729 -v -0.037000 0.093500 0.110450 -vn -0.770263 0.318864 -0.552286 -v -0.037000 0.092875 0.110283 -vn 0.075085 -0.113763 0.990667 -v -0.038500 0.092000 0.107200 -vn 0.609994 -0.396203 0.686243 -v -0.038500 0.094655 0.107200 -vn 0.609994 -0.792406 -0.000001 -v -0.038500 0.095809 0.109200 -vn 0.846478 -0.452906 0.279911 -v -0.038500 0.094000 0.108200 -vn 0.846479 -0.452906 -0.279912 -v -0.038500 0.094000 0.110200 -vn 0.609994 0.686243 -0.396204 -v -0.038500 0.096750 0.104855 -vn -0.609994 0.686243 -0.396203 -v -0.037000 0.096750 0.104855 -vn 0.075085 0.990667 -0.113763 -v -0.038500 0.096750 0.102200 -vn -0.609995 -0.686243 -0.396203 -v -0.037000 0.100750 0.104855 -vn -0.770262 -0.552289 0.318863 -v -0.037000 0.099833 0.103075 -vn -0.770261 -0.637729 0.000000 -v -0.037000 0.100000 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.037000 0.099833 0.104325 -vn -0.609994 -0.000001 -0.792406 -v -0.037000 0.098750 0.106009 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 0.099375 0.104783 -vn -0.770264 0.637725 0.000000 -v -0.037000 0.097500 0.103700 -vn -0.770261 0.552288 0.318867 -v -0.037000 0.097667 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.037000 0.098125 0.102617 -vn -0.770261 0.000000 0.637729 -v -0.037000 0.098750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.037000 0.099375 0.102617 -vn -0.770264 0.000000 -0.637725 -v -0.037000 0.098750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.037000 0.098125 0.104783 -vn -0.770261 0.552288 -0.318867 -v -0.037000 0.097667 0.104325 -vn 0.075085 -0.990667 -0.113763 -v -0.038500 0.100750 0.102200 -vn 0.609994 -0.686244 -0.396203 -v -0.038500 0.100750 0.104855 -vn 0.609994 -0.000001 -0.792406 -v -0.038500 0.098750 0.106009 -vn 0.846478 -0.279911 -0.452906 -v -0.038500 0.099750 0.104200 -vn 0.846478 0.279911 -0.452906 -v -0.038500 0.097750 0.104200 -vn 0.609994 0.686243 -0.396204 -v -0.038500 0.104750 0.104855 -vn -0.609994 0.686243 -0.396203 -v -0.037000 0.104750 0.104855 -vn 0.075085 0.990667 -0.113763 -v -0.038500 0.104750 0.102200 -vn -0.609995 -0.686243 -0.396203 -v -0.037000 0.108750 0.104855 -vn -0.770262 -0.552289 0.318863 -v -0.037000 0.107833 0.103075 -vn -0.770261 -0.637729 0.000000 -v -0.037000 0.108000 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.037000 0.107833 0.104325 -vn -0.609994 -0.000001 -0.792406 -v -0.037000 0.106750 0.106009 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 0.107375 0.104783 -vn -0.770260 0.552291 0.318866 -v -0.037000 0.105667 0.103075 -vn -0.770264 0.637725 0.000000 -v -0.037000 0.105500 0.103700 -vn -0.770264 -0.000001 -0.637725 -v -0.037000 0.106750 0.104950 -vn -0.770262 0.318868 -0.552286 -v -0.037000 0.106125 0.104783 -vn -0.770260 0.552291 -0.318866 -v -0.037000 0.105667 0.104325 -vn -0.770263 0.318864 0.552286 -v -0.037000 0.106125 0.102617 -vn -0.770261 -0.000001 0.637729 -v -0.037000 0.106750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.037000 0.107375 0.102617 -vn 0.075085 -0.990667 -0.113763 -v -0.038500 0.108750 0.102200 -vn 0.609994 -0.686244 -0.396203 -v -0.038500 0.108750 0.104855 -vn 0.609994 0.686244 -0.396203 -v -0.038500 0.112750 0.104855 -vn -0.609994 0.686244 -0.396203 -v -0.037000 0.112750 0.104855 -vn 0.075085 0.990667 -0.113763 -v -0.038500 0.112750 0.102200 -vn -0.770262 0.552289 0.318863 -v -0.037000 0.113667 0.103075 -vn -0.770261 0.637729 -0.000000 -v -0.037000 0.113500 0.103700 -vn -0.770262 0.318863 0.552289 -v -0.037000 0.114125 0.102617 -vn -0.770261 0.000000 0.637729 -v -0.037000 0.114750 0.102450 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 0.115375 0.104783 -vn -0.609994 0.000001 -0.792406 -v -0.037000 0.114750 0.106009 -vn -0.770262 -0.552289 -0.318863 -v -0.037000 0.115833 0.104325 -vn -0.609994 -0.686243 -0.396204 -v -0.037000 0.116750 0.104855 -vn -0.770264 0.000000 -0.637725 -v -0.037000 0.114750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.037000 0.114125 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.037000 0.113667 0.104325 -vn -0.770262 -0.318863 0.552289 -v -0.037000 0.115375 0.102617 -vn -0.770262 -0.552289 0.318863 -v -0.037000 0.115833 0.103075 -vn -0.770261 -0.637729 0.000000 -v -0.037000 0.116000 0.103700 -vn 0.075085 -0.990667 -0.113763 -v -0.038500 0.116750 0.102200 -vn 0.609994 -0.686243 -0.396203 -v -0.038500 0.116750 0.104855 -vn 0.609994 0.686244 -0.396203 -v -0.038500 0.120750 0.104855 -vn -0.609994 0.686244 -0.396203 -v -0.037000 0.120750 0.104855 -vn 0.075085 0.990667 -0.113762 -v -0.038500 0.120750 0.102200 -vn -0.770264 0.000000 -0.637725 -v -0.037000 0.122750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.037000 0.122125 0.104783 -vn -0.609994 0.000001 -0.792406 -v -0.037000 0.122750 0.106009 -vn -0.609994 -0.686243 -0.396204 -v -0.037000 0.124750 0.104855 -vn -0.770262 -0.552289 0.318863 -v -0.037000 0.123833 0.103075 -vn -0.770261 -0.637729 0.000000 -v -0.037000 0.124000 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.037000 0.123833 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.037000 0.123375 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.037000 0.121667 0.104325 -vn -0.770261 0.637729 -0.000000 -v -0.037000 0.121500 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.037000 0.121667 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.037000 0.122125 0.102617 -vn -0.770261 0.000000 0.637729 -v -0.037000 0.122750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.037000 0.123375 0.102617 -vn 0.075085 -0.990667 -0.113763 -v -0.038500 0.124750 0.102200 -vn 0.609994 -0.686243 -0.396203 -v -0.038500 0.124750 0.104855 -vn 0.609994 -0.000001 -0.792406 -v -0.038500 0.106750 0.106009 -vn 0.846478 -0.279911 -0.452906 -v -0.038500 0.107750 0.104200 -vn 0.846478 0.279911 -0.452906 -v -0.038500 0.105750 0.104200 -vn 0.609994 0.000001 -0.792406 -v -0.038500 0.114750 0.106009 -vn 0.846478 -0.279911 -0.452906 -v -0.038500 0.115750 0.104200 -vn 0.846478 0.279911 -0.452906 -v -0.038500 0.113750 0.104200 -vn 0.609994 0.000001 -0.792406 -v -0.038500 0.122750 0.106009 -vn 0.846478 -0.279911 -0.452907 -v -0.038500 0.123750 0.104200 -vn 0.846479 0.279911 -0.452906 -v -0.038500 0.121750 0.104200 -vn 0.034161 0.454646 -0.890017 -v -0.036500 0.136550 0.104230 -vn 0.091615 0.237887 -0.966962 -v -0.036700 0.136550 0.104230 -vn 0.414909 0.237221 -0.878394 -v -0.036700 0.137545 0.104445 -vn 0.377869 0.392565 -0.838515 -v -0.036700 0.137925 0.104586 -vn 0.408211 0.494297 -0.767485 -v -0.036700 0.138939 0.105155 -vn 0.375047 0.622829 -0.686603 -v -0.036700 0.139179 0.105341 -vn 0.391908 0.711423 -0.583340 -v -0.036700 0.140045 0.106261 -vn 0.375404 0.801576 -0.465348 -v -0.036700 0.140161 0.106428 -vn 0.371278 0.888945 -0.268199 -v -0.036700 0.140786 0.107752 -vn 0.407585 0.057149 -0.911377 -v -0.034950 0.139500 0.109700 -vn 0.392029 0.123373 -0.911643 -v -0.034950 0.138500 0.109700 -vn 0.678875 0.095838 -0.727973 -v -0.036500 0.138500 0.109700 -vn 0.376165 0.217178 -0.900741 -v -0.035124 0.140150 0.109700 -vn 0.217181 0.376163 -0.900741 -v -0.035600 0.140626 0.109700 -vn 0.057146 0.407579 -0.911380 -v -0.036250 0.140800 0.109700 -vn 0.578888 0.574259 -0.578892 -v -0.036500 0.140800 0.109700 -vn 0.797136 0.566899 -0.207845 -v -0.036500 0.136750 0.104482 -vn 0.393458 0.593613 -0.702007 -v -0.036500 0.136729 0.104456 -vn 0.915147 0.166931 -0.366934 -v -0.036500 0.137848 0.104770 -vn 0.770263 -0.000002 0.637727 -v -0.036500 0.138500 0.106950 -vn 0.770263 0.318866 0.552286 -v -0.036500 0.138000 0.107084 -vn 0.770260 0.552291 0.318863 -v -0.036500 0.137634 0.107450 -vn 0.678874 0.727973 -0.095840 -v -0.036500 0.136750 0.107950 -vn 0.770262 0.637727 0.000000 -v -0.036500 0.137500 0.107950 -vn 0.653227 0.655722 -0.378579 -v -0.036500 0.136984 0.108825 -vn 0.770260 0.552291 -0.318863 -v -0.036500 0.137634 0.108450 -vn 0.653226 0.378582 -0.655722 -v -0.036500 0.137625 0.109466 -vn 0.770265 0.318861 -0.552286 -v -0.036500 0.138000 0.108816 -vn 0.770259 -0.000002 -0.637731 -v -0.036500 0.138500 0.108950 -vn 0.770261 -0.318859 -0.552292 -v -0.036500 0.139000 0.108816 -vn 0.917198 0.397282 -0.030260 -v -0.036500 0.140800 0.109200 -vn 0.770263 -0.552285 -0.318867 -v -0.036500 0.139366 0.108450 -vn 0.911012 0.394700 -0.119450 -v -0.036500 0.140594 0.107810 -vn 0.770263 -0.637727 -0.000000 -v -0.036500 0.139500 0.107950 -vn 0.915049 0.341600 -0.214463 -v -0.036500 0.139995 0.106538 -vn 0.770263 -0.552285 0.318867 -v -0.036500 0.139366 0.107450 -vn 0.916109 0.260375 -0.304877 -v -0.036500 0.139052 0.105496 -vn 0.770260 -0.318864 0.552291 -v -0.036500 0.139000 0.107084 -vn 0.392037 0.911639 -0.123377 -v -0.034950 0.136750 0.107950 -vn 0.376084 0.925873 -0.036324 -v -0.035253 0.136750 0.105739 -vn 0.075600 0.934781 -0.347087 -v -0.036310 0.136750 0.104496 -vn 0.358781 0.923541 -0.135456 -v -0.035338 0.136750 0.105282 -vn 0.279266 0.928830 -0.243485 -v -0.035585 0.136750 0.104884 -vn 0.178104 0.931065 -0.318429 -v -0.035878 0.136750 0.104649 -vn 0.406959 0.456727 -0.791066 -v -0.034950 0.137625 0.109466 -vn 0.406958 0.791070 -0.456721 -v -0.034950 0.136984 0.108825 -vn 0.057148 0.407588 0.911376 -v -0.036250 0.140800 0.124700 -vn 0.578889 0.574264 0.578885 -v -0.036500 0.140800 0.124700 -vn 0.678875 0.095838 0.727973 -v -0.036500 0.138500 0.124700 -vn 0.217185 0.376172 0.900736 -v -0.035600 0.140626 0.124700 -vn 0.376172 0.217183 0.900736 -v -0.035124 0.140150 0.124700 -vn 0.407593 0.057150 0.911374 -v -0.034950 0.139500 0.124700 -vn 0.392037 0.123374 0.911639 -v -0.034950 0.138500 0.124700 -vn 0.770263 0.637727 -0.000002 -v -0.036500 0.137500 0.126450 -vn 0.770259 0.552293 -0.318862 -v -0.036500 0.137634 0.126950 -vn 0.503520 0.830932 0.236684 -v -0.036500 0.136750 0.129941 -vn 0.770265 0.318867 -0.552282 -v -0.036500 0.138000 0.127316 -vn 0.916751 0.164412 0.364056 -v -0.036500 0.137865 0.129623 -vn 0.770263 -0.000002 -0.637726 -v -0.036500 0.138500 0.127450 -vn 0.916348 0.262563 0.302270 -v -0.036500 0.139063 0.128896 -vn 0.770262 -0.318865 -0.552287 -v -0.036500 0.139000 0.127316 -vn 0.915127 0.341980 0.213524 -v -0.036500 0.139999 0.127854 -vn 0.770262 -0.552288 -0.318865 -v -0.036500 0.139366 0.126950 -vn 0.911050 0.394731 0.119058 -v -0.036500 0.140595 0.126586 -vn 0.770263 -0.637727 -0.000002 -v -0.036500 0.139500 0.126450 -vn 0.917220 0.397238 0.030157 -v -0.036500 0.140800 0.125200 -vn 0.770265 -0.552283 0.318868 -v -0.036500 0.139366 0.125950 -vn 0.770258 -0.318862 0.552294 -v -0.036500 0.139000 0.125584 -vn 0.770263 -0.000002 0.637727 -v -0.036500 0.138500 0.125450 -vn 0.653226 0.378580 0.655723 -v -0.036500 0.137625 0.124934 -vn 0.770262 0.318864 0.552289 -v -0.036500 0.138000 0.125584 -vn 0.653227 0.655722 0.378581 -v -0.036500 0.136984 0.125575 -vn 0.770262 0.552288 0.318864 -v -0.036500 0.137634 0.125950 -vn 0.678874 0.727973 0.095840 -v -0.036500 0.136750 0.126450 -vn 0.392038 0.911638 0.123375 -v -0.034950 0.136750 0.126450 -vn 0.406960 0.791067 0.456724 -v -0.034950 0.136984 0.125575 -vn 0.406959 0.456723 0.791068 -v -0.034950 0.137625 0.124934 -vn 0.141901 0.919683 0.366124 -v -0.036035 0.136750 0.129882 -vn 0.036087 0.926992 0.373341 -v -0.036500 0.136750 0.129968 -vn 0.451008 0.527998 0.719590 -v -0.036527 0.136750 0.129968 -vn 0.386589 0.922213 0.008518 -v -0.035200 0.136750 0.128657 -vn 0.396287 0.915772 0.065705 -v -0.035207 0.136750 0.128789 -vn 0.267264 0.918049 0.292841 -v -0.035628 0.136750 0.129630 -vn 0.361091 0.915018 0.179876 -v -0.035342 0.136750 0.129253 -vn 0.133426 -0.907514 -0.398266 -v -0.035200 0.098142 0.107404 -vn 0.658764 -0.652395 -0.374714 -v -0.036500 0.098016 0.107675 -vn 0.344939 -0.934450 -0.088429 -v -0.035200 0.098250 0.106800 -vn 0.658698 -0.752369 -0.007635 -v -0.036500 0.098250 0.106800 -vn 0.390795 -0.901666 0.185143 -v -0.035200 0.098238 0.106593 -vn 0.662042 -0.648877 0.375046 -v -0.036500 0.098016 0.105925 -vn 0.660766 -0.374860 0.650284 -v -0.036500 0.097375 0.105284 -vn 0.391321 -0.695168 0.603000 -v -0.035200 0.097922 0.105780 -vn 0.344698 -0.856588 0.383980 -v -0.035200 0.098016 0.105925 -vn 0.659324 0.000677 0.751859 -v -0.036500 0.096500 0.105050 -vn 0.391795 -0.310549 0.866058 -v -0.035200 0.097253 0.105220 -vn 0.356504 -0.551768 0.753961 -v -0.035200 0.097375 0.105284 -vn 0.657710 0.377404 0.651907 -v -0.036500 0.095625 0.105284 -vn 0.407735 0.138339 0.902560 -v -0.035200 0.096397 0.105053 -vn 0.367159 -0.105640 0.924140 -v -0.035200 0.096500 0.105050 -vn 0.654707 0.655784 -0.375908 -v -0.036500 0.094984 0.107675 -vn 0.422286 0.906198 -0.021913 -v -0.035200 0.094750 0.106800 -vn 0.653967 0.756522 -0.001406 -v -0.036500 0.094750 0.106800 -vn 0.415229 0.789484 0.451995 -v -0.035200 0.094967 0.105955 -vn 0.655411 0.654563 0.376807 -v -0.036500 0.094984 0.105925 -vn 0.393179 0.579406 0.713932 -v -0.035200 0.095566 0.105320 -vn 0.376620 0.364565 0.851616 -v -0.035200 0.095625 0.105284 -vn 0.657716 0.377398 -0.651905 -v -0.036500 0.095625 0.108316 -vn 0.393186 0.579418 -0.713919 -v -0.035200 0.095566 0.108280 -vn 0.406166 0.801281 -0.439293 -v -0.035200 0.094967 0.107645 -vn 0.660326 0.002348 -0.750976 -v -0.036500 0.096500 0.108550 -vn 0.394659 0.149700 -0.906550 -v -0.035200 0.096396 0.108547 -vn 0.380462 0.368053 -0.848402 -v -0.035200 0.095625 0.108316 -vn 0.660894 -0.378740 -0.647900 -v -0.036500 0.097375 0.108316 -vn 0.126319 -0.444736 -0.886709 -v -0.035200 0.097200 0.108404 -vn 0.388746 -0.076501 -0.918164 -v -0.035200 0.096500 0.108550 -vn 0.322669 -0.635244 -0.701676 -v -0.032200 0.097200 0.108404 -vn 0.352526 -0.505461 -0.787549 -v -0.032200 0.097375 0.108316 -vn 0.383269 -0.674646 -0.630838 -v -0.032200 0.097771 0.108003 -vn 0.274660 -0.808501 -0.520469 -v -0.032200 0.098016 0.107675 -vn 0.323530 -0.727338 -0.605234 -v -0.032200 0.098142 0.107404 -vn 0.770263 -0.552289 0.318860 -v -0.036500 0.097366 0.106300 -vn 0.770259 -0.637731 -0.000000 -v -0.036500 0.097500 0.106800 -vn 0.770263 -0.552289 -0.318860 -v -0.036500 0.097366 0.107300 -vn 0.770261 -0.318865 -0.552288 -v -0.036500 0.097000 0.107666 -vn 0.770262 0.000000 -0.637727 -v -0.036500 0.096500 0.107800 -vn 0.770261 0.318865 -0.552288 -v -0.036500 0.096000 0.107666 -vn 0.770261 0.552288 -0.318865 -v -0.036500 0.095634 0.107300 -vn 0.770262 0.637727 0.000000 -v -0.036500 0.095500 0.106800 -vn 0.770261 0.552288 0.318865 -v -0.036500 0.095634 0.106300 -vn 0.770263 0.318860 0.552289 -v -0.036500 0.096000 0.105934 -vn 0.770259 -0.000000 0.637731 -v -0.036500 0.096500 0.105800 -vn 0.770263 -0.318860 0.552289 -v -0.036500 0.097000 0.105934 -vn 0.660917 -0.750457 -0.001534 -v -0.036500 0.098250 0.127600 -vn 0.660949 -0.647847 0.378735 -v -0.036500 0.098016 0.126725 -vn 0.090476 -0.901114 0.424038 -v -0.035200 0.098104 0.126900 -vn 0.081890 -0.464700 0.881673 -v -0.035200 0.097344 0.126067 -vn 0.656889 -0.375510 0.653826 -v -0.036500 0.097375 0.126084 -vn 0.420612 0.009040 0.907195 -v -0.035200 0.096534 0.125850 -vn 0.653089 0.003253 0.757274 -v -0.036500 0.096500 0.125850 -vn 0.653676 0.375681 0.656941 -v -0.036500 0.095625 0.126084 -vn 0.656507 0.653207 0.377252 -v -0.036500 0.094984 0.126725 -vn 0.392624 0.715789 0.577488 -v -0.035200 0.095013 0.126678 -vn 0.406961 0.434093 0.803708 -v -0.035200 0.095664 0.126063 -vn 0.657037 0.753858 0.000056 -v -0.036500 0.094750 0.127600 -vn 0.393740 0.908509 0.139928 -v -0.035200 0.094751 0.127535 -vn 0.382810 0.850126 0.361582 -v -0.035200 0.094984 0.126725 -vn 0.657554 0.652475 -0.376696 -v -0.036500 0.094984 0.128475 -vn 0.393993 0.857609 -0.330569 -v -0.035200 0.094948 0.128409 -vn 0.380926 0.918052 -0.109888 -v -0.035200 0.094750 0.127600 -vn 0.658053 0.376457 -0.652109 -v -0.036500 0.095625 0.129116 -vn 0.394249 0.579412 -0.713337 -v -0.035200 0.095552 0.129071 -vn 0.379008 0.742046 -0.552919 -v -0.035200 0.094984 0.128475 -vn 0.658532 -0.000079 -0.752553 -v -0.036500 0.096500 0.129350 -vn 0.409676 0.129598 -0.902978 -v -0.035200 0.096404 0.129347 -vn 0.391924 0.379775 -0.837954 -v -0.035200 0.095625 0.129116 -vn 0.659005 -0.376173 -0.651311 -v -0.036500 0.097375 0.129116 -vn 0.394719 -0.322972 -0.860166 -v -0.035200 0.097281 0.129166 -vn 0.375101 -0.103449 -0.921193 -v -0.035200 0.096500 0.129350 -vn 0.659456 -0.651103 -0.375741 -v -0.036500 0.098016 0.128475 -vn 0.394950 -0.707999 -0.585450 -v -0.035200 0.097954 0.128574 -vn 0.373134 -0.548756 -0.748090 -v -0.035200 0.097375 0.129116 -vn 0.339310 -0.939543 0.046130 -v -0.035200 0.098250 0.127600 -vn 0.385324 -0.911942 -0.141020 -v -0.035200 0.098245 0.127727 -vn 0.371146 -0.849032 -0.376026 -v -0.035200 0.098016 0.128475 -vn 0.322188 -0.782879 0.532256 -v -0.032200 0.098104 0.126900 -vn 0.343792 -0.801454 0.489366 -v -0.032200 0.098016 0.126725 -vn 0.386044 -0.651025 0.653557 -v -0.032200 0.097771 0.126397 -vn 0.306506 -0.546591 0.779290 -v -0.032200 0.097375 0.126084 -vn 0.324451 -0.549399 0.769995 -v -0.032200 0.097344 0.126067 -vn 0.770261 -0.552292 0.318859 -v -0.036500 0.097366 0.127100 -vn 0.770261 -0.637729 0.000003 -v -0.036500 0.097500 0.127600 -vn 0.770261 -0.552293 -0.318857 -v -0.036500 0.097366 0.128100 -vn 0.770263 -0.318867 -0.552285 -v -0.036500 0.097000 0.128466 -vn 0.770262 0.000000 -0.637727 -v -0.036500 0.096500 0.128600 -vn 0.770263 0.318867 -0.552285 -v -0.036500 0.096000 0.128466 -vn 0.770259 0.552294 -0.318862 -v -0.036500 0.095634 0.128100 -vn 0.770264 0.637725 0.000002 -v -0.036500 0.095500 0.127600 -vn 0.770260 0.552291 0.318864 -v -0.036500 0.095634 0.127100 -vn 0.770263 0.318867 0.552285 -v -0.036500 0.096000 0.126734 -vn 0.770262 -0.000000 0.637727 -v -0.036500 0.096500 0.126600 -vn 0.770263 -0.318867 0.552285 -v -0.036500 0.097000 0.126734 -vn 0.301555 0.027691 0.953047 -v -0.035981 0.136000 0.130107 -vn 0.517907 0.028991 0.854946 -v -0.035750 0.136000 0.129999 -vn 0.709504 0.023710 0.704303 -v -0.035439 0.136000 0.129761 -vn 0.851021 0.021421 0.524695 -v -0.035201 0.136000 0.129450 -vn 0.951518 0.009601 0.307443 -v -0.035093 0.136000 0.129219 -vn 0.913756 0.381674 0.139196 -v -0.035008 0.136553 0.128809 -vn 0.817790 0.405540 0.408359 -v -0.035164 0.136562 0.129343 -vn 0.615728 0.417644 0.668171 -v -0.035494 0.136568 0.129778 -vn 0.322011 0.424827 0.846068 -v -0.035963 0.136572 0.130067 -vn 0.307945 0.026109 -0.951046 -v -0.035981 0.136000 0.104293 -vn 0.520713 0.026788 -0.853311 -v -0.035750 0.136000 0.104401 -vn 0.702639 0.023047 -0.711173 -v -0.035439 0.136000 0.104639 -vn 0.952564 0.010427 -0.304159 -v -0.035093 0.136000 0.105181 -vn 0.854007 0.020965 -0.519840 -v -0.035201 0.136000 0.104950 -vn 0.177909 0.446640 -0.876847 -v -0.036271 0.136550 0.104248 -vn 0.445569 0.445005 -0.776813 -v -0.035752 0.136547 0.104431 -vn 0.671641 0.437032 -0.598248 -v -0.035400 0.136543 0.104713 -vn 0.850367 0.422556 -0.313564 -v -0.035102 0.136534 0.105191 -vn 0.807279 0.466080 -0.362035 -v -0.034951 0.140250 0.109900 -vn 0.807282 0.466082 0.362027 -v -0.034951 0.140250 0.124500 -vn 0.466082 0.807278 -0.362035 -v -0.035500 0.140799 0.109900 -vn 0.466084 0.807281 0.362028 -v -0.035500 0.140799 0.124500 -vn 0.680956 0.732325 -0.000000 -v -0.035500 0.120400 0.117200 -vn 0.680957 0.711043 0.175257 -v -0.035500 0.120664 0.115022 -vn 0.680956 0.648441 0.340328 -v -0.035500 0.121442 0.112971 -vn 0.680956 0.548152 0.485621 -v -0.035500 0.122689 0.111166 -vn 0.680957 0.416008 0.602690 -v -0.035500 0.124331 0.109711 -vn 0.680956 0.259687 0.684735 -v -0.035500 0.126273 0.108691 -vn 0.680957 0.088272 0.726984 -v -0.035500 0.128403 0.108166 -vn 0.680957 -0.088271 0.726984 -v -0.035500 0.130597 0.108166 -vn 0.680956 -0.259686 0.684735 -v -0.035500 0.132727 0.108691 -vn 0.680956 -0.416009 0.602690 -v -0.035500 0.134669 0.109711 -vn 0.680957 -0.548152 0.485621 -v -0.035500 0.136311 0.111166 -vn 0.680956 -0.648441 0.340329 -v -0.035500 0.137558 0.112971 -vn 0.680957 -0.711043 0.175257 -v -0.035500 0.138336 0.115022 -vn 0.680956 -0.732325 -0.000000 -v -0.035500 0.138600 0.117200 -vn 0.680957 -0.711043 -0.175257 -v -0.035500 0.138336 0.119378 -vn 0.680955 -0.648441 -0.340329 -v -0.035500 0.137558 0.121429 -vn 0.680957 -0.548151 -0.485620 -v -0.035500 0.136311 0.123234 -vn 0.680956 -0.416009 -0.602691 -v -0.035500 0.134669 0.124689 -vn 0.680956 -0.259685 -0.684735 -v -0.035500 0.132727 0.125709 -vn 0.680956 -0.088271 -0.726985 -v -0.035500 0.130597 0.126234 -vn 0.680957 0.088272 -0.726984 -v -0.035500 0.128403 0.126234 -vn 0.680956 0.259686 -0.684735 -v -0.035500 0.126273 0.125709 -vn 0.680956 0.416008 -0.602690 -v -0.035500 0.124331 0.124689 -vn 0.680957 0.548152 -0.485620 -v -0.035500 0.122689 0.123234 -vn 0.680956 0.648441 -0.340328 -v -0.035500 0.121442 0.121429 -vn 0.680957 0.711043 -0.175257 -v -0.035500 0.120664 0.119378 -vn 0.740587 -0.440041 0.507834 -v -0.035500 0.125112 0.122264 -vn 0.740586 -0.565290 0.363289 -v -0.035500 0.123864 0.120822 -vn 0.740587 -0.644742 0.189313 -v -0.035500 0.123071 0.119088 -vn 0.740586 -0.671961 0.000000 -v -0.035500 0.122800 0.117200 -vn 0.740587 -0.644742 -0.189313 -v -0.035500 0.123071 0.115312 -vn 0.740586 -0.565291 -0.363289 -v -0.035500 0.123864 0.113578 -vn 0.740586 0.565290 0.363289 -v -0.035500 0.135136 0.120822 -vn 0.740587 0.440041 0.507833 -v -0.035500 0.133888 0.122264 -vn 0.740586 0.279142 0.611238 -v -0.035500 0.132283 0.123295 -vn 0.740586 0.095630 0.665122 -v -0.035500 0.130453 0.123832 -vn 0.740587 -0.095629 0.665121 -v -0.035500 0.128546 0.123832 -vn 0.740586 -0.279142 0.611238 -v -0.035500 0.126717 0.123295 -vn 0.740587 -0.440041 -0.507833 -v -0.035500 0.125112 0.112136 -vn 0.740586 -0.279142 -0.611238 -v -0.035500 0.126717 0.111105 -vn 0.740587 -0.095629 -0.665121 -v -0.035500 0.128546 0.110568 -vn 0.740586 0.095630 -0.665122 -v -0.035500 0.130453 0.110568 -vn 0.740586 0.279142 -0.611238 -v -0.035500 0.132283 0.111105 -vn 0.740587 0.440041 -0.507833 -v -0.035500 0.133888 0.112136 -vn 0.740586 0.565291 -0.363289 -v -0.035500 0.135136 0.113578 -vn 0.740587 0.644742 -0.189313 -v -0.035500 0.135929 0.115312 -vn 0.740586 0.671961 0.000000 -v -0.035500 0.136200 0.117200 -vn 0.740587 0.644742 0.189313 -v -0.035500 0.135929 0.119088 -vn 0.676434 -0.736503 0.000000 -v -0.034750 0.122800 0.117200 -vn 0.676433 -0.706670 -0.207497 -v -0.034750 0.123071 0.115312 -vn 0.676434 -0.619586 -0.398182 -v -0.034750 0.123864 0.113578 -vn 0.676433 -0.482309 -0.556612 -v -0.034750 0.125112 0.112136 -vn 0.676434 -0.305953 -0.669947 -v -0.034750 0.126717 0.111105 -vn 0.676434 -0.104815 -0.729007 -v -0.034750 0.128546 0.110568 -vn 0.676434 0.104815 -0.729007 -v -0.034750 0.130453 0.110568 -vn 0.676434 0.305954 -0.669947 -v -0.034750 0.132283 0.111105 -vn 0.676433 0.482309 -0.556612 -v -0.034750 0.133888 0.112136 -vn 0.676434 0.619586 -0.398182 -v -0.034750 0.135136 0.113578 -vn 0.676433 0.706670 -0.207497 -v -0.034750 0.135929 0.115312 -vn 0.676434 0.736503 0.000000 -v -0.034750 0.136200 0.117200 -vn 0.676434 0.706670 0.207497 -v -0.034750 0.135929 0.119088 -vn 0.676434 0.619587 0.398183 -v -0.034750 0.135136 0.120822 -vn 0.676433 0.482308 0.556612 -v -0.034750 0.133888 0.122264 -vn 0.676434 0.305954 0.669947 -v -0.034750 0.132283 0.123295 -vn 0.676434 0.104815 0.729007 -v -0.034750 0.130453 0.123832 -vn 0.676434 -0.104815 0.729007 -v -0.034750 0.128546 0.123832 -vn 0.676434 -0.305953 0.669947 -v -0.034750 0.126717 0.123295 -vn 0.676433 -0.482308 0.556612 -v -0.034750 0.125112 0.122264 -vn 0.676434 -0.619587 0.398183 -v -0.034750 0.123864 0.120822 -vn 0.676434 -0.706670 0.207497 -v -0.034750 0.123071 0.119088 -vn 0.746099 0.163454 -0.645460 -v -0.034750 0.128334 0.121805 -vn 0.746099 0.364179 -0.557414 -v -0.034750 0.126902 0.121177 -vn 0.746098 0.525437 -0.408967 -v -0.034750 0.125752 0.120118 -vn 0.746101 0.629757 -0.216194 -v -0.034750 0.125007 0.118742 -vn 0.746096 0.665838 -0.000000 -v -0.034750 0.124750 0.117200 -vn 0.746101 0.629757 0.216193 -v -0.034750 0.125007 0.115658 -vn 0.746098 0.525437 0.408966 -v -0.034750 0.125752 0.114282 -vn 0.746099 0.364178 0.557414 -v -0.034750 0.126902 0.113223 -vn 0.746099 -0.656754 -0.109592 -v -0.034750 0.134185 0.117982 -vn 0.746099 -0.585586 -0.316901 -v -0.034750 0.133677 0.119461 -vn 0.746099 -0.450959 -0.489870 -v -0.034750 0.132717 0.120695 -vn 0.746100 -0.267461 -0.609754 -v -0.034750 0.131408 0.121550 -vn 0.746098 -0.054984 -0.663562 -v -0.034750 0.129892 0.121934 -vn 0.746098 0.163454 0.645461 -v -0.034750 0.128334 0.112595 -vn 0.746099 -0.054984 0.663561 -v -0.034750 0.129892 0.112466 -vn 0.746099 -0.267463 0.609754 -v -0.034750 0.131408 0.112850 -vn 0.746099 -0.450958 0.489871 -v -0.034750 0.132717 0.113705 -vn 0.746099 -0.585585 0.316902 -v -0.034750 0.133677 0.114939 -vn 0.746099 -0.656754 0.109592 -v -0.034750 0.134185 0.116418 -vn 0.671870 0.740669 0.000000 -v -0.037250 0.124750 0.117200 -vn 0.671867 0.700541 0.240493 -v -0.037250 0.125007 0.115658 -vn 0.671869 0.584492 0.454930 -v -0.037250 0.125752 0.114282 -vn 0.671868 0.405109 0.620065 -v -0.037250 0.126902 0.113223 -vn 0.671869 0.181824 0.718006 -v -0.037250 0.128334 0.112595 -vn 0.671868 -0.061164 0.738141 -v -0.037250 0.129892 0.112466 -vn 0.671869 -0.297524 0.678286 -v -0.037250 0.131408 0.112850 -vn 0.671869 -0.501643 0.544929 -v -0.037250 0.132717 0.113705 -vn 0.671868 -0.651401 0.352519 -v -0.037250 0.133677 0.114939 -vn 0.671869 -0.730569 0.121910 -v -0.037250 0.134185 0.116418 -vn 0.671869 -0.730569 -0.121910 -v -0.037250 0.134185 0.117982 -vn 0.671869 -0.651401 -0.352518 -v -0.037250 0.133677 0.119461 -vn 0.671868 -0.501644 -0.544928 -v -0.037250 0.132717 0.120695 -vn 0.671868 -0.297523 -0.678287 -v -0.037250 0.131408 0.121550 -vn 0.671869 -0.061164 -0.738140 -v -0.037250 0.129892 0.121934 -vn 0.671868 0.181824 -0.718006 -v -0.037250 0.128334 0.121805 -vn 0.671868 0.405110 -0.620063 -v -0.037250 0.126902 0.121177 -vn 0.671869 0.584491 -0.454931 -v -0.037250 0.125752 0.120118 -vn 0.671866 0.700541 -0.240494 -v -0.037250 0.125007 0.118742 -vn 1.000000 0.000000 -0.000000 -v -0.037250 0.129500 0.117200 -vn -0.770263 0.552286 -0.318865 -v -0.067000 0.113667 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.067000 0.113500 0.130700 -vn -0.923880 0.000000 0.382683 -v -0.067000 0.112250 0.132200 -vn -0.987814 -0.110052 0.110052 -v -0.067000 0.117500 0.107400 -vn -0.923877 -0.382689 0.000000 -v -0.067000 0.117500 0.108075 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.108075 -vn -0.991004 0.005386 -0.133727 -v -0.067000 0.136000 0.105200 -vn -0.997001 0.041899 -0.065066 -v -0.067000 0.127500 0.105200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.129700 0.107300 -vn -0.973781 0.131340 -0.185743 -v -0.067000 0.126000 0.104200 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.126000 0.102325 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.102325 -vn -0.973781 -0.131340 0.185743 -v -0.067000 0.095500 0.130200 -vn -0.717284 -0.630262 0.297109 -v -0.067000 0.095500 0.132200 -vn -0.923880 0.000000 0.382683 -v -0.067000 0.095875 0.132200 -vn -0.945441 0.162894 -0.282148 -v -0.067000 0.136500 0.112066 -vn -0.736823 0.642996 -0.208921 -v -0.067000 0.134636 0.115531 -vn -0.945447 0.000002 -0.325776 -v -0.067000 0.137000 0.112200 -vn -0.736825 0.676083 -0.000000 -v -0.067000 0.134900 0.117200 -vn -0.945446 -0.162891 -0.282132 -v -0.067000 0.137500 0.112066 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.129700 0.108075 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.129700 0.111125 -vn -0.945436 0.325809 -0.000004 -v -0.067000 0.136000 0.111200 -vn -0.945448 0.282126 0.162887 -v -0.067000 0.136134 0.110700 -vn -0.945446 0.162887 0.282135 -v -0.067000 0.136500 0.110334 -vn -0.990580 0.130231 -0.042315 -v -0.067000 0.139804 0.107964 -vn -0.945442 0.000003 0.325792 -v -0.067000 0.137000 0.110200 -vn -0.945451 -0.162885 0.282119 -v -0.067000 0.137500 0.110334 -vn -0.945439 -0.282150 -0.162897 -v -0.067000 0.137866 0.111700 -vn -0.991444 0.130529 0.000000 -v -0.067000 0.140000 0.117200 -vn -0.945446 -0.325778 -0.000003 -v -0.067000 0.138000 0.111200 -vn -0.991444 0.130529 0.000000 -v -0.067000 0.140000 0.111125 -vn -0.945440 -0.282146 0.162903 -v -0.067000 0.137866 0.110700 -vn -0.991003 0.133729 -0.005386 -v -0.067000 0.140000 0.109200 -vn -0.990580 0.135247 -0.021421 -v -0.067000 0.139951 0.108574 -vn -0.770261 0.318867 -0.552288 -v -0.067000 0.122125 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.067000 0.121667 0.104325 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 0.119500 0.104200 -vn -0.770261 0.637728 0.000000 -v -0.067000 0.121500 0.103700 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.119500 0.102325 -vn -0.770262 0.552289 0.318863 -v -0.067000 0.121667 0.103075 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.102325 -vn -0.770262 0.318863 0.552289 -v -0.067000 0.122125 0.102617 -vn -0.770261 -0.000000 0.637728 -v -0.067000 0.122750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.067000 0.123375 0.102617 -vn -0.770262 -0.552289 0.318863 -v -0.067000 0.123833 0.103075 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 0.122750 0.104950 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.107300 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 0.123375 0.104783 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.107300 -vn -0.770262 -0.552289 -0.318863 -v -0.067000 0.123833 0.104325 -vn -0.770261 -0.637728 -0.000000 -v -0.067000 0.124000 0.103700 -vn -0.770262 0.318868 -0.552286 -v -0.067000 0.106125 0.104783 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 0.103500 0.104200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.107300 -vn -0.770260 0.318870 -0.552288 -v -0.067000 0.103850 0.107240 -vn -0.770260 0.552288 -0.318870 -v -0.067000 0.103960 0.107350 -vn -0.770260 0.552291 -0.318865 -v -0.067000 0.105667 0.104325 -vn -0.770264 0.637725 -0.000000 -v -0.067000 0.105500 0.103700 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.103500 0.102325 -vn -0.770260 0.552291 0.318865 -v -0.067000 0.105667 0.103075 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.102325 -vn -0.973781 0.131340 -0.185743 -v -0.067000 0.110000 0.104200 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.110000 0.102325 -vn -0.770262 -0.552289 0.318863 -v -0.067000 0.107833 0.103075 -vn -0.770261 -0.637728 -0.000000 -v -0.067000 0.108000 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.067000 0.107833 0.104325 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.107300 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 0.107375 0.104783 -vn -0.770264 -0.000001 -0.637726 -v -0.067000 0.106750 0.104950 -vn -0.770264 0.318864 0.552286 -v -0.067000 0.106125 0.102617 -vn -0.770261 -0.000001 0.637729 -v -0.067000 0.106750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.067000 0.107375 0.102617 -vn -0.770264 -0.637725 0.000000 -v -0.067000 0.094750 0.109200 -vn -0.770260 -0.552291 -0.318865 -v -0.067000 0.094583 0.109825 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.111125 -vn -0.770263 -0.318865 -0.552286 -v -0.067000 0.094125 0.110283 -vn -0.770261 -0.000001 -0.637729 -v -0.067000 0.093500 0.110450 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.092000 0.111125 -vn -0.770263 0.318864 -0.552286 -v -0.067000 0.092875 0.110283 -vn -0.770260 0.552291 -0.318865 -v -0.067000 0.092417 0.109825 -vn -0.770264 0.637725 -0.000000 -v -0.067000 0.092250 0.109200 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.092000 0.108075 -vn -0.770260 0.552291 0.318865 -v -0.067000 0.092417 0.108575 -vn -0.770264 0.318864 0.552286 -v -0.067000 0.092875 0.108117 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.092000 0.107300 -vn -0.770261 -0.000001 0.637729 -v -0.067000 0.093500 0.107950 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.107300 -vn -0.770263 -0.318865 0.552286 -v -0.067000 0.094125 0.108117 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.108075 -vn -0.770260 -0.552291 0.318865 -v -0.067000 0.094583 0.108575 -vn -0.923880 0.000000 0.382683 -v -0.067000 0.116750 0.132200 -vn -0.717284 0.630262 0.297109 -v -0.067000 0.118000 0.132200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.128325 -vn -0.973781 0.131340 0.185743 -v -0.067000 0.118000 0.130200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.128325 -vn -0.973781 -0.131340 0.185743 -v -0.067000 0.119500 0.130200 -vn -0.770264 0.552286 0.318863 -v -0.067000 0.121667 0.130075 -vn -0.770260 0.318865 0.552291 -v -0.067000 0.122125 0.129617 -vn -0.770264 0.000000 0.637725 -v -0.067000 0.122750 0.129450 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.128325 -vn -0.923880 0.000000 0.382683 -v -0.067000 0.124050 0.132200 -vn -0.770261 -0.637729 -0.000002 -v -0.067000 0.124000 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.067000 0.123833 0.131325 -vn -0.770260 -0.318865 0.552291 -v -0.067000 0.123375 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.067000 0.123833 0.130075 -vn -0.770260 -0.318865 -0.552291 -v -0.067000 0.123375 0.131783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 0.122750 0.131950 -vn -0.923880 0.000000 0.382683 -v -0.067000 0.122000 0.132200 -vn -0.770260 0.318865 -0.552291 -v -0.067000 0.122125 0.131783 -vn -0.717284 -0.630262 0.297109 -v -0.067000 0.119500 0.132200 -vn -0.770263 0.552286 -0.318865 -v -0.067000 0.121667 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.067000 0.121500 0.130700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.102000 0.128325 -vn -0.973781 0.131340 0.185743 -v -0.067000 0.102000 0.130200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.128325 -vn -0.973781 -0.131340 0.185743 -v -0.067000 0.103500 0.130200 -vn -0.770261 0.552288 0.318865 -v -0.067000 0.105667 0.130075 -vn -0.770263 -0.552286 -0.318865 -v -0.067000 0.107833 0.131325 -vn -0.717284 0.630262 0.297109 -v -0.067000 0.110000 0.132200 -vn -0.770261 -0.637729 -0.000002 -v -0.067000 0.108000 0.130700 -vn -0.973781 0.131340 0.185743 -v -0.067000 0.110000 0.130200 -vn -0.770264 -0.552286 0.318863 -v -0.067000 0.107833 0.130075 -vn -0.770260 -0.318865 -0.552291 -v -0.067000 0.107375 0.131783 -vn -0.770264 -0.000001 -0.637726 -v -0.067000 0.106750 0.131950 -vn -0.923880 0.000000 0.382683 -v -0.067000 0.106250 0.132200 -vn -0.770261 0.318866 -0.552288 -v -0.067000 0.106125 0.131783 -vn -0.717284 -0.630262 0.297109 -v -0.067000 0.103500 0.132200 -vn -0.770261 0.552288 -0.318867 -v -0.067000 0.105667 0.131325 -vn -0.770263 0.637726 -0.000002 -v -0.067000 0.105500 0.130700 -vn -0.770260 -0.318865 0.552291 -v -0.067000 0.107375 0.129617 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.128325 -vn -0.770264 -0.000001 0.637726 -v -0.067000 0.106750 0.129450 -vn -0.770261 0.318866 0.552288 -v -0.067000 0.106125 0.129617 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.127100 -vn -0.770264 -0.552289 0.318858 -v -0.067000 0.097040 0.127050 -vn -0.737698 -0.669355 0.088117 -v -0.067000 0.097000 0.126900 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.123275 -vn -0.770258 0.552288 0.318874 -v -0.067000 0.103960 0.127050 -vn -0.770266 0.318854 0.552289 -v -0.067000 0.103850 0.127160 -vn -0.737697 0.088113 0.669358 -v -0.067000 0.103700 0.127200 -vn -0.707107 0.000000 0.707107 -v -0.067000 0.102000 0.127200 -vn -0.737697 -0.088113 0.669358 -v -0.067000 0.097300 0.127200 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.104000 0.123275 -vn -0.737704 0.669347 0.088131 -v -0.067000 0.104000 0.126900 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.127100 -vn -0.707107 0.000000 -0.707107 -v -0.067000 0.102000 0.121200 -vn -0.737697 0.088113 -0.669358 -v -0.067000 0.103700 0.121200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.117200 -vn -0.770266 0.318854 -0.552289 -v -0.067000 0.103850 0.121240 -vn -0.770260 0.552288 -0.318870 -v -0.067000 0.103960 0.121350 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.121700 -vn -0.737702 0.669350 -0.088128 -v -0.067000 0.104000 0.121500 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.097000 0.123275 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.097000 0.121700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.121700 -vn -0.737697 -0.669358 -0.088113 -v -0.067000 0.097000 0.121500 -vn -0.717284 -0.630262 0.297109 -v -0.067000 0.111500 0.132200 -vn -0.973781 -0.131340 0.185743 -v -0.067000 0.111500 0.130200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.128325 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.092000 0.128325 -vn -0.717284 -0.297109 0.630262 -v -0.067000 0.092000 0.128450 -vn -0.973781 -0.185743 0.131340 -v -0.067000 0.094000 0.128450 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.128325 -vn -0.816496 -0.408249 0.408249 -v -0.067000 0.094000 0.130200 -vn -0.717284 -0.297109 -0.630262 -v -0.067000 0.092000 0.121950 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.092000 0.123275 -vn -0.973781 -0.185743 -0.131340 -v -0.067000 0.094000 0.121950 -vn -0.923879 -0.382685 0.000000 -v -0.067000 0.094000 0.121700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.117200 -vn -0.770266 -0.552289 -0.318854 -v -0.067000 0.097040 0.121350 -vn -0.717284 -0.297109 0.630262 -v -0.067000 0.092000 0.112450 -vn -0.973781 -0.185743 0.131340 -v -0.067000 0.094000 0.112450 -vn -0.923879 -0.382685 0.000000 -v -0.067000 0.094000 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.095875 0.102325 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.095500 0.102325 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 0.095500 0.104200 -vn -0.717284 -0.297109 -0.630262 -v -0.067000 0.092000 0.105950 -vn -0.973781 -0.185743 -0.131340 -v -0.067000 0.094000 0.105950 -vn -0.816496 -0.408249 -0.408249 -v -0.067000 0.094000 0.104200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.102325 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.111500 0.102325 -vn -0.973781 -0.131340 -0.185743 -v -0.067000 0.111500 0.104200 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 0.111500 0.102200 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.112250 0.102200 -vn -0.923880 0.000000 -0.382684 -v -0.067000 0.116750 0.102200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.107300 -vn -0.973781 0.131340 -0.185743 -v -0.067000 0.118000 0.104200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.102325 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.118000 0.102325 -vn -0.717284 0.630262 -0.297109 -v -0.067000 0.118000 0.102200 -vn -0.717283 0.630262 -0.297110 -v -0.067000 0.127500 0.104200 -vn -0.990580 0.122007 -0.062166 -v -0.067000 0.139564 0.107384 -vn -0.990581 0.110780 -0.080486 -v -0.067000 0.139236 0.106849 -vn -0.990581 0.021420 -0.135245 -v -0.067000 0.136626 0.105249 -vn -0.990580 0.042314 -0.130231 -v -0.067000 0.137236 0.105396 -vn -0.990581 0.096825 -0.096825 -v -0.067000 0.138828 0.106372 -vn -0.990580 0.080487 -0.110780 -v -0.067000 0.138351 0.105964 -vn -0.990580 0.062167 -0.122008 -v -0.067000 0.137816 0.105636 -vn -0.945436 0.325809 -0.000004 -v -0.067000 0.136000 0.123200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.129700 0.123275 -vn -0.945449 0.282127 -0.162882 -v -0.067000 0.136134 0.123700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.129700 0.127100 -vn -0.945445 0.162889 -0.282137 -v -0.067000 0.136500 0.124066 -vn -0.945448 0.000000 -0.325774 -v -0.067000 0.137000 0.124200 -vn -0.990580 0.080486 0.110781 -v -0.067000 0.138351 0.128436 -vn -0.990581 0.096825 0.096823 -v -0.067000 0.138828 0.128028 -vn -0.945450 -0.162883 -0.282123 -v -0.067000 0.137500 0.124066 -vn -0.990580 0.122008 0.062167 -v -0.067000 0.139564 0.127016 -vn -0.990580 0.110780 0.080486 -v -0.067000 0.139236 0.127551 -vn -0.991004 0.005386 0.133725 -v -0.067000 0.136000 0.129200 -vn -0.990581 0.021421 0.135244 -v -0.067000 0.136626 0.129151 -vn -0.990580 0.042314 0.130231 -v -0.067000 0.137236 0.129004 -vn -0.717284 0.630262 0.297109 -v -0.067000 0.126000 0.132200 -vn -0.973781 0.131340 0.185743 -v -0.067000 0.126000 0.130200 -vn -0.717283 0.630262 0.297110 -v -0.067000 0.127500 0.130200 -vn -0.997001 0.041898 0.065065 -v -0.067000 0.127500 0.129200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.129700 0.128325 -vn -0.973781 0.131340 -0.185743 -v -0.067000 0.102000 0.104200 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.102000 0.102325 -vn -0.770262 -0.552289 0.318863 -v -0.067000 0.099833 0.103075 -vn -0.770261 -0.637728 -0.000000 -v -0.067000 0.100000 0.103700 -vn -0.707107 0.000000 -0.707107 -v -0.067000 0.102000 0.107200 -vn -0.737703 0.088127 -0.669349 -v -0.067000 0.103700 0.107200 -vn -0.770262 -0.552289 -0.318863 -v -0.067000 0.099833 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 0.099375 0.104783 -vn -0.737702 -0.088128 -0.669350 -v -0.067000 0.097300 0.107200 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 0.098750 0.104950 -vn -0.770260 -0.318870 -0.552288 -v -0.067000 0.097150 0.107240 -vn -0.770261 0.318867 -0.552288 -v -0.067000 0.098125 0.104783 -vn -0.770261 0.552288 -0.318867 -v -0.067000 0.097667 0.104325 -vn -0.770264 0.637725 -0.000000 -v -0.067000 0.097500 0.103700 -vn -0.770261 0.552288 0.318867 -v -0.067000 0.097667 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.067000 0.098125 0.102617 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.097250 0.102325 -vn -0.770261 -0.000000 0.637728 -v -0.067000 0.098750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.067000 0.099375 0.102617 -vn -0.770266 -0.552289 -0.318854 -v -0.067000 0.097040 0.107350 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.097000 0.108075 -vn -0.737697 -0.669358 -0.088113 -v -0.067000 0.097000 0.107500 -vn -0.737703 -0.088127 0.669349 -v -0.067000 0.097300 0.113200 -vn -0.770260 -0.318870 0.552288 -v -0.067000 0.097150 0.113160 -vn -0.770266 -0.552289 0.318854 -v -0.067000 0.097040 0.113050 -vn -0.737697 -0.669358 0.088113 -v -0.067000 0.097000 0.112900 -vn -0.707107 -0.707107 0.000000 -v -0.067000 0.097000 0.111125 -vn -0.737702 0.088128 0.669350 -v -0.067000 0.103700 0.113200 -vn -0.707107 0.000000 0.707107 -v -0.067000 0.102000 0.113200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.102000 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.097250 0.117200 -vn -0.770266 -0.318854 -0.552289 -v -0.067000 0.097150 0.121240 -vn -0.770260 0.318870 0.552288 -v -0.067000 0.103850 0.113160 -vn -0.737697 -0.088113 -0.669358 -v -0.067000 0.097300 0.121200 -vn -0.737702 0.669350 -0.088128 -v -0.067000 0.104000 0.107500 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.104000 0.108075 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.108075 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.104000 0.111125 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.111125 -vn -0.737703 0.669349 0.088127 -v -0.067000 0.104000 0.112900 -vn -0.770260 0.552288 0.318870 -v -0.067000 0.103960 0.113050 -vn -0.973781 -0.185742 0.131340 -v -0.067000 0.117500 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.121700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.123275 -vn -0.923880 0.382683 0.000000 -v -0.067000 0.111000 0.123275 -vn -0.923880 0.382683 0.000000 -v -0.067000 0.111000 0.121700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.127100 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.112250 0.127000 -vn -0.987814 0.110051 -0.110052 -v -0.067000 0.111000 0.127000 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.127100 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.116750 0.127000 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.127100 -vn -0.987814 -0.110051 -0.110052 -v -0.067000 0.117500 0.127000 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.111125 -vn -0.923880 -0.382683 -0.000000 -v -0.067000 0.117500 0.111125 -vn -0.973781 -0.185742 -0.131340 -v -0.067000 0.117500 0.116700 -vn -0.707107 0.000000 -0.707107 -v -0.067000 0.116750 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.117200 -vn -0.707107 0.000000 -0.707107 -v -0.067000 0.112250 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.117200 -vn -0.973781 0.185743 -0.131340 -v -0.067000 0.111000 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.111125 -vn -0.923880 0.382683 -0.000000 -v -0.067000 0.111000 0.111125 -vn -0.923877 0.382689 0.000000 -v -0.067000 0.111000 0.108075 -vn -0.736825 -0.546963 -0.397391 -v -0.067000 0.125131 0.114026 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.111125 -vn -0.736824 -0.642996 -0.208921 -v -0.067000 0.124364 0.115531 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.117200 -vn -0.736823 -0.397393 -0.546965 -v -0.067000 0.126326 0.112831 -vn -0.736824 -0.208922 -0.642995 -v -0.067000 0.127831 0.112064 -vn -0.736824 0.000000 -0.676085 -v -0.067000 0.129500 0.111800 -vn -0.736824 0.208922 -0.642995 -v -0.067000 0.131169 0.112064 -vn -0.945449 0.282128 -0.162881 -v -0.067000 0.136134 0.111700 -vn -0.736823 0.397393 -0.546965 -v -0.067000 0.132674 0.112831 -vn -0.736825 0.546964 -0.397392 -v -0.067000 0.133869 0.114026 -vn -0.736824 -0.397392 0.546965 -v -0.067000 0.126326 0.121569 -vn -0.736824 -0.546964 0.397391 -v -0.067000 0.125131 0.120374 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.121700 -vn -0.736824 -0.642995 0.208921 -v -0.067000 0.124364 0.118869 -vn -0.736824 -0.676085 0.000000 -v -0.067000 0.124100 0.117200 -vn -0.945445 0.162889 0.282136 -v -0.067000 0.136500 0.122334 -vn -0.945447 0.000001 0.325775 -v -0.067000 0.137000 0.122200 -vn -0.736824 0.397392 0.546965 -v -0.067000 0.132674 0.121569 -vn -0.991444 0.130529 0.000000 -v -0.067000 0.140000 0.121700 -vn -0.736824 0.546965 0.397392 -v -0.067000 0.133869 0.120374 -vn -0.736823 -0.208921 0.642996 -v -0.067000 0.127831 0.122336 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.123275 -vn -0.736824 0.000000 0.676085 -v -0.067000 0.129500 0.122600 -vn -0.736823 0.208921 0.642996 -v -0.067000 0.131169 0.122336 -vn -0.945448 0.282126 0.162887 -v -0.067000 0.136134 0.122700 -vn -0.990580 0.130231 0.042315 -v -0.067000 0.139804 0.126436 -vn -0.990580 0.135247 0.021421 -v -0.067000 0.139951 0.125826 -vn -0.945439 -0.282150 -0.162897 -v -0.067000 0.137866 0.123700 -vn -0.991003 0.133729 0.005386 -v -0.067000 0.140000 0.125200 -vn -0.945446 -0.325778 -0.000003 -v -0.067000 0.138000 0.123200 -vn -0.991444 0.130529 0.000000 -v -0.067000 0.140000 0.123275 -vn -0.945440 -0.282146 0.162903 -v -0.067000 0.137866 0.122700 -vn -0.945451 -0.162886 0.282118 -v -0.067000 0.137500 0.122334 -vn -0.736823 0.642995 0.208922 -v -0.067000 0.134636 0.118869 -vn -0.945442 0.325792 -0.000002 -v -0.067000 0.122500 0.109200 -vn -0.945448 0.282126 0.162887 -v -0.067000 0.122634 0.108700 -vn -0.945445 0.162889 -0.282137 -v -0.067000 0.123000 0.110066 -vn -0.945449 0.282127 -0.162884 -v -0.067000 0.122634 0.109700 -vn -0.945447 -0.325776 -0.000001 -v -0.067000 0.124500 0.109200 -vn -0.945444 -0.282138 -0.162893 -v -0.067000 0.124366 0.109700 -vn -0.945448 -0.162886 -0.282129 -v -0.067000 0.124000 0.110066 -vn -0.945448 0.000000 -0.325774 -v -0.067000 0.123500 0.110200 -vn -0.945441 0.162897 0.282145 -v -0.067000 0.123000 0.108334 -vn -0.945447 -0.000001 0.325776 -v -0.067000 0.123500 0.108200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.108075 -vn -0.945444 -0.162893 0.282138 -v -0.067000 0.124000 0.108334 -vn -0.945443 -0.282139 0.162894 -v -0.067000 0.124366 0.108700 -vn -0.945448 0.282126 0.162888 -v -0.067000 0.122634 0.124700 -vn -0.945441 0.162897 0.282145 -v -0.067000 0.123000 0.124334 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.123275 -vn -0.945442 0.325791 -0.000002 -v -0.067000 0.122500 0.125200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.124050 0.127100 -vn -0.945448 0.000000 -0.325774 -v -0.067000 0.123500 0.126200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.122000 0.127100 -vn -0.945445 0.162889 -0.282135 -v -0.067000 0.123000 0.126066 -vn -0.945446 0.282135 -0.162887 -v -0.067000 0.122634 0.125700 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.117500 0.123275 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.117500 0.121700 -vn -0.945441 -0.282148 -0.162894 -v -0.067000 0.124366 0.125700 -vn -0.945448 -0.162886 -0.282129 -v -0.067000 0.124000 0.126066 -vn -0.945447 -0.000001 0.325776 -v -0.067000 0.123500 0.124200 -vn -0.945444 -0.162893 0.282138 -v -0.067000 0.124000 0.124334 -vn -0.945443 -0.282139 0.162895 -v -0.067000 0.124366 0.124700 -vn -0.945447 -0.325775 -0.000001 -v -0.067000 0.124500 0.125200 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 0.119500 0.102200 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.122000 0.102200 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.124050 0.102200 -vn -0.717284 0.630263 -0.297109 -v -0.067000 0.126000 0.102200 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 0.103500 0.102200 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.106250 0.102200 -vn -0.717284 0.630262 -0.297109 -v -0.067000 0.110000 0.102200 -vn -0.717284 -0.630262 -0.297109 -v -0.067000 0.095500 0.102200 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.095875 0.102200 -vn -0.923880 0.000000 -0.382683 -v -0.067000 0.097250 0.102200 -vn -0.717284 0.630263 -0.297109 -v -0.067000 0.102000 0.102200 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.107300 -vn -0.770262 0.552289 -0.318863 -v -0.067000 0.113667 0.104325 -vn -0.770261 0.637728 0.000000 -v -0.067000 0.113500 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.067000 0.113667 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.067000 0.114125 0.102617 -vn -0.770261 -0.000000 0.637729 -v -0.067000 0.114750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.067000 0.115375 0.102617 -vn -0.770262 -0.552289 -0.318863 -v -0.067000 0.115833 0.104325 -vn -0.770261 -0.637728 -0.000000 -v -0.067000 0.116000 0.103700 -vn -0.770262 -0.552289 0.318863 -v -0.067000 0.115833 0.103075 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 0.115375 0.104783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 0.114750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.067000 0.114125 0.104783 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.108075 -vn -0.945447 0.325776 0.000001 -v -0.067000 0.107000 0.109200 -vn -0.945444 0.282138 0.162893 -v -0.067000 0.107134 0.108700 -vn -0.945448 -0.282129 0.162884 -v -0.067000 0.108866 0.108700 -vn -0.945442 -0.325792 0.000002 -v -0.067000 0.109000 0.109200 -vn -0.945443 0.162894 0.282139 -v -0.067000 0.107500 0.108334 -vn -0.945447 -0.000001 0.325776 -v -0.067000 0.108000 0.108200 -vn -0.945444 -0.162893 0.282138 -v -0.067000 0.108500 0.108334 -vn -0.987814 0.110052 0.110052 -v -0.067000 0.111000 0.107400 -vn -0.923877 0.000000 0.382689 -v -0.067000 0.112250 0.107400 -vn -0.923877 0.000000 0.382689 -v -0.067000 0.116750 0.107400 -vn -0.945448 -0.282128 -0.162887 -v -0.067000 0.108866 0.109700 -vn -0.945448 -0.162887 -0.282128 -v -0.067000 0.108500 0.110066 -vn -0.945448 -0.000000 -0.325775 -v -0.067000 0.108000 0.110200 -vn -0.945444 0.282137 -0.162895 -v -0.067000 0.107134 0.109700 -vn -0.945448 0.162887 -0.282128 -v -0.067000 0.107500 0.110066 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.106250 0.123275 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.110000 0.121700 -vn -0.973781 0.185742 0.131340 -v -0.067000 0.111000 0.117700 -vn -0.707107 0.000000 0.707107 -v -0.067000 0.112250 0.117700 -vn -0.707107 0.000000 0.707107 -v -0.067000 0.116750 0.117700 -vn -0.945447 0.325776 0.000002 -v -0.067000 0.107000 0.125200 -vn -0.945444 0.282138 0.162893 -v -0.067000 0.107134 0.124700 -vn -0.945441 0.282145 -0.162897 -v -0.067000 0.107134 0.125700 -vn -0.707107 0.707107 0.000000 -v -0.067000 0.104000 0.121700 -vn -0.945444 -0.162893 0.282138 -v -0.067000 0.108500 0.124334 -vn -0.945447 -0.000001 0.325776 -v -0.067000 0.108000 0.124200 -vn -0.945443 0.162894 0.282139 -v -0.067000 0.107500 0.124334 -vn -0.945448 -0.282129 0.162884 -v -0.067000 0.108866 0.124700 -vn -0.945442 -0.325791 0.000002 -v -0.067000 0.109000 0.125200 -vn -0.945445 -0.282137 -0.162888 -v -0.067000 0.108866 0.125700 -vn -0.945448 -0.162887 -0.282127 -v -0.067000 0.108500 0.126066 -vn -0.945448 -0.000000 -0.325775 -v -0.067000 0.108000 0.126200 -vn -0.945448 0.162888 -0.282126 -v -0.067000 0.107500 0.126066 -vn -0.770261 0.552288 0.318867 -v -0.067000 0.092417 0.124575 -vn -0.770264 0.637725 -0.000000 -v -0.067000 0.092250 0.125200 -vn -0.923880 -0.382683 0.000000 -v -0.067000 0.092000 0.127100 -vn -0.770261 0.552288 -0.318867 -v -0.067000 0.092417 0.125825 -vn -0.770261 0.318866 -0.552288 -v -0.067000 0.092875 0.126283 -vn -0.770261 -0.318867 0.552288 -v -0.067000 0.094125 0.124117 -vn -0.770264 -0.000001 0.637726 -v -0.067000 0.093500 0.123950 -vn -0.770261 0.318866 0.552288 -v -0.067000 0.092875 0.124117 -vn -0.770261 -0.318867 -0.552288 -v -0.067000 0.094125 0.126283 -vn -0.770264 -0.000001 -0.637726 -v -0.067000 0.093500 0.126450 -vn -0.770261 -0.552288 0.318867 -v -0.067000 0.094583 0.124575 -vn -0.770264 -0.637725 0.000000 -v -0.067000 0.094750 0.125200 -vn -0.770261 -0.552288 -0.318867 -v -0.067000 0.094583 0.125825 -vn -0.990581 0.062165 0.122005 -v -0.067000 0.137816 0.128764 -vn -0.770264 0.000000 0.637725 -v -0.067000 0.114750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.067000 0.115375 0.129617 -vn -0.770264 0.552286 0.318863 -v -0.067000 0.113667 0.130075 -vn -0.770260 0.318865 0.552291 -v -0.067000 0.114125 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.067000 0.115833 0.130075 -vn -0.770261 -0.637729 -0.000002 -v -0.067000 0.116000 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.067000 0.115833 0.131325 -vn -0.770260 -0.318865 -0.552291 -v -0.067000 0.115375 0.131783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 0.114750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.067000 0.114125 0.131783 -vn -0.770263 -0.552286 -0.318865 -v -0.067000 0.099833 0.131325 -vn -0.717284 0.630262 0.297109 -v -0.067000 0.102000 0.132200 -vn -0.770261 -0.637729 -0.000002 -v -0.067000 0.100000 0.130700 -vn -0.770264 -0.552286 0.318863 -v -0.067000 0.099833 0.130075 -vn -0.770260 -0.318865 0.552291 -v -0.067000 0.099375 0.129617 -vn -0.770260 -0.318865 -0.552291 -v -0.067000 0.099375 0.131783 -vn -0.770264 -0.000000 -0.637725 -v -0.067000 0.098750 0.131950 -vn -0.923880 0.000000 0.382683 -v -0.067000 0.097250 0.132200 -vn -0.770260 0.318865 -0.552291 -v -0.067000 0.098125 0.131783 -vn -0.770262 0.552286 -0.318869 -v -0.067000 0.097667 0.131325 -vn -0.770263 0.637726 -0.000002 -v -0.067000 0.097500 0.130700 -vn -0.770262 0.552286 0.318867 -v -0.067000 0.097667 0.130075 -vn -1.000000 0.000000 0.000000 -v -0.067000 0.097250 0.128325 -vn -0.770260 0.318865 0.552291 -v -0.067000 0.098125 0.129617 -vn -0.770264 0.000000 0.637725 -v -0.067000 0.098750 0.129450 -vn -0.770266 -0.318854 0.552289 -v -0.067000 0.097150 0.127160 -vn 0.301511 -0.301511 -0.904534 -v -0.065000 0.124750 0.101200 -vn 0.770262 -0.318863 0.552289 -v -0.065000 0.123375 0.102617 -vn 0.770261 0.000000 0.637728 -v -0.065000 0.122750 0.102450 -vn 0.609994 0.000001 -0.792406 -v -0.065000 0.122750 0.106009 -vn 0.770264 0.000000 -0.637725 -v -0.065000 0.122750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 0.123375 0.104783 -vn 0.301512 0.301511 -0.904534 -v -0.065000 0.120750 0.101200 -vn 0.770262 0.318863 0.552289 -v -0.065000 0.122125 0.102617 -vn 0.770262 0.552289 0.318863 -v -0.065000 0.121667 0.103075 -vn 0.609995 0.686243 -0.396203 -v -0.065000 0.120750 0.104855 -vn 0.609994 -0.686243 -0.396204 -v -0.065000 0.124750 0.104855 -vn 0.770262 -0.552289 -0.318863 -v -0.065000 0.123833 0.104325 -vn 0.770261 -0.637728 0.000000 -v -0.065000 0.124000 0.103700 -vn 0.770262 -0.552289 0.318863 -v -0.065000 0.123833 0.103075 -vn 0.770261 0.637729 -0.000000 -v -0.065000 0.121500 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.065000 0.121667 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.065000 0.122125 0.104783 -vn 0.609994 0.686243 -0.396203 -v -0.065000 0.112750 0.104855 -vn 0.770262 0.552289 -0.318863 -v -0.065000 0.113667 0.104325 -vn 0.609994 0.000001 -0.792406 -v -0.065000 0.114750 0.106009 -vn 0.770261 0.318867 -0.552288 -v -0.065000 0.114125 0.104783 -vn 0.609994 -0.686243 -0.396204 -v -0.065000 0.116750 0.104855 -vn 0.770261 -0.637728 0.000000 -v -0.065000 0.116000 0.103700 -vn 0.301511 -0.301511 -0.904534 -v -0.065000 0.116750 0.101200 -vn 0.770262 -0.552289 0.318863 -v -0.065000 0.115833 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.065000 0.115375 0.102617 -vn 0.770261 0.000000 0.637728 -v -0.065000 0.114750 0.102450 -vn 0.301512 0.301511 -0.904534 -v -0.065000 0.112750 0.101200 -vn 0.770262 0.318863 0.552289 -v -0.065000 0.114125 0.102617 -vn 0.770262 0.552289 0.318863 -v -0.065000 0.113667 0.103075 -vn 0.770261 0.637729 -0.000000 -v -0.065000 0.113500 0.103700 -vn 0.770264 0.000000 -0.637725 -v -0.065000 0.114750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 0.115375 0.104783 -vn 0.770262 -0.552289 -0.318863 -v -0.065000 0.115833 0.104325 -vn 0.609994 -0.686244 -0.396203 -v -0.065000 0.108750 0.104855 -vn 0.770261 -0.637728 0.000000 -v -0.065000 0.108000 0.103700 -vn 0.301512 -0.301511 -0.904534 -v -0.065000 0.108750 0.101200 -vn 0.770262 -0.552289 0.318863 -v -0.065000 0.107833 0.103075 -vn 0.609994 -0.000001 -0.792406 -v -0.065000 0.106750 0.106009 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 0.107375 0.104783 -vn 0.770262 -0.552289 -0.318863 -v -0.065000 0.107833 0.104325 -vn 0.770262 -0.318863 0.552289 -v -0.065000 0.107375 0.102617 -vn 0.770261 -0.000001 0.637729 -v -0.065000 0.106750 0.102450 -vn 0.301511 0.301511 -0.904534 -v -0.065000 0.104750 0.101200 -vn 0.770264 0.637725 0.000000 -v -0.065000 0.105500 0.103700 -vn 0.609994 0.686243 -0.396204 -v -0.065000 0.104750 0.104855 -vn 0.770260 0.552291 0.318865 -v -0.065000 0.105667 0.103075 -vn 0.770263 0.318864 0.552286 -v -0.065000 0.106125 0.102617 -vn 0.770260 0.552291 -0.318865 -v -0.065000 0.105667 0.104325 -vn 0.770262 0.318868 -0.552286 -v -0.065000 0.106125 0.104783 -vn 0.770264 -0.000001 -0.637726 -v -0.065000 0.106750 0.104950 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.106475 -vn 0.904534 0.301511 0.301512 -v -0.062000 0.102000 0.131700 -vn 0.717283 0.630262 0.297109 -v -0.062000 0.102000 0.132200 -vn 0.741787 -0.516597 0.427645 -v -0.062000 0.100750 0.132200 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.111500 0.102700 -vn 0.717283 -0.630262 -0.297110 -v -0.062000 0.111500 0.102200 -vn 0.741787 0.516596 -0.427646 -v -0.062000 0.112750 0.102200 -vn 0.741787 -0.516596 -0.427646 -v -0.062000 0.124750 0.102200 -vn 0.717283 0.630262 -0.297110 -v -0.062000 0.126000 0.102200 -vn 0.846478 -0.279911 -0.452907 -v -0.062000 0.123750 0.104200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.126000 0.102700 -vn 0.707107 0.000000 -0.707107 -v -0.062000 0.126325 0.102700 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.106475 -vn 0.846479 0.279912 -0.452906 -v -0.062000 0.121750 0.104200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.106475 -vn 0.741787 0.516597 -0.427645 -v -0.062000 0.120750 0.102200 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.119500 0.102700 -vn 0.717283 -0.630262 -0.297110 -v -0.062000 0.119500 0.102200 -vn 0.923879 0.000000 -0.382685 -v -0.062000 0.119550 0.102200 -vn 0.846478 -0.279911 -0.452907 -v -0.062000 0.115750 0.104200 -vn 0.741787 -0.516596 -0.427646 -v -0.062000 0.116750 0.102200 -vn 0.717283 0.630262 -0.297110 -v -0.062000 0.118000 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.106475 -vn 0.846478 0.279911 -0.452906 -v -0.062000 0.113750 0.104200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.118000 0.102700 -vn 0.846478 -0.279911 -0.452907 -v -0.062000 0.107750 0.104200 -vn 0.741787 -0.516596 -0.427646 -v -0.062000 0.108750 0.102200 -vn 0.717283 0.630262 -0.297110 -v -0.062000 0.110000 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.106475 -vn 0.707107 0.000000 -0.707107 -v -0.062000 0.102250 0.102700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.103500 0.102700 -vn 0.846478 0.279911 -0.452906 -v -0.062000 0.105750 0.104200 -vn 0.707107 0.000000 -0.707107 -v -0.062000 0.110450 0.102700 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.110000 0.102700 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.102000 0.102700 -vn 0.846478 0.279911 -0.452906 -v -0.062000 0.097750 0.104200 -vn 0.846478 -0.279911 -0.452907 -v -0.062000 0.099750 0.104200 -vn 0.976004 -0.188581 0.108878 -v -0.062000 0.097279 0.106350 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.094000 0.104200 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 0.094000 0.102700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.095500 0.102700 -vn 0.976004 -0.108877 0.188580 -v -0.062000 0.096950 0.106021 -vn 0.741787 0.516596 -0.427646 -v -0.062000 0.096750 0.102200 -vn 0.717283 -0.630262 -0.297110 -v -0.062000 0.095500 0.102200 -vn 0.976004 0.188579 0.108876 -v -0.062000 0.095721 0.106350 -vn 0.976003 0.108877 0.188582 -v -0.062000 0.096050 0.106021 -vn 0.976004 -0.000000 0.217755 -v -0.062000 0.096500 0.105900 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 0.092500 0.104200 -vn 0.707107 0.000000 -0.707107 -v -0.062000 0.093800 0.104200 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.092500 0.105950 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.093800 0.106475 -vn 0.717283 -0.297110 -0.630262 -v -0.062000 0.092000 0.105950 -vn 0.923879 -0.382685 0.000000 -v -0.062000 0.092000 0.106475 -vn 0.717283 -0.297110 0.630262 -v -0.062000 0.092000 0.112450 -vn 0.741787 -0.427645 -0.516597 -v -0.062000 0.092000 0.111200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 0.092500 0.112450 -vn 0.846479 -0.452906 -0.279911 -v -0.062000 0.094000 0.110200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.092500 0.114025 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.093800 0.114025 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.092500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.093800 0.117200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.092500 0.120375 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.093800 0.120375 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.092500 0.121950 -vn 0.846478 -0.452907 0.279911 -v -0.062000 0.094000 0.124200 -vn 0.717283 -0.297110 -0.630262 -v -0.062000 0.092000 0.121950 -vn 0.741787 -0.427646 0.516596 -v -0.062000 0.092000 0.123200 -vn 0.846479 -0.452905 -0.279912 -v -0.062000 0.094000 0.126200 -vn 1.000000 -0.000000 0.000000 -v -0.062000 0.093800 0.126400 -vn 0.741788 -0.427644 -0.516597 -v -0.062000 0.092000 0.127200 -vn 0.904533 -0.301512 0.301512 -v -0.062000 0.092500 0.128450 -vn 0.717283 -0.297109 0.630263 -v -0.062000 0.092000 0.128450 -vn 0.846478 -0.279912 0.452906 -v -0.062000 0.099750 0.130200 -vn 1.000000 -0.000000 0.000000 -v -0.062000 0.102250 0.126400 -vn 0.707107 0.000000 0.707107 -v -0.062000 0.102250 0.131700 -vn 0.976003 0.217757 0.000001 -v -0.062000 0.095600 0.127600 -vn 0.976001 0.188598 -0.108875 -v -0.062000 0.095721 0.128050 -vn 0.904534 -0.301511 0.301512 -v -0.062000 0.095500 0.131700 -vn 0.976003 0.108877 -0.188583 -v -0.062000 0.096050 0.128379 -vn 0.976004 0.000000 -0.217755 -v -0.062000 0.096500 0.128500 -vn 0.976002 -0.188587 0.108879 -v -0.062000 0.097279 0.127150 -vn 0.976003 -0.108877 0.188582 -v -0.062000 0.096950 0.126821 -vn 0.976004 -0.000000 0.217755 -v -0.062000 0.096500 0.126700 -vn 0.976003 0.108877 0.188582 -v -0.062000 0.096050 0.126821 -vn 0.976003 0.188584 0.108879 -v -0.062000 0.095721 0.127150 -vn 0.717283 -0.630262 0.297109 -v -0.062000 0.095500 0.132200 -vn 0.741787 0.516597 0.427645 -v -0.062000 0.096750 0.132200 -vn 0.846479 0.279911 0.452906 -v -0.062000 0.097750 0.130200 -vn 0.976004 -0.108878 -0.188581 -v -0.062000 0.096950 0.128379 -vn 0.976003 -0.188587 -0.108877 -v -0.062000 0.097279 0.128050 -vn 0.976004 -0.217754 0.000005 -v -0.062000 0.097400 0.127600 -vn 0.577350 -0.577350 0.577350 -v -0.062000 0.094000 0.131700 -vn 0.904534 -0.301512 0.301512 -v -0.062000 0.094000 0.130200 -vn 0.707106 -0.000000 0.707107 -v -0.062000 0.093800 0.130200 -vn 0.577350 -0.577350 0.577350 -v -0.062000 0.092500 0.130200 -vn 0.707107 0.000000 0.707107 -v -0.062000 0.110450 0.131700 -vn 0.904534 0.301511 0.301512 -v -0.062000 0.110000 0.131700 -vn 0.741787 0.516597 0.427645 -v -0.062000 0.104750 0.132200 -vn 0.717283 -0.630262 0.297109 -v -0.062000 0.103500 0.132200 -vn 0.846478 0.279911 0.452907 -v -0.062000 0.105750 0.130200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 0.103500 0.131700 -vn 0.846469 -0.279920 0.452918 -v -0.062000 0.107750 0.130200 -vn 0.741787 -0.516597 0.427645 -v -0.062000 0.108750 0.132200 -vn 0.717283 0.630262 0.297109 -v -0.062000 0.110000 0.132200 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.124925 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.126400 -vn 1.000000 -0.000000 0.000000 -v -0.062000 0.110450 0.126400 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.112000 0.126700 -vn 0.904533 -0.301515 0.301511 -v -0.062000 0.119500 0.131700 -vn 0.904534 0.301511 0.301512 -v -0.062000 0.118000 0.131700 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.126400 -vn 0.923879 -0.000000 0.382684 -v -0.062000 0.119550 0.132200 -vn 0.717283 -0.630262 0.297109 -v -0.062000 0.119500 0.132200 -vn 0.741787 0.516597 0.427645 -v -0.062000 0.112750 0.132200 -vn 0.717283 -0.630262 0.297109 -v -0.062000 0.111500 0.132200 -vn 0.846478 0.279911 0.452907 -v -0.062000 0.113750 0.130200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 0.111500 0.131700 -vn 0.717283 0.630262 0.297109 -v -0.062000 0.118000 0.132200 -vn 0.741787 -0.516597 0.427645 -v -0.062000 0.116750 0.132200 -vn 0.846477 -0.279912 0.452908 -v -0.062000 0.115750 0.130200 -vn 0.707107 0.000000 0.707107 -v -0.062000 0.126325 0.131700 -vn 0.904534 0.301511 0.301512 -v -0.062000 0.126000 0.131700 -vn 0.741787 0.516598 0.427644 -v -0.062000 0.120750 0.132200 -vn 0.846479 0.279912 0.452906 -v -0.062000 0.121750 0.130200 -vn 0.846477 -0.279912 0.452908 -v -0.062000 0.123750 0.130200 -vn 0.741787 -0.516597 0.427645 -v -0.062000 0.124750 0.132200 -vn 0.717283 0.630262 0.297109 -v -0.062000 0.126000 0.132200 -vn 0.707106 0.000000 0.707107 -v -0.062000 0.133425 0.130200 -vn 0.904534 0.301512 0.301512 -v -0.062000 0.127500 0.130200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.126400 -vn 0.976002 0.108879 -0.188587 -v -0.062000 0.138050 0.127229 -vn 0.976004 0.000000 -0.217754 -v -0.062000 0.138500 0.127350 -vn 0.976005 -0.108876 -0.188573 -v -0.062000 0.138950 0.127229 -vn 0.976005 -0.188573 -0.108875 -v -0.062000 0.139279 0.126900 -vn 0.976004 -0.217754 -0.000001 -v -0.062000 0.139400 0.126450 -vn 0.976002 -0.188587 0.108879 -v -0.062000 0.139279 0.126000 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.141000 0.124925 -vn 0.976000 -0.108889 0.188593 -v -0.062000 0.138950 0.125671 -vn 0.976003 0.000002 0.217757 -v -0.062000 0.138500 0.125550 -vn 0.975997 0.108888 0.188608 -v -0.062000 0.138050 0.125671 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.124925 -vn 0.976003 0.188586 0.108876 -v -0.062000 0.137721 0.126000 -vn 1.000000 -0.000000 0.000000 -v -0.062000 0.136850 0.126400 -vn 0.976002 0.217760 0.000000 -v -0.062000 0.137600 0.126450 -vn 0.976006 0.188569 -0.108873 -v -0.062000 0.137721 0.126900 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.108000 -vn 0.976002 0.217760 0.000000 -v -0.062000 0.137600 0.107950 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.109475 -vn 0.976005 0.188577 -0.108875 -v -0.062000 0.137721 0.108400 -vn 0.976002 0.108879 -0.188589 -v -0.062000 0.138050 0.108729 -vn 0.976003 -0.000000 -0.217755 -v -0.062000 0.138500 0.108850 -vn 0.976005 -0.108876 -0.188574 -v -0.062000 0.138950 0.108729 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.141000 0.109475 -vn 0.976004 -0.188579 -0.108878 -v -0.062000 0.139279 0.108400 -vn 0.976004 -0.217755 -0.000000 -v -0.062000 0.139400 0.107950 -vn 0.976003 -0.188582 0.108877 -v -0.062000 0.139279 0.107500 -vn 0.976005 -0.108874 0.188573 -v -0.062000 0.138950 0.107171 -vn 0.976003 -0.000001 0.217757 -v -0.062000 0.138500 0.107050 -vn 0.976002 0.108877 0.188588 -v -0.062000 0.138050 0.107171 -vn 0.976004 0.188580 0.108874 -v -0.062000 0.137721 0.107500 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.106475 -vn 0.577350 0.577350 -0.577350 -v -0.062000 0.127500 0.102700 -vn 0.904534 0.301512 -0.301511 -v -0.062000 0.127500 0.104200 -vn 0.707107 0.000000 -0.707107 -v -0.062000 0.133425 0.104200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 0.116500 0.117700 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.117200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.120375 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.120375 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.124925 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.124925 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.126400 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.117200 -vn 0.904534 0.301511 0.301511 -v -0.062000 0.112000 0.117700 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.120375 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.120375 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.124200 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.124925 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.108000 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.108000 -vn 0.904534 0.301511 0.301511 -v -0.062000 0.112000 0.107700 -vn 0.904534 -0.301511 0.301511 -v -0.062000 0.116500 0.107700 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.108000 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.114025 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.114025 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.112000 0.116700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.116500 0.116700 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.109475 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.109475 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.110200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.116500 0.114025 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.114025 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.112000 0.109475 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.110450 0.109475 -vn 0.976004 0.188580 -0.108876 -v -0.062000 0.095721 0.107250 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.093800 0.108000 -vn 0.976003 0.217757 0.000000 -v -0.062000 0.095600 0.106800 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.108000 -vn 0.976003 -0.188582 -0.108877 -v -0.062000 0.097279 0.107250 -vn 0.741787 -0.516596 -0.427646 -v -0.062000 0.100750 0.102200 -vn 0.717283 0.630262 -0.297110 -v -0.062000 0.102000 0.102200 -vn 0.976004 -0.217755 -0.000000 -v -0.062000 0.097400 0.106800 -vn 0.976004 0.108876 -0.188580 -v -0.062000 0.096050 0.107579 -vn 0.976003 0.000000 -0.217757 -v -0.062000 0.096500 0.107700 -vn 0.976004 -0.108876 -0.188579 -v -0.062000 0.096950 0.107579 -vn 0.770261 0.000000 0.637729 -v -0.062000 0.129500 0.115950 -vn 0.770261 0.318862 0.552291 -v -0.062000 0.128875 0.116117 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.114025 -vn 0.770264 0.552287 0.318861 -v -0.062000 0.128417 0.116575 -vn 1.000000 0.000001 0.000000 -v -0.062000 0.126325 0.117200 -vn 0.770258 0.637733 0.000000 -v -0.062000 0.128250 0.117200 -vn 1.000000 0.000000 -0.000000 -v -0.062000 0.126325 0.120375 -vn 0.770264 0.552287 -0.318861 -v -0.062000 0.128417 0.117825 -vn 0.770261 0.318862 -0.552291 -v -0.062000 0.128875 0.118283 -vn 0.770261 0.000000 -0.637729 -v -0.062000 0.129500 0.118450 -vn 0.770263 -0.318865 -0.552286 -v -0.062000 0.130125 0.118283 -vn 1.000000 0.000000 -0.000000 -v -0.062000 0.133425 0.120375 -vn 0.770260 -0.552291 -0.318865 -v -0.062000 0.130583 0.117825 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.117200 -vn 0.770264 -0.637725 -0.000000 -v -0.062000 0.130750 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.114025 -vn 0.770260 -0.552291 0.318865 -v -0.062000 0.130583 0.116575 -vn 0.770263 -0.318865 0.552286 -v -0.062000 0.130125 0.116117 -vn 0.770263 0.000000 0.637726 -v -0.062000 0.137000 0.110300 -vn 0.770261 0.318866 0.552288 -v -0.062000 0.136550 0.110421 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.110200 -vn 0.770261 0.552288 0.318866 -v -0.062000 0.136221 0.110750 -vn 0.770263 0.637726 -0.000000 -v -0.062000 0.136100 0.111200 -vn 0.770260 0.552292 -0.318864 -v -0.062000 0.136221 0.111650 -vn 0.770259 0.000000 -0.637731 -v -0.062000 0.137000 0.112100 -vn 0.770262 -0.318858 -0.552292 -v -0.062000 0.137450 0.111979 -vn 0.707107 0.707106 0.000000 -v -0.062000 0.141000 0.114025 -vn 0.770266 -0.552286 -0.318857 -v -0.062000 0.137779 0.111650 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.141000 0.110200 -vn 0.770256 -0.637735 0.000000 -v -0.062000 0.137900 0.111200 -vn 0.770268 -0.552282 0.318860 -v -0.062000 0.137779 0.110750 -vn 0.770263 -0.552289 0.318861 -v -0.062000 0.124279 0.108750 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.108000 -vn 0.770259 -0.637731 -0.000000 -v -0.062000 0.124400 0.109200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.109475 -vn 0.770264 -0.552285 -0.318863 -v -0.062000 0.124279 0.109650 -vn 0.770260 0.552292 0.318864 -v -0.062000 0.122721 0.108750 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.119550 0.108000 -vn 0.770263 -0.318861 0.552289 -v -0.062000 0.123950 0.108421 -vn 0.770259 -0.000000 0.637731 -v -0.062000 0.123500 0.108300 -vn 0.770264 0.318863 0.552286 -v -0.062000 0.123050 0.108421 -vn 0.770263 0.637726 0.000000 -v -0.062000 0.122600 0.109200 -vn 0.770261 0.552288 -0.318866 -v -0.062000 0.122721 0.109650 -vn 0.770261 0.318866 -0.552288 -v -0.062000 0.123050 0.109979 -vn 0.770260 -0.318864 -0.552292 -v -0.062000 0.123950 0.109979 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.110200 -vn 0.770263 0.000000 -0.637726 -v -0.062000 0.123500 0.110100 -vn 0.770260 -0.552292 0.318864 -v -0.062000 0.108779 0.108750 -vn 0.770264 -0.318863 0.552285 -v -0.062000 0.108450 0.108421 -vn 0.770259 -0.000000 0.637731 -v -0.062000 0.108000 0.108300 -vn 0.770263 0.318861 0.552289 -v -0.062000 0.107550 0.108421 -vn 0.770263 0.552289 0.318861 -v -0.062000 0.107221 0.108750 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.109475 -vn 0.770263 -0.637726 -0.000000 -v -0.062000 0.108900 0.109200 -vn 0.770259 0.637731 0.000000 -v -0.062000 0.107100 0.109200 -vn 0.770264 0.552286 -0.318863 -v -0.062000 0.107221 0.109650 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.110200 -vn 0.770260 0.318864 -0.552292 -v -0.062000 0.107550 0.109979 -vn 0.770263 0.000000 -0.637726 -v -0.062000 0.108000 0.110100 -vn 0.770261 -0.318866 -0.552288 -v -0.062000 0.108450 0.109979 -vn 0.770261 -0.552288 -0.318866 -v -0.062000 0.108779 0.109650 -vn 0.770263 0.000000 0.637726 -v -0.062000 0.137000 0.122300 -vn 0.770261 0.318866 0.552288 -v -0.062000 0.136550 0.122421 -vn 0.770261 0.552288 0.318866 -v -0.062000 0.136221 0.122750 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.124200 -vn 0.770263 0.637726 -0.000000 -v -0.062000 0.136100 0.123200 -vn 0.770261 0.552288 -0.318866 -v -0.062000 0.136221 0.123650 -vn 0.770263 -0.000000 -0.637726 -v -0.062000 0.137000 0.124100 -vn 0.770258 -0.318862 -0.552295 -v -0.062000 0.137450 0.123979 -vn 0.707107 0.707106 0.000000 -v -0.062000 0.141000 0.124200 -vn 0.770268 -0.552282 -0.318860 -v -0.062000 0.137779 0.123650 -vn 0.770256 -0.637735 0.000000 -v -0.062000 0.137900 0.123200 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.141000 0.120375 -vn 0.770268 -0.552282 0.318860 -v -0.062000 0.137779 0.122750 -vn 0.770264 0.552286 -0.318863 -v -0.062000 0.107221 0.125650 -vn 0.770260 0.318864 -0.552292 -v -0.062000 0.107550 0.125979 -vn 0.770263 0.000000 -0.637726 -v -0.062000 0.108000 0.126100 -vn 0.770261 -0.318866 -0.552288 -v -0.062000 0.108450 0.125979 -vn 0.770261 -0.552288 -0.318866 -v -0.062000 0.108779 0.125650 -vn 0.770260 0.637730 0.000001 -v -0.062000 0.107100 0.125200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.124925 -vn 0.770262 0.552289 0.318862 -v -0.062000 0.107221 0.124750 -vn 0.770264 -0.637725 0.000001 -v -0.062000 0.108900 0.125200 -vn 0.770259 -0.552292 0.318865 -v -0.062000 0.108779 0.124750 -vn 0.770264 -0.318863 0.552285 -v -0.062000 0.108450 0.124421 -vn 0.770263 0.318861 0.552289 -v -0.062000 0.107550 0.124421 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.124200 -vn 0.770259 -0.000000 0.637731 -v -0.062000 0.108000 0.124300 -vn 0.770264 0.637725 0.000001 -v -0.062000 0.122600 0.125200 -vn 0.770261 0.552288 -0.318866 -v -0.062000 0.122721 0.125650 -vn 0.770261 0.318866 -0.552288 -v -0.062000 0.123050 0.125979 -vn 0.770259 0.552292 0.318865 -v -0.062000 0.122721 0.124750 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.116500 0.126700 -vn 0.770263 0.000000 -0.637726 -v -0.062000 0.123500 0.126100 -vn 0.770260 -0.318864 -0.552292 -v -0.062000 0.123950 0.125979 -vn 0.770264 -0.552285 -0.318863 -v -0.062000 0.124279 0.125650 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.124925 -vn 0.577350 0.577350 0.577350 -v -0.062000 0.127500 0.131700 -vn 0.770264 0.318863 0.552285 -v -0.062000 0.123050 0.124421 -vn 0.770259 -0.000000 0.637731 -v -0.062000 0.123500 0.124300 -vn 0.770260 -0.637730 0.000001 -v -0.062000 0.124400 0.125200 -vn 0.770262 -0.552289 0.318862 -v -0.062000 0.124279 0.124750 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.126325 0.124200 -vn 0.770263 -0.318861 0.552289 -v -0.062000 0.123950 0.124421 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.124200 -vn 0.770261 0.318866 -0.552288 -v -0.062000 0.136550 0.123979 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.126400 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.124925 -vn 0.770258 -0.318862 0.552295 -v -0.062000 0.137450 0.122421 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.120375 -vn 0.707107 0.707107 0.000000 -v -0.062000 0.141000 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.114025 -vn 0.770264 0.318863 -0.552285 -v -0.062000 0.136550 0.111979 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.120375 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.102250 0.114025 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.094000 0.124925 -vn 0.741787 -0.427645 0.516596 -v -0.062000 0.092000 0.107200 -vn 0.846478 -0.452907 0.279911 -v -0.062000 0.094000 0.108200 -vn 0.707107 -0.707107 0.000000 -v -0.062000 0.094000 0.109475 -vn 0.770258 -0.318862 0.552295 -v -0.062000 0.137450 0.110421 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.136850 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.109475 -vn 1.000000 0.000000 0.000000 -v -0.062000 0.133425 0.108000 -vn 0.741787 0.516596 -0.427646 -v -0.062000 0.104750 0.102200 -vn 0.717283 -0.630262 -0.297110 -v -0.062000 0.103500 0.102200 -vn -0.075085 0.990667 -0.113762 -v -0.063500 0.120750 0.102200 -vn -0.609994 0.686244 -0.396203 -v -0.063500 0.120750 0.104855 -vn -0.846479 0.279912 -0.452906 -v -0.063500 0.121750 0.104200 -vn -0.609994 0.000001 -0.792406 -v -0.063500 0.122750 0.106009 -vn -0.846478 -0.279911 -0.452907 -v -0.063500 0.123750 0.104200 -vn -0.609994 -0.686243 -0.396204 -v -0.063500 0.124750 0.104855 -vn -0.075085 -0.990667 -0.113763 -v -0.063500 0.124750 0.102200 -vn -0.075085 0.990667 -0.113763 -v -0.063500 0.112750 0.102200 -vn -0.609994 0.686244 -0.396203 -v -0.063500 0.112750 0.104855 -vn -0.846478 0.279911 -0.452907 -v -0.063500 0.113750 0.104200 -vn -0.609994 0.000001 -0.792406 -v -0.063500 0.114750 0.106009 -vn -0.846478 -0.279911 -0.452907 -v -0.063500 0.115750 0.104200 -vn -0.609994 -0.686243 -0.396204 -v -0.063500 0.116750 0.104855 -vn -0.075085 -0.990667 -0.113763 -v -0.063500 0.116750 0.102200 -vn -0.075085 0.990667 -0.113763 -v -0.063500 0.104750 0.102200 -vn -0.609994 0.686243 -0.396204 -v -0.063500 0.104750 0.104855 -vn -0.846478 0.279911 -0.452907 -v -0.063500 0.105750 0.104200 -vn -0.609994 -0.000001 -0.792406 -v -0.063500 0.106750 0.106009 -vn -0.846478 -0.279911 -0.452907 -v -0.063500 0.107750 0.104200 -vn -0.609994 -0.686244 -0.396203 -v -0.063500 0.108750 0.104855 -vn -0.075085 -0.990667 -0.113763 -v -0.063500 0.108750 0.102200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.120750 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.119500 0.101200 -vn -0.297109 -0.630263 -0.717283 -v -0.066000 0.119500 0.101200 -vn -0.297109 0.630262 -0.717284 -v -0.066000 0.126000 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.124750 0.101200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.126000 0.101200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.112750 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.111500 0.101200 -vn -0.297109 -0.630263 -0.717283 -v -0.066000 0.111500 0.101200 -vn -0.297109 0.630262 -0.717284 -v -0.066000 0.118000 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.116750 0.101200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.118000 0.101200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.104750 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.103500 0.101200 -vn -0.297109 -0.630263 -0.717283 -v -0.066000 0.103500 0.101200 -vn -0.297109 0.630262 -0.717284 -v -0.066000 0.110000 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.108750 0.101200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.110000 0.101200 -vn 0.609994 -0.686244 -0.396203 -v -0.065000 0.100750 0.104855 -vn 0.770261 -0.637728 0.000000 -v -0.065000 0.100000 0.103700 -vn 0.301512 -0.301511 -0.904534 -v -0.065000 0.100750 0.101200 -vn 0.770262 -0.552289 0.318863 -v -0.065000 0.099833 0.103075 -vn 0.609994 0.686243 -0.396204 -v -0.065000 0.096750 0.104855 -vn 0.301511 0.301511 -0.904534 -v -0.065000 0.096750 0.101200 -vn 0.770261 0.552288 0.318867 -v -0.065000 0.097667 0.103075 -vn 0.770261 0.318867 -0.552288 -v -0.065000 0.098125 0.104783 -vn 0.609994 -0.000001 -0.792406 -v -0.065000 0.098750 0.106009 -vn 0.770261 0.552288 -0.318867 -v -0.065000 0.097667 0.104325 -vn 0.770264 0.637725 0.000000 -v -0.065000 0.097500 0.103700 -vn 0.770264 0.000000 -0.637725 -v -0.065000 0.098750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 0.099375 0.104783 -vn 0.770262 -0.552289 -0.318863 -v -0.065000 0.099833 0.104325 -vn 0.770262 -0.318863 0.552289 -v -0.065000 0.099375 0.102617 -vn 0.770261 0.000000 0.637728 -v -0.065000 0.098750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.065000 0.098125 0.102617 -vn 0.301511 -0.904534 -0.301511 -v -0.065000 0.091000 0.111200 -vn 0.301511 -0.904534 0.301511 -v -0.065000 0.091000 0.107200 -vn 0.770264 0.637725 0.000000 -v -0.065000 0.092250 0.109200 -vn 0.770260 0.552291 0.318865 -v -0.065000 0.092417 0.108575 -vn 0.770260 -0.552291 0.318865 -v -0.065000 0.094583 0.108575 -vn 0.609994 -0.396203 0.686243 -v -0.065000 0.094655 0.107200 -vn 0.770264 -0.637725 -0.000000 -v -0.065000 0.094750 0.109200 -vn 0.609994 -0.792406 -0.000001 -v -0.065000 0.095809 0.109200 -vn 0.770260 -0.552291 -0.318865 -v -0.065000 0.094583 0.109825 -vn 0.609994 -0.396203 -0.686243 -v -0.065000 0.094655 0.111200 -vn 0.770263 -0.318865 -0.552286 -v -0.065000 0.094125 0.110283 -vn 0.770260 0.552291 -0.318865 -v -0.065000 0.092417 0.109825 -vn 0.770263 0.318864 -0.552286 -v -0.065000 0.092875 0.110283 -vn 0.770261 -0.000001 -0.637729 -v -0.065000 0.093500 0.110450 -vn 0.770263 -0.318865 0.552286 -v -0.065000 0.094125 0.108117 -vn 0.770261 -0.000001 0.637729 -v -0.065000 0.093500 0.107950 -vn 0.770263 0.318864 0.552286 -v -0.065000 0.092875 0.108117 -vn -0.075085 0.990667 -0.113763 -v -0.063500 0.096750 0.102200 -vn -0.609994 0.686243 -0.396204 -v -0.063500 0.096750 0.104855 -vn -0.846478 0.279911 -0.452907 -v -0.063500 0.097750 0.104200 -vn -0.609994 -0.000001 -0.792406 -v -0.063500 0.098750 0.106009 -vn -0.846478 -0.279911 -0.452907 -v -0.063500 0.099750 0.104200 -vn -0.609994 -0.686244 -0.396203 -v -0.063500 0.100750 0.104855 -vn -0.075085 -0.990667 -0.113763 -v -0.063500 0.100750 0.102200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.096750 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.095500 0.101200 -vn -0.297109 -0.630263 -0.717283 -v -0.066000 0.095500 0.101200 -vn -0.297109 0.630262 -0.717284 -v -0.066000 0.102000 0.101200 -vn 0.297107 -0.630263 -0.717284 -v -0.063000 0.100750 0.101200 -vn 0.297107 0.630263 -0.717284 -v -0.063000 0.102000 0.101200 -vn -0.846479 -0.452906 -0.279912 -v -0.063500 0.094000 0.110200 -vn -0.075085 -0.113762 -0.990667 -v -0.063500 0.092000 0.111200 -vn -0.609994 -0.396203 -0.686243 -v -0.063500 0.094655 0.111200 -vn -0.609994 -0.396204 0.686243 -v -0.063500 0.094655 0.107200 -vn -0.075085 -0.113763 0.990667 -v -0.063500 0.092000 0.107200 -vn -0.846478 -0.452907 0.279911 -v -0.063500 0.094000 0.108200 -vn -0.609994 -0.792406 -0.000001 -v -0.063500 0.095809 0.109200 -vn 0.297107 -0.717284 -0.630263 -v -0.063000 0.091000 0.111200 -vn 0.297107 -0.717284 0.630263 -v -0.063000 0.091000 0.112450 -vn -0.297109 -0.717284 0.630262 -v -0.066000 0.091000 0.112450 -vn -0.297109 -0.717284 -0.630262 -v -0.066000 0.091000 0.105950 -vn 0.297107 -0.717284 0.630263 -v -0.063000 0.091000 0.107200 -vn 0.297107 -0.717284 -0.630263 -v -0.063000 0.091000 0.105950 -vn -0.088123 0.737701 0.669352 -v -0.066000 0.127500 0.130200 -vn -0.130014 0.038804 0.990753 -v -0.066000 0.136000 0.130200 -vn -0.130013 0.990753 0.038803 -v -0.066000 0.141000 0.125200 -vn -0.130014 0.990753 -0.038803 -v -0.066000 0.141000 0.109200 -vn -0.088123 0.737701 -0.669352 -v -0.066000 0.127500 0.104200 -vn -0.130014 0.038804 -0.990753 -v -0.066000 0.136000 0.104200 -vn -0.297108 0.630263 -0.717284 -v -0.065500 0.127500 0.102700 -vn -0.318865 0.770262 -0.552288 -v -0.066500 0.127500 0.104334 -vn -0.552288 0.770262 -0.318865 -v -0.066866 0.127500 0.104700 -vn -0.227458 0.804186 -0.549134 -v -0.065500 0.126000 0.102700 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 0.119500 0.102700 -vn -0.227458 0.804186 -0.549133 -v -0.065500 0.118000 0.102700 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 0.111500 0.102700 -vn -0.227458 0.804186 -0.549134 -v -0.065500 0.110000 0.102700 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 0.103500 0.102700 -vn -0.227458 0.804186 -0.549133 -v -0.065500 0.102000 0.102700 -vn -0.227458 -0.804186 -0.549134 -v -0.065500 0.095500 0.102700 -vn -0.297108 -0.630263 -0.717284 -v -0.065500 0.094000 0.102700 -vn -0.297108 -0.717284 -0.630263 -v -0.065500 0.092500 0.104200 -vn -0.227458 -0.549134 -0.804186 -v -0.065500 0.092500 0.105950 -vn -0.227458 -0.549134 0.804186 -v -0.065500 0.092500 0.112450 -vn -0.227458 -0.549134 -0.804186 -v -0.065500 0.092500 0.121950 -vn -0.297109 -0.717284 -0.630262 -v -0.066000 0.091000 0.121950 -vn 0.297107 -0.717284 -0.630263 -v -0.063000 0.091000 0.121950 -vn 0.297107 -0.717284 -0.630263 -v -0.063000 0.091000 0.127200 -vn 0.297107 -0.717284 0.630263 -v -0.063000 0.091000 0.128450 -vn 0.301511 -0.904534 -0.301511 -v -0.065000 0.091000 0.127200 -vn -0.297109 -0.717284 0.630263 -v -0.066000 0.091000 0.128450 -vn 0.301511 -0.904534 0.301511 -v -0.065000 0.091000 0.123200 -vn 0.297107 -0.717284 0.630263 -v -0.063000 0.091000 0.123200 -vn -0.227458 -0.549134 0.804186 -v -0.065500 0.092500 0.128450 -vn -0.297108 -0.717284 0.630263 -v -0.065500 0.092500 0.130200 -vn -0.297108 -0.630263 0.717284 -v -0.065500 0.094000 0.131700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 0.095500 0.131700 -vn -0.297109 -0.630262 0.717284 -v -0.066000 0.095500 0.133200 -vn 0.297108 -0.630263 0.717284 -v -0.063000 0.095500 0.133200 -vn 0.297108 -0.630263 0.717284 -v -0.063000 0.100750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.102000 0.133200 -vn 0.301511 -0.301511 0.904534 -v -0.065000 0.100750 0.133200 -vn -0.297109 0.630262 0.717284 -v -0.066000 0.102000 0.133200 -vn 0.301511 0.301511 0.904534 -v -0.065000 0.096750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.096750 0.133200 -vn -0.227458 0.804186 0.549134 -v -0.065500 0.102000 0.131700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 0.103500 0.131700 -vn -0.297109 -0.630262 0.717284 -v -0.066000 0.103500 0.133200 -vn 0.297108 -0.630263 0.717284 -v -0.063000 0.103500 0.133200 -vn 0.297108 -0.630263 0.717284 -v -0.063000 0.108750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.110000 0.133200 -vn 0.301511 -0.301511 0.904534 -v -0.065000 0.108750 0.133200 -vn -0.297109 0.630262 0.717284 -v -0.066000 0.110000 0.133200 -vn 0.301511 0.301511 0.904534 -v -0.065000 0.104750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.104750 0.133200 -vn -0.227458 0.804186 0.549134 -v -0.065500 0.110000 0.131700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 0.111500 0.131700 -vn -0.297109 -0.630262 0.717284 -v -0.066000 0.111500 0.133200 -vn 0.297108 -0.630263 0.717284 -v -0.063000 0.111500 0.133200 -vn 0.297108 -0.630263 0.717284 -v -0.063000 0.116750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.118000 0.133200 -vn 0.301511 -0.301511 0.904534 -v -0.065000 0.116750 0.133200 -vn -0.297109 0.630262 0.717284 -v -0.066000 0.118000 0.133200 -vn 0.301511 0.301511 0.904534 -v -0.065000 0.112750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.112750 0.133200 -vn -0.227458 0.804186 0.549134 -v -0.065500 0.118000 0.131700 -vn -0.227458 -0.804186 0.549134 -v -0.065500 0.119500 0.131700 -vn -0.297109 -0.630262 0.717284 -v -0.066000 0.119500 0.133200 -vn 0.297108 -0.630262 0.717284 -v -0.063000 0.119500 0.133200 -vn 0.297108 -0.630263 0.717284 -v -0.063000 0.124750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.126000 0.133200 -vn 0.301511 -0.301511 0.904534 -v -0.065000 0.124750 0.133200 -vn -0.297109 0.630262 0.717284 -v -0.066000 0.126000 0.133200 -vn 0.301511 0.301511 0.904534 -v -0.065000 0.120750 0.133200 -vn 0.297108 0.630263 0.717284 -v -0.063000 0.120750 0.133200 -vn -0.227458 0.804186 0.549134 -v -0.065500 0.126000 0.131700 -vn -0.297108 0.630263 0.717284 -v -0.065500 0.127500 0.131700 -vn -0.552286 0.770263 0.318866 -v -0.066866 0.127500 0.129700 -vn -0.318863 0.770260 0.552291 -v -0.066500 0.127500 0.130066 -vn -0.128141 -0.983443 0.128141 -v -0.069700 0.097000 0.126900 -vn -0.128146 -0.983442 -0.128139 -v -0.069700 0.097000 0.121500 -vn -0.128145 -0.128139 0.983442 -v -0.069700 0.097300 0.127200 -vn -0.128141 0.128135 0.983444 -v -0.069700 0.103700 0.127200 -vn -0.128163 0.983438 -0.128156 -v -0.069700 0.104000 0.121500 -vn -0.128159 0.983438 0.128159 -v -0.069700 0.104000 0.126900 -vn -0.128141 -0.128135 -0.983444 -v -0.069700 0.097300 0.121200 -vn -0.128144 0.128138 -0.983443 -v -0.069700 0.103700 0.121200 -vn -0.988105 -0.108739 -0.108739 -v -0.070000 0.097300 0.121500 -vn -0.988105 -0.108736 0.108742 -v -0.070000 0.097300 0.126900 -vn -0.988105 0.108737 -0.108737 -v -0.070000 0.103700 0.121500 -vn -0.988105 0.108734 0.108740 -v -0.070000 0.103700 0.126900 -vn -0.128163 -0.128156 -0.983438 -v -0.069700 0.097300 0.107200 -vn -0.128161 0.128155 -0.983438 -v -0.069700 0.103700 0.107200 -vn -0.128144 -0.983443 -0.128138 -v -0.069700 0.097000 0.107500 -vn -0.128141 -0.983444 0.128135 -v -0.069700 0.097000 0.112900 -vn -0.128162 -0.128156 0.983438 -v -0.069700 0.097300 0.113200 -vn -0.128163 0.128156 0.983438 -v -0.069700 0.103700 0.113200 -vn -0.128161 0.983438 0.128155 -v -0.069700 0.104000 0.112900 -vn -0.128163 0.983438 -0.128156 -v -0.069700 0.104000 0.107500 -vn -0.988106 0.108735 -0.108735 -v -0.070000 0.103700 0.107500 -vn -0.988105 -0.108737 -0.108737 -v -0.070000 0.097300 0.107500 -vn -0.988106 0.108735 0.108735 -v -0.070000 0.103700 0.112900 -vn -0.988106 -0.108737 0.108737 -v -0.070000 0.097300 0.112900 -vn -0.609994 -0.396203 0.686244 -v -0.063500 0.094655 0.123200 -vn 0.609994 -0.396203 0.686244 -v -0.065000 0.094655 0.123200 -vn -0.075085 -0.113763 0.990667 -v -0.063500 0.092000 0.123200 -vn 0.770264 0.637725 0.000000 -v -0.065000 0.092250 0.125200 -vn 0.770261 0.552288 0.318867 -v -0.065000 0.092417 0.124575 -vn 0.770264 -0.000001 -0.637726 -v -0.065000 0.093500 0.126450 -vn 0.609994 -0.396202 -0.686244 -v -0.065000 0.094655 0.127200 -vn 0.770261 0.318866 -0.552288 -v -0.065000 0.092875 0.126283 -vn 0.770261 0.552288 -0.318867 -v -0.065000 0.092417 0.125825 -vn 0.770261 -0.318867 -0.552288 -v -0.065000 0.094125 0.126283 -vn 0.770261 -0.552288 -0.318867 -v -0.065000 0.094583 0.125825 -vn 0.609994 -0.792406 -0.000001 -v -0.065000 0.095809 0.125200 -vn 0.770264 -0.637725 -0.000000 -v -0.065000 0.094750 0.125200 -vn 0.770261 -0.552288 0.318867 -v -0.065000 0.094583 0.124575 -vn 0.770261 -0.318867 0.552288 -v -0.065000 0.094125 0.124117 -vn 0.770264 -0.000001 0.637726 -v -0.065000 0.093500 0.123950 -vn 0.770261 0.318866 0.552288 -v -0.065000 0.092875 0.124117 -vn -0.075084 -0.113761 -0.990667 -v -0.063500 0.092000 0.127200 -vn -0.609994 -0.396202 -0.686244 -v -0.063500 0.094655 0.127200 -vn -0.609994 -0.792406 -0.000001 -v -0.063500 0.095809 0.125200 -vn -0.846479 -0.452905 -0.279912 -v -0.063500 0.094000 0.126200 -vn -0.846478 -0.452907 0.279911 -v -0.063500 0.094000 0.124200 -vn -0.609994 0.686244 0.396202 -v -0.063500 0.096750 0.129545 -vn 0.609994 0.686244 0.396202 -v -0.065000 0.096750 0.129545 -vn -0.075085 0.990667 0.113762 -v -0.063500 0.096750 0.132200 -vn 0.609995 -0.686244 0.396202 -v -0.065000 0.100750 0.129545 -vn 0.770263 -0.552286 -0.318865 -v -0.065000 0.099833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.065000 0.100000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.065000 0.099833 0.130075 -vn 0.609994 -0.000001 0.792406 -v -0.065000 0.098750 0.128391 -vn 0.770260 -0.318865 0.552291 -v -0.065000 0.099375 0.129617 -vn 0.770263 0.637726 -0.000002 -v -0.065000 0.097500 0.130700 -vn 0.770262 0.552286 -0.318869 -v -0.065000 0.097667 0.131325 -vn 0.770260 0.318865 -0.552291 -v -0.065000 0.098125 0.131783 -vn 0.770264 0.000000 -0.637725 -v -0.065000 0.098750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.065000 0.099375 0.131783 -vn 0.770264 -0.000000 0.637725 -v -0.065000 0.098750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.065000 0.098125 0.129617 -vn 0.770262 0.552286 0.318867 -v -0.065000 0.097667 0.130075 -vn -0.075085 -0.990667 0.113762 -v -0.063500 0.100750 0.132200 -vn -0.609995 -0.686244 0.396202 -v -0.063500 0.100750 0.129545 -vn -0.609994 -0.000001 0.792406 -v -0.063500 0.098750 0.128391 -vn -0.846478 -0.279911 0.452906 -v -0.063500 0.099750 0.130200 -vn -0.846478 0.279911 0.452906 -v -0.063500 0.097750 0.130200 -vn -0.609994 0.686244 0.396202 -v -0.063500 0.104750 0.129545 -vn 0.609994 0.686244 0.396203 -v -0.065000 0.104750 0.129545 -vn -0.075085 0.990667 0.113762 -v -0.063500 0.104750 0.132200 -vn 0.609995 -0.686244 0.396202 -v -0.065000 0.108750 0.129545 -vn 0.770263 -0.552286 -0.318865 -v -0.065000 0.107833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.065000 0.108000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.065000 0.107833 0.130075 -vn 0.609994 -0.000001 0.792406 -v -0.065000 0.106750 0.128391 -vn 0.770260 -0.318865 0.552291 -v -0.065000 0.107375 0.129617 -vn 0.770261 0.552288 -0.318867 -v -0.065000 0.105667 0.131325 -vn 0.770263 0.637726 -0.000002 -v -0.065000 0.105500 0.130700 -vn 0.770264 -0.000001 0.637726 -v -0.065000 0.106750 0.129450 -vn 0.770261 0.318866 0.552288 -v -0.065000 0.106125 0.129617 -vn 0.770261 0.552288 0.318865 -v -0.065000 0.105667 0.130075 -vn 0.770261 0.318866 -0.552288 -v -0.065000 0.106125 0.131783 -vn 0.770264 -0.000001 -0.637726 -v -0.065000 0.106750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.065000 0.107375 0.131783 -vn -0.075085 -0.990667 0.113762 -v -0.063500 0.108750 0.132200 -vn -0.609995 -0.686244 0.396202 -v -0.063500 0.108750 0.129545 -vn -0.609995 0.686244 0.396202 -v -0.063500 0.112750 0.129545 -vn 0.609995 0.686244 0.396202 -v -0.065000 0.112750 0.129545 -vn -0.075085 0.990667 0.113762 -v -0.063500 0.112750 0.132200 -vn 0.770263 0.552286 -0.318865 -v -0.065000 0.113667 0.131325 -vn 0.770261 0.637729 -0.000002 -v -0.065000 0.113500 0.130700 -vn 0.770260 0.318865 -0.552291 -v -0.065000 0.114125 0.131783 -vn 0.770264 0.000000 -0.637725 -v -0.065000 0.114750 0.131950 -vn 0.770260 -0.318865 0.552291 -v -0.065000 0.115375 0.129617 -vn 0.609994 0.000001 0.792406 -v -0.065000 0.114750 0.128391 -vn 0.770264 -0.552286 0.318863 -v -0.065000 0.115833 0.130075 -vn 0.609994 -0.686244 0.396203 -v -0.065000 0.116750 0.129545 -vn 0.770264 -0.000000 0.637725 -v -0.065000 0.114750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.065000 0.114125 0.129617 -vn 0.770264 0.552286 0.318863 -v -0.065000 0.113667 0.130075 -vn 0.770260 -0.318865 -0.552291 -v -0.065000 0.115375 0.131783 -vn 0.770263 -0.552286 -0.318865 -v -0.065000 0.115833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.065000 0.116000 0.130700 -vn -0.075085 -0.990667 0.113762 -v -0.063500 0.116750 0.132200 -vn -0.609994 -0.686244 0.396203 -v -0.063500 0.116750 0.129545 -vn -0.609995 0.686244 0.396202 -v -0.063500 0.120750 0.129545 -vn 0.609995 0.686244 0.396202 -v -0.065000 0.120750 0.129545 -vn -0.075084 0.990667 0.113762 -v -0.063500 0.120750 0.132200 -vn 0.770264 -0.000000 0.637725 -v -0.065000 0.122750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.065000 0.122125 0.129617 -vn 0.609994 0.000001 0.792406 -v -0.065000 0.122750 0.128391 -vn 0.609994 -0.686244 0.396203 -v -0.065000 0.124750 0.129545 -vn 0.770263 -0.552286 -0.318865 -v -0.065000 0.123833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.065000 0.124000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.065000 0.123833 0.130075 -vn 0.770260 -0.318865 0.552291 -v -0.065000 0.123375 0.129617 -vn 0.770264 0.552286 0.318863 -v -0.065000 0.121667 0.130075 -vn 0.770261 0.637729 -0.000002 -v -0.065000 0.121500 0.130700 -vn 0.770263 0.552286 -0.318865 -v -0.065000 0.121667 0.131325 -vn 0.770260 0.318865 -0.552291 -v -0.065000 0.122125 0.131783 -vn 0.770264 0.000000 -0.637725 -v -0.065000 0.122750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.065000 0.123375 0.131783 -vn -0.075085 -0.990667 0.113762 -v -0.063500 0.124750 0.132200 -vn -0.609994 -0.686244 0.396203 -v -0.063500 0.124750 0.129545 -vn -0.609994 -0.000001 0.792406 -v -0.063500 0.106750 0.128391 -vn -0.846478 -0.279911 0.452906 -v -0.063500 0.107750 0.130200 -vn -0.846478 0.279911 0.452906 -v -0.063500 0.105750 0.130200 -vn -0.609994 0.000001 0.792406 -v -0.063500 0.114750 0.128391 -vn -0.846478 -0.279911 0.452906 -v -0.063500 0.115750 0.130200 -vn -0.846479 0.279911 0.452906 -v -0.063500 0.113750 0.130200 -vn -0.609994 0.000001 0.792406 -v -0.063500 0.122750 0.128391 -vn -0.846478 -0.279911 0.452906 -v -0.063500 0.123750 0.130200 -vn -0.846479 0.279912 0.452905 -v -0.063500 0.121750 0.130200 -vn -0.128743 0.979469 -0.155135 -v -0.066000 0.140938 0.108418 -vn -0.129692 0.943024 -0.306409 -v -0.066000 0.140755 0.107655 -vn -0.128747 0.883593 -0.450208 -v -0.066000 0.140455 0.106930 -vn -0.129691 0.802182 -0.582824 -v -0.066000 0.140045 0.106261 -vn -0.128741 0.701223 -0.701222 -v -0.066000 0.139536 0.105664 -vn -0.129689 0.582820 -0.802185 -v -0.066000 0.138939 0.105155 -vn -0.128736 0.450210 -0.883594 -v -0.066000 0.138270 0.104745 -vn -0.129684 0.306411 -0.943024 -v -0.066000 0.137545 0.104445 -vn -0.128746 0.155134 -0.979468 -v -0.066000 0.136782 0.104262 -vn -0.128742 0.155135 0.979469 -v -0.066000 0.136782 0.130138 -vn -0.129679 0.306406 0.943026 -v -0.066000 0.137545 0.129955 -vn -0.128739 0.450206 0.883596 -v -0.066000 0.138270 0.129655 -vn -0.129693 0.582825 0.802181 -v -0.066000 0.138939 0.129245 -vn -0.128738 0.701221 0.701225 -v -0.066000 0.139536 0.128736 -vn -0.129692 0.802182 0.582825 -v -0.066000 0.140045 0.128139 -vn -0.128747 0.883593 0.450209 -v -0.066000 0.140455 0.127470 -vn -0.129694 0.943025 0.306405 -v -0.066000 0.140755 0.126745 -vn -0.128742 0.979468 0.155135 -v -0.066000 0.140938 0.125982 -vn -0.227459 0.549132 -0.804187 -v -0.066000 0.112000 0.126700 -vn -0.227458 0.549133 0.804186 -v -0.066000 0.112000 0.117700 -vn -0.227458 -0.549133 0.804186 -v -0.066000 0.116500 0.117700 -vn -0.227459 -0.549132 -0.804187 -v -0.066000 0.116500 0.126700 -vn -0.765313 0.483795 -0.424546 -v -0.066700 0.111300 0.126700 -vn -0.765312 -0.483795 -0.424546 -v -0.066700 0.117200 0.126700 -vn -0.765310 -0.483795 0.424551 -v -0.066700 0.117200 0.107700 -vn -0.765310 0.483795 0.424551 -v -0.066700 0.111300 0.107700 -vn -0.227459 0.549132 0.804187 -v -0.066000 0.112000 0.107700 -vn -0.227459 -0.549132 0.804187 -v -0.066000 0.116500 0.107700 -vn -0.227458 -0.549133 -0.804186 -v -0.066000 0.116500 0.116700 -vn -0.227458 0.549133 -0.804186 -v -0.066000 0.112000 0.116700 -vn -0.126934 0.979699 -0.155171 -v -0.069500 0.134833 0.116355 -vn -0.126931 0.883801 -0.450316 -v -0.069500 0.134311 0.114748 -vn -0.129678 0.943027 -0.306404 -v -0.069500 0.134636 0.115531 -vn -0.126918 0.701387 -0.701390 -v -0.069500 0.133318 0.113382 -vn -0.129686 0.802184 -0.582823 -v -0.069500 0.133869 0.114026 -vn -0.126931 0.450320 -0.883799 -v -0.069500 0.131952 0.112389 -vn -0.129672 0.582823 -0.802186 -v -0.069500 0.132674 0.112831 -vn -0.126932 0.155171 -0.979699 -v -0.069500 0.130345 0.111866 -vn -0.129705 0.306406 -0.943023 -v -0.069500 0.131169 0.112064 -vn -0.126932 -0.155168 -0.979699 -v -0.069500 0.128655 0.111866 -vn -0.129698 -0.000001 -0.991554 -v -0.069500 0.129500 0.111800 -vn -0.126932 -0.450321 -0.883798 -v -0.069500 0.127048 0.112389 -vn -0.129692 -0.306407 -0.943024 -v -0.069500 0.127831 0.112064 -vn -0.126917 -0.701387 -0.701391 -v -0.069500 0.125682 0.113382 -vn -0.129673 -0.582821 -0.802187 -v -0.069500 0.126326 0.112831 -vn -0.126932 -0.883801 -0.450316 -v -0.069500 0.124689 0.114748 -vn -0.129685 -0.802187 -0.582819 -v -0.069500 0.125131 0.114026 -vn -0.126932 -0.979699 -0.155170 -v -0.069500 0.124166 0.116355 -vn -0.129698 -0.943024 -0.306406 -v -0.069500 0.124364 0.115531 -vn -0.126932 -0.979700 0.155168 -v -0.069500 0.124166 0.118045 -vn -0.129698 -0.991554 0.000001 -v -0.069500 0.124100 0.117200 -vn -0.126923 -0.883802 0.450316 -v -0.069500 0.124689 0.119652 -vn -0.129698 -0.943023 0.306410 -v -0.069500 0.124364 0.118869 -vn -0.126933 -0.701387 0.701388 -v -0.069500 0.125682 0.121018 -vn -0.129685 -0.802188 0.582818 -v -0.069500 0.125131 0.120374 -vn -0.126951 -0.450315 0.883798 -v -0.069500 0.127048 0.122011 -vn -0.129691 -0.582821 0.802185 -v -0.069500 0.126326 0.121569 -vn -0.126930 -0.155168 0.979700 -v -0.069500 0.128655 0.122534 -vn -0.129673 -0.306406 0.943027 -v -0.069500 0.127831 0.122336 -vn -0.126931 0.155170 0.979699 -v -0.069500 0.130345 0.122534 -vn -0.129677 -0.000001 0.991556 -v -0.069500 0.129500 0.122600 -vn -0.126951 0.450318 0.883797 -v -0.069500 0.131952 0.122011 -vn -0.129685 0.306405 0.943026 -v -0.069500 0.131169 0.122336 -vn -0.126933 0.701387 0.701388 -v -0.069500 0.133318 0.121018 -vn -0.129692 0.582820 0.802185 -v -0.069500 0.132674 0.121569 -vn -0.126922 0.883801 0.450318 -v -0.069500 0.134311 0.119652 -vn -0.129686 0.802186 0.582820 -v -0.069500 0.133869 0.120374 -vn -0.129719 0.991551 -0.000003 -v -0.069500 0.134900 0.117200 -vn -0.126931 0.979699 0.155173 -v -0.069500 0.134833 0.118045 -vn -0.129677 0.943027 0.306406 -v -0.069500 0.134636 0.118869 -vn -0.990583 -0.130213 -0.042309 -v -0.069800 0.124650 0.115624 -vn -0.990583 -0.135230 -0.021418 -v -0.069800 0.124463 0.116402 -vn -0.750899 0.615820 0.238572 -v -0.069800 0.125770 0.115755 -vn -0.750899 0.660417 -0.000000 -v -0.069800 0.125500 0.117200 -vn -0.990583 -0.096815 0.096814 -v -0.069800 0.125894 0.120806 -vn -0.990583 -0.080476 0.110767 -v -0.069800 0.126502 0.121326 -vn -0.750898 0.488054 -0.444922 -v -0.069800 0.126544 0.119895 -vn -0.750900 0.294373 -0.591181 -v -0.069800 0.127717 0.120781 -vn -0.750898 -0.180732 0.635207 -v -0.069800 0.130595 0.113353 -vn -0.750899 -0.397990 0.527024 -v -0.069800 0.131911 0.114008 -vn -0.990583 0.062157 -0.121991 -v -0.069800 0.131815 0.112656 -vn -0.750898 -0.561498 0.347667 -v -0.069800 0.132901 0.115094 -vn -0.990583 0.096815 -0.096815 -v -0.069800 0.133106 0.113594 -vn -0.990583 0.080476 -0.110766 -v -0.069800 0.132498 0.113074 -vn -0.990584 0.135223 -0.021417 -v -0.069800 0.134537 0.116402 -vn -0.750900 -0.649171 0.121353 -v -0.069800 0.133432 0.116465 -vn -0.990582 0.136921 0.000001 -v -0.069800 0.134600 0.117200 -vn -0.750899 -0.649172 -0.121353 -v -0.069800 0.133432 0.117935 -vn -0.990583 0.135225 0.021417 -v -0.069800 0.134537 0.117998 -vn -0.990582 0.042311 0.130220 -v -0.069800 0.131076 0.122050 -vn -0.990583 0.062158 0.121991 -v -0.069800 0.131815 0.121744 -vn -0.750900 -0.180732 -0.635205 -v -0.069800 0.130595 0.121047 -vn -0.750898 -0.397991 -0.527024 -v -0.069800 0.131911 0.120392 -vn -0.990582 -0.062160 0.121996 -v -0.069800 0.127185 0.121744 -vn -0.990582 -0.042312 0.130221 -v -0.069800 0.127924 0.122050 -vn -0.750898 0.060935 -0.657601 -v -0.069800 0.129131 0.121183 -vn -0.990582 -0.136922 -0.000000 -v -0.069800 0.124400 0.117200 -vn -0.990583 -0.135231 0.021419 -v -0.069800 0.124463 0.117998 -vn -0.750899 0.615819 -0.238572 -v -0.069800 0.125770 0.118645 -vn -0.750899 0.488054 0.444922 -v -0.069800 0.126544 0.114505 -vn -0.990583 -0.110766 -0.080476 -v -0.069800 0.125374 0.114202 -vn -0.990583 -0.121988 -0.062156 -v -0.069800 0.124956 0.114885 -vn -0.990583 -0.021419 -0.135232 -v -0.069800 0.128702 0.112163 -vn -0.990583 -0.042310 -0.130214 -v -0.069800 0.127924 0.112350 -vn -0.750899 0.060935 0.657600 -v -0.069800 0.129131 0.113217 -vn -0.750899 0.294374 0.591181 -v -0.069800 0.127717 0.113619 -vn -0.990583 0.130213 -0.042308 -v -0.069800 0.134350 0.115624 -vn -0.990583 0.121994 -0.062159 -v -0.069800 0.134044 0.114885 -vn -0.990583 0.110765 -0.080476 -v -0.069800 0.133626 0.114202 -vn -0.990583 0.130213 0.042308 -v -0.069800 0.134350 0.118776 -vn -0.750898 -0.561498 -0.347667 -v -0.069800 0.132901 0.119306 -vn -0.990582 0.121996 0.062161 -v -0.069800 0.134044 0.119515 -vn -0.990583 0.080476 0.110766 -v -0.069800 0.132498 0.121326 -vn -0.990582 0.096815 0.096816 -v -0.069800 0.133106 0.120806 -vn -0.990583 0.110766 0.080476 -v -0.069800 0.133626 0.120198 -vn -0.990582 -0.021421 0.135238 -v -0.069800 0.128702 0.122237 -vn -0.990583 0.000001 0.136915 -v -0.069800 0.129500 0.122300 -vn -0.990582 0.021419 0.135236 -v -0.069800 0.130298 0.122237 -vn -0.990583 -0.130213 0.042309 -v -0.069800 0.124650 0.118776 -vn -0.990583 -0.121991 0.062157 -v -0.069800 0.124956 0.119515 -vn -0.990583 -0.110767 0.080476 -v -0.069800 0.125374 0.120198 -vn -0.990582 -0.062159 -0.121997 -v -0.069800 0.127185 0.112656 -vn -0.990583 -0.080477 -0.110766 -v -0.069800 0.126502 0.113074 -vn -0.990583 -0.096815 -0.096814 -v -0.069800 0.125894 0.113594 -vn -0.990583 0.042310 -0.130215 -v -0.069800 0.131076 0.112350 -vn -0.990583 0.021418 -0.135230 -v -0.069800 0.130298 0.112163 -vn -0.990582 0.000001 -0.136922 -v -0.069800 0.129500 0.112100 -vn -0.667992 0.744168 0.000000 -v -0.069200 0.125500 0.117200 -vn -0.667992 0.693915 -0.268827 -v -0.069200 0.125770 0.118645 -vn -0.667994 0.549945 -0.501343 -v -0.069200 0.126544 0.119895 -vn -0.667992 0.331704 -0.666152 -v -0.069200 0.127717 0.120781 -vn -0.667993 0.068663 -0.740993 -v -0.069200 0.129131 0.121183 -vn -0.667992 -0.203652 -0.715760 -v -0.069200 0.130595 0.121047 -vn -0.667993 -0.448462 -0.593858 -v -0.069200 0.131911 0.120392 -vn -0.667993 -0.632703 -0.391755 -v -0.069200 0.132901 0.119306 -vn -0.667992 -0.731497 -0.136742 -v -0.069200 0.133432 0.117935 -vn -0.667992 -0.731497 0.136743 -v -0.069200 0.133432 0.116465 -vn -0.667993 -0.632703 0.391755 -v -0.069200 0.132901 0.115094 -vn -0.667992 -0.448462 0.593859 -v -0.069200 0.131911 0.114008 -vn -0.667993 -0.203651 0.715759 -v -0.069200 0.130595 0.113353 -vn -0.667992 0.068663 0.740994 -v -0.069200 0.129131 0.113217 -vn -0.667993 0.331704 0.666152 -v -0.069200 0.127717 0.113619 -vn -0.667993 0.549945 0.501344 -v -0.069200 0.126544 0.114505 -vn -0.667992 0.693915 0.268826 -v -0.069200 0.125770 0.115755 -vn -0.976003 0.108879 0.188584 -v -0.069200 0.128737 0.115879 -vn -0.976001 0.188590 0.108881 -v -0.069200 0.128179 0.116437 -vn -0.976002 0.217762 0.000001 -v -0.069200 0.127975 0.117200 -vn -0.976001 0.188589 -0.108883 -v -0.069200 0.128179 0.117962 -vn -0.976002 -0.108881 0.188589 -v -0.069200 0.130262 0.115879 -vn -0.976002 -0.000000 0.217761 -v -0.069200 0.129500 0.115675 -vn -0.976003 -0.188582 -0.108879 -v -0.069200 0.130821 0.117962 -vn -0.976002 -0.217760 0.000001 -v -0.069200 0.131025 0.117200 -vn -0.976003 -0.188583 0.108878 -v -0.069200 0.130821 0.116437 -vn -0.976002 -0.000000 -0.217761 -v -0.069200 0.129500 0.118725 -vn -0.976002 -0.108881 -0.188588 -v -0.069200 0.130262 0.118521 -vn -0.976003 0.108880 -0.188583 -v -0.069200 0.128737 0.118521 -vn 1.000000 -0.000003 -0.000001 -v -0.066981 0.138500 0.107950 -vn 0.460548 -0.768709 -0.443826 -v -0.066500 0.139193 0.108350 -vn 0.460548 -0.443818 -0.768714 -v -0.066500 0.138900 0.108643 -vn 0.460547 -0.887635 0.000000 -v -0.066500 0.139300 0.107950 -vn 0.460550 0.443815 -0.768715 -v -0.066500 0.138100 0.108643 -vn 0.460549 0.768717 -0.443813 -v -0.066500 0.137807 0.108350 -vn 0.460547 -0.000004 -0.887635 -v -0.066500 0.138500 0.108750 -vn 0.460549 0.768719 0.443808 -v -0.066500 0.137807 0.107550 -vn 0.460549 0.443813 0.768716 -v -0.066500 0.138100 0.107257 -vn 0.460551 0.887633 -0.000000 -v -0.066500 0.137700 0.107950 -vn 0.460548 -0.443816 0.768715 -v -0.066500 0.138900 0.107257 -vn 0.460548 -0.768712 0.443821 -v -0.066500 0.139193 0.107550 -vn 0.460549 -0.000004 0.887634 -v -0.066500 0.138500 0.107150 -vn 0.539406 -0.842046 -0.000001 -v -0.062058 0.139300 0.107950 -vn 0.539406 -0.729228 -0.421032 -v -0.062058 0.139193 0.108350 -vn 0.539411 -0.421021 -0.729230 -v -0.062058 0.138900 0.108643 -vn 0.539406 -0.000003 -0.842046 -v -0.062058 0.138500 0.108750 -vn 0.539397 0.421027 -0.729238 -v -0.062058 0.138100 0.108643 -vn 0.539409 0.729233 -0.421019 -v -0.062058 0.137807 0.108350 -vn 0.539400 0.842050 0.000000 -v -0.062058 0.137700 0.107950 -vn 0.539408 0.729237 0.421013 -v -0.062058 0.137807 0.107550 -vn 0.539400 0.421022 0.729238 -v -0.062058 0.138100 0.107257 -vn 0.539402 -0.000004 0.842048 -v -0.062058 0.138500 0.107150 -vn 0.539414 -0.421016 0.729231 -v -0.062058 0.138900 0.107257 -vn 0.539406 -0.729231 0.421026 -v -0.062058 0.139193 0.107550 -vn 1.000000 -0.000003 -0.000003 -v -0.066981 0.138500 0.126450 -vn 0.460548 -0.768711 -0.443823 -v -0.066500 0.139193 0.126850 -vn 0.460548 -0.443823 -0.768711 -v -0.066500 0.138900 0.127143 -vn 0.460547 -0.887635 -0.000004 -v -0.066500 0.139300 0.126450 -vn 0.460549 0.443820 -0.768712 -v -0.066500 0.138100 0.127143 -vn 0.460549 0.768718 -0.443810 -v -0.066500 0.137807 0.126850 -vn 0.460547 -0.000004 -0.887635 -v -0.066500 0.138500 0.127250 -vn 0.460550 0.768720 0.443806 -v -0.066500 0.137807 0.126050 -vn 0.460550 0.443806 0.768720 -v -0.066500 0.138100 0.125757 -vn 0.460551 0.887633 -0.000004 -v -0.066500 0.137700 0.126450 -vn 0.460549 -0.443810 0.768718 -v -0.066500 0.138900 0.125757 -vn 0.460549 -0.768712 0.443820 -v -0.066500 0.139193 0.126050 -vn 0.460551 -0.000004 0.887633 -v -0.066500 0.138500 0.125650 -vn 0.539405 -0.842046 -0.000004 -v -0.062058 0.139300 0.126450 -vn 0.539412 -0.729228 -0.421023 -v -0.062058 0.139193 0.126850 -vn 0.539413 -0.421024 -0.729227 -v -0.062058 0.138900 0.127143 -vn 0.539406 -0.000003 -0.842046 -v -0.062058 0.138500 0.127250 -vn 0.539398 0.421031 -0.729234 -v -0.062058 0.138100 0.127143 -vn 0.539414 0.729233 -0.421013 -v -0.062058 0.137807 0.126850 -vn 0.539400 0.842050 -0.000003 -v -0.062058 0.137700 0.126450 -vn 0.539401 0.729240 0.421017 -v -0.062058 0.137807 0.126050 -vn 0.539375 0.421018 0.729259 -v -0.062058 0.138100 0.125757 -vn 0.539397 0.000002 0.842052 -v -0.062058 0.138500 0.125650 -vn 0.539391 -0.421017 0.729248 -v -0.062058 0.138900 0.125757 -vn 0.539398 -0.729234 0.421031 -v -0.062058 0.139193 0.126050 -vn 1.000000 -0.000001 0.000001 -v -0.066981 0.096500 0.106800 -vn 0.460549 -0.768714 -0.443816 -v -0.066500 0.097193 0.107200 -vn 0.460548 -0.443820 -0.768713 -v -0.066500 0.096900 0.107493 -vn 0.460547 -0.887635 0.000000 -v -0.066500 0.097300 0.106800 -vn 0.460549 0.443815 -0.768715 -v -0.066500 0.096100 0.107493 -vn 0.460549 0.768715 -0.443815 -v -0.066500 0.095807 0.107200 -vn 0.460549 0.000000 -0.887634 -v -0.066500 0.096500 0.107600 -vn 0.460548 0.768713 0.443820 -v -0.066500 0.095807 0.106400 -vn 0.460549 0.443816 0.768714 -v -0.066500 0.096100 0.106107 -vn 0.460549 0.887634 0.000000 -v -0.066500 0.095700 0.106800 -vn 0.460548 -0.443821 0.768712 -v -0.066500 0.096900 0.106107 -vn 0.460548 -0.768712 0.443821 -v -0.066500 0.097193 0.106400 -vn 0.460547 0.000000 0.887635 -v -0.066500 0.096500 0.106000 -vn 0.539406 -0.842046 -0.000001 -v -0.062058 0.097300 0.106800 -vn 0.539404 -0.729235 -0.421023 -v -0.062058 0.097193 0.107200 -vn 0.539408 -0.421025 -0.729230 -v -0.062058 0.096900 0.107493 -vn 0.539403 0.000000 -0.842048 -v -0.062058 0.096500 0.107600 -vn 0.539407 0.421020 -0.729234 -v -0.062058 0.096100 0.107493 -vn 0.539407 0.729234 -0.421020 -v -0.062058 0.095807 0.107200 -vn 0.539403 0.842048 0.000000 -v -0.062058 0.095700 0.106800 -vn 0.539408 0.729231 0.421025 -v -0.062058 0.095807 0.106400 -vn 0.539404 0.421023 0.729234 -v -0.062058 0.096100 0.106107 -vn 0.539406 -0.000001 0.842046 -v -0.062058 0.096500 0.106000 -vn 0.539405 -0.421027 0.729231 -v -0.062058 0.096900 0.106107 -vn 0.539406 -0.729231 0.421028 -v -0.062058 0.097193 0.106400 -vn 1.000000 -0.000001 0.000000 -v -0.066981 0.096500 0.127600 -vn 0.460548 -0.768710 -0.443825 -v -0.066500 0.097193 0.128000 -vn 0.460549 -0.443816 -0.768714 -v -0.066500 0.096900 0.128293 -vn 0.460548 -0.887635 -0.000000 -v -0.066500 0.097300 0.127600 -vn 0.460550 0.443812 -0.768717 -v -0.066500 0.096100 0.128293 -vn 0.460548 0.768711 -0.443823 -v -0.066500 0.095807 0.128000 -vn 0.460547 0.000000 -0.887635 -v -0.066500 0.096500 0.128400 -vn 0.460548 0.768711 0.443823 -v -0.066500 0.095807 0.127200 -vn 0.460550 0.443812 0.768717 -v -0.066500 0.096100 0.126907 -vn 0.460550 0.887634 -0.000000 -v -0.066500 0.095700 0.127600 -vn 0.460549 -0.443816 0.768714 -v -0.066500 0.096900 0.126907 -vn 0.460548 -0.768710 0.443825 -v -0.066500 0.097193 0.127200 -vn 0.460547 0.000000 0.887635 -v -0.066500 0.096500 0.126800 -vn 0.539406 -0.842046 0.000003 -v -0.062058 0.097300 0.127600 -vn 0.539398 -0.729233 -0.421034 -v -0.062058 0.097193 0.128000 -vn 0.539403 -0.421025 -0.729234 -v -0.062058 0.096900 0.128293 -vn 0.539406 0.000001 -0.842046 -v -0.062058 0.096500 0.128400 -vn 0.539403 0.421018 -0.729238 -v -0.062058 0.096100 0.128293 -vn 0.539401 0.729233 -0.421029 -v -0.062058 0.095807 0.128000 -vn 0.539402 0.842048 0.000002 -v -0.062058 0.095700 0.127600 -vn 0.539402 0.729230 0.421034 -v -0.062058 0.095807 0.127200 -vn 0.539402 0.421021 0.729237 -v -0.062058 0.096100 0.126907 -vn 0.539406 -0.000001 0.842046 -v -0.062058 0.096500 0.126800 -vn 0.539404 -0.421023 0.729235 -v -0.062058 0.096900 0.126907 -vn 0.539400 -0.729231 0.421034 -v -0.062058 0.097193 0.127200 -vn -0.539395 0.842053 0.000002 -v -0.069041 0.128250 0.117200 -vn -0.539396 0.729239 -0.421025 -v -0.069041 0.128417 0.117825 -vn -0.539399 0.421022 -0.729239 -v -0.069041 0.128875 0.118283 -vn -0.539398 -0.000000 -0.842051 -v -0.069041 0.129500 0.118450 -vn -0.539396 -0.421030 -0.729236 -v -0.069041 0.130125 0.118283 -vn -0.539401 -0.729234 -0.421028 -v -0.069041 0.130583 0.117825 -vn -0.539400 -0.842049 0.000002 -v -0.069041 0.130750 0.117200 -vn -0.539401 -0.729236 0.421024 -v -0.069041 0.130583 0.116575 -vn -0.539397 -0.421027 0.729237 -v -0.069041 0.130125 0.116117 -vn -0.539398 -0.000000 0.842051 -v -0.069041 0.129500 0.115950 -vn -0.539400 0.421019 0.729239 -v -0.069041 0.128875 0.116117 -vn -0.539396 0.729241 0.421022 -v -0.069041 0.128417 0.116575 -vn -0.406933 0.913458 -0.000006 -v -0.066900 0.136100 0.111200 -vn -0.406967 0.791069 -0.456714 -v -0.066900 0.136221 0.111650 -vn -0.406948 0.456724 -0.791073 -v -0.066900 0.136550 0.111979 -vn -0.406965 0.000003 -0.913444 -v -0.066900 0.137000 0.112100 -vn -0.406965 -0.456710 -0.791072 -v -0.066900 0.137450 0.111979 -vn -0.406942 -0.791082 -0.456714 -v -0.066900 0.137779 0.111650 -vn -0.406962 -0.913445 -0.000005 -v -0.066900 0.137900 0.111200 -vn -0.406943 -0.791074 0.456727 -v -0.066900 0.137779 0.110750 -vn -0.406975 -0.456715 0.791064 -v -0.066900 0.137450 0.110421 -vn -0.406951 0.000004 0.913450 -v -0.066900 0.137000 0.110300 -vn -0.406960 0.456727 0.791065 -v -0.066900 0.136550 0.110421 -vn -0.406970 0.791061 0.456726 -v -0.066900 0.136221 0.110750 -vn -0.406951 0.913450 -0.000003 -v -0.066900 0.122600 0.109200 -vn -0.406969 0.791064 -0.456721 -v -0.066900 0.122721 0.109650 -vn -0.406962 0.456727 -0.791064 -v -0.066900 0.123050 0.109979 -vn -0.406968 0.000000 -0.913442 -v -0.066900 0.123500 0.110100 -vn -0.406970 -0.456719 -0.791065 -v -0.066900 0.123950 0.109979 -vn -0.406957 -0.791070 -0.456721 -v -0.066900 0.124279 0.109650 -vn -0.406965 -0.913444 -0.000002 -v -0.066900 0.124400 0.109200 -vn -0.406956 -0.791071 0.456721 -v -0.066900 0.124279 0.108750 -vn -0.406955 -0.456719 0.791073 -v -0.066900 0.123950 0.108421 -vn -0.406965 -0.000002 0.913444 -v -0.066900 0.123500 0.108300 -vn -0.406948 0.456731 0.791069 -v -0.066900 0.123050 0.108421 -vn -0.406968 0.791063 0.456723 -v -0.066900 0.122721 0.108750 -vn -0.406965 0.913444 0.000002 -v -0.066900 0.107100 0.109200 -vn -0.406957 0.791068 -0.456725 -v -0.066900 0.107221 0.109650 -vn -0.406969 0.456721 -0.791064 -v -0.066900 0.107550 0.109979 -vn -0.406969 -0.000001 -0.913442 -v -0.066900 0.108000 0.110100 -vn -0.406970 -0.456723 -0.791062 -v -0.066900 0.108450 0.109979 -vn -0.406971 -0.791062 -0.456724 -v -0.066900 0.108779 0.109650 -vn -0.406951 -0.913450 0.000003 -v -0.066900 0.108900 0.109200 -vn -0.406968 -0.791067 0.456716 -v -0.066900 0.108779 0.108750 -vn -0.406957 -0.456721 0.791070 -v -0.066900 0.108450 0.108421 -vn -0.406965 -0.000002 0.913444 -v -0.066900 0.108000 0.108300 -vn -0.406956 0.456721 0.791071 -v -0.066900 0.107550 0.108421 -vn -0.406955 0.791073 0.456719 -v -0.066900 0.107221 0.108750 -vn -0.406933 0.913458 -0.000006 -v -0.066900 0.136100 0.123200 -vn -0.406967 0.791066 -0.456719 -v -0.066900 0.136221 0.123650 -vn -0.406962 0.456727 -0.791064 -v -0.066900 0.136550 0.123979 -vn -0.406968 0.000000 -0.913442 -v -0.066900 0.137000 0.124100 -vn -0.406978 -0.456708 -0.791067 -v -0.066900 0.137450 0.123979 -vn -0.406944 -0.791079 -0.456717 -v -0.066900 0.137779 0.123650 -vn -0.406962 -0.913445 -0.000005 -v -0.066900 0.137900 0.123200 -vn -0.406943 -0.791074 0.456727 -v -0.066900 0.137779 0.122750 -vn -0.406975 -0.456715 0.791064 -v -0.066900 0.137450 0.122421 -vn -0.406969 0.000001 0.913442 -v -0.066900 0.137000 0.122300 -vn -0.406961 0.456729 0.791063 -v -0.066900 0.136550 0.122421 -vn -0.406970 0.791061 0.456726 -v -0.066900 0.136221 0.122750 -vn -0.406966 0.913444 0.000004 -v -0.066900 0.107100 0.125200 -vn -0.406948 0.791069 -0.456731 -v -0.066900 0.107221 0.125650 -vn -0.406968 0.456723 -0.791063 -v -0.066900 0.107550 0.125979 -vn -0.406969 -0.000001 -0.913442 -v -0.066900 0.108000 0.126100 -vn -0.406970 -0.456723 -0.791062 -v -0.066900 0.108450 0.125979 -vn -0.406962 -0.791064 -0.456727 -v -0.066900 0.108779 0.125650 -vn -0.406951 -0.913450 0.000005 -v -0.066900 0.108900 0.125200 -vn -0.406968 -0.791066 0.456718 -v -0.066900 0.108779 0.124750 -vn -0.406957 -0.456721 0.791070 -v -0.066900 0.108450 0.124421 -vn -0.406965 -0.000002 0.913444 -v -0.066900 0.108000 0.124300 -vn -0.406956 0.456721 0.791071 -v -0.066900 0.107550 0.124421 -vn -0.406955 0.791072 0.456721 -v -0.066900 0.107221 0.124750 -vn -0.406951 0.913450 -0.000002 -v -0.066900 0.122600 0.125200 -vn -0.406960 0.791065 -0.456727 -v -0.066900 0.122721 0.125650 -vn -0.406961 0.456729 -0.791063 -v -0.066900 0.123050 0.125979 -vn -0.406968 0.000000 -0.913442 -v -0.066900 0.123500 0.126100 -vn -0.406970 -0.456719 -0.791065 -v -0.066900 0.123950 0.125979 -vn -0.406948 -0.791073 -0.456724 -v -0.066900 0.124279 0.125650 -vn -0.406965 -0.913444 -0.000001 -v -0.066900 0.124400 0.125200 -vn -0.406956 -0.791070 0.456722 -v -0.066900 0.124279 0.124750 -vn -0.406955 -0.456719 0.791073 -v -0.066900 0.123950 0.124421 -vn -0.406965 -0.000002 0.913444 -v -0.066900 0.123500 0.124300 -vn -0.406948 0.456731 0.791069 -v -0.066900 0.123050 0.124421 -vn -0.406968 0.791062 0.456725 -v -0.066900 0.122721 0.124750 -vn -0.496976 0.033954 -0.867100 -v -0.066500 0.136000 0.104334 -vn -0.863075 0.019976 -0.504681 -v -0.066866 0.136000 0.104700 -vn -0.863077 0.504677 -0.019974 -v -0.066866 0.140500 0.109200 -vn -0.860426 0.503302 -0.079716 -v -0.066866 0.140445 0.108496 -vn -0.496980 0.867098 -0.033951 -v -0.066500 0.140866 0.109200 -vn -0.494486 0.858484 -0.135973 -v -0.066500 0.140806 0.108439 -vn -0.494484 0.826646 -0.268594 -v -0.066500 0.140628 0.107696 -vn -0.494487 0.774451 -0.394599 -v -0.066500 0.140336 0.106991 -vn -0.494485 0.703186 -0.510896 -v -0.066500 0.139937 0.106340 -vn -0.494478 0.614612 -0.614608 -v -0.066500 0.139441 0.105759 -vn -0.494480 0.510896 -0.703189 -v -0.066500 0.138860 0.105263 -vn -0.494476 0.394605 -0.774455 -v -0.066500 0.138209 0.104864 -vn -0.494478 0.268594 -0.826649 -v -0.066500 0.137504 0.104572 -vn -0.494484 0.135971 -0.858486 -v -0.066500 0.136761 0.104394 -vn -0.860421 0.484644 -0.157468 -v -0.066866 0.140280 0.107809 -vn -0.860426 0.454034 -0.231344 -v -0.066866 0.140010 0.107157 -vn -0.860425 0.412257 -0.299521 -v -0.066866 0.139641 0.106555 -vn -0.860423 0.360330 -0.360326 -v -0.066866 0.139182 0.106018 -vn -0.860424 0.299524 -0.412259 -v -0.066866 0.138645 0.105559 -vn -0.860424 0.231343 -0.454038 -v -0.066866 0.138043 0.105190 -vn -0.860422 0.157470 -0.484641 -v -0.066866 0.137391 0.104920 -vn -0.860423 0.079715 -0.503307 -v -0.066866 0.136704 0.104755 -vn -0.863077 0.504678 0.019975 -v -0.066866 0.140500 0.125200 -vn -0.496982 0.867097 0.033951 -v -0.066500 0.140866 0.125200 -vn -0.863074 0.019974 0.504683 -v -0.066866 0.136000 0.129700 -vn -0.860424 0.079717 0.503305 -v -0.066866 0.136704 0.129645 -vn -0.496971 0.033951 0.867103 -v -0.066500 0.136000 0.130066 -vn -0.494476 0.135970 0.858491 -v -0.066500 0.136761 0.130006 -vn -0.494475 0.268595 0.826651 -v -0.066500 0.137504 0.129828 -vn -0.494480 0.394604 0.774453 -v -0.066500 0.138209 0.129536 -vn -0.494481 0.510898 0.703187 -v -0.066500 0.138860 0.129137 -vn -0.494474 0.614610 0.614614 -v -0.066500 0.139441 0.128641 -vn -0.494489 0.703186 0.510891 -v -0.066500 0.139937 0.128060 -vn -0.494490 0.774450 0.394597 -v -0.066500 0.140336 0.127409 -vn -0.494484 0.826645 0.268595 -v -0.066500 0.140628 0.126704 -vn -0.494484 0.858485 0.135973 -v -0.066500 0.140806 0.125961 -vn -0.860425 0.157470 0.484636 -v -0.066866 0.137391 0.129480 -vn -0.860423 0.231344 0.454041 -v -0.066866 0.138043 0.129210 -vn -0.860421 0.299524 0.412263 -v -0.066866 0.138645 0.128841 -vn -0.860423 0.360330 0.360325 -v -0.066866 0.139182 0.128382 -vn -0.860426 0.412257 0.299518 -v -0.066866 0.139641 0.127845 -vn -0.860426 0.454035 0.231342 -v -0.066866 0.140010 0.127243 -vn -0.860420 0.484643 0.157474 -v -0.066866 0.140280 0.126591 -vn -0.860427 0.503300 0.079711 -v -0.066866 0.140445 0.125904 -vn -0.127828 0.495888 0.858927 -v -0.069700 0.103850 0.127160 -vn -0.127825 0.858914 0.495911 -v -0.069700 0.103960 0.127050 -vn -0.854928 -0.069782 0.514032 -v -0.069960 0.097300 0.127050 -vn -0.854921 0.069791 0.514041 -v -0.069960 0.103700 0.127050 -vn -0.488318 -0.112924 0.865329 -v -0.069850 0.097300 0.127160 -vn -0.488328 0.112918 0.865324 -v -0.069850 0.103700 0.127160 -vn -0.127818 -0.858927 0.495890 -v -0.069700 0.097040 0.127050 -vn -0.127833 -0.495880 0.858930 -v -0.069700 0.097150 0.127160 -vn -0.488344 0.865314 0.112921 -v -0.069850 0.103960 0.126900 -vn -0.482333 0.758615 0.438016 -v -0.069850 0.103925 0.127030 -vn -0.847418 0.265434 0.459813 -v -0.069960 0.103775 0.127030 -vn -0.847434 0.459787 0.265427 -v -0.069960 0.103830 0.126975 -vn -0.482333 0.437983 0.758634 -v -0.069850 0.103830 0.127125 -vn -0.854926 0.514032 0.069808 -v -0.069960 0.103850 0.126900 -vn -0.482345 -0.437967 0.758636 -v -0.069850 0.097170 0.127125 -vn -0.854925 -0.514030 0.069826 -v -0.069960 0.097150 0.126900 -vn -0.847435 -0.459763 0.265464 -v -0.069960 0.097170 0.126975 -vn -0.847418 -0.265463 0.459796 -v -0.069960 0.097225 0.127030 -vn -0.482351 -0.758602 0.438018 -v -0.069850 0.097075 0.127030 -vn -0.488327 -0.865324 0.112920 -v -0.069850 0.097040 0.126900 -vn -0.127842 0.858914 -0.495906 -v -0.069700 0.103960 0.121350 -vn -0.127835 0.495888 -0.858926 -v -0.069700 0.103850 0.121240 -vn -0.854924 0.514034 -0.069812 -v -0.069960 0.103850 0.121500 -vn -0.488344 0.865313 -0.112928 -v -0.069850 0.103960 0.121500 -vn -0.854921 -0.514036 -0.069834 -v -0.069960 0.097150 0.121500 -vn -0.488327 -0.865323 -0.112931 -v -0.069850 0.097040 0.121500 -vn -0.127837 -0.495891 -0.858924 -v -0.069700 0.097150 0.121240 -vn -0.127842 -0.858925 -0.495887 -v -0.069700 0.097040 0.121350 -vn -0.488327 0.112925 -0.865323 -v -0.069850 0.103700 0.121240 -vn -0.482346 0.438001 -0.758615 -v -0.069850 0.103830 0.121275 -vn -0.847428 0.459787 -0.265446 -v -0.069960 0.103830 0.121425 -vn -0.847433 0.265460 -0.459769 -v -0.069960 0.103775 0.121370 -vn -0.482350 0.758623 -0.437983 -v -0.069850 0.103925 0.121370 -vn -0.854923 0.069827 -0.514035 -v -0.069960 0.103700 0.121350 -vn -0.482358 -0.758617 -0.437985 -v -0.069850 0.097075 0.121370 -vn -0.854925 -0.069827 -0.514031 -v -0.069960 0.097300 0.121350 -vn -0.847435 -0.265469 -0.459760 -v -0.069960 0.097225 0.121370 -vn -0.847432 -0.459768 -0.265465 -v -0.069960 0.097170 0.121425 -vn -0.482360 -0.437992 -0.758612 -v -0.069850 0.097170 0.121275 -vn -0.488329 -0.112922 -0.865323 -v -0.069850 0.097300 0.121240 -vn -0.127828 -0.858927 0.495888 -v -0.069700 0.097040 0.113050 -vn -0.127838 -0.495903 0.858916 -v -0.069700 0.097150 0.113160 -vn -0.488328 -0.865324 0.112918 -v -0.069850 0.097040 0.112900 -vn -0.488327 -0.865323 -0.112925 -v -0.069850 0.097040 0.107500 -vn -0.854925 -0.514031 0.069822 -v -0.069960 0.097150 0.112900 -vn -0.854923 -0.514035 -0.069827 -v -0.069960 0.097150 0.107500 -vn -0.127842 -0.495906 -0.858914 -v -0.069700 0.097150 0.107240 -vn -0.127835 -0.858926 -0.495888 -v -0.069700 0.097040 0.107350 -vn -0.488343 -0.112926 0.865314 -v -0.069850 0.097300 0.113160 -vn -0.482355 -0.437979 0.758622 -v -0.069850 0.097170 0.113125 -vn -0.847434 -0.459763 0.265469 -v -0.069960 0.097170 0.112975 -vn -0.847428 -0.265454 0.459784 -v -0.069960 0.097225 0.113030 -vn -0.482353 -0.758611 0.438002 -v -0.069850 0.097075 0.113030 -vn -0.854926 -0.069808 0.514032 -v -0.069960 0.097300 0.113050 -vn -0.482346 -0.758615 -0.438001 -v -0.069850 0.097075 0.107370 -vn -0.854924 -0.069812 -0.514034 -v -0.069960 0.097300 0.107350 -vn -0.847428 -0.265446 -0.459787 -v -0.069960 0.097225 0.107370 -vn -0.847433 -0.459769 -0.265460 -v -0.069960 0.097170 0.107425 -vn -0.482350 -0.437983 -0.758623 -v -0.069850 0.097170 0.107275 -vn -0.488344 -0.112928 -0.865313 -v -0.069850 0.097300 0.107240 -vn -0.127833 0.495903 0.858917 -v -0.069700 0.103850 0.113160 -vn -0.127831 0.858917 0.495904 -v -0.069700 0.103960 0.113050 -vn -0.488344 0.112924 0.865314 -v -0.069850 0.103700 0.113160 -vn -0.854925 0.069806 0.514034 -v -0.069960 0.103700 0.113050 -vn -0.488343 0.112920 -0.865315 -v -0.069850 0.103700 0.107240 -vn -0.854927 0.069801 -0.514031 -v -0.069960 0.103700 0.107350 -vn -0.127833 0.858917 -0.495903 -v -0.069700 0.103960 0.107350 -vn -0.127831 0.495904 -0.858917 -v -0.069700 0.103850 0.107240 -vn -0.488343 0.865315 0.112920 -v -0.069850 0.103960 0.112900 -vn -0.482342 0.758621 0.437996 -v -0.069850 0.103925 0.113030 -vn -0.847426 0.265446 0.459790 -v -0.069960 0.103775 0.113030 -vn -0.847429 0.459785 0.265448 -v -0.069960 0.103830 0.112975 -vn -0.482343 0.437992 0.758623 -v -0.069850 0.103830 0.113125 -vn -0.854927 0.514031 0.069801 -v -0.069960 0.103850 0.112900 -vn -0.482342 0.437996 -0.758621 -v -0.069850 0.103830 0.107275 -vn -0.854925 0.514034 -0.069806 -v -0.069960 0.103850 0.107500 -vn -0.847426 0.459790 -0.265446 -v -0.069960 0.103830 0.107425 -vn -0.847429 0.265448 -0.459785 -v -0.069960 0.103775 0.107370 -vn -0.482343 0.758623 -0.437992 -v -0.069850 0.103925 0.107370 -vn -0.488344 0.865314 -0.112924 -v -0.069850 0.103960 0.107500 -vn -0.860434 -0.503289 0.079713 -v -0.069760 0.124315 0.118021 -vn -0.860427 -0.484634 0.157464 -v -0.069760 0.124507 0.118822 -vn -0.860434 -0.454023 0.231335 -v -0.069760 0.124822 0.119583 -vn -0.860432 -0.412248 0.299514 -v -0.069760 0.125253 0.120286 -vn -0.860431 -0.360318 0.360318 -v -0.069760 0.125788 0.120912 -vn -0.860424 -0.299523 0.412257 -v -0.069760 0.126414 0.121447 -vn -0.860428 -0.231341 0.454032 -v -0.069760 0.127117 0.121878 -vn -0.860435 -0.157460 0.484622 -v -0.069760 0.127878 0.122193 -vn -0.860431 -0.079714 0.503293 -v -0.069760 0.128679 0.122385 -vn -0.860430 -0.000000 0.509569 -v -0.069760 0.129500 0.122450 -vn -0.860432 0.079714 0.503291 -v -0.069760 0.130321 0.122385 -vn -0.860429 0.157465 0.484631 -v -0.069760 0.131122 0.122193 -vn -0.860430 0.231341 0.454029 -v -0.069760 0.131883 0.121878 -vn -0.860435 0.299511 0.412243 -v -0.069760 0.132586 0.121447 -vn -0.860431 0.360317 0.360320 -v -0.069760 0.133212 0.120912 -vn -0.860432 0.412247 0.299516 -v -0.069760 0.133747 0.120286 -vn -0.860431 0.454027 0.231339 -v -0.069760 0.134178 0.119583 -vn -0.860427 0.484634 0.157465 -v -0.069760 0.134493 0.118822 -vn -0.860428 0.503299 0.079711 -v -0.069760 0.134685 0.118021 -vn -0.860428 0.509572 0.000000 -v -0.069760 0.134750 0.117200 -vn -0.860427 0.503301 -0.079713 -v -0.069760 0.134685 0.116379 -vn -0.860425 0.484638 -0.157466 -v -0.069760 0.134493 0.115578 -vn -0.860429 0.454030 -0.231342 -v -0.069760 0.134178 0.114817 -vn -0.860437 0.412239 -0.299511 -v -0.069760 0.133747 0.114114 -vn -0.860438 0.360310 -0.360310 -v -0.069760 0.133212 0.113488 -vn -0.860435 0.299511 -0.412244 -v -0.069760 0.132586 0.112953 -vn -0.860429 0.231340 -0.454030 -v -0.069760 0.131883 0.112522 -vn -0.860424 0.157469 -0.484638 -v -0.069760 0.131122 0.112207 -vn -0.860434 0.079711 -0.503288 -v -0.069760 0.130321 0.112015 -vn -0.860428 0.000001 -0.509572 -v -0.069760 0.129500 0.111950 -vn -0.860433 -0.079713 -0.503290 -v -0.069760 0.128679 0.112015 -vn -0.860429 -0.157463 -0.484631 -v -0.069760 0.127878 0.112207 -vn -0.860427 -0.231341 -0.454034 -v -0.069760 0.127117 0.112522 -vn -0.860425 -0.299522 -0.412257 -v -0.069760 0.126414 0.112953 -vn -0.860438 -0.360312 -0.360307 -v -0.069760 0.125788 0.113488 -vn -0.860436 -0.412242 -0.299509 -v -0.069760 0.125253 0.114114 -vn -0.860431 -0.454028 -0.231338 -v -0.069760 0.124822 0.114817 -vn -0.860425 -0.484636 -0.157469 -v -0.069760 0.124507 0.115578 -vn -0.860433 -0.503290 -0.079712 -v -0.069760 0.124315 0.116379 -vn -0.860428 -0.509572 -0.000001 -v -0.069760 0.124250 0.117200 -vn -0.494485 -0.858485 0.135970 -v -0.069650 0.124206 0.118038 -vn -0.494483 -0.826646 0.268595 -v -0.069650 0.124403 0.118856 -vn -0.494473 -0.774458 0.394601 -v -0.069650 0.124724 0.119633 -vn -0.494479 -0.703192 0.510893 -v -0.069650 0.125164 0.120350 -vn -0.494482 -0.614610 0.614608 -v -0.069650 0.125710 0.120990 -vn -0.494473 -0.510900 0.703191 -v -0.069650 0.126350 0.121536 -vn -0.494492 -0.394597 0.774448 -v -0.069650 0.127067 0.121976 -vn -0.494475 -0.268598 0.826650 -v -0.069650 0.127844 0.122297 -vn -0.494485 -0.135969 0.858485 -v -0.069650 0.128662 0.122494 -vn -0.494469 -0.000002 0.869195 -v -0.069650 0.129500 0.122560 -vn -0.494484 0.135973 0.858485 -v -0.069650 0.130338 0.122494 -vn -0.494480 0.268590 0.826649 -v -0.069650 0.131156 0.122297 -vn -0.494494 0.394599 0.774447 -v -0.069650 0.131933 0.121976 -vn -0.494488 0.510895 0.703184 -v -0.069650 0.132650 0.121536 -vn -0.494482 0.614609 0.614608 -v -0.069650 0.133290 0.120990 -vn -0.494479 0.703190 0.510896 -v -0.069650 0.133836 0.120350 -vn -0.494473 0.774457 0.394604 -v -0.069650 0.134276 0.119633 -vn -0.494465 0.826656 0.268596 -v -0.069650 0.134597 0.118856 -vn -0.494472 0.858492 0.135971 -v -0.069650 0.134794 0.118038 -vn -0.494508 0.869173 -0.000004 -v -0.069650 0.134860 0.117200 -vn -0.494468 0.858495 -0.135968 -v -0.069650 0.134794 0.116362 -vn -0.494460 0.826660 -0.268593 -v -0.069650 0.134597 0.115544 -vn -0.494475 0.774457 -0.394601 -v -0.069650 0.134276 0.114767 -vn -0.494486 0.703186 -0.510895 -v -0.069650 0.133836 0.114050 -vn -0.494478 0.614610 -0.614611 -v -0.069650 0.133290 0.113410 -vn -0.494473 0.510900 -0.703191 -v -0.069650 0.132650 0.112864 -vn -0.494478 0.394601 -0.774456 -v -0.069650 0.131933 0.112424 -vn -0.494485 0.268591 -0.826646 -v -0.069650 0.131156 0.112103 -vn -0.494484 0.135971 -0.858486 -v -0.069650 0.130338 0.111906 -vn -0.494489 -0.000001 -0.869184 -v -0.069650 0.129500 0.111840 -vn -0.494484 -0.135970 -0.858486 -v -0.069650 0.128662 0.111906 -vn -0.494482 -0.268597 -0.826646 -v -0.069650 0.127844 0.112103 -vn -0.494476 -0.394603 -0.774456 -v -0.069650 0.127067 0.112424 -vn -0.494456 -0.510903 -0.703201 -v -0.069650 0.126350 0.112864 -vn -0.494477 -0.614611 -0.614610 -v -0.069650 0.125710 0.113410 -vn -0.494487 -0.703188 -0.510890 -v -0.069650 0.125164 0.114050 -vn -0.494478 -0.774457 -0.394599 -v -0.069650 0.124724 0.114767 -vn -0.494479 -0.826648 -0.268594 -v -0.069650 0.124403 0.115544 -vn -0.494482 -0.858487 -0.135970 -v -0.069650 0.124206 0.116362 -vn -0.494489 -0.869184 0.000001 -v -0.069650 0.124140 0.117200 -vn 0.673140 -0.513712 0.531961 -v -0.031500 0.131410 0.115222 -vn 0.674182 -0.313587 0.668687 -v -0.031500 0.130664 0.114709 -vn 0.389830 -0.465237 0.794724 -v -0.030300 0.130706 0.114728 -vn 0.675655 -0.079095 0.732963 -v -0.031500 0.129792 0.114466 -vn 0.390506 -0.189326 0.900922 -v -0.030300 0.129883 0.114477 -vn 0.386450 -0.329045 0.861618 -v -0.030300 0.130664 0.114709 -vn 0.676928 0.163115 0.717748 -v -0.031500 0.128889 0.114519 -vn 0.397979 0.113077 0.910399 -v -0.030300 0.129022 0.114492 -vn 0.392168 -0.046140 0.918736 -v -0.030300 0.129792 0.114466 -vn 0.678009 0.386936 0.624968 -v -0.031500 0.128051 0.114863 -vn 0.391665 0.390182 0.833280 -v -0.030300 0.128209 0.114772 -vn 0.381562 0.256527 0.888034 -v -0.030300 0.128889 0.114519 -vn 0.678898 0.568335 0.464858 -v -0.031500 0.127371 0.115460 -vn 0.392140 0.634070 0.666470 -v -0.030300 0.127522 0.115290 -vn 0.379255 0.525307 0.761721 -v -0.030300 0.128051 0.114863 -vn 0.679607 0.687894 0.254826 -v -0.031500 0.126921 0.116245 -vn 0.392531 0.812509 0.430985 -v -0.030300 0.127028 0.115994 -vn 0.377173 0.740178 0.556666 -v -0.030300 0.127371 0.115460 -vn 0.680131 0.732879 0.017593 -v -0.031500 0.126751 0.117134 -vn 0.392842 0.907101 0.151142 -v -0.030300 0.126777 0.116817 -vn 0.375399 0.878981 0.294054 -v -0.030300 0.126921 0.116245 -vn 0.680485 0.698556 -0.221269 -v -0.031500 0.126878 0.118031 -vn 0.393068 0.908120 -0.144275 -v -0.030300 0.126792 0.117678 -vn 0.374007 0.927426 0.001005 -v -0.030300 0.126751 0.117134 -vn 0.680657 0.588716 -0.436027 -v -0.031500 0.127290 0.118837 -vn 0.393199 0.815469 -0.424742 -v -0.030300 0.127072 0.118491 -vn 0.373048 0.880548 -0.292353 -v -0.030300 0.126878 0.118031 -vn 0.680658 0.415217 -0.603572 -v -0.031500 0.127941 0.119466 -vn 0.385463 0.632565 -0.671774 -v -0.030300 0.127590 0.119178 -vn 0.372554 0.743186 -0.555768 -v -0.030300 0.127290 0.118837 -vn 0.680483 0.196757 -0.705854 -v -0.031500 0.128761 0.119849 -vn 0.386240 0.387934 -0.836854 -v -0.030300 0.128294 0.119672 -vn 0.340451 0.551223 -0.761739 -v -0.030300 0.127941 0.119466 -vn 0.680133 -0.043156 -0.731818 -v -0.031500 0.129662 0.119945 -vn 0.396406 0.116064 -0.910709 -v -0.030300 0.129117 0.119923 -vn 0.347427 0.279388 -0.895118 -v -0.030300 0.128761 0.119849 -vn 0.679607 -0.278678 -0.678582 -v -0.031500 0.130544 0.119744 -vn 0.387547 -0.190753 -0.901899 -v -0.030300 0.129978 0.119908 -vn 0.388765 -0.039221 -0.920502 -v -0.030300 0.129662 0.119945 -vn 0.678898 -0.484411 -0.551764 -v -0.031500 0.131314 0.119267 -vn 0.388088 -0.465629 -0.795348 -v -0.030300 0.130791 0.119628 -vn 0.360369 -0.316062 -0.877633 -v -0.030300 0.130544 0.119744 -vn 0.678010 -0.638091 -0.364887 -v -0.031500 0.131887 0.118566 -vn 0.388559 -0.692765 -0.607534 -v -0.030300 0.131478 0.119110 -vn 0.366269 -0.577848 -0.729342 -v -0.030300 0.131314 0.119267 -vn 0.676928 -0.723003 -0.137967 -v -0.031500 0.132201 0.117717 -vn 0.388966 -0.848960 -0.357734 -v -0.030300 0.131972 0.118406 -vn 0.371749 -0.778410 -0.505845 -v -0.030300 0.131887 0.118566 -vn 0.675655 -0.729756 0.104621 -v -0.031500 0.132223 0.116812 -vn 0.397708 -0.913962 -0.080634 -v -0.030300 0.132223 0.117583 -vn 0.376775 -0.897148 -0.230578 -v -0.030300 0.132201 0.117717 -vn 0.674182 -0.657336 0.336732 -v -0.031500 0.131949 0.115949 -vn 0.389590 -0.893838 0.221978 -v -0.030300 0.132208 0.116722 -vn 0.395229 -0.915197 0.078794 -v -0.030300 0.132223 0.116812 -vn 0.396851 -0.637619 0.660266 -v -0.030300 0.131410 0.115222 -vn 0.389822 -0.777977 0.492738 -v -0.030300 0.131928 0.115909 -vn 0.385334 -0.850567 0.357845 -v -0.030300 0.131949 0.115949 -vn 0.916684 0.374754 0.138744 -v -0.030000 0.139534 0.120915 -vn 0.916683 0.346809 0.198534 -v -0.030000 0.138786 0.122516 -vn 0.934356 -0.356311 -0.004726 -v -0.030000 0.132549 0.117278 -vn 0.976001 -0.151272 0.156647 -v -0.030000 0.124457 0.110905 -vn 0.976002 -0.052681 0.211292 -v -0.030000 0.123993 0.110648 -vn 0.911763 -0.242089 -0.331783 -v -0.030000 0.123364 0.108434 -vn 0.976002 0.060023 0.209328 -v -0.030000 0.123463 0.110657 -vn 0.930603 0.005098 -0.365995 -v -0.030000 0.129422 0.120249 -vn 0.915894 -0.206182 0.344424 -v -0.030000 0.123673 0.126174 -vn 0.976002 -0.156645 -0.151272 -v -0.030000 0.124680 0.123667 -vn 0.933409 0.014962 0.358503 -v -0.030000 0.129316 0.114156 -vn 0.976002 -0.211292 -0.052681 -v -0.030000 0.124740 0.111891 -vn 0.976002 -0.209326 0.060024 -v -0.030000 0.124731 0.111360 -vn 0.976002 0.209326 -0.060024 -v -0.030000 0.122760 0.111925 -vn 0.916685 -0.346806 -0.198533 -v -0.030000 0.120214 0.111884 -vn 0.976002 0.211291 0.052682 -v -0.030000 0.122751 0.111395 -vn 0.916687 -0.309392 -0.252904 -v -0.030000 0.121216 0.110428 -vn 0.976003 0.156642 0.151268 -v -0.030000 0.123008 0.110931 -vn 0.976001 0.151272 -0.156647 -v -0.030000 0.123033 0.112380 -vn 0.916683 -0.392481 -0.075168 -v -0.030000 0.118991 0.115187 -vn 0.916684 -0.374755 -0.138743 -v -0.030000 0.119466 0.113485 -vn 0.976002 -0.211293 -0.052681 -v -0.030000 0.124937 0.123203 -vn 0.976002 -0.209327 0.060023 -v -0.030000 0.124928 0.122672 -vn 0.930833 0.064049 -0.359789 -v -0.030000 0.129076 0.120220 -vn 0.917899 -0.265984 -0.294473 -v -0.030000 0.122443 0.109157 -vn 0.916685 -0.355889 0.181746 -v -0.030000 0.119971 0.122066 -vn 0.916685 -0.380950 0.120690 -v -0.030000 0.119300 0.120432 -vn 0.976002 0.052681 -0.211292 -v -0.030000 0.123497 0.112637 -vn 0.916685 -0.395620 0.056342 -v -0.030000 0.118907 0.118709 -vn 0.916685 -0.399496 -0.009544 -v -0.030000 0.118803 0.116944 -vn 0.976002 -0.060023 -0.209328 -v -0.030000 0.124028 0.112628 -vn 0.976002 -0.052681 0.211292 -v -0.030000 0.124191 0.121960 -vn 0.976002 0.060023 0.209327 -v -0.030000 0.123660 0.121969 -vn 0.932765 0.356719 0.051969 -v -0.030000 0.126480 0.116776 -vn 0.933024 0.322413 0.159735 -v -0.030000 0.126759 0.115863 -vn 0.933383 0.256416 0.251092 -v -0.030000 0.127306 0.115081 -vn 0.976002 -0.156644 -0.151272 -v -0.030000 0.124483 0.112355 -vn 0.933857 0.165622 0.316986 -v -0.030000 0.128068 0.114507 -vn 0.930826 0.076196 0.357432 -v -0.030000 0.128970 0.114196 -vn 0.932592 0.355668 -0.061418 -v -0.030000 0.126496 0.117730 -vn 0.932490 0.319225 -0.168989 -v -0.030000 0.126807 0.118632 -vn 0.976002 -0.151272 0.156645 -v -0.030000 0.124655 0.122217 -vn 0.934774 0.242180 -0.259898 -v -0.030000 0.127381 0.119394 -vn 0.935150 0.151815 -0.320073 -v -0.030000 0.128163 0.119941 -vn 0.976002 0.156645 0.151272 -v -0.030000 0.123205 0.122243 -vn 0.976002 0.211292 0.052681 -v -0.030000 0.122948 0.122707 -vn 0.916685 -0.321121 0.237846 -v -0.030000 0.120902 0.123569 -vn 0.976002 0.209327 -0.060023 -v -0.030000 0.122957 0.123237 -vn 0.916683 -0.277595 0.287460 -v -0.030000 0.122067 0.124897 -vn 0.976002 0.151271 -0.156645 -v -0.030000 0.123231 0.123692 -vn 0.919654 -0.233919 0.315467 -v -0.030000 0.123435 0.126015 -vn 0.976002 0.052681 -0.211294 -v -0.030000 0.123695 0.123949 -vn 0.976002 -0.060023 -0.209327 -v -0.030000 0.124225 0.123940 -vn 0.976003 0.151268 -0.156643 -v -0.030000 0.134543 0.123495 -vn 0.976002 0.052682 -0.211291 -v -0.030000 0.135007 0.123752 -vn 0.916685 0.151736 0.369683 -v -0.030000 0.133563 0.127099 -vn 0.916686 0.309395 0.252907 -v -0.030000 0.137784 0.123972 -vn 0.916684 0.263553 0.300384 -v -0.030000 0.136557 0.125243 -vn 0.976002 -0.060024 -0.209326 -v -0.030000 0.135537 0.123743 -vn 0.931355 -0.358170 -0.065520 -v -0.030000 0.132520 0.117624 -vn 0.976002 0.060024 0.209326 -v -0.030000 0.134972 0.121772 -vn 0.916683 0.210517 0.339670 -v -0.030000 0.135137 0.126295 -vn 0.976002 -0.151268 0.156645 -v -0.030000 0.135967 0.122020 -vn 0.976002 -0.052682 0.211291 -v -0.030000 0.135503 0.121763 -vn 0.976002 0.211294 0.052682 -v -0.030000 0.134260 0.122509 -vn 0.976003 0.209321 -0.060021 -v -0.030000 0.134269 0.123040 -vn 0.917271 -0.166146 0.361953 -v -0.030000 0.124969 0.126893 -vn 0.916685 -0.107323 0.384930 -v -0.030000 0.126626 0.127507 -vn 0.976001 -0.156648 -0.151277 -v -0.030000 0.135992 0.123469 -vn 0.976002 -0.211291 -0.052680 -v -0.030000 0.136249 0.123005 -vn 0.976001 -0.209332 0.060026 -v -0.030000 0.136240 0.122475 -vn 0.933541 -0.074590 -0.350625 -v -0.030000 0.130030 0.120204 -vn 0.935067 -0.169550 -0.311290 -v -0.030000 0.130932 0.119893 -vn 0.976003 0.156644 0.151267 -v -0.030000 0.134517 0.122045 -vn 0.935159 -0.257039 -0.243738 -v -0.030000 0.131694 0.119319 -vn 0.935333 -0.319167 -0.152596 -v -0.030000 0.132241 0.118537 -vn 0.916685 0.088820 0.389615 -v -0.030000 0.131878 0.127632 -vn 0.916685 0.023479 0.398920 -v -0.030000 0.130129 0.127881 -vn 0.916682 -0.042501 0.397350 -v -0.030000 0.128362 0.127839 -vn 0.932525 -0.360728 0.016492 -v -0.030000 0.132544 0.117016 -vn 0.916685 0.355889 -0.181747 -v -0.030000 0.139029 0.112334 -vn 0.916687 0.380945 -0.120687 -v -0.030000 0.139700 0.113968 -vn 0.916682 0.395625 -0.056344 -v -0.030000 0.140093 0.115691 -vn 0.916685 0.399496 0.009544 -v -0.030000 0.140197 0.117456 -vn 0.916683 0.392481 0.075169 -v -0.030000 0.140009 0.119213 -vn 0.936216 -0.155504 0.315147 -v -0.030000 0.130837 0.114459 -vn 0.933457 -0.060414 0.353565 -v -0.030000 0.129924 0.114180 -vn 0.976003 0.209321 -0.060021 -v -0.030000 0.134072 0.111728 -vn 0.976002 0.211294 0.052682 -v -0.030000 0.134063 0.111197 -vn 0.937080 -0.242516 0.251130 -v -0.030000 0.131619 0.115006 -vn 0.976003 0.151268 -0.156643 -v -0.030000 0.134345 0.112183 -vn 0.936467 -0.309338 0.165346 -v -0.030000 0.132193 0.115768 -vn 0.976002 0.052682 -0.211291 -v -0.030000 0.134809 0.112440 -vn 0.932373 -0.352397 0.080607 -v -0.030000 0.132504 0.116670 -vn 0.976002 -0.060024 -0.209326 -v -0.030000 0.135340 0.112431 -vn 0.976003 -0.156644 -0.151267 -v -0.030000 0.135795 0.112157 -vn 0.976002 -0.211294 -0.052682 -v -0.030000 0.136052 0.111693 -vn 0.916689 0.321114 -0.237839 -v -0.030000 0.138098 0.110831 -vn 0.976003 -0.209321 0.060021 -v -0.030000 0.136043 0.111163 -vn 0.916683 0.277595 -0.287460 -v -0.030000 0.136933 0.109503 -vn 0.976002 -0.151272 0.156645 -v -0.030000 0.135769 0.110708 -vn 0.916685 0.226494 -0.329226 -v -0.030000 0.135565 0.108385 -vn 0.976002 -0.052681 0.211292 -v -0.030000 0.135305 0.110451 -vn 0.916686 0.169215 -0.362012 -v -0.030000 0.134031 0.107507 -vn 0.976002 0.060024 0.209326 -v -0.030000 0.134775 0.110460 -vn 0.916685 0.107322 -0.384930 -v -0.030000 0.132374 0.106893 -vn 0.976003 0.156644 0.151267 -v -0.030000 0.134320 0.110733 -vn 0.919041 -0.198161 -0.340728 -v -0.030000 0.123863 0.108105 -vn 0.916682 -0.151740 -0.369688 -v -0.030000 0.125437 0.107301 -vn 0.916686 -0.088819 -0.389613 -v -0.030000 0.127122 0.106768 -vn 0.916686 -0.023479 -0.398919 -v -0.030000 0.128871 0.106518 -vn 0.916686 0.042501 -0.397342 -v -0.030000 0.130638 0.106561 -vn -0.375746 0.643755 -0.666629 -v -0.034200 0.137141 0.109287 -vn 0.375747 0.525253 -0.763494 -v -0.030300 0.135735 0.108137 -vn -0.375749 0.525253 -0.763493 -v -0.034200 0.135735 0.108137 -vn 0.375750 0.392423 -0.839534 -v -0.030300 0.134158 0.107235 -vn -0.375752 0.392422 -0.839533 -v -0.034200 0.134158 0.107235 -vn 0.375747 0.248886 -0.892676 -v -0.030300 0.132454 0.106604 -vn -0.375750 0.248886 -0.892675 -v -0.034200 0.132454 0.106604 -vn 0.375750 0.098564 -0.921465 -v -0.030300 0.130670 0.106262 -vn -0.375751 0.098564 -0.921464 -v -0.034200 0.130670 0.106262 -vn 0.375748 -0.054450 -0.925121 -v -0.030300 0.128854 0.106219 -vn -0.375751 -0.054450 -0.925120 -v -0.034200 0.128854 0.106219 -vn 0.375748 -0.205978 -0.903541 -v -0.030300 0.127055 0.106475 -vn -0.375749 -0.205979 -0.903540 -v -0.034200 0.127055 0.106475 -vn 0.375741 -0.351887 -0.857318 -v -0.030300 0.125323 0.107024 -vn -0.375744 -0.351885 -0.857317 -v -0.034200 0.125323 0.107024 -vn 0.370880 -0.484071 -0.792542 -v -0.030300 0.123705 0.107850 -vn -0.375749 -0.488197 -0.787703 -v -0.034200 0.123705 0.107850 -vn 0.373009 -0.614877 -0.694831 -v -0.030300 0.122245 0.108931 -vn -0.375747 -0.611189 -0.696608 -v -0.034200 0.122245 0.108931 -vn 0.375752 -0.717510 -0.586507 -v -0.030300 0.120983 0.110238 -vn -0.375754 -0.717510 -0.586505 -v -0.034200 0.120983 0.110238 -vn 0.375746 -0.804263 -0.460409 -v -0.030300 0.119954 0.111735 -vn -0.372882 -0.804236 -0.462778 -v -0.034200 0.119954 0.111735 -vn 0.375744 -0.869075 -0.321753 -v -0.030300 0.119184 0.113381 -vn -0.375747 -0.869074 -0.321753 -v -0.034200 0.119184 0.113381 -vn 0.375744 -0.910181 -0.174320 -v -0.030300 0.118696 0.115131 -vn -0.375747 -0.910180 -0.174320 -v -0.034200 0.118696 0.115131 -vn 0.375747 -0.926458 -0.022132 -v -0.030300 0.118503 0.116937 -vn -0.375750 -0.926457 -0.022131 -v -0.034200 0.118503 0.116937 -vn 0.375746 -0.917465 0.130661 -v -0.030300 0.118610 0.118751 -vn -0.375749 -0.917464 0.130660 -v -0.034200 0.118610 0.118751 -vn 0.375747 -0.883446 0.279888 -v -0.030300 0.119014 0.120522 -vn -0.375750 -0.883445 0.279887 -v -0.034200 0.119014 0.120522 -vn 0.375747 -0.825329 0.421480 -v -0.030300 0.119704 0.122203 -vn -0.375750 -0.825328 0.421479 -v -0.034200 0.119704 0.122203 -vn 0.375746 -0.744699 0.551578 -v -0.030300 0.120661 0.123747 -vn -0.375749 -0.744697 0.551578 -v -0.034200 0.120661 0.123747 -vn 0.375743 -0.643756 0.666631 -v -0.030300 0.121859 0.125113 -vn -0.375746 -0.643755 0.666629 -v -0.034200 0.121859 0.125113 -vn 0.371081 -0.530227 0.762337 -v -0.030300 0.123265 0.126263 -vn -0.375745 -0.525254 0.763495 -v -0.034200 0.123265 0.126263 -vn 0.374426 -0.390854 0.840856 -v -0.030300 0.124842 0.127165 -vn -0.375752 -0.392422 0.839533 -v -0.034200 0.124842 0.127165 -vn 0.375746 -0.248887 0.892676 -v -0.030300 0.126546 0.127796 -vn -0.375749 -0.248887 0.892675 -v -0.034200 0.126546 0.127796 -vn 0.375742 -0.098561 0.921468 -v -0.030300 0.128330 0.128138 -vn -0.375745 -0.098563 0.921467 -v -0.034200 0.128330 0.128138 -vn 0.375748 0.054450 0.925121 -v -0.030300 0.130146 0.128181 -vn -0.375750 0.054451 0.925120 -v -0.034200 0.130146 0.128181 -vn 0.375747 0.205979 0.903542 -v -0.030300 0.131945 0.127925 -vn -0.375752 0.205979 0.903539 -v -0.034200 0.131945 0.127925 -vn 0.375746 0.351884 0.857317 -v -0.030300 0.133677 0.127376 -vn -0.375749 0.351884 0.857316 -v -0.034200 0.133677 0.127376 -vn 0.375742 0.488197 0.787707 -v -0.030300 0.135295 0.126550 -vn -0.375745 0.488196 0.787706 -v -0.034200 0.135295 0.126550 -vn 0.375745 0.611189 0.696608 -v -0.030300 0.136755 0.125469 -vn -0.375747 0.611189 0.696608 -v -0.034200 0.136755 0.125469 -vn 0.375748 0.717511 0.586508 -v -0.030300 0.138017 0.124162 -vn -0.375751 0.717511 0.586506 -v -0.034200 0.138017 0.124162 -vn 0.375743 0.804264 0.460409 -v -0.030300 0.139046 0.122665 -vn -0.375746 0.804262 0.460409 -v -0.034200 0.139046 0.122665 -vn 0.375744 0.869074 0.321755 -v -0.030300 0.139816 0.121019 -vn -0.375747 0.869073 0.321754 -v -0.034200 0.139816 0.121019 -vn 0.375744 0.910181 0.174322 -v -0.030300 0.140304 0.119269 -vn -0.375746 0.910179 0.174322 -v -0.034200 0.140304 0.119269 -vn 0.375747 0.926458 0.022131 -v -0.030300 0.140497 0.117463 -vn -0.375750 0.926457 0.022130 -v -0.034200 0.140497 0.117463 -vn 0.375742 0.917467 -0.130662 -v -0.030300 0.140390 0.115649 -vn -0.375745 0.917466 -0.130660 -v -0.034200 0.140390 0.115649 -vn 0.375752 0.883445 -0.279885 -v -0.030300 0.139986 0.113878 -vn -0.375754 0.883444 -0.279886 -v -0.034200 0.139986 0.113878 -vn 0.375748 0.825329 -0.421480 -v -0.030300 0.139296 0.112197 -vn -0.371560 0.828954 -0.418065 -v -0.034200 0.139296 0.112197 -vn 0.375753 0.744697 -0.551576 -v -0.030300 0.138339 0.110653 -vn -0.375757 0.744695 -0.551576 -v -0.034200 0.138339 0.110653 -vn 0.375743 0.643755 -0.666631 -v -0.030300 0.137141 0.109287 -vn -0.976003 0.156643 0.151267 -v -0.034500 0.134320 0.110733 -vn -0.976002 0.060024 0.209326 -v -0.034500 0.134775 0.110460 -vn -0.916688 0.169212 -0.362010 -v -0.034500 0.134031 0.107507 -vn -0.916686 0.226492 -0.329223 -v -0.034500 0.135565 0.108385 -vn -0.976002 -0.052682 0.211292 -v -0.034500 0.135305 0.110451 -vn -0.916684 0.277595 -0.287457 -v -0.034500 0.136933 0.109503 -vn -0.976002 -0.151271 0.156646 -v -0.034500 0.135769 0.110708 -vn -0.916692 0.320523 -0.238624 -v -0.034500 0.138098 0.110831 -vn -0.976003 -0.209321 0.060020 -v -0.034500 0.136043 0.111163 -vn -0.899801 0.365678 -0.237985 -v -0.034500 0.138673 0.111691 -vn -0.976002 -0.211293 -0.052681 -v -0.034500 0.136052 0.111693 -vn -0.976003 -0.156643 -0.151267 -v -0.034500 0.135795 0.112157 -vn -0.976002 -0.060024 -0.209326 -v -0.034500 0.135340 0.112431 -vn -0.722336 0.683397 -0.105823 -v -0.034500 0.133958 0.116588 -vn -0.976002 0.052682 -0.211292 -v -0.034500 0.134809 0.112440 -vn -0.728539 0.651016 -0.213094 -v -0.034500 0.133799 0.115869 -vn -0.976003 0.209321 -0.060020 -v -0.034500 0.134072 0.111728 -vn -0.731171 -0.160411 -0.663067 -v -0.034500 0.128442 0.112826 -vn -0.731172 0.009525 -0.682127 -v -0.034500 0.129563 0.112700 -vn -0.916686 0.107322 -0.384927 -v -0.034500 0.132374 0.106893 -vn -0.916687 0.042500 -0.397340 -v -0.034500 0.130638 0.106561 -vn -0.916687 -0.023480 -0.398916 -v -0.034500 0.128871 0.106518 -vn -0.976002 0.211293 0.052681 -v -0.034500 0.134063 0.111197 -vn -0.976002 -0.209326 0.060025 -v -0.034500 0.124731 0.111360 -vn -0.976002 -0.211293 -0.052682 -v -0.034500 0.124740 0.111891 -vn -0.731174 0.178864 -0.658325 -v -0.034500 0.130680 0.112857 -vn -0.731172 0.336965 -0.593163 -v -0.034500 0.131723 0.113287 -vn -0.976002 0.151269 -0.156643 -v -0.034500 0.134345 0.112183 -vn -0.731173 0.473891 -0.490727 -v -0.034500 0.132626 0.113963 -vn -0.731173 0.581042 -0.357457 -v -0.034500 0.133333 0.114842 -vn -0.719460 -0.686827 -0.103179 -v -0.034500 0.125025 0.116729 -vn -0.730066 -0.645646 -0.223929 -v -0.034500 0.125240 0.115750 -vn -0.976002 -0.060023 -0.209328 -v -0.034500 0.124028 0.112628 -vn -0.731170 -0.570834 -0.373548 -v -0.034500 0.125735 0.114736 -vn -0.976002 -0.156644 -0.151271 -v -0.034500 0.124483 0.112355 -vn -0.731171 -0.460005 -0.503770 -v -0.034500 0.126466 0.113877 -vn -0.731174 -0.320271 -0.602338 -v -0.034500 0.127387 0.113227 -vn -0.976002 0.052682 -0.211292 -v -0.034500 0.123497 0.112637 -vn -0.976002 0.151271 -0.156647 -v -0.034500 0.123033 0.112380 -vn -0.917636 -0.355736 -0.177189 -v -0.034500 0.120143 0.112010 -vn -0.976002 0.209326 -0.060025 -v -0.034500 0.122760 0.111925 -vn -0.976002 -0.151271 0.156647 -v -0.034500 0.124457 0.110905 -vn -0.916686 -0.088820 -0.389613 -v -0.034500 0.127122 0.106768 -vn -0.976002 -0.052682 0.211292 -v -0.034500 0.123993 0.110648 -vn -0.916685 -0.263550 -0.300383 -v -0.034500 0.122443 0.109157 -vn -0.916689 -0.309391 -0.252901 -v -0.034500 0.121216 0.110428 -vn -0.976002 0.211292 0.052682 -v -0.034500 0.122751 0.111395 -vn -0.919933 -0.332461 -0.207831 -v -0.034500 0.120214 0.111884 -vn -0.976003 0.156642 0.151269 -v -0.034500 0.123008 0.110931 -vn -0.976002 0.060023 0.209327 -v -0.034500 0.123463 0.110657 -vn -0.916686 -0.210513 -0.339662 -v -0.034500 0.123863 0.108105 -vn -0.916683 -0.151737 -0.369686 -v -0.034500 0.125437 0.107301 -vn -0.976002 -0.209327 0.060023 -v -0.034500 0.124928 0.122672 -vn -0.976002 -0.211293 -0.052682 -v -0.034500 0.124937 0.123203 -vn -0.731172 -0.094942 0.675554 -v -0.034500 0.128874 0.121656 -vn -0.731170 0.076043 0.677944 -v -0.034500 0.130002 0.121672 -vn -0.976002 -0.156645 -0.151271 -v -0.034500 0.124680 0.123667 -vn -0.916688 -0.169213 0.362009 -v -0.034500 0.124969 0.126893 -vn -0.976002 -0.060024 -0.209327 -v -0.034500 0.124225 0.123940 -vn -0.916684 -0.226495 0.329227 -v -0.034500 0.123435 0.126015 -vn -0.976002 0.052681 -0.211294 -v -0.034500 0.123695 0.123949 -vn -0.916684 -0.277593 0.287458 -v -0.034500 0.122067 0.124897 -vn -0.976002 0.151271 -0.156645 -v -0.034500 0.123231 0.123692 -vn -0.916686 -0.321119 0.237844 -v -0.034500 0.120902 0.123569 -vn -0.976002 0.209327 -0.060024 -v -0.034500 0.122957 0.123237 -vn -0.916686 -0.355886 0.181744 -v -0.034500 0.119971 0.122066 -vn -0.976002 0.211292 0.052682 -v -0.034500 0.122948 0.122707 -vn -0.916686 -0.380947 0.120689 -v -0.034500 0.119300 0.120432 -vn -0.976002 0.156645 0.151271 -v -0.034500 0.123205 0.122243 -vn -0.916686 -0.395617 0.056341 -v -0.034500 0.118907 0.118709 -vn -0.720500 -0.693208 -0.018539 -v -0.034500 0.125013 0.116855 -vn -0.731172 -0.671829 0.118461 -v -0.034500 0.125068 0.117981 -vn -0.916687 -0.399493 -0.009543 -v -0.034500 0.118803 0.116944 -vn -0.976002 0.060024 0.209327 -v -0.034500 0.123660 0.121969 -vn -0.916685 -0.392478 -0.075168 -v -0.034500 0.118991 0.115187 -vn -0.731174 -0.259966 0.630715 -v -0.034500 0.127785 0.121360 -vn -0.731171 -0.408653 0.546252 -v -0.034500 0.126804 0.120803 -vn -0.976002 -0.151271 0.156645 -v -0.034500 0.124655 0.122217 -vn -0.731171 -0.531660 0.427465 -v -0.034500 0.125993 0.120020 -vn -0.976002 -0.052682 0.211292 -v -0.034500 0.124191 0.121960 -vn -0.731171 -0.621263 0.281819 -v -0.034500 0.125402 0.119059 -vn -0.916685 -0.374819 -0.138562 -v -0.034500 0.119466 0.113485 -vn -0.916686 -0.107324 0.384927 -v -0.034500 0.126626 0.127507 -vn -0.916684 -0.042504 0.397346 -v -0.034500 0.128362 0.127839 -vn -0.916687 0.023481 0.398915 -v -0.034500 0.130129 0.127881 -vn -0.916687 0.088819 0.389610 -v -0.034500 0.131878 0.127632 -vn -0.916686 0.151735 0.369680 -v -0.034500 0.133563 0.127099 -vn -0.976002 -0.151269 0.156643 -v -0.034500 0.135967 0.122020 -vn -0.976001 -0.209331 0.060028 -v -0.034500 0.136240 0.122475 -vn -0.916685 0.374752 0.138743 -v -0.034500 0.139534 0.120915 -vn -0.916686 0.263550 0.300382 -v -0.034500 0.136557 0.125243 -vn -0.916687 0.309394 0.252904 -v -0.034500 0.137784 0.123972 -vn -0.976002 -0.211291 -0.052682 -v -0.034500 0.136249 0.123005 -vn -0.731173 0.242251 0.637731 -v -0.034500 0.131098 0.121407 -vn -0.976002 0.211293 0.052681 -v -0.034500 0.134260 0.122509 -vn -0.916689 0.380941 -0.120688 -v -0.034500 0.139700 0.113968 -vn -0.918771 0.355944 -0.170774 -v -0.034500 0.139029 0.112334 -vn -0.976002 -0.052682 0.211292 -v -0.034500 0.135503 0.121763 -vn -0.916684 0.346806 0.198534 -v -0.034500 0.138786 0.122516 -vn -0.724822 0.688854 -0.010660 -v -0.034500 0.133995 0.116980 -vn -0.731173 0.668258 0.137173 -v -0.034500 0.133908 0.118105 -vn -0.976001 -0.156648 -0.151275 -v -0.034500 0.135992 0.123469 -vn -0.976002 -0.060024 -0.209327 -v -0.034500 0.135537 0.123743 -vn -0.916684 0.210515 0.339668 -v -0.034500 0.135137 0.126295 -vn -0.976002 0.052682 -0.211292 -v -0.034500 0.135007 0.123752 -vn -0.976002 0.151269 -0.156643 -v -0.034500 0.134543 0.123495 -vn -0.976003 0.209321 -0.060020 -v -0.034500 0.134269 0.123040 -vn -0.976002 0.060024 0.209326 -v -0.034500 0.134972 0.121772 -vn -0.731174 0.613150 0.299053 -v -0.034500 0.133545 0.119173 -vn -0.976003 0.156643 0.151267 -v -0.034500 0.134517 0.122045 -vn -0.731173 0.519514 0.442144 -v -0.034500 0.132927 0.120117 -vn -0.731172 0.393237 0.557452 -v -0.034500 0.132094 0.120877 -vn -0.916685 0.392478 0.075169 -v -0.034500 0.140009 0.119213 -vn -0.916686 0.399493 0.009542 -v -0.034500 0.140197 0.117456 -vn -0.916684 0.395622 -0.056341 -v -0.034500 0.140093 0.115691 -vn -0.375770 0.722222 -0.580683 -v -0.036400 0.133007 0.114380 -vn -0.411990 0.782165 -0.467421 -v -0.036400 0.133333 0.114842 -vn -0.381722 0.838228 -0.389439 -v -0.036400 0.133598 0.115341 -vn -0.410699 0.874745 -0.257191 -v -0.036400 0.133799 0.115869 -vn -0.381696 0.908513 -0.170037 -v -0.036400 0.133932 0.116419 -vn -0.411986 0.910600 -0.032798 -v -0.036400 0.133995 0.116980 -vn -0.381730 0.922155 0.062545 -v -0.036400 0.133987 0.117545 -vn -0.411998 0.890140 0.194700 -v -0.036400 0.133908 0.118105 -vn -0.381723 0.877633 0.289911 -v -0.036400 0.133760 0.118650 -vn -0.390743 0.827340 0.403520 -v -0.036400 0.133545 0.119173 -vn -0.375769 0.775440 0.507436 -v -0.036400 0.133265 0.119664 -vn -0.390743 0.700996 0.596594 -v -0.036400 0.132927 0.120117 -vn -0.375765 0.624882 0.684342 -v -0.036400 0.132534 0.120523 -vn -0.411986 0.515610 0.751275 -v -0.036400 0.132094 0.120877 -vn -0.381721 0.441307 0.812119 -v -0.036400 0.131613 0.121173 -vn -0.411988 0.312583 0.855896 -v -0.036400 0.131098 0.121407 -vn -0.381727 0.225469 0.896353 -v -0.036400 0.130558 0.121574 -vn -0.411987 0.089908 0.906743 -v -0.036400 0.130002 0.121672 -vn -0.381726 -0.004519 0.924264 -v -0.036400 0.129437 0.121700 -vn -0.411992 -0.138418 0.900613 -v -0.036400 0.128874 0.121656 -vn -0.381729 -0.234236 0.894101 -v -0.036400 0.128320 0.121543 -vn -0.411991 -0.358041 0.837896 -v -0.036400 0.127785 0.121360 -vn -0.381730 -0.449236 0.807755 -v -0.036400 0.127277 0.121113 -vn -0.390745 -0.551402 0.737072 -v -0.036400 0.126804 0.120803 -vn -0.375764 -0.643753 0.666621 -v -0.036400 0.126374 0.120437 -vn -0.411982 -0.717417 0.561769 -v -0.036400 0.125993 0.120020 -vn -0.381717 -0.782809 0.491429 -v -0.036400 0.125667 0.119558 -vn -0.390743 -0.838283 0.380265 -v -0.036400 0.125402 0.119059 -vn -0.375775 -0.885266 0.274038 -v -0.036400 0.125201 0.118531 -vn -0.390745 -0.906516 0.159836 -v -0.036400 0.125068 0.117981 -vn -0.375764 -0.925609 0.045272 -v -0.036400 0.125005 0.117420 -vn -0.412697 -0.907261 -0.080984 -v -0.036400 0.125013 0.116855 -vn -0.382865 -0.906471 -0.178114 -v -0.036400 0.125092 0.116295 -vn -0.411997 -0.858722 -0.304721 -v -0.036400 0.125240 0.115750 -vn -0.381725 -0.834372 -0.397631 -v -0.036400 0.125455 0.115227 -vn -0.411983 -0.755968 -0.508707 -v -0.036400 0.125735 0.114736 -vn -0.381725 -0.709274 -0.592635 -v -0.036400 0.126073 0.114283 -vn -0.411988 -0.605705 -0.680726 -v -0.036400 0.126466 0.113877 -vn -0.381722 -0.539615 -0.750402 -v -0.036400 0.126906 0.113523 -vn -0.411986 -0.417390 -0.809971 -v -0.036400 0.127387 0.113227 -vn -0.381728 -0.336036 -0.861025 -v -0.036400 0.127902 0.112993 -vn -0.390744 -0.216447 -0.894690 -v -0.036400 0.128442 0.112826 -vn -0.375767 -0.103299 -0.920939 -v -0.036400 0.128998 0.112728 -vn -0.411987 0.024449 -0.910862 -v -0.036400 0.129563 0.112700 -vn -0.381723 0.120325 -0.916411 -v -0.036400 0.130126 0.112744 -vn -0.411992 0.250206 -0.876162 -v -0.036400 0.130680 0.112857 -vn -0.381727 0.344451 -0.857694 -v -0.036400 0.131215 0.113040 -vn -0.390746 0.454670 -0.800371 -v -0.036400 0.131723 0.113287 -vn -0.375771 0.555121 -0.742049 -v -0.036400 0.132196 0.113597 -vn -0.377386 0.643296 -0.666146 -v -0.036400 0.132626 0.113963 -vn -0.917910 0.313915 -0.242689 -v -0.036700 0.132773 0.114568 -vn -0.746099 -0.462529 0.478961 -v -0.036700 0.131410 0.115222 -vn -0.746099 -0.592987 0.302826 -v -0.036700 0.131949 0.115949 -vn -0.746098 -0.577851 -0.330797 -v -0.036700 0.131887 0.118566 -vn -0.915383 0.383614 0.122124 -v -0.036700 0.133476 0.118554 -vn -0.746099 -0.653949 -0.125248 -v -0.036700 0.132201 0.117717 -vn -0.915182 0.402246 0.025318 -v -0.036700 0.133688 0.117522 -vn -0.746099 -0.659184 0.093876 -v -0.036700 0.132223 0.116812 -vn -0.915179 0.395911 -0.075512 -v -0.036700 0.133636 0.116471 -vn -0.915176 0.364699 -0.171604 -v -0.036700 0.133325 0.115465 -vn -0.746099 -0.039121 -0.664684 -v -0.036700 0.129662 0.119945 -vn -0.915179 0.100223 0.390387 -v -0.036700 0.130488 0.121282 -vn -0.746098 -0.252824 -0.615969 -v -0.036700 0.130544 0.119744 -vn -0.915176 0.194166 0.353203 -v -0.036700 0.131472 0.120908 -vn -0.746100 -0.439130 -0.500499 -v -0.036700 0.131314 0.119267 -vn -0.917663 0.266170 0.295041 -v -0.036700 0.132332 0.120302 -vn -0.917884 0.332068 0.217300 -v -0.036700 0.133014 0.119500 -vn -0.746099 0.535054 -0.396300 -v -0.036700 0.127290 0.118837 -vn -0.917662 -0.277747 0.284172 -v -0.036700 0.126582 0.120221 -vn -0.746099 0.377384 -0.548559 -v -0.036700 0.127941 0.119466 -vn -0.915387 -0.191843 0.353924 -v -0.036700 0.127425 0.120852 -vn -0.746099 0.178822 -0.641373 -v -0.036700 0.128761 0.119849 -vn -0.915180 -0.100244 0.390381 -v -0.036700 0.128399 0.121253 -vn -0.915180 -0.000010 0.403046 -v -0.036700 0.129441 0.121400 -vn -0.918429 0.274799 -0.284560 -v -0.036700 0.132418 0.114179 -vn -0.918144 0.233197 -0.320361 -v -0.036700 0.132016 0.113837 -vn -0.746099 -0.281949 0.603193 -v -0.036700 0.130664 0.114709 -vn -0.915386 0.145971 -0.375182 -v -0.036700 0.131100 0.113317 -vn -0.746099 -0.070816 0.662058 -v -0.036700 0.129792 0.114466 -vn -0.915177 0.050525 -0.399873 -v -0.036700 0.130085 0.113041 -vn -0.746100 0.147993 0.649179 -v -0.036700 0.128889 0.114519 -vn -0.746097 0.624417 0.231175 -v -0.036700 0.126921 0.116245 -vn -0.915182 -0.395901 -0.075532 -v -0.036700 0.125386 0.116355 -vn -0.746101 0.665643 0.015901 -v -0.036700 0.126751 0.117134 -vn -0.917662 -0.396997 0.017023 -v -0.036700 0.125305 0.117405 -vn -0.746098 0.634743 -0.201097 -v -0.036700 0.126878 0.118031 -vn -0.917887 -0.379095 0.117350 -v -0.036700 0.125488 0.118442 -vn -0.915382 -0.338627 0.217731 -v -0.036700 0.125923 0.119401 -vn -0.917663 -0.041916 -0.395142 -v -0.036700 0.129032 0.113026 -vn -0.915387 -0.150418 -0.373418 -v -0.036700 0.128009 0.113274 -vn -0.746099 0.350761 0.565953 -v -0.036700 0.128051 0.114863 -vn -0.915176 -0.236904 -0.326082 -v -0.036700 0.127079 0.113768 -vn -0.746100 0.515521 0.421395 -v -0.036700 0.127371 0.115460 -vn -0.915179 -0.310546 -0.256921 -v -0.036700 0.126302 0.114478 -vn -0.915176 -0.364690 -0.171620 -v -0.036700 0.125725 0.115359 -vn -0.671868 -0.514514 0.532793 -v -0.033000 0.131410 0.115222 -vn -0.671869 -0.313638 0.670987 -v -0.033000 0.130664 0.114709 -vn -0.671869 -0.078775 0.736469 -v -0.033000 0.129792 0.114466 -vn -0.671868 0.164627 0.722144 -v -0.033000 0.128889 0.114519 -vn -0.671869 0.390185 0.629562 -v -0.033000 0.128051 0.114863 -vn -0.671869 0.573462 0.468757 -v -0.033000 0.127371 0.115460 -vn -0.671871 0.694594 0.257156 -v -0.033000 0.126921 0.116245 -vn -0.671868 0.740460 0.017688 -v -0.033000 0.126751 0.117134 -vn -0.671870 0.706080 -0.223698 -v -0.033000 0.126878 0.118031 -vn -0.671869 0.595190 -0.440841 -v -0.033000 0.127290 0.118837 -vn -0.671868 0.419800 -0.610214 -v -0.033000 0.127941 0.119466 -vn -0.671869 0.198921 -0.713458 -v -0.033000 0.128761 0.119849 -vn -0.671868 -0.043518 -0.739391 -v -0.033000 0.129662 0.119945 -vn -0.671869 -0.281239 -0.685198 -v -0.033000 0.130544 0.119744 -vn -0.671867 -0.488486 -0.556754 -v -0.033000 0.131314 0.119267 -vn -0.671870 -0.642795 -0.367975 -v -0.033000 0.131887 0.118566 -vn -0.671868 -0.727449 -0.139326 -v -0.033000 0.132201 0.117717 -vn -0.671868 -0.733272 0.104427 -v -0.033000 0.132223 0.116812 -vn -0.671869 -0.659634 0.336862 -v -0.033000 0.131949 0.115949 -vn -0.765146 -0.635239 -0.104993 -v -0.033000 0.130733 0.117404 -vn -0.765148 -0.611265 0.202247 -v -0.033000 0.130687 0.116807 -vn -0.765143 -0.447265 0.463153 -v -0.033000 0.130368 0.116301 -vn -0.765149 -0.180792 0.617949 -v -0.033000 0.129851 0.116000 -vn -0.765146 0.323424 -0.556730 -v -0.033000 0.128872 0.118281 -vn -0.765145 0.027653 -0.643263 -v -0.033000 0.129446 0.118449 -vn -0.765148 -0.274457 -0.582428 -v -0.033000 0.130033 0.118331 -vn -0.765143 -0.513691 -0.388173 -v -0.033000 0.130497 0.117954 -vn -0.765147 0.641905 -0.050086 -v -0.033000 0.128254 0.117297 -vn -0.765147 0.545103 -0.342657 -v -0.033000 0.128442 0.117865 -vn -0.765147 0.405861 0.499826 -v -0.033000 0.128712 0.116230 -vn -0.765147 0.591655 0.253959 -v -0.033000 0.128351 0.116707 -vn -0.765144 0.127096 0.631191 -v -0.033000 0.129253 0.115975 -vn 0.765143 -0.447265 0.463153 -v -0.031500 0.130368 0.116301 -vn 0.765149 -0.180792 0.617949 -v -0.031500 0.129851 0.116000 -vn 0.765144 0.127096 0.631191 -v -0.031500 0.129253 0.115975 -vn 0.765146 0.405863 0.499826 -v -0.031500 0.128712 0.116230 -vn 0.765145 0.591657 0.253960 -v -0.031500 0.128351 0.116707 -vn 0.765145 0.641907 -0.050086 -v -0.031500 0.128254 0.117297 -vn 0.765145 0.545105 -0.342657 -v -0.031500 0.128442 0.117865 -vn 0.765146 0.323424 -0.556730 -v -0.031500 0.128872 0.118281 -vn 0.765145 0.027653 -0.643263 -v -0.031500 0.129446 0.118449 -vn 0.765148 -0.274457 -0.582428 -v -0.031500 0.130033 0.118331 -vn 0.765143 -0.513691 -0.388173 -v -0.031500 0.130497 0.117954 -vn 0.765146 -0.635239 -0.104993 -v -0.031500 0.130733 0.117404 -vn 0.765148 -0.611265 0.202247 -v -0.031500 0.130687 0.116807 -vn -0.539397 -0.203711 0.817039 -v -0.034370 0.135251 0.110669 -vn -0.539397 0.232106 0.809430 -v -0.034370 0.134837 0.110676 -vn -0.539399 0.605723 0.584935 -v -0.034370 0.134482 0.110890 -vn -0.539398 0.817039 0.203709 -v -0.034370 0.134281 0.111252 -vn -0.539402 0.809430 -0.232097 -v -0.034370 0.134288 0.111666 -vn -0.539400 0.584943 -0.605714 -v -0.034370 0.134502 0.112021 -vn -0.539399 0.203715 -0.817036 -v -0.034370 0.134864 0.112222 -vn -0.539397 -0.232106 -0.809430 -v -0.034370 0.135278 0.112214 -vn -0.539399 -0.605723 -0.584935 -v -0.034370 0.135633 0.112001 -vn -0.539398 -0.817039 -0.203709 -v -0.034370 0.135833 0.111639 -vn -0.539401 -0.809431 0.232094 -v -0.034370 0.135826 0.111225 -vn -0.539398 -0.584940 0.605719 -v -0.034370 0.135613 0.110870 -vn 0.539399 0.584943 -0.605715 -v -0.030130 0.134502 0.112021 -vn 0.539402 0.809429 -0.232100 -v -0.030130 0.134288 0.111666 -vn 0.539398 0.817038 0.203711 -v -0.030130 0.134281 0.111252 -vn 0.539399 0.605725 0.584933 -v -0.030130 0.134482 0.110890 -vn 0.539398 0.232105 0.809430 -v -0.030130 0.134837 0.110676 -vn 0.539397 -0.203710 0.817039 -v -0.030130 0.135251 0.110669 -vn 0.539397 -0.584942 0.605718 -v -0.030130 0.135613 0.110870 -vn 0.539401 -0.809431 0.232097 -v -0.030130 0.135826 0.111225 -vn 0.539398 -0.817038 -0.203711 -v -0.030130 0.135833 0.111639 -vn 0.539399 -0.605725 -0.584933 -v -0.030130 0.135633 0.112001 -vn 0.539398 -0.232105 -0.809430 -v -0.030130 0.135278 0.112214 -vn 0.539398 0.203716 -0.817037 -v -0.030130 0.134864 0.112222 -vn -0.539399 -0.203715 0.817036 -v -0.034370 0.135448 0.121981 -vn -0.539397 0.232106 0.809430 -v -0.034370 0.135034 0.121988 -vn -0.539399 0.605723 0.584935 -v -0.034370 0.134679 0.122202 -vn -0.539398 0.817039 0.203709 -v -0.034370 0.134478 0.122564 -vn -0.539402 0.809430 -0.232097 -v -0.034370 0.134486 0.122978 -vn -0.539400 0.584943 -0.605714 -v -0.034370 0.134699 0.123333 -vn -0.539399 0.203715 -0.817036 -v -0.034370 0.135061 0.123534 -vn -0.539396 -0.232099 -0.809433 -v -0.034370 0.135475 0.123526 -vn -0.539392 -0.605724 -0.584940 -v -0.034370 0.135830 0.123313 -vn -0.539396 -0.817039 -0.203713 -v -0.034370 0.136031 0.122951 -vn -0.539393 -0.809431 0.232115 -v -0.034370 0.136024 0.122537 -vn -0.539395 -0.584938 0.605723 -v -0.034370 0.135810 0.122182 -vn 0.539399 0.584943 -0.605715 -v -0.030130 0.134699 0.123333 -vn 0.539402 0.809429 -0.232100 -v -0.030130 0.134486 0.122978 -vn 0.539398 0.817038 0.203711 -v -0.030130 0.134478 0.122564 -vn 0.539399 0.605725 0.584933 -v -0.030130 0.134679 0.122202 -vn 0.539398 0.232105 0.809430 -v -0.030130 0.135034 0.121988 -vn 0.539398 -0.203716 0.817037 -v -0.030130 0.135448 0.121981 -vn 0.539396 -0.584934 0.605726 -v -0.030130 0.135810 0.122182 -vn 0.539393 -0.809432 0.232110 -v -0.030130 0.136024 0.122537 -vn 0.539396 -0.817040 -0.203708 -v -0.030130 0.136031 0.122951 -vn 0.539392 -0.605721 -0.584943 -v -0.030130 0.135830 0.123313 -vn 0.539395 -0.232100 -0.809434 -v -0.030130 0.135475 0.123526 -vn 0.539398 0.203716 -0.817037 -v -0.030130 0.135061 0.123534 -vn -0.539397 -0.203711 0.817039 -v -0.034370 0.124136 0.122178 -vn -0.539396 0.232100 0.809433 -v -0.034370 0.123722 0.122186 -vn -0.539396 0.605722 0.584939 -v -0.034370 0.123367 0.122399 -vn -0.539397 0.817039 0.203711 -v -0.034370 0.123166 0.122761 -vn -0.539396 0.809433 -0.232100 -v -0.034370 0.123174 0.123175 -vn -0.539396 0.584939 -0.605722 -v -0.034370 0.123387 0.123530 -vn -0.539396 0.203712 -0.817040 -v -0.034370 0.123749 0.123731 -vn -0.539396 -0.232100 -0.809433 -v -0.034370 0.124163 0.123724 -vn -0.539396 -0.605722 -0.584939 -v -0.034370 0.124518 0.123510 -vn -0.539397 -0.817039 -0.203711 -v -0.034370 0.124719 0.123148 -vn -0.539396 -0.809433 0.232100 -v -0.034370 0.124712 0.122734 -vn -0.539396 -0.584939 0.605722 -v -0.034370 0.124498 0.122379 -vn 0.539396 0.584939 -0.605722 -v -0.030130 0.123387 0.123530 -vn 0.539396 0.809433 -0.232100 -v -0.030130 0.123174 0.123175 -vn 0.539397 0.817039 0.203710 -v -0.030130 0.123166 0.122761 -vn 0.539396 0.605721 0.584939 -v -0.030130 0.123367 0.122399 -vn 0.539396 0.232100 0.809433 -v -0.030130 0.123722 0.122186 -vn 0.539397 -0.203710 0.817039 -v -0.030130 0.124136 0.122178 -vn 0.539396 -0.584939 0.605721 -v -0.030130 0.124498 0.122379 -vn 0.539396 -0.809433 0.232100 -v -0.030130 0.124712 0.122734 -vn 0.539397 -0.817039 -0.203710 -v -0.030130 0.124719 0.123148 -vn 0.539396 -0.605721 -0.584939 -v -0.030130 0.124518 0.123510 -vn 0.539396 -0.232100 -0.809433 -v -0.030130 0.124163 0.123724 -vn 0.539396 0.203712 -0.817040 -v -0.030130 0.123749 0.123731 -vn -0.539397 -0.203711 0.817039 -v -0.034370 0.123939 0.110866 -vn -0.539396 0.232100 0.809433 -v -0.034370 0.123525 0.110874 -vn -0.539399 0.605714 0.584944 -v -0.034370 0.123170 0.111087 -vn -0.539400 0.817036 0.203715 -v -0.034370 0.122969 0.111449 -vn -0.539397 0.809430 -0.232106 -v -0.034370 0.122976 0.111863 -vn -0.539394 0.584935 -0.605727 -v -0.034370 0.123190 0.112218 -vn -0.539397 0.203711 -0.817039 -v -0.034370 0.123552 0.112419 -vn -0.539395 -0.232096 -0.809434 -v -0.034370 0.123966 0.112412 -vn -0.539397 -0.605718 -0.584941 -v -0.034370 0.124321 0.112198 -vn -0.539397 -0.817039 -0.203711 -v -0.034370 0.124522 0.111836 -vn -0.539397 -0.809430 0.232106 -v -0.034370 0.124514 0.111422 -vn -0.539394 -0.584935 0.605727 -v -0.034370 0.124301 0.111067 -vn 0.539395 0.584935 -0.605726 -v -0.030130 0.123190 0.112218 -vn 0.539397 0.809430 -0.232106 -v -0.030130 0.122976 0.111863 -vn 0.539398 0.817037 0.203716 -v -0.030130 0.122969 0.111449 -vn 0.539399 0.605715 0.584943 -v -0.030130 0.123170 0.111087 -vn 0.539396 0.232099 0.809433 -v -0.030130 0.123525 0.110874 -vn 0.539397 -0.203710 0.817039 -v -0.030130 0.123939 0.110866 -vn 0.539395 -0.584935 0.605726 -v -0.030130 0.124301 0.111067 -vn 0.539397 -0.809430 0.232106 -v -0.030130 0.124514 0.111422 -vn 0.539397 -0.817039 -0.203710 -v -0.030130 0.124522 0.111836 -vn 0.539397 -0.605718 -0.584942 -v -0.030130 0.124321 0.112198 -vn 0.539395 -0.232096 -0.809435 -v -0.030130 0.123966 0.112412 -vn 0.539397 0.203710 -0.817039 -v -0.030130 0.123552 0.112419 -vn -0.506275 0.728476 0.461528 -v -0.073520 0.024800 0.198277 -vn 0.490876 0.688986 -0.533234 -v -0.073163 0.024800 0.197361 -vn -0.412846 0.728478 0.546698 -v -0.074079 0.024800 0.197767 -vn 0.396419 0.688983 -0.606758 -v -0.073815 0.024800 0.196853 -vn -0.305361 0.728476 0.613252 -v -0.074722 0.024800 0.197369 -vn 0.291138 0.688983 -0.663732 -v -0.074541 0.024800 0.196460 -vn -0.187480 0.728476 0.658918 -v -0.075427 0.024800 0.197096 -vn 0.177924 0.688985 -0.702597 -v -0.075322 0.024800 0.196192 -vn -0.063212 0.728477 0.682148 -v -0.076171 0.024800 0.196957 -vn 0.059855 0.688983 -0.722302 -v -0.076137 0.024800 0.196056 -vn 0.063212 0.728477 0.682148 -v -0.076928 0.024800 0.196957 -vn -0.059855 0.688983 -0.722302 -v -0.076962 0.024800 0.196056 -vn 0.187480 0.728476 0.658918 -v -0.077671 0.024800 0.197096 -vn -0.177924 0.688985 -0.702597 -v -0.077777 0.024800 0.196192 -vn 0.305361 0.728476 0.613252 -v -0.078377 0.024800 0.197369 -vn -0.291138 0.688983 -0.663732 -v -0.078558 0.024800 0.196460 -vn 0.412846 0.728478 0.546698 -v -0.079020 0.024800 0.197767 -vn -0.412849 0.728474 -0.546700 -v -0.074079 0.024800 0.204311 -vn 0.490878 0.688983 0.533237 -v -0.073163 0.024800 0.204718 -vn -0.506270 0.728478 -0.461531 -v -0.073520 0.024800 0.203801 -vn 0.571952 0.688984 0.445166 -v -0.072604 0.024800 0.204110 -vn -0.582460 0.728477 -0.360641 -v -0.073064 0.024800 0.203197 -vn 0.637420 0.688985 0.344957 -v -0.072152 0.024800 0.203419 -vn -0.638811 0.728476 -0.247474 -v -0.072726 0.024800 0.202520 -vn 0.685507 0.688982 0.235336 -v -0.071820 0.024800 0.202663 -vn -0.673406 0.728476 -0.125882 -v -0.072519 0.024800 0.201792 -vn 0.714891 0.688985 0.119293 -v -0.071618 0.024800 0.201862 -vn -0.685070 0.728477 -0.000000 -v -0.072449 0.024800 0.201039 -vn 0.724777 0.688983 0.000000 -v -0.071549 0.024800 0.201039 -vn -0.673407 0.728476 0.125880 -v -0.072519 0.024800 0.200286 -vn 0.714891 0.688985 -0.119293 -v -0.071618 0.024800 0.200216 -vn -0.638809 0.728477 0.247474 -v -0.072726 0.024800 0.199558 -vn 0.685507 0.688983 -0.235334 -v -0.071820 0.024800 0.199416 -vn -0.582459 0.728476 0.360644 -v -0.073064 0.024800 0.198881 -vn 0.637422 0.688984 -0.344955 -v -0.072152 0.024800 0.198659 -vn 0.571950 0.688982 -0.445170 -v -0.072604 0.024800 0.197968 -vn 0.506270 0.728478 -0.461531 -v -0.079579 0.024800 0.203801 -vn -0.490878 0.688983 0.533237 -v -0.079936 0.024800 0.204718 -vn 0.412849 0.728474 -0.546700 -v -0.079020 0.024800 0.204311 -vn -0.396414 0.688984 0.606759 -v -0.079284 0.024800 0.205225 -vn 0.305365 0.728478 -0.613248 -v -0.078377 0.024800 0.204709 -vn -0.291138 0.688983 0.663732 -v -0.078558 0.024800 0.205618 -vn 0.187473 0.728479 -0.658918 -v -0.077671 0.024800 0.204983 -vn -0.177924 0.688985 0.702597 -v -0.077777 0.024800 0.205886 -vn 0.063205 0.728475 -0.682151 -v -0.076928 0.024800 0.205122 -vn -0.059855 0.688983 0.722302 -v -0.076962 0.024800 0.206022 -vn -0.063205 0.728475 -0.682151 -v -0.076171 0.024800 0.205122 -vn 0.059855 0.688983 0.722302 -v -0.076137 0.024800 0.206022 -vn -0.187473 0.728479 -0.658918 -v -0.075427 0.024800 0.204983 -vn 0.177924 0.688985 0.702597 -v -0.075322 0.024800 0.205886 -vn -0.305365 0.728478 -0.613248 -v -0.074722 0.024800 0.204709 -vn 0.291138 0.688983 0.663732 -v -0.074541 0.024800 0.205618 -vn 0.396414 0.688984 0.606759 -v -0.073815 0.024800 0.205225 -vn -0.396419 0.688983 -0.606758 -v -0.079284 0.024800 0.196853 -vn -0.490876 0.688986 -0.533234 -v -0.079936 0.024800 0.197361 -vn 0.506275 0.728476 0.461528 -v -0.079579 0.024800 0.198277 -vn -0.571950 0.688982 -0.445170 -v -0.080495 0.024800 0.197968 -vn 0.582459 0.728476 0.360644 -v -0.080035 0.024800 0.198881 -vn -0.637422 0.688984 -0.344955 -v -0.080947 0.024800 0.198659 -vn 0.638809 0.728478 0.247474 -v -0.080373 0.024800 0.199558 -vn -0.685507 0.688983 -0.235334 -v -0.081279 0.024800 0.199416 -vn 0.673407 0.728476 0.125880 -v -0.080580 0.024800 0.200286 -vn -0.714891 0.688985 -0.119293 -v -0.081481 0.024800 0.200216 -vn 0.685070 0.728477 0.000000 -v -0.080649 0.024800 0.201039 -vn -0.724777 0.688983 0.000000 -v -0.081549 0.024800 0.201039 -vn 0.673406 0.728476 -0.125882 -v -0.080580 0.024800 0.201792 -vn -0.714891 0.688985 0.119293 -v -0.081481 0.024800 0.201862 -vn 0.638811 0.728476 -0.247474 -v -0.080373 0.024800 0.202520 -vn -0.685507 0.688982 0.235336 -v -0.081279 0.024800 0.202663 -vn 0.582460 0.728477 -0.360641 -v -0.080035 0.024800 0.203197 -vn -0.637420 0.688985 0.344957 -v -0.080947 0.024800 0.203419 -vn -0.571952 0.688984 0.445165 -v -0.080495 0.024800 0.204110 -vn 0.724777 -0.688983 0.000000 -v -0.071549 0.020800 0.201039 -vn 0.714891 -0.688985 0.119293 -v -0.071618 0.020800 0.201862 -vn 0.685507 -0.688982 0.235336 -v -0.071820 0.020800 0.202663 -vn 0.637420 -0.688985 0.344957 -v -0.072152 0.020800 0.203419 -vn 0.571952 -0.688984 0.445165 -v -0.072604 0.020800 0.204110 -vn 0.490878 -0.688983 0.533237 -v -0.073163 0.020800 0.204718 -vn 0.396414 -0.688984 0.606759 -v -0.073815 0.020800 0.205225 -vn 0.291138 -0.688983 0.663732 -v -0.074541 0.020800 0.205618 -vn 0.177924 -0.688985 0.702597 -v -0.075322 0.020800 0.205886 -vn 0.059855 -0.688983 0.722302 -v -0.076137 0.020800 0.206022 -vn -0.059855 -0.688983 0.722302 -v -0.076962 0.020800 0.206022 -vn -0.177924 -0.688985 0.702597 -v -0.077777 0.020800 0.205886 -vn -0.291138 -0.688983 0.663732 -v -0.078558 0.020800 0.205618 -vn -0.396414 -0.688984 0.606759 -v -0.079284 0.020800 0.205225 -vn -0.490878 -0.688983 0.533237 -v -0.079936 0.020800 0.204718 -vn -0.571952 -0.688984 0.445166 -v -0.080495 0.020800 0.204110 -vn -0.637420 -0.688985 0.344957 -v -0.080947 0.020800 0.203419 -vn -0.685507 -0.688982 0.235336 -v -0.081279 0.020800 0.202663 -vn -0.714891 -0.688985 0.119293 -v -0.081481 0.020800 0.201862 -vn -0.724777 -0.688983 -0.000000 -v -0.081549 0.020800 0.201039 -vn -0.714891 -0.688985 -0.119293 -v -0.081481 0.020800 0.200216 -vn -0.685507 -0.688983 -0.235334 -v -0.081279 0.020800 0.199416 -vn -0.637422 -0.688984 -0.344955 -v -0.080947 0.020800 0.198659 -vn -0.571950 -0.688982 -0.445170 -v -0.080495 0.020800 0.197968 -vn -0.490876 -0.688986 -0.533234 -v -0.079936 0.020800 0.197361 -vn -0.396419 -0.688983 -0.606758 -v -0.079284 0.020800 0.196853 -vn -0.291138 -0.688983 -0.663732 -v -0.078558 0.020800 0.196460 -vn -0.177924 -0.688985 -0.702597 -v -0.077777 0.020800 0.196192 -vn -0.059855 -0.688983 -0.722302 -v -0.076962 0.020800 0.196056 -vn 0.059855 -0.688983 -0.722302 -v -0.076137 0.020800 0.196056 -vn 0.177924 -0.688985 -0.702597 -v -0.075322 0.020800 0.196192 -vn 0.291138 -0.688983 -0.663732 -v -0.074541 0.020800 0.196460 -vn 0.396419 -0.688983 -0.606758 -v -0.073815 0.020800 0.196853 -vn 0.490876 -0.688986 -0.533234 -v -0.073163 0.020800 0.197361 -vn 0.571950 -0.688982 -0.445170 -v -0.072604 0.020800 0.197968 -vn 0.637422 -0.688984 -0.344955 -v -0.072152 0.020800 0.198659 -vn 0.685507 -0.688983 -0.235334 -v -0.071820 0.020800 0.199416 -vn 0.714891 -0.688985 -0.119293 -v -0.071618 0.020800 0.200216 -vn 0.506275 -0.728476 0.461528 -v -0.079579 0.020800 0.198277 -vn 0.412846 -0.728478 0.546698 -v -0.079020 0.020800 0.197767 -vn 0.305361 -0.728476 0.613252 -v -0.078377 0.020800 0.197369 -vn 0.187480 -0.728476 0.658918 -v -0.077671 0.020800 0.197096 -vn 0.063212 -0.728477 0.682148 -v -0.076928 0.020800 0.196957 -vn -0.063212 -0.728477 0.682148 -v -0.076171 0.020800 0.196957 -vn -0.187480 -0.728476 0.658918 -v -0.075427 0.020800 0.197096 -vn -0.305361 -0.728476 0.613252 -v -0.074722 0.020800 0.197369 -vn -0.412846 -0.728478 0.546698 -v -0.074079 0.020800 0.197767 -vn 0.412849 -0.728474 -0.546700 -v -0.079020 0.020800 0.204311 -vn 0.506270 -0.728478 -0.461531 -v -0.079579 0.020800 0.203801 -vn 0.582460 -0.728477 -0.360641 -v -0.080035 0.020800 0.203197 -vn 0.638811 -0.728476 -0.247474 -v -0.080373 0.020800 0.202520 -vn 0.673406 -0.728476 -0.125882 -v -0.080580 0.020800 0.201792 -vn 0.685070 -0.728477 -0.000000 -v -0.080649 0.020800 0.201039 -vn 0.673407 -0.728476 0.125880 -v -0.080580 0.020800 0.200286 -vn 0.638809 -0.728477 0.247474 -v -0.080373 0.020800 0.199558 -vn 0.582459 -0.728476 0.360644 -v -0.080035 0.020800 0.198881 -vn -0.506270 -0.728478 -0.461531 -v -0.073520 0.020800 0.203801 -vn -0.412849 -0.728474 -0.546700 -v -0.074079 0.020800 0.204311 -vn -0.305365 -0.728478 -0.613248 -v -0.074722 0.020800 0.204709 -vn -0.187473 -0.728479 -0.658918 -v -0.075427 0.020800 0.204983 -vn -0.063205 -0.728475 -0.682151 -v -0.076171 0.020800 0.205122 -vn 0.063205 -0.728475 -0.682151 -v -0.076928 0.020800 0.205122 -vn 0.187473 -0.728479 -0.658918 -v -0.077671 0.020800 0.204983 -vn 0.305365 -0.728478 -0.613248 -v -0.078377 0.020800 0.204709 -vn -0.506275 -0.728476 0.461528 -v -0.073520 0.020800 0.198277 -vn -0.582459 -0.728476 0.360644 -v -0.073064 0.020800 0.198881 -vn -0.638809 -0.728478 0.247474 -v -0.072726 0.020800 0.199558 -vn -0.673407 -0.728476 0.125880 -v -0.072519 0.020800 0.200286 -vn -0.685070 -0.728477 0.000000 -v -0.072449 0.020800 0.201039 -vn -0.673406 -0.728476 -0.125882 -v -0.072519 0.020800 0.201792 -vn -0.638811 -0.728476 -0.247474 -v -0.072726 0.020800 0.202520 -vn -0.582460 -0.728477 -0.360641 -v -0.073064 0.020800 0.203197 -vn -0.726736 -0.686917 -0.000000 -v -0.072449 0.021100 0.201039 -vn -0.714361 -0.686917 -0.133538 -v -0.072519 0.021100 0.201792 -vn -0.677662 -0.686918 -0.262524 -v -0.072726 0.021100 0.202520 -vn -0.617885 -0.686916 -0.382575 -v -0.073064 0.021100 0.203197 -vn -0.537063 -0.686916 -0.489602 -v -0.073520 0.021100 0.203801 -vn -0.437955 -0.686919 -0.579946 -v -0.074079 0.021100 0.204311 -vn -0.323938 -0.686916 -0.650546 -v -0.074722 0.021100 0.204709 -vn -0.198876 -0.686915 -0.698996 -v -0.075427 0.021100 0.204983 -vn -0.067049 -0.686919 -0.723635 -v -0.076171 0.021100 0.205122 -vn 0.067049 -0.686919 -0.723635 -v -0.076928 0.021100 0.205122 -vn 0.198876 -0.686915 -0.698996 -v -0.077671 0.021100 0.204983 -vn 0.323938 -0.686916 -0.650546 -v -0.078377 0.021100 0.204709 -vn 0.437955 -0.686919 -0.579946 -v -0.079020 0.021100 0.204311 -vn 0.537063 -0.686916 -0.489602 -v -0.079579 0.021100 0.203801 -vn 0.617885 -0.686916 -0.382575 -v -0.080035 0.021100 0.203197 -vn 0.677662 -0.686918 -0.262524 -v -0.080373 0.021100 0.202520 -vn 0.714361 -0.686917 -0.133538 -v -0.080580 0.021100 0.201792 -vn 0.726736 -0.686917 0.000000 -v -0.080649 0.021100 0.201039 -vn 0.714361 -0.686918 0.133536 -v -0.080580 0.021100 0.200286 -vn 0.677662 -0.686916 0.262526 -v -0.080373 0.021100 0.199558 -vn 0.617883 -0.686917 0.382577 -v -0.080035 0.021100 0.198881 -vn 0.537065 -0.686917 0.489597 -v -0.079579 0.021100 0.198277 -vn 0.437956 -0.686916 0.579949 -v -0.079020 0.021100 0.197767 -vn 0.323932 -0.686918 0.650548 -v -0.078377 0.021100 0.197369 -vn 0.198882 -0.686917 0.698992 -v -0.077671 0.021100 0.197096 -vn 0.067056 -0.686917 0.723636 -v -0.076928 0.021100 0.196957 -vn -0.067056 -0.686917 0.723636 -v -0.076171 0.021100 0.196957 -vn -0.198882 -0.686917 0.698992 -v -0.075427 0.021100 0.197096 -vn -0.323932 -0.686918 0.650548 -v -0.074722 0.021100 0.197369 -vn -0.437956 -0.686916 0.579949 -v -0.074079 0.021100 0.197767 -vn -0.537065 -0.686917 0.489597 -v -0.073520 0.021100 0.198277 -vn -0.617883 -0.686917 0.382577 -v -0.073064 0.021100 0.198881 -vn -0.677662 -0.686916 0.262526 -v -0.072726 0.021100 0.199558 -vn -0.714361 -0.686918 0.133536 -v -0.072519 0.021100 0.200286 -vn 0.606722 -0.734195 -0.304708 -v -0.074405 0.021100 0.199962 -vn 0.660637 -0.734195 -0.156575 -v -0.074214 0.021100 0.200486 -vn 0.678938 -0.734195 0.000001 -v -0.074149 0.021100 0.201039 -vn 0.660640 -0.734194 0.156573 -v -0.074214 0.021100 0.201593 -vn 0.117897 -0.734198 -0.668621 -v -0.076133 0.021100 0.198676 -vn 0.268919 -0.734193 -0.623413 -v -0.075599 0.021100 0.198835 -vn 0.405434 -0.734196 -0.544592 -v -0.075116 0.021100 0.199114 -vn 0.520098 -0.734194 -0.436413 -v -0.074711 0.021100 0.199496 -vn -0.465914 -0.734195 -0.493845 -v -0.078196 0.021100 0.199293 -vn -0.339469 -0.734194 -0.587979 -v -0.077749 0.021100 0.198961 -vn -0.194724 -0.734194 -0.650416 -v -0.077238 0.021100 0.198740 -vn -0.039482 -0.734194 -0.677790 -v -0.076689 0.021100 0.198643 -vn -0.339474 -0.734197 0.587973 -v -0.077749 0.021100 0.203118 -vn -0.465921 -0.734192 0.493842 -v -0.078196 0.021100 0.202785 -vn -0.567243 -0.734195 0.373087 -v -0.078555 0.021100 0.202358 -vn -0.637992 -0.734196 0.232212 -v -0.078805 0.021100 0.201860 -vn -0.674349 -0.734195 0.078819 -v -0.078933 0.021100 0.201318 -vn 0.606722 -0.734196 0.304705 -v -0.074405 0.021100 0.202116 -vn 0.520098 -0.734194 0.436413 -v -0.074711 0.021100 0.202582 -vn 0.405434 -0.734196 0.544592 -v -0.075116 0.021100 0.202964 -vn 0.268909 -0.734196 0.623413 -v -0.075599 0.021100 0.203243 -vn -0.674349 -0.734195 -0.078819 -v -0.078933 0.021100 0.200760 -vn -0.637995 -0.734195 -0.232209 -v -0.078805 0.021100 0.200218 -vn -0.567243 -0.734196 -0.373083 -v -0.078555 0.021100 0.199720 -vn 0.117899 -0.734191 0.668628 -v -0.076133 0.021100 0.203403 -vn -0.039473 -0.734198 0.677787 -v -0.076689 0.021100 0.203435 -vn -0.194724 -0.734194 0.650416 -v -0.077238 0.021100 0.203338 -vn 0.731458 -0.681886 0.000001 -v -0.074149 0.020800 0.201039 -vn 0.711741 -0.681888 0.168684 -v -0.074214 0.020800 0.201593 -vn 0.653656 -0.681886 0.328276 -v -0.074405 0.020800 0.202116 -vn 0.560330 -0.681887 0.470171 -v -0.074711 0.020800 0.202582 -vn 0.436797 -0.681886 0.586719 -v -0.075116 0.020800 0.202964 -vn 0.289712 -0.681885 0.671639 -v -0.075599 0.020800 0.203243 -vn 0.127018 -0.681890 0.720342 -v -0.076133 0.020800 0.203403 -vn -0.042527 -0.681884 0.730223 -v -0.076689 0.020800 0.203435 -vn -0.209787 -0.681887 0.700728 -v -0.077238 0.020800 0.203338 -vn -0.365736 -0.681885 0.633459 -v -0.077749 0.020800 0.203118 -vn -0.501958 -0.681889 0.532039 -v -0.078196 0.020800 0.202785 -vn -0.611121 -0.681887 0.401947 -v -0.078555 0.020800 0.202358 -vn -0.687346 -0.681885 0.250176 -v -0.078805 0.020800 0.201860 -vn -0.726512 -0.681887 0.084916 -v -0.078933 0.020800 0.201318 -vn -0.726512 -0.681887 -0.084916 -v -0.078933 0.020800 0.200760 -vn -0.687346 -0.681887 -0.250171 -v -0.078805 0.020800 0.200218 -vn -0.611124 -0.681886 -0.401944 -v -0.078555 0.020800 0.199720 -vn -0.501954 -0.681887 -0.532046 -v -0.078196 0.020800 0.199293 -vn -0.365728 -0.681887 -0.633461 -v -0.077749 0.020800 0.198961 -vn -0.209787 -0.681887 -0.700728 -v -0.077238 0.020800 0.198740 -vn -0.042536 -0.681887 -0.730220 -v -0.076689 0.020800 0.198643 -vn 0.127018 -0.681884 -0.720348 -v -0.076133 0.020800 0.198676 -vn 0.289719 -0.681888 -0.671633 -v -0.075599 0.020800 0.198835 -vn 0.436797 -0.681886 -0.586719 -v -0.075116 0.020800 0.199114 -vn 0.560330 -0.681887 -0.470171 -v -0.074711 0.020800 0.199496 -vn 0.653654 -0.681887 -0.328278 -v -0.074405 0.020800 0.199962 -vn 0.711742 -0.681886 -0.168687 -v -0.074214 0.020800 0.200486 -vn 0.149118 -0.742247 0.653325 -v -0.076883 0.020800 0.199577 -vn -0.050084 -0.742242 0.668258 -v -0.076437 0.020800 0.199543 -vn -0.244825 -0.742242 0.623809 -v -0.076001 0.020800 0.199643 -vn -0.417818 -0.742245 0.523928 -v -0.075614 0.020800 0.199866 -vn -0.553690 -0.742242 0.377498 -v -0.075310 0.020800 0.200194 -vn -0.640358 -0.742244 0.197523 -v -0.075116 0.020800 0.200597 -vn -0.670132 -0.742242 0.000000 -v -0.075049 0.020800 0.201039 -vn -0.640354 -0.742246 -0.197527 -v -0.075116 0.020800 0.201481 -vn 0.603771 -0.742241 0.290756 -v -0.077901 0.020800 0.200388 -vn 0.491240 -0.742246 0.455801 -v -0.077649 0.020800 0.200019 -vn 0.335069 -0.742240 0.580352 -v -0.077299 0.020800 0.199740 -vn -0.553689 -0.742240 -0.377503 -v -0.075310 0.020800 0.201884 -vn -0.417828 -0.742242 -0.523925 -v -0.075614 0.020800 0.202212 -vn -0.244832 -0.742245 -0.623802 -v -0.076001 0.020800 0.202435 -vn -0.050073 -0.742246 -0.668254 -v -0.076437 0.020800 0.202535 -vn 0.149121 -0.742239 -0.653334 -v -0.076883 0.020800 0.202502 -vn 0.335064 -0.742247 -0.580346 -v -0.077299 0.020800 0.202338 -vn 0.491246 -0.742241 -0.455803 -v -0.077649 0.020800 0.202059 -vn 0.603766 -0.742243 -0.290760 -v -0.077901 0.020800 0.201690 -vn 0.662646 -0.742243 -0.099878 -v -0.078033 0.020800 0.201263 -vn 0.662646 -0.742243 0.099878 -v -0.078033 0.020800 0.200816 -vn -0.670132 0.742242 -0.000000 -v -0.075049 0.024800 0.201039 -vn -0.640354 0.742246 -0.197527 -v -0.075116 0.024800 0.201481 -vn -0.553689 0.742240 -0.377503 -v -0.075310 0.024800 0.201884 -vn -0.417828 0.742242 -0.523925 -v -0.075614 0.024800 0.202212 -vn -0.244832 0.742245 -0.623802 -v -0.076001 0.024800 0.202435 -vn -0.050073 0.742246 -0.668254 -v -0.076437 0.024800 0.202535 -vn 0.149121 0.742239 -0.653334 -v -0.076883 0.024800 0.202502 -vn 0.335064 0.742247 -0.580346 -v -0.077299 0.024800 0.202338 -vn 0.491246 0.742241 -0.455803 -v -0.077649 0.024800 0.202059 -vn 0.603766 0.742243 -0.290760 -v -0.077901 0.024800 0.201690 -vn 0.662646 0.742243 -0.099878 -v -0.078033 0.024800 0.201263 -vn 0.662646 0.742243 0.099878 -v -0.078033 0.024800 0.200816 -vn 0.603771 0.742241 0.290756 -v -0.077901 0.024800 0.200388 -vn 0.491240 0.742246 0.455801 -v -0.077649 0.024800 0.200019 -vn 0.335069 0.742240 0.580352 -v -0.077299 0.024800 0.199740 -vn 0.149118 0.742247 0.653325 -v -0.076883 0.024800 0.199577 -vn -0.050084 0.742242 0.668258 -v -0.076437 0.024800 0.199543 -vn -0.244825 0.742242 0.623809 -v -0.076001 0.024800 0.199643 -vn -0.417818 0.742245 0.523928 -v -0.075614 0.024800 0.199866 -vn -0.553690 0.742242 0.377498 -v -0.075310 0.024800 0.200194 -vn -0.640358 0.742244 0.197523 -v -0.075116 0.024800 0.200597 -vn -0.611124 0.681886 -0.401944 -v -0.078555 0.024800 0.199720 -vn -0.687346 0.681887 -0.250171 -v -0.078805 0.024800 0.200218 -vn -0.726512 0.681887 -0.084916 -v -0.078933 0.024800 0.200760 -vn -0.726512 0.681887 0.084916 -v -0.078933 0.024800 0.201318 -vn -0.042536 0.681887 -0.730220 -v -0.076689 0.024800 0.198643 -vn -0.209787 0.681887 -0.700728 -v -0.077238 0.024800 0.198740 -vn -0.365728 0.681887 -0.633461 -v -0.077749 0.024800 0.198961 -vn -0.501954 0.681887 -0.532046 -v -0.078196 0.024800 0.199293 -vn 0.653654 0.681887 -0.328278 -v -0.074405 0.024800 0.199962 -vn 0.560330 0.681887 -0.470171 -v -0.074711 0.024800 0.199496 -vn 0.436797 0.681886 -0.586719 -v -0.075116 0.024800 0.199114 -vn 0.289719 0.681888 -0.671633 -v -0.075599 0.024800 0.198835 -vn 0.127018 0.681884 -0.720348 -v -0.076133 0.024800 0.198676 -vn 0.653656 0.681886 0.328276 -v -0.074405 0.024800 0.202116 -vn 0.711741 0.681888 0.168684 -v -0.074214 0.024800 0.201593 -vn 0.731458 0.681886 0.000001 -v -0.074149 0.024800 0.201039 -vn 0.711742 0.681886 -0.168687 -v -0.074214 0.024800 0.200486 -vn -0.042527 0.681884 0.730223 -v -0.076689 0.024800 0.203435 -vn 0.127018 0.681890 0.720342 -v -0.076133 0.024800 0.203403 -vn 0.289712 0.681886 0.671639 -v -0.075599 0.024800 0.203243 -vn 0.436797 0.681886 0.586719 -v -0.075116 0.024800 0.202964 -vn 0.560330 0.681887 0.470171 -v -0.074711 0.024800 0.202582 -vn -0.687346 0.681885 0.250176 -v -0.078805 0.024800 0.201860 -vn -0.611121 0.681887 0.401947 -v -0.078555 0.024800 0.202358 -vn -0.501958 0.681889 0.532039 -v -0.078196 0.024800 0.202785 -vn -0.365736 0.681885 0.633459 -v -0.077749 0.024800 0.203118 -vn -0.209787 0.681887 0.700728 -v -0.077238 0.024800 0.203338 -vn 0.678938 0.734195 0.000001 -v -0.074149 0.024500 0.201039 -vn 0.660640 0.734194 0.156573 -v -0.074214 0.024500 0.201593 -vn 0.606722 0.734196 0.304705 -v -0.074405 0.024500 0.202116 -vn 0.520099 0.734194 0.436413 -v -0.074711 0.024500 0.202582 -vn 0.405434 0.734196 0.544592 -v -0.075116 0.024500 0.202964 -vn 0.268909 0.734196 0.623413 -v -0.075599 0.024500 0.203243 -vn 0.117899 0.734191 0.668628 -v -0.076133 0.024500 0.203403 -vn -0.039473 0.734198 0.677787 -v -0.076689 0.024500 0.203435 -vn -0.194724 0.734194 0.650416 -v -0.077238 0.024500 0.203338 -vn -0.339474 0.734197 0.587973 -v -0.077749 0.024500 0.203118 -vn -0.465921 0.734192 0.493842 -v -0.078196 0.024500 0.202785 -vn -0.567243 0.734195 0.373087 -v -0.078555 0.024500 0.202358 -vn -0.637992 0.734196 0.232212 -v -0.078805 0.024500 0.201860 -vn -0.674349 0.734195 0.078819 -v -0.078933 0.024500 0.201318 -vn -0.674349 0.734195 -0.078819 -v -0.078933 0.024500 0.200760 -vn -0.637995 0.734195 -0.232209 -v -0.078805 0.024500 0.200218 -vn -0.567243 0.734196 -0.373083 -v -0.078555 0.024500 0.199720 -vn -0.465914 0.734195 -0.493845 -v -0.078196 0.024500 0.199293 -vn -0.339469 0.734194 -0.587979 -v -0.077749 0.024500 0.198961 -vn -0.194724 0.734194 -0.650416 -v -0.077238 0.024500 0.198740 -vn -0.039482 0.734194 -0.677790 -v -0.076689 0.024500 0.198643 -vn 0.117897 0.734198 -0.668621 -v -0.076133 0.024500 0.198676 -vn 0.268919 0.734193 -0.623413 -v -0.075599 0.024500 0.198835 -vn 0.405434 0.734196 -0.544592 -v -0.075116 0.024500 0.199114 -vn 0.520098 0.734195 -0.436413 -v -0.074711 0.024500 0.199496 -vn 0.606722 0.734195 -0.304708 -v -0.074405 0.024500 0.199962 -vn 0.660637 0.734195 -0.156575 -v -0.074214 0.024500 0.200486 -vn 0.726736 0.686917 -0.000000 -v -0.080649 0.024500 0.201039 -vn 0.714361 0.686917 -0.133538 -v -0.080580 0.024500 0.201792 -vn 0.677662 0.686918 -0.262524 -v -0.080373 0.024500 0.202520 -vn 0.617885 0.686916 -0.382575 -v -0.080035 0.024500 0.203197 -vn -0.198882 0.686917 0.698992 -v -0.075427 0.024500 0.197096 -vn -0.067056 0.686917 0.723636 -v -0.076171 0.024500 0.196957 -vn 0.067056 0.686917 0.723636 -v -0.076928 0.024500 0.196957 -vn 0.198882 0.686917 0.698992 -v -0.077671 0.024500 0.197096 -vn 0.323932 0.686918 0.650548 -v -0.078377 0.024500 0.197369 -vn 0.437956 0.686916 0.579949 -v -0.079020 0.024500 0.197767 -vn 0.537065 0.686917 0.489597 -v -0.079579 0.024500 0.198277 -vn 0.617883 0.686917 0.382577 -v -0.080035 0.024500 0.198881 -vn 0.677662 0.686916 0.262526 -v -0.080373 0.024500 0.199558 -vn 0.714361 0.686918 0.133536 -v -0.080580 0.024500 0.200286 -vn -0.677662 0.686916 0.262526 -v -0.072726 0.024500 0.199558 -vn -0.617883 0.686917 0.382577 -v -0.073064 0.024500 0.198881 -vn -0.537065 0.686917 0.489597 -v -0.073520 0.024500 0.198277 -vn -0.437956 0.686916 0.579949 -v -0.074079 0.024500 0.197767 -vn -0.323932 0.686918 0.650548 -v -0.074722 0.024500 0.197369 -vn -0.198876 0.686915 -0.698996 -v -0.075427 0.024500 0.204983 -vn -0.323938 0.686916 -0.650546 -v -0.074722 0.024500 0.204709 -vn -0.437955 0.686919 -0.579946 -v -0.074079 0.024500 0.204311 -vn -0.537063 0.686916 -0.489602 -v -0.073520 0.024500 0.203801 -vn 0.537063 0.686916 -0.489602 -v -0.079579 0.024500 0.203801 -vn 0.437955 0.686919 -0.579946 -v -0.079020 0.024500 0.204311 -vn 0.323938 0.686916 -0.650546 -v -0.078377 0.024500 0.204709 -vn 0.198876 0.686915 -0.698996 -v -0.077671 0.024500 0.204983 -vn 0.067049 0.686919 -0.723635 -v -0.076928 0.024500 0.205122 -vn -0.067049 0.686919 -0.723635 -v -0.076171 0.024500 0.205122 -vn -0.617885 0.686916 -0.382575 -v -0.073064 0.024500 0.203197 -vn -0.677662 0.686918 -0.262524 -v -0.072726 0.024500 0.202520 -vn -0.714361 0.686917 -0.133538 -v -0.072519 0.024500 0.201792 -vn -0.726736 0.686917 0.000000 -v -0.072449 0.024500 0.201039 -vn -0.714361 0.686918 0.133536 -v -0.072519 0.024500 0.200286 -vn -0.206969 -0.742177 -0.637445 -v -0.077292 -0.019797 0.198753 -vn -0.138299 -0.742758 -0.655122 -v -0.077049 -0.019797 0.198687 -vn -0.113596 -0.865259 -0.488285 -v -0.077006 -0.020062 0.199087 -vn -0.039028 -0.865305 -0.499724 -v -0.076703 -0.020062 0.199041 -vn 0.501040 -0.865230 0.018335 -v -0.074547 -0.020062 0.201116 -vn 0.498496 -0.865039 -0.056651 -v -0.074558 -0.020062 0.200809 -vn 0.665754 -0.742982 -0.068921 -v -0.074158 -0.019797 0.200788 -vn 0.151365 -0.865383 0.477704 -v -0.075945 -0.020062 0.202950 -vn 0.222044 -0.865513 0.448981 -v -0.075660 -0.020062 0.202835 -vn 0.271922 -0.742395 0.612298 -v -0.075572 -0.019797 0.203236 -vn -0.315266 -0.918071 0.240317 -v -0.077803 -0.020277 0.201994 -vn -0.225789 -0.958825 0.172263 -v -0.077444 -0.020439 0.201721 -vn -0.196809 -0.958878 0.204500 -v -0.077329 -0.020439 0.201849 -vn -0.202571 -0.918072 -0.340748 -v -0.077355 -0.020277 0.199685 -vn -0.152009 -0.957141 -0.246527 -v -0.077124 -0.020439 0.200073 -vn -0.180782 -0.958824 -0.219030 -v -0.077265 -0.020439 0.200172 -vn 0.372757 -0.817586 0.438868 -v -0.076968 -0.020546 0.200532 -vn 0.425529 -0.819713 0.383401 -v -0.077040 -0.020546 0.200602 -vn -0.000984 -0.990511 -0.137432 -v -0.077749 -0.020398 0.201409 -vn -0.272333 -0.960993 -0.048236 -v -0.077608 -0.020439 0.201419 -vn -0.375281 -0.916744 0.136913 -v -0.078033 -0.020277 0.201572 -vn 0.165834 -0.986136 0.005882 -v -0.076919 -0.020398 0.202238 -vn -0.130863 -0.955905 0.262907 -v -0.077048 -0.020439 0.202047 -vn 0.652612 -0.741450 0.156043 -v -0.076919 -0.020486 0.201913 -vn -0.653033 -0.741738 0.152881 -v -0.076179 -0.020486 0.201913 -vn 0.138135 -0.955247 0.261574 -v -0.076050 -0.020439 0.202047 -vn -0.661475 -0.722538 0.200972 -v -0.076179 -0.020439 0.202098 -vn -0.000315 -0.989991 -0.141131 -v -0.075350 -0.020398 0.201409 -vn 0.272334 -0.960993 -0.048235 -v -0.075491 -0.020439 0.201419 -vn 0.150684 -0.746580 -0.648007 -v -0.075675 -0.020486 0.201409 -vn -0.361862 -0.930928 -0.049287 -v -0.075349 -0.020401 0.200708 -vn 0.388937 -0.915046 -0.106856 -v -0.075030 -0.020277 0.200622 -vn 0.398732 -0.915925 -0.045757 -v -0.074984 -0.020277 0.200858 -vn 0.158188 -0.987367 -0.009101 -v -0.076919 -0.020398 0.199840 -vn -0.094879 -0.958032 -0.270505 -v -0.076970 -0.020439 0.199996 -vn -0.151265 -0.916786 -0.369625 -v -0.077139 -0.020277 0.199578 -vn 0.657319 -0.708545 0.256702 -v -0.076919 -0.020546 0.200496 -vn 0.650908 -0.743652 -0.152644 -v -0.076919 -0.020486 0.200165 -vn -0.043474 -0.931343 0.361538 -v -0.076833 -0.020404 0.199837 -vn 0.211913 -0.958850 -0.188946 -v -0.075710 -0.020439 0.200291 -vn 0.238279 -0.958891 -0.154117 -v -0.075606 -0.020439 0.200428 -vn -0.248382 -0.710344 0.658573 -v -0.076006 -0.020546 0.200669 -vn 0.258607 -0.958595 -0.119240 -v -0.075523 -0.020439 0.200579 -vn 0.149423 -0.763713 0.628025 -v -0.075675 -0.020486 0.200669 -vn 0.013355 -0.986586 0.162697 -v -0.075350 -0.020398 0.200669 -vn 0.363341 -0.916877 -0.165287 -v -0.075112 -0.020277 0.200395 -vn -0.361898 -0.932163 -0.010130 -v -0.075342 -0.020414 0.201039 -vn 0.401331 -0.915798 0.015702 -v -0.074975 -0.020277 0.201099 -vn -0.362172 -0.931940 0.017854 -v -0.075343 -0.020413 0.201086 -vn 0.394904 -0.915633 0.075278 -v -0.075002 -0.020277 0.201339 -vn 0.375833 -0.916350 0.138029 -v -0.075066 -0.020277 0.201572 -vn 0.167670 -0.957932 0.232925 -v -0.075903 -0.020439 0.201959 -vn 0.178824 -0.917048 0.356435 -v -0.075850 -0.020277 0.202451 -vn 0.122049 -0.914815 0.384990 -v -0.076074 -0.020277 0.202541 -vn -0.165066 -0.986262 0.006424 -v -0.076179 -0.020398 0.202238 -vn 0.060752 -0.915362 0.398023 -v -0.076309 -0.020277 0.202596 -vn 0.030852 -0.931782 -0.361704 -v -0.076362 -0.020410 0.202244 -vn -0.000204 -0.915918 0.401366 -v -0.076549 -0.020277 0.202615 -vn -0.000378 -0.932855 -0.360251 -v -0.076549 -0.020414 0.202246 -vn -0.061066 -0.915808 0.396947 -v -0.076790 -0.020277 0.202596 -vn -0.031734 -0.932197 -0.360557 -v -0.076737 -0.020410 0.202244 -vn -0.121156 -0.915164 0.384443 -v -0.077025 -0.020277 0.202541 -vn -0.152305 -0.864975 0.478145 -v -0.077154 -0.020062 0.202950 -vn 0.349815 -0.813507 -0.464582 -v -0.076928 -0.020546 0.201577 -vn 0.654876 -0.705307 -0.271439 -v -0.076919 -0.020546 0.201582 -vn -0.167647 -0.957940 0.232906 -v -0.077196 -0.020439 0.201959 -vn 0.361221 -0.931716 0.037746 -v -0.077753 -0.020407 0.201275 -vn -0.239776 -0.957557 -0.159975 -v -0.077493 -0.020439 0.200428 -vn 0.250148 -0.709968 0.658310 -v -0.077092 -0.020546 0.200669 -vn -0.154387 -0.742142 0.652220 -v -0.077424 -0.020486 0.200669 -vn -0.211914 -0.958850 -0.188944 -v -0.077389 -0.020439 0.200291 -vn -0.451977 -0.815460 -0.361583 -v -0.076027 -0.020546 0.201437 -vn 0.196807 -0.958878 0.204499 -v -0.075770 -0.020439 0.201849 -vn -0.395930 -0.820939 -0.411459 -v -0.076094 -0.020546 0.201513 -vn -0.348943 -0.812783 -0.466501 -v -0.076171 -0.020546 0.201577 -vn -0.656637 -0.702951 -0.273291 -v -0.076179 -0.020546 0.201582 -vn -0.161460 -0.986866 -0.005132 -v -0.076179 -0.020398 0.199840 -vn 0.094878 -0.958032 -0.270504 -v -0.076129 -0.020439 0.199996 -vn -0.650908 -0.743652 -0.152644 -v -0.076179 -0.020486 0.200165 -vn 0.152009 -0.957141 -0.246526 -v -0.075975 -0.020439 0.200073 -vn -0.657319 -0.708545 0.256702 -v -0.076179 -0.020546 0.200496 -vn 0.180784 -0.958824 -0.219030 -v -0.075834 -0.020439 0.200172 -vn -0.372757 -0.817586 0.438868 -v -0.076131 -0.020546 0.200532 -vn -0.425529 -0.819712 0.383401 -v -0.076059 -0.020546 0.200602 -vn 0.395930 -0.820938 -0.411461 -v -0.077005 -0.020546 0.201513 -vn 0.451977 -0.815460 -0.361584 -v -0.077072 -0.020546 0.201437 -vn 0.263271 -0.707128 -0.656246 -v -0.077092 -0.020546 0.201409 -vn 0.228068 -0.918073 0.324233 -v -0.075643 -0.020277 0.202328 -vn -0.188170 -0.865252 -0.464684 -v -0.077299 -0.020062 0.199180 -vn -0.150684 -0.746580 -0.648007 -v -0.077424 -0.020486 0.201409 -vn -0.253084 -0.956722 0.143637 -v -0.077537 -0.020439 0.201576 -vn -0.348255 -0.918072 0.189374 -v -0.077934 -0.020277 0.201792 -vn -0.440039 -0.865320 0.239973 -v -0.078310 -0.020062 0.201997 -vn 0.274885 -0.918073 0.285623 -v -0.075457 -0.020277 0.202175 -vn 0.347134 -0.865450 0.361241 -v -0.075160 -0.020062 0.202483 -vn 0.288618 -0.865364 0.409687 -v -0.075396 -0.020062 0.202679 -vn 0.398931 -0.865334 0.303400 -v -0.074955 -0.020062 0.202254 -vn 0.315267 -0.918071 0.240316 -v -0.075296 -0.020277 0.201994 -vn 0.225787 -0.958825 0.172262 -v -0.075655 -0.020439 0.201721 -vn -0.263271 -0.707128 -0.656246 -v -0.076006 -0.020546 0.201409 -vn 0.253085 -0.956722 0.143636 -v -0.075562 -0.020439 0.201576 -vn 0.348257 -0.918071 0.189374 -v -0.075165 -0.020277 0.201792 -vn 0.440024 -0.865347 0.239903 -v -0.074789 -0.020062 0.201997 -vn 0.579525 -0.742651 0.335589 -v -0.074467 -0.019797 0.202241 -vn 0.612253 -0.742168 0.272641 -v -0.074353 -0.019797 0.202017 -vn 0.492101 -0.865211 0.096158 -v -0.074582 -0.020062 0.201421 -vn 0.472007 -0.865289 0.168771 -v -0.074663 -0.020062 0.201717 -vn 0.483305 -0.865157 -0.133866 -v -0.074617 -0.020062 0.200508 -vn 0.458572 -0.864831 -0.204399 -v -0.074720 -0.020062 0.200219 -vn 0.332739 -0.918071 -0.215478 -v -0.075227 -0.020277 0.200183 -vn 0.420384 -0.865553 -0.272205 -v -0.074867 -0.020062 0.199950 -vn 0.295946 -0.918071 -0.263745 -v -0.075373 -0.020277 0.199991 -vn 0.374020 -0.865386 -0.333490 -v -0.075053 -0.020062 0.199706 -vn 0.252211 -0.918071 -0.305835 -v -0.075547 -0.020277 0.199823 -vn 0.318799 -0.865530 -0.386296 -v -0.075274 -0.020062 0.199493 -vn 0.202573 -0.918071 -0.340749 -v -0.075744 -0.020277 0.199685 -vn 0.255820 -0.865374 -0.430911 -v -0.075525 -0.020062 0.199316 -vn 0.152234 -0.916470 -0.370010 -v -0.075960 -0.020277 0.199578 -vn 0.187576 -0.865475 -0.464509 -v -0.075800 -0.020062 0.199180 -vn 0.090461 -0.915267 -0.392560 -v -0.076190 -0.020277 0.199505 -vn 0.113726 -0.865345 -0.488103 -v -0.076093 -0.020062 0.199087 -vn 0.031135 -0.915714 -0.400623 -v -0.076429 -0.020277 0.199468 -vn 0.038854 -0.865385 -0.499599 -v -0.076396 -0.020062 0.199041 -vn -0.030770 -0.915764 -0.400536 -v -0.076670 -0.020277 0.199468 -vn -0.091728 -0.915307 -0.392172 -v -0.076909 -0.020277 0.199505 -vn -0.421627 -0.865099 -0.271726 -v -0.078232 -0.020062 0.199950 -vn -0.363502 -0.916718 -0.165813 -v -0.077987 -0.020277 0.200395 -vn -0.457892 -0.864671 -0.206590 -v -0.078379 -0.020062 0.200219 -vn -0.389123 -0.915090 -0.105802 -v -0.078069 -0.020277 0.200622 -vn -0.482901 -0.865541 -0.132836 -v -0.078482 -0.020062 0.200508 -vn -0.399125 -0.915729 -0.046263 -v -0.078115 -0.020277 0.200858 -vn -0.497841 -0.865378 -0.057223 -v -0.078541 -0.020062 0.200809 -vn -0.401459 -0.915747 0.015432 -v -0.078124 -0.020277 0.201099 -vn -0.500558 -0.865496 0.018907 -v -0.078552 -0.020062 0.201116 -vn -0.394912 -0.915525 0.076548 -v -0.078096 -0.020277 0.201339 -vn -0.491910 -0.865356 0.095832 -v -0.078517 -0.020062 0.201421 -vn -0.005809 -0.986144 0.165788 -v -0.077749 -0.020398 0.200669 -vn 0.361172 -0.932107 -0.027053 -v -0.077755 -0.020411 0.200899 -vn 0.360794 -0.932641 0.003048 -v -0.077757 -0.020414 0.201039 -vn -0.471705 -0.865419 0.168951 -v -0.078436 -0.020062 0.201717 -vn -0.637256 -0.742546 0.206229 -v -0.078836 -0.019797 0.201782 -vn -0.612239 -0.742180 0.272639 -v -0.078746 -0.019797 0.202017 -vn -0.228069 -0.918073 0.324231 -v -0.077456 -0.020277 0.202328 -vn -0.289156 -0.865157 0.409747 -v -0.077703 -0.020062 0.202679 -vn -0.347071 -0.865272 0.361726 -v -0.077939 -0.020062 0.202483 -vn -0.221663 -0.865205 0.449761 -v -0.077439 -0.020062 0.202835 -vn -0.178822 -0.917048 0.356434 -v -0.077249 -0.020277 0.202451 -vn -0.207831 -0.743034 0.636166 -v -0.077292 -0.019797 0.203326 -vn 0.076378 -0.865550 0.494965 -v -0.076243 -0.020062 0.203020 -vn -0.001140 -0.864755 0.502193 -v -0.076549 -0.020062 0.203044 -vn -0.075514 -0.865130 0.495831 -v -0.076855 -0.020062 0.203020 -vn 0.335293 -0.742197 0.580278 -v -0.075347 -0.019797 0.203121 -vn 0.542291 -0.742634 0.392958 -v -0.074604 -0.019797 0.202452 -vn 0.498132 -0.742172 0.448381 -v -0.074763 -0.019797 0.202648 -vn 0.447653 -0.742501 0.498296 -v -0.074941 -0.019797 0.202826 -vn 0.394163 -0.742504 0.541593 -v -0.075136 -0.019797 0.202984 -vn 0.669195 -0.743085 -0.001374 -v -0.074145 -0.019797 0.201039 -vn 0.666495 -0.742193 0.070241 -v -0.074158 -0.019797 0.201290 -vn 0.654707 -0.742780 0.140135 -v -0.074198 -0.019797 0.201539 -vn 0.637053 -0.742828 0.205841 -v -0.074263 -0.019797 0.201782 -vn 0.655580 -0.742219 -0.139015 -v -0.074198 -0.019797 0.200539 -vn 0.541876 -0.742266 -0.394223 -v -0.074604 -0.019797 0.199626 -vn 0.580532 -0.742299 -0.334627 -v -0.074467 -0.019797 0.199837 -vn 0.611697 -0.743181 -0.271126 -v -0.074353 -0.019797 0.200061 -vn 0.635615 -0.743390 -0.208244 -v -0.074263 -0.019797 0.200296 -vn 0.393692 -0.742201 -0.542350 -v -0.075136 -0.019797 0.199094 -vn 0.448766 -0.742360 -0.497504 -v -0.074941 -0.019797 0.199252 -vn 0.497756 -0.742388 -0.448441 -v -0.074763 -0.019797 0.199430 -vn 0.206960 -0.742175 -0.637451 -v -0.075807 -0.019797 0.198753 -vn 0.273112 -0.742469 -0.611678 -v -0.075572 -0.019797 0.198843 -vn 0.334541 -0.742461 -0.580374 -v -0.075347 -0.019797 0.198957 -vn -0.071002 -0.742760 -0.665782 -v -0.076801 -0.019797 0.198648 -vn 0.000000 -0.742178 -0.670203 -v -0.076549 -0.019797 0.198635 -vn 0.070829 -0.742597 -0.665983 -v -0.076298 -0.019797 0.198648 -vn 0.138529 -0.742598 -0.655255 -v -0.076050 -0.019797 0.198687 -vn -0.273395 -0.742989 -0.610919 -v -0.077527 -0.019797 0.198843 -vn -0.006564 -0.932410 0.361343 -v -0.076549 -0.020414 0.199832 -vn 0.022437 -0.932030 0.361685 -v -0.076456 -0.020413 0.199833 -vn -0.252213 -0.918071 -0.305834 -v -0.077552 -0.020277 0.199823 -vn -0.255611 -0.865102 -0.431580 -v -0.077574 -0.020062 0.199316 -vn -0.333808 -0.742916 -0.580214 -v -0.077752 -0.019797 0.198957 -vn -0.319791 -0.865183 -0.386254 -v -0.077825 -0.020062 0.199493 -vn -0.448802 -0.743268 -0.496115 -v -0.078158 -0.019797 0.199252 -vn -0.393697 -0.742202 -0.542346 -v -0.077963 -0.019797 0.199094 -vn -0.295945 -0.918071 -0.263745 -v -0.077726 -0.020277 0.199991 -vn -0.267394 -0.956365 -0.117758 -v -0.077576 -0.020439 0.200579 -vn -0.332740 -0.918071 -0.215476 -v -0.077872 -0.020277 0.200183 -vn -0.374048 -0.864904 -0.334707 -v -0.078046 -0.020062 0.199706 -vn -0.496557 -0.743107 -0.448580 -v -0.078336 -0.019797 0.199430 -vn -0.541880 -0.742263 -0.394223 -v -0.078495 -0.019797 0.199626 -vn -0.655581 -0.742220 -0.139006 -v -0.078901 -0.019797 0.200539 -vn -0.637049 -0.742349 -0.207573 -v -0.078836 -0.019797 0.200296 -vn -0.610603 -0.743351 -0.273116 -v -0.078746 -0.019797 0.200061 -vn -0.579925 -0.743626 -0.332729 -v -0.078632 -0.019797 0.199837 -vn -0.655050 -0.742521 0.139903 -v -0.078901 -0.019797 0.201539 -vn -0.666492 -0.742196 0.070237 -v -0.078941 -0.019797 0.201290 -vn -0.669915 -0.742438 -0.000675 -v -0.078954 -0.019797 0.201039 -vn -0.666289 -0.742433 -0.069655 -v -0.078941 -0.019797 0.200788 -vn -0.579444 -0.742706 0.335607 -v -0.078632 -0.019797 0.202241 -vn -0.274886 -0.918073 0.285622 -v -0.077642 -0.020277 0.202175 -vn -0.399000 -0.865307 0.303386 -v -0.078144 -0.020062 0.202254 -vn -0.542275 -0.742690 0.392873 -v -0.078495 -0.019797 0.202452 -vn -0.498130 -0.742173 0.448382 -v -0.078336 -0.019797 0.202648 -vn -0.270821 -0.743169 0.611847 -v -0.077527 -0.019797 0.203236 -vn -0.335288 -0.742199 0.580279 -v -0.077752 -0.019797 0.203121 -vn -0.394285 -0.742863 0.541012 -v -0.077963 -0.019797 0.202984 -vn -0.447023 -0.742900 0.498267 -v -0.078158 -0.019797 0.202826 -vn -0.139696 -0.742235 0.655418 -v -0.077049 -0.019797 0.203391 -vn 0.207302 -0.742401 0.637076 -v -0.075807 -0.019797 0.203326 -vn 0.139701 -0.742237 0.655414 -v -0.076050 -0.019797 0.203391 -vn 0.069529 -0.742314 0.666435 -v -0.076298 -0.019797 0.203430 -vn -0.001129 -0.743243 0.669021 -v -0.076549 -0.019797 0.203443 -vn -0.068192 -0.743499 0.665251 -v -0.076801 -0.019797 0.203430 -vn 0.603850 -0.719725 -0.342580 -v -0.076919 -0.019100 0.201454 -vn 0.605650 -0.676653 -0.418722 -v -0.076919 -0.019100 0.201591 -vn 0.605649 -0.676652 0.418726 -v -0.076919 -0.019100 0.200487 -vn 0.603962 -0.719631 0.342582 -v -0.076919 -0.019100 0.200624 -vn -0.605650 -0.676653 -0.418722 -v -0.076179 -0.019100 0.201591 -vn -0.603849 -0.719726 -0.342579 -v -0.076179 -0.019100 0.201454 -vn -0.603961 -0.719632 0.342581 -v -0.076179 -0.019100 0.200624 -vn -0.605649 -0.676652 0.418725 -v -0.076179 -0.019100 0.200487 -vn 0.013912 -0.763202 -0.646010 -v -0.076615 -0.019100 0.201591 -vn 0.000006 -0.446593 -0.894737 -v -0.076549 -0.019109 0.201596 -vn -0.013916 -0.763206 -0.646005 -v -0.076484 -0.019100 0.201591 -vn -0.013883 -0.763193 0.646021 -v -0.076484 -0.019100 0.200487 -vn 0.000003 -0.446055 0.895006 -v -0.076549 -0.019109 0.200482 -vn 0.013881 -0.763191 0.646024 -v -0.076615 -0.019100 0.200487 -vn 0.642938 -0.765419 0.027665 -v -0.077102 -0.019100 0.200974 -vn 0.418726 -0.676652 0.605649 -v -0.077102 -0.019100 0.200669 -vn 0.128261 -0.989929 0.059911 -v -0.077050 -0.019100 0.200798 -vn 0.345598 -0.724809 0.595998 -v -0.076964 -0.019100 0.200669 -vn 0.042859 -0.989676 0.136763 -v -0.076673 -0.019100 0.200497 -vn 0.079487 -0.989472 0.120945 -v -0.076896 -0.019100 0.200604 -vn -0.079487 -0.989472 0.120944 -v -0.076203 -0.019100 0.200604 -vn -0.042859 -0.989676 0.136762 -v -0.076426 -0.019100 0.200497 -vn -0.345597 -0.724810 0.595998 -v -0.076134 -0.019100 0.200669 -vn -0.418725 -0.676652 0.605650 -v -0.075997 -0.019100 0.200669 -vn -0.128259 -0.989929 0.059910 -v -0.076049 -0.019100 0.200798 -vn -0.642936 -0.765420 0.027664 -v -0.075997 -0.019100 0.200974 -vn -0.642936 -0.765420 -0.027665 -v -0.075997 -0.019100 0.201105 -vn -0.418726 -0.676652 -0.605649 -v -0.075997 -0.019100 0.201409 -vn -0.128261 -0.989929 -0.059912 -v -0.076049 -0.019100 0.201280 -vn -0.345685 -0.724937 -0.595792 -v -0.076134 -0.019100 0.201409 -vn -0.042838 -0.989678 -0.136755 -v -0.076426 -0.019100 0.201581 -vn -0.079487 -0.989472 -0.120944 -v -0.076203 -0.019100 0.201474 -vn 0.079487 -0.989472 -0.120945 -v -0.076896 -0.019100 0.201474 -vn 0.042838 -0.989678 -0.136755 -v -0.076673 -0.019100 0.201581 -vn -0.959778 -0.280761 -0.000001 -v -0.075993 -0.019109 0.201039 -vn 0.959778 -0.280760 -0.000002 -v -0.077106 -0.019109 0.201039 -vn 0.642938 -0.765418 -0.027665 -v -0.077102 -0.019100 0.201105 -vn 0.418726 -0.676652 -0.605649 -v -0.077102 -0.019100 0.201409 -vn 0.345686 -0.724936 -0.595793 -v -0.076964 -0.019100 0.201409 -vn 0.976028 0.131346 -0.173545 -v -0.075325 -0.018400 0.200787 -vn 0.704492 0.675629 -0.217293 -v -0.075355 -0.010500 0.200671 -vn 0.737262 0.675607 0.000000 -v -0.075299 -0.010500 0.201039 -vn 0.948708 0.025799 -0.315098 -v -0.075355 -0.018400 0.200671 -vn 0.907405 0.123974 -0.401555 -v -0.075401 -0.018400 0.200546 -vn 0.609140 0.675344 -0.415763 -v -0.075517 -0.010500 0.200335 -vn 0.845247 0.126918 -0.519086 -v -0.075517 -0.018400 0.200335 -vn 0.460116 0.675377 -0.576333 -v -0.075770 -0.010500 0.200062 -vn 0.785681 0.133134 -0.604136 -v -0.075524 -0.018400 0.200325 -vn 0.703825 0.131790 -0.698041 -v -0.075688 -0.018400 0.200133 -vn 0.602800 0.037933 -0.796990 -v -0.075770 -0.018400 0.200062 -vn 0.518551 0.124711 -0.845903 -v -0.075888 -0.018400 0.199978 -vn 0.269074 0.675351 -0.686659 -v -0.076093 -0.010500 0.199876 -vn 0.403397 0.120418 -0.907067 -v -0.076093 -0.018400 0.199876 -vn 0.055505 0.675374 -0.735384 -v -0.076456 -0.010500 0.199793 -vn 0.301789 0.133057 -0.944044 -v -0.076115 -0.018400 0.199867 -vn 0.181221 0.131681 -0.974587 -v -0.076360 -0.018400 0.199804 -vn 0.045002 0.049937 -0.997738 -v -0.076456 -0.018400 0.199793 -vn -0.053888 0.125463 -0.990634 -v -0.076613 -0.018400 0.199791 -vn -0.164497 0.675366 -0.718903 -v -0.076828 -0.010500 0.199820 -vn -0.181514 0.113778 -0.976784 -v -0.076828 -0.018400 0.199820 -vn -0.368383 0.675376 -0.638875 -v -0.077174 -0.010500 0.199957 -vn -0.289326 0.133087 -0.947934 -v -0.076863 -0.018400 0.199829 -vn -0.405864 0.131532 -0.904419 -v -0.077100 -0.018400 0.199917 -vn -0.703230 0.105757 -0.703053 -v -0.077466 -0.018400 0.200189 -vn -0.540580 0.675575 -0.501370 -v -0.077466 -0.010500 0.200189 -vn -0.607119 0.126199 -0.784526 -v -0.077315 -0.018400 0.200051 -vn -0.527865 0.061728 -0.847082 -v -0.077174 -0.018400 0.199957 -vn -0.778232 0.131268 -0.614104 -v -0.077498 -0.018400 0.200225 -vn -0.848634 0.131370 -0.512408 -v -0.077642 -0.018400 0.200432 -vn -0.664208 0.675574 -0.320044 -v -0.077676 -0.010500 0.200497 -vn -0.978596 0.099844 -0.179946 -v -0.077786 -0.018400 0.200853 -vn -0.729111 0.675546 -0.109706 -v -0.077786 -0.010500 0.200853 -vn -0.945253 0.126877 -0.300666 -v -0.077742 -0.018400 0.200665 -vn -0.914043 0.073541 -0.398895 -v -0.077676 -0.018400 0.200497 -vn -0.989408 0.131355 -0.061794 -v -0.077793 -0.018400 0.200913 -vn -0.989408 0.131355 0.061794 -v -0.077793 -0.018400 0.201166 -vn -0.729110 0.675547 0.109702 -v -0.077786 -0.010500 0.201225 -vn -0.908187 0.094726 0.407704 -v -0.077676 -0.018400 0.201581 -vn -0.664224 0.675518 0.320128 -v -0.077676 -0.010500 0.201581 -vn -0.948607 0.127607 0.289589 -v -0.077742 -0.018400 0.201413 -vn -0.978401 0.084910 0.188471 -v -0.077786 -0.018400 0.201225 -vn -0.848591 0.131411 0.512469 -v -0.077642 -0.018400 0.201646 -vn -0.778270 0.131294 0.614050 -v -0.077498 -0.018400 0.201853 -vn -0.540662 0.675516 0.501362 -v -0.077466 -0.010500 0.201889 -vn -0.516030 0.090573 0.851768 -v -0.077174 -0.018400 0.202122 -vn -0.368458 0.675489 0.638712 -v -0.077174 -0.010500 0.202122 -vn -0.616039 0.128400 0.777180 -v -0.077315 -0.018400 0.202028 -vn -0.699377 0.095842 0.708298 -v -0.077466 -0.018400 0.201889 -vn -0.405881 0.131524 0.904413 -v -0.077100 -0.018400 0.202161 -vn -0.290386 0.131342 0.947853 -v -0.076863 -0.018400 0.202249 -vn -0.164334 0.675472 0.718841 -v -0.076828 -0.010500 0.202258 -vn 0.059341 0.087409 0.994404 -v -0.076456 -0.018400 0.202286 -vn 0.055415 0.675452 0.735319 -v -0.076456 -0.010500 0.202286 -vn -0.065383 0.129121 0.989471 -v -0.076613 -0.018400 0.202288 -vn -0.176189 0.106264 0.978604 -v -0.076828 -0.018400 0.202258 -vn 0.181215 0.131685 0.974587 -v -0.076360 -0.018400 0.202275 -vn 0.300862 0.131386 0.944574 -v -0.076115 -0.018400 0.202211 -vn 0.269127 0.675436 0.686554 -v -0.076093 -0.010500 0.202203 -vn 0.614048 0.085157 0.784661 -v -0.075770 -0.018400 0.202016 -vn 0.460066 0.675398 0.576347 -v -0.075770 -0.010500 0.202016 -vn 0.508280 0.129840 0.851348 -v -0.075888 -0.018400 0.202100 -vn 0.407095 0.115871 0.906007 -v -0.076093 -0.018400 0.202203 -vn 0.703839 0.131698 0.698045 -v -0.075688 -0.018400 0.201945 -vn 0.785201 0.131471 0.605124 -v -0.075524 -0.018400 0.201753 -vn 0.609139 0.675387 0.415695 -v -0.075517 -0.010500 0.201743 -vn 0.846732 0.124275 0.517301 -v -0.075517 -0.018400 0.201743 -vn 0.901896 0.130527 0.411760 -v -0.075401 -0.018400 0.201532 -vn 0.704492 0.675628 0.217299 -v -0.075355 -0.010500 0.201408 -vn 0.951278 0.084146 0.296631 -v -0.075355 -0.018400 0.201408 -vn 0.976027 0.131349 0.173550 -v -0.075325 -0.018400 0.201291 -vn 0.991300 0.131622 -0.000005 -v -0.075299 -0.018400 0.201039 -vn -0.116636 0.992500 0.036595 -v -0.077838 -0.018500 0.201443 -vn -0.121602 0.992502 0.012364 -v -0.077893 -0.018500 0.201176 -vn -0.725587 0.688131 -0.000000 -v -0.079049 -0.018500 0.201039 -vn -0.121598 0.992502 -0.012366 -v -0.077893 -0.018500 0.200903 -vn -0.709728 0.688134 -0.150857 -v -0.078995 -0.018500 0.200519 -vn -0.116626 0.992502 -0.036592 -v -0.077838 -0.018500 0.200635 -vn -0.662858 0.688130 -0.295121 -v -0.078833 -0.018500 0.200022 -vn -0.106879 0.992501 -0.059321 -v -0.077730 -0.018500 0.200384 -vn -0.587012 0.688130 -0.426490 -v -0.078572 -0.018500 0.199570 -vn -0.092739 0.992502 -0.079616 -v -0.077574 -0.018500 0.200160 -vn -0.485509 0.688135 -0.539213 -v -0.078222 -0.018500 0.199181 -vn -0.074835 0.992499 -0.096676 -v -0.077376 -0.018500 0.199972 -vn -0.362795 0.688132 -0.628374 -v -0.077799 -0.018500 0.198874 -vn -0.053824 0.992502 -0.109735 -v -0.077144 -0.018500 0.199827 -vn -0.224214 0.688131 -0.690075 -v -0.077322 -0.018500 0.198661 -vn -0.030643 0.992500 -0.118345 -v -0.076888 -0.018500 0.199732 -vn -0.075841 0.688132 -0.721611 -v -0.076811 -0.018500 0.198553 -vn -0.006190 0.992501 -0.122083 -v -0.076618 -0.018500 0.199691 -vn 0.075841 0.688132 -0.721611 -v -0.076288 -0.018500 0.198553 -vn 0.018512 0.992498 -0.120854 -v -0.076345 -0.018500 0.199705 -vn 0.224214 0.688132 -0.690075 -v -0.075777 -0.018500 0.198661 -vn 0.042449 0.992503 -0.114613 -v -0.076081 -0.018500 0.199773 -vn 0.362796 0.688132 -0.628374 -v -0.075299 -0.018500 0.198874 -vn 0.064651 0.992503 -0.103721 -v -0.075835 -0.018500 0.199893 -vn 0.485509 0.688135 -0.539214 -v -0.074877 -0.018500 0.199181 -vn 0.084221 0.992500 -0.088601 -v -0.075619 -0.018500 0.200061 -vn 0.587015 0.688130 -0.426487 -v -0.074527 -0.018500 0.199570 -vn 0.100341 0.992499 -0.069840 -v -0.075441 -0.018500 0.200268 -vn 0.662855 0.688133 -0.295120 -v -0.074266 -0.018500 0.200022 -vn 0.112321 0.992502 -0.048200 -v -0.075309 -0.018500 0.200507 -vn 0.709728 0.688133 -0.150861 -v -0.074104 -0.018500 0.200519 -vn 0.119745 0.992500 -0.024608 -v -0.075227 -0.018500 0.200767 -vn 0.725587 0.688131 0.000000 -v -0.074049 -0.018500 0.201039 -vn 0.122251 0.992499 -0.000000 -v -0.075199 -0.018500 0.201039 -vn 0.709729 0.688132 0.150862 -v -0.074104 -0.018500 0.201559 -vn 0.119739 0.992500 0.024609 -v -0.075227 -0.018500 0.201311 -vn 0.662856 0.688133 0.295120 -v -0.074266 -0.018500 0.202056 -vn 0.112334 0.992501 0.048205 -v -0.075309 -0.018500 0.201571 -vn 0.587015 0.688128 0.426490 -v -0.074527 -0.018500 0.202509 -vn 0.100325 0.992501 0.069828 -v -0.075441 -0.018500 0.201810 -vn 0.485510 0.688132 0.539217 -v -0.074877 -0.018500 0.202897 -vn 0.084220 0.992500 0.088600 -v -0.075619 -0.018500 0.202018 -vn 0.362797 0.688128 0.628377 -v -0.075299 -0.018500 0.203204 -vn 0.064667 0.992499 0.103748 -v -0.075835 -0.018500 0.202185 -vn 0.224218 0.688130 0.690075 -v -0.075777 -0.018500 0.203417 -vn 0.042461 0.992499 0.114643 -v -0.076081 -0.018500 0.202305 -vn 0.075841 0.688132 0.721611 -v -0.076288 -0.018500 0.203525 -vn 0.018506 0.992502 0.120819 -v -0.076345 -0.018500 0.202374 -vn -0.075841 0.688132 0.721611 -v -0.076811 -0.018500 0.203525 -vn -0.006189 0.992500 0.122086 -v -0.076618 -0.018500 0.202387 -vn -0.224218 0.688130 0.690075 -v -0.077322 -0.018500 0.203417 -vn -0.030634 0.992504 0.118311 -v -0.076888 -0.018500 0.202346 -vn -0.362796 0.688129 0.628377 -v -0.077799 -0.018500 0.203204 -vn -0.053838 0.992499 0.109763 -v -0.077144 -0.018500 0.202251 -vn -0.485511 0.688132 0.539216 -v -0.078222 -0.018500 0.202897 -vn -0.074817 0.992502 0.096655 -v -0.077376 -0.018500 0.202107 -vn -0.587012 0.688129 0.426492 -v -0.078572 -0.018500 0.202509 -vn -0.092742 0.992502 0.079617 -v -0.077574 -0.018500 0.201918 -vn -0.662859 0.688129 0.295121 -v -0.078833 -0.018500 0.202056 -vn -0.106863 0.992503 0.059314 -v -0.077730 -0.018500 0.201694 -vn -0.709729 0.688133 0.150858 -v -0.078995 -0.018500 0.201559 -vn 0.988022 -0.114144 -0.103849 -v -0.074063 -0.019605 0.200778 -vn 0.971653 -0.115041 -0.206534 -v -0.074104 -0.019605 0.200519 -vn 0.944841 -0.114128 -0.307002 -v -0.074172 -0.019605 0.200267 -vn 0.907480 -0.115029 -0.404041 -v -0.074266 -0.019605 0.200022 -vn 0.860374 -0.114092 -0.496729 -v -0.074384 -0.019605 0.199789 -vn 0.803653 -0.115044 -0.583872 -v -0.074527 -0.019605 0.199570 -vn 0.738284 -0.114169 -0.664758 -v -0.074692 -0.019605 0.199366 -vn 0.664679 -0.115045 -0.738218 -v -0.074877 -0.019605 0.199181 -vn 0.583952 -0.114139 -0.803724 -v -0.075080 -0.019605 0.199017 -vn 0.496684 -0.115036 -0.860274 -v -0.075299 -0.019605 0.198874 -vn 0.404076 -0.114146 -0.907575 -v -0.075533 -0.019605 0.198755 -vn 0.306960 -0.115067 -0.944741 -v -0.075777 -0.019605 0.198661 -vn 0.206545 -0.114103 -0.971761 -v -0.076030 -0.019605 0.198594 -vn 0.103830 -0.115026 -0.987921 -v -0.076288 -0.019605 0.198553 -vn -0.000004 -0.114100 -0.993469 -v -0.076549 -0.019605 0.198539 -vn -0.103826 -0.115027 -0.987922 -v -0.076811 -0.019605 0.198553 -vn -0.206556 -0.114109 -0.971758 -v -0.077069 -0.019605 0.198594 -vn -0.306948 -0.115073 -0.944744 -v -0.077322 -0.019605 0.198661 -vn -0.404075 -0.114141 -0.907577 -v -0.077566 -0.019605 0.198755 -vn -0.496687 -0.115038 -0.860272 -v -0.077799 -0.019605 0.198874 -vn -0.583945 -0.114157 -0.803726 -v -0.078019 -0.019605 0.199017 -vn -0.664692 -0.115049 -0.738206 -v -0.078222 -0.019605 0.199181 -vn -0.738273 -0.114167 -0.664770 -v -0.078407 -0.019605 0.199366 -vn -0.803656 -0.115032 -0.583871 -v -0.078572 -0.019605 0.199570 -vn -0.860373 -0.114090 -0.496731 -v -0.078715 -0.019605 0.199789 -vn -0.907478 -0.115034 -0.404043 -v -0.078833 -0.019605 0.200022 -vn -0.944844 -0.114129 -0.306991 -v -0.078927 -0.019605 0.200267 -vn -0.971653 -0.115043 -0.206530 -v -0.078995 -0.019605 0.200519 -vn -0.988021 -0.114144 -0.103854 -v -0.079036 -0.019605 0.200778 -vn -0.993360 -0.115047 0.000003 -v -0.079049 -0.019605 0.201039 -vn -0.988021 -0.114151 0.103851 -v -0.079036 -0.019605 0.201300 -vn -0.971650 -0.115052 0.206540 -v -0.078995 -0.019605 0.201559 -vn -0.944845 -0.114132 0.306990 -v -0.078927 -0.019605 0.201812 -vn -0.907480 -0.115055 0.404032 -v -0.078833 -0.019605 0.202056 -vn -0.860363 -0.114124 0.496740 -v -0.078715 -0.019605 0.202289 -vn -0.803647 -0.115072 0.583875 -v -0.078572 -0.019605 0.202509 -vn -0.738284 -0.114132 0.664763 -v -0.078407 -0.019605 0.202712 -vn -0.664688 -0.115041 0.738211 -v -0.078222 -0.019605 0.202897 -vn -0.583946 -0.114118 0.803731 -v -0.078019 -0.019605 0.203062 -vn -0.496681 -0.115085 0.860270 -v -0.077799 -0.019605 0.203204 -vn -0.404077 -0.114148 0.907575 -v -0.077566 -0.019605 0.203323 -vn -0.306975 -0.115075 0.944735 -v -0.077322 -0.019605 0.203417 -vn -0.206553 -0.114158 0.971753 -v -0.077069 -0.019605 0.203484 -vn -0.103820 -0.115035 0.987921 -v -0.076811 -0.019605 0.203525 -vn -0.000008 -0.114156 0.993463 -v -0.076549 -0.019605 0.203539 -vn 0.103835 -0.115035 0.987920 -v -0.076288 -0.019605 0.203525 -vn 0.206544 -0.114164 0.971754 -v -0.076030 -0.019605 0.203484 -vn 0.306973 -0.115073 0.944736 -v -0.075777 -0.019605 0.203417 -vn 0.404084 -0.114149 0.907572 -v -0.075533 -0.019605 0.203323 -vn 0.496672 -0.115078 0.860276 -v -0.075299 -0.019605 0.203204 -vn 0.583959 -0.114096 0.803725 -v -0.075080 -0.019605 0.203062 -vn 0.664679 -0.115043 0.738218 -v -0.074877 -0.019605 0.202897 -vn 0.738287 -0.114135 0.664760 -v -0.074692 -0.019605 0.202712 -vn 0.803641 -0.115070 0.583884 -v -0.074527 -0.019605 0.202509 -vn 0.860375 -0.114122 0.496719 -v -0.074384 -0.019605 0.202289 -vn 0.907477 -0.115057 0.404038 -v -0.074266 -0.019605 0.202056 -vn 0.944842 -0.114132 0.306999 -v -0.074172 -0.019605 0.201812 -vn 0.971650 -0.115056 0.206539 -v -0.074104 -0.019605 0.201559 -vn 0.988020 -0.114151 0.103857 -v -0.074063 -0.019605 0.201300 -vn 0.993360 -0.115046 -0.000003 -v -0.074049 -0.019605 0.201039 -vn 0.891308 -0.443614 0.093688 -v -0.074088 -0.019712 0.201298 -vn 0.876652 -0.443578 0.186332 -v -0.074129 -0.019712 0.201554 -vn 0.852365 -0.443588 0.276955 -v -0.074196 -0.019712 0.201804 -vn 0.818748 -0.443591 0.364527 -v -0.074289 -0.019712 0.202046 -vn 0.776160 -0.443596 0.448105 -v -0.074406 -0.019712 0.202276 -vn 0.725053 -0.443616 0.526786 -v -0.074547 -0.019712 0.202494 -vn 0.666033 -0.443582 0.599695 -v -0.074710 -0.019712 0.202695 -vn 0.599697 -0.443577 0.666035 -v -0.074894 -0.019712 0.202878 -vn 0.526793 -0.443575 0.725072 -v -0.075095 -0.019712 0.203041 -vn 0.448091 -0.443628 0.776150 -v -0.075312 -0.019712 0.203182 -vn 0.364533 -0.443605 0.818737 -v -0.075543 -0.019712 0.203300 -vn 0.276954 -0.443605 0.852356 -v -0.075785 -0.019712 0.203393 -vn 0.186341 -0.443599 0.876640 -v -0.076035 -0.019712 0.203460 -vn 0.093681 -0.443581 0.891325 -v -0.076291 -0.019712 0.203500 -vn -0.000001 -0.443585 0.896232 -v -0.076549 -0.019712 0.203514 -vn -0.093677 -0.443580 0.891326 -v -0.076808 -0.019712 0.203500 -vn -0.186344 -0.443607 0.876635 -v -0.077064 -0.019712 0.203460 -vn -0.276955 -0.443601 0.852358 -v -0.077314 -0.019712 0.203393 -vn -0.364529 -0.443605 0.818739 -v -0.077556 -0.019712 0.203300 -vn -0.448103 -0.443621 0.776147 -v -0.077787 -0.019712 0.203182 -vn -0.526782 -0.443585 0.725075 -v -0.078004 -0.019712 0.203041 -vn -0.599697 -0.443584 0.666031 -v -0.078205 -0.019712 0.202878 -vn -0.666028 -0.443584 0.599699 -v -0.078389 -0.019712 0.202695 -vn -0.725060 -0.443611 0.526779 -v -0.078552 -0.019712 0.202494 -vn -0.776152 -0.443597 0.448118 -v -0.078693 -0.019712 0.202276 -vn -0.818740 -0.443611 0.364518 -v -0.078810 -0.019712 0.202046 -vn -0.852366 -0.443593 0.276944 -v -0.078903 -0.019712 0.201804 -vn -0.876649 -0.443581 0.186341 -v -0.078970 -0.019712 0.201554 -vn -0.891311 -0.443609 0.093678 -v -0.079011 -0.019712 0.201298 -vn -0.896225 -0.443600 0.000004 -v -0.079024 -0.019712 0.201039 -vn -0.891311 -0.443607 -0.093689 -v -0.079011 -0.019712 0.200780 -vn -0.876653 -0.443576 -0.186334 -v -0.078970 -0.019712 0.200525 -vn -0.852361 -0.443600 -0.276947 -v -0.078903 -0.019712 0.200274 -vn -0.818749 -0.443585 -0.364529 -v -0.078810 -0.019712 0.200033 -vn -0.776166 -0.443570 -0.448121 -v -0.078693 -0.019712 0.199802 -vn -0.725061 -0.443590 -0.526797 -v -0.078552 -0.019712 0.199584 -vn -0.666005 -0.443618 -0.599700 -v -0.078389 -0.019712 0.199383 -vn -0.599703 -0.443585 -0.666024 -v -0.078205 -0.019712 0.199200 -vn -0.526794 -0.443595 -0.725060 -v -0.078004 -0.019712 0.199037 -vn -0.448123 -0.443577 -0.776160 -v -0.077787 -0.019712 0.198896 -vn -0.364511 -0.443604 -0.818748 -v -0.077556 -0.019712 0.198778 -vn -0.276945 -0.443601 -0.852361 -v -0.077314 -0.019712 0.198686 -vn -0.186344 -0.443584 -0.876647 -v -0.077064 -0.019712 0.198618 -vn -0.093679 -0.443583 -0.891324 -v -0.076808 -0.019712 0.198578 -vn -0.000003 -0.443570 -0.896240 -v -0.076549 -0.019712 0.198564 -vn 0.093680 -0.443581 -0.891325 -v -0.076291 -0.019712 0.198578 -vn 0.186341 -0.443592 -0.876643 -v -0.076035 -0.019712 0.198618 -vn 0.276947 -0.443609 -0.852356 -v -0.075785 -0.019712 0.198686 -vn 0.364517 -0.443597 -0.818749 -v -0.075543 -0.019712 0.198778 -vn 0.448118 -0.443579 -0.776162 -v -0.075312 -0.019712 0.198896 -vn 0.526801 -0.443582 -0.725062 -v -0.075095 -0.019712 0.199037 -vn 0.599696 -0.443585 -0.666031 -v -0.074894 -0.019712 0.199200 -vn 0.666016 -0.443616 -0.599689 -v -0.074710 -0.019712 0.199383 -vn 0.725064 -0.443576 -0.526804 -v -0.074547 -0.019712 0.199584 -vn 0.776170 -0.443566 -0.448117 -v -0.074406 -0.019712 0.199802 -vn 0.818753 -0.443573 -0.364535 -v -0.074289 -0.019712 0.200033 -vn 0.852362 -0.443599 -0.276947 -v -0.074196 -0.019712 0.200274 -vn 0.876649 -0.443578 -0.186345 -v -0.074129 -0.019712 0.200525 -vn 0.891313 -0.443604 -0.093681 -v -0.074088 -0.019712 0.200780 -vn 0.896225 -0.443600 -0.000001 -v -0.074075 -0.019712 0.201039 -vn 0.000000 1.000000 0.000000 -v -0.076549 -0.010500 0.201039 -vn 0.707530 0.503873 0.495494 -v -0.075513 -0.018450 0.201761 -vn 0.603792 0.500124 0.620734 -v -0.075679 -0.018450 0.201955 -vn 0.141370 0.499674 0.854599 -v -0.076358 -0.018450 0.202288 -vn 0.296038 0.501593 0.812875 -v -0.076111 -0.018450 0.202224 -vn -0.372086 0.499300 0.782465 -v -0.077106 -0.018450 0.202173 -vn -0.223224 0.500238 0.836620 -v -0.076866 -0.018450 0.202262 -vn -0.752590 0.498926 0.429745 -v -0.077654 -0.018450 0.201652 -vn -0.662181 0.499596 0.558498 -v -0.077508 -0.018450 0.201862 -vn -0.863218 0.498836 -0.077566 -v -0.077806 -0.018450 0.200911 -vn -0.862715 0.499416 0.079412 -v -0.077806 -0.018450 0.201167 -vn -0.663596 0.499048 -0.557307 -v -0.077508 -0.018450 0.200216 -vn -0.753227 0.499505 -0.427953 -v -0.077654 -0.018450 0.200426 -vn -0.224933 0.499686 -0.836492 -v -0.076866 -0.018450 0.199816 -vn -0.373633 0.499686 -0.781481 -v -0.077106 -0.018450 0.199905 -vn 0.294879 0.500892 -0.813728 -v -0.076111 -0.018450 0.199854 -vn 0.139631 0.500090 -0.854642 -v -0.076358 -0.018450 0.199790 -vn 0.447770 0.873257 0.192158 -v -0.075355 -0.018487 0.201552 -vn 0.399929 0.873253 -0.278362 -v -0.075482 -0.018487 0.200296 -vn 0.399960 0.873237 0.278369 -v -0.075482 -0.018487 0.201782 -vn 0.335691 0.873266 0.353154 -v -0.075654 -0.018487 0.201981 -vn 0.257740 0.873258 0.413509 -v -0.075862 -0.018487 0.202142 -vn 0.169219 0.873260 0.456927 -v -0.076098 -0.018487 0.202258 -vn 0.073783 0.873249 0.481657 -v -0.076353 -0.018487 0.202324 -vn -0.024678 0.873234 0.486676 -v -0.076615 -0.018487 0.202337 -vn -0.122130 0.873254 0.471711 -v -0.076875 -0.018487 0.202298 -vn -0.214577 0.873268 0.437446 -v -0.077122 -0.018487 0.202206 -vn -0.298282 0.873235 0.385342 -v -0.077345 -0.018487 0.202067 -vn -0.369720 0.873256 0.317383 -v -0.077536 -0.018487 0.201886 -vn -0.426053 0.873243 0.236487 -v -0.077686 -0.018487 0.201670 -vn -0.464903 0.873263 0.145865 -v -0.077790 -0.018487 0.201428 -vn -0.484789 0.873241 0.049302 -v -0.077843 -0.018487 0.201171 -vn -0.484799 0.873236 -0.049291 -v -0.077843 -0.018487 0.200908 -vn -0.464920 0.873254 -0.145866 -v -0.077790 -0.018487 0.200650 -vn -0.426069 0.873235 -0.236486 -v -0.077686 -0.018487 0.200408 -vn -0.369714 0.873255 -0.317391 -v -0.077536 -0.018487 0.200192 -vn -0.298255 0.873256 -0.385316 -v -0.077345 -0.018487 0.200011 -vn -0.214602 0.873242 -0.437486 -v -0.077122 -0.018487 0.199872 -vn -0.122142 0.873239 -0.471736 -v -0.076875 -0.018487 0.199781 -vn -0.024682 0.873233 -0.486678 -v -0.076615 -0.018487 0.199741 -vn 0.073794 0.873231 -0.481687 -v -0.076353 -0.018487 0.199754 -vn 0.169246 0.873232 -0.456970 -v -0.076098 -0.018487 0.199820 -vn 0.257769 0.873233 -0.413544 -v -0.075862 -0.018487 0.199936 -vn 0.335736 0.873232 -0.353195 -v -0.075654 -0.018487 0.200097 -vn 0.477314 0.873240 -0.098099 -v -0.075276 -0.018487 0.200777 -vn 0.487284 0.873244 0.000002 -v -0.075249 -0.018487 0.201039 -vn 0.477326 0.873235 0.098089 -v -0.075276 -0.018487 0.201301 -vn 0.450631 0.501787 0.738337 -v -0.075881 -0.018450 0.202111 -vn -0.051136 0.502341 0.863156 -v -0.076613 -0.018450 0.202301 -vn -0.534213 0.502938 0.679463 -v -0.077323 -0.018450 0.202038 -vn -0.826023 0.503563 0.253201 -v -0.077755 -0.018450 0.201417 -vn -0.822559 0.504158 -0.263101 -v -0.077755 -0.018450 0.200661 -vn -0.525307 0.504863 -0.684957 -v -0.077323 -0.018450 0.200040 -vn -0.040784 0.505439 -0.861898 -v -0.076613 -0.018450 0.199777 -vn 0.457906 0.506038 -0.730922 -v -0.075881 -0.018450 0.199967 -vn 0.602461 0.500508 -0.621717 -v -0.075679 -0.018450 0.200123 -vn 0.849291 0.500998 -0.166450 -v -0.075312 -0.018450 0.200785 -vn 0.861732 0.507364 -0.000002 -v -0.075286 -0.018450 0.201039 -vn 0.849777 0.500652 0.165005 -v -0.075312 -0.018450 0.201293 -vn 0.792634 0.506709 -0.339082 -v -0.075388 -0.018450 0.200541 -vn 0.447793 0.873246 -0.192154 -v -0.075355 -0.018487 0.200526 -vn 0.707280 0.503412 -0.496319 -v -0.075513 -0.018450 0.200317 -vn 0.791708 0.501161 0.349337 -v -0.075388 -0.018450 0.201537 -vn 0.128263 -0.989929 -0.059913 -v -0.077050 -0.019100 0.201280 -vn -0.795920 -0.605401 0.000000 -v -0.075993 -0.019100 0.201039 -vn 0.795922 -0.605400 0.000000 -v -0.077105 -0.019100 0.201039 -vn 0.000002 -1.000000 -0.000001 -v -0.076549 -0.018919 0.201039 -vn 0.577350 -0.577350 -0.577350 -v -0.039549 -0.010000 0.195289 -vn 0.577350 -0.577350 0.577350 -v -0.039549 -0.010000 0.206789 -vn 0.301511 -0.904534 -0.301511 -v -0.041049 -0.010000 0.195289 -vn 0.301511 -0.904534 0.301511 -v -0.041049 -0.010000 0.206789 -vn 0.727973 -0.678874 0.095842 -v -0.041049 -0.010000 0.213039 -vn -1.000000 0.000000 -0.000004 -v -0.042549 -0.010000 0.211439 -vn 0.866025 0.000000 0.500001 -v -0.044415 -0.010000 0.210939 -vn -0.000000 -0.000002 -1.000000 -v -0.085549 -0.010000 0.211289 -vn 0.499997 -0.000004 0.866027 -v -0.044049 -0.010000 0.210573 -vn -0.500006 -0.000002 -0.866022 -v -0.085049 -0.010000 0.211155 -vn 0.000000 -0.000000 1.000000 -v -0.043549 -0.010000 0.210439 -vn 0.000000 -0.000000 1.000000 -v -0.085549 -0.010000 0.190789 -vn 1.000000 -0.000003 -0.000004 -v -0.044549 -0.010000 0.190639 -vn -0.499997 -0.000001 0.866027 -v -0.085049 -0.010000 0.190923 -vn -0.866023 0.000000 0.500004 -v -0.084683 -0.010000 0.191289 -vn -0.866023 0.000000 0.500004 -v -0.042683 -0.010000 0.210939 -vn -0.499997 0.000000 0.866027 -v -0.043049 -0.010000 0.210573 -vn -1.000000 0.000004 -0.000004 -v -0.084549 -0.010000 0.191789 -vn 0.866028 0.000000 -0.499995 -v -0.044415 -0.010000 0.191139 -vn 0.499993 0.000000 -0.866029 -v -0.044049 -0.010000 0.191505 -vn 0.727973 -0.678874 -0.095842 -v -0.041049 -0.010000 0.189039 -vn -0.866023 -0.000000 0.500004 -v -0.042683 -0.010000 0.190139 -vn 0.655721 -0.653228 -0.378579 -v -0.041183 -0.010000 0.188539 -vn -0.499997 0.000000 0.866027 -v -0.043049 -0.010000 0.189773 -vn 0.378586 -0.653226 -0.655720 -v -0.041549 -0.010000 0.188173 -vn 0.095840 -0.678874 -0.727973 -v -0.042049 -0.010000 0.188039 -vn 0.000000 0.000000 1.000000 -v -0.043549 -0.010000 0.189639 -vn 0.499997 0.000000 0.866027 -v -0.044049 -0.010000 0.189773 -vn -0.075740 0.003864 -0.997120 -v -0.083049 -0.010000 0.188039 -vn 0.866025 0.000000 0.500001 -v -0.044415 -0.010000 0.190139 -vn -0.809273 0.004460 -0.587416 -v -0.087095 -0.010000 0.190100 -vn 0.866023 0.000000 0.500004 -v -0.086415 -0.010000 0.191289 -vn -0.951434 0.001695 -0.307847 -v -0.087805 -0.010000 0.191494 -vn 1.000000 0.000000 -0.000004 -v -0.086549 -0.010000 0.191789 -vn -0.996917 -0.000000 -0.078458 -v -0.088049 -0.010000 0.193039 -vn 0.866026 -0.000000 -0.499998 -v -0.086415 -0.010000 0.192289 -vn -0.996970 0.000828 0.077786 -v -0.088049 -0.010000 0.209039 -vn 0.500006 -0.000000 -0.866022 -v -0.086049 -0.010000 0.192655 -vn -0.588053 0.005792 -0.808801 -v -0.085988 -0.010000 0.188994 -vn 0.499997 -0.000000 0.866027 -v -0.086049 -0.010000 0.190923 -vn -0.309343 0.006978 -0.950925 -v -0.084595 -0.010000 0.188284 -vn 0.378578 -0.653228 0.655722 -v -0.041549 -0.010000 0.213905 -vn 0.095841 -0.678874 0.727973 -v -0.042049 -0.010000 0.214039 -vn 0.655719 -0.653226 0.378587 -v -0.041183 -0.010000 0.213539 -vn -0.500006 -0.000000 -0.866022 -v -0.043049 -0.010000 0.212305 -vn -0.866026 0.000000 -0.499998 -v -0.042683 -0.010000 0.211939 -vn -0.866026 -0.000000 -0.499998 -v -0.084683 -0.010000 0.210789 -vn -1.000000 0.000000 -0.000004 -v -0.084549 -0.010000 0.210289 -vn -0.866023 -0.000000 0.500004 -v -0.084683 -0.010000 0.209789 -vn -0.500006 -0.000002 -0.866022 -v -0.085049 -0.010000 0.192655 -vn -0.499997 -0.000000 0.866027 -v -0.085049 -0.010000 0.209423 -vn -0.000000 -0.000000 -1.000000 -v -0.085549 -0.010000 0.192789 -vn 0.000000 -0.000000 1.000000 -v -0.085549 -0.010000 0.209289 -vn 0.499997 0.000000 0.866027 -v -0.086049 -0.010000 0.209423 -vn 0.866023 0.000000 0.500004 -v -0.086415 -0.010000 0.209789 -vn -0.951213 0.002423 0.308525 -v -0.087805 -0.010000 0.210584 -vn 1.000000 -0.000000 -0.000004 -v -0.086549 -0.010000 0.210289 -vn -0.809267 0.004299 0.587425 -v -0.087095 -0.010000 0.211978 -vn -0.000000 0.000000 -1.000000 -v -0.043549 -0.010000 0.191639 -vn -0.866026 -0.000000 -0.499998 -v -0.084683 -0.010000 0.192289 -vn -0.499994 -0.000001 -0.866029 -v -0.043049 -0.010000 0.191505 -vn -0.866026 0.000000 -0.499998 -v -0.042683 -0.010000 0.191139 -vn -1.000000 -0.000002 -0.000004 -v -0.042549 -0.010000 0.190639 -vn 1.000000 0.000003 -0.000004 -v -0.044549 -0.010000 0.211439 -vn 0.866028 -0.000000 -0.499995 -v -0.044415 -0.010000 0.211939 -vn -0.078223 0.001161 0.996935 -v -0.083049 -0.010000 0.214039 -vn 0.500006 0.000000 -0.866022 -v -0.044049 -0.010000 0.212305 -vn -0.000000 0.000000 -1.000000 -v -0.043549 -0.010000 0.212439 -vn 0.866026 0.000000 -0.499998 -v -0.086415 -0.010000 0.210789 -vn 0.500006 0.000000 -0.866022 -v -0.086049 -0.010000 0.211155 -vn -0.588048 0.005609 0.808806 -v -0.085988 -0.010000 0.213084 -vn -0.306859 0.003335 0.951749 -v -0.084595 -0.010000 0.213794 -vn 0.301511 0.904534 -0.301511 -v -0.041049 0.012000 0.195289 -vn 0.727973 0.678874 -0.095842 -v -0.041049 0.012000 0.189039 -vn -0.637727 0.770263 -0.000002 -v -0.042549 0.012000 0.190639 -vn 0.577350 0.577350 0.577350 -v -0.039549 0.012000 0.206789 -vn 0.577350 0.577350 -0.577350 -v -0.039549 0.012000 0.195289 -vn 0.301513 0.904533 0.301512 -v -0.041049 0.012000 0.206789 -vn -0.000000 0.770263 0.637727 -v -0.043549 0.012000 0.189639 -vn -0.318863 0.770260 0.552291 -v -0.043049 0.012000 0.189773 -vn 0.095840 0.678874 -0.727973 -v -0.042049 0.012000 0.188039 -vn -0.318867 0.770263 -0.552285 -v -0.043049 0.012000 0.212305 -vn 0.000000 0.770263 -0.637727 -v -0.043549 0.012000 0.212439 -vn 0.095840 0.678874 0.727973 -v -0.042049 0.012000 0.214039 -vn 0.318867 0.770263 -0.552285 -v -0.044049 0.012000 0.212305 -vn -0.076047 -0.003383 0.997099 -v -0.083049 0.012000 0.214039 -vn 0.552291 0.770261 -0.318862 -v -0.044415 0.012000 0.211939 -vn 0.637728 0.770262 -0.000002 -v -0.044549 0.012000 0.211439 -vn 0.637727 0.770262 -0.000002 -v -0.044549 0.012000 0.190639 -vn -0.552286 0.770263 0.318866 -v -0.084683 0.012000 0.191289 -vn -0.637727 0.770263 -0.000002 -v -0.084549 0.012000 0.191789 -vn -0.318857 0.770266 -0.552286 -v -0.043049 0.012000 0.191505 -vn 0.000000 0.770256 -0.637735 -v -0.043549 0.012000 0.191639 -vn -0.318863 0.770260 0.552291 -v -0.043049 0.012000 0.210573 -vn -0.552286 0.770263 0.318866 -v -0.042683 0.012000 0.210939 -vn 0.378586 0.653226 -0.655720 -v -0.041549 0.012000 0.188173 -vn 0.655721 0.653228 -0.378579 -v -0.041183 0.012000 0.188539 -vn -0.552286 0.770263 0.318866 -v -0.042683 0.012000 0.190139 -vn -0.552291 0.770260 -0.318864 -v -0.084683 0.012000 0.192289 -vn -0.318867 0.770263 -0.552285 -v -0.085049 0.012000 0.192655 -vn -0.552285 0.770263 0.318866 -v -0.084683 0.012000 0.209789 -vn -0.637727 0.770262 -0.000002 -v -0.084549 0.012000 0.210289 -vn -0.552291 0.770260 -0.318864 -v -0.084683 0.012000 0.210789 -vn 0.727973 0.678874 0.095842 -v -0.041049 0.012000 0.213039 -vn -0.637727 0.770263 -0.000002 -v -0.042549 0.012000 0.211439 -vn -0.552291 0.770260 -0.318864 -v -0.042683 0.012000 0.211939 -vn 0.655719 0.653226 0.378587 -v -0.041183 0.012000 0.213539 -vn 0.378578 0.653228 0.655722 -v -0.041549 0.012000 0.213905 -vn -0.808998 -0.006827 0.587772 -v -0.087095 0.012000 0.211978 -vn -0.587770 -0.006827 0.808999 -v -0.085988 0.012000 0.213084 -vn 0.000000 0.770263 -0.637727 -v -0.085549 0.012000 0.211289 -vn -0.309009 -0.006827 0.951035 -v -0.084595 0.012000 0.213794 -vn -0.318867 0.770263 -0.552285 -v -0.085049 0.012000 0.211155 -vn -0.997099 -0.003384 0.076045 -v -0.088049 0.012000 0.209039 -vn 0.318867 0.770263 -0.552286 -v -0.086049 0.012000 0.192655 -vn -0.997099 -0.003384 -0.076045 -v -0.088049 0.012000 0.193039 -vn 0.552291 0.770260 -0.318864 -v -0.086415 0.012000 0.192289 -vn -0.951035 -0.006827 -0.309009 -v -0.087805 0.012000 0.191494 -vn 0.637727 0.770263 -0.000002 -v -0.086549 0.012000 0.191789 -vn -0.808998 -0.006827 -0.587771 -v -0.087095 0.012000 0.190100 -vn -0.552291 0.770260 -0.318864 -v -0.042683 0.012000 0.191139 -vn -0.000000 0.770263 0.637727 -v -0.043549 0.012000 0.210439 -vn 0.318863 0.770260 0.552291 -v -0.044049 0.012000 0.210573 -vn 0.318858 0.770265 -0.552287 -v -0.044049 0.012000 0.191505 -vn 0.552286 0.770264 0.318863 -v -0.044415 0.012000 0.210939 -vn 0.552292 0.770260 -0.318862 -v -0.044415 0.012000 0.191139 -vn 0.318863 0.770260 0.552291 -v -0.044049 0.012000 0.189773 -vn -0.076047 -0.003384 -0.997099 -v -0.083049 0.012000 0.188039 -vn 0.552286 0.770264 0.318863 -v -0.044415 0.012000 0.190139 -vn -0.000000 0.770263 0.637727 -v -0.085549 0.012000 0.190789 -vn -0.318863 0.770260 0.552291 -v -0.085049 0.012000 0.190923 -vn 0.552285 0.770263 0.318866 -v -0.086415 0.012000 0.191289 -vn 0.318863 0.770260 0.552291 -v -0.086049 0.012000 0.190923 -vn -0.587773 -0.006827 -0.808997 -v -0.085988 0.012000 0.188994 -vn -0.309013 -0.006827 -0.951033 -v -0.084595 0.012000 0.188284 -vn 0.318867 0.770263 -0.552285 -v -0.086049 0.012000 0.211155 -vn 0.552291 0.770260 -0.318864 -v -0.086415 0.012000 0.210789 -vn -0.951035 -0.006827 0.309009 -v -0.087805 0.012000 0.210584 -vn 0.637727 0.770263 -0.000002 -v -0.086549 0.012000 0.210289 -vn 0.552285 0.770263 0.318866 -v -0.086415 0.012000 0.209789 -vn 0.318863 0.770260 0.552291 -v -0.086049 0.012000 0.209423 -vn 0.000000 0.770263 -0.637727 -v -0.085549 0.012000 0.192789 -vn -0.000000 0.770263 0.637727 -v -0.085549 0.012000 0.209289 -vn -0.318863 0.770260 0.552291 -v -0.085049 0.012000 0.209423 -vn 0.000000 -1.000000 0.000000 -v -0.039174 -0.015000 0.211789 -vn 0.382684 -0.923879 0.000000 -v -0.039049 -0.015000 0.211789 -vn 0.297109 -0.717283 0.630262 -v -0.039049 -0.015000 0.212289 -vn -0.003465 -0.995906 0.090327 -v -0.083049 -0.015000 0.212539 -vn -0.400397 -0.913025 0.077895 -v -0.083572 -0.015000 0.212500 -vn -0.406422 -0.913685 -0.000000 -v -0.083572 -0.015000 0.211789 -vn 0.173282 -0.774230 0.608722 -v -0.045522 -0.015000 0.211039 -vn 0.619596 -0.487327 0.615316 -v -0.045448 -0.015000 0.210993 -vn 0.336742 -0.940156 -0.052066 -v -0.045486 -0.015000 0.211669 -vn -0.637727 -0.770263 -0.000000 -v -0.044549 -0.015000 0.187539 -vn -0.552286 -0.770262 0.318867 -v -0.044717 -0.015000 0.186914 -vn 0.000000 -1.000000 0.000000 -v -0.043174 -0.015000 0.186164 -vn -0.707107 -0.707107 0.000000 -v -0.049049 -0.015000 0.186164 -vn 0.552286 -0.770263 0.318865 -v -0.046882 -0.015000 0.186914 -vn -0.131340 -0.973781 -0.185743 -v -0.049049 -0.015000 0.188039 -vn 0.637728 -0.770261 -0.000000 -v -0.047049 -0.015000 0.187539 -vn 0.552291 -0.770261 -0.318862 -v -0.046882 -0.015000 0.188164 -vn 0.318861 -0.770265 -0.552286 -v -0.046424 -0.015000 0.188622 -vn 0.229460 -0.539636 -0.810025 -v -0.045458 -0.015000 0.191039 -vn 0.000000 -0.770258 -0.637732 -v -0.045799 -0.015000 0.188789 -vn -0.318866 -0.770260 0.552291 -v -0.045174 -0.015000 0.186457 -vn 0.000000 -0.770264 0.637725 -v -0.045799 -0.015000 0.186289 -vn 0.318866 -0.770260 0.552291 -v -0.046424 -0.015000 0.186457 -vn -0.085437 -0.942584 0.322855 -v -0.043158 -0.015000 0.188729 -vn 0.003454 -0.934101 0.356992 -v -0.043442 -0.015000 0.188692 -vn -0.552291 -0.770260 -0.318864 -v -0.044717 -0.015000 0.188164 -vn 0.147417 -0.940629 0.305755 -v -0.044420 -0.015000 0.188894 -vn -0.318861 -0.770265 -0.552286 -v -0.045174 -0.015000 0.188622 -vn 0.279989 -0.940309 0.193455 -v -0.045169 -0.015000 0.189554 -vn 0.340989 -0.939227 0.039746 -v -0.045494 -0.015000 0.190498 -vn 0.707107 -0.707107 0.000000 -v -0.042549 -0.015000 0.186164 -vn 0.131340 -0.973781 -0.185743 -v -0.042549 -0.015000 0.188039 -vn -0.197237 -0.939245 0.280921 -v -0.042493 -0.015000 0.189000 -vn 0.408248 -0.816496 -0.408249 -v -0.041049 -0.015000 0.188039 -vn -0.299943 -0.941721 0.152300 -v -0.041820 -0.015000 0.189738 -vn 0.185742 -0.973781 -0.131340 -v -0.041049 -0.015000 0.189789 -vn -0.637727 -0.770263 -0.000000 -v -0.039299 -0.015000 0.193039 -vn -0.552292 -0.770260 0.318863 -v -0.039467 -0.015000 0.192414 -vn 0.000000 -0.707107 -0.707107 -v -0.039174 -0.015000 0.189789 -vn -0.318861 -0.770265 0.552285 -v -0.039924 -0.015000 0.191957 -vn 0.000000 -0.770258 0.637732 -v -0.040549 -0.015000 0.191789 -vn 0.318862 -0.770265 0.552285 -v -0.041174 -0.015000 0.191957 -vn 0.552292 -0.770260 0.318863 -v -0.041632 -0.015000 0.192414 -vn 0.637727 -0.770263 0.000000 -v -0.041799 -0.015000 0.193039 -vn -0.156016 -0.945218 -0.286744 -v -0.042618 -0.015000 0.192352 -vn -0.015344 -0.939543 -0.342087 -v -0.043587 -0.015000 0.192589 -vn 0.552287 -0.770262 -0.318866 -v -0.041632 -0.015000 0.193664 -vn 0.318866 -0.770260 -0.552289 -v -0.041174 -0.015000 0.194122 -vn 0.185742 -0.973781 0.131340 -v -0.041049 -0.015000 0.196289 -vn 0.000000 -0.770264 -0.637725 -v -0.040549 -0.015000 0.194289 -vn 0.000000 -0.707107 0.707107 -v -0.039174 -0.015000 0.196289 -vn -0.318866 -0.770260 -0.552289 -v -0.039924 -0.015000 0.194122 -vn -0.552287 -0.770262 -0.318866 -v -0.039467 -0.015000 0.193664 -vn -0.280568 -0.943020 -0.178871 -v -0.041892 -0.015000 0.191666 -vn -0.334873 -0.942133 -0.015659 -v -0.041601 -0.015000 0.190712 -vn 0.818476 -0.525303 -0.232710 -v -0.044049 -0.015000 0.192524 -vn 0.707107 -0.707107 0.000000 -v -0.044049 -0.015000 0.201039 -vn 0.000000 -1.000000 0.000000 -v -0.043174 -0.015000 0.201039 -vn 0.622386 -0.766706 0.157473 -v -0.044049 -0.015000 0.209465 -vn -0.035310 -0.938469 0.343553 -v -0.043434 -0.015000 0.209493 -vn 0.661095 -0.465170 0.588702 -v -0.044107 -0.015000 0.209570 -vn 0.382683 -0.923880 0.000000 -v -0.041049 -0.015000 0.201039 -vn 0.185742 -0.973781 -0.131340 -v -0.041049 -0.015000 0.205789 -vn 0.000000 -0.770264 -0.637725 -v -0.040549 -0.015000 0.210289 -vn -0.318866 -0.770260 -0.552289 -v -0.039924 -0.015000 0.210122 -vn -0.552287 -0.770262 -0.318866 -v -0.039467 -0.015000 0.209664 -vn 0.000000 -0.770258 0.637732 -v -0.040549 -0.015000 0.207789 -vn -0.318861 -0.770265 0.552285 -v -0.039924 -0.015000 0.207957 -vn 0.000000 -0.707107 -0.707107 -v -0.039174 -0.015000 0.205789 -vn -0.552292 -0.770260 0.318863 -v -0.039467 -0.015000 0.208414 -vn -0.637727 -0.770263 -0.000000 -v -0.039299 -0.015000 0.209039 -vn 0.630263 -0.717284 0.297108 -v -0.042549 -0.015000 0.216039 -vn 0.000000 -0.923880 0.382683 -v -0.043174 -0.015000 0.216039 -vn 0.131340 -0.973781 0.185743 -v -0.042549 -0.015000 0.214039 -vn -0.094214 -0.949432 -0.299504 -v -0.043159 -0.015000 0.213350 -vn 0.408248 -0.816496 0.408249 -v -0.041049 -0.015000 0.214039 -vn -0.183411 -0.942336 -0.279933 -v -0.042509 -0.015000 0.213088 -vn -0.289295 -0.940882 -0.176208 -v -0.041842 -0.015000 0.212381 -vn 0.185743 -0.973781 0.131340 -v -0.041049 -0.015000 0.212289 -vn -0.316745 -0.945657 -0.073530 -v -0.041634 -0.015000 0.211803 -vn 0.000000 -0.707107 0.707107 -v -0.039174 -0.015000 0.212289 -vn 0.552291 -0.770261 -0.318862 -v -0.046882 -0.015000 0.215164 -vn -0.630262 -0.717284 0.297108 -v -0.049049 -0.015000 0.216039 -vn 0.637728 -0.770261 -0.000000 -v -0.047049 -0.015000 0.214539 -vn -0.131340 -0.973781 0.185743 -v -0.049049 -0.015000 0.214039 -vn 0.552286 -0.770263 0.318865 -v -0.046882 -0.015000 0.213914 -vn 0.318866 -0.770260 0.552291 -v -0.046424 -0.015000 0.213457 -vn 0.318861 -0.770265 -0.552286 -v -0.046424 -0.015000 0.215622 -vn 0.000000 -0.770258 -0.637732 -v -0.045799 -0.015000 0.215789 -vn 0.000000 -0.770264 0.637725 -v -0.045799 -0.015000 0.213289 -vn -0.318866 -0.770260 0.552291 -v -0.045174 -0.015000 0.213457 -vn 0.270860 -0.940956 -0.203069 -v -0.045134 -0.015000 0.212576 -vn -0.552286 -0.770262 0.318867 -v -0.044717 -0.015000 0.213914 -vn -0.318861 -0.770265 -0.552286 -v -0.045174 -0.015000 0.215622 -vn -0.552291 -0.770260 -0.318863 -v -0.044717 -0.015000 0.215164 -vn -0.637727 -0.770263 -0.000000 -v -0.044549 -0.015000 0.214539 -vn 0.003697 -0.934277 -0.356529 -v -0.043434 -0.015000 0.213386 -vn 0.139683 -0.941338 -0.307200 -v -0.044388 -0.015000 0.213199 -vn 0.000000 -0.707107 0.707107 -v -0.049799 -0.015000 0.211039 -vn 0.000000 -1.000000 0.000000 -v -0.049799 -0.015000 0.211789 -vn 0.000000 -0.707107 0.707107 -v -0.057799 -0.015000 0.211039 -vn 0.000000 -1.000000 -0.000000 -v -0.057799 -0.015000 0.211789 -vn 0.000000 -0.707107 0.707107 -v -0.065799 -0.015000 0.211039 -vn 0.000000 -1.000000 0.000000 -v -0.065799 -0.015000 0.211789 -vn -0.237790 -0.534581 0.810974 -v -0.083572 -0.015000 0.211039 -vn -0.040621 -0.997107 0.064244 -v -0.074549 -0.015000 0.212539 -vn 0.131340 -0.973781 0.185743 -v -0.066549 -0.015000 0.214039 -vn -0.552286 -0.770263 0.318865 -v -0.068717 -0.015000 0.213914 -vn -0.318866 -0.770260 0.552291 -v -0.069174 -0.015000 0.213457 -vn 0.000000 -0.770264 0.637725 -v -0.069799 -0.015000 0.213289 -vn -0.630262 -0.717283 0.297109 -v -0.074549 -0.015000 0.214039 -vn -0.131340 -0.973781 0.185743 -v -0.073049 -0.015000 0.214039 -vn 0.318865 -0.770260 0.552291 -v -0.070424 -0.015000 0.213457 -vn 0.630263 -0.717284 0.297108 -v -0.066549 -0.015000 0.216039 -vn -0.552291 -0.770261 -0.318862 -v -0.068717 -0.015000 0.215164 -vn -0.637728 -0.770261 0.000000 -v -0.068549 -0.015000 0.214539 -vn 0.552286 -0.770263 0.318865 -v -0.070882 -0.015000 0.213914 -vn 0.637728 -0.770261 -0.000000 -v -0.071049 -0.015000 0.214539 -vn -0.630262 -0.717284 0.297108 -v -0.073049 -0.015000 0.216039 -vn 0.552291 -0.770261 -0.318862 -v -0.070882 -0.015000 0.215164 -vn 0.318861 -0.770265 -0.552286 -v -0.070424 -0.015000 0.215622 -vn 0.000000 -0.770258 -0.637732 -v -0.069799 -0.015000 0.215789 -vn -0.318861 -0.770265 -0.552286 -v -0.069174 -0.015000 0.215622 -vn 0.131340 -0.973781 0.185743 -v -0.058549 -0.015000 0.214039 -vn 0.630262 -0.717284 0.297108 -v -0.058549 -0.015000 0.216039 -vn -0.552291 -0.770261 -0.318862 -v -0.060717 -0.015000 0.215164 -vn -0.637728 -0.770261 0.000000 -v -0.060549 -0.015000 0.214539 -vn -0.552286 -0.770263 0.318865 -v -0.060717 -0.015000 0.213914 -vn -0.318866 -0.770260 0.552291 -v -0.061174 -0.015000 0.213457 -vn 0.000000 -0.770264 0.637725 -v -0.061799 -0.015000 0.213289 -vn 0.318866 -0.770260 0.552289 -v -0.062424 -0.015000 0.213457 -vn -0.131340 -0.973781 0.185743 -v -0.065049 -0.015000 0.214039 -vn 0.000000 -0.923879 0.382684 -v -0.065799 -0.015000 0.214039 -vn 0.552287 -0.770263 0.318864 -v -0.062882 -0.015000 0.213914 -vn 0.637728 -0.770261 -0.000000 -v -0.063049 -0.015000 0.214539 -vn -0.630262 -0.717284 0.297108 -v -0.065049 -0.015000 0.216039 -vn 0.552292 -0.770261 -0.318861 -v -0.062882 -0.015000 0.215164 -vn 0.318862 -0.770265 -0.552285 -v -0.062424 -0.015000 0.215622 -vn 0.000000 -0.770258 -0.637732 -v -0.061799 -0.015000 0.215789 -vn -0.318861 -0.770265 -0.552286 -v -0.061174 -0.015000 0.215622 -vn 0.131340 -0.973781 0.185743 -v -0.050549 -0.015000 0.214039 -vn 0.630263 -0.717284 0.297108 -v -0.050549 -0.015000 0.216039 -vn -0.552292 -0.770260 -0.318863 -v -0.052717 -0.015000 0.215164 -vn 0.552291 -0.770261 -0.318862 -v -0.054882 -0.015000 0.215164 -vn -0.630262 -0.717284 0.297108 -v -0.057049 -0.015000 0.216039 -vn 0.637728 -0.770261 -0.000000 -v -0.055049 -0.015000 0.214539 -vn -0.131340 -0.973781 0.185743 -v -0.057049 -0.015000 0.214039 -vn 0.552286 -0.770263 0.318865 -v -0.054882 -0.015000 0.213914 -vn 0.318865 -0.770260 0.552290 -v -0.054424 -0.015000 0.213457 -vn 0.000000 -0.923879 0.382684 -v -0.049799 -0.015000 0.214039 -vn -0.637727 -0.770263 -0.000000 -v -0.052549 -0.015000 0.214539 -vn -0.552287 -0.770262 0.318866 -v -0.052717 -0.015000 0.213914 -vn -0.318865 -0.770260 0.552290 -v -0.053174 -0.015000 0.213457 -vn 0.000000 -0.770265 0.637724 -v -0.053799 -0.015000 0.213289 -vn 0.000000 -0.923879 0.382684 -v -0.057799 -0.015000 0.214039 -vn 0.318861 -0.770265 -0.552286 -v -0.054424 -0.015000 0.215622 -vn 0.000001 -0.770259 -0.637731 -v -0.053799 -0.015000 0.215789 -vn -0.318861 -0.770264 -0.552287 -v -0.053174 -0.015000 0.215622 -vn 0.318862 -0.770265 0.552285 -v -0.041174 -0.015000 0.207957 -vn 0.552292 -0.770260 0.318863 -v -0.041632 -0.015000 0.208414 -vn 0.637727 -0.770263 0.000000 -v -0.041799 -0.015000 0.209039 -vn -0.183375 -0.942081 0.280814 -v -0.042509 -0.015000 0.209790 -vn 0.552287 -0.770262 -0.318866 -v -0.041632 -0.015000 0.209664 -vn -0.287243 -0.944677 0.158356 -v -0.041842 -0.015000 0.210498 -vn 0.318866 -0.770260 -0.552289 -v -0.041174 -0.015000 0.210122 -vn -0.345270 -0.938159 0.025409 -v -0.041599 -0.015000 0.211439 -vn 0.297109 -0.717284 -0.630262 -v -0.039049 -0.015000 0.205789 -vn 0.297109 -0.717284 -0.630262 -v -0.039049 -0.015000 0.189789 -vn 0.297109 -0.717284 0.630262 -v -0.039049 -0.015000 0.196289 -vn 0.630263 -0.717284 -0.297108 -v -0.042549 -0.015000 0.186039 -vn 0.000000 -0.923880 -0.382683 -v -0.043174 -0.015000 0.186039 -vn -0.630262 -0.717284 -0.297108 -v -0.049049 -0.015000 0.186039 -vn -0.552292 -0.770260 -0.318863 -v -0.052717 -0.015000 0.188164 -vn -0.637727 -0.770263 -0.000000 -v -0.052549 -0.015000 0.187539 -vn 0.000000 -0.707107 -0.707107 -v -0.049799 -0.015000 0.191039 -vn 0.707107 -0.707106 0.000000 -v -0.050549 -0.015000 0.186164 -vn -0.318865 -0.770259 0.552291 -v -0.053174 -0.015000 0.186457 -vn 0.000001 -0.770265 0.637724 -v -0.053799 -0.015000 0.186289 -vn -0.131340 -0.973781 -0.185743 -v -0.057049 -0.015000 0.188039 -vn -0.707107 -0.707107 -0.000000 -v -0.057049 -0.015000 0.186164 -vn 0.318866 -0.770260 0.552291 -v -0.054424 -0.015000 0.186457 -vn 0.552291 -0.770261 -0.318862 -v -0.054882 -0.015000 0.188164 -vn 0.000000 -0.707107 -0.707107 -v -0.057799 -0.015000 0.191039 -vn 0.637728 -0.770261 -0.000000 -v -0.055049 -0.015000 0.187539 -vn 0.552286 -0.770263 0.318865 -v -0.054882 -0.015000 0.186914 -vn 0.000000 -0.923879 -0.382684 -v -0.049799 -0.015000 0.188039 -vn 0.131340 -0.973781 -0.185743 -v -0.050549 -0.015000 0.188039 -vn -0.552287 -0.770262 0.318866 -v -0.052717 -0.015000 0.186914 -vn 0.318861 -0.770265 -0.552286 -v -0.054424 -0.015000 0.188622 -vn 0.000001 -0.770258 -0.637732 -v -0.053799 -0.015000 0.188789 -vn -0.318861 -0.770265 -0.552286 -v -0.053174 -0.015000 0.188622 -vn -0.630263 -0.717283 -0.297108 -v -0.057049 -0.015000 0.186039 -vn 0.630263 -0.717284 -0.297108 -v -0.050549 -0.015000 0.186039 -vn -0.552291 -0.770261 -0.318862 -v -0.060717 -0.015000 0.188164 -vn -0.637728 -0.770261 0.000000 -v -0.060549 -0.015000 0.187539 -vn -0.552286 -0.770263 0.318865 -v -0.060717 -0.015000 0.186914 -vn -0.318866 -0.770260 0.552291 -v -0.061174 -0.015000 0.186457 -vn 0.707107 -0.707106 0.000000 -v -0.058549 -0.015000 0.186164 -vn 0.000000 -0.770264 0.637725 -v -0.061799 -0.015000 0.186289 -vn -0.131340 -0.973781 -0.185743 -v -0.065049 -0.015000 0.188039 -vn -0.707107 -0.707107 0.000000 -v -0.065049 -0.015000 0.186164 -vn 0.318866 -0.770260 0.552291 -v -0.062424 -0.015000 0.186457 -vn 0.131340 -0.973781 -0.185743 -v -0.058549 -0.015000 0.188039 -vn 0.000000 -0.923879 -0.382684 -v -0.057799 -0.015000 0.188039 -vn 0.552286 -0.770263 0.318865 -v -0.062882 -0.015000 0.186914 -vn 0.637728 -0.770261 -0.000000 -v -0.063049 -0.015000 0.187539 -vn 0.000000 -0.707107 -0.707107 -v -0.065799 -0.015000 0.191039 -vn 0.552291 -0.770261 -0.318862 -v -0.062882 -0.015000 0.188164 -vn 0.318861 -0.770265 -0.552286 -v -0.062424 -0.015000 0.188622 -vn 0.000000 -0.770258 -0.637732 -v -0.061799 -0.015000 0.188789 -vn -0.318861 -0.770265 -0.552286 -v -0.061174 -0.015000 0.188622 -vn -0.630263 -0.717283 -0.297108 -v -0.065049 -0.015000 0.186039 -vn 0.630263 -0.717284 -0.297108 -v -0.058549 -0.015000 0.186039 -vn -0.552291 -0.770261 -0.318862 -v -0.068717 -0.015000 0.188164 -vn -0.637728 -0.770261 0.000000 -v -0.068549 -0.015000 0.187539 -vn -0.040620 -0.997107 -0.064243 -v -0.074549 -0.015000 0.189539 -vn -0.630262 -0.717283 -0.297109 -v -0.074549 -0.015000 0.188039 -vn -0.131340 -0.973781 -0.185743 -v -0.073049 -0.015000 0.188039 -vn -0.379338 -0.925069 -0.018714 -v -0.083599 -0.015000 0.189583 -vn 0.004468 -0.996376 -0.084936 -v -0.083049 -0.015000 0.189539 -vn -0.227460 -0.549130 -0.804188 -v -0.083599 -0.015000 0.191039 -vn 0.318865 -0.770260 0.552291 -v -0.070424 -0.015000 0.186457 -vn 0.552286 -0.770263 0.318865 -v -0.070882 -0.015000 0.186914 -vn 0.637728 -0.770261 -0.000000 -v -0.071049 -0.015000 0.187539 -vn 0.552291 -0.770261 -0.318862 -v -0.070882 -0.015000 0.188164 -vn -0.552286 -0.770263 0.318865 -v -0.068717 -0.015000 0.186914 -vn -0.318866 -0.770260 0.552291 -v -0.069174 -0.015000 0.186457 -vn 0.707107 -0.707106 0.000000 -v -0.066549 -0.015000 0.186164 -vn 0.000000 -0.770264 0.637725 -v -0.069799 -0.015000 0.186289 -vn -0.707107 -0.707107 0.000000 -v -0.073049 -0.015000 0.186164 -vn 0.318861 -0.770265 -0.552286 -v -0.070424 -0.015000 0.188622 -vn 0.000000 -0.770258 -0.637732 -v -0.069799 -0.015000 0.188789 -vn -0.318861 -0.770265 -0.552286 -v -0.069174 -0.015000 0.188622 -vn 0.131340 -0.973781 -0.185743 -v -0.066549 -0.015000 0.188039 -vn 0.000000 -0.923879 -0.382684 -v -0.065799 -0.015000 0.188039 -vn -0.630263 -0.717283 -0.297108 -v -0.073049 -0.015000 0.186039 -vn 0.630263 -0.717284 -0.297108 -v -0.066549 -0.015000 0.186039 -vn 0.726616 -0.511497 -0.458695 -v -0.045453 -0.014995 0.191039 -vn 0.331542 -0.328056 -0.884567 -v -0.045453 -0.017800 0.191039 -vn -0.717284 -0.297105 -0.630263 -v -0.083799 -0.015050 0.191039 -vn -0.973782 -0.185741 -0.131338 -v -0.083799 -0.014800 0.191039 -vn -0.297112 -0.717282 -0.630262 -v -0.083599 -0.015250 0.191039 -vn -0.185746 -0.131343 -0.973780 -v -0.067599 -0.015250 0.191039 -vn -0.341593 -0.341588 -0.875575 -v -0.067599 -0.017800 0.191039 -vn 0.886087 -0.325843 -0.329660 -v -0.044049 -0.017800 0.192516 -vn 0.485099 -0.523648 -0.700337 -v -0.044049 -0.014993 0.192516 -vn 0.921916 -0.333465 0.197161 -v -0.044049 -0.017800 0.209465 -vn 0.253759 -0.939708 0.229248 -v -0.044965 -0.018000 0.210098 -vn 0.276501 -0.849418 0.449485 -v -0.045405 -0.018000 0.210839 -vn -0.341588 -0.875574 0.341597 -v -0.067599 -0.018000 0.210839 -vn -0.319830 -0.932049 -0.170271 -v -0.066454 -0.018000 0.206441 -vn -0.346274 -0.932223 -0.105139 -v -0.065593 -0.018000 0.204366 -vn 0.242889 -0.938929 -0.243756 -v -0.044965 -0.018000 0.191980 -vn -0.360144 -0.932221 -0.035503 -v -0.065155 -0.018000 0.202162 -vn -0.360144 -0.932221 0.035503 -v -0.065155 -0.018000 0.199916 -vn 0.296910 -0.848128 -0.438775 -v -0.045405 -0.018000 0.191239 -vn 0.453563 -0.842678 -0.290128 -v -0.044249 -0.018000 0.192459 -vn 0.463098 -0.844522 0.268928 -v -0.044249 -0.018000 0.209619 -vn -0.408565 -0.904940 -0.118991 -v -0.067599 -0.018000 0.208181 -vn -0.408629 -0.904812 0.119740 -v -0.067599 -0.018000 0.193898 -vn -0.341590 -0.875579 -0.341582 -v -0.067599 -0.018000 0.191239 -vn -0.320350 -0.931922 0.169993 -v -0.066454 -0.018000 0.195637 -vn -0.346279 -0.932221 0.105140 -v -0.065593 -0.018000 0.197713 -vn -0.987815 -0.110047 -0.110048 -v -0.088049 -0.013300 0.193739 -vn -0.924496 -0.375118 -0.067779 -v -0.088049 -0.013300 0.193039 -vn -0.924213 -0.375928 0.067148 -v -0.088049 -0.013300 0.209039 -vn -0.987815 -0.110047 0.110048 -v -0.088049 -0.013300 0.208339 -vn -0.921352 -0.118633 0.370185 -v -0.088049 -0.013750 0.208339 -vn -0.921352 -0.118634 -0.370186 -v -0.088049 -0.013750 0.193739 -vn -0.549138 -0.804184 -0.227454 -v -0.067799 -0.015250 0.191239 -vn -0.353787 -0.934289 -0.044033 -v -0.083599 -0.015250 0.191789 -vn 0.658078 -0.735271 0.162202 -v -0.085385 -0.015250 0.198861 -vn 0.677774 -0.735271 -0.000000 -v -0.085649 -0.015250 0.201039 -vn -0.044031 -0.934292 -0.353780 -v -0.085549 -0.015250 0.193739 -vn -0.602022 -0.777812 -0.180496 -v -0.067799 -0.015250 0.208110 -vn -0.507319 -0.735272 -0.449447 -v -0.069738 -0.015250 0.207074 -vn -0.644140 -0.685653 -0.339063 -v -0.066599 -0.015250 0.206289 -vn -0.600139 -0.735270 -0.314977 -v -0.068492 -0.015250 0.205268 -vn -0.697356 -0.685529 -0.209153 -v -0.065773 -0.015250 0.204270 -vn -0.658078 -0.735271 -0.162202 -v -0.067714 -0.015250 0.203217 -vn -0.724414 -0.685729 -0.070713 -v -0.065352 -0.015250 0.202130 -vn -0.677774 -0.735271 0.000000 -v -0.067449 -0.015250 0.201039 -vn -0.724270 -0.685922 0.070313 -v -0.065352 -0.015250 0.199949 -vn -0.696941 -0.686108 0.208637 -v -0.065773 -0.015250 0.197808 -vn 0.658078 -0.735271 -0.162202 -v -0.085385 -0.015250 0.203217 -vn 0.600139 -0.735270 -0.314977 -v -0.084607 -0.015250 0.205268 -vn -0.162894 -0.945444 0.282136 -v -0.084574 -0.015250 0.208600 -vn 0.507319 -0.735272 -0.449447 -v -0.083361 -0.015250 0.207074 -vn -0.282137 -0.945445 0.162889 -v -0.083861 -0.015250 0.209314 -vn 0.385018 -0.735270 -0.557798 -v -0.081719 -0.015250 0.208528 -vn -0.353788 -0.934289 0.044032 -v -0.083599 -0.015250 0.210289 -vn 0.240343 -0.735270 -0.633729 -v -0.079776 -0.015250 0.209548 -vn 0.081698 -0.735272 -0.672831 -v -0.077646 -0.015250 0.210073 -vn -0.549128 -0.804189 0.227462 -v -0.067799 -0.015250 0.210839 -vn -0.297112 -0.717282 0.630262 -v -0.083599 -0.015250 0.211039 -vn -0.185739 -0.131336 0.973782 -v -0.067599 -0.015250 0.211039 -vn -0.081698 -0.735272 -0.672830 -v -0.075453 -0.015250 0.210073 -vn -0.240343 -0.735270 -0.633730 -v -0.073323 -0.015250 0.209548 -vn -0.385018 -0.735270 -0.557798 -v -0.071380 -0.015250 0.208528 -vn -0.044032 -0.934292 0.353779 -v -0.085549 -0.015250 0.208339 -vn -0.118636 -0.921350 0.370189 -v -0.086549 -0.015250 0.208339 -vn -0.118636 -0.921350 -0.370189 -v -0.086549 -0.015250 0.193739 -vn 0.081696 -0.735271 0.672832 -v -0.077646 -0.015250 0.192005 -vn 0.240341 -0.735271 0.633729 -v -0.079776 -0.015250 0.192530 -vn -0.282129 -0.945448 -0.162888 -v -0.083861 -0.015250 0.192764 -vn 0.385019 -0.735271 0.557797 -v -0.081719 -0.015250 0.193550 -vn -0.162884 -0.945449 -0.282124 -v -0.084574 -0.015250 0.193478 -vn 0.507321 -0.735271 0.449446 -v -0.083361 -0.015250 0.195005 -vn 0.600139 -0.735270 0.314977 -v -0.084607 -0.015250 0.196810 -vn -0.658078 -0.735271 0.162202 -v -0.067714 -0.015250 0.198861 -vn -0.601629 -0.778045 0.180798 -v -0.067799 -0.015250 0.193968 -vn -0.643461 -0.686288 0.339068 -v -0.066599 -0.015250 0.195789 -vn -0.600139 -0.735270 0.314977 -v -0.068492 -0.015250 0.196810 -vn -0.507321 -0.735271 0.449446 -v -0.069738 -0.015250 0.195005 -vn -0.385019 -0.735271 0.557797 -v -0.071380 -0.015250 0.193550 -vn -0.240341 -0.735271 0.633730 -v -0.073323 -0.015250 0.192530 -vn -0.081696 -0.735271 0.672832 -v -0.075453 -0.015250 0.192005 -vn -0.889762 -0.370450 -0.266627 -v -0.087836 -0.013300 0.191595 -vn -0.802098 -0.375407 -0.464445 -v -0.087216 -0.013300 0.190274 -vn -0.711810 -0.392620 -0.582389 -v -0.087095 -0.013300 0.190100 -vn -0.623805 -0.375024 -0.685729 -v -0.086240 -0.013300 0.189189 -vn -0.503030 -0.400470 -0.765888 -v -0.085988 -0.013300 0.188994 -vn -0.390456 -0.374930 -0.840816 -v -0.084992 -0.013300 0.188432 -vn -0.258902 -0.397509 -0.880316 -v -0.084595 -0.013300 0.188284 -vn -0.028561 -0.088068 -0.995705 -v -0.083049 -0.013500 0.188039 -vn -0.426414 -0.081116 -0.900884 -v -0.083622 -0.013500 0.188072 -vn -0.226909 -0.089207 -0.969822 -v -0.083622 -0.013300 0.188072 -vn 0.301511 0.301511 -0.904534 -v -0.071799 -0.013000 0.185039 -vn 0.318866 0.770260 0.552291 -v -0.070424 -0.013000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.069799 -0.013000 0.186289 -vn 0.000001 0.609995 -0.792405 -v -0.069799 -0.013000 0.189849 -vn 0.000000 0.770258 -0.637732 -v -0.069799 -0.013000 0.188789 -vn 0.318861 0.770265 -0.552286 -v -0.070424 -0.013000 0.188622 -vn -0.301511 0.301511 -0.904534 -v -0.067799 -0.013000 0.185039 -vn -0.318866 0.770260 0.552291 -v -0.069174 -0.013000 0.186457 -vn -0.552286 0.770263 0.318865 -v -0.068717 -0.013000 0.186914 -vn -0.686243 0.609994 -0.396205 -v -0.067799 -0.013000 0.188694 -vn 0.686243 0.609994 -0.396204 -v -0.071799 -0.013000 0.188694 -vn 0.552291 0.770261 -0.318862 -v -0.070882 -0.013000 0.188164 -vn 0.637728 0.770261 0.000000 -v -0.071049 -0.013000 0.187539 -vn 0.552286 0.770263 0.318865 -v -0.070882 -0.013000 0.186914 -vn -0.637728 0.770261 -0.000000 -v -0.068549 -0.013000 0.187539 -vn -0.552291 0.770261 -0.318862 -v -0.068717 -0.013000 0.188164 -vn -0.318861 0.770265 -0.552286 -v -0.069174 -0.013000 0.188622 -vn -0.686243 0.609994 -0.396204 -v -0.059799 -0.013000 0.188694 -vn -0.552291 0.770261 -0.318862 -v -0.060717 -0.013000 0.188164 -vn -0.000000 0.609995 -0.792405 -v -0.061799 -0.013000 0.189849 -vn -0.318861 0.770265 -0.552286 -v -0.061174 -0.013000 0.188622 -vn 0.686243 0.609994 -0.396205 -v -0.063799 -0.013000 0.188694 -vn 0.637728 0.770261 0.000000 -v -0.063049 -0.013000 0.187539 -vn 0.301511 0.301511 -0.904534 -v -0.063799 -0.013000 0.185039 -vn 0.552286 0.770263 0.318865 -v -0.062882 -0.013000 0.186914 -vn 0.318866 0.770260 0.552291 -v -0.062424 -0.013000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.061799 -0.013000 0.186289 -vn -0.301511 0.301511 -0.904534 -v -0.059799 -0.013000 0.185039 -vn -0.318866 0.770260 0.552291 -v -0.061174 -0.013000 0.186457 -vn -0.552286 0.770263 0.318865 -v -0.060717 -0.013000 0.186914 -vn -0.637729 0.770261 -0.000000 -v -0.060549 -0.013000 0.187539 -vn 0.000000 0.770258 -0.637732 -v -0.061799 -0.013000 0.188789 -vn 0.318861 0.770265 -0.552286 -v -0.062424 -0.013000 0.188622 -vn 0.552291 0.770261 -0.318862 -v -0.062882 -0.013000 0.188164 -vn 0.686243 0.609994 -0.396204 -v -0.055799 -0.013000 0.188694 -vn 0.637728 0.770261 0.000000 -v -0.055049 -0.013000 0.187539 -vn 0.301511 0.301511 -0.904534 -v -0.055799 -0.013000 0.185039 -vn 0.552286 0.770263 0.318865 -v -0.054882 -0.013000 0.186914 -vn -0.000000 0.609995 -0.792405 -v -0.053799 -0.013000 0.189849 -vn 0.318861 0.770265 -0.552286 -v -0.054424 -0.013000 0.188622 -vn 0.552291 0.770261 -0.318862 -v -0.054882 -0.013000 0.188164 -vn 0.318866 0.770260 0.552291 -v -0.054424 -0.013000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.053799 -0.013000 0.186289 -vn -0.301511 0.301511 -0.904534 -v -0.051799 -0.013000 0.185039 -vn -0.637727 0.770263 0.000000 -v -0.052549 -0.013000 0.187539 -vn -0.686243 0.609994 -0.396204 -v -0.051799 -0.013000 0.188694 -vn -0.552287 0.770262 0.318866 -v -0.052717 -0.013000 0.186914 -vn -0.318866 0.770261 0.552289 -v -0.053174 -0.013000 0.186457 -vn -0.552292 0.770260 -0.318863 -v -0.052717 -0.013000 0.188164 -vn -0.318861 0.770265 -0.552285 -v -0.053174 -0.013000 0.188622 -vn -0.000000 0.770258 -0.637732 -v -0.053799 -0.013000 0.188789 -vn 0.297109 0.717283 0.630262 -v -0.039049 -0.010000 0.212289 -vn 0.427644 0.741787 -0.516596 -v -0.039049 -0.010000 0.211039 -vn 0.301511 0.904534 0.301512 -v -0.039549 -0.010000 0.212289 -vn 0.452906 0.846478 -0.279911 -v -0.041049 -0.010000 0.210039 -vn 0.279911 0.846478 -0.452906 -v -0.070799 -0.010000 0.188039 -vn 0.516597 0.741787 -0.427644 -v -0.071799 -0.010000 0.186039 -vn -0.630263 0.717284 -0.297108 -v -0.073049 -0.010000 0.186039 -vn -0.630263 0.717284 0.297108 -v -0.073049 -0.010000 0.216039 -vn 0.516598 0.741787 0.427643 -v -0.071799 -0.010000 0.216039 -vn -0.301511 0.904534 0.301511 -v -0.073049 -0.010000 0.215539 -vn 0.279912 0.846479 0.452905 -v -0.070799 -0.010000 0.214039 -vn -0.630263 0.717284 0.297108 -v -0.065049 -0.010000 0.216039 -vn 0.516597 0.741787 0.427644 -v -0.063799 -0.010000 0.216039 -vn -0.301511 0.904534 0.301511 -v -0.065049 -0.010000 0.215539 -vn 0.279911 0.846478 0.452906 -v -0.062799 -0.010000 0.214039 -vn -0.630263 0.717284 0.297108 -v -0.057049 -0.010000 0.216039 -vn 0.516597 0.741787 0.427644 -v -0.055799 -0.010000 0.216039 -vn -0.301511 0.904534 0.301511 -v -0.057049 -0.010000 0.215539 -vn 0.279911 0.846478 0.452906 -v -0.054799 -0.010000 0.214039 -vn 0.301511 0.904534 0.301511 -v -0.058549 -0.010000 0.215539 -vn 0.301511 0.904534 0.301511 -v -0.042549 -0.010000 0.215539 -vn 0.577350 0.577350 0.577350 -v -0.041049 -0.010000 0.215539 -vn 0.301512 0.904534 0.301512 -v -0.041049 -0.010000 0.214039 -vn -0.516597 0.741787 0.427644 -v -0.067799 -0.010000 0.216039 -vn 0.630263 0.717284 0.297108 -v -0.066549 -0.010000 0.216039 -vn -0.279911 0.846478 0.452906 -v -0.068799 -0.010000 0.214039 -vn 0.301511 0.904534 0.301511 -v -0.066549 -0.010000 0.215539 -vn -0.279911 0.846478 0.452906 -v -0.060799 -0.010000 0.214039 -vn -0.516597 0.741787 0.427644 -v -0.059799 -0.010000 0.216039 -vn 0.630263 0.717284 0.297108 -v -0.058549 -0.010000 0.216039 -vn -0.301511 0.904534 0.301511 -v -0.074549 -0.010000 0.214039 -vn 0.516596 0.741788 -0.427644 -v -0.047799 -0.010000 0.186039 -vn -0.630263 0.717284 -0.297108 -v -0.049049 -0.010000 0.186039 -vn 0.279911 0.846478 -0.452907 -v -0.046799 -0.010000 0.188039 -vn -0.301511 0.904534 -0.301511 -v -0.049049 -0.010000 0.186539 -vn -0.516597 0.741787 0.427643 -v -0.051799 -0.010000 0.216039 -vn 0.630263 0.717284 0.297108 -v -0.050549 -0.010000 0.216039 -vn -0.279912 0.846479 0.452905 -v -0.052799 -0.010000 0.214039 -vn 0.301511 0.904534 0.301511 -v -0.050549 -0.010000 0.215539 -vn 0.279911 0.846478 0.452906 -v -0.046799 -0.010000 0.214039 -vn -0.279912 0.846479 0.452906 -v -0.044799 -0.010000 0.214039 -vn 0.630263 0.717284 -0.297108 -v -0.050549 -0.010000 0.186039 -vn -0.516597 0.741788 -0.427644 -v -0.051799 -0.010000 0.186039 -vn 0.301511 0.904534 -0.301511 -v -0.050549 -0.010000 0.186539 -vn -0.279912 0.846479 -0.452906 -v -0.052799 -0.010000 0.188039 -vn 0.516596 0.741788 -0.427644 -v -0.055799 -0.010000 0.186039 -vn -0.630263 0.717284 -0.297108 -v -0.057049 -0.010000 0.186039 -vn 0.279911 0.846478 -0.452907 -v -0.054799 -0.010000 0.188039 -vn -0.301511 0.904534 -0.301511 -v -0.057049 -0.010000 0.186539 -vn 0.630263 0.717284 -0.297108 -v -0.058549 -0.010000 0.186039 -vn -0.516596 0.741788 -0.427644 -v -0.059799 -0.010000 0.186039 -vn 0.301511 0.904534 -0.301511 -v -0.058549 -0.010000 0.186539 -vn -0.279911 0.846478 -0.452907 -v -0.060799 -0.010000 0.188039 -vn -0.577350 0.577350 0.577350 -v -0.074549 -0.010000 0.215539 -vn -0.630263 0.717284 0.297108 -v -0.049049 -0.010000 0.216039 -vn 0.516597 0.741787 0.427644 -v -0.047799 -0.010000 0.216039 -vn -0.301511 0.904534 0.301511 -v -0.049049 -0.010000 0.215539 -vn -0.516597 0.741787 0.427643 -v -0.043799 -0.010000 0.216039 -vn 0.630263 0.717284 0.297108 -v -0.042549 -0.010000 0.216039 -vn 0.630263 0.717284 -0.297108 -v -0.042549 -0.010000 0.186039 -vn -0.516597 0.741788 -0.427644 -v -0.043799 -0.010000 0.186039 -vn 0.301511 0.904534 -0.301511 -v -0.042549 -0.010000 0.186539 -vn -0.279911 0.846478 -0.452906 -v -0.044799 -0.010000 0.188039 -vn 0.516596 0.741788 -0.427644 -v -0.063799 -0.010000 0.186039 -vn -0.630263 0.717284 -0.297108 -v -0.065049 -0.010000 0.186039 -vn 0.279911 0.846478 -0.452907 -v -0.062799 -0.010000 0.188039 -vn -0.301511 0.904534 -0.301511 -v -0.065049 -0.010000 0.186539 -vn 0.301511 0.904534 -0.301511 -v -0.066549 -0.010000 0.186539 -vn -0.301511 0.904534 -0.301511 -v -0.073049 -0.010000 0.186539 -vn -0.577350 0.577350 -0.577350 -v -0.074549 -0.010000 0.186539 -vn -0.301511 0.904534 -0.301511 -v -0.074549 -0.010000 0.188039 -vn 0.452906 0.846478 -0.279911 -v -0.041049 -0.010000 0.194039 -vn 0.452906 0.846478 0.279911 -v -0.041049 -0.010000 0.192039 -vn 0.427644 0.741787 0.516597 -v -0.039049 -0.010000 0.207039 -vn 0.297109 0.717283 -0.630262 -v -0.039049 -0.010000 0.205789 -vn 0.452906 0.846478 0.279911 -v -0.041049 -0.010000 0.208039 -vn 0.301511 0.904534 -0.301511 -v -0.039549 -0.010000 0.205789 -vn 0.301511 0.904534 0.301511 -v -0.039549 -0.010000 0.196289 -vn 0.297109 0.717283 0.630262 -v -0.039049 -0.010000 0.196289 -vn 0.427644 0.741787 -0.516597 -v -0.039049 -0.010000 0.195039 -vn 0.577350 0.577350 0.577351 -v -0.039549 -0.010000 0.214039 -vn 0.427644 0.741787 0.516597 -v -0.039049 -0.010000 0.191039 -vn 0.297109 0.717283 -0.630262 -v -0.039049 -0.010000 0.189789 -vn 0.301511 0.904534 -0.301511 -v -0.039549 -0.010000 0.189789 -vn 0.577350 0.577350 -0.577350 -v -0.039549 -0.010000 0.188039 -vn 0.577350 0.577350 -0.577350 -v -0.041049 -0.010000 0.186539 -vn 0.301511 0.904534 -0.301511 -v -0.041049 -0.010000 0.188039 -vn -0.279911 0.846478 -0.452907 -v -0.068799 -0.010000 0.188039 -vn -0.516596 0.741788 -0.427644 -v -0.067799 -0.010000 0.186039 -vn 0.630263 0.717284 -0.297108 -v -0.066549 -0.010000 0.186039 -vn -0.990667 -0.075085 -0.113763 -v -0.067799 -0.011500 0.186039 -vn -0.686243 -0.609994 -0.396205 -v -0.067799 -0.011500 0.188694 -vn -0.279911 -0.846478 -0.452907 -v -0.068799 -0.011500 0.188039 -vn 0.000001 -0.609995 -0.792405 -v -0.069799 -0.011500 0.189849 -vn 0.279911 -0.846478 -0.452906 -v -0.070799 -0.011500 0.188039 -vn 0.686243 -0.609994 -0.396204 -v -0.071799 -0.011500 0.188694 -vn 0.990667 -0.075085 -0.113762 -v -0.071799 -0.011500 0.186039 -vn -0.990667 -0.075085 -0.113763 -v -0.059799 -0.011500 0.186039 -vn -0.686243 -0.609994 -0.396204 -v -0.059799 -0.011500 0.188694 -vn -0.279911 -0.846478 -0.452907 -v -0.060799 -0.011500 0.188039 -vn -0.000000 -0.609995 -0.792405 -v -0.061799 -0.011500 0.189849 -vn 0.279911 -0.846478 -0.452907 -v -0.062799 -0.011500 0.188039 -vn 0.686243 -0.609994 -0.396205 -v -0.063799 -0.011500 0.188694 -vn 0.990667 -0.075085 -0.113763 -v -0.063799 -0.011500 0.186039 -vn -0.990667 -0.075085 -0.113763 -v -0.051799 -0.011500 0.186039 -vn -0.686243 -0.609994 -0.396204 -v -0.051799 -0.011500 0.188694 -vn -0.279911 -0.846478 -0.452907 -v -0.052799 -0.011500 0.188039 -vn 0.000000 -0.609995 -0.792406 -v -0.053799 -0.011500 0.189849 -vn 0.279911 -0.846478 -0.452907 -v -0.054799 -0.011500 0.188039 -vn 0.686243 -0.609994 -0.396204 -v -0.055799 -0.011500 0.188694 -vn 0.990667 -0.075085 -0.113763 -v -0.055799 -0.011500 0.186039 -vn -0.630262 0.297109 -0.717283 -v -0.067799 -0.011000 0.185039 -vn 0.630262 0.297109 -0.717283 -v -0.066549 -0.011000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.066549 -0.014000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.073049 -0.014000 0.185039 -vn 0.630262 0.297109 -0.717283 -v -0.071799 -0.011000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.073049 -0.011000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.059799 -0.011000 0.185039 -vn 0.630262 0.297109 -0.717283 -v -0.058549 -0.011000 0.185039 -vn 0.630263 -0.297109 -0.717283 -v -0.058549 -0.014000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.065049 -0.014000 0.185039 -vn 0.630262 0.297109 -0.717283 -v -0.063799 -0.011000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.065049 -0.011000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.051799 -0.011000 0.185039 -vn 0.630262 0.297109 -0.717284 -v -0.050549 -0.011000 0.185039 -vn 0.630263 -0.297109 -0.717283 -v -0.050549 -0.014000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.057049 -0.014000 0.185039 -vn 0.630262 0.297109 -0.717283 -v -0.055799 -0.011000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.057049 -0.011000 0.185039 -vn 0.686243 0.609994 -0.396204 -v -0.047799 -0.013000 0.188694 -vn 0.637728 0.770261 0.000000 -v -0.047049 -0.013000 0.187539 -vn 0.301511 0.301511 -0.904534 -v -0.047799 -0.013000 0.185039 -vn 0.552286 0.770263 0.318865 -v -0.046882 -0.013000 0.186914 -vn -0.686243 0.609994 -0.396204 -v -0.043799 -0.013000 0.188694 -vn -0.301511 0.301511 -0.904534 -v -0.043799 -0.013000 0.185039 -vn -0.552286 0.770262 0.318867 -v -0.044717 -0.013000 0.186914 -vn -0.318861 0.770265 -0.552286 -v -0.045174 -0.013000 0.188622 -vn 0.000000 0.609995 -0.792405 -v -0.045799 -0.013000 0.189849 -vn -0.552291 0.770260 -0.318864 -v -0.044717 -0.013000 0.188164 -vn -0.637727 0.770263 0.000000 -v -0.044549 -0.013000 0.187539 -vn 0.000000 0.770258 -0.637732 -v -0.045799 -0.013000 0.188789 -vn 0.318861 0.770265 -0.552286 -v -0.046424 -0.013000 0.188622 -vn 0.552291 0.770261 -0.318862 -v -0.046882 -0.013000 0.188164 -vn 0.318866 0.770260 0.552291 -v -0.046424 -0.013000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.045799 -0.013000 0.186289 -vn -0.318866 0.770260 0.552291 -v -0.045174 -0.013000 0.186457 -vn 0.904534 0.301511 -0.301511 -v -0.038049 -0.013000 0.195039 -vn 0.904534 0.301511 0.301511 -v -0.038049 -0.013000 0.191039 -vn -0.637727 0.770263 0.000000 -v -0.039299 -0.013000 0.193039 -vn -0.552292 0.770260 0.318863 -v -0.039467 -0.013000 0.192414 -vn 0.552292 0.770260 0.318863 -v -0.041632 -0.013000 0.192414 -vn 0.396203 0.609994 0.686243 -v -0.041704 -0.013000 0.191039 -vn 0.637727 0.770263 -0.000000 -v -0.041799 -0.013000 0.193039 -vn 0.792406 0.609994 0.000000 -v -0.042859 -0.013000 0.193039 -vn 0.552287 0.770262 -0.318866 -v -0.041632 -0.013000 0.193664 -vn 0.396203 0.609994 -0.686244 -v -0.041704 -0.013000 0.195039 -vn 0.318866 0.770260 -0.552289 -v -0.041174 -0.013000 0.194122 -vn -0.552287 0.770262 -0.318866 -v -0.039467 -0.013000 0.193664 -vn -0.318866 0.770260 -0.552290 -v -0.039924 -0.013000 0.194122 -vn 0.000000 0.770264 -0.637725 -v -0.040549 -0.013000 0.194289 -vn 0.318862 0.770265 0.552285 -v -0.041174 -0.013000 0.191957 -vn 0.000000 0.770258 0.637732 -v -0.040549 -0.013000 0.191789 -vn -0.318861 0.770265 0.552285 -v -0.039924 -0.013000 0.191957 -vn -0.990667 -0.075085 -0.113763 -v -0.043799 -0.011500 0.186039 -vn -0.686243 -0.609994 -0.396204 -v -0.043799 -0.011500 0.188694 -vn -0.279911 -0.846478 -0.452906 -v -0.044799 -0.011500 0.188039 -vn -0.000000 -0.609995 -0.792405 -v -0.045799 -0.011500 0.189849 -vn 0.279911 -0.846478 -0.452907 -v -0.046799 -0.011500 0.188039 -vn 0.686243 -0.609994 -0.396204 -v -0.047799 -0.011500 0.188694 -vn 0.990667 -0.075085 -0.113763 -v -0.047799 -0.011500 0.186039 -vn -0.630262 0.297109 -0.717283 -v -0.043799 -0.011000 0.185039 -vn 0.630262 0.297109 -0.717284 -v -0.042549 -0.011000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.042549 -0.014000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.049049 -0.014000 0.185039 -vn 0.630262 0.297109 -0.717283 -v -0.047799 -0.011000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.049049 -0.011000 0.185039 -vn 0.452906 -0.846478 -0.279911 -v -0.041049 -0.011500 0.194039 -vn 0.113763 -0.075085 -0.990667 -v -0.039049 -0.011500 0.195039 -vn 0.396203 -0.609994 -0.686243 -v -0.041704 -0.011500 0.195039 -vn 0.396203 -0.609994 0.686244 -v -0.041704 -0.011500 0.191039 -vn 0.113763 -0.075085 0.990667 -v -0.039049 -0.011500 0.191039 -vn 0.452906 -0.846478 0.279911 -v -0.041049 -0.011500 0.192039 -vn 0.792406 -0.609994 -0.000000 -v -0.042859 -0.011500 0.193039 -vn 0.717284 0.297108 -0.630263 -v -0.038049 -0.011000 0.195039 -vn 0.717284 0.297108 0.630263 -v -0.038049 -0.011000 0.196289 -vn 0.717284 -0.297108 0.630262 -v -0.038049 -0.014000 0.196289 -vn 0.717284 -0.297108 -0.630262 -v -0.038049 -0.014000 0.189789 -vn 0.717284 0.297108 0.630263 -v -0.038049 -0.011000 0.191039 -vn 0.717284 0.297108 -0.630263 -v -0.038049 -0.011000 0.189789 -vn -0.736839 -0.087119 0.670431 -v -0.074549 -0.013500 0.214039 -vn -0.019677 -0.081892 0.996447 -v -0.083049 -0.013500 0.214039 -vn -0.736841 -0.087124 -0.670428 -v -0.074549 -0.013500 0.188039 -vn -0.630263 -0.297108 -0.717284 -v -0.074549 -0.013500 0.186539 -vn -0.768477 -0.319811 -0.554224 -v -0.074549 -0.014250 0.188240 -vn -0.768480 -0.554222 -0.319807 -v -0.074549 -0.014799 0.188789 -vn -0.804186 -0.227458 -0.549133 -v -0.073049 -0.013500 0.186539 -vn 0.804186 -0.227458 -0.549133 -v -0.066549 -0.013500 0.186539 -vn -0.804186 -0.227458 -0.549133 -v -0.065049 -0.013500 0.186539 -vn 0.804186 -0.227458 -0.549133 -v -0.058549 -0.013500 0.186539 -vn -0.804186 -0.227458 -0.549133 -v -0.057049 -0.013500 0.186539 -vn 0.804186 -0.227458 -0.549133 -v -0.050549 -0.013500 0.186539 -vn -0.804186 -0.227458 -0.549133 -v -0.049049 -0.013500 0.186539 -vn 0.804186 -0.227458 -0.549133 -v -0.042549 -0.013500 0.186539 -vn 0.630263 -0.297108 -0.717284 -v -0.041049 -0.013500 0.186539 -vn 0.717284 -0.297109 -0.630262 -v -0.039549 -0.013500 0.188039 -vn 0.549133 -0.227458 -0.804186 -v -0.039549 -0.013500 0.189789 -vn 0.549133 -0.227458 0.804187 -v -0.039549 -0.013500 0.196289 -vn 0.549133 -0.227458 -0.804187 -v -0.039549 -0.013500 0.205789 -vn 0.717284 -0.297108 -0.630262 -v -0.038049 -0.014000 0.205789 -vn 0.717284 0.297108 -0.630263 -v -0.038049 -0.011000 0.205789 -vn 0.717284 0.297108 -0.630263 -v -0.038049 -0.011000 0.211039 -vn 0.717284 0.297108 0.630263 -v -0.038049 -0.011000 0.212289 -vn 0.904534 0.301512 -0.301511 -v -0.038049 -0.013000 0.211039 -vn 0.717284 -0.297108 0.630262 -v -0.038049 -0.014000 0.212289 -vn 0.904534 0.301511 0.301511 -v -0.038049 -0.013000 0.207039 -vn 0.717284 0.297108 0.630263 -v -0.038049 -0.011000 0.207039 -vn 0.549132 -0.227458 0.804187 -v -0.039549 -0.013500 0.212289 -vn 0.717283 -0.297109 0.630263 -v -0.039549 -0.013500 0.214039 -vn 0.630263 -0.297108 0.717284 -v -0.041049 -0.013500 0.215539 -vn 0.804186 -0.227458 0.549133 -v -0.042549 -0.013500 0.215539 -vn 0.630262 0.297109 0.717283 -v -0.042549 -0.011000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.042549 -0.014000 0.217039 -vn 0.630262 0.297109 0.717283 -v -0.047799 -0.011000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.049049 -0.011000 0.217039 -vn 0.301511 0.301511 0.904534 -v -0.047799 -0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.049049 -0.014000 0.217039 -vn -0.301511 0.301511 0.904534 -v -0.043799 -0.013000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.043799 -0.011000 0.217039 -vn -0.804186 -0.227458 0.549133 -v -0.049049 -0.013500 0.215539 -vn 0.804186 -0.227458 0.549133 -v -0.050549 -0.013500 0.215539 -vn 0.630262 0.297109 0.717283 -v -0.050549 -0.011000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.050549 -0.014000 0.217039 -vn 0.630262 0.297109 0.717283 -v -0.055799 -0.011000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.057049 -0.011000 0.217039 -vn 0.301511 0.301511 0.904534 -v -0.055799 -0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.057049 -0.014000 0.217039 -vn -0.301511 0.301511 0.904534 -v -0.051799 -0.013000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.051799 -0.011000 0.217039 -vn -0.804186 -0.227458 0.549133 -v -0.057049 -0.013500 0.215539 -vn 0.804186 -0.227458 0.549133 -v -0.058549 -0.013500 0.215539 -vn 0.630262 0.297109 0.717283 -v -0.058549 -0.011000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.058549 -0.014000 0.217039 -vn 0.630262 0.297109 0.717283 -v -0.063799 -0.011000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.065049 -0.011000 0.217039 -vn 0.301511 0.301511 0.904534 -v -0.063799 -0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.065049 -0.014000 0.217039 -vn -0.301511 0.301511 0.904534 -v -0.059799 -0.013000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.059799 -0.011000 0.217039 -vn -0.804186 -0.227458 0.549133 -v -0.065049 -0.013500 0.215539 -vn 0.804186 -0.227458 0.549133 -v -0.066549 -0.013500 0.215539 -vn 0.630262 0.297109 0.717283 -v -0.066549 -0.011000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.066549 -0.014000 0.217039 -vn 0.630262 0.297109 0.717283 -v -0.071799 -0.011000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.073049 -0.011000 0.217039 -vn 0.301511 0.301511 0.904534 -v -0.071799 -0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.073049 -0.014000 0.217039 -vn -0.301511 0.301512 0.904534 -v -0.067799 -0.013000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.067799 -0.011000 0.217039 -vn -0.804186 -0.227458 0.549133 -v -0.073049 -0.013500 0.215539 -vn -0.630263 -0.297108 0.717284 -v -0.074549 -0.013500 0.215539 -vn -0.768478 -0.554225 0.319806 -v -0.074549 -0.014799 0.213289 -vn -0.768482 -0.319806 0.554220 -v -0.074549 -0.014250 0.213838 -vn -0.977023 -0.174809 0.121937 -v -0.083799 -0.014747 0.211039 -vn -0.717284 -0.297105 0.630263 -v -0.083799 -0.015050 0.211039 -vn 0.226214 -0.332589 0.915539 -v -0.045522 -0.017800 0.211039 -vn -0.341580 -0.341576 0.875585 -v -0.067599 -0.017800 0.211039 -vn -0.875577 -0.341581 0.341594 -v -0.067799 -0.017800 0.210839 -vn -0.888586 -0.371672 -0.268839 -v -0.067799 -0.017800 0.208110 -vn -0.812014 -0.391739 -0.432636 -v -0.066630 -0.017800 0.206347 -vn -0.880347 -0.391676 -0.267544 -v -0.065785 -0.017800 0.204308 -vn -0.915764 -0.391403 -0.090445 -v -0.065354 -0.017800 0.202143 -vn -0.915900 -0.391145 0.090178 -v -0.065354 -0.017800 0.199935 -vn -0.880746 -0.390896 0.267370 -v -0.065785 -0.017800 0.197771 -vn -0.812382 -0.391243 0.432394 -v -0.066630 -0.017800 0.195732 -vn -0.888355 -0.371661 0.269617 -v -0.067799 -0.017800 0.193968 -vn -0.875583 -0.341583 -0.341579 -v -0.067799 -0.017800 0.191239 -vn 0.396203 -0.609994 0.686244 -v -0.041704 -0.011500 0.207039 -vn 0.396203 0.609994 0.686243 -v -0.041704 -0.013000 0.207039 -vn 0.113763 -0.075085 0.990667 -v -0.039049 -0.011500 0.207039 -vn -0.637727 0.770263 0.000000 -v -0.039299 -0.013000 0.209039 -vn -0.552292 0.770260 0.318863 -v -0.039467 -0.013000 0.208414 -vn 0.000000 0.770264 -0.637725 -v -0.040549 -0.013000 0.210289 -vn 0.396202 0.609994 -0.686244 -v -0.041704 -0.013000 0.211039 -vn -0.318866 0.770260 -0.552290 -v -0.039924 -0.013000 0.210122 -vn -0.552287 0.770262 -0.318866 -v -0.039467 -0.013000 0.209664 -vn 0.318866 0.770260 -0.552289 -v -0.041174 -0.013000 0.210122 -vn 0.552287 0.770262 -0.318866 -v -0.041632 -0.013000 0.209664 -vn 0.792406 0.609994 -0.000001 -v -0.042859 -0.013000 0.209039 -vn 0.637727 0.770263 -0.000000 -v -0.041799 -0.013000 0.209039 -vn 0.552292 0.770260 0.318863 -v -0.041632 -0.013000 0.208414 -vn 0.318862 0.770265 0.552285 -v -0.041174 -0.013000 0.207957 -vn 0.000000 0.770258 0.637732 -v -0.040549 -0.013000 0.207789 -vn -0.318861 0.770265 0.552285 -v -0.039924 -0.013000 0.207957 -vn 0.113763 -0.075085 -0.990667 -v -0.039049 -0.011500 0.211039 -vn 0.396202 -0.609995 -0.686244 -v -0.041704 -0.011500 0.211039 -vn 0.792406 -0.609994 -0.000001 -v -0.042859 -0.011500 0.209039 -vn 0.452906 -0.846478 -0.279911 -v -0.041049 -0.011500 0.210039 -vn 0.452906 -0.846478 0.279911 -v -0.041049 -0.011500 0.208039 -vn -0.686244 -0.609994 0.396202 -v -0.043799 -0.011500 0.213384 -vn -0.686244 0.609994 0.396202 -v -0.043799 -0.013000 0.213384 -vn -0.990667 -0.075085 0.113762 -v -0.043799 -0.011500 0.216039 -vn 0.686244 0.609994 0.396203 -v -0.047799 -0.013000 0.213384 -vn 0.552291 0.770261 -0.318862 -v -0.046882 -0.013000 0.215164 -vn 0.637728 0.770261 0.000000 -v -0.047049 -0.013000 0.214539 -vn 0.552286 0.770263 0.318865 -v -0.046882 -0.013000 0.213914 -vn -0.000001 0.609994 0.792406 -v -0.045799 -0.013000 0.212230 -vn 0.318866 0.770260 0.552291 -v -0.046424 -0.013000 0.213457 -vn -0.637727 0.770263 0.000000 -v -0.044549 -0.013000 0.214539 -vn -0.552291 0.770260 -0.318864 -v -0.044717 -0.013000 0.215164 -vn -0.318861 0.770265 -0.552286 -v -0.045174 -0.013000 0.215622 -vn 0.000000 0.770258 -0.637732 -v -0.045799 -0.013000 0.215789 -vn 0.318861 0.770265 -0.552286 -v -0.046424 -0.013000 0.215622 -vn 0.000000 0.770264 0.637725 -v -0.045799 -0.013000 0.213289 -vn -0.318866 0.770260 0.552291 -v -0.045174 -0.013000 0.213457 -vn -0.552286 0.770262 0.318867 -v -0.044717 -0.013000 0.213914 -vn 0.990667 -0.075085 0.113762 -v -0.047799 -0.011500 0.216039 -vn 0.686244 -0.609994 0.396203 -v -0.047799 -0.011500 0.213384 -vn -0.000001 -0.609994 0.792406 -v -0.045799 -0.011500 0.212230 -vn 0.279911 -0.846478 0.452906 -v -0.046799 -0.011500 0.214039 -vn -0.279912 -0.846479 0.452906 -v -0.044799 -0.011500 0.214039 -vn -0.686244 -0.609995 0.396202 -v -0.051799 -0.011500 0.213384 -vn -0.686244 0.609994 0.396202 -v -0.051799 -0.013000 0.213384 -vn -0.990667 -0.075085 0.113762 -v -0.051799 -0.011500 0.216039 -vn 0.686244 0.609994 0.396203 -v -0.055799 -0.013000 0.213384 -vn 0.552291 0.770261 -0.318862 -v -0.054882 -0.013000 0.215164 -vn 0.637728 0.770261 0.000000 -v -0.055049 -0.013000 0.214539 -vn 0.552286 0.770263 0.318865 -v -0.054882 -0.013000 0.213914 -vn -0.000001 0.609994 0.792406 -v -0.053799 -0.013000 0.212230 -vn 0.318866 0.770260 0.552291 -v -0.054424 -0.013000 0.213457 -vn -0.552292 0.770260 -0.318863 -v -0.052717 -0.013000 0.215164 -vn -0.637727 0.770263 0.000000 -v -0.052549 -0.013000 0.214539 -vn -0.000000 0.770264 0.637725 -v -0.053799 -0.013000 0.213289 -vn -0.318866 0.770261 0.552289 -v -0.053174 -0.013000 0.213457 -vn -0.552287 0.770262 0.318866 -v -0.052717 -0.013000 0.213914 -vn -0.318862 0.770265 -0.552285 -v -0.053174 -0.013000 0.215622 -vn 0.000000 0.770258 -0.637732 -v -0.053799 -0.013000 0.215789 -vn 0.318861 0.770265 -0.552286 -v -0.054424 -0.013000 0.215622 -vn 0.990667 -0.075085 0.113762 -v -0.055799 -0.011500 0.216039 -vn 0.686244 -0.609994 0.396203 -v -0.055799 -0.011500 0.213384 -vn -0.686244 -0.609995 0.396202 -v -0.059799 -0.011500 0.213384 -vn -0.686244 0.609995 0.396202 -v -0.059799 -0.013000 0.213384 -vn -0.990667 -0.075085 0.113762 -v -0.059799 -0.011500 0.216039 -vn -0.552291 0.770261 -0.318862 -v -0.060717 -0.013000 0.215164 -vn -0.637729 0.770261 -0.000000 -v -0.060549 -0.013000 0.214539 -vn -0.318861 0.770265 -0.552286 -v -0.061174 -0.013000 0.215622 -vn 0.000000 0.770258 -0.637732 -v -0.061799 -0.013000 0.215789 -vn 0.318866 0.770260 0.552289 -v -0.062424 -0.013000 0.213457 -vn -0.000001 0.609994 0.792406 -v -0.061799 -0.013000 0.212230 -vn 0.552287 0.770263 0.318864 -v -0.062882 -0.013000 0.213914 -vn 0.686244 0.609994 0.396202 -v -0.063799 -0.013000 0.213384 -vn 0.000000 0.770264 0.637725 -v -0.061799 -0.013000 0.213289 -vn -0.318866 0.770260 0.552291 -v -0.061174 -0.013000 0.213457 -vn -0.552286 0.770263 0.318865 -v -0.060717 -0.013000 0.213914 -vn 0.318862 0.770265 -0.552285 -v -0.062424 -0.013000 0.215622 -vn 0.552292 0.770261 -0.318861 -v -0.062882 -0.013000 0.215164 -vn 0.637728 0.770261 0.000000 -v -0.063049 -0.013000 0.214539 -vn 0.990667 -0.075085 0.113762 -v -0.063799 -0.011500 0.216039 -vn 0.686244 -0.609994 0.396203 -v -0.063799 -0.011500 0.213384 -vn -0.686244 -0.609994 0.396203 -v -0.067799 -0.011500 0.213384 -vn -0.686244 0.609994 0.396202 -v -0.067799 -0.013000 0.213384 -vn -0.990667 -0.075085 0.113762 -v -0.067799 -0.011500 0.216039 -vn 0.000000 0.770264 0.637725 -v -0.069799 -0.013000 0.213289 -vn -0.318866 0.770260 0.552291 -v -0.069174 -0.013000 0.213457 -vn 0.000001 0.609994 0.792406 -v -0.069799 -0.013000 0.212230 -vn 0.686244 0.609995 0.396202 -v -0.071799 -0.013000 0.213384 -vn 0.552291 0.770261 -0.318862 -v -0.070882 -0.013000 0.215164 -vn 0.637728 0.770261 0.000000 -v -0.071049 -0.013000 0.214539 -vn 0.552286 0.770263 0.318865 -v -0.070882 -0.013000 0.213914 -vn 0.318866 0.770260 0.552291 -v -0.070424 -0.013000 0.213457 -vn -0.552286 0.770263 0.318865 -v -0.068717 -0.013000 0.213914 -vn -0.637728 0.770261 -0.000000 -v -0.068549 -0.013000 0.214539 -vn -0.552291 0.770261 -0.318862 -v -0.068717 -0.013000 0.215164 -vn -0.318861 0.770265 -0.552286 -v -0.069174 -0.013000 0.215622 -vn 0.000000 0.770258 -0.637732 -v -0.069799 -0.013000 0.215789 -vn 0.318861 0.770265 -0.552286 -v -0.070424 -0.013000 0.215622 -vn 0.990667 -0.075084 0.113762 -v -0.071799 -0.011500 0.216039 -vn 0.686244 -0.609995 0.396202 -v -0.071799 -0.011500 0.213384 -vn -0.000001 -0.609994 0.792406 -v -0.053799 -0.011500 0.212230 -vn 0.279912 -0.846479 0.452906 -v -0.054799 -0.011500 0.214039 -vn -0.279911 -0.846479 0.452906 -v -0.052799 -0.011500 0.214039 -vn -0.000001 -0.609994 0.792406 -v -0.061799 -0.011500 0.212230 -vn 0.279911 -0.846478 0.452906 -v -0.062799 -0.011500 0.214039 -vn -0.279911 -0.846479 0.452906 -v -0.060799 -0.011500 0.214039 -vn 0.000001 -0.609994 0.792406 -v -0.069799 -0.011500 0.212230 -vn 0.279912 -0.846479 0.452905 -v -0.070799 -0.011500 0.214039 -vn -0.279911 -0.846478 0.452906 -v -0.068799 -0.011500 0.214039 -vn -0.454637 -0.034159 0.890022 -v -0.083599 -0.013500 0.214009 -vn -0.237883 -0.091614 0.966964 -v -0.083599 -0.013300 0.214009 -vn -0.237234 -0.414898 0.878396 -v -0.084595 -0.013300 0.213794 -vn -0.392577 -0.377852 0.838517 -v -0.084975 -0.013300 0.213654 -vn -0.494295 -0.408204 0.767491 -v -0.085988 -0.013300 0.213084 -vn -0.622835 -0.375035 0.686605 -v -0.086229 -0.013300 0.212898 -vn -0.711421 -0.391911 0.583340 -v -0.087095 -0.013300 0.211978 -vn -0.801572 -0.375410 0.465349 -v -0.087210 -0.013300 0.211812 -vn -0.888949 -0.371265 0.268202 -v -0.087835 -0.013300 0.210487 -vn -0.057150 -0.407593 0.911374 -v -0.086549 -0.015050 0.208539 -vn -0.123375 -0.392039 0.911638 -v -0.085549 -0.015050 0.208539 -vn -0.095840 -0.678874 0.727973 -v -0.085549 -0.013500 0.208539 -vn -0.217183 -0.376175 0.900735 -v -0.087199 -0.014876 0.208539 -vn -0.376178 -0.217186 0.900733 -v -0.087675 -0.014400 0.208539 -vn -0.407597 -0.057148 0.911372 -v -0.087849 -0.013750 0.208539 -vn -0.574277 -0.578883 0.578879 -v -0.087849 -0.013500 0.208539 -vn -0.566906 -0.797132 0.207842 -v -0.083799 -0.013500 0.213758 -vn -0.593612 -0.393455 0.702010 -v -0.083779 -0.013500 0.213783 -vn -0.166941 -0.915139 0.366949 -v -0.084898 -0.013500 0.213469 -vn -0.000000 -0.770263 -0.637727 -v -0.085549 -0.013500 0.211289 -vn -0.318867 -0.770263 -0.552285 -v -0.085049 -0.013500 0.211155 -vn -0.552291 -0.770260 -0.318864 -v -0.084683 -0.013500 0.210789 -vn -0.727973 -0.678875 0.095838 -v -0.083799 -0.013500 0.210289 -vn -0.637727 -0.770263 -0.000002 -v -0.084549 -0.013500 0.210289 -vn -0.655722 -0.653226 0.378582 -v -0.084034 -0.013500 0.209414 -vn -0.552286 -0.770263 0.318866 -v -0.084683 -0.013500 0.209789 -vn -0.378579 -0.653227 0.655722 -v -0.084674 -0.013500 0.208774 -vn -0.318863 -0.770260 0.552291 -v -0.085049 -0.013500 0.209423 -vn 0.000000 -0.770263 0.637727 -v -0.085549 -0.013500 0.209289 -vn 0.318863 -0.770260 0.552291 -v -0.086049 -0.013500 0.209423 -vn -0.397291 -0.917194 0.030260 -v -0.087849 -0.013500 0.209039 -vn 0.552285 -0.770263 0.318866 -v -0.086415 -0.013500 0.209789 -vn -0.394716 -0.911005 0.119455 -v -0.087644 -0.013500 0.210429 -vn 0.637727 -0.770263 -0.000002 -v -0.086549 -0.013500 0.210289 -vn -0.341595 -0.915052 0.214459 -v -0.087044 -0.013500 0.211701 -vn 0.552291 -0.770260 -0.318864 -v -0.086415 -0.013500 0.210789 -vn -0.260384 -0.916103 0.304887 -v -0.086102 -0.013500 0.212744 -vn 0.318867 -0.770263 -0.552285 -v -0.086049 -0.013500 0.211155 -vn -0.911643 -0.392029 0.123374 -v -0.083799 -0.015050 0.210289 -vn -0.925873 -0.376085 0.036324 -v -0.083799 -0.014747 0.212500 -vn -0.934777 -0.075601 0.347097 -v -0.083799 -0.013690 0.213743 -vn -0.923537 -0.358788 0.135462 -v -0.083799 -0.014662 0.212957 -vn -0.928827 -0.279272 0.243491 -v -0.083799 -0.014415 0.213355 -vn -0.931062 -0.178111 0.318434 -v -0.083799 -0.014122 0.213590 -vn -0.456721 -0.406960 0.791068 -v -0.084674 -0.015050 0.208774 -vn -0.791066 -0.406959 0.456726 -v -0.084034 -0.015050 0.209414 -vn -0.407597 -0.057149 -0.911372 -v -0.087849 -0.013750 0.193539 -vn -0.574277 -0.578883 -0.578879 -v -0.087849 -0.013500 0.193539 -vn -0.095840 -0.678874 -0.727973 -v -0.085549 -0.013500 0.193539 -vn -0.376178 -0.217186 -0.900733 -v -0.087675 -0.014400 0.193539 -vn -0.217184 -0.376175 -0.900735 -v -0.087199 -0.014876 0.193539 -vn -0.057149 -0.407593 -0.911374 -v -0.086549 -0.015050 0.193539 -vn -0.123374 -0.392039 -0.911638 -v -0.085549 -0.015050 0.193539 -vn -0.637727 -0.770263 -0.000002 -v -0.084549 -0.013500 0.191789 -vn -0.552286 -0.770263 0.318866 -v -0.084683 -0.013500 0.191289 -vn -0.830928 -0.503528 -0.236680 -v -0.083799 -0.013500 0.188298 -vn -0.318863 -0.770260 0.552291 -v -0.085049 -0.013500 0.190923 -vn -0.164416 -0.916752 -0.364050 -v -0.084914 -0.013500 0.188616 -vn 0.000000 -0.770263 0.637727 -v -0.085549 -0.013500 0.190789 -vn -0.262571 -0.916342 -0.302281 -v -0.086112 -0.013500 0.189343 -vn 0.318863 -0.770260 0.552291 -v -0.086049 -0.013500 0.190923 -vn -0.341972 -0.915130 -0.213524 -v -0.087049 -0.013500 0.190385 -vn 0.552285 -0.770263 0.318866 -v -0.086415 -0.013500 0.191289 -vn -0.394734 -0.911049 -0.119058 -v -0.087645 -0.013500 0.191653 -vn 0.637727 -0.770263 -0.000002 -v -0.086549 -0.013500 0.191789 -vn -0.397247 -0.917216 -0.030155 -v -0.087849 -0.013500 0.193039 -vn 0.552291 -0.770260 -0.318864 -v -0.086415 -0.013500 0.192289 -vn 0.318867 -0.770263 -0.552285 -v -0.086049 -0.013500 0.192655 -vn -0.000000 -0.770263 -0.637727 -v -0.085549 -0.013500 0.192789 -vn -0.378579 -0.653227 -0.655722 -v -0.084674 -0.013500 0.193305 -vn -0.318867 -0.770263 -0.552285 -v -0.085049 -0.013500 0.192655 -vn -0.655721 -0.653226 -0.378583 -v -0.084034 -0.013500 0.192664 -vn -0.552291 -0.770260 -0.318864 -v -0.084683 -0.013500 0.192289 -vn -0.727973 -0.678874 -0.095840 -v -0.083799 -0.013500 0.191789 -vn -0.911642 -0.392029 -0.123375 -v -0.083799 -0.015050 0.191789 -vn -0.791064 -0.406967 -0.456723 -v -0.084034 -0.015050 0.192664 -vn -0.456719 -0.406975 -0.791062 -v -0.084674 -0.015050 0.193305 -vn -0.919677 -0.141908 -0.366136 -v -0.083799 -0.013965 0.188357 -vn -0.926994 -0.036080 -0.373338 -v -0.083799 -0.013500 0.188271 -vn -0.527996 -0.451014 -0.719588 -v -0.083799 -0.013473 0.188271 -vn -0.922214 -0.386586 -0.008524 -v -0.083799 -0.014800 0.189583 -vn -0.915772 -0.396290 -0.065703 -v -0.083799 -0.014793 0.189450 -vn -0.918049 -0.267267 -0.292839 -v -0.083799 -0.014372 0.188609 -vn -0.915021 -0.361084 -0.179873 -v -0.083799 -0.014658 0.188986 -vn 0.907512 -0.133422 0.398272 -v -0.045192 -0.014800 0.210835 -vn 0.652397 -0.658765 0.374709 -v -0.045065 -0.013500 0.210564 -vn 0.934450 -0.344938 0.088435 -v -0.045299 -0.014800 0.211439 -vn 0.752368 -0.658698 0.007637 -v -0.045299 -0.013500 0.211439 -vn 0.901668 -0.390793 -0.185137 -v -0.045287 -0.014800 0.211646 -vn 0.648876 -0.662043 -0.375046 -v -0.045065 -0.013500 0.212314 -vn 0.374858 -0.660766 -0.650284 -v -0.044424 -0.013500 0.212955 -vn 0.695175 -0.391317 -0.602996 -v -0.044971 -0.014800 0.212459 -vn 0.856590 -0.344697 -0.383975 -v -0.045065 -0.014800 0.212314 -vn -0.000675 -0.659325 -0.751858 -v -0.043549 -0.013500 0.213189 -vn 0.310547 -0.391812 -0.866051 -v -0.044302 -0.014800 0.213019 -vn 0.551759 -0.356522 -0.753959 -v -0.044424 -0.014800 0.212955 -vn -0.377400 -0.657713 -0.651907 -v -0.042674 -0.013500 0.212955 -vn -0.138306 -0.407743 -0.902562 -v -0.043446 -0.014800 0.213186 -vn 0.105669 -0.367162 -0.924135 -v -0.043549 -0.014800 0.213189 -vn -0.655784 -0.654709 0.375905 -v -0.042034 -0.013500 0.210564 -vn -0.906200 -0.422281 0.021915 -v -0.041799 -0.014800 0.211439 -vn -0.756522 -0.653967 0.001405 -v -0.041799 -0.013500 0.211439 -vn -0.789486 -0.415223 -0.451997 -v -0.042017 -0.014800 0.212284 -vn -0.654563 -0.655410 -0.376808 -v -0.042034 -0.013500 0.212314 -vn -0.579364 -0.393183 -0.713964 -v -0.042615 -0.014800 0.212919 -vn -0.364523 -0.376618 -0.851635 -v -0.042674 -0.014800 0.212955 -vn -0.377401 -0.657716 0.651904 -v -0.042674 -0.013500 0.209924 -vn -0.579413 -0.393175 0.713929 -v -0.042615 -0.014800 0.209959 -vn -0.801280 -0.406166 0.439294 -v -0.042017 -0.014800 0.210594 -vn -0.002348 -0.660325 0.750976 -v -0.043549 -0.013500 0.209689 -vn -0.149701 -0.394650 0.906554 -v -0.043446 -0.014800 0.209692 -vn -0.368045 -0.380444 0.848413 -v -0.042674 -0.014800 0.209924 -vn 0.378744 -0.660892 0.647901 -v -0.044424 -0.013500 0.209924 -vn 0.444718 -0.126316 0.886719 -v -0.044250 -0.014800 0.209835 -vn 0.076506 -0.388736 0.918167 -v -0.043549 -0.014800 0.209689 -vn 0.635228 -0.322675 0.701688 -v -0.044250 -0.017800 0.209835 -vn 0.505453 -0.352524 0.787556 -v -0.044424 -0.017800 0.209924 -vn 0.674655 -0.383268 0.630830 -v -0.044820 -0.017800 0.210236 -vn 0.808500 -0.274674 0.520463 -v -0.045065 -0.017800 0.210564 -vn 0.727335 -0.323523 0.605241 -v -0.045192 -0.017800 0.210835 -vn 0.552291 -0.770261 -0.318862 -v -0.044415 -0.013500 0.211939 -vn 0.637729 -0.770261 -0.000002 -v -0.044549 -0.013500 0.211439 -vn 0.552286 -0.770264 0.318863 -v -0.044415 -0.013500 0.210939 -vn 0.318863 -0.770260 0.552291 -v -0.044049 -0.013500 0.210573 -vn 0.000000 -0.770263 0.637727 -v -0.043549 -0.013500 0.210439 -vn -0.318863 -0.770260 0.552291 -v -0.043049 -0.013500 0.210573 -vn -0.552286 -0.770263 0.318866 -v -0.042683 -0.013500 0.210939 -vn -0.637727 -0.770263 -0.000002 -v -0.042549 -0.013500 0.211439 -vn -0.552291 -0.770260 -0.318864 -v -0.042683 -0.013500 0.211939 -vn -0.318867 -0.770263 -0.552285 -v -0.043049 -0.013500 0.212305 -vn -0.000000 -0.770263 -0.637727 -v -0.043549 -0.013500 0.212439 -vn 0.318867 -0.770263 -0.552285 -v -0.044049 -0.013500 0.212305 -vn 0.750456 -0.660919 0.001532 -v -0.045299 -0.013500 0.190639 -vn 0.647848 -0.660949 -0.378734 -v -0.045065 -0.013500 0.191514 -vn 0.901120 -0.090476 -0.424025 -v -0.045154 -0.014800 0.191339 -vn 0.464696 -0.081885 -0.881676 -v -0.044394 -0.014800 0.192172 -vn 0.375511 -0.656888 -0.653826 -v -0.044424 -0.013500 0.192155 -vn -0.009040 -0.420598 -0.907202 -v -0.043583 -0.014800 0.192389 -vn -0.003255 -0.653089 -0.757274 -v -0.043549 -0.013500 0.192389 -vn -0.375680 -0.653677 -0.656941 -v -0.042674 -0.013500 0.192155 -vn -0.653207 -0.656506 -0.377253 -v -0.042034 -0.013500 0.191514 -vn -0.715793 -0.392609 -0.577494 -v -0.042062 -0.014800 0.191561 -vn -0.434095 -0.406960 -0.803707 -v -0.042713 -0.014800 0.192176 -vn -0.753859 -0.657037 -0.000056 -v -0.041799 -0.013500 0.190639 -vn -0.908508 -0.393743 -0.139926 -v -0.041801 -0.014800 0.190704 -vn -0.850129 -0.382801 -0.361585 -v -0.042034 -0.014800 0.191514 -vn -0.652477 -0.657550 0.376699 -v -0.042034 -0.013500 0.189764 -vn -0.857631 -0.393995 0.330511 -v -0.041998 -0.014800 0.189830 -vn -0.918052 -0.380927 0.109887 -v -0.041799 -0.014800 0.190639 -vn -0.376454 -0.658050 0.652114 -v -0.042674 -0.013500 0.189124 -vn -0.579462 -0.394239 0.713302 -v -0.042601 -0.014800 0.189168 -vn -0.742072 -0.379022 0.552876 -v -0.042034 -0.014800 0.189764 -vn 0.000078 -0.658534 0.752551 -v -0.043549 -0.013500 0.188889 -vn -0.129597 -0.409687 0.902974 -v -0.043453 -0.014800 0.188892 -vn -0.379827 -0.391924 0.837930 -v -0.042674 -0.014800 0.189124 -vn 0.376171 -0.659003 0.651315 -v -0.044424 -0.013500 0.189124 -vn 0.322957 -0.394718 0.860172 -v -0.044331 -0.014800 0.189073 -vn 0.103442 -0.375119 0.921187 -v -0.043549 -0.014800 0.188889 -vn 0.651104 -0.659455 0.375743 -v -0.045065 -0.013500 0.189764 -vn 0.707994 -0.394943 0.585461 -v -0.045003 -0.014800 0.189665 -vn 0.548757 -0.373132 0.748090 -v -0.044424 -0.014800 0.189124 -vn 0.939533 -0.339334 -0.046154 -v -0.045299 -0.014800 0.190639 -vn 0.911943 -0.385325 0.141013 -v -0.045295 -0.014800 0.190512 -vn 0.849024 -0.371145 0.376045 -v -0.045065 -0.014800 0.189764 -vn 0.782881 -0.322207 -0.532241 -v -0.045154 -0.017800 0.191339 -vn 0.801454 -0.343795 -0.489363 -v -0.045065 -0.017800 0.191514 -vn 0.651029 -0.386038 -0.653556 -v -0.044820 -0.017800 0.191842 -vn 0.546604 -0.306497 -0.779284 -v -0.044424 -0.017800 0.192155 -vn 0.549390 -0.324454 -0.770000 -v -0.044394 -0.017800 0.192172 -vn 0.552291 -0.770261 -0.318862 -v -0.044415 -0.013500 0.191139 -vn 0.637729 -0.770261 -0.000002 -v -0.044549 -0.013500 0.190639 -vn 0.552286 -0.770264 0.318863 -v -0.044415 -0.013500 0.190139 -vn 0.318863 -0.770260 0.552291 -v -0.044049 -0.013500 0.189773 -vn 0.000000 -0.770263 0.637727 -v -0.043549 -0.013500 0.189639 -vn -0.318863 -0.770260 0.552291 -v -0.043049 -0.013500 0.189773 -vn -0.552286 -0.770263 0.318866 -v -0.042683 -0.013500 0.190139 -vn -0.637727 -0.770263 -0.000002 -v -0.042549 -0.013500 0.190639 -vn -0.552291 -0.770260 -0.318864 -v -0.042683 -0.013500 0.191139 -vn -0.318857 -0.770266 -0.552286 -v -0.043049 -0.013500 0.191505 -vn 0.000000 -0.770255 -0.637736 -v -0.043549 -0.013500 0.191639 -vn 0.318857 -0.770266 -0.552286 -v -0.044049 -0.013500 0.191505 -vn -0.027693 -0.301576 -0.953040 -v -0.083049 -0.014019 0.188132 -vn -0.028992 -0.517919 -0.854938 -v -0.083049 -0.014250 0.188240 -vn -0.023718 -0.709494 -0.704312 -v -0.083049 -0.014561 0.188478 -vn -0.021422 -0.851020 -0.524697 -v -0.083049 -0.014799 0.188789 -vn -0.009598 -0.951519 -0.307442 -v -0.083049 -0.014907 0.189020 -vn -0.381661 -0.913760 -0.139205 -v -0.083603 -0.014992 0.189430 -vn -0.405548 -0.817783 -0.408365 -v -0.083612 -0.014836 0.188896 -vn -0.417649 -0.615726 -0.668170 -v -0.083618 -0.014506 0.188461 -vn -0.424812 -0.322016 -0.846074 -v -0.083621 -0.014037 0.188172 -vn -0.026108 -0.307935 0.951049 -v -0.083049 -0.014019 0.213946 -vn -0.026791 -0.520712 0.853312 -v -0.083049 -0.014250 0.213838 -vn -0.023040 -0.702648 0.711165 -v -0.083049 -0.014561 0.213600 -vn -0.010427 -0.952564 0.304161 -v -0.083049 -0.014907 0.213058 -vn -0.020963 -0.854004 0.519844 -v -0.083049 -0.014799 0.213289 -vn -0.446627 -0.177914 0.876853 -v -0.083599 -0.013729 0.213991 -vn -0.445001 -0.445572 0.776814 -v -0.083597 -0.014248 0.213808 -vn -0.437024 -0.671646 0.598249 -v -0.083592 -0.014600 0.213526 -vn -0.422546 -0.850370 0.313569 -v -0.083584 -0.014898 0.213048 -vn -0.466083 -0.807282 0.362025 -v -0.087299 -0.015049 0.208339 -vn -0.466084 -0.807282 -0.362025 -v -0.087299 -0.015049 0.193739 -vn -0.807283 -0.466084 0.362022 -v -0.087849 -0.014500 0.208339 -vn -0.807283 -0.466084 -0.362023 -v -0.087849 -0.014500 0.193739 -vn -0.732324 -0.680957 -0.000000 -v -0.067449 -0.014500 0.201039 -vn -0.711044 -0.680956 -0.175257 -v -0.067714 -0.014500 0.203217 -vn -0.648441 -0.680957 -0.340328 -v -0.068492 -0.014500 0.205268 -vn -0.548152 -0.680956 -0.485622 -v -0.069738 -0.014500 0.207074 -vn -0.416005 -0.680957 -0.602692 -v -0.071380 -0.014500 0.208528 -vn -0.259687 -0.680957 -0.684734 -v -0.073323 -0.014500 0.209548 -vn -0.088274 -0.680956 -0.726985 -v -0.075453 -0.014500 0.210073 -vn 0.088274 -0.680956 -0.726985 -v -0.077646 -0.014500 0.210073 -vn 0.259687 -0.680957 -0.684734 -v -0.079776 -0.014500 0.209548 -vn 0.416005 -0.680957 -0.602692 -v -0.081719 -0.014500 0.208528 -vn 0.548152 -0.680956 -0.485622 -v -0.083361 -0.014500 0.207074 -vn 0.648441 -0.680957 -0.340328 -v -0.084607 -0.014500 0.205268 -vn 0.711044 -0.680956 -0.175257 -v -0.085385 -0.014500 0.203217 -vn 0.732324 -0.680957 0.000000 -v -0.085649 -0.014500 0.201039 -vn 0.711044 -0.680956 0.175257 -v -0.085385 -0.014500 0.198861 -vn 0.648441 -0.680957 0.340328 -v -0.084607 -0.014500 0.196810 -vn 0.548153 -0.680956 0.485620 -v -0.083361 -0.014500 0.195005 -vn 0.416007 -0.680956 0.602691 -v -0.081719 -0.014500 0.193550 -vn 0.259685 -0.680956 0.684735 -v -0.079776 -0.014500 0.192530 -vn 0.088271 -0.680957 0.726984 -v -0.077646 -0.014500 0.192005 -vn -0.088271 -0.680957 0.726985 -v -0.075453 -0.014500 0.192005 -vn -0.259685 -0.680956 0.684735 -v -0.073323 -0.014500 0.192530 -vn -0.416007 -0.680956 0.602691 -v -0.071380 -0.014500 0.193550 -vn -0.548153 -0.680956 0.485620 -v -0.069738 -0.014500 0.195005 -vn -0.648441 -0.680957 0.340328 -v -0.068492 -0.014500 0.196810 -vn -0.711044 -0.680956 0.175257 -v -0.067714 -0.014500 0.198861 -vn 0.440043 -0.740586 -0.507834 -v -0.072162 -0.014500 0.195976 -vn 0.565290 -0.740587 -0.363290 -v -0.070913 -0.014500 0.197417 -vn 0.644742 -0.740587 -0.189313 -v -0.070121 -0.014500 0.199152 -vn 0.671961 -0.740586 0.000000 -v -0.069849 -0.014500 0.201039 -vn 0.644742 -0.740587 0.189313 -v -0.070121 -0.014500 0.202927 -vn 0.565290 -0.740587 0.363289 -v -0.070913 -0.014500 0.204661 -vn -0.565290 -0.740587 -0.363290 -v -0.082186 -0.014500 0.197417 -vn -0.440043 -0.740586 -0.507834 -v -0.080937 -0.014500 0.195976 -vn -0.279143 -0.740588 -0.611236 -v -0.079333 -0.014500 0.194945 -vn -0.095629 -0.740586 -0.665122 -v -0.077503 -0.014500 0.194407 -vn 0.095629 -0.740586 -0.665122 -v -0.075596 -0.014500 0.194407 -vn 0.279143 -0.740588 -0.611236 -v -0.073766 -0.014500 0.194945 -vn 0.440041 -0.740587 0.507834 -v -0.072162 -0.014500 0.206103 -vn 0.279144 -0.740586 0.611237 -v -0.073766 -0.014500 0.207134 -vn 0.095631 -0.740587 0.665121 -v -0.075596 -0.014500 0.207671 -vn -0.095631 -0.740587 0.665121 -v -0.077503 -0.014500 0.207671 -vn -0.279144 -0.740586 0.611238 -v -0.079333 -0.014500 0.207134 -vn -0.440040 -0.740587 0.507834 -v -0.080937 -0.014500 0.206103 -vn -0.565290 -0.740587 0.363290 -v -0.082186 -0.014500 0.204661 -vn -0.644742 -0.740587 0.189313 -v -0.082978 -0.014500 0.202927 -vn -0.671961 -0.740586 -0.000000 -v -0.083249 -0.014500 0.201039 -vn -0.644742 -0.740587 -0.189313 -v -0.082978 -0.014500 0.199152 -vn 0.736503 -0.676434 -0.000000 -v -0.069849 -0.015250 0.201039 -vn 0.706670 -0.676434 0.207497 -v -0.070121 -0.015250 0.202927 -vn 0.619586 -0.676434 0.398184 -v -0.070913 -0.015250 0.204661 -vn 0.482307 -0.676434 0.556613 -v -0.072162 -0.015250 0.206103 -vn 0.305955 -0.676434 0.669946 -v -0.073766 -0.015250 0.207134 -vn 0.104817 -0.676434 0.729007 -v -0.075596 -0.015250 0.207671 -vn -0.104817 -0.676433 0.729007 -v -0.077503 -0.015250 0.207671 -vn -0.305955 -0.676434 0.669946 -v -0.079333 -0.015250 0.207134 -vn -0.482307 -0.676434 0.556613 -v -0.080937 -0.015250 0.206103 -vn -0.619586 -0.676434 0.398184 -v -0.082186 -0.015250 0.204661 -vn -0.706670 -0.676434 0.207497 -v -0.082978 -0.015250 0.202927 -vn -0.736503 -0.676434 0.000000 -v -0.083249 -0.015250 0.201039 -vn -0.706670 -0.676434 -0.207497 -v -0.082978 -0.015250 0.199152 -vn -0.619586 -0.676434 -0.398184 -v -0.082186 -0.015250 0.197417 -vn -0.482308 -0.676434 -0.556610 -v -0.080937 -0.015250 0.195976 -vn -0.305955 -0.676433 -0.669948 -v -0.079333 -0.015250 0.194945 -vn -0.104814 -0.676434 -0.729007 -v -0.077503 -0.015250 0.194407 -vn 0.104814 -0.676434 -0.729007 -v -0.075596 -0.015250 0.194407 -vn 0.305956 -0.676433 -0.669948 -v -0.073766 -0.015250 0.194945 -vn 0.482308 -0.676434 -0.556611 -v -0.072162 -0.015250 0.195976 -vn 0.619586 -0.676434 -0.398184 -v -0.070913 -0.015250 0.197417 -vn 0.706670 -0.676434 -0.207497 -v -0.070121 -0.015250 0.199152 -vn -0.163455 -0.746099 0.645461 -v -0.075383 -0.015250 0.196434 -vn -0.364177 -0.746098 0.557416 -v -0.073951 -0.015250 0.197063 -vn -0.525437 -0.746099 0.408964 -v -0.072801 -0.015250 0.198122 -vn -0.629759 -0.746098 0.216197 -v -0.072057 -0.015250 0.199497 -vn -0.665834 -0.746100 -0.000001 -v -0.071799 -0.015250 0.201039 -vn -0.629760 -0.746098 -0.216196 -v -0.072057 -0.015250 0.202581 -vn -0.525437 -0.746100 -0.408963 -v -0.072801 -0.015250 0.203957 -vn -0.364177 -0.746098 -0.557416 -v -0.073951 -0.015250 0.205016 -vn 0.656754 -0.746099 0.109594 -v -0.081235 -0.015250 0.200257 -vn 0.585585 -0.746099 0.316903 -v -0.080727 -0.015250 0.198778 -vn 0.450958 -0.746099 0.489871 -v -0.079767 -0.015250 0.197544 -vn 0.267463 -0.746099 0.609754 -v -0.078458 -0.015250 0.196689 -vn 0.054983 -0.746100 0.663560 -v -0.076942 -0.015250 0.196305 -vn -0.163451 -0.746100 -0.645460 -v -0.075383 -0.015250 0.205644 -vn 0.054986 -0.746099 -0.663561 -v -0.076942 -0.015250 0.205773 -vn 0.267463 -0.746099 -0.609754 -v -0.078458 -0.015250 0.205389 -vn 0.450958 -0.746099 -0.489871 -v -0.079767 -0.015250 0.204534 -vn 0.585585 -0.746099 -0.316903 -v -0.080727 -0.015250 0.203300 -vn 0.656754 -0.746099 -0.109594 -v -0.081235 -0.015250 0.201821 -vn -0.740671 -0.671868 -0.000001 -v -0.071799 -0.012750 0.201039 -vn -0.700538 -0.671870 -0.240494 -v -0.072057 -0.012750 0.202581 -vn -0.584495 -0.671868 -0.454929 -v -0.072801 -0.012750 0.203957 -vn -0.405108 -0.671869 -0.620064 -v -0.073951 -0.012750 0.205016 -vn -0.181823 -0.671868 -0.718007 -v -0.075383 -0.012750 0.205644 -vn 0.061166 -0.671869 -0.738140 -v -0.076942 -0.012750 0.205773 -vn 0.297524 -0.671869 -0.678286 -v -0.078458 -0.012750 0.205389 -vn 0.501643 -0.671869 -0.544929 -v -0.079767 -0.012750 0.204534 -vn 0.651400 -0.671869 -0.352521 -v -0.080727 -0.012750 0.203300 -vn 0.730569 -0.671868 -0.121911 -v -0.081235 -0.012750 0.201821 -vn 0.730569 -0.671868 0.121911 -v -0.081235 -0.012750 0.200257 -vn 0.651400 -0.671869 0.352521 -v -0.080727 -0.012750 0.198778 -vn 0.501643 -0.671869 0.544929 -v -0.079767 -0.012750 0.197544 -vn 0.297524 -0.671869 0.678286 -v -0.078458 -0.012750 0.196689 -vn 0.061163 -0.671868 0.738141 -v -0.076942 -0.012750 0.196305 -vn -0.181826 -0.671869 0.718005 -v -0.075383 -0.012750 0.196434 -vn -0.405108 -0.671869 0.620064 -v -0.073951 -0.012750 0.197063 -vn -0.584493 -0.671868 0.454930 -v -0.072801 -0.012750 0.198122 -vn -0.700538 -0.671869 0.240495 -v -0.072057 -0.012750 0.199497 -vn 0.000000 -1.000000 0.000000 -v -0.076549 -0.012750 0.201039 -vn -0.552286 0.770263 0.318865 -v -0.060717 0.017000 0.186914 -vn -0.637728 0.770261 -0.000000 -v -0.060549 0.017000 0.187539 -vn 0.000000 0.923880 -0.382683 -v -0.059299 0.017000 0.186039 -vn 0.110049 0.987814 -0.110058 -v -0.064549 0.017000 0.210839 -vn 0.382685 0.923879 0.000000 -v -0.064549 0.017000 0.210164 -vn 0.000000 1.000000 0.000000 -v -0.069049 0.017000 0.210164 -vn -0.005386 0.991004 0.133723 -v -0.083049 0.017000 0.213039 -vn -0.041898 0.997001 0.065064 -v -0.074549 0.017000 0.213039 -vn 0.000000 1.000000 0.000000 -v -0.076749 0.017000 0.210939 -vn -0.131340 0.973781 0.185743 -v -0.073049 0.017000 0.214039 -vn -0.707107 0.707107 0.000000 -v -0.073049 0.017000 0.215914 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.215914 -vn 0.131340 0.973781 -0.185743 -v -0.042549 0.017000 0.188039 -vn 0.630263 0.717284 -0.297108 -v -0.042549 0.017000 0.186039 -vn 0.000000 0.923880 -0.382683 -v -0.042924 0.017000 0.186039 -vn -0.162885 0.945449 0.282126 -v -0.083549 0.017000 0.206173 -vn -0.642994 0.736824 0.208922 -v -0.081685 0.017000 0.202708 -vn -0.000001 0.945449 0.325771 -v -0.084049 0.017000 0.206039 -vn -0.676085 0.736824 0.000000 -v -0.081949 0.017000 0.201039 -vn 0.162887 0.945447 0.282132 -v -0.084549 0.017000 0.206173 -vn 0.000000 1.000000 0.000000 -v -0.076749 0.017000 0.210164 -vn 0.000000 1.000000 0.000000 -v -0.076749 0.017000 0.207114 -vn -0.325772 0.945448 -0.000002 -v -0.083049 0.017000 0.207039 -vn -0.282144 0.945442 -0.162892 -v -0.083183 0.017000 0.207539 -vn -0.162885 0.945449 -0.282126 -v -0.083549 0.017000 0.207905 -vn -0.130227 0.990581 0.042314 -v -0.086854 0.017000 0.210275 -vn -0.000001 0.945449 -0.325770 -v -0.084049 0.017000 0.208039 -vn 0.162887 0.945447 -0.282130 -v -0.084549 0.017000 0.207905 -vn 0.282125 0.945448 0.162889 -v -0.084915 0.017000 0.206539 -vn -0.130526 0.991445 0.000000 -v -0.087049 0.017000 0.201039 -vn 0.325773 0.945448 0.000001 -v -0.085049 0.017000 0.207039 -vn -0.130526 0.991445 0.000000 -v -0.087049 0.017000 0.207114 -vn 0.282143 0.945442 -0.162895 -v -0.084915 0.017000 0.207539 -vn -0.133725 0.991004 0.005386 -v -0.087049 0.017000 0.209039 -vn -0.135243 0.990581 0.021421 -v -0.087000 0.017000 0.209665 -vn -0.318866 0.770260 0.552291 -v -0.069174 0.017000 0.213457 -vn -0.552286 0.770263 0.318865 -v -0.068717 0.017000 0.213914 -vn 0.131340 0.973781 0.185743 -v -0.066549 0.017000 0.214039 -vn -0.637728 0.770261 -0.000000 -v -0.068549 0.017000 0.214539 -vn 0.707107 0.707107 0.000000 -v -0.066549 0.017000 0.215914 -vn -0.552291 0.770261 -0.318862 -v -0.068717 0.017000 0.215164 -vn 0.000000 1.000000 0.000000 -v -0.069049 0.017000 0.215914 -vn -0.318861 0.770265 -0.552286 -v -0.069174 0.017000 0.215622 -vn 0.000000 0.770258 -0.637732 -v -0.069799 0.017000 0.215789 -vn 0.318861 0.770265 -0.552286 -v -0.070424 0.017000 0.215622 -vn 0.552291 0.770261 -0.318862 -v -0.070882 0.017000 0.215164 -vn 0.000000 0.770264 0.637725 -v -0.069799 0.017000 0.213289 -vn -0.000000 1.000000 -0.000000 -v -0.069049 0.017000 0.210939 -vn 0.318865 0.770260 0.552291 -v -0.070424 0.017000 0.213457 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.210939 -vn 0.552286 0.770263 0.318865 -v -0.070882 0.017000 0.213914 -vn 0.637728 0.770261 0.000000 -v -0.071049 0.017000 0.214539 -vn -0.318866 0.770260 0.552290 -v -0.053174 0.017000 0.213457 -vn 0.131340 0.973781 0.185743 -v -0.050549 0.017000 0.214039 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.210939 -vn -0.318854 0.770266 0.552289 -v -0.050899 0.017000 0.210999 -vn -0.552288 0.770261 0.318866 -v -0.051009 0.017000 0.210889 -vn -0.552287 0.770262 0.318866 -v -0.052717 0.017000 0.213914 -vn -0.637727 0.770263 0.000000 -v -0.052549 0.017000 0.214539 -vn 0.707107 0.707107 0.000000 -v -0.050549 0.017000 0.215914 -vn -0.552292 0.770260 -0.318863 -v -0.052717 0.017000 0.215164 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.215914 -vn -0.131340 0.973781 0.185743 -v -0.057049 0.017000 0.214039 -vn -0.707107 0.707107 0.000000 -v -0.057049 0.017000 0.215914 -vn 0.552291 0.770261 -0.318862 -v -0.054882 0.017000 0.215164 -vn 0.637728 0.770261 0.000000 -v -0.055049 0.017000 0.214539 -vn 0.552286 0.770263 0.318865 -v -0.054882 0.017000 0.213914 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.210939 -vn 0.318866 0.770260 0.552291 -v -0.054424 0.017000 0.213457 -vn 0.000000 0.770264 0.637725 -v -0.053799 0.017000 0.213289 -vn -0.318861 0.770265 -0.552285 -v -0.053174 0.017000 0.215622 -vn 0.000000 0.770258 -0.637732 -v -0.053799 0.017000 0.215789 -vn 0.318861 0.770265 -0.552286 -v -0.054424 0.017000 0.215622 -vn 0.637727 0.770263 -0.000000 -v -0.041799 0.017000 0.209039 -vn 0.552292 0.770260 0.318863 -v -0.041632 0.017000 0.208414 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.207114 -vn 0.318862 0.770265 0.552285 -v -0.041174 0.017000 0.207957 -vn 0.000001 0.770258 0.637732 -v -0.040549 0.017000 0.207789 -vn 0.382683 0.923880 0.000000 -v -0.039049 0.017000 0.207114 -vn -0.318861 0.770265 0.552285 -v -0.039924 0.017000 0.207957 -vn -0.552292 0.770260 0.318863 -v -0.039467 0.017000 0.208414 -vn -0.637727 0.770263 0.000000 -v -0.039299 0.017000 0.209039 -vn 0.382683 0.923880 0.000000 -v -0.039049 0.017000 0.210164 -vn -0.552287 0.770262 -0.318866 -v -0.039467 0.017000 0.209664 -vn -0.318866 0.770260 -0.552289 -v -0.039924 0.017000 0.210122 -vn 0.382683 0.923880 0.000000 -v -0.039049 0.017000 0.210939 -vn 0.000000 0.770264 -0.637725 -v -0.040549 0.017000 0.210289 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.210939 -vn 0.318866 0.770260 -0.552289 -v -0.041174 0.017000 0.210122 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.210164 -vn 0.552287 0.770262 -0.318866 -v -0.041632 0.017000 0.209664 -vn -0.000001 0.923880 -0.382683 -v -0.063799 0.017000 0.186039 -vn -0.630263 0.717283 -0.297108 -v -0.065049 0.017000 0.186039 -vn -0.000000 1.000000 -0.000000 -v -0.063799 0.017000 0.189914 -vn -0.131341 0.973781 -0.185743 -v -0.065049 0.017000 0.188039 -vn -0.000000 1.000000 -0.000000 -v -0.069049 0.017000 0.189914 -vn 0.131340 0.973781 -0.185743 -v -0.066549 0.017000 0.188039 -vn -0.552291 0.770261 -0.318862 -v -0.068717 0.017000 0.188164 -vn -0.318861 0.770265 -0.552286 -v -0.069174 0.017000 0.188622 -vn 0.000000 0.770258 -0.637732 -v -0.069799 0.017000 0.188789 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.189914 -vn 0.000000 0.923880 -0.382683 -v -0.071099 0.017000 0.186039 -vn 0.637728 0.770261 0.000000 -v -0.071049 0.017000 0.187539 -vn 0.552286 0.770263 0.318865 -v -0.070882 0.017000 0.186914 -vn 0.318861 0.770265 -0.552286 -v -0.070424 0.017000 0.188622 -vn 0.552291 0.770261 -0.318862 -v -0.070882 0.017000 0.188164 -vn 0.318866 0.770260 0.552291 -v -0.070424 0.017000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.069799 0.017000 0.186289 -vn 0.000000 0.923880 -0.382683 -v -0.069049 0.017000 0.186039 -vn -0.318866 0.770260 0.552291 -v -0.069174 0.017000 0.186457 -vn 0.630263 0.717284 -0.297108 -v -0.066549 0.017000 0.186039 -vn -0.552286 0.770263 0.318865 -v -0.068717 0.017000 0.186914 -vn -0.637728 0.770261 -0.000000 -v -0.068549 0.017000 0.187539 -vn 0.000000 1.000000 0.000000 -v -0.049049 0.017000 0.189914 -vn -0.131340 0.973781 -0.185743 -v -0.049049 0.017000 0.188039 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.189914 -vn 0.131340 0.973781 -0.185743 -v -0.050549 0.017000 0.188039 -vn -0.552292 0.770260 -0.318863 -v -0.052717 0.017000 0.188164 -vn 0.552286 0.770263 0.318865 -v -0.054882 0.017000 0.186914 -vn -0.630262 0.717284 -0.297108 -v -0.057049 0.017000 0.186039 -vn 0.637728 0.770261 0.000000 -v -0.055049 0.017000 0.187539 -vn -0.131340 0.973781 -0.185743 -v -0.057049 0.017000 0.188039 -vn 0.552291 0.770261 -0.318862 -v -0.054882 0.017000 0.188164 -vn 0.318866 0.770260 0.552291 -v -0.054424 0.017000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.053799 0.017000 0.186289 -vn 0.000000 0.923880 -0.382683 -v -0.053299 0.017000 0.186039 -vn -0.318866 0.770260 0.552290 -v -0.053174 0.017000 0.186457 -vn 0.630263 0.717284 -0.297108 -v -0.050549 0.017000 0.186039 -vn -0.552287 0.770262 0.318866 -v -0.052717 0.017000 0.186914 -vn -0.637727 0.770263 0.000000 -v -0.052549 0.017000 0.187539 -vn 0.318861 0.770265 -0.552286 -v -0.054424 0.017000 0.188622 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.189914 -vn 0.000000 0.770258 -0.637732 -v -0.053799 0.017000 0.188789 -vn -0.318861 0.770265 -0.552285 -v -0.053174 0.017000 0.188622 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.191139 -vn 0.552289 0.770264 -0.318858 -v -0.044090 0.017000 0.191189 -vn 0.669356 0.737698 -0.088116 -v -0.044049 0.017000 0.191339 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.194964 -vn -0.552289 0.770264 -0.318858 -v -0.051009 0.017000 0.191189 -vn -0.318854 0.770266 -0.552289 -v -0.050899 0.017000 0.191079 -vn -0.088113 0.737697 -0.669358 -v -0.050749 0.017000 0.191039 -vn 0.000000 0.707107 -0.707107 -v -0.049049 0.017000 0.191039 -vn 0.088115 0.737698 -0.669357 -v -0.044349 0.017000 0.191039 -vn -0.707107 0.707107 0.000000 -v -0.051049 0.017000 0.194964 -vn -0.669356 0.737698 -0.088116 -v -0.051049 0.017000 0.191339 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.191139 -vn 0.000000 0.707107 0.707107 -v -0.049049 0.017000 0.197039 -vn -0.088113 0.737697 0.669358 -v -0.050749 0.017000 0.197039 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.201039 -vn -0.318854 0.770266 0.552289 -v -0.050899 0.017000 0.196999 -vn -0.552288 0.770261 0.318866 -v -0.051009 0.017000 0.196889 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.196539 -vn -0.669351 0.737701 0.088124 -v -0.051049 0.017000 0.196739 -vn 0.707107 0.707107 0.000000 -v -0.044049 0.017000 0.194964 -vn 0.707107 0.707107 0.000000 -v -0.044049 0.017000 0.196539 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.196539 -vn 0.669351 0.737701 0.088124 -v -0.044049 0.017000 0.196739 -vn 0.630263 0.717284 -0.297108 -v -0.058549 0.017000 0.186039 -vn 0.131340 0.973781 -0.185743 -v -0.058549 0.017000 0.188039 -vn 0.000000 1.000000 0.000000 -v -0.059299 0.017000 0.189914 -vn 0.382683 0.923880 0.000000 -v -0.039049 0.017000 0.189914 -vn 0.297109 0.717284 -0.630262 -v -0.039049 0.017000 0.189789 -vn 0.185742 0.973781 -0.131340 -v -0.041049 0.017000 0.189789 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.189914 -vn 0.408248 0.816497 -0.408248 -v -0.041049 0.017000 0.188039 -vn 0.297109 0.717284 0.630262 -v -0.039049 0.017000 0.196289 -vn 0.382683 0.923880 0.000000 -v -0.039049 0.017000 0.194964 -vn 0.185742 0.973781 0.131340 -v -0.041049 0.017000 0.196289 -vn 0.382683 0.923880 0.000000 -v -0.041049 0.017000 0.196539 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.201039 -vn 0.552288 0.770261 0.318866 -v -0.044090 0.017000 0.196889 -vn 0.297109 0.717284 -0.630262 -v -0.039049 0.017000 0.205789 -vn 0.185742 0.973781 -0.131340 -v -0.041049 0.017000 0.205789 -vn 0.382683 0.923880 0.000000 -v -0.041049 0.017000 0.201039 -vn 0.000000 1.000000 0.000000 -v -0.042924 0.017000 0.215914 -vn 0.707107 0.707107 0.000000 -v -0.042549 0.017000 0.215914 -vn 0.131340 0.973781 0.185743 -v -0.042549 0.017000 0.214039 -vn 0.297109 0.717284 0.630262 -v -0.039049 0.017000 0.212289 -vn 0.185743 0.973781 0.131340 -v -0.041049 0.017000 0.212289 -vn 0.408248 0.816497 0.408249 -v -0.041049 0.017000 0.214039 -vn 0.000000 1.000000 0.000000 -v -0.059299 0.017000 0.215914 -vn 0.707107 0.707107 0.000000 -v -0.058549 0.017000 0.215914 -vn 0.131340 0.973781 0.185743 -v -0.058549 0.017000 0.214039 -vn 0.630263 0.717284 0.297108 -v -0.058549 0.017000 0.216039 -vn -0.000000 0.923880 0.382683 -v -0.059299 0.017000 0.216039 -vn -0.000001 0.923880 0.382683 -v -0.063799 0.017000 0.216039 -vn -0.000001 1.000000 -0.000000 -v -0.063799 0.017000 0.210939 -vn -0.131341 0.973781 0.185743 -v -0.065049 0.017000 0.214039 -vn -0.000001 1.000000 0.000000 -v -0.063799 0.017000 0.215914 -vn -0.707107 0.707106 0.000000 -v -0.065049 0.017000 0.215914 -vn -0.630263 0.717283 0.297108 -v -0.065049 0.017000 0.216039 -vn -0.630262 0.717283 0.297109 -v -0.074549 0.017000 0.214039 -vn -0.122005 0.990581 0.062165 -v -0.086613 0.017000 0.210855 -vn -0.110777 0.990581 0.080485 -v -0.086286 0.017000 0.211390 -vn -0.021420 0.990581 0.135242 -v -0.083675 0.017000 0.212990 -vn -0.042315 0.990581 0.130228 -v -0.084286 0.017000 0.212843 -vn -0.096824 0.990581 0.096823 -v -0.085878 0.017000 0.211868 -vn -0.080484 0.990581 0.110777 -v -0.085401 0.017000 0.212275 -vn -0.062164 0.990581 0.122003 -v -0.084865 0.017000 0.212603 -vn -0.325772 0.945448 -0.000002 -v -0.083049 0.017000 0.195039 -vn 0.000000 1.000000 0.000000 -v -0.076749 0.017000 0.194964 -vn -0.282129 0.945447 0.162889 -v -0.083183 0.017000 0.194539 -vn 0.000000 1.000000 0.000000 -v -0.076749 0.017000 0.191139 -vn -0.162896 0.945441 0.282147 -v -0.083549 0.017000 0.194173 -vn -0.000004 0.945448 0.325774 -v -0.084049 0.017000 0.194039 -vn -0.080486 0.990581 -0.110780 -v -0.085401 0.017000 0.189803 -vn -0.096825 0.990580 -0.096826 -v -0.085878 0.017000 0.190211 -vn 0.162903 0.945438 0.282151 -v -0.084549 0.017000 0.194173 -vn -0.122004 0.990581 -0.062163 -v -0.086613 0.017000 0.191223 -vn -0.110779 0.990581 -0.080486 -v -0.086286 0.017000 0.190688 -vn -0.005386 0.991004 -0.133727 -v -0.083049 0.017000 0.189039 -vn -0.021421 0.990581 -0.135245 -v -0.083675 0.017000 0.189088 -vn -0.042314 0.990581 -0.130224 -v -0.084286 0.017000 0.189235 -vn -0.630263 0.717284 -0.297108 -v -0.073049 0.017000 0.186039 -vn -0.131340 0.973781 -0.185743 -v -0.073049 0.017000 0.188039 -vn -0.630262 0.717283 -0.297109 -v -0.074549 0.017000 0.188039 -vn -0.041899 0.997001 -0.065066 -v -0.074549 0.017000 0.189039 -vn 0.000000 1.000000 0.000000 -v -0.076749 0.017000 0.189914 -vn -0.131340 0.973781 0.185743 -v -0.049049 0.017000 0.214039 -vn -0.707107 0.707107 0.000000 -v -0.049049 0.017000 0.215914 -vn 0.552291 0.770261 -0.318862 -v -0.046882 0.017000 0.215164 -vn 0.637728 0.770261 0.000000 -v -0.047049 0.017000 0.214539 -vn 0.000000 0.707107 0.707107 -v -0.049049 0.017000 0.211039 -vn -0.088113 0.737697 0.669358 -v -0.050749 0.017000 0.211039 -vn 0.552286 0.770263 0.318865 -v -0.046882 0.017000 0.213914 -vn 0.318866 0.770260 0.552291 -v -0.046424 0.017000 0.213457 -vn 0.088115 0.737697 0.669357 -v -0.044349 0.017000 0.211039 -vn 0.000000 0.770264 0.637725 -v -0.045799 0.017000 0.213289 -vn 0.318856 0.770265 0.552289 -v -0.044199 0.017000 0.210999 -vn -0.318866 0.770260 0.552291 -v -0.045174 0.017000 0.213457 -vn -0.552286 0.770262 0.318867 -v -0.044717 0.017000 0.213914 -vn -0.637727 0.770263 0.000000 -v -0.044549 0.017000 0.214539 -vn -0.552291 0.770260 -0.318864 -v -0.044717 0.017000 0.215164 -vn -0.318861 0.770265 -0.552286 -v -0.045174 0.017000 0.215622 -vn 0.000000 1.000000 0.000000 -v -0.044299 0.017000 0.215914 -vn -0.000000 0.770258 -0.637732 -v -0.045799 0.017000 0.215789 -vn 0.318861 0.770265 -0.552286 -v -0.046424 0.017000 0.215622 -vn 0.552288 0.770261 0.318866 -v -0.044090 0.017000 0.210889 -vn 0.707107 0.707107 0.000000 -v -0.044049 0.017000 0.210164 -vn 0.669351 0.737701 0.088124 -v -0.044049 0.017000 0.210739 -vn 0.088115 0.737698 -0.669357 -v -0.044349 0.017000 0.205039 -vn 0.318869 0.770273 -0.552269 -v -0.044199 0.017000 0.205079 -vn 0.552308 0.770252 -0.318853 -v -0.044090 0.017000 0.205189 -vn 0.669351 0.737701 -0.088124 -v -0.044049 0.017000 0.205339 -vn 0.707107 0.707107 0.000000 -v -0.044049 0.017000 0.207114 -vn -0.088113 0.737697 -0.669358 -v -0.050749 0.017000 0.205039 -vn 0.000000 0.707107 -0.707107 -v -0.049049 0.017000 0.205039 -vn 0.000000 1.000000 0.000000 -v -0.049049 0.017000 0.201039 -vn 0.000000 1.000000 0.000000 -v -0.044299 0.017000 0.201039 -vn 0.318856 0.770265 0.552289 -v -0.044199 0.017000 0.196999 -vn -0.318867 0.770274 -0.552269 -v -0.050899 0.017000 0.205079 -vn 0.088115 0.737698 0.669357 -v -0.044349 0.017000 0.197039 -vn -0.669351 0.737701 0.088124 -v -0.051049 0.017000 0.210739 -vn -0.707107 0.707107 0.000000 -v -0.051049 0.017000 0.210164 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.210164 -vn -0.707107 0.707107 0.000000 -v -0.051049 0.017000 0.207114 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.207114 -vn -0.669351 0.737701 -0.088124 -v -0.051049 0.017000 0.205339 -vn -0.552308 0.770252 -0.318853 -v -0.051009 0.017000 0.205189 -vn 0.185741 0.973781 -0.131341 -v -0.064549 0.017000 0.200539 -vn -0.000000 1.000000 -0.000000 -v -0.069049 0.017000 0.201039 -vn -0.000001 1.000000 0.000000 -v -0.063799 0.017000 0.201039 -vn 0.000000 1.000000 0.000000 -v -0.069049 0.017000 0.196539 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.194964 -vn -0.382683 0.923880 0.000000 -v -0.058049 0.017000 0.194964 -vn -0.382683 0.923880 0.000000 -v -0.058049 0.017000 0.196539 -vn 0.000000 1.000000 0.000000 -v -0.059299 0.017000 0.191139 -vn -0.000000 0.923881 0.382679 -v -0.059299 0.017000 0.191239 -vn -0.110049 0.987815 0.110049 -v -0.058049 0.017000 0.191239 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.191139 -vn -0.000001 0.923881 0.382680 -v -0.063799 0.017000 0.191239 -vn -0.000001 1.000000 0.000000 -v -0.063799 0.017000 0.191139 -vn 0.110049 0.987814 0.110058 -v -0.064549 0.017000 0.191239 -vn 0.000000 1.000000 0.000000 -v -0.069049 0.017000 0.207114 -vn 0.382682 0.923880 0.000000 -v -0.064549 0.017000 0.207114 -vn 0.185741 0.973781 0.131341 -v -0.064549 0.017000 0.201539 -vn -0.000001 0.707107 0.707107 -v -0.063799 0.017000 0.201539 -vn 0.000000 1.000000 0.000000 -v -0.059299 0.017000 0.201039 -vn 0.000000 0.707107 0.707107 -v -0.059299 0.017000 0.201539 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.201039 -vn -0.185742 0.973781 0.131339 -v -0.058049 0.017000 0.201539 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.207114 -vn -0.382683 0.923880 -0.000000 -v -0.058049 0.017000 0.207114 -vn -0.382682 0.923880 0.000000 -v -0.058049 0.017000 0.210164 -vn 0.546965 0.736824 0.397392 -v -0.072181 0.017000 0.204213 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.207114 -vn 0.642994 0.736824 0.208922 -v -0.071414 0.017000 0.202708 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.201039 -vn 0.397393 0.736824 0.546963 -v -0.073375 0.017000 0.205408 -vn 0.208922 0.736823 0.642995 -v -0.074881 0.017000 0.206175 -vn -0.000000 0.736825 0.676083 -v -0.076549 0.017000 0.206439 -vn -0.208922 0.736823 0.642995 -v -0.078218 0.017000 0.206175 -vn -0.282126 0.945448 0.162891 -v -0.083183 0.017000 0.206539 -vn -0.397393 0.736825 0.546963 -v -0.079724 0.017000 0.205408 -vn -0.546965 0.736824 0.397392 -v -0.080918 0.017000 0.204213 -vn 0.397394 0.736823 -0.546964 -v -0.073375 0.017000 0.196670 -vn 0.546963 0.736825 -0.397392 -v -0.072181 0.017000 0.197865 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.196539 -vn 0.642995 0.736824 -0.208921 -v -0.071414 0.017000 0.199370 -vn 0.676085 0.736824 0.000000 -v -0.071149 0.017000 0.201039 -vn -0.162880 0.945450 -0.282125 -v -0.083549 0.017000 0.195905 -vn -0.000004 0.945437 -0.325804 -v -0.084049 0.017000 0.196039 -vn -0.397394 0.736823 -0.546964 -v -0.079724 0.017000 0.196670 -vn -0.130526 0.991445 0.000000 -v -0.087049 0.017000 0.196539 -vn -0.546963 0.736825 -0.397392 -v -0.080918 0.017000 0.197865 -vn 0.208922 0.736825 -0.642993 -v -0.074881 0.017000 0.195903 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.194964 -vn -0.000000 0.736822 -0.676086 -v -0.076549 0.017000 0.195639 -vn -0.208922 0.736825 -0.642993 -v -0.078218 0.017000 0.195903 -vn -0.282144 0.945442 -0.162892 -v -0.083183 0.017000 0.195539 -vn -0.130227 0.990581 -0.042314 -v -0.086854 0.017000 0.191803 -vn -0.135244 0.990581 -0.021421 -v -0.087000 0.017000 0.192413 -vn 0.282125 0.945448 0.162889 -v -0.084915 0.017000 0.194539 -vn -0.133725 0.991004 -0.005386 -v -0.087049 0.017000 0.193039 -vn 0.325773 0.945448 0.000001 -v -0.085049 0.017000 0.195039 -vn -0.130526 0.991445 0.000000 -v -0.087049 0.017000 0.194964 -vn 0.282143 0.945442 -0.162895 -v -0.084915 0.017000 0.195539 -vn 0.162887 0.945447 -0.282131 -v -0.084549 0.017000 0.195905 -vn -0.642995 0.736824 -0.208921 -v -0.081685 0.017000 0.199370 -vn -0.325770 0.945449 -0.000000 -v -0.069549 0.017000 0.209039 -vn -0.282134 0.945446 -0.162887 -v -0.069683 0.017000 0.209539 -vn -0.162895 0.945441 0.282147 -v -0.070049 0.017000 0.208173 -vn -0.282120 0.945451 0.162881 -v -0.069683 0.017000 0.208539 -vn 0.325773 0.945448 0.000001 -v -0.071549 0.017000 0.209039 -vn 0.282125 0.945448 0.162889 -v -0.071415 0.017000 0.208539 -vn 0.162900 0.945441 0.282145 -v -0.071049 0.017000 0.208173 -vn -0.000003 0.945448 0.325774 -v -0.070549 0.017000 0.208039 -vn -0.162880 0.945450 -0.282123 -v -0.070049 0.017000 0.209905 -vn -0.000004 0.945437 -0.325805 -v -0.070549 0.017000 0.210039 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.210164 -vn 0.162885 0.945450 -0.282123 -v -0.071049 0.017000 0.209905 -vn 0.282142 0.945442 -0.162895 -v -0.071415 0.017000 0.209539 -vn -0.282134 0.945446 -0.162887 -v -0.069683 0.017000 0.193539 -vn -0.162885 0.945449 -0.282124 -v -0.070049 0.017000 0.193905 -vn 0.000000 1.000000 0.000000 -v -0.069049 0.017000 0.194964 -vn -0.325770 0.945449 -0.000000 -v -0.069549 0.017000 0.193039 -vn 0.000000 1.000000 0.000000 -v -0.071099 0.017000 0.191139 -vn 0.000000 0.945449 0.325771 -v -0.070549 0.017000 0.192039 -vn -0.000000 1.000000 0.000000 -v -0.069049 0.017000 0.191139 -vn -0.162885 0.945449 0.282126 -v -0.070049 0.017000 0.192173 -vn -0.282116 0.945452 0.162882 -v -0.069683 0.017000 0.192539 -vn 0.382682 0.923880 -0.000000 -v -0.064549 0.017000 0.194964 -vn 0.382682 0.923880 0.000000 -v -0.064549 0.017000 0.196539 -vn 0.282125 0.945448 0.162889 -v -0.071415 0.017000 0.192539 -vn 0.162884 0.945449 0.282126 -v -0.071049 0.017000 0.192173 -vn -0.000000 0.945449 -0.325771 -v -0.070549 0.017000 0.194039 -vn 0.162886 0.945450 -0.282123 -v -0.071049 0.017000 0.193905 -vn 0.282142 0.945442 -0.162895 -v -0.071415 0.017000 0.193539 -vn 0.325773 0.945448 0.000001 -v -0.071549 0.017000 0.193039 -vn 0.630263 0.717284 0.297108 -v -0.066549 0.017000 0.216039 -vn 0.000000 0.923880 0.382683 -v -0.069049 0.017000 0.216039 -vn 0.000000 0.923880 0.382683 -v -0.071099 0.017000 0.216039 -vn -0.630263 0.717284 0.297108 -v -0.073049 0.017000 0.216039 -vn 0.630263 0.717284 0.297108 -v -0.050549 0.017000 0.216039 -vn 0.000000 0.923880 0.382683 -v -0.053299 0.017000 0.216039 -vn -0.630263 0.717284 0.297108 -v -0.057049 0.017000 0.216039 -vn 0.630263 0.717284 0.297108 -v -0.042549 0.017000 0.216039 -vn 0.000000 0.923880 0.382683 -v -0.042924 0.017000 0.216039 -vn 0.000000 0.923880 0.382683 -v -0.044299 0.017000 0.216039 -vn -0.630263 0.717284 0.297108 -v -0.049049 0.017000 0.216039 -vn 0.000000 1.000000 0.000000 -v -0.059299 0.017000 0.210939 -vn -0.552286 0.770263 0.318865 -v -0.060717 0.017000 0.213914 -vn -0.637728 0.770261 -0.000000 -v -0.060549 0.017000 0.214539 -vn -0.552291 0.770261 -0.318862 -v -0.060717 0.017000 0.215164 -vn -0.318861 0.770265 -0.552286 -v -0.061174 0.017000 0.215622 -vn 0.000000 0.770258 -0.637732 -v -0.061799 0.017000 0.215789 -vn 0.318862 0.770265 -0.552285 -v -0.062424 0.017000 0.215622 -vn 0.552287 0.770263 0.318864 -v -0.062882 0.017000 0.213914 -vn 0.637728 0.770261 0.000000 -v -0.063049 0.017000 0.214539 -vn 0.552292 0.770261 -0.318861 -v -0.062882 0.017000 0.215164 -vn 0.318866 0.770260 0.552289 -v -0.062424 0.017000 0.213457 -vn 0.000000 0.770264 0.637725 -v -0.061799 0.017000 0.213289 -vn -0.318866 0.770260 0.552291 -v -0.061174 0.017000 0.213457 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.210164 -vn -0.325771 0.945449 -0.000001 -v -0.054049 0.017000 0.209039 -vn -0.282139 0.945444 -0.162889 -v -0.054183 0.017000 0.209539 -vn 0.282137 0.945445 -0.162890 -v -0.055915 0.017000 0.209539 -vn 0.325780 0.945446 -0.000001 -v -0.056049 0.017000 0.209039 -vn -0.162880 0.945450 -0.282124 -v -0.054549 0.017000 0.209905 -vn -0.000004 0.945437 -0.325805 -v -0.055049 0.017000 0.210039 -vn 0.162885 0.945450 -0.282123 -v -0.055549 0.017000 0.209905 -vn -0.110049 0.987815 -0.110049 -v -0.058049 0.017000 0.210839 -vn 0.000000 0.923881 -0.382679 -v -0.059299 0.017000 0.210839 -vn -0.000001 0.923881 -0.382680 -v -0.063799 0.017000 0.210839 -vn 0.282120 0.945450 0.162886 -v -0.055915 0.017000 0.208539 -vn 0.162901 0.945441 0.282144 -v -0.055549 0.017000 0.208173 -vn -0.000003 0.945448 0.325774 -v -0.055049 0.017000 0.208039 -vn -0.282124 0.945449 0.162885 -v -0.054183 0.017000 0.208539 -vn -0.162895 0.945441 0.282147 -v -0.054549 0.017000 0.208173 -vn 0.000000 1.000000 0.000000 -v -0.053299 0.017000 0.194964 -vn 0.000000 1.000000 0.000000 -v -0.057049 0.017000 0.196539 -vn -0.185742 0.973781 -0.131339 -v -0.058049 0.017000 0.200539 -vn 0.000000 0.707107 -0.707107 -v -0.059299 0.017000 0.200539 -vn -0.000001 0.707107 -0.707107 -v -0.063799 0.017000 0.200539 -vn -0.325771 0.945449 -0.000001 -v -0.054049 0.017000 0.193039 -vn -0.282139 0.945444 -0.162889 -v -0.054183 0.017000 0.193539 -vn -0.282121 0.945450 0.162886 -v -0.054183 0.017000 0.192539 -vn -0.707107 0.707107 0.000000 -v -0.051049 0.017000 0.196539 -vn 0.162886 0.945450 -0.282123 -v -0.055549 0.017000 0.193905 -vn -0.000000 0.945449 -0.325771 -v -0.055049 0.017000 0.194039 -vn -0.162885 0.945449 -0.282125 -v -0.054549 0.017000 0.193905 -vn 0.282137 0.945445 -0.162890 -v -0.055915 0.017000 0.193539 -vn 0.325780 0.945446 -0.000001 -v -0.056049 0.017000 0.193039 -vn 0.282120 0.945450 0.162886 -v -0.055915 0.017000 0.192539 -vn 0.162884 0.945449 0.282125 -v -0.055549 0.017000 0.192173 -vn 0.000000 0.945449 0.325771 -v -0.055049 0.017000 0.192039 -vn -0.162885 0.945449 0.282126 -v -0.054549 0.017000 0.192173 -vn -0.552287 0.770262 -0.318866 -v -0.039467 0.017000 0.193664 -vn -0.637727 0.770263 0.000000 -v -0.039299 0.017000 0.193039 -vn 0.382683 0.923880 0.000000 -v -0.039049 0.017000 0.191139 -vn -0.552292 0.770260 0.318863 -v -0.039467 0.017000 0.192414 -vn -0.318861 0.770265 0.552285 -v -0.039924 0.017000 0.191957 -vn 0.318866 0.770260 -0.552289 -v -0.041174 0.017000 0.194122 -vn 0.000000 0.770264 -0.637725 -v -0.040549 0.017000 0.194289 -vn -0.318866 0.770260 -0.552290 -v -0.039924 0.017000 0.194122 -vn 0.318862 0.770265 0.552285 -v -0.041174 0.017000 0.191957 -vn 0.000001 0.770258 0.637732 -v -0.040549 0.017000 0.191789 -vn 0.552287 0.770262 -0.318866 -v -0.041632 0.017000 0.193664 -vn 0.637727 0.770263 -0.000000 -v -0.041799 0.017000 0.193039 -vn 0.552292 0.770260 0.318863 -v -0.041632 0.017000 0.192414 -vn -0.062165 0.990581 -0.122007 -v -0.084865 0.017000 0.189475 -vn 0.000000 0.770258 -0.637732 -v -0.061799 0.017000 0.188789 -vn 0.318861 0.770265 -0.552286 -v -0.062424 0.017000 0.188622 -vn -0.552291 0.770261 -0.318862 -v -0.060717 0.017000 0.188164 -vn -0.318861 0.770265 -0.552286 -v -0.061174 0.017000 0.188622 -vn 0.552291 0.770261 -0.318862 -v -0.062882 0.017000 0.188164 -vn 0.637728 0.770261 0.000000 -v -0.063049 0.017000 0.187539 -vn 0.552286 0.770263 0.318865 -v -0.062882 0.017000 0.186914 -vn 0.318866 0.770260 0.552291 -v -0.062424 0.017000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.061799 0.017000 0.186289 -vn -0.318866 0.770260 0.552291 -v -0.061174 0.017000 0.186457 -vn 0.552286 0.770263 0.318865 -v -0.046882 0.017000 0.186914 -vn -0.630262 0.717284 -0.297108 -v -0.049049 0.017000 0.186039 -vn 0.637728 0.770261 0.000000 -v -0.047049 0.017000 0.187539 -vn 0.552291 0.770261 -0.318862 -v -0.046882 0.017000 0.188164 -vn 0.318861 0.770265 -0.552287 -v -0.046424 0.017000 0.188622 -vn 0.318866 0.770260 0.552291 -v -0.046424 0.017000 0.186457 -vn 0.000000 0.770264 0.637725 -v -0.045799 0.017000 0.186289 -vn 0.000000 0.923880 -0.382683 -v -0.044299 0.017000 0.186039 -vn -0.318866 0.770260 0.552291 -v -0.045174 0.017000 0.186457 -vn -0.552286 0.770262 0.318867 -v -0.044717 0.017000 0.186914 -vn -0.637727 0.770263 0.000000 -v -0.044549 0.017000 0.187539 -vn -0.552291 0.770260 -0.318864 -v -0.044717 0.017000 0.188164 -vn 0.000000 1.000000 0.000000 -v -0.044299 0.017000 0.189914 -vn -0.318861 0.770265 -0.552286 -v -0.045174 0.017000 0.188622 -vn -0.000000 0.770258 -0.637732 -v -0.045799 0.017000 0.188789 -vn 0.318856 0.770265 -0.552289 -v -0.044199 0.017000 0.191079 -vn 0.301511 -0.301511 0.904534 -v -0.071799 0.015000 0.217039 -vn 0.318861 -0.770265 -0.552286 -v -0.070424 0.015000 0.215622 -vn -0.000000 -0.770258 -0.637732 -v -0.069799 0.015000 0.215789 -vn 0.000001 -0.609994 0.792406 -v -0.069799 0.015000 0.212230 -vn 0.000000 -0.770264 0.637725 -v -0.069799 0.015000 0.213289 -vn 0.318866 -0.770260 0.552291 -v -0.070424 0.015000 0.213457 -vn -0.301511 -0.301512 0.904534 -v -0.067799 0.015000 0.217039 -vn -0.318861 -0.770265 -0.552286 -v -0.069174 0.015000 0.215622 -vn -0.552291 -0.770261 -0.318862 -v -0.068717 0.015000 0.215164 -vn -0.686244 -0.609994 0.396202 -v -0.067799 0.015000 0.213384 -vn 0.686244 -0.609994 0.396202 -v -0.071799 0.015000 0.213384 -vn 0.552286 -0.770263 0.318865 -v -0.070882 0.015000 0.213914 -vn 0.637728 -0.770261 -0.000000 -v -0.071049 0.015000 0.214539 -vn 0.552291 -0.770261 -0.318862 -v -0.070882 0.015000 0.215164 -vn -0.637729 -0.770261 0.000000 -v -0.068549 0.015000 0.214539 -vn -0.552286 -0.770263 0.318865 -v -0.068717 0.015000 0.213914 -vn -0.318865 -0.770260 0.552291 -v -0.069174 0.015000 0.213457 -vn -0.686244 -0.609994 0.396202 -v -0.059799 0.015000 0.213384 -vn -0.552286 -0.770263 0.318865 -v -0.060717 0.015000 0.213914 -vn -0.000001 -0.609994 0.792406 -v -0.061799 0.015000 0.212230 -vn -0.318866 -0.770260 0.552291 -v -0.061174 0.015000 0.213457 -vn 0.686244 -0.609994 0.396202 -v -0.063799 0.015000 0.213384 -vn 0.637728 -0.770261 -0.000000 -v -0.063049 0.015000 0.214539 -vn 0.301511 -0.301511 0.904534 -v -0.063799 0.015000 0.217039 -vn 0.552292 -0.770261 -0.318861 -v -0.062882 0.015000 0.215164 -vn 0.318862 -0.770265 -0.552285 -v -0.062424 0.015000 0.215622 -vn 0.000000 -0.770258 -0.637732 -v -0.061799 0.015000 0.215789 -vn -0.301511 -0.301511 0.904534 -v -0.059799 0.015000 0.217039 -vn -0.318861 -0.770265 -0.552286 -v -0.061174 0.015000 0.215622 -vn -0.552291 -0.770261 -0.318862 -v -0.060717 0.015000 0.215164 -vn -0.637728 -0.770261 0.000000 -v -0.060549 0.015000 0.214539 -vn 0.000000 -0.770264 0.637725 -v -0.061799 0.015000 0.213289 -vn 0.318866 -0.770260 0.552289 -v -0.062424 0.015000 0.213457 -vn 0.552287 -0.770263 0.318864 -v -0.062882 0.015000 0.213914 -vn 0.686244 -0.609994 0.396202 -v -0.055799 0.015000 0.213384 -vn 0.637729 -0.770261 -0.000000 -v -0.055049 0.015000 0.214539 -vn 0.301511 -0.301511 0.904534 -v -0.055799 0.015000 0.217039 -vn 0.552291 -0.770261 -0.318862 -v -0.054882 0.015000 0.215164 -vn -0.000000 -0.609994 0.792406 -v -0.053799 0.015000 0.212230 -vn 0.318866 -0.770260 0.552291 -v -0.054424 0.015000 0.213457 -vn 0.552286 -0.770263 0.318865 -v -0.054882 0.015000 0.213914 -vn 0.318861 -0.770265 -0.552286 -v -0.054424 0.015000 0.215622 -vn 0.000001 -0.770258 -0.637732 -v -0.053799 0.015000 0.215789 -vn -0.301511 -0.301511 0.904534 -v -0.051799 0.015000 0.217039 -vn -0.637727 -0.770263 -0.000000 -v -0.052549 0.015000 0.214539 -vn -0.686244 -0.609995 0.396202 -v -0.051799 0.015000 0.213384 -vn -0.552292 -0.770260 -0.318863 -v -0.052717 0.015000 0.215164 -vn -0.318861 -0.770265 -0.552286 -v -0.053174 0.015000 0.215622 -vn -0.552287 -0.770262 0.318866 -v -0.052717 0.015000 0.213914 -vn -0.318866 -0.770260 0.552290 -v -0.053174 0.015000 0.213457 -vn 0.000001 -0.770264 0.637725 -v -0.053799 0.015000 0.213289 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.211764 -vn -0.301511 -0.904534 -0.301511 -v -0.049049 0.012000 0.186539 -vn -0.630263 -0.717284 -0.297108 -v -0.049049 0.012000 0.186039 -vn 0.516596 -0.741788 -0.427644 -v -0.047799 0.012000 0.186039 -vn 0.301511 -0.904534 0.301511 -v -0.058549 0.012000 0.215539 -vn 0.630263 -0.717284 0.297108 -v -0.058549 0.012000 0.216039 -vn -0.516597 -0.741787 0.427644 -v -0.059799 0.012000 0.216039 -vn 0.516598 -0.741787 0.427643 -v -0.071799 0.012000 0.216039 -vn -0.630263 -0.717284 0.297108 -v -0.073049 0.012000 0.216039 -vn 0.279912 -0.846479 0.452905 -v -0.070799 0.012000 0.214039 -vn -0.301511 -0.904534 0.301511 -v -0.073049 0.012000 0.215539 -vn 0.000000 -0.707107 0.707107 -v -0.073374 0.012000 0.215539 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.211764 -vn -0.279911 -0.846479 0.452906 -v -0.068799 0.012000 0.214039 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.211764 -vn -0.516597 -0.741787 0.427644 -v -0.067799 0.012000 0.216039 -vn 0.301511 -0.904534 0.301511 -v -0.066549 0.012000 0.215539 -vn 0.630263 -0.717284 0.297108 -v -0.066549 0.012000 0.216039 -vn 0.000000 -0.923880 0.382683 -v -0.066599 0.012000 0.216039 -vn 0.279911 -0.846478 0.452906 -v -0.062799 0.012000 0.214039 -vn 0.516597 -0.741787 0.427644 -v -0.063799 0.012000 0.216039 -vn -0.630263 -0.717284 0.297108 -v -0.065049 0.012000 0.216039 -vn 0.000000 -1.000000 -0.000000 -v -0.057499 0.012000 0.211764 -vn -0.279911 -0.846478 0.452906 -v -0.060799 0.012000 0.214039 -vn -0.301511 -0.904534 0.301511 -v -0.065049 0.012000 0.215539 -vn 0.279912 -0.846479 0.452906 -v -0.054799 0.012000 0.214039 -vn 0.516597 -0.741787 0.427644 -v -0.055799 0.012000 0.216039 -vn -0.630263 -0.717284 0.297108 -v -0.057049 0.012000 0.216039 -vn 0.000000 -1.000000 0.000000 -v -0.049299 0.012000 0.211764 -vn 0.000000 -0.707107 0.707107 -v -0.049299 0.012000 0.215539 -vn 0.301511 -0.904534 0.301511 -v -0.050549 0.012000 0.215539 -vn -0.279911 -0.846479 0.452906 -v -0.052799 0.012000 0.214039 -vn 0.000000 -0.707107 0.707107 -v -0.057499 0.012000 0.215539 -vn -0.301511 -0.904534 0.301511 -v -0.057049 0.012000 0.215539 -vn -0.301511 -0.904534 0.301511 -v -0.049049 0.012000 0.215539 -vn -0.279912 -0.846479 0.452906 -v -0.044799 0.012000 0.214039 -vn 0.279911 -0.846478 0.452906 -v -0.046799 0.012000 0.214039 -vn 0.188573 -0.976005 -0.108876 -v -0.044329 0.012000 0.211889 -vn 0.301511 -0.904534 0.301511 -v -0.041049 0.012000 0.214039 -vn 0.577350 -0.577350 0.577350 -v -0.041049 0.012000 0.215539 -vn 0.301511 -0.904534 0.301511 -v -0.042549 0.012000 0.215539 -vn 0.108878 -0.976004 -0.188580 -v -0.043999 0.012000 0.212219 -vn -0.516597 -0.741787 0.427643 -v -0.043799 0.012000 0.216039 -vn 0.630263 -0.717284 0.297108 -v -0.042549 0.012000 0.216039 -vn -0.188578 -0.976004 -0.108878 -v -0.042770 0.012000 0.211889 -vn -0.108878 -0.976003 -0.188581 -v -0.043099 0.012000 0.212219 -vn 0.000000 -0.976004 -0.217755 -v -0.043549 0.012000 0.212339 -vn 0.577350 -0.577350 0.577351 -v -0.039549 0.012000 0.214039 -vn 0.000000 -0.707107 0.707107 -v -0.040849 0.012000 0.214039 -vn 0.301511 -0.904534 0.301512 -v -0.039549 0.012000 0.212289 -vn 0.000000 -1.000000 0.000000 -v -0.040849 0.012000 0.211764 -vn 0.297109 -0.717283 0.630262 -v -0.039049 0.012000 0.212289 -vn 0.382684 -0.923879 0.000000 -v -0.039049 0.012000 0.211764 -vn 0.297109 -0.717283 -0.630262 -v -0.039049 0.012000 0.205789 -vn 0.427644 -0.741787 0.516597 -v -0.039049 0.012000 0.207039 -vn 0.301511 -0.904534 -0.301511 -v -0.039549 0.012000 0.205789 -vn 0.452906 -0.846478 0.279911 -v -0.041049 0.012000 0.208039 -vn 0.707107 -0.707107 0.000000 -v -0.039549 0.012000 0.204214 -vn 0.000000 -1.000000 0.000000 -v -0.040849 0.012000 0.204214 -vn 0.707107 -0.707107 0.000000 -v -0.039549 0.012000 0.201039 -vn 0.000000 -1.000000 0.000000 -v -0.040849 0.012000 0.201039 -vn 0.707107 -0.707107 0.000000 -v -0.039549 0.012000 0.197864 -vn 0.000000 -1.000000 0.000000 -v -0.040849 0.012000 0.197864 -vn 0.301511 -0.904534 0.301511 -v -0.039549 0.012000 0.196289 -vn 0.452906 -0.846478 -0.279911 -v -0.041049 0.012000 0.194039 -vn 0.297109 -0.717283 0.630262 -v -0.039049 0.012000 0.196289 -vn 0.427644 -0.741787 -0.516596 -v -0.039049 0.012000 0.195039 -vn 0.452906 -0.846478 0.279911 -v -0.041049 0.012000 0.192039 -vn 0.000000 -1.000000 0.000000 -v -0.040849 0.012000 0.191839 -vn 0.427644 -0.741787 0.516597 -v -0.039049 0.012000 0.191039 -vn 0.301511 -0.904534 -0.301511 -v -0.039549 0.012000 0.189789 -vn 0.297109 -0.717283 -0.630262 -v -0.039049 0.012000 0.189789 -vn 0.279911 -0.846478 -0.452907 -v -0.046799 0.012000 0.188039 -vn 0.000000 -1.000000 -0.000000 -v -0.049299 0.012000 0.191839 -vn 0.000000 -0.707107 -0.707107 -v -0.049299 0.012000 0.186539 -vn -0.217756 -0.976003 0.000000 -v -0.042649 0.012000 0.190639 -vn -0.188593 -0.976001 0.108880 -v -0.042770 0.012000 0.190189 -vn 0.301511 -0.904534 -0.301511 -v -0.042549 0.012000 0.186539 -vn -0.108874 -0.976004 0.188580 -v -0.043099 0.012000 0.189860 -vn -0.000003 -0.975997 0.217784 -v -0.043549 0.012000 0.189739 -vn 0.188573 -0.976005 -0.108876 -v -0.044329 0.012000 0.191089 -vn 0.108878 -0.976004 -0.188580 -v -0.043999 0.012000 0.191419 -vn 0.000000 -0.976004 -0.217755 -v -0.043549 0.012000 0.191539 -vn -0.108878 -0.976003 -0.188581 -v -0.043099 0.012000 0.191419 -vn -0.188578 -0.976004 -0.108878 -v -0.042770 0.012000 0.191089 -vn 0.630263 -0.717284 -0.297108 -v -0.042549 0.012000 0.186039 -vn -0.516597 -0.741788 -0.427644 -v -0.043799 0.012000 0.186039 -vn -0.279911 -0.846478 -0.452906 -v -0.044799 0.012000 0.188039 -vn 0.108878 -0.976004 0.188579 -v -0.043999 0.012000 0.189860 -vn 0.188588 -0.976002 0.108878 -v -0.044329 0.012000 0.190189 -vn 0.217756 -0.976003 -0.000000 -v -0.044449 0.012000 0.190639 -vn 0.577350 -0.577350 -0.577350 -v -0.041049 0.012000 0.186539 -vn 0.301511 -0.904534 -0.301511 -v -0.041049 0.012000 0.188039 -vn 0.000000 -0.707107 -0.707107 -v -0.040849 0.012000 0.188039 -vn 0.577350 -0.577350 -0.577350 -v -0.039549 0.012000 0.188039 -vn 0.000000 -0.707107 -0.707107 -v -0.057499 0.012000 0.186539 -vn -0.301511 -0.904534 -0.301511 -v -0.057049 0.012000 0.186539 -vn -0.516597 -0.741788 -0.427644 -v -0.051799 0.012000 0.186039 -vn 0.630263 -0.717284 -0.297108 -v -0.050549 0.012000 0.186039 -vn -0.279911 -0.846478 -0.452907 -v -0.052799 0.012000 0.188039 -vn 0.301511 -0.904534 -0.301511 -v -0.050549 0.012000 0.186539 -vn 0.279909 -0.846481 -0.452904 -v -0.054799 0.012000 0.188039 -vn 0.516596 -0.741788 -0.427644 -v -0.055799 0.012000 0.186039 -vn -0.630263 -0.717284 -0.297108 -v -0.057049 0.012000 0.186039 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.193314 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.191839 -vn 0.000000 -1.000000 -0.000000 -v -0.057499 0.012000 0.191839 -vn -0.301511 -0.904534 0.301511 -v -0.059049 0.012000 0.191539 -vn 0.301511 -0.904534 -0.301511 -v -0.066549 0.012000 0.186539 -vn -0.301511 -0.904534 -0.301511 -v -0.065049 0.012000 0.186539 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.191839 -vn 0.000000 -0.923880 -0.382683 -v -0.066599 0.012000 0.186039 -vn 0.630263 -0.717284 -0.297108 -v -0.066549 0.012000 0.186039 -vn -0.516596 -0.741788 -0.427644 -v -0.059799 0.012000 0.186039 -vn 0.630263 -0.717284 -0.297108 -v -0.058549 0.012000 0.186039 -vn -0.279911 -0.846478 -0.452907 -v -0.060799 0.012000 0.188039 -vn 0.301511 -0.904534 -0.301511 -v -0.058549 0.012000 0.186539 -vn -0.630263 -0.717284 -0.297108 -v -0.065049 0.012000 0.186039 -vn 0.516596 -0.741788 -0.427644 -v -0.063799 0.012000 0.186039 -vn 0.279911 -0.846478 -0.452907 -v -0.062799 0.012000 0.188039 -vn 0.000000 -0.707107 -0.707107 -v -0.073374 0.012000 0.186539 -vn -0.301511 -0.904534 -0.301511 -v -0.073049 0.012000 0.186539 -vn -0.516596 -0.741788 -0.427644 -v -0.067799 0.012000 0.186039 -vn -0.279911 -0.846478 -0.452907 -v -0.068799 0.012000 0.188039 -vn 0.279911 -0.846479 -0.452906 -v -0.070799 0.012000 0.188039 -vn 0.516597 -0.741787 -0.427644 -v -0.071799 0.012000 0.186039 -vn -0.630263 -0.717284 -0.297108 -v -0.073049 0.012000 0.186039 -vn 0.000000 -0.707107 -0.707107 -v -0.080474 0.012000 0.188039 -vn -0.301511 -0.904534 -0.301511 -v -0.074549 0.012000 0.188039 -vn 0.000000 -1.000000 -0.000000 -v -0.073374 0.012000 0.191839 -vn -0.108891 -0.975999 0.188600 -v -0.085099 0.012000 0.191010 -vn 0.000002 -0.976003 0.217757 -v -0.085549 0.012000 0.190889 -vn 0.108888 -0.975999 0.188599 -v -0.085999 0.012000 0.191010 -vn 0.188597 -0.976000 0.108886 -v -0.086329 0.012000 0.191339 -vn 0.217756 -0.976003 -0.000001 -v -0.086449 0.012000 0.191789 -vn 0.188583 -0.976003 -0.108881 -v -0.086329 0.012000 0.192239 -vn -0.707107 -0.707107 0.000000 -v -0.088049 0.012000 0.193314 -vn 0.108877 -0.976004 -0.188580 -v -0.085999 0.012000 0.192569 -vn 0.000000 -0.976004 -0.217755 -v -0.085549 0.012000 0.192689 -vn -0.108878 -0.976004 -0.188581 -v -0.085099 0.012000 0.192569 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.193314 -vn -0.188583 -0.976003 -0.108882 -v -0.084770 0.012000 0.192239 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.191839 -vn -0.217756 -0.976003 0.000001 -v -0.084649 0.012000 0.191789 -vn -0.188596 -0.976000 0.108884 -v -0.084770 0.012000 0.191339 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.210239 -vn -0.217756 -0.976003 0.000001 -v -0.084649 0.012000 0.210289 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.208764 -vn -0.188596 -0.976000 0.108884 -v -0.084770 0.012000 0.209839 -vn -0.108891 -0.975999 0.188600 -v -0.085099 0.012000 0.209510 -vn 0.000002 -0.976003 0.217757 -v -0.085549 0.012000 0.209389 -vn 0.108888 -0.975999 0.188599 -v -0.085999 0.012000 0.209510 -vn -0.707107 -0.707107 0.000000 -v -0.088049 0.012000 0.208764 -vn 0.188597 -0.976000 0.108886 -v -0.086329 0.012000 0.209839 -vn 0.217756 -0.976003 -0.000001 -v -0.086449 0.012000 0.210289 -vn 0.188583 -0.976003 -0.108881 -v -0.086329 0.012000 0.210739 -vn 0.108877 -0.976004 -0.188580 -v -0.085999 0.012000 0.211069 -vn 0.000000 -0.976004 -0.217755 -v -0.085549 0.012000 0.211189 -vn -0.108878 -0.976004 -0.188581 -v -0.085099 0.012000 0.211069 -vn -0.188583 -0.976003 -0.108882 -v -0.084770 0.012000 0.210739 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.211764 -vn -0.577350 -0.577350 0.577350 -v -0.074549 0.012000 0.215539 -vn -0.301511 -0.904534 0.301511 -v -0.074549 0.012000 0.214039 -vn 0.000000 -0.707107 0.707107 -v -0.080474 0.012000 0.214039 -vn 0.301511 -0.904534 -0.301511 -v -0.063549 0.012000 0.200539 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.201039 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.197864 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.197864 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.194039 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.194039 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.193314 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.193314 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.191839 -vn 0.000000 -1.000000 0.000000 -v -0.057499 0.012000 0.201039 -vn -0.301511 -0.904534 -0.301511 -v -0.059049 0.012000 0.200539 -vn 0.000000 -1.000000 0.000000 -v -0.057499 0.012000 0.197864 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.197864 -vn 0.000000 -1.000000 0.000000 -v -0.057499 0.012000 0.194039 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.194039 -vn 0.000000 -1.000000 0.000000 -v -0.057499 0.012000 0.193314 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.210239 -vn 0.000000 -1.000000 0.000000 -v -0.057499 0.012000 0.210239 -vn -0.301511 -0.904534 -0.301511 -v -0.059049 0.012000 0.210539 -vn 0.301511 -0.904534 -0.301511 -v -0.063549 0.012000 0.210539 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.210239 -vn 0.000000 -1.000000 0.000000 -v -0.057499 0.012000 0.204214 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.204214 -vn -0.301511 -0.904534 0.301511 -v -0.059049 0.012000 0.201539 -vn 0.301511 -0.904534 0.301511 -v -0.063549 0.012000 0.201539 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.208764 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.208764 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.208039 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.208039 -vn 0.707107 -0.707107 0.000000 -v -0.063549 0.012000 0.204214 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.204214 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.208039 -vn 0.000000 -1.000000 -0.000000 -v -0.057499 0.012000 0.208039 -vn -0.707107 -0.707107 0.000000 -v -0.059049 0.012000 0.208764 -vn 0.000000 -1.000000 0.000000 -v -0.057499 0.012000 0.208764 -vn -0.188591 -0.976001 0.108881 -v -0.042770 0.012000 0.210989 -vn 0.000000 -1.000000 0.000000 -v -0.040849 0.012000 0.210239 -vn -0.217756 -0.976003 0.000000 -v -0.042649 0.012000 0.211439 -vn 0.000000 -1.000000 0.000000 -v -0.049299 0.012000 0.210239 -vn 0.188585 -0.976003 0.108879 -v -0.044329 0.012000 0.210989 -vn 0.516597 -0.741787 0.427644 -v -0.047799 0.012000 0.216039 -vn -0.630263 -0.717284 0.297108 -v -0.049049 0.012000 0.216039 -vn 0.217756 -0.976003 -0.000000 -v -0.044449 0.012000 0.211439 -vn -0.108877 -0.976003 0.188583 -v -0.043099 0.012000 0.210660 -vn -0.000000 -0.976004 0.217755 -v -0.043549 0.012000 0.210539 -vn 0.108878 -0.976003 0.188581 -v -0.043999 0.012000 0.210660 -vn 0.000001 -0.770264 -0.637725 -v -0.076549 0.012000 0.202289 -vn -0.318866 -0.770261 -0.552288 -v -0.075924 0.012000 0.202122 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.204214 -vn -0.552288 -0.770261 -0.318867 -v -0.075467 0.012000 0.201664 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.201039 -vn -0.637725 -0.770264 0.000000 -v -0.075299 0.012000 0.201039 -vn 0.000000 -1.000000 -0.000000 -v -0.073374 0.012000 0.197864 -vn -0.552293 -0.770259 0.318864 -v -0.075467 0.012000 0.200414 -vn -0.318861 -0.770266 0.552284 -v -0.075924 0.012000 0.199957 -vn 0.000001 -0.770258 0.637732 -v -0.076549 0.012000 0.199789 -vn 0.318862 -0.770266 0.552284 -v -0.077174 0.012000 0.199957 -vn 0.000000 -1.000000 -0.000000 -v -0.080474 0.012000 0.197864 -vn 0.552293 -0.770259 0.318864 -v -0.077632 0.012000 0.200414 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.201039 -vn 0.637725 -0.770264 0.000000 -v -0.077799 0.012000 0.201039 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.204214 -vn 0.552288 -0.770261 -0.318867 -v -0.077632 0.012000 0.201664 -vn 0.318867 -0.770261 -0.552288 -v -0.077174 0.012000 0.202122 -vn -0.000003 -0.770263 -0.637726 -v -0.084049 0.012000 0.207939 -vn -0.318865 -0.770259 -0.552292 -v -0.083599 0.012000 0.207819 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.208039 -vn -0.552285 -0.770264 -0.318863 -v -0.083270 0.012000 0.207489 -vn -0.637731 -0.770259 -0.000000 -v -0.083149 0.012000 0.207039 -vn -0.552285 -0.770264 0.318863 -v -0.083270 0.012000 0.206589 -vn -0.000003 -0.770263 0.637726 -v -0.084049 0.012000 0.206139 -vn 0.318865 -0.770262 0.552288 -v -0.084499 0.012000 0.206260 -vn -0.707107 -0.707107 0.000000 -v -0.088049 0.012000 0.204214 -vn 0.552289 -0.770263 0.318861 -v -0.084829 0.012000 0.206589 -vn -0.707107 -0.707107 0.000000 -v -0.088049 0.012000 0.208039 -vn 0.637731 -0.770259 0.000000 -v -0.084949 0.012000 0.207039 -vn 0.552289 -0.770263 -0.318861 -v -0.084829 0.012000 0.207489 -vn 0.552285 -0.770264 -0.318863 -v -0.071329 0.012000 0.209489 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.210239 -vn 0.637731 -0.770259 0.000000 -v -0.071449 0.012000 0.209039 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.208764 -vn 0.552292 -0.770262 0.318858 -v -0.071329 0.012000 0.208589 -vn -0.552288 -0.770261 -0.318866 -v -0.069770 0.012000 0.209489 -vn 0.000000 -1.000000 0.000000 -v -0.066599 0.012000 0.210239 -vn 0.318864 -0.770260 -0.552292 -v -0.070999 0.012000 0.209819 -vn -0.000000 -0.770263 -0.637726 -v -0.070549 0.012000 0.209939 -vn -0.318866 -0.770261 -0.552288 -v -0.070099 0.012000 0.209819 -vn -0.637726 -0.770263 0.000000 -v -0.069649 0.012000 0.209039 -vn -0.552295 -0.770258 0.318862 -v -0.069770 0.012000 0.208589 -vn -0.318860 -0.770268 0.552283 -v -0.070099 0.012000 0.208260 -vn 0.318857 -0.770266 0.552286 -v -0.070999 0.012000 0.208260 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.208039 -vn 0.000000 -0.770256 0.637735 -v -0.070549 0.012000 0.208139 -vn 0.552287 -0.770263 -0.318865 -v -0.055829 0.012000 0.209489 -vn 0.318865 -0.770260 -0.552290 -v -0.055499 0.012000 0.209819 -vn 0.000000 -0.770264 -0.637725 -v -0.055049 0.012000 0.209939 -vn -0.318865 -0.770260 -0.552290 -v -0.054599 0.012000 0.209819 -vn -0.552287 -0.770263 -0.318864 -v -0.054270 0.012000 0.209489 -vn 0.000000 -1.000000 -0.000000 -v -0.049299 0.012000 0.208764 -vn 0.637728 -0.770261 0.000000 -v -0.055949 0.012000 0.209039 -vn -0.637728 -0.770261 -0.000000 -v -0.054149 0.012000 0.209039 -vn -0.552293 -0.770260 0.318860 -v -0.054270 0.012000 0.208589 -vn 0.000000 -1.000000 -0.000000 -v -0.049299 0.012000 0.208039 -vn -0.318859 -0.770267 0.552284 -v -0.054599 0.012000 0.208260 -vn 0.000000 -0.770257 0.637734 -v -0.055049 0.012000 0.208139 -vn 0.318859 -0.770267 0.552284 -v -0.055499 0.012000 0.208260 -vn 0.552294 -0.770260 0.318860 -v -0.055829 0.012000 0.208589 -vn -0.000003 -0.770263 -0.637726 -v -0.084049 0.012000 0.195939 -vn -0.318865 -0.770259 -0.552292 -v -0.083599 0.012000 0.195819 -vn -0.552285 -0.770265 -0.318863 -v -0.083270 0.012000 0.195489 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.194039 -vn -0.637731 -0.770259 -0.000000 -v -0.083149 0.012000 0.195039 -vn -0.552292 -0.770262 0.318858 -v -0.083270 0.012000 0.194589 -vn -0.000003 -0.770256 0.637735 -v -0.084049 0.012000 0.194139 -vn 0.318858 -0.770268 0.552283 -v -0.084499 0.012000 0.194260 -vn -0.707107 -0.707107 0.000000 -v -0.088049 0.012000 0.194039 -vn 0.552295 -0.770260 0.318856 -v -0.084829 0.012000 0.194589 -vn 0.637731 -0.770259 0.000000 -v -0.084949 0.012000 0.195039 -vn -0.707107 -0.707107 0.000000 -v -0.088049 0.012000 0.197864 -vn 0.552289 -0.770263 -0.318861 -v -0.084829 0.012000 0.195489 -vn -0.552287 -0.770263 0.318864 -v -0.054270 0.012000 0.192589 -vn -0.318865 -0.770261 0.552290 -v -0.054599 0.012000 0.192260 -vn 0.000000 -0.770264 0.637725 -v -0.055049 0.012000 0.192139 -vn 0.318865 -0.770260 0.552290 -v -0.055499 0.012000 0.192260 -vn 0.552287 -0.770263 0.318864 -v -0.055829 0.012000 0.192589 -vn -0.637728 -0.770262 -0.000000 -v -0.054149 0.012000 0.193039 -vn 0.000000 -1.000000 0.000000 -v -0.049299 0.012000 0.193314 -vn -0.552287 -0.770263 -0.318864 -v -0.054270 0.012000 0.193489 -vn 0.637728 -0.770261 0.000000 -v -0.055949 0.012000 0.193039 -vn 0.552287 -0.770263 -0.318865 -v -0.055829 0.012000 0.193489 -vn 0.318865 -0.770260 -0.552290 -v -0.055499 0.012000 0.193819 -vn -0.318865 -0.770260 -0.552290 -v -0.054599 0.012000 0.193819 -vn 0.000000 -1.000000 0.000000 -v -0.049299 0.012000 0.194039 -vn 0.000000 -0.770264 -0.637725 -v -0.055049 0.012000 0.193939 -vn -0.637726 -0.770263 0.000000 -v -0.069649 0.012000 0.193039 -vn -0.552288 -0.770261 0.318866 -v -0.069770 0.012000 0.192589 -vn -0.318866 -0.770261 0.552288 -v -0.070099 0.012000 0.192260 -vn -0.552288 -0.770261 -0.318866 -v -0.069770 0.012000 0.193489 -vn 0.301511 -0.904534 0.301511 -v -0.063549 0.012000 0.191539 -vn 0.000000 -0.770263 0.637726 -v -0.070549 0.012000 0.192139 -vn 0.318864 -0.770260 0.552292 -v -0.070999 0.012000 0.192260 -vn 0.552285 -0.770264 0.318863 -v -0.071329 0.012000 0.192589 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.193314 -vn -0.577350 -0.577350 -0.577350 -v -0.074549 0.012000 0.186539 -vn -0.318866 -0.770261 -0.552288 -v -0.070099 0.012000 0.193819 -vn -0.000000 -0.770263 -0.637726 -v -0.070549 0.012000 0.193939 -vn 0.637731 -0.770259 0.000000 -v -0.071449 0.012000 0.193039 -vn 0.552285 -0.770264 -0.318863 -v -0.071329 0.012000 0.193489 -vn 0.000000 -1.000000 0.000000 -v -0.073374 0.012000 0.194039 -vn 0.318864 -0.770260 -0.552292 -v -0.070999 0.012000 0.193819 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.194039 -vn -0.318859 -0.770266 0.552286 -v -0.083599 0.012000 0.194260 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.191839 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.193314 -vn 0.318865 -0.770262 -0.552288 -v -0.084499 0.012000 0.195819 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.197864 -vn -0.707107 -0.707107 0.000000 -v -0.088049 0.012000 0.201039 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.201039 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.204214 -vn -0.318865 -0.770259 0.552292 -v -0.083599 0.012000 0.206260 -vn 0.000000 -1.000000 0.000000 -v -0.049299 0.012000 0.197864 -vn 0.000000 -1.000000 0.000000 -v -0.049299 0.012000 0.201039 -vn 0.000000 -1.000000 0.000000 -v -0.049299 0.012000 0.204214 -vn 0.707107 -0.707107 0.000000 -v -0.041049 0.012000 0.193314 -vn 0.427644 -0.741787 -0.516597 -v -0.039049 0.012000 0.211039 -vn 0.452906 -0.846478 -0.279911 -v -0.041049 0.012000 0.210039 -vn 0.707107 -0.707107 0.000000 -v -0.041049 0.012000 0.208764 -vn 0.318865 -0.770262 -0.552289 -v -0.084499 0.012000 0.207819 -vn 0.000000 -1.000000 0.000000 -v -0.083899 0.012000 0.208039 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.208764 -vn 0.000000 -1.000000 0.000000 -v -0.080474 0.012000 0.210239 -vn -0.516597 -0.741787 0.427643 -v -0.051799 0.012000 0.216039 -vn 0.630263 -0.717284 0.297108 -v -0.050549 0.012000 0.216039 -vn -0.990667 0.075085 0.113762 -v -0.067799 0.013500 0.216039 -vn -0.686244 0.609994 0.396202 -v -0.067799 0.013500 0.213384 -vn -0.279911 0.846478 0.452906 -v -0.068799 0.013500 0.214039 -vn 0.000001 0.609994 0.792406 -v -0.069799 0.013500 0.212230 -vn 0.279912 0.846479 0.452905 -v -0.070799 0.013500 0.214039 -vn 0.686244 0.609995 0.396202 -v -0.071799 0.013500 0.213384 -vn 0.990667 0.075084 0.113762 -v -0.071799 0.013500 0.216039 -vn -0.990667 0.075085 0.113762 -v -0.059799 0.013500 0.216039 -vn -0.686244 0.609994 0.396202 -v -0.059799 0.013500 0.213384 -vn -0.279911 0.846478 0.452906 -v -0.060799 0.013500 0.214039 -vn -0.000001 0.609994 0.792406 -v -0.061799 0.013500 0.212230 -vn 0.279911 0.846478 0.452906 -v -0.062799 0.013500 0.214039 -vn 0.686244 0.609994 0.396202 -v -0.063799 0.013500 0.213384 -vn 0.990667 0.075085 0.113762 -v -0.063799 0.013500 0.216039 -vn -0.990667 0.075085 0.113762 -v -0.051799 0.013500 0.216039 -vn -0.686244 0.609994 0.396202 -v -0.051799 0.013500 0.213384 -vn -0.279912 0.846479 0.452905 -v -0.052799 0.013500 0.214039 -vn -0.000001 0.609994 0.792406 -v -0.053799 0.013500 0.212230 -vn 0.279911 0.846478 0.452906 -v -0.054799 0.013500 0.214039 -vn 0.686244 0.609994 0.396202 -v -0.055799 0.013500 0.213384 -vn 0.990667 0.075085 0.113762 -v -0.055799 0.013500 0.216039 -vn -0.630262 -0.297109 0.717283 -v -0.067799 0.013000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.066549 0.013000 0.217039 -vn 0.630263 0.297109 0.717283 -v -0.066549 0.016000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.073049 0.016000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.071799 0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.073049 0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.059799 0.013000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.058549 0.013000 0.217039 -vn 0.630262 0.297109 0.717283 -v -0.058549 0.016000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.065049 0.016000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.063799 0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.065049 0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.051799 0.013000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.050549 0.013000 0.217039 -vn 0.630263 0.297109 0.717283 -v -0.050549 0.016000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.057049 0.016000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.055799 0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.057049 0.013000 0.217039 -vn 0.686244 -0.609994 0.396202 -v -0.047799 0.015000 0.213384 -vn 0.637729 -0.770261 -0.000000 -v -0.047049 0.015000 0.214539 -vn 0.301511 -0.301511 0.904534 -v -0.047799 0.015000 0.217039 -vn 0.552291 -0.770261 -0.318862 -v -0.046882 0.015000 0.215164 -vn -0.686244 -0.609995 0.396202 -v -0.043799 0.015000 0.213384 -vn -0.301511 -0.301511 0.904534 -v -0.043799 0.015000 0.217039 -vn -0.552291 -0.770260 -0.318864 -v -0.044717 0.015000 0.215164 -vn -0.318865 -0.770260 0.552291 -v -0.045174 0.015000 0.213457 -vn -0.000001 -0.609994 0.792406 -v -0.045799 0.015000 0.212230 -vn -0.552286 -0.770262 0.318867 -v -0.044717 0.015000 0.213914 -vn -0.637727 -0.770263 -0.000000 -v -0.044549 0.015000 0.214539 -vn -0.000000 -0.770264 0.637725 -v -0.045799 0.015000 0.213289 -vn 0.318866 -0.770260 0.552291 -v -0.046424 0.015000 0.213457 -vn 0.552286 -0.770263 0.318865 -v -0.046882 0.015000 0.213914 -vn 0.318861 -0.770265 -0.552286 -v -0.046424 0.015000 0.215622 -vn 0.000000 -0.770258 -0.637732 -v -0.045799 0.015000 0.215789 -vn -0.318861 -0.770265 -0.552287 -v -0.045174 0.015000 0.215622 -vn 0.904534 -0.301511 0.301511 -v -0.038049 0.015000 0.207039 -vn 0.904534 -0.301511 -0.301511 -v -0.038049 0.015000 0.211039 -vn -0.637727 -0.770263 -0.000000 -v -0.039299 0.015000 0.209039 -vn -0.552287 -0.770262 -0.318866 -v -0.039467 0.015000 0.209664 -vn 0.552287 -0.770262 -0.318866 -v -0.041632 0.015000 0.209664 -vn 0.396202 -0.609995 -0.686244 -v -0.041704 0.015000 0.211039 -vn 0.637727 -0.770263 0.000000 -v -0.041799 0.015000 0.209039 -vn 0.792406 -0.609994 -0.000001 -v -0.042859 0.015000 0.209039 -vn 0.552292 -0.770260 0.318863 -v -0.041632 0.015000 0.208414 -vn 0.396203 -0.609994 0.686244 -v -0.041704 0.015000 0.207039 -vn 0.318862 -0.770265 0.552285 -v -0.041174 0.015000 0.207957 -vn -0.552292 -0.770260 0.318863 -v -0.039467 0.015000 0.208414 -vn -0.318861 -0.770265 0.552285 -v -0.039924 0.015000 0.207957 -vn 0.000000 -0.770258 0.637732 -v -0.040549 0.015000 0.207789 -vn 0.318866 -0.770260 -0.552289 -v -0.041174 0.015000 0.210122 -vn 0.000000 -0.770264 -0.637725 -v -0.040549 0.015000 0.210289 -vn -0.318866 -0.770260 -0.552290 -v -0.039924 0.015000 0.210122 -vn -0.990667 0.075085 0.113762 -v -0.043799 0.013500 0.216039 -vn -0.686244 0.609994 0.396202 -v -0.043799 0.013500 0.213384 -vn -0.279912 0.846479 0.452906 -v -0.044799 0.013500 0.214039 -vn -0.000001 0.609994 0.792406 -v -0.045799 0.013500 0.212230 -vn 0.279911 0.846478 0.452906 -v -0.046799 0.013500 0.214039 -vn 0.686244 0.609994 0.396202 -v -0.047799 0.013500 0.213384 -vn 0.990667 0.075085 0.113762 -v -0.047799 0.013500 0.216039 -vn -0.630262 -0.297109 0.717283 -v -0.043799 0.013000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.042549 0.013000 0.217039 -vn 0.630262 0.297109 0.717283 -v -0.042549 0.016000 0.217039 -vn -0.630262 0.297109 0.717283 -v -0.049049 0.016000 0.217039 -vn 0.630262 -0.297109 0.717283 -v -0.047799 0.013000 0.217039 -vn -0.630262 -0.297109 0.717283 -v -0.049049 0.013000 0.217039 -vn 0.452906 0.846478 0.279911 -v -0.041049 0.013500 0.208039 -vn 0.113763 0.075085 0.990667 -v -0.039049 0.013500 0.207039 -vn 0.396203 0.609994 0.686244 -v -0.041704 0.013500 0.207039 -vn 0.396202 0.609994 -0.686244 -v -0.041704 0.013500 0.211039 -vn 0.113763 0.075085 -0.990667 -v -0.039049 0.013500 0.211039 -vn 0.452906 0.846478 -0.279911 -v -0.041049 0.013500 0.210039 -vn 0.792406 0.609994 -0.000001 -v -0.042859 0.013500 0.209039 -vn 0.717284 -0.297108 0.630263 -v -0.038049 0.013000 0.207039 -vn 0.717284 -0.297108 -0.630263 -v -0.038049 0.013000 0.205789 -vn 0.717284 0.297109 -0.630262 -v -0.038049 0.016000 0.205789 -vn 0.717284 0.297109 0.630262 -v -0.038049 0.016000 0.212289 -vn 0.717284 -0.297108 -0.630263 -v -0.038049 0.013000 0.211039 -vn 0.717284 -0.297108 0.630263 -v -0.038049 0.013000 0.212289 -vn -0.737701 0.088123 -0.669352 -v -0.074549 0.016000 0.188039 -vn -0.038813 0.130014 -0.990752 -v -0.083049 0.016000 0.188039 -vn -0.990753 0.130008 -0.038804 -v -0.088049 0.016000 0.193039 -vn -0.990753 0.130007 0.038804 -v -0.088049 0.016000 0.209039 -vn -0.737701 0.088123 0.669352 -v -0.074549 0.016000 0.214039 -vn -0.038803 0.130013 0.990753 -v -0.083049 0.016000 0.214039 -vn -0.630262 0.297108 0.717284 -v -0.074549 0.015500 0.215539 -vn -0.770260 0.318863 0.552292 -v -0.074549 0.016500 0.213905 -vn -0.770264 0.552286 0.318864 -v -0.074549 0.016866 0.213539 -vn -0.804186 0.227458 0.549133 -v -0.073049 0.015500 0.215539 -vn 0.804186 0.227458 0.549133 -v -0.066549 0.015500 0.215539 -vn -0.804186 0.227458 0.549133 -v -0.065049 0.015500 0.215539 -vn 0.804186 0.227458 0.549133 -v -0.058549 0.015500 0.215539 -vn -0.804186 0.227458 0.549133 -v -0.057049 0.015500 0.215539 -vn 0.804186 0.227458 0.549133 -v -0.050549 0.015500 0.215539 -vn -0.804186 0.227458 0.549133 -v -0.049049 0.015500 0.215539 -vn 0.804186 0.227458 0.549133 -v -0.042549 0.015500 0.215539 -vn 0.630263 0.297108 0.717284 -v -0.041049 0.015500 0.215539 -vn 0.717283 0.297109 0.630263 -v -0.039549 0.015500 0.214039 -vn 0.549132 0.227458 0.804187 -v -0.039549 0.015500 0.212289 -vn 0.549133 0.227458 -0.804187 -v -0.039549 0.015500 0.205789 -vn 0.549133 0.227458 0.804186 -v -0.039549 0.015500 0.196289 -vn 0.717284 0.297109 0.630262 -v -0.038049 0.016000 0.196289 -vn 0.717284 -0.297108 0.630263 -v -0.038049 0.013000 0.196289 -vn 0.717284 -0.297108 0.630263 -v -0.038049 0.013000 0.191039 -vn 0.717284 -0.297108 -0.630263 -v -0.038049 0.013000 0.189789 -vn 0.904534 -0.301511 0.301511 -v -0.038049 0.015000 0.191039 -vn 0.717284 0.297109 -0.630263 -v -0.038049 0.016000 0.189789 -vn 0.904534 -0.301511 -0.301511 -v -0.038049 0.015000 0.195039 -vn 0.717284 -0.297108 -0.630263 -v -0.038049 0.013000 0.195039 -vn 0.549133 0.227458 -0.804187 -v -0.039549 0.015500 0.189789 -vn 0.717284 0.297109 -0.630262 -v -0.039549 0.015500 0.188039 -vn 0.630263 0.297108 -0.717284 -v -0.041049 0.015500 0.186539 -vn 0.804186 0.227458 -0.549133 -v -0.042549 0.015500 0.186539 -vn 0.630262 0.297109 -0.717283 -v -0.042549 0.016000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.042549 0.013000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.047799 0.013000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.049049 0.013000 0.185039 -vn 0.301511 -0.301511 -0.904534 -v -0.047799 0.015000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.049049 0.016000 0.185039 -vn -0.301511 -0.301511 -0.904534 -v -0.043799 0.015000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.043799 0.013000 0.185039 -vn -0.804186 0.227458 -0.549133 -v -0.049049 0.015500 0.186539 -vn 0.804186 0.227458 -0.549133 -v -0.050549 0.015500 0.186539 -vn 0.630262 0.297109 -0.717283 -v -0.050549 0.016000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.050549 0.013000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.055799 0.013000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.057049 0.013000 0.185039 -vn 0.301511 -0.301511 -0.904534 -v -0.055799 0.015000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.057049 0.016000 0.185039 -vn -0.301511 -0.301511 -0.904534 -v -0.051799 0.015000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.051799 0.013000 0.185039 -vn -0.804186 0.227458 -0.549133 -v -0.057049 0.015500 0.186539 -vn 0.804186 0.227458 -0.549133 -v -0.058549 0.015500 0.186539 -vn 0.630262 0.297109 -0.717283 -v -0.058549 0.016000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.058549 0.013000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.063799 0.013000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.065049 0.013000 0.185039 -vn 0.301511 -0.301511 -0.904534 -v -0.063799 0.015000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.065049 0.016000 0.185039 -vn -0.301511 -0.301511 -0.904534 -v -0.059799 0.015000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.059799 0.013000 0.185039 -vn -0.804186 0.227458 -0.549133 -v -0.065049 0.015500 0.186539 -vn 0.804186 0.227458 -0.549133 -v -0.066549 0.015500 0.186539 -vn 0.630262 0.297109 -0.717283 -v -0.066549 0.016000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.066549 0.013000 0.185039 -vn 0.630262 -0.297109 -0.717283 -v -0.071799 0.013000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.073049 0.013000 0.185039 -vn 0.301511 -0.301511 -0.904534 -v -0.071799 0.015000 0.185039 -vn -0.630262 0.297109 -0.717283 -v -0.073049 0.016000 0.185039 -vn -0.301511 -0.301511 -0.904534 -v -0.067799 0.015000 0.185039 -vn -0.630262 -0.297109 -0.717283 -v -0.067799 0.013000 0.185039 -vn -0.804186 0.227458 -0.549133 -v -0.073049 0.015500 0.186539 -vn -0.630263 0.297108 -0.717284 -v -0.074549 0.015500 0.186539 -vn -0.770260 0.552291 -0.318863 -v -0.074549 0.016866 0.188539 -vn -0.770263 0.318867 -0.552285 -v -0.074549 0.016500 0.188173 -vn 0.983442 0.128147 -0.128140 -v -0.044049 0.019700 0.191339 -vn 0.983441 0.128147 0.128151 -v -0.044049 0.019700 0.196739 -vn 0.128142 0.128140 -0.983443 -v -0.044349 0.019700 0.191039 -vn -0.128135 0.128136 -0.983444 -v -0.050749 0.019700 0.191039 -vn -0.983441 0.128147 0.128152 -v -0.051049 0.019700 0.196739 -vn -0.983442 0.128149 -0.128142 -v -0.051049 0.019700 0.191339 -vn 0.128138 0.128136 0.983444 -v -0.044349 0.019700 0.197039 -vn -0.128139 0.128140 0.983443 -v -0.050749 0.019700 0.197039 -vn 0.108731 0.988107 0.108734 -v -0.044349 0.020000 0.196739 -vn 0.108732 0.988108 -0.108723 -v -0.044349 0.020000 0.191339 -vn -0.108727 0.988107 0.108734 -v -0.050749 0.020000 0.196739 -vn -0.108729 0.988108 -0.108723 -v -0.050749 0.020000 0.191339 -vn 0.128138 0.128136 0.983444 -v -0.044349 0.019700 0.211039 -vn -0.128139 0.128140 0.983443 -v -0.050749 0.019700 0.211039 -vn 0.983441 0.128147 0.128151 -v -0.044049 0.019700 0.210739 -vn 0.983441 0.128147 -0.128152 -v -0.044049 0.019700 0.205339 -vn 0.128142 0.128140 -0.983443 -v -0.044349 0.019700 0.205039 -vn -0.128135 0.128136 -0.983444 -v -0.050749 0.019700 0.205039 -vn -0.983441 0.128146 -0.128151 -v -0.051049 0.019700 0.205339 -vn -0.983441 0.128147 0.128152 -v -0.051049 0.019700 0.210739 -vn -0.108727 0.988107 0.108734 -v -0.050749 0.020000 0.210739 -vn 0.108731 0.988107 0.108734 -v -0.044349 0.020000 0.210739 -vn -0.108726 0.988107 -0.108731 -v -0.050749 0.020000 0.205339 -vn 0.108729 0.988107 -0.108731 -v -0.044349 0.020000 0.205339 -vn 0.396203 0.609994 -0.686244 -v -0.041704 0.013500 0.195039 -vn 0.396203 -0.609994 -0.686244 -v -0.041704 0.015000 0.195039 -vn 0.113763 0.075085 -0.990667 -v -0.039049 0.013500 0.195039 -vn -0.637727 -0.770263 -0.000000 -v -0.039299 0.015000 0.193039 -vn -0.552287 -0.770262 -0.318866 -v -0.039467 0.015000 0.193664 -vn 0.000000 -0.770258 0.637732 -v -0.040549 0.015000 0.191789 -vn 0.396203 -0.609994 0.686244 -v -0.041704 0.015000 0.191039 -vn -0.318861 -0.770265 0.552285 -v -0.039924 0.015000 0.191957 -vn -0.552292 -0.770260 0.318863 -v -0.039467 0.015000 0.192414 -vn 0.318862 -0.770265 0.552285 -v -0.041174 0.015000 0.191957 -vn 0.552292 -0.770260 0.318863 -v -0.041632 0.015000 0.192414 -vn 0.792406 -0.609994 -0.000000 -v -0.042859 0.015000 0.193039 -vn 0.637727 -0.770263 0.000000 -v -0.041799 0.015000 0.193039 -vn 0.552287 -0.770262 -0.318866 -v -0.041632 0.015000 0.193664 -vn 0.318866 -0.770260 -0.552289 -v -0.041174 0.015000 0.194122 -vn 0.000000 -0.770264 -0.637725 -v -0.040549 0.015000 0.194289 -vn -0.318866 -0.770260 -0.552290 -v -0.039924 0.015000 0.194122 -vn 0.113763 0.075085 0.990667 -v -0.039049 0.013500 0.191039 -vn 0.396203 0.609994 0.686244 -v -0.041704 0.013500 0.191039 -vn 0.792406 0.609994 0.000000 -v -0.042859 0.013500 0.193039 -vn 0.452906 0.846478 0.279911 -v -0.041049 0.013500 0.192039 -vn 0.452906 0.846478 -0.279911 -v -0.041049 0.013500 0.194039 -vn -0.686243 0.609994 -0.396204 -v -0.043799 0.013500 0.188694 -vn -0.686243 -0.609994 -0.396204 -v -0.043799 0.015000 0.188694 -vn -0.990667 0.075085 -0.113763 -v -0.043799 0.013500 0.186039 -vn 0.686243 -0.609994 -0.396204 -v -0.047799 0.015000 0.188694 -vn 0.552286 -0.770263 0.318865 -v -0.046882 0.015000 0.186914 -vn 0.637729 -0.770261 -0.000000 -v -0.047049 0.015000 0.187539 -vn 0.552291 -0.770261 -0.318862 -v -0.046882 0.015000 0.188164 -vn -0.000000 -0.609995 -0.792405 -v -0.045799 0.015000 0.189849 -vn 0.318861 -0.770265 -0.552286 -v -0.046424 0.015000 0.188622 -vn -0.637727 -0.770263 -0.000000 -v -0.044549 0.015000 0.187539 -vn -0.552286 -0.770262 0.318867 -v -0.044717 0.015000 0.186914 -vn -0.318865 -0.770260 0.552291 -v -0.045174 0.015000 0.186457 -vn -0.000000 -0.770264 0.637725 -v -0.045799 0.015000 0.186289 -vn 0.318866 -0.770260 0.552291 -v -0.046424 0.015000 0.186457 -vn 0.000000 -0.770258 -0.637732 -v -0.045799 0.015000 0.188789 -vn -0.318861 -0.770265 -0.552287 -v -0.045174 0.015000 0.188622 -vn -0.552291 -0.770260 -0.318864 -v -0.044717 0.015000 0.188164 -vn 0.990667 0.075085 -0.113763 -v -0.047799 0.013500 0.186039 -vn 0.686243 0.609994 -0.396204 -v -0.047799 0.013500 0.188694 -vn 0.000000 0.609995 -0.792405 -v -0.045799 0.013500 0.189849 -vn 0.279911 0.846478 -0.452907 -v -0.046799 0.013500 0.188039 -vn -0.279911 0.846478 -0.452907 -v -0.044799 0.013500 0.188039 -vn -0.686243 0.609994 -0.396204 -v -0.051799 0.013500 0.188694 -vn -0.686243 -0.609994 -0.396204 -v -0.051799 0.015000 0.188694 -vn -0.990667 0.075085 -0.113763 -v -0.051799 0.013500 0.186039 -vn 0.686243 -0.609994 -0.396204 -v -0.055799 0.015000 0.188694 -vn 0.552286 -0.770263 0.318865 -v -0.054882 0.015000 0.186914 -vn 0.637729 -0.770261 -0.000000 -v -0.055049 0.015000 0.187539 -vn 0.552291 -0.770261 -0.318862 -v -0.054882 0.015000 0.188164 -vn 0.000000 -0.609995 -0.792405 -v -0.053799 0.015000 0.189849 -vn 0.318861 -0.770265 -0.552286 -v -0.054424 0.015000 0.188622 -vn -0.552287 -0.770262 0.318866 -v -0.052717 0.015000 0.186914 -vn -0.637727 -0.770263 -0.000000 -v -0.052549 0.015000 0.187539 -vn 0.000001 -0.770258 -0.637732 -v -0.053799 0.015000 0.188789 -vn -0.318861 -0.770265 -0.552286 -v -0.053174 0.015000 0.188622 -vn -0.552292 -0.770260 -0.318863 -v -0.052717 0.015000 0.188164 -vn -0.318865 -0.770260 0.552290 -v -0.053174 0.015000 0.186457 -vn 0.000001 -0.770264 0.637725 -v -0.053799 0.015000 0.186289 -vn 0.318866 -0.770260 0.552291 -v -0.054424 0.015000 0.186457 -vn 0.990667 0.075085 -0.113763 -v -0.055799 0.013500 0.186039 -vn 0.686243 0.609994 -0.396204 -v -0.055799 0.013500 0.188694 -vn -0.686243 0.609994 -0.396204 -v -0.059799 0.013500 0.188694 -vn -0.686243 -0.609994 -0.396204 -v -0.059799 0.015000 0.188694 -vn -0.990667 0.075085 -0.113763 -v -0.059799 0.013500 0.186039 -vn -0.552286 -0.770263 0.318865 -v -0.060717 0.015000 0.186914 -vn -0.637728 -0.770261 0.000000 -v -0.060549 0.015000 0.187539 -vn -0.318866 -0.770260 0.552291 -v -0.061174 0.015000 0.186457 -vn 0.000000 -0.770264 0.637725 -v -0.061799 0.015000 0.186289 -vn 0.318861 -0.770265 -0.552286 -v -0.062424 0.015000 0.188622 -vn -0.000000 -0.609995 -0.792405 -v -0.061799 0.015000 0.189849 -vn 0.552291 -0.770261 -0.318862 -v -0.062882 0.015000 0.188164 -vn 0.686243 -0.609994 -0.396205 -v -0.063799 0.015000 0.188694 -vn 0.000000 -0.770258 -0.637732 -v -0.061799 0.015000 0.188789 -vn -0.318861 -0.770265 -0.552286 -v -0.061174 0.015000 0.188622 -vn -0.552291 -0.770261 -0.318862 -v -0.060717 0.015000 0.188164 -vn 0.318866 -0.770260 0.552291 -v -0.062424 0.015000 0.186457 -vn 0.552286 -0.770263 0.318865 -v -0.062882 0.015000 0.186914 -vn 0.637728 -0.770261 -0.000000 -v -0.063049 0.015000 0.187539 -vn 0.990667 0.075085 -0.113763 -v -0.063799 0.013500 0.186039 -vn 0.686243 0.609994 -0.396205 -v -0.063799 0.013500 0.188694 -vn -0.686243 0.609994 -0.396205 -v -0.067799 0.013500 0.188694 -vn -0.686243 -0.609994 -0.396205 -v -0.067799 0.015000 0.188694 -vn -0.990667 0.075085 -0.113763 -v -0.067799 0.013500 0.186039 -vn -0.000000 -0.770258 -0.637732 -v -0.069799 0.015000 0.188789 -vn -0.318861 -0.770265 -0.552286 -v -0.069174 0.015000 0.188622 -vn 0.000001 -0.609995 -0.792405 -v -0.069799 0.015000 0.189849 -vn 0.686243 -0.609994 -0.396204 -v -0.071799 0.015000 0.188694 -vn 0.552286 -0.770263 0.318865 -v -0.070882 0.015000 0.186914 -vn 0.637729 -0.770261 -0.000000 -v -0.071049 0.015000 0.187539 -vn 0.552291 -0.770261 -0.318862 -v -0.070882 0.015000 0.188164 -vn 0.318861 -0.770265 -0.552286 -v -0.070424 0.015000 0.188622 -vn -0.552291 -0.770261 -0.318862 -v -0.068717 0.015000 0.188164 -vn -0.637728 -0.770261 0.000000 -v -0.068549 0.015000 0.187539 -vn -0.552286 -0.770263 0.318865 -v -0.068717 0.015000 0.186914 -vn -0.318865 -0.770260 0.552291 -v -0.069174 0.015000 0.186457 -vn 0.000000 -0.770264 0.637725 -v -0.069799 0.015000 0.186289 -vn 0.318866 -0.770260 0.552291 -v -0.070424 0.015000 0.186457 -vn 0.990667 0.075085 -0.113762 -v -0.071799 0.013500 0.186039 -vn 0.686243 0.609994 -0.396204 -v -0.071799 0.013500 0.188694 -vn -0.000000 0.609995 -0.792405 -v -0.053799 0.013500 0.189849 -vn 0.279911 0.846478 -0.452907 -v -0.054799 0.013500 0.188039 -vn -0.279911 0.846478 -0.452906 -v -0.052799 0.013500 0.188039 -vn -0.000000 0.609995 -0.792405 -v -0.061799 0.013500 0.189849 -vn 0.279911 0.846478 -0.452907 -v -0.062799 0.013500 0.188039 -vn -0.279911 0.846478 -0.452907 -v -0.060799 0.013500 0.188039 -vn 0.000001 0.609995 -0.792405 -v -0.069799 0.013500 0.189849 -vn 0.279911 0.846478 -0.452906 -v -0.070799 0.013500 0.188039 -vn -0.279911 0.846478 -0.452907 -v -0.068799 0.013500 0.188039 -vn -0.979470 0.128741 0.155130 -v -0.087988 0.016000 0.209821 -vn -0.943024 0.129694 0.306407 -v -0.087805 0.016000 0.210584 -vn -0.883591 0.128748 0.450212 -v -0.087504 0.016000 0.211309 -vn -0.802181 0.129695 0.582825 -v -0.087095 0.016000 0.211978 -vn -0.701224 0.128742 0.701220 -v -0.086585 0.016000 0.212575 -vn -0.582823 0.129693 0.802183 -v -0.085988 0.016000 0.213084 -vn -0.450209 0.128747 0.883593 -v -0.085319 0.016000 0.213494 -vn -0.306406 0.129693 0.943024 -v -0.084595 0.016000 0.213794 -vn -0.155136 0.128743 0.979468 -v -0.083832 0.016000 0.213978 -vn -0.155134 0.128743 -0.979469 -v -0.083832 0.016000 0.188101 -vn -0.306407 0.129692 -0.943024 -v -0.084595 0.016000 0.188284 -vn -0.450216 0.128747 -0.883589 -v -0.085319 0.016000 0.188584 -vn -0.582819 0.129695 -0.802185 -v -0.085988 0.016000 0.188994 -vn -0.701221 0.128749 -0.701222 -v -0.086585 0.016000 0.189504 -vn -0.802185 0.129695 -0.582819 -v -0.087095 0.016000 0.190100 -vn -0.883591 0.128748 -0.450213 -v -0.087504 0.016000 0.190769 -vn -0.943024 0.129692 -0.306408 -v -0.087805 0.016000 0.191494 -vn -0.979469 0.128744 -0.155132 -v -0.087988 0.016000 0.192257 -vn -0.549133 0.227459 0.804187 -v -0.059049 0.016000 0.191539 -vn -0.549132 0.227459 -0.804187 -v -0.059049 0.016000 0.200539 -vn 0.549132 0.227459 -0.804187 -v -0.063549 0.016000 0.200539 -vn 0.549132 0.227459 0.804187 -v -0.063549 0.016000 0.191539 -vn -0.483790 0.765317 0.424544 -v -0.058349 0.016700 0.191539 -vn 0.483791 0.765316 0.424544 -v -0.064249 0.016700 0.191539 -vn 0.483791 0.765316 -0.424543 -v -0.064249 0.016700 0.210539 -vn -0.483790 0.765317 -0.424544 -v -0.058349 0.016700 0.210539 -vn -0.549132 0.227459 -0.804187 -v -0.059049 0.016000 0.210539 -vn 0.549132 0.227459 -0.804187 -v -0.063549 0.016000 0.210539 -vn 0.549132 0.227459 0.804187 -v -0.063549 0.016000 0.201539 -vn -0.549132 0.227459 0.804187 -v -0.059049 0.016000 0.201539 -vn -0.979699 0.126934 0.155170 -v -0.081883 0.019500 0.201884 -vn -0.883802 0.126916 0.450318 -v -0.081361 0.019500 0.203491 -vn -0.943023 0.129688 0.306412 -v -0.081685 0.019500 0.202708 -vn -0.701385 0.126951 0.701386 -v -0.080368 0.019500 0.204857 -vn -0.802188 0.129675 0.582819 -v -0.080918 0.019500 0.204213 -vn -0.450312 0.126963 0.883799 -v -0.079001 0.019500 0.205851 -vn -0.582824 0.129690 0.802183 -v -0.079724 0.019500 0.205408 -vn -0.155171 0.126931 0.979699 -v -0.077394 0.019500 0.206373 -vn -0.306408 0.129683 0.943025 -v -0.078218 0.019500 0.206175 -vn 0.155168 0.126933 0.979699 -v -0.075705 0.019500 0.206373 -vn 0.000003 0.129722 0.991550 -v -0.076549 0.019500 0.206439 -vn 0.450317 0.126963 0.883796 -v -0.074098 0.019500 0.205851 -vn 0.306405 0.129681 0.943027 -v -0.074881 0.019500 0.206175 -vn 0.701388 0.126951 0.701384 -v -0.072731 0.019500 0.204857 -vn 0.582820 0.129691 0.802185 -v -0.073375 0.019500 0.205408 -vn 0.883801 0.126915 0.450320 -v -0.071738 0.019500 0.203491 -vn 0.802187 0.129677 0.582821 -v -0.072181 0.019500 0.204213 -vn 0.979699 0.126934 0.155169 -v -0.071216 0.019500 0.201884 -vn 0.943024 0.129686 0.306411 -v -0.071414 0.019500 0.202708 -vn 0.979699 0.126934 -0.155170 -v -0.071216 0.019500 0.200194 -vn 0.991556 0.129680 0.000001 -v -0.071149 0.019500 0.201039 -vn 0.883799 0.126934 -0.450318 -v -0.071738 0.019500 0.198588 -vn 0.943027 0.129674 -0.306406 -v -0.071414 0.019500 0.199370 -vn 0.701388 0.126922 -0.701389 -v -0.072731 0.019500 0.197221 -vn 0.802181 0.129702 -0.582823 -v -0.072181 0.019500 0.197865 -vn 0.450325 0.126925 -0.883797 -v -0.074098 0.019500 0.196228 -vn 0.582822 0.129688 -0.802185 -v -0.073375 0.019500 0.196670 -vn 0.155161 0.126975 -0.979695 -v -0.075705 0.019500 0.195706 -vn 0.306407 0.129721 -0.943020 -v -0.074881 0.019500 0.195903 -vn -0.155166 0.126972 -0.979695 -v -0.077394 0.019500 0.195706 -vn 0.000004 0.129682 -0.991556 -v -0.076549 0.019500 0.195639 -vn -0.450321 0.126927 -0.883799 -v -0.079001 0.019500 0.196228 -vn -0.306410 0.129724 -0.943019 -v -0.078218 0.019500 0.195903 -vn -0.701385 0.126921 -0.701391 -v -0.080368 0.019500 0.197221 -vn -0.582823 0.129688 -0.802183 -v -0.079724 0.019500 0.196670 -vn -0.883799 0.126935 -0.450318 -v -0.081361 0.019500 0.198588 -vn -0.802183 0.129700 -0.582821 -v -0.080918 0.019500 0.197865 -vn -0.991556 0.129680 -0.000001 -v -0.081949 0.019500 0.201039 -vn -0.979699 0.126934 -0.155168 -v -0.081883 0.019500 0.200194 -vn -0.943026 0.129674 -0.306409 -v -0.081685 0.019500 0.199370 -vn 0.130228 0.990581 0.042313 -v -0.071699 0.019800 0.202615 -vn 0.135241 0.990581 0.021420 -v -0.071512 0.019800 0.201837 -vn -0.615821 0.750899 -0.238569 -v -0.072820 0.019800 0.202484 -vn -0.660418 0.750898 -0.000000 -v -0.072549 0.019800 0.201039 -vn 0.096823 0.990581 -0.096824 -v -0.072943 0.019800 0.197433 -vn 0.080493 0.990579 -0.110787 -v -0.073552 0.019800 0.196913 -vn -0.488054 0.750899 0.444920 -v -0.073593 0.019800 0.198344 -vn -0.294374 0.750898 0.591181 -v -0.074767 0.019800 0.197458 -vn 0.180730 0.750899 -0.635206 -v -0.077644 0.019800 0.204886 -vn 0.397990 0.750899 -0.527024 -v -0.078960 0.019800 0.204231 -vn -0.062160 0.990582 0.121998 -v -0.078865 0.019800 0.205583 -vn 0.561499 0.750898 -0.347665 -v -0.079950 0.019800 0.203145 -vn -0.096824 0.990581 0.096823 -v -0.080156 0.019800 0.204645 -vn -0.080486 0.990581 0.110778 -v -0.079547 0.019800 0.205165 -vn -0.135241 0.990581 0.021420 -v -0.081587 0.019800 0.201837 -vn 0.649172 0.750899 -0.121352 -v -0.080481 0.019800 0.201774 -vn -0.136928 0.990581 0.000000 -v -0.081649 0.019800 0.201039 -vn 0.649172 0.750899 0.121352 -v -0.080481 0.019800 0.200304 -vn -0.135243 0.990581 -0.021421 -v -0.081587 0.019800 0.200241 -vn -0.042313 0.990581 -0.130224 -v -0.078125 0.019800 0.196189 -vn -0.062166 0.990580 -0.122007 -v -0.078865 0.019800 0.196495 -vn 0.180734 0.750898 0.635207 -v -0.077644 0.019800 0.197192 -vn 0.397990 0.750899 0.527024 -v -0.078960 0.019800 0.197847 -vn 0.062165 0.990581 -0.122007 -v -0.074234 0.019800 0.196495 -vn 0.042312 0.990581 -0.130224 -v -0.074973 0.019800 0.196189 -vn -0.060934 0.750900 0.657599 -v -0.076180 0.019800 0.197056 -vn 0.136928 0.990581 -0.000000 -v -0.071449 0.019800 0.201039 -vn 0.135243 0.990581 -0.021421 -v -0.071512 0.019800 0.200241 -vn -0.615821 0.750899 0.238569 -v -0.072820 0.019800 0.199594 -vn -0.488052 0.750900 -0.444921 -v -0.073593 0.019800 0.203734 -vn 0.110776 0.990581 0.080483 -v -0.072423 0.019800 0.204037 -vn 0.122007 0.990581 0.062166 -v -0.072005 0.019800 0.203354 -vn 0.021421 0.990582 0.135237 -v -0.075752 0.019800 0.206076 -vn 0.042315 0.990580 0.130236 -v -0.074973 0.019800 0.205890 -vn -0.060937 0.750899 -0.657600 -v -0.076180 0.019800 0.205022 -vn -0.294373 0.750898 -0.591183 -v -0.074767 0.019800 0.204620 -vn -0.130229 0.990581 0.042313 -v -0.081400 0.019800 0.202615 -vn -0.122007 0.990581 0.062165 -v -0.081094 0.019800 0.203354 -vn -0.110776 0.990581 0.080483 -v -0.080675 0.019800 0.204037 -vn -0.130229 0.990581 -0.042313 -v -0.081400 0.019800 0.199463 -vn 0.561499 0.750898 0.347665 -v -0.079950 0.019800 0.198933 -vn -0.122007 0.990581 -0.062166 -v -0.081094 0.019800 0.198724 -vn -0.080491 0.990579 -0.110788 -v -0.079547 0.019800 0.196913 -vn -0.096823 0.990581 -0.096822 -v -0.080156 0.019800 0.197433 -vn -0.110776 0.990581 -0.080484 -v -0.080675 0.019800 0.198041 -vn 0.021423 0.990580 -0.135249 -v -0.075752 0.019800 0.196002 -vn -0.000001 0.990582 -0.136921 -v -0.076549 0.019800 0.195939 -vn -0.021420 0.990580 -0.135250 -v -0.077347 0.019800 0.196002 -vn 0.130229 0.990581 -0.042313 -v -0.071699 0.019800 0.199463 -vn 0.122007 0.990581 -0.062165 -v -0.072005 0.019800 0.198724 -vn 0.110776 0.990581 -0.080484 -v -0.072423 0.019800 0.198041 -vn 0.062162 0.990582 0.121996 -v -0.074234 0.019800 0.205583 -vn 0.080486 0.990581 0.110779 -v -0.073552 0.019800 0.205165 -vn 0.096823 0.990581 0.096823 -v -0.072943 0.019800 0.204645 -vn -0.042318 0.990580 0.130235 -v -0.078125 0.019800 0.205890 -vn -0.021418 0.990582 0.135237 -v -0.077347 0.019800 0.206076 -vn -0.000001 0.990580 0.136933 -v -0.076549 0.019800 0.206139 -vn -0.744167 0.667993 0.000000 -v -0.072549 0.019200 0.201039 -vn -0.693917 0.667992 0.268823 -v -0.072820 0.019200 0.199594 -vn -0.549947 0.667993 0.501343 -v -0.073593 0.019200 0.198344 -vn -0.331705 0.667993 0.666151 -v -0.074767 0.019200 0.197458 -vn -0.068662 0.667992 0.740995 -v -0.076180 0.019200 0.197056 -vn 0.203653 0.667994 0.715758 -v -0.077644 0.019200 0.197192 -vn 0.448462 0.667992 0.593859 -v -0.078960 0.019200 0.197847 -vn 0.632704 0.667993 0.391753 -v -0.079950 0.019200 0.198933 -vn 0.731497 0.667992 0.136741 -v -0.080481 0.019200 0.200304 -vn 0.731497 0.667992 -0.136741 -v -0.080481 0.019200 0.201774 -vn 0.632704 0.667993 -0.391753 -v -0.079950 0.019200 0.203145 -vn 0.448462 0.667992 -0.593859 -v -0.078960 0.019200 0.204231 -vn 0.203650 0.667993 -0.715760 -v -0.077644 0.019200 0.204886 -vn -0.068665 0.667993 -0.740993 -v -0.076180 0.019200 0.205022 -vn -0.331702 0.667994 -0.666152 -v -0.074767 0.019200 0.204620 -vn -0.549946 0.667992 -0.501345 -v -0.073593 0.019200 0.203734 -vn -0.693917 0.667992 -0.268823 -v -0.072820 0.019200 0.202484 -vn -0.108877 0.976004 -0.188580 -v -0.075787 0.019200 0.202360 -vn -0.188589 0.976002 -0.108881 -v -0.075229 0.019200 0.201802 -vn -0.217757 0.976003 -0.000000 -v -0.075024 0.019200 0.201039 -vn -0.188584 0.976003 0.108879 -v -0.075229 0.019200 0.200277 -vn 0.108878 0.976004 -0.188580 -v -0.077312 0.019200 0.202360 -vn -0.000000 0.976003 -0.217758 -v -0.076549 0.019200 0.202564 -vn 0.188582 0.976003 0.108880 -v -0.077870 0.019200 0.200277 -vn 0.217757 0.976003 -0.000000 -v -0.078074 0.019200 0.201039 -vn 0.188587 0.976002 -0.108881 -v -0.077870 0.019200 0.201802 -vn -0.000001 0.976002 0.217760 -v -0.076549 0.019200 0.199514 -vn 0.108882 0.976002 0.188586 -v -0.077312 0.019200 0.199718 -vn -0.108880 0.976002 0.188587 -v -0.075787 0.019200 0.199718 -vn 0.000000 -1.000000 -0.000003 -v -0.085549 0.016981 0.210289 -vn 0.768716 -0.460549 0.443813 -v -0.086242 0.016500 0.209889 -vn 0.443808 -0.460549 0.768719 -v -0.085949 0.016500 0.209596 -vn 0.887634 -0.460549 -0.000004 -v -0.086349 0.016500 0.210289 -vn -0.443808 -0.460549 0.768719 -v -0.085149 0.016500 0.209596 -vn -0.768716 -0.460549 0.443813 -v -0.084857 0.016500 0.209889 -vn 0.000000 -0.460551 0.887633 -v -0.085549 0.016500 0.209489 -vn -0.768715 -0.460548 -0.443816 -v -0.084857 0.016500 0.210689 -vn -0.443821 -0.460548 -0.768712 -v -0.085149 0.016500 0.210982 -vn -0.887634 -0.460549 -0.000004 -v -0.084749 0.016500 0.210289 -vn 0.443821 -0.460548 -0.768712 -v -0.085949 0.016500 0.210982 -vn 0.768715 -0.460548 -0.443816 -v -0.086242 0.016500 0.210689 -vn -0.000000 -0.460547 -0.887635 -v -0.085549 0.016500 0.211089 -vn 0.842049 -0.539402 -0.000006 -v -0.086349 0.012058 0.210289 -vn 0.729244 -0.539387 0.421029 -v -0.086242 0.012058 0.209889 -vn 0.421018 -0.539381 0.729254 -v -0.085949 0.012058 0.209596 -vn 0.000005 -0.539397 0.842051 -v -0.085549 0.012058 0.209489 -vn -0.421022 -0.539383 0.729251 -v -0.085149 0.012058 0.209596 -vn -0.729246 -0.539386 0.421027 -v -0.084857 0.012058 0.209889 -vn -0.842049 -0.539401 -0.000001 -v -0.084749 0.012058 0.210289 -vn -0.729238 -0.539401 -0.421020 -v -0.084857 0.012058 0.210689 -vn -0.421028 -0.539405 -0.729231 -v -0.085149 0.012058 0.210982 -vn 0.000001 -0.539406 -0.842046 -v -0.085549 0.012058 0.211089 -vn 0.421027 -0.539405 -0.729231 -v -0.085949 0.012058 0.210982 -vn 0.729239 -0.539401 -0.421019 -v -0.086242 0.012058 0.210689 -vn 0.000000 -1.000000 -0.000003 -v -0.085549 0.016981 0.191789 -vn 0.768716 -0.460549 0.443813 -v -0.086242 0.016500 0.191389 -vn 0.443808 -0.460549 0.768719 -v -0.085949 0.016500 0.191096 -vn 0.887634 -0.460549 -0.000004 -v -0.086349 0.016500 0.191789 -vn -0.443808 -0.460549 0.768719 -v -0.085149 0.016500 0.191096 -vn -0.768716 -0.460549 0.443813 -v -0.084857 0.016500 0.191389 -vn 0.000000 -0.460551 0.887633 -v -0.085549 0.016500 0.190989 -vn -0.768715 -0.460548 -0.443816 -v -0.084857 0.016500 0.192189 -vn -0.443821 -0.460548 -0.768712 -v -0.085149 0.016500 0.192482 -vn -0.887634 -0.460549 -0.000004 -v -0.084749 0.016500 0.191789 -vn 0.443821 -0.460548 -0.768712 -v -0.085949 0.016500 0.192482 -vn 0.768715 -0.460548 -0.443816 -v -0.086242 0.016500 0.192189 -vn -0.000000 -0.460547 -0.887635 -v -0.085549 0.016500 0.192589 -vn 0.842049 -0.539402 -0.000006 -v -0.086349 0.012058 0.191789 -vn 0.729244 -0.539387 0.421029 -v -0.086242 0.012058 0.191389 -vn 0.421018 -0.539381 0.729254 -v -0.085949 0.012058 0.191096 -vn 0.000005 -0.539397 0.842051 -v -0.085549 0.012058 0.190989 -vn -0.421022 -0.539383 0.729251 -v -0.085149 0.012058 0.191096 -vn -0.729246 -0.539386 0.421027 -v -0.084857 0.012058 0.191389 -vn -0.842049 -0.539401 -0.000001 -v -0.084749 0.012058 0.191789 -vn -0.729238 -0.539401 -0.421020 -v -0.084857 0.012058 0.192189 -vn -0.421028 -0.539405 -0.729231 -v -0.085149 0.012058 0.192482 -vn 0.000001 -0.539406 -0.842046 -v -0.085549 0.012058 0.192589 -vn 0.421027 -0.539405 -0.729231 -v -0.085949 0.012058 0.192482 -vn 0.729239 -0.539401 -0.421019 -v -0.086242 0.012058 0.192189 -vn 0.000001 -1.000000 -0.000001 -v -0.043549 0.016981 0.211439 -vn 0.768711 -0.460548 0.443824 -v -0.044242 0.016500 0.211039 -vn 0.443814 -0.460549 0.768715 -v -0.043949 0.016500 0.210746 -vn 0.887635 -0.460548 -0.000004 -v -0.044349 0.016500 0.211439 -vn -0.443812 -0.460550 0.768717 -v -0.043149 0.016500 0.210746 -vn -0.768711 -0.460548 0.443823 -v -0.042857 0.016500 0.211039 -vn 0.000000 -0.460547 0.887635 -v -0.043549 0.016500 0.210639 -vn -0.768715 -0.460548 -0.443816 -v -0.042857 0.016500 0.211839 -vn -0.443821 -0.460548 -0.768712 -v -0.043149 0.016500 0.212132 -vn -0.887634 -0.460549 -0.000004 -v -0.042749 0.016500 0.211439 -vn 0.443824 -0.460548 -0.768711 -v -0.043949 0.016500 0.212132 -vn 0.768714 -0.460548 -0.443817 -v -0.044242 0.016500 0.211839 -vn -0.000000 -0.460547 -0.887635 -v -0.043549 0.016500 0.212239 -vn 0.842047 -0.539404 -0.000003 -v -0.044349 0.012058 0.211439 -vn 0.729230 -0.539400 0.421035 -v -0.044242 0.012058 0.211039 -vn 0.421023 -0.539403 0.729235 -v -0.043949 0.012058 0.210746 -vn -0.000001 -0.539406 0.842046 -v -0.043549 0.012058 0.210639 -vn -0.421018 -0.539403 0.729238 -v -0.043149 0.012058 0.210746 -vn -0.729236 -0.539396 0.421031 -v -0.042857 0.012058 0.211039 -vn -0.842049 -0.539402 -0.000003 -v -0.042749 0.012058 0.211439 -vn -0.729235 -0.539408 -0.421018 -v -0.042857 0.012058 0.211839 -vn -0.421027 -0.539406 -0.729231 -v -0.043149 0.012058 0.212132 -vn 0.000001 -0.539406 -0.842046 -v -0.043549 0.012058 0.212239 -vn 0.421029 -0.539406 -0.729230 -v -0.043949 0.012058 0.212132 -vn 0.729230 -0.539412 -0.421020 -v -0.044242 0.012058 0.211839 -vn 0.000001 -1.000000 -0.000004 -v -0.043549 0.016981 0.190639 -vn 0.768716 -0.460549 0.443814 -v -0.044242 0.016500 0.190239 -vn 0.443823 -0.460551 0.768710 -v -0.043949 0.016500 0.189946 -vn 0.887635 -0.460548 -0.000004 -v -0.044349 0.016500 0.190639 -vn -0.443820 -0.460551 0.768711 -v -0.043149 0.016500 0.189946 -vn -0.768716 -0.460549 0.443813 -v -0.042857 0.016500 0.190239 -vn 0.000000 -0.460551 0.887633 -v -0.043549 0.016500 0.189839 -vn -0.768715 -0.460548 -0.443816 -v -0.042857 0.016500 0.191039 -vn -0.443821 -0.460548 -0.768712 -v -0.043149 0.016500 0.191332 -vn -0.887634 -0.460549 -0.000004 -v -0.042749 0.016500 0.190639 -vn 0.443824 -0.460548 -0.768711 -v -0.043949 0.016500 0.191332 -vn 0.768714 -0.460548 -0.443817 -v -0.044242 0.016500 0.191039 -vn -0.000000 -0.460547 -0.887635 -v -0.043549 0.016500 0.191439 -vn 0.842047 -0.539404 -0.000003 -v -0.044349 0.012058 0.190639 -vn 0.729237 -0.539398 0.421026 -v -0.044242 0.012058 0.190239 -vn 0.421032 -0.539405 0.729229 -v -0.043949 0.012058 0.189946 -vn -0.000006 -0.539376 0.842065 -v -0.043549 0.012058 0.189839 -vn -0.421023 -0.539403 0.729235 -v -0.043149 0.012058 0.189946 -vn -0.729242 -0.539394 0.421023 -v -0.042857 0.012058 0.190239 -vn -0.842049 -0.539402 -0.000003 -v -0.042749 0.012058 0.190639 -vn -0.729235 -0.539408 -0.421018 -v -0.042857 0.012058 0.191039 -vn -0.421027 -0.539406 -0.729231 -v -0.043149 0.012058 0.191332 -vn 0.000001 -0.539406 -0.842046 -v -0.043549 0.012058 0.191439 -vn 0.421029 -0.539406 -0.729230 -v -0.043949 0.012058 0.191332 -vn 0.729230 -0.539412 -0.421020 -v -0.044242 0.012058 0.191039 -vn -0.842048 0.539402 -0.000000 -v -0.075299 0.019041 0.201039 -vn -0.729238 0.539401 0.421020 -v -0.075467 0.019041 0.200414 -vn -0.421022 0.539400 0.729238 -v -0.075924 0.019041 0.199957 -vn -0.000000 0.539397 0.842051 -v -0.076549 0.019041 0.199789 -vn 0.421027 0.539399 0.729236 -v -0.077174 0.019041 0.199957 -vn 0.729237 0.539400 0.421023 -v -0.077632 0.019041 0.200414 -vn 0.842048 0.539402 -0.000001 -v -0.077799 0.019041 0.201039 -vn 0.729235 0.539397 -0.421031 -v -0.077632 0.019041 0.201664 -vn 0.421029 0.539404 -0.729231 -v -0.077174 0.019041 0.202122 -vn -0.000000 0.539403 -0.842048 -v -0.076549 0.019041 0.202289 -vn -0.421025 0.539404 -0.729233 -v -0.075924 0.019041 0.202122 -vn -0.729236 0.539398 -0.421028 -v -0.075467 0.019041 0.201664 -vn -0.913442 0.406970 -0.000003 -v -0.083149 0.016900 0.207039 -vn -0.791065 0.406971 0.456718 -v -0.083270 0.016900 0.206589 -vn -0.456720 0.406975 0.791062 -v -0.083599 0.016900 0.206260 -vn -0.000003 0.406974 0.913440 -v -0.084049 0.016900 0.206139 -vn 0.456726 0.406966 0.791062 -v -0.084499 0.016900 0.206260 -vn 0.791068 0.406968 0.456714 -v -0.084829 0.016900 0.206589 -vn 0.913441 0.406971 0.000002 -v -0.084949 0.016900 0.207039 -vn 0.791070 0.406952 -0.456725 -v -0.084829 0.016900 0.207489 -vn 0.456728 0.406965 -0.791062 -v -0.084499 0.016900 0.207819 -vn -0.000004 0.406973 -0.913440 -v -0.084049 0.016900 0.207939 -vn -0.456719 0.406974 -0.791062 -v -0.083599 0.016900 0.207819 -vn -0.791071 0.406953 -0.456723 -v -0.083270 0.016900 0.207489 -vn -0.913440 0.406973 -0.000000 -v -0.069649 0.016900 0.209039 -vn -0.791065 0.406983 0.456707 -v -0.069770 0.016900 0.208589 -vn -0.456716 0.406949 0.791077 -v -0.070099 0.016900 0.208260 -vn -0.000005 0.406967 0.913443 -v -0.070549 0.016900 0.208139 -vn 0.456722 0.406947 0.791075 -v -0.070999 0.016900 0.208260 -vn 0.791071 0.406966 0.456712 -v -0.071329 0.016900 0.208589 -vn 0.913441 0.406971 0.000002 -v -0.071449 0.016900 0.209039 -vn 0.791067 0.406952 -0.456730 -v -0.071329 0.016900 0.209489 -vn 0.456722 0.406972 -0.791061 -v -0.070999 0.016900 0.209819 -vn -0.000006 0.406938 -0.913456 -v -0.070549 0.016900 0.209939 -vn -0.456718 0.406972 -0.791064 -v -0.070099 0.016900 0.209819 -vn -0.791062 0.406967 -0.456726 -v -0.069770 0.016900 0.209489 -vn -0.913441 0.406971 -0.000002 -v -0.054149 0.016900 0.209039 -vn -0.791068 0.406976 0.456708 -v -0.054270 0.016900 0.208589 -vn -0.456715 0.406948 0.791079 -v -0.054599 0.016900 0.208260 -vn -0.000005 0.406967 0.913443 -v -0.055049 0.016900 0.208139 -vn 0.456724 0.406948 0.791073 -v -0.055499 0.016900 0.208260 -vn 0.791066 0.406973 0.456713 -v -0.055829 0.016900 0.208589 -vn 0.913444 0.406963 -0.000001 -v -0.055949 0.016900 0.209039 -vn 0.791065 0.406958 -0.456728 -v -0.055829 0.016900 0.209489 -vn 0.456723 0.406973 -0.791060 -v -0.055499 0.016900 0.209819 -vn -0.000006 0.406938 -0.913456 -v -0.055049 0.016900 0.209939 -vn -0.456716 0.406972 -0.791066 -v -0.054599 0.016900 0.209819 -vn -0.791066 0.406960 -0.456725 -v -0.054270 0.016900 0.209489 -vn -0.913442 0.406970 -0.000003 -v -0.083149 0.016900 0.195039 -vn -0.791071 0.406970 0.456709 -v -0.083270 0.016900 0.194589 -vn -0.456715 0.406947 0.791079 -v -0.083599 0.016900 0.194260 -vn -0.000009 0.406967 0.913443 -v -0.084049 0.016900 0.194139 -vn 0.456730 0.406939 0.791074 -v -0.084499 0.016900 0.194260 -vn 0.791073 0.406964 0.456710 -v -0.084829 0.016900 0.194589 -vn 0.913441 0.406971 0.000002 -v -0.084949 0.016900 0.195039 -vn 0.791070 0.406952 -0.456725 -v -0.084829 0.016900 0.195489 -vn 0.456728 0.406965 -0.791062 -v -0.084499 0.016900 0.195819 -vn -0.000009 0.406938 -0.913456 -v -0.084049 0.016900 0.195939 -vn -0.456715 0.406971 -0.791066 -v -0.083599 0.016900 0.195819 -vn -0.791071 0.406953 -0.456723 -v -0.083270 0.016900 0.195489 -vn -0.913441 0.406971 -0.000002 -v -0.054149 0.016900 0.193039 -vn -0.791062 0.406978 0.456717 -v -0.054270 0.016900 0.192589 -vn -0.456719 0.406976 0.791061 -v -0.054599 0.016900 0.192260 -vn 0.000001 0.406973 0.913440 -v -0.055049 0.016900 0.192139 -vn 0.456720 0.406975 0.791062 -v -0.055499 0.016900 0.192260 -vn 0.791062 0.406977 0.456718 -v -0.055829 0.016900 0.192589 -vn 0.913444 0.406963 -0.000001 -v -0.055949 0.016900 0.193039 -vn 0.791065 0.406958 -0.456728 -v -0.055829 0.016900 0.193489 -vn 0.456723 0.406973 -0.791060 -v -0.055499 0.016900 0.193819 -vn -0.000001 0.406973 -0.913440 -v -0.055049 0.016900 0.193939 -vn -0.456720 0.406975 -0.791062 -v -0.054599 0.016900 0.193819 -vn -0.791066 0.406960 -0.456725 -v -0.054270 0.016900 0.193489 -vn -0.913440 0.406973 -0.000000 -v -0.069649 0.016900 0.193039 -vn -0.791059 0.406984 0.456716 -v -0.069770 0.016900 0.192589 -vn -0.456721 0.406977 0.791060 -v -0.070099 0.016900 0.192260 -vn 0.000001 0.406973 0.913440 -v -0.070549 0.016900 0.192139 -vn 0.456717 0.406975 0.791063 -v -0.070999 0.016900 0.192260 -vn 0.791066 0.406970 0.456717 -v -0.071329 0.016900 0.192589 -vn 0.913441 0.406971 0.000002 -v -0.071449 0.016900 0.193039 -vn 0.791067 0.406952 -0.456730 -v -0.071329 0.016900 0.193489 -vn 0.456722 0.406972 -0.791061 -v -0.070999 0.016900 0.193819 -vn -0.000001 0.406973 -0.913440 -v -0.070549 0.016900 0.193939 -vn -0.456722 0.406975 -0.791060 -v -0.070099 0.016900 0.193819 -vn -0.791062 0.406967 -0.456726 -v -0.069770 0.016900 0.193489 -vn -0.033951 0.496973 0.867101 -v -0.083049 0.016500 0.213905 -vn -0.019975 0.863074 0.504682 -v -0.083049 0.016866 0.213539 -vn -0.504679 0.863076 0.019976 -v -0.087549 0.016866 0.209039 -vn -0.503306 0.860423 0.079717 -v -0.087494 0.016866 0.209743 -vn -0.867103 0.496971 0.033954 -v -0.087915 0.016500 0.209039 -vn -0.858488 0.494479 0.135973 -v -0.087856 0.016500 0.209800 -vn -0.826646 0.494483 0.268594 -v -0.087677 0.016500 0.210543 -vn -0.774452 0.494483 0.394603 -v -0.087385 0.016500 0.211248 -vn -0.703187 0.494483 0.510896 -v -0.086986 0.016500 0.211899 -vn -0.614612 0.494478 0.614609 -v -0.086490 0.016500 0.212480 -vn -0.510895 0.494484 0.703188 -v -0.085910 0.016500 0.212976 -vn -0.394601 0.494481 0.774454 -v -0.085259 0.016500 0.213375 -vn -0.268595 0.494482 0.826647 -v -0.084553 0.016500 0.213667 -vn -0.135974 0.494478 0.858488 -v -0.083811 0.016500 0.213845 -vn -0.484642 0.860422 0.157470 -v -0.087329 0.016866 0.210430 -vn -0.454039 0.860423 0.231345 -v -0.087059 0.016866 0.211082 -vn -0.412261 0.860423 0.299523 -v -0.086690 0.016866 0.211684 -vn -0.360327 0.860424 0.360328 -v -0.086231 0.016866 0.212221 -vn -0.299524 0.860423 0.412259 -v -0.085694 0.016866 0.212680 -vn -0.231343 0.860423 0.454041 -v -0.085092 0.016866 0.213049 -vn -0.157470 0.860423 0.484640 -v -0.084440 0.016866 0.213319 -vn -0.079717 0.860423 0.503307 -v -0.083753 0.016866 0.213484 -vn -0.504679 0.863076 -0.019975 -v -0.087549 0.016866 0.193039 -vn -0.867103 0.496970 -0.033954 -v -0.087915 0.016500 0.193039 -vn -0.019976 0.863077 -0.504677 -v -0.083049 0.016866 0.188539 -vn -0.079714 0.860422 -0.503308 -v -0.083753 0.016866 0.188595 -vn -0.033959 0.496980 -0.867097 -v -0.083049 0.016500 0.188173 -vn -0.135971 0.494481 -0.858487 -v -0.083811 0.016500 0.188233 -vn -0.268595 0.494481 -0.826647 -v -0.084553 0.016500 0.188411 -vn -0.394607 0.494482 -0.774450 -v -0.085259 0.016500 0.188703 -vn -0.510895 0.494484 -0.703187 -v -0.085910 0.016500 0.189102 -vn -0.614608 0.494485 -0.614607 -v -0.086490 0.016500 0.189598 -vn -0.703188 0.494484 -0.510895 -v -0.086986 0.016500 0.190179 -vn -0.774452 0.494479 -0.394606 -v -0.087385 0.016500 0.190830 -vn -0.826647 0.494480 -0.268596 -v -0.087677 0.016500 0.191535 -vn -0.858489 0.494478 -0.135972 -v -0.087856 0.016500 0.192278 -vn -0.157470 0.860422 -0.484641 -v -0.084440 0.016866 0.188759 -vn -0.231347 0.860422 -0.454040 -v -0.085092 0.016866 0.189030 -vn -0.299525 0.860422 -0.412261 -v -0.085694 0.016866 0.189399 -vn -0.360329 0.860422 -0.360328 -v -0.086231 0.016866 0.189857 -vn -0.412261 0.860421 -0.299526 -v -0.086690 0.016866 0.190394 -vn -0.454041 0.860421 -0.231347 -v -0.087059 0.016866 0.190996 -vn -0.484639 0.860424 -0.157468 -v -0.087329 0.016866 0.191649 -vn -0.503307 0.860423 -0.079717 -v -0.087494 0.016866 0.192335 -vn -0.495890 0.127828 -0.858926 -v -0.050899 0.019700 0.191079 -vn -0.858924 0.127836 -0.495890 -v -0.051009 0.019700 0.191189 -vn 0.069833 0.854930 -0.514022 -v -0.044349 0.019960 0.191189 -vn -0.069823 0.854934 -0.514017 -v -0.050749 0.019960 0.191189 -vn 0.112932 0.488323 -0.865325 -v -0.044349 0.019850 0.191079 -vn -0.112921 0.488325 -0.865325 -v -0.050749 0.019850 0.191079 -vn 0.858924 0.127829 -0.495892 -v -0.044090 0.019700 0.191189 -vn 0.495889 0.127832 -0.858926 -v -0.044199 0.019700 0.191079 -vn -0.865321 0.488332 -0.112924 -v -0.051009 0.019850 0.191339 -vn -0.758624 0.482355 -0.437977 -v -0.050974 0.019850 0.191209 -vn -0.265472 0.847443 -0.459744 -v -0.050824 0.019960 0.191209 -vn -0.459772 0.847442 -0.265429 -v -0.050879 0.019960 0.191264 -vn -0.437998 0.482352 -0.758613 -v -0.050879 0.019850 0.191114 -vn -0.514025 0.854929 -0.069820 -v -0.050899 0.019960 0.191339 -vn 0.437991 0.482353 -0.758617 -v -0.044220 0.019850 0.191114 -vn 0.514023 0.854931 -0.069814 -v -0.044199 0.019960 0.191339 -vn 0.459764 0.847443 -0.265438 -v -0.044220 0.019960 0.191264 -vn 0.265478 0.847438 -0.459751 -v -0.044274 0.019960 0.191209 -vn 0.758624 0.482352 -0.437979 -v -0.044124 0.019850 0.191209 -vn 0.865323 0.488332 -0.112912 -v -0.044090 0.019850 0.191339 -vn -0.858916 0.127835 0.495904 -v -0.051009 0.019700 0.196889 -vn -0.495888 0.127834 0.858926 -v -0.050899 0.019700 0.196999 -vn -0.514025 0.854929 0.069820 -v -0.050899 0.019960 0.196739 -vn -0.865320 0.488332 0.112931 -v -0.051009 0.019850 0.196739 -vn 0.514027 0.854928 0.069820 -v -0.044199 0.019960 0.196739 -vn 0.865321 0.488332 0.112924 -v -0.044090 0.019850 0.196739 -vn 0.495892 0.127828 0.858924 -v -0.044199 0.019700 0.196999 -vn 0.858918 0.127828 0.495904 -v -0.044090 0.019700 0.196889 -vn -0.112928 0.488323 0.865325 -v -0.050749 0.019850 0.196999 -vn -0.437993 0.482344 0.758621 -v -0.050879 0.019850 0.196964 -vn -0.459764 0.847433 0.265470 -v -0.050879 0.019960 0.196814 -vn -0.265442 0.847438 0.459771 -v -0.050824 0.019960 0.196869 -vn -0.758620 0.482346 0.437993 -v -0.050974 0.019850 0.196869 -vn -0.069830 0.854925 0.514031 -v -0.050749 0.019960 0.196889 -vn 0.758622 0.482346 0.437989 -v -0.044124 0.019850 0.196869 -vn 0.069827 0.854927 0.514027 -v -0.044349 0.019960 0.196889 -vn 0.265458 0.847437 0.459763 -v -0.044274 0.019960 0.196869 -vn 0.459764 0.847430 0.265479 -v -0.044220 0.019960 0.196814 -vn 0.437997 0.482351 0.758615 -v -0.044220 0.019850 0.196964 -vn 0.112924 0.488324 0.865325 -v -0.044349 0.019850 0.196999 -vn 0.858941 0.127810 -0.495868 -v -0.044090 0.019700 0.205189 -vn 0.495912 0.127824 -0.858914 -v -0.044199 0.019700 0.205079 -vn 0.865324 0.488329 -0.112915 -v -0.044090 0.019850 0.205339 -vn 0.865321 0.488332 0.112924 -v -0.044090 0.019850 0.210739 -vn 0.514023 0.854931 -0.069814 -v -0.044199 0.019960 0.205339 -vn 0.514027 0.854928 0.069820 -v -0.044199 0.019960 0.210739 -vn 0.495892 0.127828 0.858924 -v -0.044199 0.019700 0.210999 -vn 0.858918 0.127828 0.495904 -v -0.044090 0.019700 0.210889 -vn 0.112922 0.488342 -0.865315 -v -0.044349 0.019850 0.205079 -vn 0.437991 0.482353 -0.758617 -v -0.044220 0.019850 0.205114 -vn 0.459764 0.847443 -0.265438 -v -0.044220 0.019960 0.205264 -vn 0.265448 0.847440 -0.459763 -v -0.044274 0.019960 0.205209 -vn 0.758631 0.482339 -0.437982 -v -0.044124 0.019850 0.205209 -vn 0.069777 0.854952 -0.513993 -v -0.044349 0.019960 0.205189 -vn 0.758622 0.482346 0.437989 -v -0.044124 0.019850 0.210869 -vn 0.069827 0.854927 0.514027 -v -0.044349 0.019960 0.210889 -vn 0.265458 0.847437 0.459763 -v -0.044274 0.019960 0.210869 -vn 0.459764 0.847430 0.265479 -v -0.044220 0.019960 0.210814 -vn 0.437997 0.482351 0.758615 -v -0.044220 0.019850 0.210964 -vn 0.112924 0.488324 0.865325 -v -0.044349 0.019850 0.210999 -vn -0.495918 0.127828 -0.858909 -v -0.050899 0.019700 0.205079 -vn -0.858936 0.127822 -0.495874 -v -0.051009 0.019700 0.205189 -vn -0.112919 0.488353 -0.865310 -v -0.050749 0.019850 0.205079 -vn -0.069788 0.854945 -0.514002 -v -0.050749 0.019960 0.205189 -vn -0.112928 0.488323 0.865325 -v -0.050749 0.019850 0.210999 -vn -0.069830 0.854925 0.514031 -v -0.050749 0.019960 0.210889 -vn -0.858916 0.127835 0.495904 -v -0.051009 0.019700 0.210889 -vn -0.495888 0.127834 0.858926 -v -0.050899 0.019700 0.210999 -vn -0.865321 0.488332 -0.112924 -v -0.051009 0.019850 0.205339 -vn -0.758627 0.482337 -0.437991 -v -0.050974 0.019850 0.205209 -vn -0.265431 0.847437 -0.459780 -v -0.050824 0.019960 0.205209 -vn -0.459772 0.847442 -0.265429 -v -0.050879 0.019960 0.205264 -vn -0.437999 0.482354 -0.758611 -v -0.050879 0.019850 0.205114 -vn -0.514025 0.854929 -0.069820 -v -0.050899 0.019960 0.205339 -vn -0.437993 0.482344 0.758621 -v -0.050879 0.019850 0.210964 -vn -0.514025 0.854929 0.069820 -v -0.050899 0.019960 0.210739 -vn -0.459764 0.847433 0.265470 -v -0.050879 0.019960 0.210814 -vn -0.265442 0.847438 0.459771 -v -0.050824 0.019960 0.210869 -vn -0.758620 0.482346 0.437993 -v -0.050974 0.019850 0.210869 -vn -0.865320 0.488332 0.112931 -v -0.051009 0.019850 0.210739 -vn 0.503301 0.860426 -0.079715 -v -0.071364 0.019760 0.200218 -vn 0.484640 0.860423 -0.157469 -v -0.071556 0.019760 0.199417 -vn 0.454044 0.860420 -0.231348 -v -0.071872 0.019760 0.198656 -vn 0.412268 0.860417 -0.299530 -v -0.072302 0.019760 0.197953 -vn 0.360317 0.860430 -0.360322 -v -0.072837 0.019760 0.197327 -vn 0.299526 0.860423 -0.412258 -v -0.073464 0.019760 0.196792 -vn 0.231345 0.860423 -0.454040 -v -0.074166 0.019760 0.196361 -vn 0.157469 0.860419 -0.484647 -v -0.074927 0.019760 0.196046 -vn 0.079720 0.860415 -0.503319 -v -0.075728 0.019760 0.195854 -vn -0.000002 0.860424 -0.509578 -v -0.076549 0.019760 0.195789 -vn -0.079717 0.860415 -0.503320 -v -0.077371 0.019760 0.195854 -vn -0.157469 0.860419 -0.484646 -v -0.078172 0.019760 0.196046 -vn -0.231345 0.860424 -0.454038 -v -0.078933 0.019760 0.196361 -vn -0.299524 0.860423 -0.412259 -v -0.079635 0.019760 0.196792 -vn -0.360321 0.860429 -0.360320 -v -0.080262 0.019760 0.197327 -vn -0.412267 0.860416 -0.299533 -v -0.080797 0.019760 0.197953 -vn -0.454043 0.860420 -0.231348 -v -0.081227 0.019760 0.198656 -vn -0.484640 0.860423 -0.157469 -v -0.081543 0.019760 0.199417 -vn -0.503302 0.860426 -0.079713 -v -0.081735 0.019760 0.200218 -vn -0.509582 0.860422 -0.000001 -v -0.081799 0.019760 0.201039 -vn -0.503300 0.860427 0.079716 -v -0.081735 0.019760 0.201860 -vn -0.484640 0.860423 0.157469 -v -0.081543 0.019760 0.202661 -vn -0.454033 0.860428 0.231341 -v -0.081227 0.019760 0.203423 -vn -0.412255 0.860426 0.299520 -v -0.080797 0.019760 0.204125 -vn -0.360334 0.860418 0.360333 -v -0.080262 0.019760 0.204751 -vn -0.299519 0.860427 0.412255 -v -0.079635 0.019760 0.205286 -vn -0.231353 0.860413 0.454054 -v -0.078933 0.019760 0.205717 -vn -0.157463 0.860431 0.484627 -v -0.078172 0.019760 0.206032 -vn -0.079717 0.860419 0.503313 -v -0.077371 0.019760 0.206224 -vn -0.000000 0.860420 0.509585 -v -0.076549 0.019760 0.206289 -vn 0.079715 0.860420 0.503312 -v -0.075728 0.019760 0.206224 -vn 0.157468 0.860431 0.484627 -v -0.074927 0.019760 0.206032 -vn 0.231348 0.860413 0.454058 -v -0.074166 0.019760 0.205717 -vn 0.299522 0.860427 0.412252 -v -0.073464 0.019760 0.205286 -vn 0.360332 0.860418 0.360336 -v -0.072837 0.019760 0.204751 -vn 0.412255 0.860427 0.299518 -v -0.072302 0.019760 0.204125 -vn 0.454033 0.860428 0.231340 -v -0.071872 0.019760 0.203423 -vn 0.484639 0.860423 0.157470 -v -0.071556 0.019760 0.202661 -vn 0.503300 0.860427 0.079715 -v -0.071364 0.019760 0.201860 -vn 0.509582 0.860422 0.000001 -v -0.071299 0.019760 0.201039 -vn 0.858486 0.494483 -0.135972 -v -0.071256 0.019650 0.200201 -vn 0.826655 0.494467 -0.268596 -v -0.071452 0.019650 0.199383 -vn 0.774455 0.494476 -0.394604 -v -0.071774 0.019650 0.198606 -vn 0.703191 0.494477 -0.510896 -v -0.072213 0.019650 0.197889 -vn 0.614610 0.494476 -0.614612 -v -0.072760 0.019650 0.197249 -vn 0.510894 0.494486 -0.703186 -v -0.073399 0.019650 0.196703 -vn 0.394608 0.494475 -0.774454 -v -0.074116 0.019650 0.196263 -vn 0.268589 0.494503 -0.826636 -v -0.074893 0.019650 0.195942 -vn 0.135969 0.494505 -0.858474 -v -0.075711 0.019650 0.195745 -vn 0.000004 0.494469 -0.869195 -v -0.076549 0.019650 0.195679 -vn -0.135974 0.494508 -0.858471 -v -0.077388 0.019650 0.195745 -vn -0.268592 0.494500 -0.826637 -v -0.078206 0.019650 0.195942 -vn -0.394605 0.494472 -0.774457 -v -0.078983 0.019650 0.196263 -vn -0.510896 0.494486 -0.703185 -v -0.079700 0.019650 0.196703 -vn -0.614609 0.494478 -0.614612 -v -0.080339 0.019650 0.197249 -vn -0.703190 0.494479 -0.510895 -v -0.080886 0.019650 0.197889 -vn -0.774457 0.494475 -0.394603 -v -0.081325 0.019650 0.198606 -vn -0.826655 0.494466 -0.268599 -v -0.081647 0.019650 0.199383 -vn -0.858486 0.494483 -0.135969 -v -0.081843 0.019650 0.200201 -vn -0.869196 0.494469 -0.000002 -v -0.081909 0.019650 0.201039 -vn -0.858486 0.494484 0.135973 -v -0.081843 0.019650 0.201878 -vn -0.826649 0.494478 0.268594 -v -0.081647 0.019650 0.202695 -vn -0.774458 0.494470 0.394607 -v -0.081325 0.019650 0.203472 -vn -0.703191 0.494473 0.510900 -v -0.080886 0.019650 0.204190 -vn -0.614609 0.494486 0.614605 -v -0.080339 0.019650 0.204829 -vn -0.510894 0.494486 0.703186 -v -0.079700 0.019650 0.205375 -vn -0.394603 0.494484 0.774451 -v -0.078983 0.019650 0.205815 -vn -0.268593 0.494487 0.826644 -v -0.078206 0.019650 0.206137 -vn -0.135975 0.494470 0.858493 -v -0.077388 0.019650 0.206333 -vn 0.000004 0.494507 0.869174 -v -0.076549 0.019650 0.206399 -vn 0.135969 0.494467 0.858496 -v -0.075711 0.019650 0.206333 -vn 0.268595 0.494490 0.826642 -v -0.074893 0.019650 0.206137 -vn 0.394602 0.494486 0.774450 -v -0.074116 0.019650 0.205815 -vn 0.510895 0.494485 0.703187 -v -0.073399 0.019650 0.205375 -vn 0.614610 0.494486 0.614604 -v -0.072760 0.019650 0.204829 -vn 0.703192 0.494470 0.510902 -v -0.072213 0.019650 0.204190 -vn 0.774457 0.494470 0.394608 -v -0.071774 0.019650 0.203472 -vn 0.826649 0.494479 0.268593 -v -0.071452 0.019650 0.202695 -vn 0.858486 0.494483 0.135971 -v -0.071256 0.019650 0.201878 -vn 0.869196 0.494469 0.000002 -v -0.071190 0.019650 0.201039 -vn 0.513712 -0.673143 -0.531957 -v -0.078460 -0.018500 0.203017 -vn 0.313587 -0.674180 -0.668688 -v -0.077714 -0.018500 0.203530 -vn 0.465217 -0.389834 -0.794735 -v -0.077755 -0.019700 0.203511 -vn 0.079089 -0.675658 -0.732961 -v -0.076842 -0.018500 0.203774 -vn 0.189281 -0.390519 -0.900926 -v -0.076932 -0.019700 0.203762 -vn 0.329015 -0.386447 -0.861631 -v -0.077714 -0.019700 0.203530 -vn -0.163111 -0.676926 -0.717750 -v -0.075938 -0.018500 0.203720 -vn -0.113050 -0.397981 -0.910401 -v -0.076072 -0.019700 0.203747 -vn 0.046097 -0.392171 -0.918737 -v -0.076842 -0.019700 0.203774 -vn -0.386933 -0.678008 -0.624970 -v -0.075101 -0.018500 0.203377 -vn -0.390175 -0.391668 -0.833282 -v -0.075258 -0.019700 0.203467 -vn -0.256504 -0.381569 -0.888037 -v -0.075938 -0.019700 0.203720 -vn -0.568332 -0.678900 -0.464858 -v -0.074420 -0.018500 0.202780 -vn -0.634075 -0.392139 -0.666465 -v -0.074571 -0.019700 0.202949 -vn -0.525300 -0.379258 -0.761724 -v -0.075101 -0.019700 0.203377 -vn -0.687894 -0.679606 -0.254828 -v -0.073971 -0.018500 0.201994 -vn -0.812503 -0.392534 -0.430995 -v -0.074078 -0.019700 0.202245 -vn -0.740182 -0.377173 -0.556660 -v -0.074420 -0.019700 0.202780 -vn -0.732877 -0.680134 -0.017591 -v -0.073800 -0.018500 0.201105 -vn -0.907101 -0.392845 -0.151131 -v -0.073826 -0.019700 0.201422 -vn -0.878977 -0.375401 -0.294063 -v -0.073971 -0.019700 0.201994 -vn -0.698557 -0.680483 0.221271 -v -0.073928 -0.018500 0.200209 -vn -0.908124 -0.393062 0.144266 -v -0.073841 -0.019700 0.200562 -vn -0.927426 -0.374007 -0.000993 -v -0.073800 -0.019700 0.201105 -vn -0.588713 -0.680660 0.436027 -v -0.074340 -0.018500 0.199402 -vn -0.815461 -0.393206 0.424749 -v -0.074121 -0.019700 0.199748 -vn -0.880548 -0.373047 0.292353 -v -0.073928 -0.019700 0.200209 -vn -0.415217 -0.680658 0.603573 -v -0.074991 -0.018500 0.198773 -vn -0.632565 -0.385468 0.671771 -v -0.074639 -0.019700 0.199061 -vn -0.743186 -0.372563 0.555761 -v -0.074340 -0.019700 0.199402 -vn -0.196757 -0.680487 0.705850 -v -0.075811 -0.018500 0.198390 -vn -0.387934 -0.386238 0.836856 -v -0.075344 -0.019700 0.198567 -vn -0.551227 -0.340445 0.761739 -v -0.074991 -0.019700 0.198773 -vn 0.043155 -0.680133 0.731817 -v -0.076711 -0.018500 0.198294 -vn -0.116077 -0.396403 0.910709 -v -0.076167 -0.019700 0.198316 -vn -0.279389 -0.347431 0.895116 -v -0.075811 -0.019700 0.198390 -vn 0.278679 -0.679607 0.678581 -v -0.077594 -0.018500 0.198495 -vn 0.190753 -0.387549 0.901898 -v -0.077027 -0.019700 0.198331 -vn 0.039225 -0.388765 0.920502 -v -0.076711 -0.019700 0.198294 -vn 0.484412 -0.678899 0.551762 -v -0.078363 -0.018500 0.198972 -vn 0.465629 -0.388088 0.795347 -v -0.077841 -0.019700 0.198611 -vn 0.316059 -0.360370 0.877633 -v -0.077594 -0.019700 0.198495 -vn 0.638091 -0.678009 0.364888 -v -0.078936 -0.018500 0.199673 -vn 0.692765 -0.388557 0.607536 -v -0.078528 -0.019700 0.199129 -vn 0.577854 -0.366266 0.729338 -v -0.078363 -0.019700 0.198972 -vn 0.723005 -0.676926 0.137967 -v -0.079250 -0.018500 0.200522 -vn 0.848964 -0.388966 0.357723 -v -0.079021 -0.019700 0.199834 -vn 0.778417 -0.371753 0.505833 -v -0.078936 -0.019700 0.199673 -vn 0.729756 -0.675655 -0.104626 -v -0.079272 -0.018500 0.201427 -vn 0.913961 -0.397711 0.080629 -v -0.079273 -0.019700 0.200656 -vn 0.897145 -0.376778 0.230584 -v -0.079250 -0.019700 0.200522 -vn 0.657335 -0.674182 -0.336733 -v -0.078999 -0.018500 0.202290 -vn 0.893833 -0.389597 -0.221982 -v -0.079258 -0.019700 0.201517 -vn 0.915195 -0.395233 -0.078802 -v -0.079272 -0.019700 0.201427 -vn 0.637616 -0.396861 -0.660263 -v -0.078460 -0.019700 0.203017 -vn 0.778005 -0.389838 -0.492681 -v -0.078978 -0.019700 0.202330 -vn 0.850591 -0.385336 -0.357786 -v -0.078999 -0.019700 0.202290 -vn -0.374757 -0.916683 -0.138745 -v -0.086584 -0.020000 0.197324 -vn -0.346807 -0.916684 -0.198534 -v -0.085836 -0.020000 0.195723 -vn 0.356302 -0.934359 0.004719 -v -0.079598 -0.020000 0.200961 -vn 0.151265 -0.976003 -0.156641 -v -0.071507 -0.020000 0.207334 -vn 0.052682 -0.976002 -0.211291 -v -0.071043 -0.020000 0.207591 -vn 0.242083 -0.911768 0.331775 -v -0.070413 -0.020000 0.209805 -vn -0.060020 -0.976003 -0.209320 -v -0.070512 -0.020000 0.207582 -vn -0.005098 -0.930603 0.365995 -v -0.076472 -0.020000 0.197990 -vn 0.206174 -0.915899 -0.344416 -v -0.070722 -0.020000 0.192065 -vn 0.156644 -0.976002 0.151270 -v -0.071730 -0.020000 0.194572 -vn -0.014962 -0.933409 -0.358503 -v -0.076365 -0.020000 0.204084 -vn 0.211291 -0.976002 0.052682 -v -0.071789 -0.020000 0.206348 -vn 0.209318 -0.976004 -0.060021 -v -0.071780 -0.020000 0.206879 -vn -0.209325 -0.976002 0.060022 -v -0.069809 -0.020000 0.206314 -vn 0.346807 -0.916684 0.198533 -v -0.067263 -0.020000 0.206355 -vn -0.211290 -0.976003 -0.052681 -v -0.069800 -0.020000 0.206844 -vn 0.309396 -0.916686 0.252905 -v -0.068265 -0.020000 0.207811 -vn -0.156643 -0.976002 -0.151270 -v -0.070057 -0.020000 0.207308 -vn -0.151264 -0.976004 0.156640 -v -0.070083 -0.020000 0.205859 -vn 0.392474 -0.916687 0.075168 -v -0.066040 -0.020000 0.203052 -vn 0.374754 -0.916684 0.138743 -v -0.066515 -0.020000 0.204754 -vn 0.211290 -0.976003 0.052681 -v -0.071987 -0.020000 0.195036 -vn 0.209329 -0.976002 -0.060022 -v -0.071977 -0.020000 0.195567 -vn -0.064056 -0.930830 0.359796 -v -0.076125 -0.020000 0.198019 -vn 0.265976 -0.917903 0.294467 -v -0.069493 -0.020000 0.209082 -vn 0.355885 -0.916687 -0.181744 -v -0.067020 -0.020000 0.196173 -vn 0.380947 -0.916686 -0.120688 -v -0.066349 -0.020000 0.197808 -vn -0.052681 -0.976002 0.211292 -v -0.070547 -0.020000 0.205602 -vn 0.395617 -0.916686 -0.056341 -v -0.065956 -0.020000 0.199531 -vn 0.399500 -0.916683 0.009542 -v -0.065853 -0.020000 0.201295 -vn 0.060021 -0.976004 0.209318 -v -0.071077 -0.020000 0.205611 -vn 0.052679 -0.976003 -0.211290 -v -0.071240 -0.020000 0.196279 -vn -0.060024 -0.976001 -0.209332 -v -0.070710 -0.020000 0.196270 -vn -0.356715 -0.932767 -0.051966 -v -0.073529 -0.020000 0.201464 -vn -0.322410 -0.933025 -0.159737 -v -0.073808 -0.020000 0.202376 -vn -0.256417 -0.933383 -0.251092 -v -0.074355 -0.020000 0.203158 -vn 0.156641 -0.976003 0.151265 -v -0.071532 -0.020000 0.205884 -vn -0.165621 -0.933858 -0.316983 -v -0.075118 -0.020000 0.203732 -vn -0.076189 -0.930828 -0.357426 -v -0.076020 -0.020000 0.204043 -vn -0.355675 -0.932590 0.061418 -v -0.073546 -0.020000 0.200509 -vn -0.319219 -0.932493 0.168987 -v -0.073856 -0.020000 0.199607 -vn 0.151274 -0.976001 -0.156646 -v -0.071704 -0.020000 0.196022 -vn -0.242175 -0.934776 0.259893 -v -0.074431 -0.020000 0.198845 -vn -0.151818 -0.935148 0.320077 -v -0.075212 -0.020000 0.198298 -vn -0.156640 -0.976004 -0.151264 -v -0.070255 -0.020000 0.195996 -vn -0.211295 -0.976002 -0.052680 -v -0.069998 -0.020000 0.195532 -vn 0.321117 -0.916687 -0.237841 -v -0.067951 -0.020000 0.194671 -vn -0.209318 -0.976004 0.060021 -v -0.070007 -0.020000 0.195002 -vn 0.277595 -0.916683 -0.287459 -v -0.069117 -0.020000 0.193342 -vn -0.151265 -0.976003 0.156641 -v -0.070280 -0.020000 0.194547 -vn 0.233913 -0.919656 -0.315464 -v -0.070485 -0.020000 0.192224 -vn -0.052682 -0.976002 0.211291 -v -0.070744 -0.020000 0.194290 -vn 0.060021 -0.976004 0.209318 -v -0.071275 -0.020000 0.194299 -vn -0.151275 -0.976001 0.156646 -v -0.081592 -0.020000 0.194745 -vn -0.052679 -0.976003 0.211289 -v -0.082056 -0.020000 0.194487 -vn -0.151736 -0.916686 -0.369679 -v -0.080612 -0.020000 0.191140 -vn -0.309401 -0.916683 -0.252910 -v -0.084834 -0.020000 0.194267 -vn -0.263552 -0.916684 -0.300384 -v -0.083606 -0.020000 0.192996 -vn 0.060023 -0.976000 0.209334 -v -0.082587 -0.020000 0.194497 -vn 0.358166 -0.931356 0.065521 -v -0.079570 -0.020000 0.200615 -vn -0.060021 -0.976004 -0.209318 -v -0.082022 -0.020000 0.196467 -vn -0.210510 -0.916688 -0.339660 -v -0.082186 -0.020000 0.191944 -vn 0.151264 -0.976004 -0.156640 -v -0.083016 -0.020000 0.196219 -vn 0.052681 -0.976002 -0.211293 -v -0.082552 -0.020000 0.196476 -vn -0.211291 -0.976002 -0.052682 -v -0.081310 -0.020000 0.195730 -vn -0.209322 -0.976003 0.060020 -v -0.081319 -0.020000 0.195199 -vn 0.166149 -0.917267 -0.361961 -v -0.072019 -0.020000 0.191346 -vn 0.107322 -0.916686 -0.384928 -v -0.073676 -0.020000 0.190732 -vn 0.156643 -0.976003 0.151269 -v -0.083042 -0.020000 0.194770 -vn 0.211294 -0.976002 0.052679 -v -0.083299 -0.020000 0.195234 -vn 0.209325 -0.976002 -0.060022 -v -0.083289 -0.020000 0.195764 -vn 0.074590 -0.933541 0.350623 -v -0.077079 -0.020000 0.198035 -vn 0.169551 -0.935067 0.311290 -v -0.077981 -0.020000 0.198346 -vn -0.156641 -0.976003 -0.151265 -v -0.081567 -0.020000 0.196194 -vn 0.257042 -0.935158 0.243739 -v -0.078743 -0.020000 0.198920 -vn 0.319166 -0.935333 0.152597 -v -0.079291 -0.020000 0.199702 -vn -0.088818 -0.916685 -0.389615 -v -0.078928 -0.020000 0.190607 -vn -0.023481 -0.916681 -0.398929 -v -0.077178 -0.020000 0.190358 -vn 0.042502 -0.916688 -0.397336 -v -0.075411 -0.020000 0.190400 -vn 0.360730 -0.932525 -0.016493 -v -0.079594 -0.020000 0.201223 -vn -0.355889 -0.916685 0.181747 -v -0.086079 -0.020000 0.205906 -vn -0.380950 -0.916685 0.120691 -v -0.086750 -0.020000 0.204271 -vn -0.395614 -0.916687 0.056340 -v -0.087143 -0.020000 0.202548 -vn -0.399500 -0.916683 -0.009542 -v -0.087246 -0.020000 0.200784 -vn -0.392474 -0.916686 -0.075169 -v -0.087058 -0.020000 0.199026 -vn 0.155505 -0.936217 -0.315145 -v -0.077886 -0.020000 0.203780 -vn 0.060406 -0.933461 -0.353555 -v -0.076974 -0.020000 0.204059 -vn -0.209325 -0.976002 0.060022 -v -0.081121 -0.020000 0.206511 -vn -0.211290 -0.976003 -0.052681 -v -0.081112 -0.020000 0.207042 -vn 0.242506 -0.937085 -0.251123 -v -0.078668 -0.020000 0.203233 -vn -0.151264 -0.976004 0.156641 -v -0.081395 -0.020000 0.206057 -vn 0.309331 -0.936471 -0.165340 -v -0.079242 -0.020000 0.202471 -vn -0.052681 -0.976002 0.211292 -v -0.081859 -0.020000 0.205799 -vn 0.352391 -0.932375 -0.080601 -v -0.079553 -0.020000 0.201569 -vn 0.060021 -0.976004 0.209318 -v -0.082389 -0.020000 0.205809 -vn 0.156641 -0.976003 0.151265 -v -0.082844 -0.020000 0.206082 -vn 0.211291 -0.976002 0.052682 -v -0.083101 -0.020000 0.206546 -vn -0.321118 -0.916687 0.237842 -v -0.085148 -0.020000 0.207408 -vn 0.209318 -0.976004 -0.060021 -v -0.083092 -0.020000 0.207076 -vn -0.277595 -0.916684 0.287458 -v -0.083982 -0.020000 0.208736 -vn 0.151265 -0.976003 -0.156641 -v -0.082819 -0.020000 0.207531 -vn -0.226497 -0.916682 0.329233 -v -0.082614 -0.020000 0.209854 -vn 0.052682 -0.976002 -0.211291 -v -0.082355 -0.020000 0.207788 -vn -0.169214 -0.916688 0.362007 -v -0.081080 -0.020000 0.210732 -vn -0.060020 -0.976003 -0.209320 -v -0.081824 -0.020000 0.207779 -vn -0.107322 -0.916686 0.384928 -v -0.079423 -0.020000 0.211346 -vn -0.156643 -0.976002 -0.151270 -v -0.081369 -0.020000 0.207506 -vn 0.198167 -0.919039 0.340731 -v -0.070913 -0.020000 0.210134 -vn 0.151734 -0.916686 0.369679 -v -0.072487 -0.020000 0.210938 -vn 0.088820 -0.916685 0.389614 -v -0.074171 -0.020000 0.211471 -vn 0.023479 -0.916686 0.398918 -v -0.075921 -0.020000 0.211721 -vn -0.042500 -0.916683 0.397349 -v -0.077687 -0.020000 0.211678 -vn -0.643755 0.375745 0.666629 -v -0.084191 -0.015800 0.208952 -vn -0.525254 -0.375741 0.763496 -v -0.082784 -0.019700 0.210102 -vn -0.525256 0.375741 0.763495 -v -0.082784 -0.015800 0.210102 -vn -0.392423 -0.375753 0.839532 -v -0.081207 -0.019700 0.211004 -vn -0.392421 0.375753 0.839533 -v -0.081207 -0.015800 0.211004 -vn -0.248885 -0.375748 0.892676 -v -0.079504 -0.019700 0.211635 -vn -0.248885 0.375749 0.892675 -v -0.079504 -0.015800 0.211635 -vn -0.098561 -0.375743 0.921468 -v -0.077719 -0.019700 0.211977 -vn -0.098562 0.375744 0.921467 -v -0.077719 -0.015800 0.211977 -vn 0.054450 -0.375749 0.925120 -v -0.075903 -0.019700 0.212020 -vn 0.054451 0.375749 0.925120 -v -0.075903 -0.015800 0.212020 -vn 0.205979 -0.375748 0.903541 -v -0.074105 -0.019700 0.211764 -vn 0.205978 0.375748 0.903541 -v -0.074105 -0.015800 0.211764 -vn 0.351885 -0.375749 0.857315 -v -0.072373 -0.019700 0.211215 -vn 0.351886 0.375749 0.857315 -v -0.072373 -0.015800 0.211215 -vn 0.484072 -0.370879 0.792542 -v -0.070755 -0.019700 0.210389 -vn 0.488194 0.375744 0.787707 -v -0.070755 -0.015800 0.210389 -vn 0.614874 -0.373017 0.694829 -v -0.069295 -0.019700 0.209308 -vn 0.611188 0.375752 0.696605 -v -0.069295 -0.015800 0.209308 -vn 0.717513 -0.375749 0.586505 -v -0.068033 -0.019700 0.208001 -vn 0.717513 0.375750 0.586505 -v -0.068033 -0.015800 0.208001 -vn 0.804264 -0.375745 0.460409 -v -0.067003 -0.019700 0.206504 -vn 0.804238 0.372879 0.462777 -v -0.067003 -0.015800 0.206504 -vn 0.869074 -0.375746 0.321754 -v -0.066234 -0.019700 0.204858 -vn 0.869074 0.375746 0.321755 -v -0.066234 -0.015800 0.204858 -vn 0.910178 -0.375750 0.174320 -v -0.065746 -0.019700 0.203108 -vn 0.910179 0.375750 0.174319 -v -0.065746 -0.015800 0.203108 -vn 0.926459 -0.375744 0.022130 -v -0.065553 -0.019700 0.201302 -vn 0.926459 0.375744 0.022131 -v -0.065553 -0.015800 0.201302 -vn 0.917465 -0.375748 -0.130659 -v -0.065659 -0.019700 0.199488 -vn 0.917465 0.375748 -0.130659 -v -0.065659 -0.015800 0.199488 -vn 0.883445 -0.375750 -0.279887 -v -0.066063 -0.019700 0.197717 -vn 0.883445 0.375750 -0.279887 -v -0.066063 -0.015800 0.197717 -vn 0.825327 -0.375751 -0.421481 -v -0.066753 -0.019700 0.196036 -vn 0.825327 0.375751 -0.421481 -v -0.066753 -0.015800 0.196036 -vn 0.744698 -0.375751 -0.551576 -v -0.067710 -0.019700 0.194492 -vn 0.744698 0.375752 -0.551576 -v -0.067710 -0.015800 0.194492 -vn 0.643756 -0.375744 -0.666629 -v -0.068908 -0.019700 0.193126 -vn 0.643757 0.375744 -0.666628 -v -0.068908 -0.015800 0.193126 -vn 0.530223 -0.371089 -0.762337 -v -0.070315 -0.019700 0.191977 -vn 0.525250 0.375749 -0.763495 -v -0.070315 -0.015800 0.191977 -vn 0.390853 -0.374421 -0.840858 -v -0.071892 -0.019700 0.191074 -vn 0.392422 0.375744 -0.839536 -v -0.071892 -0.015800 0.191074 -vn 0.248888 -0.375749 -0.892675 -v -0.073595 -0.019700 0.190443 -vn 0.248888 0.375748 -0.892675 -v -0.073595 -0.015800 0.190443 -vn 0.098563 -0.375752 -0.921464 -v -0.075380 -0.019700 0.190102 -vn 0.098560 0.375754 -0.921464 -v -0.075380 -0.015800 0.190102 -vn -0.054451 -0.375740 -0.925124 -v -0.077196 -0.019700 0.190058 -vn -0.054449 0.375741 -0.925124 -v -0.077196 -0.015800 0.190058 -vn -0.205975 -0.375748 -0.903542 -v -0.078994 -0.019700 0.190314 -vn -0.205976 0.375748 -0.903542 -v -0.078994 -0.015800 0.190314 -vn -0.351886 -0.375750 -0.857315 -v -0.080726 -0.019700 0.190863 -vn -0.351885 0.375750 -0.857315 -v -0.080726 -0.015800 0.190863 -vn -0.488195 -0.375752 -0.787703 -v -0.082344 -0.019700 0.191689 -vn -0.488196 0.375753 -0.787702 -v -0.082344 -0.015800 0.191689 -vn -0.611192 -0.375745 -0.696606 -v -0.083804 -0.019700 0.192771 -vn -0.611191 0.375746 -0.696606 -v -0.083804 -0.015800 0.192771 -vn -0.717514 -0.375743 -0.586507 -v -0.085066 -0.019700 0.194077 -vn -0.717514 0.375743 -0.586508 -v -0.085066 -0.015800 0.194077 -vn -0.804263 -0.375744 -0.460410 -v -0.086096 -0.019700 0.195574 -vn -0.804263 0.375745 -0.460409 -v -0.086096 -0.015800 0.195574 -vn -0.869076 -0.375743 -0.321753 -v -0.086865 -0.019700 0.197220 -vn -0.869075 0.375743 -0.321754 -v -0.086865 -0.015800 0.197220 -vn -0.910178 -0.375750 -0.174321 -v -0.087353 -0.019700 0.198970 -vn -0.910178 0.375750 -0.174319 -v -0.087353 -0.015800 0.198970 -vn -0.926459 -0.375744 -0.022131 -v -0.087546 -0.019700 0.200776 -vn -0.926459 0.375745 -0.022133 -v -0.087546 -0.015800 0.200776 -vn -0.917464 -0.375752 0.130657 -v -0.087440 -0.019700 0.202590 -vn -0.917463 0.375752 0.130659 -v -0.087440 -0.015800 0.202590 -vn -0.883446 -0.375747 0.279888 -v -0.087036 -0.019700 0.204361 -vn -0.883446 0.375748 0.279888 -v -0.087036 -0.015800 0.204361 -vn -0.825329 -0.375747 0.421480 -v -0.086346 -0.019700 0.206042 -vn -0.828955 0.371556 0.418066 -v -0.086346 -0.015800 0.206042 -vn -0.744698 -0.375751 0.551576 -v -0.085389 -0.019700 0.207586 -vn -0.744697 0.375752 0.551577 -v -0.085389 -0.015800 0.207586 -vn -0.643755 -0.375744 0.666630 -v -0.084191 -0.019700 0.208952 -vn -0.156645 0.976002 -0.151270 -v -0.081369 -0.015500 0.207506 -vn -0.060020 0.976003 -0.209321 -v -0.081824 -0.015500 0.207779 -vn -0.169211 0.916689 0.362007 -v -0.081080 -0.015500 0.210732 -vn -0.226498 0.916682 0.329230 -v -0.082614 -0.015500 0.209854 -vn 0.052681 0.976002 -0.211292 -v -0.082355 -0.015500 0.207788 -vn -0.277595 0.916684 0.287457 -v -0.083982 -0.015500 0.208736 -vn 0.151266 0.976003 -0.156642 -v -0.082819 -0.015500 0.207531 -vn -0.320528 0.916689 0.238627 -v -0.085148 -0.015500 0.207408 -vn 0.209320 0.976004 -0.060020 -v -0.083092 -0.015500 0.207076 -vn -0.365687 0.899796 0.237990 -v -0.085722 -0.015500 0.206548 -vn 0.211292 0.976002 0.052681 -v -0.083101 -0.015500 0.206546 -vn 0.156642 0.976003 0.151266 -v -0.082844 -0.015500 0.206082 -vn 0.060020 0.976004 0.209320 -v -0.082389 -0.015500 0.205809 -vn -0.683402 0.722331 0.105830 -v -0.081008 -0.015500 0.201652 -vn -0.052680 0.976002 0.211293 -v -0.081859 -0.015500 0.205799 -vn -0.651016 0.728540 0.213091 -v -0.080848 -0.015500 0.202370 -vn -0.209326 0.976002 0.060023 -v -0.081121 -0.015500 0.206511 -vn 0.160412 0.731171 0.663066 -v -0.075491 -0.015500 0.205413 -vn -0.009524 0.731171 0.682128 -v -0.076612 -0.015500 0.205539 -vn -0.107322 0.916685 0.384928 -v -0.079423 -0.015500 0.211346 -vn -0.042502 0.916683 0.397348 -v -0.077687 -0.015500 0.211678 -vn 0.023480 0.916686 0.398917 -v -0.075921 -0.015500 0.211721 -vn -0.211291 0.976002 -0.052681 -v -0.081112 -0.015500 0.207042 -vn 0.209321 0.976003 -0.060020 -v -0.071780 -0.015500 0.206879 -vn 0.211293 0.976002 0.052681 -v -0.071789 -0.015500 0.206348 -vn -0.178865 0.731173 0.658326 -v -0.077729 -0.015500 0.205382 -vn -0.336966 0.731172 0.593163 -v -0.078772 -0.015500 0.204952 -vn -0.151266 0.976003 0.156641 -v -0.081395 -0.015500 0.206057 -vn -0.473890 0.731172 0.490730 -v -0.079675 -0.015500 0.204276 -vn -0.581042 0.731173 0.357457 -v -0.080382 -0.015500 0.203397 -vn 0.686826 0.719461 0.103181 -v -0.072074 -0.015500 0.201510 -vn 0.645649 0.730064 0.223929 -v -0.072290 -0.015500 0.202489 -vn 0.060020 0.976003 0.209321 -v -0.071077 -0.015500 0.205611 -vn 0.570837 0.731171 0.373544 -v -0.072784 -0.015500 0.203503 -vn 0.156643 0.976003 0.151267 -v -0.071532 -0.015500 0.205884 -vn 0.460003 0.731172 0.503770 -v -0.073515 -0.015500 0.204362 -vn 0.320270 0.731171 0.602342 -v -0.074437 -0.015500 0.205012 -vn -0.052681 0.976002 0.211294 -v -0.070547 -0.015500 0.205602 -vn -0.151266 0.976003 0.156642 -v -0.070083 -0.015500 0.205859 -vn 0.355738 0.917636 0.177186 -v -0.067193 -0.015500 0.206230 -vn -0.209327 0.976002 0.060023 -v -0.069809 -0.015500 0.206314 -vn 0.151267 0.976003 -0.156643 -v -0.071507 -0.015500 0.207334 -vn 0.088819 0.916686 0.389614 -v -0.074171 -0.015500 0.211471 -vn 0.052681 0.976002 -0.211293 -v -0.071043 -0.015500 0.207591 -vn 0.263547 0.916688 0.300377 -v -0.069493 -0.015500 0.209082 -vn 0.309396 0.916686 0.252905 -v -0.068265 -0.015500 0.207811 -vn -0.211292 0.976002 -0.052682 -v -0.069800 -0.015500 0.206844 -vn 0.332469 0.919930 0.207830 -v -0.067263 -0.015500 0.206355 -vn -0.156646 0.976002 -0.151271 -v -0.070057 -0.015500 0.207308 -vn -0.060020 0.976003 -0.209323 -v -0.070512 -0.015500 0.207582 -vn 0.210514 0.916683 0.339669 -v -0.070913 -0.015500 0.210134 -vn 0.151735 0.916686 0.369679 -v -0.072487 -0.015500 0.210938 -vn 0.209331 0.976001 -0.060023 -v -0.071977 -0.015500 0.195567 -vn 0.211292 0.976002 0.052682 -v -0.071987 -0.015500 0.195036 -vn 0.094943 0.731172 -0.675555 -v -0.075923 -0.015500 0.196583 -vn -0.076043 0.731171 -0.677943 -v -0.077051 -0.015500 0.196567 -vn 0.156647 0.976002 0.151271 -v -0.071730 -0.015500 0.194572 -vn 0.169217 0.916684 -0.362018 -v -0.072019 -0.015500 0.191346 -vn 0.060021 0.976003 0.209321 -v -0.071275 -0.015500 0.194299 -vn 0.226491 0.916686 -0.329224 -v -0.070485 -0.015500 0.192224 -vn -0.052681 0.976002 0.211293 -v -0.070744 -0.015500 0.194290 -vn 0.277597 0.916683 -0.287458 -v -0.069117 -0.015500 0.193342 -vn -0.151267 0.976003 0.156643 -v -0.070280 -0.015500 0.194547 -vn 0.321117 0.916687 -0.237842 -v -0.067951 -0.015500 0.194671 -vn -0.209321 0.976003 0.060020 -v -0.070007 -0.015500 0.195002 -vn 0.355885 0.916687 -0.181744 -v -0.067020 -0.015500 0.196173 -vn -0.211298 0.976001 -0.052679 -v -0.069998 -0.015500 0.195532 -vn 0.380947 0.916686 -0.120688 -v -0.066349 -0.015500 0.197808 -vn -0.156641 0.976003 -0.151267 -v -0.070255 -0.015500 0.195996 -vn 0.395617 0.916686 -0.056341 -v -0.065956 -0.015500 0.199531 -vn 0.693209 0.720499 0.018542 -v -0.072063 -0.015500 0.201384 -vn 0.671827 0.731174 -0.118461 -v -0.072118 -0.015500 0.200258 -vn 0.399501 0.916683 0.009544 -v -0.065853 -0.015500 0.201295 -vn -0.060026 0.976000 -0.209334 -v -0.070710 -0.015500 0.196270 -vn 0.392474 0.916687 0.075167 -v -0.066040 -0.015500 0.203052 -vn 0.259962 0.731174 -0.630718 -v -0.074835 -0.015500 0.196879 -vn 0.408652 0.731172 -0.546251 -v -0.073854 -0.015500 0.197436 -vn 0.151275 0.976001 -0.156647 -v -0.071704 -0.015500 0.196022 -vn 0.531659 0.731172 -0.427465 -v -0.073042 -0.015500 0.198219 -vn 0.052681 0.976002 -0.211293 -v -0.071240 -0.015500 0.196279 -vn 0.621264 0.731171 -0.281817 -v -0.072451 -0.015500 0.199180 -vn 0.374820 0.916684 0.138563 -v -0.066515 -0.015500 0.204754 -vn 0.107321 0.916686 -0.384928 -v -0.073676 -0.015500 0.190732 -vn 0.042499 0.916688 -0.397337 -v -0.075411 -0.015500 0.190400 -vn -0.023477 0.916681 -0.398929 -v -0.077178 -0.015500 0.190358 -vn -0.088819 0.916686 -0.389613 -v -0.078928 -0.015500 0.190607 -vn -0.151735 0.916687 -0.369678 -v -0.080612 -0.015500 0.191140 -vn 0.151266 0.976003 -0.156641 -v -0.083016 -0.015500 0.196219 -vn 0.209326 0.976002 -0.060023 -v -0.083289 -0.015500 0.195764 -vn -0.374756 0.916683 -0.138746 -v -0.086584 -0.015500 0.197324 -vn -0.263551 0.916684 -0.300385 -v -0.083606 -0.015500 0.192996 -vn -0.309400 0.916683 -0.252910 -v -0.084834 -0.015500 0.194267 -vn 0.211296 0.976002 0.052679 -v -0.083299 -0.015500 0.195234 -vn -0.242251 0.731171 -0.637733 -v -0.078147 -0.015500 0.196832 -vn -0.211292 0.976002 -0.052681 -v -0.081310 -0.015500 0.195730 -vn -0.380950 0.916685 0.120690 -v -0.086750 -0.015500 0.204271 -vn -0.355945 0.918770 0.170774 -v -0.086079 -0.015500 0.205906 -vn 0.052680 0.976002 -0.211295 -v -0.082552 -0.015500 0.196476 -vn -0.346807 0.916684 -0.198533 -v -0.085836 -0.015500 0.195723 -vn -0.688851 0.724824 0.010664 -v -0.081044 -0.015500 0.201259 -vn -0.668259 0.731173 -0.137174 -v -0.080958 -0.015500 0.200134 -vn 0.156642 0.976002 0.151270 -v -0.083042 -0.015500 0.194770 -vn 0.060026 0.976000 0.209334 -v -0.082587 -0.015500 0.194497 -vn -0.210511 0.916688 -0.339658 -v -0.082186 -0.015500 0.191944 -vn -0.052682 0.976003 0.211290 -v -0.082056 -0.015500 0.194487 -vn -0.151274 0.976001 0.156647 -v -0.081592 -0.015500 0.194745 -vn -0.209323 0.976003 0.060019 -v -0.081319 -0.015500 0.195199 -vn -0.060020 0.976004 -0.209320 -v -0.082022 -0.015500 0.196467 -vn -0.613151 0.731173 -0.299053 -v -0.080594 -0.015500 0.199066 -vn -0.156642 0.976003 -0.151266 -v -0.081567 -0.015500 0.196194 -vn -0.519516 0.731172 -0.442143 -v -0.079976 -0.015500 0.198123 -vn -0.393238 0.731173 -0.557449 -v -0.079143 -0.015500 0.197362 -vn -0.392473 0.916687 -0.075167 -v -0.087058 -0.015500 0.199026 -vn -0.399499 0.916684 -0.009544 -v -0.087246 -0.015500 0.200784 -vn -0.395612 0.916688 0.056342 -v -0.087143 -0.015500 0.202548 -vn -0.722222 0.375769 0.580683 -v -0.080056 -0.013600 0.203859 -vn -0.782166 0.411991 0.467419 -v -0.080382 -0.013600 0.203397 -vn -0.838228 0.381724 0.389436 -v -0.080648 -0.013600 0.202898 -vn -0.874745 0.410698 0.257192 -v -0.080848 -0.013600 0.202370 -vn -0.908513 0.381693 0.170041 -v -0.080981 -0.013600 0.201821 -vn -0.910600 0.411986 0.032791 -v -0.081044 -0.013600 0.201259 -vn -0.922159 0.381720 -0.062548 -v -0.081036 -0.013600 0.200694 -vn -0.890146 0.411986 -0.194697 -v -0.080958 -0.013600 0.200134 -vn -0.877632 0.381723 -0.289913 -v -0.080809 -0.013600 0.199589 -vn -0.827341 0.390744 -0.403518 -v -0.080594 -0.013600 0.199066 -vn -0.775439 0.375770 -0.507435 -v -0.080315 -0.013600 0.198575 -vn -0.700993 0.390744 -0.596597 -v -0.079976 -0.013600 0.198123 -vn -0.624887 0.375768 -0.684335 -v -0.079584 -0.013600 0.197716 -vn -0.515617 0.411990 -0.751268 -v -0.079143 -0.013600 0.197362 -vn -0.441299 0.381730 -0.812119 -v -0.078662 -0.013600 0.197066 -vn -0.312581 0.411989 -0.855896 -v -0.078147 -0.013600 0.196832 -vn -0.225475 0.381720 -0.896354 -v -0.077608 -0.013600 0.196665 -vn -0.089908 0.411980 -0.906746 -v -0.077051 -0.013600 0.196567 -vn 0.004526 0.381723 -0.924266 -v -0.076487 -0.013600 0.196540 -vn 0.138424 0.411988 -0.900613 -v -0.075923 -0.013600 0.196583 -vn 0.234231 0.381721 -0.894106 -v -0.075370 -0.013600 0.196697 -vn 0.358036 0.411987 -0.837900 -v -0.074835 -0.013600 0.196879 -vn 0.449234 0.381722 -0.807761 -v -0.074327 -0.013600 0.197126 -vn 0.551408 0.390741 -0.737069 -v -0.073854 -0.013600 0.197436 -vn 0.643753 0.375764 -0.666621 -v -0.073424 -0.013600 0.197802 -vn 0.717409 0.411982 -0.561778 -v -0.073042 -0.013600 0.198219 -vn 0.782807 0.381728 -0.491423 -v -0.072717 -0.013600 0.198681 -vn 0.838286 0.390743 -0.380258 -v -0.072451 -0.013600 0.199180 -vn 0.885270 0.375763 -0.274042 -v -0.072251 -0.013600 0.199708 -vn 0.906516 0.390741 -0.159843 -v -0.072118 -0.013600 0.200258 -vn 0.925608 0.375766 -0.045265 -v -0.072055 -0.013600 0.200819 -vn 0.907261 0.412697 0.080990 -v -0.072063 -0.013600 0.201384 -vn 0.906474 0.382857 0.178118 -v -0.072141 -0.013600 0.201944 -vn 0.858729 0.411985 0.304718 -v -0.072290 -0.013600 0.202489 -vn 0.834374 0.381722 0.397628 -v -0.072505 -0.013600 0.203012 -vn 0.755970 0.411981 0.508705 -v -0.072784 -0.013600 0.203503 -vn 0.709275 0.381725 0.592634 -v -0.073123 -0.013600 0.203956 -vn 0.605701 0.411991 0.680728 -v -0.073515 -0.013600 0.204362 -vn 0.539610 0.381723 0.750405 -v -0.073956 -0.013600 0.204716 -vn 0.417394 0.411984 0.809970 -v -0.074437 -0.013600 0.205012 -vn 0.336037 0.381726 0.861025 -v -0.074951 -0.013600 0.205246 -vn 0.216447 0.390747 0.894689 -v -0.075491 -0.013600 0.205413 -vn 0.103299 0.375775 0.920936 -v -0.076048 -0.013600 0.205511 -vn -0.024446 0.411988 0.910861 -v -0.076612 -0.013600 0.205539 -vn -0.120326 0.381724 0.916411 -v -0.077176 -0.013600 0.205495 -vn -0.250208 0.411989 0.876163 -v -0.077729 -0.013600 0.205382 -vn -0.344454 0.381718 0.857696 -v -0.078264 -0.013600 0.205200 -vn -0.454677 0.390736 0.800371 -v -0.078772 -0.013600 0.204952 -vn -0.555125 0.375761 0.742051 -v -0.079245 -0.013600 0.204642 -vn -0.643292 0.377373 0.666156 -v -0.079675 -0.013600 0.204276 -vn -0.313914 0.917913 0.242678 -v -0.079823 -0.013300 0.203671 -vn 0.462533 0.746097 -0.478960 -v -0.078460 -0.013300 0.203017 -vn 0.592985 0.746099 -0.302828 -v -0.078999 -0.013300 0.202290 -vn 0.577850 0.746097 0.330799 -v -0.078936 -0.013300 0.199673 -vn -0.383609 0.915385 -0.122126 -v -0.080525 -0.013300 0.199686 -vn 0.653947 0.746101 0.125246 -v -0.079250 -0.013300 0.200522 -vn -0.402260 0.915175 -0.025317 -v -0.080737 -0.013300 0.200717 -vn 0.659184 0.746098 -0.093880 -v -0.079272 -0.013300 0.201427 -vn -0.395914 0.915178 0.075515 -v -0.080686 -0.013300 0.201768 -vn -0.364696 0.915177 0.171602 -v -0.080374 -0.013300 0.202774 -vn 0.039118 0.746100 0.664683 -v -0.076711 -0.013300 0.198294 -vn -0.100228 0.915175 -0.390396 -v -0.077537 -0.013300 0.196957 -vn 0.252825 0.746099 0.615968 -v -0.077594 -0.013300 0.198495 -vn -0.194160 0.915180 -0.353195 -v -0.078521 -0.013300 0.197331 -vn 0.439131 0.746100 0.500499 -v -0.078363 -0.013300 0.198972 -vn -0.266169 0.917664 -0.295037 -v -0.079382 -0.013300 0.197938 -vn -0.332067 0.917885 -0.217300 -v -0.080064 -0.013300 0.198739 -vn -0.535055 0.746097 0.396301 -v -0.074340 -0.013300 0.199402 -vn 0.277746 0.917662 -0.284170 -v -0.073632 -0.013300 0.198018 -vn -0.377385 0.746100 0.548558 -v -0.074991 -0.013300 0.198773 -vn 0.191845 0.915383 -0.353933 -v -0.074475 -0.013300 0.197387 -vn -0.178824 0.746097 0.641375 -v -0.075811 -0.013300 0.198390 -vn 0.100242 0.915176 -0.390390 -v -0.075448 -0.013300 0.196986 -vn 0.000013 0.915178 -0.403049 -v -0.076491 -0.013300 0.196840 -vn -0.274808 0.918423 0.284571 -v -0.079467 -0.013300 0.204060 -vn -0.233203 0.918139 0.320370 -v -0.079065 -0.013300 0.204402 -vn 0.281947 0.746102 -0.603189 -v -0.077714 -0.013300 0.203530 -vn -0.145975 0.915381 0.375191 -v -0.078150 -0.013300 0.204922 -vn 0.070814 0.746096 -0.662062 -v -0.076842 -0.013300 0.203774 -vn -0.050525 0.915178 0.399871 -v -0.077134 -0.013300 0.205198 -vn -0.147989 0.746100 -0.649180 -v -0.075938 -0.013300 0.203720 -vn -0.624416 0.746099 -0.231174 -v -0.073971 -0.013300 0.201994 -vn 0.395911 0.915177 0.075534 -v -0.072435 -0.013300 0.201884 -vn -0.665645 0.746099 -0.015901 -v -0.073800 -0.013300 0.201105 -vn 0.396995 0.917663 -0.017021 -v -0.072354 -0.013300 0.200834 -vn -0.634740 0.746100 0.201097 -v -0.073928 -0.013300 0.200209 -vn 0.379105 0.917882 -0.117355 -v -0.072537 -0.013300 0.199797 -vn 0.338617 0.915388 -0.217722 -v -0.072972 -0.013300 0.198838 -vn 0.041916 0.917666 0.395135 -v -0.076081 -0.013300 0.205213 -vn 0.150417 0.915387 0.373419 -v -0.075058 -0.013300 0.204965 -vn -0.350762 0.746099 -0.565953 -v -0.075101 -0.013300 0.203377 -vn 0.236900 0.915177 0.326082 -v -0.074128 -0.013300 0.204471 -vn -0.515521 0.746099 -0.421396 -v -0.074420 -0.013300 0.202780 -vn 0.310545 0.915180 0.256920 -v -0.073351 -0.013300 0.203761 -vn 0.364689 0.915177 0.171620 -v -0.072775 -0.013300 0.202880 -vn 0.514515 0.671870 -0.532789 -v -0.078460 -0.017000 0.203017 -vn 0.313638 0.671866 -0.670990 -v -0.077714 -0.017000 0.203530 -vn 0.078772 0.671871 -0.736468 -v -0.076842 -0.017000 0.203774 -vn -0.164622 0.671868 -0.722145 -v -0.075938 -0.017000 0.203720 -vn -0.390185 0.671869 -0.629562 -v -0.075101 -0.017000 0.203377 -vn -0.573462 0.671869 -0.468758 -v -0.074420 -0.017000 0.202780 -vn -0.694596 0.671869 -0.257156 -v -0.073971 -0.017000 0.201994 -vn -0.740459 0.671869 -0.017688 -v -0.073800 -0.017000 0.201105 -vn -0.706082 0.671868 0.223700 -v -0.073928 -0.017000 0.200209 -vn -0.595189 0.671870 0.440841 -v -0.074340 -0.017000 0.199402 -vn -0.419801 0.671868 0.610214 -v -0.074991 -0.017000 0.198773 -vn -0.198921 0.671870 0.713457 -v -0.075811 -0.017000 0.198390 -vn 0.043515 0.671867 0.739392 -v -0.076711 -0.017000 0.198294 -vn 0.281240 0.671869 0.685198 -v -0.077594 -0.017000 0.198495 -vn 0.488487 0.671868 0.556753 -v -0.078363 -0.017000 0.198972 -vn 0.642794 0.671870 0.367977 -v -0.078936 -0.017000 0.199673 -vn 0.727450 0.671867 0.139324 -v -0.079250 -0.017000 0.200522 -vn 0.733271 0.671869 -0.104431 -v -0.079272 -0.017000 0.201427 -vn 0.659633 0.671868 -0.336864 -v -0.078999 -0.017000 0.202290 -vn 0.635241 0.765144 0.104989 -v -0.077783 -0.017000 0.200835 -vn 0.611265 0.765148 -0.202247 -v -0.077736 -0.017000 0.201432 -vn 0.447262 0.765144 -0.463153 -v -0.077418 -0.017000 0.201938 -vn 0.180791 0.765148 -0.617951 -v -0.076900 -0.017000 0.202239 -vn -0.323424 0.765146 0.556730 -v -0.075922 -0.017000 0.199958 -vn -0.027648 0.765147 0.643261 -v -0.076496 -0.017000 0.199790 -vn 0.274456 0.765143 0.582435 -v -0.077082 -0.017000 0.199908 -vn 0.513684 0.765148 0.388173 -v -0.077547 -0.017000 0.200286 -vn -0.641906 0.765146 0.050085 -v -0.075303 -0.017000 0.200942 -vn -0.545104 0.765146 0.342657 -v -0.075491 -0.017000 0.200374 -vn -0.405861 0.765150 -0.499822 -v -0.075762 -0.017000 0.202009 -vn -0.591660 0.765144 -0.253956 -v -0.075401 -0.017000 0.201532 -vn -0.127092 0.765142 -0.631193 -v -0.076303 -0.017000 0.202265 -vn 0.447262 -0.765144 -0.463153 -v -0.077418 -0.018500 0.201938 -vn 0.180791 -0.765148 -0.617951 -v -0.076900 -0.018500 0.202239 -vn -0.127093 -0.765142 -0.631193 -v -0.076303 -0.018500 0.202265 -vn -0.405861 -0.765150 -0.499822 -v -0.075762 -0.018500 0.202009 -vn -0.591660 -0.765144 -0.253956 -v -0.075401 -0.018500 0.201532 -vn -0.641906 -0.765146 0.050085 -v -0.075303 -0.018500 0.200942 -vn -0.545104 -0.765146 0.342657 -v -0.075491 -0.018500 0.200374 -vn -0.323424 -0.765146 0.556730 -v -0.075922 -0.018500 0.199958 -vn -0.027648 -0.765147 0.643261 -v -0.076496 -0.018500 0.199790 -vn 0.274456 -0.765143 0.582435 -v -0.077082 -0.018500 0.199908 -vn 0.513684 -0.765148 0.388173 -v -0.077547 -0.018500 0.200286 -vn 0.635241 -0.765144 0.104990 -v -0.077783 -0.018500 0.200835 -vn 0.611265 -0.765148 -0.202247 -v -0.077736 -0.018500 0.201432 -vn 0.203709 0.539399 -0.817038 -v -0.082300 -0.015630 0.207570 -vn -0.232099 0.539401 -0.809430 -v -0.081886 -0.015630 0.207563 -vn -0.605721 0.539398 -0.584938 -v -0.081531 -0.015630 0.207350 -vn -0.817038 0.539398 -0.203711 -v -0.081331 -0.015630 0.206987 -vn -0.809432 0.539398 0.232100 -v -0.081338 -0.015630 0.206573 -vn -0.584935 0.539403 0.605720 -v -0.081551 -0.015630 0.206218 -vn -0.203705 0.539399 0.817039 -v -0.081913 -0.015630 0.206018 -vn 0.232097 0.539403 0.809429 -v -0.082327 -0.015630 0.206025 -vn 0.605718 0.539403 0.584936 -v -0.082682 -0.015630 0.206238 -vn 0.817038 0.539399 0.203709 -v -0.082883 -0.015630 0.206600 -vn 0.809429 0.539403 -0.232097 -v -0.082876 -0.015630 0.207014 -vn 0.584936 0.539403 -0.605718 -v -0.082662 -0.015630 0.207369 -vn -0.584933 -0.539404 0.605720 -v -0.081551 -0.019870 0.206218 -vn -0.809431 -0.539399 0.232098 -v -0.081338 -0.019870 0.206573 -vn -0.817037 -0.539400 -0.203709 -v -0.081331 -0.019870 0.206987 -vn -0.605719 -0.539399 -0.584938 -v -0.081531 -0.019870 0.207350 -vn -0.232101 -0.539403 -0.809428 -v -0.081886 -0.019870 0.207563 -vn 0.203711 -0.539401 -0.817036 -v -0.082300 -0.019870 0.207570 -vn 0.584936 -0.539403 -0.605718 -v -0.082662 -0.019870 0.207369 -vn 0.809427 -0.539405 -0.232099 -v -0.082876 -0.019870 0.207014 -vn 0.817036 -0.539401 0.203711 -v -0.082883 -0.019870 0.206600 -vn 0.605718 -0.539403 0.584936 -v -0.082682 -0.019870 0.206238 -vn 0.232099 -0.539405 0.809427 -v -0.082327 -0.019870 0.206025 -vn -0.203707 -0.539401 0.817038 -v -0.081913 -0.019870 0.206018 -vn 0.203710 0.539398 -0.817038 -v -0.082498 -0.015630 0.196258 -vn -0.232097 0.539403 -0.809429 -v -0.082084 -0.015630 0.196251 -vn -0.605718 0.539403 -0.584936 -v -0.081729 -0.015630 0.196038 -vn -0.817038 0.539399 -0.203709 -v -0.081528 -0.015630 0.195675 -vn -0.809430 0.539400 0.232101 -v -0.081535 -0.015630 0.195261 -vn -0.584939 0.539393 0.605724 -v -0.081748 -0.015630 0.194906 -vn -0.203713 0.539398 0.817038 -v -0.082111 -0.015630 0.194706 -vn 0.232104 0.539390 0.809436 -v -0.082525 -0.015630 0.194713 -vn 0.605720 0.539396 0.584941 -v -0.082880 -0.015630 0.194926 -vn 0.817039 0.539396 0.203713 -v -0.083080 -0.015630 0.195288 -vn 0.809432 0.539398 -0.232099 -v -0.083073 -0.015630 0.195702 -vn 0.584938 0.539402 -0.605717 -v -0.082860 -0.015630 0.196057 -vn -0.584940 -0.539395 0.605721 -v -0.081748 -0.019870 0.194906 -vn -0.809428 -0.539401 0.232103 -v -0.081535 -0.019870 0.195261 -vn -0.817036 -0.539401 -0.203711 -v -0.081528 -0.019870 0.195675 -vn -0.605718 -0.539403 -0.584936 -v -0.081729 -0.019870 0.196038 -vn -0.232099 -0.539405 -0.809427 -v -0.082084 -0.019870 0.196251 -vn 0.203713 -0.539400 -0.817037 -v -0.082498 -0.019870 0.196258 -vn 0.584936 -0.539403 -0.605719 -v -0.082860 -0.019870 0.196057 -vn 0.809431 -0.539399 -0.232098 -v -0.083073 -0.019870 0.195702 -vn 0.817039 -0.539397 0.203713 -v -0.083080 -0.019870 0.195288 -vn 0.605721 -0.539398 0.584937 -v -0.082880 -0.019870 0.194926 -vn 0.232099 -0.539392 0.809436 -v -0.082525 -0.019870 0.194713 -vn -0.203707 -0.539399 0.817038 -v -0.082111 -0.019870 0.194706 -vn 0.203714 0.539395 -0.817040 -v -0.071186 -0.015630 0.196061 -vn -0.232102 0.539390 -0.809436 -v -0.070772 -0.015630 0.196053 -vn -0.605717 0.539399 -0.584940 -v -0.070417 -0.015630 0.195840 -vn -0.817040 0.539395 -0.203711 -v -0.070216 -0.015630 0.195478 -vn -0.809430 0.539402 0.232097 -v -0.070223 -0.015630 0.195064 -vn -0.584937 0.539401 0.605719 -v -0.070436 -0.015630 0.194709 -vn -0.203709 0.539398 0.817039 -v -0.070799 -0.015630 0.194508 -vn 0.232097 0.539402 0.809430 -v -0.071213 -0.015630 0.194515 -vn 0.605722 0.539397 0.584937 -v -0.071568 -0.015630 0.194729 -vn 0.817039 0.539397 0.203711 -v -0.071768 -0.015630 0.195091 -vn 0.809434 0.539392 -0.232104 -v -0.071761 -0.015630 0.195505 -vn 0.584941 0.539390 -0.605724 -v -0.071548 -0.015630 0.195860 -vn -0.584936 -0.539403 0.605718 -v -0.070436 -0.019870 0.194709 -vn -0.809427 -0.539405 0.232099 -v -0.070223 -0.019870 0.195064 -vn -0.817037 -0.539398 -0.203715 -v -0.070216 -0.019870 0.195478 -vn -0.605720 -0.539402 -0.584935 -v -0.070417 -0.019870 0.195840 -vn -0.232097 -0.539393 -0.809435 -v -0.070772 -0.019870 0.196053 -vn 0.203709 -0.539398 -0.817039 -v -0.071186 -0.019870 0.196061 -vn 0.584940 -0.539395 -0.605722 -v -0.071548 -0.019870 0.195860 -vn 0.809433 -0.539395 -0.232102 -v -0.071761 -0.019870 0.195505 -vn 0.817037 -0.539400 0.203709 -v -0.071768 -0.019870 0.195091 -vn 0.605719 -0.539399 0.584938 -v -0.071568 -0.019870 0.194729 -vn 0.232100 -0.539405 0.809427 -v -0.071213 -0.019870 0.194515 -vn -0.203711 -0.539401 0.817036 -v -0.070799 -0.019870 0.194508 -vn 0.203709 0.539398 -0.817039 -v -0.070988 -0.015630 0.207373 -vn -0.232099 0.539400 -0.809431 -v -0.070574 -0.015630 0.207365 -vn -0.605722 0.539396 -0.584938 -v -0.070219 -0.015630 0.207152 -vn -0.817039 0.539397 -0.203711 -v -0.070019 -0.015630 0.206790 -vn -0.809433 0.539396 0.232100 -v -0.070026 -0.015630 0.206376 -vn -0.584935 0.539401 0.605720 -v -0.070239 -0.015630 0.206021 -vn -0.203706 0.539397 0.817040 -v -0.070601 -0.015630 0.205820 -vn 0.232097 0.539402 0.809430 -v -0.071015 -0.015630 0.205827 -vn 0.605719 0.539401 0.584937 -v -0.071370 -0.015630 0.206041 -vn 0.817039 0.539398 0.203709 -v -0.071571 -0.015630 0.206403 -vn 0.809430 0.539402 -0.232097 -v -0.071564 -0.015630 0.206817 -vn 0.584937 0.539401 -0.605719 -v -0.071350 -0.015630 0.207172 -vn -0.584933 -0.539404 0.605720 -v -0.070239 -0.019870 0.206021 -vn -0.809431 -0.539399 0.232098 -v -0.070026 -0.019870 0.206376 -vn -0.817037 -0.539400 -0.203709 -v -0.070019 -0.019870 0.206790 -vn -0.605719 -0.539399 -0.584938 -v -0.070219 -0.019870 0.207152 -vn -0.232101 -0.539403 -0.809428 -v -0.070574 -0.019870 0.207365 -vn 0.203711 -0.539401 -0.817036 -v -0.070988 -0.019870 0.207373 -vn 0.584936 -0.539403 -0.605718 -v -0.071350 -0.019870 0.207172 -vn 0.809427 -0.539405 -0.232099 -v -0.071564 -0.019870 0.206817 -vn 0.817036 -0.539401 0.203711 -v -0.071571 -0.019870 0.206403 -vn 0.605718 -0.539403 0.584936 -v -0.071370 -0.019870 0.206041 -vn 0.232099 -0.539405 0.809427 -v -0.071015 -0.019870 0.205827 -vn -0.203707 -0.539401 0.817038 -v -0.070601 -0.019870 0.205820 -# 18574 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 6//6 16//16 4//4 -f 4//4 16//16 17//17 -f 4//4 17//17 3//3 -f 3//3 17//17 11//11 -f 15//15 13//13 18//18 -f 18//18 13//13 19//19 -f 18//18 19//19 20//20 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 24//24 27//27 26//26 -f 26//26 27//27 28//28 -f 26//26 28//28 29//29 -f 29//29 28//28 30//30 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 39//39 12//12 31//31 -f 31//31 12//12 40//40 -f 31//31 40//40 32//32 -f 30//30 13//13 29//29 -f 29//29 13//13 12//12 -f 29//29 12//12 41//41 -f 41//41 12//12 39//39 -f 42//42 43//43 44//44 -f 44//44 43//43 45//45 -f 44//44 45//45 5//5 -f 5//5 45//45 46//46 -f 5//5 46//46 6//6 -f 10//10 47//47 11//11 -f 11//11 47//47 48//48 -f 11//11 48//48 3//3 -f 3//3 48//48 49//49 -f 3//3 49//49 50//50 -f 50//50 49//49 51//51 -f 50//50 51//51 52//52 -f 52//52 51//51 53//53 -f 52//52 53//53 38//38 -f 38//38 53//53 54//54 -f 38//38 54//54 37//37 -f 37//37 54//54 55//55 -f 37//37 55//55 56//56 -f 56//56 55//55 57//57 -f 56//56 57//57 58//58 -f 20//20 59//59 18//18 -f 18//18 59//59 3//3 -f 18//18 3//3 60//60 -f 60//60 3//3 50//50 -f 59//59 61//61 3//3 -f 3//3 61//61 62//62 -f 3//3 62//62 21//21 -f 21//21 62//62 63//63 -f 21//21 63//63 22//22 -f 7//7 64//64 8//8 -f 8//8 64//64 65//65 -f 8//8 65//65 66//66 -f 66//66 65//65 67//67 -f 66//66 67//67 43//43 -f 43//43 67//67 68//68 -f 43//43 68//68 45//45 -f 57//57 69//69 58//58 -f 58//58 69//69 70//70 -f 58//58 70//70 71//71 -f 71//71 70//70 8//8 -f 71//71 8//8 72//72 -f 72//72 8//8 66//66 -f 73//73 74//74 75//75 -f 76//76 77//77 78//78 -f 78//78 77//77 73//73 -f 79//79 80//80 81//81 -f 82//82 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 86//86 87//87 88//88 -f 89//89 90//90 91//91 -f 78//78 92//92 93//93 -f 78//78 94//94 95//95 -f 96//96 81//81 97//97 -f 97//97 81//81 80//80 -f 97//97 80//80 74//74 -f 74//74 80//80 98//98 -f 74//74 98//98 75//75 -f 99//99 100//100 101//101 -f 102//102 103//103 88//88 -f 78//78 95//95 104//104 -f 95//95 105//105 104//104 -f 104//104 105//105 106//106 -f 104//104 106//106 107//107 -f 107//107 106//106 82//82 -f 107//107 82//82 108//108 -f 108//108 82//82 84//84 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 112//112 86//86 111//111 -f 111//111 86//86 88//88 -f 111//111 88//88 113//113 -f 113//113 88//88 103//103 -f 114//114 115//115 116//116 -f 116//116 115//115 117//117 -f 116//116 117//117 118//118 -f 118//118 117//117 119//119 -f 118//118 119//119 120//120 -f 73//73 75//75 78//78 -f 78//78 75//75 121//121 -f 78//78 121//121 92//92 -f 94//94 78//78 122//122 -f 122//122 78//78 93//93 -f 122//122 93//93 123//123 -f 123//123 93//93 124//124 -f 123//123 124//124 125//125 -f 91//91 99//99 89//89 -f 89//89 99//99 101//101 -f 89//89 101//101 126//126 -f 126//126 101//101 102//102 -f 126//126 102//102 124//124 -f 124//124 102//102 88//88 -f 124//124 88//88 125//125 -f 79//79 81//81 127//127 -f 127//127 81//81 128//128 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 89//89 -f 89//89 130//130 131//131 -f 89//89 131//131 90//90 -f 119//119 132//132 120//120 -f 120//120 132//132 133//133 -f 120//120 133//133 134//134 -f 134//134 133//133 130//130 -f 134//134 130//130 135//135 -f 135//135 130//130 128//128 -f 111//111 136//136 109//109 -f 109//109 136//136 137//137 -f 109//109 137//137 138//138 -f 138//138 137//137 139//139 -f 138//138 139//139 114//114 -f 114//114 139//139 140//140 -f 114//114 140//140 115//115 -f 115//115 140//140 141//141 -f 115//115 141//141 142//142 -f 142//142 141//141 143//143 -f 142//142 143//143 100//100 -f 100//100 143//143 144//144 -f 100//100 144//144 101//101 -f 114//114 116//116 37//37 -f 37//37 116//116 35//35 -f 26//26 29//29 81//81 -f 81//81 29//29 128//128 -f 74//74 73//73 21//21 -f 21//21 73//73 3//3 -f 1//1 3//3 77//77 -f 77//77 3//3 73//73 -f 2//2 1//1 76//76 -f 76//76 1//1 77//77 -f 4//4 2//2 78//78 -f 78//78 2//2 76//76 -f 5//5 4//4 104//104 -f 104//104 4//4 78//78 -f 84//84 86//86 43//43 -f 43//43 86//86 66//66 -f 57//57 139//139 69//69 -f 69//69 139//139 137//137 -f 69//69 137//137 70//70 -f 70//70 137//137 136//136 -f 70//70 136//136 8//8 -f 8//8 136//136 111//111 -f 8//8 111//111 10//10 -f 10//10 111//111 113//113 -f 10//10 113//113 47//47 -f 47//47 113//113 103//103 -f 47//47 103//103 48//48 -f 48//48 103//103 102//102 -f 48//48 102//102 49//49 -f 49//49 102//102 101//101 -f 49//49 101//101 51//51 -f 51//51 101//101 144//144 -f 51//51 144//144 53//53 -f 53//53 144//144 143//143 -f 53//53 143//143 54//54 -f 54//54 143//143 141//141 -f 54//54 141//141 55//55 -f 55//55 141//141 140//140 -f 55//55 140//140 57//57 -f 57//57 140//140 139//139 -f 64//64 88//88 65//65 -f 65//65 88//88 87//87 -f 65//65 87//87 67//67 -f 67//67 87//87 85//85 -f 67//67 85//85 68//68 -f 68//68 85//85 83//83 -f 68//68 83//83 45//45 -f 45//45 83//83 82//82 -f 45//45 82//82 46//46 -f 46//46 82//82 106//106 -f 46//46 106//106 6//6 -f 6//6 106//106 105//105 -f 6//6 105//105 16//16 -f 16//16 105//105 95//95 -f 16//16 95//95 17//17 -f 17//17 95//95 94//94 -f 17//17 94//94 11//11 -f 11//11 94//94 122//122 -f 11//11 122//122 9//9 -f 9//9 122//122 123//123 -f 9//9 123//123 7//7 -f 7//7 123//123 125//125 -f 7//7 125//125 64//64 -f 64//64 125//125 88//88 -f 13//13 89//89 19//19 -f 19//19 89//89 126//126 -f 19//19 126//126 20//20 -f 20//20 126//126 124//124 -f 20//20 124//124 59//59 -f 59//59 124//124 93//93 -f 59//59 93//93 61//61 -f 61//61 93//93 92//92 -f 61//61 92//92 62//62 -f 62//62 92//92 121//121 -f 62//62 121//121 63//63 -f 63//63 121//121 75//75 -f 63//63 75//75 22//22 -f 22//22 75//75 98//98 -f 22//22 98//98 24//24 -f 24//24 98//98 80//80 -f 24//24 80//80 27//27 -f 27//27 80//80 79//79 -f 27//27 79//79 28//28 -f 28//28 79//79 127//127 -f 28//28 127//127 30//30 -f 30//30 127//127 129//129 -f 30//30 129//129 13//13 -f 13//13 129//129 89//89 -f 34//34 119//119 36//36 -f 36//36 119//119 117//117 -f 36//36 117//117 38//38 -f 38//38 117//117 115//115 -f 38//38 115//115 52//52 -f 52//52 115//115 142//142 -f 52//52 142//142 50//50 -f 50//50 142//142 100//100 -f 50//50 100//100 60//60 -f 60//60 100//100 99//99 -f 60//60 99//99 18//18 -f 18//18 99//99 91//91 -f 18//18 91//91 15//15 -f 15//15 91//91 90//90 -f 15//15 90//90 14//14 -f 14//14 90//90 131//131 -f 14//14 131//131 12//12 -f 12//12 131//131 130//130 -f 12//12 130//130 40//40 -f 40//40 130//130 133//133 -f 40//40 133//133 32//32 -f 32//32 133//133 132//132 -f 32//32 132//132 34//34 -f 34//34 132//132 119//119 -f 66//66 86//86 112//112 -f 66//66 112//112 72//72 -f 72//72 112//112 110//110 -f 72//72 110//110 71//71 -f 71//71 110//110 109//109 -f 71//71 109//109 58//58 -f 58//58 109//109 138//138 -f 58//58 138//138 56//56 -f 56//56 138//138 114//114 -f 56//56 114//114 37//37 -f 35//35 116//116 118//118 -f 35//35 118//118 33//33 -f 33//33 118//118 120//120 -f 33//33 120//120 31//31 -f 31//31 120//120 134//134 -f 31//31 134//134 39//39 -f 39//39 134//134 135//135 -f 39//39 135//135 41//41 -f 41//41 135//135 128//128 -f 41//41 128//128 29//29 -f 5//5 104//104 107//107 -f 5//5 107//107 44//44 -f 44//44 107//107 108//108 -f 44//44 108//108 42//42 -f 42//42 108//108 84//84 -f 42//42 84//84 43//43 -f 26//26 81//81 96//96 -f 26//26 96//96 25//25 -f 25//25 96//96 97//97 -f 25//25 97//97 23//23 -f 23//23 97//97 74//74 -f 23//23 74//74 21//21 -f 145//145 146//146 147//147 -f 148//148 149//149 150//150 -f 151//151 152//152 153//153 -f 154//154 155//155 156//156 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 155//155 165//165 156//156 -f 156//156 165//165 166//166 -f 156//156 166//166 157//157 -f 157//157 166//166 167//167 -f 157//157 167//167 158//158 -f 156//156 168//168 154//154 -f 154//154 168//168 169//169 -f 154//154 169//169 170//170 -f 170//170 169//169 171//171 -f 170//170 171//171 172//172 -f 172//172 171//171 173//173 -f 172//172 173//173 164//164 -f 164//164 173//173 174//174 -f 164//164 174//174 163//163 -f 156//156 175//175 168//168 -f 168//168 175//175 176//176 -f 168//168 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 180//180 -f 180//180 184//184 185//185 -f 180//180 185//185 186//186 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 187//187 189//189 186//186 -f 186//186 189//189 198//198 -f 186//186 198//198 180//180 -f 180//180 198//198 199//199 -f 180//180 199//199 179//179 -f 200//200 190//190 201//201 -f 201//201 190//190 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 188//188 191//191 190//190 -f 190//190 191//191 193//193 -f 190//190 193//193 202//202 -f 202//202 193//193 206//206 -f 202//202 206//206 204//204 -f 204//204 206//206 207//207 -f 208//208 209//209 145//145 -f 145//145 209//209 210//210 -f 211//211 207//207 212//212 -f 212//212 207//207 213//213 -f 212//212 213//213 214//214 -f 214//214 213//213 215//215 -f 216//216 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 219//219 221//221 220//220 -f 220//220 221//221 222//222 -f 220//220 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 226//226 227//227 228//228 -f 228//228 227//227 229//229 -f 228//228 229//229 230//230 -f 230//230 229//229 231//231 -f 226//226 232//232 227//227 -f 227//227 232//232 233//233 -f 227//227 233//233 217//217 -f 234//234 153//153 235//235 -f 235//235 153//153 236//236 -f 235//235 236//236 237//237 -f 233//233 238//238 217//217 -f 217//217 238//238 239//239 -f 217//217 239//239 219//219 -f 219//219 239//239 240//240 -f 219//219 240//240 241//241 -f 241//241 240//240 237//237 -f 241//241 237//237 242//242 -f 242//242 237//237 236//236 -f 151//151 153//153 243//243 -f 243//243 153//153 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 249//249 -f 249//249 248//248 150//150 -f 150//150 248//248 250//250 -f 150//150 250//250 148//148 -f 251//251 252//252 248//248 -f 248//248 252//252 253//253 -f 248//248 253//253 254//254 -f 255//255 250//250 256//256 -f 256//256 250//250 248//248 -f 256//256 248//248 257//257 -f 257//257 248//248 254//254 -f 258//258 259//259 251//251 -f 251//251 259//259 260//260 -f 251//251 260//260 252//252 -f 257//257 261//261 256//256 -f 256//256 261//261 262//262 -f 256//256 262//262 263//263 -f 263//263 262//262 264//264 -f 264//264 265//265 263//263 -f 263//263 265//265 266//266 -f 263//263 266//266 258//258 -f 258//258 266//266 267//267 -f 258//258 267//267 259//259 -f 268//268 269//269 270//270 -f 270//270 271//271 268//268 -f 268//268 271//271 272//272 -f 268//268 272//272 246//246 -f 246//246 272//272 273//273 -f 246//246 273//273 274//274 -f 274//274 275//275 246//246 -f 246//246 275//275 276//276 -f 246//246 276//276 248//248 -f 248//248 276//276 277//277 -f 248//248 277//277 251//251 -f 275//275 278//278 276//276 -f 276//276 278//278 279//279 -f 276//276 279//279 280//280 -f 280//280 279//279 281//281 -f 281//281 282//282 280//280 -f 280//280 282//282 283//283 -f 280//280 283//283 269//269 -f 269//269 283//283 284//284 -f 269//269 284//284 270//270 -f 285//285 286//286 287//287 -f 288//288 289//289 290//290 -f 290//290 289//289 291//291 -f 290//290 291//291 292//292 -f 292//292 291//291 293//293 -f 234//234 231//231 153//153 -f 153//153 231//231 229//229 -f 153//153 229//229 244//244 -f 244//244 229//229 294//294 -f 244//244 294//294 285//285 -f 287//287 295//295 285//285 -f 285//285 295//295 296//296 -f 285//285 296//296 244//244 -f 244//244 296//296 297//297 -f 244//244 297//297 298//298 -f 298//298 293//293 244//244 -f 244//244 293//293 291//291 -f 244//244 291//291 246//246 -f 246//246 291//291 299//299 -f 246//246 299//299 268//268 -f 288//288 300//300 289//289 -f 289//289 300//300 301//301 -f 289//289 301//301 286//286 -f 286//286 301//301 302//302 -f 286//286 302//302 287//287 -f 211//211 303//303 207//207 -f 207//207 303//303 304//304 -f 207//207 304//304 204//204 -f 204//204 304//304 305//305 -f 204//204 305//305 306//306 -f 306//306 305//305 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 309//309 -f 308//308 309//309 310//310 -f 310//310 309//309 208//208 -f 310//310 208//208 224//224 -f 224//224 208//208 145//145 -f 224//224 145//145 225//225 -f 225//225 145//145 147//147 -f 311//311 146//146 213//213 -f 213//213 146//146 145//145 -f 213//213 145//145 215//215 -f 215//215 145//145 210//210 -f 312//312 313//313 183//183 -f 183//183 313//313 195//195 -f 183//183 195//195 181//181 -f 181//181 195//195 197//197 -f 314//314 175//175 315//315 -f 315//315 175//175 156//156 -f 315//315 156//156 316//316 -f 316//316 156//156 157//157 -f 317//317 318//318 319//319 -f 320//320 321//321 322//322 -f 323//323 324//324 325//325 -f 325//325 324//324 322//322 -f 326//326 327//327 328//328 -f 328//328 327//327 323//323 -f 328//328 323//323 329//329 -f 329//329 323//323 325//325 -f 160//160 161//161 159//159 -f 159//159 161//161 163//163 -f 159//159 163//163 330//330 -f 330//330 163//163 319//319 -f 330//330 319//319 331//331 -f 331//331 319//319 318//318 -f 331//331 318//318 320//320 -f 320//320 318//318 332//332 -f 320//320 332//332 321//321 -f 326//326 333//333 327//327 -f 327//327 333//333 334//334 -f 327//327 334//334 319//319 -f 319//319 334//334 335//335 -f 319//319 335//335 317//317 -f 322//322 324//324 320//320 -f 320//320 324//324 336//336 -f 320//320 336//336 337//337 -f 338//338 339//339 327//327 -f 340//340 341//341 342//342 -f 342//342 341//341 343//343 -f 344//344 345//345 346//346 -f 346//346 345//345 343//343 -f 340//340 342//342 339//339 -f 339//339 342//342 347//347 -f 339//339 347//347 327//327 -f 327//327 347//347 348//348 -f 327//327 348//348 323//323 -f 346//346 349//349 344//344 -f 344//344 349//349 350//350 -f 344//344 350//350 351//351 -f 351//351 350//350 352//352 -f 352//352 353//353 351//351 -f 351//351 353//353 354//354 -f 351//351 354//354 327//327 -f 327//327 354//354 355//355 -f 327//327 355//355 338//338 -f 343//343 345//345 342//342 -f 342//342 345//345 356//356 -f 342//342 356//356 357//357 -f 358//358 359//359 351//351 -f 360//360 361//361 362//362 -f 363//363 364//364 365//365 -f 365//365 364//364 360//360 -f 365//365 360//360 351//351 -f 366//366 367//367 360//360 -f 360//360 367//367 368//368 -f 360//360 368//368 369//369 -f 370//370 371//371 372//372 -f 372//372 371//371 373//373 -f 360//360 362//362 366//366 -f 366//366 362//362 374//374 -f 366//366 374//374 373//373 -f 369//369 375//375 360//360 -f 360//360 375//375 376//376 -f 360//360 376//376 351//351 -f 351//351 376//376 377//377 -f 351//351 377//377 358//358 -f 370//370 372//372 359//359 -f 359//359 372//372 378//378 -f 359//359 378//378 351//351 -f 351//351 378//378 379//379 -f 351//351 379//379 344//344 -f 373//373 374//374 372//372 -f 372//372 374//374 380//380 -f 372//372 380//380 381//381 -f 163//163 382//382 383//383 -f 384//384 385//385 386//386 -f 386//386 385//385 365//365 -f 386//386 365//365 387//387 -f 387//387 365//365 351//351 -f 387//387 351//351 388//388 -f 388//388 351//351 327//327 -f 388//388 327//327 383//383 -f 383//383 327//327 319//319 -f 383//383 319//319 163//163 -f 389//389 390//390 200//200 -f 389//389 200//200 391//391 -f 391//391 200//200 201//201 -f 391//391 201//201 203//203 -f 392//392 393//393 394//394 -f 395//395 396//396 397//397 -f 396//396 398//398 397//397 -f 397//397 398//398 399//399 -f 397//397 399//399 400//400 -f 401//401 402//402 397//397 -f 397//397 402//402 392//392 -f 392//392 394//394 397//397 -f 397//397 394//394 403//403 -f 397//397 403//403 395//395 -f 404//404 405//405 406//406 -f 406//406 405//405 400//400 -f 406//406 400//400 407//407 -f 407//407 400//400 399//399 -f 408//408 409//409 410//410 -f 410//410 409//409 411//411 -f 412//412 408//408 413//413 -f 413//413 408//408 410//410 -f 413//413 410//410 414//414 -f 414//414 410//410 415//415 -f 386//386 387//387 416//416 -f 386//386 416//416 417//417 -f 418//418 419//419 420//420 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 423//423 424//424 425//425 -f 425//425 424//424 426//426 -f 425//425 426//426 427//427 -f 427//427 426//426 428//428 -f 427//427 428//428 429//429 -f 429//429 428//428 430//430 -f 431//431 432//432 433//433 -f 433//433 432//432 434//434 -f 433//433 434//434 435//435 -f 435//435 434//434 436//436 -f 435//435 436//436 437//437 -f 437//437 436//436 438//438 -f 438//438 439//439 437//437 -f 437//437 439//439 440//440 -f 437//437 440//440 441//441 -f 441//441 440//440 442//442 -f 439//439 443//443 440//440 -f 440//440 443//443 444//444 -f 440//440 444//444 421//421 -f 421//421 444//444 445//445 -f 421//421 445//445 422//422 -f 433//433 446//446 431//431 -f 431//431 446//446 447//447 -f 431//431 447//447 419//419 -f 419//419 447//447 448//448 -f 419//419 448//448 420//420 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 453//453 454//454 420//420 -f 420//420 454//454 455//455 -f 420//420 455//455 418//418 -f 456//456 457//457 428//428 -f 428//428 457//457 458//458 -f 428//428 458//458 430//430 -f 456//456 459//459 457//457 -f 457//457 459//459 460//460 -f 457//457 460//460 416//416 -f 416//416 460//460 461//461 -f 416//416 461//461 462//462 -f 462//462 463//463 416//416 -f 416//416 463//463 449//449 -f 416//416 449//449 417//417 -f 417//417 449//449 451//451 -f 409//409 464//464 411//411 -f 411//411 464//464 465//465 -f 465//465 464//464 466//466 -f 466//466 464//464 467//467 -f 466//466 467//467 468//468 -f 468//468 467//467 469//469 -f 469//469 467//467 470//470 -f 469//469 470//470 471//471 -f 471//471 470//470 472//472 -f 472//472 470//470 473//473 -f 472//472 473//473 474//474 -f 475//475 476//476 477//477 -f 474//474 473//473 477//477 -f 477//477 473//473 478//478 -f 477//477 478//478 475//475 -f 479//479 480//480 481//481 -f 482//482 483//483 484//484 -f 479//479 481//481 485//485 -f 481//481 486//486 485//485 -f 485//485 486//486 487//487 -f 485//485 487//487 488//488 -f 482//482 484//484 489//489 -f 484//484 490//490 489//489 -f 489//489 490//490 491//491 -f 489//489 491//491 479//479 -f 479//479 491//491 492//492 -f 479//479 492//492 480//480 -f 487//487 493//493 488//488 -f 488//488 493//493 494//494 -f 488//488 494//494 482//482 -f 482//482 494//494 495//495 -f 482//482 495//495 483//483 -f 496//496 497//497 498//498 -f 498//498 497//497 499//499 -f 500//500 501//501 502//502 -f 502//502 501//501 503//503 -f 503//503 504//504 502//502 -f 502//502 504//504 505//505 -f 502//502 505//505 506//506 -f 505//505 507//507 506//506 -f 506//506 507//507 508//508 -f 506//506 508//508 496//496 -f 496//496 508//508 509//509 -f 496//496 509//509 497//497 -f 499//499 510//510 498//498 -f 498//498 510//510 511//511 -f 498//498 511//511 500//500 -f 500//500 511//511 512//512 -f 500//500 512//512 501//501 -f 513//513 514//514 515//515 -f 515//515 514//514 516//516 -f 517//517 518//518 513//513 -f 513//513 518//518 519//519 -f 513//513 519//519 514//514 -f 516//516 520//520 515//515 -f 515//515 520//520 521//521 -f 515//515 521//521 522//522 -f 523//523 524//524 525//525 -f 525//525 524//524 522//522 -f 525//525 522//522 526//526 -f 526//526 522//522 521//521 -f 523//523 527//527 524//524 -f 524//524 527//527 528//528 -f 524//524 528//528 517//517 -f 517//517 528//528 529//529 -f 517//517 529//529 518//518 -f 530//530 531//531 532//532 -f 532//532 531//531 533//533 -f 534//534 535//535 536//536 -f 537//537 538//538 467//467 -f 539//539 540//540 541//541 -f 541//541 540//540 542//542 -f 467//467 538//538 470//470 -f 470//470 538//538 543//543 -f 470//470 543//543 473//473 -f 544//544 545//545 546//546 -f 546//546 545//545 547//547 -f 548//548 549//549 550//550 -f 550//550 549//549 551//551 -f 550//550 551//551 552//552 -f 553//553 554//554 555//555 -f 556//556 557//557 558//558 -f 558//558 557//557 559//559 -f 560//560 561//561 562//562 -f 563//563 564//564 565//565 -f 566//566 567//567 568//568 -f 568//568 567//567 569//569 -f 570//570 571//571 565//565 -f 572//572 573//573 574//574 -f 574//574 573//573 575//575 -f 576//576 577//577 578//578 -f 579//579 580//580 581//581 -f 581//581 580//580 582//582 -f 583//583 584//584 585//585 -f 585//585 584//584 586//586 -f 571//571 587//587 565//565 -f 565//565 587//587 588//588 -f 565//565 588//588 563//563 -f 547//547 560//560 564//564 -f 589//589 590//590 591//591 -f 591//591 590//590 592//592 -f 593//593 555//555 594//594 -f 594//594 555//555 595//595 -f 596//596 541//541 563//563 -f 563//563 541//541 542//542 -f 563//563 542//542 564//564 -f 564//564 542//542 558//558 -f 564//564 558//558 547//547 -f 547//547 558//558 559//559 -f 547//547 559//559 546//546 -f 597//597 598//598 599//599 -f 599//599 598//598 577//577 -f 599//599 577//577 575//575 -f 575//575 577//577 576//576 -f 575//575 576//576 600//600 -f 601//601 602//602 578//578 -f 578//578 602//602 553//553 -f 578//578 553//553 576//576 -f 576//576 553//553 555//555 -f 576//576 555//555 603//603 -f 604//604 605//605 606//606 -f 606//606 605//605 607//607 -f 608//608 609//609 610//610 -f 562//562 552//552 560//560 -f 560//560 552//552 551//551 -f 560//560 551//551 564//564 -f 564//564 551//551 574//574 -f 564//564 574//574 611//611 -f 611//611 574//574 575//575 -f 611//611 575//575 612//612 -f 612//612 575//575 600//600 -f 613//613 610//610 614//614 -f 614//614 610//610 615//615 -f 614//614 615//615 593//593 -f 543//543 608//608 616//616 -f 616//616 608//608 610//610 -f 616//616 610//610 617//617 -f 617//617 610//610 613//613 -f 609//609 608//608 564//564 -f 564//564 608//608 618//618 -f 564//564 618//618 619//619 -f 620//620 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 615//615 625//625 593//593 -f 593//593 625//625 626//626 -f 593//593 626//626 555//555 -f 555//555 626//626 627//627 -f 555//555 627//627 603//603 -f 628//628 629//629 564//564 -f 564//564 629//629 630//630 -f 564//564 630//630 565//565 -f 631//631 409//409 632//632 -f 632//632 409//409 408//408 -f 632//632 408//408 633//633 -f 633//633 408//408 634//634 -f 633//633 634//634 635//635 -f 635//635 634//634 570//570 -f 635//635 570//570 636//636 -f 636//636 570//570 565//565 -f 536//536 637//637 534//534 -f 534//534 637//637 638//638 -f 534//534 638//638 639//639 -f 640//640 641//641 595//595 -f 642//642 628//628 643//643 -f 643//643 628//628 564//564 -f 643//643 564//564 644//644 -f 644//644 564//564 619//619 -f 537//537 467//467 645//645 -f 645//645 467//467 464//464 -f 645//645 464//464 646//646 -f 646//646 464//464 409//409 -f 646//646 409//409 647//647 -f 647//647 409//409 631//631 -f 647//647 631//631 648//648 -f 648//648 631//631 649//649 -f 648//648 649//649 643//643 -f 643//643 649//649 650//650 -f 643//643 650//650 642//642 -f 651//651 652//652 653//653 -f 653//653 652//652 654//654 -f 653//653 654//654 655//655 -f 656//656 657//657 655//655 -f 655//655 657//657 640//640 -f 655//655 640//640 653//653 -f 653//653 640//640 595//595 -f 653//653 595//595 533//533 -f 533//533 595//595 555//555 -f 533//533 555//555 532//532 -f 532//532 555//555 658//658 -f 607//607 659//659 606//606 -f 606//606 659//659 660//660 -f 606//606 660//660 661//661 -f 568//568 616//616 607//607 -f 607//607 616//616 662//662 -f 607//607 662//662 659//659 -f 663//663 664//664 641//641 -f 641//641 664//664 665//665 -f 641//641 665//665 595//595 -f 595//595 665//665 666//666 -f 667//667 606//606 668//668 -f 668//668 606//606 661//661 -f 668//668 661//661 666//666 -f 666//666 661//661 669//669 -f 666//666 669//669 595//595 -f 569//569 581//581 568//568 -f 568//568 581//581 582//582 -f 568//568 582//582 616//616 -f 616//616 582//582 585//585 -f 670//670 534//534 616//616 -f 616//616 534//534 639//639 -f 616//616 639//639 543//543 -f 543//543 639//639 478//478 -f 543//543 478//478 473//473 -f 586//586 591//591 585//585 -f 585//585 591//591 592//592 -f 585//585 592//592 616//616 -f 616//616 592//592 622//622 -f 616//616 622//622 670//670 -f 670//670 622//622 624//624 -f 670//670 624//624 671//671 -f 671//671 624//624 672//672 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 677//677 -f 677//677 676//676 678//678 -f 677//677 678//678 679//679 -f 680//680 681//681 682//682 -f 682//682 681//681 683//683 -f 682//682 683//683 684//684 -f 684//684 683//683 685//685 -f 684//684 685//685 686//686 -f 687//687 688//688 689//689 -f 689//689 688//688 690//690 -f 689//689 690//690 691//691 -f 691//691 690//690 692//692 -f 691//691 692//692 693//693 -f 694//694 695//695 485//485 -f 485//485 695//695 696//696 -f 485//485 696//696 479//479 -f 479//479 696//696 697//697 -f 479//479 697//697 698//698 -f 698//698 697//697 699//699 -f 700//700 701//701 506//506 -f 506//506 701//701 702//702 -f 506//506 702//702 502//502 -f 502//502 702//702 703//703 -f 502//502 703//703 704//704 -f 704//704 703//703 705//705 -f 706//706 707//707 522//522 -f 522//522 707//707 708//708 -f 522//522 708//708 515//515 -f 515//515 708//708 709//709 -f 515//515 709//709 710//710 -f 710//710 709//709 711//711 -f 712//712 713//713 714//714 -f 714//714 713//713 715//715 -f 716//716 717//717 718//718 -f 719//719 720//720 721//721 -f 721//721 720//720 716//716 -f 721//721 716//716 722//722 -f 722//722 716//716 718//718 -f 719//719 723//723 720//720 -f 720//720 723//723 724//724 -f 720//720 724//724 712//712 -f 712//712 724//724 725//725 -f 712//712 725//725 713//713 -f 715//715 726//726 714//714 -f 714//714 726//726 727//727 -f 714//714 727//727 717//717 -f 717//717 727//727 728//728 -f 717//717 728//728 718//718 -f 729//729 730//730 731//731 -f 731//731 730//730 732//732 -f 733//733 734//734 735//735 -f 735//735 734//734 736//736 -f 735//735 736//736 737//737 -f 737//737 736//736 738//738 -f 737//737 738//738 739//739 -f 731//731 740//740 729//729 -f 729//729 740//740 741//741 -f 729//729 741//741 738//738 -f 738//738 741//741 742//742 -f 738//738 742//742 739//739 -f 733//733 743//743 734//734 -f 734//734 743//743 744//744 -f 734//734 744//744 730//730 -f 730//730 744//744 745//745 -f 730//730 745//745 732//732 -f 746//746 747//747 748//748 -f 748//748 747//747 749//749 -f 748//748 749//749 750//750 -f 750//750 749//749 751//751 -f 750//750 751//751 752//752 -f 753//753 754//754 717//717 -f 717//717 754//754 755//755 -f 717//717 755//755 714//714 -f 714//714 755//755 756//756 -f 714//714 756//756 757//757 -f 757//757 756//756 758//758 -f 759//759 760//760 761//761 -f 762//762 763//763 764//764 -f 759//759 761//761 764//764 -f 764//764 761//761 765//765 -f 764//764 765//765 762//762 -f 766//766 767//767 729//729 -f 729//729 767//767 768//768 -f 729//729 768//768 730//730 -f 730//730 768//768 769//769 -f 730//730 769//769 770//770 -f 770//770 769//769 771//771 -f 772//772 563//563 773//773 -f 773//773 563//563 588//588 -f 475//475 478//478 774//774 -f 774//774 478//478 639//639 -f 639//639 638//638 774//774 -f 774//774 638//638 775//775 -f 774//774 775//775 776//776 -f 776//776 775//775 361//361 -f 776//776 361//361 777//777 -f 777//777 361//361 360//360 -f 775//775 638//638 778//778 -f 778//778 638//638 637//637 -f 374//374 362//362 778//778 -f 778//778 637//637 536//536 -f 374//374 778//778 380//380 -f 380//380 778//778 697//697 -f 697//697 778//778 536//536 -f 697//697 536//536 699//699 -f 672//672 624//624 779//779 -f 779//779 378//378 372//372 -f 672//672 779//779 695//695 -f 695//695 779//779 696//696 -f 696//696 779//779 372//372 -f 696//696 372//372 381//381 -f 779//779 624//624 780//780 -f 780//780 624//624 623//623 -f 345//345 344//344 780//780 -f 780//780 623//623 621//621 -f 345//345 780//780 356//356 -f 356//356 780//780 703//703 -f 703//703 780//780 621//621 -f 703//703 621//621 705//705 -f 589//589 591//591 781//781 -f 781//781 347//347 342//342 -f 589//589 781//781 701//701 -f 701//701 781//781 702//702 -f 702//702 781//781 342//342 -f 702//702 342//342 357//357 -f 781//781 591//591 782//782 -f 782//782 591//591 586//586 -f 324//324 323//323 782//782 -f 782//782 586//586 584//584 -f 324//324 782//782 336//336 -f 336//336 782//782 709//709 -f 709//709 782//782 584//584 -f 709//709 584//584 711//711 -f 579//579 581//581 783//783 -f 783//783 331//331 320//320 -f 579//579 783//783 707//707 -f 707//707 783//783 708//708 -f 708//708 783//783 320//320 -f 708//708 320//320 337//337 -f 783//783 581//581 784//784 -f 784//784 581//581 569//569 -f 157//157 159//159 784//784 -f 784//784 569//569 567//567 -f 157//157 784//784 316//316 -f 316//316 784//784 756//756 -f 756//756 784//784 567//567 -f 756//756 567//567 758//758 -f 604//604 606//606 785//785 -f 785//785 176//176 175//175 -f 604//604 785//785 754//754 -f 754//754 785//785 755//755 -f 755//755 785//785 175//175 -f 755//755 175//175 314//314 -f 785//785 606//606 786//786 -f 786//786 606//606 667//667 -f 786//786 667//667 178//178 -f 178//178 667//667 668//668 -f 178//178 668//668 787//787 -f 787//787 668//668 666//666 -f 787//787 666//666 788//788 -f 788//788 666//666 665//665 -f 183//183 180//180 788//788 -f 788//788 665//665 664//664 -f 183//183 788//788 312//312 -f 312//312 788//788 769//769 -f 769//769 788//788 664//664 -f 769//769 664//664 771//771 -f 656//656 655//655 789//789 -f 789//789 193//193 195//195 -f 656//656 789//789 767//767 -f 767//767 789//789 768//768 -f 768//768 789//789 195//195 -f 768//768 195//195 313//313 -f 789//789 655//655 790//790 -f 790//790 655//655 654//654 -f 213//213 207//207 790//790 -f 790//790 654//654 652//652 -f 213//213 790//790 311//311 -f 311//311 790//790 791//791 -f 791//791 790//790 652//652 -f 791//791 652//652 792//792 -f 793//793 794//794 795//795 -f 795//795 794//794 796//796 -f 795//795 796//796 797//797 -f 797//797 796//796 791//791 -f 797//797 791//791 798//798 -f 798//798 791//791 792//792 -f 530//530 532//532 799//799 -f 799//799 223//223 225//225 -f 530//530 799//799 794//794 -f 794//794 799//799 796//796 -f 796//796 799//799 225//225 -f 796//796 225//225 147//147 -f 799//799 532//532 800//800 -f 800//800 532//532 658//658 -f 800//800 658//658 220//220 -f 220//220 658//658 555//555 -f 220//220 555//555 801//801 -f 801//801 555//555 554//554 -f 801//801 554//554 802//802 -f 802//802 554//554 553//553 -f 602//602 803//803 804//804 -f 553//553 602//602 802//802 -f 802//802 602//602 804//804 -f 802//802 804//804 218//218 -f 218//218 804//804 216//216 -f 805//805 806//806 807//807 -f 807//807 806//806 808//808 -f 807//807 808//808 809//809 -f 809//809 808//808 804//804 -f 809//809 804//804 810//810 -f 810//810 804//804 803//803 -f 229//229 227//227 811//811 -f 811//811 227//227 808//808 -f 808//808 806//806 811//811 -f 811//811 806//806 597//597 -f 811//811 597//597 599//599 -f 811//811 599//599 812//812 -f 812//812 599//599 575//575 -f 573//573 813//813 814//814 -f 575//575 573//573 812//812 -f 812//812 573//573 814//814 -f 812//812 814//814 285//285 -f 285//285 814//814 286//286 -f 815//815 816//816 817//817 -f 817//817 816//816 818//818 -f 817//817 818//818 819//819 -f 819//819 818//818 814//814 -f 819//819 814//814 820//820 -f 820//820 814//814 813//813 -f 291//291 289//289 821//821 -f 821//821 289//289 818//818 -f 818//818 816//816 821//821 -f 821//821 816//816 548//548 -f 821//821 548//548 550//550 -f 821//821 550//550 822//822 -f 822//822 550//550 552//552 -f 562//562 823//823 824//824 -f 552//552 562//562 822//822 -f 822//822 562//562 824//824 -f 822//822 824//824 268//268 -f 268//268 824//824 269//269 -f 825//825 826//826 827//827 -f 827//827 826//826 828//828 -f 827//827 828//828 829//829 -f 829//829 828//828 824//824 -f 829//829 824//824 830//830 -f 830//830 824//824 823//823 -f 276//276 280//280 831//831 -f 831//831 280//280 828//828 -f 828//828 826//826 831//831 -f 831//831 826//826 544//544 -f 831//831 544//544 546//546 -f 831//831 546//546 832//832 -f 832//832 546//546 559//559 -f 557//557 833//833 834//834 -f 559//559 557//557 832//832 -f 832//832 557//557 834//834 -f 832//832 834//834 251//251 -f 251//251 834//834 258//258 -f 835//835 836//836 837//837 -f 837//837 836//836 838//838 -f 837//837 838//838 839//839 -f 839//839 838//838 834//834 -f 839//839 834//834 840//840 -f 840//840 834//834 833//833 -f 256//256 263//263 841//841 -f 841//841 263//263 838//838 -f 838//838 836//836 841//841 -f 841//841 836//836 539//539 -f 841//841 539//539 541//541 -f 841//841 541//541 842//842 -f 842//842 541//541 596//596 -f 843//843 250//250 255//255 -f 596//596 563//563 842//842 -f 842//842 563//563 772//772 -f 842//842 772//772 255//255 -f 255//255 772//772 844//844 -f 255//255 844//844 843//843 -f 249//249 845//845 846//846 -f 151//151 243//243 847//847 -f 847//847 243//243 245//245 -f 847//847 245//245 848//848 -f 848//848 245//245 247//247 -f 848//848 247//247 442//442 -f 442//442 247//247 249//249 -f 442//442 249//249 441//441 -f 441//441 249//249 846//846 -f 440//440 421//421 849//849 -f 849//849 421//421 850//850 -f 850//850 421//421 423//423 -f 850//850 423//423 851//851 -f 851//851 423//423 425//425 -f 851//851 425//425 852//852 -f 852//852 425//425 427//427 -f 852//852 427//427 853//853 -f 853//853 427//427 429//429 -f 853//853 429//429 854//854 -f 854//854 429//429 430//430 -f 854//854 430//430 855//855 -f 855//855 430//430 458//458 -f 855//855 458//458 856//856 -f 856//856 458//458 457//457 -f 856//856 457//457 857//857 -f 857//857 457//457 858//858 -f 858//858 457//457 416//416 -f 859//859 860//860 861//861 -f 861//861 860//860 797//797 -f 861//861 797//797 651//651 -f 651//651 797//797 798//798 -f 795//795 797//797 862//862 -f 862//862 797//797 863//863 -f 864//864 865//865 866//866 -f 866//866 865//865 795//795 -f 866//866 795//795 867//867 -f 867//867 795//795 862//862 -f 864//864 868//868 865//865 -f 865//865 868//868 869//869 -f 865//865 869//869 870//870 -f 870//870 869//869 871//871 -f 870//870 871//871 860//860 -f 860//860 871//871 872//872 -f 872//872 873//873 860//860 -f 860//860 873//873 874//874 -f 860//860 874//874 797//797 -f 797//797 874//874 875//875 -f 797//797 875//875 863//863 -f 531//531 793//793 876//876 -f 876//876 793//793 795//795 -f 876//876 795//795 877//877 -f 877//877 795//795 865//865 -f 859//859 878//878 860//860 -f 860//860 878//878 870//870 -f 878//878 877//877 870//870 -f 870//870 877//877 865//865 -f 876//876 877//877 879//879 -f 879//879 877//877 878//878 -f 879//879 878//878 880//880 -f 880//880 878//878 859//859 -f 880//880 859//859 861//861 -f 651//651 653//653 861//861 -f 861//861 653//653 880//880 -f 653//653 533//533 880//880 -f 880//880 533//533 879//879 -f 533//533 531//531 879//879 -f 879//879 531//531 876//876 -f 881//881 882//882 883//883 -f 883//883 882//882 809//809 -f 883//883 809//809 601//601 -f 601//601 809//809 810//810 -f 884//884 807//807 885//885 -f 885//885 886//886 884//884 -f 884//884 886//886 887//887 -f 884//884 887//887 888//888 -f 888//888 887//887 889//889 -f 882//882 890//890 809//809 -f 809//809 890//890 891//891 -f 891//891 892//892 809//809 -f 809//809 892//892 893//893 -f 809//809 893//893 807//807 -f 807//807 893//893 894//894 -f 807//807 894//894 885//885 -f 889//889 895//895 888//888 -f 888//888 895//895 896//896 -f 888//888 896//896 882//882 -f 882//882 896//896 897//897 -f 882//882 897//897 890//890 -f 598//598 805//805 898//898 -f 898//898 805//805 807//807 -f 898//898 807//807 899//899 -f 899//899 807//807 884//884 -f 881//881 900//900 882//882 -f 882//882 900//900 888//888 -f 900//900 899//899 888//888 -f 888//888 899//899 884//884 -f 901//901 898//898 899//899 -f 881//881 883//883 902//902 -f 901//901 899//899 902//902 -f 902//902 899//899 900//900 -f 902//902 900//900 881//881 -f 578//578 902//902 601//601 -f 601//601 902//902 883//883 -f 577//577 901//901 578//578 -f 578//578 901//901 902//902 -f 598//598 898//898 577//577 -f 577//577 898//898 901//901 -f 862//862 215//215 867//867 -f 867//867 215//215 210//210 -f 867//867 210//210 866//866 -f 866//866 210//210 209//209 -f 866//866 209//209 864//864 -f 864//864 209//209 208//208 -f 864//864 208//208 868//868 -f 868//868 208//208 309//309 -f 868//868 309//309 869//869 -f 869//869 309//309 307//307 -f 869//869 307//307 871//871 -f 871//871 307//307 305//305 -f 871//871 305//305 872//872 -f 872//872 305//305 304//304 -f 872//872 304//304 873//873 -f 873//873 304//304 303//303 -f 873//873 303//303 874//874 -f 874//874 303//303 211//211 -f 874//874 211//211 875//875 -f 875//875 211//211 212//212 -f 875//875 212//212 863//863 -f 863//863 212//212 214//214 -f 863//863 214//214 862//862 -f 862//862 214//214 215//215 -f 890//890 240//240 891//891 -f 891//891 240//240 239//239 -f 891//891 239//239 892//892 -f 892//892 239//239 238//238 -f 892//892 238//238 893//893 -f 893//893 238//238 233//233 -f 893//893 233//233 894//894 -f 894//894 233//233 232//232 -f 894//894 232//232 885//885 -f 885//885 232//232 226//226 -f 885//885 226//226 886//886 -f 886//886 226//226 228//228 -f 886//886 228//228 887//887 -f 887//887 228//228 230//230 -f 887//887 230//230 889//889 -f 889//889 230//230 231//231 -f 889//889 231//231 895//895 -f 895//895 231//231 234//234 -f 895//895 234//234 896//896 -f 896//896 234//234 235//235 -f 896//896 235//235 897//897 -f 897//897 235//235 237//237 -f 897//897 237//237 890//890 -f 890//890 237//237 240//240 -f 903//903 904//904 905//905 -f 905//905 904//904 819//819 -f 905//905 819//819 572//572 -f 572//572 819//819 820//820 -f 906//906 817//817 907//907 -f 907//907 908//908 906//906 -f 906//906 908//908 909//909 -f 906//906 909//909 910//910 -f 910//910 909//909 911//911 -f 912//912 819//819 913//913 -f 913//913 819//819 904//904 -f 911//911 914//914 910//910 -f 910//910 914//914 915//915 -f 910//910 915//915 904//904 -f 904//904 915//915 916//916 -f 904//904 916//916 913//913 -f 912//912 917//917 819//819 -f 819//819 917//917 918//918 -f 819//819 918//918 817//817 -f 817//817 918//918 919//919 -f 817//817 919//919 907//907 -f 549//549 815//815 920//920 -f 920//920 815//815 817//817 -f 920//920 817//817 921//921 -f 921//921 817//817 906//906 -f 922//922 923//923 924//924 -f 924//924 923//923 829//829 -f 924//924 829//829 561//561 -f 561//561 829//829 830//830 -f 925//925 829//829 926//926 -f 926//926 829//829 923//923 -f 925//925 927//927 829//829 -f 829//829 927//927 928//928 -f 829//829 928//928 827//827 -f 929//929 930//930 931//931 -f 931//931 930//930 932//932 -f 929//929 933//933 930//930 -f 930//930 933//933 934//934 -f 930//930 934//934 923//923 -f 923//923 934//934 935//935 -f 923//923 935//935 926//926 -f 928//928 936//936 827//827 -f 827//827 936//936 937//937 -f 827//827 937//937 932//932 -f 932//932 937//937 938//938 -f 932//932 938//938 931//931 -f 545//545 825//825 939//939 -f 939//939 825//825 827//827 -f 939//939 827//827 940//940 -f 940//940 827//827 932//932 -f 941//941 942//942 943//943 -f 943//943 942//942 839//839 -f 943//943 839//839 556//556 -f 556//556 839//839 840//840 -f 944//944 945//945 946//946 -f 946//946 945//945 942//942 -f 947//947 837//837 948//948 -f 948//948 949//949 947//947 -f 947//947 949//949 950//950 -f 947//947 950//950 946//946 -f 946//946 950//950 951//951 -f 946//946 951//951 944//944 -f 945//945 952//952 942//942 -f 942//942 952//952 953//953 -f 942//942 953//953 839//839 -f 839//839 953//953 954//954 -f 954//954 955//955 839//839 -f 839//839 955//955 956//956 -f 839//839 956//956 837//837 -f 837//837 956//956 957//957 -f 837//837 957//957 948//948 -f 540//540 835//835 958//958 -f 958//958 835//835 837//837 -f 958//958 837//837 959//959 -f 959//959 837//837 947//947 -f 903//903 960//960 904//904 -f 904//904 960//960 910//910 -f 960//960 921//921 910//910 -f 910//910 921//921 906//906 -f 961//961 920//920 921//921 -f 903//903 905//905 962//962 -f 961//961 921//921 962//962 -f 962//962 921//921 960//960 -f 962//962 960//960 903//903 -f 922//922 963//963 923//923 -f 923//923 963//963 930//930 -f 963//963 940//940 930//930 -f 930//930 940//940 932//932 -f 964//964 939//939 940//940 -f 922//922 924//924 965//965 -f 964//964 940//940 965//965 -f 965//965 940//940 963//963 -f 965//965 963//963 922//922 -f 941//941 966//966 942//942 -f 942//942 966//966 946//946 -f 966//966 959//959 946//946 -f 946//946 959//959 947//947 -f 967//967 958//958 959//959 -f 941//941 943//943 968//968 -f 967//967 959//959 968//968 -f 968//968 959//959 966//966 -f 968//968 966//966 941//941 -f 574//574 962//962 572//572 -f 572//572 962//962 905//905 -f 551//551 961//961 574//574 -f 574//574 961//961 962//962 -f 549//549 920//920 551//551 -f 551//551 920//920 961//961 -f 560//560 965//965 561//561 -f 561//561 965//965 924//924 -f 547//547 964//964 560//560 -f 560//560 964//964 965//965 -f 545//545 939//939 547//547 -f 547//547 939//939 964//964 -f 558//558 968//968 556//556 -f 556//556 968//968 943//943 -f 542//542 967//967 558//558 -f 558//558 967//967 968//968 -f 540//540 958//958 542//542 -f 542//542 958//958 967//967 -f 913//913 295//295 912//912 -f 912//912 295//295 287//287 -f 912//912 287//287 917//917 -f 917//917 287//287 302//302 -f 917//917 302//302 918//918 -f 918//918 302//302 301//301 -f 918//918 301//301 919//919 -f 919//919 301//301 300//300 -f 919//919 300//300 907//907 -f 907//907 300//300 288//288 -f 907//907 288//288 908//908 -f 908//908 288//288 290//290 -f 908//908 290//290 909//909 -f 909//909 290//290 292//292 -f 909//909 292//292 911//911 -f 911//911 292//292 293//293 -f 911//911 293//293 914//914 -f 914//914 293//293 298//298 -f 914//914 298//298 915//915 -f 915//915 298//298 297//297 -f 915//915 297//297 916//916 -f 916//916 297//297 296//296 -f 916//916 296//296 913//913 -f 913//913 296//296 295//295 -f 926//926 271//271 925//925 -f 925//925 271//271 270//270 -f 925//925 270//270 927//927 -f 927//927 270//270 284//284 -f 927//927 284//284 928//928 -f 928//928 284//284 283//283 -f 928//928 283//283 936//936 -f 936//936 283//283 282//282 -f 936//936 282//282 937//937 -f 937//937 282//282 281//281 -f 937//937 281//281 938//938 -f 938//938 281//281 279//279 -f 938//938 279//279 931//931 -f 931//931 279//279 278//278 -f 931//931 278//278 929//929 -f 929//929 278//278 275//275 -f 929//929 275//275 933//933 -f 933//933 275//275 274//274 -f 933//933 274//274 934//934 -f 934//934 274//274 273//273 -f 934//934 273//273 935//935 -f 935//935 273//273 272//272 -f 935//935 272//272 926//926 -f 926//926 272//272 271//271 -f 953//953 260//260 954//954 -f 954//954 260//260 259//259 -f 954//954 259//259 955//955 -f 955//955 259//259 267//267 -f 955//955 267//267 956//956 -f 956//956 267//267 266//266 -f 956//956 266//266 957//957 -f 957//957 266//266 265//265 -f 957//957 265//265 948//948 -f 948//948 265//265 264//264 -f 948//948 264//264 949//949 -f 949//949 264//264 262//262 -f 949//949 262//262 950//950 -f 950//950 262//262 261//261 -f 950//950 261//261 951//951 -f 951//951 261//261 257//257 -f 951//951 257//257 944//944 -f 944//944 257//257 254//254 -f 944//944 254//254 945//945 -f 945//945 254//254 253//253 -f 945//945 253//253 952//952 -f 952//952 253//253 252//252 -f 952//952 252//252 953//953 -f 953//953 252//252 260//260 -f 762//762 734//734 763//763 -f 763//763 734//734 730//730 -f 763//763 730//730 663//663 -f 663//663 730//730 770//770 -f 657//657 766//766 760//760 -f 760//760 766//766 729//729 -f 760//760 729//729 761//761 -f 761//761 729//729 738//738 -f 762//762 765//765 734//734 -f 734//734 765//765 736//736 -f 765//765 761//761 736//736 -f 736//736 761//761 738//738 -f 641//641 764//764 663//663 -f 663//663 764//764 763//763 -f 640//640 759//759 641//641 -f 641//641 759//759 764//764 -f 657//657 760//760 640//640 -f 640//640 760//760 759//759 -f 751//751 712//712 752//752 -f 752//752 712//712 714//714 -f 752//752 714//714 566//566 -f 566//566 714//714 757//757 -f 605//605 753//753 746//746 -f 746//746 753//753 717//717 -f 746//746 717//717 747//747 -f 747//747 717//717 716//716 -f 751//751 749//749 712//712 -f 712//712 749//749 720//720 -f 749//749 747//747 720//720 -f 720//720 747//747 716//716 -f 566//566 568//568 752//752 -f 752//752 568//568 750//750 -f 568//568 607//607 750//750 -f 750//750 607//607 748//748 -f 607//607 605//605 748//748 -f 748//748 605//605 746//746 -f 731//731 181//181 740//740 -f 740//740 181//181 197//197 -f 740//740 197//197 741//741 -f 741//741 197//197 196//196 -f 741//741 196//196 742//742 -f 742//742 196//196 194//194 -f 742//742 194//194 739//739 -f 739//739 194//194 192//192 -f 739//739 192//192 737//737 -f 737//737 192//192 191//191 -f 737//737 191//191 735//735 -f 735//735 191//191 188//188 -f 735//735 188//188 733//733 -f 733//733 188//188 187//187 -f 733//733 187//187 743//743 -f 743//743 187//187 186//186 -f 743//743 186//186 744//744 -f 744//744 186//186 185//185 -f 744//744 185//185 745//745 -f 745//745 185//185 184//184 -f 745//745 184//184 732//732 -f 732//732 184//184 182//182 -f 732//732 182//182 731//731 -f 731//731 182//182 181//181 -f 722//722 154//154 721//721 -f 721//721 154//154 170//170 -f 721//721 170//170 719//719 -f 719//719 170//170 172//172 -f 719//719 172//172 723//723 -f 723//723 172//172 164//164 -f 723//723 164//164 724//724 -f 724//724 164//164 162//162 -f 724//724 162//162 725//725 -f 725//725 162//162 161//161 -f 725//725 161//161 713//713 -f 713//713 161//161 160//160 -f 713//713 160//160 715//715 -f 715//715 160//160 158//158 -f 715//715 158//158 726//726 -f 726//726 158//158 167//167 -f 726//726 167//167 727//727 -f 727//727 167//167 166//166 -f 727//727 166//166 728//728 -f 728//728 166//166 165//165 -f 728//728 165//165 718//718 -f 718//718 165//165 155//155 -f 718//718 155//155 722//722 -f 722//722 155//155 154//154 -f 692//692 513//513 693//693 -f 693//693 513//513 515//515 -f 693//693 515//515 583//583 -f 583//583 515//515 710//710 -f 580//580 706//706 687//687 -f 687//687 706//706 522//522 -f 687//687 522//522 688//688 -f 688//688 522//522 524//524 -f 685//685 500//500 686//686 -f 686//686 500//500 502//502 -f 686//686 502//502 620//620 -f 620//620 502//502 704//704 -f 590//590 700//700 680//680 -f 680//680 700//700 506//506 -f 680//680 506//506 681//681 -f 681//681 506//506 496//496 -f 678//678 489//489 679//679 -f 679//679 489//489 479//479 -f 679//679 479//479 535//535 -f 535//535 479//479 698//698 -f 671//671 694//694 673//673 -f 673//673 694//694 485//485 -f 673//673 485//485 674//674 -f 674//674 485//485 488//488 -f 692//692 690//690 513//513 -f 513//513 690//690 517//517 -f 690//690 688//688 517//517 -f 517//517 688//688 524//524 -f 685//685 683//683 500//500 -f 500//500 683//683 498//498 -f 683//683 681//681 498//498 -f 498//498 681//681 496//496 -f 678//678 676//676 489//489 -f 489//489 676//676 482//482 -f 676//676 674//674 482//482 -f 482//482 674//674 488//488 -f 583//583 585//585 693//693 -f 693//693 585//585 691//691 -f 585//585 582//582 691//691 -f 691//691 582//582 689//689 -f 582//582 580//580 689//689 -f 689//689 580//580 687//687 -f 620//620 622//622 686//686 -f 686//686 622//622 684//684 -f 622//622 592//592 684//684 -f 684//684 592//592 682//682 -f 592//592 590//590 682//682 -f 682//682 590//590 680//680 -f 535//535 534//534 679//679 -f 679//679 534//534 677//677 -f 534//534 670//670 677//677 -f 677//677 670//670 675//675 -f 670//670 671//671 675//675 -f 675//675 671//671 673//673 -f 523//523 318//318 527//527 -f 527//527 318//318 317//317 -f 527//527 317//317 528//528 -f 528//528 317//317 335//335 -f 528//528 335//335 529//529 -f 529//529 335//335 334//334 -f 529//529 334//334 518//518 -f 518//518 334//334 333//333 -f 518//518 333//333 519//519 -f 519//519 333//333 326//326 -f 519//519 326//326 514//514 -f 514//514 326//326 328//328 -f 514//514 328//328 516//516 -f 516//516 328//328 329//329 -f 516//516 329//329 520//520 -f 520//520 329//329 325//325 -f 520//520 325//325 521//521 -f 521//521 325//325 322//322 -f 521//521 322//322 526//526 -f 526//526 322//322 321//321 -f 526//526 321//321 525//525 -f 525//525 321//321 332//332 -f 525//525 332//332 523//523 -f 523//523 332//332 318//318 -f 509//509 339//339 497//497 -f 497//497 339//339 338//338 -f 497//497 338//338 499//499 -f 499//499 338//338 355//355 -f 499//499 355//355 510//510 -f 510//510 355//355 354//354 -f 510//510 354//354 511//511 -f 511//511 354//354 353//353 -f 511//511 353//353 512//512 -f 512//512 353//353 352//352 -f 512//512 352//352 501//501 -f 501//501 352//352 350//350 -f 501//501 350//350 503//503 -f 503//503 350//350 349//349 -f 503//503 349//349 504//504 -f 504//504 349//349 346//346 -f 504//504 346//346 505//505 -f 505//505 346//346 343//343 -f 505//505 343//343 507//507 -f 507//507 343//343 341//341 -f 507//507 341//341 508//508 -f 508//508 341//341 340//340 -f 508//508 340//340 509//509 -f 509//509 340//340 339//339 -f 493//493 359//359 494//494 -f 494//494 359//359 358//358 -f 494//494 358//358 495//495 -f 495//495 358//358 377//377 -f 495//495 377//377 483//483 -f 483//483 377//377 376//376 -f 483//483 376//376 484//484 -f 484//484 376//376 375//375 -f 484//484 375//375 490//490 -f 490//490 375//375 369//369 -f 490//490 369//369 491//491 -f 491//491 369//369 368//368 -f 491//491 368//368 492//492 -f 492//492 368//368 367//367 -f 492//492 367//367 480//480 -f 480//480 367//367 366//366 -f 480//480 366//366 481//481 -f 481//481 366//366 373//373 -f 481//481 373//373 486//486 -f 486//486 373//373 371//371 -f 486//486 371//371 487//487 -f 487//487 371//371 370//370 -f 487//487 370//370 493//493 -f 493//493 370//370 359//359 -f 969//969 773//773 970//970 -f 970//970 773//773 588//588 -f 970//970 588//588 971//971 -f 971//971 588//588 587//587 -f 971//971 587//587 972//972 -f 972//972 587//587 571//571 -f 972//972 571//571 973//973 -f 973//973 571//571 974//974 -f 974//974 571//571 570//570 -f 974//974 570//570 975//975 -f 975//975 570//570 976//976 -f 976//976 570//570 634//634 -f 976//976 634//634 977//977 -f 977//977 634//634 408//408 -f 977//977 408//408 412//412 -f 978//978 979//979 980//980 -f 981//981 978//978 982//982 -f 982//982 978//978 980//980 -f 982//982 980//980 983//983 -f 983//983 980//980 984//984 -f 985//985 986//986 987//987 -f 988//988 989//989 985//985 -f 985//985 989//989 990//990 -f 985//985 990//990 991//991 -f 991//991 990//990 992//992 -f 991//991 992//992 993//993 -f 993//993 992//992 994//994 -f 993//993 994//994 995//995 -f 995//995 994//994 996//996 -f 995//995 996//996 980//980 -f 980//980 996//996 997//997 -f 980//980 997//997 984//984 -f 984//984 997//997 998//998 -f 984//984 998//998 999//999 -f 999//999 998//998 1000//1000 -f 999//999 1000//1000 1001//1001 -f 1001//1001 1000//1000 1002//1002 -f 1001//1001 1002//1002 1003//1003 -f 1003//1003 1002//1002 1004//1004 -f 1003//1003 1004//1004 1005//1005 -f 1005//1005 1004//1004 1006//1006 -f 1005//1005 1006//1006 987//987 -f 987//987 1006//1006 988//988 -f 987//987 988//988 985//985 -f 1007//1007 846//846 991//991 -f 991//991 846//846 845//845 -f 991//991 845//845 985//985 -f 985//985 845//845 1008//1008 -f 985//985 1008//1008 1009//1009 -f 1010//1010 1011//1011 1008//1008 -f 1008//1008 1011//1011 1012//1012 -f 1008//1008 1012//1012 1009//1009 -f 980//980 979//979 995//995 -f 995//995 979//979 1013//1013 -f 995//995 1013//1013 993//993 -f 993//993 1013//1013 1014//1014 -f 993//993 1014//1014 991//991 -f 991//991 1014//1014 1007//1007 -f 1015//1015 1016//1016 1017//1017 -f 1018//1018 1015//1015 1019//1019 -f 1019//1019 1015//1015 1017//1017 -f 1019//1019 1017//1017 1020//1020 -f 1020//1020 1017//1017 1021//1021 -f 1022//1022 1023//1023 1024//1024 -f 1024//1024 1023//1023 1025//1025 -f 1024//1024 1025//1025 1026//1026 -f 1026//1026 1025//1025 1027//1027 -f 1026//1026 1027//1027 1028//1028 -f 1028//1028 1027//1027 1029//1029 -f 1028//1028 1029//1029 1030//1030 -f 1030//1030 1029//1029 1031//1031 -f 1030//1030 1031//1031 1032//1032 -f 1032//1032 1031//1031 1033//1033 -f 1032//1032 1033//1033 1034//1034 -f 1034//1034 1033//1033 1035//1035 -f 1034//1034 1035//1035 1016//1016 -f 1016//1016 1035//1035 1036//1036 -f 1016//1016 1036//1036 1017//1017 -f 1017//1017 1036//1036 1037//1037 -f 1017//1017 1037//1037 1038//1038 -f 1038//1038 1037//1037 1039//1039 -f 1038//1038 1039//1039 1040//1040 -f 1040//1040 1039//1039 1041//1041 -f 1040//1040 1041//1041 1042//1042 -f 1042//1042 1041//1041 1022//1022 -f 1042//1042 1022//1022 1024//1024 -f 1042//1042 1043//1043 1040//1040 -f 1040//1040 1043//1043 1044//1044 -f 1040//1040 1044//1044 1038//1038 -f 1038//1038 1044//1044 1045//1045 -f 1038//1038 1045//1045 1017//1017 -f 1017//1017 1045//1045 1021//1021 -f 1046//1046 1024//1024 1047//1047 -f 1047//1047 1024//1024 1048//1048 -f 384//384 1043//1043 385//385 -f 385//385 1043//1043 1042//1042 -f 385//385 1042//1042 1049//1049 -f 1049//1049 1042//1042 1024//1024 -f 1049//1049 1024//1024 1050//1050 -f 1046//1046 1051//1051 1024//1024 -f 1024//1024 1051//1051 1052//1052 -f 1024//1024 1052//1052 1050//1050 -f 1053//1053 1054//1054 1055//1055 -f 1055//1055 1054//1054 1056//1056 -f 1055//1055 1056//1056 1057//1057 -f 1057//1057 1056//1056 1058//1058 -f 1059//1059 1060//1060 1058//1058 -f 1058//1058 1060//1060 1061//1061 -f 1058//1058 1061//1061 1057//1057 -f 1062//1062 1063//1063 1059//1059 -f 1059//1059 1063//1063 1064//1064 -f 1059//1059 1064//1064 1060//1060 -f 1065//1065 1066//1066 1062//1062 -f 1062//1062 1066//1066 1067//1067 -f 1062//1062 1067//1067 1063//1063 -f 1068//1068 1069//1069 1070//1070 -f 1070//1070 1069//1069 1071//1071 -f 1070//1070 1071//1071 1072//1072 -f 1072//1072 1071//1071 1073//1073 -f 1072//1072 1073//1073 1065//1065 -f 1065//1065 1073//1073 1074//1074 -f 1065//1065 1074//1074 1066//1066 -f 1075//1075 1076//1076 1068//1068 -f 1068//1068 1076//1076 1077//1077 -f 1068//1068 1077//1077 1069//1069 -f 1078//1078 1079//1079 1075//1075 -f 1075//1075 1079//1079 1080//1080 -f 1075//1075 1080//1080 1076//1076 -f 1081//1081 1082//1082 1078//1078 -f 1078//1078 1082//1082 1083//1083 -f 1078//1078 1083//1083 1079//1079 -f 1084//1084 1082//1082 1085//1085 -f 1085//1085 1082//1082 1081//1081 -f 1085//1085 1081//1081 1086//1086 -f 1086//1086 1081//1081 1054//1054 -f 1086//1086 1054//1054 1087//1087 -f 1087//1087 1054//1054 1053//1053 -f 1087//1087 1053//1053 1088//1088 -f 1089//1089 1058//1058 1090//1090 -f 1090//1090 1058//1058 1056//1056 -f 1090//1090 1056//1056 1091//1091 -f 1091//1091 1056//1056 1054//1054 -f 1091//1091 1054//1054 1092//1092 -f 1092//1092 1054//1054 1081//1081 -f 1092//1092 1081//1081 1093//1093 -f 1093//1093 1081//1081 1078//1078 -f 1093//1093 1078//1078 1094//1094 -f 1094//1094 1078//1078 1075//1075 -f 1094//1094 1075//1075 1095//1095 -f 1095//1095 1075//1075 1068//1068 -f 1095//1095 1068//1068 1096//1096 -f 1096//1096 1068//1068 1070//1070 -f 1096//1096 1070//1070 1097//1097 -f 1097//1097 1070//1070 1072//1072 -f 1097//1097 1072//1072 1098//1098 -f 1098//1098 1072//1072 1065//1065 -f 1098//1098 1065//1065 1099//1099 -f 1099//1099 1065//1065 1062//1062 -f 1099//1099 1062//1062 1100//1100 -f 1100//1100 1062//1062 1059//1059 -f 1100//1100 1059//1059 1089//1089 -f 1089//1089 1059//1059 1058//1058 -f 1101//1101 1102//1102 1103//1103 -f 1104//1104 1105//1105 1106//1106 -f 1106//1106 1105//1105 1107//1107 -f 1106//1106 1107//1107 1108//1108 -f 1109//1109 1110//1110 1108//1108 -f 1108//1108 1110//1110 1111//1111 -f 1108//1108 1111//1111 1106//1106 -f 1112//1112 1113//1113 1109//1109 -f 1109//1109 1113//1113 1114//1114 -f 1109//1109 1114//1114 1110//1110 -f 1115//1115 1116//1116 1112//1112 -f 1112//1112 1116//1116 1117//1117 -f 1112//1112 1117//1117 1113//1113 -f 1118//1118 1119//1119 1115//1115 -f 1115//1115 1119//1119 1120//1120 -f 1115//1115 1120//1120 1116//1116 -f 1121//1121 1122//1122 1118//1118 -f 1118//1118 1122//1122 1123//1123 -f 1118//1118 1123//1123 1119//1119 -f 1124//1124 1125//1125 1121//1121 -f 1121//1121 1125//1125 1126//1126 -f 1121//1121 1126//1126 1122//1122 -f 1127//1127 1128//1128 1124//1124 -f 1124//1124 1128//1128 1129//1129 -f 1124//1124 1129//1129 1125//1125 -f 1103//1103 1130//1130 1101//1101 -f 1101//1101 1130//1130 1131//1131 -f 1101//1101 1131//1131 1127//1127 -f 1127//1127 1131//1131 1132//1132 -f 1127//1127 1132//1132 1128//1128 -f 1133//1133 1103//1103 1134//1134 -f 1134//1134 1103//1103 1102//1102 -f 1134//1134 1102//1102 1135//1135 -f 1135//1135 1102//1102 1105//1105 -f 1135//1135 1105//1105 1136//1136 -f 1136//1136 1105//1105 1104//1104 -f 1136//1136 1104//1104 1137//1137 -f 1138//1138 1102//1102 1139//1139 -f 1139//1139 1102//1102 1101//1101 -f 1139//1139 1101//1101 1140//1140 -f 1140//1140 1101//1101 1127//1127 -f 1140//1140 1127//1127 1141//1141 -f 1141//1141 1127//1127 1124//1124 -f 1141//1141 1124//1124 1142//1142 -f 1142//1142 1124//1124 1121//1121 -f 1142//1142 1121//1121 1143//1143 -f 1143//1143 1121//1121 1118//1118 -f 1143//1143 1118//1118 1144//1144 -f 1144//1144 1118//1118 1115//1115 -f 1144//1144 1115//1115 1145//1145 -f 1145//1145 1115//1115 1112//1112 -f 1145//1145 1112//1112 1146//1146 -f 1146//1146 1112//1112 1109//1109 -f 1146//1146 1109//1109 1147//1147 -f 1147//1147 1109//1109 1108//1108 -f 1147//1147 1108//1108 1148//1148 -f 1148//1148 1108//1108 1107//1107 -f 1148//1148 1107//1107 1149//1149 -f 1149//1149 1107//1107 1105//1105 -f 1149//1149 1105//1105 1138//1138 -f 1138//1138 1105//1105 1102//1102 -f 628//628 992//992 629//629 -f 629//629 992//992 990//990 -f 629//629 990//990 630//630 -f 630//630 990//990 989//989 -f 630//630 989//989 565//565 -f 565//565 989//989 988//988 -f 565//565 988//988 636//636 -f 636//636 988//988 1006//1006 -f 636//636 1006//1006 635//635 -f 635//635 1006//1006 1004//1004 -f 635//635 1004//1004 633//633 -f 633//633 1004//1004 1002//1002 -f 633//633 1002//1002 632//632 -f 632//632 1002//1002 1000//1000 -f 632//632 1000//1000 631//631 -f 631//631 1000//1000 998//998 -f 631//631 998//998 649//649 -f 649//649 998//998 997//997 -f 649//649 997//997 650//650 -f 650//650 997//997 996//996 -f 650//650 996//996 642//642 -f 642//642 996//996 994//994 -f 642//642 994//994 628//628 -f 628//628 994//994 992//992 -f 619//619 1022//1022 644//644 -f 644//644 1022//1022 1041//1041 -f 644//644 1041//1041 643//643 -f 643//643 1041//1041 1039//1039 -f 643//643 1039//1039 648//648 -f 648//648 1039//1039 1037//1037 -f 648//648 1037//1037 647//647 -f 647//647 1037//1037 1036//1036 -f 647//647 1036//1036 646//646 -f 646//646 1036//1036 1035//1035 -f 646//646 1035//1035 645//645 -f 645//645 1035//1035 1033//1033 -f 645//645 1033//1033 537//537 -f 537//537 1033//1033 1031//1031 -f 537//537 1031//1031 538//538 -f 538//538 1031//1031 1029//1029 -f 538//538 1029//1029 543//543 -f 543//543 1029//1029 1027//1027 -f 543//543 1027//1027 608//608 -f 608//608 1027//1027 1025//1025 -f 608//608 1025//1025 618//618 -f 618//618 1025//1025 1023//1023 -f 618//618 1023//1023 619//619 -f 619//619 1023//1023 1022//1022 -f 595//595 1145//1145 594//594 -f 594//594 1145//1145 1146//1146 -f 594//594 1146//1146 593//593 -f 593//593 1146//1146 1147//1147 -f 593//593 1147//1147 614//614 -f 614//614 1147//1147 1148//1148 -f 614//614 1148//1148 613//613 -f 613//613 1148//1148 1149//1149 -f 613//613 1149//1149 617//617 -f 617//617 1149//1149 1138//1138 -f 617//617 1138//1138 616//616 -f 616//616 1138//1138 1139//1139 -f 616//616 1139//1139 662//662 -f 662//662 1139//1139 1140//1140 -f 662//662 1140//1140 659//659 -f 659//659 1140//1140 1141//1141 -f 659//659 1141//1141 660//660 -f 660//660 1141//1141 1142//1142 -f 660//660 1142//1142 661//661 -f 661//661 1142//1142 1143//1143 -f 661//661 1143//1143 669//669 -f 669//669 1143//1143 1144//1144 -f 669//669 1144//1144 595//595 -f 595//595 1144//1144 1145//1145 -f 627//627 1096//1096 603//603 -f 603//603 1096//1096 1097//1097 -f 603//603 1097//1097 576//576 -f 576//576 1097//1097 1098//1098 -f 576//576 1098//1098 600//600 -f 600//600 1098//1098 1099//1099 -f 600//600 1099//1099 612//612 -f 612//612 1099//1099 1100//1100 -f 612//612 1100//1100 611//611 -f 611//611 1100//1100 1089//1089 -f 611//611 1089//1089 564//564 -f 564//564 1089//1089 1090//1090 -f 564//564 1090//1090 609//609 -f 609//609 1090//1090 1091//1091 -f 609//609 1091//1091 610//610 -f 610//610 1091//1091 1092//1092 -f 610//610 1092//1092 615//615 -f 615//615 1092//1092 1093//1093 -f 615//615 1093//1093 625//625 -f 625//625 1093//1093 1094//1094 -f 625//625 1094//1094 626//626 -f 626//626 1094//1094 1095//1095 -f 626//626 1095//1095 627//627 -f 627//627 1095//1095 1096//1096 -f 475//475 774//774 1150//1150 -f 1150//1150 774//774 776//776 -f 1150//1150 776//776 1151//1151 -f 1151//1151 776//776 1152//1152 -f 1152//1152 776//776 777//777 -f 1152//1152 777//777 1153//1153 -f 1153//1153 777//777 1154//1154 -f 1154//1154 777//777 360//360 -f 1154//1154 360//360 364//364 -f 364//364 363//363 1155//1155 -f 364//364 1155//1155 1154//1154 -f 1154//1154 1155//1155 1156//1156 -f 1154//1154 1156//1156 1153//1153 -f 1153//1153 1156//1156 1157//1157 -f 1153//1153 1157//1157 1152//1152 -f 1152//1152 1157//1157 1151//1151 -f 1151//1151 1157//1157 1158//1158 -f 1151//1151 1158//1158 1150//1150 -f 1150//1150 1158//1158 476//476 -f 1150//1150 476//476 475//475 -f 773//773 1159//1159 772//772 -f 772//772 1159//1159 844//844 -f 1159//1159 1160//1160 844//844 -f 844//844 1160//1160 1161//1161 -f 844//844 1161//1161 843//843 -f 148//148 250//250 1162//1162 -f 1162//1162 250//250 843//843 -f 1162//1162 843//843 1163//1163 -f 1163//1163 843//843 1161//1161 -f 773//773 969//969 1164//1164 -f 773//773 1164//1164 1159//1159 -f 1159//1159 1164//1164 1165//1165 -f 1159//1159 1165//1165 1160//1160 -f 1160//1160 1165//1165 1166//1166 -f 1160//1160 1166//1166 1161//1161 -f 1161//1161 1166//1166 1163//1163 -f 1163//1163 1166//1166 1167//1167 -f 1163//1163 1167//1167 1162//1162 -f 1162//1162 1167//1167 149//149 -f 1162//1162 149//149 148//148 -f 448//448 447//447 1168//1168 -f 448//448 1168//1168 1169//1169 -f 1169//1169 1168//1168 1170//1170 -f 1169//1169 1170//1170 1171//1171 -f 1171//1171 1170//1170 414//414 -f 1171//1171 414//414 415//415 -f 1172//1172 428//428 1173//1173 -f 1173//1173 428//428 426//426 -f 1173//1173 426//426 1174//1174 -f 1174//1174 426//426 424//424 -f 1174//1174 424//424 1175//1175 -f 1175//1175 424//424 422//422 -f 1175//1175 422//422 1176//1176 -f 1176//1176 422//422 445//445 -f 1176//1176 445//445 1177//1177 -f 1177//1177 445//445 444//444 -f 1177//1177 444//444 1178//1178 -f 1178//1178 444//444 443//443 -f 1178//1178 443//443 1179//1179 -f 1179//1179 443//443 439//439 -f 1179//1179 439//439 1180//1180 -f 1180//1180 439//439 438//438 -f 1180//1180 438//438 1181//1181 -f 1181//1181 438//438 436//436 -f 1181//1181 436//436 1182//1182 -f 1182//1182 436//436 434//434 -f 1182//1182 434//434 1183//1183 -f 1183//1183 434//434 432//432 -f 1183//1183 432//432 1184//1184 -f 1184//1184 432//432 431//431 -f 1184//1184 431//431 1185//1185 -f 1185//1185 431//431 419//419 -f 1185//1185 419//419 1186//1186 -f 1186//1186 419//419 418//418 -f 1186//1186 418//418 1187//1187 -f 1187//1187 418//418 455//455 -f 1187//1187 455//455 1188//1188 -f 1188//1188 455//455 454//454 -f 1188//1188 454//454 1189//1189 -f 1189//1189 454//454 452//452 -f 1189//1189 452//452 1190//1190 -f 1190//1190 452//452 450//450 -f 1190//1190 450//450 1191//1191 -f 1191//1191 450//450 449//449 -f 1191//1191 449//449 1192//1192 -f 1192//1192 449//449 463//463 -f 1192//1192 463//463 1193//1193 -f 1193//1193 463//463 462//462 -f 1193//1193 462//462 1194//1194 -f 1194//1194 462//462 461//461 -f 1194//1194 461//461 1195//1195 -f 1195//1195 461//461 460//460 -f 1195//1195 460//460 1196//1196 -f 1196//1196 460//460 459//459 -f 1196//1196 459//459 1197//1197 -f 1197//1197 459//459 456//456 -f 1197//1197 456//456 1172//1172 -f 1172//1172 456//456 428//428 -f 1198//1198 1195//1195 1199//1199 -f 1199//1199 1195//1195 1196//1196 -f 1199//1199 1196//1196 1200//1200 -f 1200//1200 1196//1196 1197//1197 -f 1200//1200 1197//1197 1201//1201 -f 1201//1201 1197//1197 1172//1172 -f 1201//1201 1172//1172 1202//1202 -f 1202//1202 1172//1172 1173//1173 -f 1202//1202 1173//1173 1203//1203 -f 1204//1204 1188//1188 1205//1205 -f 1205//1205 1188//1188 1189//1189 -f 1205//1205 1189//1189 1206//1206 -f 1206//1206 1189//1189 1190//1190 -f 1206//1206 1190//1190 1207//1207 -f 1207//1207 1190//1190 1191//1191 -f 1207//1207 1191//1191 1208//1208 -f 1208//1208 1191//1191 1192//1192 -f 1208//1208 1192//1192 1209//1209 -f 1209//1209 1192//1192 1193//1193 -f 1209//1209 1193//1193 1198//1198 -f 1198//1198 1193//1193 1194//1194 -f 1198//1198 1194//1194 1195//1195 -f 1173//1173 1174//1174 1203//1203 -f 1203//1203 1174//1174 1175//1175 -f 1203//1203 1175//1175 1210//1210 -f 1210//1210 1175//1175 1176//1176 -f 1210//1210 1176//1176 1211//1211 -f 1211//1211 1176//1176 1177//1177 -f 1211//1211 1177//1177 1212//1212 -f 1212//1212 1177//1177 1178//1178 -f 1212//1212 1178//1178 1213//1213 -f 1213//1213 1178//1178 1179//1179 -f 1213//1213 1179//1179 1214//1214 -f 1214//1214 1179//1179 1180//1180 -f 1214//1214 1180//1180 1215//1215 -f 1180//1180 1181//1181 1215//1215 -f 1215//1215 1181//1181 1182//1182 -f 1215//1215 1182//1182 1216//1216 -f 1216//1216 1182//1182 1183//1183 -f 1216//1216 1183//1183 1217//1217 -f 1217//1217 1183//1183 1184//1184 -f 1217//1217 1184//1184 1218//1218 -f 1218//1218 1184//1184 1185//1185 -f 1218//1218 1185//1185 1219//1219 -f 1219//1219 1185//1185 1186//1186 -f 1219//1219 1186//1186 1204//1204 -f 1204//1204 1186//1186 1187//1187 -f 1204//1204 1187//1187 1188//1188 -f 1220//1220 1202//1202 1221//1221 -f 1221//1221 1202//1202 1203//1203 -f 1221//1221 1203//1203 1222//1222 -f 1222//1222 1203//1203 1210//1210 -f 1222//1222 1210//1210 1223//1223 -f 1223//1223 1210//1210 1211//1211 -f 1223//1223 1211//1211 1224//1224 -f 1224//1224 1211//1211 1212//1212 -f 1224//1224 1212//1212 1225//1225 -f 1225//1225 1212//1212 1213//1213 -f 1225//1225 1213//1213 1226//1226 -f 1226//1226 1213//1213 1214//1214 -f 1226//1226 1214//1214 1227//1227 -f 1227//1227 1214//1214 1215//1215 -f 1227//1227 1215//1215 1228//1228 -f 1228//1228 1215//1215 1216//1216 -f 1228//1228 1216//1216 1229//1229 -f 1229//1229 1216//1216 1217//1217 -f 1229//1229 1217//1217 1230//1230 -f 1230//1230 1217//1217 1218//1218 -f 1230//1230 1218//1218 1231//1231 -f 1231//1231 1218//1218 1219//1219 -f 1231//1231 1219//1219 1232//1232 -f 1232//1232 1219//1219 1204//1204 -f 1232//1232 1204//1204 1233//1233 -f 1233//1233 1204//1204 1205//1205 -f 1233//1233 1205//1205 1234//1234 -f 1234//1234 1205//1205 1206//1206 -f 1234//1234 1206//1206 1235//1235 -f 1235//1235 1206//1206 1207//1207 -f 1235//1235 1207//1207 1236//1236 -f 1236//1236 1207//1207 1208//1208 -f 1236//1236 1208//1208 1237//1237 -f 1237//1237 1208//1208 1209//1209 -f 1237//1237 1209//1209 1238//1238 -f 1238//1238 1209//1209 1198//1198 -f 1238//1238 1198//1198 1239//1239 -f 1239//1239 1198//1198 1199//1199 -f 1239//1239 1199//1199 1240//1240 -f 1240//1240 1199//1199 1200//1200 -f 1240//1240 1200//1200 1241//1241 -f 1241//1241 1200//1200 1201//1201 -f 1241//1241 1201//1201 1220//1220 -f 1220//1220 1201//1201 1202//1202 -f 1242//1242 1238//1238 1243//1243 -f 1243//1243 1238//1238 1239//1239 -f 1243//1243 1239//1239 1244//1244 -f 1244//1244 1239//1239 1240//1240 -f 1244//1244 1240//1240 1245//1245 -f 1245//1245 1240//1240 1241//1241 -f 1245//1245 1241//1241 1246//1246 -f 1246//1246 1241//1241 1220//1220 -f 1246//1246 1220//1220 1247//1247 -f 1247//1247 1220//1220 1221//1221 -f 1247//1247 1221//1221 1248//1248 -f 1248//1248 1221//1221 1222//1222 -f 1248//1248 1222//1222 1249//1249 -f 1250//1250 1232//1232 1251//1251 -f 1251//1251 1232//1232 1233//1233 -f 1251//1251 1233//1233 1252//1252 -f 1252//1252 1233//1233 1234//1234 -f 1252//1252 1234//1234 1253//1253 -f 1253//1253 1234//1234 1235//1235 -f 1253//1253 1235//1235 1254//1254 -f 1254//1254 1235//1235 1236//1236 -f 1254//1254 1236//1236 1242//1242 -f 1242//1242 1236//1236 1237//1237 -f 1242//1242 1237//1237 1238//1238 -f 1222//1222 1223//1223 1249//1249 -f 1249//1249 1223//1223 1224//1224 -f 1249//1249 1224//1224 1255//1255 -f 1255//1255 1224//1224 1225//1225 -f 1255//1255 1225//1225 1256//1256 -f 1256//1256 1225//1225 1226//1226 -f 1256//1256 1226//1226 1257//1257 -f 1257//1257 1226//1226 1227//1227 -f 1257//1257 1227//1227 1258//1258 -f 1258//1258 1227//1227 1228//1228 -f 1258//1258 1228//1228 1259//1259 -f 1259//1259 1228//1228 1229//1229 -f 1259//1259 1229//1229 1260//1260 -f 1260//1260 1229//1229 1230//1230 -f 1260//1260 1230//1230 1250//1250 -f 1250//1250 1230//1230 1231//1231 -f 1250//1250 1231//1231 1232//1232 -f 1261//1261 1246//1246 1262//1262 -f 1262//1262 1246//1246 1247//1247 -f 1262//1262 1247//1247 1263//1263 -f 1263//1263 1247//1247 1248//1248 -f 1263//1263 1248//1248 1264//1264 -f 1264//1264 1248//1248 1249//1249 -f 1264//1264 1249//1249 1265//1265 -f 1265//1265 1249//1249 1255//1255 -f 1265//1265 1255//1255 1266//1266 -f 1266//1266 1255//1255 1256//1256 -f 1266//1266 1256//1256 1267//1267 -f 1267//1267 1256//1256 1257//1257 -f 1267//1267 1257//1257 1268//1268 -f 1268//1268 1257//1257 1258//1258 -f 1268//1268 1258//1258 1269//1269 -f 1269//1269 1258//1258 1259//1259 -f 1269//1269 1259//1259 1270//1270 -f 1270//1270 1259//1259 1260//1260 -f 1270//1270 1260//1260 1271//1271 -f 1271//1271 1260//1260 1250//1250 -f 1271//1271 1250//1250 1272//1272 -f 1272//1272 1250//1250 1251//1251 -f 1272//1272 1251//1251 1273//1273 -f 1273//1273 1251//1251 1252//1252 -f 1273//1273 1252//1252 1274//1274 -f 1274//1274 1252//1252 1253//1253 -f 1274//1274 1253//1253 1275//1275 -f 1275//1275 1253//1253 1254//1254 -f 1275//1275 1254//1254 1276//1276 -f 1276//1276 1254//1254 1242//1242 -f 1276//1276 1242//1242 1277//1277 -f 1277//1277 1242//1242 1243//1243 -f 1277//1277 1243//1243 1278//1278 -f 1278//1278 1243//1243 1244//1244 -f 1278//1278 1244//1244 1279//1279 -f 1279//1279 1244//1244 1245//1245 -f 1279//1279 1245//1245 1261//1261 -f 1261//1261 1245//1245 1246//1246 -f 1261//1261 1262//1262 1280//1280 -f 1277//1277 1278//1278 1280//1280 -f 1280//1280 1278//1278 1279//1279 -f 1280//1280 1279//1279 1261//1261 -f 1274//1274 1275//1275 1280//1280 -f 1280//1280 1275//1275 1276//1276 -f 1280//1280 1276//1276 1277//1277 -f 1271//1271 1272//1272 1280//1280 -f 1280//1280 1272//1272 1273//1273 -f 1280//1280 1273//1273 1274//1274 -f 1268//1268 1269//1269 1280//1280 -f 1280//1280 1269//1269 1270//1270 -f 1280//1280 1270//1270 1271//1271 -f 1265//1265 1266//1266 1280//1280 -f 1280//1280 1266//1266 1267//1267 -f 1280//1280 1267//1267 1268//1268 -f 1262//1262 1263//1263 1280//1280 -f 1280//1280 1263//1263 1264//1264 -f 1280//1280 1264//1264 1265//1265 -f 838//838 263//263 834//834 -f 834//834 263//263 258//258 -f 828//828 280//280 824//824 -f 824//824 280//280 269//269 -f 818//818 289//289 814//814 -f 814//814 289//289 286//286 -f 216//216 804//804 217//217 -f 217//217 804//804 808//808 -f 217//217 808//808 227//227 -f 311//311 791//791 146//146 -f 146//146 791//791 796//796 -f 146//146 796//796 147//147 -f 768//768 313//313 769//769 -f 769//769 313//313 312//312 -f 316//316 756//756 315//315 -f 315//315 756//756 755//755 -f 315//315 755//755 314//314 -f 708//708 337//337 709//709 -f 709//709 337//337 336//336 -f 702//702 357//357 703//703 -f 703//703 357//357 356//356 -f 696//696 381//381 697//697 -f 697//697 381//381 380//380 -f 535//535 698//698 536//536 -f 536//536 698//698 699//699 -f 672//672 695//695 671//671 -f 671//671 695//695 694//694 -f 620//620 704//704 621//621 -f 621//621 704//704 705//705 -f 589//589 701//701 590//590 -f 590//590 701//701 700//700 -f 583//583 710//710 584//584 -f 584//584 710//710 711//711 -f 579//579 707//707 580//580 -f 580//580 707//707 706//706 -f 566//566 757//757 567//567 -f 567//567 757//757 758//758 -f 604//604 754//754 605//605 -f 605//605 754//754 753//753 -f 539//539 836//836 540//540 -f 540//540 836//836 835//835 -f 556//556 840//840 557//557 -f 557//557 840//840 833//833 -f 544//544 826//826 545//545 -f 545//545 826//826 825//825 -f 561//561 830//830 562//562 -f 562//562 830//830 823//823 -f 548//548 816//816 549//549 -f 549//549 816//816 815//815 -f 572//572 820//820 573//573 -f 573//573 820//820 813//813 -f 597//597 806//806 598//598 -f 598//598 806//806 805//805 -f 601//601 810//810 602//602 -f 602//602 810//810 803//803 -f 663//663 770//770 664//664 -f 664//664 770//770 771//771 -f 656//656 767//767 657//657 -f 657//657 767//767 766//766 -f 651//651 798//798 652//652 -f 652//652 798//798 792//792 -f 530//530 794//794 531//531 -f 531//531 794//794 793//793 -f 842//842 255//255 841//841 -f 841//841 255//255 256//256 -f 276//276 831//831 277//277 -f 277//277 831//831 832//832 -f 277//277 832//832 251//251 -f 291//291 821//821 299//299 -f 299//299 821//821 822//822 -f 299//299 822//822 268//268 -f 229//229 811//811 294//294 -f 294//294 811//811 812//812 -f 294//294 812//812 285//285 -f 802//802 218//218 801//801 -f 801//801 218//218 220//220 -f 800//800 220//220 799//799 -f 799//799 220//220 223//223 -f 778//778 362//362 775//775 -f 775//775 362//362 361//361 -f 378//378 779//779 379//379 -f 379//379 779//779 780//780 -f 379//379 780//780 344//344 -f 347//347 781//781 348//348 -f 348//348 781//781 782//782 -f 348//348 782//782 323//323 -f 331//331 783//783 330//330 -f 330//330 783//783 784//784 -f 330//330 784//784 159//159 -f 788//788 180//180 787//787 -f 787//787 180//180 178//178 -f 786//786 178//178 785//785 -f 785//785 178//178 176//176 -f 790//790 207//207 789//789 -f 789//789 207//207 206//206 -f 789//789 206//206 193//193 -f 417//417 1043//1043 386//386 -f 386//386 1043//1043 384//384 -f 1043//1043 417//417 1044//1044 -f 1044//1044 417//417 451//451 -f 1044//1044 451//451 1045//1045 -f 1045//1045 451//451 453//453 -f 1045//1045 453//453 1021//1021 -f 1021//1021 453//453 420//420 -f 1049//1049 363//363 385//385 -f 385//385 363//363 365//365 -f 448//448 1020//1020 420//420 -f 420//420 1020//1020 1021//1021 -f 1047//1047 476//476 1046//1046 -f 1046//1046 476//476 1158//1158 -f 1046//1046 1158//1158 1051//1051 -f 1051//1051 1158//1158 1157//1157 -f 1051//1051 1157//1157 1052//1052 -f 1052//1052 1157//1157 1156//1156 -f 1052//1052 1156//1156 1050//1050 -f 1050//1050 1156//1156 1155//1155 -f 1050//1050 1155//1155 1049//1049 -f 1049//1049 1155//1155 363//363 -f 1020//1020 448//448 1169//1169 -f 1020//1020 1169//1169 1019//1019 -f 1019//1019 1169//1169 1171//1171 -f 1019//1019 1171//1171 1018//1018 -f 1018//1018 1171//1171 415//415 -f 1018//1018 415//415 1015//1015 -f 1048//1048 477//477 1047//1047 -f 1047//1047 477//477 476//476 -f 410//410 1016//1016 415//415 -f 415//415 1016//1016 1015//1015 -f 1034//1034 411//411 465//465 -f 477//477 1048//1048 474//474 -f 474//474 1048//1048 1024//1024 -f 474//474 1024//1024 1026//1026 -f 1034//1034 465//465 1032//1032 -f 1032//1032 465//465 466//466 -f 1032//1032 466//466 1030//1030 -f 1030//1030 466//466 468//468 -f 1030//1030 468//468 1028//1028 -f 468//468 469//469 1028//1028 -f 1028//1028 469//469 471//471 -f 1028//1028 471//471 1026//1026 -f 1026//1026 471//471 472//472 -f 1026//1026 472//472 474//474 -f 411//411 1034//1034 410//410 -f 410//410 1034//1034 1016//1016 -f 1007//1007 437//437 846//846 -f 846//846 437//437 441//441 -f 845//845 249//249 1008//1008 -f 1008//1008 249//249 150//150 -f 1008//1008 150//150 149//149 -f 979//979 446//446 1013//1013 -f 1013//1013 446//446 433//433 -f 1013//1013 433//433 1014//1014 -f 1014//1014 433//433 435//435 -f 1014//1014 435//435 1007//1007 -f 1007//1007 435//435 437//437 -f 986//986 985//985 1009//1009 -f 986//986 1009//1009 969//969 -f 1008//1008 149//149 1010//1010 -f 1010//1010 149//149 1167//1167 -f 1010//1010 1167//1167 1011//1011 -f 1011//1011 1167//1167 1166//1166 -f 1011//1011 1166//1166 1012//1012 -f 1012//1012 1166//1166 1165//1165 -f 1012//1012 1165//1165 1009//1009 -f 1009//1009 1165//1165 1164//1164 -f 1009//1009 1164//1164 969//969 -f 978//978 447//447 979//979 -f 979//979 447//447 446//446 -f 969//969 970//970 986//986 -f 983//983 414//414 1170//1170 -f 983//983 1170//1170 982//982 -f 982//982 1170//1170 1168//1168 -f 982//982 1168//1168 981//981 -f 981//981 1168//1168 447//447 -f 981//981 447//447 978//978 -f 987//987 986//986 970//970 -f 970//970 971//971 987//987 -f 987//987 971//971 972//972 -f 987//987 972//972 1005//1005 -f 1005//1005 972//972 973//973 -f 973//973 974//974 1005//1005 -f 1005//1005 974//974 975//975 -f 1005//1005 975//975 1003//1003 -f 975//975 976//976 1003//1003 -f 1003//1003 976//976 977//977 -f 1003//1003 977//977 1001//1001 -f 1001//1001 977//977 412//412 -f 1001//1001 412//412 999//999 -f 984//984 413//413 983//983 -f 983//983 413//413 414//414 -f 413//413 984//984 412//412 -f 412//412 984//984 999//999 -f 416//416 387//387 858//858 -f 858//858 387//387 388//388 -f 405//405 858//858 388//388 -f 404//404 857//857 405//405 -f 405//405 857//857 858//858 -f 1103//1103 1133//1133 382//382 -f 382//382 1133//1133 383//383 -f 383//383 400//400 388//388 -f 388//388 400//400 405//405 -f 857//857 404//404 856//856 -f 856//856 404//404 406//406 -f 856//856 406//406 855//855 -f 855//855 406//406 407//407 -f 855//855 407//407 854//854 -f 854//854 407//407 399//399 -f 854//854 399//399 853//853 -f 853//853 399//399 398//398 -f 853//853 398//398 852//852 -f 852//852 398//398 396//396 -f 852//852 396//396 851//851 -f 851//851 396//396 395//395 -f 851//851 395//395 850//850 -f 850//850 395//395 403//403 -f 382//382 163//163 174//174 -f 190//190 200//200 1106//1106 -f 1106//1106 200//200 390//390 -f 1106//1106 390//390 1104//1104 -f 190//190 1106//1106 189//189 -f 189//189 1106//1106 1111//1111 -f 189//189 1111//1111 198//198 -f 1111//1111 1110//1110 198//198 -f 198//198 1110//1110 1114//1114 -f 198//198 1114//1114 199//199 -f 1114//1114 1113//1113 199//199 -f 199//199 1113//1113 1117//1117 -f 199//199 1117//1117 179//179 -f 1117//1117 1116//1116 179//179 -f 179//179 1116//1116 1120//1120 -f 179//179 1120//1120 177//177 -f 1120//1120 1119//1119 177//177 -f 177//177 1119//1119 1123//1123 -f 177//177 1123//1123 168//168 -f 168//168 1123//1123 1122//1122 -f 168//168 1122//1122 169//169 -f 169//169 1122//1122 1126//1126 -f 169//169 1126//1126 171//171 -f 1126//1126 1125//1125 171//171 -f 171//171 1125//1125 1129//1129 -f 171//171 1129//1129 173//173 -f 1129//1129 1128//1128 173//173 -f 173//173 1128//1128 1132//1132 -f 173//173 1132//1132 174//174 -f 174//174 1132//1132 1131//1131 -f 174//174 1131//1131 382//382 -f 382//382 1131//1131 1130//1130 -f 382//382 1130//1130 1103//1103 -f 383//383 1133//1133 400//400 -f 394//394 849//849 403//403 -f 403//403 849//849 850//850 -f 849//849 848//848 440//440 -f 440//440 848//848 442//442 -f 389//389 1137//1137 390//390 -f 390//390 1137//1137 1104//1104 -f 1136//1136 1137//1137 401//401 -f 1136//1136 401//401 1135//1135 -f 1135//1135 401//401 397//397 -f 1135//1135 397//397 1134//1134 -f 1134//1134 397//397 400//400 -f 1134//1134 400//400 1133//1133 -f 849//849 394//394 848//848 -f 1137//1137 389//389 401//401 -f 393//393 847//847 394//394 -f 394//394 847//847 848//848 -f 391//391 402//402 389//389 -f 389//389 402//402 401//401 -f 402//402 1084//1084 1085//1085 -f 402//402 1085//1085 392//392 -f 392//392 1085//1085 1086//1086 -f 392//392 1086//1086 393//393 -f 393//393 1086//1086 1087//1087 -f 393//393 1087//1087 1088//1088 -f 393//393 1088//1088 847//847 -f 402//402 391//391 1084//1084 -f 151//151 847//847 152//152 -f 152//152 847//847 1088//1088 -f 152//152 1088//1088 1053//1053 -f 391//391 203//203 1084//1084 -f 1084//1084 203//203 205//205 -f 1084//1084 205//205 1082//1082 -f 1082//1082 205//205 1083//1083 -f 1083//1083 205//205 204//204 -f 153//153 152//152 1053//1053 -f 1053//1053 1055//1055 153//153 -f 153//153 1055//1055 1057//1057 -f 153//153 1057//1057 236//236 -f 1057//1057 1061//1061 236//236 -f 236//236 1061//1061 1060//1060 -f 236//236 1060//1060 242//242 -f 1060//1060 1064//1064 242//242 -f 242//242 1064//1064 1063//1063 -f 242//242 1063//1063 241//241 -f 1063//1063 1067//1067 241//241 -f 241//241 1067//1067 1066//1066 -f 241//241 1066//1066 219//219 -f 219//219 1066//1066 221//221 -f 1066//1066 1074//1074 221//221 -f 221//221 1074//1074 1073//1073 -f 221//221 1073//1073 222//222 -f 222//222 1073//1073 1071//1071 -f 222//222 1071//1071 224//224 -f 224//224 1071//1071 1069//1069 -f 224//224 1069//1069 310//310 -f 310//310 1069//1069 308//308 -f 308//308 1069//1069 1077//1077 -f 308//308 1077//1077 306//306 -f 1077//1077 1076//1076 306//306 -f 306//306 1076//1076 1080//1080 -f 306//306 1080//1080 204//204 -f 204//204 1080//1080 1079//1079 -f 204//204 1079//1079 1083//1083 -f 1281//1281 1282//1282 1283//1283 -f 1284//1284 1285//1285 1286//1286 -f 1287//1287 1288//1288 1289//1289 -f 1290//1290 1291//1291 1292//1292 -f 1293//1293 1294//1294 1295//1295 -f 1296//1296 1297//1297 1298//1298 -f 1298//1298 1297//1297 1299//1299 -f 1298//1298 1299//1299 1300//1300 -f 1301//1301 1302//1302 1303//1303 -f 1303//1303 1304//1304 1301//1301 -f 1301//1301 1304//1304 1305//1305 -f 1301//1301 1305//1305 1306//1306 -f 1306//1306 1305//1305 1307//1307 -f 1306//1306 1307//1307 1308//1308 -f 1309//1309 1310//1310 1311//1311 -f 1311//1311 1310//1310 1312//1312 -f 1311//1311 1312//1312 1313//1313 -f 1313//1313 1312//1312 1314//1314 -f 1313//1313 1314//1314 1308//1308 -f 1308//1308 1314//1314 1315//1315 -f 1308//1308 1315//1315 1306//1306 -f 1316//1316 1317//1317 1318//1318 -f 1318//1318 1317//1317 1319//1319 -f 1318//1318 1319//1319 1320//1320 -f 1320//1320 1319//1319 1321//1321 -f 1320//1320 1321//1321 1322//1322 -f 1321//1321 1323//1323 1322//1322 -f 1322//1322 1323//1323 1324//1324 -f 1322//1322 1324//1324 1292//1292 -f 1292//1292 1324//1324 1325//1325 -f 1292//1292 1325//1325 1326//1326 -f 1327//1327 1328//1328 1329//1329 -f 1329//1329 1328//1328 1330//1330 -f 1329//1329 1330//1330 1331//1331 -f 1331//1331 1330//1330 1332//1332 -f 1333//1333 1334//1334 1335//1335 -f 1335//1335 1334//1334 1336//1336 -f 1335//1335 1336//1336 1337//1337 -f 1333//1333 1338//1338 1334//1334 -f 1334//1334 1338//1338 1339//1339 -f 1334//1334 1339//1339 1340//1340 -f 1340//1340 1339//1339 1341//1341 -f 1340//1340 1341//1341 1342//1342 -f 1343//1343 1344//1344 1345//1345 -f 1346//1346 1347//1347 1348//1348 -f 1348//1348 1347//1347 1349//1349 -f 1348//1348 1349//1349 1335//1335 -f 1335//1335 1349//1349 1350//1350 -f 1335//1335 1350//1350 1333//1333 -f 1341//1341 1351//1351 1342//1342 -f 1342//1342 1351//1351 1352//1352 -f 1342//1342 1352//1352 1344//1344 -f 1344//1344 1352//1352 1353//1353 -f 1344//1344 1353//1353 1345//1345 -f 1354//1354 1355//1355 1356//1356 -f 1355//1355 1357//1357 1356//1356 -f 1356//1356 1357//1357 1358//1358 -f 1356//1356 1358//1358 1359//1359 -f 1359//1359 1358//1358 1360//1360 -f 1360//1360 1361//1361 1359//1359 -f 1359//1359 1361//1361 1362//1362 -f 1359//1359 1362//1362 1363//1363 -f 1362//1362 1364//1364 1363//1363 -f 1363//1363 1364//1364 1365//1365 -f 1363//1363 1365//1365 1366//1366 -f 1366//1366 1365//1365 1367//1367 -f 1366//1366 1367//1367 1368//1368 -f 1368//1368 1367//1367 1369//1369 -f 1368//1368 1369//1369 1370//1370 -f 1370//1370 1369//1369 1371//1371 -f 1370//1370 1371//1371 1354//1354 -f 1372//1372 1373//1373 1374//1374 -f 1374//1374 1373//1373 1375//1375 -f 1374//1374 1375//1375 1376//1376 -f 1376//1376 1375//1375 1377//1377 -f 1376//1376 1377//1377 1378//1378 -f 1378//1378 1379//1379 1376//1376 -f 1376//1376 1379//1379 1380//1380 -f 1376//1376 1380//1380 1381//1381 -f 1382//1382 1383//1383 1384//1384 -f 1380//1380 1385//1385 1381//1381 -f 1381//1381 1385//1385 1386//1386 -f 1381//1381 1386//1386 1383//1383 -f 1384//1384 1387//1387 1382//1382 -f 1382//1382 1387//1387 1388//1388 -f 1382//1382 1388//1388 1389//1389 -f 1389//1389 1388//1388 1390//1390 -f 1389//1389 1390//1390 1391//1391 -f 1391//1391 1390//1390 1392//1392 -f 1391//1391 1392//1392 1377//1377 -f 1377//1377 1392//1392 1393//1393 -f 1377//1377 1393//1393 1378//1378 -f 1394//1394 1395//1395 1396//1396 -f 1396//1396 1395//1395 1397//1397 -f 1396//1396 1397//1397 1398//1398 -f 1399//1399 1400//1400 1401//1401 -f 1401//1401 1400//1400 1402//1402 -f 1401//1401 1402//1402 1403//1403 -f 1399//1399 1404//1404 1400//1400 -f 1400//1400 1404//1404 1405//1405 -f 1400//1400 1405//1405 1406//1406 -f 1406//1406 1405//1405 1407//1407 -f 1406//1406 1407//1407 1408//1408 -f 1408//1408 1407//1407 1409//1409 -f 1408//1408 1409//1409 1397//1397 -f 1397//1397 1409//1409 1410//1410 -f 1397//1397 1410//1410 1398//1398 -f 1411//1411 1412//1412 1413//1413 -f 1413//1413 1412//1412 1396//1396 -f 1413//1413 1396//1396 1414//1414 -f 1414//1414 1396//1396 1398//1398 -f 1415//1415 1416//1416 1417//1417 -f 1415//1415 1417//1417 1418//1418 -f 1419//1419 1420//1420 1396//1396 -f 1396//1396 1420//1420 1421//1421 -f 1396//1396 1421//1421 1394//1394 -f 1394//1394 1421//1421 1422//1422 -f 1394//1394 1422//1422 1423//1423 -f 1424//1424 1425//1425 1426//1426 -f 1427//1427 1428//1428 1429//1429 -f 1428//1428 1430//1430 1429//1429 -f 1429//1429 1430//1430 1431//1431 -f 1429//1429 1431//1431 1432//1432 -f 1432//1432 1431//1431 1433//1433 -f 1417//1417 1434//1434 1418//1418 -f 1418//1418 1434//1434 1435//1435 -f 1418//1418 1435//1435 1436//1436 -f 1436//1436 1435//1435 1437//1437 -f 1438//1438 1283//1283 1439//1439 -f 1439//1439 1283//1283 1440//1440 -f 1439//1439 1440//1440 1402//1402 -f 1402//1402 1440//1440 1412//1412 -f 1402//1402 1412//1412 1403//1403 -f 1403//1403 1412//1412 1411//1411 -f 1441//1441 1442//1442 1443//1443 -f 1444//1444 1443//1443 1445//1445 -f 1446//1446 1447//1447 1448//1448 -f 1448//1448 1447//1447 1418//1418 -f 1448//1448 1418//1418 1449//1449 -f 1449//1449 1418//1418 1436//1436 -f 1449//1449 1436//1436 1450//1450 -f 1450//1450 1436//1436 1437//1437 -f 1450//1450 1437//1437 1451//1451 -f 1359//1359 1452//1452 1356//1356 -f 1356//1356 1452//1452 1453//1453 -f 1356//1356 1453//1453 1450//1450 -f 1450//1450 1453//1453 1454//1454 -f 1450//1450 1454//1454 1449//1449 -f 1455//1455 1456//1456 1457//1457 -f 1458//1458 1366//1366 1459//1459 -f 1459//1459 1366//1366 1368//1368 -f 1459//1459 1368//1368 1460//1460 -f 1460//1460 1368//1368 1457//1457 -f 1461//1461 1462//1462 1463//1463 -f 1464//1464 1462//1462 1465//1465 -f 1465//1465 1462//1462 1461//1461 -f 1465//1465 1461//1461 1466//1466 -f 1327//1327 1316//1316 1328//1328 -f 1328//1328 1316//1316 1318//1318 -f 1328//1328 1318//1318 1467//1467 -f 1467//1467 1318//1318 1468//1468 -f 1467//1467 1468//1468 1469//1469 -f 1469//1469 1468//1468 1470//1470 -f 1469//1469 1470//1470 1471//1471 -f 1289//1289 1288//1288 1330//1330 -f 1326//1326 1332//1332 1292//1292 -f 1292//1292 1332//1332 1330//1330 -f 1292//1292 1330//1330 1290//1290 -f 1290//1290 1330//1330 1288//1288 -f 1290//1290 1288//1288 1472//1472 -f 1289//1289 1473//1473 1287//1287 -f 1287//1287 1473//1473 1474//1474 -f 1287//1287 1474//1474 1475//1475 -f 1475//1475 1474//1474 1476//1476 -f 1477//1477 1478//1478 1474//1474 -f 1474//1474 1478//1478 1479//1479 -f 1474//1474 1479//1479 1476//1476 -f 1480//1480 1481//1481 1482//1482 -f 1482//1482 1481//1481 1483//1483 -f 1482//1482 1483//1483 1484//1484 -f 1484//1484 1483//1483 1485//1485 -f 1486//1486 1487//1487 1483//1483 -f 1488//1488 1485//1485 1489//1489 -f 1489//1489 1485//1485 1483//1483 -f 1489//1489 1483//1483 1490//1490 -f 1490//1490 1483//1483 1487//1487 -f 1491//1491 1492//1492 1493//1493 -f 1383//1383 1382//1382 1381//1381 -f 1381//1381 1382//1382 1494//1494 -f 1381//1381 1494//1494 1495//1495 -f 1495//1495 1496//1496 1381//1381 -f 1381//1381 1496//1496 1497//1497 -f 1381//1381 1497//1497 1498//1498 -f 1498//1498 1497//1497 1491//1491 -f 1499//1499 1500//1500 1501//1501 -f 1501//1501 1502//1502 1499//1499 -f 1499//1499 1502//1502 1503//1503 -f 1499//1499 1503//1503 1334//1334 -f 1334//1334 1503//1503 1504//1504 -f 1334//1334 1504//1504 1336//1336 -f 1502//1502 1505//1505 1503//1503 -f 1503//1503 1505//1505 1506//1506 -f 1503//1503 1506//1506 1507//1507 -f 1507//1507 1506//1506 1508//1508 -f 1507//1507 1508//1508 1509//1509 -f 1508//1508 1510//1510 1509//1509 -f 1509//1509 1510//1510 1511//1511 -f 1509//1509 1511//1511 1512//1512 -f 1513//1513 1514//1514 1515//1515 -f 1515//1515 1514//1514 1516//1516 -f 1515//1515 1516//1516 1500//1500 -f 1500//1500 1516//1516 1517//1517 -f 1500//1500 1517//1517 1501//1501 -f 1368//1368 1518//1518 1509//1509 -f 1457//1457 1368//1368 1455//1455 -f 1455//1455 1368//1368 1509//1509 -f 1455//1455 1509//1509 1515//1515 -f 1515//1515 1509//1509 1512//1512 -f 1515//1515 1512//1512 1513//1513 -f 1354//1354 1356//1356 1370//1370 -f 1370//1370 1356//1356 1519//1519 -f 1370//1370 1519//1519 1368//1368 -f 1368//1368 1519//1519 1520//1520 -f 1368//1368 1520//1520 1518//1518 -f 1521//1521 1522//1522 1450//1450 -f 1522//1522 1523//1523 1450//1450 -f 1450//1450 1523//1523 1524//1524 -f 1450//1450 1524//1524 1356//1356 -f 1356//1356 1524//1524 1525//1525 -f 1356//1356 1525//1525 1519//1519 -f 1526//1526 1527//1527 1528//1528 -f 1528//1528 1527//1527 1521//1521 -f 1528//1528 1521//1521 1529//1529 -f 1529//1529 1521//1521 1450//1450 -f 1529//1529 1450//1450 1530//1530 -f 1530//1530 1450//1450 1451//1451 -f 1531//1531 1526//1526 1429//1429 -f 1429//1429 1526//1526 1528//1528 -f 1429//1429 1528//1528 1427//1427 -f 1427//1427 1528//1528 1529//1529 -f 1427//1427 1529//1529 1532//1532 -f 1532//1532 1529//1529 1530//1530 -f 1533//1533 1534//1534 1535//1535 -f 1535//1535 1534//1534 1536//1536 -f 1535//1535 1536//1536 1537//1537 -f 1537//1537 1536//1536 1538//1538 -f 1537//1537 1538//1538 1429//1429 -f 1429//1429 1538//1538 1539//1539 -f 1429//1429 1539//1539 1531//1531 -f 1540//1540 1541//1541 1542//1542 -f 1541//1541 1540//1540 1543//1543 -f 1544//1544 1545//1545 1546//1546 -f 1547//1547 1548//1548 1549//1549 -f 1545//1545 1544//1544 1549//1549 -f 1549//1549 1544//1544 1550//1550 -f 1549//1549 1550//1550 1547//1547 -f 1548//1548 1547//1547 1551//1551 -f 1551//1551 1547//1547 1552//1552 -f 1551//1551 1552//1552 1553//1553 -f 1554//1554 1555//1555 1541//1541 -f 1541//1541 1555//1555 1556//1556 -f 1541//1541 1556//1556 1542//1542 -f 1542//1542 1556//1556 1557//1557 -f 1542//1542 1557//1557 1558//1558 -f 1558//1558 1557//1557 1559//1559 -f 1558//1558 1559//1559 1560//1560 -f 1560//1560 1559//1559 1561//1561 -f 1560//1560 1561//1561 1562//1562 -f 1562//1562 1561//1561 1563//1563 -f 1562//1562 1563//1563 1564//1564 -f 1565//1565 1566//1566 1567//1567 -f 1567//1567 1566//1566 1568//1568 -f 1565//1565 1569//1569 1566//1566 -f 1566//1566 1569//1569 1570//1570 -f 1566//1566 1570//1570 1302//1302 -f 1302//1302 1570//1570 1571//1571 -f 1302//1302 1571//1571 1303//1303 -f 1303//1303 1571//1571 1572//1572 -f 1303//1303 1572//1572 1573//1573 -f 1573//1573 1572//1572 1574//1574 -f 1573//1573 1574//1574 1296//1296 -f 1296//1296 1574//1574 1575//1575 -f 1296//1296 1575//1575 1297//1297 -f 1576//1576 1577//1577 1578//1578 -f 1578//1578 1577//1577 1579//1579 -f 1578//1578 1579//1579 1568//1568 -f 1568//1568 1579//1579 1580//1580 -f 1568//1568 1580//1580 1567//1567 -f 1581//1581 1582//1582 1583//1583 -f 1583//1583 1582//1582 1584//1584 -f 1583//1583 1584//1584 1585//1585 -f 1576//1576 1578//1578 1586//1586 -f 1586//1586 1578//1578 1587//1587 -f 1586//1586 1587//1587 1588//1588 -f 1588//1588 1587//1587 1481//1481 -f 1588//1588 1481//1481 1589//1589 -f 1589//1589 1481//1481 1480//1480 -f 1589//1589 1480//1480 1583//1583 -f 1583//1583 1480//1480 1590//1590 -f 1583//1583 1590//1590 1581//1581 -f 1489//1489 1591//1591 1488//1488 -f 1488//1488 1591//1591 1592//1592 -f 1488//1488 1592//1592 1593//1593 -f 1593//1593 1592//1592 1594//1594 -f 1593//1593 1594//1594 1595//1595 -f 1595//1595 1594//1594 1596//1596 -f 1595//1595 1596//1596 1597//1597 -f 1597//1597 1596//1596 1584//1584 -f 1597//1597 1584//1584 1598//1598 -f 1598//1598 1584//1584 1582//1582 -f 1309//1309 1300//1300 1310//1310 -f 1310//1310 1300//1300 1299//1299 -f 1310//1310 1299//1299 1584//1584 -f 1584//1584 1299//1299 1599//1599 -f 1584//1584 1599//1599 1585//1585 -f 1286//1286 1600//1600 1601//1601 -f 1554//1554 1602//1602 1603//1603 -f 1285//1285 1555//1555 1286//1286 -f 1286//1286 1555//1555 1554//1554 -f 1286//1286 1554//1554 1600//1600 -f 1600//1600 1554//1554 1603//1603 -f 1301//1301 1604//1604 1302//1302 -f 1302//1302 1604//1604 1605//1605 -f 1302//1302 1605//1605 1566//1566 -f 1566//1566 1605//1605 1606//1606 -f 1566//1566 1606//1606 1607//1607 -f 1601//1601 1608//1608 1286//1286 -f 1286//1286 1608//1608 1609//1609 -f 1286//1286 1609//1609 1610//1610 -f 1610//1610 1609//1609 1611//1611 -f 1610//1610 1611//1611 1301//1301 -f 1301//1301 1611//1611 1612//1612 -f 1301//1301 1612//1612 1604//1604 -f 1613//1613 1614//1614 1615//1615 -f 1613//1613 1615//1615 1616//1616 -f 1617//1617 1618//1618 1619//1619 -f 1619//1619 1618//1618 1620//1620 -f 1619//1619 1620//1620 1621//1621 -f 1621//1621 1616//1616 1619//1619 -f 1619//1619 1616//1616 1615//1615 -f 1619//1619 1615//1615 1622//1622 -f 1622//1622 1615//1615 1543//1543 -f 1622//1622 1543//1543 1623//1623 -f 1623//1623 1543//1543 1540//1540 -f 1483//1483 1624//1624 1617//1617 -f 1617//1617 1624//1624 1625//1625 -f 1617//1617 1625//1625 1618//1618 -f 1614//1614 1626//1626 1587//1587 -f 1587//1587 1626//1626 1627//1627 -f 1587//1587 1627//1627 1481//1481 -f 1481//1481 1627//1627 1628//1628 -f 1481//1481 1628//1628 1483//1483 -f 1483//1483 1628//1628 1629//1629 -f 1483//1483 1629//1629 1624//1624 -f 1630//1630 1320//1320 1631//1631 -f 1631//1631 1320//1320 1322//1322 -f 1631//1631 1322//1322 1632//1632 -f 1632//1632 1322//1322 1292//1292 -f 1632//1632 1292//1292 1633//1633 -f 1633//1633 1292//1292 1291//1291 -f 1634//1634 1340//1340 1635//1635 -f 1635//1635 1340//1340 1342//1342 -f 1635//1635 1342//1342 1636//1636 -f 1636//1636 1342//1342 1344//1344 -f 1637//1637 1456//1456 1638//1638 -f 1638//1638 1456//1456 1455//1455 -f 1638//1638 1455//1455 1639//1639 -f 1639//1639 1455//1455 1515//1515 -f 1639//1639 1515//1515 1640//1640 -f 1640//1640 1515//1515 1500//1500 -f 1345//1345 1346//1346 1343//1343 -f 1343//1343 1346//1346 1348//1348 -f 1343//1343 1348//1348 1463//1463 -f 1463//1463 1348//1348 1641//1641 -f 1463//1463 1641//1641 1461//1461 -f 1461//1461 1641//1641 1642//1642 -f 1642//1642 1643//1643 1461//1461 -f 1461//1461 1643//1643 1644//1644 -f 1461//1461 1644//1644 1645//1645 -f 1646//1646 1647//1647 1469//1469 -f 1471//1471 1466//1466 1469//1469 -f 1469//1469 1466//1466 1461//1461 -f 1469//1469 1461//1461 1646//1646 -f 1646//1646 1461//1461 1645//1645 -f 1648//1648 1467//1467 1649//1649 -f 1649//1649 1467//1467 1469//1469 -f 1649//1649 1469//1469 1650//1650 -f 1650//1650 1469//1469 1647//1647 -f 1648//1648 1651//1651 1467//1467 -f 1467//1467 1651//1651 1652//1652 -f 1467//1467 1652//1652 1641//1641 -f 1641//1641 1652//1652 1653//1653 -f 1641//1641 1653//1653 1642//1642 -f 1467//1467 1284//1284 1328//1328 -f 1328//1328 1284//1284 1286//1286 -f 1328//1328 1286//1286 1330//1330 -f 1330//1330 1286//1286 1610//1610 -f 1330//1330 1610//1610 1289//1289 -f 1289//1289 1610//1610 1301//1301 -f 1289//1289 1301//1301 1473//1473 -f 1473//1473 1301//1301 1306//1306 -f 1337//1337 1533//1533 1335//1335 -f 1335//1335 1533//1533 1535//1535 -f 1335//1335 1535//1535 1348//1348 -f 1348//1348 1535//1535 1654//1654 -f 1535//1535 1655//1655 1656//1656 -f 1657//1657 1658//1658 1654//1654 -f 1656//1656 1659//1659 1535//1535 -f 1535//1535 1659//1659 1660//1660 -f 1535//1535 1660//1660 1654//1654 -f 1654//1654 1660//1660 1661//1661 -f 1654//1654 1661//1661 1657//1657 -f 1658//1658 1562//1562 1654//1654 -f 1654//1654 1562//1562 1564//1564 -f 1654//1654 1564//1564 1348//1348 -f 1348//1348 1564//1564 1662//1662 -f 1348//1348 1662//1662 1641//1641 -f 1641//1641 1662//1662 1663//1663 -f 1641//1641 1663//1663 1467//1467 -f 1467//1467 1663//1663 1664//1664 -f 1467//1467 1664//1664 1284//1284 -f 1658//1658 1665//1665 1562//1562 -f 1562//1562 1665//1665 1666//1666 -f 1562//1562 1666//1666 1667//1667 -f 1655//1655 1535//1535 1668//1668 -f 1668//1668 1535//1535 1537//1537 -f 1668//1668 1537//1537 1669//1669 -f 1670//1670 1671//1671 1432//1432 -f 1432//1432 1671//1671 1560//1560 -f 1432//1432 1560//1560 1429//1429 -f 1429//1429 1560//1560 1562//1562 -f 1429//1429 1562//1562 1537//1537 -f 1537//1537 1562//1562 1667//1667 -f 1537//1537 1667//1667 1669//1669 -f 1614//1614 1587//1587 1615//1615 -f 1615//1615 1587//1587 1578//1578 -f 1615//1615 1578//1578 1543//1543 -f 1543//1543 1578//1578 1568//1568 -f 1543//1543 1568//1568 1541//1541 -f 1541//1541 1568//1568 1566//1566 -f 1541//1541 1566//1566 1554//1554 -f 1554//1554 1566//1566 1607//1607 -f 1554//1554 1607//1607 1602//1602 -f 1670//1670 1544//1544 1671//1671 -f 1671//1671 1544//1544 1546//1546 -f 1671//1671 1546//1546 1560//1560 -f 1560//1560 1546//1546 1672//1672 -f 1560//1560 1672//1672 1558//1558 -f 1558//1558 1672//1672 1673//1673 -f 1558//1558 1673//1673 1542//1542 -f 1542//1542 1673//1673 1674//1674 -f 1542//1542 1674//1674 1540//1540 -f 1675//1675 1676//1676 1670//1670 -f 1677//1677 1675//1675 1426//1426 -f 1426//1426 1675//1675 1670//1670 -f 1426//1426 1670//1670 1424//1424 -f 1424//1424 1670//1670 1432//1432 -f 1424//1424 1432//1432 1678//1678 -f 1678//1678 1432//1432 1433//1433 -f 1679//1679 1544//1544 1680//1680 -f 1680//1680 1544//1544 1670//1670 -f 1680//1680 1670//1670 1681//1681 -f 1681//1681 1670//1670 1676//1676 -f 1679//1679 1682//1682 1544//1544 -f 1544//1544 1682//1682 1683//1683 -f 1544//1544 1683//1683 1550//1550 -f 1550//1550 1683//1683 1684//1684 -f 1684//1684 1685//1685 1550//1550 -f 1550//1550 1685//1685 1686//1686 -f 1550//1550 1686//1686 1426//1426 -f 1426//1426 1686//1686 1687//1687 -f 1426//1426 1687//1687 1677//1677 -f 1688//1688 1447//1447 1689//1689 -f 1689//1689 1447//1447 1690//1690 -f 1689//1689 1690//1690 1691//1691 -f 1691//1691 1690//1690 1692//1692 -f 1693//1693 1418//1418 1694//1694 -f 1694//1694 1418//1418 1447//1447 -f 1694//1694 1447//1447 1695//1695 -f 1695//1695 1447//1447 1688//1688 -f 1415//1415 1696//1696 1697//1697 -f 1693//1693 1698//1698 1418//1418 -f 1418//1418 1698//1698 1699//1699 -f 1418//1418 1699//1699 1415//1415 -f 1415//1415 1699//1699 1700//1700 -f 1415//1415 1700//1700 1696//1696 -f 1493//1493 1701//1701 1491//1491 -f 1491//1491 1701//1701 1486//1486 -f 1491//1491 1486//1486 1498//1498 -f 1498//1498 1486//1486 1483//1483 -f 1498//1498 1483//1483 1381//1381 -f 1381//1381 1483//1483 1617//1617 -f 1381//1381 1617//1617 1376//1376 -f 1376//1376 1617//1617 1619//1619 -f 1376//1376 1619//1619 1374//1374 -f 1425//1425 1419//1419 1426//1426 -f 1426//1426 1419//1419 1396//1396 -f 1426//1426 1396//1396 1550//1550 -f 1550//1550 1396//1396 1412//1412 -f 1550//1550 1412//1412 1547//1547 -f 1547//1547 1412//1412 1440//1440 -f 1547//1547 1440//1440 1552//1552 -f 1443//1443 1444//1444 1441//1441 -f 1441//1441 1444//1444 1415//1415 -f 1441//1441 1415//1415 1690//1690 -f 1690//1690 1415//1415 1697//1697 -f 1690//1690 1697//1697 1692//1692 -f 1702//1702 1703//1703 1374//1374 -f 1283//1283 1282//1282 1440//1440 -f 1440//1440 1282//1282 1704//1704 -f 1440//1440 1704//1704 1705//1705 -f 1622//1622 1553//1553 1619//1619 -f 1619//1619 1553//1553 1552//1552 -f 1619//1619 1552//1552 1374//1374 -f 1374//1374 1552//1552 1440//1440 -f 1374//1374 1440//1440 1702//1702 -f 1702//1702 1440//1440 1705//1705 -f 1703//1703 1706//1706 1374//1374 -f 1374//1374 1706//1706 1707//1707 -f 1374//1374 1707//1707 1372//1372 -f 1372//1372 1707//1707 1708//1708 -f 1708//1708 1709//1709 1372//1372 -f 1372//1372 1709//1709 1710//1710 -f 1372//1372 1710//1710 1283//1283 -f 1283//1283 1710//1710 1711//1711 -f 1283//1283 1711//1711 1281//1281 -f 1712//1712 1713//1713 1714//1714 -f 1714//1714 1713//1713 1395//1395 -f 1714//1714 1395//1395 1715//1715 -f 1715//1715 1395//1395 1394//1394 -f 1715//1715 1394//1394 1716//1716 -f 1712//1712 1717//1717 1713//1713 -f 1713//1713 1717//1717 1718//1718 -f 1713//1713 1718//1718 1719//1719 -f 1719//1719 1718//1718 1720//1720 -f 1719//1719 1720//1720 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1724//1724 1723//1723 1725//1725 -f 1724//1724 1725//1725 1726//1726 -f 1416//1416 1415//1415 1727//1727 -f 1727//1727 1415//1415 1444//1444 -f 1727//1727 1444//1444 1423//1423 -f 1423//1423 1444//1444 1724//1724 -f 1423//1423 1724//1724 1394//1394 -f 1394//1394 1724//1724 1726//1726 -f 1394//1394 1726//1726 1716//1716 -f 1445//1445 1293//1293 1444//1444 -f 1444//1444 1293//1293 1295//1295 -f 1444//1444 1295//1295 1724//1724 -f 1724//1724 1295//1295 1719//1719 -f 1724//1724 1719//1719 1722//1722 -f 1722//1722 1719//1719 1721//1721 -f 1728//1728 1729//1729 1730//1730 -f 1731//1731 1732//1732 1733//1733 -f 1728//1728 1730//1730 1734//1734 -f 1730//1730 1735//1735 1734//1734 -f 1734//1734 1735//1735 1736//1736 -f 1734//1734 1736//1736 1737//1737 -f 1731//1731 1733//1733 1738//1738 -f 1733//1733 1739//1739 1738//1738 -f 1738//1738 1739//1739 1740//1740 -f 1738//1738 1740//1740 1728//1728 -f 1728//1728 1740//1740 1741//1741 -f 1728//1728 1741//1741 1729//1729 -f 1736//1736 1742//1742 1737//1737 -f 1737//1737 1742//1742 1743//1743 -f 1737//1737 1743//1743 1731//1731 -f 1731//1731 1743//1743 1744//1744 -f 1731//1731 1744//1744 1732//1732 -f 1745//1745 1746//1746 1747//1747 -f 1747//1747 1746//1746 1748//1748 -f 1749//1749 1750//1750 1751//1751 -f 1751//1751 1750//1750 1752//1752 -f 1752//1752 1753//1753 1751//1751 -f 1751//1751 1753//1753 1754//1754 -f 1751//1751 1754//1754 1755//1755 -f 1754//1754 1756//1756 1755//1755 -f 1755//1755 1756//1756 1757//1757 -f 1755//1755 1757//1757 1745//1745 -f 1745//1745 1757//1757 1758//1758 -f 1745//1745 1758//1758 1746//1746 -f 1748//1748 1759//1759 1747//1747 -f 1747//1747 1759//1759 1760//1760 -f 1747//1747 1760//1760 1749//1749 -f 1749//1749 1760//1760 1761//1761 -f 1749//1749 1761//1761 1750//1750 -f 1762//1762 1763//1763 1764//1764 -f 1764//1764 1763//1763 1765//1765 -f 1766//1766 1767//1767 1762//1762 -f 1762//1762 1767//1767 1768//1768 -f 1762//1762 1768//1768 1763//1763 -f 1765//1765 1769//1769 1764//1764 -f 1764//1764 1769//1769 1770//1770 -f 1764//1764 1770//1770 1771//1771 -f 1772//1772 1773//1773 1774//1774 -f 1774//1774 1773//1773 1771//1771 -f 1774//1774 1771//1771 1775//1775 -f 1775//1775 1771//1771 1770//1770 -f 1772//1772 1776//1776 1773//1773 -f 1773//1773 1776//1776 1777//1777 -f 1773//1773 1777//1777 1766//1766 -f 1766//1766 1777//1777 1778//1778 -f 1766//1766 1778//1778 1767//1767 -f 110//110 109//109 1779//1779 -f 1780//1780 1781//1781 1782//1782 -f 1783//1783 1784//1784 1785//1785 -f 1786//1786 1787//1787 1788//1788 -f 1788//1788 1787//1787 1789//1789 -f 1789//1789 1790//1790 1788//1788 -f 1788//1788 1790//1790 1791//1791 -f 1788//1788 1791//1791 1792//1792 -f 1792//1792 1791//1791 1793//1793 -f 1792//1792 1793//1793 1794//1794 -f 1795//1795 1796//1796 1797//1797 -f 1798//1798 1799//1799 1800//1800 -f 1801//1801 1802//1802 1793//1793 -f 1793//1793 1802//1802 1798//1798 -f 1800//1800 1803//1803 1798//1798 -f 1798//1798 1803//1803 1795//1795 -f 1798//1798 1795//1795 1793//1793 -f 1793//1793 1795//1795 1797//1797 -f 1793//1793 1797//1797 1794//1794 -f 1804//1804 1805//1805 1806//1806 -f 1807//1807 1808//1808 1809//1809 -f 1810//1810 1804//1804 1801//1801 -f 1785//1785 1802//1802 1783//1783 -f 1783//1783 1802//1802 1801//1801 -f 1783//1783 1801//1801 1811//1811 -f 1811//1811 1801//1801 1804//1804 -f 1811//1811 1804//1804 1812//1812 -f 1812//1812 1804//1804 1806//1806 -f 1808//1808 1807//1807 1813//1813 -f 1814//1814 1815//1815 1816//1816 -f 1817//1817 1818//1818 1819//1819 -f 1816//1816 1820//1820 1814//1814 -f 1814//1814 1820//1820 1819//1819 -f 1814//1814 1819//1819 1821//1821 -f 1821//1821 1819//1819 1822//1822 -f 1823//1823 1817//1817 1824//1824 -f 1824//1824 1817//1817 1819//1819 -f 1824//1824 1819//1819 1825//1825 -f 1825//1825 1819//1819 1820//1820 -f 1826//1826 1827//1827 1828//1828 -f 1828//1828 1827//1827 1829//1829 -f 1828//1828 1829//1829 1830//1830 -f 1830//1830 1829//1829 1831//1831 -f 1832//1832 1833//1833 1834//1834 -f 1834//1834 1833//1833 1835//1835 -f 1836//1836 1837//1837 1838//1838 -f 1838//1838 1837//1837 1839//1839 -f 1838//1838 1839//1839 1840//1840 -f 1840//1840 1839//1839 1841//1841 -f 1840//1840 1841//1841 1842//1842 -f 1842//1842 1841//1841 1843//1843 -f 1842//1842 1843//1843 1844//1844 -f 1844//1844 1843//1843 1845//1845 -f 1846//1846 1847//1847 1848//1848 -f 1848//1848 1847//1847 1849//1849 -f 1848//1848 1849//1849 1850//1850 -f 1782//1782 1851//1851 1780//1780 -f 1780//1780 1851//1851 1852//1852 -f 1780//1780 1852//1852 1853//1853 -f 1854//1854 1855//1855 1856//1856 -f 1856//1856 1855//1855 1857//1857 -f 1856//1856 1857//1857 1858//1858 -f 1859//1859 1860//1860 1852//1852 -f 1852//1852 1860//1860 1861//1861 -f 1861//1861 1862//1862 1847//1847 -f 1847//1847 1862//1862 1863//1863 -f 1864//1864 1856//1856 1865//1865 -f 1865//1865 1856//1856 1858//1858 -f 1865//1865 1858//1858 1866//1866 -f 1866//1866 1858//1858 1867//1867 -f 1866//1866 1867//1867 1851//1851 -f 1851//1851 1867//1867 1868//1868 -f 1851//1851 1868//1868 1852//1852 -f 1852//1852 1868//1868 1869//1869 -f 1852//1852 1869//1869 1859//1859 -f 1856//1856 1870//1870 1854//1854 -f 1854//1854 1870//1870 1871//1871 -f 1854//1854 1871//1871 1863//1863 -f 1863//1863 1871//1871 1872//1872 -f 1863//1863 1872//1872 1847//1847 -f 1847//1847 1872//1872 1873//1873 -f 1847//1847 1873//1873 1849//1849 -f 1874//1874 1875//1875 1852//1852 -f 1876//1876 1877//1877 1878//1878 -f 1878//1878 1877//1877 1879//1879 -f 1879//1879 1853//1853 1878//1878 -f 1878//1878 1853//1853 1852//1852 -f 1878//1878 1852//1852 1880//1880 -f 1880//1880 1852//1852 1875//1875 -f 1880//1880 1875//1875 1881//1881 -f 1881//1881 1875//1875 1882//1882 -f 1883//1883 1884//1884 1885//1885 -f 1885//1885 1884//1884 1886//1886 -f 1887//1887 1888//1888 1886//1886 -f 1889//1889 1890//1890 1887//1887 -f 1887//1887 1890//1890 1891//1891 -f 1892//1892 1893//1893 1894//1894 -f 1894//1894 1893//1893 1895//1895 -f 1894//1894 1895//1895 1874//1874 -f 1896//1896 1897//1897 1888//1888 -f 1888//1888 1897//1897 1898//1898 -f 1888//1888 1898//1898 1886//1886 -f 1899//1899 1900//1900 1889//1889 -f 1901//1901 1890//1890 1902//1902 -f 1902//1902 1890//1890 1889//1889 -f 1902//1902 1889//1889 1903//1903 -f 1903//1903 1889//1889 1900//1900 -f 1903//1903 1900//1900 1904//1904 -f 1904//1904 1900//1900 1905//1905 -f 1906//1906 1907//1907 1908//1908 -f 135//135 1909//1909 134//134 -f 134//134 1909//1909 1910//1910 -f 134//134 1910//1910 120//120 -f 1910//1910 1911//1911 120//120 -f 120//120 1911//1911 1912//1912 -f 120//120 1912//1912 118//118 -f 118//118 1912//1912 1913//1913 -f 118//118 1913//1913 116//116 -f 116//116 1913//1913 1914//1914 -f 116//116 1914//1914 1915//1915 -f 1915//1915 1914//1914 1916//1916 -f 1917//1917 1918//1918 1919//1919 -f 1919//1919 1918//1918 1920//1920 -f 1919//1919 1920//1920 1921//1921 -f 1921//1921 1920//1920 1922//1922 -f 1921//1921 1922//1922 135//135 -f 135//135 1922//1922 1923//1923 -f 135//135 1923//1923 1909//1909 -f 1924//1924 1925//1925 1926//1926 -f 1926//1926 1925//1925 1927//1927 -f 1926//1926 1927//1927 1928//1928 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 114//114 -f 114//114 1932//1932 1933//1933 -f 1934//1934 109//109 1933//1933 -f 1933//1933 109//109 138//138 -f 1933//1933 138//138 114//114 -f 1934//1934 1935//1935 109//109 -f 109//109 1935//1935 1936//1936 -f 109//109 1936//1936 1779//1779 -f 1779//1779 1936//1936 1937//1937 -f 1779//1779 1937//1937 1938//1938 -f 1939//1939 86//86 1779//1779 -f 1779//1779 86//86 112//112 -f 1779//1779 112//112 110//110 -f 1790//1790 1940//1940 1791//1791 -f 1791//1791 1940//1940 1941//1941 -f 1791//1791 1941//1941 1939//1939 -f 1939//1939 1941//1941 1942//1942 -f 1939//1939 1942//1942 86//86 -f 1943//1943 1944//1944 1945//1945 -f 1945//1945 1944//1944 1946//1946 -f 1945//1945 1946//1946 1947//1947 -f 1947//1947 1946//1946 1948//1948 -f 1947//1947 1948//1948 1949//1949 -f 1949//1949 1948//1948 1950//1950 -f 1949//1949 1950//1950 1951//1951 -f 1952//1952 1953//1953 1954//1954 -f 1954//1954 1953//1953 1955//1955 -f 1954//1954 1955//1955 1956//1956 -f 1956//1956 1955//1955 1957//1957 -f 1956//1956 1957//1957 1958//1958 -f 1959//1959 1960//1960 1961//1961 -f 1961//1961 1960//1960 1801//1801 -f 1961//1961 1801//1801 1962//1962 -f 1962//1962 1801//1801 1793//1793 -f 1962//1962 1793//1793 1963//1963 -f 1964//1964 1965//1965 1952//1952 -f 1952//1952 1965//1965 1966//1966 -f 1952//1952 1966//1966 1967//1967 -f 1968//1968 1969//1969 1970//1970 -f 1970//1970 1969//1969 1971//1971 -f 1970//1970 1971//1971 1972//1972 -f 1972//1972 1971//1971 1973//1973 -f 1972//1972 1973//1973 1967//1967 -f 1967//1967 1973//1973 1944//1944 -f 1967//1967 1944//1944 1952//1952 -f 1952//1952 1944//1944 1943//1943 -f 1952//1952 1943//1943 1953//1953 -f 1974//1974 1975//1975 1976//1976 -f 1976//1976 1975//1975 1977//1977 -f 1976//1976 1977//1977 1959//1959 -f 1978//1978 1979//1979 1980//1980 -f 1980//1980 1979//1979 1829//1829 -f 1980//1980 1829//1829 1823//1823 -f 1823//1823 1829//1829 1827//1827 -f 1823//1823 1827//1827 1817//1817 -f 1807//1807 1981//1981 1982//1982 -f 1983//1983 1984//1984 1815//1815 -f 1815//1815 1984//1984 1813//1813 -f 1815//1815 1813//1813 1816//1816 -f 1816//1816 1813//1813 1807//1807 -f 1816//1816 1807//1807 1985//1985 -f 1985//1985 1807//1807 1982//1982 -f 1978//1978 1986//1986 1979//1979 -f 1979//1979 1986//1986 1987//1987 -f 1979//1979 1987//1987 1981//1981 -f 1981//1981 1987//1987 1988//1988 -f 1981//1981 1988//1988 1982//1982 -f 1989//1989 1990//1990 1991//1991 -f 1991//1991 1990//1990 1992//1992 -f 1991//1991 1992//1992 1993//1993 -f 1993//1993 1992//1992 1994//1994 -f 1993//1993 1994//1994 1995//1995 -f 1995//1995 1994//1994 1996//1996 -f 1995//1995 1996//1996 1997//1997 -f 1998//1998 1999//1999 2000//2000 -f 2000//2000 1999//1999 2001//2001 -f 2000//2000 2001//2001 2002//2002 -f 2002//2002 2001//2001 2003//2003 -f 2002//2002 2003//2003 2004//2004 -f 2004//2004 2003//2003 2005//2005 -f 2004//2004 2005//2005 2006//2006 -f 2007//2007 2008//2008 2009//2009 -f 2008//2008 2010//2010 2009//2009 -f 2009//2009 2010//2010 2011//2011 -f 2009//2009 2011//2011 2004//2004 -f 2004//2004 2011//2011 2012//2012 -f 2013//2013 2014//2014 2015//2015 -f 2015//2015 2014//2014 2016//2016 -f 2015//2015 2016//2016 2017//2017 -f 2017//2017 2016//2016 2018//2018 -f 2017//2017 2018//2018 2019//2019 -f 2020//2020 2021//2021 2022//2022 -f 2022//2022 2021//2021 2023//2023 -f 2022//2022 2023//2023 2024//2024 -f 2025//2025 1969//1969 2026//2026 -f 2026//2026 1969//1969 1968//1968 -f 2026//2026 1968//1968 1963//1963 -f 2020//2020 2027//2027 2021//2021 -f 2021//2021 2027//2027 2028//2028 -f 2021//2021 2028//2028 2026//2026 -f 2026//2026 2028//2028 2029//2029 -f 2026//2026 2029//2029 2025//2025 -f 2025//2025 2030//2030 1969//1969 -f 1969//1969 2030//2030 2031//2031 -f 1969//1969 2031//2031 1971//1971 -f 1971//1971 2031//2031 2032//2032 -f 2024//2024 2023//2023 2033//2033 -f 2033//2033 2023//2023 2034//2034 -f 2033//2033 2034//2034 2035//2035 -f 2036//2036 2037//2037 1960//1960 -f 2038//2038 2039//2039 1981//1981 -f 1981//1981 2039//2039 2040//2040 -f 1981//1981 2040//2040 2041//2041 -f 1959//1959 1977//1977 1960//1960 -f 1960//1960 1977//1977 2042//2042 -f 1960//1960 2042//2042 2036//2036 -f 2040//2040 2043//2043 2041//2041 -f 2041//2041 2043//2043 2044//2044 -f 2041//2041 2044//2044 2045//2045 -f 2044//2044 2046//2046 2045//2045 -f 2045//2045 2046//2046 2047//2047 -f 2045//2045 2047//2047 1975//1975 -f 1975//1975 2047//2047 2048//2048 -f 1975//1975 2048//2048 1977//1977 -f 1977//1977 2048//2048 2049//2049 -f 1977//1977 2049//2049 2042//2042 -f 2050//2050 2051//2051 2000//2000 -f 2000//2000 2051//2051 2052//2052 -f 2000//2000 2052//2052 2053//2053 -f 2053//2053 2052//2052 2054//2054 -f 2053//2053 2054//2054 2055//2055 -f 2056//2056 2057//2057 2058//2058 -f 2057//2057 2059//2059 2058//2058 -f 2058//2058 2059//2059 2060//2060 -f 2058//2058 2060//2060 2061//2061 -f 2061//2061 2060//2060 2062//2062 -f 2063//2063 2064//2064 1852//1852 -f 2065//2065 2066//2066 1885//1885 -f 2066//2066 2067//2067 1885//1885 -f 1885//1885 2067//2067 1958//1958 -f 1885//1885 1958//1958 1883//1883 -f 1883//1883 1958//1958 1957//1957 -f 2063//2063 1852//1852 2068//2068 -f 2068//2068 1852//1852 2069//2069 -f 2068//2068 2069//2069 2070//2070 -f 1898//1898 1894//1894 1886//1886 -f 1886//1886 1894//1894 1874//1874 -f 1886//1886 1874//1874 1885//1885 -f 1885//1885 1874//1874 1852//1852 -f 1885//1885 1852//1852 2065//2065 -f 2065//2065 1852//1852 2064//2064 -f 2067//2067 2071//2071 1958//1958 -f 1958//1958 2071//2071 2072//2072 -f 1958//1958 2072//2072 1956//1956 -f 1956//1956 2072//2072 2073//2073 -f 2070//2070 2069//2069 2074//2074 -f 2074//2074 2069//2069 2075//2075 -f 2074//2074 2075//2075 2076//2076 -f 2077//2077 2078//2078 1889//1889 -f 1889//1889 2078//2078 2079//2079 -f 2080//2080 2077//2077 1950//1950 -f 1950//1950 2077//2077 1889//1889 -f 1950//1950 1889//1889 1951//1951 -f 1951//1951 1889//1889 1887//1887 -f 1951//1951 1887//1887 2081//2081 -f 2081//2081 1887//1887 1886//1886 -f 2082//2082 2083//2083 1908//1908 -f 1908//1908 2083//2083 2084//2084 -f 1908//1908 2084//2084 2085//2085 -f 2079//2079 2082//2082 1889//1889 -f 1889//1889 2082//2082 1908//1908 -f 1889//1889 1908//1908 1899//1899 -f 1899//1899 1908//1908 1907//1907 -f 1899//1899 1907//1907 2086//2086 -f 2080//2080 1950//1950 2087//2087 -f 2087//2087 1950//1950 1948//1948 -f 2087//2087 1948//1948 2088//2088 -f 2084//2084 2089//2089 2085//2085 -f 2085//2085 2089//2089 2090//2090 -f 2085//2085 2090//2090 2091//2091 -f 2091//2091 2090//2090 2092//2092 -f 1916//1916 1917//1917 1915//1915 -f 1915//1915 1917//1917 1919//1919 -f 1915//1915 1919//1919 2058//2058 -f 2058//2058 1919//1919 2093//2093 -f 2058//2058 2093//2093 2056//2056 -f 2056//2056 2093//2093 2094//2094 -f 135//135 128//128 1921//1921 -f 1921//1921 128//128 2095//2095 -f 1921//1921 2095//2095 1919//1919 -f 1919//1919 2095//2095 2096//2096 -f 1919//1919 2096//2096 2093//2093 -f 2093//2093 2096//2096 2053//2053 -f 2093//2093 2053//2053 2094//2094 -f 2094//2094 2053//2053 2055//2055 -f 128//128 1906//1906 2095//2095 -f 2095//2095 1906//1906 1908//1908 -f 2095//2095 1908//1908 2096//2096 -f 2096//2096 1908//1908 2085//2085 -f 2096//2096 2085//2085 2053//2053 -f 2053//2053 2085//2085 2091//2091 -f 2053//2053 2091//2091 2000//2000 -f 2000//2000 2091//2091 1995//1995 -f 2000//2000 1995//1995 1998//1998 -f 1998//1998 1995//1995 1997//1997 -f 2062//2062 2097//2097 2061//2061 -f 2061//2061 2097//2097 2098//2098 -f 2061//2061 2098//2098 2099//2099 -f 2099//2099 2098//2098 2100//2100 -f 2099//2099 2100//2100 2015//2015 -f 2015//2015 2100//2100 2101//2101 -f 2015//2015 2101//2101 2013//2013 -f 2013//2013 2101//2101 2102//2102 -f 2097//2097 2050//2050 2098//2098 -f 2098//2098 2050//2050 2000//2000 -f 2098//2098 2000//2000 2100//2100 -f 2100//2100 2000//2000 2002//2002 -f 2100//2100 2002//2002 2101//2101 -f 2101//2101 2002//2002 2004//2004 -f 2101//2101 2004//2004 2102//2102 -f 2102//2102 2004//2004 2012//2012 -f 2073//2073 2076//2076 1956//1956 -f 1956//1956 2076//2076 2075//2075 -f 1956//1956 2075//2075 1954//1954 -f 1954//1954 2075//2075 2103//2103 -f 1954//1954 2103//2103 1952//1952 -f 1952//1952 2103//2103 2104//2104 -f 1952//1952 2104//2104 1964//1964 -f 1964//1964 2104//2104 2105//2105 -f 1861//1861 1847//1847 1852//1852 -f 1852//1852 1847//1847 1846//1846 -f 1852//1852 1846//1846 2069//2069 -f 2069//2069 1846//1846 2106//2106 -f 2069//2069 2106//2106 2075//2075 -f 2075//2075 2106//2106 1843//1843 -f 2075//2075 1843//1843 2103//2103 -f 2103//2103 1843//1843 1841//1841 -f 2103//2103 1841//1841 2104//2104 -f 2104//2104 1841//1841 1839//1839 -f 2104//2104 1839//1839 2105//2105 -f 2105//2105 1839//1839 1837//1837 -f 2105//2105 1837//1837 1835//1835 -f 1835//1835 1837//1837 1836//1836 -f 1835//1835 1836//1836 1834//1834 -f 2092//2092 2088//2088 2091//2091 -f 2091//2091 2088//2088 1948//1948 -f 2091//2091 1948//1948 1995//1995 -f 1995//1995 1948//1948 1946//1946 -f 1995//1995 1946//1946 1993//1993 -f 1993//1993 1946//1946 1944//1944 -f 1993//1993 1944//1944 1991//1991 -f 1991//1991 1944//1944 1973//1973 -f 1991//1991 1973//1973 2034//2034 -f 2034//2034 1973//1973 1971//1971 -f 2034//2034 1971//1971 2035//2035 -f 2035//2035 1971//1971 2032//2032 -f 1831//1831 1829//1829 2107//2107 -f 2107//2107 1829//1829 1979//1979 -f 2107//2107 1979//1979 2108//2108 -f 2108//2108 1979//1979 1981//1981 -f 2108//2108 1981//1981 2109//2109 -f 2109//2109 1981//1981 2041//2041 -f 2109//2109 2041//2041 1835//1835 -f 1835//1835 2041//2041 2045//2045 -f 1835//1835 2045//2045 2105//2105 -f 2105//2105 2045//2045 1975//1975 -f 2105//2105 1975//1975 1964//1964 -f 1964//1964 1975//1975 1974//1974 -f 1964//1964 1974//1974 1965//1965 -f 2019//2019 2110//2110 2017//2017 -f 2017//2017 2110//2110 2111//2111 -f 2017//2017 2111//2111 1931//1931 -f 1931//1931 2111//2111 1926//1926 -f 1931//1931 1926//1926 1929//1929 -f 1929//1929 1926//1926 1928//1928 -f 2110//2110 2007//2007 2111//2111 -f 2111//2111 2007//2007 2009//2009 -f 2111//2111 2009//2009 1926//1926 -f 1926//1926 2009//2009 2112//2112 -f 1926//1926 2112//2112 1924//1924 -f 1924//1924 2112//2112 2113//2113 -f 2006//2006 1989//1989 2004//2004 -f 2004//2004 1989//1989 1991//1991 -f 2004//2004 1991//1991 2009//2009 -f 2009//2009 1991//1991 2034//2034 -f 2009//2009 2034//2034 2112//2112 -f 2112//2112 2034//2034 2023//2023 -f 2112//2112 2023//2023 2113//2113 -f 2113//2113 2023//2023 2021//2021 -f 1963//1963 1793//1793 2026//2026 -f 2026//2026 1793//1793 1791//1791 -f 2026//2026 1791//1791 2021//2021 -f 2021//2021 1791//1791 1939//1939 -f 2021//2021 1939//1939 2113//2113 -f 2113//2113 1939//1939 1779//1779 -f 2113//2113 1779//1779 1924//1924 -f 1924//1924 1779//1779 1938//1938 -f 1924//1924 1938//1938 1925//1925 -f 2037//2037 2038//2038 1960//1960 -f 1960//1960 2038//2038 1981//1981 -f 1960//1960 1981//1981 1801//1801 -f 1801//1801 1981//1981 1807//1807 -f 1801//1801 1807//1807 1810//1810 -f 1810//1810 1807//1807 1809//1809 -f 1810//1810 1809//1809 2114//2114 -f 2114//2114 1809//1809 2115//2115 -f 2116//2116 2117//2117 2118//2118 -f 2118//2118 2117//2117 2119//2119 -f 2118//2118 2119//2119 2120//2120 -f 2120//2120 2119//2119 2121//2121 -f 2120//2120 2121//2121 2122//2122 -f 2123//2123 2124//2124 2125//2125 -f 2125//2125 2124//2124 2126//2126 -f 2125//2125 2126//2126 2127//2127 -f 2127//2127 2126//2126 2128//2128 -f 2127//2127 2128//2128 2129//2129 -f 2130//2130 2131//2131 2132//2132 -f 2132//2132 2131//2131 2133//2133 -f 2132//2132 2133//2133 2134//2134 -f 2134//2134 2133//2133 2135//2135 -f 2134//2134 2135//2135 2136//2136 -f 2137//2137 2138//2138 1734//1734 -f 1734//1734 2138//2138 2139//2139 -f 1734//1734 2139//2139 1728//1728 -f 1728//1728 2139//2139 2140//2140 -f 1728//1728 2140//2140 2141//2141 -f 2141//2141 2140//2140 2142//2142 -f 2143//2143 2144//2144 1755//1755 -f 1755//1755 2144//2144 2145//2145 -f 1755//1755 2145//2145 1751//1751 -f 1751//1751 2145//2145 2146//2146 -f 1751//1751 2146//2146 2147//2147 -f 2147//2147 2146//2146 2148//2148 -f 2149//2149 2150//2150 1771//1771 -f 1771//1771 2150//2150 2151//2151 -f 1771//1771 2151//2151 1764//1764 -f 1764//1764 2151//2151 2152//2152 -f 1764//1764 2152//2152 2153//2153 -f 2153//2153 2152//2152 2154//2154 -f 2155//2155 2156//2156 2157//2157 -f 2157//2157 2156//2156 2158//2158 -f 2159//2159 2160//2160 2161//2161 -f 2162//2162 2163//2163 2164//2164 -f 2164//2164 2163//2163 2159//2159 -f 2164//2164 2159//2159 2165//2165 -f 2165//2165 2159//2159 2161//2161 -f 2162//2162 2166//2166 2163//2163 -f 2163//2163 2166//2166 2167//2167 -f 2163//2163 2167//2167 2155//2155 -f 2155//2155 2167//2167 2168//2168 -f 2155//2155 2168//2168 2156//2156 -f 2158//2158 2169//2169 2157//2157 -f 2157//2157 2169//2169 2170//2170 -f 2157//2157 2170//2170 2160//2160 -f 2160//2160 2170//2170 2171//2171 -f 2160//2160 2171//2171 2161//2161 -f 2172//2172 2173//2173 2174//2174 -f 2174//2174 2173//2173 2175//2175 -f 2176//2176 2177//2177 2178//2178 -f 2178//2178 2177//2177 2179//2179 -f 2178//2178 2179//2179 2180//2180 -f 2180//2180 2179//2179 2181//2181 -f 2180//2180 2181//2181 2182//2182 -f 2174//2174 2183//2183 2172//2172 -f 2172//2172 2183//2183 2184//2184 -f 2172//2172 2184//2184 2181//2181 -f 2181//2181 2184//2184 2185//2185 -f 2181//2181 2185//2185 2182//2182 -f 2176//2176 2186//2186 2177//2177 -f 2177//2177 2186//2186 2187//2187 -f 2177//2177 2187//2187 2173//2173 -f 2173//2173 2187//2187 2188//2188 -f 2173//2173 2188//2188 2175//2175 -f 2189//2189 2190//2190 2191//2191 -f 2191//2191 2190//2190 2192//2192 -f 2191//2191 2192//2192 2193//2193 -f 2193//2193 2192//2192 2194//2194 -f 2193//2193 2194//2194 2195//2195 -f 2196//2196 2197//2197 2160//2160 -f 2160//2160 2197//2197 2198//2198 -f 2160//2160 2198//2198 2157//2157 -f 2157//2157 2198//2198 2199//2199 -f 2157//2157 2199//2199 2200//2200 -f 2200//2200 2199//2199 2201//2201 -f 2202//2202 2203//2203 2204//2204 -f 2205//2205 2206//2206 2207//2207 -f 2202//2202 2204//2204 2207//2207 -f 2207//2207 2204//2204 2208//2208 -f 2207//2207 2208//2208 2205//2205 -f 2209//2209 2210//2210 2172//2172 -f 2172//2172 2210//2210 2211//2211 -f 2172//2172 2211//2211 2173//2173 -f 2173//2173 2211//2211 2212//2212 -f 2173//2173 2212//2212 2213//2213 -f 2213//2213 2212//2212 2214//2214 -f 2215//2215 1907//1907 2216//2216 -f 2216//2216 1907//1907 1906//1906 -f 2216//2216 1906//1906 128//128 -f 116//116 1915//1915 2217//2217 -f 2217//2217 1915//1915 2058//2058 -f 2058//2058 2061//2061 2217//2217 -f 2217//2217 2061//2061 2099//2099 -f 2217//2217 2099//2099 2218//2218 -f 2218//2218 2099//2099 2015//2015 -f 2015//2015 2017//2017 2218//2218 -f 2218//2218 2017//2017 1931//1931 -f 2218//2218 1931//1931 114//114 -f 1941//1941 2219//2219 1942//1942 -f 1942//1942 2219//2219 2220//2220 -f 1942//1942 2220//2220 86//86 -f 1941//1941 1940//1940 2219//2219 -f 2219//2219 1940//1940 2221//2221 -f 2219//2219 2221//2221 2222//2222 -f 2222//2222 2221//2221 1472//1472 -f 2222//2222 1472//1472 2223//2223 -f 2223//2223 1472//1472 1288//1288 -f 1789//1789 2224//2224 1790//1790 -f 1790//1790 2224//2224 2221//2221 -f 1790//1790 2221//2221 1940//1940 -f 2140//2140 1633//1633 2224//2224 -f 2224//2224 1633//1633 1291//1291 -f 2224//2224 1291//1291 1290//1290 -f 1789//1789 1787//1787 2224//2224 -f 2224//2224 1787//1787 2142//2142 -f 2224//2224 2142//2142 2140//2140 -f 2225//2225 1318//1318 1320//1320 -f 1796//1796 1795//1795 2138//2138 -f 2138//2138 1795//1795 2225//2225 -f 2138//2138 2225//2225 2139//2139 -f 2139//2139 2225//2225 1320//1320 -f 2139//2139 1320//1320 1630//1630 -f 2225//2225 1795//1795 2226//2226 -f 2226//2226 1795//1795 1803//1803 -f 2146//2146 1471//1471 2226//2226 -f 2226//2226 1471//1471 1470//1470 -f 2226//2226 1470//1470 1468//1468 -f 1803//1803 1800//1800 2226//2226 -f 2226//2226 1800//1800 2148//2148 -f 2226//2226 2148//2148 2146//2146 -f 1784//1784 1783//1783 2227//2227 -f 2227//2227 1463//1463 1462//1462 -f 1784//1784 2227//2227 2144//2144 -f 2144//2144 2227//2227 2145//2145 -f 2145//2145 2227//2227 1462//1462 -f 2145//2145 1462//1462 1464//1464 -f 1812//1812 2228//2228 1811//1811 -f 1811//1811 2228//2228 2227//2227 -f 1811//1811 2227//2227 1783//1783 -f 2152//2152 1636//1636 2228//2228 -f 2228//2228 1636//1636 1344//1344 -f 2228//2228 1344//1344 1343//1343 -f 1812//1812 1806//1806 2228//2228 -f 2228//2228 1806//1806 2154//2154 -f 2228//2228 2154//2154 2152//2152 -f 2229//2229 1334//1334 1340//1340 -f 2115//2115 1809//1809 2150//2150 -f 2150//2150 1809//1809 2229//2229 -f 2150//2150 2229//2229 2151//2151 -f 2151//2151 2229//2229 1340//1340 -f 2151//2151 1340//1340 1634//1634 -f 1813//1813 2230//2230 1808//1808 -f 1808//1808 2230//2230 2229//2229 -f 1808//1808 2229//2229 1809//1809 -f 2199//2199 1640//1640 2230//2230 -f 2230//2230 1640//1640 1500//1500 -f 2230//2230 1500//1500 1499//1499 -f 1813//1813 1984//1984 2230//2230 -f 2230//2230 1984//1984 2201//2201 -f 2230//2230 2201//2201 2199//2199 -f 2231//2231 1457//1457 1456//1456 -f 1822//1822 1819//1819 2197//2197 -f 2197//2197 1819//1819 2231//2231 -f 2197//2197 2231//2231 2198//2198 -f 2198//2198 2231//2231 1456//1456 -f 2198//2198 1456//1456 1637//1637 -f 2231//2231 1819//1819 2232//2232 -f 2232//2232 1819//1819 1818//1818 -f 2232//2232 1818//1818 1460//1460 -f 1460//1460 1818//1818 1817//1817 -f 1826//1826 2233//2233 1827//1827 -f 1827//1827 2233//2233 1460//1460 -f 1827//1827 1460//1460 1817//1817 -f 2233//2233 1826//1826 2234//2234 -f 2234//2234 1826//1826 1828//1828 -f 2234//2234 1828//1828 1830//1830 -f 1458//1458 1459//1459 2212//2212 -f 2212//2212 1459//1459 2234//2234 -f 2212//2212 2234//2234 2214//2214 -f 2214//2214 2234//2234 1830//1830 -f 2235//2235 1453//1453 1452//1452 -f 1832//1832 1834//1834 2210//2210 -f 2210//2210 1834//1834 2235//2235 -f 2210//2210 2235//2235 2211//2211 -f 2211//2211 2235//2235 1452//1452 -f 1834//1834 1836//1836 2235//2235 -f 2235//2235 1836//1836 1838//1838 -f 2235//2235 1838//1838 2236//2236 -f 2236//2236 1838//1838 1840//1840 -f 2236//2236 1840//1840 1842//1842 -f 2236//2236 1842//1842 1844//1844 -f 1446//1446 1448//1448 2237//2237 -f 2237//2237 1448//1448 2236//2236 -f 2237//2237 2236//2236 2238//2238 -f 2238//2238 2236//2236 1844//1844 -f 2239//2239 2240//2240 2241//2241 -f 2241//2241 2240//2240 2242//2242 -f 2241//2241 2242//2242 2243//2243 -f 2243//2243 2242//2242 2237//2237 -f 2243//2243 2237//2237 2244//2244 -f 2244//2244 2237//2237 2238//2238 -f 2245//2245 1443//1443 1442//1442 -f 1850//1850 1849//1849 2240//2240 -f 2240//2240 1849//1849 2245//2245 -f 2240//2240 2245//2245 2242//2242 -f 2242//2242 2245//2245 1442//1442 -f 2245//2245 1849//1849 2246//2246 -f 2246//2246 1849//1849 1873//1873 -f 2246//2246 1873//1873 1445//1445 -f 1445//1445 1873//1873 1872//1872 -f 1445//1445 1872//1872 1871//1871 -f 1445//1445 1871//1871 2247//2247 -f 2247//2247 1871//1871 1870//1870 -f 2247//2247 1870//1870 2248//2248 -f 2248//2248 1870//1870 1856//1856 -f 2248//2248 1856//1856 1864//1864 -f 1294//1294 1293//1293 2249//2249 -f 2249//2249 1293//1293 2248//2248 -f 2249//2249 2248//2248 2250//2250 -f 2250//2250 2248//2248 1864//1864 -f 2251//2251 2252//2252 2253//2253 -f 2253//2253 2252//2252 2254//2254 -f 2253//2253 2254//2254 2255//2255 -f 2255//2255 2254//2254 2249//2249 -f 2255//2255 2249//2249 2256//2256 -f 2256//2256 2249//2249 2250//2250 -f 2257//2257 1395//1395 1713//1713 -f 1781//1781 1780//1780 2252//2252 -f 2252//2252 1780//1780 2257//2257 -f 2252//2252 2257//2257 2254//2254 -f 2254//2254 2257//2257 1713//1713 -f 1879//1879 2258//2258 1853//1853 -f 1853//1853 2258//2258 2257//2257 -f 1853//1853 2257//2257 1780//1780 -f 2258//2258 1879//1879 1877//1877 -f 1408//1408 1397//1397 2259//2259 -f 2259//2259 1397//1397 2258//2258 -f 2259//2259 2258//2258 2260//2260 -f 2260//2260 2258//2258 1877//1877 -f 2261//2261 2262//2262 2263//2263 -f 2263//2263 2262//2262 2264//2264 -f 2263//2263 2264//2264 2265//2265 -f 2265//2265 2264//2264 2259//2259 -f 2265//2265 2259//2259 2266//2266 -f 2266//2266 2259//2259 2260//2260 -f 2267//2267 1402//1402 1400//1400 -f 1882//1882 1875//1875 2262//2262 -f 2262//2262 1875//1875 2267//2267 -f 2262//2262 2267//2267 2264//2264 -f 2264//2264 2267//2267 1400//1400 -f 1895//1895 2268//2268 1874//1874 -f 1874//1874 2268//2268 2267//2267 -f 1874//1874 2267//2267 1875//1875 -f 2268//2268 1895//1895 1893//1893 -f 1438//1438 1439//1439 2269//2269 -f 2269//2269 1439//1439 2268//2268 -f 2269//2269 2268//2268 2270//2270 -f 2270//2270 2268//2268 1893//1893 -f 2271//2271 2272//2272 2273//2273 -f 2273//2273 2272//2272 2274//2274 -f 2273//2273 2274//2274 2275//2275 -f 2275//2275 2274//2274 2269//2269 -f 2275//2275 2269//2269 2276//2276 -f 2276//2276 2269//2269 2270//2270 -f 1375//1375 1373//1373 2277//2277 -f 2277//2277 1373//1373 2274//2274 -f 2274//2274 2272//2272 2277//2277 -f 2277//2277 2272//2272 1896//1896 -f 2277//2277 1896//1896 1888//1888 -f 2277//2277 1888//1888 2278//2278 -f 2278//2278 1888//1888 1887//1887 -f 2278//2278 1887//1887 1891//1891 -f 1391//1391 1377//1377 2279//2279 -f 2279//2279 1377//1377 2278//2278 -f 2279//2279 2278//2278 2280//2280 -f 2280//2280 2278//2278 1891//1891 -f 2281//2281 2282//2282 2283//2283 -f 2283//2283 2282//2282 2284//2284 -f 2283//2283 2284//2284 2285//2285 -f 2285//2285 2284//2284 2279//2279 -f 2285//2285 2279//2279 2286//2286 -f 2286//2286 2279//2279 2280//2280 -f 2287//2287 1495//1495 1494//1494 -f 1905//1905 1900//1900 2282//2282 -f 2282//2282 1900//1900 2287//2287 -f 2282//2282 2287//2287 2284//2284 -f 2284//2284 2287//2287 1494//1494 -f 2086//2086 2288//2288 1899//1899 -f 1899//1899 2288//2288 2287//2287 -f 1899//1899 2287//2287 1900//1900 -f 2289//2289 1497//1497 1496//1496 -f 2086//2086 1907//1907 2288//2288 -f 2288//2288 1907//1907 2215//2215 -f 2288//2288 2215//2215 1496//1496 -f 1496//1496 2215//2215 2290//2290 -f 1496//1496 2290//2290 2289//2289 -f 1417//1417 2291//2291 1434//1434 -f 1434//1434 2291//2291 2292//2292 -f 1434//1434 2292//2292 1435//1435 -f 1435//1435 2292//2292 1437//1437 -f 2293//2293 1423//1423 2294//2294 -f 2294//2294 1423//1423 1422//1422 -f 2294//2294 1422//1422 1421//1421 -f 2295//2295 2296//2296 1425//1425 -f 1425//1425 1424//1424 2295//2295 -f 2295//2295 1424//1424 1678//1678 -f 2295//2295 1678//1678 1433//1433 -f 1532//1532 2297//2297 1427//1427 -f 1427//1427 2297//2297 2298//2298 -f 1427//1427 2298//2298 1428//1428 -f 2299//2299 2300//2300 2301//2301 -f 2301//2301 2300//2300 2302//2302 -f 1507//1507 2303//2303 1503//1503 -f 1503//1503 2303//2303 2304//2304 -f 1503//1503 2304//2304 1504//1504 -f 2305//2305 1520//1520 1519//1519 -f 2305//2305 1519//1519 2306//2306 -f 2306//2306 1519//1519 1525//1525 -f 2306//2306 1525//1525 1524//1524 -f 2307//2307 1521//1521 2308//2308 -f 2308//2308 1521//1521 1527//1527 -f 2308//2308 1527//1527 1526//1526 -f 2309//2309 1538//1538 1536//1536 -f 2309//2309 1536//1536 2310//2310 -f 2310//2310 1536//1536 1534//1534 -f 2310//2310 1534//1534 1533//1533 -f 2311//2311 2312//2312 2313//2313 -f 2313//2313 2312//2312 2314//2314 -f 2315//2315 2316//2316 2317//2317 -f 2317//2317 2316//2316 2243//2243 -f 2317//2317 2243//2243 1845//1845 -f 1845//1845 2243//2243 2244//2244 -f 2241//2241 2243//2243 2318//2318 -f 2318//2318 2243//2243 2319//2319 -f 2320//2320 2321//2321 2322//2322 -f 2322//2322 2321//2321 2241//2241 -f 2322//2322 2241//2241 2323//2323 -f 2323//2323 2241//2241 2318//2318 -f 2320//2320 2324//2324 2321//2321 -f 2321//2321 2324//2324 2325//2325 -f 2321//2321 2325//2325 2326//2326 -f 2326//2326 2325//2325 2327//2327 -f 2326//2326 2327//2327 2316//2316 -f 2316//2316 2327//2327 2328//2328 -f 2328//2328 2329//2329 2316//2316 -f 2316//2316 2329//2329 2330//2330 -f 2316//2316 2330//2330 2243//2243 -f 2243//2243 2330//2330 2331//2331 -f 2243//2243 2331//2331 2319//2319 -f 1848//1848 2239//2239 2332//2332 -f 2332//2332 2239//2239 2241//2241 -f 2332//2332 2241//2241 2333//2333 -f 2333//2333 2241//2241 2321//2321 -f 2315//2315 2334//2334 2316//2316 -f 2316//2316 2334//2334 2326//2326 -f 2334//2334 2333//2333 2326//2326 -f 2326//2326 2333//2333 2321//2321 -f 2332//2332 2333//2333 2335//2335 -f 2335//2335 2333//2333 2334//2334 -f 2335//2335 2334//2334 2336//2336 -f 2336//2336 2334//2334 2315//2315 -f 2336//2336 2315//2315 2317//2317 -f 1845//1845 1843//1843 2317//2317 -f 2317//2317 1843//1843 2336//2336 -f 1846//1846 2335//2335 2106//2106 -f 2106//2106 2335//2335 2336//2336 -f 2106//2106 2336//2336 1843//1843 -f 1846//1846 1848//1848 2335//2335 -f 2335//2335 1848//1848 2332//2332 -f 2337//2337 2338//2338 2339//2339 -f 2339//2339 2338//2338 2255//2255 -f 2339//2339 2255//2255 1865//1865 -f 1865//1865 2255//2255 2256//2256 -f 2340//2340 2253//2253 2341//2341 -f 2341//2341 2342//2342 2340//2340 -f 2340//2340 2342//2342 2343//2343 -f 2340//2340 2343//2343 2344//2344 -f 2344//2344 2343//2343 2345//2345 -f 2338//2338 2346//2346 2255//2255 -f 2255//2255 2346//2346 2347//2347 -f 2347//2347 2348//2348 2255//2255 -f 2255//2255 2348//2348 2349//2349 -f 2255//2255 2349//2349 2253//2253 -f 2253//2253 2349//2349 2350//2350 -f 2253//2253 2350//2350 2341//2341 -f 2345//2345 2351//2351 2344//2344 -f 2344//2344 2351//2351 2352//2352 -f 2344//2344 2352//2352 2338//2338 -f 2338//2338 2352//2352 2353//2353 -f 2338//2338 2353//2353 2346//2346 -f 1782//1782 2251//2251 2354//2354 -f 2354//2354 2251//2251 2253//2253 -f 2354//2354 2253//2253 2355//2355 -f 2355//2355 2253//2253 2340//2340 -f 2337//2337 2356//2356 2338//2338 -f 2338//2338 2356//2356 2344//2344 -f 2356//2356 2355//2355 2344//2344 -f 2344//2344 2355//2355 2340//2340 -f 2357//2357 2354//2354 2355//2355 -f 2337//2337 2339//2339 2358//2358 -f 2357//2357 2355//2355 2358//2358 -f 2358//2358 2355//2355 2356//2356 -f 2358//2358 2356//2356 2337//2337 -f 1866//1866 2358//2358 1865//1865 -f 1865//1865 2358//2358 2339//2339 -f 1851//1851 2357//2357 1866//1866 -f 1866//1866 2357//2357 2358//2358 -f 1782//1782 2354//2354 1851//1851 -f 1851//1851 2354//2354 2357//2357 -f 2318//2318 1689//1689 2323//2323 -f 2323//2323 1689//1689 1691//1691 -f 2323//2323 1691//1691 2322//2322 -f 2322//2322 1691//1691 1692//1692 -f 2322//2322 1692//1692 2320//2320 -f 2320//2320 1692//1692 1697//1697 -f 2320//2320 1697//1697 2324//2324 -f 2324//2324 1697//1697 1696//1696 -f 2324//2324 1696//1696 2325//2325 -f 2325//2325 1696//1696 1700//1700 -f 2325//2325 1700//1700 2327//2327 -f 2327//2327 1700//1700 1699//1699 -f 2327//2327 1699//1699 2328//2328 -f 2328//2328 1699//1699 1698//1698 -f 2328//2328 1698//1698 2329//2329 -f 2329//2329 1698//1698 1693//1693 -f 2329//2329 1693//1693 2330//2330 -f 2330//2330 1693//1693 1694//1694 -f 2330//2330 1694//1694 2331//2331 -f 2331//2331 1694//1694 1695//1695 -f 2331//2331 1695//1695 2319//2319 -f 2319//2319 1695//1695 1688//1688 -f 2319//2319 1688//1688 2318//2318 -f 2318//2318 1688//1688 1689//1689 -f 2346//2346 1722//1722 2347//2347 -f 2347//2347 1722//1722 1721//1721 -f 2347//2347 1721//1721 2348//2348 -f 2348//2348 1721//1721 1720//1720 -f 2348//2348 1720//1720 2349//2349 -f 2349//2349 1720//1720 1718//1718 -f 2349//2349 1718//1718 2350//2350 -f 2350//2350 1718//1718 1717//1717 -f 2350//2350 1717//1717 2341//2341 -f 2341//2341 1717//1717 1712//1712 -f 2341//2341 1712//1712 2342//2342 -f 2342//2342 1712//1712 1714//1714 -f 2342//2342 1714//1714 2343//2343 -f 2343//2343 1714//1714 1715//1715 -f 2343//2343 1715//1715 2345//2345 -f 2345//2345 1715//1715 1716//1716 -f 2345//2345 1716//1716 2351//2351 -f 2351//2351 1716//1716 1726//1726 -f 2351//2351 1726//1726 2352//2352 -f 2352//2352 1726//1726 1725//1725 -f 2352//2352 1725//1725 2353//2353 -f 2353//2353 1725//1725 1723//1723 -f 2353//2353 1723//1723 2346//2346 -f 2346//2346 1723//1723 1722//1722 -f 2359//2359 2360//2360 2361//2361 -f 2361//2361 2360//2360 2265//2265 -f 2361//2361 2265//2265 1876//1876 -f 1876//1876 2265//2265 2266//2266 -f 2362//2362 2263//2263 2363//2363 -f 2363//2363 2364//2364 2362//2362 -f 2362//2362 2364//2364 2365//2365 -f 2362//2362 2365//2365 2366//2366 -f 2366//2366 2365//2365 2367//2367 -f 2368//2368 2265//2265 2369//2369 -f 2369//2369 2265//2265 2360//2360 -f 2367//2367 2370//2370 2366//2366 -f 2366//2366 2370//2370 2371//2371 -f 2366//2366 2371//2371 2360//2360 -f 2360//2360 2371//2371 2372//2372 -f 2360//2360 2372//2372 2369//2369 -f 2368//2368 2373//2373 2265//2265 -f 2265//2265 2373//2373 2374//2374 -f 2265//2265 2374//2374 2263//2263 -f 2263//2263 2374//2374 2375//2375 -f 2263//2263 2375//2375 2363//2363 -f 1881//1881 2261//2261 2376//2376 -f 2376//2376 2261//2261 2263//2263 -f 2376//2376 2263//2263 2377//2377 -f 2377//2377 2263//2263 2362//2362 -f 2378//2378 2379//2379 2380//2380 -f 2380//2380 2379//2379 2275//2275 -f 2380//2380 2275//2275 1892//1892 -f 1892//1892 2275//2275 2276//2276 -f 2381//2381 2275//2275 2382//2382 -f 2382//2382 2275//2275 2379//2379 -f 2381//2381 2383//2383 2275//2275 -f 2275//2275 2383//2383 2384//2384 -f 2275//2275 2384//2384 2273//2273 -f 2385//2385 2386//2386 2387//2387 -f 2387//2387 2386//2386 2388//2388 -f 2385//2385 2389//2389 2386//2386 -f 2386//2386 2389//2389 2390//2390 -f 2386//2386 2390//2390 2379//2379 -f 2379//2379 2390//2390 2391//2391 -f 2379//2379 2391//2391 2382//2382 -f 2384//2384 2392//2392 2273//2273 -f 2273//2273 2392//2392 2393//2393 -f 2273//2273 2393//2393 2388//2388 -f 2388//2388 2393//2393 2394//2394 -f 2388//2388 2394//2394 2387//2387 -f 1897//1897 2271//2271 2395//2395 -f 2395//2395 2271//2271 2273//2273 -f 2395//2395 2273//2273 2396//2396 -f 2396//2396 2273//2273 2388//2388 -f 2397//2397 2398//2398 2399//2399 -f 2399//2399 2398//2398 2285//2285 -f 2399//2399 2285//2285 1901//1901 -f 1901//1901 2285//2285 2286//2286 -f 2400//2400 2401//2401 2402//2402 -f 2402//2402 2401//2401 2398//2398 -f 2403//2403 2283//2283 2404//2404 -f 2404//2404 2405//2405 2403//2403 -f 2403//2403 2405//2405 2406//2406 -f 2403//2403 2406//2406 2402//2402 -f 2402//2402 2406//2406 2407//2407 -f 2402//2402 2407//2407 2400//2400 -f 2401//2401 2408//2408 2398//2398 -f 2398//2398 2408//2408 2409//2409 -f 2398//2398 2409//2409 2285//2285 -f 2285//2285 2409//2409 2410//2410 -f 2410//2410 2411//2411 2285//2285 -f 2285//2285 2411//2411 2412//2412 -f 2285//2285 2412//2412 2283//2283 -f 2283//2283 2412//2412 2413//2413 -f 2283//2283 2413//2413 2404//2404 -f 1904//1904 2281//2281 2414//2414 -f 2414//2414 2281//2281 2283//2283 -f 2414//2414 2283//2283 2415//2415 -f 2415//2415 2283//2283 2403//2403 -f 2359//2359 2416//2416 2360//2360 -f 2360//2360 2416//2416 2366//2366 -f 2416//2416 2377//2377 2366//2366 -f 2366//2366 2377//2377 2362//2362 -f 2417//2417 2376//2376 2377//2377 -f 2359//2359 2361//2361 2418//2418 -f 2417//2417 2377//2377 2418//2418 -f 2418//2418 2377//2377 2416//2416 -f 2418//2418 2416//2416 2359//2359 -f 2378//2378 2419//2419 2379//2379 -f 2379//2379 2419//2419 2386//2386 -f 2419//2419 2396//2396 2386//2386 -f 2386//2386 2396//2396 2388//2388 -f 2420//2420 2395//2395 2396//2396 -f 2378//2378 2380//2380 2421//2421 -f 2420//2420 2396//2396 2421//2421 -f 2421//2421 2396//2396 2419//2419 -f 2421//2421 2419//2419 2378//2378 -f 2397//2397 2422//2422 2398//2398 -f 2398//2398 2422//2422 2402//2402 -f 2422//2422 2415//2415 2402//2402 -f 2402//2402 2415//2415 2403//2403 -f 2423//2423 2414//2414 2415//2415 -f 2397//2397 2399//2399 2424//2424 -f 2423//2423 2415//2415 2424//2424 -f 2424//2424 2415//2415 2422//2422 -f 2424//2424 2422//2422 2397//2397 -f 1878//1878 2418//2418 1876//1876 -f 1876//1876 2418//2418 2361//2361 -f 1880//1880 2417//2417 1878//1878 -f 1878//1878 2417//2417 2418//2418 -f 1881//1881 2376//2376 1880//1880 -f 1880//1880 2376//2376 2417//2417 -f 1894//1894 2421//2421 1892//1892 -f 1892//1892 2421//2421 2380//2380 -f 1898//1898 2420//2420 1894//1894 -f 1894//1894 2420//2420 2421//2421 -f 1897//1897 2395//2395 1898//1898 -f 1898//1898 2395//2395 2420//2420 -f 1902//1902 2424//2424 1901//1901 -f 1901//1901 2424//2424 2399//2399 -f 1903//1903 2423//2423 1902//1902 -f 1902//1902 2423//2423 2424//2424 -f 1904//1904 2414//2414 1903//1903 -f 1903//1903 2414//2414 2423//2423 -f 2369//2369 1410//1410 2368//2368 -f 2368//2368 1410//1410 1409//1409 -f 2368//2368 1409//1409 2373//2373 -f 2373//2373 1409//1409 1407//1407 -f 2373//2373 1407//1407 2374//2374 -f 2374//2374 1407//1407 1405//1405 -f 2374//2374 1405//1405 2375//2375 -f 2375//2375 1405//1405 1404//1404 -f 2375//2375 1404//1404 2363//2363 -f 2363//2363 1404//1404 1399//1399 -f 2363//2363 1399//1399 2364//2364 -f 2364//2364 1399//1399 1401//1401 -f 2364//2364 1401//1401 2365//2365 -f 2365//2365 1401//1401 1403//1403 -f 2365//2365 1403//1403 2367//2367 -f 2367//2367 1403//1403 1411//1411 -f 2367//2367 1411//1411 2370//2370 -f 2370//2370 1411//1411 1413//1413 -f 2370//2370 1413//1413 2371//2371 -f 2371//2371 1413//1413 1414//1414 -f 2371//2371 1414//1414 2372//2372 -f 2372//2372 1414//1414 1398//1398 -f 2372//2372 1398//1398 2369//2369 -f 2369//2369 1398//1398 1410//1410 -f 2382//2382 1282//1282 2381//2381 -f 2381//2381 1282//1282 1281//1281 -f 2381//2381 1281//1281 2383//2383 -f 2383//2383 1281//1281 1711//1711 -f 2383//2383 1711//1711 2384//2384 -f 2384//2384 1711//1711 1710//1710 -f 2384//2384 1710//1710 2392//2392 -f 2392//2392 1710//1710 1709//1709 -f 2392//2392 1709//1709 2393//2393 -f 2393//2393 1709//1709 1708//1708 -f 2393//2393 1708//1708 2394//2394 -f 2394//2394 1708//1708 1707//1707 -f 2394//2394 1707//1707 2387//2387 -f 2387//2387 1707//1707 1706//1706 -f 2387//2387 1706//1706 2385//2385 -f 2385//2385 1706//1706 1703//1703 -f 2385//2385 1703//1703 2389//2389 -f 2389//2389 1703//1703 1702//1702 -f 2389//2389 1702//1702 2390//2390 -f 2390//2390 1702//1702 1705//1705 -f 2390//2390 1705//1705 2391//2391 -f 2391//2391 1705//1705 1704//1704 -f 2391//2391 1704//1704 2382//2382 -f 2382//2382 1704//1704 1282//1282 -f 2409//2409 1393//1393 2410//2410 -f 2410//2410 1393//1393 1392//1392 -f 2410//2410 1392//1392 2411//2411 -f 2411//2411 1392//1392 1390//1390 -f 2411//2411 1390//1390 2412//2412 -f 2412//2412 1390//1390 1388//1388 -f 2412//2412 1388//1388 2413//2413 -f 2413//2413 1388//1388 1387//1387 -f 2413//2413 1387//1387 2404//2404 -f 2404//2404 1387//1387 1384//1384 -f 2404//2404 1384//1384 2405//2405 -f 2405//2405 1384//1384 1383//1383 -f 2405//2405 1383//1383 2406//2406 -f 2406//2406 1383//1383 1386//1386 -f 2406//2406 1386//1386 2407//2407 -f 2407//2407 1386//1386 1385//1385 -f 2407//2407 1385//1385 2400//2400 -f 2400//2400 1385//1385 1380//1380 -f 2400//2400 1380//1380 2401//2401 -f 2401//2401 1380//1380 1379//1379 -f 2401//2401 1379//1379 2408//2408 -f 2408//2408 1379//1379 1378//1378 -f 2408//2408 1378//1378 2409//2409 -f 2409//2409 1378//1378 1393//1393 -f 2205//2205 2177//2177 2206//2206 -f 2206//2206 2177//2177 2173//2173 -f 2206//2206 2173//2173 2107//2107 -f 2107//2107 2173//2173 2213//2213 -f 1833//1833 2209//2209 2203//2203 -f 2203//2203 2209//2209 2172//2172 -f 2203//2203 2172//2172 2204//2204 -f 2204//2204 2172//2172 2181//2181 -f 2205//2205 2208//2208 2177//2177 -f 2177//2177 2208//2208 2179//2179 -f 2208//2208 2204//2204 2179//2179 -f 2179//2179 2204//2204 2181//2181 -f 2108//2108 2207//2207 2107//2107 -f 2107//2107 2207//2207 2206//2206 -f 1835//1835 2202//2202 2109//2109 -f 2109//2109 2202//2202 2207//2207 -f 2109//2109 2207//2207 2108//2108 -f 1833//1833 2203//2203 1835//1835 -f 1835//1835 2203//2203 2202//2202 -f 2194//2194 2155//2155 2195//2195 -f 2195//2195 2155//2155 2157//2157 -f 2195//2195 2157//2157 1983//1983 -f 1983//1983 2157//2157 2200//2200 -f 1821//1821 2196//2196 2189//2189 -f 2189//2189 2196//2196 2160//2160 -f 2189//2189 2160//2160 2190//2190 -f 2190//2190 2160//2160 2159//2159 -f 2194//2194 2192//2192 2155//2155 -f 2155//2155 2192//2192 2163//2163 -f 2192//2192 2190//2190 2163//2163 -f 2163//2163 2190//2190 2159//2159 -f 1983//1983 1815//1815 2195//2195 -f 2195//2195 1815//1815 2193//2193 -f 1815//1815 1814//1814 2193//2193 -f 2193//2193 1814//1814 2191//2191 -f 1814//1814 1821//1821 2191//2191 -f 2191//2191 1821//1821 2189//2189 -f 2174//2174 1362//1362 2183//2183 -f 2183//2183 1362//1362 1361//1361 -f 2183//2183 1361//1361 2184//2184 -f 2184//2184 1361//1361 1360//1360 -f 2184//2184 1360//1360 2185//2185 -f 2185//2185 1360//1360 1358//1358 -f 2185//2185 1358//1358 2182//2182 -f 2182//2182 1358//1358 1357//1357 -f 2182//2182 1357//1357 2180//2180 -f 2180//2180 1357//1357 1355//1355 -f 2180//2180 1355//1355 2178//2178 -f 2178//2178 1355//1355 1354//1354 -f 2178//2178 1354//1354 2176//2176 -f 2176//2176 1354//1354 1371//1371 -f 2176//2176 1371//1371 2186//2186 -f 2186//2186 1371//1371 1369//1369 -f 2186//2186 1369//1369 2187//2187 -f 2187//2187 1369//1369 1367//1367 -f 2187//2187 1367//1367 2188//2188 -f 2188//2188 1367//1367 1365//1365 -f 2188//2188 1365//1365 2175//2175 -f 2175//2175 1365//1365 1364//1364 -f 2175//2175 1364//1364 2174//2174 -f 2174//2174 1364//1364 1362//1362 -f 2165//2165 1512//1512 2164//2164 -f 2164//2164 1512//1512 1511//1511 -f 2164//2164 1511//1511 2162//2162 -f 2162//2162 1511//1511 1510//1510 -f 2162//2162 1510//1510 2166//2166 -f 2166//2166 1510//1510 1508//1508 -f 2166//2166 1508//1508 2167//2167 -f 2167//2167 1508//1508 1506//1506 -f 2167//2167 1506//1506 2168//2168 -f 2168//2168 1506//1506 1505//1505 -f 2168//2168 1505//1505 2156//2156 -f 2156//2156 1505//1505 1502//1502 -f 2156//2156 1502//1502 2158//2158 -f 2158//2158 1502//1502 1501//1501 -f 2158//2158 1501//1501 2169//2169 -f 2169//2169 1501//1501 1517//1517 -f 2169//2169 1517//1517 2170//2170 -f 2170//2170 1517//1517 1516//1516 -f 2170//2170 1516//1516 2171//2171 -f 2171//2171 1516//1516 1514//1514 -f 2171//2171 1514//1514 2161//2161 -f 2161//2161 1514//1514 1513//1513 -f 2161//2161 1513//1513 2165//2165 -f 2165//2165 1513//1513 1512//1512 -f 2135//2135 1762//1762 2136//2136 -f 2136//2136 1762//1762 1764//1764 -f 2136//2136 1764//1764 1805//1805 -f 1805//1805 1764//1764 2153//2153 -f 2114//2114 2149//2149 2130//2130 -f 2130//2130 2149//2149 1771//1771 -f 2130//2130 1771//1771 2131//2131 -f 2131//2131 1771//1771 1773//1773 -f 2128//2128 1749//1749 2129//2129 -f 2129//2129 1749//1749 1751//1751 -f 2129//2129 1751//1751 1799//1799 -f 1799//1799 1751//1751 2147//2147 -f 1785//1785 2143//2143 2123//2123 -f 2123//2123 2143//2143 1755//1755 -f 2123//2123 1755//1755 2124//2124 -f 2124//2124 1755//1755 1745//1745 -f 2121//2121 1738//1738 2122//2122 -f 2122//2122 1738//1738 1728//1728 -f 2122//2122 1728//1728 1786//1786 -f 1786//1786 1728//1728 2141//2141 -f 1794//1794 2137//2137 2116//2116 -f 2116//2116 2137//2137 1734//1734 -f 2116//2116 1734//1734 2117//2117 -f 2117//2117 1734//1734 1737//1737 -f 2135//2135 2133//2133 1762//1762 -f 1762//1762 2133//2133 1766//1766 -f 2133//2133 2131//2131 1766//1766 -f 1766//1766 2131//2131 1773//1773 -f 2128//2128 2126//2126 1749//1749 -f 1749//1749 2126//2126 1747//1747 -f 2126//2126 2124//2124 1747//1747 -f 1747//1747 2124//2124 1745//1745 -f 2121//2121 2119//2119 1738//1738 -f 1738//1738 2119//2119 1731//1731 -f 2119//2119 2117//2117 1731//1731 -f 1731//1731 2117//2117 1737//1737 -f 1805//1805 1804//1804 2136//2136 -f 2136//2136 1804//1804 2134//2134 -f 1804//1804 1810//1810 2134//2134 -f 2134//2134 1810//1810 2132//2132 -f 1810//1810 2114//2114 2132//2132 -f 2132//2132 2114//2114 2130//2130 -f 1799//1799 1798//1798 2129//2129 -f 2129//2129 1798//1798 2127//2127 -f 1798//1798 1802//1802 2127//2127 -f 2127//2127 1802//1802 2125//2125 -f 1802//1802 1785//1785 2125//2125 -f 2125//2125 1785//1785 2123//2123 -f 1786//1786 1788//1788 2122//2122 -f 2122//2122 1788//1788 2120//2120 -f 1788//1788 1792//1792 2120//2120 -f 2120//2120 1792//1792 2118//2118 -f 1792//1792 1794//1794 2118//2118 -f 2118//2118 1794//1794 2116//2116 -f 1772//1772 1339//1339 1776//1776 -f 1776//1776 1339//1339 1338//1338 -f 1776//1776 1338//1338 1777//1777 -f 1777//1777 1338//1338 1333//1333 -f 1777//1777 1333//1333 1778//1778 -f 1778//1778 1333//1333 1350//1350 -f 1778//1778 1350//1350 1767//1767 -f 1767//1767 1350//1350 1349//1349 -f 1767//1767 1349//1349 1768//1768 -f 1768//1768 1349//1349 1347//1347 -f 1768//1768 1347//1347 1763//1763 -f 1763//1763 1347//1347 1346//1346 -f 1763//1763 1346//1346 1765//1765 -f 1765//1765 1346//1346 1345//1345 -f 1765//1765 1345//1345 1769//1769 -f 1769//1769 1345//1345 1353//1353 -f 1769//1769 1353//1353 1770//1770 -f 1770//1770 1353//1353 1352//1352 -f 1770//1770 1352//1352 1775//1775 -f 1775//1775 1352//1352 1351//1351 -f 1775//1775 1351//1351 1774//1774 -f 1774//1774 1351//1351 1341//1341 -f 1774//1774 1341//1341 1772//1772 -f 1772//1772 1341//1341 1339//1339 -f 1758//1758 1643//1643 1746//1746 -f 1746//1746 1643//1643 1642//1642 -f 1746//1746 1642//1642 1748//1748 -f 1748//1748 1642//1642 1653//1653 -f 1748//1748 1653//1653 1759//1759 -f 1759//1759 1653//1653 1652//1652 -f 1759//1759 1652//1652 1760//1760 -f 1760//1760 1652//1652 1651//1651 -f 1760//1760 1651//1651 1761//1761 -f 1761//1761 1651//1651 1648//1648 -f 1761//1761 1648//1648 1750//1750 -f 1750//1750 1648//1648 1649//1649 -f 1750//1750 1649//1649 1752//1752 -f 1752//1752 1649//1649 1650//1650 -f 1752//1752 1650//1650 1753//1753 -f 1753//1753 1650//1650 1647//1647 -f 1753//1753 1647//1647 1754//1754 -f 1754//1754 1647//1647 1646//1646 -f 1754//1754 1646//1646 1756//1756 -f 1756//1756 1646//1646 1645//1645 -f 1756//1756 1645//1645 1757//1757 -f 1757//1757 1645//1645 1644//1644 -f 1757//1757 1644//1644 1758//1758 -f 1758//1758 1644//1644 1643//1643 -f 1742//1742 1319//1319 1743//1743 -f 1743//1743 1319//1319 1317//1317 -f 1743//1743 1317//1317 1744//1744 -f 1744//1744 1317//1317 1316//1316 -f 1744//1744 1316//1316 1732//1732 -f 1732//1732 1316//1316 1327//1327 -f 1732//1732 1327//1327 1733//1733 -f 1733//1733 1327//1327 1329//1329 -f 1733//1733 1329//1329 1739//1739 -f 1739//1739 1329//1329 1331//1331 -f 1739//1739 1331//1331 1740//1740 -f 1740//1740 1331//1331 1332//1332 -f 1740//1740 1332//1332 1741//1741 -f 1741//1741 1332//1332 1326//1326 -f 1741//1741 1326//1326 1729//1729 -f 1729//1729 1326//1326 1325//1325 -f 1729//1729 1325//1325 1730//1730 -f 1730//1730 1325//1325 1324//1324 -f 1730//1730 1324//1324 1735//1735 -f 1735//1735 1324//1324 1323//1323 -f 1735//1735 1323//1323 1736//1736 -f 1736//1736 1323//1323 1321//1321 -f 1736//1736 1321//1321 1742//1742 -f 1742//1742 1321//1321 1319//1319 -f 2218//2218 114//114 2425//2425 -f 2425//2425 114//114 138//138 -f 2425//2425 138//138 2426//2426 -f 2426//2426 138//138 2427//2427 -f 2427//2427 138//138 109//109 -f 2427//2427 109//109 2428//2428 -f 2428//2428 109//109 2429//2429 -f 2429//2429 109//109 110//110 -f 2429//2429 110//110 2430//2430 -f 2430//2430 110//110 2431//2431 -f 2431//2431 110//110 112//112 -f 2431//2431 112//112 2432//2432 -f 2432//2432 112//112 2433//2433 -f 2433//2433 112//112 86//86 -f 2433//2433 86//86 2220//2220 -f 2216//2216 128//128 2434//2434 -f 2434//2434 128//128 135//135 -f 2434//2434 135//135 2435//2435 -f 2435//2435 135//135 2436//2436 -f 2436//2436 135//135 134//134 -f 2436//2436 134//134 2437//2437 -f 2437//2437 134//134 2438//2438 -f 2438//2438 134//134 120//120 -f 2438//2438 120//120 2439//2439 -f 2439//2439 120//120 2440//2440 -f 2440//2440 120//120 118//118 -f 2440//2440 118//118 2441//2441 -f 2441//2441 118//118 2442//2442 -f 2442//2442 118//118 116//116 -f 2442//2442 116//116 2217//2217 -f 2443//2443 1886//1886 1884//1884 -f 1884//1884 1883//1883 2443//2443 -f 2443//2443 1883//1883 1957//1957 -f 2443//2443 1957//1957 2444//2444 -f 2444//2444 1957//1957 1955//1955 -f 2444//2444 1955//1955 1953//1953 -f 1672//1672 2444//2444 1673//1673 -f 1673//1673 2444//2444 1674//1674 -f 1953//1953 1943//1943 2444//2444 -f 2444//2444 1943//1943 2445//2445 -f 2444//2444 2445//2445 1674//1674 -f 1674//1674 2445//2445 1540//1540 -f 1947//1947 2446//2446 1945//1945 -f 1945//1945 2446//2446 2445//2445 -f 1945//1945 2445//2445 1943//1943 -f 1947//1947 1949//1949 2446//2446 -f 2446//2446 1949//1949 1951//1951 -f 2446//2446 1951//1951 2081//2081 -f 2447//2447 2448//2448 2446//2446 -f 2081//2081 1886//1886 2446//2446 -f 2446//2446 1886//1886 2443//2443 -f 2446//2446 2443//2443 2447//2447 -f 2449//2449 2450//2450 2451//2451 -f 1961//1961 1962//1962 2451//2451 -f 2451//2451 1962//1962 2452//2452 -f 2451//2451 2452//2452 2449//2449 -f 2452//2452 1962//1962 1963//1963 -f 1963//1963 1968//1968 2452//2452 -f 2452//2452 1968//1968 1970//1970 -f 2452//2452 1970//1970 2453//2453 -f 2453//2453 1970//1970 1972//1972 -f 2453//2453 1972//1972 1967//1967 -f 1556//1556 2453//2453 1557//1557 -f 1557//1557 2453//2453 1559//1559 -f 1967//1967 1966//1966 2453//2453 -f 2453//2453 1966//1966 2454//2454 -f 2453//2453 2454//2454 1559//1559 -f 1559//1559 2454//2454 1561//1561 -f 1974//1974 2451//2451 1965//1965 -f 1965//1965 2451//2451 2454//2454 -f 1965//1965 2454//2454 1966//1966 -f 1974//1974 1976//1976 2451//2451 -f 2451//2451 1976//1976 1959//1959 -f 2451//2451 1959//1959 1961//1961 -f 2455//2455 1299//1299 1297//1297 -f 1575//1575 2456//2456 1297//1297 -f 1297//1297 2456//2456 2457//2457 -f 1297//1297 2457//2457 2455//2455 -f 1574//1574 2458//2458 1575//1575 -f 1575//1575 2458//2458 2459//2459 -f 1575//1575 2459//2459 2456//2456 -f 1572//1572 2460//2460 1574//1574 -f 1574//1574 2460//2460 2461//2461 -f 1574//1574 2461//2461 2458//2458 -f 1571//1571 2462//2462 1572//1572 -f 1572//1572 2462//2462 2463//2463 -f 1572//1572 2463//2463 2460//2460 -f 1570//1570 2464//2464 1571//1571 -f 1571//1571 2464//2464 2465//2465 -f 1571//1571 2465//2465 2462//2462 -f 1569//1569 2466//2466 1570//1570 -f 1570//1570 2466//2466 2467//2467 -f 1570//1570 2467//2467 2464//2464 -f 1565//1565 2468//2468 1569//1569 -f 1569//1569 2468//2468 2469//2469 -f 1569//1569 2469//2469 2466//2466 -f 1567//1567 2470//2470 1565//1565 -f 1565//1565 2470//2470 2471//2471 -f 1565//1565 2471//2471 2468//2468 -f 1580//1580 2472//2472 1567//1567 -f 1567//1567 2472//2472 2473//2473 -f 1567//1567 2473//2473 2470//2470 -f 1579//1579 2474//2474 1580//1580 -f 1580//1580 2474//2474 2475//2475 -f 1580//1580 2475//2475 2472//2472 -f 1577//1577 2476//2476 1579//1579 -f 1579//1579 2476//2476 2477//2477 -f 1579//1579 2477//2477 2474//2474 -f 1576//1576 2478//2478 1577//1577 -f 1577//1577 2478//2478 2479//2479 -f 1577//1577 2479//2479 2476//2476 -f 1586//1586 2480//2480 1576//1576 -f 1576//1576 2480//2480 2481//2481 -f 1576//1576 2481//2481 2478//2478 -f 1588//1588 2482//2482 1586//1586 -f 1586//1586 2482//2482 2483//2483 -f 1586//1586 2483//2483 2480//2480 -f 1589//1589 2484//2484 1588//1588 -f 1588//1588 2484//2484 2485//2485 -f 1588//1588 2485//2485 2482//2482 -f 1583//1583 2486//2486 1589//1589 -f 1589//1589 2486//2486 2487//2487 -f 1589//1589 2487//2487 2484//2484 -f 1585//1585 2488//2488 1583//1583 -f 1583//1583 2488//2488 2489//2489 -f 1583//1583 2489//2489 2486//2486 -f 1599//1599 2490//2490 1585//1585 -f 1585//1585 2490//2490 2491//2491 -f 1585//1585 2491//2491 2488//2488 -f 2455//2455 2492//2492 1299//1299 -f 1299//1299 2492//2492 2493//2493 -f 1299//1299 2493//2493 1599//1599 -f 1599//1599 2493//2493 2494//2494 -f 1599//1599 2494//2494 2490//2490 -f 2495//2495 2496//2496 2497//2497 -f 2497//2497 2496//2496 2498//2498 -f 2499//2499 2500//2500 2501//2501 -f 2501//2501 2500//2500 2502//2502 -f 2503//2503 2504//2504 2505//2505 -f 2506//2506 2507//2507 2504//2504 -f 2504//2504 2507//2507 2508//2508 -f 2504//2504 2508//2508 2505//2505 -f 2509//2509 2510//2510 2511//2511 -f 2511//2511 2510//2510 2512//2512 -f 2511//2511 2512//2512 2513//2513 -f 2514//2514 2515//2515 2516//2516 -f 2516//2516 2515//2515 2517//2517 -f 2500//2500 2518//2518 2502//2502 -f 2502//2502 2518//2518 2519//2519 -f 2502//2502 2519//2519 2520//2520 -f 2496//2496 2521//2521 2498//2498 -f 2498//2498 2521//2521 2522//2522 -f 2498//2498 2522//2522 2523//2523 -f 2524//2524 2525//2525 2497//2497 -f 2497//2497 2525//2525 2526//2526 -f 2497//2497 2526//2526 2495//2495 -f 2527//2527 2528//2528 2529//2529 -f 2529//2529 2528//2528 2530//2530 -f 2509//2509 2531//2531 2510//2510 -f 2510//2510 2531//2531 2532//2532 -f 2510//2510 2532//2532 2506//2506 -f 2506//2506 2532//2532 2533//2533 -f 2506//2506 2533//2533 2507//2507 -f 2513//2513 2512//2512 2534//2534 -f 2534//2534 2512//2512 2535//2535 -f 2534//2534 2535//2535 2536//2536 -f 2515//2515 2537//2537 2517//2517 -f 2517//2517 2537//2537 2538//2538 -f 2517//2517 2538//2538 2535//2535 -f 2535//2535 2538//2538 2539//2539 -f 2535//2535 2539//2539 2536//2536 -f 2519//2519 2540//2540 2520//2520 -f 2520//2520 2540//2540 2541//2541 -f 2520//2520 2541//2541 2516//2516 -f 2516//2516 2541//2541 2542//2542 -f 2516//2516 2542//2542 2514//2514 -f 2522//2522 2543//2543 2523//2523 -f 2523//2523 2543//2543 2544//2544 -f 2523//2523 2544//2544 2501//2501 -f 2501//2501 2544//2544 2545//2545 -f 2501//2501 2545//2545 2499//2499 -f 2528//2528 2546//2546 2530//2530 -f 2530//2530 2546//2546 2547//2547 -f 2530//2530 2547//2547 2524//2524 -f 2524//2524 2547//2547 2548//2548 -f 2524//2524 2548//2548 2525//2525 -f 2505//2505 2549//2549 2503//2503 -f 2503//2503 2549//2549 2550//2550 -f 2503//2503 2550//2550 2529//2529 -f 2529//2529 2550//2550 2551//2551 -f 2529//2529 2551//2551 2527//2527 -f 2552//2552 2498//2498 2553//2553 -f 2553//2553 2498//2498 2523//2523 -f 2553//2553 2523//2523 2554//2554 -f 2554//2554 2523//2523 2501//2501 -f 2554//2554 2501//2501 2555//2555 -f 2555//2555 2501//2501 2502//2502 -f 2555//2555 2502//2502 2556//2556 -f 2556//2556 2502//2502 2520//2520 -f 2556//2556 2520//2520 2557//2557 -f 2557//2557 2520//2520 2516//2516 -f 2557//2557 2516//2516 2558//2558 -f 2558//2558 2516//2516 2517//2517 -f 2558//2558 2517//2517 2559//2559 -f 2559//2559 2517//2517 2535//2535 -f 2559//2559 2535//2535 2560//2560 -f 2560//2560 2535//2535 2512//2512 -f 2560//2560 2512//2512 2561//2561 -f 2561//2561 2512//2512 2510//2510 -f 2561//2561 2510//2510 2562//2562 -f 2562//2562 2510//2510 2506//2506 -f 2562//2562 2506//2506 2563//2563 -f 2563//2563 2506//2506 2504//2504 -f 2563//2563 2504//2504 2564//2564 -f 2564//2564 2504//2504 2503//2503 -f 2564//2564 2503//2503 2565//2565 -f 2565//2565 2503//2503 2529//2529 -f 2565//2565 2529//2529 2566//2566 -f 2566//2566 2529//2529 2530//2530 -f 2566//2566 2530//2530 2567//2567 -f 2567//2567 2530//2530 2524//2524 -f 2567//2567 2524//2524 2568//2568 -f 2568//2568 2524//2524 2497//2497 -f 2568//2568 2497//2497 2552//2552 -f 2552//2552 2497//2497 2498//2498 -f 2569//2569 2567//2567 2570//2570 -f 2570//2570 2567//2567 2568//2568 -f 2570//2570 2568//2568 2571//2571 -f 2571//2571 2568//2568 2552//2552 -f 2571//2571 2552//2552 2572//2572 -f 2573//2573 2564//2564 2574//2574 -f 2574//2574 2564//2564 2565//2565 -f 2574//2574 2565//2565 2569//2569 -f 2569//2569 2565//2565 2566//2566 -f 2569//2569 2566//2566 2567//2567 -f 2575//2575 2560//2560 2576//2576 -f 2576//2576 2560//2560 2561//2561 -f 2576//2576 2561//2561 2577//2577 -f 2577//2577 2561//2561 2562//2562 -f 2577//2577 2562//2562 2573//2573 -f 2573//2573 2562//2562 2563//2563 -f 2573//2573 2563//2563 2564//2564 -f 2578//2578 2557//2557 2579//2579 -f 2579//2579 2557//2557 2558//2558 -f 2579//2579 2558//2558 2575//2575 -f 2575//2575 2558//2558 2559//2559 -f 2575//2575 2559//2559 2560//2560 -f 2552//2552 2553//2553 2572//2572 -f 2572//2572 2553//2553 2554//2554 -f 2572//2572 2554//2554 2580//2580 -f 2580//2580 2554//2554 2555//2555 -f 2580//2580 2555//2555 2578//2578 -f 2578//2578 2555//2555 2556//2556 -f 2578//2578 2556//2556 2557//2557 -f 2581//2581 2582//2582 2583//2583 -f 2584//2584 2582//2582 2581//2581 -f 2581//2581 2585//2585 2586//2586 -f 2587//2587 2585//2585 2581//2581 -f 2583//2583 2587//2587 2581//2581 -f 2581//2581 2588//2588 2589//2589 -f 2590//2590 2588//2588 2581//2581 -f 2586//2586 2590//2590 2581//2581 -f 2581//2581 2591//2591 2592//2592 -f 2593//2593 2591//2591 2581//2581 -f 2589//2589 2593//2593 2581//2581 -f 2592//2592 2584//2584 2581//2581 -f 2584//2584 2594//2594 2582//2582 -f 2582//2582 2594//2594 2595//2595 -f 2582//2582 2595//2595 2583//2583 -f 2583//2583 2595//2595 2596//2596 -f 2583//2583 2596//2596 2587//2587 -f 2587//2587 2596//2596 2597//2597 -f 2587//2587 2597//2597 2585//2585 -f 2585//2585 2597//2597 2598//2598 -f 2585//2585 2598//2598 2586//2586 -f 2586//2586 2598//2598 2599//2599 -f 2586//2586 2599//2599 2590//2590 -f 2590//2590 2599//2599 2600//2600 -f 2590//2590 2600//2600 2588//2588 -f 2588//2588 2600//2600 2601//2601 -f 2588//2588 2601//2601 2589//2589 -f 2589//2589 2601//2601 2602//2602 -f 2589//2589 2602//2602 2593//2593 -f 2593//2593 2602//2602 2603//2603 -f 2593//2593 2603//2603 2591//2591 -f 2591//2591 2603//2603 2604//2604 -f 2591//2591 2604//2604 2592//2592 -f 2592//2592 2604//2604 2605//2605 -f 2592//2592 2605//2605 2584//2584 -f 2584//2584 2605//2605 2594//2594 -f 2595//2595 1932//1932 2596//2596 -f 2596//2596 1932//1932 1930//1930 -f 2596//2596 1930//1930 2597//2597 -f 2597//2597 1930//1930 1929//1929 -f 2597//2597 1929//1929 2598//2598 -f 2598//2598 1929//1929 1928//1928 -f 2598//2598 1928//1928 2599//2599 -f 2599//2599 1928//1928 1927//1927 -f 2599//2599 1927//1927 2600//2600 -f 2600//2600 1927//1927 1925//1925 -f 2600//2600 1925//1925 2601//2601 -f 2601//2601 1925//1925 1938//1938 -f 2601//2601 1938//1938 2602//2602 -f 2602//2602 1938//1938 1937//1937 -f 2602//2602 1937//1937 2603//2603 -f 2603//2603 1937//1937 1936//1936 -f 2603//2603 1936//1936 2604//2604 -f 2604//2604 1936//1936 1935//1935 -f 2604//2604 1935//1935 2605//2605 -f 2605//2605 1935//1935 1934//1934 -f 2605//2605 1934//1934 2594//2594 -f 2594//2594 1934//1934 1933//1933 -f 2594//2594 1933//1933 2595//2595 -f 2595//2595 1933//1933 1932//1932 -f 2606//2606 2607//2607 2608//2608 -f 2609//2609 2607//2607 2606//2606 -f 2606//2606 2610//2610 2611//2611 -f 2612//2612 2610//2610 2606//2606 -f 2608//2608 2612//2612 2606//2606 -f 2606//2606 2613//2613 2614//2614 -f 2615//2615 2613//2613 2606//2606 -f 2611//2611 2615//2615 2606//2606 -f 2606//2606 2616//2616 2617//2617 -f 2618//2618 2616//2616 2606//2606 -f 2614//2614 2618//2618 2606//2606 -f 2617//2617 2609//2609 2606//2606 -f 2609//2609 2619//2619 2607//2607 -f 2607//2607 2619//2619 2620//2620 -f 2607//2607 2620//2620 2608//2608 -f 2608//2608 2620//2620 2621//2621 -f 2608//2608 2621//2621 2612//2612 -f 2612//2612 2621//2621 2622//2622 -f 2612//2612 2622//2622 2610//2610 -f 2610//2610 2622//2622 2623//2623 -f 2610//2610 2623//2623 2611//2611 -f 2611//2611 2623//2623 2624//2624 -f 2611//2611 2624//2624 2615//2615 -f 2615//2615 2624//2624 2625//2625 -f 2615//2615 2625//2625 2613//2613 -f 2613//2613 2625//2625 2626//2626 -f 2613//2613 2626//2626 2614//2614 -f 2614//2614 2626//2626 2627//2627 -f 2614//2614 2627//2627 2618//2618 -f 2618//2618 2627//2627 2628//2628 -f 2618//2618 2628//2628 2616//2616 -f 2616//2616 2628//2628 2629//2629 -f 2616//2616 2629//2629 2617//2617 -f 2617//2617 2629//2629 2630//2630 -f 2617//2617 2630//2630 2609//2609 -f 2609//2609 2630//2630 2619//2619 -f 2620//2620 1912//1912 2621//2621 -f 2621//2621 1912//1912 1911//1911 -f 2621//2621 1911//1911 2622//2622 -f 2622//2622 1911//1911 1910//1910 -f 2622//2622 1910//1910 2623//2623 -f 2623//2623 1910//1910 1909//1909 -f 2623//2623 1909//1909 2624//2624 -f 2624//2624 1909//1909 1923//1923 -f 2624//2624 1923//1923 2625//2625 -f 2625//2625 1923//1923 1922//1922 -f 2625//2625 1922//1922 2626//2626 -f 2626//2626 1922//1922 1920//1920 -f 2626//2626 1920//1920 2627//2627 -f 2627//2627 1920//1920 1918//1918 -f 2627//2627 1918//1918 2628//2628 -f 2628//2628 1918//1918 1917//1917 -f 2628//2628 1917//1917 2629//2629 -f 2629//2629 1917//1917 1916//1916 -f 2629//2629 1916//1916 2630//2630 -f 2630//2630 1916//1916 1914//1914 -f 2630//2630 1914//1914 2619//2619 -f 2619//2619 1914//1914 1913//1913 -f 2619//2619 1913//1913 2620//2620 -f 2620//2620 1913//1913 1912//1912 -f 2631//2631 2632//2632 2633//2633 -f 2634//2634 2632//2632 2631//2631 -f 2631//2631 2635//2635 2636//2636 -f 2637//2637 2635//2635 2631//2631 -f 2633//2633 2637//2637 2631//2631 -f 2631//2631 2638//2638 2639//2639 -f 2640//2640 2638//2638 2631//2631 -f 2636//2636 2640//2640 2631//2631 -f 2631//2631 2641//2641 2642//2642 -f 2643//2643 2641//2641 2631//2631 -f 2639//2639 2643//2643 2631//2631 -f 2642//2642 2634//2634 2631//2631 -f 2634//2634 2644//2644 2632//2632 -f 2632//2632 2644//2644 2645//2645 -f 2632//2632 2645//2645 2633//2633 -f 2633//2633 2645//2645 2646//2646 -f 2633//2633 2646//2646 2637//2637 -f 2637//2637 2646//2646 2647//2647 -f 2637//2637 2647//2647 2635//2635 -f 2635//2635 2647//2647 2648//2648 -f 2635//2635 2648//2648 2636//2636 -f 2636//2636 2648//2648 2649//2649 -f 2636//2636 2649//2649 2640//2640 -f 2640//2640 2649//2649 2650//2650 -f 2640//2640 2650//2650 2638//2638 -f 2638//2638 2650//2650 2651//2651 -f 2638//2638 2651//2651 2639//2639 -f 2639//2639 2651//2651 2652//2652 -f 2639//2639 2652//2652 2643//2643 -f 2643//2643 2652//2652 2653//2653 -f 2643//2643 2653//2653 2641//2641 -f 2641//2641 2653//2653 2654//2654 -f 2641//2641 2654//2654 2642//2642 -f 2642//2642 2654//2654 2655//2655 -f 2642//2642 2655//2655 2634//2634 -f 2634//2634 2655//2655 2644//2644 -f 2645//2645 1982//1982 2646//2646 -f 2646//2646 1982//1982 1988//1988 -f 2646//2646 1988//1988 2647//2647 -f 2647//2647 1988//1988 1987//1987 -f 2647//2647 1987//1987 2648//2648 -f 2648//2648 1987//1987 1986//1986 -f 2648//2648 1986//1986 2649//2649 -f 2649//2649 1986//1986 1978//1978 -f 2649//2649 1978//1978 2650//2650 -f 2650//2650 1978//1978 1980//1980 -f 2650//2650 1980//1980 2651//2651 -f 2651//2651 1980//1980 1823//1823 -f 2651//2651 1823//1823 2652//2652 -f 2652//2652 1823//1823 1824//1824 -f 2652//2652 1824//1824 2653//2653 -f 2653//2653 1824//1824 1825//1825 -f 2653//2653 1825//1825 2654//2654 -f 2654//2654 1825//1825 1820//1820 -f 2654//2654 1820//1820 2655//2655 -f 2655//2655 1820//1820 1816//1816 -f 2655//2655 1816//1816 2644//2644 -f 2644//2644 1816//1816 1985//1985 -f 2644//2644 1985//1985 2645//2645 -f 2645//2645 1985//1985 1982//1982 -f 2656//2656 2657//2657 2658//2658 -f 2659//2659 2657//2657 2656//2656 -f 2656//2656 2660//2660 2661//2661 -f 2662//2662 2660//2660 2656//2656 -f 2658//2658 2662//2662 2656//2656 -f 2656//2656 2663//2663 2664//2664 -f 2665//2665 2663//2663 2656//2656 -f 2661//2661 2665//2665 2656//2656 -f 2656//2656 2666//2666 2667//2667 -f 2668//2668 2666//2666 2656//2656 -f 2664//2664 2668//2668 2656//2656 -f 2667//2667 2659//2659 2656//2656 -f 2659//2659 2669//2669 2657//2657 -f 2657//2657 2669//2669 2670//2670 -f 2657//2657 2670//2670 2658//2658 -f 2658//2658 2670//2670 2671//2671 -f 2658//2658 2671//2671 2662//2662 -f 2662//2662 2671//2671 2672//2672 -f 2662//2662 2672//2672 2660//2660 -f 2660//2660 2672//2672 2673//2673 -f 2660//2660 2673//2673 2661//2661 -f 2661//2661 2673//2673 2674//2674 -f 2661//2661 2674//2674 2665//2665 -f 2665//2665 2674//2674 2675//2675 -f 2665//2665 2675//2675 2663//2663 -f 2663//2663 2675//2675 2676//2676 -f 2663//2663 2676//2676 2664//2664 -f 2664//2664 2676//2676 2677//2677 -f 2664//2664 2677//2677 2668//2668 -f 2668//2668 2677//2677 2678//2678 -f 2668//2668 2678//2678 2666//2666 -f 2666//2666 2678//2678 2679//2679 -f 2666//2666 2679//2679 2667//2667 -f 2667//2667 2679//2679 2680//2680 -f 2667//2667 2680//2680 2659//2659 -f 2659//2659 2680//2680 2669//2669 -f 2670//2670 1868//1868 2671//2671 -f 2671//2671 1868//1868 1867//1867 -f 2671//2671 1867//1867 2672//2672 -f 2672//2672 1867//1867 1858//1858 -f 2672//2672 1858//1858 2673//2673 -f 2673//2673 1858//1858 1857//1857 -f 2673//2673 1857//1857 2674//2674 -f 2674//2674 1857//1857 1855//1855 -f 2674//2674 1855//1855 2675//2675 -f 2675//2675 1855//1855 1854//1854 -f 2675//2675 1854//1854 2676//2676 -f 2676//2676 1854//1854 1863//1863 -f 2676//2676 1863//1863 2677//2677 -f 2677//2677 1863//1863 1862//1862 -f 2677//2677 1862//1862 2678//2678 -f 2678//2678 1862//1862 1861//1861 -f 2678//2678 1861//1861 2679//2679 -f 2679//2679 1861//1861 1860//1860 -f 2679//2679 1860//1860 2680//2680 -f 2680//2680 1860//1860 1859//1859 -f 2680//2680 1859//1859 2669//2669 -f 2669//2669 1859//1859 1869//1869 -f 2669//2669 1869//1869 2670//2670 -f 2670//2670 1869//1869 1868//1868 -f 1994//1994 2681//2681 1996//1996 -f 1996//1996 2681//2681 2682//2682 -f 1996//1996 2682//2682 1997//1997 -f 1997//1997 2682//2682 2683//2683 -f 1997//1997 2683//2683 1998//1998 -f 1998//1998 2683//2683 2684//2684 -f 1998//1998 2684//2684 1999//1999 -f 1999//1999 2684//2684 2685//2685 -f 1999//1999 2685//2685 2001//2001 -f 2001//2001 2685//2685 2686//2686 -f 2001//2001 2686//2686 2003//2003 -f 2003//2003 2686//2686 2687//2687 -f 2003//2003 2687//2687 2005//2005 -f 2005//2005 2687//2687 2688//2688 -f 2005//2005 2688//2688 2006//2006 -f 2006//2006 2688//2688 2689//2689 -f 2006//2006 2689//2689 1989//1989 -f 1989//1989 2689//2689 2690//2690 -f 1989//1989 2690//2690 1990//1990 -f 1990//1990 2690//2690 2691//2691 -f 1990//1990 2691//2691 1992//1992 -f 1992//1992 2691//2691 2692//2692 -f 1992//1992 2692//2692 1994//1994 -f 1994//1994 2692//2692 2681//2681 -f 2682//2682 2572//2572 2683//2683 -f 2683//2683 2572//2572 2580//2580 -f 2683//2683 2580//2580 2684//2684 -f 2684//2684 2580//2580 2578//2578 -f 2684//2684 2578//2578 2685//2685 -f 2685//2685 2578//2578 2579//2579 -f 2685//2685 2579//2579 2686//2686 -f 2686//2686 2579//2579 2575//2575 -f 2686//2686 2575//2575 2687//2687 -f 2687//2687 2575//2575 2576//2576 -f 2687//2687 2576//2576 2688//2688 -f 2688//2688 2576//2576 2577//2577 -f 2688//2688 2577//2577 2689//2689 -f 2689//2689 2577//2577 2573//2573 -f 2689//2689 2573//2573 2690//2690 -f 2690//2690 2573//2573 2574//2574 -f 2690//2690 2574//2574 2691//2691 -f 2691//2691 2574//2574 2569//2569 -f 2691//2691 2569//2569 2692//2692 -f 2692//2692 2569//2569 2570//2570 -f 2692//2692 2570//2570 2681//2681 -f 2681//2681 2570//2570 2571//2571 -f 2681//2681 2571//2571 2682//2682 -f 2682//2682 2571//2571 2572//2572 -f 2011//2011 2693//2693 2012//2012 -f 2012//2012 2693//2693 2694//2694 -f 2012//2012 2694//2694 2102//2102 -f 2102//2102 2694//2694 2695//2695 -f 2102//2102 2695//2695 2013//2013 -f 2013//2013 2695//2695 2696//2696 -f 2013//2013 2696//2696 2014//2014 -f 2014//2014 2696//2696 2697//2697 -f 2014//2014 2697//2697 2016//2016 -f 2016//2016 2697//2697 2698//2698 -f 2016//2016 2698//2698 2018//2018 -f 2018//2018 2698//2698 2699//2699 -f 2018//2018 2699//2699 2019//2019 -f 2019//2019 2699//2699 2700//2700 -f 2019//2019 2700//2700 2110//2110 -f 2110//2110 2700//2700 2701//2701 -f 2110//2110 2701//2701 2007//2007 -f 2007//2007 2701//2701 2702//2702 -f 2007//2007 2702//2702 2008//2008 -f 2008//2008 2702//2702 2703//2703 -f 2008//2008 2703//2703 2010//2010 -f 2010//2010 2703//2703 2704//2704 -f 2010//2010 2704//2704 2011//2011 -f 2011//2011 2704//2704 2693//2693 -f 2694//2694 1573//1573 2695//2695 -f 2695//2695 1573//1573 1296//1296 -f 2695//2695 1296//1296 2696//2696 -f 2696//2696 1296//1296 1298//1298 -f 2696//2696 1298//1298 2697//2697 -f 2697//2697 1298//1298 1300//1300 -f 2697//2697 1300//1300 2698//2698 -f 2698//2698 1300//1300 1309//1309 -f 2698//2698 1309//1309 2699//2699 -f 2699//2699 1309//1309 1311//1311 -f 2699//2699 1311//1311 2700//2700 -f 2700//2700 1311//1311 1313//1313 -f 2700//2700 1313//1313 2701//2701 -f 2701//2701 1313//1313 1308//1308 -f 2701//2701 1308//1308 2702//2702 -f 2702//2702 1308//1308 1307//1307 -f 2702//2702 1307//1307 2703//2703 -f 2703//2703 1307//1307 1305//1305 -f 2703//2703 1305//1305 2704//2704 -f 2704//2704 1305//1305 1304//1304 -f 2704//2704 1304//1304 2693//2693 -f 2693//2693 1304//1304 1303//1303 -f 2693//2693 1303//1303 2694//2694 -f 2694//2694 1303//1303 1573//1573 -f 2030//2030 2705//2705 2031//2031 -f 2031//2031 2705//2705 2706//2706 -f 2031//2031 2706//2706 2032//2032 -f 2032//2032 2706//2706 2707//2707 -f 2032//2032 2707//2707 2035//2035 -f 2035//2035 2707//2707 2708//2708 -f 2035//2035 2708//2708 2033//2033 -f 2033//2033 2708//2708 2709//2709 -f 2033//2033 2709//2709 2024//2024 -f 2024//2024 2709//2709 2710//2710 -f 2024//2024 2710//2710 2022//2022 -f 2022//2022 2710//2710 2711//2711 -f 2022//2022 2711//2711 2020//2020 -f 2020//2020 2711//2711 2712//2712 -f 2020//2020 2712//2712 2027//2027 -f 2027//2027 2712//2712 2713//2713 -f 2027//2027 2713//2713 2028//2028 -f 2028//2028 2713//2713 2714//2714 -f 2028//2028 2714//2714 2029//2029 -f 2029//2029 2714//2714 2715//2715 -f 2029//2029 2715//2715 2025//2025 -f 2025//2025 2715//2715 2716//2716 -f 2025//2025 2716//2716 2030//2030 -f 2030//2030 2716//2716 2705//2705 -f 2706//2706 1603//1603 2707//2707 -f 2707//2707 1603//1603 1602//1602 -f 2707//2707 1602//1602 2708//2708 -f 2708//2708 1602//1602 1607//1607 -f 2708//2708 1607//1607 2709//2709 -f 2709//2709 1607//1607 1606//1606 -f 2709//2709 1606//1606 2710//2710 -f 2710//2710 1606//1606 1605//1605 -f 2710//2710 1605//1605 2711//2711 -f 2711//2711 1605//1605 1604//1604 -f 2711//2711 1604//1604 2712//2712 -f 2712//2712 1604//1604 1612//1612 -f 2712//2712 1612//1612 2713//2713 -f 2713//2713 1612//1612 1611//1611 -f 2713//2713 1611//1611 2714//2714 -f 2714//2714 1611//1611 1609//1609 -f 2714//2714 1609//1609 2715//2715 -f 2715//2715 1609//1609 1608//1608 -f 2715//2715 1608//1608 2716//2716 -f 2716//2716 1608//1608 1601//1601 -f 2716//2716 1601//1601 2705//2705 -f 2705//2705 1601//1601 1600//1600 -f 2705//2705 1600//1600 2706//2706 -f 2706//2706 1600//1600 1603//1603 -f 2043//2043 2717//2717 2044//2044 -f 2044//2044 2717//2717 2718//2718 -f 2044//2044 2718//2718 2046//2046 -f 2046//2046 2718//2718 2719//2719 -f 2046//2046 2719//2719 2047//2047 -f 2047//2047 2719//2719 2720//2720 -f 2047//2047 2720//2720 2048//2048 -f 2048//2048 2720//2720 2721//2721 -f 2048//2048 2721//2721 2049//2049 -f 2049//2049 2721//2721 2722//2722 -f 2049//2049 2722//2722 2042//2042 -f 2042//2042 2722//2722 2723//2723 -f 2042//2042 2723//2723 2036//2036 -f 2036//2036 2723//2723 2724//2724 -f 2036//2036 2724//2724 2037//2037 -f 2037//2037 2724//2724 2725//2725 -f 2037//2037 2725//2725 2038//2038 -f 2038//2038 2725//2725 2726//2726 -f 2038//2038 2726//2726 2039//2039 -f 2039//2039 2726//2726 2727//2727 -f 2039//2039 2727//2727 2040//2040 -f 2040//2040 2727//2727 2728//2728 -f 2040//2040 2728//2728 2043//2043 -f 2043//2043 2728//2728 2717//2717 -f 2718//2718 1668//1668 2719//2719 -f 2719//2719 1668//1668 1669//1669 -f 2719//2719 1669//1669 2720//2720 -f 2720//2720 1669//1669 1667//1667 -f 2720//2720 1667//1667 2721//2721 -f 2721//2721 1667//1667 1666//1666 -f 2721//2721 1666//1666 2722//2722 -f 2722//2722 1666//1666 1665//1665 -f 2722//2722 1665//1665 2723//2723 -f 2723//2723 1665//1665 1658//1658 -f 2723//2723 1658//1658 2724//2724 -f 2724//2724 1658//1658 1657//1657 -f 2724//2724 1657//1657 2725//2725 -f 2725//2725 1657//1657 1661//1661 -f 2725//2725 1661//1661 2726//2726 -f 2726//2726 1661//1661 1660//1660 -f 2726//2726 1660//1660 2727//2727 -f 2727//2727 1660//1660 1659//1659 -f 2727//2727 1659//1659 2728//2728 -f 2728//2728 1659//1659 1656//1656 -f 2728//2728 1656//1656 2717//2717 -f 2717//2717 1656//1656 1655//1655 -f 2717//2717 1655//1655 2718//2718 -f 2718//2718 1655//1655 1668//1668 -f 2054//2054 2729//2729 2055//2055 -f 2055//2055 2729//2729 2730//2730 -f 2055//2055 2730//2730 2094//2094 -f 2094//2094 2730//2730 2731//2731 -f 2094//2094 2731//2731 2056//2056 -f 2056//2056 2731//2731 2732//2732 -f 2056//2056 2732//2732 2057//2057 -f 2057//2057 2732//2732 2733//2733 -f 2057//2057 2733//2733 2059//2059 -f 2059//2059 2733//2733 2734//2734 -f 2059//2059 2734//2734 2060//2060 -f 2060//2060 2734//2734 2735//2735 -f 2060//2060 2735//2735 2062//2062 -f 2062//2062 2735//2735 2736//2736 -f 2062//2062 2736//2736 2097//2097 -f 2097//2097 2736//2736 2737//2737 -f 2097//2097 2737//2737 2050//2050 -f 2050//2050 2737//2737 2738//2738 -f 2050//2050 2738//2738 2051//2051 -f 2051//2051 2738//2738 2739//2739 -f 2051//2051 2739//2739 2052//2052 -f 2052//2052 2739//2739 2740//2740 -f 2052//2052 2740//2740 2054//2054 -f 2054//2054 2740//2740 2729//2729 -f 2730//2730 1482//1482 2731//2731 -f 2731//2731 1482//1482 1484//1484 -f 2731//2731 1484//1484 2732//2732 -f 2732//2732 1484//1484 1485//1485 -f 2732//2732 1485//1485 2733//2733 -f 2733//2733 1485//1485 1488//1488 -f 2733//2733 1488//1488 2734//2734 -f 2734//2734 1488//1488 1593//1593 -f 2734//2734 1593//1593 2735//2735 -f 2735//2735 1593//1593 1595//1595 -f 2735//2735 1595//1595 2736//2736 -f 2736//2736 1595//1595 1597//1597 -f 2736//2736 1597//1597 2737//2737 -f 2737//2737 1597//1597 1598//1598 -f 2737//2737 1598//1598 2738//2738 -f 2738//2738 1598//1598 1582//1582 -f 2738//2738 1582//1582 2739//2739 -f 2739//2739 1582//1582 1581//1581 -f 2739//2739 1581//1581 2740//2740 -f 2740//2740 1581//1581 1590//1590 -f 2740//2740 1590//1590 2729//2729 -f 2729//2729 1590//1590 1480//1480 -f 2729//2729 1480//1480 2730//2730 -f 2730//2730 1480//1480 1482//1482 -f 2068//2068 2741//2741 2063//2063 -f 2063//2063 2741//2741 2742//2742 -f 2063//2063 2742//2742 2064//2064 -f 2064//2064 2742//2742 2743//2743 -f 2064//2064 2743//2743 2065//2065 -f 2065//2065 2743//2743 2744//2744 -f 2065//2065 2744//2744 2066//2066 -f 2066//2066 2744//2744 2745//2745 -f 2066//2066 2745//2745 2067//2067 -f 2067//2067 2745//2745 2746//2746 -f 2067//2067 2746//2746 2071//2071 -f 2071//2071 2746//2746 2747//2747 -f 2071//2071 2747//2747 2072//2072 -f 2072//2072 2747//2747 2748//2748 -f 2072//2072 2748//2748 2073//2073 -f 2073//2073 2748//2748 2749//2749 -f 2073//2073 2749//2749 2076//2076 -f 2076//2076 2749//2749 2750//2750 -f 2076//2076 2750//2750 2074//2074 -f 2074//2074 2750//2750 2751//2751 -f 2074//2074 2751//2751 2070//2070 -f 2070//2070 2751//2751 2752//2752 -f 2070//2070 2752//2752 2068//2068 -f 2068//2068 2752//2752 2741//2741 -f 2742//2742 1677//1677 2743//2743 -f 2743//2743 1677//1677 1687//1687 -f 2743//2743 1687//1687 2744//2744 -f 2744//2744 1687//1687 1686//1686 -f 2744//2744 1686//1686 2745//2745 -f 2745//2745 1686//1686 1685//1685 -f 2745//2745 1685//1685 2746//2746 -f 2746//2746 1685//1685 1684//1684 -f 2746//2746 1684//1684 2747//2747 -f 2747//2747 1684//1684 1683//1683 -f 2747//2747 1683//1683 2748//2748 -f 2748//2748 1683//1683 1682//1682 -f 2748//2748 1682//1682 2749//2749 -f 2749//2749 1682//1682 1679//1679 -f 2749//2749 1679//1679 2750//2750 -f 2750//2750 1679//1679 1680//1680 -f 2750//2750 1680//1680 2751//2751 -f 2751//2751 1680//1680 1681//1681 -f 2751//2751 1681//1681 2752//2752 -f 2752//2752 1681//1681 1676//1676 -f 2752//2752 1676//1676 2741//2741 -f 2741//2741 1676//1676 1675//1675 -f 2741//2741 1675//1675 2742//2742 -f 2742//2742 1675//1675 1677//1677 -f 2077//2077 2753//2753 2078//2078 -f 2078//2078 2753//2753 2754//2754 -f 2078//2078 2754//2754 2079//2079 -f 2079//2079 2754//2754 2755//2755 -f 2079//2079 2755//2755 2082//2082 -f 2082//2082 2755//2755 2756//2756 -f 2082//2082 2756//2756 2083//2083 -f 2083//2083 2756//2756 2757//2757 -f 2083//2083 2757//2757 2084//2084 -f 2084//2084 2757//2757 2758//2758 -f 2084//2084 2758//2758 2089//2089 -f 2089//2089 2758//2758 2759//2759 -f 2089//2089 2759//2759 2090//2090 -f 2090//2090 2759//2759 2760//2760 -f 2090//2090 2760//2760 2092//2092 -f 2092//2092 2760//2760 2761//2761 -f 2092//2092 2761//2761 2088//2088 -f 2088//2088 2761//2761 2762//2762 -f 2088//2088 2762//2762 2087//2087 -f 2087//2087 2762//2762 2763//2763 -f 2087//2087 2763//2763 2080//2080 -f 2080//2080 2763//2763 2764//2764 -f 2080//2080 2764//2764 2077//2077 -f 2077//2077 2764//2764 2753//2753 -f 2754//2754 1621//1621 2755//2755 -f 2755//2755 1621//1621 1620//1620 -f 2755//2755 1620//1620 2756//2756 -f 2756//2756 1620//1620 1618//1618 -f 2756//2756 1618//1618 2757//2757 -f 2757//2757 1618//1618 1625//1625 -f 2757//2757 1625//1625 2758//2758 -f 2758//2758 1625//1625 1624//1624 -f 2758//2758 1624//1624 2759//2759 -f 2759//2759 1624//1624 1629//1629 -f 2759//2759 1629//1629 2760//2760 -f 2760//2760 1629//1629 1628//1628 -f 2760//2760 1628//1628 2761//2761 -f 2761//2761 1628//1628 1627//1627 -f 2761//2761 1627//1627 2762//2762 -f 2762//2762 1627//1627 1626//1626 -f 2762//2762 1626//1626 2763//2763 -f 2763//2763 1626//1626 1614//1614 -f 2763//2763 1614//1614 2764//2764 -f 2764//2764 1614//1614 1613//1613 -f 2764//2764 1613//1613 2753//2753 -f 2753//2753 1613//1613 1616//1616 -f 2753//2753 1616//1616 2754//2754 -f 2754//2754 1616//1616 1621//1621 -f 2220//2220 2219//2219 2222//2222 -f 2220//2220 2222//2222 2765//2765 -f 2765//2765 2222//2222 2223//2223 -f 2765//2765 2223//2223 2766//2766 -f 2766//2766 2223//2223 1288//1288 -f 2766//2766 1288//1288 1287//1287 -f 1314//1314 2767//2767 2768//2768 -f 2767//2767 2769//2769 2770//2770 -f 2769//2769 2218//2218 2425//2425 -f 2769//2769 2425//2425 2770//2770 -f 2770//2770 2425//2425 2426//2426 -f 2770//2770 2426//2426 2771//2771 -f 2771//2771 2426//2426 2427//2427 -f 2771//2771 2427//2427 2772//2772 -f 2772//2772 2427//2427 2428//2428 -f 2772//2772 2428//2428 2773//2773 -f 2773//2773 2428//2428 2429//2429 -f 2773//2773 2429//2429 2774//2774 -f 2774//2774 2429//2429 2430//2430 -f 2774//2774 2430//2430 2775//2775 -f 2775//2775 2430//2430 2431//2431 -f 2775//2775 2431//2431 2776//2776 -f 2776//2776 2431//2431 2432//2432 -f 2776//2776 2432//2432 2777//2777 -f 2777//2777 2432//2432 2433//2433 -f 2777//2777 2433//2433 2778//2778 -f 2778//2778 2433//2433 2220//2220 -f 2778//2778 2220//2220 2765//2765 -f 2767//2767 2770//2770 2768//2768 -f 2768//2768 2770//2770 2771//2771 -f 2768//2768 2771//2771 2779//2779 -f 2779//2779 2771//2771 2772//2772 -f 2779//2779 2772//2772 2780//2780 -f 2780//2780 2772//2772 2773//2773 -f 2780//2780 2773//2773 2781//2781 -f 2781//2781 2773//2773 2774//2774 -f 2781//2781 2774//2774 2782//2782 -f 2782//2782 2774//2774 2775//2775 -f 2782//2782 2775//2775 2783//2783 -f 2783//2783 2775//2775 2776//2776 -f 2783//2783 2776//2776 2784//2784 -f 2784//2784 2776//2776 2777//2777 -f 2784//2784 2777//2777 2785//2785 -f 2785//2785 2777//2777 2778//2778 -f 2785//2785 2778//2778 2786//2786 -f 2786//2786 2778//2778 2765//2765 -f 2786//2786 2765//2765 2766//2766 -f 1314//1314 2768//2768 1315//1315 -f 1315//1315 2768//2768 2779//2779 -f 1315//1315 2779//2779 1306//1306 -f 1306//1306 2779//2779 2780//2780 -f 1306//1306 2780//2780 1473//1473 -f 1473//1473 2780//2780 2781//2781 -f 1473//1473 2781//2781 1474//1474 -f 1474//1474 2781//2781 2782//2782 -f 1474//1474 2782//2782 1477//1477 -f 1477//1477 2782//2782 2783//2783 -f 1477//1477 2783//2783 1478//1478 -f 1478//1478 2783//2783 2784//2784 -f 1478//1478 2784//2784 1479//1479 -f 1479//1479 2784//2784 2785//2785 -f 1479//1479 2785//2785 1476//1476 -f 1476//1476 2785//2785 2786//2786 -f 1476//1476 2786//2786 1475//1475 -f 1475//1475 2786//2786 2766//2766 -f 1475//1475 2766//2766 1287//1287 -f 1596//1596 1594//1594 2787//2787 -f 2217//2217 2218//2218 2769//2769 -f 2217//2217 2769//2769 2788//2788 -f 2788//2788 2769//2769 2767//2767 -f 2788//2788 2767//2767 2787//2787 -f 1314//1314 1312//1312 2767//2767 -f 2767//2767 1312//1312 1310//1310 -f 2767//2767 1310//1310 2787//2787 -f 2787//2787 1310//1310 1584//1584 -f 2787//2787 1584//1584 1596//1596 -f 1491//1491 2789//2789 2790//2790 -f 2789//2789 2791//2791 2792//2792 -f 2791//2791 2216//2216 2434//2434 -f 2791//2791 2434//2434 2792//2792 -f 2792//2792 2434//2434 2435//2435 -f 2792//2792 2435//2435 2793//2793 -f 2793//2793 2435//2435 2436//2436 -f 2793//2793 2436//2436 2794//2794 -f 2794//2794 2436//2436 2437//2437 -f 2794//2794 2437//2437 2795//2795 -f 2795//2795 2437//2437 2438//2438 -f 2795//2795 2438//2438 2796//2796 -f 2796//2796 2438//2438 2439//2439 -f 2796//2796 2439//2439 2797//2797 -f 2797//2797 2439//2439 2440//2440 -f 2797//2797 2440//2440 2798//2798 -f 2798//2798 2440//2440 2441//2441 -f 2798//2798 2441//2441 2799//2799 -f 2799//2799 2441//2441 2442//2442 -f 2799//2799 2442//2442 2800//2800 -f 2800//2800 2442//2442 2217//2217 -f 2800//2800 2217//2217 2788//2788 -f 2789//2789 2792//2792 2790//2790 -f 2790//2790 2792//2792 2793//2793 -f 2790//2790 2793//2793 2801//2801 -f 2801//2801 2793//2793 2794//2794 -f 2801//2801 2794//2794 2802//2802 -f 2802//2802 2794//2794 2795//2795 -f 2802//2802 2795//2795 2803//2803 -f 2803//2803 2795//2795 2796//2796 -f 2803//2803 2796//2796 2804//2804 -f 2804//2804 2796//2796 2797//2797 -f 2804//2804 2797//2797 2805//2805 -f 2805//2805 2797//2797 2798//2798 -f 2805//2805 2798//2798 2806//2806 -f 2806//2806 2798//2798 2799//2799 -f 2806//2806 2799//2799 2807//2807 -f 2807//2807 2799//2799 2800//2800 -f 2807//2807 2800//2800 2808//2808 -f 2808//2808 2800//2800 2788//2788 -f 2808//2808 2788//2788 2787//2787 -f 1491//1491 2790//2790 1492//1492 -f 1492//1492 2790//2790 2801//2801 -f 1492//1492 2801//2801 1493//1493 -f 1493//1493 2801//2801 2802//2802 -f 1493//1493 2802//2802 1701//1701 -f 1701//1701 2802//2802 2803//2803 -f 1701//1701 2803//2803 1486//1486 -f 1486//1486 2803//2803 2804//2804 -f 1486//1486 2804//2804 1487//1487 -f 1487//1487 2804//2804 2805//2805 -f 1487//1487 2805//2805 1490//1490 -f 1490//1490 2805//2805 2806//2806 -f 1490//1490 2806//2806 1489//1489 -f 1489//1489 2806//2806 2807//2807 -f 1489//1489 2807//2807 1591//1591 -f 1591//1591 2807//2807 2808//2808 -f 1591//1591 2808//2808 1592//1592 -f 1592//1592 2808//2808 2787//2787 -f 1592//1592 2787//2787 1594//1594 -f 2215//2215 2216//2216 2791//2791 -f 2215//2215 2791//2791 2290//2290 -f 2290//2290 2791//2791 2789//2789 -f 2290//2290 2789//2789 2289//2289 -f 2289//2289 2789//2789 1491//1491 -f 2289//2289 1491//1491 1497//1497 -f 2284//2284 1494//1494 1382//1382 -f 2284//2284 1382//1382 2279//2279 -f 2279//2279 1382//1382 1389//1389 -f 2279//2279 1389//1389 1391//1391 -f 2274//2274 1373//1373 1372//1372 -f 2274//2274 1372//1372 2269//2269 -f 2269//2269 1372//1372 1283//1283 -f 2269//2269 1283//1283 1438//1438 -f 2264//2264 1400//1400 2259//2259 -f 2259//2259 1400//1400 1406//1406 -f 2259//2259 1406//1406 1408//1408 -f 2249//2249 2254//2254 1713//1713 -f 1713//1713 1719//1719 2249//2249 -f 2249//2249 1719//1719 1295//1295 -f 2249//2249 1295//1295 1294//1294 -f 1442//1442 1441//1441 2242//2242 -f 2242//2242 1441//1441 1690//1690 -f 2242//2242 1690//1690 2237//2237 -f 2237//2237 1690//1690 1447//1447 -f 2237//2237 1447//1447 1446//1446 -f 1366//1366 1458//1458 2212//2212 -f 2211//2211 1452//1452 1359//1359 -f 2211//2211 1359//1359 2212//2212 -f 2212//2212 1359//1359 1363//1363 -f 2212//2212 1363//1363 1366//1366 -f 1640//1640 2199//2199 1639//1639 -f 1639//1639 2199//2199 2198//2198 -f 1639//1639 2198//2198 1638//1638 -f 1638//1638 2198//2198 1637//1637 -f 1636//1636 2152//2152 1635//1635 -f 1635//1635 2152//2152 2151//2151 -f 1635//1635 2151//2151 1634//1634 -f 1466//1466 1471//1471 2146//2146 -f 1466//1466 2146//2146 1465//1465 -f 1465//1465 2146//2146 2145//2145 -f 1465//1465 2145//2145 1464//1464 -f 2139//2139 1630//1630 1631//1631 -f 2139//2139 1631//1631 2140//2140 -f 2140//2140 1631//1631 1632//1632 -f 2140//2140 1632//1632 1633//1633 -f 1786//1786 2141//2141 1787//1787 -f 1787//1787 2141//2141 2142//2142 -f 1796//1796 2138//2138 1797//1797 -f 1797//1797 2138//2138 2137//2137 -f 1797//1797 2137//2137 1794//1794 -f 1799//1799 2147//2147 1800//1800 -f 1800//1800 2147//2147 2148//2148 -f 1784//1784 2144//2144 1785//1785 -f 1785//1785 2144//2144 2143//2143 -f 1805//1805 2153//2153 1806//1806 -f 1806//1806 2153//2153 2154//2154 -f 2115//2115 2150//2150 2114//2114 -f 2114//2114 2150//2150 2149//2149 -f 1983//1983 2200//2200 1984//1984 -f 1984//1984 2200//2200 2201//2201 -f 1822//1822 2197//2197 1821//1821 -f 1821//1821 2197//2197 2196//2196 -f 1905//1905 2282//2282 1904//1904 -f 1904//1904 2282//2282 2281//2281 -f 1901//1901 2286//2286 1890//1890 -f 1890//1890 2286//2286 2280//2280 -f 1890//1890 2280//2280 1891//1891 -f 1896//1896 2272//2272 1897//1897 -f 1897//1897 2272//2272 2271//2271 -f 1892//1892 2276//2276 1893//1893 -f 1893//1893 2276//2276 2270//2270 -f 1882//1882 2262//2262 1881//1881 -f 1881//1881 2262//2262 2261//2261 -f 1876//1876 2266//2266 1877//1877 -f 1877//1877 2266//2266 2260//2260 -f 1781//1781 2252//2252 1782//1782 -f 1782//1782 2252//2252 2251//2251 -f 1865//1865 2256//2256 1864//1864 -f 1864//1864 2256//2256 2250//2250 -f 2107//2107 2213//2213 1831//1831 -f 1831//1831 2213//2213 2214//2214 -f 1831//1831 2214//2214 1830//1830 -f 1832//1832 2210//2210 1833//1833 -f 1833//1833 2210//2210 2209//2209 -f 1845//1845 2244//2244 1844//1844 -f 1844//1844 2244//2244 2238//2238 -f 1850//1850 2240//2240 1848//1848 -f 1848//1848 2240//2240 2239//2239 -f 2288//2288 1496//1496 2287//2287 -f 2287//2287 1496//1496 1495//1495 -f 2278//2278 1377//1377 2277//2277 -f 2277//2277 1377//1377 1375//1375 -f 2268//2268 1439//1439 2267//2267 -f 2267//2267 1439//1439 1402//1402 -f 2258//2258 1397//1397 2257//2257 -f 2257//2257 1397//1397 1395//1395 -f 2248//2248 1293//1293 2247//2247 -f 2247//2247 1293//1293 1445//1445 -f 2246//2246 1445//1445 2245//2245 -f 2245//2245 1445//1445 1443//1443 -f 2224//2224 1290//1290 2221//2221 -f 2221//2221 1290//1290 1472//1472 -f 2226//2226 1468//1468 2225//2225 -f 2225//2225 1468//1468 1318//1318 -f 2228//2228 1343//1343 2227//2227 -f 2227//2227 1343//1343 1463//1463 -f 2230//2230 1499//1499 2229//2229 -f 2229//2229 1499//1499 1334//1334 -f 2234//2234 1459//1459 2233//2233 -f 2233//2233 1459//1459 1460//1460 -f 2232//2232 1460//1460 2231//2231 -f 2231//2231 1460//1460 1457//1457 -f 1453//1453 2235//2235 1454//1454 -f 1454//1454 2235//2235 2236//2236 -f 1454//1454 2236//2236 1449//1449 -f 1449//1449 2236//2236 1448//1448 -f 2448//2448 1553//1553 1622//1622 -f 1623//1623 1540//1540 2445//2445 -f 1623//1623 2445//2445 1622//1622 -f 1622//1622 2445//2445 2446//2446 -f 1622//1622 2446//2446 2448//2448 -f 1549//1549 2447//2447 1545//1545 -f 1545//1545 2447//2447 2443//2443 -f 1545//1545 2443//2443 1546//1546 -f 1546//1546 2443//2443 2444//2444 -f 1546//1546 2444//2444 1672//1672 -f 1563//1563 1561//1561 2454//2454 -f 1662//1662 1564//1564 2450//2450 -f 2450//2450 1564//1564 1563//1563 -f 2450//2450 1563//1563 2451//2451 -f 2451//2451 1563//1563 2454//2454 -f 2453//2453 1556//1556 2452//2452 -f 2452//2452 1556//1556 1555//1555 -f 2452//2452 1555//1555 2449//2449 -f 2449//2449 1555//1555 1285//1285 -f 2449//2449 1285//1285 1284//1284 -f 2447//2447 1549//1549 1548//1548 -f 2447//2447 1548//1548 2448//2448 -f 2448//2448 1548//1548 1551//1551 -f 2448//2448 1551//1551 1553//1553 -f 2449//2449 1284//1284 1664//1664 -f 2449//2449 1664//1664 2450//2450 -f 2450//2450 1664//1664 1663//1663 -f 2450//2450 1663//1663 1662//1662 -f 2294//2294 1421//1421 1420//1420 -f 2294//2294 1420//1420 2809//2809 -f 2809//2809 1420//1420 1419//1419 -f 2809//2809 1419//1419 2810//2810 -f 2810//2810 1419//1419 1425//1425 -f 2810//2810 1425//1425 2296//2296 -f 2302//2302 2300//2300 2811//2811 -f 2302//2302 2811//2811 2812//2812 -f 2812//2812 2811//2811 2813//2813 -f 2812//2812 2813//2813 2814//2814 -f 2814//2814 2813//2813 2293//2293 -f 2814//2814 2293//2293 2294//2294 -f 2291//2291 1417//1417 1416//1416 -f 2291//2291 1416//1416 2815//2815 -f 2815//2815 1416//1416 1727//1727 -f 2815//2815 1727//1727 2816//2816 -f 2816//2816 1727//1727 1423//1423 -f 2816//2816 1423//1423 2293//2293 -f 2296//2296 2817//2817 2818//2818 -f 2302//2302 2812//2812 2819//2819 -f 2817//2817 2820//2820 2818//2818 -f 2818//2818 2820//2820 2819//2819 -f 2818//2818 2819//2819 2821//2821 -f 2821//2821 2819//2819 2812//2812 -f 2821//2821 2812//2812 2814//2814 -f 2296//2296 2818//2818 2810//2810 -f 2810//2810 2818//2818 2821//2821 -f 2810//2810 2821//2821 2809//2809 -f 2809//2809 2821//2821 2814//2814 -f 2809//2809 2814//2814 2294//2294 -f 2820//2820 2302//2302 2819//2819 -f 2817//2817 2822//2822 2820//2820 -f 2820//2820 2822//2822 2302//2302 -f 2293//2293 2813//2813 2823//2823 -f 2300//2300 2824//2824 2825//2825 -f 2813//2813 2826//2826 2823//2823 -f 2823//2823 2826//2826 2825//2825 -f 2823//2823 2825//2825 2827//2827 -f 2827//2827 2825//2825 2824//2824 -f 2827//2827 2824//2824 2828//2828 -f 2293//2293 2823//2823 2816//2816 -f 2816//2816 2823//2823 2827//2827 -f 2816//2816 2827//2827 2815//2815 -f 2815//2815 2827//2827 2828//2828 -f 2815//2815 2828//2828 2291//2291 -f 2826//2826 2300//2300 2825//2825 -f 2813//2813 2811//2811 2826//2826 -f 2826//2826 2811//2811 2300//2300 -f 2295//2295 1433//1433 1431//1431 -f 2295//2295 1431//1431 2829//2829 -f 2829//2829 1431//1431 1430//1430 -f 2829//2829 1430//1430 2830//2830 -f 2830//2830 1430//1430 1428//1428 -f 2830//2830 1428//1428 2298//2298 -f 2301//2301 2302//2302 2822//2822 -f 2301//2301 2822//2822 2831//2831 -f 2831//2831 2822//2822 2817//2817 -f 2831//2831 2817//2817 2832//2832 -f 2832//2832 2817//2817 2296//2296 -f 2832//2832 2296//2296 2295//2295 -f 2300//2300 2299//2299 2833//2833 -f 2300//2300 2833//2833 2824//2824 -f 2824//2824 2833//2833 2834//2834 -f 2824//2824 2834//2834 2828//2828 -f 2828//2828 2834//2834 2292//2292 -f 2828//2828 2292//2292 2291//2291 -f 2297//2297 1532//1532 1530//1530 -f 2297//2297 1530//1530 2835//2835 -f 2835//2835 1530//1530 1451//1451 -f 2835//2835 1451//1451 2836//2836 -f 2836//2836 1451//1451 1437//1437 -f 2836//2836 1437//1437 2292//2292 -f 2298//2298 2837//2837 2838//2838 -f 2301//2301 2831//2831 2839//2839 -f 2837//2837 2840//2840 2838//2838 -f 2838//2838 2840//2840 2839//2839 -f 2838//2838 2839//2839 2841//2841 -f 2841//2841 2839//2839 2831//2831 -f 2841//2841 2831//2831 2832//2832 -f 2298//2298 2838//2838 2830//2830 -f 2830//2830 2838//2838 2841//2841 -f 2830//2830 2841//2841 2829//2829 -f 2829//2829 2841//2841 2832//2832 -f 2829//2829 2832//2832 2295//2295 -f 2840//2840 2301//2301 2839//2839 -f 2837//2837 2842//2842 2840//2840 -f 2840//2840 2842//2842 2301//2301 -f 2292//2292 2834//2834 2843//2843 -f 2299//2299 2844//2844 2845//2845 -f 2834//2834 2846//2846 2843//2843 -f 2843//2843 2846//2846 2845//2845 -f 2843//2843 2845//2845 2847//2847 -f 2847//2847 2845//2845 2844//2844 -f 2847//2847 2844//2844 2848//2848 -f 2292//2292 2843//2843 2836//2836 -f 2836//2836 2843//2843 2847//2847 -f 2836//2836 2847//2847 2835//2835 -f 2835//2835 2847//2847 2848//2848 -f 2835//2835 2848//2848 2297//2297 -f 2846//2846 2299//2299 2845//2845 -f 2834//2834 2833//2833 2846//2846 -f 2846//2846 2833//2833 2299//2299 -f 2299//2299 2301//2301 2842//2842 -f 2299//2299 2842//2842 2844//2844 -f 2844//2844 2842//2842 2837//2837 -f 2844//2844 2837//2837 2848//2848 -f 2848//2848 2837//2837 2298//2298 -f 2848//2848 2298//2298 2297//2297 -f 2306//2306 1524//1524 1523//1523 -f 2306//2306 1523//1523 2849//2849 -f 2849//2849 1523//1523 1522//1522 -f 2849//2849 1522//1522 2850//2850 -f 2850//2850 1522//1522 1521//1521 -f 2850//2850 1521//1521 2307//2307 -f 2305//2305 2306//2306 2851//2851 -f 2305//2305 2851//2851 2852//2852 -f 2852//2852 2851//2851 2853//2853 -f 2852//2852 2853//2853 2854//2854 -f 2854//2854 2853//2853 2314//2314 -f 2854//2854 2314//2314 2312//2312 -f 2303//2303 1507//1507 1509//1509 -f 2303//2303 1509//1509 2855//2855 -f 2855//2855 1509//1509 1518//1518 -f 2855//2855 1518//1518 2856//2856 -f 2856//2856 1518//1518 1520//1520 -f 2856//2856 1520//1520 2305//2305 -f 2307//2307 2857//2857 2858//2858 -f 2314//2314 2853//2853 2859//2859 -f 2857//2857 2860//2860 2858//2858 -f 2858//2858 2860//2860 2859//2859 -f 2858//2858 2859//2859 2861//2861 -f 2861//2861 2859//2859 2853//2853 -f 2861//2861 2853//2853 2851//2851 -f 2307//2307 2858//2858 2850//2850 -f 2850//2850 2858//2858 2861//2861 -f 2850//2850 2861//2861 2849//2849 -f 2849//2849 2861//2861 2851//2851 -f 2849//2849 2851//2851 2306//2306 -f 2860//2860 2314//2314 2859//2859 -f 2857//2857 2862//2862 2860//2860 -f 2860//2860 2862//2862 2314//2314 -f 2305//2305 2852//2852 2863//2863 -f 2312//2312 2864//2864 2865//2865 -f 2852//2852 2866//2866 2863//2863 -f 2863//2863 2866//2866 2865//2865 -f 2863//2863 2865//2865 2867//2867 -f 2867//2867 2865//2865 2864//2864 -f 2867//2867 2864//2864 2868//2868 -f 2305//2305 2863//2863 2856//2856 -f 2856//2856 2863//2863 2867//2867 -f 2856//2856 2867//2867 2855//2855 -f 2855//2855 2867//2867 2868//2868 -f 2855//2855 2868//2868 2303//2303 -f 2866//2866 2312//2312 2865//2865 -f 2852//2852 2854//2854 2866//2866 -f 2866//2866 2854//2854 2312//2312 -f 2308//2308 1526//1526 1531//1531 -f 2308//2308 1531//1531 2869//2869 -f 2869//2869 1531//1531 1539//1539 -f 2869//2869 1539//1539 2870//2870 -f 2870//2870 1539//1539 1538//1538 -f 2870//2870 1538//1538 2309//2309 -f 2307//2307 2308//2308 2871//2871 -f 2307//2307 2871//2871 2857//2857 -f 2857//2857 2871//2871 2872//2872 -f 2857//2857 2872//2872 2862//2862 -f 2862//2862 2872//2872 2313//2313 -f 2862//2862 2313//2313 2314//2314 -f 2304//2304 2303//2303 2868//2868 -f 2304//2304 2868//2868 2873//2873 -f 2873//2873 2868//2868 2864//2864 -f 2873//2873 2864//2864 2874//2874 -f 2874//2874 2864//2864 2312//2312 -f 2874//2874 2312//2312 2311//2311 -f 2310//2310 1533//1533 1337//1337 -f 2310//2310 1337//1337 2875//2875 -f 2875//2875 1337//1337 1336//1336 -f 2875//2875 1336//1336 2876//2876 -f 2876//2876 1336//1336 1504//1504 -f 2876//2876 1504//1504 2304//2304 -f 2309//2309 2877//2877 2878//2878 -f 2313//2313 2872//2872 2879//2879 -f 2877//2877 2880//2880 2878//2878 -f 2878//2878 2880//2880 2879//2879 -f 2878//2878 2879//2879 2881//2881 -f 2881//2881 2879//2879 2872//2872 -f 2881//2881 2872//2872 2871//2871 -f 2309//2309 2878//2878 2870//2870 -f 2870//2870 2878//2878 2881//2881 -f 2870//2870 2881//2881 2869//2869 -f 2869//2869 2881//2881 2871//2871 -f 2869//2869 2871//2871 2308//2308 -f 2880//2880 2313//2313 2879//2879 -f 2877//2877 2882//2882 2880//2880 -f 2880//2880 2882//2882 2313//2313 -f 2304//2304 2873//2873 2883//2883 -f 2311//2311 2884//2884 2885//2885 -f 2873//2873 2886//2886 2883//2883 -f 2883//2883 2886//2886 2885//2885 -f 2883//2883 2885//2885 2887//2887 -f 2887//2887 2885//2885 2884//2884 -f 2887//2887 2884//2884 2888//2888 -f 2304//2304 2883//2883 2876//2876 -f 2876//2876 2883//2883 2887//2887 -f 2876//2876 2887//2887 2875//2875 -f 2875//2875 2887//2887 2888//2888 -f 2875//2875 2888//2888 2310//2310 -f 2886//2886 2311//2311 2885//2885 -f 2873//2873 2874//2874 2886//2886 -f 2886//2886 2874//2874 2311//2311 -f 2309//2309 2310//2310 2888//2888 -f 2309//2309 2888//2888 2877//2877 -f 2877//2877 2888//2888 2884//2884 -f 2877//2877 2884//2884 2882//2882 -f 2882//2882 2884//2884 2311//2311 -f 2882//2882 2311//2311 2313//2313 -f 2521//2521 2889//2889 2522//2522 -f 2522//2522 2889//2889 2890//2890 -f 2522//2522 2890//2890 2543//2543 -f 2543//2543 2890//2890 2891//2891 -f 2543//2543 2891//2891 2544//2544 -f 2544//2544 2891//2891 2892//2892 -f 2544//2544 2892//2892 2545//2545 -f 2545//2545 2892//2892 2893//2893 -f 2545//2545 2893//2893 2499//2499 -f 2499//2499 2893//2893 2894//2894 -f 2499//2499 2894//2894 2500//2500 -f 2500//2500 2894//2894 2895//2895 -f 2500//2500 2895//2895 2518//2518 -f 2518//2518 2895//2895 2896//2896 -f 2518//2518 2896//2896 2519//2519 -f 2519//2519 2896//2896 2897//2897 -f 2519//2519 2897//2897 2540//2540 -f 2540//2540 2897//2897 2898//2898 -f 2540//2540 2898//2898 2541//2541 -f 2541//2541 2898//2898 2899//2899 -f 2541//2541 2899//2899 2542//2542 -f 2542//2542 2899//2899 2900//2900 -f 2542//2542 2900//2900 2514//2514 -f 2514//2514 2900//2900 2901//2901 -f 2514//2514 2901//2901 2515//2515 -f 2515//2515 2901//2901 2902//2902 -f 2515//2515 2902//2902 2537//2537 -f 2537//2537 2902//2902 2903//2903 -f 2537//2537 2903//2903 2538//2538 -f 2538//2538 2903//2903 2904//2904 -f 2538//2538 2904//2904 2539//2539 -f 2539//2539 2904//2904 2905//2905 -f 2539//2539 2905//2905 2536//2536 -f 2536//2536 2905//2905 2906//2906 -f 2536//2536 2906//2906 2534//2534 -f 2534//2534 2906//2906 2907//2907 -f 2534//2534 2907//2907 2513//2513 -f 2513//2513 2907//2907 2908//2908 -f 2513//2513 2908//2908 2511//2511 -f 2511//2511 2908//2908 2909//2909 -f 2511//2511 2909//2909 2509//2509 -f 2509//2509 2909//2909 2910//2910 -f 2509//2509 2910//2910 2531//2531 -f 2531//2531 2910//2910 2911//2911 -f 2531//2531 2911//2911 2532//2532 -f 2532//2532 2911//2911 2912//2912 -f 2532//2532 2912//2912 2533//2533 -f 2533//2533 2912//2912 2913//2913 -f 2533//2533 2913//2913 2507//2507 -f 2507//2507 2913//2913 2914//2914 -f 2507//2507 2914//2914 2508//2508 -f 2508//2508 2914//2914 2915//2915 -f 2508//2508 2915//2915 2505//2505 -f 2505//2505 2915//2915 2916//2916 -f 2505//2505 2916//2916 2549//2549 -f 2549//2549 2916//2916 2917//2917 -f 2549//2549 2917//2917 2550//2550 -f 2550//2550 2917//2917 2918//2918 -f 2550//2550 2918//2918 2551//2551 -f 2551//2551 2918//2918 2919//2919 -f 2551//2551 2919//2919 2527//2527 -f 2527//2527 2919//2919 2920//2920 -f 2527//2527 2920//2920 2528//2528 -f 2528//2528 2920//2920 2921//2921 -f 2528//2528 2921//2921 2546//2546 -f 2546//2546 2921//2921 2922//2922 -f 2546//2546 2922//2922 2547//2547 -f 2547//2547 2922//2922 2923//2923 -f 2547//2547 2923//2923 2548//2548 -f 2548//2548 2923//2923 2924//2924 -f 2548//2548 2924//2924 2525//2525 -f 2525//2525 2924//2924 2925//2925 -f 2525//2525 2925//2925 2526//2526 -f 2526//2526 2925//2925 2926//2926 -f 2526//2526 2926//2926 2495//2495 -f 2495//2495 2926//2926 2927//2927 -f 2495//2495 2927//2927 2496//2496 -f 2496//2496 2927//2927 2928//2928 -f 2496//2496 2928//2928 2521//2521 -f 2521//2521 2928//2928 2889//2889 -f 2928//2928 2929//2929 2889//2889 -f 2889//2889 2929//2929 2930//2930 -f 2889//2889 2930//2930 2890//2890 -f 2890//2890 2930//2930 2931//2931 -f 2890//2890 2931//2931 2891//2891 -f 2891//2891 2931//2931 2932//2932 -f 2891//2891 2932//2932 2892//2892 -f 2892//2892 2932//2932 2933//2933 -f 2892//2892 2933//2933 2893//2893 -f 2893//2893 2933//2933 2934//2934 -f 2893//2893 2934//2934 2894//2894 -f 2894//2894 2934//2934 2935//2935 -f 2894//2894 2935//2935 2895//2895 -f 2895//2895 2935//2935 2936//2936 -f 2895//2895 2936//2936 2896//2896 -f 2896//2896 2936//2936 2937//2937 -f 2896//2896 2937//2937 2897//2897 -f 2897//2897 2937//2937 2938//2938 -f 2897//2897 2938//2938 2898//2898 -f 2898//2898 2938//2938 2939//2939 -f 2898//2898 2939//2939 2899//2899 -f 2899//2899 2939//2939 2940//2940 -f 2899//2899 2940//2940 2900//2900 -f 2900//2900 2940//2940 2941//2941 -f 2900//2900 2941//2941 2901//2901 -f 2901//2901 2941//2941 2942//2942 -f 2901//2901 2942//2942 2902//2902 -f 2902//2902 2942//2942 2943//2943 -f 2902//2902 2943//2943 2903//2903 -f 2903//2903 2943//2943 2944//2944 -f 2903//2903 2944//2944 2904//2904 -f 2904//2904 2944//2944 2945//2945 -f 2904//2904 2945//2945 2905//2905 -f 2905//2905 2945//2945 2946//2946 -f 2905//2905 2946//2946 2906//2906 -f 2906//2906 2946//2946 2947//2947 -f 2906//2906 2947//2947 2907//2907 -f 2907//2907 2947//2947 2948//2948 -f 2907//2907 2948//2948 2908//2908 -f 2908//2908 2948//2948 2949//2949 -f 2908//2908 2949//2949 2909//2909 -f 2909//2909 2949//2949 2950//2950 -f 2909//2909 2950//2950 2910//2910 -f 2910//2910 2950//2950 2951//2951 -f 2910//2910 2951//2951 2911//2911 -f 2911//2911 2951//2951 2952//2952 -f 2911//2911 2952//2952 2912//2912 -f 2912//2912 2952//2952 2953//2953 -f 2912//2912 2953//2953 2913//2913 -f 2913//2913 2953//2953 2954//2954 -f 2913//2913 2954//2954 2914//2914 -f 2914//2914 2954//2954 2955//2955 -f 2914//2914 2955//2955 2915//2915 -f 2915//2915 2955//2955 2956//2956 -f 2915//2915 2956//2956 2916//2916 -f 2916//2916 2956//2956 2957//2957 -f 2916//2916 2957//2957 2917//2917 -f 2917//2917 2957//2957 2958//2958 -f 2917//2917 2958//2958 2918//2918 -f 2918//2918 2958//2958 2959//2959 -f 2918//2918 2959//2959 2919//2919 -f 2919//2919 2959//2959 2960//2960 -f 2919//2919 2960//2960 2920//2920 -f 2920//2920 2960//2960 2961//2961 -f 2920//2920 2961//2961 2921//2921 -f 2921//2921 2961//2961 2962//2962 -f 2921//2921 2962//2962 2922//2922 -f 2922//2922 2962//2962 2963//2963 -f 2922//2922 2963//2963 2923//2923 -f 2923//2923 2963//2963 2964//2964 -f 2923//2923 2964//2964 2924//2924 -f 2924//2924 2964//2964 2965//2965 -f 2924//2924 2965//2965 2925//2925 -f 2925//2925 2965//2965 2966//2966 -f 2925//2925 2966//2966 2926//2926 -f 2926//2926 2966//2966 2967//2967 -f 2926//2926 2967//2967 2927//2927 -f 2927//2927 2967//2967 2968//2968 -f 2927//2927 2968//2968 2928//2928 -f 2928//2928 2968//2968 2929//2929 -f 2968//2968 2474//2474 2929//2929 -f 2929//2929 2474//2474 2477//2477 -f 2929//2929 2477//2477 2930//2930 -f 2930//2930 2477//2477 2476//2476 -f 2930//2930 2476//2476 2931//2931 -f 2931//2931 2476//2476 2479//2479 -f 2931//2931 2479//2479 2932//2932 -f 2932//2932 2479//2479 2478//2478 -f 2932//2932 2478//2478 2933//2933 -f 2933//2933 2478//2478 2481//2481 -f 2933//2933 2481//2481 2934//2934 -f 2934//2934 2481//2481 2480//2480 -f 2934//2934 2480//2480 2935//2935 -f 2935//2935 2480//2480 2483//2483 -f 2935//2935 2483//2483 2936//2936 -f 2936//2936 2483//2483 2482//2482 -f 2936//2936 2482//2482 2937//2937 -f 2937//2937 2482//2482 2485//2485 -f 2937//2937 2485//2485 2938//2938 -f 2938//2938 2485//2485 2484//2484 -f 2938//2938 2484//2484 2939//2939 -f 2939//2939 2484//2484 2487//2487 -f 2939//2939 2487//2487 2940//2940 -f 2940//2940 2487//2487 2486//2486 -f 2940//2940 2486//2486 2941//2941 -f 2941//2941 2486//2486 2489//2489 -f 2941//2941 2489//2489 2942//2942 -f 2942//2942 2489//2489 2488//2488 -f 2942//2942 2488//2488 2943//2943 -f 2943//2943 2488//2488 2491//2491 -f 2943//2943 2491//2491 2944//2944 -f 2944//2944 2491//2491 2490//2490 -f 2944//2944 2490//2490 2945//2945 -f 2945//2945 2490//2490 2494//2494 -f 2945//2945 2494//2494 2946//2946 -f 2946//2946 2494//2494 2493//2493 -f 2946//2946 2493//2493 2947//2947 -f 2947//2947 2493//2493 2492//2492 -f 2947//2947 2492//2492 2948//2948 -f 2948//2948 2492//2492 2455//2455 -f 2948//2948 2455//2455 2949//2949 -f 2949//2949 2455//2455 2457//2457 -f 2949//2949 2457//2457 2950//2950 -f 2950//2950 2457//2457 2456//2456 -f 2950//2950 2456//2456 2951//2951 -f 2951//2951 2456//2456 2459//2459 -f 2951//2951 2459//2459 2952//2952 -f 2952//2952 2459//2459 2458//2458 -f 2952//2952 2458//2458 2953//2953 -f 2953//2953 2458//2458 2461//2461 -f 2953//2953 2461//2461 2954//2954 -f 2954//2954 2461//2461 2460//2460 -f 2954//2954 2460//2460 2955//2955 -f 2955//2955 2460//2460 2463//2463 -f 2955//2955 2463//2463 2956//2956 -f 2956//2956 2463//2463 2462//2462 -f 2956//2956 2462//2462 2957//2957 -f 2957//2957 2462//2462 2465//2465 -f 2957//2957 2465//2465 2958//2958 -f 2958//2958 2465//2465 2464//2464 -f 2958//2958 2464//2464 2959//2959 -f 2959//2959 2464//2464 2467//2467 -f 2959//2959 2467//2467 2960//2960 -f 2960//2960 2467//2467 2466//2466 -f 2960//2960 2466//2466 2961//2961 -f 2961//2961 2466//2466 2469//2469 -f 2961//2961 2469//2469 2962//2962 -f 2962//2962 2469//2469 2468//2468 -f 2962//2962 2468//2468 2963//2963 -f 2963//2963 2468//2468 2471//2471 -f 2963//2963 2471//2471 2964//2964 -f 2964//2964 2471//2471 2470//2470 -f 2964//2964 2470//2470 2965//2965 -f 2965//2965 2470//2470 2473//2473 -f 2965//2965 2473//2473 2966//2966 -f 2966//2966 2473//2473 2472//2472 -f 2966//2966 2472//2472 2967//2967 -f 2967//2967 2472//2472 2475//2475 -f 2967//2967 2475//2475 2968//2968 -f 2968//2968 2475//2475 2474//2474 -f 2969//2969 2970//2970 2971//2971 -f 2972//2972 2973//2973 2970//2970 -f 2970//2970 2973//2973 2974//2974 -f 2970//2970 2974//2974 2971//2971 -f 2975//2975 2976//2976 2972//2972 -f 2972//2972 2976//2976 2977//2977 -f 2972//2972 2977//2977 2973//2973 -f 2978//2978 2979//2979 2975//2975 -f 2975//2975 2979//2979 2980//2980 -f 2975//2975 2980//2980 2976//2976 -f 2981//2981 2982//2982 2978//2978 -f 2978//2978 2982//2982 2983//2983 -f 2978//2978 2983//2983 2979//2979 -f 2984//2984 2985//2985 2981//2981 -f 2981//2981 2985//2985 2986//2986 -f 2981//2981 2986//2986 2982//2982 -f 2987//2987 2988//2988 2984//2984 -f 2984//2984 2988//2988 2989//2989 -f 2984//2984 2989//2989 2985//2985 -f 2990//2990 2991//2991 2987//2987 -f 2987//2987 2991//2991 2992//2992 -f 2987//2987 2992//2992 2988//2988 -f 2993//2993 2994//2994 2990//2990 -f 2990//2990 2994//2994 2995//2995 -f 2990//2990 2995//2995 2991//2991 -f 2996//2996 2997//2997 2993//2993 -f 2993//2993 2997//2997 2998//2998 -f 2993//2993 2998//2998 2994//2994 -f 2999//2999 3000//3000 2996//2996 -f 2996//2996 3000//3000 3001//3001 -f 2996//2996 3001//3001 2997//2997 -f 3002//3002 3003//3003 2999//2999 -f 2999//2999 3003//3003 3004//3004 -f 2999//2999 3004//3004 3000//3000 -f 3005//3005 3006//3006 3002//3002 -f 3002//3002 3006//3006 3007//3007 -f 3002//3002 3007//3007 3003//3003 -f 3008//3008 3009//3009 3005//3005 -f 3005//3005 3009//3009 3010//3010 -f 3005//3005 3010//3010 3006//3006 -f 3011//3011 3012//3012 3008//3008 -f 3008//3008 3012//3012 3013//3013 -f 3008//3008 3013//3013 3009//3009 -f 3014//3014 3015//3015 3011//3011 -f 3011//3011 3015//3015 3016//3016 -f 3011//3011 3016//3016 3012//3012 -f 3017//3017 3018//3018 3014//3014 -f 3014//3014 3018//3018 3019//3019 -f 3014//3014 3019//3019 3015//3015 -f 3020//3020 3021//3021 3017//3017 -f 3017//3017 3021//3021 3022//3022 -f 3017//3017 3022//3022 3018//3018 -f 2971//2971 3023//3023 2969//2969 -f 2969//2969 3023//3023 3024//3024 -f 2969//2969 3024//3024 3020//3020 -f 3020//3020 3024//3024 3025//3025 -f 3020//3020 3025//3025 3021//3021 -f 3026//3026 3027//3027 3028//3028 -f 3029//3029 3030//3030 3031//3031 -f 3031//3031 3030//3030 3032//3032 -f 3033//3033 3034//3034 3035//3035 -f 3036//3036 3037//3037 3038//3038 -f 3039//3039 3040//3040 3041//3041 -f 3041//3041 3040//3040 3042//3042 -f 3041//3041 3042//3042 3043//3043 -f 3044//3044 3045//3045 3039//3039 -f 3039//3039 3045//3045 3046//3046 -f 3039//3039 3046//3046 3040//3040 -f 3035//3035 3047//3047 3033//3033 -f 3033//3033 3047//3047 3048//3048 -f 3033//3033 3048//3048 3049//3049 -f 3043//3043 3042//3042 3032//3032 -f 3032//3032 3042//3042 3050//3050 -f 3032//3032 3050//3050 3031//3031 -f 3051//3051 3052//3052 3053//3053 -f 3053//3053 3052//3052 3054//3054 -f 3053//3053 3054//3054 3044//3044 -f 3044//3044 3054//3054 3055//3055 -f 3044//3044 3055//3055 3045//3045 -f 3056//3056 3057//3057 3053//3053 -f 3053//3053 3057//3057 3058//3058 -f 3053//3053 3058//3058 3051//3051 -f 3059//3059 3057//3057 3060//3060 -f 3060//3060 3057//3057 3056//3056 -f 3060//3060 3056//3056 3061//3061 -f 3061//3061 3056//3056 3062//3062 -f 3061//3061 3062//3062 3063//3063 -f 3063//3063 3062//3062 3037//3037 -f 3063//3063 3037//3037 3064//3064 -f 3064//3064 3037//3037 3036//3036 -f 3059//3059 3065//3065 3057//3057 -f 3057//3057 3065//3065 3066//3066 -f 3057//3057 3066//3066 3067//3067 -f 3067//3067 3066//3066 3068//3068 -f 3067//3067 3068//3068 3048//3048 -f 3048//3048 3068//3068 3069//3069 -f 3048//3048 3069//3069 3049//3049 -f 3058//3058 3070//3070 3051//3051 -f 3051//3051 3070//3070 3071//3071 -f 3051//3051 3071//3071 3072//3072 -f 3072//3072 3071//3071 3073//3073 -f 3072//3072 3073//3073 3074//3074 -f 3074//3074 3073//3073 3075//3075 -f 3074//3074 3075//3075 3076//3076 -f 3076//3076 3075//3075 3077//3077 -f 3076//3076 3077//3077 3034//3034 -f 3034//3034 3077//3077 3078//3078 -f 3034//3034 3078//3078 3035//3035 -f 3079//3079 3080//3080 3081//3081 -f 3082//3082 3083//3083 3084//3084 -f 3085//3085 3028//3028 3086//3086 -f 3084//3084 3083//3083 3080//3080 -f 3080//3080 3083//3083 3087//3087 -f 3080//3080 3087//3087 3081//3081 -f 3027//3027 3088//3088 3028//3028 -f 3028//3028 3088//3088 3089//3089 -f 3028//3028 3089//3089 3086//3086 -f 3033//3033 3090//3090 3034//3034 -f 3034//3034 3090//3090 3091//3091 -f 3034//3034 3091//3091 3092//3092 -f 3092//3092 3091//3091 3093//3093 -f 3084//3084 3094//3094 3082//3082 -f 3082//3082 3094//3094 3095//3095 -f 3082//3082 3095//3095 3027//3027 -f 3027//3027 3095//3095 3096//3096 -f 3027//3027 3096//3096 3088//3088 -f 3033//3033 3097//3097 3090//3090 -f 3090//3090 3097//3097 3098//3098 -f 3090//3090 3098//3098 3099//3099 -f 3099//3099 3098//3098 3100//3100 -f 3099//3099 3100//3100 3086//3086 -f 3086//3086 3100//3100 3101//3101 -f 3086//3086 3101//3101 3085//3085 -f 3081//3081 3102//3102 3079//3079 -f 3079//3079 3102//3102 3103//3103 -f 3079//3079 3103//3103 3091//3091 -f 3091//3091 3103//3103 3104//3104 -f 3091//3091 3104//3104 3093//3093 -f 3105//3105 3106//3106 3107//3107 -f 3107//3107 3108//3108 3105//3105 -f 3105//3105 3108//3108 3109//3109 -f 3105//3105 3109//3109 3028//3028 -f 3028//3028 3109//3109 3110//3110 -f 3028//3028 3110//3110 3026//3026 -f 3111//3111 3112//3112 3113//3113 -f 3113//3113 3112//3112 3036//3036 -f 3113//3113 3036//3036 3114//3114 -f 3111//3111 3113//3113 3115//3115 -f 3115//3115 3113//3113 3116//3116 -f 3115//3115 3116//3116 3117//3117 -f 3117//3117 3116//3116 3118//3118 -f 3117//3117 3118//3118 3119//3119 -f 3119//3119 3118//3118 3105//3105 -f 3105//3105 3118//3118 3120//3120 -f 3105//3105 3120//3120 3106//3106 -f 3120//3120 3121//3121 3106//3106 -f 3106//3106 3121//3121 3122//3122 -f 3106//3106 3122//3122 3123//3123 -f 3123//3123 3122//3122 3124//3124 -f 3123//3123 3124//3124 3125//3125 -f 3125//3125 3124//3124 3126//3126 -f 3125//3125 3126//3126 3127//3127 -f 3127//3127 3126//3126 3128//3128 -f 3127//3127 3128//3128 3129//3129 -f 3129//3129 3128//3128 3130//3130 -f 3129//3129 3130//3130 3131//3131 -f 3131//3131 3130//3130 3132//3132 -f 3038//3038 3029//3029 3036//3036 -f 3036//3036 3029//3029 3031//3031 -f 3036//3036 3031//3031 3114//3114 -f 3114//3114 3031//3031 3133//3133 -f 3114//3114 3133//3133 3134//3134 -f 3134//3134 3135//3135 3114//3114 -f 3114//3114 3135//3135 3136//3136 -f 3114//3114 3136//3136 3132//3132 -f 3132//3132 3136//3136 3137//3137 -f 3132//3132 3137//3137 3131//3131 -f 3138//3138 3139//3139 3140//3140 -f 3140//3140 3139//3139 3141//3141 -f 3140//3140 3141//3141 3142//3142 -f 3142//3142 3141//3141 3143//3143 -f 3142//3142 3143//3143 3144//3144 -f 3144//3144 3143//3143 3145//3145 -f 3144//3144 3145//3145 3146//3146 -f 3146//3146 3145//3145 3147//3147 -f 3146//3146 3147//3147 3148//3148 -f 3148//3148 3147//3147 3149//3149 -f 3148//3148 3149//3149 3150//3150 -f 3150//3150 3149//3149 3151//3151 -f 3150//3150 3151//3151 3152//3152 -f 3152//3152 3151//3151 3153//3153 -f 3152//3152 3153//3153 3154//3154 -f 3154//3154 3153//3153 3155//3155 -f 3154//3154 3155//3155 3156//3156 -f 3156//3156 3155//3155 3157//3157 -f 3156//3156 3157//3157 3158//3158 -f 3158//3158 3157//3157 3159//3159 -f 3158//3158 3159//3159 3160//3160 -f 3160//3160 3159//3159 3161//3161 -f 3160//3160 3161//3161 3162//3162 -f 3162//3162 3161//3161 3163//3163 -f 3162//3162 3163//3163 3164//3164 -f 3164//3164 3163//3163 3165//3165 -f 3164//3164 3165//3165 3166//3166 -f 3166//3166 3165//3165 3167//3167 -f 3166//3166 3167//3167 3168//3168 -f 3168//3168 3167//3167 3169//3169 -f 3168//3168 3169//3169 3170//3170 -f 3170//3170 3169//3169 3171//3171 -f 3170//3170 3171//3171 3172//3172 -f 3172//3172 3171//3171 3173//3173 -f 3172//3172 3173//3173 3174//3174 -f 3174//3174 3173//3173 3175//3175 -f 3174//3174 3175//3175 3176//3176 -f 3176//3176 3175//3175 3177//3177 -f 3176//3176 3177//3177 3178//3178 -f 3178//3178 3177//3177 3179//3179 -f 3178//3178 3179//3179 3180//3180 -f 3180//3180 3179//3179 3181//3181 -f 3180//3180 3181//3181 3182//3182 -f 3182//3182 3181//3181 3183//3183 -f 3182//3182 3183//3183 3184//3184 -f 3184//3184 3183//3183 3185//3185 -f 3184//3184 3185//3185 3186//3186 -f 3186//3186 3185//3185 3187//3187 -f 3186//3186 3187//3187 3188//3188 -f 3188//3188 3187//3187 3189//3189 -f 3188//3188 3189//3189 3190//3190 -f 3190//3190 3189//3189 3191//3191 -f 3190//3190 3191//3191 3192//3192 -f 3192//3192 3191//3191 3193//3193 -f 3192//3192 3193//3193 3194//3194 -f 3194//3194 3193//3193 3195//3195 -f 3194//3194 3195//3195 3196//3196 -f 3196//3196 3195//3195 3197//3197 -f 3196//3196 3197//3197 3198//3198 -f 3198//3198 3197//3197 3199//3199 -f 3198//3198 3199//3199 3200//3200 -f 3200//3200 3199//3199 3201//3201 -f 3200//3200 3201//3201 3202//3202 -f 3202//3202 3201//3201 3203//3203 -f 3202//3202 3203//3203 3204//3204 -f 3204//3204 3203//3203 3205//3205 -f 3204//3204 3205//3205 3206//3206 -f 3206//3206 3205//3205 3207//3207 -f 3206//3206 3207//3207 3208//3208 -f 3208//3208 3207//3207 3209//3209 -f 3208//3208 3209//3209 3210//3210 -f 3210//3210 3209//3209 3211//3211 -f 3210//3210 3211//3211 3212//3212 -f 3212//3212 3211//3211 3213//3213 -f 3212//3212 3213//3213 3138//3138 -f 3138//3138 3213//3213 3139//3139 -f 3214//3214 3215//3215 3216//3216 -f 3216//3216 3215//3215 3217//3217 -f 3217//3217 3215//3215 3218//3218 -f 3217//3217 3218//3218 3219//3219 -f 3219//3219 3218//3218 3220//3220 -f 3219//3219 3220//3220 3221//3221 -f 3221//3221 3220//3220 3222//3222 -f 3221//3221 3222//3222 3223//3223 -f 3223//3223 3222//3222 3224//3224 -f 3223//3223 3224//3224 3225//3225 -f 3225//3225 3226//3226 3227//3227 -f 3227//3227 3226//3226 3228//3228 -f 3227//3227 3228//3228 3229//3229 -f 3230//3230 3231//3231 3232//3232 -f 3216//3216 3233//3233 3214//3214 -f 3214//3214 3233//3233 3234//3234 -f 3214//3214 3234//3234 3235//3235 -f 3230//3230 3236//3236 3231//3231 -f 3231//3231 3236//3236 3237//3237 -f 3231//3231 3237//3237 3238//3238 -f 3232//3232 3239//3239 3230//3230 -f 3230//3230 3239//3239 3240//3240 -f 3230//3230 3240//3240 3241//3241 -f 3241//3241 3240//3240 3242//3242 -f 3241//3241 3242//3242 3228//3228 -f 3228//3228 3242//3242 3243//3243 -f 3228//3228 3243//3243 3229//3229 -f 3244//3244 3245//3245 3246//3246 -f 3246//3246 3245//3245 3247//3247 -f 3246//3246 3247//3247 3248//3248 -f 3248//3248 3247//3247 3249//3249 -f 3248//3248 3249//3249 3238//3238 -f 3238//3238 3249//3249 3250//3250 -f 3238//3238 3250//3250 3231//3231 -f 3251//3251 3252//3252 3253//3253 -f 3253//3253 3252//3252 3254//3254 -f 3236//3236 3214//3214 3237//3237 -f 3237//3237 3214//3214 3235//3235 -f 3237//3237 3235//3235 3255//3255 -f 3255//3255 3235//3235 3256//3256 -f 3255//3255 3256//3256 3257//3257 -f 3258//3258 3259//3259 3260//3260 -f 3260//3260 3259//3259 3254//3254 -f 3254//3254 3259//3259 3261//3261 -f 3254//3254 3261//3261 3253//3253 -f 3260//3260 3262//3262 3258//3258 -f 3258//3258 3262//3262 3263//3263 -f 3258//3258 3263//3263 3264//3264 -f 3264//3264 3263//3263 3257//3257 -f 3264//3264 3257//3257 3265//3265 -f 3265//3265 3257//3257 3256//3256 -f 3266//3266 3267//3267 3268//3268 -f 3268//3268 3267//3267 3269//3269 -f 3267//3267 3270//3270 3271//3271 -f 3271//3271 3270//3270 3272//3272 -f 3271//3271 3272//3272 3273//3273 -f 3273//3273 3272//3272 3274//3274 -f 3273//3273 3274//3274 3275//3275 -f 3275//3275 3274//3274 3276//3276 -f 3275//3275 3276//3276 3277//3277 -f 3277//3277 3276//3276 3278//3278 -f 3277//3277 3278//3278 3279//3279 -f 3279//3279 3278//3278 3280//3280 -f 3279//3279 3280//3280 3281//3281 -f 3281//3281 3280//3280 3282//3282 -f 3281//3281 3282//3282 3283//3283 -f 3246//3246 3251//3251 3244//3244 -f 3244//3244 3251//3251 3253//3253 -f 3244//3244 3253//3253 3284//3284 -f 3284//3284 3253//3253 3285//3285 -f 3283//3283 3282//3282 3286//3286 -f 3286//3286 3282//3282 3287//3287 -f 3286//3286 3287//3287 3288//3288 -f 3268//3268 3289//3289 3266//3266 -f 3266//3266 3289//3289 3290//3290 -f 3266//3266 3290//3290 3291//3291 -f 3291//3291 3290//3290 3292//3292 -f 3291//3291 3292//3292 3293//3293 -f 3293//3293 3292//3292 3294//3294 -f 3294//3294 3285//3285 3293//3293 -f 3293//3293 3285//3285 3253//3253 -f 3293//3293 3253//3253 3287//3287 -f 3287//3287 3253//3253 3295//3295 -f 3287//3287 3295//3295 3288//3288 -f 3267//3267 3271//3271 3269//3269 -f 3269//3269 3271//3271 3296//3296 -f 3269//3269 3296//3296 3297//3297 -f 3297//3297 3298//3298 3269//3269 -f 3269//3269 3298//3298 3299//3299 -f 3269//3269 3299//3299 3300//3300 -f 3301//3301 3302//3302 3303//3303 -f 3304//3304 3305//3305 3306//3306 -f 3307//3307 3269//3269 3308//3308 -f 3309//3309 3310//3310 3311//3311 -f 3306//3306 3305//3305 3302//3302 -f 3302//3302 3305//3305 3312//3312 -f 3302//3302 3312//3312 3303//3303 -f 3225//3225 3227//3227 3223//3223 -f 3223//3223 3227//3227 3313//3313 -f 3223//3223 3313//3313 3314//3314 -f 3306//3306 3315//3315 3304//3304 -f 3304//3304 3315//3315 3316//3316 -f 3304//3304 3316//3316 3317//3317 -f 3317//3317 3316//3316 3318//3318 -f 3317//3317 3318//3318 3300//3300 -f 3300//3300 3318//3318 3319//3319 -f 3300//3300 3319//3319 3269//3269 -f 3269//3269 3319//3319 3320//3320 -f 3269//3269 3320//3320 3308//3308 -f 3310//3310 3223//3223 3311//3311 -f 3311//3311 3223//3223 3314//3314 -f 3311//3311 3314//3314 3321//3321 -f 3321//3321 3314//3314 3322//3322 -f 3321//3321 3322//3322 3323//3323 -f 3323//3323 3322//3322 3324//3324 -f 3323//3323 3324//3324 3308//3308 -f 3308//3308 3324//3324 3325//3325 -f 3308//3308 3325//3325 3307//3307 -f 3303//3303 3326//3326 3301//3301 -f 3301//3301 3326//3326 3327//3327 -f 3301//3301 3327//3327 3311//3311 -f 3311//3311 3327//3327 3328//3328 -f 3311//3311 3328//3328 3309//3309 -f 3243//3243 3242//3242 3329//3329 -f 3329//3329 3330//3330 3243//3243 -f 3243//3243 3330//3330 3331//3331 -f 3243//3243 3331//3331 3229//3229 -f 3229//3229 3331//3331 3332//3332 -f 3229//3229 3332//3332 3227//3227 -f 3227//3227 3332//3332 3333//3333 -f 3227//3227 3333//3333 3313//3313 -f 3333//3333 3334//3334 3313//3313 -f 3313//3313 3334//3334 3335//3335 -f 3313//3313 3335//3335 3314//3314 -f 3335//3335 3336//3336 3314//3314 -f 3314//3314 3336//3336 3337//3337 -f 3314//3314 3337//3337 3322//3322 -f 3337//3337 3338//3338 3322//3322 -f 3322//3322 3338//3338 3339//3339 -f 3322//3322 3339//3339 3324//3324 -f 3339//3339 3340//3340 3324//3324 -f 3324//3324 3340//3340 3341//3341 -f 3324//3324 3341//3341 3325//3325 -f 3341//3341 3342//3342 3325//3325 -f 3325//3325 3342//3342 3343//3343 -f 3325//3325 3343//3343 3307//3307 -f 3343//3343 3344//3344 3307//3307 -f 3307//3307 3344//3344 3345//3345 -f 3307//3307 3345//3345 3269//3269 -f 3345//3345 3346//3346 3269//3269 -f 3269//3269 3346//3346 3347//3347 -f 3269//3269 3347//3347 3268//3268 -f 3347//3347 3348//3348 3268//3268 -f 3268//3268 3348//3348 3349//3349 -f 3268//3268 3349//3349 3289//3289 -f 3349//3349 3350//3350 3289//3289 -f 3289//3289 3350//3350 3351//3351 -f 3289//3289 3351//3351 3290//3290 -f 3351//3351 3352//3352 3290//3290 -f 3290//3290 3352//3352 3353//3353 -f 3290//3290 3353//3353 3292//3292 -f 3353//3353 3354//3354 3292//3292 -f 3292//3292 3354//3354 3355//3355 -f 3292//3292 3355//3355 3294//3294 -f 3355//3355 3356//3356 3294//3294 -f 3294//3294 3356//3356 3357//3357 -f 3294//3294 3357//3357 3285//3285 -f 3357//3357 3358//3358 3285//3285 -f 3285//3285 3358//3358 3359//3359 -f 3285//3285 3359//3359 3284//3284 -f 3284//3284 3359//3359 3360//3360 -f 3284//3284 3360//3360 3244//3244 -f 3244//3244 3360//3360 3361//3361 -f 3244//3244 3361//3361 3245//3245 -f 3361//3361 3362//3362 3245//3245 -f 3245//3245 3362//3362 3363//3363 -f 3245//3245 3363//3363 3247//3247 -f 3363//3363 3364//3364 3247//3247 -f 3247//3247 3364//3364 3365//3365 -f 3247//3247 3365//3365 3249//3249 -f 3365//3365 3366//3366 3249//3249 -f 3249//3249 3366//3366 3367//3367 -f 3249//3249 3367//3367 3250//3250 -f 3367//3367 3368//3368 3250//3250 -f 3250//3250 3368//3368 3369//3369 -f 3250//3250 3369//3369 3231//3231 -f 3369//3369 3370//3370 3231//3231 -f 3231//3231 3370//3370 3371//3371 -f 3231//3231 3371//3371 3232//3232 -f 3371//3371 3372//3372 3232//3232 -f 3232//3232 3372//3372 3373//3373 -f 3232//3232 3373//3373 3239//3239 -f 3373//3373 3374//3374 3239//3239 -f 3239//3239 3374//3374 3375//3375 -f 3239//3239 3375//3375 3240//3240 -f 3375//3375 3376//3376 3240//3240 -f 3240//3240 3376//3376 3377//3377 -f 3240//3240 3377//3377 3242//3242 -f 3242//3242 3377//3377 3378//3378 -f 3242//3242 3378//3378 3329//3329 -f 3379//3379 3380//3380 3381//3381 -f 3382//3382 3383//3383 3384//3384 -f 3384//3384 3383//3383 3385//3385 -f 3384//3384 3385//3385 3386//3386 -f 3386//3386 3385//3385 3387//3387 -f 3386//3386 3387//3387 3381//3381 -f 3381//3381 3387//3387 3388//3388 -f 3381//3381 3388//3388 3379//3379 -f 3389//3389 3390//3390 3391//3391 -f 3391//3391 3390//3390 3392//3392 -f 3391//3391 3392//3392 3393//3393 -f 3393//3393 3392//3392 3394//3394 -f 3393//3393 3394//3394 3382//3382 -f 3382//3382 3394//3394 3395//3395 -f 3382//3382 3395//3395 3383//3383 -f 3396//3396 3397//3397 3398//3398 -f 3398//3398 3397//3397 3399//3399 -f 3398//3398 3399//3399 3400//3400 -f 3400//3400 3399//3399 3401//3401 -f 3400//3400 3401//3401 3389//3389 -f 3389//3389 3401//3401 3402//3402 -f 3389//3389 3402//3402 3390//3390 -f 3379//3379 3403//3403 3380//3380 -f 3380//3380 3403//3403 3404//3404 -f 3380//3380 3404//3404 3405//3405 -f 3405//3405 3404//3404 3406//3406 -f 3405//3405 3406//3406 3407//3407 -f 3407//3407 3406//3406 3408//3408 -f 3407//3407 3408//3408 3409//3409 -f 3410//3410 3411//3411 3412//3412 -f 3412//3412 3411//3411 3413//3413 -f 3412//3412 3413//3413 3414//3414 -f 3414//3414 3413//3413 3415//3415 -f 3414//3414 3415//3415 3396//3396 -f 3396//3396 3415//3415 3416//3416 -f 3396//3396 3416//3416 3397//3397 -f 3408//3408 3417//3417 3409//3409 -f 3409//3409 3417//3417 3418//3418 -f 3409//3409 3418//3418 3419//3419 -f 3419//3419 3418//3418 3420//3420 -f 3419//3419 3420//3420 3421//3421 -f 3421//3421 3420//3420 3422//3422 -f 3421//3421 3422//3422 3410//3410 -f 3410//3410 3422//3422 3423//3423 -f 3410//3410 3423//3423 3411//3411 -f 3424//3424 3380//3380 3425//3425 -f 3425//3425 3380//3380 3405//3405 -f 3425//3425 3405//3405 3426//3426 -f 3426//3426 3405//3405 3407//3407 -f 3426//3426 3407//3407 3427//3427 -f 3427//3427 3407//3407 3409//3409 -f 3427//3427 3409//3409 3428//3428 -f 3428//3428 3409//3409 3419//3419 -f 3428//3428 3419//3419 3429//3429 -f 3429//3429 3419//3419 3421//3421 -f 3429//3429 3421//3421 3430//3430 -f 3430//3430 3421//3421 3410//3410 -f 3430//3430 3410//3410 3431//3431 -f 3431//3431 3410//3410 3412//3412 -f 3431//3431 3412//3412 3432//3432 -f 3432//3432 3412//3412 3414//3414 -f 3432//3432 3414//3414 3433//3433 -f 3433//3433 3414//3414 3396//3396 -f 3433//3433 3396//3396 3434//3434 -f 3434//3434 3396//3396 3398//3398 -f 3434//3434 3398//3398 3435//3435 -f 3435//3435 3398//3398 3400//3400 -f 3435//3435 3400//3400 3436//3436 -f 3436//3436 3400//3400 3389//3389 -f 3436//3436 3389//3389 3437//3437 -f 3437//3437 3389//3389 3391//3391 -f 3437//3437 3391//3391 3438//3438 -f 3438//3438 3391//3391 3393//3393 -f 3438//3438 3393//3393 3439//3439 -f 3439//3439 3393//3393 3382//3382 -f 3439//3439 3382//3382 3440//3440 -f 3440//3440 3382//3382 3384//3384 -f 3440//3440 3384//3384 3441//3441 -f 3441//3441 3384//3384 3386//3386 -f 3441//3441 3386//3386 3442//3442 -f 3442//3442 3386//3386 3381//3381 -f 3442//3442 3381//3381 3424//3424 -f 3424//3424 3381//3381 3380//3380 -f 3443//3443 3441//3441 3444//3444 -f 3444//3444 3441//3441 3442//3442 -f 3444//3444 3442//3442 3445//3445 -f 3445//3445 3442//3442 3424//3424 -f 3445//3445 3424//3424 3446//3446 -f 3447//3447 3435//3435 3448//3448 -f 3448//3448 3435//3435 3436//3436 -f 3448//3448 3436//3436 3449//3449 -f 3436//3436 3437//3437 3449//3449 -f 3449//3449 3437//3437 3438//3438 -f 3449//3449 3438//3438 3450//3450 -f 3450//3450 3438//3438 3439//3439 -f 3450//3450 3439//3439 3443//3443 -f 3443//3443 3439//3439 3440//3440 -f 3443//3443 3440//3440 3441//3441 -f 3451//3451 3432//3432 3452//3452 -f 3452//3452 3432//3432 3433//3433 -f 3452//3452 3433//3433 3447//3447 -f 3447//3447 3433//3433 3434//3434 -f 3447//3447 3434//3434 3435//3435 -f 3453//3453 3429//3429 3454//3454 -f 3454//3454 3429//3429 3430//3430 -f 3454//3454 3430//3430 3451//3451 -f 3451//3451 3430//3430 3431//3431 -f 3451//3451 3431//3431 3432//3432 -f 3424//3424 3425//3425 3446//3446 -f 3446//3446 3425//3425 3426//3426 -f 3446//3446 3426//3426 3455//3455 -f 3455//3455 3426//3426 3427//3427 -f 3455//3455 3427//3427 3453//3453 -f 3453//3453 3427//3427 3428//3428 -f 3453//3453 3428//3428 3429//3429 -f 3456//3456 3445//3445 3457//3457 -f 3457//3457 3445//3445 3446//3446 -f 3457//3457 3446//3446 3458//3458 -f 3458//3458 3446//3446 3455//3455 -f 3458//3458 3455//3455 3459//3459 -f 3459//3459 3455//3455 3453//3453 -f 3459//3459 3453//3453 3460//3460 -f 3460//3460 3453//3453 3454//3454 -f 3460//3460 3454//3454 3461//3461 -f 3461//3461 3454//3454 3451//3451 -f 3461//3461 3451//3451 3462//3462 -f 3462//3462 3451//3451 3452//3452 -f 3462//3462 3452//3452 3463//3463 -f 3463//3463 3452//3452 3447//3447 -f 3463//3463 3447//3447 3464//3464 -f 3464//3464 3447//3447 3448//3448 -f 3464//3464 3448//3448 3465//3465 -f 3465//3465 3448//3448 3449//3449 -f 3465//3465 3449//3449 3466//3466 -f 3466//3466 3449//3449 3450//3450 -f 3466//3466 3450//3450 3467//3467 -f 3467//3467 3450//3450 3443//3443 -f 3467//3467 3443//3443 3468//3468 -f 3468//3468 3443//3443 3444//3444 -f 3468//3468 3444//3444 3456//3456 -f 3456//3456 3444//3444 3445//3445 -f 3464//3464 2999//2999 3463//3463 -f 3463//3463 2999//2999 2996//2996 -f 3463//3463 2996//2996 3462//3462 -f 3466//3466 3008//3008 3465//3465 -f 3465//3465 3008//3008 3005//3005 -f 3465//3465 3005//3005 3464//3464 -f 3464//3464 3005//3005 3002//3002 -f 3464//3464 3002//3002 2999//2999 -f 3468//3468 3017//3017 3467//3467 -f 3467//3467 3017//3017 3014//3014 -f 3467//3467 3014//3014 3466//3466 -f 3466//3466 3014//3014 3011//3011 -f 3466//3466 3011//3011 3008//3008 -f 3458//3458 2972//2972 3457//3457 -f 3457//3457 2972//2972 2970//2970 -f 3457//3457 2970//2970 3456//3456 -f 3456//3456 2970//2970 2969//2969 -f 3456//3456 2969//2969 3468//3468 -f 3468//3468 2969//2969 3020//3020 -f 3468//3468 3020//3020 3017//3017 -f 3460//3460 2981//2981 3459//3459 -f 3459//3459 2981//2981 2978//2978 -f 3459//3459 2978//2978 3458//3458 -f 3458//3458 2978//2978 2975//2975 -f 3458//3458 2975//2975 2972//2972 -f 2996//2996 2993//2993 3462//3462 -f 3462//3462 2993//2993 2990//2990 -f 3462//3462 2990//2990 3461//3461 -f 3461//3461 2990//2990 2987//2987 -f 3461//3461 2987//2987 3460//3460 -f 3460//3460 2987//2987 2984//2984 -f 3460//3460 2984//2984 2981//2981 -f 3469//3469 3218//3218 3470//3470 -f 3470//3470 3218//3218 3215//3215 -f 3470//3470 3215//3215 3471//3471 -f 3471//3471 3215//3215 3214//3214 -f 3471//3471 3214//3214 3472//3472 -f 3472//3472 3214//3214 3236//3236 -f 3472//3472 3236//3236 3473//3473 -f 3473//3473 3236//3236 3230//3230 -f 3473//3473 3230//3230 3474//3474 -f 3474//3474 3230//3230 3241//3241 -f 3474//3474 3241//3241 3475//3475 -f 3475//3475 3241//3241 3228//3228 -f 3475//3475 3228//3228 3476//3476 -f 3476//3476 3228//3228 3226//3226 -f 3476//3476 3226//3226 3477//3477 -f 3477//3477 3226//3226 3225//3225 -f 3477//3477 3225//3225 3478//3478 -f 3478//3478 3225//3225 3224//3224 -f 3478//3478 3224//3224 3479//3479 -f 3479//3479 3224//3224 3222//3222 -f 3479//3479 3222//3222 3480//3480 -f 3480//3480 3222//3222 3220//3220 -f 3480//3480 3220//3220 3469//3469 -f 3469//3469 3220//3220 3218//3218 -f 3474//3474 3481//3481 3473//3473 -f 3473//3473 3481//3481 3482//3482 -f 3473//3473 3482//3482 3472//3472 -f 3472//3472 3482//3482 3483//3483 -f 3472//3472 3483//3483 3471//3471 -f 3471//3471 3483//3483 3484//3484 -f 3471//3471 3484//3484 3470//3470 -f 3470//3470 3484//3484 3485//3485 -f 3470//3470 3485//3485 3469//3469 -f 3469//3469 3485//3485 3486//3486 -f 3469//3469 3486//3486 3480//3480 -f 3480//3480 3486//3486 3487//3487 -f 3480//3480 3487//3487 3479//3479 -f 3479//3479 3487//3487 3488//3488 -f 3479//3479 3488//3488 3478//3478 -f 3478//3478 3488//3488 3489//3489 -f 3478//3478 3489//3489 3477//3477 -f 3477//3477 3489//3489 3490//3490 -f 3477//3477 3490//3490 3476//3476 -f 3476//3476 3490//3490 3491//3491 -f 3476//3476 3491//3491 3475//3475 -f 3475//3475 3491//3491 3492//3492 -f 3475//3475 3492//3492 3474//3474 -f 3474//3474 3492//3492 3481//3481 -f 3482//3482 3113//3113 3483//3483 -f 3483//3483 3113//3113 3114//3114 -f 3483//3483 3114//3114 3484//3484 -f 3484//3484 3114//3114 3132//3132 -f 3484//3484 3132//3132 3485//3485 -f 3485//3485 3132//3132 3130//3130 -f 3485//3485 3130//3130 3486//3486 -f 3486//3486 3130//3130 3128//3128 -f 3486//3486 3128//3128 3487//3487 -f 3487//3487 3128//3128 3126//3126 -f 3487//3487 3126//3126 3488//3488 -f 3488//3488 3126//3126 3124//3124 -f 3488//3488 3124//3124 3489//3489 -f 3489//3489 3124//3124 3122//3122 -f 3489//3489 3122//3122 3490//3490 -f 3490//3490 3122//3122 3121//3121 -f 3490//3490 3121//3121 3491//3491 -f 3491//3491 3121//3121 3120//3120 -f 3491//3491 3120//3120 3492//3492 -f 3492//3492 3120//3120 3118//3118 -f 3492//3492 3118//3118 3481//3481 -f 3481//3481 3118//3118 3116//3116 -f 3481//3481 3116//3116 3482//3482 -f 3482//3482 3116//3116 3113//3113 -f 3493//3493 3311//3311 3494//3494 -f 3494//3494 3311//3311 3321//3321 -f 3494//3494 3321//3321 3495//3495 -f 3495//3495 3321//3321 3323//3323 -f 3495//3495 3323//3323 3496//3496 -f 3496//3496 3323//3323 3308//3308 -f 3496//3496 3308//3308 3497//3497 -f 3497//3497 3308//3308 3320//3320 -f 3497//3497 3320//3320 3498//3498 -f 3498//3498 3320//3320 3319//3319 -f 3498//3498 3319//3319 3499//3499 -f 3499//3499 3319//3319 3318//3318 -f 3499//3499 3318//3318 3500//3500 -f 3500//3500 3318//3318 3316//3316 -f 3500//3500 3316//3316 3501//3501 -f 3501//3501 3316//3316 3315//3315 -f 3501//3501 3315//3315 3502//3502 -f 3502//3502 3315//3315 3306//3306 -f 3502//3502 3306//3306 3503//3503 -f 3503//3503 3306//3306 3302//3302 -f 3503//3503 3302//3302 3504//3504 -f 3504//3504 3302//3302 3301//3301 -f 3504//3504 3301//3301 3493//3493 -f 3493//3493 3301//3301 3311//3311 -f 3498//3498 3505//3505 3497//3497 -f 3497//3497 3505//3505 3506//3506 -f 3497//3497 3506//3506 3496//3496 -f 3496//3496 3506//3506 3507//3507 -f 3496//3496 3507//3507 3495//3495 -f 3495//3495 3507//3507 3508//3508 -f 3495//3495 3508//3508 3494//3494 -f 3494//3494 3508//3508 3509//3509 -f 3494//3494 3509//3509 3493//3493 -f 3493//3493 3509//3509 3510//3510 -f 3493//3493 3510//3510 3504//3504 -f 3504//3504 3510//3510 3511//3511 -f 3504//3504 3511//3511 3503//3503 -f 3503//3503 3511//3511 3512//3512 -f 3503//3503 3512//3512 3502//3502 -f 3502//3502 3512//3512 3513//3513 -f 3502//3502 3513//3513 3501//3501 -f 3501//3501 3513//3513 3514//3514 -f 3501//3501 3514//3514 3500//3500 -f 3500//3500 3514//3514 3515//3515 -f 3500//3500 3515//3515 3499//3499 -f 3499//3499 3515//3515 3516//3516 -f 3499//3499 3516//3516 3498//3498 -f 3498//3498 3516//3516 3505//3505 -f 3506//3506 3091//3091 3507//3507 -f 3507//3507 3091//3091 3090//3090 -f 3507//3507 3090//3090 3508//3508 -f 3508//3508 3090//3090 3099//3099 -f 3508//3508 3099//3099 3509//3509 -f 3509//3509 3099//3099 3086//3086 -f 3509//3509 3086//3086 3510//3510 -f 3510//3510 3086//3086 3089//3089 -f 3510//3510 3089//3089 3511//3511 -f 3511//3511 3089//3089 3088//3088 -f 3511//3511 3088//3088 3512//3512 -f 3512//3512 3088//3088 3096//3096 -f 3512//3512 3096//3096 3513//3513 -f 3513//3513 3096//3096 3095//3095 -f 3513//3513 3095//3095 3514//3514 -f 3514//3514 3095//3095 3094//3094 -f 3514//3514 3094//3094 3515//3515 -f 3515//3515 3094//3094 3084//3084 -f 3515//3515 3084//3084 3516//3516 -f 3516//3516 3084//3084 3080//3080 -f 3516//3516 3080//3080 3505//3505 -f 3505//3505 3080//3080 3079//3079 -f 3505//3505 3079//3079 3506//3506 -f 3506//3506 3079//3079 3091//3091 -f 3517//3517 3293//3293 3518//3518 -f 3518//3518 3293//3293 3287//3287 -f 3518//3518 3287//3287 3519//3519 -f 3519//3519 3287//3287 3282//3282 -f 3519//3519 3282//3282 3520//3520 -f 3520//3520 3282//3282 3280//3280 -f 3520//3520 3280//3280 3521//3521 -f 3521//3521 3280//3280 3278//3278 -f 3521//3521 3278//3278 3522//3522 -f 3522//3522 3278//3278 3276//3276 -f 3522//3522 3276//3276 3523//3523 -f 3523//3523 3276//3276 3274//3274 -f 3523//3523 3274//3274 3524//3524 -f 3524//3524 3274//3274 3272//3272 -f 3524//3524 3272//3272 3525//3525 -f 3525//3525 3272//3272 3270//3270 -f 3525//3525 3270//3270 3526//3526 -f 3526//3526 3270//3270 3267//3267 -f 3526//3526 3267//3267 3527//3527 -f 3527//3527 3267//3267 3266//3266 -f 3527//3527 3266//3266 3528//3528 -f 3528//3528 3266//3266 3291//3291 -f 3528//3528 3291//3291 3517//3517 -f 3517//3517 3291//3291 3293//3293 -f 3522//3522 3529//3529 3521//3521 -f 3521//3521 3529//3529 3530//3530 -f 3521//3521 3530//3530 3520//3520 -f 3520//3520 3530//3530 3531//3531 -f 3520//3520 3531//3531 3519//3519 -f 3519//3519 3531//3531 3532//3532 -f 3519//3519 3532//3532 3518//3518 -f 3518//3518 3532//3532 3533//3533 -f 3518//3518 3533//3533 3517//3517 -f 3517//3517 3533//3533 3534//3534 -f 3517//3517 3534//3534 3528//3528 -f 3528//3528 3534//3534 3535//3535 -f 3528//3528 3535//3535 3527//3527 -f 3527//3527 3535//3535 3536//3536 -f 3527//3527 3536//3536 3526//3526 -f 3526//3526 3536//3536 3537//3537 -f 3526//3526 3537//3537 3525//3525 -f 3525//3525 3537//3537 3538//3538 -f 3525//3525 3538//3538 3524//3524 -f 3524//3524 3538//3538 3539//3539 -f 3524//3524 3539//3539 3523//3523 -f 3523//3523 3539//3539 3540//3540 -f 3523//3523 3540//3540 3522//3522 -f 3522//3522 3540//3540 3529//3529 -f 3530//3530 3073//3073 3531//3531 -f 3531//3531 3073//3073 3071//3071 -f 3531//3531 3071//3071 3532//3532 -f 3532//3532 3071//3071 3070//3070 -f 3532//3532 3070//3070 3533//3533 -f 3533//3533 3070//3070 3058//3058 -f 3533//3533 3058//3058 3534//3534 -f 3534//3534 3058//3058 3057//3057 -f 3534//3534 3057//3057 3535//3535 -f 3535//3535 3057//3057 3067//3067 -f 3535//3535 3067//3067 3536//3536 -f 3536//3536 3067//3067 3048//3048 -f 3536//3536 3048//3048 3537//3537 -f 3537//3537 3048//3048 3047//3047 -f 3537//3537 3047//3047 3538//3538 -f 3538//3538 3047//3047 3035//3035 -f 3538//3538 3035//3035 3539//3539 -f 3539//3539 3035//3035 3078//3078 -f 3539//3539 3078//3078 3540//3540 -f 3540//3540 3078//3078 3077//3077 -f 3540//3540 3077//3077 3529//3529 -f 3529//3529 3077//3077 3075//3075 -f 3529//3529 3075//3075 3530//3530 -f 3530//3530 3075//3075 3073//3073 -f 3541//3541 3257//3257 3542//3542 -f 3542//3542 3257//3257 3263//3263 -f 3542//3542 3263//3263 3543//3543 -f 3543//3543 3263//3263 3262//3262 -f 3543//3543 3262//3262 3544//3544 -f 3544//3544 3262//3262 3260//3260 -f 3544//3544 3260//3260 3545//3545 -f 3545//3545 3260//3260 3254//3254 -f 3545//3545 3254//3254 3546//3546 -f 3546//3546 3254//3254 3252//3252 -f 3546//3546 3252//3252 3547//3547 -f 3547//3547 3252//3252 3251//3251 -f 3547//3547 3251//3251 3548//3548 -f 3548//3548 3251//3251 3246//3246 -f 3548//3548 3246//3246 3549//3549 -f 3549//3549 3246//3246 3248//3248 -f 3549//3549 3248//3248 3550//3550 -f 3550//3550 3248//3248 3238//3238 -f 3550//3550 3238//3238 3551//3551 -f 3551//3551 3238//3238 3237//3237 -f 3551//3551 3237//3237 3552//3552 -f 3552//3552 3237//3237 3255//3255 -f 3552//3552 3255//3255 3541//3541 -f 3541//3541 3255//3255 3257//3257 -f 3546//3546 3553//3553 3545//3545 -f 3545//3545 3553//3553 3554//3554 -f 3545//3545 3554//3554 3544//3544 -f 3544//3544 3554//3554 3555//3555 -f 3544//3544 3555//3555 3543//3543 -f 3543//3543 3555//3555 3556//3556 -f 3543//3543 3556//3556 3542//3542 -f 3542//3542 3556//3556 3557//3557 -f 3542//3542 3557//3557 3541//3541 -f 3541//3541 3557//3557 3558//3558 -f 3541//3541 3558//3558 3552//3552 -f 3552//3552 3558//3558 3559//3559 -f 3552//3552 3559//3559 3551//3551 -f 3551//3551 3559//3559 3560//3560 -f 3551//3551 3560//3560 3550//3550 -f 3550//3550 3560//3560 3561//3561 -f 3550//3550 3561//3561 3549//3549 -f 3549//3549 3561//3561 3562//3562 -f 3549//3549 3562//3562 3548//3548 -f 3548//3548 3562//3562 3563//3563 -f 3548//3548 3563//3563 3547//3547 -f 3547//3547 3563//3563 3564//3564 -f 3547//3547 3564//3564 3546//3546 -f 3546//3546 3564//3564 3553//3553 -f 3554//3554 3039//3039 3555//3555 -f 3555//3555 3039//3039 3041//3041 -f 3555//3555 3041//3041 3556//3556 -f 3556//3556 3041//3041 3043//3043 -f 3556//3556 3043//3043 3557//3557 -f 3557//3557 3043//3043 3032//3032 -f 3557//3557 3032//3032 3558//3558 -f 3558//3558 3032//3032 3030//3030 -f 3558//3558 3030//3030 3559//3559 -f 3559//3559 3030//3030 3029//3029 -f 3559//3559 3029//3029 3560//3560 -f 3560//3560 3029//3029 3038//3038 -f 3560//3560 3038//3038 3561//3561 -f 3561//3561 3038//3038 3037//3037 -f 3561//3561 3037//3037 3562//3562 -f 3562//3562 3037//3037 3062//3062 -f 3562//3562 3062//3062 3563//3563 -f 3563//3563 3062//3062 3056//3056 -f 3563//3563 3056//3056 3564//3564 -f 3564//3564 3056//3056 3053//3053 -f 3564//3564 3053//3053 3553//3553 -f 3553//3553 3053//3053 3044//3044 -f 3553//3553 3044//3044 3554//3554 -f 3554//3554 3044//3044 3039//3039 -f 3049//3049 3069//3069 3000//3000 -f 3000//3000 3004//3004 3049//3049 -f 3049//3049 3004//3004 3003//3003 -f 3049//3049 3003//3003 3033//3033 -f 3033//3033 3003//3003 3007//3007 -f 3033//3033 3007//3007 3097//3097 -f 3097//3097 3007//3007 3006//3006 -f 3097//3097 3006//3006 3098//3098 -f 3006//3006 3010//3010 3098//3098 -f 3098//3098 3010//3010 3009//3009 -f 3098//3098 3009//3009 3100//3100 -f 3009//3009 3013//3013 3100//3100 -f 3100//3100 3013//3013 3012//3012 -f 3100//3100 3012//3012 3101//3101 -f 3012//3012 3016//3016 3101//3101 -f 3101//3101 3016//3016 3015//3015 -f 3101//3101 3015//3015 3085//3085 -f 3015//3015 3019//3019 3085//3085 -f 3085//3085 3019//3019 3018//3018 -f 3085//3085 3018//3018 3028//3028 -f 3028//3028 3018//3018 3105//3105 -f 3105//3105 3018//3018 3022//3022 -f 3105//3105 3022//3022 3119//3119 -f 3119//3119 3022//3022 3021//3021 -f 3119//3119 3021//3021 3117//3117 -f 3021//3021 3025//3025 3117//3117 -f 3117//3117 3025//3025 3024//3024 -f 3117//3117 3024//3024 3115//3115 -f 3115//3115 3024//3024 3023//3023 -f 3115//3115 3023//3023 3111//3111 -f 3023//3023 2971//2971 3111//3111 -f 3111//3111 2971//2971 2974//2974 -f 3111//3111 2974//2974 3112//3112 -f 2974//2974 2973//2973 3112//3112 -f 3112//3112 2973//2973 2977//2977 -f 3112//3112 2977//2977 3036//3036 -f 3036//3036 2977//2977 2976//2976 -f 3036//3036 2976//2976 3064//3064 -f 3064//3064 2976//2976 2980//2980 -f 3064//3064 2980//2980 3063//3063 -f 2980//2980 2979//2979 3063//3063 -f 3063//3063 2979//2979 2983//2983 -f 3063//3063 2983//2983 3061//3061 -f 2983//2983 2982//2982 3061//3061 -f 3061//3061 2982//2982 2986//2986 -f 3061//3061 2986//2986 3060//3060 -f 2986//2986 2985//2985 3060//3060 -f 3060//3060 2985//2985 2989//2989 -f 3060//3060 2989//2989 3059//3059 -f 2989//2989 2988//2988 3059//3059 -f 3059//3059 2988//2988 2992//2992 -f 3059//3059 2992//2992 3065//3065 -f 2992//2992 2991//2991 3065//3065 -f 3065//3065 2991//2991 2995//2995 -f 3065//3065 2995//2995 3066//3066 -f 2995//2995 2994//2994 3066//3066 -f 3066//3066 2994//2994 2998//2998 -f 3066//3066 2998//2998 3068//3068 -f 3068//3068 2998//2998 2997//2997 -f 3068//3068 2997//2997 3069//3069 -f 3069//3069 2997//2997 3001//3001 -f 3069//3069 3001//3001 3000//3000 -f 3397//3397 3353//3353 3352//3352 -f 3397//3397 3352//3352 3399//3399 -f 3399//3399 3352//3352 3351//3351 -f 3399//3399 3351//3351 3401//3401 -f 3351//3351 3350//3350 3401//3401 -f 3401//3401 3350//3350 3349//3349 -f 3401//3401 3349//3349 3402//3402 -f 3349//3349 3348//3348 3402//3402 -f 3402//3402 3348//3348 3347//3347 -f 3402//3402 3347//3347 3390//3390 -f 3347//3347 3346//3346 3390//3390 -f 3390//3390 3346//3346 3345//3345 -f 3390//3390 3345//3345 3392//3392 -f 3345//3345 3344//3344 3392//3392 -f 3392//3392 3344//3344 3343//3343 -f 3392//3392 3343//3343 3394//3394 -f 3394//3394 3343//3343 3342//3342 -f 3342//3342 3341//3341 3394//3394 -f 3394//3394 3341//3341 3340//3340 -f 3394//3394 3340//3340 3395//3395 -f 3340//3340 3339//3339 3395//3395 -f 3395//3395 3339//3339 3338//3338 -f 3395//3395 3338//3338 3383//3383 -f 3383//3383 3338//3338 3337//3337 -f 3383//3383 3337//3337 3385//3385 -f 3337//3337 3336//3336 3385//3385 -f 3385//3385 3336//3336 3335//3335 -f 3385//3385 3335//3335 3387//3387 -f 3335//3335 3334//3334 3387//3387 -f 3387//3387 3334//3334 3333//3333 -f 3387//3387 3333//3333 3388//3388 -f 3333//3333 3332//3332 3388//3388 -f 3388//3388 3332//3332 3331//3331 -f 3388//3388 3331//3331 3379//3379 -f 3331//3331 3330//3330 3379//3379 -f 3379//3379 3330//3330 3329//3329 -f 3379//3379 3329//3329 3403//3403 -f 3403//3403 3329//3329 3378//3378 -f 3403//3403 3378//3378 3404//3404 -f 3378//3378 3377//3377 3404//3404 -f 3404//3404 3377//3377 3376//3376 -f 3404//3404 3376//3376 3406//3406 -f 3406//3406 3376//3376 3375//3375 -f 3406//3406 3375//3375 3408//3408 -f 3375//3375 3374//3374 3408//3408 -f 3408//3408 3374//3374 3373//3373 -f 3408//3408 3373//3373 3417//3417 -f 3417//3417 3373//3373 3372//3372 -f 3372//3372 3371//3371 3417//3417 -f 3417//3417 3371//3371 3370//3370 -f 3417//3417 3370//3370 3418//3418 -f 3418//3418 3370//3370 3369//3369 -f 3418//3418 3369//3369 3420//3420 -f 3369//3369 3368//3368 3420//3420 -f 3420//3420 3368//3368 3367//3367 -f 3420//3420 3367//3367 3422//3422 -f 3367//3367 3366//3366 3422//3422 -f 3422//3422 3366//3366 3365//3365 -f 3422//3422 3365//3365 3423//3423 -f 3365//3365 3364//3364 3423//3423 -f 3423//3423 3364//3364 3363//3363 -f 3423//3423 3363//3363 3411//3411 -f 3363//3363 3362//3362 3411//3411 -f 3411//3411 3362//3362 3361//3361 -f 3411//3411 3361//3361 3413//3413 -f 3413//3413 3361//3361 3360//3360 -f 3360//3360 3359//3359 3413//3413 -f 3413//3413 3359//3359 3358//3358 -f 3413//3413 3358//3358 3415//3415 -f 3358//3358 3357//3357 3415//3415 -f 3415//3415 3357//3357 3356//3356 -f 3415//3415 3356//3356 3416//3416 -f 3416//3416 3356//3356 3355//3355 -f 3416//3416 3355//3355 3397//3397 -f 3397//3397 3355//3355 3354//3354 -f 3397//3397 3354//3354 3353//3353 -f 3221//3221 3223//3223 3210//3210 -f 3160//3160 3259//3259 3158//3158 -f 3158//3158 3259//3259 3258//3258 -f 3158//3158 3258//3258 3156//3156 -f 3156//3156 3258//3258 3264//3264 -f 3156//3156 3264//3264 3154//3154 -f 3154//3154 3264//3264 3265//3265 -f 3154//3154 3265//3265 3152//3152 -f 3152//3152 3265//3265 3256//3256 -f 3152//3152 3256//3256 3150//3150 -f 3150//3150 3256//3256 3235//3235 -f 3150//3150 3235//3235 3148//3148 -f 3148//3148 3235//3235 3234//3234 -f 3148//3148 3234//3234 3146//3146 -f 3146//3146 3234//3234 3233//3233 -f 3146//3146 3233//3233 3144//3144 -f 3144//3144 3233//3233 3216//3216 -f 3144//3144 3216//3216 3142//3142 -f 3142//3142 3216//3216 3217//3217 -f 3142//3142 3217//3217 3140//3140 -f 3140//3140 3217//3217 3219//3219 -f 3140//3140 3219//3219 3138//3138 -f 3138//3138 3219//3219 3221//3221 -f 3138//3138 3221//3221 3212//3212 -f 3212//3212 3221//3221 3210//3210 -f 3295//3295 3253//3253 3160//3160 -f 3160//3160 3253//3253 3261//3261 -f 3160//3160 3261//3261 3259//3259 -f 3223//3223 3310//3310 3210//3210 -f 3210//3210 3310//3310 3309//3309 -f 3210//3210 3309//3309 3208//3208 -f 3208//3208 3309//3309 3328//3328 -f 3208//3208 3328//3328 3206//3206 -f 3206//3206 3328//3328 3327//3327 -f 3206//3206 3327//3327 3204//3204 -f 3204//3204 3327//3327 3326//3326 -f 3204//3204 3326//3326 3202//3202 -f 3202//3202 3326//3326 3303//3303 -f 3202//3202 3303//3303 3200//3200 -f 3200//3200 3303//3303 3312//3312 -f 3200//3200 3312//3312 3198//3198 -f 3198//3198 3312//3312 3305//3305 -f 3198//3198 3305//3305 3196//3196 -f 3196//3196 3305//3305 3304//3304 -f 3196//3196 3304//3304 3194//3194 -f 3194//3194 3304//3304 3317//3317 -f 3194//3194 3317//3317 3192//3192 -f 3192//3192 3317//3317 3300//3300 -f 3192//3192 3300//3300 3190//3190 -f 3190//3190 3300//3300 3299//3299 -f 3190//3190 3299//3299 3188//3188 -f 3188//3188 3299//3299 3298//3298 -f 3188//3188 3298//3298 3186//3186 -f 3186//3186 3298//3298 3297//3297 -f 3186//3186 3297//3297 3184//3184 -f 3184//3184 3297//3297 3296//3296 -f 3184//3184 3296//3296 3182//3182 -f 3182//3182 3296//3296 3271//3271 -f 3182//3182 3271//3271 3180//3180 -f 3180//3180 3271//3271 3273//3273 -f 3180//3180 3273//3273 3178//3178 -f 3178//3178 3273//3273 3275//3275 -f 3178//3178 3275//3275 3176//3176 -f 3176//3176 3275//3275 3277//3277 -f 3176//3176 3277//3277 3174//3174 -f 3174//3174 3277//3277 3279//3279 -f 3174//3174 3279//3279 3172//3172 -f 3172//3172 3279//3279 3281//3281 -f 3172//3172 3281//3281 3170//3170 -f 3170//3170 3281//3281 3283//3283 -f 3170//3170 3283//3283 3168//3168 -f 3168//3168 3283//3283 3286//3286 -f 3168//3168 3286//3286 3166//3166 -f 3166//3166 3286//3286 3288//3288 -f 3166//3166 3288//3288 3164//3164 -f 3164//3164 3288//3288 3295//3295 -f 3164//3164 3295//3295 3162//3162 -f 3162//3162 3295//3295 3160//3160 -f 3155//3155 3042//3042 3157//3157 -f 3157//3157 3042//3042 3040//3040 -f 3157//3157 3040//3040 3159//3159 -f 3159//3159 3040//3040 3046//3046 -f 3159//3159 3046//3046 3161//3161 -f 3161//3161 3046//3046 3045//3045 -f 3161//3161 3045//3045 3163//3163 -f 3163//3163 3045//3045 3055//3055 -f 3163//3163 3055//3055 3165//3165 -f 3165//3165 3055//3055 3054//3054 -f 3165//3165 3054//3054 3167//3167 -f 3167//3167 3054//3054 3052//3052 -f 3167//3167 3052//3052 3169//3169 -f 3169//3169 3052//3052 3051//3051 -f 3169//3169 3051//3051 3171//3171 -f 3171//3171 3051//3051 3072//3072 -f 3171//3171 3072//3072 3173//3173 -f 3173//3173 3072//3072 3074//3074 -f 3173//3173 3074//3074 3175//3175 -f 3175//3175 3074//3074 3076//3076 -f 3175//3175 3076//3076 3177//3177 -f 3177//3177 3076//3076 3034//3034 -f 3177//3177 3034//3034 3179//3179 -f 3034//3034 3092//3092 3179//3179 -f 3179//3179 3092//3092 3093//3093 -f 3179//3179 3093//3093 3181//3181 -f 3181//3181 3093//3093 3104//3104 -f 3181//3181 3104//3104 3183//3183 -f 3183//3183 3104//3104 3103//3103 -f 3183//3183 3103//3103 3185//3185 -f 3185//3185 3103//3103 3102//3102 -f 3185//3185 3102//3102 3187//3187 -f 3187//3187 3102//3102 3081//3081 -f 3187//3187 3081//3081 3189//3189 -f 3189//3189 3081//3081 3087//3087 -f 3189//3189 3087//3087 3191//3191 -f 3191//3191 3087//3087 3083//3083 -f 3191//3191 3083//3083 3193//3193 -f 3193//3193 3083//3083 3082//3082 -f 3193//3193 3082//3082 3195//3195 -f 3195//3195 3082//3082 3027//3027 -f 3195//3195 3027//3027 3197//3197 -f 3197//3197 3027//3027 3026//3026 -f 3197//3197 3026//3026 3199//3199 -f 3199//3199 3026//3026 3110//3110 -f 3199//3199 3110//3110 3201//3201 -f 3201//3201 3110//3110 3109//3109 -f 3201//3201 3109//3109 3203//3203 -f 3203//3203 3109//3109 3108//3108 -f 3203//3203 3108//3108 3205//3205 -f 3205//3205 3108//3108 3107//3107 -f 3205//3205 3107//3107 3207//3207 -f 3207//3207 3107//3107 3106//3106 -f 3207//3207 3106//3106 3209//3209 -f 3209//3209 3106//3106 3123//3123 -f 3209//3209 3123//3123 3211//3211 -f 3211//3211 3123//3123 3125//3125 -f 3211//3211 3125//3125 3213//3213 -f 3213//3213 3125//3125 3127//3127 -f 3213//3213 3127//3127 3139//3139 -f 3139//3139 3127//3127 3129//3129 -f 3139//3139 3129//3129 3141//3141 -f 3141//3141 3129//3129 3131//3131 -f 3141//3141 3131//3131 3143//3143 -f 3143//3143 3131//3131 3137//3137 -f 3143//3143 3137//3137 3145//3145 -f 3145//3145 3137//3137 3136//3136 -f 3145//3145 3136//3136 3147//3147 -f 3147//3147 3136//3136 3135//3135 -f 3147//3147 3135//3135 3149//3149 -f 3149//3149 3135//3135 3134//3134 -f 3149//3149 3134//3134 3151//3151 -f 3151//3151 3134//3134 3133//3133 -f 3151//3151 3133//3133 3153//3153 -f 3153//3153 3133//3133 3031//3031 -f 3153//3153 3031//3031 3155//3155 -f 3155//3155 3031//3031 3050//3050 -f 3155//3155 3050//3050 3042//3042 -f 3565//3565 3566//3566 3567//3567 -f 3567//3567 3566//3566 3568//3568 -f 3568//3568 3569//3569 3570//3570 -f 3571//3571 3572//3572 3573//3573 -f 3573//3573 3572//3572 3574//3574 -f 3573//3573 3574//3574 3575//3575 -f 3576//3576 3577//3577 3578//3578 -f 3578//3578 3577//3577 3579//3579 -f 3570//3570 3580//3580 3568//3568 -f 3568//3568 3580//3580 3581//3581 -f 3568//3568 3581//3581 3567//3567 -f 3567//3567 3581//3581 3575//3575 -f 3579//3579 3577//3577 3582//3582 -f 3582//3582 3577//3577 3583//3583 -f 3582//3582 3583//3583 3584//3584 -f 3585//3585 3586//3586 3587//3587 -f 3587//3587 3586//3586 3588//3588 -f 3587//3587 3588//3588 3589//3589 -f 3589//3589 3588//3588 3590//3590 -f 3588//3588 3591//3591 3590//3590 -f 3590//3590 3591//3591 3592//3592 -f 3590//3590 3592//3592 3593//3593 -f 3593//3593 3592//3592 3594//3594 -f 3595//3595 3596//3596 3597//3597 -f 3597//3597 3596//3596 3598//3598 -f 3597//3597 3598//3598 3599//3599 -f 3599//3599 3598//3598 3600//3600 -f 3599//3599 3600//3600 3601//3601 -f 3601//3601 3600//3600 3602//3602 -f 3603//3603 3576//3576 3595//3595 -f 3595//3595 3576//3576 3604//3604 -f 3595//3595 3604//3604 3596//3596 -f 3594//3594 3577//3577 3593//3593 -f 3593//3593 3577//3577 3576//3576 -f 3593//3593 3576//3576 3605//3605 -f 3605//3605 3576//3576 3603//3603 -f 3606//3606 3607//3607 3608//3608 -f 3608//3608 3607//3607 3609//3609 -f 3608//3608 3609//3609 3569//3569 -f 3569//3569 3609//3609 3610//3610 -f 3569//3569 3610//3610 3570//3570 -f 3574//3574 3611//3611 3575//3575 -f 3575//3575 3611//3611 3612//3612 -f 3575//3575 3612//3612 3567//3567 -f 3567//3567 3612//3612 3613//3613 -f 3567//3567 3613//3613 3614//3614 -f 3614//3614 3613//3613 3615//3615 -f 3614//3614 3615//3615 3616//3616 -f 3616//3616 3615//3615 3617//3617 -f 3616//3616 3617//3617 3602//3602 -f 3602//3602 3617//3617 3618//3618 -f 3602//3602 3618//3618 3601//3601 -f 3601//3601 3618//3618 3619//3619 -f 3601//3601 3619//3619 3620//3620 -f 3620//3620 3619//3619 3621//3621 -f 3620//3620 3621//3621 3622//3622 -f 3584//3584 3623//3623 3582//3582 -f 3582//3582 3623//3623 3567//3567 -f 3582//3582 3567//3567 3624//3624 -f 3624//3624 3567//3567 3614//3614 -f 3623//3623 3625//3625 3567//3567 -f 3567//3567 3625//3625 3626//3626 -f 3567//3567 3626//3626 3585//3585 -f 3585//3585 3626//3626 3627//3627 -f 3585//3585 3627//3627 3586//3586 -f 3571//3571 3628//3628 3572//3572 -f 3572//3572 3628//3628 3629//3629 -f 3572//3572 3629//3629 3630//3630 -f 3630//3630 3629//3629 3631//3631 -f 3630//3630 3631//3631 3607//3607 -f 3607//3607 3631//3631 3632//3632 -f 3607//3607 3632//3632 3609//3609 -f 3621//3621 3633//3633 3622//3622 -f 3622//3622 3633//3633 3634//3634 -f 3622//3622 3634//3634 3635//3635 -f 3635//3635 3634//3634 3572//3572 -f 3635//3635 3572//3572 3636//3636 -f 3636//3636 3572//3572 3630//3630 -f 3637//3637 3638//3638 3639//3639 -f 3640//3640 3641//3641 3642//3642 -f 3642//3642 3641//3641 3637//3637 -f 3643//3643 3644//3644 3645//3645 -f 3646//3646 3647//3647 3648//3648 -f 3648//3648 3647//3647 3649//3649 -f 3648//3648 3649//3649 3650//3650 -f 3650//3650 3649//3649 3651//3651 -f 3650//3650 3651//3651 3652//3652 -f 3653//3653 3654//3654 3655//3655 -f 3642//3642 3656//3656 3657//3657 -f 3642//3642 3658//3658 3659//3659 -f 3660//3660 3645//3645 3661//3661 -f 3661//3661 3645//3645 3644//3644 -f 3661//3661 3644//3644 3638//3638 -f 3638//3638 3644//3644 3662//3662 -f 3638//3638 3662//3662 3639//3639 -f 3663//3663 3664//3664 3665//3665 -f 3666//3666 3667//3667 3652//3652 -f 3642//3642 3659//3659 3668//3668 -f 3659//3659 3669//3669 3668//3668 -f 3668//3668 3669//3669 3670//3670 -f 3668//3668 3670//3670 3671//3671 -f 3671//3671 3670//3670 3646//3646 -f 3671//3671 3646//3646 3672//3672 -f 3672//3672 3646//3646 3648//3648 -f 3673//3673 3674//3674 3675//3675 -f 3675//3675 3674//3674 3676//3676 -f 3676//3676 3650//3650 3675//3675 -f 3675//3675 3650//3650 3652//3652 -f 3675//3675 3652//3652 3677//3677 -f 3677//3677 3652//3652 3667//3667 -f 3678//3678 3679//3679 3680//3680 -f 3680//3680 3679//3679 3681//3681 -f 3680//3680 3681//3681 3682//3682 -f 3682//3682 3681//3681 3683//3683 -f 3682//3682 3683//3683 3684//3684 -f 3637//3637 3639//3639 3642//3642 -f 3642//3642 3639//3639 3685//3685 -f 3642//3642 3685//3685 3656//3656 -f 3658//3658 3642//3642 3686//3686 -f 3686//3686 3642//3642 3657//3657 -f 3686//3686 3657//3657 3687//3687 -f 3687//3687 3657//3657 3688//3688 -f 3687//3687 3688//3688 3689//3689 -f 3655//3655 3663//3663 3653//3653 -f 3653//3653 3663//3663 3665//3665 -f 3653//3653 3665//3665 3690//3690 -f 3690//3690 3665//3665 3666//3666 -f 3690//3690 3666//3666 3688//3688 -f 3688//3688 3666//3666 3652//3652 -f 3688//3688 3652//3652 3689//3689 -f 3643//3643 3645//3645 3691//3691 -f 3691//3691 3645//3645 3692//3692 -f 3691//3691 3692//3692 3693//3693 -f 3693//3693 3692//3692 3694//3694 -f 3693//3693 3694//3694 3653//3653 -f 3653//3653 3694//3694 3695//3695 -f 3653//3653 3695//3695 3654//3654 -f 3683//3683 3696//3696 3684//3684 -f 3684//3684 3696//3696 3697//3697 -f 3684//3684 3697//3697 3698//3698 -f 3698//3698 3697//3697 3694//3694 -f 3698//3698 3694//3694 3699//3699 -f 3699//3699 3694//3694 3692//3692 -f 3675//3675 3700//3700 3673//3673 -f 3673//3673 3700//3700 3701//3701 -f 3673//3673 3701//3701 3702//3702 -f 3702//3702 3701//3701 3703//3703 -f 3702//3702 3703//3703 3678//3678 -f 3678//3678 3703//3703 3704//3704 -f 3678//3678 3704//3704 3679//3679 -f 3679//3679 3704//3704 3705//3705 -f 3679//3679 3705//3705 3706//3706 -f 3706//3706 3705//3705 3707//3707 -f 3706//3706 3707//3707 3664//3664 -f 3664//3664 3707//3707 3708//3708 -f 3664//3664 3708//3708 3665//3665 -f 3678//3678 3680//3680 3601//3601 -f 3601//3601 3680//3680 3599//3599 -f 3590//3590 3593//3593 3645//3645 -f 3645//3645 3593//3593 3692//3692 -f 3638//3638 3637//3637 3585//3585 -f 3585//3585 3637//3637 3567//3567 -f 3565//3565 3567//3567 3641//3641 -f 3641//3641 3567//3567 3637//3637 -f 3566//3566 3565//3565 3640//3640 -f 3640//3640 3565//3565 3641//3641 -f 3568//3568 3566//3566 3642//3642 -f 3642//3642 3566//3566 3640//3640 -f 3569//3569 3568//3568 3668//3668 -f 3668//3668 3568//3568 3642//3642 -f 3648//3648 3650//3650 3607//3607 -f 3607//3607 3650//3650 3630//3630 -f 3621//3621 3703//3703 3633//3633 -f 3633//3633 3703//3703 3701//3701 -f 3633//3633 3701//3701 3634//3634 -f 3634//3634 3701//3701 3700//3700 -f 3634//3634 3700//3700 3572//3572 -f 3572//3572 3700//3700 3675//3675 -f 3572//3572 3675//3675 3574//3574 -f 3574//3574 3675//3675 3677//3677 -f 3574//3574 3677//3677 3611//3611 -f 3611//3611 3677//3677 3667//3667 -f 3611//3611 3667//3667 3612//3612 -f 3612//3612 3667//3667 3666//3666 -f 3612//3612 3666//3666 3613//3613 -f 3613//3613 3666//3666 3665//3665 -f 3613//3613 3665//3665 3615//3615 -f 3615//3615 3665//3665 3708//3708 -f 3615//3615 3708//3708 3617//3617 -f 3617//3617 3708//3708 3707//3707 -f 3617//3617 3707//3707 3618//3618 -f 3618//3618 3707//3707 3705//3705 -f 3618//3618 3705//3705 3619//3619 -f 3619//3619 3705//3705 3704//3704 -f 3619//3619 3704//3704 3621//3621 -f 3621//3621 3704//3704 3703//3703 -f 3628//3628 3652//3652 3629//3629 -f 3629//3629 3652//3652 3651//3651 -f 3629//3629 3651//3651 3631//3631 -f 3631//3631 3651//3651 3649//3649 -f 3631//3631 3649//3649 3632//3632 -f 3632//3632 3649//3649 3647//3647 -f 3632//3632 3647//3647 3609//3609 -f 3609//3609 3647//3647 3646//3646 -f 3609//3609 3646//3646 3610//3610 -f 3610//3610 3646//3646 3670//3670 -f 3610//3610 3670//3670 3570//3570 -f 3570//3570 3670//3670 3669//3669 -f 3570//3570 3669//3669 3580//3580 -f 3580//3580 3669//3669 3659//3659 -f 3580//3580 3659//3659 3581//3581 -f 3581//3581 3659//3659 3658//3658 -f 3581//3581 3658//3658 3575//3575 -f 3575//3575 3658//3658 3686//3686 -f 3575//3575 3686//3686 3573//3573 -f 3573//3573 3686//3686 3687//3687 -f 3573//3573 3687//3687 3571//3571 -f 3571//3571 3687//3687 3689//3689 -f 3571//3571 3689//3689 3628//3628 -f 3628//3628 3689//3689 3652//3652 -f 3577//3577 3653//3653 3583//3583 -f 3583//3583 3653//3653 3690//3690 -f 3583//3583 3690//3690 3584//3584 -f 3584//3584 3690//3690 3688//3688 -f 3584//3584 3688//3688 3623//3623 -f 3623//3623 3688//3688 3657//3657 -f 3623//3623 3657//3657 3625//3625 -f 3625//3625 3657//3657 3656//3656 -f 3625//3625 3656//3656 3626//3626 -f 3626//3626 3656//3656 3685//3685 -f 3626//3626 3685//3685 3627//3627 -f 3627//3627 3685//3685 3639//3639 -f 3627//3627 3639//3639 3586//3586 -f 3586//3586 3639//3639 3662//3662 -f 3586//3586 3662//3662 3588//3588 -f 3588//3588 3662//3662 3644//3644 -f 3588//3588 3644//3644 3591//3591 -f 3591//3591 3644//3644 3643//3643 -f 3591//3591 3643//3643 3592//3592 -f 3592//3592 3643//3643 3691//3691 -f 3592//3592 3691//3691 3594//3594 -f 3594//3594 3691//3691 3693//3693 -f 3594//3594 3693//3693 3577//3577 -f 3577//3577 3693//3693 3653//3653 -f 3598//3598 3683//3683 3600//3600 -f 3600//3600 3683//3683 3681//3681 -f 3600//3600 3681//3681 3602//3602 -f 3602//3602 3681//3681 3679//3679 -f 3602//3602 3679//3679 3616//3616 -f 3616//3616 3679//3679 3706//3706 -f 3616//3616 3706//3706 3614//3614 -f 3614//3614 3706//3706 3664//3664 -f 3614//3614 3664//3664 3624//3624 -f 3624//3624 3664//3664 3663//3663 -f 3624//3624 3663//3663 3582//3582 -f 3582//3582 3663//3663 3655//3655 -f 3582//3582 3655//3655 3579//3579 -f 3579//3579 3655//3655 3654//3654 -f 3579//3579 3654//3654 3578//3578 -f 3578//3578 3654//3654 3695//3695 -f 3578//3578 3695//3695 3576//3576 -f 3576//3576 3695//3695 3694//3694 -f 3576//3576 3694//3694 3604//3604 -f 3604//3604 3694//3694 3697//3697 -f 3604//3604 3697//3697 3596//3596 -f 3596//3596 3697//3697 3696//3696 -f 3596//3596 3696//3696 3598//3598 -f 3598//3598 3696//3696 3683//3683 -f 3630//3630 3650//3650 3676//3676 -f 3630//3630 3676//3676 3636//3636 -f 3636//3636 3676//3676 3674//3674 -f 3636//3636 3674//3674 3635//3635 -f 3635//3635 3674//3674 3673//3673 -f 3635//3635 3673//3673 3622//3622 -f 3622//3622 3673//3673 3702//3702 -f 3622//3622 3702//3702 3620//3620 -f 3620//3620 3702//3702 3678//3678 -f 3620//3620 3678//3678 3601//3601 -f 3599//3599 3680//3680 3682//3682 -f 3599//3599 3682//3682 3597//3597 -f 3597//3597 3682//3682 3684//3684 -f 3597//3597 3684//3684 3595//3595 -f 3595//3595 3684//3684 3698//3698 -f 3595//3595 3698//3698 3603//3603 -f 3603//3603 3698//3698 3699//3699 -f 3603//3603 3699//3699 3605//3605 -f 3605//3605 3699//3699 3692//3692 -f 3605//3605 3692//3692 3593//3593 -f 3569//3569 3668//3668 3671//3671 -f 3569//3569 3671//3671 3608//3608 -f 3608//3608 3671//3671 3672//3672 -f 3608//3608 3672//3672 3606//3606 -f 3606//3606 3672//3672 3648//3648 -f 3606//3606 3648//3648 3607//3607 -f 3590//3590 3645//3645 3660//3660 -f 3590//3590 3660//3660 3589//3589 -f 3589//3589 3660//3660 3661//3661 -f 3589//3589 3661//3661 3587//3587 -f 3587//3587 3661//3661 3638//3638 -f 3587//3587 3638//3638 3585//3585 -f 3709//3709 3710//3710 3711//3711 -f 3712//3712 3713//3713 3714//3714 -f 3715//3715 3716//3716 3717//3717 -f 3718//3718 3719//3719 3720//3720 -f 3721//3721 3722//3722 3723//3723 -f 3723//3723 3722//3722 3724//3724 -f 3725//3725 3726//3726 3727//3727 -f 3727//3727 3726//3726 3728//3728 -f 3719//3719 3729//3729 3720//3720 -f 3720//3720 3729//3729 3730//3730 -f 3720//3720 3730//3730 3721//3721 -f 3721//3721 3730//3730 3731//3731 -f 3721//3721 3731//3731 3722//3722 -f 3720//3720 3732//3732 3718//3718 -f 3718//3718 3732//3732 3733//3733 -f 3718//3718 3733//3733 3734//3734 -f 3734//3734 3733//3733 3735//3735 -f 3734//3734 3735//3735 3736//3736 -f 3736//3736 3735//3735 3737//3737 -f 3736//3736 3737//3737 3728//3728 -f 3728//3728 3737//3737 3738//3738 -f 3728//3728 3738//3738 3727//3727 -f 3720//3720 3739//3739 3732//3732 -f 3732//3732 3739//3739 3740//3740 -f 3732//3732 3740//3740 3741//3741 -f 3741//3741 3740//3740 3742//3742 -f 3741//3741 3742//3742 3743//3743 -f 3743//3743 3742//3742 3744//3744 -f 3745//3745 3746//3746 3747//3747 -f 3747//3747 3746//3746 3748//3748 -f 3747//3747 3748//3748 3744//3744 -f 3744//3744 3748//3748 3749//3749 -f 3744//3744 3749//3749 3750//3750 -f 3751//3751 3752//3752 3753//3753 -f 3753//3753 3752//3752 3754//3754 -f 3755//3755 3756//3756 3757//3757 -f 3757//3757 3756//3756 3758//3758 -f 3757//3757 3758//3758 3759//3759 -f 3759//3759 3758//3758 3760//3760 -f 3759//3759 3760//3760 3761//3761 -f 3751//3751 3753//3753 3750//3750 -f 3750//3750 3753//3753 3762//3762 -f 3750//3750 3762//3762 3744//3744 -f 3744//3744 3762//3762 3763//3763 -f 3744//3744 3763//3763 3743//3743 -f 3764//3764 3754//3754 3765//3765 -f 3765//3765 3754//3754 3766//3766 -f 3765//3765 3766//3766 3767//3767 -f 3767//3767 3766//3766 3768//3768 -f 3767//3767 3768//3768 3769//3769 -f 3752//3752 3755//3755 3754//3754 -f 3754//3754 3755//3755 3757//3757 -f 3754//3754 3757//3757 3766//3766 -f 3766//3766 3757//3757 3770//3770 -f 3766//3766 3770//3770 3768//3768 -f 3768//3768 3770//3770 3771//3771 -f 3772//3772 3773//3773 3709//3709 -f 3709//3709 3773//3773 3774//3774 -f 3775//3775 3771//3771 3776//3776 -f 3776//3776 3771//3771 3777//3777 -f 3776//3776 3777//3777 3778//3778 -f 3778//3778 3777//3777 3779//3779 -f 3780//3780 3781//3781 3782//3782 -f 3782//3782 3781//3781 3783//3783 -f 3782//3782 3783//3783 3784//3784 -f 3783//3783 3785//3785 3784//3784 -f 3784//3784 3785//3785 3786//3786 -f 3784//3784 3786//3786 3787//3787 -f 3787//3787 3786//3786 3788//3788 -f 3787//3787 3788//3788 3789//3789 -f 3790//3790 3791//3791 3792//3792 -f 3792//3792 3791//3791 3793//3793 -f 3792//3792 3793//3793 3794//3794 -f 3794//3794 3793//3793 3795//3795 -f 3790//3790 3796//3796 3791//3791 -f 3791//3791 3796//3796 3797//3797 -f 3791//3791 3797//3797 3781//3781 -f 3798//3798 3717//3717 3799//3799 -f 3799//3799 3717//3717 3800//3800 -f 3799//3799 3800//3800 3801//3801 -f 3797//3797 3802//3802 3781//3781 -f 3781//3781 3802//3802 3803//3803 -f 3781//3781 3803//3803 3783//3783 -f 3783//3783 3803//3803 3804//3804 -f 3783//3783 3804//3804 3805//3805 -f 3805//3805 3804//3804 3801//3801 -f 3805//3805 3801//3801 3806//3806 -f 3806//3806 3801//3801 3800//3800 -f 3715//3715 3717//3717 3807//3807 -f 3807//3807 3717//3717 3808//3808 -f 3807//3807 3808//3808 3809//3809 -f 3809//3809 3808//3808 3810//3810 -f 3809//3809 3810//3810 3811//3811 -f 3811//3811 3810//3810 3812//3812 -f 3811//3811 3812//3812 3813//3813 -f 3813//3813 3812//3812 3714//3714 -f 3714//3714 3812//3812 3814//3814 -f 3714//3714 3814//3814 3712//3712 -f 3815//3815 3816//3816 3812//3812 -f 3812//3812 3816//3816 3817//3817 -f 3812//3812 3817//3817 3818//3818 -f 3819//3819 3814//3814 3820//3820 -f 3820//3820 3814//3814 3812//3812 -f 3820//3820 3812//3812 3821//3821 -f 3821//3821 3812//3812 3818//3818 -f 3822//3822 3823//3823 3815//3815 -f 3815//3815 3823//3823 3824//3824 -f 3815//3815 3824//3824 3816//3816 -f 3821//3821 3825//3825 3820//3820 -f 3820//3820 3825//3825 3826//3826 -f 3820//3820 3826//3826 3827//3827 -f 3827//3827 3826//3826 3828//3828 -f 3828//3828 3829//3829 3827//3827 -f 3827//3827 3829//3829 3830//3830 -f 3827//3827 3830//3830 3822//3822 -f 3822//3822 3830//3830 3831//3831 -f 3822//3822 3831//3831 3823//3823 -f 3832//3832 3833//3833 3834//3834 -f 3834//3834 3835//3835 3832//3832 -f 3832//3832 3835//3835 3836//3836 -f 3832//3832 3836//3836 3810//3810 -f 3810//3810 3836//3836 3837//3837 -f 3810//3810 3837//3837 3838//3838 -f 3838//3838 3839//3839 3810//3810 -f 3810//3810 3839//3839 3840//3840 -f 3810//3810 3840//3840 3812//3812 -f 3812//3812 3840//3840 3841//3841 -f 3812//3812 3841//3841 3815//3815 -f 3839//3839 3842//3842 3840//3840 -f 3840//3840 3842//3842 3843//3843 -f 3840//3840 3843//3843 3844//3844 -f 3844//3844 3843//3843 3845//3845 -f 3845//3845 3846//3846 3844//3844 -f 3844//3844 3846//3846 3847//3847 -f 3844//3844 3847//3847 3833//3833 -f 3833//3833 3847//3847 3848//3848 -f 3833//3833 3848//3848 3834//3834 -f 3849//3849 3850//3850 3851//3851 -f 3852//3852 3853//3853 3854//3854 -f 3854//3854 3853//3853 3855//3855 -f 3854//3854 3855//3855 3856//3856 -f 3856//3856 3855//3855 3857//3857 -f 3798//3798 3795//3795 3717//3717 -f 3717//3717 3795//3795 3793//3793 -f 3717//3717 3793//3793 3808//3808 -f 3808//3808 3793//3793 3858//3858 -f 3808//3808 3858//3858 3849//3849 -f 3851//3851 3859//3859 3849//3849 -f 3849//3849 3859//3859 3860//3860 -f 3849//3849 3860//3860 3808//3808 -f 3808//3808 3860//3860 3861//3861 -f 3808//3808 3861//3861 3862//3862 -f 3862//3862 3857//3857 3808//3808 -f 3808//3808 3857//3857 3855//3855 -f 3808//3808 3855//3855 3810//3810 -f 3810//3810 3855//3855 3863//3863 -f 3810//3810 3863//3863 3832//3832 -f 3852//3852 3864//3864 3853//3853 -f 3853//3853 3864//3864 3865//3865 -f 3853//3853 3865//3865 3850//3850 -f 3850//3850 3865//3865 3866//3866 -f 3850//3850 3866//3866 3851//3851 -f 3775//3775 3867//3867 3771//3771 -f 3771//3771 3867//3867 3868//3868 -f 3771//3771 3868//3868 3768//3768 -f 3768//3768 3868//3868 3869//3869 -f 3768//3768 3869//3869 3870//3870 -f 3870//3870 3869//3869 3871//3871 -f 3870//3870 3871//3871 3872//3872 -f 3872//3872 3871//3871 3873//3873 -f 3872//3872 3873//3873 3874//3874 -f 3874//3874 3873//3873 3772//3772 -f 3874//3874 3772//3772 3788//3788 -f 3788//3788 3772//3772 3709//3709 -f 3788//3788 3709//3709 3789//3789 -f 3789//3789 3709//3709 3711//3711 -f 3875//3875 3710//3710 3777//3777 -f 3777//3777 3710//3710 3709//3709 -f 3777//3777 3709//3709 3779//3779 -f 3779//3779 3709//3709 3774//3774 -f 3876//3876 3877//3877 3747//3747 -f 3747//3747 3877//3877 3759//3759 -f 3747//3747 3759//3759 3745//3745 -f 3745//3745 3759//3759 3761//3761 -f 3878//3878 3739//3739 3879//3879 -f 3879//3879 3739//3739 3720//3720 -f 3879//3879 3720//3720 3880//3880 -f 3880//3880 3720//3720 3721//3721 -f 3881//3881 3882//3882 3883//3883 -f 3884//3884 3885//3885 3886//3886 -f 3887//3887 3888//3888 3889//3889 -f 3889//3889 3888//3888 3886//3886 -f 3890//3890 3891//3891 3892//3892 -f 3892//3892 3891//3891 3887//3887 -f 3892//3892 3887//3887 3893//3893 -f 3893//3893 3887//3887 3889//3889 -f 3724//3724 3725//3725 3723//3723 -f 3723//3723 3725//3725 3727//3727 -f 3723//3723 3727//3727 3894//3894 -f 3894//3894 3727//3727 3883//3883 -f 3894//3894 3883//3883 3895//3895 -f 3895//3895 3883//3883 3882//3882 -f 3895//3895 3882//3882 3884//3884 -f 3884//3884 3882//3882 3896//3896 -f 3884//3884 3896//3896 3885//3885 -f 3890//3890 3897//3897 3891//3891 -f 3891//3891 3897//3897 3898//3898 -f 3891//3891 3898//3898 3883//3883 -f 3883//3883 3898//3898 3899//3899 -f 3883//3883 3899//3899 3881//3881 -f 3886//3886 3888//3888 3884//3884 -f 3884//3884 3888//3888 3900//3900 -f 3884//3884 3900//3900 3901//3901 -f 3902//3902 3903//3903 3891//3891 -f 3904//3904 3905//3905 3906//3906 -f 3906//3906 3905//3905 3907//3907 -f 3908//3908 3909//3909 3910//3910 -f 3910//3910 3909//3909 3907//3907 -f 3904//3904 3906//3906 3903//3903 -f 3903//3903 3906//3906 3911//3911 -f 3903//3903 3911//3911 3891//3891 -f 3891//3891 3911//3911 3912//3912 -f 3891//3891 3912//3912 3887//3887 -f 3910//3910 3913//3913 3908//3908 -f 3908//3908 3913//3913 3914//3914 -f 3908//3908 3914//3914 3915//3915 -f 3915//3915 3914//3914 3916//3916 -f 3916//3916 3917//3917 3915//3915 -f 3915//3915 3917//3917 3918//3918 -f 3915//3915 3918//3918 3891//3891 -f 3891//3891 3918//3918 3919//3919 -f 3891//3891 3919//3919 3902//3902 -f 3907//3907 3909//3909 3906//3906 -f 3906//3906 3909//3909 3920//3920 -f 3906//3906 3920//3920 3921//3921 -f 3922//3922 3923//3923 3915//3915 -f 3924//3924 3925//3925 3926//3926 -f 3927//3927 3928//3928 3929//3929 -f 3929//3929 3928//3928 3924//3924 -f 3929//3929 3924//3924 3915//3915 -f 3930//3930 3931//3931 3924//3924 -f 3924//3924 3931//3931 3932//3932 -f 3924//3924 3932//3932 3933//3933 -f 3934//3934 3935//3935 3936//3936 -f 3936//3936 3935//3935 3937//3937 -f 3924//3924 3926//3926 3930//3930 -f 3930//3930 3926//3926 3938//3938 -f 3930//3930 3938//3938 3937//3937 -f 3933//3933 3939//3939 3924//3924 -f 3924//3924 3939//3939 3940//3940 -f 3924//3924 3940//3940 3915//3915 -f 3915//3915 3940//3940 3941//3941 -f 3915//3915 3941//3941 3922//3922 -f 3934//3934 3936//3936 3923//3923 -f 3923//3923 3936//3936 3942//3942 -f 3923//3923 3942//3942 3915//3915 -f 3915//3915 3942//3942 3943//3943 -f 3915//3915 3943//3943 3908//3908 -f 3937//3937 3938//3938 3936//3936 -f 3936//3936 3938//3938 3944//3944 -f 3936//3936 3944//3944 3945//3945 -f 3727//3727 3946//3946 3947//3947 -f 3948//3948 3949//3949 3950//3950 -f 3950//3950 3949//3949 3929//3929 -f 3950//3950 3929//3929 3951//3951 -f 3951//3951 3929//3929 3915//3915 -f 3951//3951 3915//3915 3952//3952 -f 3952//3952 3915//3915 3891//3891 -f 3952//3952 3891//3891 3947//3947 -f 3947//3947 3891//3891 3883//3883 -f 3947//3947 3883//3883 3727//3727 -f 3953//3953 3954//3954 3764//3764 -f 3953//3953 3764//3764 3955//3955 -f 3955//3955 3764//3764 3765//3765 -f 3955//3955 3765//3765 3767//3767 -f 3956//3956 3957//3957 3958//3958 -f 3959//3959 3960//3960 3961//3961 -f 3960//3960 3962//3962 3961//3961 -f 3961//3961 3962//3962 3963//3963 -f 3961//3961 3963//3963 3964//3964 -f 3965//3965 3966//3966 3961//3961 -f 3961//3961 3966//3966 3956//3956 -f 3956//3956 3958//3958 3961//3961 -f 3961//3961 3958//3958 3967//3967 -f 3961//3961 3967//3967 3959//3959 -f 3968//3968 3969//3969 3970//3970 -f 3970//3970 3969//3969 3964//3964 -f 3970//3970 3964//3964 3971//3971 -f 3971//3971 3964//3964 3963//3963 -f 3601//3601 3599//3599 3972//3972 -f 3972//3972 3599//3599 3973//3973 -f 3974//3974 3601//3601 3975//3975 -f 3975//3975 3601//3601 3972//3972 -f 3975//3975 3972//3972 3976//3976 -f 3976//3976 3972//3972 3977//3977 -f 3950//3950 3951//3951 3978//3978 -f 3950//3950 3978//3978 3979//3979 -f 3980//3980 3981//3981 3982//3982 -f 3983//3983 3984//3984 3985//3985 -f 3985//3985 3984//3984 3986//3986 -f 3985//3985 3986//3986 3987//3987 -f 3987//3987 3986//3986 3988//3988 -f 3987//3987 3988//3988 3989//3989 -f 3989//3989 3988//3988 3990//3990 -f 3989//3989 3990//3990 3991//3991 -f 3991//3991 3990//3990 3992//3992 -f 3993//3993 3994//3994 3995//3995 -f 3995//3995 3994//3994 3996//3996 -f 3995//3995 3996//3996 3997//3997 -f 3997//3997 3996//3996 3998//3998 -f 3997//3997 3998//3998 3999//3999 -f 3999//3999 3998//3998 4000//4000 -f 4000//4000 4001//4001 3999//3999 -f 3999//3999 4001//4001 4002//4002 -f 3999//3999 4002//4002 4003//4003 -f 4003//4003 4002//4002 4004//4004 -f 4001//4001 4005//4005 4002//4002 -f 4002//4002 4005//4005 4006//4006 -f 4002//4002 4006//4006 3983//3983 -f 3983//3983 4006//4006 4007//4007 -f 3983//3983 4007//4007 3984//3984 -f 3995//3995 4008//4008 3993//3993 -f 3993//3993 4008//4008 4009//4009 -f 3993//3993 4009//4009 3981//3981 -f 3981//3981 4009//4009 4010//4010 -f 3981//3981 4010//4010 3982//3982 -f 4011//4011 4012//4012 4013//4013 -f 4013//4013 4012//4012 4014//4014 -f 4013//4013 4014//4014 4015//4015 -f 4015//4015 4014//4014 4016//4016 -f 4015//4015 4016//4016 3982//3982 -f 3982//3982 4016//4016 4017//4017 -f 3982//3982 4017//4017 3980//3980 -f 4018//4018 4019//4019 3990//3990 -f 3990//3990 4019//4019 4020//4020 -f 3990//3990 4020//4020 3992//3992 -f 4018//4018 4021//4021 4019//4019 -f 4019//4019 4021//4021 4022//4022 -f 4019//4019 4022//4022 3978//3978 -f 3978//3978 4022//4022 4023//4023 -f 3978//3978 4023//4023 4024//4024 -f 4024//4024 4025//4025 3978//3978 -f 3978//3978 4025//4025 4011//4011 -f 3978//3978 4011//4011 3979//3979 -f 3979//3979 4011//4011 4013//4013 -f 3599//3599 3597//3597 3973//3973 -f 3973//3973 3597//3597 4026//4026 -f 4026//4026 3597//3597 4027//4027 -f 4027//4027 3597//3597 3595//3595 -f 4027//4027 3595//3595 4028//4028 -f 4028//4028 3595//3595 4029//4029 -f 4029//4029 3595//3595 3603//3603 -f 4029//4029 3603//3603 4030//4030 -f 4030//4030 3603//3603 4031//4031 -f 4031//4031 3603//3603 3605//3605 -f 4031//4031 3605//3605 4032//4032 -f 4033//4033 4034//4034 4035//4035 -f 4032//4032 3605//3605 4035//4035 -f 4035//4035 3605//3605 3593//3593 -f 4035//4035 3593//3593 4033//4033 -f 4036//4036 4037//4037 4038//4038 -f 4039//4039 4040//4040 4041//4041 -f 4036//4036 4038//4038 4042//4042 -f 4038//4038 4043//4043 4042//4042 -f 4042//4042 4043//4043 4044//4044 -f 4042//4042 4044//4044 4045//4045 -f 4039//4039 4041//4041 4046//4046 -f 4041//4041 4047//4047 4046//4046 -f 4046//4046 4047//4047 4048//4048 -f 4046//4046 4048//4048 4036//4036 -f 4036//4036 4048//4048 4049//4049 -f 4036//4036 4049//4049 4037//4037 -f 4044//4044 4050//4050 4045//4045 -f 4045//4045 4050//4050 4051//4051 -f 4045//4045 4051//4051 4039//4039 -f 4039//4039 4051//4051 4052//4052 -f 4039//4039 4052//4052 4040//4040 -f 4053//4053 4054//4054 4055//4055 -f 4055//4055 4054//4054 4056//4056 -f 4057//4057 4058//4058 4059//4059 -f 4059//4059 4058//4058 4060//4060 -f 4060//4060 4061//4061 4059//4059 -f 4059//4059 4061//4061 4062//4062 -f 4059//4059 4062//4062 4063//4063 -f 4062//4062 4064//4064 4063//4063 -f 4063//4063 4064//4064 4065//4065 -f 4063//4063 4065//4065 4053//4053 -f 4053//4053 4065//4065 4066//4066 -f 4053//4053 4066//4066 4054//4054 -f 4056//4056 4067//4067 4055//4055 -f 4055//4055 4067//4067 4068//4068 -f 4055//4055 4068//4068 4057//4057 -f 4057//4057 4068//4068 4069//4069 -f 4057//4057 4069//4069 4058//4058 -f 4070//4070 4071//4071 4072//4072 -f 4072//4072 4071//4071 4073//4073 -f 4074//4074 4075//4075 4070//4070 -f 4070//4070 4075//4075 4076//4076 -f 4070//4070 4076//4076 4071//4071 -f 4073//4073 4077//4077 4072//4072 -f 4072//4072 4077//4077 4078//4078 -f 4072//4072 4078//4078 4079//4079 -f 4080//4080 4081//4081 4082//4082 -f 4082//4082 4081//4081 4079//4079 -f 4082//4082 4079//4079 4083//4083 -f 4083//4083 4079//4079 4078//4078 -f 4080//4080 4084//4084 4081//4081 -f 4081//4081 4084//4084 4085//4085 -f 4081//4081 4085//4085 4074//4074 -f 4074//4074 4085//4085 4086//4086 -f 4074//4074 4086//4086 4075//4075 -f 4087//4087 4088//4088 4089//4089 -f 4089//4089 4088//4088 4090//4090 -f 4091//4091 4092//4092 4093//4093 -f 3596//3596 3604//3604 3595//3595 -f 4094//4094 4095//4095 4096//4096 -f 4096//4096 4095//4095 4097//4097 -f 3595//3595 3604//3604 3603//3603 -f 3603//3603 3604//3604 3576//3576 -f 3603//3603 3576//3576 3605//3605 -f 4098//4098 4099//4099 4100//4100 -f 4100//4100 4099//4099 4101//4101 -f 4102//4102 4103//4103 4104//4104 -f 4104//4104 4103//4103 4105//4105 -f 4104//4104 4105//4105 4106//4106 -f 4107//4107 4108//4108 4109//4109 -f 4110//4110 4111//4111 4112//4112 -f 4112//4112 4111//4111 4113//4113 -f 4114//4114 4115//4115 4116//4116 -f 4117//4117 3628//3628 3572//3572 -f 4118//4118 4119//4119 4120//4120 -f 4120//4120 4119//4119 4121//4121 -f 3622//3622 3635//3635 3572//3572 -f 4122//4122 4123//4123 4124//4124 -f 4124//4124 4123//4123 4125//4125 -f 3609//3609 4126//4126 4127//4127 -f 4128//4128 4129//4129 4130//4130 -f 4130//4130 4129//4129 4131//4131 -f 4132//4132 4133//4133 4134//4134 -f 4134//4134 4133//4133 4135//4135 -f 3635//3635 3636//3636 3572//3572 -f 3572//3572 3636//3636 3630//3630 -f 3572//3572 3630//3630 4117//4117 -f 4101//4101 4114//4114 3628//3628 -f 4136//4136 4137//4137 4138//4138 -f 4138//4138 4137//4137 4139//4139 -f 3625//3625 4109//4109 3626//3626 -f 3626//3626 4109//4109 3627//3627 -f 4140//4140 4096//4096 4117//4117 -f 4117//4117 4096//4096 4097//4097 -f 4117//4117 4097//4097 3628//3628 -f 3628//3628 4097//4097 4112//4112 -f 3628//3628 4112//4112 4101//4101 -f 4101//4101 4112//4112 4113//4113 -f 4101//4101 4113//4113 4100//4100 -f 4141//4141 4142//4142 4143//4143 -f 4143//4143 4142//4142 4126//4126 -f 4143//4143 4126//4126 4125//4125 -f 4125//4125 4126//4126 3609//3609 -f 4125//4125 3609//3609 3632//3632 -f 4144//4144 4145//4145 4127//4127 -f 4127//4127 4145//4145 4107//4107 -f 4127//4127 4107//4107 3609//3609 -f 3609//3609 4107//4107 4109//4109 -f 3609//3609 4109//4109 3610//3610 -f 4146//4146 4147//4147 4148//4148 -f 4148//4148 4147//4147 4149//4149 -f 3578//3578 3571//3571 3573//3573 -f 4116//4116 4106//4106 4114//4114 -f 4114//4114 4106//4106 4105//4105 -f 4114//4114 4105//4105 3628//3628 -f 3628//3628 4105//4105 4124//4124 -f 3628//3628 4124//4124 3629//3629 -f 3629//3629 4124//4124 4125//4125 -f 3629//3629 4125//4125 3631//3631 -f 3631//3631 4125//4125 3632//3632 -f 3584//3584 3573//3573 3623//3623 -f 3623//3623 3573//3573 3575//3575 -f 3623//3623 3575//3575 3625//3625 -f 3576//3576 3578//3578 3577//3577 -f 3577//3577 3578//3578 3573//3573 -f 3577//3577 3573//3573 3583//3583 -f 3583//3583 3573//3573 3584//3584 -f 3571//3571 3578//3578 3628//3628 -f 3628//3628 3578//3578 3579//3579 -f 3628//3628 3579//3579 3582//3582 -f 4150//4150 4151//4151 4152//4152 -f 4152//4152 4151//4151 4153//4153 -f 4152//4152 4153//4153 4154//4154 -f 3575//3575 3581//3581 3625//3625 -f 3625//3625 3581//3581 3580//3580 -f 3625//3625 3580//3580 4109//4109 -f 4109//4109 3580//3580 3570//3570 -f 4109//4109 3570//3570 3610//3610 -f 3612//3612 3611//3611 3628//3628 -f 3628//3628 3611//3611 3574//3574 -f 3628//3628 3574//3574 3572//3572 -f 3618//3618 3599//3599 3619//3619 -f 3619//3619 3599//3599 3601//3601 -f 3619//3619 3601//3601 3621//3621 -f 3621//3621 3601//3601 3620//3620 -f 3621//3621 3620//3620 3633//3633 -f 3633//3633 3620//3620 3622//3622 -f 3633//3633 3622//3622 3634//3634 -f 3634//3634 3622//3622 3572//3572 -f 4093//4093 4155//4155 4091//4091 -f 4091//4091 4155//4155 4156//4156 -f 4091//4091 4156//4156 4157//4157 -f 4158//4158 4159//4159 3627//3627 -f 3613//3613 3612//3612 3614//3614 -f 3614//3614 3612//3612 3628//3628 -f 3614//3614 3628//3628 3624//3624 -f 3624//3624 3628//3628 3582//3582 -f 3596//3596 3595//3595 3598//3598 -f 3598//3598 3595//3595 3597//3597 -f 3598//3598 3597//3597 3600//3600 -f 3600//3600 3597//3597 3599//3599 -f 3600//3600 3599//3599 3602//3602 -f 3602//3602 3599//3599 3618//3618 -f 3602//3602 3618//3618 3616//3616 -f 3616//3616 3618//3618 3617//3617 -f 3616//3616 3617//3617 3614//3614 -f 3614//3614 3617//3617 3615//3615 -f 3614//3614 3615//3615 3613//3613 -f 4160//4160 4161//4161 4162//4162 -f 4162//4162 4161//4161 4163//4163 -f 4162//4162 4163//4163 4164//4164 -f 4165//4165 4166//4166 4164//4164 -f 4164//4164 4166//4166 4158//4158 -f 4164//4164 4158//4158 4162//4162 -f 4162//4162 4158//4158 3627//3627 -f 4162//4162 3627//3627 4090//4090 -f 4090//4090 3627//3627 4109//4109 -f 4090//4090 4109//4109 4089//4089 -f 4089//4089 4109//4109 4167//4167 -f 4149//4149 3592//3592 4148//4148 -f 4148//4148 3592//3592 3591//3591 -f 4148//4148 3591//3591 3588//3588 -f 4120//4120 3577//3577 4149//4149 -f 4149//4149 3577//3577 3594//3594 -f 4149//4149 3594//3594 3592//3592 -f 4168//4168 4169//4169 4159//4159 -f 4159//4159 4169//4169 4170//4170 -f 4159//4159 4170//4170 3627//3627 -f 3627//3627 4170//4170 4171//4171 -f 4172//4172 4148//4148 4173//4173 -f 4173//4173 4148//4148 3588//3588 -f 4173//4173 3588//3588 4171//4171 -f 4171//4171 3588//3588 3586//3586 -f 4171//4171 3586//3586 3627//3627 -f 4121//4121 4130//4130 4120//4120 -f 4120//4120 4130//4130 4131//4131 -f 4120//4120 4131//4131 3577//3577 -f 3577//3577 4131//4131 4134//4134 -f 4174//4174 4091//4091 3577//3577 -f 3577//3577 4091//4091 4157//4157 -f 3577//3577 4157//4157 3576//3576 -f 3576//3576 4157//4157 3593//3593 -f 3576//3576 3593//3593 3605//3605 -f 4135//4135 4138//4138 4134//4134 -f 4134//4134 4138//4138 4139//4139 -f 4134//4134 4139//4139 3577//3577 -f 3577//3577 4139//4139 4152//4152 -f 3577//3577 4152//4152 4174//4174 -f 4174//4174 4152//4152 4154//4154 -f 4174//4174 4154//4154 4175//4175 -f 4175//4175 4154//4154 4176//4176 -f 4177//4177 4178//4178 4179//4179 -f 4179//4179 4178//4178 4180//4180 -f 4179//4179 4180//4180 4181//4181 -f 4181//4181 4180//4180 4182//4182 -f 4181//4181 4182//4182 4183//4183 -f 4184//4184 4185//4185 4186//4186 -f 4186//4186 4185//4185 4187//4187 -f 4186//4186 4187//4187 4188//4188 -f 4188//4188 4187//4187 4189//4189 -f 4188//4188 4189//4189 4190//4190 -f 4191//4191 4192//4192 4193//4193 -f 4193//4193 4192//4192 4194//4194 -f 4193//4193 4194//4194 4195//4195 -f 4195//4195 4194//4194 4196//4196 -f 4195//4195 4196//4196 4197//4197 -f 4198//4198 4199//4199 4042//4042 -f 4042//4042 4199//4199 4200//4200 -f 4042//4042 4200//4200 4036//4036 -f 4036//4036 4200//4200 4201//4201 -f 4036//4036 4201//4201 4202//4202 -f 4202//4202 4201//4201 4203//4203 -f 4204//4204 4205//4205 4063//4063 -f 4063//4063 4205//4205 4206//4206 -f 4063//4063 4206//4206 4059//4059 -f 4059//4059 4206//4206 4207//4207 -f 4059//4059 4207//4207 4208//4208 -f 4208//4208 4207//4207 4209//4209 -f 4210//4210 4211//4211 4079//4079 -f 4079//4079 4211//4211 4212//4212 -f 4079//4079 4212//4212 4072//4072 -f 4072//4072 4212//4212 4213//4213 -f 4072//4072 4213//4213 4214//4214 -f 4214//4214 4213//4213 4215//4215 -f 4216//4216 4217//4217 4218//4218 -f 4218//4218 4217//4217 4219//4219 -f 4220//4220 4221//4221 4222//4222 -f 4223//4223 4224//4224 4225//4225 -f 4225//4225 4224//4224 4220//4220 -f 4225//4225 4220//4220 4226//4226 -f 4226//4226 4220//4220 4222//4222 -f 4223//4223 4227//4227 4224//4224 -f 4224//4224 4227//4227 4228//4228 -f 4224//4224 4228//4228 4216//4216 -f 4216//4216 4228//4228 4229//4229 -f 4216//4216 4229//4229 4217//4217 -f 4219//4219 4230//4230 4218//4218 -f 4218//4218 4230//4230 4231//4231 -f 4218//4218 4231//4231 4221//4221 -f 4221//4221 4231//4231 4232//4232 -f 4221//4221 4232//4232 4222//4222 -f 4233//4233 4234//4234 4235//4235 -f 4235//4235 4234//4234 4236//4236 -f 4237//4237 4238//4238 4239//4239 -f 4239//4239 4238//4238 4240//4240 -f 4239//4239 4240//4240 4241//4241 -f 4241//4241 4240//4240 4242//4242 -f 4241//4241 4242//4242 4243//4243 -f 4235//4235 4244//4244 4233//4233 -f 4233//4233 4244//4244 4245//4245 -f 4233//4233 4245//4245 4242//4242 -f 4242//4242 4245//4245 4246//4246 -f 4242//4242 4246//4246 4243//4243 -f 4237//4237 4247//4247 4238//4238 -f 4238//4238 4247//4247 4248//4248 -f 4238//4238 4248//4248 4234//4234 -f 4234//4234 4248//4248 4249//4249 -f 4234//4234 4249//4249 4236//4236 -f 4250//4250 4251//4251 4252//4252 -f 4252//4252 4251//4251 4253//4253 -f 4252//4252 4253//4253 4254//4254 -f 4254//4254 4253//4253 4255//4255 -f 4254//4254 4255//4255 4256//4256 -f 4257//4257 4258//4258 4221//4221 -f 4221//4221 4258//4258 4259//4259 -f 4221//4221 4259//4259 4218//4218 -f 4218//4218 4259//4259 4260//4260 -f 4218//4218 4260//4260 4261//4261 -f 4261//4261 4260//4260 4262//4262 -f 4263//4263 4264//4264 4265//4265 -f 4266//4266 4267//4267 4268//4268 -f 4263//4263 4265//4265 4268//4268 -f 4268//4268 4265//4265 4269//4269 -f 4268//4268 4269//4269 4266//4266 -f 4270//4270 4271//4271 4233//4233 -f 4233//4233 4271//4271 4272//4272 -f 4233//4233 4272//4272 4234//4234 -f 4234//4234 4272//4272 4273//4273 -f 4234//4234 4273//4273 4274//4274 -f 4274//4274 4273//4273 4275//4275 -f 4276//4276 4117//4117 4277//4277 -f 4277//4277 4117//4117 3630//3630 -f 4033//4033 3593//3593 4278//4278 -f 4278//4278 3593//3593 4157//4157 -f 4157//4157 4156//4156 4278//4278 -f 4278//4278 4156//4156 4279//4279 -f 4278//4278 4279//4279 4280//4280 -f 4280//4280 4279//4279 3925//3925 -f 4280//4280 3925//3925 4281//4281 -f 4281//4281 3925//3925 3924//3924 -f 4279//4279 4156//4156 4282//4282 -f 4282//4282 4156//4156 4155//4155 -f 3938//3938 3926//3926 4282//4282 -f 4282//4282 4155//4155 4093//4093 -f 3938//3938 4282//4282 3944//3944 -f 3944//3944 4282//4282 4201//4201 -f 4201//4201 4282//4282 4093//4093 -f 4201//4201 4093//4093 4203//4203 -f 4176//4176 4154//4154 4283//4283 -f 4283//4283 3942//3942 3936//3936 -f 4176//4176 4283//4283 4199//4199 -f 4199//4199 4283//4283 4200//4200 -f 4200//4200 4283//4283 3936//3936 -f 4200//4200 3936//3936 3945//3945 -f 4283//4283 4154//4154 4284//4284 -f 4284//4284 4154//4154 4153//4153 -f 3909//3909 3908//3908 4284//4284 -f 4284//4284 4153//4153 4151//4151 -f 3909//3909 4284//4284 3920//3920 -f 3920//3920 4284//4284 4207//4207 -f 4207//4207 4284//4284 4151//4151 -f 4207//4207 4151//4151 4209//4209 -f 4136//4136 4138//4138 4285//4285 -f 4285//4285 3911//3911 3906//3906 -f 4136//4136 4285//4285 4205//4205 -f 4205//4205 4285//4285 4206//4206 -f 4206//4206 4285//4285 3906//3906 -f 4206//4206 3906//3906 3921//3921 -f 4285//4285 4138//4138 4286//4286 -f 4286//4286 4138//4138 4135//4135 -f 3888//3888 3887//3887 4286//4286 -f 4286//4286 4135//4135 4133//4133 -f 3888//3888 4286//4286 3900//3900 -f 3900//3900 4286//4286 4213//4213 -f 4213//4213 4286//4286 4133//4133 -f 4213//4213 4133//4133 4215//4215 -f 4128//4128 4130//4130 4287//4287 -f 4287//4287 3895//3895 3884//3884 -f 4128//4128 4287//4287 4211//4211 -f 4211//4211 4287//4287 4212//4212 -f 4212//4212 4287//4287 3884//3884 -f 4212//4212 3884//3884 3901//3901 -f 4287//4287 4130//4130 4288//4288 -f 4288//4288 4130//4130 4121//4121 -f 3721//3721 3723//3723 4288//4288 -f 4288//4288 4121//4121 4119//4119 -f 3721//3721 4288//4288 3880//3880 -f 3880//3880 4288//4288 4260//4260 -f 4260//4260 4288//4288 4119//4119 -f 4260//4260 4119//4119 4262//4262 -f 4146//4146 4148//4148 4289//4289 -f 4289//4289 3740//3740 3739//3739 -f 4146//4146 4289//4289 4258//4258 -f 4258//4258 4289//4289 4259//4259 -f 4259//4259 4289//4289 3739//3739 -f 4259//4259 3739//3739 3878//3878 -f 4289//4289 4148//4148 4290//4290 -f 4290//4290 4148//4148 4172//4172 -f 4290//4290 4172//4172 3742//3742 -f 3742//3742 4172//4172 4173//4173 -f 3742//3742 4173//4173 4291//4291 -f 4291//4291 4173//4173 4171//4171 -f 4291//4291 4171//4171 4292//4292 -f 4292//4292 4171//4171 4170//4170 -f 3747//3747 3744//3744 4292//4292 -f 4292//4292 4170//4170 4169//4169 -f 3747//3747 4292//4292 3876//3876 -f 3876//3876 4292//4292 4273//4273 -f 4273//4273 4292//4292 4169//4169 -f 4273//4273 4169//4169 4275//4275 -f 4165//4165 4164//4164 4293//4293 -f 4293//4293 3757//3757 3759//3759 -f 4165//4165 4293//4293 4271//4271 -f 4271//4271 4293//4293 4272//4272 -f 4272//4272 4293//4293 3759//3759 -f 4272//4272 3759//3759 3877//3877 -f 4293//4293 4164//4164 4294//4294 -f 4294//4294 4164//4164 4163//4163 -f 3777//3777 3771//3771 4294//4294 -f 4294//4294 4163//4163 4161//4161 -f 3777//3777 4294//4294 3875//3875 -f 3875//3875 4294//4294 4295//4295 -f 4295//4295 4294//4294 4161//4161 -f 4295//4295 4161//4161 4296//4296 -f 4297//4297 4298//4298 4299//4299 -f 4299//4299 4298//4298 4300//4300 -f 4299//4299 4300//4300 4301//4301 -f 4301//4301 4300//4300 4295//4295 -f 4301//4301 4295//4295 4302//4302 -f 4302//4302 4295//4295 4296//4296 -f 4087//4087 4089//4089 4303//4303 -f 4303//4303 3787//3787 3789//3789 -f 4087//4087 4303//4303 4298//4298 -f 4298//4298 4303//4303 4300//4300 -f 4300//4300 4303//4303 3789//3789 -f 4300//4300 3789//3789 3711//3711 -f 4303//4303 4089//4089 4304//4304 -f 4304//4304 4089//4089 4167//4167 -f 4304//4304 4167//4167 3784//3784 -f 3784//3784 4167//4167 4109//4109 -f 3784//3784 4109//4109 4305//4305 -f 4305//4305 4109//4109 4108//4108 -f 4305//4305 4108//4108 4306//4306 -f 4306//4306 4108//4108 4107//4107 -f 4145//4145 4307//4307 4308//4308 -f 4107//4107 4145//4145 4306//4306 -f 4306//4306 4145//4145 4308//4308 -f 4306//4306 4308//4308 3782//3782 -f 3782//3782 4308//4308 3780//3780 -f 4309//4309 4310//4310 4311//4311 -f 4311//4311 4310//4310 4312//4312 -f 4311//4311 4312//4312 4313//4313 -f 4313//4313 4312//4312 4308//4308 -f 4313//4313 4308//4308 4314//4314 -f 4314//4314 4308//4308 4307//4307 -f 3793//3793 3791//3791 4315//4315 -f 4315//4315 3791//3791 4312//4312 -f 4312//4312 4310//4310 4315//4315 -f 4315//4315 4310//4310 4141//4141 -f 4315//4315 4141//4141 4143//4143 -f 4315//4315 4143//4143 4316//4316 -f 4316//4316 4143//4143 4125//4125 -f 4123//4123 4317//4317 4318//4318 -f 4125//4125 4123//4123 4316//4316 -f 4316//4316 4123//4123 4318//4318 -f 4316//4316 4318//4318 3849//3849 -f 3849//3849 4318//4318 3850//3850 -f 4319//4319 4320//4320 4321//4321 -f 4321//4321 4320//4320 4322//4322 -f 4321//4321 4322//4322 4323//4323 -f 4323//4323 4322//4322 4318//4318 -f 4323//4323 4318//4318 4324//4324 -f 4324//4324 4318//4318 4317//4317 -f 3855//3855 3853//3853 4325//4325 -f 4325//4325 3853//3853 4322//4322 -f 4322//4322 4320//4320 4325//4325 -f 4325//4325 4320//4320 4102//4102 -f 4325//4325 4102//4102 4104//4104 -f 4325//4325 4104//4104 4326//4326 -f 4326//4326 4104//4104 4106//4106 -f 4116//4116 4327//4327 4328//4328 -f 4106//4106 4116//4116 4326//4326 -f 4326//4326 4116//4116 4328//4328 -f 4326//4326 4328//4328 3832//3832 -f 3832//3832 4328//4328 3833//3833 -f 4329//4329 4330//4330 4331//4331 -f 4331//4331 4330//4330 4332//4332 -f 4331//4331 4332//4332 4333//4333 -f 4333//4333 4332//4332 4328//4328 -f 4333//4333 4328//4328 4334//4334 -f 4334//4334 4328//4328 4327//4327 -f 3840//3840 3844//3844 4335//4335 -f 4335//4335 3844//3844 4332//4332 -f 4332//4332 4330//4330 4335//4335 -f 4335//4335 4330//4330 4098//4098 -f 4335//4335 4098//4098 4100//4100 -f 4335//4335 4100//4100 4336//4336 -f 4336//4336 4100//4100 4113//4113 -f 4111//4111 4337//4337 4338//4338 -f 4113//4113 4111//4111 4336//4336 -f 4336//4336 4111//4111 4338//4338 -f 4336//4336 4338//4338 3815//3815 -f 3815//3815 4338//4338 3822//3822 -f 4339//4339 4340//4340 4341//4341 -f 4341//4341 4340//4340 4342//4342 -f 4341//4341 4342//4342 4343//4343 -f 4343//4343 4342//4342 4338//4338 -f 4343//4343 4338//4338 4344//4344 -f 4344//4344 4338//4338 4337//4337 -f 3820//3820 3827//3827 4345//4345 -f 4345//4345 3827//3827 4342//4342 -f 4342//4342 4340//4340 4345//4345 -f 4345//4345 4340//4340 4094//4094 -f 4345//4345 4094//4094 4096//4096 -f 4345//4345 4096//4096 4346//4346 -f 4346//4346 4096//4096 4140//4140 -f 4347//4347 3814//3814 3819//3819 -f 4140//4140 4117//4117 4346//4346 -f 4346//4346 4117//4117 4276//4276 -f 4346//4346 4276//4276 3819//3819 -f 3819//3819 4276//4276 4348//4348 -f 3819//3819 4348//4348 4347//4347 -f 3813//3813 4349//4349 4350//4350 -f 3715//3715 3807//3807 4351//4351 -f 4351//4351 3807//3807 3809//3809 -f 4351//4351 3809//3809 4352//4352 -f 4352//4352 3809//3809 3811//3811 -f 4352//4352 3811//3811 4004//4004 -f 4004//4004 3811//3811 3813//3813 -f 4004//4004 3813//3813 4003//4003 -f 4003//4003 3813//3813 4350//4350 -f 4002//4002 3983//3983 4353//4353 -f 4353//4353 3983//3983 4354//4354 -f 4354//4354 3983//3983 3985//3985 -f 4354//4354 3985//3985 4355//4355 -f 4355//4355 3985//3985 3987//3987 -f 4355//4355 3987//3987 4356//4356 -f 4356//4356 3987//3987 3989//3989 -f 4356//4356 3989//3989 4357//4357 -f 4357//4357 3989//3989 3991//3991 -f 4357//4357 3991//3991 4358//4358 -f 4358//4358 3991//3991 3992//3992 -f 4358//4358 3992//3992 4359//4359 -f 4359//4359 3992//3992 4020//4020 -f 4359//4359 4020//4020 4360//4360 -f 4360//4360 4020//4020 4019//4019 -f 4360//4360 4019//4019 4361//4361 -f 4361//4361 4019//4019 4362//4362 -f 4362//4362 4019//4019 3978//3978 -f 4363//4363 4364//4364 4365//4365 -f 4365//4365 4364//4364 4301//4301 -f 4365//4365 4301//4301 4160//4160 -f 4160//4160 4301//4301 4302//4302 -f 4299//4299 4301//4301 4366//4366 -f 4366//4366 4301//4301 4367//4367 -f 4368//4368 4369//4369 4370//4370 -f 4370//4370 4369//4369 4299//4299 -f 4370//4370 4299//4299 4371//4371 -f 4371//4371 4299//4299 4366//4366 -f 4368//4368 4372//4372 4369//4369 -f 4369//4369 4372//4372 4373//4373 -f 4369//4369 4373//4373 4374//4374 -f 4374//4374 4373//4373 4375//4375 -f 4374//4374 4375//4375 4364//4364 -f 4364//4364 4375//4375 4376//4376 -f 4376//4376 4377//4377 4364//4364 -f 4364//4364 4377//4377 4378//4378 -f 4364//4364 4378//4378 4301//4301 -f 4301//4301 4378//4378 4379//4379 -f 4301//4301 4379//4379 4367//4367 -f 4088//4088 4297//4297 4380//4380 -f 4380//4380 4297//4297 4299//4299 -f 4380//4380 4299//4299 4381//4381 -f 4381//4381 4299//4299 4369//4369 -f 4363//4363 4382//4382 4364//4364 -f 4364//4364 4382//4382 4374//4374 -f 4382//4382 4381//4381 4374//4374 -f 4374//4374 4381//4381 4369//4369 -f 4380//4380 4381//4381 4383//4383 -f 4383//4383 4381//4381 4382//4382 -f 4383//4383 4382//4382 4384//4384 -f 4384//4384 4382//4382 4363//4363 -f 4384//4384 4363//4363 4365//4365 -f 4160//4160 4162//4162 4365//4365 -f 4365//4365 4162//4162 4384//4384 -f 4162//4162 4090//4090 4384//4384 -f 4384//4384 4090//4090 4383//4383 -f 4090//4090 4088//4088 4383//4383 -f 4383//4383 4088//4088 4380//4380 -f 4385//4385 4386//4386 4387//4387 -f 4387//4387 4386//4386 4313//4313 -f 4387//4387 4313//4313 4144//4144 -f 4144//4144 4313//4313 4314//4314 -f 4388//4388 4311//4311 4389//4389 -f 4389//4389 4390//4390 4388//4388 -f 4388//4388 4390//4390 4391//4391 -f 4388//4388 4391//4391 4392//4392 -f 4392//4392 4391//4391 4393//4393 -f 4386//4386 4394//4394 4313//4313 -f 4313//4313 4394//4394 4395//4395 -f 4395//4395 4396//4396 4313//4313 -f 4313//4313 4396//4396 4397//4397 -f 4313//4313 4397//4397 4311//4311 -f 4311//4311 4397//4397 4398//4398 -f 4311//4311 4398//4398 4389//4389 -f 4393//4393 4399//4399 4392//4392 -f 4392//4392 4399//4399 4400//4400 -f 4392//4392 4400//4400 4386//4386 -f 4386//4386 4400//4400 4401//4401 -f 4386//4386 4401//4401 4394//4394 -f 4142//4142 4309//4309 4402//4402 -f 4402//4402 4309//4309 4311//4311 -f 4402//4402 4311//4311 4403//4403 -f 4403//4403 4311//4311 4388//4388 -f 4385//4385 4404//4404 4386//4386 -f 4386//4386 4404//4404 4392//4392 -f 4404//4404 4403//4403 4392//4392 -f 4392//4392 4403//4403 4388//4388 -f 4405//4405 4402//4402 4403//4403 -f 4385//4385 4387//4387 4406//4406 -f 4405//4405 4403//4403 4406//4406 -f 4406//4406 4403//4403 4404//4404 -f 4406//4406 4404//4404 4385//4385 -f 4127//4127 4406//4406 4144//4144 -f 4144//4144 4406//4406 4387//4387 -f 4126//4126 4405//4405 4127//4127 -f 4127//4127 4405//4405 4406//4406 -f 4142//4142 4402//4402 4126//4126 -f 4126//4126 4402//4402 4405//4405 -f 4366//4366 3779//3779 4371//4371 -f 4371//4371 3779//3779 3774//3774 -f 4371//4371 3774//3774 4370//4370 -f 4370//4370 3774//3774 3773//3773 -f 4370//4370 3773//3773 4368//4368 -f 4368//4368 3773//3773 3772//3772 -f 4368//4368 3772//3772 4372//4372 -f 4372//4372 3772//3772 3873//3873 -f 4372//4372 3873//3873 4373//4373 -f 4373//4373 3873//3873 3871//3871 -f 4373//4373 3871//3871 4375//4375 -f 4375//4375 3871//3871 3869//3869 -f 4375//4375 3869//3869 4376//4376 -f 4376//4376 3869//3869 3868//3868 -f 4376//4376 3868//3868 4377//4377 -f 4377//4377 3868//3868 3867//3867 -f 4377//4377 3867//3867 4378//4378 -f 4378//4378 3867//3867 3775//3775 -f 4378//4378 3775//3775 4379//4379 -f 4379//4379 3775//3775 3776//3776 -f 4379//4379 3776//3776 4367//4367 -f 4367//4367 3776//3776 3778//3778 -f 4367//4367 3778//3778 4366//4366 -f 4366//4366 3778//3778 3779//3779 -f 4394//4394 3804//3804 4395//4395 -f 4395//4395 3804//3804 3803//3803 -f 4395//4395 3803//3803 4396//4396 -f 4396//4396 3803//3803 3802//3802 -f 4396//4396 3802//3802 4397//4397 -f 4397//4397 3802//3802 3797//3797 -f 4397//4397 3797//3797 4398//4398 -f 4398//4398 3797//3797 3796//3796 -f 4398//4398 3796//3796 4389//4389 -f 4389//4389 3796//3796 3790//3790 -f 4389//4389 3790//3790 4390//4390 -f 4390//4390 3790//3790 3792//3792 -f 4390//4390 3792//3792 4391//4391 -f 4391//4391 3792//3792 3794//3794 -f 4391//4391 3794//3794 4393//4393 -f 4393//4393 3794//3794 3795//3795 -f 4393//4393 3795//3795 4399//4399 -f 4399//4399 3795//3795 3798//3798 -f 4399//4399 3798//3798 4400//4400 -f 4400//4400 3798//3798 3799//3799 -f 4400//4400 3799//3799 4401//4401 -f 4401//4401 3799//3799 3801//3801 -f 4401//4401 3801//3801 4394//4394 -f 4394//4394 3801//3801 3804//3804 -f 4407//4407 4408//4408 4409//4409 -f 4409//4409 4408//4408 4323//4323 -f 4409//4409 4323//4323 4122//4122 -f 4122//4122 4323//4323 4324//4324 -f 4410//4410 4321//4321 4411//4411 -f 4411//4411 4412//4412 4410//4410 -f 4410//4410 4412//4412 4413//4413 -f 4410//4410 4413//4413 4414//4414 -f 4414//4414 4413//4413 4415//4415 -f 4416//4416 4323//4323 4417//4417 -f 4417//4417 4323//4323 4408//4408 -f 4415//4415 4418//4418 4414//4414 -f 4414//4414 4418//4418 4419//4419 -f 4414//4414 4419//4419 4408//4408 -f 4408//4408 4419//4419 4420//4420 -f 4408//4408 4420//4420 4417//4417 -f 4416//4416 4421//4421 4323//4323 -f 4323//4323 4421//4421 4422//4422 -f 4323//4323 4422//4422 4321//4321 -f 4321//4321 4422//4422 4423//4423 -f 4321//4321 4423//4423 4411//4411 -f 4103//4103 4319//4319 4424//4424 -f 4424//4424 4319//4319 4321//4321 -f 4424//4424 4321//4321 4425//4425 -f 4425//4425 4321//4321 4410//4410 -f 4426//4426 4427//4427 4428//4428 -f 4428//4428 4427//4427 4333//4333 -f 4428//4428 4333//4333 4115//4115 -f 4115//4115 4333//4333 4334//4334 -f 4429//4429 4333//4333 4430//4430 -f 4430//4430 4333//4333 4427//4427 -f 4429//4429 4431//4431 4333//4333 -f 4333//4333 4431//4431 4432//4432 -f 4333//4333 4432//4432 4331//4331 -f 4433//4433 4434//4434 4435//4435 -f 4435//4435 4434//4434 4436//4436 -f 4433//4433 4437//4437 4434//4434 -f 4434//4434 4437//4437 4438//4438 -f 4434//4434 4438//4438 4427//4427 -f 4427//4427 4438//4438 4439//4439 -f 4427//4427 4439//4439 4430//4430 -f 4432//4432 4440//4440 4331//4331 -f 4331//4331 4440//4440 4441//4441 -f 4331//4331 4441//4441 4436//4436 -f 4436//4436 4441//4441 4442//4442 -f 4436//4436 4442//4442 4435//4435 -f 4099//4099 4329//4329 4443//4443 -f 4443//4443 4329//4329 4331//4331 -f 4443//4443 4331//4331 4444//4444 -f 4444//4444 4331//4331 4436//4436 -f 4445//4445 4446//4446 4447//4447 -f 4447//4447 4446//4446 4343//4343 -f 4447//4447 4343//4343 4110//4110 -f 4110//4110 4343//4343 4344//4344 -f 4448//4448 4449//4449 4450//4450 -f 4450//4450 4449//4449 4446//4446 -f 4451//4451 4341//4341 4452//4452 -f 4452//4452 4453//4453 4451//4451 -f 4451//4451 4453//4453 4454//4454 -f 4451//4451 4454//4454 4450//4450 -f 4450//4450 4454//4454 4455//4455 -f 4450//4450 4455//4455 4448//4448 -f 4449//4449 4456//4456 4446//4446 -f 4446//4446 4456//4456 4457//4457 -f 4446//4446 4457//4457 4343//4343 -f 4343//4343 4457//4457 4458//4458 -f 4458//4458 4459//4459 4343//4343 -f 4343//4343 4459//4459 4460//4460 -f 4343//4343 4460//4460 4341//4341 -f 4341//4341 4460//4460 4461//4461 -f 4341//4341 4461//4461 4452//4452 -f 4095//4095 4339//4339 4462//4462 -f 4462//4462 4339//4339 4341//4341 -f 4462//4462 4341//4341 4463//4463 -f 4463//4463 4341//4341 4451//4451 -f 4407//4407 4464//4464 4408//4408 -f 4408//4408 4464//4464 4414//4414 -f 4464//4464 4425//4425 4414//4414 -f 4414//4414 4425//4425 4410//4410 -f 4465//4465 4424//4424 4425//4425 -f 4407//4407 4409//4409 4466//4466 -f 4465//4465 4425//4425 4466//4466 -f 4466//4466 4425//4425 4464//4464 -f 4466//4466 4464//4464 4407//4407 -f 4426//4426 4467//4467 4427//4427 -f 4427//4427 4467//4467 4434//4434 -f 4467//4467 4444//4444 4434//4434 -f 4434//4434 4444//4444 4436//4436 -f 4468//4468 4443//4443 4444//4444 -f 4426//4426 4428//4428 4469//4469 -f 4468//4468 4444//4444 4469//4469 -f 4469//4469 4444//4444 4467//4467 -f 4469//4469 4467//4467 4426//4426 -f 4445//4445 4470//4470 4446//4446 -f 4446//4446 4470//4470 4450//4450 -f 4470//4470 4463//4463 4450//4450 -f 4450//4450 4463//4463 4451//4451 -f 4471//4471 4462//4462 4463//4463 -f 4445//4445 4447//4447 4472//4472 -f 4471//4471 4463//4463 4472//4472 -f 4472//4472 4463//4463 4470//4470 -f 4472//4472 4470//4470 4445//4445 -f 4124//4124 4466//4466 4122//4122 -f 4122//4122 4466//4466 4409//4409 -f 4105//4105 4465//4465 4124//4124 -f 4124//4124 4465//4465 4466//4466 -f 4103//4103 4424//4424 4105//4105 -f 4105//4105 4424//4424 4465//4465 -f 4114//4114 4469//4469 4115//4115 -f 4115//4115 4469//4469 4428//4428 -f 4101//4101 4468//4468 4114//4114 -f 4114//4114 4468//4468 4469//4469 -f 4099//4099 4443//4443 4101//4101 -f 4101//4101 4443//4443 4468//4468 -f 4112//4112 4472//4472 4110//4110 -f 4110//4110 4472//4472 4447//4447 -f 4097//4097 4471//4471 4112//4112 -f 4112//4112 4471//4471 4472//4472 -f 4095//4095 4462//4462 4097//4097 -f 4097//4097 4462//4462 4471//4471 -f 4417//4417 3859//3859 4416//4416 -f 4416//4416 3859//3859 3851//3851 -f 4416//4416 3851//3851 4421//4421 -f 4421//4421 3851//3851 3866//3866 -f 4421//4421 3866//3866 4422//4422 -f 4422//4422 3866//3866 3865//3865 -f 4422//4422 3865//3865 4423//4423 -f 4423//4423 3865//3865 3864//3864 -f 4423//4423 3864//3864 4411//4411 -f 4411//4411 3864//3864 3852//3852 -f 4411//4411 3852//3852 4412//4412 -f 4412//4412 3852//3852 3854//3854 -f 4412//4412 3854//3854 4413//4413 -f 4413//4413 3854//3854 3856//3856 -f 4413//4413 3856//3856 4415//4415 -f 4415//4415 3856//3856 3857//3857 -f 4415//4415 3857//3857 4418//4418 -f 4418//4418 3857//3857 3862//3862 -f 4418//4418 3862//3862 4419//4419 -f 4419//4419 3862//3862 3861//3861 -f 4419//4419 3861//3861 4420//4420 -f 4420//4420 3861//3861 3860//3860 -f 4420//4420 3860//3860 4417//4417 -f 4417//4417 3860//3860 3859//3859 -f 4430//4430 3835//3835 4429//4429 -f 4429//4429 3835//3835 3834//3834 -f 4429//4429 3834//3834 4431//4431 -f 4431//4431 3834//3834 3848//3848 -f 4431//4431 3848//3848 4432//4432 -f 4432//4432 3848//3848 3847//3847 -f 4432//4432 3847//3847 4440//4440 -f 4440//4440 3847//3847 3846//3846 -f 4440//4440 3846//3846 4441//4441 -f 4441//4441 3846//3846 3845//3845 -f 4441//4441 3845//3845 4442//4442 -f 4442//4442 3845//3845 3843//3843 -f 4442//4442 3843//3843 4435//4435 -f 4435//4435 3843//3843 3842//3842 -f 4435//4435 3842//3842 4433//4433 -f 4433//4433 3842//3842 3839//3839 -f 4433//4433 3839//3839 4437//4437 -f 4437//4437 3839//3839 3838//3838 -f 4437//4437 3838//3838 4438//4438 -f 4438//4438 3838//3838 3837//3837 -f 4438//4438 3837//3837 4439//4439 -f 4439//4439 3837//3837 3836//3836 -f 4439//4439 3836//3836 4430//4430 -f 4430//4430 3836//3836 3835//3835 -f 4457//4457 3824//3824 4458//4458 -f 4458//4458 3824//3824 3823//3823 -f 4458//4458 3823//3823 4459//4459 -f 4459//4459 3823//3823 3831//3831 -f 4459//4459 3831//3831 4460//4460 -f 4460//4460 3831//3831 3830//3830 -f 4460//4460 3830//3830 4461//4461 -f 4461//4461 3830//3830 3829//3829 -f 4461//4461 3829//3829 4452//4452 -f 4452//4452 3829//3829 3828//3828 -f 4452//4452 3828//3828 4453//4453 -f 4453//4453 3828//3828 3826//3826 -f 4453//4453 3826//3826 4454//4454 -f 4454//4454 3826//3826 3825//3825 -f 4454//4454 3825//3825 4455//4455 -f 4455//4455 3825//3825 3821//3821 -f 4455//4455 3821//3821 4448//4448 -f 4448//4448 3821//3821 3818//3818 -f 4448//4448 3818//3818 4449//4449 -f 4449//4449 3818//3818 3817//3817 -f 4449//4449 3817//3817 4456//4456 -f 4456//4456 3817//3817 3816//3816 -f 4456//4456 3816//3816 4457//4457 -f 4457//4457 3816//3816 3824//3824 -f 4266//4266 4238//4238 4267//4267 -f 4267//4267 4238//4238 4234//4234 -f 4267//4267 4234//4234 4168//4168 -f 4168//4168 4234//4234 4274//4274 -f 4166//4166 4270//4270 4264//4264 -f 4264//4264 4270//4270 4233//4233 -f 4264//4264 4233//4233 4265//4265 -f 4265//4265 4233//4233 4242//4242 -f 4266//4266 4269//4269 4238//4238 -f 4238//4238 4269//4269 4240//4240 -f 4269//4269 4265//4265 4240//4240 -f 4240//4240 4265//4265 4242//4242 -f 4159//4159 4268//4268 4168//4168 -f 4168//4168 4268//4268 4267//4267 -f 4158//4158 4263//4263 4159//4159 -f 4159//4159 4263//4263 4268//4268 -f 4166//4166 4264//4264 4158//4158 -f 4158//4158 4264//4264 4263//4263 -f 4255//4255 4216//4216 4256//4256 -f 4256//4256 4216//4216 4218//4218 -f 4256//4256 4218//4218 4118//4118 -f 4118//4118 4218//4218 4261//4261 -f 4147//4147 4257//4257 4250//4250 -f 4250//4250 4257//4257 4221//4221 -f 4250//4250 4221//4221 4251//4251 -f 4251//4251 4221//4221 4220//4220 -f 4255//4255 4253//4253 4216//4216 -f 4216//4216 4253//4253 4224//4224 -f 4253//4253 4251//4251 4224//4224 -f 4224//4224 4251//4251 4220//4220 -f 4118//4118 4120//4120 4256//4256 -f 4256//4256 4120//4120 4254//4254 -f 4120//4120 4149//4149 4254//4254 -f 4254//4254 4149//4149 4252//4252 -f 4149//4149 4147//4147 4252//4252 -f 4252//4252 4147//4147 4250//4250 -f 4235//4235 3745//3745 4244//4244 -f 4244//4244 3745//3745 3761//3761 -f 4244//4244 3761//3761 4245//4245 -f 4245//4245 3761//3761 3760//3760 -f 4245//4245 3760//3760 4246//4246 -f 4246//4246 3760//3760 3758//3758 -f 4246//4246 3758//3758 4243//4243 -f 4243//4243 3758//3758 3756//3756 -f 4243//4243 3756//3756 4241//4241 -f 4241//4241 3756//3756 3755//3755 -f 4241//4241 3755//3755 4239//4239 -f 4239//4239 3755//3755 3752//3752 -f 4239//4239 3752//3752 4237//4237 -f 4237//4237 3752//3752 3751//3751 -f 4237//4237 3751//3751 4247//4247 -f 4247//4247 3751//3751 3750//3750 -f 4247//4247 3750//3750 4248//4248 -f 4248//4248 3750//3750 3749//3749 -f 4248//4248 3749//3749 4249//4249 -f 4249//4249 3749//3749 3748//3748 -f 4249//4249 3748//3748 4236//4236 -f 4236//4236 3748//3748 3746//3746 -f 4236//4236 3746//3746 4235//4235 -f 4235//4235 3746//3746 3745//3745 -f 4226//4226 3718//3718 4225//4225 -f 4225//4225 3718//3718 3734//3734 -f 4225//4225 3734//3734 4223//4223 -f 4223//4223 3734//3734 3736//3736 -f 4223//4223 3736//3736 4227//4227 -f 4227//4227 3736//3736 3728//3728 -f 4227//4227 3728//3728 4228//4228 -f 4228//4228 3728//3728 3726//3726 -f 4228//4228 3726//3726 4229//4229 -f 4229//4229 3726//3726 3725//3725 -f 4229//4229 3725//3725 4217//4217 -f 4217//4217 3725//3725 3724//3724 -f 4217//4217 3724//3724 4219//4219 -f 4219//4219 3724//3724 3722//3722 -f 4219//4219 3722//3722 4230//4230 -f 4230//4230 3722//3722 3731//3731 -f 4230//4230 3731//3731 4231//4231 -f 4231//4231 3731//3731 3730//3730 -f 4231//4231 3730//3730 4232//4232 -f 4232//4232 3730//3730 3729//3729 -f 4232//4232 3729//3729 4222//4222 -f 4222//4222 3729//3729 3719//3719 -f 4222//4222 3719//3719 4226//4226 -f 4226//4226 3719//3719 3718//3718 -f 4196//4196 4070//4070 4197//4197 -f 4197//4197 4070//4070 4072//4072 -f 4197//4197 4072//4072 4132//4132 -f 4132//4132 4072//4072 4214//4214 -f 4129//4129 4210//4210 4191//4191 -f 4191//4191 4210//4210 4079//4079 -f 4191//4191 4079//4079 4192//4192 -f 4192//4192 4079//4079 4081//4081 -f 4189//4189 4057//4057 4190//4190 -f 4190//4190 4057//4057 4059//4059 -f 4190//4190 4059//4059 4150//4150 -f 4150//4150 4059//4059 4208//4208 -f 4137//4137 4204//4204 4184//4184 -f 4184//4184 4204//4204 4063//4063 -f 4184//4184 4063//4063 4185//4185 -f 4185//4185 4063//4063 4053//4053 -f 4182//4182 4046//4046 4183//4183 -f 4183//4183 4046//4046 4036//4036 -f 4183//4183 4036//4036 4092//4092 -f 4092//4092 4036//4036 4202//4202 -f 4175//4175 4198//4198 4177//4177 -f 4177//4177 4198//4198 4042//4042 -f 4177//4177 4042//4042 4178//4178 -f 4178//4178 4042//4042 4045//4045 -f 4196//4196 4194//4194 4070//4070 -f 4070//4070 4194//4194 4074//4074 -f 4194//4194 4192//4192 4074//4074 -f 4074//4074 4192//4192 4081//4081 -f 4189//4189 4187//4187 4057//4057 -f 4057//4057 4187//4187 4055//4055 -f 4187//4187 4185//4185 4055//4055 -f 4055//4055 4185//4185 4053//4053 -f 4182//4182 4180//4180 4046//4046 -f 4046//4046 4180//4180 4039//4039 -f 4180//4180 4178//4178 4039//4039 -f 4039//4039 4178//4178 4045//4045 -f 4132//4132 4134//4134 4197//4197 -f 4197//4197 4134//4134 4195//4195 -f 4134//4134 4131//4131 4195//4195 -f 4195//4195 4131//4131 4193//4193 -f 4131//4131 4129//4129 4193//4193 -f 4193//4193 4129//4129 4191//4191 -f 4150//4150 4152//4152 4190//4190 -f 4190//4190 4152//4152 4188//4188 -f 4152//4152 4139//4139 4188//4188 -f 4188//4188 4139//4139 4186//4186 -f 4139//4139 4137//4137 4186//4186 -f 4186//4186 4137//4137 4184//4184 -f 4092//4092 4091//4091 4183//4183 -f 4183//4183 4091//4091 4181//4181 -f 4091//4091 4174//4174 4181//4181 -f 4181//4181 4174//4174 4179//4179 -f 4174//4174 4175//4175 4179//4179 -f 4179//4179 4175//4175 4177//4177 -f 4080//4080 3882//3882 4084//4084 -f 4084//4084 3882//3882 3881//3881 -f 4084//4084 3881//3881 4085//4085 -f 4085//4085 3881//3881 3899//3899 -f 4085//4085 3899//3899 4086//4086 -f 4086//4086 3899//3899 3898//3898 -f 4086//4086 3898//3898 4075//4075 -f 4075//4075 3898//3898 3897//3897 -f 4075//4075 3897//3897 4076//4076 -f 4076//4076 3897//3897 3890//3890 -f 4076//4076 3890//3890 4071//4071 -f 4071//4071 3890//3890 3892//3892 -f 4071//4071 3892//3892 4073//4073 -f 4073//4073 3892//3892 3893//3893 -f 4073//4073 3893//3893 4077//4077 -f 4077//4077 3893//3893 3889//3889 -f 4077//4077 3889//3889 4078//4078 -f 4078//4078 3889//3889 3886//3886 -f 4078//4078 3886//3886 4083//4083 -f 4083//4083 3886//3886 3885//3885 -f 4083//4083 3885//3885 4082//4082 -f 4082//4082 3885//3885 3896//3896 -f 4082//4082 3896//3896 4080//4080 -f 4080//4080 3896//3896 3882//3882 -f 4066//4066 3903//3903 4054//4054 -f 4054//4054 3903//3903 3902//3902 -f 4054//4054 3902//3902 4056//4056 -f 4056//4056 3902//3902 3919//3919 -f 4056//4056 3919//3919 4067//4067 -f 4067//4067 3919//3919 3918//3918 -f 4067//4067 3918//3918 4068//4068 -f 4068//4068 3918//3918 3917//3917 -f 4068//4068 3917//3917 4069//4069 -f 4069//4069 3917//3917 3916//3916 -f 4069//4069 3916//3916 4058//4058 -f 4058//4058 3916//3916 3914//3914 -f 4058//4058 3914//3914 4060//4060 -f 4060//4060 3914//3914 3913//3913 -f 4060//4060 3913//3913 4061//4061 -f 4061//4061 3913//3913 3910//3910 -f 4061//4061 3910//3910 4062//4062 -f 4062//4062 3910//3910 3907//3907 -f 4062//4062 3907//3907 4064//4064 -f 4064//4064 3907//3907 3905//3905 -f 4064//4064 3905//3905 4065//4065 -f 4065//4065 3905//3905 3904//3904 -f 4065//4065 3904//3904 4066//4066 -f 4066//4066 3904//3904 3903//3903 -f 4050//4050 3923//3923 4051//4051 -f 4051//4051 3923//3923 3922//3922 -f 4051//4051 3922//3922 4052//4052 -f 4052//4052 3922//3922 3941//3941 -f 4052//4052 3941//3941 4040//4040 -f 4040//4040 3941//3941 3940//3940 -f 4040//4040 3940//3940 4041//4041 -f 4041//4041 3940//3940 3939//3939 -f 4041//4041 3939//3939 4047//4047 -f 4047//4047 3939//3939 3933//3933 -f 4047//4047 3933//3933 4048//4048 -f 4048//4048 3933//3933 3932//3932 -f 4048//4048 3932//3932 4049//4049 -f 4049//4049 3932//3932 3931//3931 -f 4049//4049 3931//3931 4037//4037 -f 4037//4037 3931//3931 3930//3930 -f 4037//4037 3930//3930 4038//4038 -f 4038//4038 3930//3930 3937//3937 -f 4038//4038 3937//3937 4043//4043 -f 4043//4043 3937//3937 3935//3935 -f 4043//4043 3935//3935 4044//4044 -f 4044//4044 3935//3935 3934//3934 -f 4044//4044 3934//3934 4050//4050 -f 4050//4050 3934//3934 3923//3923 -f 4473//4473 4277//4277 4474//4474 -f 4474//4474 4277//4277 3630//3630 -f 4474//4474 3630//3630 4475//4475 -f 4475//4475 3630//3630 3636//3636 -f 4475//4475 3636//3636 4476//4476 -f 4476//4476 3636//3636 3635//3635 -f 4476//4476 3635//3635 4477//4477 -f 4477//4477 3635//3635 4478//4478 -f 4478//4478 3635//3635 3622//3622 -f 4478//4478 3622//3622 4479//4479 -f 4479//4479 3622//3622 4480//4480 -f 4480//4480 3622//3622 3620//3620 -f 4480//4480 3620//3620 4481//4481 -f 4481//4481 3620//3620 3601//3601 -f 4481//4481 3601//3601 3974//3974 -f 4482//4482 4483//4483 4484//4484 -f 4485//4485 4482//4482 4486//4486 -f 4486//4486 4482//4482 4484//4484 -f 4486//4486 4484//4484 4487//4487 -f 4487//4487 4484//4484 4488//4488 -f 4489//4489 4490//4490 4491//4491 -f 4492//4492 4493//4493 4489//4489 -f 4489//4489 4493//4493 4494//4494 -f 4489//4489 4494//4494 4495//4495 -f 4495//4495 4494//4494 4496//4496 -f 4495//4495 4496//4496 4497//4497 -f 4497//4497 4496//4496 4498//4498 -f 4497//4497 4498//4498 4499//4499 -f 4499//4499 4498//4498 4500//4500 -f 4499//4499 4500//4500 4484//4484 -f 4484//4484 4500//4500 4501//4501 -f 4484//4484 4501//4501 4488//4488 -f 4488//4488 4501//4501 4502//4502 -f 4488//4488 4502//4502 4503//4503 -f 4503//4503 4502//4502 4504//4504 -f 4503//4503 4504//4504 4505//4505 -f 4505//4505 4504//4504 4506//4506 -f 4505//4505 4506//4506 4507//4507 -f 4507//4507 4506//4506 4508//4508 -f 4507//4507 4508//4508 4509//4509 -f 4509//4509 4508//4508 4510//4510 -f 4509//4509 4510//4510 4491//4491 -f 4491//4491 4510//4510 4492//4492 -f 4491//4491 4492//4492 4489//4489 -f 4511//4511 4350//4350 4495//4495 -f 4495//4495 4350//4350 4349//4349 -f 4495//4495 4349//4349 4489//4489 -f 4489//4489 4349//4349 4512//4512 -f 4489//4489 4512//4512 4513//4513 -f 4514//4514 4515//4515 4512//4512 -f 4512//4512 4515//4515 4516//4516 -f 4512//4512 4516//4516 4513//4513 -f 4484//4484 4483//4483 4499//4499 -f 4499//4499 4483//4483 4517//4517 -f 4499//4499 4517//4517 4497//4497 -f 4497//4497 4517//4517 4518//4518 -f 4497//4497 4518//4518 4495//4495 -f 4495//4495 4518//4518 4511//4511 -f 4519//4519 4520//4520 4521//4521 -f 4522//4522 4519//4519 4523//4523 -f 4523//4523 4519//4519 4521//4521 -f 4523//4523 4521//4521 4524//4524 -f 4524//4524 4521//4521 4525//4525 -f 4526//4526 4527//4527 4528//4528 -f 4528//4528 4527//4527 4529//4529 -f 4528//4528 4529//4529 4530//4530 -f 4530//4530 4529//4529 4531//4531 -f 4530//4530 4531//4531 4532//4532 -f 4532//4532 4531//4531 4533//4533 -f 4532//4532 4533//4533 4534//4534 -f 4534//4534 4533//4533 4535//4535 -f 4534//4534 4535//4535 4536//4536 -f 4536//4536 4535//4535 4537//4537 -f 4536//4536 4537//4537 4538//4538 -f 4538//4538 4537//4537 4539//4539 -f 4538//4538 4539//4539 4520//4520 -f 4520//4520 4539//4539 4540//4540 -f 4520//4520 4540//4540 4521//4521 -f 4521//4521 4540//4540 4541//4541 -f 4521//4521 4541//4541 4542//4542 -f 4542//4542 4541//4541 4543//4543 -f 4542//4542 4543//4543 4544//4544 -f 4544//4544 4543//4543 4545//4545 -f 4544//4544 4545//4545 4546//4546 -f 4546//4546 4545//4545 4526//4526 -f 4546//4546 4526//4526 4528//4528 -f 4546//4546 4547//4547 4544//4544 -f 4544//4544 4547//4547 4548//4548 -f 4544//4544 4548//4548 4542//4542 -f 4542//4542 4548//4548 4549//4549 -f 4542//4542 4549//4549 4521//4521 -f 4521//4521 4549//4549 4525//4525 -f 4550//4550 4528//4528 4551//4551 -f 4551//4551 4528//4528 4552//4552 -f 3948//3948 4547//4547 3949//3949 -f 3949//3949 4547//4547 4546//4546 -f 3949//3949 4546//4546 4553//4553 -f 4553//4553 4546//4546 4528//4528 -f 4553//4553 4528//4528 4554//4554 -f 4550//4550 4555//4555 4528//4528 -f 4528//4528 4555//4555 4556//4556 -f 4528//4528 4556//4556 4554//4554 -f 4557//4557 4558//4558 4559//4559 -f 4559//4559 4558//4558 4560//4560 -f 4559//4559 4560//4560 4561//4561 -f 4561//4561 4560//4560 4562//4562 -f 4563//4563 4564//4564 4562//4562 -f 4562//4562 4564//4564 4565//4565 -f 4562//4562 4565//4565 4561//4561 -f 4566//4566 4567//4567 4563//4563 -f 4563//4563 4567//4567 4568//4568 -f 4563//4563 4568//4568 4564//4564 -f 4569//4569 4570//4570 4566//4566 -f 4566//4566 4570//4570 4571//4571 -f 4566//4566 4571//4571 4567//4567 -f 4572//4572 4573//4573 4574//4574 -f 4574//4574 4573//4573 4575//4575 -f 4574//4574 4575//4575 4576//4576 -f 4576//4576 4575//4575 4577//4577 -f 4576//4576 4577//4577 4569//4569 -f 4569//4569 4577//4577 4578//4578 -f 4569//4569 4578//4578 4570//4570 -f 4579//4579 4580//4580 4572//4572 -f 4572//4572 4580//4580 4581//4581 -f 4572//4572 4581//4581 4573//4573 -f 4582//4582 4583//4583 4579//4579 -f 4579//4579 4583//4583 4584//4584 -f 4579//4579 4584//4584 4580//4580 -f 4585//4585 4586//4586 4582//4582 -f 4582//4582 4586//4586 4587//4587 -f 4582//4582 4587//4587 4583//4583 -f 4588//4588 4586//4586 4589//4589 -f 4589//4589 4586//4586 4585//4585 -f 4589//4589 4585//4585 4590//4590 -f 4590//4590 4585//4585 4558//4558 -f 4590//4590 4558//4558 4591//4591 -f 4591//4591 4558//4558 4557//4557 -f 4591//4591 4557//4557 4592//4592 -f 4593//4593 4562//4562 4594//4594 -f 4594//4594 4562//4562 4560//4560 -f 4594//4594 4560//4560 4595//4595 -f 4595//4595 4560//4560 4558//4558 -f 4595//4595 4558//4558 4596//4596 -f 4596//4596 4558//4558 4585//4585 -f 4596//4596 4585//4585 4597//4597 -f 4597//4597 4585//4585 4582//4582 -f 4597//4597 4582//4582 4598//4598 -f 4598//4598 4582//4582 4579//4579 -f 4598//4598 4579//4579 4599//4599 -f 4599//4599 4579//4579 4572//4572 -f 4599//4599 4572//4572 4600//4600 -f 4600//4600 4572//4572 4574//4574 -f 4600//4600 4574//4574 4601//4601 -f 4601//4601 4574//4574 4576//4576 -f 4601//4601 4576//4576 4602//4602 -f 4602//4602 4576//4576 4569//4569 -f 4602//4602 4569//4569 4603//4603 -f 4603//4603 4569//4569 4566//4566 -f 4603//4603 4566//4566 4604//4604 -f 4604//4604 4566//4566 4563//4563 -f 4604//4604 4563//4563 4593//4593 -f 4593//4593 4563//4563 4562//4562 -f 4605//4605 4606//4606 4607//4607 -f 4608//4608 4609//4609 4610//4610 -f 4610//4610 4609//4609 4611//4611 -f 4610//4610 4611//4611 4612//4612 -f 4613//4613 4614//4614 4612//4612 -f 4612//4612 4614//4614 4615//4615 -f 4612//4612 4615//4615 4610//4610 -f 4616//4616 4617//4617 4613//4613 -f 4613//4613 4617//4617 4618//4618 -f 4613//4613 4618//4618 4614//4614 -f 4619//4619 4620//4620 4616//4616 -f 4616//4616 4620//4620 4621//4621 -f 4616//4616 4621//4621 4617//4617 -f 4622//4622 4623//4623 4619//4619 -f 4619//4619 4623//4623 4624//4624 -f 4619//4619 4624//4624 4620//4620 -f 4625//4625 4626//4626 4622//4622 -f 4622//4622 4626//4626 4627//4627 -f 4622//4622 4627//4627 4623//4623 -f 4628//4628 4629//4629 4625//4625 -f 4625//4625 4629//4629 4630//4630 -f 4625//4625 4630//4630 4626//4626 -f 4631//4631 4632//4632 4628//4628 -f 4628//4628 4632//4632 4633//4633 -f 4628//4628 4633//4633 4629//4629 -f 4607//4607 4634//4634 4605//4605 -f 4605//4605 4634//4634 4635//4635 -f 4605//4605 4635//4635 4631//4631 -f 4631//4631 4635//4635 4636//4636 -f 4631//4631 4636//4636 4632//4632 -f 4637//4637 4607//4607 4638//4638 -f 4638//4638 4607//4607 4606//4606 -f 4638//4638 4606//4606 4639//4639 -f 4639//4639 4606//4606 4609//4609 -f 4639//4639 4609//4609 4640//4640 -f 4640//4640 4609//4609 4608//4608 -f 4640//4640 4608//4608 4641//4641 -f 4642//4642 4606//4606 4643//4643 -f 4643//4643 4606//4606 4605//4605 -f 4643//4643 4605//4605 4644//4644 -f 4644//4644 4605//4605 4631//4631 -f 4644//4644 4631//4631 4645//4645 -f 4645//4645 4631//4631 4628//4628 -f 4645//4645 4628//4628 4646//4646 -f 4646//4646 4628//4628 4625//4625 -f 4646//4646 4625//4625 4647//4647 -f 4647//4647 4625//4625 4622//4622 -f 4647//4647 4622//4622 4648//4648 -f 4648//4648 4622//4622 4619//4619 -f 4648//4648 4619//4619 4649//4649 -f 4649//4649 4619//4619 4616//4616 -f 4649//4649 4616//4616 4650//4650 -f 4650//4650 4616//4616 4613//4613 -f 4650//4650 4613//4613 4651//4651 -f 4651//4651 4613//4613 4612//4612 -f 4651//4651 4612//4612 4652//4652 -f 4652//4652 4612//4612 4611//4611 -f 4652//4652 4611//4611 4653//4653 -f 4653//4653 4611//4611 4609//4609 -f 4653//4653 4609//4609 4642//4642 -f 4642//4642 4609//4609 4606//4606 -f 3612//3612 4496//4496 3611//3611 -f 3611//3611 4496//4496 4494//4494 -f 3611//3611 4494//4494 3574//3574 -f 3574//3574 4494//4494 4493//4493 -f 3574//3574 4493//4493 3572//3572 -f 3572//3572 4493//4493 4492//4492 -f 3572//3572 4492//4492 3634//3634 -f 3634//3634 4492//4492 4510//4510 -f 3634//3634 4510//4510 3633//3633 -f 3633//3633 4510//4510 4508//4508 -f 3633//3633 4508//4508 3621//3621 -f 3621//3621 4508//4508 4506//4506 -f 3621//3621 4506//4506 3619//3619 -f 3619//3619 4506//4506 4504//4504 -f 3619//3619 4504//4504 3618//3618 -f 3618//3618 4504//4504 4502//4502 -f 3618//3618 4502//4502 3617//3617 -f 3617//3617 4502//4502 4501//4501 -f 3617//3617 4501//4501 3615//3615 -f 3615//3615 4501//4501 4500//4500 -f 3615//3615 4500//4500 3613//3613 -f 3613//3613 4500//4500 4498//4498 -f 3613//3613 4498//4498 3612//3612 -f 3612//3612 4498//4498 4496//4496 -f 3582//3582 4526//4526 3624//3624 -f 3624//3624 4526//4526 4545//4545 -f 3624//3624 4545//4545 3614//3614 -f 3614//3614 4545//4545 4543//4543 -f 3614//3614 4543//4543 3616//3616 -f 3616//3616 4543//4543 4541//4541 -f 3616//3616 4541//4541 3602//3602 -f 3602//3602 4541//4541 4540//4540 -f 3602//3602 4540//4540 3600//3600 -f 3600//3600 4540//4540 4539//4539 -f 3600//3600 4539//4539 3598//3598 -f 3598//3598 4539//4539 4537//4537 -f 3598//3598 4537//4537 3596//3596 -f 3596//3596 4537//4537 4535//4535 -f 3596//3596 4535//4535 3604//3604 -f 3604//3604 4535//4535 4533//4533 -f 3604//3604 4533//4533 3576//3576 -f 3576//3576 4533//4533 4531//4531 -f 3576//3576 4531//4531 3578//3578 -f 3578//3578 4531//4531 4529//4529 -f 3578//3578 4529//4529 3579//3579 -f 3579//3579 4529//4529 4527//4527 -f 3579//3579 4527//4527 3582//3582 -f 3582//3582 4527//4527 4526//4526 -f 3627//3627 4649//4649 3626//3626 -f 3626//3626 4649//4649 4650//4650 -f 3626//3626 4650//4650 3625//3625 -f 3625//3625 4650//4650 4651//4651 -f 3625//3625 4651//4651 3623//3623 -f 3623//3623 4651//4651 4652//4652 -f 3623//3623 4652//4652 3584//3584 -f 3584//3584 4652//4652 4653//4653 -f 3584//3584 4653//4653 3583//3583 -f 3583//3583 4653//4653 4642//4642 -f 3583//3583 4642//4642 3577//3577 -f 3577//3577 4642//4642 4643//4643 -f 3577//3577 4643//4643 3594//3594 -f 3594//3594 4643//4643 4644//4644 -f 3594//3594 4644//4644 3592//3592 -f 3592//3592 4644//4644 4645//4645 -f 3592//3592 4645//4645 3591//3591 -f 3591//3591 4645//4645 4646//4646 -f 3591//3591 4646//4646 3588//3588 -f 3588//3588 4646//4646 4647//4647 -f 3588//3588 4647//4647 3586//3586 -f 3586//3586 4647//4647 4648//4648 -f 3586//3586 4648//4648 3627//3627 -f 3627//3627 4648//4648 4649//4649 -f 3570//3570 4600//4600 3610//3610 -f 3610//3610 4600//4600 4601//4601 -f 3610//3610 4601//4601 3609//3609 -f 3609//3609 4601//4601 4602//4602 -f 3609//3609 4602//4602 3632//3632 -f 3632//3632 4602//4602 4603//4603 -f 3632//3632 4603//4603 3631//3631 -f 3631//3631 4603//4603 4604//4604 -f 3631//3631 4604//4604 3629//3629 -f 3629//3629 4604//4604 4593//4593 -f 3629//3629 4593//4593 3628//3628 -f 3628//3628 4593//4593 4594//4594 -f 3628//3628 4594//4594 3571//3571 -f 3571//3571 4594//4594 4595//4595 -f 3571//3571 4595//4595 3573//3573 -f 3573//3573 4595//4595 4596//4596 -f 3573//3573 4596//4596 3575//3575 -f 3575//3575 4596//4596 4597//4597 -f 3575//3575 4597//4597 3581//3581 -f 3581//3581 4597//4597 4598//4598 -f 3581//3581 4598//4598 3580//3580 -f 3580//3580 4598//4598 4599//4599 -f 3580//3580 4599//4599 3570//3570 -f 3570//3570 4599//4599 4600//4600 -f 4033//4033 4278//4278 4654//4654 -f 4654//4654 4278//4278 4280//4280 -f 4654//4654 4280//4280 4655//4655 -f 4655//4655 4280//4280 4656//4656 -f 4656//4656 4280//4280 4281//4281 -f 4656//4656 4281//4281 4657//4657 -f 4657//4657 4281//4281 4658//4658 -f 4658//4658 4281//4281 3924//3924 -f 4658//4658 3924//3924 3928//3928 -f 3928//3928 3927//3927 4659//4659 -f 3928//3928 4659//4659 4658//4658 -f 4658//4658 4659//4659 4660//4660 -f 4658//4658 4660//4660 4657//4657 -f 4657//4657 4660//4660 4661//4661 -f 4657//4657 4661//4661 4656//4656 -f 4656//4656 4661//4661 4655//4655 -f 4655//4655 4661//4661 4662//4662 -f 4655//4655 4662//4662 4654//4654 -f 4654//4654 4662//4662 4034//4034 -f 4654//4654 4034//4034 4033//4033 -f 4277//4277 4663//4663 4276//4276 -f 4276//4276 4663//4663 4348//4348 -f 4663//4663 4664//4664 4348//4348 -f 4348//4348 4664//4664 4665//4665 -f 4348//4348 4665//4665 4347//4347 -f 3712//3712 3814//3814 4666//4666 -f 4666//4666 3814//3814 4347//4347 -f 4666//4666 4347//4347 4667//4667 -f 4667//4667 4347//4347 4665//4665 -f 4277//4277 4473//4473 4668//4668 -f 4277//4277 4668//4668 4663//4663 -f 4663//4663 4668//4668 4669//4669 -f 4663//4663 4669//4669 4664//4664 -f 4664//4664 4669//4669 4670//4670 -f 4664//4664 4670//4670 4665//4665 -f 4665//4665 4670//4670 4667//4667 -f 4667//4667 4670//4670 4671//4671 -f 4667//4667 4671//4671 4666//4666 -f 4666//4666 4671//4671 3713//3713 -f 4666//4666 3713//3713 3712//3712 -f 4010//4010 4009//4009 4672//4672 -f 4010//4010 4672//4672 4673//4673 -f 4673//4673 4672//4672 4674//4674 -f 4673//4673 4674//4674 4675//4675 -f 4675//4675 4674//4674 3976//3976 -f 4675//4675 3976//3976 3977//3977 -f 4676//4676 3990//3990 4677//4677 -f 4677//4677 3990//3990 3988//3988 -f 4677//4677 3988//3988 4678//4678 -f 4678//4678 3988//3988 3986//3986 -f 4678//4678 3986//3986 4679//4679 -f 4679//4679 3986//3986 3984//3984 -f 4679//4679 3984//3984 4680//4680 -f 4680//4680 3984//3984 4007//4007 -f 4680//4680 4007//4007 4681//4681 -f 4681//4681 4007//4007 4006//4006 -f 4681//4681 4006//4006 4682//4682 -f 4682//4682 4006//4006 4005//4005 -f 4682//4682 4005//4005 4683//4683 -f 4683//4683 4005//4005 4001//4001 -f 4683//4683 4001//4001 4684//4684 -f 4684//4684 4001//4001 4000//4000 -f 4684//4684 4000//4000 4685//4685 -f 4685//4685 4000//4000 3998//3998 -f 4685//4685 3998//3998 4686//4686 -f 4686//4686 3998//3998 3996//3996 -f 4686//4686 3996//3996 4687//4687 -f 4687//4687 3996//3996 3994//3994 -f 4687//4687 3994//3994 4688//4688 -f 4688//4688 3994//3994 3993//3993 -f 4688//4688 3993//3993 4689//4689 -f 4689//4689 3993//3993 3981//3981 -f 4689//4689 3981//3981 4690//4690 -f 4690//4690 3981//3981 3980//3980 -f 4690//4690 3980//3980 4691//4691 -f 4691//4691 3980//3980 4017//4017 -f 4691//4691 4017//4017 4692//4692 -f 4692//4692 4017//4017 4016//4016 -f 4692//4692 4016//4016 4693//4693 -f 4693//4693 4016//4016 4014//4014 -f 4693//4693 4014//4014 4694//4694 -f 4694//4694 4014//4014 4012//4012 -f 4694//4694 4012//4012 4695//4695 -f 4695//4695 4012//4012 4011//4011 -f 4695//4695 4011//4011 4696//4696 -f 4696//4696 4011//4011 4025//4025 -f 4696//4696 4025//4025 4697//4697 -f 4697//4697 4025//4025 4024//4024 -f 4697//4697 4024//4024 4698//4698 -f 4698//4698 4024//4024 4023//4023 -f 4698//4698 4023//4023 4699//4699 -f 4699//4699 4023//4023 4022//4022 -f 4699//4699 4022//4022 4700//4700 -f 4700//4700 4022//4022 4021//4021 -f 4700//4700 4021//4021 4701//4701 -f 4701//4701 4021//4021 4018//4018 -f 4701//4701 4018//4018 4676//4676 -f 4676//4676 4018//4018 3990//3990 -f 4702//4702 4699//4699 4703//4703 -f 4703//4703 4699//4699 4700//4700 -f 4703//4703 4700//4700 4704//4704 -f 4704//4704 4700//4700 4701//4701 -f 4704//4704 4701//4701 4705//4705 -f 4705//4705 4701//4701 4676//4676 -f 4705//4705 4676//4676 4706//4706 -f 4706//4706 4676//4676 4677//4677 -f 4706//4706 4677//4677 4707//4707 -f 4708//4708 4692//4692 4709//4709 -f 4709//4709 4692//4692 4693//4693 -f 4709//4709 4693//4693 4710//4710 -f 4710//4710 4693//4693 4694//4694 -f 4710//4710 4694//4694 4711//4711 -f 4711//4711 4694//4694 4695//4695 -f 4711//4711 4695//4695 4712//4712 -f 4712//4712 4695//4695 4696//4696 -f 4712//4712 4696//4696 4713//4713 -f 4713//4713 4696//4696 4697//4697 -f 4713//4713 4697//4697 4702//4702 -f 4702//4702 4697//4697 4698//4698 -f 4702//4702 4698//4698 4699//4699 -f 4677//4677 4678//4678 4707//4707 -f 4707//4707 4678//4678 4679//4679 -f 4707//4707 4679//4679 4714//4714 -f 4714//4714 4679//4679 4680//4680 -f 4714//4714 4680//4680 4715//4715 -f 4715//4715 4680//4680 4681//4681 -f 4715//4715 4681//4681 4716//4716 -f 4716//4716 4681//4681 4682//4682 -f 4716//4716 4682//4682 4717//4717 -f 4717//4717 4682//4682 4683//4683 -f 4717//4717 4683//4683 4718//4718 -f 4718//4718 4683//4683 4684//4684 -f 4718//4718 4684//4684 4719//4719 -f 4684//4684 4685//4685 4719//4719 -f 4719//4719 4685//4685 4686//4686 -f 4719//4719 4686//4686 4720//4720 -f 4720//4720 4686//4686 4687//4687 -f 4720//4720 4687//4687 4721//4721 -f 4721//4721 4687//4687 4688//4688 -f 4721//4721 4688//4688 4722//4722 -f 4722//4722 4688//4688 4689//4689 -f 4722//4722 4689//4689 4723//4723 -f 4723//4723 4689//4689 4690//4690 -f 4723//4723 4690//4690 4708//4708 -f 4708//4708 4690//4690 4691//4691 -f 4708//4708 4691//4691 4692//4692 -f 4724//4724 4706//4706 4725//4725 -f 4725//4725 4706//4706 4707//4707 -f 4725//4725 4707//4707 4726//4726 -f 4726//4726 4707//4707 4714//4714 -f 4726//4726 4714//4714 4727//4727 -f 4727//4727 4714//4714 4715//4715 -f 4727//4727 4715//4715 4728//4728 -f 4728//4728 4715//4715 4716//4716 -f 4728//4728 4716//4716 4729//4729 -f 4729//4729 4716//4716 4717//4717 -f 4729//4729 4717//4717 4730//4730 -f 4730//4730 4717//4717 4718//4718 -f 4730//4730 4718//4718 4731//4731 -f 4731//4731 4718//4718 4719//4719 -f 4731//4731 4719//4719 4732//4732 -f 4732//4732 4719//4719 4720//4720 -f 4732//4732 4720//4720 4733//4733 -f 4733//4733 4720//4720 4721//4721 -f 4733//4733 4721//4721 4734//4734 -f 4734//4734 4721//4721 4722//4722 -f 4734//4734 4722//4722 4735//4735 -f 4735//4735 4722//4722 4723//4723 -f 4735//4735 4723//4723 4736//4736 -f 4736//4736 4723//4723 4708//4708 -f 4736//4736 4708//4708 4737//4737 -f 4737//4737 4708//4708 4709//4709 -f 4737//4737 4709//4709 4738//4738 -f 4738//4738 4709//4709 4710//4710 -f 4738//4738 4710//4710 4739//4739 -f 4739//4739 4710//4710 4711//4711 -f 4739//4739 4711//4711 4740//4740 -f 4740//4740 4711//4711 4712//4712 -f 4740//4740 4712//4712 4741//4741 -f 4741//4741 4712//4712 4713//4713 -f 4741//4741 4713//4713 4742//4742 -f 4742//4742 4713//4713 4702//4702 -f 4742//4742 4702//4702 4743//4743 -f 4743//4743 4702//4702 4703//4703 -f 4743//4743 4703//4703 4744//4744 -f 4744//4744 4703//4703 4704//4704 -f 4744//4744 4704//4704 4745//4745 -f 4745//4745 4704//4704 4705//4705 -f 4745//4745 4705//4705 4724//4724 -f 4724//4724 4705//4705 4706//4706 -f 4746//4746 4742//4742 4747//4747 -f 4747//4747 4742//4742 4743//4743 -f 4747//4747 4743//4743 4748//4748 -f 4748//4748 4743//4743 4744//4744 -f 4748//4748 4744//4744 4749//4749 -f 4749//4749 4744//4744 4745//4745 -f 4749//4749 4745//4745 4750//4750 -f 4750//4750 4745//4745 4724//4724 -f 4750//4750 4724//4724 4751//4751 -f 4751//4751 4724//4724 4725//4725 -f 4751//4751 4725//4725 4752//4752 -f 4752//4752 4725//4725 4726//4726 -f 4752//4752 4726//4726 4753//4753 -f 4754//4754 4736//4736 4755//4755 -f 4755//4755 4736//4736 4737//4737 -f 4755//4755 4737//4737 4756//4756 -f 4756//4756 4737//4737 4738//4738 -f 4756//4756 4738//4738 4757//4757 -f 4757//4757 4738//4738 4739//4739 -f 4757//4757 4739//4739 4758//4758 -f 4758//4758 4739//4739 4740//4740 -f 4758//4758 4740//4740 4746//4746 -f 4746//4746 4740//4740 4741//4741 -f 4746//4746 4741//4741 4742//4742 -f 4726//4726 4727//4727 4753//4753 -f 4753//4753 4727//4727 4728//4728 -f 4753//4753 4728//4728 4759//4759 -f 4759//4759 4728//4728 4729//4729 -f 4759//4759 4729//4729 4760//4760 -f 4760//4760 4729//4729 4730//4730 -f 4760//4760 4730//4730 4761//4761 -f 4761//4761 4730//4730 4731//4731 -f 4761//4761 4731//4731 4762//4762 -f 4762//4762 4731//4731 4732//4732 -f 4762//4762 4732//4732 4763//4763 -f 4763//4763 4732//4732 4733//4733 -f 4763//4763 4733//4733 4764//4764 -f 4764//4764 4733//4733 4734//4734 -f 4764//4764 4734//4734 4754//4754 -f 4754//4754 4734//4734 4735//4735 -f 4754//4754 4735//4735 4736//4736 -f 4765//4765 4750//4750 4766//4766 -f 4766//4766 4750//4750 4751//4751 -f 4766//4766 4751//4751 4767//4767 -f 4767//4767 4751//4751 4752//4752 -f 4767//4767 4752//4752 4768//4768 -f 4768//4768 4752//4752 4753//4753 -f 4768//4768 4753//4753 4769//4769 -f 4769//4769 4753//4753 4759//4759 -f 4769//4769 4759//4759 4770//4770 -f 4770//4770 4759//4759 4760//4760 -f 4770//4770 4760//4760 4771//4771 -f 4771//4771 4760//4760 4761//4761 -f 4771//4771 4761//4761 4772//4772 -f 4772//4772 4761//4761 4762//4762 -f 4772//4772 4762//4762 4773//4773 -f 4773//4773 4762//4762 4763//4763 -f 4773//4773 4763//4763 4774//4774 -f 4774//4774 4763//4763 4764//4764 -f 4774//4774 4764//4764 4775//4775 -f 4775//4775 4764//4764 4754//4754 -f 4775//4775 4754//4754 4776//4776 -f 4776//4776 4754//4754 4755//4755 -f 4776//4776 4755//4755 4777//4777 -f 4777//4777 4755//4755 4756//4756 -f 4777//4777 4756//4756 4778//4778 -f 4778//4778 4756//4756 4757//4757 -f 4778//4778 4757//4757 4779//4779 -f 4779//4779 4757//4757 4758//4758 -f 4779//4779 4758//4758 4780//4780 -f 4780//4780 4758//4758 4746//4746 -f 4780//4780 4746//4746 4781//4781 -f 4781//4781 4746//4746 4747//4747 -f 4781//4781 4747//4747 4782//4782 -f 4782//4782 4747//4747 4748//4748 -f 4782//4782 4748//4748 4783//4783 -f 4783//4783 4748//4748 4749//4749 -f 4783//4783 4749//4749 4765//4765 -f 4765//4765 4749//4749 4750//4750 -f 4765//4765 4766//4766 4784//4784 -f 4781//4781 4782//4782 4784//4784 -f 4784//4784 4782//4782 4783//4783 -f 4784//4784 4783//4783 4765//4765 -f 4778//4778 4779//4779 4784//4784 -f 4784//4784 4779//4779 4780//4780 -f 4784//4784 4780//4780 4781//4781 -f 4775//4775 4776//4776 4784//4784 -f 4784//4784 4776//4776 4777//4777 -f 4784//4784 4777//4777 4778//4778 -f 4772//4772 4773//4773 4784//4784 -f 4784//4784 4773//4773 4774//4774 -f 4784//4784 4774//4774 4775//4775 -f 4769//4769 4770//4770 4784//4784 -f 4784//4784 4770//4770 4771//4771 -f 4784//4784 4771//4771 4772//4772 -f 4766//4766 4767//4767 4784//4784 -f 4784//4784 4767//4767 4768//4768 -f 4784//4784 4768//4768 4769//4769 -f 4342//4342 3827//3827 4338//4338 -f 4338//4338 3827//3827 3822//3822 -f 4332//4332 3844//3844 4328//4328 -f 4328//4328 3844//3844 3833//3833 -f 4322//4322 3853//3853 4318//4318 -f 4318//4318 3853//3853 3850//3850 -f 3780//3780 4308//4308 3781//3781 -f 3781//3781 4308//4308 4312//4312 -f 3781//3781 4312//4312 3791//3791 -f 3875//3875 4295//4295 3710//3710 -f 3710//3710 4295//4295 4300//4300 -f 3710//3710 4300//4300 3711//3711 -f 4272//4272 3877//3877 4273//4273 -f 4273//4273 3877//3877 3876//3876 -f 3880//3880 4260//4260 3879//3879 -f 3879//3879 4260//4260 4259//4259 -f 3879//3879 4259//4259 3878//3878 -f 4212//4212 3901//3901 4213//4213 -f 4213//4213 3901//3901 3900//3900 -f 4206//4206 3921//3921 4207//4207 -f 4207//4207 3921//3921 3920//3920 -f 4200//4200 3945//3945 4201//4201 -f 4201//4201 3945//3945 3944//3944 -f 4092//4092 4202//4202 4093//4093 -f 4093//4093 4202//4202 4203//4203 -f 4176//4176 4199//4199 4175//4175 -f 4175//4175 4199//4199 4198//4198 -f 4150//4150 4208//4208 4151//4151 -f 4151//4151 4208//4208 4209//4209 -f 4136//4136 4205//4205 4137//4137 -f 4137//4137 4205//4205 4204//4204 -f 4132//4132 4214//4214 4133//4133 -f 4133//4133 4214//4214 4215//4215 -f 4128//4128 4211//4211 4129//4129 -f 4129//4129 4211//4211 4210//4210 -f 4118//4118 4261//4261 4119//4119 -f 4119//4119 4261//4261 4262//4262 -f 4146//4146 4258//4258 4147//4147 -f 4147//4147 4258//4258 4257//4257 -f 4094//4094 4340//4340 4095//4095 -f 4095//4095 4340//4340 4339//4339 -f 4110//4110 4344//4344 4111//4111 -f 4111//4111 4344//4344 4337//4337 -f 4098//4098 4330//4330 4099//4099 -f 4099//4099 4330//4330 4329//4329 -f 4115//4115 4334//4334 4116//4116 -f 4116//4116 4334//4334 4327//4327 -f 4102//4102 4320//4320 4103//4103 -f 4103//4103 4320//4320 4319//4319 -f 4122//4122 4324//4324 4123//4123 -f 4123//4123 4324//4324 4317//4317 -f 4141//4141 4310//4310 4142//4142 -f 4142//4142 4310//4310 4309//4309 -f 4144//4144 4314//4314 4145//4145 -f 4145//4145 4314//4314 4307//4307 -f 4168//4168 4274//4274 4169//4169 -f 4169//4169 4274//4274 4275//4275 -f 4165//4165 4271//4271 4166//4166 -f 4166//4166 4271//4271 4270//4270 -f 4160//4160 4302//4302 4161//4161 -f 4161//4161 4302//4302 4296//4296 -f 4087//4087 4298//4298 4088//4088 -f 4088//4088 4298//4298 4297//4297 -f 4346//4346 3819//3819 4345//4345 -f 4345//4345 3819//3819 3820//3820 -f 3840//3840 4335//4335 3841//3841 -f 3841//3841 4335//4335 4336//4336 -f 3841//3841 4336//4336 3815//3815 -f 3855//3855 4325//4325 3863//3863 -f 3863//3863 4325//4325 4326//4326 -f 3863//3863 4326//4326 3832//3832 -f 3793//3793 4315//4315 3858//3858 -f 3858//3858 4315//4315 4316//4316 -f 3858//3858 4316//4316 3849//3849 -f 4306//4306 3782//3782 4305//4305 -f 4305//4305 3782//3782 3784//3784 -f 4304//4304 3784//3784 4303//4303 -f 4303//4303 3784//3784 3787//3787 -f 4282//4282 3926//3926 4279//4279 -f 4279//4279 3926//3926 3925//3925 -f 3942//3942 4283//4283 3943//3943 -f 3943//3943 4283//4283 4284//4284 -f 3943//3943 4284//4284 3908//3908 -f 3911//3911 4285//4285 3912//3912 -f 3912//3912 4285//4285 4286//4286 -f 3912//3912 4286//4286 3887//3887 -f 3895//3895 4287//4287 3894//3894 -f 3894//3894 4287//4287 4288//4288 -f 3894//3894 4288//4288 3723//3723 -f 4292//4292 3744//3744 4291//4291 -f 4291//4291 3744//3744 3742//3742 -f 4290//4290 3742//3742 4289//4289 -f 4289//4289 3742//3742 3740//3740 -f 4294//4294 3771//3771 4293//4293 -f 4293//4293 3771//3771 3770//3770 -f 4293//4293 3770//3770 3757//3757 -f 3979//3979 4547//4547 3950//3950 -f 3950//3950 4547//4547 3948//3948 -f 4547//4547 3979//3979 4548//4548 -f 4548//4548 3979//3979 4013//4013 -f 4548//4548 4013//4013 4549//4549 -f 4549//4549 4013//4013 4015//4015 -f 4549//4549 4015//4015 4525//4525 -f 4525//4525 4015//4015 3982//3982 -f 4553//4553 3927//3927 3949//3949 -f 3949//3949 3927//3927 3929//3929 -f 4010//4010 4524//4524 3982//3982 -f 3982//3982 4524//4524 4525//4525 -f 4551//4551 4034//4034 4550//4550 -f 4550//4550 4034//4034 4662//4662 -f 4550//4550 4662//4662 4555//4555 -f 4555//4555 4662//4662 4661//4661 -f 4555//4555 4661//4661 4556//4556 -f 4556//4556 4661//4661 4660//4660 -f 4556//4556 4660//4660 4554//4554 -f 4554//4554 4660//4660 4659//4659 -f 4554//4554 4659//4659 4553//4553 -f 4553//4553 4659//4659 3927//3927 -f 4524//4524 4010//4010 4673//4673 -f 4524//4524 4673//4673 4523//4523 -f 4523//4523 4673//4673 4675//4675 -f 4523//4523 4675//4675 4522//4522 -f 4522//4522 4675//4675 3977//3977 -f 4522//4522 3977//3977 4519//4519 -f 4552//4552 4035//4035 4551//4551 -f 4551//4551 4035//4035 4034//4034 -f 3972//3972 4520//4520 3977//3977 -f 3977//3977 4520//4520 4519//4519 -f 4538//4538 3973//3973 4026//4026 -f 4035//4035 4552//4552 4032//4032 -f 4032//4032 4552//4552 4528//4528 -f 4032//4032 4528//4528 4530//4530 -f 4538//4538 4026//4026 4536//4536 -f 4536//4536 4026//4026 4027//4027 -f 4536//4536 4027//4027 4534//4534 -f 4534//4534 4027//4027 4028//4028 -f 4534//4534 4028//4028 4532//4532 -f 4028//4028 4029//4029 4532//4532 -f 4532//4532 4029//4029 4030//4030 -f 4532//4532 4030//4030 4530//4530 -f 4530//4530 4030//4030 4031//4031 -f 4530//4530 4031//4031 4032//4032 -f 3973//3973 4538//4538 3972//3972 -f 3972//3972 4538//4538 4520//4520 -f 4511//4511 3999//3999 4350//4350 -f 4350//4350 3999//3999 4003//4003 -f 4349//4349 3813//3813 4512//4512 -f 4512//4512 3813//3813 3714//3714 -f 4512//4512 3714//3714 3713//3713 -f 4483//4483 4008//4008 4517//4517 -f 4517//4517 4008//4008 3995//3995 -f 4517//4517 3995//3995 4518//4518 -f 4518//4518 3995//3995 3997//3997 -f 4518//4518 3997//3997 4511//4511 -f 4511//4511 3997//3997 3999//3999 -f 4490//4490 4489//4489 4513//4513 -f 4490//4490 4513//4513 4473//4473 -f 4512//4512 3713//3713 4514//4514 -f 4514//4514 3713//3713 4671//4671 -f 4514//4514 4671//4671 4515//4515 -f 4515//4515 4671//4671 4670//4670 -f 4515//4515 4670//4670 4516//4516 -f 4516//4516 4670//4670 4669//4669 -f 4516//4516 4669//4669 4513//4513 -f 4513//4513 4669//4669 4668//4668 -f 4513//4513 4668//4668 4473//4473 -f 4482//4482 4009//4009 4483//4483 -f 4483//4483 4009//4009 4008//4008 -f 4473//4473 4474//4474 4490//4490 -f 4487//4487 3976//3976 4674//4674 -f 4487//4487 4674//4674 4486//4486 -f 4486//4486 4674//4674 4672//4672 -f 4486//4486 4672//4672 4485//4485 -f 4485//4485 4672//4672 4009//4009 -f 4485//4485 4009//4009 4482//4482 -f 4491//4491 4490//4490 4474//4474 -f 4474//4474 4475//4475 4491//4491 -f 4491//4491 4475//4475 4476//4476 -f 4491//4491 4476//4476 4509//4509 -f 4509//4509 4476//4476 4477//4477 -f 4477//4477 4478//4478 4509//4509 -f 4509//4509 4478//4478 4479//4479 -f 4509//4509 4479//4479 4507//4507 -f 4479//4479 4480//4480 4507//4507 -f 4507//4507 4480//4480 4481//4481 -f 4507//4507 4481//4481 4505//4505 -f 4505//4505 4481//4481 3974//3974 -f 4505//4505 3974//3974 4503//4503 -f 4488//4488 3975//3975 4487//4487 -f 4487//4487 3975//3975 3976//3976 -f 3975//3975 4488//4488 3974//3974 -f 3974//3974 4488//4488 4503//4503 -f 3978//3978 3951//3951 4362//4362 -f 4362//4362 3951//3951 3952//3952 -f 3969//3969 4362//4362 3952//3952 -f 3968//3968 4361//4361 3969//3969 -f 3969//3969 4361//4361 4362//4362 -f 4607//4607 4637//4637 3946//3946 -f 3946//3946 4637//4637 3947//3947 -f 3947//3947 3964//3964 3952//3952 -f 3952//3952 3964//3964 3969//3969 -f 4361//4361 3968//3968 4360//4360 -f 4360//4360 3968//3968 3970//3970 -f 4360//4360 3970//3970 4359//4359 -f 4359//4359 3970//3970 3971//3971 -f 4359//4359 3971//3971 4358//4358 -f 4358//4358 3971//3971 3963//3963 -f 4358//4358 3963//3963 4357//4357 -f 4357//4357 3963//3963 3962//3962 -f 4357//4357 3962//3962 4356//4356 -f 4356//4356 3962//3962 3960//3960 -f 4356//4356 3960//3960 4355//4355 -f 4355//4355 3960//3960 3959//3959 -f 4355//4355 3959//3959 4354//4354 -f 4354//4354 3959//3959 3967//3967 -f 3946//3946 3727//3727 3738//3738 -f 3754//3754 3764//3764 4610//4610 -f 4610//4610 3764//3764 3954//3954 -f 4610//4610 3954//3954 4608//4608 -f 3754//3754 4610//4610 3753//3753 -f 3753//3753 4610//4610 4615//4615 -f 3753//3753 4615//4615 3762//3762 -f 4615//4615 4614//4614 3762//3762 -f 3762//3762 4614//4614 4618//4618 -f 3762//3762 4618//4618 3763//3763 -f 4618//4618 4617//4617 3763//3763 -f 3763//3763 4617//4617 4621//4621 -f 3763//3763 4621//4621 3743//3743 -f 4621//4621 4620//4620 3743//3743 -f 3743//3743 4620//4620 4624//4624 -f 3743//3743 4624//4624 3741//3741 -f 4624//4624 4623//4623 3741//3741 -f 3741//3741 4623//4623 4627//4627 -f 3741//3741 4627//4627 3732//3732 -f 3732//3732 4627//4627 4626//4626 -f 3732//3732 4626//4626 3733//3733 -f 3733//3733 4626//4626 4630//4630 -f 3733//3733 4630//4630 3735//3735 -f 4630//4630 4629//4629 3735//3735 -f 3735//3735 4629//4629 4633//4633 -f 3735//3735 4633//4633 3737//3737 -f 4633//4633 4632//4632 3737//3737 -f 3737//3737 4632//4632 4636//4636 -f 3737//3737 4636//4636 3738//3738 -f 3738//3738 4636//4636 4635//4635 -f 3738//3738 4635//4635 3946//3946 -f 3946//3946 4635//4635 4634//4634 -f 3946//3946 4634//4634 4607//4607 -f 3947//3947 4637//4637 3964//3964 -f 3958//3958 4353//4353 3967//3967 -f 3967//3967 4353//4353 4354//4354 -f 4353//4353 4352//4352 4002//4002 -f 4002//4002 4352//4352 4004//4004 -f 3953//3953 4641//4641 3954//3954 -f 3954//3954 4641//4641 4608//4608 -f 4640//4640 4641//4641 3965//3965 -f 4640//4640 3965//3965 4639//4639 -f 4639//4639 3965//3965 3961//3961 -f 4639//4639 3961//3961 4638//4638 -f 4638//4638 3961//3961 3964//3964 -f 4638//4638 3964//3964 4637//4637 -f 4353//4353 3958//3958 4352//4352 -f 4641//4641 3953//3953 3965//3965 -f 3957//3957 4351//4351 3958//3958 -f 3958//3958 4351//4351 4352//4352 -f 3955//3955 3966//3966 3953//3953 -f 3953//3953 3966//3966 3965//3965 -f 3966//3966 4588//4588 4589//4589 -f 3966//3966 4589//4589 3956//3956 -f 3956//3956 4589//4589 4590//4590 -f 3956//3956 4590//4590 3957//3957 -f 3957//3957 4590//4590 4591//4591 -f 3957//3957 4591//4591 4592//4592 -f 3957//3957 4592//4592 4351//4351 -f 3966//3966 3955//3955 4588//4588 -f 3715//3715 4351//4351 3716//3716 -f 3716//3716 4351//4351 4592//4592 -f 3716//3716 4592//4592 4557//4557 -f 3955//3955 3767//3767 4588//4588 -f 4588//4588 3767//3767 3769//3769 -f 4588//4588 3769//3769 4586//4586 -f 4586//4586 3769//3769 4587//4587 -f 4587//4587 3769//3769 3768//3768 -f 3717//3717 3716//3716 4557//4557 -f 4557//4557 4559//4559 3717//3717 -f 3717//3717 4559//4559 4561//4561 -f 3717//3717 4561//4561 3800//3800 -f 4561//4561 4565//4565 3800//3800 -f 3800//3800 4565//4565 4564//4564 -f 3800//3800 4564//4564 3806//3806 -f 4564//4564 4568//4568 3806//3806 -f 3806//3806 4568//4568 4567//4567 -f 3806//3806 4567//4567 3805//3805 -f 4567//4567 4571//4571 3805//3805 -f 3805//3805 4571//4571 4570//4570 -f 3805//3805 4570//4570 3783//3783 -f 3783//3783 4570//4570 3785//3785 -f 4570//4570 4578//4578 3785//3785 -f 3785//3785 4578//4578 4577//4577 -f 3785//3785 4577//4577 3786//3786 -f 3786//3786 4577//4577 4575//4575 -f 3786//3786 4575//4575 3788//3788 -f 3788//3788 4575//4575 4573//4573 -f 3788//3788 4573//4573 3874//3874 -f 3874//3874 4573//4573 3872//3872 -f 3872//3872 4573//4573 4581//4581 -f 3872//3872 4581//4581 3870//3870 -f 4581//4581 4580//4580 3870//3870 -f 3870//3870 4580//4580 4584//4584 -f 3870//3870 4584//4584 3768//3768 -f 3768//3768 4584//4584 4583//4583 -f 3768//3768 4583//4583 4587//4587 -f 4785//4785 4786//4786 4787//4787 -f 4788//4788 4789//4789 4790//4790 -f 4791//4791 4792//4792 4793//4793 -f 4794//4794 4795//4795 4796//4796 -f 4797//4797 4798//4798 4799//4799 -f 4800//4800 4801//4801 4802//4802 -f 4802//4802 4801//4801 4803//4803 -f 4802//4802 4803//4803 4804//4804 -f 4805//4805 4806//4806 4807//4807 -f 4807//4807 4808//4808 4805//4805 -f 4805//4805 4808//4808 4809//4809 -f 4805//4805 4809//4809 4810//4810 -f 4810//4810 4809//4809 4811//4811 -f 4810//4810 4811//4811 4812//4812 -f 4813//4813 4814//4814 4815//4815 -f 4815//4815 4814//4814 4816//4816 -f 4815//4815 4816//4816 4817//4817 -f 4817//4817 4816//4816 4818//4818 -f 4817//4817 4818//4818 4812//4812 -f 4812//4812 4818//4818 4819//4819 -f 4812//4812 4819//4819 4810//4810 -f 4820//4820 4821//4821 4822//4822 -f 4822//4822 4821//4821 4823//4823 -f 4822//4822 4823//4823 4824//4824 -f 4824//4824 4823//4823 4825//4825 -f 4824//4824 4825//4825 4826//4826 -f 4825//4825 4827//4827 4826//4826 -f 4826//4826 4827//4827 4828//4828 -f 4826//4826 4828//4828 4796//4796 -f 4796//4796 4828//4828 4829//4829 -f 4796//4796 4829//4829 4830//4830 -f 4831//4831 4832//4832 4833//4833 -f 4833//4833 4832//4832 4834//4834 -f 4833//4833 4834//4834 4835//4835 -f 4835//4835 4834//4834 4836//4836 -f 4837//4837 4838//4838 4839//4839 -f 4839//4839 4838//4838 4840//4840 -f 4839//4839 4840//4840 4841//4841 -f 4837//4837 4842//4842 4838//4838 -f 4838//4838 4842//4842 4843//4843 -f 4838//4838 4843//4843 4844//4844 -f 4844//4844 4843//4843 4845//4845 -f 4844//4844 4845//4845 4846//4846 -f 4847//4847 4848//4848 4849//4849 -f 4850//4850 4851//4851 4852//4852 -f 4852//4852 4851//4851 4853//4853 -f 4852//4852 4853//4853 4839//4839 -f 4839//4839 4853//4853 4854//4854 -f 4839//4839 4854//4854 4837//4837 -f 4845//4845 4855//4855 4846//4846 -f 4846//4846 4855//4855 4856//4856 -f 4846//4846 4856//4856 4848//4848 -f 4848//4848 4856//4856 4857//4857 -f 4848//4848 4857//4857 4849//4849 -f 4858//4858 4859//4859 4860//4860 -f 4859//4859 4861//4861 4860//4860 -f 4860//4860 4861//4861 4862//4862 -f 4860//4860 4862//4862 4863//4863 -f 4863//4863 4862//4862 4864//4864 -f 4864//4864 4865//4865 4863//4863 -f 4863//4863 4865//4865 4866//4866 -f 4863//4863 4866//4866 4867//4867 -f 4866//4866 4868//4868 4867//4867 -f 4867//4867 4868//4868 4869//4869 -f 4867//4867 4869//4869 4870//4870 -f 4870//4870 4869//4869 4871//4871 -f 4870//4870 4871//4871 4872//4872 -f 4872//4872 4871//4871 4873//4873 -f 4872//4872 4873//4873 4874//4874 -f 4874//4874 4873//4873 4875//4875 -f 4874//4874 4875//4875 4858//4858 -f 4876//4876 4877//4877 4878//4878 -f 4878//4878 4877//4877 4879//4879 -f 4878//4878 4879//4879 4880//4880 -f 4880//4880 4879//4879 4881//4881 -f 4880//4880 4881//4881 4882//4882 -f 4882//4882 4883//4883 4880//4880 -f 4880//4880 4883//4883 4884//4884 -f 4880//4880 4884//4884 4885//4885 -f 4886//4886 4887//4887 4888//4888 -f 4884//4884 4889//4889 4885//4885 -f 4885//4885 4889//4889 4890//4890 -f 4885//4885 4890//4890 4887//4887 -f 4888//4888 4891//4891 4886//4886 -f 4886//4886 4891//4891 4892//4892 -f 4886//4886 4892//4892 4893//4893 -f 4893//4893 4892//4892 4894//4894 -f 4893//4893 4894//4894 4895//4895 -f 4895//4895 4894//4894 4896//4896 -f 4895//4895 4896//4896 4881//4881 -f 4881//4881 4896//4896 4897//4897 -f 4881//4881 4897//4897 4882//4882 -f 4898//4898 4899//4899 4900//4900 -f 4900//4900 4899//4899 4901//4901 -f 4900//4900 4901//4901 4902//4902 -f 4903//4903 4904//4904 4905//4905 -f 4905//4905 4904//4904 4906//4906 -f 4905//4905 4906//4906 4907//4907 -f 4903//4903 4908//4908 4904//4904 -f 4904//4904 4908//4908 4909//4909 -f 4904//4904 4909//4909 4910//4910 -f 4910//4910 4909//4909 4911//4911 -f 4910//4910 4911//4911 4912//4912 -f 4912//4912 4911//4911 4913//4913 -f 4912//4912 4913//4913 4901//4901 -f 4901//4901 4913//4913 4914//4914 -f 4901//4901 4914//4914 4902//4902 -f 4915//4915 4916//4916 4917//4917 -f 4917//4917 4916//4916 4900//4900 -f 4917//4917 4900//4900 4918//4918 -f 4918//4918 4900//4900 4902//4902 -f 4919//4919 4920//4920 4921//4921 -f 4919//4919 4921//4921 4922//4922 -f 4923//4923 4924//4924 4900//4900 -f 4900//4900 4924//4924 4925//4925 -f 4900//4900 4925//4925 4898//4898 -f 4898//4898 4925//4925 4926//4926 -f 4898//4898 4926//4926 4927//4927 -f 4928//4928 4929//4929 4930//4930 -f 4931//4931 4932//4932 4933//4933 -f 4932//4932 4934//4934 4933//4933 -f 4933//4933 4934//4934 4935//4935 -f 4933//4933 4935//4935 4936//4936 -f 4936//4936 4935//4935 4937//4937 -f 4921//4921 4938//4938 4922//4922 -f 4922//4922 4938//4938 4939//4939 -f 4922//4922 4939//4939 4940//4940 -f 4940//4940 4939//4939 4941//4941 -f 4942//4942 4787//4787 4943//4943 -f 4943//4943 4787//4787 4944//4944 -f 4943//4943 4944//4944 4906//4906 -f 4906//4906 4944//4944 4916//4916 -f 4906//4906 4916//4916 4907//4907 -f 4907//4907 4916//4916 4915//4915 -f 4945//4945 4946//4946 4947//4947 -f 4948//4948 4947//4947 4949//4949 -f 4950//4950 4951//4951 4952//4952 -f 4952//4952 4951//4951 4922//4922 -f 4952//4952 4922//4922 4953//4953 -f 4953//4953 4922//4922 4940//4940 -f 4953//4953 4940//4940 4954//4954 -f 4954//4954 4940//4940 4941//4941 -f 4954//4954 4941//4941 4955//4955 -f 4863//4863 4956//4956 4860//4860 -f 4860//4860 4956//4956 4957//4957 -f 4860//4860 4957//4957 4954//4954 -f 4954//4954 4957//4957 4958//4958 -f 4954//4954 4958//4958 4953//4953 -f 4959//4959 4960//4960 4961//4961 -f 4962//4962 4870//4870 4963//4963 -f 4963//4963 4870//4870 4872//4872 -f 4963//4963 4872//4872 4964//4964 -f 4964//4964 4872//4872 4961//4961 -f 4965//4965 4966//4966 4967//4967 -f 4968//4968 4966//4966 4969//4969 -f 4969//4969 4966//4966 4965//4965 -f 4969//4969 4965//4965 4970//4970 -f 4831//4831 4820//4820 4832//4832 -f 4832//4832 4820//4820 4822//4822 -f 4832//4832 4822//4822 4971//4971 -f 4971//4971 4822//4822 4972//4972 -f 4971//4971 4972//4972 4973//4973 -f 4973//4973 4972//4972 4974//4974 -f 4973//4973 4974//4974 4975//4975 -f 4793//4793 4792//4792 4834//4834 -f 4830//4830 4836//4836 4796//4796 -f 4796//4796 4836//4836 4834//4834 -f 4796//4796 4834//4834 4794//4794 -f 4794//4794 4834//4834 4792//4792 -f 4794//4794 4792//4792 4976//4976 -f 4793//4793 4977//4977 4791//4791 -f 4791//4791 4977//4977 4978//4978 -f 4791//4791 4978//4978 4979//4979 -f 4979//4979 4978//4978 4980//4980 -f 4981//4981 4982//4982 4978//4978 -f 4978//4978 4982//4982 4983//4983 -f 4978//4978 4983//4983 4980//4980 -f 4984//4984 4985//4985 4986//4986 -f 4986//4986 4985//4985 4987//4987 -f 4986//4986 4987//4987 4988//4988 -f 4988//4988 4987//4987 4989//4989 -f 4990//4990 4991//4991 4987//4987 -f 4992//4992 4989//4989 4993//4993 -f 4993//4993 4989//4989 4987//4987 -f 4993//4993 4987//4987 4994//4994 -f 4994//4994 4987//4987 4991//4991 -f 4995//4995 4996//4996 4997//4997 -f 4887//4887 4886//4886 4885//4885 -f 4885//4885 4886//4886 4998//4998 -f 4885//4885 4998//4998 4999//4999 -f 4999//4999 5000//5000 4885//4885 -f 4885//4885 5000//5000 5001//5001 -f 4885//4885 5001//5001 5002//5002 -f 5002//5002 5001//5001 4995//4995 -f 5003//5003 5004//5004 5005//5005 -f 5005//5005 5006//5006 5003//5003 -f 5003//5003 5006//5006 5007//5007 -f 5003//5003 5007//5007 4838//4838 -f 4838//4838 5007//5007 5008//5008 -f 4838//4838 5008//5008 4840//4840 -f 5006//5006 5009//5009 5007//5007 -f 5007//5007 5009//5009 5010//5010 -f 5007//5007 5010//5010 5011//5011 -f 5011//5011 5010//5010 5012//5012 -f 5011//5011 5012//5012 5013//5013 -f 5012//5012 5014//5014 5013//5013 -f 5013//5013 5014//5014 5015//5015 -f 5013//5013 5015//5015 5016//5016 -f 5017//5017 5018//5018 5019//5019 -f 5019//5019 5018//5018 5020//5020 -f 5019//5019 5020//5020 5004//5004 -f 5004//5004 5020//5020 5021//5021 -f 5004//5004 5021//5021 5005//5005 -f 4872//4872 5022//5022 5013//5013 -f 4961//4961 4872//4872 4959//4959 -f 4959//4959 4872//4872 5013//5013 -f 4959//4959 5013//5013 5019//5019 -f 5019//5019 5013//5013 5016//5016 -f 5019//5019 5016//5016 5017//5017 -f 4858//4858 4860//4860 4874//4874 -f 4874//4874 4860//4860 5023//5023 -f 4874//4874 5023//5023 4872//4872 -f 4872//4872 5023//5023 5024//5024 -f 4872//4872 5024//5024 5022//5022 -f 5025//5025 5026//5026 4954//4954 -f 5026//5026 5027//5027 4954//4954 -f 4954//4954 5027//5027 5028//5028 -f 4954//4954 5028//5028 4860//4860 -f 4860//4860 5028//5028 5029//5029 -f 4860//4860 5029//5029 5023//5023 -f 5030//5030 5031//5031 5032//5032 -f 5032//5032 5031//5031 5025//5025 -f 5032//5032 5025//5025 5033//5033 -f 5033//5033 5025//5025 4954//4954 -f 5033//5033 4954//4954 5034//5034 -f 5034//5034 4954//4954 4955//4955 -f 5035//5035 5030//5030 4933//4933 -f 4933//4933 5030//5030 5032//5032 -f 4933//4933 5032//5032 4931//4931 -f 4931//4931 5032//5032 5033//5033 -f 4931//4931 5033//5033 5036//5036 -f 5036//5036 5033//5033 5034//5034 -f 5037//5037 5038//5038 5039//5039 -f 5039//5039 5038//5038 5040//5040 -f 5039//5039 5040//5040 5041//5041 -f 5041//5041 5040//5040 5042//5042 -f 5041//5041 5042//5042 4933//4933 -f 4933//4933 5042//5042 5043//5043 -f 4933//4933 5043//5043 5035//5035 -f 5044//5044 5045//5045 5046//5046 -f 5045//5045 5044//5044 5047//5047 -f 5048//5048 5049//5049 5050//5050 -f 5051//5051 5052//5052 5053//5053 -f 5049//5049 5048//5048 5053//5053 -f 5053//5053 5048//5048 5054//5054 -f 5053//5053 5054//5054 5051//5051 -f 5052//5052 5051//5051 5055//5055 -f 5055//5055 5051//5051 5056//5056 -f 5055//5055 5056//5056 5057//5057 -f 5058//5058 5059//5059 5045//5045 -f 5045//5045 5059//5059 5060//5060 -f 5045//5045 5060//5060 5046//5046 -f 5046//5046 5060//5060 5061//5061 -f 5046//5046 5061//5061 5062//5062 -f 5062//5062 5061//5061 5063//5063 -f 5062//5062 5063//5063 5064//5064 -f 5064//5064 5063//5063 5065//5065 -f 5064//5064 5065//5065 5066//5066 -f 5066//5066 5065//5065 5067//5067 -f 5066//5066 5067//5067 5068//5068 -f 5069//5069 5070//5070 5071//5071 -f 5071//5071 5070//5070 5072//5072 -f 5069//5069 5073//5073 5070//5070 -f 5070//5070 5073//5073 5074//5074 -f 5070//5070 5074//5074 4806//4806 -f 4806//4806 5074//5074 5075//5075 -f 4806//4806 5075//5075 4807//4807 -f 4807//4807 5075//5075 5076//5076 -f 4807//4807 5076//5076 5077//5077 -f 5077//5077 5076//5076 5078//5078 -f 5077//5077 5078//5078 4800//4800 -f 4800//4800 5078//5078 5079//5079 -f 4800//4800 5079//5079 4801//4801 -f 5080//5080 5081//5081 5082//5082 -f 5082//5082 5081//5081 5083//5083 -f 5082//5082 5083//5083 5072//5072 -f 5072//5072 5083//5083 5084//5084 -f 5072//5072 5084//5084 5071//5071 -f 5085//5085 5086//5086 5087//5087 -f 5087//5087 5086//5086 5088//5088 -f 5087//5087 5088//5088 5089//5089 -f 5080//5080 5082//5082 5090//5090 -f 5090//5090 5082//5082 5091//5091 -f 5090//5090 5091//5091 5092//5092 -f 5092//5092 5091//5091 4985//4985 -f 5092//5092 4985//4985 5093//5093 -f 5093//5093 4985//4985 4984//4984 -f 5093//5093 4984//4984 5087//5087 -f 5087//5087 4984//4984 5094//5094 -f 5087//5087 5094//5094 5085//5085 -f 4993//4993 5095//5095 4992//4992 -f 4992//4992 5095//5095 5096//5096 -f 4992//4992 5096//5096 5097//5097 -f 5097//5097 5096//5096 5098//5098 -f 5097//5097 5098//5098 5099//5099 -f 5099//5099 5098//5098 5100//5100 -f 5099//5099 5100//5100 5101//5101 -f 5101//5101 5100//5100 5088//5088 -f 5101//5101 5088//5088 5102//5102 -f 5102//5102 5088//5088 5086//5086 -f 4813//4813 4804//4804 4814//4814 -f 4814//4814 4804//4804 4803//4803 -f 4814//4814 4803//4803 5088//5088 -f 5088//5088 4803//4803 5103//5103 -f 5088//5088 5103//5103 5089//5089 -f 4790//4790 5104//5104 5105//5105 -f 5058//5058 5106//5106 5107//5107 -f 4789//4789 5059//5059 4790//4790 -f 4790//4790 5059//5059 5058//5058 -f 4790//4790 5058//5058 5104//5104 -f 5104//5104 5058//5058 5107//5107 -f 4805//4805 5108//5108 4806//4806 -f 4806//4806 5108//5108 5109//5109 -f 4806//4806 5109//5109 5070//5070 -f 5070//5070 5109//5109 5110//5110 -f 5070//5070 5110//5110 5111//5111 -f 5105//5105 5112//5112 4790//4790 -f 4790//4790 5112//5112 5113//5113 -f 4790//4790 5113//5113 5114//5114 -f 5114//5114 5113//5113 5115//5115 -f 5114//5114 5115//5115 4805//4805 -f 4805//4805 5115//5115 5116//5116 -f 4805//4805 5116//5116 5108//5108 -f 5117//5117 5118//5118 5119//5119 -f 5117//5117 5119//5119 5120//5120 -f 5121//5121 5122//5122 5123//5123 -f 5123//5123 5122//5122 5124//5124 -f 5123//5123 5124//5124 5125//5125 -f 5125//5125 5120//5120 5123//5123 -f 5123//5123 5120//5120 5119//5119 -f 5123//5123 5119//5119 5126//5126 -f 5126//5126 5119//5119 5047//5047 -f 5126//5126 5047//5047 5127//5127 -f 5127//5127 5047//5047 5044//5044 -f 4987//4987 5128//5128 5121//5121 -f 5121//5121 5128//5128 5129//5129 -f 5121//5121 5129//5129 5122//5122 -f 5118//5118 5130//5130 5091//5091 -f 5091//5091 5130//5130 5131//5131 -f 5091//5091 5131//5131 4985//4985 -f 4985//4985 5131//5131 5132//5132 -f 4985//4985 5132//5132 4987//4987 -f 4987//4987 5132//5132 5133//5133 -f 4987//4987 5133//5133 5128//5128 -f 5134//5134 4824//4824 5135//5135 -f 5135//5135 4824//4824 4826//4826 -f 5135//5135 4826//4826 5136//5136 -f 5136//5136 4826//4826 4796//4796 -f 5136//5136 4796//4796 5137//5137 -f 5137//5137 4796//4796 4795//4795 -f 5138//5138 4844//4844 5139//5139 -f 5139//5139 4844//4844 4846//4846 -f 5139//5139 4846//4846 5140//5140 -f 5140//5140 4846//4846 4848//4848 -f 5141//5141 4960//4960 5142//5142 -f 5142//5142 4960//4960 4959//4959 -f 5142//5142 4959//4959 5143//5143 -f 5143//5143 4959//4959 5019//5019 -f 5143//5143 5019//5019 5144//5144 -f 5144//5144 5019//5019 5004//5004 -f 4849//4849 4850//4850 4847//4847 -f 4847//4847 4850//4850 4852//4852 -f 4847//4847 4852//4852 4967//4967 -f 4967//4967 4852//4852 5145//5145 -f 4967//4967 5145//5145 4965//4965 -f 4965//4965 5145//5145 5146//5146 -f 5146//5146 5147//5147 4965//4965 -f 4965//4965 5147//5147 5148//5148 -f 4965//4965 5148//5148 5149//5149 -f 5150//5150 5151//5151 4973//4973 -f 4975//4975 4970//4970 4973//4973 -f 4973//4973 4970//4970 4965//4965 -f 4973//4973 4965//4965 5150//5150 -f 5150//5150 4965//4965 5149//5149 -f 5152//5152 4971//4971 5153//5153 -f 5153//5153 4971//4971 4973//4973 -f 5153//5153 4973//4973 5154//5154 -f 5154//5154 4973//4973 5151//5151 -f 5152//5152 5155//5155 4971//4971 -f 4971//4971 5155//5155 5156//5156 -f 4971//4971 5156//5156 5145//5145 -f 5145//5145 5156//5156 5157//5157 -f 5145//5145 5157//5157 5146//5146 -f 4971//4971 4788//4788 4832//4832 -f 4832//4832 4788//4788 4790//4790 -f 4832//4832 4790//4790 4834//4834 -f 4834//4834 4790//4790 5114//5114 -f 4834//4834 5114//5114 4793//4793 -f 4793//4793 5114//5114 4805//4805 -f 4793//4793 4805//4805 4977//4977 -f 4977//4977 4805//4805 4810//4810 -f 4841//4841 5037//5037 4839//4839 -f 4839//4839 5037//5037 5039//5039 -f 4839//4839 5039//5039 4852//4852 -f 4852//4852 5039//5039 5158//5158 -f 5039//5039 5159//5159 5160//5160 -f 5161//5161 5162//5162 5158//5158 -f 5160//5160 5163//5163 5039//5039 -f 5039//5039 5163//5163 5164//5164 -f 5039//5039 5164//5164 5158//5158 -f 5158//5158 5164//5164 5165//5165 -f 5158//5158 5165//5165 5161//5161 -f 5162//5162 5066//5066 5158//5158 -f 5158//5158 5066//5066 5068//5068 -f 5158//5158 5068//5068 4852//4852 -f 4852//4852 5068//5068 5166//5166 -f 4852//4852 5166//5166 5145//5145 -f 5145//5145 5166//5166 5167//5167 -f 5145//5145 5167//5167 4971//4971 -f 4971//4971 5167//5167 5168//5168 -f 4971//4971 5168//5168 4788//4788 -f 5162//5162 5169//5169 5066//5066 -f 5066//5066 5169//5169 5170//5170 -f 5066//5066 5170//5170 5171//5171 -f 5159//5159 5039//5039 5172//5172 -f 5172//5172 5039//5039 5041//5041 -f 5172//5172 5041//5041 5173//5173 -f 5174//5174 5175//5175 4936//4936 -f 4936//4936 5175//5175 5064//5064 -f 4936//4936 5064//5064 4933//4933 -f 4933//4933 5064//5064 5066//5066 -f 4933//4933 5066//5066 5041//5041 -f 5041//5041 5066//5066 5171//5171 -f 5041//5041 5171//5171 5173//5173 -f 5118//5118 5091//5091 5119//5119 -f 5119//5119 5091//5091 5082//5082 -f 5119//5119 5082//5082 5047//5047 -f 5047//5047 5082//5082 5072//5072 -f 5047//5047 5072//5072 5045//5045 -f 5045//5045 5072//5072 5070//5070 -f 5045//5045 5070//5070 5058//5058 -f 5058//5058 5070//5070 5111//5111 -f 5058//5058 5111//5111 5106//5106 -f 5174//5174 5048//5048 5175//5175 -f 5175//5175 5048//5048 5050//5050 -f 5175//5175 5050//5050 5064//5064 -f 5064//5064 5050//5050 5176//5176 -f 5064//5064 5176//5176 5062//5062 -f 5062//5062 5176//5176 5177//5177 -f 5062//5062 5177//5177 5046//5046 -f 5046//5046 5177//5177 5178//5178 -f 5046//5046 5178//5178 5044//5044 -f 5179//5179 5180//5180 5174//5174 -f 5181//5181 5179//5179 4930//4930 -f 4930//4930 5179//5179 5174//5174 -f 4930//4930 5174//5174 4928//4928 -f 4928//4928 5174//5174 4936//4936 -f 4928//4928 4936//4936 5182//5182 -f 5182//5182 4936//4936 4937//4937 -f 5183//5183 5048//5048 5184//5184 -f 5184//5184 5048//5048 5174//5174 -f 5184//5184 5174//5174 5185//5185 -f 5185//5185 5174//5174 5180//5180 -f 5183//5183 5186//5186 5048//5048 -f 5048//5048 5186//5186 5187//5187 -f 5048//5048 5187//5187 5054//5054 -f 5054//5054 5187//5187 5188//5188 -f 5188//5188 5189//5189 5054//5054 -f 5054//5054 5189//5189 5190//5190 -f 5054//5054 5190//5190 4930//4930 -f 4930//4930 5190//5190 5191//5191 -f 4930//4930 5191//5191 5181//5181 -f 5192//5192 4951//4951 5193//5193 -f 5193//5193 4951//4951 5194//5194 -f 5193//5193 5194//5194 5195//5195 -f 5195//5195 5194//5194 5196//5196 -f 5197//5197 4922//4922 5198//5198 -f 5198//5198 4922//4922 4951//4951 -f 5198//5198 4951//4951 5199//5199 -f 5199//5199 4951//4951 5192//5192 -f 4919//4919 5200//5200 5201//5201 -f 5197//5197 5202//5202 4922//4922 -f 4922//4922 5202//5202 5203//5203 -f 4922//4922 5203//5203 4919//4919 -f 4919//4919 5203//5203 5204//5204 -f 4919//4919 5204//5204 5200//5200 -f 4997//4997 5205//5205 4995//4995 -f 4995//4995 5205//5205 4990//4990 -f 4995//4995 4990//4990 5002//5002 -f 5002//5002 4990//4990 4987//4987 -f 5002//5002 4987//4987 4885//4885 -f 4885//4885 4987//4987 5121//5121 -f 4885//4885 5121//5121 4880//4880 -f 4880//4880 5121//5121 5123//5123 -f 4880//4880 5123//5123 4878//4878 -f 4929//4929 4923//4923 4930//4930 -f 4930//4930 4923//4923 4900//4900 -f 4930//4930 4900//4900 5054//5054 -f 5054//5054 4900//4900 4916//4916 -f 5054//5054 4916//4916 5051//5051 -f 5051//5051 4916//4916 4944//4944 -f 5051//5051 4944//4944 5056//5056 -f 4947//4947 4948//4948 4945//4945 -f 4945//4945 4948//4948 4919//4919 -f 4945//4945 4919//4919 5194//5194 -f 5194//5194 4919//4919 5201//5201 -f 5194//5194 5201//5201 5196//5196 -f 5206//5206 5207//5207 4878//4878 -f 4787//4787 4786//4786 4944//4944 -f 4944//4944 4786//4786 5208//5208 -f 4944//4944 5208//5208 5209//5209 -f 5126//5126 5057//5057 5123//5123 -f 5123//5123 5057//5057 5056//5056 -f 5123//5123 5056//5056 4878//4878 -f 4878//4878 5056//5056 4944//4944 -f 4878//4878 4944//4944 5206//5206 -f 5206//5206 4944//4944 5209//5209 -f 5207//5207 5210//5210 4878//4878 -f 4878//4878 5210//5210 5211//5211 -f 4878//4878 5211//5211 4876//4876 -f 4876//4876 5211//5211 5212//5212 -f 5212//5212 5213//5213 4876//4876 -f 4876//4876 5213//5213 5214//5214 -f 4876//4876 5214//5214 4787//4787 -f 4787//4787 5214//5214 5215//5215 -f 4787//4787 5215//5215 4785//4785 -f 5216//5216 5217//5217 5218//5218 -f 5218//5218 5217//5217 4899//4899 -f 5218//5218 4899//4899 5219//5219 -f 5219//5219 4899//4899 4898//4898 -f 5219//5219 4898//4898 5220//5220 -f 5216//5216 5221//5221 5217//5217 -f 5217//5217 5221//5221 5222//5222 -f 5217//5217 5222//5222 5223//5223 -f 5223//5223 5222//5222 5224//5224 -f 5223//5223 5224//5224 5225//5225 -f 5226//5226 5227//5227 5228//5228 -f 5228//5228 5227//5227 5229//5229 -f 5228//5228 5229//5229 5230//5230 -f 4920//4920 4919//4919 5231//5231 -f 5231//5231 4919//4919 4948//4948 -f 5231//5231 4948//4948 4927//4927 -f 4927//4927 4948//4948 5228//5228 -f 4927//4927 5228//5228 4898//4898 -f 4898//4898 5228//5228 5230//5230 -f 4898//4898 5230//5230 5220//5220 -f 4949//4949 4797//4797 4948//4948 -f 4948//4948 4797//4797 4799//4799 -f 4948//4948 4799//4799 5228//5228 -f 5228//5228 4799//4799 5223//5223 -f 5228//5228 5223//5223 5226//5226 -f 5226//5226 5223//5223 5225//5225 -f 5232//5232 5233//5233 5234//5234 -f 5235//5235 5236//5236 5237//5237 -f 5232//5232 5234//5234 5238//5238 -f 5234//5234 5239//5239 5238//5238 -f 5238//5238 5239//5239 5240//5240 -f 5238//5238 5240//5240 5241//5241 -f 5235//5235 5237//5237 5242//5242 -f 5237//5237 5243//5243 5242//5242 -f 5242//5242 5243//5243 5244//5244 -f 5242//5242 5244//5244 5232//5232 -f 5232//5232 5244//5244 5245//5245 -f 5232//5232 5245//5245 5233//5233 -f 5240//5240 5246//5246 5241//5241 -f 5241//5241 5246//5246 5247//5247 -f 5241//5241 5247//5247 5235//5235 -f 5235//5235 5247//5247 5248//5248 -f 5235//5235 5248//5248 5236//5236 -f 5249//5249 5250//5250 5251//5251 -f 5251//5251 5250//5250 5252//5252 -f 5253//5253 5254//5254 5255//5255 -f 5255//5255 5254//5254 5256//5256 -f 5256//5256 5257//5257 5255//5255 -f 5255//5255 5257//5257 5258//5258 -f 5255//5255 5258//5258 5259//5259 -f 5258//5258 5260//5260 5259//5259 -f 5259//5259 5260//5260 5261//5261 -f 5259//5259 5261//5261 5249//5249 -f 5249//5249 5261//5261 5262//5262 -f 5249//5249 5262//5262 5250//5250 -f 5252//5252 5263//5263 5251//5251 -f 5251//5251 5263//5263 5264//5264 -f 5251//5251 5264//5264 5253//5253 -f 5253//5253 5264//5264 5265//5265 -f 5253//5253 5265//5265 5254//5254 -f 5266//5266 5267//5267 5268//5268 -f 5268//5268 5267//5267 5269//5269 -f 5270//5270 5271//5271 5266//5266 -f 5266//5266 5271//5271 5272//5272 -f 5266//5266 5272//5272 5267//5267 -f 5269//5269 5273//5273 5268//5268 -f 5268//5268 5273//5273 5274//5274 -f 5268//5268 5274//5274 5275//5275 -f 5276//5276 5277//5277 5278//5278 -f 5278//5278 5277//5277 5275//5275 -f 5278//5278 5275//5275 5279//5279 -f 5279//5279 5275//5275 5274//5274 -f 5276//5276 5280//5280 5277//5277 -f 5277//5277 5280//5280 5281//5281 -f 5277//5277 5281//5281 5270//5270 -f 5270//5270 5281//5281 5282//5282 -f 5270//5270 5282//5282 5271//5271 -f 3674//3674 3673//3673 5283//5283 -f 5284//5284 5285//5285 5286//5286 -f 5287//5287 5288//5288 5289//5289 -f 5290//5290 5291//5291 5292//5292 -f 5292//5292 5291//5291 5293//5293 -f 5293//5293 5294//5294 5292//5292 -f 5292//5292 5294//5294 5295//5295 -f 5292//5292 5295//5295 5296//5296 -f 5296//5296 5295//5295 5297//5297 -f 5296//5296 5297//5297 5298//5298 -f 5299//5299 5300//5300 5301//5301 -f 5302//5302 5303//5303 5304//5304 -f 5305//5305 5306//5306 5297//5297 -f 5297//5297 5306//5306 5302//5302 -f 5304//5304 5307//5307 5302//5302 -f 5302//5302 5307//5307 5299//5299 -f 5302//5302 5299//5299 5297//5297 -f 5297//5297 5299//5299 5301//5301 -f 5297//5297 5301//5301 5298//5298 -f 5308//5308 5309//5309 5310//5310 -f 5311//5311 5312//5312 5313//5313 -f 5314//5314 5308//5308 5305//5305 -f 5289//5289 5306//5306 5287//5287 -f 5287//5287 5306//5306 5305//5305 -f 5287//5287 5305//5305 5315//5315 -f 5315//5315 5305//5305 5308//5308 -f 5315//5315 5308//5308 5316//5316 -f 5316//5316 5308//5308 5310//5310 -f 5312//5312 5311//5311 5317//5317 -f 5318//5318 5319//5319 5320//5320 -f 5321//5321 5322//5322 5323//5323 -f 5320//5320 5324//5324 5318//5318 -f 5318//5318 5324//5324 5323//5323 -f 5318//5318 5323//5323 5325//5325 -f 5325//5325 5323//5323 5326//5326 -f 5327//5327 5321//5321 5328//5328 -f 5328//5328 5321//5321 5323//5323 -f 5328//5328 5323//5323 5329//5329 -f 5329//5329 5323//5323 5324//5324 -f 5330//5330 5331//5331 5332//5332 -f 5332//5332 5331//5331 5333//5333 -f 5332//5332 5333//5333 5334//5334 -f 5334//5334 5333//5333 5335//5335 -f 5336//5336 5337//5337 5338//5338 -f 5338//5338 5337//5337 5339//5339 -f 5340//5340 5341//5341 5342//5342 -f 5342//5342 5341//5341 5343//5343 -f 5342//5342 5343//5343 5344//5344 -f 5344//5344 5343//5343 5345//5345 -f 5344//5344 5345//5345 5346//5346 -f 5346//5346 5345//5345 5347//5347 -f 5346//5346 5347//5347 5348//5348 -f 5348//5348 5347//5347 5349//5349 -f 5350//5350 5351//5351 5352//5352 -f 5352//5352 5351//5351 5353//5353 -f 5352//5352 5353//5353 5354//5354 -f 5286//5286 5355//5355 5284//5284 -f 5284//5284 5355//5355 5356//5356 -f 5284//5284 5356//5356 5357//5357 -f 5358//5358 5359//5359 5360//5360 -f 5360//5360 5359//5359 5361//5361 -f 5360//5360 5361//5361 5362//5362 -f 5363//5363 5364//5364 5356//5356 -f 5356//5356 5364//5364 5365//5365 -f 5365//5365 5366//5366 5351//5351 -f 5351//5351 5366//5366 5367//5367 -f 5368//5368 5360//5360 5369//5369 -f 5369//5369 5360//5360 5362//5362 -f 5369//5369 5362//5362 5370//5370 -f 5370//5370 5362//5362 5371//5371 -f 5370//5370 5371//5371 5355//5355 -f 5355//5355 5371//5371 5372//5372 -f 5355//5355 5372//5372 5356//5356 -f 5356//5356 5372//5372 5373//5373 -f 5356//5356 5373//5373 5363//5363 -f 5360//5360 5374//5374 5358//5358 -f 5358//5358 5374//5374 5375//5375 -f 5358//5358 5375//5375 5367//5367 -f 5367//5367 5375//5375 5376//5376 -f 5367//5367 5376//5376 5351//5351 -f 5351//5351 5376//5376 5377//5377 -f 5351//5351 5377//5377 5353//5353 -f 5378//5378 5379//5379 5356//5356 -f 5380//5380 5381//5381 5382//5382 -f 5382//5382 5381//5381 5383//5383 -f 5383//5383 5357//5357 5382//5382 -f 5382//5382 5357//5357 5356//5356 -f 5382//5382 5356//5356 5384//5384 -f 5384//5384 5356//5356 5379//5379 -f 5384//5384 5379//5379 5385//5385 -f 5385//5385 5379//5379 5386//5386 -f 5387//5387 5388//5388 5389//5389 -f 5389//5389 5388//5388 5390//5390 -f 5391//5391 5392//5392 5390//5390 -f 5393//5393 5394//5394 5391//5391 -f 5391//5391 5394//5394 5395//5395 -f 5396//5396 5397//5397 5398//5398 -f 5398//5398 5397//5397 5399//5399 -f 5398//5398 5399//5399 5378//5378 -f 5400//5400 5401//5401 5392//5392 -f 5392//5392 5401//5401 5402//5402 -f 5392//5392 5402//5402 5390//5390 -f 5403//5403 5404//5404 5393//5393 -f 5405//5405 5394//5394 5406//5406 -f 5406//5406 5394//5394 5393//5393 -f 5406//5406 5393//5393 5407//5407 -f 5407//5407 5393//5393 5404//5404 -f 5407//5407 5404//5404 5408//5408 -f 5408//5408 5404//5404 5409//5409 -f 5410//5410 5411//5411 5412//5412 -f 3699//3699 5413//5413 3698//3698 -f 3698//3698 5413//5413 5414//5414 -f 3698//3698 5414//5414 3684//3684 -f 5414//5414 5415//5415 3684//3684 -f 3684//3684 5415//5415 5416//5416 -f 3684//3684 5416//5416 3682//3682 -f 3682//3682 5416//5416 5417//5417 -f 3682//3682 5417//5417 3680//3680 -f 3680//3680 5417//5417 5418//5418 -f 3680//3680 5418//5418 5419//5419 -f 5419//5419 5418//5418 5420//5420 -f 5421//5421 5422//5422 5423//5423 -f 5423//5423 5422//5422 5424//5424 -f 5423//5423 5424//5424 5425//5425 -f 5425//5425 5424//5424 5426//5426 -f 5425//5425 5426//5426 3699//3699 -f 3699//3699 5426//5426 5427//5427 -f 3699//3699 5427//5427 5413//5413 -f 5428//5428 5429//5429 5430//5430 -f 5430//5430 5429//5429 5431//5431 -f 5430//5430 5431//5431 5432//5432 -f 5433//5433 5434//5434 5435//5435 -f 5435//5435 5434//5434 5436//5436 -f 5435//5435 5436//5436 3678//3678 -f 3678//3678 5436//5436 5437//5437 -f 5438//5438 3673//3673 5437//5437 -f 5437//5437 3673//3673 3702//3702 -f 5437//5437 3702//3702 3678//3678 -f 5438//5438 5439//5439 3673//3673 -f 3673//3673 5439//5439 5440//5440 -f 3673//3673 5440//5440 5283//5283 -f 5283//5283 5440//5440 5441//5441 -f 5283//5283 5441//5441 5442//5442 -f 5443//5443 3650//3650 5283//5283 -f 5283//5283 3650//3650 3676//3676 -f 5283//5283 3676//3676 3674//3674 -f 5294//5294 5444//5444 5295//5295 -f 5295//5295 5444//5444 5445//5445 -f 5295//5295 5445//5445 5443//5443 -f 5443//5443 5445//5445 5446//5446 -f 5443//5443 5446//5446 3650//3650 -f 5447//5447 5448//5448 5449//5449 -f 5449//5449 5448//5448 5450//5450 -f 5449//5449 5450//5450 5451//5451 -f 5451//5451 5450//5450 5452//5452 -f 5451//5451 5452//5452 5453//5453 -f 5453//5453 5452//5452 5454//5454 -f 5453//5453 5454//5454 5455//5455 -f 5456//5456 5457//5457 5458//5458 -f 5458//5458 5457//5457 5459//5459 -f 5458//5458 5459//5459 5460//5460 -f 5460//5460 5459//5459 5461//5461 -f 5460//5460 5461//5461 5462//5462 -f 5463//5463 5464//5464 5465//5465 -f 5465//5465 5464//5464 5305//5305 -f 5465//5465 5305//5305 5466//5466 -f 5466//5466 5305//5305 5297//5297 -f 5466//5466 5297//5297 5467//5467 -f 5468//5468 5469//5469 5456//5456 -f 5456//5456 5469//5469 5470//5470 -f 5456//5456 5470//5470 5471//5471 -f 5472//5472 5473//5473 5474//5474 -f 5474//5474 5473//5473 5475//5475 -f 5474//5474 5475//5475 5476//5476 -f 5476//5476 5475//5475 5477//5477 -f 5476//5476 5477//5477 5471//5471 -f 5471//5471 5477//5477 5448//5448 -f 5471//5471 5448//5448 5456//5456 -f 5456//5456 5448//5448 5447//5447 -f 5456//5456 5447//5447 5457//5457 -f 5478//5478 5479//5479 5480//5480 -f 5480//5480 5479//5479 5481//5481 -f 5480//5480 5481//5481 5463//5463 -f 5482//5482 5483//5483 5484//5484 -f 5484//5484 5483//5483 5333//5333 -f 5484//5484 5333//5333 5327//5327 -f 5327//5327 5333//5333 5331//5331 -f 5327//5327 5331//5331 5321//5321 -f 5311//5311 5485//5485 5486//5486 -f 5487//5487 5488//5488 5319//5319 -f 5319//5319 5488//5488 5317//5317 -f 5319//5319 5317//5317 5320//5320 -f 5320//5320 5317//5317 5311//5311 -f 5320//5320 5311//5311 5489//5489 -f 5489//5489 5311//5311 5486//5486 -f 5482//5482 5490//5490 5483//5483 -f 5483//5483 5490//5490 5491//5491 -f 5483//5483 5491//5491 5485//5485 -f 5485//5485 5491//5491 5492//5492 -f 5485//5485 5492//5492 5486//5486 -f 5493//5493 5494//5494 5495//5495 -f 5495//5495 5494//5494 5496//5496 -f 5495//5495 5496//5496 5497//5497 -f 5497//5497 5496//5496 5498//5498 -f 5497//5497 5498//5498 5499//5499 -f 5499//5499 5498//5498 5500//5500 -f 5499//5499 5500//5500 5501//5501 -f 5502//5502 5503//5503 5504//5504 -f 5504//5504 5503//5503 5505//5505 -f 5504//5504 5505//5505 5506//5506 -f 5506//5506 5505//5505 5507//5507 -f 5506//5506 5507//5507 5508//5508 -f 5508//5508 5507//5507 5509//5509 -f 5508//5508 5509//5509 5510//5510 -f 5511//5511 5512//5512 5513//5513 -f 5512//5512 5514//5514 5513//5513 -f 5513//5513 5514//5514 5515//5515 -f 5513//5513 5515//5515 5508//5508 -f 5508//5508 5515//5515 5516//5516 -f 5517//5517 5518//5518 5519//5519 -f 5519//5519 5518//5518 5520//5520 -f 5519//5519 5520//5520 5521//5521 -f 5521//5521 5520//5520 5522//5522 -f 5521//5521 5522//5522 5523//5523 -f 5524//5524 5525//5525 5526//5526 -f 5526//5526 5525//5525 5527//5527 -f 5526//5526 5527//5527 5528//5528 -f 5529//5529 5473//5473 5530//5530 -f 5530//5530 5473//5473 5472//5472 -f 5530//5530 5472//5472 5467//5467 -f 5524//5524 5531//5531 5525//5525 -f 5525//5525 5531//5531 5532//5532 -f 5525//5525 5532//5532 5530//5530 -f 5530//5530 5532//5532 5533//5533 -f 5530//5530 5533//5533 5529//5529 -f 5529//5529 5534//5534 5473//5473 -f 5473//5473 5534//5534 5535//5535 -f 5473//5473 5535//5535 5475//5475 -f 5475//5475 5535//5535 5536//5536 -f 5528//5528 5527//5527 5537//5537 -f 5537//5537 5527//5527 5538//5538 -f 5537//5537 5538//5538 5539//5539 -f 5540//5540 5541//5541 5464//5464 -f 5542//5542 5543//5543 5485//5485 -f 5485//5485 5543//5543 5544//5544 -f 5485//5485 5544//5544 5545//5545 -f 5463//5463 5481//5481 5464//5464 -f 5464//5464 5481//5481 5546//5546 -f 5464//5464 5546//5546 5540//5540 -f 5544//5544 5547//5547 5545//5545 -f 5545//5545 5547//5547 5548//5548 -f 5545//5545 5548//5548 5549//5549 -f 5548//5548 5550//5550 5549//5549 -f 5549//5549 5550//5550 5551//5551 -f 5549//5549 5551//5551 5479//5479 -f 5479//5479 5551//5551 5552//5552 -f 5479//5479 5552//5552 5481//5481 -f 5481//5481 5552//5552 5553//5553 -f 5481//5481 5553//5553 5546//5546 -f 5554//5554 5555//5555 5504//5504 -f 5504//5504 5555//5555 5556//5556 -f 5504//5504 5556//5556 5557//5557 -f 5557//5557 5556//5556 5558//5558 -f 5557//5557 5558//5558 5559//5559 -f 5560//5560 5561//5561 5562//5562 -f 5561//5561 5563//5563 5562//5562 -f 5562//5562 5563//5563 5564//5564 -f 5562//5562 5564//5564 5565//5565 -f 5565//5565 5564//5564 5566//5566 -f 5567//5567 5568//5568 5356//5356 -f 5569//5569 5570//5570 5389//5389 -f 5570//5570 5571//5571 5389//5389 -f 5389//5389 5571//5571 5462//5462 -f 5389//5389 5462//5462 5387//5387 -f 5387//5387 5462//5462 5461//5461 -f 5567//5567 5356//5356 5572//5572 -f 5572//5572 5356//5356 5573//5573 -f 5572//5572 5573//5573 5574//5574 -f 5402//5402 5398//5398 5390//5390 -f 5390//5390 5398//5398 5378//5378 -f 5390//5390 5378//5378 5389//5389 -f 5389//5389 5378//5378 5356//5356 -f 5389//5389 5356//5356 5569//5569 -f 5569//5569 5356//5356 5568//5568 -f 5571//5571 5575//5575 5462//5462 -f 5462//5462 5575//5575 5576//5576 -f 5462//5462 5576//5576 5460//5460 -f 5460//5460 5576//5576 5577//5577 -f 5574//5574 5573//5573 5578//5578 -f 5578//5578 5573//5573 5579//5579 -f 5578//5578 5579//5579 5580//5580 -f 5581//5581 5582//5582 5393//5393 -f 5393//5393 5582//5582 5583//5583 -f 5584//5584 5581//5581 5454//5454 -f 5454//5454 5581//5581 5393//5393 -f 5454//5454 5393//5393 5455//5455 -f 5455//5455 5393//5393 5391//5391 -f 5455//5455 5391//5391 5585//5585 -f 5585//5585 5391//5391 5390//5390 -f 5586//5586 5587//5587 5412//5412 -f 5412//5412 5587//5587 5588//5588 -f 5412//5412 5588//5588 5589//5589 -f 5583//5583 5586//5586 5393//5393 -f 5393//5393 5586//5586 5412//5412 -f 5393//5393 5412//5412 5403//5403 -f 5403//5403 5412//5412 5411//5411 -f 5403//5403 5411//5411 5590//5590 -f 5584//5584 5454//5454 5591//5591 -f 5591//5591 5454//5454 5452//5452 -f 5591//5591 5452//5452 5592//5592 -f 5588//5588 5593//5593 5589//5589 -f 5589//5589 5593//5593 5594//5594 -f 5589//5589 5594//5594 5595//5595 -f 5595//5595 5594//5594 5596//5596 -f 5420//5420 5421//5421 5419//5419 -f 5419//5419 5421//5421 5423//5423 -f 5419//5419 5423//5423 5562//5562 -f 5562//5562 5423//5423 5597//5597 -f 5562//5562 5597//5597 5560//5560 -f 5560//5560 5597//5597 5598//5598 -f 3699//3699 3692//3692 5425//5425 -f 5425//5425 3692//3692 5599//5599 -f 5425//5425 5599//5599 5423//5423 -f 5423//5423 5599//5599 5600//5600 -f 5423//5423 5600//5600 5597//5597 -f 5597//5597 5600//5600 5557//5557 -f 5597//5597 5557//5557 5598//5598 -f 5598//5598 5557//5557 5559//5559 -f 3692//3692 5410//5410 5599//5599 -f 5599//5599 5410//5410 5412//5412 -f 5599//5599 5412//5412 5600//5600 -f 5600//5600 5412//5412 5589//5589 -f 5600//5600 5589//5589 5557//5557 -f 5557//5557 5589//5589 5595//5595 -f 5557//5557 5595//5595 5504//5504 -f 5504//5504 5595//5595 5499//5499 -f 5504//5504 5499//5499 5502//5502 -f 5502//5502 5499//5499 5501//5501 -f 5566//5566 5601//5601 5565//5565 -f 5565//5565 5601//5601 5602//5602 -f 5565//5565 5602//5602 5603//5603 -f 5603//5603 5602//5602 5604//5604 -f 5603//5603 5604//5604 5519//5519 -f 5519//5519 5604//5604 5605//5605 -f 5519//5519 5605//5605 5517//5517 -f 5517//5517 5605//5605 5606//5606 -f 5601//5601 5554//5554 5602//5602 -f 5602//5602 5554//5554 5504//5504 -f 5602//5602 5504//5504 5604//5604 -f 5604//5604 5504//5504 5506//5506 -f 5604//5604 5506//5506 5605//5605 -f 5605//5605 5506//5506 5508//5508 -f 5605//5605 5508//5508 5606//5606 -f 5606//5606 5508//5508 5516//5516 -f 5577//5577 5580//5580 5460//5460 -f 5460//5460 5580//5580 5579//5579 -f 5460//5460 5579//5579 5458//5458 -f 5458//5458 5579//5579 5607//5607 -f 5458//5458 5607//5607 5456//5456 -f 5456//5456 5607//5607 5608//5608 -f 5456//5456 5608//5608 5468//5468 -f 5468//5468 5608//5608 5609//5609 -f 5365//5365 5351//5351 5356//5356 -f 5356//5356 5351//5351 5350//5350 -f 5356//5356 5350//5350 5573//5573 -f 5573//5573 5350//5350 5610//5610 -f 5573//5573 5610//5610 5579//5579 -f 5579//5579 5610//5610 5347//5347 -f 5579//5579 5347//5347 5607//5607 -f 5607//5607 5347//5347 5345//5345 -f 5607//5607 5345//5345 5608//5608 -f 5608//5608 5345//5345 5343//5343 -f 5608//5608 5343//5343 5609//5609 -f 5609//5609 5343//5343 5341//5341 -f 5609//5609 5341//5341 5339//5339 -f 5339//5339 5341//5341 5340//5340 -f 5339//5339 5340//5340 5338//5338 -f 5596//5596 5592//5592 5595//5595 -f 5595//5595 5592//5592 5452//5452 -f 5595//5595 5452//5452 5499//5499 -f 5499//5499 5452//5452 5450//5450 -f 5499//5499 5450//5450 5497//5497 -f 5497//5497 5450//5450 5448//5448 -f 5497//5497 5448//5448 5495//5495 -f 5495//5495 5448//5448 5477//5477 -f 5495//5495 5477//5477 5538//5538 -f 5538//5538 5477//5477 5475//5475 -f 5538//5538 5475//5475 5539//5539 -f 5539//5539 5475//5475 5536//5536 -f 5335//5335 5333//5333 5611//5611 -f 5611//5611 5333//5333 5483//5483 -f 5611//5611 5483//5483 5612//5612 -f 5612//5612 5483//5483 5485//5485 -f 5612//5612 5485//5485 5613//5613 -f 5613//5613 5485//5485 5545//5545 -f 5613//5613 5545//5545 5339//5339 -f 5339//5339 5545//5545 5549//5549 -f 5339//5339 5549//5549 5609//5609 -f 5609//5609 5549//5549 5479//5479 -f 5609//5609 5479//5479 5468//5468 -f 5468//5468 5479//5479 5478//5478 -f 5468//5468 5478//5478 5469//5469 -f 5523//5523 5614//5614 5521//5521 -f 5521//5521 5614//5614 5615//5615 -f 5521//5521 5615//5615 5435//5435 -f 5435//5435 5615//5615 5430//5430 -f 5435//5435 5430//5430 5433//5433 -f 5433//5433 5430//5430 5432//5432 -f 5614//5614 5511//5511 5615//5615 -f 5615//5615 5511//5511 5513//5513 -f 5615//5615 5513//5513 5430//5430 -f 5430//5430 5513//5513 5616//5616 -f 5430//5430 5616//5616 5428//5428 -f 5428//5428 5616//5616 5617//5617 -f 5510//5510 5493//5493 5508//5508 -f 5508//5508 5493//5493 5495//5495 -f 5508//5508 5495//5495 5513//5513 -f 5513//5513 5495//5495 5538//5538 -f 5513//5513 5538//5538 5616//5616 -f 5616//5616 5538//5538 5527//5527 -f 5616//5616 5527//5527 5617//5617 -f 5617//5617 5527//5527 5525//5525 -f 5467//5467 5297//5297 5530//5530 -f 5530//5530 5297//5297 5295//5295 -f 5530//5530 5295//5295 5525//5525 -f 5525//5525 5295//5295 5443//5443 -f 5525//5525 5443//5443 5617//5617 -f 5617//5617 5443//5443 5283//5283 -f 5617//5617 5283//5283 5428//5428 -f 5428//5428 5283//5283 5442//5442 -f 5428//5428 5442//5442 5429//5429 -f 5541//5541 5542//5542 5464//5464 -f 5464//5464 5542//5542 5485//5485 -f 5464//5464 5485//5485 5305//5305 -f 5305//5305 5485//5485 5311//5311 -f 5305//5305 5311//5311 5314//5314 -f 5314//5314 5311//5311 5313//5313 -f 5314//5314 5313//5313 5618//5618 -f 5618//5618 5313//5313 5619//5619 -f 5620//5620 5621//5621 5622//5622 -f 5622//5622 5621//5621 5623//5623 -f 5622//5622 5623//5623 5624//5624 -f 5624//5624 5623//5623 5625//5625 -f 5624//5624 5625//5625 5626//5626 -f 5627//5627 5628//5628 5629//5629 -f 5629//5629 5628//5628 5630//5630 -f 5629//5629 5630//5630 5631//5631 -f 5631//5631 5630//5630 5632//5632 -f 5631//5631 5632//5632 5633//5633 -f 5634//5634 5635//5635 5636//5636 -f 5636//5636 5635//5635 5637//5637 -f 5636//5636 5637//5637 5638//5638 -f 5638//5638 5637//5637 5639//5639 -f 5638//5638 5639//5639 5640//5640 -f 5641//5641 5642//5642 5238//5238 -f 5238//5238 5642//5642 5643//5643 -f 5238//5238 5643//5643 5232//5232 -f 5232//5232 5643//5643 5644//5644 -f 5232//5232 5644//5644 5645//5645 -f 5645//5645 5644//5644 5646//5646 -f 5647//5647 5648//5648 5259//5259 -f 5259//5259 5648//5648 5649//5649 -f 5259//5259 5649//5649 5255//5255 -f 5255//5255 5649//5649 5650//5650 -f 5255//5255 5650//5650 5651//5651 -f 5651//5651 5650//5650 5652//5652 -f 5653//5653 5654//5654 5275//5275 -f 5275//5275 5654//5654 5655//5655 -f 5275//5275 5655//5655 5268//5268 -f 5268//5268 5655//5655 5656//5656 -f 5268//5268 5656//5656 5657//5657 -f 5657//5657 5656//5656 5658//5658 -f 5659//5659 5660//5660 5661//5661 -f 5661//5661 5660//5660 5662//5662 -f 5663//5663 5664//5664 5665//5665 -f 5666//5666 5667//5667 5668//5668 -f 5668//5668 5667//5667 5663//5663 -f 5668//5668 5663//5663 5669//5669 -f 5669//5669 5663//5663 5665//5665 -f 5666//5666 5670//5670 5667//5667 -f 5667//5667 5670//5670 5671//5671 -f 5667//5667 5671//5671 5659//5659 -f 5659//5659 5671//5671 5672//5672 -f 5659//5659 5672//5672 5660//5660 -f 5662//5662 5673//5673 5661//5661 -f 5661//5661 5673//5673 5674//5674 -f 5661//5661 5674//5674 5664//5664 -f 5664//5664 5674//5674 5675//5675 -f 5664//5664 5675//5675 5665//5665 -f 5676//5676 5677//5677 5678//5678 -f 5678//5678 5677//5677 5679//5679 -f 5680//5680 5681//5681 5682//5682 -f 5682//5682 5681//5681 5683//5683 -f 5682//5682 5683//5683 5684//5684 -f 5684//5684 5683//5683 5685//5685 -f 5684//5684 5685//5685 5686//5686 -f 5678//5678 5687//5687 5676//5676 -f 5676//5676 5687//5687 5688//5688 -f 5676//5676 5688//5688 5685//5685 -f 5685//5685 5688//5688 5689//5689 -f 5685//5685 5689//5689 5686//5686 -f 5680//5680 5690//5690 5681//5681 -f 5681//5681 5690//5690 5691//5691 -f 5681//5681 5691//5691 5677//5677 -f 5677//5677 5691//5691 5692//5692 -f 5677//5677 5692//5692 5679//5679 -f 5693//5693 5694//5694 5695//5695 -f 5695//5695 5694//5694 5696//5696 -f 5695//5695 5696//5696 5697//5697 -f 5697//5697 5696//5696 5698//5698 -f 5697//5697 5698//5698 5699//5699 -f 5700//5700 5701//5701 5664//5664 -f 5664//5664 5701//5701 5702//5702 -f 5664//5664 5702//5702 5661//5661 -f 5661//5661 5702//5702 5703//5703 -f 5661//5661 5703//5703 5704//5704 -f 5704//5704 5703//5703 5705//5705 -f 5706//5706 5707//5707 5708//5708 -f 5709//5709 5710//5710 5711//5711 -f 5706//5706 5708//5708 5711//5711 -f 5711//5711 5708//5708 5712//5712 -f 5711//5711 5712//5712 5709//5709 -f 5713//5713 5714//5714 5676//5676 -f 5676//5676 5714//5714 5715//5715 -f 5676//5676 5715//5715 5677//5677 -f 5677//5677 5715//5715 5716//5716 -f 5677//5677 5716//5716 5717//5717 -f 5717//5717 5716//5716 5718//5718 -f 5719//5719 5411//5411 5720//5720 -f 5720//5720 5411//5411 5410//5410 -f 5720//5720 5410//5410 3692//3692 -f 3680//3680 5419//5419 5721//5721 -f 5721//5721 5419//5419 5562//5562 -f 5562//5562 5565//5565 5721//5721 -f 5721//5721 5565//5565 5603//5603 -f 5721//5721 5603//5603 5722//5722 -f 5722//5722 5603//5603 5519//5519 -f 5519//5519 5521//5521 5722//5722 -f 5722//5722 5521//5521 5435//5435 -f 5722//5722 5435//5435 3678//3678 -f 5445//5445 5723//5723 5446//5446 -f 5446//5446 5723//5723 5724//5724 -f 5446//5446 5724//5724 3650//3650 -f 5445//5445 5444//5444 5723//5723 -f 5723//5723 5444//5444 5725//5725 -f 5723//5723 5725//5725 5726//5726 -f 5726//5726 5725//5725 4976//4976 -f 5726//5726 4976//4976 5727//5727 -f 5727//5727 4976//4976 4792//4792 -f 5293//5293 5728//5728 5294//5294 -f 5294//5294 5728//5728 5725//5725 -f 5294//5294 5725//5725 5444//5444 -f 5644//5644 5137//5137 5728//5728 -f 5728//5728 5137//5137 4795//4795 -f 5728//5728 4795//4795 4794//4794 -f 5293//5293 5291//5291 5728//5728 -f 5728//5728 5291//5291 5646//5646 -f 5728//5728 5646//5646 5644//5644 -f 5729//5729 4822//4822 4824//4824 -f 5300//5300 5299//5299 5642//5642 -f 5642//5642 5299//5299 5729//5729 -f 5642//5642 5729//5729 5643//5643 -f 5643//5643 5729//5729 4824//4824 -f 5643//5643 4824//4824 5134//5134 -f 5729//5729 5299//5299 5730//5730 -f 5730//5730 5299//5299 5307//5307 -f 5650//5650 4975//4975 5730//5730 -f 5730//5730 4975//4975 4974//4974 -f 5730//5730 4974//4974 4972//4972 -f 5307//5307 5304//5304 5730//5730 -f 5730//5730 5304//5304 5652//5652 -f 5730//5730 5652//5652 5650//5650 -f 5288//5288 5287//5287 5731//5731 -f 5731//5731 4967//4967 4966//4966 -f 5288//5288 5731//5731 5648//5648 -f 5648//5648 5731//5731 5649//5649 -f 5649//5649 5731//5731 4966//4966 -f 5649//5649 4966//4966 4968//4968 -f 5316//5316 5732//5732 5315//5315 -f 5315//5315 5732//5732 5731//5731 -f 5315//5315 5731//5731 5287//5287 -f 5656//5656 5140//5140 5732//5732 -f 5732//5732 5140//5140 4848//4848 -f 5732//5732 4848//4848 4847//4847 -f 5316//5316 5310//5310 5732//5732 -f 5732//5732 5310//5310 5658//5658 -f 5732//5732 5658//5658 5656//5656 -f 5733//5733 4838//4838 4844//4844 -f 5619//5619 5313//5313 5654//5654 -f 5654//5654 5313//5313 5733//5733 -f 5654//5654 5733//5733 5655//5655 -f 5655//5655 5733//5733 4844//4844 -f 5655//5655 4844//4844 5138//5138 -f 5317//5317 5734//5734 5312//5312 -f 5312//5312 5734//5734 5733//5733 -f 5312//5312 5733//5733 5313//5313 -f 5703//5703 5144//5144 5734//5734 -f 5734//5734 5144//5144 5004//5004 -f 5734//5734 5004//5004 5003//5003 -f 5317//5317 5488//5488 5734//5734 -f 5734//5734 5488//5488 5705//5705 -f 5734//5734 5705//5705 5703//5703 -f 5735//5735 4961//4961 4960//4960 -f 5326//5326 5323//5323 5701//5701 -f 5701//5701 5323//5323 5735//5735 -f 5701//5701 5735//5735 5702//5702 -f 5702//5702 5735//5735 4960//4960 -f 5702//5702 4960//4960 5141//5141 -f 5735//5735 5323//5323 5736//5736 -f 5736//5736 5323//5323 5322//5322 -f 5736//5736 5322//5322 4964//4964 -f 4964//4964 5322//5322 5321//5321 -f 5330//5330 5737//5737 5331//5331 -f 5331//5331 5737//5737 4964//4964 -f 5331//5331 4964//4964 5321//5321 -f 5737//5737 5330//5330 5738//5738 -f 5738//5738 5330//5330 5332//5332 -f 5738//5738 5332//5332 5334//5334 -f 4962//4962 4963//4963 5716//5716 -f 5716//5716 4963//4963 5738//5738 -f 5716//5716 5738//5738 5718//5718 -f 5718//5718 5738//5738 5334//5334 -f 5739//5739 4957//4957 4956//4956 -f 5336//5336 5338//5338 5714//5714 -f 5714//5714 5338//5338 5739//5739 -f 5714//5714 5739//5739 5715//5715 -f 5715//5715 5739//5739 4956//4956 -f 5338//5338 5340//5340 5739//5739 -f 5739//5739 5340//5340 5342//5342 -f 5739//5739 5342//5342 5740//5740 -f 5740//5740 5342//5342 5344//5344 -f 5740//5740 5344//5344 5346//5346 -f 5740//5740 5346//5346 5348//5348 -f 4950//4950 4952//4952 5741//5741 -f 5741//5741 4952//4952 5740//5740 -f 5741//5741 5740//5740 5742//5742 -f 5742//5742 5740//5740 5348//5348 -f 5743//5743 5744//5744 5745//5745 -f 5745//5745 5744//5744 5746//5746 -f 5745//5745 5746//5746 5747//5747 -f 5747//5747 5746//5746 5741//5741 -f 5747//5747 5741//5741 5748//5748 -f 5748//5748 5741//5741 5742//5742 -f 5749//5749 4947//4947 4946//4946 -f 5354//5354 5353//5353 5744//5744 -f 5744//5744 5353//5353 5749//5749 -f 5744//5744 5749//5749 5746//5746 -f 5746//5746 5749//5749 4946//4946 -f 5749//5749 5353//5353 5750//5750 -f 5750//5750 5353//5353 5377//5377 -f 5750//5750 5377//5377 4949//4949 -f 4949//4949 5377//5377 5376//5376 -f 4949//4949 5376//5376 5375//5375 -f 4949//4949 5375//5375 5751//5751 -f 5751//5751 5375//5375 5374//5374 -f 5751//5751 5374//5374 5752//5752 -f 5752//5752 5374//5374 5360//5360 -f 5752//5752 5360//5360 5368//5368 -f 4798//4798 4797//4797 5753//5753 -f 5753//5753 4797//4797 5752//5752 -f 5753//5753 5752//5752 5754//5754 -f 5754//5754 5752//5752 5368//5368 -f 5755//5755 5756//5756 5757//5757 -f 5757//5757 5756//5756 5758//5758 -f 5757//5757 5758//5758 5759//5759 -f 5759//5759 5758//5758 5753//5753 -f 5759//5759 5753//5753 5760//5760 -f 5760//5760 5753//5753 5754//5754 -f 5761//5761 4899//4899 5217//5217 -f 5285//5285 5284//5284 5756//5756 -f 5756//5756 5284//5284 5761//5761 -f 5756//5756 5761//5761 5758//5758 -f 5758//5758 5761//5761 5217//5217 -f 5383//5383 5762//5762 5357//5357 -f 5357//5357 5762//5762 5761//5761 -f 5357//5357 5761//5761 5284//5284 -f 5762//5762 5383//5383 5381//5381 -f 4912//4912 4901//4901 5763//5763 -f 5763//5763 4901//4901 5762//5762 -f 5763//5763 5762//5762 5764//5764 -f 5764//5764 5762//5762 5381//5381 -f 5765//5765 5766//5766 5767//5767 -f 5767//5767 5766//5766 5768//5768 -f 5767//5767 5768//5768 5769//5769 -f 5769//5769 5768//5768 5763//5763 -f 5769//5769 5763//5763 5770//5770 -f 5770//5770 5763//5763 5764//5764 -f 5771//5771 4906//4906 4904//4904 -f 5386//5386 5379//5379 5766//5766 -f 5766//5766 5379//5379 5771//5771 -f 5766//5766 5771//5771 5768//5768 -f 5768//5768 5771//5771 4904//4904 -f 5399//5399 5772//5772 5378//5378 -f 5378//5378 5772//5772 5771//5771 -f 5378//5378 5771//5771 5379//5379 -f 5772//5772 5399//5399 5397//5397 -f 4942//4942 4943//4943 5773//5773 -f 5773//5773 4943//4943 5772//5772 -f 5773//5773 5772//5772 5774//5774 -f 5774//5774 5772//5772 5397//5397 -f 5775//5775 5776//5776 5777//5777 -f 5777//5777 5776//5776 5778//5778 -f 5777//5777 5778//5778 5779//5779 -f 5779//5779 5778//5778 5773//5773 -f 5779//5779 5773//5773 5780//5780 -f 5780//5780 5773//5773 5774//5774 -f 4879//4879 4877//4877 5781//5781 -f 5781//5781 4877//4877 5778//5778 -f 5778//5778 5776//5776 5781//5781 -f 5781//5781 5776//5776 5400//5400 -f 5781//5781 5400//5400 5392//5392 -f 5781//5781 5392//5392 5782//5782 -f 5782//5782 5392//5392 5391//5391 -f 5782//5782 5391//5391 5395//5395 -f 4895//4895 4881//4881 5783//5783 -f 5783//5783 4881//4881 5782//5782 -f 5783//5783 5782//5782 5784//5784 -f 5784//5784 5782//5782 5395//5395 -f 5785//5785 5786//5786 5787//5787 -f 5787//5787 5786//5786 5788//5788 -f 5787//5787 5788//5788 5789//5789 -f 5789//5789 5788//5788 5783//5783 -f 5789//5789 5783//5783 5790//5790 -f 5790//5790 5783//5783 5784//5784 -f 5791//5791 4999//4999 4998//4998 -f 5409//5409 5404//5404 5786//5786 -f 5786//5786 5404//5404 5791//5791 -f 5786//5786 5791//5791 5788//5788 -f 5788//5788 5791//5791 4998//4998 -f 5590//5590 5792//5792 5403//5403 -f 5403//5403 5792//5792 5791//5791 -f 5403//5403 5791//5791 5404//5404 -f 5793//5793 5001//5001 5000//5000 -f 5590//5590 5411//5411 5792//5792 -f 5792//5792 5411//5411 5719//5719 -f 5792//5792 5719//5719 5000//5000 -f 5000//5000 5719//5719 5794//5794 -f 5000//5000 5794//5794 5793//5793 -f 4921//4921 5795//5795 4938//4938 -f 4938//4938 5795//5795 5796//5796 -f 4938//4938 5796//5796 4939//4939 -f 4939//4939 5796//5796 4941//4941 -f 5797//5797 4927//4927 5798//5798 -f 5798//5798 4927//4927 4926//4926 -f 5798//5798 4926//4926 4925//4925 -f 5799//5799 5800//5800 4929//4929 -f 4929//4929 4928//4928 5799//5799 -f 5799//5799 4928//4928 5182//5182 -f 5799//5799 5182//5182 4937//4937 -f 5036//5036 5801//5801 4931//4931 -f 4931//4931 5801//5801 5802//5802 -f 4931//4931 5802//5802 4932//4932 -f 5803//5803 5804//5804 5805//5805 -f 5805//5805 5804//5804 5806//5806 -f 5011//5011 5807//5807 5007//5007 -f 5007//5007 5807//5807 5808//5808 -f 5007//5007 5808//5808 5008//5008 -f 5809//5809 5024//5024 5023//5023 -f 5809//5809 5023//5023 5810//5810 -f 5810//5810 5023//5023 5029//5029 -f 5810//5810 5029//5029 5028//5028 -f 5811//5811 5025//5025 5812//5812 -f 5812//5812 5025//5025 5031//5031 -f 5812//5812 5031//5031 5030//5030 -f 5813//5813 5042//5042 5040//5040 -f 5813//5813 5040//5040 5814//5814 -f 5814//5814 5040//5040 5038//5038 -f 5814//5814 5038//5038 5037//5037 -f 5815//5815 5816//5816 5817//5817 -f 5817//5817 5816//5816 5818//5818 -f 5819//5819 5820//5820 5821//5821 -f 5821//5821 5820//5820 5747//5747 -f 5821//5821 5747//5747 5349//5349 -f 5349//5349 5747//5747 5748//5748 -f 5745//5745 5747//5747 5822//5822 -f 5822//5822 5747//5747 5823//5823 -f 5824//5824 5825//5825 5826//5826 -f 5826//5826 5825//5825 5745//5745 -f 5826//5826 5745//5745 5827//5827 -f 5827//5827 5745//5745 5822//5822 -f 5824//5824 5828//5828 5825//5825 -f 5825//5825 5828//5828 5829//5829 -f 5825//5825 5829//5829 5830//5830 -f 5830//5830 5829//5829 5831//5831 -f 5830//5830 5831//5831 5820//5820 -f 5820//5820 5831//5831 5832//5832 -f 5832//5832 5833//5833 5820//5820 -f 5820//5820 5833//5833 5834//5834 -f 5820//5820 5834//5834 5747//5747 -f 5747//5747 5834//5834 5835//5835 -f 5747//5747 5835//5835 5823//5823 -f 5352//5352 5743//5743 5836//5836 -f 5836//5836 5743//5743 5745//5745 -f 5836//5836 5745//5745 5837//5837 -f 5837//5837 5745//5745 5825//5825 -f 5819//5819 5838//5838 5820//5820 -f 5820//5820 5838//5838 5830//5830 -f 5838//5838 5837//5837 5830//5830 -f 5830//5830 5837//5837 5825//5825 -f 5836//5836 5837//5837 5839//5839 -f 5839//5839 5837//5837 5838//5838 -f 5839//5839 5838//5838 5840//5840 -f 5840//5840 5838//5838 5819//5819 -f 5840//5840 5819//5819 5821//5821 -f 5349//5349 5347//5347 5821//5821 -f 5821//5821 5347//5347 5840//5840 -f 5350//5350 5839//5839 5610//5610 -f 5610//5610 5839//5839 5840//5840 -f 5610//5610 5840//5840 5347//5347 -f 5350//5350 5352//5352 5839//5839 -f 5839//5839 5352//5352 5836//5836 -f 5841//5841 5842//5842 5843//5843 -f 5843//5843 5842//5842 5759//5759 -f 5843//5843 5759//5759 5369//5369 -f 5369//5369 5759//5759 5760//5760 -f 5844//5844 5757//5757 5845//5845 -f 5845//5845 5846//5846 5844//5844 -f 5844//5844 5846//5846 5847//5847 -f 5844//5844 5847//5847 5848//5848 -f 5848//5848 5847//5847 5849//5849 -f 5842//5842 5850//5850 5759//5759 -f 5759//5759 5850//5850 5851//5851 -f 5851//5851 5852//5852 5759//5759 -f 5759//5759 5852//5852 5853//5853 -f 5759//5759 5853//5853 5757//5757 -f 5757//5757 5853//5853 5854//5854 -f 5757//5757 5854//5854 5845//5845 -f 5849//5849 5855//5855 5848//5848 -f 5848//5848 5855//5855 5856//5856 -f 5848//5848 5856//5856 5842//5842 -f 5842//5842 5856//5856 5857//5857 -f 5842//5842 5857//5857 5850//5850 -f 5286//5286 5755//5755 5858//5858 -f 5858//5858 5755//5755 5757//5757 -f 5858//5858 5757//5757 5859//5859 -f 5859//5859 5757//5757 5844//5844 -f 5841//5841 5860//5860 5842//5842 -f 5842//5842 5860//5860 5848//5848 -f 5860//5860 5859//5859 5848//5848 -f 5848//5848 5859//5859 5844//5844 -f 5861//5861 5858//5858 5859//5859 -f 5841//5841 5843//5843 5862//5862 -f 5861//5861 5859//5859 5862//5862 -f 5862//5862 5859//5859 5860//5860 -f 5862//5862 5860//5860 5841//5841 -f 5370//5370 5862//5862 5369//5369 -f 5369//5369 5862//5862 5843//5843 -f 5355//5355 5861//5861 5370//5370 -f 5370//5370 5861//5861 5862//5862 -f 5286//5286 5858//5858 5355//5355 -f 5355//5355 5858//5858 5861//5861 -f 5822//5822 5193//5193 5827//5827 -f 5827//5827 5193//5193 5195//5195 -f 5827//5827 5195//5195 5826//5826 -f 5826//5826 5195//5195 5196//5196 -f 5826//5826 5196//5196 5824//5824 -f 5824//5824 5196//5196 5201//5201 -f 5824//5824 5201//5201 5828//5828 -f 5828//5828 5201//5201 5200//5200 -f 5828//5828 5200//5200 5829//5829 -f 5829//5829 5200//5200 5204//5204 -f 5829//5829 5204//5204 5831//5831 -f 5831//5831 5204//5204 5203//5203 -f 5831//5831 5203//5203 5832//5832 -f 5832//5832 5203//5203 5202//5202 -f 5832//5832 5202//5202 5833//5833 -f 5833//5833 5202//5202 5197//5197 -f 5833//5833 5197//5197 5834//5834 -f 5834//5834 5197//5197 5198//5198 -f 5834//5834 5198//5198 5835//5835 -f 5835//5835 5198//5198 5199//5199 -f 5835//5835 5199//5199 5823//5823 -f 5823//5823 5199//5199 5192//5192 -f 5823//5823 5192//5192 5822//5822 -f 5822//5822 5192//5192 5193//5193 -f 5850//5850 5226//5226 5851//5851 -f 5851//5851 5226//5226 5225//5225 -f 5851//5851 5225//5225 5852//5852 -f 5852//5852 5225//5225 5224//5224 -f 5852//5852 5224//5224 5853//5853 -f 5853//5853 5224//5224 5222//5222 -f 5853//5853 5222//5222 5854//5854 -f 5854//5854 5222//5222 5221//5221 -f 5854//5854 5221//5221 5845//5845 -f 5845//5845 5221//5221 5216//5216 -f 5845//5845 5216//5216 5846//5846 -f 5846//5846 5216//5216 5218//5218 -f 5846//5846 5218//5218 5847//5847 -f 5847//5847 5218//5218 5219//5219 -f 5847//5847 5219//5219 5849//5849 -f 5849//5849 5219//5219 5220//5220 -f 5849//5849 5220//5220 5855//5855 -f 5855//5855 5220//5220 5230//5230 -f 5855//5855 5230//5230 5856//5856 -f 5856//5856 5230//5230 5229//5229 -f 5856//5856 5229//5229 5857//5857 -f 5857//5857 5229//5229 5227//5227 -f 5857//5857 5227//5227 5850//5850 -f 5850//5850 5227//5227 5226//5226 -f 5863//5863 5864//5864 5865//5865 -f 5865//5865 5864//5864 5769//5769 -f 5865//5865 5769//5769 5380//5380 -f 5380//5380 5769//5769 5770//5770 -f 5866//5866 5767//5767 5867//5867 -f 5867//5867 5868//5868 5866//5866 -f 5866//5866 5868//5868 5869//5869 -f 5866//5866 5869//5869 5870//5870 -f 5870//5870 5869//5869 5871//5871 -f 5872//5872 5769//5769 5873//5873 -f 5873//5873 5769//5769 5864//5864 -f 5871//5871 5874//5874 5870//5870 -f 5870//5870 5874//5874 5875//5875 -f 5870//5870 5875//5875 5864//5864 -f 5864//5864 5875//5875 5876//5876 -f 5864//5864 5876//5876 5873//5873 -f 5872//5872 5877//5877 5769//5769 -f 5769//5769 5877//5877 5878//5878 -f 5769//5769 5878//5878 5767//5767 -f 5767//5767 5878//5878 5879//5879 -f 5767//5767 5879//5879 5867//5867 -f 5385//5385 5765//5765 5880//5880 -f 5880//5880 5765//5765 5767//5767 -f 5880//5880 5767//5767 5881//5881 -f 5881//5881 5767//5767 5866//5866 -f 5882//5882 5883//5883 5884//5884 -f 5884//5884 5883//5883 5779//5779 -f 5884//5884 5779//5779 5396//5396 -f 5396//5396 5779//5779 5780//5780 -f 5885//5885 5779//5779 5886//5886 -f 5886//5886 5779//5779 5883//5883 -f 5885//5885 5887//5887 5779//5779 -f 5779//5779 5887//5887 5888//5888 -f 5779//5779 5888//5888 5777//5777 -f 5889//5889 5890//5890 5891//5891 -f 5891//5891 5890//5890 5892//5892 -f 5889//5889 5893//5893 5890//5890 -f 5890//5890 5893//5893 5894//5894 -f 5890//5890 5894//5894 5883//5883 -f 5883//5883 5894//5894 5895//5895 -f 5883//5883 5895//5895 5886//5886 -f 5888//5888 5896//5896 5777//5777 -f 5777//5777 5896//5896 5897//5897 -f 5777//5777 5897//5897 5892//5892 -f 5892//5892 5897//5897 5898//5898 -f 5892//5892 5898//5898 5891//5891 -f 5401//5401 5775//5775 5899//5899 -f 5899//5899 5775//5775 5777//5777 -f 5899//5899 5777//5777 5900//5900 -f 5900//5900 5777//5777 5892//5892 -f 5901//5901 5902//5902 5903//5903 -f 5903//5903 5902//5902 5789//5789 -f 5903//5903 5789//5789 5405//5405 -f 5405//5405 5789//5789 5790//5790 -f 5904//5904 5905//5905 5906//5906 -f 5906//5906 5905//5905 5902//5902 -f 5907//5907 5787//5787 5908//5908 -f 5908//5908 5909//5909 5907//5907 -f 5907//5907 5909//5909 5910//5910 -f 5907//5907 5910//5910 5906//5906 -f 5906//5906 5910//5910 5911//5911 -f 5906//5906 5911//5911 5904//5904 -f 5905//5905 5912//5912 5902//5902 -f 5902//5902 5912//5912 5913//5913 -f 5902//5902 5913//5913 5789//5789 -f 5789//5789 5913//5913 5914//5914 -f 5914//5914 5915//5915 5789//5789 -f 5789//5789 5915//5915 5916//5916 -f 5789//5789 5916//5916 5787//5787 -f 5787//5787 5916//5916 5917//5917 -f 5787//5787 5917//5917 5908//5908 -f 5408//5408 5785//5785 5918//5918 -f 5918//5918 5785//5785 5787//5787 -f 5918//5918 5787//5787 5919//5919 -f 5919//5919 5787//5787 5907//5907 -f 5863//5863 5920//5920 5864//5864 -f 5864//5864 5920//5920 5870//5870 -f 5920//5920 5881//5881 5870//5870 -f 5870//5870 5881//5881 5866//5866 -f 5921//5921 5880//5880 5881//5881 -f 5863//5863 5865//5865 5922//5922 -f 5921//5921 5881//5881 5922//5922 -f 5922//5922 5881//5881 5920//5920 -f 5922//5922 5920//5920 5863//5863 -f 5882//5882 5923//5923 5883//5883 -f 5883//5883 5923//5923 5890//5890 -f 5923//5923 5900//5900 5890//5890 -f 5890//5890 5900//5900 5892//5892 -f 5924//5924 5899//5899 5900//5900 -f 5882//5882 5884//5884 5925//5925 -f 5924//5924 5900//5900 5925//5925 -f 5925//5925 5900//5900 5923//5923 -f 5925//5925 5923//5923 5882//5882 -f 5901//5901 5926//5926 5902//5902 -f 5902//5902 5926//5926 5906//5906 -f 5926//5926 5919//5919 5906//5906 -f 5906//5906 5919//5919 5907//5907 -f 5927//5927 5918//5918 5919//5919 -f 5901//5901 5903//5903 5928//5928 -f 5927//5927 5919//5919 5928//5928 -f 5928//5928 5919//5919 5926//5926 -f 5928//5928 5926//5926 5901//5901 -f 5382//5382 5922//5922 5380//5380 -f 5380//5380 5922//5922 5865//5865 -f 5384//5384 5921//5921 5382//5382 -f 5382//5382 5921//5921 5922//5922 -f 5385//5385 5880//5880 5384//5384 -f 5384//5384 5880//5880 5921//5921 -f 5398//5398 5925//5925 5396//5396 -f 5396//5396 5925//5925 5884//5884 -f 5402//5402 5924//5924 5398//5398 -f 5398//5398 5924//5924 5925//5925 -f 5401//5401 5899//5899 5402//5402 -f 5402//5402 5899//5899 5924//5924 -f 5406//5406 5928//5928 5405//5405 -f 5405//5405 5928//5928 5903//5903 -f 5407//5407 5927//5927 5406//5406 -f 5406//5406 5927//5927 5928//5928 -f 5408//5408 5918//5918 5407//5407 -f 5407//5407 5918//5918 5927//5927 -f 5873//5873 4914//4914 5872//5872 -f 5872//5872 4914//4914 4913//4913 -f 5872//5872 4913//4913 5877//5877 -f 5877//5877 4913//4913 4911//4911 -f 5877//5877 4911//4911 5878//5878 -f 5878//5878 4911//4911 4909//4909 -f 5878//5878 4909//4909 5879//5879 -f 5879//5879 4909//4909 4908//4908 -f 5879//5879 4908//4908 5867//5867 -f 5867//5867 4908//4908 4903//4903 -f 5867//5867 4903//4903 5868//5868 -f 5868//5868 4903//4903 4905//4905 -f 5868//5868 4905//4905 5869//5869 -f 5869//5869 4905//4905 4907//4907 -f 5869//5869 4907//4907 5871//5871 -f 5871//5871 4907//4907 4915//4915 -f 5871//5871 4915//4915 5874//5874 -f 5874//5874 4915//4915 4917//4917 -f 5874//5874 4917//4917 5875//5875 -f 5875//5875 4917//4917 4918//4918 -f 5875//5875 4918//4918 5876//5876 -f 5876//5876 4918//4918 4902//4902 -f 5876//5876 4902//4902 5873//5873 -f 5873//5873 4902//4902 4914//4914 -f 5886//5886 4786//4786 5885//5885 -f 5885//5885 4786//4786 4785//4785 -f 5885//5885 4785//4785 5887//5887 -f 5887//5887 4785//4785 5215//5215 -f 5887//5887 5215//5215 5888//5888 -f 5888//5888 5215//5215 5214//5214 -f 5888//5888 5214//5214 5896//5896 -f 5896//5896 5214//5214 5213//5213 -f 5896//5896 5213//5213 5897//5897 -f 5897//5897 5213//5213 5212//5212 -f 5897//5897 5212//5212 5898//5898 -f 5898//5898 5212//5212 5211//5211 -f 5898//5898 5211//5211 5891//5891 -f 5891//5891 5211//5211 5210//5210 -f 5891//5891 5210//5210 5889//5889 -f 5889//5889 5210//5210 5207//5207 -f 5889//5889 5207//5207 5893//5893 -f 5893//5893 5207//5207 5206//5206 -f 5893//5893 5206//5206 5894//5894 -f 5894//5894 5206//5206 5209//5209 -f 5894//5894 5209//5209 5895//5895 -f 5895//5895 5209//5209 5208//5208 -f 5895//5895 5208//5208 5886//5886 -f 5886//5886 5208//5208 4786//4786 -f 5913//5913 4897//4897 5914//5914 -f 5914//5914 4897//4897 4896//4896 -f 5914//5914 4896//4896 5915//5915 -f 5915//5915 4896//4896 4894//4894 -f 5915//5915 4894//4894 5916//5916 -f 5916//5916 4894//4894 4892//4892 -f 5916//5916 4892//4892 5917//5917 -f 5917//5917 4892//4892 4891//4891 -f 5917//5917 4891//4891 5908//5908 -f 5908//5908 4891//4891 4888//4888 -f 5908//5908 4888//4888 5909//5909 -f 5909//5909 4888//4888 4887//4887 -f 5909//5909 4887//4887 5910//5910 -f 5910//5910 4887//4887 4890//4890 -f 5910//5910 4890//4890 5911//5911 -f 5911//5911 4890//4890 4889//4889 -f 5911//5911 4889//4889 5904//5904 -f 5904//5904 4889//4889 4884//4884 -f 5904//5904 4884//4884 5905//5905 -f 5905//5905 4884//4884 4883//4883 -f 5905//5905 4883//4883 5912//5912 -f 5912//5912 4883//4883 4882//4882 -f 5912//5912 4882//4882 5913//5913 -f 5913//5913 4882//4882 4897//4897 -f 5709//5709 5681//5681 5710//5710 -f 5710//5710 5681//5681 5677//5677 -f 5710//5710 5677//5677 5611//5611 -f 5611//5611 5677//5677 5717//5717 -f 5337//5337 5713//5713 5707//5707 -f 5707//5707 5713//5713 5676//5676 -f 5707//5707 5676//5676 5708//5708 -f 5708//5708 5676//5676 5685//5685 -f 5709//5709 5712//5712 5681//5681 -f 5681//5681 5712//5712 5683//5683 -f 5712//5712 5708//5708 5683//5683 -f 5683//5683 5708//5708 5685//5685 -f 5612//5612 5711//5711 5611//5611 -f 5611//5611 5711//5711 5710//5710 -f 5339//5339 5706//5706 5613//5613 -f 5613//5613 5706//5706 5711//5711 -f 5613//5613 5711//5711 5612//5612 -f 5337//5337 5707//5707 5339//5339 -f 5339//5339 5707//5707 5706//5706 -f 5698//5698 5659//5659 5699//5699 -f 5699//5699 5659//5659 5661//5661 -f 5699//5699 5661//5661 5487//5487 -f 5487//5487 5661//5661 5704//5704 -f 5325//5325 5700//5700 5693//5693 -f 5693//5693 5700//5700 5664//5664 -f 5693//5693 5664//5664 5694//5694 -f 5694//5694 5664//5664 5663//5663 -f 5698//5698 5696//5696 5659//5659 -f 5659//5659 5696//5696 5667//5667 -f 5696//5696 5694//5694 5667//5667 -f 5667//5667 5694//5694 5663//5663 -f 5487//5487 5319//5319 5699//5699 -f 5699//5699 5319//5319 5697//5697 -f 5319//5319 5318//5318 5697//5697 -f 5697//5697 5318//5318 5695//5695 -f 5318//5318 5325//5325 5695//5695 -f 5695//5695 5325//5325 5693//5693 -f 5678//5678 4866//4866 5687//5687 -f 5687//5687 4866//4866 4865//4865 -f 5687//5687 4865//4865 5688//5688 -f 5688//5688 4865//4865 4864//4864 -f 5688//5688 4864//4864 5689//5689 -f 5689//5689 4864//4864 4862//4862 -f 5689//5689 4862//4862 5686//5686 -f 5686//5686 4862//4862 4861//4861 -f 5686//5686 4861//4861 5684//5684 -f 5684//5684 4861//4861 4859//4859 -f 5684//5684 4859//4859 5682//5682 -f 5682//5682 4859//4859 4858//4858 -f 5682//5682 4858//4858 5680//5680 -f 5680//5680 4858//4858 4875//4875 -f 5680//5680 4875//4875 5690//5690 -f 5690//5690 4875//4875 4873//4873 -f 5690//5690 4873//4873 5691//5691 -f 5691//5691 4873//4873 4871//4871 -f 5691//5691 4871//4871 5692//5692 -f 5692//5692 4871//4871 4869//4869 -f 5692//5692 4869//4869 5679//5679 -f 5679//5679 4869//4869 4868//4868 -f 5679//5679 4868//4868 5678//5678 -f 5678//5678 4868//4868 4866//4866 -f 5669//5669 5016//5016 5668//5668 -f 5668//5668 5016//5016 5015//5015 -f 5668//5668 5015//5015 5666//5666 -f 5666//5666 5015//5015 5014//5014 -f 5666//5666 5014//5014 5670//5670 -f 5670//5670 5014//5014 5012//5012 -f 5670//5670 5012//5012 5671//5671 -f 5671//5671 5012//5012 5010//5010 -f 5671//5671 5010//5010 5672//5672 -f 5672//5672 5010//5010 5009//5009 -f 5672//5672 5009//5009 5660//5660 -f 5660//5660 5009//5009 5006//5006 -f 5660//5660 5006//5006 5662//5662 -f 5662//5662 5006//5006 5005//5005 -f 5662//5662 5005//5005 5673//5673 -f 5673//5673 5005//5005 5021//5021 -f 5673//5673 5021//5021 5674//5674 -f 5674//5674 5021//5021 5020//5020 -f 5674//5674 5020//5020 5675//5675 -f 5675//5675 5020//5020 5018//5018 -f 5675//5675 5018//5018 5665//5665 -f 5665//5665 5018//5018 5017//5017 -f 5665//5665 5017//5017 5669//5669 -f 5669//5669 5017//5017 5016//5016 -f 5639//5639 5266//5266 5640//5640 -f 5640//5640 5266//5266 5268//5268 -f 5640//5640 5268//5268 5309//5309 -f 5309//5309 5268//5268 5657//5657 -f 5618//5618 5653//5653 5634//5634 -f 5634//5634 5653//5653 5275//5275 -f 5634//5634 5275//5275 5635//5635 -f 5635//5635 5275//5275 5277//5277 -f 5632//5632 5253//5253 5633//5633 -f 5633//5633 5253//5253 5255//5255 -f 5633//5633 5255//5255 5303//5303 -f 5303//5303 5255//5255 5651//5651 -f 5289//5289 5647//5647 5627//5627 -f 5627//5627 5647//5647 5259//5259 -f 5627//5627 5259//5259 5628//5628 -f 5628//5628 5259//5259 5249//5249 -f 5625//5625 5242//5242 5626//5626 -f 5626//5626 5242//5242 5232//5232 -f 5626//5626 5232//5232 5290//5290 -f 5290//5290 5232//5232 5645//5645 -f 5298//5298 5641//5641 5620//5620 -f 5620//5620 5641//5641 5238//5238 -f 5620//5620 5238//5238 5621//5621 -f 5621//5621 5238//5238 5241//5241 -f 5639//5639 5637//5637 5266//5266 -f 5266//5266 5637//5637 5270//5270 -f 5637//5637 5635//5635 5270//5270 -f 5270//5270 5635//5635 5277//5277 -f 5632//5632 5630//5630 5253//5253 -f 5253//5253 5630//5630 5251//5251 -f 5630//5630 5628//5628 5251//5251 -f 5251//5251 5628//5628 5249//5249 -f 5625//5625 5623//5623 5242//5242 -f 5242//5242 5623//5623 5235//5235 -f 5623//5623 5621//5621 5235//5235 -f 5235//5235 5621//5621 5241//5241 -f 5309//5309 5308//5308 5640//5640 -f 5640//5640 5308//5308 5638//5638 -f 5308//5308 5314//5314 5638//5638 -f 5638//5638 5314//5314 5636//5636 -f 5314//5314 5618//5618 5636//5636 -f 5636//5636 5618//5618 5634//5634 -f 5303//5303 5302//5302 5633//5633 -f 5633//5633 5302//5302 5631//5631 -f 5302//5302 5306//5306 5631//5631 -f 5631//5631 5306//5306 5629//5629 -f 5306//5306 5289//5289 5629//5629 -f 5629//5629 5289//5289 5627//5627 -f 5290//5290 5292//5292 5626//5626 -f 5626//5626 5292//5292 5624//5624 -f 5292//5292 5296//5296 5624//5624 -f 5624//5624 5296//5296 5622//5622 -f 5296//5296 5298//5298 5622//5622 -f 5622//5622 5298//5298 5620//5620 -f 5276//5276 4843//4843 5280//5280 -f 5280//5280 4843//4843 4842//4842 -f 5280//5280 4842//4842 5281//5281 -f 5281//5281 4842//4842 4837//4837 -f 5281//5281 4837//4837 5282//5282 -f 5282//5282 4837//4837 4854//4854 -f 5282//5282 4854//4854 5271//5271 -f 5271//5271 4854//4854 4853//4853 -f 5271//5271 4853//4853 5272//5272 -f 5272//5272 4853//4853 4851//4851 -f 5272//5272 4851//4851 5267//5267 -f 5267//5267 4851//4851 4850//4850 -f 5267//5267 4850//4850 5269//5269 -f 5269//5269 4850//4850 4849//4849 -f 5269//5269 4849//4849 5273//5273 -f 5273//5273 4849//4849 4857//4857 -f 5273//5273 4857//4857 5274//5274 -f 5274//5274 4857//4857 4856//4856 -f 5274//5274 4856//4856 5279//5279 -f 5279//5279 4856//4856 4855//4855 -f 5279//5279 4855//4855 5278//5278 -f 5278//5278 4855//4855 4845//4845 -f 5278//5278 4845//4845 5276//5276 -f 5276//5276 4845//4845 4843//4843 -f 5262//5262 5147//5147 5250//5250 -f 5250//5250 5147//5147 5146//5146 -f 5250//5250 5146//5146 5252//5252 -f 5252//5252 5146//5146 5157//5157 -f 5252//5252 5157//5157 5263//5263 -f 5263//5263 5157//5157 5156//5156 -f 5263//5263 5156//5156 5264//5264 -f 5264//5264 5156//5156 5155//5155 -f 5264//5264 5155//5155 5265//5265 -f 5265//5265 5155//5155 5152//5152 -f 5265//5265 5152//5152 5254//5254 -f 5254//5254 5152//5152 5153//5153 -f 5254//5254 5153//5153 5256//5256 -f 5256//5256 5153//5153 5154//5154 -f 5256//5256 5154//5154 5257//5257 -f 5257//5257 5154//5154 5151//5151 -f 5257//5257 5151//5151 5258//5258 -f 5258//5258 5151//5151 5150//5150 -f 5258//5258 5150//5150 5260//5260 -f 5260//5260 5150//5150 5149//5149 -f 5260//5260 5149//5149 5261//5261 -f 5261//5261 5149//5149 5148//5148 -f 5261//5261 5148//5148 5262//5262 -f 5262//5262 5148//5148 5147//5147 -f 5246//5246 4823//4823 5247//5247 -f 5247//5247 4823//4823 4821//4821 -f 5247//5247 4821//4821 5248//5248 -f 5248//5248 4821//4821 4820//4820 -f 5248//5248 4820//4820 5236//5236 -f 5236//5236 4820//4820 4831//4831 -f 5236//5236 4831//4831 5237//5237 -f 5237//5237 4831//4831 4833//4833 -f 5237//5237 4833//4833 5243//5243 -f 5243//5243 4833//4833 4835//4835 -f 5243//5243 4835//4835 5244//5244 -f 5244//5244 4835//4835 4836//4836 -f 5244//5244 4836//4836 5245//5245 -f 5245//5245 4836//4836 4830//4830 -f 5245//5245 4830//4830 5233//5233 -f 5233//5233 4830//4830 4829//4829 -f 5233//5233 4829//4829 5234//5234 -f 5234//5234 4829//4829 4828//4828 -f 5234//5234 4828//4828 5239//5239 -f 5239//5239 4828//4828 4827//4827 -f 5239//5239 4827//4827 5240//5240 -f 5240//5240 4827//4827 4825//4825 -f 5240//5240 4825//4825 5246//5246 -f 5246//5246 4825//4825 4823//4823 -f 5722//5722 3678//3678 5929//5929 -f 5929//5929 3678//3678 3702//3702 -f 5929//5929 3702//3702 5930//5930 -f 5930//5930 3702//3702 5931//5931 -f 5931//5931 3702//3702 3673//3673 -f 5931//5931 3673//3673 5932//5932 -f 5932//5932 3673//3673 5933//5933 -f 5933//5933 3673//3673 3674//3674 -f 5933//5933 3674//3674 5934//5934 -f 5934//5934 3674//3674 5935//5935 -f 5935//5935 3674//3674 3676//3676 -f 5935//5935 3676//3676 5936//5936 -f 5936//5936 3676//3676 5937//5937 -f 5937//5937 3676//3676 3650//3650 -f 5937//5937 3650//3650 5724//5724 -f 5720//5720 3692//3692 5938//5938 -f 5938//5938 3692//3692 3699//3699 -f 5938//5938 3699//3699 5939//5939 -f 5939//5939 3699//3699 5940//5940 -f 5940//5940 3699//3699 3698//3698 -f 5940//5940 3698//3698 5941//5941 -f 5941//5941 3698//3698 5942//5942 -f 5942//5942 3698//3698 3684//3684 -f 5942//5942 3684//3684 5943//5943 -f 5943//5943 3684//3684 5944//5944 -f 5944//5944 3684//3684 3682//3682 -f 5944//5944 3682//3682 5945//5945 -f 5945//5945 3682//3682 5946//5946 -f 5946//5946 3682//3682 3680//3680 -f 5946//5946 3680//3680 5721//5721 -f 5947//5947 5390//5390 5388//5388 -f 5388//5388 5387//5387 5947//5947 -f 5947//5947 5387//5387 5461//5461 -f 5947//5947 5461//5461 5948//5948 -f 5948//5948 5461//5461 5459//5459 -f 5948//5948 5459//5459 5457//5457 -f 5176//5176 5948//5948 5177//5177 -f 5177//5177 5948//5948 5178//5178 -f 5457//5457 5447//5447 5948//5948 -f 5948//5948 5447//5447 5949//5949 -f 5948//5948 5949//5949 5178//5178 -f 5178//5178 5949//5949 5044//5044 -f 5451//5451 5950//5950 5449//5449 -f 5449//5449 5950//5950 5949//5949 -f 5449//5449 5949//5949 5447//5447 -f 5451//5451 5453//5453 5950//5950 -f 5950//5950 5453//5453 5455//5455 -f 5950//5950 5455//5455 5585//5585 -f 5951//5951 5952//5952 5950//5950 -f 5585//5585 5390//5390 5950//5950 -f 5950//5950 5390//5390 5947//5947 -f 5950//5950 5947//5947 5951//5951 -f 5953//5953 5954//5954 5955//5955 -f 5465//5465 5466//5466 5955//5955 -f 5955//5955 5466//5466 5956//5956 -f 5955//5955 5956//5956 5953//5953 -f 5956//5956 5466//5466 5467//5467 -f 5467//5467 5472//5472 5956//5956 -f 5956//5956 5472//5472 5474//5474 -f 5956//5956 5474//5474 5957//5957 -f 5957//5957 5474//5474 5476//5476 -f 5957//5957 5476//5476 5471//5471 -f 5060//5060 5957//5957 5061//5061 -f 5061//5061 5957//5957 5063//5063 -f 5471//5471 5470//5470 5957//5957 -f 5957//5957 5470//5470 5958//5958 -f 5957//5957 5958//5958 5063//5063 -f 5063//5063 5958//5958 5065//5065 -f 5478//5478 5955//5955 5469//5469 -f 5469//5469 5955//5955 5958//5958 -f 5469//5469 5958//5958 5470//5470 -f 5478//5478 5480//5480 5955//5955 -f 5955//5955 5480//5480 5463//5463 -f 5955//5955 5463//5463 5465//5465 -f 5959//5959 4803//4803 4801//4801 -f 5079//5079 5960//5960 4801//4801 -f 4801//4801 5960//5960 5961//5961 -f 4801//4801 5961//5961 5959//5959 -f 5078//5078 5962//5962 5079//5079 -f 5079//5079 5962//5962 5963//5963 -f 5079//5079 5963//5963 5960//5960 -f 5076//5076 5964//5964 5078//5078 -f 5078//5078 5964//5964 5965//5965 -f 5078//5078 5965//5965 5962//5962 -f 5075//5075 5966//5966 5076//5076 -f 5076//5076 5966//5966 5967//5967 -f 5076//5076 5967//5967 5964//5964 -f 5074//5074 5968//5968 5075//5075 -f 5075//5075 5968//5968 5969//5969 -f 5075//5075 5969//5969 5966//5966 -f 5073//5073 5970//5970 5074//5074 -f 5074//5074 5970//5970 5971//5971 -f 5074//5074 5971//5971 5968//5968 -f 5069//5069 5972//5972 5073//5073 -f 5073//5073 5972//5972 5973//5973 -f 5073//5073 5973//5973 5970//5970 -f 5071//5071 5974//5974 5069//5069 -f 5069//5069 5974//5974 5975//5975 -f 5069//5069 5975//5975 5972//5972 -f 5084//5084 5976//5976 5071//5071 -f 5071//5071 5976//5976 5977//5977 -f 5071//5071 5977//5977 5974//5974 -f 5083//5083 5978//5978 5084//5084 -f 5084//5084 5978//5978 5979//5979 -f 5084//5084 5979//5979 5976//5976 -f 5081//5081 5980//5980 5083//5083 -f 5083//5083 5980//5980 5981//5981 -f 5083//5083 5981//5981 5978//5978 -f 5080//5080 5982//5982 5081//5081 -f 5081//5081 5982//5982 5983//5983 -f 5081//5081 5983//5983 5980//5980 -f 5090//5090 5984//5984 5080//5080 -f 5080//5080 5984//5984 5985//5985 -f 5080//5080 5985//5985 5982//5982 -f 5092//5092 5986//5986 5090//5090 -f 5090//5090 5986//5986 5987//5987 -f 5090//5090 5987//5987 5984//5984 -f 5093//5093 5988//5988 5092//5092 -f 5092//5092 5988//5988 5989//5989 -f 5092//5092 5989//5989 5986//5986 -f 5087//5087 5990//5990 5093//5093 -f 5093//5093 5990//5990 5991//5991 -f 5093//5093 5991//5991 5988//5988 -f 5089//5089 5992//5992 5087//5087 -f 5087//5087 5992//5992 5993//5993 -f 5087//5087 5993//5993 5990//5990 -f 5103//5103 5994//5994 5089//5089 -f 5089//5089 5994//5994 5995//5995 -f 5089//5089 5995//5995 5992//5992 -f 5959//5959 5996//5996 4803//4803 -f 4803//4803 5996//5996 5997//5997 -f 4803//4803 5997//5997 5103//5103 -f 5103//5103 5997//5997 5998//5998 -f 5103//5103 5998//5998 5994//5994 -f 5999//5999 6000//6000 6001//6001 -f 6001//6001 6000//6000 6002//6002 -f 6003//6003 6004//6004 6005//6005 -f 6005//6005 6004//6004 6006//6006 -f 6007//6007 6008//6008 6009//6009 -f 6010//6010 6011//6011 6008//6008 -f 6008//6008 6011//6011 6012//6012 -f 6008//6008 6012//6012 6009//6009 -f 6013//6013 6014//6014 6015//6015 -f 6015//6015 6014//6014 6016//6016 -f 6015//6015 6016//6016 6017//6017 -f 6018//6018 6019//6019 6020//6020 -f 6020//6020 6019//6019 6021//6021 -f 6004//6004 6022//6022 6006//6006 -f 6006//6006 6022//6022 6023//6023 -f 6006//6006 6023//6023 6024//6024 -f 6000//6000 6025//6025 6002//6002 -f 6002//6002 6025//6025 6026//6026 -f 6002//6002 6026//6026 6027//6027 -f 6028//6028 6029//6029 6001//6001 -f 6001//6001 6029//6029 6030//6030 -f 6001//6001 6030//6030 5999//5999 -f 6031//6031 6032//6032 6033//6033 -f 6033//6033 6032//6032 6034//6034 -f 6013//6013 6035//6035 6014//6014 -f 6014//6014 6035//6035 6036//6036 -f 6014//6014 6036//6036 6010//6010 -f 6010//6010 6036//6036 6037//6037 -f 6010//6010 6037//6037 6011//6011 -f 6017//6017 6016//6016 6038//6038 -f 6038//6038 6016//6016 6039//6039 -f 6038//6038 6039//6039 6040//6040 -f 6019//6019 6041//6041 6021//6021 -f 6021//6021 6041//6041 6042//6042 -f 6021//6021 6042//6042 6039//6039 -f 6039//6039 6042//6042 6043//6043 -f 6039//6039 6043//6043 6040//6040 -f 6023//6023 6044//6044 6024//6024 -f 6024//6024 6044//6044 6045//6045 -f 6024//6024 6045//6045 6020//6020 -f 6020//6020 6045//6045 6046//6046 -f 6020//6020 6046//6046 6018//6018 -f 6026//6026 6047//6047 6027//6027 -f 6027//6027 6047//6047 6048//6048 -f 6027//6027 6048//6048 6005//6005 -f 6005//6005 6048//6048 6049//6049 -f 6005//6005 6049//6049 6003//6003 -f 6032//6032 6050//6050 6034//6034 -f 6034//6034 6050//6050 6051//6051 -f 6034//6034 6051//6051 6028//6028 -f 6028//6028 6051//6051 6052//6052 -f 6028//6028 6052//6052 6029//6029 -f 6009//6009 6053//6053 6007//6007 -f 6007//6007 6053//6053 6054//6054 -f 6007//6007 6054//6054 6033//6033 -f 6033//6033 6054//6054 6055//6055 -f 6033//6033 6055//6055 6031//6031 -f 6056//6056 6002//6002 6057//6057 -f 6057//6057 6002//6002 6027//6027 -f 6057//6057 6027//6027 6058//6058 -f 6058//6058 6027//6027 6005//6005 -f 6058//6058 6005//6005 6059//6059 -f 6059//6059 6005//6005 6006//6006 -f 6059//6059 6006//6006 6060//6060 -f 6060//6060 6006//6006 6024//6024 -f 6060//6060 6024//6024 6061//6061 -f 6061//6061 6024//6024 6020//6020 -f 6061//6061 6020//6020 6062//6062 -f 6062//6062 6020//6020 6021//6021 -f 6062//6062 6021//6021 6063//6063 -f 6063//6063 6021//6021 6039//6039 -f 6063//6063 6039//6039 6064//6064 -f 6064//6064 6039//6039 6016//6016 -f 6064//6064 6016//6016 6065//6065 -f 6065//6065 6016//6016 6014//6014 -f 6065//6065 6014//6014 6066//6066 -f 6066//6066 6014//6014 6010//6010 -f 6066//6066 6010//6010 6067//6067 -f 6067//6067 6010//6010 6008//6008 -f 6067//6067 6008//6008 6068//6068 -f 6068//6068 6008//6008 6007//6007 -f 6068//6068 6007//6007 6069//6069 -f 6069//6069 6007//6007 6033//6033 -f 6069//6069 6033//6033 6070//6070 -f 6070//6070 6033//6033 6034//6034 -f 6070//6070 6034//6034 6071//6071 -f 6071//6071 6034//6034 6028//6028 -f 6071//6071 6028//6028 6072//6072 -f 6072//6072 6028//6028 6001//6001 -f 6072//6072 6001//6001 6056//6056 -f 6056//6056 6001//6001 6002//6002 -f 6073//6073 6071//6071 6074//6074 -f 6074//6074 6071//6071 6072//6072 -f 6074//6074 6072//6072 6075//6075 -f 6075//6075 6072//6072 6056//6056 -f 6075//6075 6056//6056 6076//6076 -f 6077//6077 6068//6068 6078//6078 -f 6078//6078 6068//6068 6069//6069 -f 6078//6078 6069//6069 6073//6073 -f 6073//6073 6069//6069 6070//6070 -f 6073//6073 6070//6070 6071//6071 -f 6079//6079 6064//6064 6080//6080 -f 6080//6080 6064//6064 6065//6065 -f 6080//6080 6065//6065 6081//6081 -f 6081//6081 6065//6065 6066//6066 -f 6081//6081 6066//6066 6077//6077 -f 6077//6077 6066//6066 6067//6067 -f 6077//6077 6067//6067 6068//6068 -f 6082//6082 6061//6061 6083//6083 -f 6083//6083 6061//6061 6062//6062 -f 6083//6083 6062//6062 6079//6079 -f 6079//6079 6062//6062 6063//6063 -f 6079//6079 6063//6063 6064//6064 -f 6056//6056 6057//6057 6076//6076 -f 6076//6076 6057//6057 6058//6058 -f 6076//6076 6058//6058 6084//6084 -f 6084//6084 6058//6058 6059//6059 -f 6084//6084 6059//6059 6082//6082 -f 6082//6082 6059//6059 6060//6060 -f 6082//6082 6060//6060 6061//6061 -f 6085//6085 6086//6086 6087//6087 -f 6088//6088 6086//6086 6085//6085 -f 6085//6085 6089//6089 6090//6090 -f 6091//6091 6089//6089 6085//6085 -f 6087//6087 6091//6091 6085//6085 -f 6085//6085 6092//6092 6093//6093 -f 6094//6094 6092//6092 6085//6085 -f 6090//6090 6094//6094 6085//6085 -f 6085//6085 6095//6095 6096//6096 -f 6097//6097 6095//6095 6085//6085 -f 6093//6093 6097//6097 6085//6085 -f 6096//6096 6088//6088 6085//6085 -f 6088//6088 6098//6098 6086//6086 -f 6086//6086 6098//6098 6099//6099 -f 6086//6086 6099//6099 6087//6087 -f 6087//6087 6099//6099 6100//6100 -f 6087//6087 6100//6100 6091//6091 -f 6091//6091 6100//6100 6101//6101 -f 6091//6091 6101//6101 6089//6089 -f 6089//6089 6101//6101 6102//6102 -f 6089//6089 6102//6102 6090//6090 -f 6090//6090 6102//6102 6103//6103 -f 6090//6090 6103//6103 6094//6094 -f 6094//6094 6103//6103 6104//6104 -f 6094//6094 6104//6104 6092//6092 -f 6092//6092 6104//6104 6105//6105 -f 6092//6092 6105//6105 6093//6093 -f 6093//6093 6105//6105 6106//6106 -f 6093//6093 6106//6106 6097//6097 -f 6097//6097 6106//6106 6107//6107 -f 6097//6097 6107//6107 6095//6095 -f 6095//6095 6107//6107 6108//6108 -f 6095//6095 6108//6108 6096//6096 -f 6096//6096 6108//6108 6109//6109 -f 6096//6096 6109//6109 6088//6088 -f 6088//6088 6109//6109 6098//6098 -f 6099//6099 5436//5436 6100//6100 -f 6100//6100 5436//5436 5434//5434 -f 6100//6100 5434//5434 6101//6101 -f 6101//6101 5434//5434 5433//5433 -f 6101//6101 5433//5433 6102//6102 -f 6102//6102 5433//5433 5432//5432 -f 6102//6102 5432//5432 6103//6103 -f 6103//6103 5432//5432 5431//5431 -f 6103//6103 5431//5431 6104//6104 -f 6104//6104 5431//5431 5429//5429 -f 6104//6104 5429//5429 6105//6105 -f 6105//6105 5429//5429 5442//5442 -f 6105//6105 5442//5442 6106//6106 -f 6106//6106 5442//5442 5441//5441 -f 6106//6106 5441//5441 6107//6107 -f 6107//6107 5441//5441 5440//5440 -f 6107//6107 5440//5440 6108//6108 -f 6108//6108 5440//5440 5439//5439 -f 6108//6108 5439//5439 6109//6109 -f 6109//6109 5439//5439 5438//5438 -f 6109//6109 5438//5438 6098//6098 -f 6098//6098 5438//5438 5437//5437 -f 6098//6098 5437//5437 6099//6099 -f 6099//6099 5437//5437 5436//5436 -f 6110//6110 6111//6111 6112//6112 -f 6113//6113 6111//6111 6110//6110 -f 6110//6110 6114//6114 6115//6115 -f 6116//6116 6114//6114 6110//6110 -f 6112//6112 6116//6116 6110//6110 -f 6110//6110 6117//6117 6118//6118 -f 6119//6119 6117//6117 6110//6110 -f 6115//6115 6119//6119 6110//6110 -f 6110//6110 6120//6120 6121//6121 -f 6122//6122 6120//6120 6110//6110 -f 6118//6118 6122//6122 6110//6110 -f 6121//6121 6113//6113 6110//6110 -f 6113//6113 6123//6123 6111//6111 -f 6111//6111 6123//6123 6124//6124 -f 6111//6111 6124//6124 6112//6112 -f 6112//6112 6124//6124 6125//6125 -f 6112//6112 6125//6125 6116//6116 -f 6116//6116 6125//6125 6126//6126 -f 6116//6116 6126//6126 6114//6114 -f 6114//6114 6126//6126 6127//6127 -f 6114//6114 6127//6127 6115//6115 -f 6115//6115 6127//6127 6128//6128 -f 6115//6115 6128//6128 6119//6119 -f 6119//6119 6128//6128 6129//6129 -f 6119//6119 6129//6129 6117//6117 -f 6117//6117 6129//6129 6130//6130 -f 6117//6117 6130//6130 6118//6118 -f 6118//6118 6130//6130 6131//6131 -f 6118//6118 6131//6131 6122//6122 -f 6122//6122 6131//6131 6132//6132 -f 6122//6122 6132//6132 6120//6120 -f 6120//6120 6132//6132 6133//6133 -f 6120//6120 6133//6133 6121//6121 -f 6121//6121 6133//6133 6134//6134 -f 6121//6121 6134//6134 6113//6113 -f 6113//6113 6134//6134 6123//6123 -f 6124//6124 5416//5416 6125//6125 -f 6125//6125 5416//5416 5415//5415 -f 6125//6125 5415//5415 6126//6126 -f 6126//6126 5415//5415 5414//5414 -f 6126//6126 5414//5414 6127//6127 -f 6127//6127 5414//5414 5413//5413 -f 6127//6127 5413//5413 6128//6128 -f 6128//6128 5413//5413 5427//5427 -f 6128//6128 5427//5427 6129//6129 -f 6129//6129 5427//5427 5426//5426 -f 6129//6129 5426//5426 6130//6130 -f 6130//6130 5426//5426 5424//5424 -f 6130//6130 5424//5424 6131//6131 -f 6131//6131 5424//5424 5422//5422 -f 6131//6131 5422//5422 6132//6132 -f 6132//6132 5422//5422 5421//5421 -f 6132//6132 5421//5421 6133//6133 -f 6133//6133 5421//5421 5420//5420 -f 6133//6133 5420//5420 6134//6134 -f 6134//6134 5420//5420 5418//5418 -f 6134//6134 5418//5418 6123//6123 -f 6123//6123 5418//5418 5417//5417 -f 6123//6123 5417//5417 6124//6124 -f 6124//6124 5417//5417 5416//5416 -f 6135//6135 6136//6136 6137//6137 -f 6138//6138 6136//6136 6135//6135 -f 6135//6135 6139//6139 6140//6140 -f 6141//6141 6139//6139 6135//6135 -f 6137//6137 6141//6141 6135//6135 -f 6135//6135 6142//6142 6143//6143 -f 6144//6144 6142//6142 6135//6135 -f 6140//6140 6144//6144 6135//6135 -f 6135//6135 6145//6145 6146//6146 -f 6147//6147 6145//6145 6135//6135 -f 6143//6143 6147//6147 6135//6135 -f 6146//6146 6138//6138 6135//6135 -f 6138//6138 6148//6148 6136//6136 -f 6136//6136 6148//6148 6149//6149 -f 6136//6136 6149//6149 6137//6137 -f 6137//6137 6149//6149 6150//6150 -f 6137//6137 6150//6150 6141//6141 -f 6141//6141 6150//6150 6151//6151 -f 6141//6141 6151//6151 6139//6139 -f 6139//6139 6151//6151 6152//6152 -f 6139//6139 6152//6152 6140//6140 -f 6140//6140 6152//6152 6153//6153 -f 6140//6140 6153//6153 6144//6144 -f 6144//6144 6153//6153 6154//6154 -f 6144//6144 6154//6154 6142//6142 -f 6142//6142 6154//6154 6155//6155 -f 6142//6142 6155//6155 6143//6143 -f 6143//6143 6155//6155 6156//6156 -f 6143//6143 6156//6156 6147//6147 -f 6147//6147 6156//6156 6157//6157 -f 6147//6147 6157//6157 6145//6145 -f 6145//6145 6157//6157 6158//6158 -f 6145//6145 6158//6158 6146//6146 -f 6146//6146 6158//6158 6159//6159 -f 6146//6146 6159//6159 6138//6138 -f 6138//6138 6159//6159 6148//6148 -f 6149//6149 5486//5486 6150//6150 -f 6150//6150 5486//5486 5492//5492 -f 6150//6150 5492//5492 6151//6151 -f 6151//6151 5492//5492 5491//5491 -f 6151//6151 5491//5491 6152//6152 -f 6152//6152 5491//5491 5490//5490 -f 6152//6152 5490//5490 6153//6153 -f 6153//6153 5490//5490 5482//5482 -f 6153//6153 5482//5482 6154//6154 -f 6154//6154 5482//5482 5484//5484 -f 6154//6154 5484//5484 6155//6155 -f 6155//6155 5484//5484 5327//5327 -f 6155//6155 5327//5327 6156//6156 -f 6156//6156 5327//5327 5328//5328 -f 6156//6156 5328//5328 6157//6157 -f 6157//6157 5328//5328 5329//5329 -f 6157//6157 5329//5329 6158//6158 -f 6158//6158 5329//5329 5324//5324 -f 6158//6158 5324//5324 6159//6159 -f 6159//6159 5324//5324 5320//5320 -f 6159//6159 5320//5320 6148//6148 -f 6148//6148 5320//5320 5489//5489 -f 6148//6148 5489//5489 6149//6149 -f 6149//6149 5489//5489 5486//5486 -f 6160//6160 6161//6161 6162//6162 -f 6163//6163 6161//6161 6160//6160 -f 6160//6160 6164//6164 6165//6165 -f 6166//6166 6164//6164 6160//6160 -f 6162//6162 6166//6166 6160//6160 -f 6160//6160 6167//6167 6168//6168 -f 6169//6169 6167//6167 6160//6160 -f 6165//6165 6169//6169 6160//6160 -f 6160//6160 6170//6170 6171//6171 -f 6172//6172 6170//6170 6160//6160 -f 6168//6168 6172//6172 6160//6160 -f 6171//6171 6163//6163 6160//6160 -f 6163//6163 6173//6173 6161//6161 -f 6161//6161 6173//6173 6174//6174 -f 6161//6161 6174//6174 6162//6162 -f 6162//6162 6174//6174 6175//6175 -f 6162//6162 6175//6175 6166//6166 -f 6166//6166 6175//6175 6176//6176 -f 6166//6166 6176//6176 6164//6164 -f 6164//6164 6176//6176 6177//6177 -f 6164//6164 6177//6177 6165//6165 -f 6165//6165 6177//6177 6178//6178 -f 6165//6165 6178//6178 6169//6169 -f 6169//6169 6178//6178 6179//6179 -f 6169//6169 6179//6179 6167//6167 -f 6167//6167 6179//6179 6180//6180 -f 6167//6167 6180//6180 6168//6168 -f 6168//6168 6180//6180 6181//6181 -f 6168//6168 6181//6181 6172//6172 -f 6172//6172 6181//6181 6182//6182 -f 6172//6172 6182//6182 6170//6170 -f 6170//6170 6182//6182 6183//6183 -f 6170//6170 6183//6183 6171//6171 -f 6171//6171 6183//6183 6184//6184 -f 6171//6171 6184//6184 6163//6163 -f 6163//6163 6184//6184 6173//6173 -f 6174//6174 5372//5372 6175//6175 -f 6175//6175 5372//5372 5371//5371 -f 6175//6175 5371//5371 6176//6176 -f 6176//6176 5371//5371 5362//5362 -f 6176//6176 5362//5362 6177//6177 -f 6177//6177 5362//5362 5361//5361 -f 6177//6177 5361//5361 6178//6178 -f 6178//6178 5361//5361 5359//5359 -f 6178//6178 5359//5359 6179//6179 -f 6179//6179 5359//5359 5358//5358 -f 6179//6179 5358//5358 6180//6180 -f 6180//6180 5358//5358 5367//5367 -f 6180//6180 5367//5367 6181//6181 -f 6181//6181 5367//5367 5366//5366 -f 6181//6181 5366//5366 6182//6182 -f 6182//6182 5366//5366 5365//5365 -f 6182//6182 5365//5365 6183//6183 -f 6183//6183 5365//5365 5364//5364 -f 6183//6183 5364//5364 6184//6184 -f 6184//6184 5364//5364 5363//5363 -f 6184//6184 5363//5363 6173//6173 -f 6173//6173 5363//5363 5373//5373 -f 6173//6173 5373//5373 6174//6174 -f 6174//6174 5373//5373 5372//5372 -f 5498//5498 6185//6185 5500//5500 -f 5500//5500 6185//6185 6186//6186 -f 5500//5500 6186//6186 5501//5501 -f 5501//5501 6186//6186 6187//6187 -f 5501//5501 6187//6187 5502//5502 -f 5502//5502 6187//6187 6188//6188 -f 5502//5502 6188//6188 5503//5503 -f 5503//5503 6188//6188 6189//6189 -f 5503//5503 6189//6189 5505//5505 -f 5505//5505 6189//6189 6190//6190 -f 5505//5505 6190//6190 5507//5507 -f 5507//5507 6190//6190 6191//6191 -f 5507//5507 6191//6191 5509//5509 -f 5509//5509 6191//6191 6192//6192 -f 5509//5509 6192//6192 5510//5510 -f 5510//5510 6192//6192 6193//6193 -f 5510//5510 6193//6193 5493//5493 -f 5493//5493 6193//6193 6194//6194 -f 5493//5493 6194//6194 5494//5494 -f 5494//5494 6194//6194 6195//6195 -f 5494//5494 6195//6195 5496//5496 -f 5496//5496 6195//6195 6196//6196 -f 5496//5496 6196//6196 5498//5498 -f 5498//5498 6196//6196 6185//6185 -f 6186//6186 6076//6076 6187//6187 -f 6187//6187 6076//6076 6084//6084 -f 6187//6187 6084//6084 6188//6188 -f 6188//6188 6084//6084 6082//6082 -f 6188//6188 6082//6082 6189//6189 -f 6189//6189 6082//6082 6083//6083 -f 6189//6189 6083//6083 6190//6190 -f 6190//6190 6083//6083 6079//6079 -f 6190//6190 6079//6079 6191//6191 -f 6191//6191 6079//6079 6080//6080 -f 6191//6191 6080//6080 6192//6192 -f 6192//6192 6080//6080 6081//6081 -f 6192//6192 6081//6081 6193//6193 -f 6193//6193 6081//6081 6077//6077 -f 6193//6193 6077//6077 6194//6194 -f 6194//6194 6077//6077 6078//6078 -f 6194//6194 6078//6078 6195//6195 -f 6195//6195 6078//6078 6073//6073 -f 6195//6195 6073//6073 6196//6196 -f 6196//6196 6073//6073 6074//6074 -f 6196//6196 6074//6074 6185//6185 -f 6185//6185 6074//6074 6075//6075 -f 6185//6185 6075//6075 6186//6186 -f 6186//6186 6075//6075 6076//6076 -f 5515//5515 6197//6197 5516//5516 -f 5516//5516 6197//6197 6198//6198 -f 5516//5516 6198//6198 5606//5606 -f 5606//5606 6198//6198 6199//6199 -f 5606//5606 6199//6199 5517//5517 -f 5517//5517 6199//6199 6200//6200 -f 5517//5517 6200//6200 5518//5518 -f 5518//5518 6200//6200 6201//6201 -f 5518//5518 6201//6201 5520//5520 -f 5520//5520 6201//6201 6202//6202 -f 5520//5520 6202//6202 5522//5522 -f 5522//5522 6202//6202 6203//6203 -f 5522//5522 6203//6203 5523//5523 -f 5523//5523 6203//6203 6204//6204 -f 5523//5523 6204//6204 5614//5614 -f 5614//5614 6204//6204 6205//6205 -f 5614//5614 6205//6205 5511//5511 -f 5511//5511 6205//6205 6206//6206 -f 5511//5511 6206//6206 5512//5512 -f 5512//5512 6206//6206 6207//6207 -f 5512//5512 6207//6207 5514//5514 -f 5514//5514 6207//6207 6208//6208 -f 5514//5514 6208//6208 5515//5515 -f 5515//5515 6208//6208 6197//6197 -f 6198//6198 5077//5077 6199//6199 -f 6199//6199 5077//5077 4800//4800 -f 6199//6199 4800//4800 6200//6200 -f 6200//6200 4800//4800 4802//4802 -f 6200//6200 4802//4802 6201//6201 -f 6201//6201 4802//4802 4804//4804 -f 6201//6201 4804//4804 6202//6202 -f 6202//6202 4804//4804 4813//4813 -f 6202//6202 4813//4813 6203//6203 -f 6203//6203 4813//4813 4815//4815 -f 6203//6203 4815//4815 6204//6204 -f 6204//6204 4815//4815 4817//4817 -f 6204//6204 4817//4817 6205//6205 -f 6205//6205 4817//4817 4812//4812 -f 6205//6205 4812//4812 6206//6206 -f 6206//6206 4812//4812 4811//4811 -f 6206//6206 4811//4811 6207//6207 -f 6207//6207 4811//4811 4809//4809 -f 6207//6207 4809//4809 6208//6208 -f 6208//6208 4809//4809 4808//4808 -f 6208//6208 4808//4808 6197//6197 -f 6197//6197 4808//4808 4807//4807 -f 6197//6197 4807//4807 6198//6198 -f 6198//6198 4807//4807 5077//5077 -f 5534//5534 6209//6209 5535//5535 -f 5535//5535 6209//6209 6210//6210 -f 5535//5535 6210//6210 5536//5536 -f 5536//5536 6210//6210 6211//6211 -f 5536//5536 6211//6211 5539//5539 -f 5539//5539 6211//6211 6212//6212 -f 5539//5539 6212//6212 5537//5537 -f 5537//5537 6212//6212 6213//6213 -f 5537//5537 6213//6213 5528//5528 -f 5528//5528 6213//6213 6214//6214 -f 5528//5528 6214//6214 5526//5526 -f 5526//5526 6214//6214 6215//6215 -f 5526//5526 6215//6215 5524//5524 -f 5524//5524 6215//6215 6216//6216 -f 5524//5524 6216//6216 5531//5531 -f 5531//5531 6216//6216 6217//6217 -f 5531//5531 6217//6217 5532//5532 -f 5532//5532 6217//6217 6218//6218 -f 5532//5532 6218//6218 5533//5533 -f 5533//5533 6218//6218 6219//6219 -f 5533//5533 6219//6219 5529//5529 -f 5529//5529 6219//6219 6220//6220 -f 5529//5529 6220//6220 5534//5534 -f 5534//5534 6220//6220 6209//6209 -f 6210//6210 5107//5107 6211//6211 -f 6211//6211 5107//5107 5106//5106 -f 6211//6211 5106//5106 6212//6212 -f 6212//6212 5106//5106 5111//5111 -f 6212//6212 5111//5111 6213//6213 -f 6213//6213 5111//5111 5110//5110 -f 6213//6213 5110//5110 6214//6214 -f 6214//6214 5110//5110 5109//5109 -f 6214//6214 5109//5109 6215//6215 -f 6215//6215 5109//5109 5108//5108 -f 6215//6215 5108//5108 6216//6216 -f 6216//6216 5108//5108 5116//5116 -f 6216//6216 5116//5116 6217//6217 -f 6217//6217 5116//5116 5115//5115 -f 6217//6217 5115//5115 6218//6218 -f 6218//6218 5115//5115 5113//5113 -f 6218//6218 5113//5113 6219//6219 -f 6219//6219 5113//5113 5112//5112 -f 6219//6219 5112//5112 6220//6220 -f 6220//6220 5112//5112 5105//5105 -f 6220//6220 5105//5105 6209//6209 -f 6209//6209 5105//5105 5104//5104 -f 6209//6209 5104//5104 6210//6210 -f 6210//6210 5104//5104 5107//5107 -f 5547//5547 6221//6221 5548//5548 -f 5548//5548 6221//6221 6222//6222 -f 5548//5548 6222//6222 5550//5550 -f 5550//5550 6222//6222 6223//6223 -f 5550//5550 6223//6223 5551//5551 -f 5551//5551 6223//6223 6224//6224 -f 5551//5551 6224//6224 5552//5552 -f 5552//5552 6224//6224 6225//6225 -f 5552//5552 6225//6225 5553//5553 -f 5553//5553 6225//6225 6226//6226 -f 5553//5553 6226//6226 5546//5546 -f 5546//5546 6226//6226 6227//6227 -f 5546//5546 6227//6227 5540//5540 -f 5540//5540 6227//6227 6228//6228 -f 5540//5540 6228//6228 5541//5541 -f 5541//5541 6228//6228 6229//6229 -f 5541//5541 6229//6229 5542//5542 -f 5542//5542 6229//6229 6230//6230 -f 5542//5542 6230//6230 5543//5543 -f 5543//5543 6230//6230 6231//6231 -f 5543//5543 6231//6231 5544//5544 -f 5544//5544 6231//6231 6232//6232 -f 5544//5544 6232//6232 5547//5547 -f 5547//5547 6232//6232 6221//6221 -f 6222//6222 5172//5172 6223//6223 -f 6223//6223 5172//5172 5173//5173 -f 6223//6223 5173//5173 6224//6224 -f 6224//6224 5173//5173 5171//5171 -f 6224//6224 5171//5171 6225//6225 -f 6225//6225 5171//5171 5170//5170 -f 6225//6225 5170//5170 6226//6226 -f 6226//6226 5170//5170 5169//5169 -f 6226//6226 5169//5169 6227//6227 -f 6227//6227 5169//5169 5162//5162 -f 6227//6227 5162//5162 6228//6228 -f 6228//6228 5162//5162 5161//5161 -f 6228//6228 5161//5161 6229//6229 -f 6229//6229 5161//5161 5165//5165 -f 6229//6229 5165//5165 6230//6230 -f 6230//6230 5165//5165 5164//5164 -f 6230//6230 5164//5164 6231//6231 -f 6231//6231 5164//5164 5163//5163 -f 6231//6231 5163//5163 6232//6232 -f 6232//6232 5163//5163 5160//5160 -f 6232//6232 5160//5160 6221//6221 -f 6221//6221 5160//5160 5159//5159 -f 6221//6221 5159//5159 6222//6222 -f 6222//6222 5159//5159 5172//5172 -f 5558//5558 6233//6233 5559//5559 -f 5559//5559 6233//6233 6234//6234 -f 5559//5559 6234//6234 5598//5598 -f 5598//5598 6234//6234 6235//6235 -f 5598//5598 6235//6235 5560//5560 -f 5560//5560 6235//6235 6236//6236 -f 5560//5560 6236//6236 5561//5561 -f 5561//5561 6236//6236 6237//6237 -f 5561//5561 6237//6237 5563//5563 -f 5563//5563 6237//6237 6238//6238 -f 5563//5563 6238//6238 5564//5564 -f 5564//5564 6238//6238 6239//6239 -f 5564//5564 6239//6239 5566//5566 -f 5566//5566 6239//6239 6240//6240 -f 5566//5566 6240//6240 5601//5601 -f 5601//5601 6240//6240 6241//6241 -f 5601//5601 6241//6241 5554//5554 -f 5554//5554 6241//6241 6242//6242 -f 5554//5554 6242//6242 5555//5555 -f 5555//5555 6242//6242 6243//6243 -f 5555//5555 6243//6243 5556//5556 -f 5556//5556 6243//6243 6244//6244 -f 5556//5556 6244//6244 5558//5558 -f 5558//5558 6244//6244 6233//6233 -f 6234//6234 4986//4986 6235//6235 -f 6235//6235 4986//4986 4988//4988 -f 6235//6235 4988//4988 6236//6236 -f 6236//6236 4988//4988 4989//4989 -f 6236//6236 4989//4989 6237//6237 -f 6237//6237 4989//4989 4992//4992 -f 6237//6237 4992//4992 6238//6238 -f 6238//6238 4992//4992 5097//5097 -f 6238//6238 5097//5097 6239//6239 -f 6239//6239 5097//5097 5099//5099 -f 6239//6239 5099//5099 6240//6240 -f 6240//6240 5099//5099 5101//5101 -f 6240//6240 5101//5101 6241//6241 -f 6241//6241 5101//5101 5102//5102 -f 6241//6241 5102//5102 6242//6242 -f 6242//6242 5102//5102 5086//5086 -f 6242//6242 5086//5086 6243//6243 -f 6243//6243 5086//5086 5085//5085 -f 6243//6243 5085//5085 6244//6244 -f 6244//6244 5085//5085 5094//5094 -f 6244//6244 5094//5094 6233//6233 -f 6233//6233 5094//5094 4984//4984 -f 6233//6233 4984//4984 6234//6234 -f 6234//6234 4984//4984 4986//4986 -f 5572//5572 6245//6245 5567//5567 -f 5567//5567 6245//6245 6246//6246 -f 5567//5567 6246//6246 5568//5568 -f 5568//5568 6246//6246 6247//6247 -f 5568//5568 6247//6247 5569//5569 -f 5569//5569 6247//6247 6248//6248 -f 5569//5569 6248//6248 5570//5570 -f 5570//5570 6248//6248 6249//6249 -f 5570//5570 6249//6249 5571//5571 -f 5571//5571 6249//6249 6250//6250 -f 5571//5571 6250//6250 5575//5575 -f 5575//5575 6250//6250 6251//6251 -f 5575//5575 6251//6251 5576//5576 -f 5576//5576 6251//6251 6252//6252 -f 5576//5576 6252//6252 5577//5577 -f 5577//5577 6252//6252 6253//6253 -f 5577//5577 6253//6253 5580//5580 -f 5580//5580 6253//6253 6254//6254 -f 5580//5580 6254//6254 5578//5578 -f 5578//5578 6254//6254 6255//6255 -f 5578//5578 6255//6255 5574//5574 -f 5574//5574 6255//6255 6256//6256 -f 5574//5574 6256//6256 5572//5572 -f 5572//5572 6256//6256 6245//6245 -f 6246//6246 5181//5181 6247//6247 -f 6247//6247 5181//5181 5191//5191 -f 6247//6247 5191//5191 6248//6248 -f 6248//6248 5191//5191 5190//5190 -f 6248//6248 5190//5190 6249//6249 -f 6249//6249 5190//5190 5189//5189 -f 6249//6249 5189//5189 6250//6250 -f 6250//6250 5189//5189 5188//5188 -f 6250//6250 5188//5188 6251//6251 -f 6251//6251 5188//5188 5187//5187 -f 6251//6251 5187//5187 6252//6252 -f 6252//6252 5187//5187 5186//5186 -f 6252//6252 5186//5186 6253//6253 -f 6253//6253 5186//5186 5183//5183 -f 6253//6253 5183//5183 6254//6254 -f 6254//6254 5183//5183 5184//5184 -f 6254//6254 5184//5184 6255//6255 -f 6255//6255 5184//5184 5185//5185 -f 6255//6255 5185//5185 6256//6256 -f 6256//6256 5185//5185 5180//5180 -f 6256//6256 5180//5180 6245//6245 -f 6245//6245 5180//5180 5179//5179 -f 6245//6245 5179//5179 6246//6246 -f 6246//6246 5179//5179 5181//5181 -f 5581//5581 6257//6257 5582//5582 -f 5582//5582 6257//6257 6258//6258 -f 5582//5582 6258//6258 5583//5583 -f 5583//5583 6258//6258 6259//6259 -f 5583//5583 6259//6259 5586//5586 -f 5586//5586 6259//6259 6260//6260 -f 5586//5586 6260//6260 5587//5587 -f 5587//5587 6260//6260 6261//6261 -f 5587//5587 6261//6261 5588//5588 -f 5588//5588 6261//6261 6262//6262 -f 5588//5588 6262//6262 5593//5593 -f 5593//5593 6262//6262 6263//6263 -f 5593//5593 6263//6263 5594//5594 -f 5594//5594 6263//6263 6264//6264 -f 5594//5594 6264//6264 5596//5596 -f 5596//5596 6264//6264 6265//6265 -f 5596//5596 6265//6265 5592//5592 -f 5592//5592 6265//6265 6266//6266 -f 5592//5592 6266//6266 5591//5591 -f 5591//5591 6266//6266 6267//6267 -f 5591//5591 6267//6267 5584//5584 -f 5584//5584 6267//6267 6268//6268 -f 5584//5584 6268//6268 5581//5581 -f 5581//5581 6268//6268 6257//6257 -f 6258//6258 5125//5125 6259//6259 -f 6259//6259 5125//5125 5124//5124 -f 6259//6259 5124//5124 6260//6260 -f 6260//6260 5124//5124 5122//5122 -f 6260//6260 5122//5122 6261//6261 -f 6261//6261 5122//5122 5129//5129 -f 6261//6261 5129//5129 6262//6262 -f 6262//6262 5129//5129 5128//5128 -f 6262//6262 5128//5128 6263//6263 -f 6263//6263 5128//5128 5133//5133 -f 6263//6263 5133//5133 6264//6264 -f 6264//6264 5133//5133 5132//5132 -f 6264//6264 5132//5132 6265//6265 -f 6265//6265 5132//5132 5131//5131 -f 6265//6265 5131//5131 6266//6266 -f 6266//6266 5131//5131 5130//5130 -f 6266//6266 5130//5130 6267//6267 -f 6267//6267 5130//5130 5118//5118 -f 6267//6267 5118//5118 6268//6268 -f 6268//6268 5118//5118 5117//5117 -f 6268//6268 5117//5117 6257//6257 -f 6257//6257 5117//5117 5120//5120 -f 6257//6257 5120//5120 6258//6258 -f 6258//6258 5120//5120 5125//5125 -f 5724//5724 5723//5723 5726//5726 -f 5724//5724 5726//5726 6269//6269 -f 6269//6269 5726//5726 5727//5727 -f 6269//6269 5727//5727 6270//6270 -f 6270//6270 5727//5727 4792//4792 -f 6270//6270 4792//4792 4791//4791 -f 4818//4818 6271//6271 6272//6272 -f 6271//6271 6273//6273 6274//6274 -f 6273//6273 5722//5722 5929//5929 -f 6273//6273 5929//5929 6274//6274 -f 6274//6274 5929//5929 5930//5930 -f 6274//6274 5930//5930 6275//6275 -f 6275//6275 5930//5930 5931//5931 -f 6275//6275 5931//5931 6276//6276 -f 6276//6276 5931//5931 5932//5932 -f 6276//6276 5932//5932 6277//6277 -f 6277//6277 5932//5932 5933//5933 -f 6277//6277 5933//5933 6278//6278 -f 6278//6278 5933//5933 5934//5934 -f 6278//6278 5934//5934 6279//6279 -f 6279//6279 5934//5934 5935//5935 -f 6279//6279 5935//5935 6280//6280 -f 6280//6280 5935//5935 5936//5936 -f 6280//6280 5936//5936 6281//6281 -f 6281//6281 5936//5936 5937//5937 -f 6281//6281 5937//5937 6282//6282 -f 6282//6282 5937//5937 5724//5724 -f 6282//6282 5724//5724 6269//6269 -f 6271//6271 6274//6274 6272//6272 -f 6272//6272 6274//6274 6275//6275 -f 6272//6272 6275//6275 6283//6283 -f 6283//6283 6275//6275 6276//6276 -f 6283//6283 6276//6276 6284//6284 -f 6284//6284 6276//6276 6277//6277 -f 6284//6284 6277//6277 6285//6285 -f 6285//6285 6277//6277 6278//6278 -f 6285//6285 6278//6278 6286//6286 -f 6286//6286 6278//6278 6279//6279 -f 6286//6286 6279//6279 6287//6287 -f 6287//6287 6279//6279 6280//6280 -f 6287//6287 6280//6280 6288//6288 -f 6288//6288 6280//6280 6281//6281 -f 6288//6288 6281//6281 6289//6289 -f 6289//6289 6281//6281 6282//6282 -f 6289//6289 6282//6282 6290//6290 -f 6290//6290 6282//6282 6269//6269 -f 6290//6290 6269//6269 6270//6270 -f 4818//4818 6272//6272 4819//4819 -f 4819//4819 6272//6272 6283//6283 -f 4819//4819 6283//6283 4810//4810 -f 4810//4810 6283//6283 6284//6284 -f 4810//4810 6284//6284 4977//4977 -f 4977//4977 6284//6284 6285//6285 -f 4977//4977 6285//6285 4978//4978 -f 4978//4978 6285//6285 6286//6286 -f 4978//4978 6286//6286 4981//4981 -f 4981//4981 6286//6286 6287//6287 -f 4981//4981 6287//6287 4982//4982 -f 4982//4982 6287//6287 6288//6288 -f 4982//4982 6288//6288 4983//4983 -f 4983//4983 6288//6288 6289//6289 -f 4983//4983 6289//6289 4980//4980 -f 4980//4980 6289//6289 6290//6290 -f 4980//4980 6290//6290 4979//4979 -f 4979//4979 6290//6290 6270//6270 -f 4979//4979 6270//6270 4791//4791 -f 5100//5100 5098//5098 6291//6291 -f 5721//5721 5722//5722 6273//6273 -f 5721//5721 6273//6273 6292//6292 -f 6292//6292 6273//6273 6271//6271 -f 6292//6292 6271//6271 6291//6291 -f 4818//4818 4816//4816 6271//6271 -f 6271//6271 4816//4816 4814//4814 -f 6271//6271 4814//4814 6291//6291 -f 6291//6291 4814//4814 5088//5088 -f 6291//6291 5088//5088 5100//5100 -f 4995//4995 6293//6293 6294//6294 -f 6293//6293 6295//6295 6296//6296 -f 6295//6295 5720//5720 5938//5938 -f 6295//6295 5938//5938 6296//6296 -f 6296//6296 5938//5938 5939//5939 -f 6296//6296 5939//5939 6297//6297 -f 6297//6297 5939//5939 5940//5940 -f 6297//6297 5940//5940 6298//6298 -f 6298//6298 5940//5940 5941//5941 -f 6298//6298 5941//5941 6299//6299 -f 6299//6299 5941//5941 5942//5942 -f 6299//6299 5942//5942 6300//6300 -f 6300//6300 5942//5942 5943//5943 -f 6300//6300 5943//5943 6301//6301 -f 6301//6301 5943//5943 5944//5944 -f 6301//6301 5944//5944 6302//6302 -f 6302//6302 5944//5944 5945//5945 -f 6302//6302 5945//5945 6303//6303 -f 6303//6303 5945//5945 5946//5946 -f 6303//6303 5946//5946 6304//6304 -f 6304//6304 5946//5946 5721//5721 -f 6304//6304 5721//5721 6292//6292 -f 6293//6293 6296//6296 6294//6294 -f 6294//6294 6296//6296 6297//6297 -f 6294//6294 6297//6297 6305//6305 -f 6305//6305 6297//6297 6298//6298 -f 6305//6305 6298//6298 6306//6306 -f 6306//6306 6298//6298 6299//6299 -f 6306//6306 6299//6299 6307//6307 -f 6307//6307 6299//6299 6300//6300 -f 6307//6307 6300//6300 6308//6308 -f 6308//6308 6300//6300 6301//6301 -f 6308//6308 6301//6301 6309//6309 -f 6309//6309 6301//6301 6302//6302 -f 6309//6309 6302//6302 6310//6310 -f 6310//6310 6302//6302 6303//6303 -f 6310//6310 6303//6303 6311//6311 -f 6311//6311 6303//6303 6304//6304 -f 6311//6311 6304//6304 6312//6312 -f 6312//6312 6304//6304 6292//6292 -f 6312//6312 6292//6292 6291//6291 -f 4995//4995 6294//6294 4996//4996 -f 4996//4996 6294//6294 6305//6305 -f 4996//4996 6305//6305 4997//4997 -f 4997//4997 6305//6305 6306//6306 -f 4997//4997 6306//6306 5205//5205 -f 5205//5205 6306//6306 6307//6307 -f 5205//5205 6307//6307 4990//4990 -f 4990//4990 6307//6307 6308//6308 -f 4990//4990 6308//6308 4991//4991 -f 4991//4991 6308//6308 6309//6309 -f 4991//4991 6309//6309 4994//4994 -f 4994//4994 6309//6309 6310//6310 -f 4994//4994 6310//6310 4993//4993 -f 4993//4993 6310//6310 6311//6311 -f 4993//4993 6311//6311 5095//5095 -f 5095//5095 6311//6311 6312//6312 -f 5095//5095 6312//6312 5096//5096 -f 5096//5096 6312//6312 6291//6291 -f 5096//5096 6291//6291 5098//5098 -f 5719//5719 5720//5720 6295//6295 -f 5719//5719 6295//6295 5794//5794 -f 5794//5794 6295//6295 6293//6293 -f 5794//5794 6293//6293 5793//5793 -f 5793//5793 6293//6293 4995//4995 -f 5793//5793 4995//4995 5001//5001 -f 5788//5788 4998//4998 4886//4886 -f 5788//5788 4886//4886 5783//5783 -f 5783//5783 4886//4886 4893//4893 -f 5783//5783 4893//4893 4895//4895 -f 5778//5778 4877//4877 4876//4876 -f 5778//5778 4876//4876 5773//5773 -f 5773//5773 4876//4876 4787//4787 -f 5773//5773 4787//4787 4942//4942 -f 5768//5768 4904//4904 5763//5763 -f 5763//5763 4904//4904 4910//4910 -f 5763//5763 4910//4910 4912//4912 -f 5753//5753 5758//5758 5217//5217 -f 5217//5217 5223//5223 5753//5753 -f 5753//5753 5223//5223 4799//4799 -f 5753//5753 4799//4799 4798//4798 -f 4946//4946 4945//4945 5746//5746 -f 5746//5746 4945//4945 5194//5194 -f 5746//5746 5194//5194 5741//5741 -f 5741//5741 5194//5194 4951//4951 -f 5741//5741 4951//4951 4950//4950 -f 4870//4870 4962//4962 5716//5716 -f 5715//5715 4956//4956 4863//4863 -f 5715//5715 4863//4863 5716//5716 -f 5716//5716 4863//4863 4867//4867 -f 5716//5716 4867//4867 4870//4870 -f 5144//5144 5703//5703 5143//5143 -f 5143//5143 5703//5703 5702//5702 -f 5143//5143 5702//5702 5142//5142 -f 5142//5142 5702//5702 5141//5141 -f 5140//5140 5656//5656 5139//5139 -f 5139//5139 5656//5656 5655//5655 -f 5139//5139 5655//5655 5138//5138 -f 4970//4970 4975//4975 5650//5650 -f 4970//4970 5650//5650 4969//4969 -f 4969//4969 5650//5650 5649//5649 -f 4969//4969 5649//5649 4968//4968 -f 5643//5643 5134//5134 5135//5135 -f 5643//5643 5135//5135 5644//5644 -f 5644//5644 5135//5135 5136//5136 -f 5644//5644 5136//5136 5137//5137 -f 5290//5290 5645//5645 5291//5291 -f 5291//5291 5645//5645 5646//5646 -f 5300//5300 5642//5642 5301//5301 -f 5301//5301 5642//5642 5641//5641 -f 5301//5301 5641//5641 5298//5298 -f 5303//5303 5651//5651 5304//5304 -f 5304//5304 5651//5651 5652//5652 -f 5288//5288 5648//5648 5289//5289 -f 5289//5289 5648//5648 5647//5647 -f 5309//5309 5657//5657 5310//5310 -f 5310//5310 5657//5657 5658//5658 -f 5619//5619 5654//5654 5618//5618 -f 5618//5618 5654//5654 5653//5653 -f 5487//5487 5704//5704 5488//5488 -f 5488//5488 5704//5704 5705//5705 -f 5326//5326 5701//5701 5325//5325 -f 5325//5325 5701//5701 5700//5700 -f 5409//5409 5786//5786 5408//5408 -f 5408//5408 5786//5786 5785//5785 -f 5405//5405 5790//5790 5394//5394 -f 5394//5394 5790//5790 5784//5784 -f 5394//5394 5784//5784 5395//5395 -f 5400//5400 5776//5776 5401//5401 -f 5401//5401 5776//5776 5775//5775 -f 5396//5396 5780//5780 5397//5397 -f 5397//5397 5780//5780 5774//5774 -f 5386//5386 5766//5766 5385//5385 -f 5385//5385 5766//5766 5765//5765 -f 5380//5380 5770//5770 5381//5381 -f 5381//5381 5770//5770 5764//5764 -f 5285//5285 5756//5756 5286//5286 -f 5286//5286 5756//5756 5755//5755 -f 5369//5369 5760//5760 5368//5368 -f 5368//5368 5760//5760 5754//5754 -f 5611//5611 5717//5717 5335//5335 -f 5335//5335 5717//5717 5718//5718 -f 5335//5335 5718//5718 5334//5334 -f 5336//5336 5714//5714 5337//5337 -f 5337//5337 5714//5714 5713//5713 -f 5349//5349 5748//5748 5348//5348 -f 5348//5348 5748//5748 5742//5742 -f 5354//5354 5744//5744 5352//5352 -f 5352//5352 5744//5744 5743//5743 -f 5792//5792 5000//5000 5791//5791 -f 5791//5791 5000//5000 4999//4999 -f 5782//5782 4881//4881 5781//5781 -f 5781//5781 4881//4881 4879//4879 -f 5772//5772 4943//4943 5771//5771 -f 5771//5771 4943//4943 4906//4906 -f 5762//5762 4901//4901 5761//5761 -f 5761//5761 4901//4901 4899//4899 -f 5752//5752 4797//4797 5751//5751 -f 5751//5751 4797//4797 4949//4949 -f 5750//5750 4949//4949 5749//5749 -f 5749//5749 4949//4949 4947//4947 -f 5728//5728 4794//4794 5725//5725 -f 5725//5725 4794//4794 4976//4976 -f 5730//5730 4972//4972 5729//5729 -f 5729//5729 4972//4972 4822//4822 -f 5732//5732 4847//4847 5731//5731 -f 5731//5731 4847//4847 4967//4967 -f 5734//5734 5003//5003 5733//5733 -f 5733//5733 5003//5003 4838//4838 -f 5738//5738 4963//4963 5737//5737 -f 5737//5737 4963//4963 4964//4964 -f 5736//5736 4964//4964 5735//5735 -f 5735//5735 4964//4964 4961//4961 -f 4957//4957 5739//5739 4958//4958 -f 4958//4958 5739//5739 5740//5740 -f 4958//4958 5740//5740 4953//4953 -f 4953//4953 5740//5740 4952//4952 -f 5952//5952 5057//5057 5126//5126 -f 5127//5127 5044//5044 5949//5949 -f 5127//5127 5949//5949 5126//5126 -f 5126//5126 5949//5949 5950//5950 -f 5126//5126 5950//5950 5952//5952 -f 5053//5053 5951//5951 5049//5049 -f 5049//5049 5951//5951 5947//5947 -f 5049//5049 5947//5947 5050//5050 -f 5050//5050 5947//5947 5948//5948 -f 5050//5050 5948//5948 5176//5176 -f 5067//5067 5065//5065 5958//5958 -f 5166//5166 5068//5068 5954//5954 -f 5954//5954 5068//5068 5067//5067 -f 5954//5954 5067//5067 5955//5955 -f 5955//5955 5067//5067 5958//5958 -f 5957//5957 5060//5060 5956//5956 -f 5956//5956 5060//5060 5059//5059 -f 5956//5956 5059//5059 5953//5953 -f 5953//5953 5059//5059 4789//4789 -f 5953//5953 4789//4789 4788//4788 -f 5951//5951 5053//5053 5052//5052 -f 5951//5951 5052//5052 5952//5952 -f 5952//5952 5052//5052 5055//5055 -f 5952//5952 5055//5055 5057//5057 -f 5953//5953 4788//4788 5168//5168 -f 5953//5953 5168//5168 5954//5954 -f 5954//5954 5168//5168 5167//5167 -f 5954//5954 5167//5167 5166//5166 -f 5798//5798 4925//4925 4924//4924 -f 5798//5798 4924//4924 6313//6313 -f 6313//6313 4924//4924 4923//4923 -f 6313//6313 4923//4923 6314//6314 -f 6314//6314 4923//4923 4929//4929 -f 6314//6314 4929//4929 5800//5800 -f 5806//5806 5804//5804 6315//6315 -f 5806//5806 6315//6315 6316//6316 -f 6316//6316 6315//6315 6317//6317 -f 6316//6316 6317//6317 6318//6318 -f 6318//6318 6317//6317 5797//5797 -f 6318//6318 5797//5797 5798//5798 -f 5795//5795 4921//4921 4920//4920 -f 5795//5795 4920//4920 6319//6319 -f 6319//6319 4920//4920 5231//5231 -f 6319//6319 5231//5231 6320//6320 -f 6320//6320 5231//5231 4927//4927 -f 6320//6320 4927//4927 5797//5797 -f 5800//5800 6321//6321 6322//6322 -f 5806//5806 6316//6316 6323//6323 -f 6321//6321 6324//6324 6322//6322 -f 6322//6322 6324//6324 6323//6323 -f 6322//6322 6323//6323 6325//6325 -f 6325//6325 6323//6323 6316//6316 -f 6325//6325 6316//6316 6318//6318 -f 5800//5800 6322//6322 6314//6314 -f 6314//6314 6322//6322 6325//6325 -f 6314//6314 6325//6325 6313//6313 -f 6313//6313 6325//6325 6318//6318 -f 6313//6313 6318//6318 5798//5798 -f 6324//6324 5806//5806 6323//6323 -f 6321//6321 6326//6326 6324//6324 -f 6324//6324 6326//6326 5806//5806 -f 5797//5797 6317//6317 6327//6327 -f 5804//5804 6328//6328 6329//6329 -f 6317//6317 6330//6330 6327//6327 -f 6327//6327 6330//6330 6329//6329 -f 6327//6327 6329//6329 6331//6331 -f 6331//6331 6329//6329 6328//6328 -f 6331//6331 6328//6328 6332//6332 -f 5797//5797 6327//6327 6320//6320 -f 6320//6320 6327//6327 6331//6331 -f 6320//6320 6331//6331 6319//6319 -f 6319//6319 6331//6331 6332//6332 -f 6319//6319 6332//6332 5795//5795 -f 6330//6330 5804//5804 6329//6329 -f 6317//6317 6315//6315 6330//6330 -f 6330//6330 6315//6315 5804//5804 -f 5799//5799 4937//4937 4935//4935 -f 5799//5799 4935//4935 6333//6333 -f 6333//6333 4935//4935 4934//4934 -f 6333//6333 4934//4934 6334//6334 -f 6334//6334 4934//4934 4932//4932 -f 6334//6334 4932//4932 5802//5802 -f 5805//5805 5806//5806 6326//6326 -f 5805//5805 6326//6326 6335//6335 -f 6335//6335 6326//6326 6321//6321 -f 6335//6335 6321//6321 6336//6336 -f 6336//6336 6321//6321 5800//5800 -f 6336//6336 5800//5800 5799//5799 -f 5804//5804 5803//5803 6337//6337 -f 5804//5804 6337//6337 6328//6328 -f 6328//6328 6337//6337 6338//6338 -f 6328//6328 6338//6338 6332//6332 -f 6332//6332 6338//6338 5796//5796 -f 6332//6332 5796//5796 5795//5795 -f 5801//5801 5036//5036 5034//5034 -f 5801//5801 5034//5034 6339//6339 -f 6339//6339 5034//5034 4955//4955 -f 6339//6339 4955//4955 6340//6340 -f 6340//6340 4955//4955 4941//4941 -f 6340//6340 4941//4941 5796//5796 -f 5802//5802 6341//6341 6342//6342 -f 5805//5805 6335//6335 6343//6343 -f 6341//6341 6344//6344 6342//6342 -f 6342//6342 6344//6344 6343//6343 -f 6342//6342 6343//6343 6345//6345 -f 6345//6345 6343//6343 6335//6335 -f 6345//6345 6335//6335 6336//6336 -f 5802//5802 6342//6342 6334//6334 -f 6334//6334 6342//6342 6345//6345 -f 6334//6334 6345//6345 6333//6333 -f 6333//6333 6345//6345 6336//6336 -f 6333//6333 6336//6336 5799//5799 -f 6344//6344 5805//5805 6343//6343 -f 6341//6341 6346//6346 6344//6344 -f 6344//6344 6346//6346 5805//5805 -f 5796//5796 6338//6338 6347//6347 -f 5803//5803 6348//6348 6349//6349 -f 6338//6338 6350//6350 6347//6347 -f 6347//6347 6350//6350 6349//6349 -f 6347//6347 6349//6349 6351//6351 -f 6351//6351 6349//6349 6348//6348 -f 6351//6351 6348//6348 6352//6352 -f 5796//5796 6347//6347 6340//6340 -f 6340//6340 6347//6347 6351//6351 -f 6340//6340 6351//6351 6339//6339 -f 6339//6339 6351//6351 6352//6352 -f 6339//6339 6352//6352 5801//5801 -f 6350//6350 5803//5803 6349//6349 -f 6338//6338 6337//6337 6350//6350 -f 6350//6350 6337//6337 5803//5803 -f 5803//5803 5805//5805 6346//6346 -f 5803//5803 6346//6346 6348//6348 -f 6348//6348 6346//6346 6341//6341 -f 6348//6348 6341//6341 6352//6352 -f 6352//6352 6341//6341 5802//5802 -f 6352//6352 5802//5802 5801//5801 -f 5810//5810 5028//5028 5027//5027 -f 5810//5810 5027//5027 6353//6353 -f 6353//6353 5027//5027 5026//5026 -f 6353//6353 5026//5026 6354//6354 -f 6354//6354 5026//5026 5025//5025 -f 6354//6354 5025//5025 5811//5811 -f 5809//5809 5810//5810 6355//6355 -f 5809//5809 6355//6355 6356//6356 -f 6356//6356 6355//6355 6357//6357 -f 6356//6356 6357//6357 6358//6358 -f 6358//6358 6357//6357 5818//5818 -f 6358//6358 5818//5818 5816//5816 -f 5807//5807 5011//5011 5013//5013 -f 5807//5807 5013//5013 6359//6359 -f 6359//6359 5013//5013 5022//5022 -f 6359//6359 5022//5022 6360//6360 -f 6360//6360 5022//5022 5024//5024 -f 6360//6360 5024//5024 5809//5809 -f 5811//5811 6361//6361 6362//6362 -f 5818//5818 6357//6357 6363//6363 -f 6361//6361 6364//6364 6362//6362 -f 6362//6362 6364//6364 6363//6363 -f 6362//6362 6363//6363 6365//6365 -f 6365//6365 6363//6363 6357//6357 -f 6365//6365 6357//6357 6355//6355 -f 5811//5811 6362//6362 6354//6354 -f 6354//6354 6362//6362 6365//6365 -f 6354//6354 6365//6365 6353//6353 -f 6353//6353 6365//6365 6355//6355 -f 6353//6353 6355//6355 5810//5810 -f 6364//6364 5818//5818 6363//6363 -f 6361//6361 6366//6366 6364//6364 -f 6364//6364 6366//6366 5818//5818 -f 5809//5809 6356//6356 6367//6367 -f 5816//5816 6368//6368 6369//6369 -f 6356//6356 6370//6370 6367//6367 -f 6367//6367 6370//6370 6369//6369 -f 6367//6367 6369//6369 6371//6371 -f 6371//6371 6369//6369 6368//6368 -f 6371//6371 6368//6368 6372//6372 -f 5809//5809 6367//6367 6360//6360 -f 6360//6360 6367//6367 6371//6371 -f 6360//6360 6371//6371 6359//6359 -f 6359//6359 6371//6371 6372//6372 -f 6359//6359 6372//6372 5807//5807 -f 6370//6370 5816//5816 6369//6369 -f 6356//6356 6358//6358 6370//6370 -f 6370//6370 6358//6358 5816//5816 -f 5812//5812 5030//5030 5035//5035 -f 5812//5812 5035//5035 6373//6373 -f 6373//6373 5035//5035 5043//5043 -f 6373//6373 5043//5043 6374//6374 -f 6374//6374 5043//5043 5042//5042 -f 6374//6374 5042//5042 5813//5813 -f 5811//5811 5812//5812 6375//6375 -f 5811//5811 6375//6375 6361//6361 -f 6361//6361 6375//6375 6376//6376 -f 6361//6361 6376//6376 6366//6366 -f 6366//6366 6376//6376 5817//5817 -f 6366//6366 5817//5817 5818//5818 -f 5808//5808 5807//5807 6372//6372 -f 5808//5808 6372//6372 6377//6377 -f 6377//6377 6372//6372 6368//6368 -f 6377//6377 6368//6368 6378//6378 -f 6378//6378 6368//6368 5816//5816 -f 6378//6378 5816//5816 5815//5815 -f 5814//5814 5037//5037 4841//4841 -f 5814//5814 4841//4841 6379//6379 -f 6379//6379 4841//4841 4840//4840 -f 6379//6379 4840//4840 6380//6380 -f 6380//6380 4840//4840 5008//5008 -f 6380//6380 5008//5008 5808//5808 -f 5813//5813 6381//6381 6382//6382 -f 5817//5817 6376//6376 6383//6383 -f 6381//6381 6384//6384 6382//6382 -f 6382//6382 6384//6384 6383//6383 -f 6382//6382 6383//6383 6385//6385 -f 6385//6385 6383//6383 6376//6376 -f 6385//6385 6376//6376 6375//6375 -f 5813//5813 6382//6382 6374//6374 -f 6374//6374 6382//6382 6385//6385 -f 6374//6374 6385//6385 6373//6373 -f 6373//6373 6385//6385 6375//6375 -f 6373//6373 6375//6375 5812//5812 -f 6384//6384 5817//5817 6383//6383 -f 6381//6381 6386//6386 6384//6384 -f 6384//6384 6386//6386 5817//5817 -f 5808//5808 6377//6377 6387//6387 -f 5815//5815 6388//6388 6389//6389 -f 6377//6377 6390//6390 6387//6387 -f 6387//6387 6390//6390 6389//6389 -f 6387//6387 6389//6389 6391//6391 -f 6391//6391 6389//6389 6388//6388 -f 6391//6391 6388//6388 6392//6392 -f 5808//5808 6387//6387 6380//6380 -f 6380//6380 6387//6387 6391//6391 -f 6380//6380 6391//6391 6379//6379 -f 6379//6379 6391//6391 6392//6392 -f 6379//6379 6392//6392 5814//5814 -f 6390//6390 5815//5815 6389//6389 -f 6377//6377 6378//6378 6390//6390 -f 6390//6390 6378//6378 5815//5815 -f 5813//5813 5814//5814 6392//6392 -f 5813//5813 6392//6392 6381//6381 -f 6381//6381 6392//6392 6388//6388 -f 6381//6381 6388//6388 6386//6386 -f 6386//6386 6388//6388 5815//5815 -f 6386//6386 5815//5815 5817//5817 -f 6025//6025 6393//6393 6026//6026 -f 6026//6026 6393//6393 6394//6394 -f 6026//6026 6394//6394 6047//6047 -f 6047//6047 6394//6394 6395//6395 -f 6047//6047 6395//6395 6048//6048 -f 6048//6048 6395//6395 6396//6396 -f 6048//6048 6396//6396 6049//6049 -f 6049//6049 6396//6396 6397//6397 -f 6049//6049 6397//6397 6003//6003 -f 6003//6003 6397//6397 6398//6398 -f 6003//6003 6398//6398 6004//6004 -f 6004//6004 6398//6398 6399//6399 -f 6004//6004 6399//6399 6022//6022 -f 6022//6022 6399//6399 6400//6400 -f 6022//6022 6400//6400 6023//6023 -f 6023//6023 6400//6400 6401//6401 -f 6023//6023 6401//6401 6044//6044 -f 6044//6044 6401//6401 6402//6402 -f 6044//6044 6402//6402 6045//6045 -f 6045//6045 6402//6402 6403//6403 -f 6045//6045 6403//6403 6046//6046 -f 6046//6046 6403//6403 6404//6404 -f 6046//6046 6404//6404 6018//6018 -f 6018//6018 6404//6404 6405//6405 -f 6018//6018 6405//6405 6019//6019 -f 6019//6019 6405//6405 6406//6406 -f 6019//6019 6406//6406 6041//6041 -f 6041//6041 6406//6406 6407//6407 -f 6041//6041 6407//6407 6042//6042 -f 6042//6042 6407//6407 6408//6408 -f 6042//6042 6408//6408 6043//6043 -f 6043//6043 6408//6408 6409//6409 -f 6043//6043 6409//6409 6040//6040 -f 6040//6040 6409//6409 6410//6410 -f 6040//6040 6410//6410 6038//6038 -f 6038//6038 6410//6410 6411//6411 -f 6038//6038 6411//6411 6017//6017 -f 6017//6017 6411//6411 6412//6412 -f 6017//6017 6412//6412 6015//6015 -f 6015//6015 6412//6412 6413//6413 -f 6015//6015 6413//6413 6013//6013 -f 6013//6013 6413//6413 6414//6414 -f 6013//6013 6414//6414 6035//6035 -f 6035//6035 6414//6414 6415//6415 -f 6035//6035 6415//6415 6036//6036 -f 6036//6036 6415//6415 6416//6416 -f 6036//6036 6416//6416 6037//6037 -f 6037//6037 6416//6416 6417//6417 -f 6037//6037 6417//6417 6011//6011 -f 6011//6011 6417//6417 6418//6418 -f 6011//6011 6418//6418 6012//6012 -f 6012//6012 6418//6418 6419//6419 -f 6012//6012 6419//6419 6009//6009 -f 6009//6009 6419//6419 6420//6420 -f 6009//6009 6420//6420 6053//6053 -f 6053//6053 6420//6420 6421//6421 -f 6053//6053 6421//6421 6054//6054 -f 6054//6054 6421//6421 6422//6422 -f 6054//6054 6422//6422 6055//6055 -f 6055//6055 6422//6422 6423//6423 -f 6055//6055 6423//6423 6031//6031 -f 6031//6031 6423//6423 6424//6424 -f 6031//6031 6424//6424 6032//6032 -f 6032//6032 6424//6424 6425//6425 -f 6032//6032 6425//6425 6050//6050 -f 6050//6050 6425//6425 6426//6426 -f 6050//6050 6426//6426 6051//6051 -f 6051//6051 6426//6426 6427//6427 -f 6051//6051 6427//6427 6052//6052 -f 6052//6052 6427//6427 6428//6428 -f 6052//6052 6428//6428 6029//6029 -f 6029//6029 6428//6428 6429//6429 -f 6029//6029 6429//6429 6030//6030 -f 6030//6030 6429//6429 6430//6430 -f 6030//6030 6430//6430 5999//5999 -f 5999//5999 6430//6430 6431//6431 -f 5999//5999 6431//6431 6000//6000 -f 6000//6000 6431//6431 6432//6432 -f 6000//6000 6432//6432 6025//6025 -f 6025//6025 6432//6432 6393//6393 -f 6432//6432 6433//6433 6393//6393 -f 6393//6393 6433//6433 6434//6434 -f 6393//6393 6434//6434 6394//6394 -f 6394//6394 6434//6434 6435//6435 -f 6394//6394 6435//6435 6395//6395 -f 6395//6395 6435//6435 6436//6436 -f 6395//6395 6436//6436 6396//6396 -f 6396//6396 6436//6436 6437//6437 -f 6396//6396 6437//6437 6397//6397 -f 6397//6397 6437//6437 6438//6438 -f 6397//6397 6438//6438 6398//6398 -f 6398//6398 6438//6438 6439//6439 -f 6398//6398 6439//6439 6399//6399 -f 6399//6399 6439//6439 6440//6440 -f 6399//6399 6440//6440 6400//6400 -f 6400//6400 6440//6440 6441//6441 -f 6400//6400 6441//6441 6401//6401 -f 6401//6401 6441//6441 6442//6442 -f 6401//6401 6442//6442 6402//6402 -f 6402//6402 6442//6442 6443//6443 -f 6402//6402 6443//6443 6403//6403 -f 6403//6403 6443//6443 6444//6444 -f 6403//6403 6444//6444 6404//6404 -f 6404//6404 6444//6444 6445//6445 -f 6404//6404 6445//6445 6405//6405 -f 6405//6405 6445//6445 6446//6446 -f 6405//6405 6446//6446 6406//6406 -f 6406//6406 6446//6446 6447//6447 -f 6406//6406 6447//6447 6407//6407 -f 6407//6407 6447//6447 6448//6448 -f 6407//6407 6448//6448 6408//6408 -f 6408//6408 6448//6448 6449//6449 -f 6408//6408 6449//6449 6409//6409 -f 6409//6409 6449//6449 6450//6450 -f 6409//6409 6450//6450 6410//6410 -f 6410//6410 6450//6450 6451//6451 -f 6410//6410 6451//6451 6411//6411 -f 6411//6411 6451//6451 6452//6452 -f 6411//6411 6452//6452 6412//6412 -f 6412//6412 6452//6452 6453//6453 -f 6412//6412 6453//6453 6413//6413 -f 6413//6413 6453//6453 6454//6454 -f 6413//6413 6454//6454 6414//6414 -f 6414//6414 6454//6454 6455//6455 -f 6414//6414 6455//6455 6415//6415 -f 6415//6415 6455//6455 6456//6456 -f 6415//6415 6456//6456 6416//6416 -f 6416//6416 6456//6456 6457//6457 -f 6416//6416 6457//6457 6417//6417 -f 6417//6417 6457//6457 6458//6458 -f 6417//6417 6458//6458 6418//6418 -f 6418//6418 6458//6458 6459//6459 -f 6418//6418 6459//6459 6419//6419 -f 6419//6419 6459//6459 6460//6460 -f 6419//6419 6460//6460 6420//6420 -f 6420//6420 6460//6460 6461//6461 -f 6420//6420 6461//6461 6421//6421 -f 6421//6421 6461//6461 6462//6462 -f 6421//6421 6462//6462 6422//6422 -f 6422//6422 6462//6462 6463//6463 -f 6422//6422 6463//6463 6423//6423 -f 6423//6423 6463//6463 6464//6464 -f 6423//6423 6464//6464 6424//6424 -f 6424//6424 6464//6464 6465//6465 -f 6424//6424 6465//6465 6425//6425 -f 6425//6425 6465//6465 6466//6466 -f 6425//6425 6466//6466 6426//6426 -f 6426//6426 6466//6466 6467//6467 -f 6426//6426 6467//6467 6427//6427 -f 6427//6427 6467//6467 6468//6468 -f 6427//6427 6468//6468 6428//6428 -f 6428//6428 6468//6468 6469//6469 -f 6428//6428 6469//6469 6429//6429 -f 6429//6429 6469//6469 6470//6470 -f 6429//6429 6470//6470 6430//6430 -f 6430//6430 6470//6470 6471//6471 -f 6430//6430 6471//6471 6431//6431 -f 6431//6431 6471//6471 6472//6472 -f 6431//6431 6472//6472 6432//6432 -f 6432//6432 6472//6472 6433//6433 -f 6472//6472 5978//5978 6433//6433 -f 6433//6433 5978//5978 5981//5981 -f 6433//6433 5981//5981 6434//6434 -f 6434//6434 5981//5981 5980//5980 -f 6434//6434 5980//5980 6435//6435 -f 6435//6435 5980//5980 5983//5983 -f 6435//6435 5983//5983 6436//6436 -f 6436//6436 5983//5983 5982//5982 -f 6436//6436 5982//5982 6437//6437 -f 6437//6437 5982//5982 5985//5985 -f 6437//6437 5985//5985 6438//6438 -f 6438//6438 5985//5985 5984//5984 -f 6438//6438 5984//5984 6439//6439 -f 6439//6439 5984//5984 5987//5987 -f 6439//6439 5987//5987 6440//6440 -f 6440//6440 5987//5987 5986//5986 -f 6440//6440 5986//5986 6441//6441 -f 6441//6441 5986//5986 5989//5989 -f 6441//6441 5989//5989 6442//6442 -f 6442//6442 5989//5989 5988//5988 -f 6442//6442 5988//5988 6443//6443 -f 6443//6443 5988//5988 5991//5991 -f 6443//6443 5991//5991 6444//6444 -f 6444//6444 5991//5991 5990//5990 -f 6444//6444 5990//5990 6445//6445 -f 6445//6445 5990//5990 5993//5993 -f 6445//6445 5993//5993 6446//6446 -f 6446//6446 5993//5993 5992//5992 -f 6446//6446 5992//5992 6447//6447 -f 6447//6447 5992//5992 5995//5995 -f 6447//6447 5995//5995 6448//6448 -f 6448//6448 5995//5995 5994//5994 -f 6448//6448 5994//5994 6449//6449 -f 6449//6449 5994//5994 5998//5998 -f 6449//6449 5998//5998 6450//6450 -f 6450//6450 5998//5998 5997//5997 -f 6450//6450 5997//5997 6451//6451 -f 6451//6451 5997//5997 5996//5996 -f 6451//6451 5996//5996 6452//6452 -f 6452//6452 5996//5996 5959//5959 -f 6452//6452 5959//5959 6453//6453 -f 6453//6453 5959//5959 5961//5961 -f 6453//6453 5961//5961 6454//6454 -f 6454//6454 5961//5961 5960//5960 -f 6454//6454 5960//5960 6455//6455 -f 6455//6455 5960//5960 5963//5963 -f 6455//6455 5963//5963 6456//6456 -f 6456//6456 5963//5963 5962//5962 -f 6456//6456 5962//5962 6457//6457 -f 6457//6457 5962//5962 5965//5965 -f 6457//6457 5965//5965 6458//6458 -f 6458//6458 5965//5965 5964//5964 -f 6458//6458 5964//5964 6459//6459 -f 6459//6459 5964//5964 5967//5967 -f 6459//6459 5967//5967 6460//6460 -f 6460//6460 5967//5967 5966//5966 -f 6460//6460 5966//5966 6461//6461 -f 6461//6461 5966//5966 5969//5969 -f 6461//6461 5969//5969 6462//6462 -f 6462//6462 5969//5969 5968//5968 -f 6462//6462 5968//5968 6463//6463 -f 6463//6463 5968//5968 5971//5971 -f 6463//6463 5971//5971 6464//6464 -f 6464//6464 5971//5971 5970//5970 -f 6464//6464 5970//5970 6465//6465 -f 6465//6465 5970//5970 5973//5973 -f 6465//6465 5973//5973 6466//6466 -f 6466//6466 5973//5973 5972//5972 -f 6466//6466 5972//5972 6467//6467 -f 6467//6467 5972//5972 5975//5975 -f 6467//6467 5975//5975 6468//6468 -f 6468//6468 5975//5975 5974//5974 -f 6468//6468 5974//5974 6469//6469 -f 6469//6469 5974//5974 5977//5977 -f 6469//6469 5977//5977 6470//6470 -f 6470//6470 5977//5977 5976//5976 -f 6470//6470 5976//5976 6471//6471 -f 6471//6471 5976//5976 5979//5979 -f 6471//6471 5979//5979 6472//6472 -f 6472//6472 5979//5979 5978//5978 -f 6473//6473 6474//6474 6475//6475 -f 6476//6476 6477//6477 6474//6474 -f 6474//6474 6477//6477 6478//6478 -f 6474//6474 6478//6478 6475//6475 -f 6479//6479 6480//6480 6476//6476 -f 6476//6476 6480//6480 6481//6481 -f 6476//6476 6481//6481 6477//6477 -f 6482//6482 6483//6483 6479//6479 -f 6479//6479 6483//6483 6484//6484 -f 6479//6479 6484//6484 6480//6480 -f 6485//6485 6486//6486 6482//6482 -f 6482//6482 6486//6486 6487//6487 -f 6482//6482 6487//6487 6483//6483 -f 6488//6488 6489//6489 6485//6485 -f 6485//6485 6489//6489 6490//6490 -f 6485//6485 6490//6490 6486//6486 -f 6491//6491 6492//6492 6488//6488 -f 6488//6488 6492//6492 6493//6493 -f 6488//6488 6493//6493 6489//6489 -f 6494//6494 6495//6495 6491//6491 -f 6491//6491 6495//6495 6496//6496 -f 6491//6491 6496//6496 6492//6492 -f 6497//6497 6498//6498 6494//6494 -f 6494//6494 6498//6498 6499//6499 -f 6494//6494 6499//6499 6495//6495 -f 6500//6500 6501//6501 6497//6497 -f 6497//6497 6501//6501 6502//6502 -f 6497//6497 6502//6502 6498//6498 -f 6503//6503 6504//6504 6500//6500 -f 6500//6500 6504//6504 6505//6505 -f 6500//6500 6505//6505 6501//6501 -f 6506//6506 6507//6507 6503//6503 -f 6503//6503 6507//6507 6508//6508 -f 6503//6503 6508//6508 6504//6504 -f 6509//6509 6510//6510 6506//6506 -f 6506//6506 6510//6510 6511//6511 -f 6506//6506 6511//6511 6507//6507 -f 6512//6512 6513//6513 6509//6509 -f 6509//6509 6513//6513 6514//6514 -f 6509//6509 6514//6514 6510//6510 -f 6515//6515 6516//6516 6512//6512 -f 6512//6512 6516//6516 6517//6517 -f 6512//6512 6517//6517 6513//6513 -f 6518//6518 6519//6519 6515//6515 -f 6515//6515 6519//6519 6520//6520 -f 6515//6515 6520//6520 6516//6516 -f 6521//6521 6522//6522 6518//6518 -f 6518//6518 6522//6522 6523//6523 -f 6518//6518 6523//6523 6519//6519 -f 6524//6524 6525//6525 6521//6521 -f 6521//6521 6525//6525 6526//6526 -f 6521//6521 6526//6526 6522//6522 -f 6475//6475 6527//6527 6473//6473 -f 6473//6473 6527//6527 6528//6528 -f 6473//6473 6528//6528 6524//6524 -f 6524//6524 6528//6528 6529//6529 -f 6524//6524 6529//6529 6525//6525 -f 6530//6530 6531//6531 6532//6532 -f 6533//6533 6534//6534 6535//6535 -f 6535//6535 6534//6534 6536//6536 -f 6537//6537 6538//6538 6539//6539 -f 6540//6540 6541//6541 6542//6542 -f 6543//6543 6544//6544 6545//6545 -f 6545//6545 6544//6544 6546//6546 -f 6545//6545 6546//6546 6547//6547 -f 6548//6548 6549//6549 6543//6543 -f 6543//6543 6549//6549 6550//6550 -f 6543//6543 6550//6550 6544//6544 -f 6539//6539 6551//6551 6537//6537 -f 6537//6537 6551//6551 6552//6552 -f 6537//6537 6552//6552 6553//6553 -f 6547//6547 6546//6546 6536//6536 -f 6536//6536 6546//6546 6554//6554 -f 6536//6536 6554//6554 6535//6535 -f 6555//6555 6556//6556 6557//6557 -f 6557//6557 6556//6556 6558//6558 -f 6557//6557 6558//6558 6548//6548 -f 6548//6548 6558//6558 6559//6559 -f 6548//6548 6559//6559 6549//6549 -f 6560//6560 6561//6561 6557//6557 -f 6557//6557 6561//6561 6562//6562 -f 6557//6557 6562//6562 6555//6555 -f 6563//6563 6561//6561 6564//6564 -f 6564//6564 6561//6561 6560//6560 -f 6564//6564 6560//6560 6565//6565 -f 6565//6565 6560//6560 6566//6566 -f 6565//6565 6566//6566 6567//6567 -f 6567//6567 6566//6566 6541//6541 -f 6567//6567 6541//6541 6568//6568 -f 6568//6568 6541//6541 6540//6540 -f 6563//6563 6569//6569 6561//6561 -f 6561//6561 6569//6569 6570//6570 -f 6561//6561 6570//6570 6571//6571 -f 6571//6571 6570//6570 6572//6572 -f 6571//6571 6572//6572 6552//6552 -f 6552//6552 6572//6572 6573//6573 -f 6552//6552 6573//6573 6553//6553 -f 6562//6562 6574//6574 6555//6555 -f 6555//6555 6574//6574 6575//6575 -f 6555//6555 6575//6575 6576//6576 -f 6576//6576 6575//6575 6577//6577 -f 6576//6576 6577//6577 6578//6578 -f 6578//6578 6577//6577 6579//6579 -f 6578//6578 6579//6579 6580//6580 -f 6580//6580 6579//6579 6581//6581 -f 6580//6580 6581//6581 6538//6538 -f 6538//6538 6581//6581 6582//6582 -f 6538//6538 6582//6582 6539//6539 -f 6583//6583 6584//6584 6585//6585 -f 6586//6586 6587//6587 6588//6588 -f 6589//6589 6532//6532 6590//6590 -f 6588//6588 6587//6587 6584//6584 -f 6584//6584 6587//6587 6591//6591 -f 6584//6584 6591//6591 6585//6585 -f 6531//6531 6592//6592 6532//6532 -f 6532//6532 6592//6592 6593//6593 -f 6532//6532 6593//6593 6590//6590 -f 6537//6537 6594//6594 6538//6538 -f 6538//6538 6594//6594 6595//6595 -f 6538//6538 6595//6595 6596//6596 -f 6596//6596 6595//6595 6597//6597 -f 6588//6588 6598//6598 6586//6586 -f 6586//6586 6598//6598 6599//6599 -f 6586//6586 6599//6599 6531//6531 -f 6531//6531 6599//6599 6600//6600 -f 6531//6531 6600//6600 6592//6592 -f 6537//6537 6601//6601 6594//6594 -f 6594//6594 6601//6601 6602//6602 -f 6594//6594 6602//6602 6603//6603 -f 6603//6603 6602//6602 6604//6604 -f 6603//6603 6604//6604 6590//6590 -f 6590//6590 6604//6604 6605//6605 -f 6590//6590 6605//6605 6589//6589 -f 6585//6585 6606//6606 6583//6583 -f 6583//6583 6606//6606 6607//6607 -f 6583//6583 6607//6607 6595//6595 -f 6595//6595 6607//6607 6608//6608 -f 6595//6595 6608//6608 6597//6597 -f 6609//6609 6610//6610 6611//6611 -f 6611//6611 6612//6612 6609//6609 -f 6609//6609 6612//6612 6613//6613 -f 6609//6609 6613//6613 6532//6532 -f 6532//6532 6613//6613 6614//6614 -f 6532//6532 6614//6614 6530//6530 -f 6615//6615 6616//6616 6617//6617 -f 6617//6617 6616//6616 6540//6540 -f 6617//6617 6540//6540 6618//6618 -f 6615//6615 6617//6617 6619//6619 -f 6619//6619 6617//6617 6620//6620 -f 6619//6619 6620//6620 6621//6621 -f 6621//6621 6620//6620 6622//6622 -f 6621//6621 6622//6622 6623//6623 -f 6623//6623 6622//6622 6609//6609 -f 6609//6609 6622//6622 6624//6624 -f 6609//6609 6624//6624 6610//6610 -f 6624//6624 6625//6625 6610//6610 -f 6610//6610 6625//6625 6626//6626 -f 6610//6610 6626//6626 6627//6627 -f 6627//6627 6626//6626 6628//6628 -f 6627//6627 6628//6628 6629//6629 -f 6629//6629 6628//6628 6630//6630 -f 6629//6629 6630//6630 6631//6631 -f 6631//6631 6630//6630 6632//6632 -f 6631//6631 6632//6632 6633//6633 -f 6633//6633 6632//6632 6634//6634 -f 6633//6633 6634//6634 6635//6635 -f 6635//6635 6634//6634 6636//6636 -f 6542//6542 6533//6533 6540//6540 -f 6540//6540 6533//6533 6535//6535 -f 6540//6540 6535//6535 6618//6618 -f 6618//6618 6535//6535 6637//6637 -f 6618//6618 6637//6637 6638//6638 -f 6638//6638 6639//6639 6618//6618 -f 6618//6618 6639//6639 6640//6640 -f 6618//6618 6640//6640 6636//6636 -f 6636//6636 6640//6640 6641//6641 -f 6636//6636 6641//6641 6635//6635 -f 6642//6642 6643//6643 6644//6644 -f 6644//6644 6643//6643 6645//6645 -f 6644//6644 6645//6645 6646//6646 -f 6646//6646 6645//6645 6647//6647 -f 6646//6646 6647//6647 6648//6648 -f 6648//6648 6647//6647 6649//6649 -f 6648//6648 6649//6649 6650//6650 -f 6650//6650 6649//6649 6651//6651 -f 6650//6650 6651//6651 6652//6652 -f 6652//6652 6651//6651 6653//6653 -f 6652//6652 6653//6653 6654//6654 -f 6654//6654 6653//6653 6655//6655 -f 6654//6654 6655//6655 6656//6656 -f 6656//6656 6655//6655 6657//6657 -f 6656//6656 6657//6657 6658//6658 -f 6658//6658 6657//6657 6659//6659 -f 6658//6658 6659//6659 6660//6660 -f 6660//6660 6659//6659 6661//6661 -f 6660//6660 6661//6661 6662//6662 -f 6662//6662 6661//6661 6663//6663 -f 6662//6662 6663//6663 6664//6664 -f 6664//6664 6663//6663 6665//6665 -f 6664//6664 6665//6665 6666//6666 -f 6666//6666 6665//6665 6667//6667 -f 6666//6666 6667//6667 6668//6668 -f 6668//6668 6667//6667 6669//6669 -f 6668//6668 6669//6669 6670//6670 -f 6670//6670 6669//6669 6671//6671 -f 6670//6670 6671//6671 6672//6672 -f 6672//6672 6671//6671 6673//6673 -f 6672//6672 6673//6673 6674//6674 -f 6674//6674 6673//6673 6675//6675 -f 6674//6674 6675//6675 6676//6676 -f 6676//6676 6675//6675 6677//6677 -f 6676//6676 6677//6677 6678//6678 -f 6678//6678 6677//6677 6679//6679 -f 6678//6678 6679//6679 6680//6680 -f 6680//6680 6679//6679 6681//6681 -f 6680//6680 6681//6681 6682//6682 -f 6682//6682 6681//6681 6683//6683 -f 6682//6682 6683//6683 6684//6684 -f 6684//6684 6683//6683 6685//6685 -f 6684//6684 6685//6685 6686//6686 -f 6686//6686 6685//6685 6687//6687 -f 6686//6686 6687//6687 6688//6688 -f 6688//6688 6687//6687 6689//6689 -f 6688//6688 6689//6689 6690//6690 -f 6690//6690 6689//6689 6691//6691 -f 6690//6690 6691//6691 6692//6692 -f 6692//6692 6691//6691 6693//6693 -f 6692//6692 6693//6693 6694//6694 -f 6694//6694 6693//6693 6695//6695 -f 6694//6694 6695//6695 6696//6696 -f 6696//6696 6695//6695 6697//6697 -f 6696//6696 6697//6697 6698//6698 -f 6698//6698 6697//6697 6699//6699 -f 6698//6698 6699//6699 6700//6700 -f 6700//6700 6699//6699 6701//6701 -f 6700//6700 6701//6701 6702//6702 -f 6702//6702 6701//6701 6703//6703 -f 6702//6702 6703//6703 6704//6704 -f 6704//6704 6703//6703 6705//6705 -f 6704//6704 6705//6705 6706//6706 -f 6706//6706 6705//6705 6707//6707 -f 6706//6706 6707//6707 6708//6708 -f 6708//6708 6707//6707 6709//6709 -f 6708//6708 6709//6709 6710//6710 -f 6710//6710 6709//6709 6711//6711 -f 6710//6710 6711//6711 6712//6712 -f 6712//6712 6711//6711 6713//6713 -f 6712//6712 6713//6713 6714//6714 -f 6714//6714 6713//6713 6715//6715 -f 6714//6714 6715//6715 6716//6716 -f 6716//6716 6715//6715 6717//6717 -f 6716//6716 6717//6717 6642//6642 -f 6642//6642 6717//6717 6643//6643 -f 6718//6718 6719//6719 6720//6720 -f 6720//6720 6719//6719 6721//6721 -f 6721//6721 6719//6719 6722//6722 -f 6721//6721 6722//6722 6723//6723 -f 6723//6723 6722//6722 6724//6724 -f 6723//6723 6724//6724 6725//6725 -f 6725//6725 6724//6724 6726//6726 -f 6725//6725 6726//6726 6727//6727 -f 6727//6727 6726//6726 6728//6728 -f 6727//6727 6728//6728 6729//6729 -f 6729//6729 6730//6730 6731//6731 -f 6731//6731 6730//6730 6732//6732 -f 6731//6731 6732//6732 6733//6733 -f 6734//6734 6735//6735 6736//6736 -f 6720//6720 6737//6737 6718//6718 -f 6718//6718 6737//6737 6738//6738 -f 6718//6718 6738//6738 6739//6739 -f 6734//6734 6740//6740 6735//6735 -f 6735//6735 6740//6740 6741//6741 -f 6735//6735 6741//6741 6742//6742 -f 6736//6736 6743//6743 6734//6734 -f 6734//6734 6743//6743 6744//6744 -f 6734//6734 6744//6744 6745//6745 -f 6745//6745 6744//6744 6746//6746 -f 6745//6745 6746//6746 6732//6732 -f 6732//6732 6746//6746 6747//6747 -f 6732//6732 6747//6747 6733//6733 -f 6748//6748 6749//6749 6750//6750 -f 6750//6750 6749//6749 6751//6751 -f 6750//6750 6751//6751 6752//6752 -f 6752//6752 6751//6751 6753//6753 -f 6752//6752 6753//6753 6742//6742 -f 6742//6742 6753//6753 6754//6754 -f 6742//6742 6754//6754 6735//6735 -f 6755//6755 6756//6756 6757//6757 -f 6757//6757 6756//6756 6758//6758 -f 6740//6740 6718//6718 6741//6741 -f 6741//6741 6718//6718 6739//6739 -f 6741//6741 6739//6739 6759//6759 -f 6759//6759 6739//6739 6760//6760 -f 6759//6759 6760//6760 6761//6761 -f 6762//6762 6763//6763 6764//6764 -f 6764//6764 6763//6763 6758//6758 -f 6758//6758 6763//6763 6765//6765 -f 6758//6758 6765//6765 6757//6757 -f 6764//6764 6766//6766 6762//6762 -f 6762//6762 6766//6766 6767//6767 -f 6762//6762 6767//6767 6768//6768 -f 6768//6768 6767//6767 6761//6761 -f 6768//6768 6761//6761 6769//6769 -f 6769//6769 6761//6761 6760//6760 -f 6770//6770 6771//6771 6772//6772 -f 6772//6772 6771//6771 6773//6773 -f 6771//6771 6774//6774 6775//6775 -f 6775//6775 6774//6774 6776//6776 -f 6775//6775 6776//6776 6777//6777 -f 6777//6777 6776//6776 6778//6778 -f 6777//6777 6778//6778 6779//6779 -f 6779//6779 6778//6778 6780//6780 -f 6779//6779 6780//6780 6781//6781 -f 6781//6781 6780//6780 6782//6782 -f 6781//6781 6782//6782 6783//6783 -f 6783//6783 6782//6782 6784//6784 -f 6783//6783 6784//6784 6785//6785 -f 6785//6785 6784//6784 6786//6786 -f 6785//6785 6786//6786 6787//6787 -f 6750//6750 6755//6755 6748//6748 -f 6748//6748 6755//6755 6757//6757 -f 6748//6748 6757//6757 6788//6788 -f 6788//6788 6757//6757 6789//6789 -f 6787//6787 6786//6786 6790//6790 -f 6790//6790 6786//6786 6791//6791 -f 6790//6790 6791//6791 6792//6792 -f 6772//6772 6793//6793 6770//6770 -f 6770//6770 6793//6793 6794//6794 -f 6770//6770 6794//6794 6795//6795 -f 6795//6795 6794//6794 6796//6796 -f 6795//6795 6796//6796 6797//6797 -f 6797//6797 6796//6796 6798//6798 -f 6798//6798 6789//6789 6797//6797 -f 6797//6797 6789//6789 6757//6757 -f 6797//6797 6757//6757 6791//6791 -f 6791//6791 6757//6757 6799//6799 -f 6791//6791 6799//6799 6792//6792 -f 6771//6771 6775//6775 6773//6773 -f 6773//6773 6775//6775 6800//6800 -f 6773//6773 6800//6800 6801//6801 -f 6801//6801 6802//6802 6773//6773 -f 6773//6773 6802//6802 6803//6803 -f 6773//6773 6803//6803 6804//6804 -f 6805//6805 6806//6806 6807//6807 -f 6808//6808 6809//6809 6810//6810 -f 6811//6811 6773//6773 6812//6812 -f 6813//6813 6814//6814 6815//6815 -f 6810//6810 6809//6809 6806//6806 -f 6806//6806 6809//6809 6816//6816 -f 6806//6806 6816//6816 6807//6807 -f 6729//6729 6731//6731 6727//6727 -f 6727//6727 6731//6731 6817//6817 -f 6727//6727 6817//6817 6818//6818 -f 6810//6810 6819//6819 6808//6808 -f 6808//6808 6819//6819 6820//6820 -f 6808//6808 6820//6820 6821//6821 -f 6821//6821 6820//6820 6822//6822 -f 6821//6821 6822//6822 6804//6804 -f 6804//6804 6822//6822 6823//6823 -f 6804//6804 6823//6823 6773//6773 -f 6773//6773 6823//6823 6824//6824 -f 6773//6773 6824//6824 6812//6812 -f 6814//6814 6727//6727 6815//6815 -f 6815//6815 6727//6727 6818//6818 -f 6815//6815 6818//6818 6825//6825 -f 6825//6825 6818//6818 6826//6826 -f 6825//6825 6826//6826 6827//6827 -f 6827//6827 6826//6826 6828//6828 -f 6827//6827 6828//6828 6812//6812 -f 6812//6812 6828//6828 6829//6829 -f 6812//6812 6829//6829 6811//6811 -f 6807//6807 6830//6830 6805//6805 -f 6805//6805 6830//6830 6831//6831 -f 6805//6805 6831//6831 6815//6815 -f 6815//6815 6831//6831 6832//6832 -f 6815//6815 6832//6832 6813//6813 -f 6747//6747 6746//6746 6833//6833 -f 6833//6833 6834//6834 6747//6747 -f 6747//6747 6834//6834 6835//6835 -f 6747//6747 6835//6835 6733//6733 -f 6733//6733 6835//6835 6836//6836 -f 6733//6733 6836//6836 6731//6731 -f 6731//6731 6836//6836 6837//6837 -f 6731//6731 6837//6837 6817//6817 -f 6837//6837 6838//6838 6817//6817 -f 6817//6817 6838//6838 6839//6839 -f 6817//6817 6839//6839 6818//6818 -f 6839//6839 6840//6840 6818//6818 -f 6818//6818 6840//6840 6841//6841 -f 6818//6818 6841//6841 6826//6826 -f 6841//6841 6842//6842 6826//6826 -f 6826//6826 6842//6842 6843//6843 -f 6826//6826 6843//6843 6828//6828 -f 6843//6843 6844//6844 6828//6828 -f 6828//6828 6844//6844 6845//6845 -f 6828//6828 6845//6845 6829//6829 -f 6845//6845 6846//6846 6829//6829 -f 6829//6829 6846//6846 6847//6847 -f 6829//6829 6847//6847 6811//6811 -f 6847//6847 6848//6848 6811//6811 -f 6811//6811 6848//6848 6849//6849 -f 6811//6811 6849//6849 6773//6773 -f 6849//6849 6850//6850 6773//6773 -f 6773//6773 6850//6850 6851//6851 -f 6773//6773 6851//6851 6772//6772 -f 6851//6851 6852//6852 6772//6772 -f 6772//6772 6852//6852 6853//6853 -f 6772//6772 6853//6853 6793//6793 -f 6853//6853 6854//6854 6793//6793 -f 6793//6793 6854//6854 6855//6855 -f 6793//6793 6855//6855 6794//6794 -f 6855//6855 6856//6856 6794//6794 -f 6794//6794 6856//6856 6857//6857 -f 6794//6794 6857//6857 6796//6796 -f 6857//6857 6858//6858 6796//6796 -f 6796//6796 6858//6858 6859//6859 -f 6796//6796 6859//6859 6798//6798 -f 6859//6859 6860//6860 6798//6798 -f 6798//6798 6860//6860 6861//6861 -f 6798//6798 6861//6861 6789//6789 -f 6861//6861 6862//6862 6789//6789 -f 6789//6789 6862//6862 6863//6863 -f 6789//6789 6863//6863 6788//6788 -f 6788//6788 6863//6863 6864//6864 -f 6788//6788 6864//6864 6748//6748 -f 6748//6748 6864//6864 6865//6865 -f 6748//6748 6865//6865 6749//6749 -f 6865//6865 6866//6866 6749//6749 -f 6749//6749 6866//6866 6867//6867 -f 6749//6749 6867//6867 6751//6751 -f 6867//6867 6868//6868 6751//6751 -f 6751//6751 6868//6868 6869//6869 -f 6751//6751 6869//6869 6753//6753 -f 6869//6869 6870//6870 6753//6753 -f 6753//6753 6870//6870 6871//6871 -f 6753//6753 6871//6871 6754//6754 -f 6871//6871 6872//6872 6754//6754 -f 6754//6754 6872//6872 6873//6873 -f 6754//6754 6873//6873 6735//6735 -f 6873//6873 6874//6874 6735//6735 -f 6735//6735 6874//6874 6875//6875 -f 6735//6735 6875//6875 6736//6736 -f 6875//6875 6876//6876 6736//6736 -f 6736//6736 6876//6876 6877//6877 -f 6736//6736 6877//6877 6743//6743 -f 6877//6877 6878//6878 6743//6743 -f 6743//6743 6878//6878 6879//6879 -f 6743//6743 6879//6879 6744//6744 -f 6879//6879 6880//6880 6744//6744 -f 6744//6744 6880//6880 6881//6881 -f 6744//6744 6881//6881 6746//6746 -f 6746//6746 6881//6881 6882//6882 -f 6746//6746 6882//6882 6833//6833 -f 6883//6883 6884//6884 6885//6885 -f 6886//6886 6887//6887 6888//6888 -f 6888//6888 6887//6887 6889//6889 -f 6888//6888 6889//6889 6890//6890 -f 6890//6890 6889//6889 6891//6891 -f 6890//6890 6891//6891 6885//6885 -f 6885//6885 6891//6891 6892//6892 -f 6885//6885 6892//6892 6883//6883 -f 6893//6893 6894//6894 6895//6895 -f 6895//6895 6894//6894 6896//6896 -f 6895//6895 6896//6896 6897//6897 -f 6897//6897 6896//6896 6898//6898 -f 6897//6897 6898//6898 6886//6886 -f 6886//6886 6898//6898 6899//6899 -f 6886//6886 6899//6899 6887//6887 -f 6900//6900 6901//6901 6902//6902 -f 6902//6902 6901//6901 6903//6903 -f 6902//6902 6903//6903 6904//6904 -f 6904//6904 6903//6903 6905//6905 -f 6904//6904 6905//6905 6893//6893 -f 6893//6893 6905//6905 6906//6906 -f 6893//6893 6906//6906 6894//6894 -f 6883//6883 6907//6907 6884//6884 -f 6884//6884 6907//6907 6908//6908 -f 6884//6884 6908//6908 6909//6909 -f 6909//6909 6908//6908 6910//6910 -f 6909//6909 6910//6910 6911//6911 -f 6911//6911 6910//6910 6912//6912 -f 6911//6911 6912//6912 6913//6913 -f 6914//6914 6915//6915 6916//6916 -f 6916//6916 6915//6915 6917//6917 -f 6916//6916 6917//6917 6918//6918 -f 6918//6918 6917//6917 6919//6919 -f 6918//6918 6919//6919 6900//6900 -f 6900//6900 6919//6919 6920//6920 -f 6900//6900 6920//6920 6901//6901 -f 6912//6912 6921//6921 6913//6913 -f 6913//6913 6921//6921 6922//6922 -f 6913//6913 6922//6922 6923//6923 -f 6923//6923 6922//6922 6924//6924 -f 6923//6923 6924//6924 6925//6925 -f 6925//6925 6924//6924 6926//6926 -f 6925//6925 6926//6926 6914//6914 -f 6914//6914 6926//6926 6927//6927 -f 6914//6914 6927//6927 6915//6915 -f 6928//6928 6884//6884 6929//6929 -f 6929//6929 6884//6884 6909//6909 -f 6929//6929 6909//6909 6930//6930 -f 6930//6930 6909//6909 6911//6911 -f 6930//6930 6911//6911 6931//6931 -f 6931//6931 6911//6911 6913//6913 -f 6931//6931 6913//6913 6932//6932 -f 6932//6932 6913//6913 6923//6923 -f 6932//6932 6923//6923 6933//6933 -f 6933//6933 6923//6923 6925//6925 -f 6933//6933 6925//6925 6934//6934 -f 6934//6934 6925//6925 6914//6914 -f 6934//6934 6914//6914 6935//6935 -f 6935//6935 6914//6914 6916//6916 -f 6935//6935 6916//6916 6936//6936 -f 6936//6936 6916//6916 6918//6918 -f 6936//6936 6918//6918 6937//6937 -f 6937//6937 6918//6918 6900//6900 -f 6937//6937 6900//6900 6938//6938 -f 6938//6938 6900//6900 6902//6902 -f 6938//6938 6902//6902 6939//6939 -f 6939//6939 6902//6902 6904//6904 -f 6939//6939 6904//6904 6940//6940 -f 6940//6940 6904//6904 6893//6893 -f 6940//6940 6893//6893 6941//6941 -f 6941//6941 6893//6893 6895//6895 -f 6941//6941 6895//6895 6942//6942 -f 6942//6942 6895//6895 6897//6897 -f 6942//6942 6897//6897 6943//6943 -f 6943//6943 6897//6897 6886//6886 -f 6943//6943 6886//6886 6944//6944 -f 6944//6944 6886//6886 6888//6888 -f 6944//6944 6888//6888 6945//6945 -f 6945//6945 6888//6888 6890//6890 -f 6945//6945 6890//6890 6946//6946 -f 6946//6946 6890//6890 6885//6885 -f 6946//6946 6885//6885 6928//6928 -f 6928//6928 6885//6885 6884//6884 -f 6947//6947 6945//6945 6948//6948 -f 6948//6948 6945//6945 6946//6946 -f 6948//6948 6946//6946 6949//6949 -f 6949//6949 6946//6946 6928//6928 -f 6949//6949 6928//6928 6950//6950 -f 6951//6951 6939//6939 6952//6952 -f 6952//6952 6939//6939 6940//6940 -f 6952//6952 6940//6940 6953//6953 -f 6940//6940 6941//6941 6953//6953 -f 6953//6953 6941//6941 6942//6942 -f 6953//6953 6942//6942 6954//6954 -f 6954//6954 6942//6942 6943//6943 -f 6954//6954 6943//6943 6947//6947 -f 6947//6947 6943//6943 6944//6944 -f 6947//6947 6944//6944 6945//6945 -f 6955//6955 6936//6936 6956//6956 -f 6956//6956 6936//6936 6937//6937 -f 6956//6956 6937//6937 6951//6951 -f 6951//6951 6937//6937 6938//6938 -f 6951//6951 6938//6938 6939//6939 -f 6957//6957 6933//6933 6958//6958 -f 6958//6958 6933//6933 6934//6934 -f 6958//6958 6934//6934 6955//6955 -f 6955//6955 6934//6934 6935//6935 -f 6955//6955 6935//6935 6936//6936 -f 6928//6928 6929//6929 6950//6950 -f 6950//6950 6929//6929 6930//6930 -f 6950//6950 6930//6930 6959//6959 -f 6959//6959 6930//6930 6931//6931 -f 6959//6959 6931//6931 6957//6957 -f 6957//6957 6931//6931 6932//6932 -f 6957//6957 6932//6932 6933//6933 -f 6960//6960 6949//6949 6961//6961 -f 6961//6961 6949//6949 6950//6950 -f 6961//6961 6950//6950 6962//6962 -f 6962//6962 6950//6950 6959//6959 -f 6962//6962 6959//6959 6963//6963 -f 6963//6963 6959//6959 6957//6957 -f 6963//6963 6957//6957 6964//6964 -f 6964//6964 6957//6957 6958//6958 -f 6964//6964 6958//6958 6965//6965 -f 6965//6965 6958//6958 6955//6955 -f 6965//6965 6955//6955 6966//6966 -f 6966//6966 6955//6955 6956//6956 -f 6966//6966 6956//6956 6967//6967 -f 6967//6967 6956//6956 6951//6951 -f 6967//6967 6951//6951 6968//6968 -f 6968//6968 6951//6951 6952//6952 -f 6968//6968 6952//6952 6969//6969 -f 6969//6969 6952//6952 6953//6953 -f 6969//6969 6953//6953 6970//6970 -f 6970//6970 6953//6953 6954//6954 -f 6970//6970 6954//6954 6971//6971 -f 6971//6971 6954//6954 6947//6947 -f 6971//6971 6947//6947 6972//6972 -f 6972//6972 6947//6947 6948//6948 -f 6972//6972 6948//6948 6960//6960 -f 6960//6960 6948//6948 6949//6949 -f 6968//6968 6503//6503 6967//6967 -f 6967//6967 6503//6503 6500//6500 -f 6967//6967 6500//6500 6966//6966 -f 6970//6970 6512//6512 6969//6969 -f 6969//6969 6512//6512 6509//6509 -f 6969//6969 6509//6509 6968//6968 -f 6968//6968 6509//6509 6506//6506 -f 6968//6968 6506//6506 6503//6503 -f 6972//6972 6521//6521 6971//6971 -f 6971//6971 6521//6521 6518//6518 -f 6971//6971 6518//6518 6970//6970 -f 6970//6970 6518//6518 6515//6515 -f 6970//6970 6515//6515 6512//6512 -f 6962//6962 6476//6476 6961//6961 -f 6961//6961 6476//6476 6474//6474 -f 6961//6961 6474//6474 6960//6960 -f 6960//6960 6474//6474 6473//6473 -f 6960//6960 6473//6473 6972//6972 -f 6972//6972 6473//6473 6524//6524 -f 6972//6972 6524//6524 6521//6521 -f 6964//6964 6485//6485 6963//6963 -f 6963//6963 6485//6485 6482//6482 -f 6963//6963 6482//6482 6962//6962 -f 6962//6962 6482//6482 6479//6479 -f 6962//6962 6479//6479 6476//6476 -f 6500//6500 6497//6497 6966//6966 -f 6966//6966 6497//6497 6494//6494 -f 6966//6966 6494//6494 6965//6965 -f 6965//6965 6494//6494 6491//6491 -f 6965//6965 6491//6491 6964//6964 -f 6964//6964 6491//6491 6488//6488 -f 6964//6964 6488//6488 6485//6485 -f 6973//6973 6722//6722 6974//6974 -f 6974//6974 6722//6722 6719//6719 -f 6974//6974 6719//6719 6975//6975 -f 6975//6975 6719//6719 6718//6718 -f 6975//6975 6718//6718 6976//6976 -f 6976//6976 6718//6718 6740//6740 -f 6976//6976 6740//6740 6977//6977 -f 6977//6977 6740//6740 6734//6734 -f 6977//6977 6734//6734 6978//6978 -f 6978//6978 6734//6734 6745//6745 -f 6978//6978 6745//6745 6979//6979 -f 6979//6979 6745//6745 6732//6732 -f 6979//6979 6732//6732 6980//6980 -f 6980//6980 6732//6732 6730//6730 -f 6980//6980 6730//6730 6981//6981 -f 6981//6981 6730//6730 6729//6729 -f 6981//6981 6729//6729 6982//6982 -f 6982//6982 6729//6729 6728//6728 -f 6982//6982 6728//6728 6983//6983 -f 6983//6983 6728//6728 6726//6726 -f 6983//6983 6726//6726 6984//6984 -f 6984//6984 6726//6726 6724//6724 -f 6984//6984 6724//6724 6973//6973 -f 6973//6973 6724//6724 6722//6722 -f 6978//6978 6985//6985 6977//6977 -f 6977//6977 6985//6985 6986//6986 -f 6977//6977 6986//6986 6976//6976 -f 6976//6976 6986//6986 6987//6987 -f 6976//6976 6987//6987 6975//6975 -f 6975//6975 6987//6987 6988//6988 -f 6975//6975 6988//6988 6974//6974 -f 6974//6974 6988//6988 6989//6989 -f 6974//6974 6989//6989 6973//6973 -f 6973//6973 6989//6989 6990//6990 -f 6973//6973 6990//6990 6984//6984 -f 6984//6984 6990//6990 6991//6991 -f 6984//6984 6991//6991 6983//6983 -f 6983//6983 6991//6991 6992//6992 -f 6983//6983 6992//6992 6982//6982 -f 6982//6982 6992//6992 6993//6993 -f 6982//6982 6993//6993 6981//6981 -f 6981//6981 6993//6993 6994//6994 -f 6981//6981 6994//6994 6980//6980 -f 6980//6980 6994//6994 6995//6995 -f 6980//6980 6995//6995 6979//6979 -f 6979//6979 6995//6995 6996//6996 -f 6979//6979 6996//6996 6978//6978 -f 6978//6978 6996//6996 6985//6985 -f 6986//6986 6617//6617 6987//6987 -f 6987//6987 6617//6617 6618//6618 -f 6987//6987 6618//6618 6988//6988 -f 6988//6988 6618//6618 6636//6636 -f 6988//6988 6636//6636 6989//6989 -f 6989//6989 6636//6636 6634//6634 -f 6989//6989 6634//6634 6990//6990 -f 6990//6990 6634//6634 6632//6632 -f 6990//6990 6632//6632 6991//6991 -f 6991//6991 6632//6632 6630//6630 -f 6991//6991 6630//6630 6992//6992 -f 6992//6992 6630//6630 6628//6628 -f 6992//6992 6628//6628 6993//6993 -f 6993//6993 6628//6628 6626//6626 -f 6993//6993 6626//6626 6994//6994 -f 6994//6994 6626//6626 6625//6625 -f 6994//6994 6625//6625 6995//6995 -f 6995//6995 6625//6625 6624//6624 -f 6995//6995 6624//6624 6996//6996 -f 6996//6996 6624//6624 6622//6622 -f 6996//6996 6622//6622 6985//6985 -f 6985//6985 6622//6622 6620//6620 -f 6985//6985 6620//6620 6986//6986 -f 6986//6986 6620//6620 6617//6617 -f 6997//6997 6815//6815 6998//6998 -f 6998//6998 6815//6815 6825//6825 -f 6998//6998 6825//6825 6999//6999 -f 6999//6999 6825//6825 6827//6827 -f 6999//6999 6827//6827 7000//7000 -f 7000//7000 6827//6827 6812//6812 -f 7000//7000 6812//6812 7001//7001 -f 7001//7001 6812//6812 6824//6824 -f 7001//7001 6824//6824 7002//7002 -f 7002//7002 6824//6824 6823//6823 -f 7002//7002 6823//6823 7003//7003 -f 7003//7003 6823//6823 6822//6822 -f 7003//7003 6822//6822 7004//7004 -f 7004//7004 6822//6822 6820//6820 -f 7004//7004 6820//6820 7005//7005 -f 7005//7005 6820//6820 6819//6819 -f 7005//7005 6819//6819 7006//7006 -f 7006//7006 6819//6819 6810//6810 -f 7006//7006 6810//6810 7007//7007 -f 7007//7007 6810//6810 6806//6806 -f 7007//7007 6806//6806 7008//7008 -f 7008//7008 6806//6806 6805//6805 -f 7008//7008 6805//6805 6997//6997 -f 6997//6997 6805//6805 6815//6815 -f 7002//7002 7009//7009 7001//7001 -f 7001//7001 7009//7009 7010//7010 -f 7001//7001 7010//7010 7000//7000 -f 7000//7000 7010//7010 7011//7011 -f 7000//7000 7011//7011 6999//6999 -f 6999//6999 7011//7011 7012//7012 -f 6999//6999 7012//7012 6998//6998 -f 6998//6998 7012//7012 7013//7013 -f 6998//6998 7013//7013 6997//6997 -f 6997//6997 7013//7013 7014//7014 -f 6997//6997 7014//7014 7008//7008 -f 7008//7008 7014//7014 7015//7015 -f 7008//7008 7015//7015 7007//7007 -f 7007//7007 7015//7015 7016//7016 -f 7007//7007 7016//7016 7006//7006 -f 7006//7006 7016//7016 7017//7017 -f 7006//7006 7017//7017 7005//7005 -f 7005//7005 7017//7017 7018//7018 -f 7005//7005 7018//7018 7004//7004 -f 7004//7004 7018//7018 7019//7019 -f 7004//7004 7019//7019 7003//7003 -f 7003//7003 7019//7019 7020//7020 -f 7003//7003 7020//7020 7002//7002 -f 7002//7002 7020//7020 7009//7009 -f 7010//7010 6595//6595 7011//7011 -f 7011//7011 6595//6595 6594//6594 -f 7011//7011 6594//6594 7012//7012 -f 7012//7012 6594//6594 6603//6603 -f 7012//7012 6603//6603 7013//7013 -f 7013//7013 6603//6603 6590//6590 -f 7013//7013 6590//6590 7014//7014 -f 7014//7014 6590//6590 6593//6593 -f 7014//7014 6593//6593 7015//7015 -f 7015//7015 6593//6593 6592//6592 -f 7015//7015 6592//6592 7016//7016 -f 7016//7016 6592//6592 6600//6600 -f 7016//7016 6600//6600 7017//7017 -f 7017//7017 6600//6600 6599//6599 -f 7017//7017 6599//6599 7018//7018 -f 7018//7018 6599//6599 6598//6598 -f 7018//7018 6598//6598 7019//7019 -f 7019//7019 6598//6598 6588//6588 -f 7019//7019 6588//6588 7020//7020 -f 7020//7020 6588//6588 6584//6584 -f 7020//7020 6584//6584 7009//7009 -f 7009//7009 6584//6584 6583//6583 -f 7009//7009 6583//6583 7010//7010 -f 7010//7010 6583//6583 6595//6595 -f 7021//7021 6797//6797 7022//7022 -f 7022//7022 6797//6797 6791//6791 -f 7022//7022 6791//6791 7023//7023 -f 7023//7023 6791//6791 6786//6786 -f 7023//7023 6786//6786 7024//7024 -f 7024//7024 6786//6786 6784//6784 -f 7024//7024 6784//6784 7025//7025 -f 7025//7025 6784//6784 6782//6782 -f 7025//7025 6782//6782 7026//7026 -f 7026//7026 6782//6782 6780//6780 -f 7026//7026 6780//6780 7027//7027 -f 7027//7027 6780//6780 6778//6778 -f 7027//7027 6778//6778 7028//7028 -f 7028//7028 6778//6778 6776//6776 -f 7028//7028 6776//6776 7029//7029 -f 7029//7029 6776//6776 6774//6774 -f 7029//7029 6774//6774 7030//7030 -f 7030//7030 6774//6774 6771//6771 -f 7030//7030 6771//6771 7031//7031 -f 7031//7031 6771//6771 6770//6770 -f 7031//7031 6770//6770 7032//7032 -f 7032//7032 6770//6770 6795//6795 -f 7032//7032 6795//6795 7021//7021 -f 7021//7021 6795//6795 6797//6797 -f 7026//7026 7033//7033 7025//7025 -f 7025//7025 7033//7033 7034//7034 -f 7025//7025 7034//7034 7024//7024 -f 7024//7024 7034//7034 7035//7035 -f 7024//7024 7035//7035 7023//7023 -f 7023//7023 7035//7035 7036//7036 -f 7023//7023 7036//7036 7022//7022 -f 7022//7022 7036//7036 7037//7037 -f 7022//7022 7037//7037 7021//7021 -f 7021//7021 7037//7037 7038//7038 -f 7021//7021 7038//7038 7032//7032 -f 7032//7032 7038//7038 7039//7039 -f 7032//7032 7039//7039 7031//7031 -f 7031//7031 7039//7039 7040//7040 -f 7031//7031 7040//7040 7030//7030 -f 7030//7030 7040//7040 7041//7041 -f 7030//7030 7041//7041 7029//7029 -f 7029//7029 7041//7041 7042//7042 -f 7029//7029 7042//7042 7028//7028 -f 7028//7028 7042//7042 7043//7043 -f 7028//7028 7043//7043 7027//7027 -f 7027//7027 7043//7043 7044//7044 -f 7027//7027 7044//7044 7026//7026 -f 7026//7026 7044//7044 7033//7033 -f 7034//7034 6577//6577 7035//7035 -f 7035//7035 6577//6577 6575//6575 -f 7035//7035 6575//6575 7036//7036 -f 7036//7036 6575//6575 6574//6574 -f 7036//7036 6574//6574 7037//7037 -f 7037//7037 6574//6574 6562//6562 -f 7037//7037 6562//6562 7038//7038 -f 7038//7038 6562//6562 6561//6561 -f 7038//7038 6561//6561 7039//7039 -f 7039//7039 6561//6561 6571//6571 -f 7039//7039 6571//6571 7040//7040 -f 7040//7040 6571//6571 6552//6552 -f 7040//7040 6552//6552 7041//7041 -f 7041//7041 6552//6552 6551//6551 -f 7041//7041 6551//6551 7042//7042 -f 7042//7042 6551//6551 6539//6539 -f 7042//7042 6539//6539 7043//7043 -f 7043//7043 6539//6539 6582//6582 -f 7043//7043 6582//6582 7044//7044 -f 7044//7044 6582//6582 6581//6581 -f 7044//7044 6581//6581 7033//7033 -f 7033//7033 6581//6581 6579//6579 -f 7033//7033 6579//6579 7034//7034 -f 7034//7034 6579//6579 6577//6577 -f 7045//7045 6761//6761 7046//7046 -f 7046//7046 6761//6761 6767//6767 -f 7046//7046 6767//6767 7047//7047 -f 7047//7047 6767//6767 6766//6766 -f 7047//7047 6766//6766 7048//7048 -f 7048//7048 6766//6766 6764//6764 -f 7048//7048 6764//6764 7049//7049 -f 7049//7049 6764//6764 6758//6758 -f 7049//7049 6758//6758 7050//7050 -f 7050//7050 6758//6758 6756//6756 -f 7050//7050 6756//6756 7051//7051 -f 7051//7051 6756//6756 6755//6755 -f 7051//7051 6755//6755 7052//7052 -f 7052//7052 6755//6755 6750//6750 -f 7052//7052 6750//6750 7053//7053 -f 7053//7053 6750//6750 6752//6752 -f 7053//7053 6752//6752 7054//7054 -f 7054//7054 6752//6752 6742//6742 -f 7054//7054 6742//6742 7055//7055 -f 7055//7055 6742//6742 6741//6741 -f 7055//7055 6741//6741 7056//7056 -f 7056//7056 6741//6741 6759//6759 -f 7056//7056 6759//6759 7045//7045 -f 7045//7045 6759//6759 6761//6761 -f 7050//7050 7057//7057 7049//7049 -f 7049//7049 7057//7057 7058//7058 -f 7049//7049 7058//7058 7048//7048 -f 7048//7048 7058//7058 7059//7059 -f 7048//7048 7059//7059 7047//7047 -f 7047//7047 7059//7059 7060//7060 -f 7047//7047 7060//7060 7046//7046 -f 7046//7046 7060//7060 7061//7061 -f 7046//7046 7061//7061 7045//7045 -f 7045//7045 7061//7061 7062//7062 -f 7045//7045 7062//7062 7056//7056 -f 7056//7056 7062//7062 7063//7063 -f 7056//7056 7063//7063 7055//7055 -f 7055//7055 7063//7063 7064//7064 -f 7055//7055 7064//7064 7054//7054 -f 7054//7054 7064//7064 7065//7065 -f 7054//7054 7065//7065 7053//7053 -f 7053//7053 7065//7065 7066//7066 -f 7053//7053 7066//7066 7052//7052 -f 7052//7052 7066//7066 7067//7067 -f 7052//7052 7067//7067 7051//7051 -f 7051//7051 7067//7067 7068//7068 -f 7051//7051 7068//7068 7050//7050 -f 7050//7050 7068//7068 7057//7057 -f 7058//7058 6543//6543 7059//7059 -f 7059//7059 6543//6543 6545//6545 -f 7059//7059 6545//6545 7060//7060 -f 7060//7060 6545//6545 6547//6547 -f 7060//7060 6547//6547 7061//7061 -f 7061//7061 6547//6547 6536//6536 -f 7061//7061 6536//6536 7062//7062 -f 7062//7062 6536//6536 6534//6534 -f 7062//7062 6534//6534 7063//7063 -f 7063//7063 6534//6534 6533//6533 -f 7063//7063 6533//6533 7064//7064 -f 7064//7064 6533//6533 6542//6542 -f 7064//7064 6542//6542 7065//7065 -f 7065//7065 6542//6542 6541//6541 -f 7065//7065 6541//6541 7066//7066 -f 7066//7066 6541//6541 6566//6566 -f 7066//7066 6566//6566 7067//7067 -f 7067//7067 6566//6566 6560//6560 -f 7067//7067 6560//6560 7068//7068 -f 7068//7068 6560//6560 6557//6557 -f 7068//7068 6557//6557 7057//7057 -f 7057//7057 6557//6557 6548//6548 -f 7057//7057 6548//6548 7058//7058 -f 7058//7058 6548//6548 6543//6543 -f 6553//6553 6573//6573 6504//6504 -f 6504//6504 6508//6508 6553//6553 -f 6553//6553 6508//6508 6507//6507 -f 6553//6553 6507//6507 6537//6537 -f 6537//6537 6507//6507 6511//6511 -f 6537//6537 6511//6511 6601//6601 -f 6601//6601 6511//6511 6510//6510 -f 6601//6601 6510//6510 6602//6602 -f 6510//6510 6514//6514 6602//6602 -f 6602//6602 6514//6514 6513//6513 -f 6602//6602 6513//6513 6604//6604 -f 6513//6513 6517//6517 6604//6604 -f 6604//6604 6517//6517 6516//6516 -f 6604//6604 6516//6516 6605//6605 -f 6516//6516 6520//6520 6605//6605 -f 6605//6605 6520//6520 6519//6519 -f 6605//6605 6519//6519 6589//6589 -f 6519//6519 6523//6523 6589//6589 -f 6589//6589 6523//6523 6522//6522 -f 6589//6589 6522//6522 6532//6532 -f 6532//6532 6522//6522 6609//6609 -f 6609//6609 6522//6522 6526//6526 -f 6609//6609 6526//6526 6623//6623 -f 6623//6623 6526//6526 6525//6525 -f 6623//6623 6525//6525 6621//6621 -f 6525//6525 6529//6529 6621//6621 -f 6621//6621 6529//6529 6528//6528 -f 6621//6621 6528//6528 6619//6619 -f 6619//6619 6528//6528 6527//6527 -f 6619//6619 6527//6527 6615//6615 -f 6527//6527 6475//6475 6615//6615 -f 6615//6615 6475//6475 6478//6478 -f 6615//6615 6478//6478 6616//6616 -f 6478//6478 6477//6477 6616//6616 -f 6616//6616 6477//6477 6481//6481 -f 6616//6616 6481//6481 6540//6540 -f 6540//6540 6481//6481 6480//6480 -f 6540//6540 6480//6480 6568//6568 -f 6568//6568 6480//6480 6484//6484 -f 6568//6568 6484//6484 6567//6567 -f 6484//6484 6483//6483 6567//6567 -f 6567//6567 6483//6483 6487//6487 -f 6567//6567 6487//6487 6565//6565 -f 6487//6487 6486//6486 6565//6565 -f 6565//6565 6486//6486 6490//6490 -f 6565//6565 6490//6490 6564//6564 -f 6490//6490 6489//6489 6564//6564 -f 6564//6564 6489//6489 6493//6493 -f 6564//6564 6493//6493 6563//6563 -f 6493//6493 6492//6492 6563//6563 -f 6563//6563 6492//6492 6496//6496 -f 6563//6563 6496//6496 6569//6569 -f 6496//6496 6495//6495 6569//6569 -f 6569//6569 6495//6495 6499//6499 -f 6569//6569 6499//6499 6570//6570 -f 6499//6499 6498//6498 6570//6570 -f 6570//6570 6498//6498 6502//6502 -f 6570//6570 6502//6502 6572//6572 -f 6572//6572 6502//6502 6501//6501 -f 6572//6572 6501//6501 6573//6573 -f 6573//6573 6501//6501 6505//6505 -f 6573//6573 6505//6505 6504//6504 -f 6901//6901 6857//6857 6856//6856 -f 6901//6901 6856//6856 6903//6903 -f 6903//6903 6856//6856 6855//6855 -f 6903//6903 6855//6855 6905//6905 -f 6855//6855 6854//6854 6905//6905 -f 6905//6905 6854//6854 6853//6853 -f 6905//6905 6853//6853 6906//6906 -f 6853//6853 6852//6852 6906//6906 -f 6906//6906 6852//6852 6851//6851 -f 6906//6906 6851//6851 6894//6894 -f 6851//6851 6850//6850 6894//6894 -f 6894//6894 6850//6850 6849//6849 -f 6894//6894 6849//6849 6896//6896 -f 6849//6849 6848//6848 6896//6896 -f 6896//6896 6848//6848 6847//6847 -f 6896//6896 6847//6847 6898//6898 -f 6898//6898 6847//6847 6846//6846 -f 6846//6846 6845//6845 6898//6898 -f 6898//6898 6845//6845 6844//6844 -f 6898//6898 6844//6844 6899//6899 -f 6844//6844 6843//6843 6899//6899 -f 6899//6899 6843//6843 6842//6842 -f 6899//6899 6842//6842 6887//6887 -f 6887//6887 6842//6842 6841//6841 -f 6887//6887 6841//6841 6889//6889 -f 6841//6841 6840//6840 6889//6889 -f 6889//6889 6840//6840 6839//6839 -f 6889//6889 6839//6839 6891//6891 -f 6839//6839 6838//6838 6891//6891 -f 6891//6891 6838//6838 6837//6837 -f 6891//6891 6837//6837 6892//6892 -f 6837//6837 6836//6836 6892//6892 -f 6892//6892 6836//6836 6835//6835 -f 6892//6892 6835//6835 6883//6883 -f 6835//6835 6834//6834 6883//6883 -f 6883//6883 6834//6834 6833//6833 -f 6883//6883 6833//6833 6907//6907 -f 6907//6907 6833//6833 6882//6882 -f 6907//6907 6882//6882 6908//6908 -f 6882//6882 6881//6881 6908//6908 -f 6908//6908 6881//6881 6880//6880 -f 6908//6908 6880//6880 6910//6910 -f 6910//6910 6880//6880 6879//6879 -f 6910//6910 6879//6879 6912//6912 -f 6879//6879 6878//6878 6912//6912 -f 6912//6912 6878//6878 6877//6877 -f 6912//6912 6877//6877 6921//6921 -f 6921//6921 6877//6877 6876//6876 -f 6876//6876 6875//6875 6921//6921 -f 6921//6921 6875//6875 6874//6874 -f 6921//6921 6874//6874 6922//6922 -f 6922//6922 6874//6874 6873//6873 -f 6922//6922 6873//6873 6924//6924 -f 6873//6873 6872//6872 6924//6924 -f 6924//6924 6872//6872 6871//6871 -f 6924//6924 6871//6871 6926//6926 -f 6871//6871 6870//6870 6926//6926 -f 6926//6926 6870//6870 6869//6869 -f 6926//6926 6869//6869 6927//6927 -f 6869//6869 6868//6868 6927//6927 -f 6927//6927 6868//6868 6867//6867 -f 6927//6927 6867//6867 6915//6915 -f 6867//6867 6866//6866 6915//6915 -f 6915//6915 6866//6866 6865//6865 -f 6915//6915 6865//6865 6917//6917 -f 6917//6917 6865//6865 6864//6864 -f 6864//6864 6863//6863 6917//6917 -f 6917//6917 6863//6863 6862//6862 -f 6917//6917 6862//6862 6919//6919 -f 6862//6862 6861//6861 6919//6919 -f 6919//6919 6861//6861 6860//6860 -f 6919//6919 6860//6860 6920//6920 -f 6920//6920 6860//6860 6859//6859 -f 6920//6920 6859//6859 6901//6901 -f 6901//6901 6859//6859 6858//6858 -f 6901//6901 6858//6858 6857//6857 -f 6725//6725 6727//6727 6714//6714 -f 6664//6664 6763//6763 6662//6662 -f 6662//6662 6763//6763 6762//6762 -f 6662//6662 6762//6762 6660//6660 -f 6660//6660 6762//6762 6768//6768 -f 6660//6660 6768//6768 6658//6658 -f 6658//6658 6768//6768 6769//6769 -f 6658//6658 6769//6769 6656//6656 -f 6656//6656 6769//6769 6760//6760 -f 6656//6656 6760//6760 6654//6654 -f 6654//6654 6760//6760 6739//6739 -f 6654//6654 6739//6739 6652//6652 -f 6652//6652 6739//6739 6738//6738 -f 6652//6652 6738//6738 6650//6650 -f 6650//6650 6738//6738 6737//6737 -f 6650//6650 6737//6737 6648//6648 -f 6648//6648 6737//6737 6720//6720 -f 6648//6648 6720//6720 6646//6646 -f 6646//6646 6720//6720 6721//6721 -f 6646//6646 6721//6721 6644//6644 -f 6644//6644 6721//6721 6723//6723 -f 6644//6644 6723//6723 6642//6642 -f 6642//6642 6723//6723 6725//6725 -f 6642//6642 6725//6725 6716//6716 -f 6716//6716 6725//6725 6714//6714 -f 6799//6799 6757//6757 6664//6664 -f 6664//6664 6757//6757 6765//6765 -f 6664//6664 6765//6765 6763//6763 -f 6727//6727 6814//6814 6714//6714 -f 6714//6714 6814//6814 6813//6813 -f 6714//6714 6813//6813 6712//6712 -f 6712//6712 6813//6813 6832//6832 -f 6712//6712 6832//6832 6710//6710 -f 6710//6710 6832//6832 6831//6831 -f 6710//6710 6831//6831 6708//6708 -f 6708//6708 6831//6831 6830//6830 -f 6708//6708 6830//6830 6706//6706 -f 6706//6706 6830//6830 6807//6807 -f 6706//6706 6807//6807 6704//6704 -f 6704//6704 6807//6807 6816//6816 -f 6704//6704 6816//6816 6702//6702 -f 6702//6702 6816//6816 6809//6809 -f 6702//6702 6809//6809 6700//6700 -f 6700//6700 6809//6809 6808//6808 -f 6700//6700 6808//6808 6698//6698 -f 6698//6698 6808//6808 6821//6821 -f 6698//6698 6821//6821 6696//6696 -f 6696//6696 6821//6821 6804//6804 -f 6696//6696 6804//6804 6694//6694 -f 6694//6694 6804//6804 6803//6803 -f 6694//6694 6803//6803 6692//6692 -f 6692//6692 6803//6803 6802//6802 -f 6692//6692 6802//6802 6690//6690 -f 6690//6690 6802//6802 6801//6801 -f 6690//6690 6801//6801 6688//6688 -f 6688//6688 6801//6801 6800//6800 -f 6688//6688 6800//6800 6686//6686 -f 6686//6686 6800//6800 6775//6775 -f 6686//6686 6775//6775 6684//6684 -f 6684//6684 6775//6775 6777//6777 -f 6684//6684 6777//6777 6682//6682 -f 6682//6682 6777//6777 6779//6779 -f 6682//6682 6779//6779 6680//6680 -f 6680//6680 6779//6779 6781//6781 -f 6680//6680 6781//6781 6678//6678 -f 6678//6678 6781//6781 6783//6783 -f 6678//6678 6783//6783 6676//6676 -f 6676//6676 6783//6783 6785//6785 -f 6676//6676 6785//6785 6674//6674 -f 6674//6674 6785//6785 6787//6787 -f 6674//6674 6787//6787 6672//6672 -f 6672//6672 6787//6787 6790//6790 -f 6672//6672 6790//6790 6670//6670 -f 6670//6670 6790//6790 6792//6792 -f 6670//6670 6792//6792 6668//6668 -f 6668//6668 6792//6792 6799//6799 -f 6668//6668 6799//6799 6666//6666 -f 6666//6666 6799//6799 6664//6664 -f 6659//6659 6546//6546 6661//6661 -f 6661//6661 6546//6546 6544//6544 -f 6661//6661 6544//6544 6663//6663 -f 6663//6663 6544//6544 6550//6550 -f 6663//6663 6550//6550 6665//6665 -f 6665//6665 6550//6550 6549//6549 -f 6665//6665 6549//6549 6667//6667 -f 6667//6667 6549//6549 6559//6559 -f 6667//6667 6559//6559 6669//6669 -f 6669//6669 6559//6559 6558//6558 -f 6669//6669 6558//6558 6671//6671 -f 6671//6671 6558//6558 6556//6556 -f 6671//6671 6556//6556 6673//6673 -f 6673//6673 6556//6556 6555//6555 -f 6673//6673 6555//6555 6675//6675 -f 6675//6675 6555//6555 6576//6576 -f 6675//6675 6576//6576 6677//6677 -f 6677//6677 6576//6576 6578//6578 -f 6677//6677 6578//6578 6679//6679 -f 6679//6679 6578//6578 6580//6580 -f 6679//6679 6580//6580 6681//6681 -f 6681//6681 6580//6580 6538//6538 -f 6681//6681 6538//6538 6683//6683 -f 6538//6538 6596//6596 6683//6683 -f 6683//6683 6596//6596 6597//6597 -f 6683//6683 6597//6597 6685//6685 -f 6685//6685 6597//6597 6608//6608 -f 6685//6685 6608//6608 6687//6687 -f 6687//6687 6608//6608 6607//6607 -f 6687//6687 6607//6607 6689//6689 -f 6689//6689 6607//6607 6606//6606 -f 6689//6689 6606//6606 6691//6691 -f 6691//6691 6606//6606 6585//6585 -f 6691//6691 6585//6585 6693//6693 -f 6693//6693 6585//6585 6591//6591 -f 6693//6693 6591//6591 6695//6695 -f 6695//6695 6591//6591 6587//6587 -f 6695//6695 6587//6587 6697//6697 -f 6697//6697 6587//6587 6586//6586 -f 6697//6697 6586//6586 6699//6699 -f 6699//6699 6586//6586 6531//6531 -f 6699//6699 6531//6531 6701//6701 -f 6701//6701 6531//6531 6530//6530 -f 6701//6701 6530//6530 6703//6703 -f 6703//6703 6530//6530 6614//6614 -f 6703//6703 6614//6614 6705//6705 -f 6705//6705 6614//6614 6613//6613 -f 6705//6705 6613//6613 6707//6707 -f 6707//6707 6613//6613 6612//6612 -f 6707//6707 6612//6612 6709//6709 -f 6709//6709 6612//6612 6611//6611 -f 6709//6709 6611//6611 6711//6711 -f 6711//6711 6611//6611 6610//6610 -f 6711//6711 6610//6610 6713//6713 -f 6713//6713 6610//6610 6627//6627 -f 6713//6713 6627//6627 6715//6715 -f 6715//6715 6627//6627 6629//6629 -f 6715//6715 6629//6629 6717//6717 -f 6717//6717 6629//6629 6631//6631 -f 6717//6717 6631//6631 6643//6643 -f 6643//6643 6631//6631 6633//6633 -f 6643//6643 6633//6633 6645//6645 -f 6645//6645 6633//6633 6635//6635 -f 6645//6645 6635//6635 6647//6647 -f 6647//6647 6635//6635 6641//6641 -f 6647//6647 6641//6641 6649//6649 -f 6649//6649 6641//6641 6640//6640 -f 6649//6649 6640//6640 6651//6651 -f 6651//6651 6640//6640 6639//6639 -f 6651//6651 6639//6639 6653//6653 -f 6653//6653 6639//6639 6638//6638 -f 6653//6653 6638//6638 6655//6655 -f 6655//6655 6638//6638 6637//6637 -f 6655//6655 6637//6637 6657//6657 -f 6657//6657 6637//6637 6535//6535 -f 6657//6657 6535//6535 6659//6659 -f 6659//6659 6535//6535 6554//6554 -f 6659//6659 6554//6554 6546//6546 -f 7069//7069 7070//7070 7071//7071 -f 7071//7071 7070//7070 7072//7072 -f 7072//7072 7073//7073 7074//7074 -f 7075//7075 7076//7076 7077//7077 -f 7077//7077 7076//7076 7078//7078 -f 7077//7077 7078//7078 7079//7079 -f 7080//7080 7081//7081 7082//7082 -f 7082//7082 7081//7081 7083//7083 -f 7074//7074 7084//7084 7072//7072 -f 7072//7072 7084//7084 7085//7085 -f 7072//7072 7085//7085 7071//7071 -f 7071//7071 7085//7085 7079//7079 -f 7083//7083 7081//7081 7086//7086 -f 7086//7086 7081//7081 7087//7087 -f 7086//7086 7087//7087 7088//7088 -f 7089//7089 7090//7090 7091//7091 -f 7091//7091 7090//7090 7092//7092 -f 7091//7091 7092//7092 7093//7093 -f 7093//7093 7092//7092 7094//7094 -f 7092//7092 7095//7095 7094//7094 -f 7094//7094 7095//7095 7096//7096 -f 7094//7094 7096//7096 7097//7097 -f 7097//7097 7096//7096 7098//7098 -f 7099//7099 7100//7100 7101//7101 -f 7101//7101 7100//7100 7102//7102 -f 7101//7101 7102//7102 7103//7103 -f 7103//7103 7102//7102 7104//7104 -f 7103//7103 7104//7104 7105//7105 -f 7105//7105 7104//7104 7106//7106 -f 7107//7107 7080//7080 7099//7099 -f 7099//7099 7080//7080 7108//7108 -f 7099//7099 7108//7108 7100//7100 -f 7098//7098 7081//7081 7097//7097 -f 7097//7097 7081//7081 7080//7080 -f 7097//7097 7080//7080 7109//7109 -f 7109//7109 7080//7080 7107//7107 -f 7110//7110 7111//7111 7112//7112 -f 7112//7112 7111//7111 7113//7113 -f 7112//7112 7113//7113 7073//7073 -f 7073//7073 7113//7113 7114//7114 -f 7073//7073 7114//7114 7074//7074 -f 7078//7078 7115//7115 7079//7079 -f 7079//7079 7115//7115 7116//7116 -f 7079//7079 7116//7116 7071//7071 -f 7071//7071 7116//7116 7117//7117 -f 7071//7071 7117//7117 7118//7118 -f 7118//7118 7117//7117 7119//7119 -f 7118//7118 7119//7119 7120//7120 -f 7120//7120 7119//7119 7121//7121 -f 7120//7120 7121//7121 7106//7106 -f 7106//7106 7121//7121 7122//7122 -f 7106//7106 7122//7122 7105//7105 -f 7105//7105 7122//7122 7123//7123 -f 7105//7105 7123//7123 7124//7124 -f 7124//7124 7123//7123 7125//7125 -f 7124//7124 7125//7125 7126//7126 -f 7088//7088 7127//7127 7086//7086 -f 7086//7086 7127//7127 7071//7071 -f 7086//7086 7071//7071 7128//7128 -f 7128//7128 7071//7071 7118//7118 -f 7127//7127 7129//7129 7071//7071 -f 7071//7071 7129//7129 7130//7130 -f 7071//7071 7130//7130 7089//7089 -f 7089//7089 7130//7130 7131//7131 -f 7089//7089 7131//7131 7090//7090 -f 7075//7075 7132//7132 7076//7076 -f 7076//7076 7132//7132 7133//7133 -f 7076//7076 7133//7133 7134//7134 -f 7134//7134 7133//7133 7135//7135 -f 7134//7134 7135//7135 7111//7111 -f 7111//7111 7135//7135 7136//7136 -f 7111//7111 7136//7136 7113//7113 -f 7125//7125 7137//7137 7126//7126 -f 7126//7126 7137//7137 7138//7138 -f 7126//7126 7138//7138 7139//7139 -f 7139//7139 7138//7138 7076//7076 -f 7139//7139 7076//7076 7140//7140 -f 7140//7140 7076//7076 7134//7134 -f 7141//7141 7142//7142 7143//7143 -f 7144//7144 7145//7145 7146//7146 -f 7146//7146 7145//7145 7141//7141 -f 7147//7147 7148//7148 7149//7149 -f 7150//7150 7151//7151 7152//7152 -f 7152//7152 7151//7151 7153//7153 -f 7152//7152 7153//7153 7154//7154 -f 7154//7154 7153//7153 7155//7155 -f 7154//7154 7155//7155 7156//7156 -f 7157//7157 7158//7158 7159//7159 -f 7146//7146 7160//7160 7161//7161 -f 7146//7146 7162//7162 7163//7163 -f 7164//7164 7149//7149 7165//7165 -f 7165//7165 7149//7149 7148//7148 -f 7165//7165 7148//7148 7142//7142 -f 7142//7142 7148//7148 7166//7166 -f 7142//7142 7166//7166 7143//7143 -f 7167//7167 7168//7168 7169//7169 -f 7170//7170 7171//7171 7156//7156 -f 7146//7146 7163//7163 7172//7172 -f 7163//7163 7173//7173 7172//7172 -f 7172//7172 7173//7173 7174//7174 -f 7172//7172 7174//7174 7175//7175 -f 7175//7175 7174//7174 7150//7150 -f 7175//7175 7150//7150 7176//7176 -f 7176//7176 7150//7150 7152//7152 -f 7177//7177 7178//7178 7179//7179 -f 7179//7179 7178//7178 7180//7180 -f 7180//7180 7154//7154 7179//7179 -f 7179//7179 7154//7154 7156//7156 -f 7179//7179 7156//7156 7181//7181 -f 7181//7181 7156//7156 7171//7171 -f 7182//7182 7183//7183 7184//7184 -f 7184//7184 7183//7183 7185//7185 -f 7184//7184 7185//7185 7186//7186 -f 7186//7186 7185//7185 7187//7187 -f 7186//7186 7187//7187 7188//7188 -f 7141//7141 7143//7143 7146//7146 -f 7146//7146 7143//7143 7189//7189 -f 7146//7146 7189//7189 7160//7160 -f 7162//7162 7146//7146 7190//7190 -f 7190//7190 7146//7146 7161//7161 -f 7190//7190 7161//7161 7191//7191 -f 7191//7191 7161//7161 7192//7192 -f 7191//7191 7192//7192 7193//7193 -f 7159//7159 7167//7167 7157//7157 -f 7157//7157 7167//7167 7169//7169 -f 7157//7157 7169//7169 7194//7194 -f 7194//7194 7169//7169 7170//7170 -f 7194//7194 7170//7170 7192//7192 -f 7192//7192 7170//7170 7156//7156 -f 7192//7192 7156//7156 7193//7193 -f 7147//7147 7149//7149 7195//7195 -f 7195//7195 7149//7149 7196//7196 -f 7195//7195 7196//7196 7197//7197 -f 7197//7197 7196//7196 7198//7198 -f 7197//7197 7198//7198 7157//7157 -f 7157//7157 7198//7198 7199//7199 -f 7157//7157 7199//7199 7158//7158 -f 7187//7187 7200//7200 7188//7188 -f 7188//7188 7200//7200 7201//7201 -f 7188//7188 7201//7201 7202//7202 -f 7202//7202 7201//7201 7198//7198 -f 7202//7202 7198//7198 7203//7203 -f 7203//7203 7198//7198 7196//7196 -f 7179//7179 7204//7204 7177//7177 -f 7177//7177 7204//7204 7205//7205 -f 7177//7177 7205//7205 7206//7206 -f 7206//7206 7205//7205 7207//7207 -f 7206//7206 7207//7207 7182//7182 -f 7182//7182 7207//7207 7208//7208 -f 7182//7182 7208//7208 7183//7183 -f 7183//7183 7208//7208 7209//7209 -f 7183//7183 7209//7209 7210//7210 -f 7210//7210 7209//7209 7211//7211 -f 7210//7210 7211//7211 7168//7168 -f 7168//7168 7211//7211 7212//7212 -f 7168//7168 7212//7212 7169//7169 -f 7182//7182 7184//7184 7105//7105 -f 7105//7105 7184//7184 7103//7103 -f 7094//7094 7097//7097 7149//7149 -f 7149//7149 7097//7097 7196//7196 -f 7142//7142 7141//7141 7089//7089 -f 7089//7089 7141//7141 7071//7071 -f 7069//7069 7071//7071 7145//7145 -f 7145//7145 7071//7071 7141//7141 -f 7070//7070 7069//7069 7144//7144 -f 7144//7144 7069//7069 7145//7145 -f 7072//7072 7070//7070 7146//7146 -f 7146//7146 7070//7070 7144//7144 -f 7073//7073 7072//7072 7172//7172 -f 7172//7172 7072//7072 7146//7146 -f 7152//7152 7154//7154 7111//7111 -f 7111//7111 7154//7154 7134//7134 -f 7125//7125 7207//7207 7137//7137 -f 7137//7137 7207//7207 7205//7205 -f 7137//7137 7205//7205 7138//7138 -f 7138//7138 7205//7205 7204//7204 -f 7138//7138 7204//7204 7076//7076 -f 7076//7076 7204//7204 7179//7179 -f 7076//7076 7179//7179 7078//7078 -f 7078//7078 7179//7179 7181//7181 -f 7078//7078 7181//7181 7115//7115 -f 7115//7115 7181//7181 7171//7171 -f 7115//7115 7171//7171 7116//7116 -f 7116//7116 7171//7171 7170//7170 -f 7116//7116 7170//7170 7117//7117 -f 7117//7117 7170//7170 7169//7169 -f 7117//7117 7169//7169 7119//7119 -f 7119//7119 7169//7169 7212//7212 -f 7119//7119 7212//7212 7121//7121 -f 7121//7121 7212//7212 7211//7211 -f 7121//7121 7211//7211 7122//7122 -f 7122//7122 7211//7211 7209//7209 -f 7122//7122 7209//7209 7123//7123 -f 7123//7123 7209//7209 7208//7208 -f 7123//7123 7208//7208 7125//7125 -f 7125//7125 7208//7208 7207//7207 -f 7132//7132 7156//7156 7133//7133 -f 7133//7133 7156//7156 7155//7155 -f 7133//7133 7155//7155 7135//7135 -f 7135//7135 7155//7155 7153//7153 -f 7135//7135 7153//7153 7136//7136 -f 7136//7136 7153//7153 7151//7151 -f 7136//7136 7151//7151 7113//7113 -f 7113//7113 7151//7151 7150//7150 -f 7113//7113 7150//7150 7114//7114 -f 7114//7114 7150//7150 7174//7174 -f 7114//7114 7174//7174 7074//7074 -f 7074//7074 7174//7174 7173//7173 -f 7074//7074 7173//7173 7084//7084 -f 7084//7084 7173//7173 7163//7163 -f 7084//7084 7163//7163 7085//7085 -f 7085//7085 7163//7163 7162//7162 -f 7085//7085 7162//7162 7079//7079 -f 7079//7079 7162//7162 7190//7190 -f 7079//7079 7190//7190 7077//7077 -f 7077//7077 7190//7190 7191//7191 -f 7077//7077 7191//7191 7075//7075 -f 7075//7075 7191//7191 7193//7193 -f 7075//7075 7193//7193 7132//7132 -f 7132//7132 7193//7193 7156//7156 -f 7081//7081 7157//7157 7087//7087 -f 7087//7087 7157//7157 7194//7194 -f 7087//7087 7194//7194 7088//7088 -f 7088//7088 7194//7194 7192//7192 -f 7088//7088 7192//7192 7127//7127 -f 7127//7127 7192//7192 7161//7161 -f 7127//7127 7161//7161 7129//7129 -f 7129//7129 7161//7161 7160//7160 -f 7129//7129 7160//7160 7130//7130 -f 7130//7130 7160//7160 7189//7189 -f 7130//7130 7189//7189 7131//7131 -f 7131//7131 7189//7189 7143//7143 -f 7131//7131 7143//7143 7090//7090 -f 7090//7090 7143//7143 7166//7166 -f 7090//7090 7166//7166 7092//7092 -f 7092//7092 7166//7166 7148//7148 -f 7092//7092 7148//7148 7095//7095 -f 7095//7095 7148//7148 7147//7147 -f 7095//7095 7147//7147 7096//7096 -f 7096//7096 7147//7147 7195//7195 -f 7096//7096 7195//7195 7098//7098 -f 7098//7098 7195//7195 7197//7197 -f 7098//7098 7197//7197 7081//7081 -f 7081//7081 7197//7197 7157//7157 -f 7102//7102 7187//7187 7104//7104 -f 7104//7104 7187//7187 7185//7185 -f 7104//7104 7185//7185 7106//7106 -f 7106//7106 7185//7185 7183//7183 -f 7106//7106 7183//7183 7120//7120 -f 7120//7120 7183//7183 7210//7210 -f 7120//7120 7210//7210 7118//7118 -f 7118//7118 7210//7210 7168//7168 -f 7118//7118 7168//7168 7128//7128 -f 7128//7128 7168//7168 7167//7167 -f 7128//7128 7167//7167 7086//7086 -f 7086//7086 7167//7167 7159//7159 -f 7086//7086 7159//7159 7083//7083 -f 7083//7083 7159//7159 7158//7158 -f 7083//7083 7158//7158 7082//7082 -f 7082//7082 7158//7158 7199//7199 -f 7082//7082 7199//7199 7080//7080 -f 7080//7080 7199//7199 7198//7198 -f 7080//7080 7198//7198 7108//7108 -f 7108//7108 7198//7198 7201//7201 -f 7108//7108 7201//7201 7100//7100 -f 7100//7100 7201//7201 7200//7200 -f 7100//7100 7200//7200 7102//7102 -f 7102//7102 7200//7200 7187//7187 -f 7134//7134 7154//7154 7180//7180 -f 7134//7134 7180//7180 7140//7140 -f 7140//7140 7180//7180 7178//7178 -f 7140//7140 7178//7178 7139//7139 -f 7139//7139 7178//7178 7177//7177 -f 7139//7139 7177//7177 7126//7126 -f 7126//7126 7177//7177 7206//7206 -f 7126//7126 7206//7206 7124//7124 -f 7124//7124 7206//7206 7182//7182 -f 7124//7124 7182//7182 7105//7105 -f 7103//7103 7184//7184 7186//7186 -f 7103//7103 7186//7186 7101//7101 -f 7101//7101 7186//7186 7188//7188 -f 7101//7101 7188//7188 7099//7099 -f 7099//7099 7188//7188 7202//7202 -f 7099//7099 7202//7202 7107//7107 -f 7107//7107 7202//7202 7203//7203 -f 7107//7107 7203//7203 7109//7109 -f 7109//7109 7203//7203 7196//7196 -f 7109//7109 7196//7196 7097//7097 -f 7073//7073 7172//7172 7175//7175 -f 7073//7073 7175//7175 7112//7112 -f 7112//7112 7175//7175 7176//7176 -f 7112//7112 7176//7176 7110//7110 -f 7110//7110 7176//7176 7152//7152 -f 7110//7110 7152//7152 7111//7111 -f 7094//7094 7149//7149 7164//7164 -f 7094//7094 7164//7164 7093//7093 -f 7093//7093 7164//7164 7165//7165 -f 7093//7093 7165//7165 7091//7091 -f 7091//7091 7165//7165 7142//7142 -f 7091//7091 7142//7142 7089//7089 -f 7213//7213 7214//7214 7215//7215 -f 7216//7216 7217//7217 7218//7218 -f 7219//7219 7220//7220 7221//7221 -f 7222//7222 7223//7223 7224//7224 -f 7225//7225 7226//7226 7227//7227 -f 7227//7227 7226//7226 7228//7228 -f 7229//7229 7230//7230 7231//7231 -f 7231//7231 7230//7230 7232//7232 -f 7223//7223 7233//7233 7224//7224 -f 7224//7224 7233//7233 7234//7234 -f 7224//7224 7234//7234 7225//7225 -f 7225//7225 7234//7234 7235//7235 -f 7225//7225 7235//7235 7226//7226 -f 7224//7224 7236//7236 7222//7222 -f 7222//7222 7236//7236 7237//7237 -f 7222//7222 7237//7237 7238//7238 -f 7238//7238 7237//7237 7239//7239 -f 7238//7238 7239//7239 7240//7240 -f 7240//7240 7239//7239 7241//7241 -f 7240//7240 7241//7241 7232//7232 -f 7232//7232 7241//7241 7242//7242 -f 7232//7232 7242//7242 7231//7231 -f 7224//7224 7243//7243 7236//7236 -f 7236//7236 7243//7243 7244//7244 -f 7236//7236 7244//7244 7245//7245 -f 7245//7245 7244//7244 7246//7246 -f 7245//7245 7246//7246 7247//7247 -f 7247//7247 7246//7246 7248//7248 -f 7249//7249 7250//7250 7251//7251 -f 7251//7251 7250//7250 7252//7252 -f 7251//7251 7252//7252 7248//7248 -f 7248//7248 7252//7252 7253//7253 -f 7248//7248 7253//7253 7254//7254 -f 7255//7255 7256//7256 7257//7257 -f 7257//7257 7256//7256 7258//7258 -f 7259//7259 7260//7260 7261//7261 -f 7261//7261 7260//7260 7262//7262 -f 7261//7261 7262//7262 7263//7263 -f 7263//7263 7262//7262 7264//7264 -f 7263//7263 7264//7264 7265//7265 -f 7255//7255 7257//7257 7254//7254 -f 7254//7254 7257//7257 7266//7266 -f 7254//7254 7266//7266 7248//7248 -f 7248//7248 7266//7266 7267//7267 -f 7248//7248 7267//7267 7247//7247 -f 7268//7268 7258//7258 7269//7269 -f 7269//7269 7258//7258 7270//7270 -f 7269//7269 7270//7270 7271//7271 -f 7271//7271 7270//7270 7272//7272 -f 7271//7271 7272//7272 7273//7273 -f 7256//7256 7259//7259 7258//7258 -f 7258//7258 7259//7259 7261//7261 -f 7258//7258 7261//7261 7270//7270 -f 7270//7270 7261//7261 7274//7274 -f 7270//7270 7274//7274 7272//7272 -f 7272//7272 7274//7274 7275//7275 -f 7276//7276 7277//7277 7213//7213 -f 7213//7213 7277//7277 7278//7278 -f 7279//7279 7275//7275 7280//7280 -f 7280//7280 7275//7275 7281//7281 -f 7280//7280 7281//7281 7282//7282 -f 7282//7282 7281//7281 7283//7283 -f 7284//7284 7285//7285 7286//7286 -f 7286//7286 7285//7285 7287//7287 -f 7286//7286 7287//7287 7288//7288 -f 7287//7287 7289//7289 7288//7288 -f 7288//7288 7289//7289 7290//7290 -f 7288//7288 7290//7290 7291//7291 -f 7291//7291 7290//7290 7292//7292 -f 7291//7291 7292//7292 7293//7293 -f 7294//7294 7295//7295 7296//7296 -f 7296//7296 7295//7295 7297//7297 -f 7296//7296 7297//7297 7298//7298 -f 7298//7298 7297//7297 7299//7299 -f 7294//7294 7300//7300 7295//7295 -f 7295//7295 7300//7300 7301//7301 -f 7295//7295 7301//7301 7285//7285 -f 7302//7302 7221//7221 7303//7303 -f 7303//7303 7221//7221 7304//7304 -f 7303//7303 7304//7304 7305//7305 -f 7301//7301 7306//7306 7285//7285 -f 7285//7285 7306//7306 7307//7307 -f 7285//7285 7307//7307 7287//7287 -f 7287//7287 7307//7307 7308//7308 -f 7287//7287 7308//7308 7309//7309 -f 7309//7309 7308//7308 7305//7305 -f 7309//7309 7305//7305 7310//7310 -f 7310//7310 7305//7305 7304//7304 -f 7219//7219 7221//7221 7311//7311 -f 7311//7311 7221//7221 7312//7312 -f 7311//7311 7312//7312 7313//7313 -f 7313//7313 7312//7312 7314//7314 -f 7313//7313 7314//7314 7315//7315 -f 7315//7315 7314//7314 7316//7316 -f 7315//7315 7316//7316 7317//7317 -f 7317//7317 7316//7316 7218//7218 -f 7218//7218 7316//7316 7318//7318 -f 7218//7218 7318//7318 7216//7216 -f 7319//7319 7320//7320 7316//7316 -f 7316//7316 7320//7320 7321//7321 -f 7316//7316 7321//7321 7322//7322 -f 7323//7323 7318//7318 7324//7324 -f 7324//7324 7318//7318 7316//7316 -f 7324//7324 7316//7316 7325//7325 -f 7325//7325 7316//7316 7322//7322 -f 7326//7326 7327//7327 7319//7319 -f 7319//7319 7327//7327 7328//7328 -f 7319//7319 7328//7328 7320//7320 -f 7325//7325 7329//7329 7324//7324 -f 7324//7324 7329//7329 7330//7330 -f 7324//7324 7330//7330 7331//7331 -f 7331//7331 7330//7330 7332//7332 -f 7332//7332 7333//7333 7331//7331 -f 7331//7331 7333//7333 7334//7334 -f 7331//7331 7334//7334 7326//7326 -f 7326//7326 7334//7334 7335//7335 -f 7326//7326 7335//7335 7327//7327 -f 7336//7336 7337//7337 7338//7338 -f 7338//7338 7339//7339 7336//7336 -f 7336//7336 7339//7339 7340//7340 -f 7336//7336 7340//7340 7314//7314 -f 7314//7314 7340//7340 7341//7341 -f 7314//7314 7341//7341 7342//7342 -f 7342//7342 7343//7343 7314//7314 -f 7314//7314 7343//7343 7344//7344 -f 7314//7314 7344//7344 7316//7316 -f 7316//7316 7344//7344 7345//7345 -f 7316//7316 7345//7345 7319//7319 -f 7343//7343 7346//7346 7344//7344 -f 7344//7344 7346//7346 7347//7347 -f 7344//7344 7347//7347 7348//7348 -f 7348//7348 7347//7347 7349//7349 -f 7349//7349 7350//7350 7348//7348 -f 7348//7348 7350//7350 7351//7351 -f 7348//7348 7351//7351 7337//7337 -f 7337//7337 7351//7351 7352//7352 -f 7337//7337 7352//7352 7338//7338 -f 7353//7353 7354//7354 7355//7355 -f 7356//7356 7357//7357 7358//7358 -f 7358//7358 7357//7357 7359//7359 -f 7358//7358 7359//7359 7360//7360 -f 7360//7360 7359//7359 7361//7361 -f 7302//7302 7299//7299 7221//7221 -f 7221//7221 7299//7299 7297//7297 -f 7221//7221 7297//7297 7312//7312 -f 7312//7312 7297//7297 7362//7362 -f 7312//7312 7362//7362 7353//7353 -f 7355//7355 7363//7363 7353//7353 -f 7353//7353 7363//7363 7364//7364 -f 7353//7353 7364//7364 7312//7312 -f 7312//7312 7364//7364 7365//7365 -f 7312//7312 7365//7365 7366//7366 -f 7366//7366 7361//7361 7312//7312 -f 7312//7312 7361//7361 7359//7359 -f 7312//7312 7359//7359 7314//7314 -f 7314//7314 7359//7359 7367//7367 -f 7314//7314 7367//7367 7336//7336 -f 7356//7356 7368//7368 7357//7357 -f 7357//7357 7368//7368 7369//7369 -f 7357//7357 7369//7369 7354//7354 -f 7354//7354 7369//7369 7370//7370 -f 7354//7354 7370//7370 7355//7355 -f 7279//7279 7371//7371 7275//7275 -f 7275//7275 7371//7371 7372//7372 -f 7275//7275 7372//7372 7272//7272 -f 7272//7272 7372//7372 7373//7373 -f 7272//7272 7373//7373 7374//7374 -f 7374//7374 7373//7373 7375//7375 -f 7374//7374 7375//7375 7376//7376 -f 7376//7376 7375//7375 7377//7377 -f 7376//7376 7377//7377 7378//7378 -f 7378//7378 7377//7377 7276//7276 -f 7378//7378 7276//7276 7292//7292 -f 7292//7292 7276//7276 7213//7213 -f 7292//7292 7213//7213 7293//7293 -f 7293//7293 7213//7213 7215//7215 -f 7379//7379 7214//7214 7281//7281 -f 7281//7281 7214//7214 7213//7213 -f 7281//7281 7213//7213 7283//7283 -f 7283//7283 7213//7213 7278//7278 -f 7380//7380 7381//7381 7251//7251 -f 7251//7251 7381//7381 7263//7263 -f 7251//7251 7263//7263 7249//7249 -f 7249//7249 7263//7263 7265//7265 -f 7382//7382 7243//7243 7383//7383 -f 7383//7383 7243//7243 7224//7224 -f 7383//7383 7224//7224 7384//7384 -f 7384//7384 7224//7224 7225//7225 -f 7385//7385 7386//7386 7387//7387 -f 7388//7388 7389//7389 7390//7390 -f 7391//7391 7392//7392 7393//7393 -f 7393//7393 7392//7392 7390//7390 -f 7394//7394 7395//7395 7396//7396 -f 7396//7396 7395//7395 7391//7391 -f 7396//7396 7391//7391 7397//7397 -f 7397//7397 7391//7391 7393//7393 -f 7228//7228 7229//7229 7227//7227 -f 7227//7227 7229//7229 7231//7231 -f 7227//7227 7231//7231 7398//7398 -f 7398//7398 7231//7231 7387//7387 -f 7398//7398 7387//7387 7399//7399 -f 7399//7399 7387//7387 7386//7386 -f 7399//7399 7386//7386 7388//7388 -f 7388//7388 7386//7386 7400//7400 -f 7388//7388 7400//7400 7389//7389 -f 7394//7394 7401//7401 7395//7395 -f 7395//7395 7401//7401 7402//7402 -f 7395//7395 7402//7402 7387//7387 -f 7387//7387 7402//7402 7403//7403 -f 7387//7387 7403//7403 7385//7385 -f 7390//7390 7392//7392 7388//7388 -f 7388//7388 7392//7392 7404//7404 -f 7388//7388 7404//7404 7405//7405 -f 7406//7406 7407//7407 7395//7395 -f 7408//7408 7409//7409 7410//7410 -f 7410//7410 7409//7409 7411//7411 -f 7412//7412 7413//7413 7414//7414 -f 7414//7414 7413//7413 7411//7411 -f 7408//7408 7410//7410 7407//7407 -f 7407//7407 7410//7410 7415//7415 -f 7407//7407 7415//7415 7395//7395 -f 7395//7395 7415//7415 7416//7416 -f 7395//7395 7416//7416 7391//7391 -f 7414//7414 7417//7417 7412//7412 -f 7412//7412 7417//7417 7418//7418 -f 7412//7412 7418//7418 7419//7419 -f 7419//7419 7418//7418 7420//7420 -f 7420//7420 7421//7421 7419//7419 -f 7419//7419 7421//7421 7422//7422 -f 7419//7419 7422//7422 7395//7395 -f 7395//7395 7422//7422 7423//7423 -f 7395//7395 7423//7423 7406//7406 -f 7411//7411 7413//7413 7410//7410 -f 7410//7410 7413//7413 7424//7424 -f 7410//7410 7424//7424 7425//7425 -f 7426//7426 7427//7427 7419//7419 -f 7428//7428 7429//7429 7430//7430 -f 7431//7431 7432//7432 7433//7433 -f 7433//7433 7432//7432 7428//7428 -f 7433//7433 7428//7428 7419//7419 -f 7434//7434 7435//7435 7428//7428 -f 7428//7428 7435//7435 7436//7436 -f 7428//7428 7436//7436 7437//7437 -f 7438//7438 7439//7439 7440//7440 -f 7440//7440 7439//7439 7441//7441 -f 7428//7428 7430//7430 7434//7434 -f 7434//7434 7430//7430 7442//7442 -f 7434//7434 7442//7442 7441//7441 -f 7437//7437 7443//7443 7428//7428 -f 7428//7428 7443//7443 7444//7444 -f 7428//7428 7444//7444 7419//7419 -f 7419//7419 7444//7444 7445//7445 -f 7419//7419 7445//7445 7426//7426 -f 7438//7438 7440//7440 7427//7427 -f 7427//7427 7440//7440 7446//7446 -f 7427//7427 7446//7446 7419//7419 -f 7419//7419 7446//7446 7447//7447 -f 7419//7419 7447//7447 7412//7412 -f 7441//7441 7442//7442 7440//7440 -f 7440//7440 7442//7442 7448//7448 -f 7440//7440 7448//7448 7449//7449 -f 7231//7231 7450//7450 7451//7451 -f 7452//7452 7453//7453 7454//7454 -f 7454//7454 7453//7453 7433//7433 -f 7454//7454 7433//7433 7455//7455 -f 7455//7455 7433//7433 7419//7419 -f 7455//7455 7419//7419 7456//7456 -f 7456//7456 7419//7419 7395//7395 -f 7456//7456 7395//7395 7451//7451 -f 7451//7451 7395//7395 7387//7387 -f 7451//7451 7387//7387 7231//7231 -f 7457//7457 7458//7458 7268//7268 -f 7457//7457 7268//7268 7459//7459 -f 7459//7459 7268//7268 7269//7269 -f 7459//7459 7269//7269 7271//7271 -f 7460//7460 7461//7461 7462//7462 -f 7463//7463 7464//7464 7465//7465 -f 7464//7464 7466//7466 7465//7465 -f 7465//7465 7466//7466 7467//7467 -f 7465//7465 7467//7467 7468//7468 -f 7469//7469 7470//7470 7465//7465 -f 7465//7465 7470//7470 7460//7460 -f 7460//7460 7462//7462 7465//7465 -f 7465//7465 7462//7462 7471//7471 -f 7465//7465 7471//7471 7463//7463 -f 7472//7472 7473//7473 7474//7474 -f 7474//7474 7473//7473 7468//7468 -f 7474//7474 7468//7468 7475//7475 -f 7475//7475 7468//7468 7467//7467 -f 7476//7476 7477//7477 7478//7478 -f 7478//7478 7477//7477 7479//7479 -f 7480//7480 7476//7476 7481//7481 -f 7481//7481 7476//7476 7478//7478 -f 7481//7481 7478//7478 7482//7482 -f 7482//7482 7478//7478 7483//7483 -f 7454//7454 7455//7455 7484//7484 -f 7454//7454 7484//7484 7485//7485 -f 7486//7486 7487//7487 7488//7488 -f 7489//7489 7490//7490 7491//7491 -f 7491//7491 7490//7490 7492//7492 -f 7491//7491 7492//7492 7493//7493 -f 7493//7493 7492//7492 7494//7494 -f 7493//7493 7494//7494 7495//7495 -f 7495//7495 7494//7494 7496//7496 -f 7495//7495 7496//7496 7497//7497 -f 7497//7497 7496//7496 7498//7498 -f 7499//7499 7500//7500 7501//7501 -f 7501//7501 7500//7500 7502//7502 -f 7501//7501 7502//7502 7503//7503 -f 7503//7503 7502//7502 7504//7504 -f 7503//7503 7504//7504 7505//7505 -f 7505//7505 7504//7504 7506//7506 -f 7506//7506 7507//7507 7505//7505 -f 7505//7505 7507//7507 7508//7508 -f 7505//7505 7508//7508 7509//7509 -f 7509//7509 7508//7508 7510//7510 -f 7507//7507 7511//7511 7508//7508 -f 7508//7508 7511//7511 7512//7512 -f 7508//7508 7512//7512 7489//7489 -f 7489//7489 7512//7512 7513//7513 -f 7489//7489 7513//7513 7490//7490 -f 7501//7501 7514//7514 7499//7499 -f 7499//7499 7514//7514 7515//7515 -f 7499//7499 7515//7515 7487//7487 -f 7487//7487 7515//7515 7516//7516 -f 7487//7487 7516//7516 7488//7488 -f 7517//7517 7518//7518 7519//7519 -f 7519//7519 7518//7518 7520//7520 -f 7519//7519 7520//7520 7521//7521 -f 7521//7521 7520//7520 7522//7522 -f 7521//7521 7522//7522 7488//7488 -f 7488//7488 7522//7522 7523//7523 -f 7488//7488 7523//7523 7486//7486 -f 7524//7524 7525//7525 7496//7496 -f 7496//7496 7525//7525 7526//7526 -f 7496//7496 7526//7526 7498//7498 -f 7524//7524 7527//7527 7525//7525 -f 7525//7525 7527//7527 7528//7528 -f 7525//7525 7528//7528 7484//7484 -f 7484//7484 7528//7528 7529//7529 -f 7484//7484 7529//7529 7530//7530 -f 7530//7530 7531//7531 7484//7484 -f 7484//7484 7531//7531 7517//7517 -f 7484//7484 7517//7517 7485//7485 -f 7485//7485 7517//7517 7519//7519 -f 7477//7477 7532//7532 7479//7479 -f 7479//7479 7532//7532 7533//7533 -f 7533//7533 7532//7532 7534//7534 -f 7534//7534 7532//7532 7535//7535 -f 7534//7534 7535//7535 7536//7536 -f 7536//7536 7535//7535 7537//7537 -f 7537//7537 7535//7535 7538//7538 -f 7537//7537 7538//7538 7539//7539 -f 7539//7539 7538//7538 7540//7540 -f 7540//7540 7538//7538 7541//7541 -f 7540//7540 7541//7541 7542//7542 -f 7543//7543 7544//7544 7545//7545 -f 7542//7542 7541//7541 7545//7545 -f 7545//7545 7541//7541 7546//7546 -f 7545//7545 7546//7546 7543//7543 -f 7547//7547 7548//7548 7549//7549 -f 7550//7550 7551//7551 7552//7552 -f 7547//7547 7549//7549 7553//7553 -f 7549//7549 7554//7554 7553//7553 -f 7553//7553 7554//7554 7555//7555 -f 7553//7553 7555//7555 7556//7556 -f 7550//7550 7552//7552 7557//7557 -f 7552//7552 7558//7558 7557//7557 -f 7557//7557 7558//7558 7559//7559 -f 7557//7557 7559//7559 7547//7547 -f 7547//7547 7559//7559 7560//7560 -f 7547//7547 7560//7560 7548//7548 -f 7555//7555 7561//7561 7556//7556 -f 7556//7556 7561//7561 7562//7562 -f 7556//7556 7562//7562 7550//7550 -f 7550//7550 7562//7562 7563//7563 -f 7550//7550 7563//7563 7551//7551 -f 7564//7564 7565//7565 7566//7566 -f 7566//7566 7565//7565 7567//7567 -f 7568//7568 7569//7569 7570//7570 -f 7570//7570 7569//7569 7571//7571 -f 7571//7571 7572//7572 7570//7570 -f 7570//7570 7572//7572 7573//7573 -f 7570//7570 7573//7573 7574//7574 -f 7573//7573 7575//7575 7574//7574 -f 7574//7574 7575//7575 7576//7576 -f 7574//7574 7576//7576 7564//7564 -f 7564//7564 7576//7576 7577//7577 -f 7564//7564 7577//7577 7565//7565 -f 7567//7567 7578//7578 7566//7566 -f 7566//7566 7578//7578 7579//7579 -f 7566//7566 7579//7579 7568//7568 -f 7568//7568 7579//7579 7580//7580 -f 7568//7568 7580//7580 7569//7569 -f 7581//7581 7582//7582 7583//7583 -f 7583//7583 7582//7582 7584//7584 -f 7585//7585 7586//7586 7581//7581 -f 7581//7581 7586//7586 7587//7587 -f 7581//7581 7587//7587 7582//7582 -f 7584//7584 7588//7588 7583//7583 -f 7583//7583 7588//7588 7589//7589 -f 7583//7583 7589//7589 7590//7590 -f 7591//7591 7592//7592 7593//7593 -f 7593//7593 7592//7592 7590//7590 -f 7593//7593 7590//7590 7594//7594 -f 7594//7594 7590//7590 7589//7589 -f 7591//7591 7595//7595 7592//7592 -f 7592//7592 7595//7595 7596//7596 -f 7592//7592 7596//7596 7585//7585 -f 7585//7585 7596//7596 7597//7597 -f 7585//7585 7597//7597 7586//7586 -f 7598//7598 7599//7599 7600//7600 -f 7600//7600 7599//7599 7601//7601 -f 7602//7602 7603//7603 7604//7604 -f 7605//7605 7606//7606 7535//7535 -f 7607//7607 7608//7608 7609//7609 -f 7609//7609 7608//7608 7610//7610 -f 7535//7535 7606//7606 7538//7538 -f 7538//7538 7606//7606 7611//7611 -f 7538//7538 7611//7611 7541//7541 -f 7612//7612 7613//7613 7614//7614 -f 7614//7614 7613//7613 7615//7615 -f 7616//7616 7617//7617 7618//7618 -f 7618//7618 7617//7617 7619//7619 -f 7618//7618 7619//7619 7620//7620 -f 7621//7621 7622//7622 7623//7623 -f 7624//7624 7625//7625 7626//7626 -f 7626//7626 7625//7625 7627//7627 -f 7628//7628 7629//7629 7630//7630 -f 7631//7631 7632//7632 7633//7633 -f 7634//7634 7635//7635 7636//7636 -f 7636//7636 7635//7635 7637//7637 -f 7638//7638 7639//7639 7633//7633 -f 7640//7640 7641//7641 7642//7642 -f 7642//7642 7641//7641 7643//7643 -f 7644//7644 7645//7645 7646//7646 -f 7647//7647 7648//7648 7649//7649 -f 7649//7649 7648//7648 7650//7650 -f 7651//7651 7652//7652 7653//7653 -f 7653//7653 7652//7652 7654//7654 -f 7639//7639 7655//7655 7633//7633 -f 7633//7633 7655//7655 7656//7656 -f 7633//7633 7656//7656 7631//7631 -f 7615//7615 7628//7628 7632//7632 -f 7657//7657 7658//7658 7659//7659 -f 7659//7659 7658//7658 7660//7660 -f 7661//7661 7623//7623 7662//7662 -f 7662//7662 7623//7623 7663//7663 -f 7664//7664 7609//7609 7631//7631 -f 7631//7631 7609//7609 7610//7610 -f 7631//7631 7610//7610 7632//7632 -f 7632//7632 7610//7610 7626//7626 -f 7632//7632 7626//7626 7615//7615 -f 7615//7615 7626//7626 7627//7627 -f 7615//7615 7627//7627 7614//7614 -f 7665//7665 7666//7666 7667//7667 -f 7667//7667 7666//7666 7645//7645 -f 7667//7667 7645//7645 7643//7643 -f 7643//7643 7645//7645 7644//7644 -f 7643//7643 7644//7644 7668//7668 -f 7669//7669 7670//7670 7646//7646 -f 7646//7646 7670//7670 7621//7621 -f 7646//7646 7621//7621 7644//7644 -f 7644//7644 7621//7621 7623//7623 -f 7644//7644 7623//7623 7671//7671 -f 7672//7672 7673//7673 7674//7674 -f 7674//7674 7673//7673 7675//7675 -f 7676//7676 7677//7677 7678//7678 -f 7630//7630 7620//7620 7628//7628 -f 7628//7628 7620//7620 7619//7619 -f 7628//7628 7619//7619 7632//7632 -f 7632//7632 7619//7619 7642//7642 -f 7632//7632 7642//7642 7679//7679 -f 7679//7679 7642//7642 7643//7643 -f 7679//7679 7643//7643 7680//7680 -f 7680//7680 7643//7643 7668//7668 -f 7681//7681 7678//7678 7682//7682 -f 7682//7682 7678//7678 7683//7683 -f 7682//7682 7683//7683 7661//7661 -f 7611//7611 7676//7676 7684//7684 -f 7684//7684 7676//7676 7678//7678 -f 7684//7684 7678//7678 7685//7685 -f 7685//7685 7678//7678 7681//7681 -f 7677//7677 7676//7676 7632//7632 -f 7632//7632 7676//7676 7686//7686 -f 7632//7632 7686//7686 7687//7687 -f 7688//7688 7689//7689 7690//7690 -f 7690//7690 7689//7689 7691//7691 -f 7690//7690 7691//7691 7692//7692 -f 7683//7683 7693//7693 7661//7661 -f 7661//7661 7693//7693 7694//7694 -f 7661//7661 7694//7694 7623//7623 -f 7623//7623 7694//7694 7695//7695 -f 7623//7623 7695//7695 7671//7671 -f 7696//7696 7697//7697 7632//7632 -f 7632//7632 7697//7697 7698//7698 -f 7632//7632 7698//7698 7633//7633 -f 7699//7699 7477//7477 7700//7700 -f 7700//7700 7477//7477 7476//7476 -f 7700//7700 7476//7476 7701//7701 -f 7701//7701 7476//7476 7702//7702 -f 7701//7701 7702//7702 7703//7703 -f 7703//7703 7702//7702 7638//7638 -f 7703//7703 7638//7638 7704//7704 -f 7704//7704 7638//7638 7633//7633 -f 7604//7604 7705//7705 7602//7602 -f 7602//7602 7705//7705 7706//7706 -f 7602//7602 7706//7706 7707//7707 -f 7708//7708 7709//7709 7663//7663 -f 7710//7710 7696//7696 7711//7711 -f 7711//7711 7696//7696 7632//7632 -f 7711//7711 7632//7632 7712//7712 -f 7712//7712 7632//7632 7687//7687 -f 7605//7605 7535//7535 7713//7713 -f 7713//7713 7535//7535 7532//7532 -f 7713//7713 7532//7532 7714//7714 -f 7714//7714 7532//7532 7477//7477 -f 7714//7714 7477//7477 7715//7715 -f 7715//7715 7477//7477 7699//7699 -f 7715//7715 7699//7699 7716//7716 -f 7716//7716 7699//7699 7717//7717 -f 7716//7716 7717//7717 7711//7711 -f 7711//7711 7717//7717 7718//7718 -f 7711//7711 7718//7718 7710//7710 -f 7719//7719 7720//7720 7721//7721 -f 7721//7721 7720//7720 7722//7722 -f 7721//7721 7722//7722 7723//7723 -f 7724//7724 7725//7725 7723//7723 -f 7723//7723 7725//7725 7708//7708 -f 7723//7723 7708//7708 7721//7721 -f 7721//7721 7708//7708 7663//7663 -f 7721//7721 7663//7663 7601//7601 -f 7601//7601 7663//7663 7623//7623 -f 7601//7601 7623//7623 7600//7600 -f 7600//7600 7623//7623 7726//7726 -f 7675//7675 7727//7727 7674//7674 -f 7674//7674 7727//7727 7728//7728 -f 7674//7674 7728//7728 7729//7729 -f 7636//7636 7684//7684 7675//7675 -f 7675//7675 7684//7684 7730//7730 -f 7675//7675 7730//7730 7727//7727 -f 7731//7731 7732//7732 7709//7709 -f 7709//7709 7732//7732 7733//7733 -f 7709//7709 7733//7733 7663//7663 -f 7663//7663 7733//7733 7734//7734 -f 7735//7735 7674//7674 7736//7736 -f 7736//7736 7674//7674 7729//7729 -f 7736//7736 7729//7729 7734//7734 -f 7734//7734 7729//7729 7737//7737 -f 7734//7734 7737//7737 7663//7663 -f 7637//7637 7649//7649 7636//7636 -f 7636//7636 7649//7649 7650//7650 -f 7636//7636 7650//7650 7684//7684 -f 7684//7684 7650//7650 7653//7653 -f 7738//7738 7602//7602 7684//7684 -f 7684//7684 7602//7602 7707//7707 -f 7684//7684 7707//7707 7611//7611 -f 7611//7611 7707//7707 7546//7546 -f 7611//7611 7546//7546 7541//7541 -f 7654//7654 7659//7659 7653//7653 -f 7653//7653 7659//7659 7660//7660 -f 7653//7653 7660//7660 7684//7684 -f 7684//7684 7660//7660 7690//7690 -f 7684//7684 7690//7690 7738//7738 -f 7738//7738 7690//7690 7692//7692 -f 7738//7738 7692//7692 7739//7739 -f 7739//7739 7692//7692 7740//7740 -f 7741//7741 7742//7742 7743//7743 -f 7743//7743 7742//7742 7744//7744 -f 7743//7743 7744//7744 7745//7745 -f 7745//7745 7744//7744 7746//7746 -f 7745//7745 7746//7746 7747//7747 -f 7748//7748 7749//7749 7750//7750 -f 7750//7750 7749//7749 7751//7751 -f 7750//7750 7751//7751 7752//7752 -f 7752//7752 7751//7751 7753//7753 -f 7752//7752 7753//7753 7754//7754 -f 7755//7755 7756//7756 7757//7757 -f 7757//7757 7756//7756 7758//7758 -f 7757//7757 7758//7758 7759//7759 -f 7759//7759 7758//7758 7760//7760 -f 7759//7759 7760//7760 7761//7761 -f 7762//7762 7763//7763 7553//7553 -f 7553//7553 7763//7763 7764//7764 -f 7553//7553 7764//7764 7547//7547 -f 7547//7547 7764//7764 7765//7765 -f 7547//7547 7765//7765 7766//7766 -f 7766//7766 7765//7765 7767//7767 -f 7768//7768 7769//7769 7574//7574 -f 7574//7574 7769//7769 7770//7770 -f 7574//7574 7770//7770 7570//7570 -f 7570//7570 7770//7770 7771//7771 -f 7570//7570 7771//7771 7772//7772 -f 7772//7772 7771//7771 7773//7773 -f 7774//7774 7775//7775 7590//7590 -f 7590//7590 7775//7775 7776//7776 -f 7590//7590 7776//7776 7583//7583 -f 7583//7583 7776//7776 7777//7777 -f 7583//7583 7777//7777 7778//7778 -f 7778//7778 7777//7777 7779//7779 -f 7780//7780 7781//7781 7782//7782 -f 7782//7782 7781//7781 7783//7783 -f 7784//7784 7785//7785 7786//7786 -f 7787//7787 7788//7788 7789//7789 -f 7789//7789 7788//7788 7784//7784 -f 7789//7789 7784//7784 7790//7790 -f 7790//7790 7784//7784 7786//7786 -f 7787//7787 7791//7791 7788//7788 -f 7788//7788 7791//7791 7792//7792 -f 7788//7788 7792//7792 7780//7780 -f 7780//7780 7792//7792 7793//7793 -f 7780//7780 7793//7793 7781//7781 -f 7783//7783 7794//7794 7782//7782 -f 7782//7782 7794//7794 7795//7795 -f 7782//7782 7795//7795 7785//7785 -f 7785//7785 7795//7795 7796//7796 -f 7785//7785 7796//7796 7786//7786 -f 7797//7797 7798//7798 7799//7799 -f 7799//7799 7798//7798 7800//7800 -f 7801//7801 7802//7802 7803//7803 -f 7803//7803 7802//7802 7804//7804 -f 7803//7803 7804//7804 7805//7805 -f 7805//7805 7804//7804 7806//7806 -f 7805//7805 7806//7806 7807//7807 -f 7799//7799 7808//7808 7797//7797 -f 7797//7797 7808//7808 7809//7809 -f 7797//7797 7809//7809 7806//7806 -f 7806//7806 7809//7809 7810//7810 -f 7806//7806 7810//7810 7807//7807 -f 7801//7801 7811//7811 7802//7802 -f 7802//7802 7811//7811 7812//7812 -f 7802//7802 7812//7812 7798//7798 -f 7798//7798 7812//7812 7813//7813 -f 7798//7798 7813//7813 7800//7800 -f 7814//7814 7815//7815 7816//7816 -f 7816//7816 7815//7815 7817//7817 -f 7816//7816 7817//7817 7818//7818 -f 7818//7818 7817//7817 7819//7819 -f 7818//7818 7819//7819 7820//7820 -f 7821//7821 7822//7822 7785//7785 -f 7785//7785 7822//7822 7823//7823 -f 7785//7785 7823//7823 7782//7782 -f 7782//7782 7823//7823 7824//7824 -f 7782//7782 7824//7824 7825//7825 -f 7825//7825 7824//7824 7826//7826 -f 7827//7827 7828//7828 7829//7829 -f 7830//7830 7831//7831 7832//7832 -f 7827//7827 7829//7829 7832//7832 -f 7832//7832 7829//7829 7833//7833 -f 7832//7832 7833//7833 7830//7830 -f 7834//7834 7835//7835 7797//7797 -f 7797//7797 7835//7835 7836//7836 -f 7797//7797 7836//7836 7798//7798 -f 7798//7798 7836//7836 7837//7837 -f 7798//7798 7837//7837 7838//7838 -f 7838//7838 7837//7837 7839//7839 -f 7840//7840 7631//7631 7841//7841 -f 7841//7841 7631//7631 7656//7656 -f 7543//7543 7546//7546 7842//7842 -f 7842//7842 7546//7546 7707//7707 -f 7707//7707 7706//7706 7842//7842 -f 7842//7842 7706//7706 7843//7843 -f 7842//7842 7843//7843 7844//7844 -f 7844//7844 7843//7843 7429//7429 -f 7844//7844 7429//7429 7845//7845 -f 7845//7845 7429//7429 7428//7428 -f 7843//7843 7706//7706 7846//7846 -f 7846//7846 7706//7706 7705//7705 -f 7442//7442 7430//7430 7846//7846 -f 7846//7846 7705//7705 7604//7604 -f 7442//7442 7846//7846 7448//7448 -f 7448//7448 7846//7846 7765//7765 -f 7765//7765 7846//7846 7604//7604 -f 7765//7765 7604//7604 7767//7767 -f 7740//7740 7692//7692 7847//7847 -f 7847//7847 7446//7446 7440//7440 -f 7740//7740 7847//7847 7763//7763 -f 7763//7763 7847//7847 7764//7764 -f 7764//7764 7847//7847 7440//7440 -f 7764//7764 7440//7440 7449//7449 -f 7847//7847 7692//7692 7848//7848 -f 7848//7848 7692//7692 7691//7691 -f 7413//7413 7412//7412 7848//7848 -f 7848//7848 7691//7691 7689//7689 -f 7413//7413 7848//7848 7424//7424 -f 7424//7424 7848//7848 7771//7771 -f 7771//7771 7848//7848 7689//7689 -f 7771//7771 7689//7689 7773//7773 -f 7657//7657 7659//7659 7849//7849 -f 7849//7849 7415//7415 7410//7410 -f 7657//7657 7849//7849 7769//7769 -f 7769//7769 7849//7849 7770//7770 -f 7770//7770 7849//7849 7410//7410 -f 7770//7770 7410//7410 7425//7425 -f 7849//7849 7659//7659 7850//7850 -f 7850//7850 7659//7659 7654//7654 -f 7392//7392 7391//7391 7850//7850 -f 7850//7850 7654//7654 7652//7652 -f 7392//7392 7850//7850 7404//7404 -f 7404//7404 7850//7850 7777//7777 -f 7777//7777 7850//7850 7652//7652 -f 7777//7777 7652//7652 7779//7779 -f 7647//7647 7649//7649 7851//7851 -f 7851//7851 7399//7399 7388//7388 -f 7647//7647 7851//7851 7775//7775 -f 7775//7775 7851//7851 7776//7776 -f 7776//7776 7851//7851 7388//7388 -f 7776//7776 7388//7388 7405//7405 -f 7851//7851 7649//7649 7852//7852 -f 7852//7852 7649//7649 7637//7637 -f 7225//7225 7227//7227 7852//7852 -f 7852//7852 7637//7637 7635//7635 -f 7225//7225 7852//7852 7384//7384 -f 7384//7384 7852//7852 7824//7824 -f 7824//7824 7852//7852 7635//7635 -f 7824//7824 7635//7635 7826//7826 -f 7672//7672 7674//7674 7853//7853 -f 7853//7853 7244//7244 7243//7243 -f 7672//7672 7853//7853 7822//7822 -f 7822//7822 7853//7853 7823//7823 -f 7823//7823 7853//7853 7243//7243 -f 7823//7823 7243//7243 7382//7382 -f 7853//7853 7674//7674 7854//7854 -f 7854//7854 7674//7674 7735//7735 -f 7854//7854 7735//7735 7246//7246 -f 7246//7246 7735//7735 7736//7736 -f 7246//7246 7736//7736 7855//7855 -f 7855//7855 7736//7736 7734//7734 -f 7855//7855 7734//7734 7856//7856 -f 7856//7856 7734//7734 7733//7733 -f 7251//7251 7248//7248 7856//7856 -f 7856//7856 7733//7733 7732//7732 -f 7251//7251 7856//7856 7380//7380 -f 7380//7380 7856//7856 7837//7837 -f 7837//7837 7856//7856 7732//7732 -f 7837//7837 7732//7732 7839//7839 -f 7724//7724 7723//7723 7857//7857 -f 7857//7857 7261//7261 7263//7263 -f 7724//7724 7857//7857 7835//7835 -f 7835//7835 7857//7857 7836//7836 -f 7836//7836 7857//7857 7263//7263 -f 7836//7836 7263//7263 7381//7381 -f 7857//7857 7723//7723 7858//7858 -f 7858//7858 7723//7723 7722//7722 -f 7281//7281 7275//7275 7858//7858 -f 7858//7858 7722//7722 7720//7720 -f 7281//7281 7858//7858 7379//7379 -f 7379//7379 7858//7858 7859//7859 -f 7859//7859 7858//7858 7720//7720 -f 7859//7859 7720//7720 7860//7860 -f 7861//7861 7862//7862 7863//7863 -f 7863//7863 7862//7862 7864//7864 -f 7863//7863 7864//7864 7865//7865 -f 7865//7865 7864//7864 7859//7859 -f 7865//7865 7859//7859 7866//7866 -f 7866//7866 7859//7859 7860//7860 -f 7598//7598 7600//7600 7867//7867 -f 7867//7867 7291//7291 7293//7293 -f 7598//7598 7867//7867 7862//7862 -f 7862//7862 7867//7867 7864//7864 -f 7864//7864 7867//7867 7293//7293 -f 7864//7864 7293//7293 7215//7215 -f 7867//7867 7600//7600 7868//7868 -f 7868//7868 7600//7600 7726//7726 -f 7868//7868 7726//7726 7288//7288 -f 7288//7288 7726//7726 7623//7623 -f 7288//7288 7623//7623 7869//7869 -f 7869//7869 7623//7623 7622//7622 -f 7869//7869 7622//7622 7870//7870 -f 7870//7870 7622//7622 7621//7621 -f 7670//7670 7871//7871 7872//7872 -f 7621//7621 7670//7670 7870//7870 -f 7870//7870 7670//7670 7872//7872 -f 7870//7870 7872//7872 7286//7286 -f 7286//7286 7872//7872 7284//7284 -f 7873//7873 7874//7874 7875//7875 -f 7875//7875 7874//7874 7876//7876 -f 7875//7875 7876//7876 7877//7877 -f 7877//7877 7876//7876 7872//7872 -f 7877//7877 7872//7872 7878//7878 -f 7878//7878 7872//7872 7871//7871 -f 7297//7297 7295//7295 7879//7879 -f 7879//7879 7295//7295 7876//7876 -f 7876//7876 7874//7874 7879//7879 -f 7879//7879 7874//7874 7665//7665 -f 7879//7879 7665//7665 7667//7667 -f 7879//7879 7667//7667 7880//7880 -f 7880//7880 7667//7667 7643//7643 -f 7641//7641 7881//7881 7882//7882 -f 7643//7643 7641//7641 7880//7880 -f 7880//7880 7641//7641 7882//7882 -f 7880//7880 7882//7882 7353//7353 -f 7353//7353 7882//7882 7354//7354 -f 7883//7883 7884//7884 7885//7885 -f 7885//7885 7884//7884 7886//7886 -f 7885//7885 7886//7886 7887//7887 -f 7887//7887 7886//7886 7882//7882 -f 7887//7887 7882//7882 7888//7888 -f 7888//7888 7882//7882 7881//7881 -f 7359//7359 7357//7357 7889//7889 -f 7889//7889 7357//7357 7886//7886 -f 7886//7886 7884//7884 7889//7889 -f 7889//7889 7884//7884 7616//7616 -f 7889//7889 7616//7616 7618//7618 -f 7889//7889 7618//7618 7890//7890 -f 7890//7890 7618//7618 7620//7620 -f 7630//7630 7891//7891 7892//7892 -f 7620//7620 7630//7630 7890//7890 -f 7890//7890 7630//7630 7892//7892 -f 7890//7890 7892//7892 7336//7336 -f 7336//7336 7892//7892 7337//7337 -f 7893//7893 7894//7894 7895//7895 -f 7895//7895 7894//7894 7896//7896 -f 7895//7895 7896//7896 7897//7897 -f 7897//7897 7896//7896 7892//7892 -f 7897//7897 7892//7892 7898//7898 -f 7898//7898 7892//7892 7891//7891 -f 7344//7344 7348//7348 7899//7899 -f 7899//7899 7348//7348 7896//7896 -f 7896//7896 7894//7894 7899//7899 -f 7899//7899 7894//7894 7612//7612 -f 7899//7899 7612//7612 7614//7614 -f 7899//7899 7614//7614 7900//7900 -f 7900//7900 7614//7614 7627//7627 -f 7625//7625 7901//7901 7902//7902 -f 7627//7627 7625//7625 7900//7900 -f 7900//7900 7625//7625 7902//7902 -f 7900//7900 7902//7902 7319//7319 -f 7319//7319 7902//7902 7326//7326 -f 7903//7903 7904//7904 7905//7905 -f 7905//7905 7904//7904 7906//7906 -f 7905//7905 7906//7906 7907//7907 -f 7907//7907 7906//7906 7902//7902 -f 7907//7907 7902//7902 7908//7908 -f 7908//7908 7902//7902 7901//7901 -f 7324//7324 7331//7331 7909//7909 -f 7909//7909 7331//7331 7906//7906 -f 7906//7906 7904//7904 7909//7909 -f 7909//7909 7904//7904 7607//7607 -f 7909//7909 7607//7607 7609//7609 -f 7909//7909 7609//7609 7910//7910 -f 7910//7910 7609//7609 7664//7664 -f 7911//7911 7318//7318 7323//7323 -f 7664//7664 7631//7631 7910//7910 -f 7910//7910 7631//7631 7840//7840 -f 7910//7910 7840//7840 7323//7323 -f 7323//7323 7840//7840 7912//7912 -f 7323//7323 7912//7912 7911//7911 -f 7317//7317 7913//7913 7914//7914 -f 7219//7219 7311//7311 7915//7915 -f 7915//7915 7311//7311 7313//7313 -f 7915//7915 7313//7313 7916//7916 -f 7916//7916 7313//7313 7315//7315 -f 7916//7916 7315//7315 7510//7510 -f 7510//7510 7315//7315 7317//7317 -f 7510//7510 7317//7317 7509//7509 -f 7509//7509 7317//7317 7914//7914 -f 7508//7508 7489//7489 7917//7917 -f 7917//7917 7489//7489 7918//7918 -f 7918//7918 7489//7489 7491//7491 -f 7918//7918 7491//7491 7919//7919 -f 7919//7919 7491//7491 7493//7493 -f 7919//7919 7493//7493 7920//7920 -f 7920//7920 7493//7493 7495//7495 -f 7920//7920 7495//7495 7921//7921 -f 7921//7921 7495//7495 7497//7497 -f 7921//7921 7497//7497 7922//7922 -f 7922//7922 7497//7497 7498//7498 -f 7922//7922 7498//7498 7923//7923 -f 7923//7923 7498//7498 7526//7526 -f 7923//7923 7526//7526 7924//7924 -f 7924//7924 7526//7526 7525//7525 -f 7924//7924 7525//7525 7925//7925 -f 7925//7925 7525//7525 7926//7926 -f 7926//7926 7525//7525 7484//7484 -f 7927//7927 7928//7928 7929//7929 -f 7929//7929 7928//7928 7865//7865 -f 7929//7929 7865//7865 7719//7719 -f 7719//7719 7865//7865 7866//7866 -f 7863//7863 7865//7865 7930//7930 -f 7930//7930 7865//7865 7931//7931 -f 7932//7932 7933//7933 7934//7934 -f 7934//7934 7933//7933 7863//7863 -f 7934//7934 7863//7863 7935//7935 -f 7935//7935 7863//7863 7930//7930 -f 7932//7932 7936//7936 7933//7933 -f 7933//7933 7936//7936 7937//7937 -f 7933//7933 7937//7937 7938//7938 -f 7938//7938 7937//7937 7939//7939 -f 7938//7938 7939//7939 7928//7928 -f 7928//7928 7939//7939 7940//7940 -f 7940//7940 7941//7941 7928//7928 -f 7928//7928 7941//7941 7942//7942 -f 7928//7928 7942//7942 7865//7865 -f 7865//7865 7942//7942 7943//7943 -f 7865//7865 7943//7943 7931//7931 -f 7599//7599 7861//7861 7944//7944 -f 7944//7944 7861//7861 7863//7863 -f 7944//7944 7863//7863 7945//7945 -f 7945//7945 7863//7863 7933//7933 -f 7927//7927 7946//7946 7928//7928 -f 7928//7928 7946//7946 7938//7938 -f 7946//7946 7945//7945 7938//7938 -f 7938//7938 7945//7945 7933//7933 -f 7944//7944 7945//7945 7947//7947 -f 7947//7947 7945//7945 7946//7946 -f 7947//7947 7946//7946 7948//7948 -f 7948//7948 7946//7946 7927//7927 -f 7948//7948 7927//7927 7929//7929 -f 7719//7719 7721//7721 7929//7929 -f 7929//7929 7721//7721 7948//7948 -f 7721//7721 7601//7601 7948//7948 -f 7948//7948 7601//7601 7947//7947 -f 7601//7601 7599//7599 7947//7947 -f 7947//7947 7599//7599 7944//7944 -f 7949//7949 7950//7950 7951//7951 -f 7951//7951 7950//7950 7877//7877 -f 7951//7951 7877//7877 7669//7669 -f 7669//7669 7877//7877 7878//7878 -f 7952//7952 7875//7875 7953//7953 -f 7953//7953 7954//7954 7952//7952 -f 7952//7952 7954//7954 7955//7955 -f 7952//7952 7955//7955 7956//7956 -f 7956//7956 7955//7955 7957//7957 -f 7950//7950 7958//7958 7877//7877 -f 7877//7877 7958//7958 7959//7959 -f 7959//7959 7960//7960 7877//7877 -f 7877//7877 7960//7960 7961//7961 -f 7877//7877 7961//7961 7875//7875 -f 7875//7875 7961//7961 7962//7962 -f 7875//7875 7962//7962 7953//7953 -f 7957//7957 7963//7963 7956//7956 -f 7956//7956 7963//7963 7964//7964 -f 7956//7956 7964//7964 7950//7950 -f 7950//7950 7964//7964 7965//7965 -f 7950//7950 7965//7965 7958//7958 -f 7666//7666 7873//7873 7966//7966 -f 7966//7966 7873//7873 7875//7875 -f 7966//7966 7875//7875 7967//7967 -f 7967//7967 7875//7875 7952//7952 -f 7949//7949 7968//7968 7950//7950 -f 7950//7950 7968//7968 7956//7956 -f 7968//7968 7967//7967 7956//7956 -f 7956//7956 7967//7967 7952//7952 -f 7969//7969 7966//7966 7967//7967 -f 7949//7949 7951//7951 7970//7970 -f 7969//7969 7967//7967 7970//7970 -f 7970//7970 7967//7967 7968//7968 -f 7970//7970 7968//7968 7949//7949 -f 7646//7646 7970//7970 7669//7669 -f 7669//7669 7970//7970 7951//7951 -f 7645//7645 7969//7969 7646//7646 -f 7646//7646 7969//7969 7970//7970 -f 7666//7666 7966//7966 7645//7645 -f 7645//7645 7966//7966 7969//7969 -f 7930//7930 7283//7283 7935//7935 -f 7935//7935 7283//7283 7278//7278 -f 7935//7935 7278//7278 7934//7934 -f 7934//7934 7278//7278 7277//7277 -f 7934//7934 7277//7277 7932//7932 -f 7932//7932 7277//7277 7276//7276 -f 7932//7932 7276//7276 7936//7936 -f 7936//7936 7276//7276 7377//7377 -f 7936//7936 7377//7377 7937//7937 -f 7937//7937 7377//7377 7375//7375 -f 7937//7937 7375//7375 7939//7939 -f 7939//7939 7375//7375 7373//7373 -f 7939//7939 7373//7373 7940//7940 -f 7940//7940 7373//7373 7372//7372 -f 7940//7940 7372//7372 7941//7941 -f 7941//7941 7372//7372 7371//7371 -f 7941//7941 7371//7371 7942//7942 -f 7942//7942 7371//7371 7279//7279 -f 7942//7942 7279//7279 7943//7943 -f 7943//7943 7279//7279 7280//7280 -f 7943//7943 7280//7280 7931//7931 -f 7931//7931 7280//7280 7282//7282 -f 7931//7931 7282//7282 7930//7930 -f 7930//7930 7282//7282 7283//7283 -f 7958//7958 7308//7308 7959//7959 -f 7959//7959 7308//7308 7307//7307 -f 7959//7959 7307//7307 7960//7960 -f 7960//7960 7307//7307 7306//7306 -f 7960//7960 7306//7306 7961//7961 -f 7961//7961 7306//7306 7301//7301 -f 7961//7961 7301//7301 7962//7962 -f 7962//7962 7301//7301 7300//7300 -f 7962//7962 7300//7300 7953//7953 -f 7953//7953 7300//7300 7294//7294 -f 7953//7953 7294//7294 7954//7954 -f 7954//7954 7294//7294 7296//7296 -f 7954//7954 7296//7296 7955//7955 -f 7955//7955 7296//7296 7298//7298 -f 7955//7955 7298//7298 7957//7957 -f 7957//7957 7298//7298 7299//7299 -f 7957//7957 7299//7299 7963//7963 -f 7963//7963 7299//7299 7302//7302 -f 7963//7963 7302//7302 7964//7964 -f 7964//7964 7302//7302 7303//7303 -f 7964//7964 7303//7303 7965//7965 -f 7965//7965 7303//7303 7305//7305 -f 7965//7965 7305//7305 7958//7958 -f 7958//7958 7305//7305 7308//7308 -f 7971//7971 7972//7972 7973//7973 -f 7973//7973 7972//7972 7887//7887 -f 7973//7973 7887//7887 7640//7640 -f 7640//7640 7887//7887 7888//7888 -f 7974//7974 7885//7885 7975//7975 -f 7975//7975 7976//7976 7974//7974 -f 7974//7974 7976//7976 7977//7977 -f 7974//7974 7977//7977 7978//7978 -f 7978//7978 7977//7977 7979//7979 -f 7980//7980 7887//7887 7981//7981 -f 7981//7981 7887//7887 7972//7972 -f 7979//7979 7982//7982 7978//7978 -f 7978//7978 7982//7982 7983//7983 -f 7978//7978 7983//7983 7972//7972 -f 7972//7972 7983//7983 7984//7984 -f 7972//7972 7984//7984 7981//7981 -f 7980//7980 7985//7985 7887//7887 -f 7887//7887 7985//7985 7986//7986 -f 7887//7887 7986//7986 7885//7885 -f 7885//7885 7986//7986 7987//7987 -f 7885//7885 7987//7987 7975//7975 -f 7617//7617 7883//7883 7988//7988 -f 7988//7988 7883//7883 7885//7885 -f 7988//7988 7885//7885 7989//7989 -f 7989//7989 7885//7885 7974//7974 -f 7990//7990 7991//7991 7992//7992 -f 7992//7992 7991//7991 7897//7897 -f 7992//7992 7897//7897 7629//7629 -f 7629//7629 7897//7897 7898//7898 -f 7993//7993 7897//7897 7994//7994 -f 7994//7994 7897//7897 7991//7991 -f 7993//7993 7995//7995 7897//7897 -f 7897//7897 7995//7995 7996//7996 -f 7897//7897 7996//7996 7895//7895 -f 7997//7997 7998//7998 7999//7999 -f 7999//7999 7998//7998 8000//8000 -f 7997//7997 8001//8001 7998//7998 -f 7998//7998 8001//8001 8002//8002 -f 7998//7998 8002//8002 7991//7991 -f 7991//7991 8002//8002 8003//8003 -f 7991//7991 8003//8003 7994//7994 -f 7996//7996 8004//8004 7895//7895 -f 7895//7895 8004//8004 8005//8005 -f 7895//7895 8005//8005 8000//8000 -f 8000//8000 8005//8005 8006//8006 -f 8000//8000 8006//8006 7999//7999 -f 7613//7613 7893//7893 8007//8007 -f 8007//8007 7893//7893 7895//7895 -f 8007//8007 7895//7895 8008//8008 -f 8008//8008 7895//7895 8000//8000 -f 8009//8009 8010//8010 8011//8011 -f 8011//8011 8010//8010 7907//7907 -f 8011//8011 7907//7907 7624//7624 -f 7624//7624 7907//7907 7908//7908 -f 8012//8012 8013//8013 8014//8014 -f 8014//8014 8013//8013 8010//8010 -f 8015//8015 7905//7905 8016//8016 -f 8016//8016 8017//8017 8015//8015 -f 8015//8015 8017//8017 8018//8018 -f 8015//8015 8018//8018 8014//8014 -f 8014//8014 8018//8018 8019//8019 -f 8014//8014 8019//8019 8012//8012 -f 8013//8013 8020//8020 8010//8010 -f 8010//8010 8020//8020 8021//8021 -f 8010//8010 8021//8021 7907//7907 -f 7907//7907 8021//8021 8022//8022 -f 8022//8022 8023//8023 7907//7907 -f 7907//7907 8023//8023 8024//8024 -f 7907//7907 8024//8024 7905//7905 -f 7905//7905 8024//8024 8025//8025 -f 7905//7905 8025//8025 8016//8016 -f 7608//7608 7903//7903 8026//8026 -f 8026//8026 7903//7903 7905//7905 -f 8026//8026 7905//7905 8027//8027 -f 8027//8027 7905//7905 8015//8015 -f 7971//7971 8028//8028 7972//7972 -f 7972//7972 8028//8028 7978//7978 -f 8028//8028 7989//7989 7978//7978 -f 7978//7978 7989//7989 7974//7974 -f 8029//8029 7988//7988 7989//7989 -f 7971//7971 7973//7973 8030//8030 -f 8029//8029 7989//7989 8030//8030 -f 8030//8030 7989//7989 8028//8028 -f 8030//8030 8028//8028 7971//7971 -f 7990//7990 8031//8031 7991//7991 -f 7991//7991 8031//8031 7998//7998 -f 8031//8031 8008//8008 7998//7998 -f 7998//7998 8008//8008 8000//8000 -f 8032//8032 8007//8007 8008//8008 -f 7990//7990 7992//7992 8033//8033 -f 8032//8032 8008//8008 8033//8033 -f 8033//8033 8008//8008 8031//8031 -f 8033//8033 8031//8031 7990//7990 -f 8009//8009 8034//8034 8010//8010 -f 8010//8010 8034//8034 8014//8014 -f 8034//8034 8027//8027 8014//8014 -f 8014//8014 8027//8027 8015//8015 -f 8035//8035 8026//8026 8027//8027 -f 8009//8009 8011//8011 8036//8036 -f 8035//8035 8027//8027 8036//8036 -f 8036//8036 8027//8027 8034//8034 -f 8036//8036 8034//8034 8009//8009 -f 7642//7642 8030//8030 7640//7640 -f 7640//7640 8030//8030 7973//7973 -f 7619//7619 8029//8029 7642//7642 -f 7642//7642 8029//8029 8030//8030 -f 7617//7617 7988//7988 7619//7619 -f 7619//7619 7988//7988 8029//8029 -f 7628//7628 8033//8033 7629//7629 -f 7629//7629 8033//8033 7992//7992 -f 7615//7615 8032//8032 7628//7628 -f 7628//7628 8032//8032 8033//8033 -f 7613//7613 8007//8007 7615//7615 -f 7615//7615 8007//8007 8032//8032 -f 7626//7626 8036//8036 7624//7624 -f 7624//7624 8036//8036 8011//8011 -f 7610//7610 8035//8035 7626//7626 -f 7626//7626 8035//8035 8036//8036 -f 7608//7608 8026//8026 7610//7610 -f 7610//7610 8026//8026 8035//8035 -f 7981//7981 7363//7363 7980//7980 -f 7980//7980 7363//7363 7355//7355 -f 7980//7980 7355//7355 7985//7985 -f 7985//7985 7355//7355 7370//7370 -f 7985//7985 7370//7370 7986//7986 -f 7986//7986 7370//7370 7369//7369 -f 7986//7986 7369//7369 7987//7987 -f 7987//7987 7369//7369 7368//7368 -f 7987//7987 7368//7368 7975//7975 -f 7975//7975 7368//7368 7356//7356 -f 7975//7975 7356//7356 7976//7976 -f 7976//7976 7356//7356 7358//7358 -f 7976//7976 7358//7358 7977//7977 -f 7977//7977 7358//7358 7360//7360 -f 7977//7977 7360//7360 7979//7979 -f 7979//7979 7360//7360 7361//7361 -f 7979//7979 7361//7361 7982//7982 -f 7982//7982 7361//7361 7366//7366 -f 7982//7982 7366//7366 7983//7983 -f 7983//7983 7366//7366 7365//7365 -f 7983//7983 7365//7365 7984//7984 -f 7984//7984 7365//7365 7364//7364 -f 7984//7984 7364//7364 7981//7981 -f 7981//7981 7364//7364 7363//7363 -f 7994//7994 7339//7339 7993//7993 -f 7993//7993 7339//7339 7338//7338 -f 7993//7993 7338//7338 7995//7995 -f 7995//7995 7338//7338 7352//7352 -f 7995//7995 7352//7352 7996//7996 -f 7996//7996 7352//7352 7351//7351 -f 7996//7996 7351//7351 8004//8004 -f 8004//8004 7351//7351 7350//7350 -f 8004//8004 7350//7350 8005//8005 -f 8005//8005 7350//7350 7349//7349 -f 8005//8005 7349//7349 8006//8006 -f 8006//8006 7349//7349 7347//7347 -f 8006//8006 7347//7347 7999//7999 -f 7999//7999 7347//7347 7346//7346 -f 7999//7999 7346//7346 7997//7997 -f 7997//7997 7346//7346 7343//7343 -f 7997//7997 7343//7343 8001//8001 -f 8001//8001 7343//7343 7342//7342 -f 8001//8001 7342//7342 8002//8002 -f 8002//8002 7342//7342 7341//7341 -f 8002//8002 7341//7341 8003//8003 -f 8003//8003 7341//7341 7340//7340 -f 8003//8003 7340//7340 7994//7994 -f 7994//7994 7340//7340 7339//7339 -f 8021//8021 7328//7328 8022//8022 -f 8022//8022 7328//7328 7327//7327 -f 8022//8022 7327//7327 8023//8023 -f 8023//8023 7327//7327 7335//7335 -f 8023//8023 7335//7335 8024//8024 -f 8024//8024 7335//7335 7334//7334 -f 8024//8024 7334//7334 8025//8025 -f 8025//8025 7334//7334 7333//7333 -f 8025//8025 7333//7333 8016//8016 -f 8016//8016 7333//7333 7332//7332 -f 8016//8016 7332//7332 8017//8017 -f 8017//8017 7332//7332 7330//7330 -f 8017//8017 7330//7330 8018//8018 -f 8018//8018 7330//7330 7329//7329 -f 8018//8018 7329//7329 8019//8019 -f 8019//8019 7329//7329 7325//7325 -f 8019//8019 7325//7325 8012//8012 -f 8012//8012 7325//7325 7322//7322 -f 8012//8012 7322//7322 8013//8013 -f 8013//8013 7322//7322 7321//7321 -f 8013//8013 7321//7321 8020//8020 -f 8020//8020 7321//7321 7320//7320 -f 8020//8020 7320//7320 8021//8021 -f 8021//8021 7320//7320 7328//7328 -f 7830//7830 7802//7802 7831//7831 -f 7831//7831 7802//7802 7798//7798 -f 7831//7831 7798//7798 7731//7731 -f 7731//7731 7798//7798 7838//7838 -f 7725//7725 7834//7834 7828//7828 -f 7828//7828 7834//7834 7797//7797 -f 7828//7828 7797//7797 7829//7829 -f 7829//7829 7797//7797 7806//7806 -f 7830//7830 7833//7833 7802//7802 -f 7802//7802 7833//7833 7804//7804 -f 7833//7833 7829//7829 7804//7804 -f 7804//7804 7829//7829 7806//7806 -f 7709//7709 7832//7832 7731//7731 -f 7731//7731 7832//7832 7831//7831 -f 7708//7708 7827//7827 7709//7709 -f 7709//7709 7827//7827 7832//7832 -f 7725//7725 7828//7828 7708//7708 -f 7708//7708 7828//7828 7827//7827 -f 7819//7819 7780//7780 7820//7820 -f 7820//7820 7780//7780 7782//7782 -f 7820//7820 7782//7782 7634//7634 -f 7634//7634 7782//7782 7825//7825 -f 7673//7673 7821//7821 7814//7814 -f 7814//7814 7821//7821 7785//7785 -f 7814//7814 7785//7785 7815//7815 -f 7815//7815 7785//7785 7784//7784 -f 7819//7819 7817//7817 7780//7780 -f 7780//7780 7817//7817 7788//7788 -f 7817//7817 7815//7815 7788//7788 -f 7788//7788 7815//7815 7784//7784 -f 7634//7634 7636//7636 7820//7820 -f 7820//7820 7636//7636 7818//7818 -f 7636//7636 7675//7675 7818//7818 -f 7818//7818 7675//7675 7816//7816 -f 7675//7675 7673//7673 7816//7816 -f 7816//7816 7673//7673 7814//7814 -f 7799//7799 7249//7249 7808//7808 -f 7808//7808 7249//7249 7265//7265 -f 7808//7808 7265//7265 7809//7809 -f 7809//7809 7265//7265 7264//7264 -f 7809//7809 7264//7264 7810//7810 -f 7810//7810 7264//7264 7262//7262 -f 7810//7810 7262//7262 7807//7807 -f 7807//7807 7262//7262 7260//7260 -f 7807//7807 7260//7260 7805//7805 -f 7805//7805 7260//7260 7259//7259 -f 7805//7805 7259//7259 7803//7803 -f 7803//7803 7259//7259 7256//7256 -f 7803//7803 7256//7256 7801//7801 -f 7801//7801 7256//7256 7255//7255 -f 7801//7801 7255//7255 7811//7811 -f 7811//7811 7255//7255 7254//7254 -f 7811//7811 7254//7254 7812//7812 -f 7812//7812 7254//7254 7253//7253 -f 7812//7812 7253//7253 7813//7813 -f 7813//7813 7253//7253 7252//7252 -f 7813//7813 7252//7252 7800//7800 -f 7800//7800 7252//7252 7250//7250 -f 7800//7800 7250//7250 7799//7799 -f 7799//7799 7250//7250 7249//7249 -f 7790//7790 7222//7222 7789//7789 -f 7789//7789 7222//7222 7238//7238 -f 7789//7789 7238//7238 7787//7787 -f 7787//7787 7238//7238 7240//7240 -f 7787//7787 7240//7240 7791//7791 -f 7791//7791 7240//7240 7232//7232 -f 7791//7791 7232//7232 7792//7792 -f 7792//7792 7232//7232 7230//7230 -f 7792//7792 7230//7230 7793//7793 -f 7793//7793 7230//7230 7229//7229 -f 7793//7793 7229//7229 7781//7781 -f 7781//7781 7229//7229 7228//7228 -f 7781//7781 7228//7228 7783//7783 -f 7783//7783 7228//7228 7226//7226 -f 7783//7783 7226//7226 7794//7794 -f 7794//7794 7226//7226 7235//7235 -f 7794//7794 7235//7235 7795//7795 -f 7795//7795 7235//7235 7234//7234 -f 7795//7795 7234//7234 7796//7796 -f 7796//7796 7234//7234 7233//7233 -f 7796//7796 7233//7233 7786//7786 -f 7786//7786 7233//7233 7223//7223 -f 7786//7786 7223//7223 7790//7790 -f 7790//7790 7223//7223 7222//7222 -f 7760//7760 7581//7581 7761//7761 -f 7761//7761 7581//7581 7583//7583 -f 7761//7761 7583//7583 7651//7651 -f 7651//7651 7583//7583 7778//7778 -f 7648//7648 7774//7774 7755//7755 -f 7755//7755 7774//7774 7590//7590 -f 7755//7755 7590//7590 7756//7756 -f 7756//7756 7590//7590 7592//7592 -f 7753//7753 7568//7568 7754//7754 -f 7754//7754 7568//7568 7570//7570 -f 7754//7754 7570//7570 7688//7688 -f 7688//7688 7570//7570 7772//7772 -f 7658//7658 7768//7768 7748//7748 -f 7748//7748 7768//7768 7574//7574 -f 7748//7748 7574//7574 7749//7749 -f 7749//7749 7574//7574 7564//7564 -f 7746//7746 7557//7557 7747//7747 -f 7747//7747 7557//7557 7547//7547 -f 7747//7747 7547//7547 7603//7603 -f 7603//7603 7547//7547 7766//7766 -f 7739//7739 7762//7762 7741//7741 -f 7741//7741 7762//7762 7553//7553 -f 7741//7741 7553//7553 7742//7742 -f 7742//7742 7553//7553 7556//7556 -f 7760//7760 7758//7758 7581//7581 -f 7581//7581 7758//7758 7585//7585 -f 7758//7758 7756//7756 7585//7585 -f 7585//7585 7756//7756 7592//7592 -f 7753//7753 7751//7751 7568//7568 -f 7568//7568 7751//7751 7566//7566 -f 7751//7751 7749//7749 7566//7566 -f 7566//7566 7749//7749 7564//7564 -f 7746//7746 7744//7744 7557//7557 -f 7557//7557 7744//7744 7550//7550 -f 7744//7744 7742//7742 7550//7550 -f 7550//7550 7742//7742 7556//7556 -f 7651//7651 7653//7653 7761//7761 -f 7761//7761 7653//7653 7759//7759 -f 7653//7653 7650//7650 7759//7759 -f 7759//7759 7650//7650 7757//7757 -f 7650//7650 7648//7648 7757//7757 -f 7757//7757 7648//7648 7755//7755 -f 7688//7688 7690//7690 7754//7754 -f 7754//7754 7690//7690 7752//7752 -f 7690//7690 7660//7660 7752//7752 -f 7752//7752 7660//7660 7750//7750 -f 7660//7660 7658//7658 7750//7750 -f 7750//7750 7658//7658 7748//7748 -f 7603//7603 7602//7602 7747//7747 -f 7747//7747 7602//7602 7745//7745 -f 7602//7602 7738//7738 7745//7745 -f 7745//7745 7738//7738 7743//7743 -f 7738//7738 7739//7739 7743//7743 -f 7743//7743 7739//7739 7741//7741 -f 7591//7591 7386//7386 7595//7595 -f 7595//7595 7386//7386 7385//7385 -f 7595//7595 7385//7385 7596//7596 -f 7596//7596 7385//7385 7403//7403 -f 7596//7596 7403//7403 7597//7597 -f 7597//7597 7403//7403 7402//7402 -f 7597//7597 7402//7402 7586//7586 -f 7586//7586 7402//7402 7401//7401 -f 7586//7586 7401//7401 7587//7587 -f 7587//7587 7401//7401 7394//7394 -f 7587//7587 7394//7394 7582//7582 -f 7582//7582 7394//7394 7396//7396 -f 7582//7582 7396//7396 7584//7584 -f 7584//7584 7396//7396 7397//7397 -f 7584//7584 7397//7397 7588//7588 -f 7588//7588 7397//7397 7393//7393 -f 7588//7588 7393//7393 7589//7589 -f 7589//7589 7393//7393 7390//7390 -f 7589//7589 7390//7390 7594//7594 -f 7594//7594 7390//7390 7389//7389 -f 7594//7594 7389//7389 7593//7593 -f 7593//7593 7389//7389 7400//7400 -f 7593//7593 7400//7400 7591//7591 -f 7591//7591 7400//7400 7386//7386 -f 7577//7577 7407//7407 7565//7565 -f 7565//7565 7407//7407 7406//7406 -f 7565//7565 7406//7406 7567//7567 -f 7567//7567 7406//7406 7423//7423 -f 7567//7567 7423//7423 7578//7578 -f 7578//7578 7423//7423 7422//7422 -f 7578//7578 7422//7422 7579//7579 -f 7579//7579 7422//7422 7421//7421 -f 7579//7579 7421//7421 7580//7580 -f 7580//7580 7421//7421 7420//7420 -f 7580//7580 7420//7420 7569//7569 -f 7569//7569 7420//7420 7418//7418 -f 7569//7569 7418//7418 7571//7571 -f 7571//7571 7418//7418 7417//7417 -f 7571//7571 7417//7417 7572//7572 -f 7572//7572 7417//7417 7414//7414 -f 7572//7572 7414//7414 7573//7573 -f 7573//7573 7414//7414 7411//7411 -f 7573//7573 7411//7411 7575//7575 -f 7575//7575 7411//7411 7409//7409 -f 7575//7575 7409//7409 7576//7576 -f 7576//7576 7409//7409 7408//7408 -f 7576//7576 7408//7408 7577//7577 -f 7577//7577 7408//7408 7407//7407 -f 7561//7561 7427//7427 7562//7562 -f 7562//7562 7427//7427 7426//7426 -f 7562//7562 7426//7426 7563//7563 -f 7563//7563 7426//7426 7445//7445 -f 7563//7563 7445//7445 7551//7551 -f 7551//7551 7445//7445 7444//7444 -f 7551//7551 7444//7444 7552//7552 -f 7552//7552 7444//7444 7443//7443 -f 7552//7552 7443//7443 7558//7558 -f 7558//7558 7443//7443 7437//7437 -f 7558//7558 7437//7437 7559//7559 -f 7559//7559 7437//7437 7436//7436 -f 7559//7559 7436//7436 7560//7560 -f 7560//7560 7436//7436 7435//7435 -f 7560//7560 7435//7435 7548//7548 -f 7548//7548 7435//7435 7434//7434 -f 7548//7548 7434//7434 7549//7549 -f 7549//7549 7434//7434 7441//7441 -f 7549//7549 7441//7441 7554//7554 -f 7554//7554 7441//7441 7439//7439 -f 7554//7554 7439//7439 7555//7555 -f 7555//7555 7439//7439 7438//7438 -f 7555//7555 7438//7438 7561//7561 -f 7561//7561 7438//7438 7427//7427 -f 8037//8037 7841//7841 8038//8038 -f 8038//8038 7841//7841 7656//7656 -f 8038//8038 7656//7656 8039//8039 -f 8039//8039 7656//7656 7655//7655 -f 8039//8039 7655//7655 8040//8040 -f 8040//8040 7655//7655 7639//7639 -f 8040//8040 7639//7639 8041//8041 -f 8041//8041 7639//7639 8042//8042 -f 8042//8042 7639//7639 7638//7638 -f 8042//8042 7638//7638 8043//8043 -f 8043//8043 7638//7638 8044//8044 -f 8044//8044 7638//7638 7702//7702 -f 8044//8044 7702//7702 8045//8045 -f 8045//8045 7702//7702 7476//7476 -f 8045//8045 7476//7476 7480//7480 -f 8046//8046 8047//8047 8048//8048 -f 8049//8049 8046//8046 8050//8050 -f 8050//8050 8046//8046 8048//8048 -f 8050//8050 8048//8048 8051//8051 -f 8051//8051 8048//8048 8052//8052 -f 8053//8053 8054//8054 8055//8055 -f 8056//8056 8057//8057 8053//8053 -f 8053//8053 8057//8057 8058//8058 -f 8053//8053 8058//8058 8059//8059 -f 8059//8059 8058//8058 8060//8060 -f 8059//8059 8060//8060 8061//8061 -f 8061//8061 8060//8060 8062//8062 -f 8061//8061 8062//8062 8063//8063 -f 8063//8063 8062//8062 8064//8064 -f 8063//8063 8064//8064 8048//8048 -f 8048//8048 8064//8064 8065//8065 -f 8048//8048 8065//8065 8052//8052 -f 8052//8052 8065//8065 8066//8066 -f 8052//8052 8066//8066 8067//8067 -f 8067//8067 8066//8066 8068//8068 -f 8067//8067 8068//8068 8069//8069 -f 8069//8069 8068//8068 8070//8070 -f 8069//8069 8070//8070 8071//8071 -f 8071//8071 8070//8070 8072//8072 -f 8071//8071 8072//8072 8073//8073 -f 8073//8073 8072//8072 8074//8074 -f 8073//8073 8074//8074 8055//8055 -f 8055//8055 8074//8074 8056//8056 -f 8055//8055 8056//8056 8053//8053 -f 8075//8075 7914//7914 8059//8059 -f 8059//8059 7914//7914 7913//7913 -f 8059//8059 7913//7913 8053//8053 -f 8053//8053 7913//7913 8076//8076 -f 8053//8053 8076//8076 8077//8077 -f 8078//8078 8079//8079 8076//8076 -f 8076//8076 8079//8079 8080//8080 -f 8076//8076 8080//8080 8077//8077 -f 8048//8048 8047//8047 8063//8063 -f 8063//8063 8047//8047 8081//8081 -f 8063//8063 8081//8081 8061//8061 -f 8061//8061 8081//8081 8082//8082 -f 8061//8061 8082//8082 8059//8059 -f 8059//8059 8082//8082 8075//8075 -f 8083//8083 8084//8084 8085//8085 -f 8086//8086 8083//8083 8087//8087 -f 8087//8087 8083//8083 8085//8085 -f 8087//8087 8085//8085 8088//8088 -f 8088//8088 8085//8085 8089//8089 -f 8090//8090 8091//8091 8092//8092 -f 8092//8092 8091//8091 8093//8093 -f 8092//8092 8093//8093 8094//8094 -f 8094//8094 8093//8093 8095//8095 -f 8094//8094 8095//8095 8096//8096 -f 8096//8096 8095//8095 8097//8097 -f 8096//8096 8097//8097 8098//8098 -f 8098//8098 8097//8097 8099//8099 -f 8098//8098 8099//8099 8100//8100 -f 8100//8100 8099//8099 8101//8101 -f 8100//8100 8101//8101 8102//8102 -f 8102//8102 8101//8101 8103//8103 -f 8102//8102 8103//8103 8084//8084 -f 8084//8084 8103//8103 8104//8104 -f 8084//8084 8104//8104 8085//8085 -f 8085//8085 8104//8104 8105//8105 -f 8085//8085 8105//8105 8106//8106 -f 8106//8106 8105//8105 8107//8107 -f 8106//8106 8107//8107 8108//8108 -f 8108//8108 8107//8107 8109//8109 -f 8108//8108 8109//8109 8110//8110 -f 8110//8110 8109//8109 8090//8090 -f 8110//8110 8090//8090 8092//8092 -f 8110//8110 8111//8111 8108//8108 -f 8108//8108 8111//8111 8112//8112 -f 8108//8108 8112//8112 8106//8106 -f 8106//8106 8112//8112 8113//8113 -f 8106//8106 8113//8113 8085//8085 -f 8085//8085 8113//8113 8089//8089 -f 8114//8114 8092//8092 8115//8115 -f 8115//8115 8092//8092 8116//8116 -f 7452//7452 8111//8111 7453//7453 -f 7453//7453 8111//8111 8110//8110 -f 7453//7453 8110//8110 8117//8117 -f 8117//8117 8110//8110 8092//8092 -f 8117//8117 8092//8092 8118//8118 -f 8114//8114 8119//8119 8092//8092 -f 8092//8092 8119//8119 8120//8120 -f 8092//8092 8120//8120 8118//8118 -f 8121//8121 8122//8122 8123//8123 -f 8123//8123 8122//8122 8124//8124 -f 8123//8123 8124//8124 8125//8125 -f 8125//8125 8124//8124 8126//8126 -f 8127//8127 8128//8128 8126//8126 -f 8126//8126 8128//8128 8129//8129 -f 8126//8126 8129//8129 8125//8125 -f 8130//8130 8131//8131 8127//8127 -f 8127//8127 8131//8131 8132//8132 -f 8127//8127 8132//8132 8128//8128 -f 8133//8133 8134//8134 8130//8130 -f 8130//8130 8134//8134 8135//8135 -f 8130//8130 8135//8135 8131//8131 -f 8136//8136 8137//8137 8138//8138 -f 8138//8138 8137//8137 8139//8139 -f 8138//8138 8139//8139 8140//8140 -f 8140//8140 8139//8139 8141//8141 -f 8140//8140 8141//8141 8133//8133 -f 8133//8133 8141//8141 8142//8142 -f 8133//8133 8142//8142 8134//8134 -f 8143//8143 8144//8144 8136//8136 -f 8136//8136 8144//8144 8145//8145 -f 8136//8136 8145//8145 8137//8137 -f 8146//8146 8147//8147 8143//8143 -f 8143//8143 8147//8147 8148//8148 -f 8143//8143 8148//8148 8144//8144 -f 8149//8149 8150//8150 8146//8146 -f 8146//8146 8150//8150 8151//8151 -f 8146//8146 8151//8151 8147//8147 -f 8152//8152 8150//8150 8153//8153 -f 8153//8153 8150//8150 8149//8149 -f 8153//8153 8149//8149 8154//8154 -f 8154//8154 8149//8149 8122//8122 -f 8154//8154 8122//8122 8155//8155 -f 8155//8155 8122//8122 8121//8121 -f 8155//8155 8121//8121 8156//8156 -f 8157//8157 8126//8126 8158//8158 -f 8158//8158 8126//8126 8124//8124 -f 8158//8158 8124//8124 8159//8159 -f 8159//8159 8124//8124 8122//8122 -f 8159//8159 8122//8122 8160//8160 -f 8160//8160 8122//8122 8149//8149 -f 8160//8160 8149//8149 8161//8161 -f 8161//8161 8149//8149 8146//8146 -f 8161//8161 8146//8146 8162//8162 -f 8162//8162 8146//8146 8143//8143 -f 8162//8162 8143//8143 8163//8163 -f 8163//8163 8143//8143 8136//8136 -f 8163//8163 8136//8136 8164//8164 -f 8164//8164 8136//8136 8138//8138 -f 8164//8164 8138//8138 8165//8165 -f 8165//8165 8138//8138 8140//8140 -f 8165//8165 8140//8140 8166//8166 -f 8166//8166 8140//8140 8133//8133 -f 8166//8166 8133//8133 8167//8167 -f 8167//8167 8133//8133 8130//8130 -f 8167//8167 8130//8130 8168//8168 -f 8168//8168 8130//8130 8127//8127 -f 8168//8168 8127//8127 8157//8157 -f 8157//8157 8127//8127 8126//8126 -f 8169//8169 8170//8170 8171//8171 -f 8172//8172 8173//8173 8174//8174 -f 8174//8174 8173//8173 8175//8175 -f 8174//8174 8175//8175 8176//8176 -f 8177//8177 8178//8178 8176//8176 -f 8176//8176 8178//8178 8179//8179 -f 8176//8176 8179//8179 8174//8174 -f 8180//8180 8181//8181 8177//8177 -f 8177//8177 8181//8181 8182//8182 -f 8177//8177 8182//8182 8178//8178 -f 8183//8183 8184//8184 8180//8180 -f 8180//8180 8184//8184 8185//8185 -f 8180//8180 8185//8185 8181//8181 -f 8186//8186 8187//8187 8183//8183 -f 8183//8183 8187//8187 8188//8188 -f 8183//8183 8188//8188 8184//8184 -f 8189//8189 8190//8190 8186//8186 -f 8186//8186 8190//8190 8191//8191 -f 8186//8186 8191//8191 8187//8187 -f 8192//8192 8193//8193 8189//8189 -f 8189//8189 8193//8193 8194//8194 -f 8189//8189 8194//8194 8190//8190 -f 8195//8195 8196//8196 8192//8192 -f 8192//8192 8196//8196 8197//8197 -f 8192//8192 8197//8197 8193//8193 -f 8171//8171 8198//8198 8169//8169 -f 8169//8169 8198//8198 8199//8199 -f 8169//8169 8199//8199 8195//8195 -f 8195//8195 8199//8199 8200//8200 -f 8195//8195 8200//8200 8196//8196 -f 8201//8201 8171//8171 8202//8202 -f 8202//8202 8171//8171 8170//8170 -f 8202//8202 8170//8170 8203//8203 -f 8203//8203 8170//8170 8173//8173 -f 8203//8203 8173//8173 8204//8204 -f 8204//8204 8173//8173 8172//8172 -f 8204//8204 8172//8172 8205//8205 -f 8206//8206 8170//8170 8207//8207 -f 8207//8207 8170//8170 8169//8169 -f 8207//8207 8169//8169 8208//8208 -f 8208//8208 8169//8169 8195//8195 -f 8208//8208 8195//8195 8209//8209 -f 8209//8209 8195//8195 8192//8192 -f 8209//8209 8192//8192 8210//8210 -f 8210//8210 8192//8192 8189//8189 -f 8210//8210 8189//8189 8211//8211 -f 8211//8211 8189//8189 8186//8186 -f 8211//8211 8186//8186 8212//8212 -f 8212//8212 8186//8186 8183//8183 -f 8212//8212 8183//8183 8213//8213 -f 8213//8213 8183//8183 8180//8180 -f 8213//8213 8180//8180 8214//8214 -f 8214//8214 8180//8180 8177//8177 -f 8214//8214 8177//8177 8215//8215 -f 8215//8215 8177//8177 8176//8176 -f 8215//8215 8176//8176 8216//8216 -f 8216//8216 8176//8176 8175//8175 -f 8216//8216 8175//8175 8217//8217 -f 8217//8217 8175//8175 8173//8173 -f 8217//8217 8173//8173 8206//8206 -f 8206//8206 8173//8173 8170//8170 -f 7696//7696 8060//8060 7697//7697 -f 7697//7697 8060//8060 8058//8058 -f 7697//7697 8058//8058 7698//7698 -f 7698//7698 8058//8058 8057//8057 -f 7698//7698 8057//8057 7633//7633 -f 7633//7633 8057//8057 8056//8056 -f 7633//7633 8056//8056 7704//7704 -f 7704//7704 8056//8056 8074//8074 -f 7704//7704 8074//8074 7703//7703 -f 7703//7703 8074//8074 8072//8072 -f 7703//7703 8072//8072 7701//7701 -f 7701//7701 8072//8072 8070//8070 -f 7701//7701 8070//8070 7700//7700 -f 7700//7700 8070//8070 8068//8068 -f 7700//7700 8068//8068 7699//7699 -f 7699//7699 8068//8068 8066//8066 -f 7699//7699 8066//8066 7717//7717 -f 7717//7717 8066//8066 8065//8065 -f 7717//7717 8065//8065 7718//7718 -f 7718//7718 8065//8065 8064//8064 -f 7718//7718 8064//8064 7710//7710 -f 7710//7710 8064//8064 8062//8062 -f 7710//7710 8062//8062 7696//7696 -f 7696//7696 8062//8062 8060//8060 -f 7687//7687 8090//8090 7712//7712 -f 7712//7712 8090//8090 8109//8109 -f 7712//7712 8109//8109 7711//7711 -f 7711//7711 8109//8109 8107//8107 -f 7711//7711 8107//8107 7716//7716 -f 7716//7716 8107//8107 8105//8105 -f 7716//7716 8105//8105 7715//7715 -f 7715//7715 8105//8105 8104//8104 -f 7715//7715 8104//8104 7714//7714 -f 7714//7714 8104//8104 8103//8103 -f 7714//7714 8103//8103 7713//7713 -f 7713//7713 8103//8103 8101//8101 -f 7713//7713 8101//8101 7605//7605 -f 7605//7605 8101//8101 8099//8099 -f 7605//7605 8099//8099 7606//7606 -f 7606//7606 8099//8099 8097//8097 -f 7606//7606 8097//8097 7611//7611 -f 7611//7611 8097//8097 8095//8095 -f 7611//7611 8095//8095 7676//7676 -f 7676//7676 8095//8095 8093//8093 -f 7676//7676 8093//8093 7686//7686 -f 7686//7686 8093//8093 8091//8091 -f 7686//7686 8091//8091 7687//7687 -f 7687//7687 8091//8091 8090//8090 -f 7663//7663 8213//8213 7662//7662 -f 7662//7662 8213//8213 8214//8214 -f 7662//7662 8214//8214 7661//7661 -f 7661//7661 8214//8214 8215//8215 -f 7661//7661 8215//8215 7682//7682 -f 7682//7682 8215//8215 8216//8216 -f 7682//7682 8216//8216 7681//7681 -f 7681//7681 8216//8216 8217//8217 -f 7681//7681 8217//8217 7685//7685 -f 7685//7685 8217//8217 8206//8206 -f 7685//7685 8206//8206 7684//7684 -f 7684//7684 8206//8206 8207//8207 -f 7684//7684 8207//8207 7730//7730 -f 7730//7730 8207//8207 8208//8208 -f 7730//7730 8208//8208 7727//7727 -f 7727//7727 8208//8208 8209//8209 -f 7727//7727 8209//8209 7728//7728 -f 7728//7728 8209//8209 8210//8210 -f 7728//7728 8210//8210 7729//7729 -f 7729//7729 8210//8210 8211//8211 -f 7729//7729 8211//8211 7737//7737 -f 7737//7737 8211//8211 8212//8212 -f 7737//7737 8212//8212 7663//7663 -f 7663//7663 8212//8212 8213//8213 -f 7695//7695 8164//8164 7671//7671 -f 7671//7671 8164//8164 8165//8165 -f 7671//7671 8165//8165 7644//7644 -f 7644//7644 8165//8165 8166//8166 -f 7644//7644 8166//8166 7668//7668 -f 7668//7668 8166//8166 8167//8167 -f 7668//7668 8167//8167 7680//7680 -f 7680//7680 8167//8167 8168//8168 -f 7680//7680 8168//8168 7679//7679 -f 7679//7679 8168//8168 8157//8157 -f 7679//7679 8157//8157 7632//7632 -f 7632//7632 8157//8157 8158//8158 -f 7632//7632 8158//8158 7677//7677 -f 7677//7677 8158//8158 8159//8159 -f 7677//7677 8159//8159 7678//7678 -f 7678//7678 8159//8159 8160//8160 -f 7678//7678 8160//8160 7683//7683 -f 7683//7683 8160//8160 8161//8161 -f 7683//7683 8161//8161 7693//7693 -f 7693//7693 8161//8161 8162//8162 -f 7693//7693 8162//8162 7694//7694 -f 7694//7694 8162//8162 8163//8163 -f 7694//7694 8163//8163 7695//7695 -f 7695//7695 8163//8163 8164//8164 -f 7543//7543 7842//7842 8218//8218 -f 8218//8218 7842//7842 7844//7844 -f 8218//8218 7844//7844 8219//8219 -f 8219//8219 7844//7844 8220//8220 -f 8220//8220 7844//7844 7845//7845 -f 8220//8220 7845//7845 8221//8221 -f 8221//8221 7845//7845 8222//8222 -f 8222//8222 7845//7845 7428//7428 -f 8222//8222 7428//7428 7432//7432 -f 7432//7432 7431//7431 8223//8223 -f 7432//7432 8223//8223 8222//8222 -f 8222//8222 8223//8223 8224//8224 -f 8222//8222 8224//8224 8221//8221 -f 8221//8221 8224//8224 8225//8225 -f 8221//8221 8225//8225 8220//8220 -f 8220//8220 8225//8225 8219//8219 -f 8219//8219 8225//8225 8226//8226 -f 8219//8219 8226//8226 8218//8218 -f 8218//8218 8226//8226 7544//7544 -f 8218//8218 7544//7544 7543//7543 -f 7841//7841 8227//8227 7840//7840 -f 7840//7840 8227//8227 7912//7912 -f 8227//8227 8228//8228 7912//7912 -f 7912//7912 8228//8228 8229//8229 -f 7912//7912 8229//8229 7911//7911 -f 7216//7216 7318//7318 8230//8230 -f 8230//8230 7318//7318 7911//7911 -f 8230//8230 7911//7911 8231//8231 -f 8231//8231 7911//7911 8229//8229 -f 7841//7841 8037//8037 8232//8232 -f 7841//7841 8232//8232 8227//8227 -f 8227//8227 8232//8232 8233//8233 -f 8227//8227 8233//8233 8228//8228 -f 8228//8228 8233//8233 8234//8234 -f 8228//8228 8234//8234 8229//8229 -f 8229//8229 8234//8234 8231//8231 -f 8231//8231 8234//8234 8235//8235 -f 8231//8231 8235//8235 8230//8230 -f 8230//8230 8235//8235 7217//7217 -f 8230//8230 7217//7217 7216//7216 -f 7516//7516 7515//7515 8236//8236 -f 7516//7516 8236//8236 8237//8237 -f 8237//8237 8236//8236 8238//8238 -f 8237//8237 8238//8238 8239//8239 -f 8239//8239 8238//8238 7482//7482 -f 8239//8239 7482//7482 7483//7483 -f 8240//8240 7496//7496 8241//8241 -f 8241//8241 7496//7496 7494//7494 -f 8241//8241 7494//7494 8242//8242 -f 8242//8242 7494//7494 7492//7492 -f 8242//8242 7492//7492 8243//8243 -f 8243//8243 7492//7492 7490//7490 -f 8243//8243 7490//7490 8244//8244 -f 8244//8244 7490//7490 7513//7513 -f 8244//8244 7513//7513 8245//8245 -f 8245//8245 7513//7513 7512//7512 -f 8245//8245 7512//7512 8246//8246 -f 8246//8246 7512//7512 7511//7511 -f 8246//8246 7511//7511 8247//8247 -f 8247//8247 7511//7511 7507//7507 -f 8247//8247 7507//7507 8248//8248 -f 8248//8248 7507//7507 7506//7506 -f 8248//8248 7506//7506 8249//8249 -f 8249//8249 7506//7506 7504//7504 -f 8249//8249 7504//7504 8250//8250 -f 8250//8250 7504//7504 7502//7502 -f 8250//8250 7502//7502 8251//8251 -f 8251//8251 7502//7502 7500//7500 -f 8251//8251 7500//7500 8252//8252 -f 8252//8252 7500//7500 7499//7499 -f 8252//8252 7499//7499 8253//8253 -f 8253//8253 7499//7499 7487//7487 -f 8253//8253 7487//7487 8254//8254 -f 8254//8254 7487//7487 7486//7486 -f 8254//8254 7486//7486 8255//8255 -f 8255//8255 7486//7486 7523//7523 -f 8255//8255 7523//7523 8256//8256 -f 8256//8256 7523//7523 7522//7522 -f 8256//8256 7522//7522 8257//8257 -f 8257//8257 7522//7522 7520//7520 -f 8257//8257 7520//7520 8258//8258 -f 8258//8258 7520//7520 7518//7518 -f 8258//8258 7518//7518 8259//8259 -f 8259//8259 7518//7518 7517//7517 -f 8259//8259 7517//7517 8260//8260 -f 8260//8260 7517//7517 7531//7531 -f 8260//8260 7531//7531 8261//8261 -f 8261//8261 7531//7531 7530//7530 -f 8261//8261 7530//7530 8262//8262 -f 8262//8262 7530//7530 7529//7529 -f 8262//8262 7529//7529 8263//8263 -f 8263//8263 7529//7529 7528//7528 -f 8263//8263 7528//7528 8264//8264 -f 8264//8264 7528//7528 7527//7527 -f 8264//8264 7527//7527 8265//8265 -f 8265//8265 7527//7527 7524//7524 -f 8265//8265 7524//7524 8240//8240 -f 8240//8240 7524//7524 7496//7496 -f 8266//8266 8263//8263 8267//8267 -f 8267//8267 8263//8263 8264//8264 -f 8267//8267 8264//8264 8268//8268 -f 8268//8268 8264//8264 8265//8265 -f 8268//8268 8265//8265 8269//8269 -f 8269//8269 8265//8265 8240//8240 -f 8269//8269 8240//8240 8270//8270 -f 8270//8270 8240//8240 8241//8241 -f 8270//8270 8241//8241 8271//8271 -f 8272//8272 8256//8256 8273//8273 -f 8273//8273 8256//8256 8257//8257 -f 8273//8273 8257//8257 8274//8274 -f 8274//8274 8257//8257 8258//8258 -f 8274//8274 8258//8258 8275//8275 -f 8275//8275 8258//8258 8259//8259 -f 8275//8275 8259//8259 8276//8276 -f 8276//8276 8259//8259 8260//8260 -f 8276//8276 8260//8260 8277//8277 -f 8277//8277 8260//8260 8261//8261 -f 8277//8277 8261//8261 8266//8266 -f 8266//8266 8261//8261 8262//8262 -f 8266//8266 8262//8262 8263//8263 -f 8241//8241 8242//8242 8271//8271 -f 8271//8271 8242//8242 8243//8243 -f 8271//8271 8243//8243 8278//8278 -f 8278//8278 8243//8243 8244//8244 -f 8278//8278 8244//8244 8279//8279 -f 8279//8279 8244//8244 8245//8245 -f 8279//8279 8245//8245 8280//8280 -f 8280//8280 8245//8245 8246//8246 -f 8280//8280 8246//8246 8281//8281 -f 8281//8281 8246//8246 8247//8247 -f 8281//8281 8247//8247 8282//8282 -f 8282//8282 8247//8247 8248//8248 -f 8282//8282 8248//8248 8283//8283 -f 8248//8248 8249//8249 8283//8283 -f 8283//8283 8249//8249 8250//8250 -f 8283//8283 8250//8250 8284//8284 -f 8284//8284 8250//8250 8251//8251 -f 8284//8284 8251//8251 8285//8285 -f 8285//8285 8251//8251 8252//8252 -f 8285//8285 8252//8252 8286//8286 -f 8286//8286 8252//8252 8253//8253 -f 8286//8286 8253//8253 8287//8287 -f 8287//8287 8253//8253 8254//8254 -f 8287//8287 8254//8254 8272//8272 -f 8272//8272 8254//8254 8255//8255 -f 8272//8272 8255//8255 8256//8256 -f 8288//8288 8270//8270 8289//8289 -f 8289//8289 8270//8270 8271//8271 -f 8289//8289 8271//8271 8290//8290 -f 8290//8290 8271//8271 8278//8278 -f 8290//8290 8278//8278 8291//8291 -f 8291//8291 8278//8278 8279//8279 -f 8291//8291 8279//8279 8292//8292 -f 8292//8292 8279//8279 8280//8280 -f 8292//8292 8280//8280 8293//8293 -f 8293//8293 8280//8280 8281//8281 -f 8293//8293 8281//8281 8294//8294 -f 8294//8294 8281//8281 8282//8282 -f 8294//8294 8282//8282 8295//8295 -f 8295//8295 8282//8282 8283//8283 -f 8295//8295 8283//8283 8296//8296 -f 8296//8296 8283//8283 8284//8284 -f 8296//8296 8284//8284 8297//8297 -f 8297//8297 8284//8284 8285//8285 -f 8297//8297 8285//8285 8298//8298 -f 8298//8298 8285//8285 8286//8286 -f 8298//8298 8286//8286 8299//8299 -f 8299//8299 8286//8286 8287//8287 -f 8299//8299 8287//8287 8300//8300 -f 8300//8300 8287//8287 8272//8272 -f 8300//8300 8272//8272 8301//8301 -f 8301//8301 8272//8272 8273//8273 -f 8301//8301 8273//8273 8302//8302 -f 8302//8302 8273//8273 8274//8274 -f 8302//8302 8274//8274 8303//8303 -f 8303//8303 8274//8274 8275//8275 -f 8303//8303 8275//8275 8304//8304 -f 8304//8304 8275//8275 8276//8276 -f 8304//8304 8276//8276 8305//8305 -f 8305//8305 8276//8276 8277//8277 -f 8305//8305 8277//8277 8306//8306 -f 8306//8306 8277//8277 8266//8266 -f 8306//8306 8266//8266 8307//8307 -f 8307//8307 8266//8266 8267//8267 -f 8307//8307 8267//8267 8308//8308 -f 8308//8308 8267//8267 8268//8268 -f 8308//8308 8268//8268 8309//8309 -f 8309//8309 8268//8268 8269//8269 -f 8309//8309 8269//8269 8288//8288 -f 8288//8288 8269//8269 8270//8270 -f 8310//8310 8306//8306 8311//8311 -f 8311//8311 8306//8306 8307//8307 -f 8311//8311 8307//8307 8312//8312 -f 8312//8312 8307//8307 8308//8308 -f 8312//8312 8308//8308 8313//8313 -f 8313//8313 8308//8308 8309//8309 -f 8313//8313 8309//8309 8314//8314 -f 8314//8314 8309//8309 8288//8288 -f 8314//8314 8288//8288 8315//8315 -f 8315//8315 8288//8288 8289//8289 -f 8315//8315 8289//8289 8316//8316 -f 8316//8316 8289//8289 8290//8290 -f 8316//8316 8290//8290 8317//8317 -f 8318//8318 8300//8300 8319//8319 -f 8319//8319 8300//8300 8301//8301 -f 8319//8319 8301//8301 8320//8320 -f 8320//8320 8301//8301 8302//8302 -f 8320//8320 8302//8302 8321//8321 -f 8321//8321 8302//8302 8303//8303 -f 8321//8321 8303//8303 8322//8322 -f 8322//8322 8303//8303 8304//8304 -f 8322//8322 8304//8304 8310//8310 -f 8310//8310 8304//8304 8305//8305 -f 8310//8310 8305//8305 8306//8306 -f 8290//8290 8291//8291 8317//8317 -f 8317//8317 8291//8291 8292//8292 -f 8317//8317 8292//8292 8323//8323 -f 8323//8323 8292//8292 8293//8293 -f 8323//8323 8293//8293 8324//8324 -f 8324//8324 8293//8293 8294//8294 -f 8324//8324 8294//8294 8325//8325 -f 8325//8325 8294//8294 8295//8295 -f 8325//8325 8295//8295 8326//8326 -f 8326//8326 8295//8295 8296//8296 -f 8326//8326 8296//8296 8327//8327 -f 8327//8327 8296//8296 8297//8297 -f 8327//8327 8297//8297 8328//8328 -f 8328//8328 8297//8297 8298//8298 -f 8328//8328 8298//8298 8318//8318 -f 8318//8318 8298//8298 8299//8299 -f 8318//8318 8299//8299 8300//8300 -f 8329//8329 8314//8314 8330//8330 -f 8330//8330 8314//8314 8315//8315 -f 8330//8330 8315//8315 8331//8331 -f 8331//8331 8315//8315 8316//8316 -f 8331//8331 8316//8316 8332//8332 -f 8332//8332 8316//8316 8317//8317 -f 8332//8332 8317//8317 8333//8333 -f 8333//8333 8317//8317 8323//8323 -f 8333//8333 8323//8323 8334//8334 -f 8334//8334 8323//8323 8324//8324 -f 8334//8334 8324//8324 8335//8335 -f 8335//8335 8324//8324 8325//8325 -f 8335//8335 8325//8325 8336//8336 -f 8336//8336 8325//8325 8326//8326 -f 8336//8336 8326//8326 8337//8337 -f 8337//8337 8326//8326 8327//8327 -f 8337//8337 8327//8327 8338//8338 -f 8338//8338 8327//8327 8328//8328 -f 8338//8338 8328//8328 8339//8339 -f 8339//8339 8328//8328 8318//8318 -f 8339//8339 8318//8318 8340//8340 -f 8340//8340 8318//8318 8319//8319 -f 8340//8340 8319//8319 8341//8341 -f 8341//8341 8319//8319 8320//8320 -f 8341//8341 8320//8320 8342//8342 -f 8342//8342 8320//8320 8321//8321 -f 8342//8342 8321//8321 8343//8343 -f 8343//8343 8321//8321 8322//8322 -f 8343//8343 8322//8322 8344//8344 -f 8344//8344 8322//8322 8310//8310 -f 8344//8344 8310//8310 8345//8345 -f 8345//8345 8310//8310 8311//8311 -f 8345//8345 8311//8311 8346//8346 -f 8346//8346 8311//8311 8312//8312 -f 8346//8346 8312//8312 8347//8347 -f 8347//8347 8312//8312 8313//8313 -f 8347//8347 8313//8313 8329//8329 -f 8329//8329 8313//8313 8314//8314 -f 8329//8329 8330//8330 8348//8348 -f 8345//8345 8346//8346 8348//8348 -f 8348//8348 8346//8346 8347//8347 -f 8348//8348 8347//8347 8329//8329 -f 8342//8342 8343//8343 8348//8348 -f 8348//8348 8343//8343 8344//8344 -f 8348//8348 8344//8344 8345//8345 -f 8339//8339 8340//8340 8348//8348 -f 8348//8348 8340//8340 8341//8341 -f 8348//8348 8341//8341 8342//8342 -f 8336//8336 8337//8337 8348//8348 -f 8348//8348 8337//8337 8338//8338 -f 8348//8348 8338//8338 8339//8339 -f 8333//8333 8334//8334 8348//8348 -f 8348//8348 8334//8334 8335//8335 -f 8348//8348 8335//8335 8336//8336 -f 8330//8330 8331//8331 8348//8348 -f 8348//8348 8331//8331 8332//8332 -f 8348//8348 8332//8332 8333//8333 -f 7906//7906 7331//7331 7902//7902 -f 7902//7902 7331//7331 7326//7326 -f 7896//7896 7348//7348 7892//7892 -f 7892//7892 7348//7348 7337//7337 -f 7886//7886 7357//7357 7882//7882 -f 7882//7882 7357//7357 7354//7354 -f 7284//7284 7872//7872 7285//7285 -f 7285//7285 7872//7872 7876//7876 -f 7285//7285 7876//7876 7295//7295 -f 7379//7379 7859//7859 7214//7214 -f 7214//7214 7859//7859 7864//7864 -f 7214//7214 7864//7864 7215//7215 -f 7836//7836 7381//7381 7837//7837 -f 7837//7837 7381//7381 7380//7380 -f 7384//7384 7824//7824 7383//7383 -f 7383//7383 7824//7824 7823//7823 -f 7383//7383 7823//7823 7382//7382 -f 7776//7776 7405//7405 7777//7777 -f 7777//7777 7405//7405 7404//7404 -f 7770//7770 7425//7425 7771//7771 -f 7771//7771 7425//7425 7424//7424 -f 7764//7764 7449//7449 7765//7765 -f 7765//7765 7449//7449 7448//7448 -f 7603//7603 7766//7766 7604//7604 -f 7604//7604 7766//7766 7767//7767 -f 7740//7740 7763//7763 7739//7739 -f 7739//7739 7763//7763 7762//7762 -f 7688//7688 7772//7772 7689//7689 -f 7689//7689 7772//7772 7773//7773 -f 7657//7657 7769//7769 7658//7658 -f 7658//7658 7769//7769 7768//7768 -f 7651//7651 7778//7778 7652//7652 -f 7652//7652 7778//7778 7779//7779 -f 7647//7647 7775//7775 7648//7648 -f 7648//7648 7775//7775 7774//7774 -f 7634//7634 7825//7825 7635//7635 -f 7635//7635 7825//7825 7826//7826 -f 7672//7672 7822//7822 7673//7673 -f 7673//7673 7822//7822 7821//7821 -f 7607//7607 7904//7904 7608//7608 -f 7608//7608 7904//7904 7903//7903 -f 7624//7624 7908//7908 7625//7625 -f 7625//7625 7908//7908 7901//7901 -f 7612//7612 7894//7894 7613//7613 -f 7613//7613 7894//7894 7893//7893 -f 7629//7629 7898//7898 7630//7630 -f 7630//7630 7898//7898 7891//7891 -f 7616//7616 7884//7884 7617//7617 -f 7617//7617 7884//7884 7883//7883 -f 7640//7640 7888//7888 7641//7641 -f 7641//7641 7888//7888 7881//7881 -f 7665//7665 7874//7874 7666//7666 -f 7666//7666 7874//7874 7873//7873 -f 7669//7669 7878//7878 7670//7670 -f 7670//7670 7878//7878 7871//7871 -f 7731//7731 7838//7838 7732//7732 -f 7732//7732 7838//7838 7839//7839 -f 7724//7724 7835//7835 7725//7725 -f 7725//7725 7835//7835 7834//7834 -f 7719//7719 7866//7866 7720//7720 -f 7720//7720 7866//7866 7860//7860 -f 7598//7598 7862//7862 7599//7599 -f 7599//7599 7862//7862 7861//7861 -f 7910//7910 7323//7323 7909//7909 -f 7909//7909 7323//7323 7324//7324 -f 7344//7344 7899//7899 7345//7345 -f 7345//7345 7899//7899 7900//7900 -f 7345//7345 7900//7900 7319//7319 -f 7359//7359 7889//7889 7367//7367 -f 7367//7367 7889//7889 7890//7890 -f 7367//7367 7890//7890 7336//7336 -f 7297//7297 7879//7879 7362//7362 -f 7362//7362 7879//7879 7880//7880 -f 7362//7362 7880//7880 7353//7353 -f 7870//7870 7286//7286 7869//7869 -f 7869//7869 7286//7286 7288//7288 -f 7868//7868 7288//7288 7867//7867 -f 7867//7867 7288//7288 7291//7291 -f 7846//7846 7430//7430 7843//7843 -f 7843//7843 7430//7430 7429//7429 -f 7446//7446 7847//7847 7447//7447 -f 7447//7447 7847//7847 7848//7848 -f 7447//7447 7848//7848 7412//7412 -f 7415//7415 7849//7849 7416//7416 -f 7416//7416 7849//7849 7850//7850 -f 7416//7416 7850//7850 7391//7391 -f 7399//7399 7851//7851 7398//7398 -f 7398//7398 7851//7851 7852//7852 -f 7398//7398 7852//7852 7227//7227 -f 7856//7856 7248//7248 7855//7855 -f 7855//7855 7248//7248 7246//7246 -f 7854//7854 7246//7246 7853//7853 -f 7853//7853 7246//7246 7244//7244 -f 7858//7858 7275//7275 7857//7857 -f 7857//7857 7275//7275 7274//7274 -f 7857//7857 7274//7274 7261//7261 -f 7485//7485 8111//8111 7454//7454 -f 7454//7454 8111//8111 7452//7452 -f 8111//8111 7485//7485 8112//8112 -f 8112//8112 7485//7485 7519//7519 -f 8112//8112 7519//7519 8113//8113 -f 8113//8113 7519//7519 7521//7521 -f 8113//8113 7521//7521 8089//8089 -f 8089//8089 7521//7521 7488//7488 -f 8117//8117 7431//7431 7453//7453 -f 7453//7453 7431//7431 7433//7433 -f 7516//7516 8088//8088 7488//7488 -f 7488//7488 8088//8088 8089//8089 -f 8115//8115 7544//7544 8114//8114 -f 8114//8114 7544//7544 8226//8226 -f 8114//8114 8226//8226 8119//8119 -f 8119//8119 8226//8226 8225//8225 -f 8119//8119 8225//8225 8120//8120 -f 8120//8120 8225//8225 8224//8224 -f 8120//8120 8224//8224 8118//8118 -f 8118//8118 8224//8224 8223//8223 -f 8118//8118 8223//8223 8117//8117 -f 8117//8117 8223//8223 7431//7431 -f 8088//8088 7516//7516 8237//8237 -f 8088//8088 8237//8237 8087//8087 -f 8087//8087 8237//8237 8239//8239 -f 8087//8087 8239//8239 8086//8086 -f 8086//8086 8239//8239 7483//7483 -f 8086//8086 7483//7483 8083//8083 -f 8116//8116 7545//7545 8115//8115 -f 8115//8115 7545//7545 7544//7544 -f 7478//7478 8084//8084 7483//7483 -f 7483//7483 8084//8084 8083//8083 -f 8102//8102 7479//7479 7533//7533 -f 7545//7545 8116//8116 7542//7542 -f 7542//7542 8116//8116 8092//8092 -f 7542//7542 8092//8092 8094//8094 -f 8102//8102 7533//7533 8100//8100 -f 8100//8100 7533//7533 7534//7534 -f 8100//8100 7534//7534 8098//8098 -f 8098//8098 7534//7534 7536//7536 -f 8098//8098 7536//7536 8096//8096 -f 7536//7536 7537//7537 8096//8096 -f 8096//8096 7537//7537 7539//7539 -f 8096//8096 7539//7539 8094//8094 -f 8094//8094 7539//7539 7540//7540 -f 8094//8094 7540//7540 7542//7542 -f 7479//7479 8102//8102 7478//7478 -f 7478//7478 8102//8102 8084//8084 -f 8075//8075 7505//7505 7914//7914 -f 7914//7914 7505//7505 7509//7509 -f 7913//7913 7317//7317 8076//8076 -f 8076//8076 7317//7317 7218//7218 -f 8076//8076 7218//7218 7217//7217 -f 8047//8047 7514//7514 8081//8081 -f 8081//8081 7514//7514 7501//7501 -f 8081//8081 7501//7501 8082//8082 -f 8082//8082 7501//7501 7503//7503 -f 8082//8082 7503//7503 8075//8075 -f 8075//8075 7503//7503 7505//7505 -f 8054//8054 8053//8053 8077//8077 -f 8054//8054 8077//8077 8037//8037 -f 8076//8076 7217//7217 8078//8078 -f 8078//8078 7217//7217 8235//8235 -f 8078//8078 8235//8235 8079//8079 -f 8079//8079 8235//8235 8234//8234 -f 8079//8079 8234//8234 8080//8080 -f 8080//8080 8234//8234 8233//8233 -f 8080//8080 8233//8233 8077//8077 -f 8077//8077 8233//8233 8232//8232 -f 8077//8077 8232//8232 8037//8037 -f 8046//8046 7515//7515 8047//8047 -f 8047//8047 7515//7515 7514//7514 -f 8037//8037 8038//8038 8054//8054 -f 8051//8051 7482//7482 8238//8238 -f 8051//8051 8238//8238 8050//8050 -f 8050//8050 8238//8238 8236//8236 -f 8050//8050 8236//8236 8049//8049 -f 8049//8049 8236//8236 7515//7515 -f 8049//8049 7515//7515 8046//8046 -f 8055//8055 8054//8054 8038//8038 -f 8038//8038 8039//8039 8055//8055 -f 8055//8055 8039//8039 8040//8040 -f 8055//8055 8040//8040 8073//8073 -f 8073//8073 8040//8040 8041//8041 -f 8041//8041 8042//8042 8073//8073 -f 8073//8073 8042//8042 8043//8043 -f 8073//8073 8043//8043 8071//8071 -f 8043//8043 8044//8044 8071//8071 -f 8071//8071 8044//8044 8045//8045 -f 8071//8071 8045//8045 8069//8069 -f 8069//8069 8045//8045 7480//7480 -f 8069//8069 7480//7480 8067//8067 -f 8052//8052 7481//7481 8051//8051 -f 8051//8051 7481//7481 7482//7482 -f 7481//7481 8052//8052 7480//7480 -f 7480//7480 8052//8052 8067//8067 -f 7484//7484 7455//7455 7926//7926 -f 7926//7926 7455//7455 7456//7456 -f 7473//7473 7926//7926 7456//7456 -f 7472//7472 7925//7925 7473//7473 -f 7473//7473 7925//7925 7926//7926 -f 8171//8171 8201//8201 7450//7450 -f 7450//7450 8201//8201 7451//7451 -f 7451//7451 7468//7468 7456//7456 -f 7456//7456 7468//7468 7473//7473 -f 7925//7925 7472//7472 7924//7924 -f 7924//7924 7472//7472 7474//7474 -f 7924//7924 7474//7474 7923//7923 -f 7923//7923 7474//7474 7475//7475 -f 7923//7923 7475//7475 7922//7922 -f 7922//7922 7475//7475 7467//7467 -f 7922//7922 7467//7467 7921//7921 -f 7921//7921 7467//7467 7466//7466 -f 7921//7921 7466//7466 7920//7920 -f 7920//7920 7466//7466 7464//7464 -f 7920//7920 7464//7464 7919//7919 -f 7919//7919 7464//7464 7463//7463 -f 7919//7919 7463//7463 7918//7918 -f 7918//7918 7463//7463 7471//7471 -f 7450//7450 7231//7231 7242//7242 -f 7258//7258 7268//7268 8174//8174 -f 8174//8174 7268//7268 7458//7458 -f 8174//8174 7458//7458 8172//8172 -f 7258//7258 8174//8174 7257//7257 -f 7257//7257 8174//8174 8179//8179 -f 7257//7257 8179//8179 7266//7266 -f 8179//8179 8178//8178 7266//7266 -f 7266//7266 8178//8178 8182//8182 -f 7266//7266 8182//8182 7267//7267 -f 8182//8182 8181//8181 7267//7267 -f 7267//7267 8181//8181 8185//8185 -f 7267//7267 8185//8185 7247//7247 -f 8185//8185 8184//8184 7247//7247 -f 7247//7247 8184//8184 8188//8188 -f 7247//7247 8188//8188 7245//7245 -f 8188//8188 8187//8187 7245//7245 -f 7245//7245 8187//8187 8191//8191 -f 7245//7245 8191//8191 7236//7236 -f 7236//7236 8191//8191 8190//8190 -f 7236//7236 8190//8190 7237//7237 -f 7237//7237 8190//8190 8194//8194 -f 7237//7237 8194//8194 7239//7239 -f 8194//8194 8193//8193 7239//7239 -f 7239//7239 8193//8193 8197//8197 -f 7239//7239 8197//8197 7241//7241 -f 8197//8197 8196//8196 7241//7241 -f 7241//7241 8196//8196 8200//8200 -f 7241//7241 8200//8200 7242//7242 -f 7242//7242 8200//8200 8199//8199 -f 7242//7242 8199//8199 7450//7450 -f 7450//7450 8199//8199 8198//8198 -f 7450//7450 8198//8198 8171//8171 -f 7451//7451 8201//8201 7468//7468 -f 7462//7462 7917//7917 7471//7471 -f 7471//7471 7917//7917 7918//7918 -f 7917//7917 7916//7916 7508//7508 -f 7508//7508 7916//7916 7510//7510 -f 7457//7457 8205//8205 7458//7458 -f 7458//7458 8205//8205 8172//8172 -f 8204//8204 8205//8205 7469//7469 -f 8204//8204 7469//7469 8203//8203 -f 8203//8203 7469//7469 7465//7465 -f 8203//8203 7465//7465 8202//8202 -f 8202//8202 7465//7465 7468//7468 -f 8202//8202 7468//7468 8201//8201 -f 7917//7917 7462//7462 7916//7916 -f 8205//8205 7457//7457 7469//7469 -f 7461//7461 7915//7915 7462//7462 -f 7462//7462 7915//7915 7916//7916 -f 7459//7459 7470//7470 7457//7457 -f 7457//7457 7470//7470 7469//7469 -f 7470//7470 8152//8152 8153//8153 -f 7470//7470 8153//8153 7460//7460 -f 7460//7460 8153//8153 8154//8154 -f 7460//7460 8154//8154 7461//7461 -f 7461//7461 8154//8154 8155//8155 -f 7461//7461 8155//8155 8156//8156 -f 7461//7461 8156//8156 7915//7915 -f 7470//7470 7459//7459 8152//8152 -f 7219//7219 7915//7915 7220//7220 -f 7220//7220 7915//7915 8156//8156 -f 7220//7220 8156//8156 8121//8121 -f 7459//7459 7271//7271 8152//8152 -f 8152//8152 7271//7271 7273//7273 -f 8152//8152 7273//7273 8150//8150 -f 8150//8150 7273//7273 8151//8151 -f 8151//8151 7273//7273 7272//7272 -f 7221//7221 7220//7220 8121//8121 -f 8121//8121 8123//8123 7221//7221 -f 7221//7221 8123//8123 8125//8125 -f 7221//7221 8125//8125 7304//7304 -f 8125//8125 8129//8129 7304//7304 -f 7304//7304 8129//8129 8128//8128 -f 7304//7304 8128//8128 7310//7310 -f 8128//8128 8132//8132 7310//7310 -f 7310//7310 8132//8132 8131//8131 -f 7310//7310 8131//8131 7309//7309 -f 8131//8131 8135//8135 7309//7309 -f 7309//7309 8135//8135 8134//8134 -f 7309//7309 8134//8134 7287//7287 -f 7287//7287 8134//8134 7289//7289 -f 8134//8134 8142//8142 7289//7289 -f 7289//7289 8142//8142 8141//8141 -f 7289//7289 8141//8141 7290//7290 -f 7290//7290 8141//8141 8139//8139 -f 7290//7290 8139//8139 7292//7292 -f 7292//7292 8139//8139 8137//8137 -f 7292//7292 8137//8137 7378//7378 -f 7378//7378 8137//8137 7376//7376 -f 7376//7376 8137//8137 8145//8145 -f 7376//7376 8145//8145 7374//7374 -f 8145//8145 8144//8144 7374//7374 -f 7374//7374 8144//8144 8148//8148 -f 7374//7374 8148//8148 7272//7272 -f 7272//7272 8148//8148 8147//8147 -f 7272//7272 8147//8147 8151//8151 -f 8349//8349 8350//8350 8351//8351 -f 8352//8352 8353//8353 8354//8354 -f 8355//8355 8356//8356 8357//8357 -f 8358//8358 8359//8359 8360//8360 -f 8361//8361 8362//8362 8363//8363 -f 8364//8364 8365//8365 8366//8366 -f 8366//8366 8365//8365 8367//8367 -f 8366//8366 8367//8367 8368//8368 -f 8369//8369 8370//8370 8371//8371 -f 8371//8371 8372//8372 8369//8369 -f 8369//8369 8372//8372 8373//8373 -f 8369//8369 8373//8373 8374//8374 -f 8374//8374 8373//8373 8375//8375 -f 8374//8374 8375//8375 8376//8376 -f 8377//8377 8378//8378 8379//8379 -f 8379//8379 8378//8378 8380//8380 -f 8379//8379 8380//8380 8381//8381 -f 8381//8381 8380//8380 8382//8382 -f 8381//8381 8382//8382 8376//8376 -f 8376//8376 8382//8382 8383//8383 -f 8376//8376 8383//8383 8374//8374 -f 8384//8384 8385//8385 8386//8386 -f 8386//8386 8385//8385 8387//8387 -f 8386//8386 8387//8387 8388//8388 -f 8388//8388 8387//8387 8389//8389 -f 8388//8388 8389//8389 8390//8390 -f 8389//8389 8391//8391 8390//8390 -f 8390//8390 8391//8391 8392//8392 -f 8390//8390 8392//8392 8360//8360 -f 8360//8360 8392//8392 8393//8393 -f 8360//8360 8393//8393 8394//8394 -f 8395//8395 8396//8396 8397//8397 -f 8397//8397 8396//8396 8398//8398 -f 8397//8397 8398//8398 8399//8399 -f 8399//8399 8398//8398 8400//8400 -f 8401//8401 8402//8402 8403//8403 -f 8403//8403 8402//8402 8404//8404 -f 8403//8403 8404//8404 8405//8405 -f 8401//8401 8406//8406 8402//8402 -f 8402//8402 8406//8406 8407//8407 -f 8402//8402 8407//8407 8408//8408 -f 8408//8408 8407//8407 8409//8409 -f 8408//8408 8409//8409 8410//8410 -f 8411//8411 8412//8412 8413//8413 -f 8414//8414 8415//8415 8416//8416 -f 8416//8416 8415//8415 8417//8417 -f 8416//8416 8417//8417 8403//8403 -f 8403//8403 8417//8417 8418//8418 -f 8403//8403 8418//8418 8401//8401 -f 8409//8409 8419//8419 8410//8410 -f 8410//8410 8419//8419 8420//8420 -f 8410//8410 8420//8420 8412//8412 -f 8412//8412 8420//8420 8421//8421 -f 8412//8412 8421//8421 8413//8413 -f 8422//8422 8423//8423 8424//8424 -f 8423//8423 8425//8425 8424//8424 -f 8424//8424 8425//8425 8426//8426 -f 8424//8424 8426//8426 8427//8427 -f 8427//8427 8426//8426 8428//8428 -f 8428//8428 8429//8429 8427//8427 -f 8427//8427 8429//8429 8430//8430 -f 8427//8427 8430//8430 8431//8431 -f 8430//8430 8432//8432 8431//8431 -f 8431//8431 8432//8432 8433//8433 -f 8431//8431 8433//8433 8434//8434 -f 8434//8434 8433//8433 8435//8435 -f 8434//8434 8435//8435 8436//8436 -f 8436//8436 8435//8435 8437//8437 -f 8436//8436 8437//8437 8438//8438 -f 8438//8438 8437//8437 8439//8439 -f 8438//8438 8439//8439 8422//8422 -f 8440//8440 8441//8441 8442//8442 -f 8442//8442 8441//8441 8443//8443 -f 8442//8442 8443//8443 8444//8444 -f 8444//8444 8443//8443 8445//8445 -f 8444//8444 8445//8445 8446//8446 -f 8446//8446 8447//8447 8444//8444 -f 8444//8444 8447//8447 8448//8448 -f 8444//8444 8448//8448 8449//8449 -f 8450//8450 8451//8451 8452//8452 -f 8448//8448 8453//8453 8449//8449 -f 8449//8449 8453//8453 8454//8454 -f 8449//8449 8454//8454 8451//8451 -f 8452//8452 8455//8455 8450//8450 -f 8450//8450 8455//8455 8456//8456 -f 8450//8450 8456//8456 8457//8457 -f 8457//8457 8456//8456 8458//8458 -f 8457//8457 8458//8458 8459//8459 -f 8459//8459 8458//8458 8460//8460 -f 8459//8459 8460//8460 8445//8445 -f 8445//8445 8460//8460 8461//8461 -f 8445//8445 8461//8461 8446//8446 -f 8462//8462 8463//8463 8464//8464 -f 8464//8464 8463//8463 8465//8465 -f 8464//8464 8465//8465 8466//8466 -f 8467//8467 8468//8468 8469//8469 -f 8469//8469 8468//8468 8470//8470 -f 8469//8469 8470//8470 8471//8471 -f 8467//8467 8472//8472 8468//8468 -f 8468//8468 8472//8472 8473//8473 -f 8468//8468 8473//8473 8474//8474 -f 8474//8474 8473//8473 8475//8475 -f 8474//8474 8475//8475 8476//8476 -f 8476//8476 8475//8475 8477//8477 -f 8476//8476 8477//8477 8465//8465 -f 8465//8465 8477//8477 8478//8478 -f 8465//8465 8478//8478 8466//8466 -f 8479//8479 8480//8480 8481//8481 -f 8481//8481 8480//8480 8464//8464 -f 8481//8481 8464//8464 8482//8482 -f 8482//8482 8464//8464 8466//8466 -f 8483//8483 8484//8484 8485//8485 -f 8483//8483 8485//8485 8486//8486 -f 8487//8487 8488//8488 8464//8464 -f 8464//8464 8488//8488 8489//8489 -f 8464//8464 8489//8489 8462//8462 -f 8462//8462 8489//8489 8490//8490 -f 8462//8462 8490//8490 8491//8491 -f 8492//8492 8493//8493 8494//8494 -f 8495//8495 8496//8496 8497//8497 -f 8496//8496 8498//8498 8497//8497 -f 8497//8497 8498//8498 8499//8499 -f 8497//8497 8499//8499 8500//8500 -f 8500//8500 8499//8499 8501//8501 -f 8485//8485 8502//8502 8486//8486 -f 8486//8486 8502//8502 8503//8503 -f 8486//8486 8503//8503 8504//8504 -f 8504//8504 8503//8503 8505//8505 -f 8506//8506 8351//8351 8507//8507 -f 8507//8507 8351//8351 8508//8508 -f 8507//8507 8508//8508 8470//8470 -f 8470//8470 8508//8508 8480//8480 -f 8470//8470 8480//8480 8471//8471 -f 8471//8471 8480//8480 8479//8479 -f 8509//8509 8510//8510 8511//8511 -f 8512//8512 8511//8511 8513//8513 -f 8514//8514 8515//8515 8516//8516 -f 8516//8516 8515//8515 8486//8486 -f 8516//8516 8486//8486 8517//8517 -f 8517//8517 8486//8486 8504//8504 -f 8517//8517 8504//8504 8518//8518 -f 8518//8518 8504//8504 8505//8505 -f 8518//8518 8505//8505 8519//8519 -f 8427//8427 8520//8520 8424//8424 -f 8424//8424 8520//8520 8521//8521 -f 8424//8424 8521//8521 8518//8518 -f 8518//8518 8521//8521 8522//8522 -f 8518//8518 8522//8522 8517//8517 -f 8523//8523 8524//8524 8525//8525 -f 8526//8526 8434//8434 8527//8527 -f 8527//8527 8434//8434 8436//8436 -f 8527//8527 8436//8436 8528//8528 -f 8528//8528 8436//8436 8525//8525 -f 8529//8529 8530//8530 8531//8531 -f 8532//8532 8530//8530 8533//8533 -f 8533//8533 8530//8530 8529//8529 -f 8533//8533 8529//8529 8534//8534 -f 8395//8395 8384//8384 8396//8396 -f 8396//8396 8384//8384 8386//8386 -f 8396//8396 8386//8386 8535//8535 -f 8535//8535 8386//8386 8536//8536 -f 8535//8535 8536//8536 8537//8537 -f 8537//8537 8536//8536 8538//8538 -f 8537//8537 8538//8538 8539//8539 -f 8357//8357 8356//8356 8398//8398 -f 8394//8394 8400//8400 8360//8360 -f 8360//8360 8400//8400 8398//8398 -f 8360//8360 8398//8398 8358//8358 -f 8358//8358 8398//8398 8356//8356 -f 8358//8358 8356//8356 8540//8540 -f 8357//8357 8541//8541 8355//8355 -f 8355//8355 8541//8541 8542//8542 -f 8355//8355 8542//8542 8543//8543 -f 8543//8543 8542//8542 8544//8544 -f 8545//8545 8546//8546 8542//8542 -f 8542//8542 8546//8546 8547//8547 -f 8542//8542 8547//8547 8544//8544 -f 8548//8548 8549//8549 8550//8550 -f 8550//8550 8549//8549 8551//8551 -f 8550//8550 8551//8551 8552//8552 -f 8552//8552 8551//8551 8553//8553 -f 8554//8554 8555//8555 8551//8551 -f 8556//8556 8553//8553 8557//8557 -f 8557//8557 8553//8553 8551//8551 -f 8557//8557 8551//8551 8558//8558 -f 8558//8558 8551//8551 8555//8555 -f 8559//8559 8560//8560 8561//8561 -f 8451//8451 8450//8450 8449//8449 -f 8449//8449 8450//8450 8562//8562 -f 8449//8449 8562//8562 8563//8563 -f 8563//8563 8564//8564 8449//8449 -f 8449//8449 8564//8564 8565//8565 -f 8449//8449 8565//8565 8566//8566 -f 8566//8566 8565//8565 8559//8559 -f 8567//8567 8568//8568 8569//8569 -f 8569//8569 8570//8570 8567//8567 -f 8567//8567 8570//8570 8571//8571 -f 8567//8567 8571//8571 8402//8402 -f 8402//8402 8571//8571 8572//8572 -f 8402//8402 8572//8572 8404//8404 -f 8570//8570 8573//8573 8571//8571 -f 8571//8571 8573//8573 8574//8574 -f 8571//8571 8574//8574 8575//8575 -f 8575//8575 8574//8574 8576//8576 -f 8575//8575 8576//8576 8577//8577 -f 8576//8576 8578//8578 8577//8577 -f 8577//8577 8578//8578 8579//8579 -f 8577//8577 8579//8579 8580//8580 -f 8581//8581 8582//8582 8583//8583 -f 8583//8583 8582//8582 8584//8584 -f 8583//8583 8584//8584 8568//8568 -f 8568//8568 8584//8584 8585//8585 -f 8568//8568 8585//8585 8569//8569 -f 8436//8436 8586//8586 8577//8577 -f 8525//8525 8436//8436 8523//8523 -f 8523//8523 8436//8436 8577//8577 -f 8523//8523 8577//8577 8583//8583 -f 8583//8583 8577//8577 8580//8580 -f 8583//8583 8580//8580 8581//8581 -f 8422//8422 8424//8424 8438//8438 -f 8438//8438 8424//8424 8587//8587 -f 8438//8438 8587//8587 8436//8436 -f 8436//8436 8587//8587 8588//8588 -f 8436//8436 8588//8588 8586//8586 -f 8589//8589 8590//8590 8518//8518 -f 8590//8590 8591//8591 8518//8518 -f 8518//8518 8591//8591 8592//8592 -f 8518//8518 8592//8592 8424//8424 -f 8424//8424 8592//8592 8593//8593 -f 8424//8424 8593//8593 8587//8587 -f 8594//8594 8595//8595 8596//8596 -f 8596//8596 8595//8595 8589//8589 -f 8596//8596 8589//8589 8597//8597 -f 8597//8597 8589//8589 8518//8518 -f 8597//8597 8518//8518 8598//8598 -f 8598//8598 8518//8518 8519//8519 -f 8599//8599 8594//8594 8497//8497 -f 8497//8497 8594//8594 8596//8596 -f 8497//8497 8596//8596 8495//8495 -f 8495//8495 8596//8596 8597//8597 -f 8495//8495 8597//8597 8600//8600 -f 8600//8600 8597//8597 8598//8598 -f 8601//8601 8602//8602 8603//8603 -f 8603//8603 8602//8602 8604//8604 -f 8603//8603 8604//8604 8605//8605 -f 8605//8605 8604//8604 8606//8606 -f 8605//8605 8606//8606 8497//8497 -f 8497//8497 8606//8606 8607//8607 -f 8497//8497 8607//8607 8599//8599 -f 8608//8608 8609//8609 8610//8610 -f 8609//8609 8608//8608 8611//8611 -f 8612//8612 8613//8613 8614//8614 -f 8615//8615 8616//8616 8617//8617 -f 8613//8613 8612//8612 8617//8617 -f 8617//8617 8612//8612 8618//8618 -f 8617//8617 8618//8618 8615//8615 -f 8616//8616 8615//8615 8619//8619 -f 8619//8619 8615//8615 8620//8620 -f 8619//8619 8620//8620 8621//8621 -f 8622//8622 8623//8623 8609//8609 -f 8609//8609 8623//8623 8624//8624 -f 8609//8609 8624//8624 8610//8610 -f 8610//8610 8624//8624 8625//8625 -f 8610//8610 8625//8625 8626//8626 -f 8626//8626 8625//8625 8627//8627 -f 8626//8626 8627//8627 8628//8628 -f 8628//8628 8627//8627 8629//8629 -f 8628//8628 8629//8629 8630//8630 -f 8630//8630 8629//8629 8631//8631 -f 8630//8630 8631//8631 8632//8632 -f 8633//8633 8634//8634 8635//8635 -f 8635//8635 8634//8634 8636//8636 -f 8633//8633 8637//8637 8634//8634 -f 8634//8634 8637//8637 8638//8638 -f 8634//8634 8638//8638 8370//8370 -f 8370//8370 8638//8638 8639//8639 -f 8370//8370 8639//8639 8371//8371 -f 8371//8371 8639//8639 8640//8640 -f 8371//8371 8640//8640 8641//8641 -f 8641//8641 8640//8640 8642//8642 -f 8641//8641 8642//8642 8364//8364 -f 8364//8364 8642//8642 8643//8643 -f 8364//8364 8643//8643 8365//8365 -f 8644//8644 8645//8645 8646//8646 -f 8646//8646 8645//8645 8647//8647 -f 8646//8646 8647//8647 8636//8636 -f 8636//8636 8647//8647 8648//8648 -f 8636//8636 8648//8648 8635//8635 -f 8649//8649 8650//8650 8651//8651 -f 8651//8651 8650//8650 8652//8652 -f 8651//8651 8652//8652 8653//8653 -f 8644//8644 8646//8646 8654//8654 -f 8654//8654 8646//8646 8655//8655 -f 8654//8654 8655//8655 8656//8656 -f 8656//8656 8655//8655 8549//8549 -f 8656//8656 8549//8549 8657//8657 -f 8657//8657 8549//8549 8548//8548 -f 8657//8657 8548//8548 8651//8651 -f 8651//8651 8548//8548 8658//8658 -f 8651//8651 8658//8658 8649//8649 -f 8557//8557 8659//8659 8556//8556 -f 8556//8556 8659//8659 8660//8660 -f 8556//8556 8660//8660 8661//8661 -f 8661//8661 8660//8660 8662//8662 -f 8661//8661 8662//8662 8663//8663 -f 8663//8663 8662//8662 8664//8664 -f 8663//8663 8664//8664 8665//8665 -f 8665//8665 8664//8664 8652//8652 -f 8665//8665 8652//8652 8666//8666 -f 8666//8666 8652//8652 8650//8650 -f 8377//8377 8368//8368 8378//8378 -f 8378//8378 8368//8368 8367//8367 -f 8378//8378 8367//8367 8652//8652 -f 8652//8652 8367//8367 8667//8667 -f 8652//8652 8667//8667 8653//8653 -f 8354//8354 8668//8668 8669//8669 -f 8622//8622 8670//8670 8671//8671 -f 8353//8353 8623//8623 8354//8354 -f 8354//8354 8623//8623 8622//8622 -f 8354//8354 8622//8622 8668//8668 -f 8668//8668 8622//8622 8671//8671 -f 8369//8369 8672//8672 8370//8370 -f 8370//8370 8672//8672 8673//8673 -f 8370//8370 8673//8673 8634//8634 -f 8634//8634 8673//8673 8674//8674 -f 8634//8634 8674//8674 8675//8675 -f 8669//8669 8676//8676 8354//8354 -f 8354//8354 8676//8676 8677//8677 -f 8354//8354 8677//8677 8678//8678 -f 8678//8678 8677//8677 8679//8679 -f 8678//8678 8679//8679 8369//8369 -f 8369//8369 8679//8679 8680//8680 -f 8369//8369 8680//8680 8672//8672 -f 8681//8681 8682//8682 8683//8683 -f 8681//8681 8683//8683 8684//8684 -f 8685//8685 8686//8686 8687//8687 -f 8687//8687 8686//8686 8688//8688 -f 8687//8687 8688//8688 8689//8689 -f 8689//8689 8684//8684 8687//8687 -f 8687//8687 8684//8684 8683//8683 -f 8687//8687 8683//8683 8690//8690 -f 8690//8690 8683//8683 8611//8611 -f 8690//8690 8611//8611 8691//8691 -f 8691//8691 8611//8611 8608//8608 -f 8551//8551 8692//8692 8685//8685 -f 8685//8685 8692//8692 8693//8693 -f 8685//8685 8693//8693 8686//8686 -f 8682//8682 8694//8694 8655//8655 -f 8655//8655 8694//8694 8695//8695 -f 8655//8655 8695//8695 8549//8549 -f 8549//8549 8695//8695 8696//8696 -f 8549//8549 8696//8696 8551//8551 -f 8551//8551 8696//8696 8697//8697 -f 8551//8551 8697//8697 8692//8692 -f 8698//8698 8388//8388 8699//8699 -f 8699//8699 8388//8388 8390//8390 -f 8699//8699 8390//8390 8700//8700 -f 8700//8700 8390//8390 8360//8360 -f 8700//8700 8360//8360 8701//8701 -f 8701//8701 8360//8360 8359//8359 -f 8702//8702 8408//8408 8703//8703 -f 8703//8703 8408//8408 8410//8410 -f 8703//8703 8410//8410 8704//8704 -f 8704//8704 8410//8410 8412//8412 -f 8705//8705 8524//8524 8706//8706 -f 8706//8706 8524//8524 8523//8523 -f 8706//8706 8523//8523 8707//8707 -f 8707//8707 8523//8523 8583//8583 -f 8707//8707 8583//8583 8708//8708 -f 8708//8708 8583//8583 8568//8568 -f 8413//8413 8414//8414 8411//8411 -f 8411//8411 8414//8414 8416//8416 -f 8411//8411 8416//8416 8531//8531 -f 8531//8531 8416//8416 8709//8709 -f 8531//8531 8709//8709 8529//8529 -f 8529//8529 8709//8709 8710//8710 -f 8710//8710 8711//8711 8529//8529 -f 8529//8529 8711//8711 8712//8712 -f 8529//8529 8712//8712 8713//8713 -f 8714//8714 8715//8715 8537//8537 -f 8539//8539 8534//8534 8537//8537 -f 8537//8537 8534//8534 8529//8529 -f 8537//8537 8529//8529 8714//8714 -f 8714//8714 8529//8529 8713//8713 -f 8716//8716 8535//8535 8717//8717 -f 8717//8717 8535//8535 8537//8537 -f 8717//8717 8537//8537 8718//8718 -f 8718//8718 8537//8537 8715//8715 -f 8716//8716 8719//8719 8535//8535 -f 8535//8535 8719//8719 8720//8720 -f 8535//8535 8720//8720 8709//8709 -f 8709//8709 8720//8720 8721//8721 -f 8709//8709 8721//8721 8710//8710 -f 8535//8535 8352//8352 8396//8396 -f 8396//8396 8352//8352 8354//8354 -f 8396//8396 8354//8354 8398//8398 -f 8398//8398 8354//8354 8678//8678 -f 8398//8398 8678//8678 8357//8357 -f 8357//8357 8678//8678 8369//8369 -f 8357//8357 8369//8369 8541//8541 -f 8541//8541 8369//8369 8374//8374 -f 8405//8405 8601//8601 8403//8403 -f 8403//8403 8601//8601 8603//8603 -f 8403//8403 8603//8603 8416//8416 -f 8416//8416 8603//8603 8722//8722 -f 8603//8603 8723//8723 8724//8724 -f 8725//8725 8726//8726 8722//8722 -f 8724//8724 8727//8727 8603//8603 -f 8603//8603 8727//8727 8728//8728 -f 8603//8603 8728//8728 8722//8722 -f 8722//8722 8728//8728 8729//8729 -f 8722//8722 8729//8729 8725//8725 -f 8726//8726 8630//8630 8722//8722 -f 8722//8722 8630//8630 8632//8632 -f 8722//8722 8632//8632 8416//8416 -f 8416//8416 8632//8632 8730//8730 -f 8416//8416 8730//8730 8709//8709 -f 8709//8709 8730//8730 8731//8731 -f 8709//8709 8731//8731 8535//8535 -f 8535//8535 8731//8731 8732//8732 -f 8535//8535 8732//8732 8352//8352 -f 8726//8726 8733//8733 8630//8630 -f 8630//8630 8733//8733 8734//8734 -f 8630//8630 8734//8734 8735//8735 -f 8723//8723 8603//8603 8736//8736 -f 8736//8736 8603//8603 8605//8605 -f 8736//8736 8605//8605 8737//8737 -f 8738//8738 8739//8739 8500//8500 -f 8500//8500 8739//8739 8628//8628 -f 8500//8500 8628//8628 8497//8497 -f 8497//8497 8628//8628 8630//8630 -f 8497//8497 8630//8630 8605//8605 -f 8605//8605 8630//8630 8735//8735 -f 8605//8605 8735//8735 8737//8737 -f 8682//8682 8655//8655 8683//8683 -f 8683//8683 8655//8655 8646//8646 -f 8683//8683 8646//8646 8611//8611 -f 8611//8611 8646//8646 8636//8636 -f 8611//8611 8636//8636 8609//8609 -f 8609//8609 8636//8636 8634//8634 -f 8609//8609 8634//8634 8622//8622 -f 8622//8622 8634//8634 8675//8675 -f 8622//8622 8675//8675 8670//8670 -f 8738//8738 8612//8612 8739//8739 -f 8739//8739 8612//8612 8614//8614 -f 8739//8739 8614//8614 8628//8628 -f 8628//8628 8614//8614 8740//8740 -f 8628//8628 8740//8740 8626//8626 -f 8626//8626 8740//8740 8741//8741 -f 8626//8626 8741//8741 8610//8610 -f 8610//8610 8741//8741 8742//8742 -f 8610//8610 8742//8742 8608//8608 -f 8743//8743 8744//8744 8738//8738 -f 8745//8745 8743//8743 8494//8494 -f 8494//8494 8743//8743 8738//8738 -f 8494//8494 8738//8738 8492//8492 -f 8492//8492 8738//8738 8500//8500 -f 8492//8492 8500//8500 8746//8746 -f 8746//8746 8500//8500 8501//8501 -f 8747//8747 8612//8612 8748//8748 -f 8748//8748 8612//8612 8738//8738 -f 8748//8748 8738//8738 8749//8749 -f 8749//8749 8738//8738 8744//8744 -f 8747//8747 8750//8750 8612//8612 -f 8612//8612 8750//8750 8751//8751 -f 8612//8612 8751//8751 8618//8618 -f 8618//8618 8751//8751 8752//8752 -f 8752//8752 8753//8753 8618//8618 -f 8618//8618 8753//8753 8754//8754 -f 8618//8618 8754//8754 8494//8494 -f 8494//8494 8754//8754 8755//8755 -f 8494//8494 8755//8755 8745//8745 -f 8756//8756 8515//8515 8757//8757 -f 8757//8757 8515//8515 8758//8758 -f 8757//8757 8758//8758 8759//8759 -f 8759//8759 8758//8758 8760//8760 -f 8761//8761 8486//8486 8762//8762 -f 8762//8762 8486//8486 8515//8515 -f 8762//8762 8515//8515 8763//8763 -f 8763//8763 8515//8515 8756//8756 -f 8483//8483 8764//8764 8765//8765 -f 8761//8761 8766//8766 8486//8486 -f 8486//8486 8766//8766 8767//8767 -f 8486//8486 8767//8767 8483//8483 -f 8483//8483 8767//8767 8768//8768 -f 8483//8483 8768//8768 8764//8764 -f 8561//8561 8769//8769 8559//8559 -f 8559//8559 8769//8769 8554//8554 -f 8559//8559 8554//8554 8566//8566 -f 8566//8566 8554//8554 8551//8551 -f 8566//8566 8551//8551 8449//8449 -f 8449//8449 8551//8551 8685//8685 -f 8449//8449 8685//8685 8444//8444 -f 8444//8444 8685//8685 8687//8687 -f 8444//8444 8687//8687 8442//8442 -f 8493//8493 8487//8487 8494//8494 -f 8494//8494 8487//8487 8464//8464 -f 8494//8494 8464//8464 8618//8618 -f 8618//8618 8464//8464 8480//8480 -f 8618//8618 8480//8480 8615//8615 -f 8615//8615 8480//8480 8508//8508 -f 8615//8615 8508//8508 8620//8620 -f 8511//8511 8512//8512 8509//8509 -f 8509//8509 8512//8512 8483//8483 -f 8509//8509 8483//8483 8758//8758 -f 8758//8758 8483//8483 8765//8765 -f 8758//8758 8765//8765 8760//8760 -f 8770//8770 8771//8771 8442//8442 -f 8351//8351 8350//8350 8508//8508 -f 8508//8508 8350//8350 8772//8772 -f 8508//8508 8772//8772 8773//8773 -f 8690//8690 8621//8621 8687//8687 -f 8687//8687 8621//8621 8620//8620 -f 8687//8687 8620//8620 8442//8442 -f 8442//8442 8620//8620 8508//8508 -f 8442//8442 8508//8508 8770//8770 -f 8770//8770 8508//8508 8773//8773 -f 8771//8771 8774//8774 8442//8442 -f 8442//8442 8774//8774 8775//8775 -f 8442//8442 8775//8775 8440//8440 -f 8440//8440 8775//8775 8776//8776 -f 8776//8776 8777//8777 8440//8440 -f 8440//8440 8777//8777 8778//8778 -f 8440//8440 8778//8778 8351//8351 -f 8351//8351 8778//8778 8779//8779 -f 8351//8351 8779//8779 8349//8349 -f 8780//8780 8781//8781 8782//8782 -f 8782//8782 8781//8781 8463//8463 -f 8782//8782 8463//8463 8783//8783 -f 8783//8783 8463//8463 8462//8462 -f 8783//8783 8462//8462 8784//8784 -f 8780//8780 8785//8785 8781//8781 -f 8781//8781 8785//8785 8786//8786 -f 8781//8781 8786//8786 8787//8787 -f 8787//8787 8786//8786 8788//8788 -f 8787//8787 8788//8788 8789//8789 -f 8790//8790 8791//8791 8792//8792 -f 8792//8792 8791//8791 8793//8793 -f 8792//8792 8793//8793 8794//8794 -f 8484//8484 8483//8483 8795//8795 -f 8795//8795 8483//8483 8512//8512 -f 8795//8795 8512//8512 8491//8491 -f 8491//8491 8512//8512 8792//8792 -f 8491//8491 8792//8792 8462//8462 -f 8462//8462 8792//8792 8794//8794 -f 8462//8462 8794//8794 8784//8784 -f 8513//8513 8361//8361 8512//8512 -f 8512//8512 8361//8361 8363//8363 -f 8512//8512 8363//8363 8792//8792 -f 8792//8792 8363//8363 8787//8787 -f 8792//8792 8787//8787 8790//8790 -f 8790//8790 8787//8787 8789//8789 -f 8796//8796 8797//8797 8798//8798 -f 8799//8799 8800//8800 8801//8801 -f 8796//8796 8798//8798 8802//8802 -f 8798//8798 8803//8803 8802//8802 -f 8802//8802 8803//8803 8804//8804 -f 8802//8802 8804//8804 8805//8805 -f 8799//8799 8801//8801 8806//8806 -f 8801//8801 8807//8807 8806//8806 -f 8806//8806 8807//8807 8808//8808 -f 8806//8806 8808//8808 8796//8796 -f 8796//8796 8808//8808 8809//8809 -f 8796//8796 8809//8809 8797//8797 -f 8804//8804 8810//8810 8805//8805 -f 8805//8805 8810//8810 8811//8811 -f 8805//8805 8811//8811 8799//8799 -f 8799//8799 8811//8811 8812//8812 -f 8799//8799 8812//8812 8800//8800 -f 8813//8813 8814//8814 8815//8815 -f 8815//8815 8814//8814 8816//8816 -f 8817//8817 8818//8818 8819//8819 -f 8819//8819 8818//8818 8820//8820 -f 8820//8820 8821//8821 8819//8819 -f 8819//8819 8821//8821 8822//8822 -f 8819//8819 8822//8822 8823//8823 -f 8822//8822 8824//8824 8823//8823 -f 8823//8823 8824//8824 8825//8825 -f 8823//8823 8825//8825 8813//8813 -f 8813//8813 8825//8825 8826//8826 -f 8813//8813 8826//8826 8814//8814 -f 8816//8816 8827//8827 8815//8815 -f 8815//8815 8827//8827 8828//8828 -f 8815//8815 8828//8828 8817//8817 -f 8817//8817 8828//8828 8829//8829 -f 8817//8817 8829//8829 8818//8818 -f 8830//8830 8831//8831 8832//8832 -f 8832//8832 8831//8831 8833//8833 -f 8834//8834 8835//8835 8830//8830 -f 8830//8830 8835//8835 8836//8836 -f 8830//8830 8836//8836 8831//8831 -f 8833//8833 8837//8837 8832//8832 -f 8832//8832 8837//8837 8838//8838 -f 8832//8832 8838//8838 8839//8839 -f 8840//8840 8841//8841 8842//8842 -f 8842//8842 8841//8841 8839//8839 -f 8842//8842 8839//8839 8843//8843 -f 8843//8843 8839//8839 8838//8838 -f 8840//8840 8844//8844 8841//8841 -f 8841//8841 8844//8844 8845//8845 -f 8841//8841 8845//8845 8834//8834 -f 8834//8834 8845//8845 8846//8846 -f 8834//8834 8846//8846 8835//8835 -f 7178//7178 7177//7177 8847//8847 -f 8848//8848 8849//8849 8850//8850 -f 8851//8851 8852//8852 8853//8853 -f 8854//8854 8855//8855 8856//8856 -f 8856//8856 8855//8855 8857//8857 -f 8857//8857 8858//8858 8856//8856 -f 8856//8856 8858//8858 8859//8859 -f 8856//8856 8859//8859 8860//8860 -f 8860//8860 8859//8859 8861//8861 -f 8860//8860 8861//8861 8862//8862 -f 8863//8863 8864//8864 8865//8865 -f 8866//8866 8867//8867 8868//8868 -f 8869//8869 8870//8870 8861//8861 -f 8861//8861 8870//8870 8866//8866 -f 8868//8868 8871//8871 8866//8866 -f 8866//8866 8871//8871 8863//8863 -f 8866//8866 8863//8863 8861//8861 -f 8861//8861 8863//8863 8865//8865 -f 8861//8861 8865//8865 8862//8862 -f 8872//8872 8873//8873 8874//8874 -f 8875//8875 8876//8876 8877//8877 -f 8878//8878 8872//8872 8869//8869 -f 8853//8853 8870//8870 8851//8851 -f 8851//8851 8870//8870 8869//8869 -f 8851//8851 8869//8869 8879//8879 -f 8879//8879 8869//8869 8872//8872 -f 8879//8879 8872//8872 8880//8880 -f 8880//8880 8872//8872 8874//8874 -f 8876//8876 8875//8875 8881//8881 -f 8882//8882 8883//8883 8884//8884 -f 8885//8885 8886//8886 8887//8887 -f 8884//8884 8888//8888 8882//8882 -f 8882//8882 8888//8888 8887//8887 -f 8882//8882 8887//8887 8889//8889 -f 8889//8889 8887//8887 8890//8890 -f 8891//8891 8885//8885 8892//8892 -f 8892//8892 8885//8885 8887//8887 -f 8892//8892 8887//8887 8893//8893 -f 8893//8893 8887//8887 8888//8888 -f 8894//8894 8895//8895 8896//8896 -f 8896//8896 8895//8895 8897//8897 -f 8896//8896 8897//8897 8898//8898 -f 8898//8898 8897//8897 8899//8899 -f 8900//8900 8901//8901 8902//8902 -f 8902//8902 8901//8901 8903//8903 -f 8904//8904 8905//8905 8906//8906 -f 8906//8906 8905//8905 8907//8907 -f 8906//8906 8907//8907 8908//8908 -f 8908//8908 8907//8907 8909//8909 -f 8908//8908 8909//8909 8910//8910 -f 8910//8910 8909//8909 8911//8911 -f 8910//8910 8911//8911 8912//8912 -f 8912//8912 8911//8911 8913//8913 -f 8914//8914 8915//8915 8916//8916 -f 8916//8916 8915//8915 8917//8917 -f 8916//8916 8917//8917 8918//8918 -f 8850//8850 8919//8919 8848//8848 -f 8848//8848 8919//8919 8920//8920 -f 8848//8848 8920//8920 8921//8921 -f 8922//8922 8923//8923 8924//8924 -f 8924//8924 8923//8923 8925//8925 -f 8924//8924 8925//8925 8926//8926 -f 8927//8927 8928//8928 8920//8920 -f 8920//8920 8928//8928 8929//8929 -f 8929//8929 8930//8930 8915//8915 -f 8915//8915 8930//8930 8931//8931 -f 8932//8932 8924//8924 8933//8933 -f 8933//8933 8924//8924 8926//8926 -f 8933//8933 8926//8926 8934//8934 -f 8934//8934 8926//8926 8935//8935 -f 8934//8934 8935//8935 8919//8919 -f 8919//8919 8935//8935 8936//8936 -f 8919//8919 8936//8936 8920//8920 -f 8920//8920 8936//8936 8937//8937 -f 8920//8920 8937//8937 8927//8927 -f 8924//8924 8938//8938 8922//8922 -f 8922//8922 8938//8938 8939//8939 -f 8922//8922 8939//8939 8931//8931 -f 8931//8931 8939//8939 8940//8940 -f 8931//8931 8940//8940 8915//8915 -f 8915//8915 8940//8940 8941//8941 -f 8915//8915 8941//8941 8917//8917 -f 8942//8942 8943//8943 8920//8920 -f 8944//8944 8945//8945 8946//8946 -f 8946//8946 8945//8945 8947//8947 -f 8947//8947 8921//8921 8946//8946 -f 8946//8946 8921//8921 8920//8920 -f 8946//8946 8920//8920 8948//8948 -f 8948//8948 8920//8920 8943//8943 -f 8948//8948 8943//8943 8949//8949 -f 8949//8949 8943//8943 8950//8950 -f 8951//8951 8952//8952 8953//8953 -f 8953//8953 8952//8952 8954//8954 -f 8955//8955 8956//8956 8954//8954 -f 8957//8957 8958//8958 8955//8955 -f 8955//8955 8958//8958 8959//8959 -f 8960//8960 8961//8961 8962//8962 -f 8962//8962 8961//8961 8963//8963 -f 8962//8962 8963//8963 8942//8942 -f 8964//8964 8965//8965 8956//8956 -f 8956//8956 8965//8965 8966//8966 -f 8956//8956 8966//8966 8954//8954 -f 8967//8967 8968//8968 8957//8957 -f 8969//8969 8958//8958 8970//8970 -f 8970//8970 8958//8958 8957//8957 -f 8970//8970 8957//8957 8971//8971 -f 8971//8971 8957//8957 8968//8968 -f 8971//8971 8968//8968 8972//8972 -f 8972//8972 8968//8968 8973//8973 -f 8974//8974 8975//8975 8976//8976 -f 7203//7203 8977//8977 7202//7202 -f 7202//7202 8977//8977 8978//8978 -f 7202//7202 8978//8978 7188//7188 -f 8978//8978 8979//8979 7188//7188 -f 7188//7188 8979//8979 8980//8980 -f 7188//7188 8980//8980 7186//7186 -f 7186//7186 8980//8980 8981//8981 -f 7186//7186 8981//8981 7184//7184 -f 7184//7184 8981//8981 8982//8982 -f 7184//7184 8982//8982 8983//8983 -f 8983//8983 8982//8982 8984//8984 -f 8985//8985 8986//8986 8987//8987 -f 8987//8987 8986//8986 8988//8988 -f 8987//8987 8988//8988 8989//8989 -f 8989//8989 8988//8988 8990//8990 -f 8989//8989 8990//8990 7203//7203 -f 7203//7203 8990//8990 8991//8991 -f 7203//7203 8991//8991 8977//8977 -f 8992//8992 8993//8993 8994//8994 -f 8994//8994 8993//8993 8995//8995 -f 8994//8994 8995//8995 8996//8996 -f 8997//8997 8998//8998 8999//8999 -f 8999//8999 8998//8998 9000//9000 -f 8999//8999 9000//9000 7182//7182 -f 7182//7182 9000//9000 9001//9001 -f 9002//9002 7177//7177 9001//9001 -f 9001//9001 7177//7177 7206//7206 -f 9001//9001 7206//7206 7182//7182 -f 9002//9002 9003//9003 7177//7177 -f 7177//7177 9003//9003 9004//9004 -f 7177//7177 9004//9004 8847//8847 -f 8847//8847 9004//9004 9005//9005 -f 8847//8847 9005//9005 9006//9006 -f 9007//9007 7154//7154 8847//8847 -f 8847//8847 7154//7154 7180//7180 -f 8847//8847 7180//7180 7178//7178 -f 8858//8858 9008//9008 8859//8859 -f 8859//8859 9008//9008 9009//9009 -f 8859//8859 9009//9009 9007//9007 -f 9007//9007 9009//9009 9010//9010 -f 9007//9007 9010//9010 7154//7154 -f 9011//9011 9012//9012 9013//9013 -f 9013//9013 9012//9012 9014//9014 -f 9013//9013 9014//9014 9015//9015 -f 9015//9015 9014//9014 9016//9016 -f 9015//9015 9016//9016 9017//9017 -f 9017//9017 9016//9016 9018//9018 -f 9017//9017 9018//9018 9019//9019 -f 9020//9020 9021//9021 9022//9022 -f 9022//9022 9021//9021 9023//9023 -f 9022//9022 9023//9023 9024//9024 -f 9024//9024 9023//9023 9025//9025 -f 9024//9024 9025//9025 9026//9026 -f 9027//9027 9028//9028 9029//9029 -f 9029//9029 9028//9028 8869//8869 -f 9029//9029 8869//8869 9030//9030 -f 9030//9030 8869//8869 8861//8861 -f 9030//9030 8861//8861 9031//9031 -f 9032//9032 9033//9033 9020//9020 -f 9020//9020 9033//9033 9034//9034 -f 9020//9020 9034//9034 9035//9035 -f 9036//9036 9037//9037 9038//9038 -f 9038//9038 9037//9037 9039//9039 -f 9038//9038 9039//9039 9040//9040 -f 9040//9040 9039//9039 9041//9041 -f 9040//9040 9041//9041 9035//9035 -f 9035//9035 9041//9041 9012//9012 -f 9035//9035 9012//9012 9020//9020 -f 9020//9020 9012//9012 9011//9011 -f 9020//9020 9011//9011 9021//9021 -f 9042//9042 9043//9043 9044//9044 -f 9044//9044 9043//9043 9045//9045 -f 9044//9044 9045//9045 9027//9027 -f 9046//9046 9047//9047 9048//9048 -f 9048//9048 9047//9047 8897//8897 -f 9048//9048 8897//8897 8891//8891 -f 8891//8891 8897//8897 8895//8895 -f 8891//8891 8895//8895 8885//8885 -f 8875//8875 9049//9049 9050//9050 -f 9051//9051 9052//9052 8883//8883 -f 8883//8883 9052//9052 8881//8881 -f 8883//8883 8881//8881 8884//8884 -f 8884//8884 8881//8881 8875//8875 -f 8884//8884 8875//8875 9053//9053 -f 9053//9053 8875//8875 9050//9050 -f 9046//9046 9054//9054 9047//9047 -f 9047//9047 9054//9054 9055//9055 -f 9047//9047 9055//9055 9049//9049 -f 9049//9049 9055//9055 9056//9056 -f 9049//9049 9056//9056 9050//9050 -f 9057//9057 9058//9058 9059//9059 -f 9059//9059 9058//9058 9060//9060 -f 9059//9059 9060//9060 9061//9061 -f 9061//9061 9060//9060 9062//9062 -f 9061//9061 9062//9062 9063//9063 -f 9063//9063 9062//9062 9064//9064 -f 9063//9063 9064//9064 9065//9065 -f 9066//9066 9067//9067 9068//9068 -f 9068//9068 9067//9067 9069//9069 -f 9068//9068 9069//9069 9070//9070 -f 9070//9070 9069//9069 9071//9071 -f 9070//9070 9071//9071 9072//9072 -f 9072//9072 9071//9071 9073//9073 -f 9072//9072 9073//9073 9074//9074 -f 9075//9075 9076//9076 9077//9077 -f 9076//9076 9078//9078 9077//9077 -f 9077//9077 9078//9078 9079//9079 -f 9077//9077 9079//9079 9072//9072 -f 9072//9072 9079//9079 9080//9080 -f 9081//9081 9082//9082 9083//9083 -f 9083//9083 9082//9082 9084//9084 -f 9083//9083 9084//9084 9085//9085 -f 9085//9085 9084//9084 9086//9086 -f 9085//9085 9086//9086 9087//9087 -f 9088//9088 9089//9089 9090//9090 -f 9090//9090 9089//9089 9091//9091 -f 9090//9090 9091//9091 9092//9092 -f 9093//9093 9037//9037 9094//9094 -f 9094//9094 9037//9037 9036//9036 -f 9094//9094 9036//9036 9031//9031 -f 9088//9088 9095//9095 9089//9089 -f 9089//9089 9095//9095 9096//9096 -f 9089//9089 9096//9096 9094//9094 -f 9094//9094 9096//9096 9097//9097 -f 9094//9094 9097//9097 9093//9093 -f 9093//9093 9098//9098 9037//9037 -f 9037//9037 9098//9098 9099//9099 -f 9037//9037 9099//9099 9039//9039 -f 9039//9039 9099//9099 9100//9100 -f 9092//9092 9091//9091 9101//9101 -f 9101//9101 9091//9091 9102//9102 -f 9101//9101 9102//9102 9103//9103 -f 9104//9104 9105//9105 9028//9028 -f 9106//9106 9107//9107 9049//9049 -f 9049//9049 9107//9107 9108//9108 -f 9049//9049 9108//9108 9109//9109 -f 9027//9027 9045//9045 9028//9028 -f 9028//9028 9045//9045 9110//9110 -f 9028//9028 9110//9110 9104//9104 -f 9108//9108 9111//9111 9109//9109 -f 9109//9109 9111//9111 9112//9112 -f 9109//9109 9112//9112 9113//9113 -f 9112//9112 9114//9114 9113//9113 -f 9113//9113 9114//9114 9115//9115 -f 9113//9113 9115//9115 9043//9043 -f 9043//9043 9115//9115 9116//9116 -f 9043//9043 9116//9116 9045//9045 -f 9045//9045 9116//9116 9117//9117 -f 9045//9045 9117//9117 9110//9110 -f 9118//9118 9119//9119 9068//9068 -f 9068//9068 9119//9119 9120//9120 -f 9068//9068 9120//9120 9121//9121 -f 9121//9121 9120//9120 9122//9122 -f 9121//9121 9122//9122 9123//9123 -f 9124//9124 9125//9125 9126//9126 -f 9125//9125 9127//9127 9126//9126 -f 9126//9126 9127//9127 9128//9128 -f 9126//9126 9128//9128 9129//9129 -f 9129//9129 9128//9128 9130//9130 -f 9131//9131 9132//9132 8920//8920 -f 9133//9133 9134//9134 8953//8953 -f 9134//9134 9135//9135 8953//8953 -f 8953//8953 9135//9135 9026//9026 -f 8953//8953 9026//9026 8951//8951 -f 8951//8951 9026//9026 9025//9025 -f 9131//9131 8920//8920 9136//9136 -f 9136//9136 8920//8920 9137//9137 -f 9136//9136 9137//9137 9138//9138 -f 8966//8966 8962//8962 8954//8954 -f 8954//8954 8962//8962 8942//8942 -f 8954//8954 8942//8942 8953//8953 -f 8953//8953 8942//8942 8920//8920 -f 8953//8953 8920//8920 9133//9133 -f 9133//9133 8920//8920 9132//9132 -f 9135//9135 9139//9139 9026//9026 -f 9026//9026 9139//9139 9140//9140 -f 9026//9026 9140//9140 9024//9024 -f 9024//9024 9140//9140 9141//9141 -f 9138//9138 9137//9137 9142//9142 -f 9142//9142 9137//9137 9143//9143 -f 9142//9142 9143//9143 9144//9144 -f 9145//9145 9146//9146 8957//8957 -f 8957//8957 9146//9146 9147//9147 -f 9148//9148 9145//9145 9018//9018 -f 9018//9018 9145//9145 8957//8957 -f 9018//9018 8957//8957 9019//9019 -f 9019//9019 8957//8957 8955//8955 -f 9019//9019 8955//8955 9149//9149 -f 9149//9149 8955//8955 8954//8954 -f 9150//9150 9151//9151 8976//8976 -f 8976//8976 9151//9151 9152//9152 -f 8976//8976 9152//9152 9153//9153 -f 9147//9147 9150//9150 8957//8957 -f 8957//8957 9150//9150 8976//8976 -f 8957//8957 8976//8976 8967//8967 -f 8967//8967 8976//8976 8975//8975 -f 8967//8967 8975//8975 9154//9154 -f 9148//9148 9018//9018 9155//9155 -f 9155//9155 9018//9018 9016//9016 -f 9155//9155 9016//9016 9156//9156 -f 9152//9152 9157//9157 9153//9153 -f 9153//9153 9157//9157 9158//9158 -f 9153//9153 9158//9158 9159//9159 -f 9159//9159 9158//9158 9160//9160 -f 8984//8984 8985//8985 8983//8983 -f 8983//8983 8985//8985 8987//8987 -f 8983//8983 8987//8987 9126//9126 -f 9126//9126 8987//8987 9161//9161 -f 9126//9126 9161//9161 9124//9124 -f 9124//9124 9161//9161 9162//9162 -f 7203//7203 7196//7196 8989//8989 -f 8989//8989 7196//7196 9163//9163 -f 8989//8989 9163//9163 8987//8987 -f 8987//8987 9163//9163 9164//9164 -f 8987//8987 9164//9164 9161//9161 -f 9161//9161 9164//9164 9121//9121 -f 9161//9161 9121//9121 9162//9162 -f 9162//9162 9121//9121 9123//9123 -f 7196//7196 8974//8974 9163//9163 -f 9163//9163 8974//8974 8976//8976 -f 9163//9163 8976//8976 9164//9164 -f 9164//9164 8976//8976 9153//9153 -f 9164//9164 9153//9153 9121//9121 -f 9121//9121 9153//9153 9159//9159 -f 9121//9121 9159//9159 9068//9068 -f 9068//9068 9159//9159 9063//9063 -f 9068//9068 9063//9063 9066//9066 -f 9066//9066 9063//9063 9065//9065 -f 9130//9130 9165//9165 9129//9129 -f 9129//9129 9165//9165 9166//9166 -f 9129//9129 9166//9166 9167//9167 -f 9167//9167 9166//9166 9168//9168 -f 9167//9167 9168//9168 9083//9083 -f 9083//9083 9168//9168 9169//9169 -f 9083//9083 9169//9169 9081//9081 -f 9081//9081 9169//9169 9170//9170 -f 9165//9165 9118//9118 9166//9166 -f 9166//9166 9118//9118 9068//9068 -f 9166//9166 9068//9068 9168//9168 -f 9168//9168 9068//9068 9070//9070 -f 9168//9168 9070//9070 9169//9169 -f 9169//9169 9070//9070 9072//9072 -f 9169//9169 9072//9072 9170//9170 -f 9170//9170 9072//9072 9080//9080 -f 9141//9141 9144//9144 9024//9024 -f 9024//9024 9144//9144 9143//9143 -f 9024//9024 9143//9143 9022//9022 -f 9022//9022 9143//9143 9171//9171 -f 9022//9022 9171//9171 9020//9020 -f 9020//9020 9171//9171 9172//9172 -f 9020//9020 9172//9172 9032//9032 -f 9032//9032 9172//9172 9173//9173 -f 8929//8929 8915//8915 8920//8920 -f 8920//8920 8915//8915 8914//8914 -f 8920//8920 8914//8914 9137//9137 -f 9137//9137 8914//8914 9174//9174 -f 9137//9137 9174//9174 9143//9143 -f 9143//9143 9174//9174 8911//8911 -f 9143//9143 8911//8911 9171//9171 -f 9171//9171 8911//8911 8909//8909 -f 9171//9171 8909//8909 9172//9172 -f 9172//9172 8909//8909 8907//8907 -f 9172//9172 8907//8907 9173//9173 -f 9173//9173 8907//8907 8905//8905 -f 9173//9173 8905//8905 8903//8903 -f 8903//8903 8905//8905 8904//8904 -f 8903//8903 8904//8904 8902//8902 -f 9160//9160 9156//9156 9159//9159 -f 9159//9159 9156//9156 9016//9016 -f 9159//9159 9016//9016 9063//9063 -f 9063//9063 9016//9016 9014//9014 -f 9063//9063 9014//9014 9061//9061 -f 9061//9061 9014//9014 9012//9012 -f 9061//9061 9012//9012 9059//9059 -f 9059//9059 9012//9012 9041//9041 -f 9059//9059 9041//9041 9102//9102 -f 9102//9102 9041//9041 9039//9039 -f 9102//9102 9039//9039 9103//9103 -f 9103//9103 9039//9039 9100//9100 -f 8899//8899 8897//8897 9175//9175 -f 9175//9175 8897//8897 9047//9047 -f 9175//9175 9047//9047 9176//9176 -f 9176//9176 9047//9047 9049//9049 -f 9176//9176 9049//9049 9177//9177 -f 9177//9177 9049//9049 9109//9109 -f 9177//9177 9109//9109 8903//8903 -f 8903//8903 9109//9109 9113//9113 -f 8903//8903 9113//9113 9173//9173 -f 9173//9173 9113//9113 9043//9043 -f 9173//9173 9043//9043 9032//9032 -f 9032//9032 9043//9043 9042//9042 -f 9032//9032 9042//9042 9033//9033 -f 9087//9087 9178//9178 9085//9085 -f 9085//9085 9178//9178 9179//9179 -f 9085//9085 9179//9179 8999//8999 -f 8999//8999 9179//9179 8994//8994 -f 8999//8999 8994//8994 8997//8997 -f 8997//8997 8994//8994 8996//8996 -f 9178//9178 9075//9075 9179//9179 -f 9179//9179 9075//9075 9077//9077 -f 9179//9179 9077//9077 8994//8994 -f 8994//8994 9077//9077 9180//9180 -f 8994//8994 9180//9180 8992//8992 -f 8992//8992 9180//9180 9181//9181 -f 9074//9074 9057//9057 9072//9072 -f 9072//9072 9057//9057 9059//9059 -f 9072//9072 9059//9059 9077//9077 -f 9077//9077 9059//9059 9102//9102 -f 9077//9077 9102//9102 9180//9180 -f 9180//9180 9102//9102 9091//9091 -f 9180//9180 9091//9091 9181//9181 -f 9181//9181 9091//9091 9089//9089 -f 9031//9031 8861//8861 9094//9094 -f 9094//9094 8861//8861 8859//8859 -f 9094//9094 8859//8859 9089//9089 -f 9089//9089 8859//8859 9007//9007 -f 9089//9089 9007//9007 9181//9181 -f 9181//9181 9007//9007 8847//8847 -f 9181//9181 8847//8847 8992//8992 -f 8992//8992 8847//8847 9006//9006 -f 8992//8992 9006//9006 8993//8993 -f 9105//9105 9106//9106 9028//9028 -f 9028//9028 9106//9106 9049//9049 -f 9028//9028 9049//9049 8869//8869 -f 8869//8869 9049//9049 8875//8875 -f 8869//8869 8875//8875 8878//8878 -f 8878//8878 8875//8875 8877//8877 -f 8878//8878 8877//8877 9182//9182 -f 9182//9182 8877//8877 9183//9183 -f 9184//9184 9185//9185 9186//9186 -f 9186//9186 9185//9185 9187//9187 -f 9186//9186 9187//9187 9188//9188 -f 9188//9188 9187//9187 9189//9189 -f 9188//9188 9189//9189 9190//9190 -f 9191//9191 9192//9192 9193//9193 -f 9193//9193 9192//9192 9194//9194 -f 9193//9193 9194//9194 9195//9195 -f 9195//9195 9194//9194 9196//9196 -f 9195//9195 9196//9196 9197//9197 -f 9198//9198 9199//9199 9200//9200 -f 9200//9200 9199//9199 9201//9201 -f 9200//9200 9201//9201 9202//9202 -f 9202//9202 9201//9201 9203//9203 -f 9202//9202 9203//9203 9204//9204 -f 9205//9205 9206//9206 8802//8802 -f 8802//8802 9206//9206 9207//9207 -f 8802//8802 9207//9207 8796//8796 -f 8796//8796 9207//9207 9208//9208 -f 8796//8796 9208//9208 9209//9209 -f 9209//9209 9208//9208 9210//9210 -f 9211//9211 9212//9212 8823//8823 -f 8823//8823 9212//9212 9213//9213 -f 8823//8823 9213//9213 8819//8819 -f 8819//8819 9213//9213 9214//9214 -f 8819//8819 9214//9214 9215//9215 -f 9215//9215 9214//9214 9216//9216 -f 9217//9217 9218//9218 8839//8839 -f 8839//8839 9218//9218 9219//9219 -f 8839//8839 9219//9219 8832//8832 -f 8832//8832 9219//9219 9220//9220 -f 8832//8832 9220//9220 9221//9221 -f 9221//9221 9220//9220 9222//9222 -f 9223//9223 9224//9224 9225//9225 -f 9225//9225 9224//9224 9226//9226 -f 9227//9227 9228//9228 9229//9229 -f 9230//9230 9231//9231 9232//9232 -f 9232//9232 9231//9231 9227//9227 -f 9232//9232 9227//9227 9233//9233 -f 9233//9233 9227//9227 9229//9229 -f 9230//9230 9234//9234 9231//9231 -f 9231//9231 9234//9234 9235//9235 -f 9231//9231 9235//9235 9223//9223 -f 9223//9223 9235//9235 9236//9236 -f 9223//9223 9236//9236 9224//9224 -f 9226//9226 9237//9237 9225//9225 -f 9225//9225 9237//9237 9238//9238 -f 9225//9225 9238//9238 9228//9228 -f 9228//9228 9238//9238 9239//9239 -f 9228//9228 9239//9239 9229//9229 -f 9240//9240 9241//9241 9242//9242 -f 9242//9242 9241//9241 9243//9243 -f 9244//9244 9245//9245 9246//9246 -f 9246//9246 9245//9245 9247//9247 -f 9246//9246 9247//9247 9248//9248 -f 9248//9248 9247//9247 9249//9249 -f 9248//9248 9249//9249 9250//9250 -f 9242//9242 9251//9251 9240//9240 -f 9240//9240 9251//9251 9252//9252 -f 9240//9240 9252//9252 9249//9249 -f 9249//9249 9252//9252 9253//9253 -f 9249//9249 9253//9253 9250//9250 -f 9244//9244 9254//9254 9245//9245 -f 9245//9245 9254//9254 9255//9255 -f 9245//9245 9255//9255 9241//9241 -f 9241//9241 9255//9255 9256//9256 -f 9241//9241 9256//9256 9243//9243 -f 9257//9257 9258//9258 9259//9259 -f 9259//9259 9258//9258 9260//9260 -f 9259//9259 9260//9260 9261//9261 -f 9261//9261 9260//9260 9262//9262 -f 9261//9261 9262//9262 9263//9263 -f 9264//9264 9265//9265 9228//9228 -f 9228//9228 9265//9265 9266//9266 -f 9228//9228 9266//9266 9225//9225 -f 9225//9225 9266//9266 9267//9267 -f 9225//9225 9267//9267 9268//9268 -f 9268//9268 9267//9267 9269//9269 -f 9270//9270 9271//9271 9272//9272 -f 9273//9273 9274//9274 9275//9275 -f 9270//9270 9272//9272 9275//9275 -f 9275//9275 9272//9272 9276//9276 -f 9275//9275 9276//9276 9273//9273 -f 9277//9277 9278//9278 9240//9240 -f 9240//9240 9278//9278 9279//9279 -f 9240//9240 9279//9279 9241//9241 -f 9241//9241 9279//9279 9280//9280 -f 9241//9241 9280//9280 9281//9281 -f 9281//9281 9280//9280 9282//9282 -f 9283//9283 8975//8975 9284//9284 -f 9284//9284 8975//8975 8974//8974 -f 9284//9284 8974//8974 7196//7196 -f 7184//7184 8983//8983 9285//9285 -f 9285//9285 8983//8983 9126//9126 -f 9126//9126 9129//9129 9285//9285 -f 9285//9285 9129//9129 9167//9167 -f 9285//9285 9167//9167 9286//9286 -f 9286//9286 9167//9167 9083//9083 -f 9083//9083 9085//9085 9286//9286 -f 9286//9286 9085//9085 8999//8999 -f 9286//9286 8999//8999 7182//7182 -f 9009//9009 9287//9287 9010//9010 -f 9010//9010 9287//9287 9288//9288 -f 9010//9010 9288//9288 7154//7154 -f 9009//9009 9008//9008 9287//9287 -f 9287//9287 9008//9008 9289//9289 -f 9287//9287 9289//9289 9290//9290 -f 9290//9290 9289//9289 8540//8540 -f 9290//9290 8540//8540 9291//9291 -f 9291//9291 8540//8540 8356//8356 -f 8857//8857 9292//9292 8858//8858 -f 8858//8858 9292//9292 9289//9289 -f 8858//8858 9289//9289 9008//9008 -f 9208//9208 8701//8701 9292//9292 -f 9292//9292 8701//8701 8359//8359 -f 9292//9292 8359//8359 8358//8358 -f 8857//8857 8855//8855 9292//9292 -f 9292//9292 8855//8855 9210//9210 -f 9292//9292 9210//9210 9208//9208 -f 9293//9293 8386//8386 8388//8388 -f 8864//8864 8863//8863 9206//9206 -f 9206//9206 8863//8863 9293//9293 -f 9206//9206 9293//9293 9207//9207 -f 9207//9207 9293//9293 8388//8388 -f 9207//9207 8388//8388 8698//8698 -f 9293//9293 8863//8863 9294//9294 -f 9294//9294 8863//8863 8871//8871 -f 9214//9214 8539//8539 9294//9294 -f 9294//9294 8539//8539 8538//8538 -f 9294//9294 8538//8538 8536//8536 -f 8871//8871 8868//8868 9294//9294 -f 9294//9294 8868//8868 9216//9216 -f 9294//9294 9216//9216 9214//9214 -f 8852//8852 8851//8851 9295//9295 -f 9295//9295 8531//8531 8530//8530 -f 8852//8852 9295//9295 9212//9212 -f 9212//9212 9295//9295 9213//9213 -f 9213//9213 9295//9295 8530//8530 -f 9213//9213 8530//8530 8532//8532 -f 8880//8880 9296//9296 8879//8879 -f 8879//8879 9296//9296 9295//9295 -f 8879//8879 9295//9295 8851//8851 -f 9220//9220 8704//8704 9296//9296 -f 9296//9296 8704//8704 8412//8412 -f 9296//9296 8412//8412 8411//8411 -f 8880//8880 8874//8874 9296//9296 -f 9296//9296 8874//8874 9222//9222 -f 9296//9296 9222//9222 9220//9220 -f 9297//9297 8402//8402 8408//8408 -f 9183//9183 8877//8877 9218//9218 -f 9218//9218 8877//8877 9297//9297 -f 9218//9218 9297//9297 9219//9219 -f 9219//9219 9297//9297 8408//8408 -f 9219//9219 8408//8408 8702//8702 -f 8881//8881 9298//9298 8876//8876 -f 8876//8876 9298//9298 9297//9297 -f 8876//8876 9297//9297 8877//8877 -f 9267//9267 8708//8708 9298//9298 -f 9298//9298 8708//8708 8568//8568 -f 9298//9298 8568//8568 8567//8567 -f 8881//8881 9052//9052 9298//9298 -f 9298//9298 9052//9052 9269//9269 -f 9298//9298 9269//9269 9267//9267 -f 9299//9299 8525//8525 8524//8524 -f 8890//8890 8887//8887 9265//9265 -f 9265//9265 8887//8887 9299//9299 -f 9265//9265 9299//9299 9266//9266 -f 9266//9266 9299//9299 8524//8524 -f 9266//9266 8524//8524 8705//8705 -f 9299//9299 8887//8887 9300//9300 -f 9300//9300 8887//8887 8886//8886 -f 9300//9300 8886//8886 8528//8528 -f 8528//8528 8886//8886 8885//8885 -f 8894//8894 9301//9301 8895//8895 -f 8895//8895 9301//9301 8528//8528 -f 8895//8895 8528//8528 8885//8885 -f 9301//9301 8894//8894 9302//9302 -f 9302//9302 8894//8894 8896//8896 -f 9302//9302 8896//8896 8898//8898 -f 8526//8526 8527//8527 9280//9280 -f 9280//9280 8527//8527 9302//9302 -f 9280//9280 9302//9302 9282//9282 -f 9282//9282 9302//9302 8898//8898 -f 9303//9303 8521//8521 8520//8520 -f 8900//8900 8902//8902 9278//9278 -f 9278//9278 8902//8902 9303//9303 -f 9278//9278 9303//9303 9279//9279 -f 9279//9279 9303//9303 8520//8520 -f 8902//8902 8904//8904 9303//9303 -f 9303//9303 8904//8904 8906//8906 -f 9303//9303 8906//8906 9304//9304 -f 9304//9304 8906//8906 8908//8908 -f 9304//9304 8908//8908 8910//8910 -f 9304//9304 8910//8910 8912//8912 -f 8514//8514 8516//8516 9305//9305 -f 9305//9305 8516//8516 9304//9304 -f 9305//9305 9304//9304 9306//9306 -f 9306//9306 9304//9304 8912//8912 -f 9307//9307 9308//9308 9309//9309 -f 9309//9309 9308//9308 9310//9310 -f 9309//9309 9310//9310 9311//9311 -f 9311//9311 9310//9310 9305//9305 -f 9311//9311 9305//9305 9312//9312 -f 9312//9312 9305//9305 9306//9306 -f 9313//9313 8511//8511 8510//8510 -f 8918//8918 8917//8917 9308//9308 -f 9308//9308 8917//8917 9313//9313 -f 9308//9308 9313//9313 9310//9310 -f 9310//9310 9313//9313 8510//8510 -f 9313//9313 8917//8917 9314//9314 -f 9314//9314 8917//8917 8941//8941 -f 9314//9314 8941//8941 8513//8513 -f 8513//8513 8941//8941 8940//8940 -f 8513//8513 8940//8940 8939//8939 -f 8513//8513 8939//8939 9315//9315 -f 9315//9315 8939//8939 8938//8938 -f 9315//9315 8938//8938 9316//9316 -f 9316//9316 8938//8938 8924//8924 -f 9316//9316 8924//8924 8932//8932 -f 8362//8362 8361//8361 9317//9317 -f 9317//9317 8361//8361 9316//9316 -f 9317//9317 9316//9316 9318//9318 -f 9318//9318 9316//9316 8932//8932 -f 9319//9319 9320//9320 9321//9321 -f 9321//9321 9320//9320 9322//9322 -f 9321//9321 9322//9322 9323//9323 -f 9323//9323 9322//9322 9317//9317 -f 9323//9323 9317//9317 9324//9324 -f 9324//9324 9317//9317 9318//9318 -f 9325//9325 8463//8463 8781//8781 -f 8849//8849 8848//8848 9320//9320 -f 9320//9320 8848//8848 9325//9325 -f 9320//9320 9325//9325 9322//9322 -f 9322//9322 9325//9325 8781//8781 -f 8947//8947 9326//9326 8921//8921 -f 8921//8921 9326//9326 9325//9325 -f 8921//8921 9325//9325 8848//8848 -f 9326//9326 8947//8947 8945//8945 -f 8476//8476 8465//8465 9327//9327 -f 9327//9327 8465//8465 9326//9326 -f 9327//9327 9326//9326 9328//9328 -f 9328//9328 9326//9326 8945//8945 -f 9329//9329 9330//9330 9331//9331 -f 9331//9331 9330//9330 9332//9332 -f 9331//9331 9332//9332 9333//9333 -f 9333//9333 9332//9332 9327//9327 -f 9333//9333 9327//9327 9334//9334 -f 9334//9334 9327//9327 9328//9328 -f 9335//9335 8470//8470 8468//8468 -f 8950//8950 8943//8943 9330//9330 -f 9330//9330 8943//8943 9335//9335 -f 9330//9330 9335//9335 9332//9332 -f 9332//9332 9335//9335 8468//8468 -f 8963//8963 9336//9336 8942//8942 -f 8942//8942 9336//9336 9335//9335 -f 8942//8942 9335//9335 8943//8943 -f 9336//9336 8963//8963 8961//8961 -f 8506//8506 8507//8507 9337//9337 -f 9337//9337 8507//8507 9336//9336 -f 9337//9337 9336//9336 9338//9338 -f 9338//9338 9336//9336 8961//8961 -f 9339//9339 9340//9340 9341//9341 -f 9341//9341 9340//9340 9342//9342 -f 9341//9341 9342//9342 9343//9343 -f 9343//9343 9342//9342 9337//9337 -f 9343//9343 9337//9337 9344//9344 -f 9344//9344 9337//9337 9338//9338 -f 8443//8443 8441//8441 9345//9345 -f 9345//9345 8441//8441 9342//9342 -f 9342//9342 9340//9340 9345//9345 -f 9345//9345 9340//9340 8964//8964 -f 9345//9345 8964//8964 8956//8956 -f 9345//9345 8956//8956 9346//9346 -f 9346//9346 8956//8956 8955//8955 -f 9346//9346 8955//8955 8959//8959 -f 8459//8459 8445//8445 9347//9347 -f 9347//9347 8445//8445 9346//9346 -f 9347//9347 9346//9346 9348//9348 -f 9348//9348 9346//9346 8959//8959 -f 9349//9349 9350//9350 9351//9351 -f 9351//9351 9350//9350 9352//9352 -f 9351//9351 9352//9352 9353//9353 -f 9353//9353 9352//9352 9347//9347 -f 9353//9353 9347//9347 9354//9354 -f 9354//9354 9347//9347 9348//9348 -f 9355//9355 8563//8563 8562//8562 -f 8973//8973 8968//8968 9350//9350 -f 9350//9350 8968//8968 9355//9355 -f 9350//9350 9355//9355 9352//9352 -f 9352//9352 9355//9355 8562//8562 -f 9154//9154 9356//9356 8967//8967 -f 8967//8967 9356//9356 9355//9355 -f 8967//8967 9355//9355 8968//8968 -f 9357//9357 8565//8565 8564//8564 -f 9154//9154 8975//8975 9356//9356 -f 9356//9356 8975//8975 9283//9283 -f 9356//9356 9283//9283 8564//8564 -f 8564//8564 9283//9283 9358//9358 -f 8564//8564 9358//9358 9357//9357 -f 8485//8485 9359//9359 8502//8502 -f 8502//8502 9359//9359 9360//9360 -f 8502//8502 9360//9360 8503//8503 -f 8503//8503 9360//9360 8505//8505 -f 9361//9361 8491//8491 9362//9362 -f 9362//9362 8491//8491 8490//8490 -f 9362//9362 8490//8490 8489//8489 -f 9363//9363 9364//9364 8493//8493 -f 8493//8493 8492//8492 9363//9363 -f 9363//9363 8492//8492 8746//8746 -f 9363//9363 8746//8746 8501//8501 -f 8600//8600 9365//9365 8495//8495 -f 8495//8495 9365//9365 9366//9366 -f 8495//8495 9366//9366 8496//8496 -f 9367//9367 9368//9368 9369//9369 -f 9369//9369 9368//9368 9370//9370 -f 8575//8575 9371//9371 8571//8571 -f 8571//8571 9371//9371 9372//9372 -f 8571//8571 9372//9372 8572//8572 -f 9373//9373 8588//8588 8587//8587 -f 9373//9373 8587//8587 9374//9374 -f 9374//9374 8587//8587 8593//8593 -f 9374//9374 8593//8593 8592//8592 -f 9375//9375 8589//8589 9376//9376 -f 9376//9376 8589//8589 8595//8595 -f 9376//9376 8595//8595 8594//8594 -f 9377//9377 8606//8606 8604//8604 -f 9377//9377 8604//8604 9378//9378 -f 9378//9378 8604//8604 8602//8602 -f 9378//9378 8602//8602 8601//8601 -f 9379//9379 9380//9380 9381//9381 -f 9381//9381 9380//9380 9382//9382 -f 9383//9383 9384//9384 9385//9385 -f 9385//9385 9384//9384 9311//9311 -f 9385//9385 9311//9311 8913//8913 -f 8913//8913 9311//9311 9312//9312 -f 9309//9309 9311//9311 9386//9386 -f 9386//9386 9311//9311 9387//9387 -f 9388//9388 9389//9389 9390//9390 -f 9390//9390 9389//9389 9309//9309 -f 9390//9390 9309//9309 9391//9391 -f 9391//9391 9309//9309 9386//9386 -f 9388//9388 9392//9392 9389//9389 -f 9389//9389 9392//9392 9393//9393 -f 9389//9389 9393//9393 9394//9394 -f 9394//9394 9393//9393 9395//9395 -f 9394//9394 9395//9395 9384//9384 -f 9384//9384 9395//9395 9396//9396 -f 9396//9396 9397//9397 9384//9384 -f 9384//9384 9397//9397 9398//9398 -f 9384//9384 9398//9398 9311//9311 -f 9311//9311 9398//9398 9399//9399 -f 9311//9311 9399//9399 9387//9387 -f 8916//8916 9307//9307 9400//9400 -f 9400//9400 9307//9307 9309//9309 -f 9400//9400 9309//9309 9401//9401 -f 9401//9401 9309//9309 9389//9389 -f 9383//9383 9402//9402 9384//9384 -f 9384//9384 9402//9402 9394//9394 -f 9402//9402 9401//9401 9394//9394 -f 9394//9394 9401//9401 9389//9389 -f 9400//9400 9401//9401 9403//9403 -f 9403//9403 9401//9401 9402//9402 -f 9403//9403 9402//9402 9404//9404 -f 9404//9404 9402//9402 9383//9383 -f 9404//9404 9383//9383 9385//9385 -f 8913//8913 8911//8911 9385//9385 -f 9385//9385 8911//8911 9404//9404 -f 8914//8914 9403//9403 9174//9174 -f 9174//9174 9403//9403 9404//9404 -f 9174//9174 9404//9404 8911//8911 -f 8914//8914 8916//8916 9403//9403 -f 9403//9403 8916//8916 9400//9400 -f 9405//9405 9406//9406 9407//9407 -f 9407//9407 9406//9406 9323//9323 -f 9407//9407 9323//9323 8933//8933 -f 8933//8933 9323//9323 9324//9324 -f 9408//9408 9321//9321 9409//9409 -f 9409//9409 9410//9410 9408//9408 -f 9408//9408 9410//9410 9411//9411 -f 9408//9408 9411//9411 9412//9412 -f 9412//9412 9411//9411 9413//9413 -f 9406//9406 9414//9414 9323//9323 -f 9323//9323 9414//9414 9415//9415 -f 9415//9415 9416//9416 9323//9323 -f 9323//9323 9416//9416 9417//9417 -f 9323//9323 9417//9417 9321//9321 -f 9321//9321 9417//9417 9418//9418 -f 9321//9321 9418//9418 9409//9409 -f 9413//9413 9419//9419 9412//9412 -f 9412//9412 9419//9419 9420//9420 -f 9412//9412 9420//9420 9406//9406 -f 9406//9406 9420//9420 9421//9421 -f 9406//9406 9421//9421 9414//9414 -f 8850//8850 9319//9319 9422//9422 -f 9422//9422 9319//9319 9321//9321 -f 9422//9422 9321//9321 9423//9423 -f 9423//9423 9321//9321 9408//9408 -f 9405//9405 9424//9424 9406//9406 -f 9406//9406 9424//9424 9412//9412 -f 9424//9424 9423//9423 9412//9412 -f 9412//9412 9423//9423 9408//9408 -f 9425//9425 9422//9422 9423//9423 -f 9405//9405 9407//9407 9426//9426 -f 9425//9425 9423//9423 9426//9426 -f 9426//9426 9423//9423 9424//9424 -f 9426//9426 9424//9424 9405//9405 -f 8934//8934 9426//9426 8933//8933 -f 8933//8933 9426//9426 9407//9407 -f 8919//8919 9425//9425 8934//8934 -f 8934//8934 9425//9425 9426//9426 -f 8850//8850 9422//9422 8919//8919 -f 8919//8919 9422//9422 9425//9425 -f 9386//9386 8757//8757 9391//9391 -f 9391//9391 8757//8757 8759//8759 -f 9391//9391 8759//8759 9390//9390 -f 9390//9390 8759//8759 8760//8760 -f 9390//9390 8760//8760 9388//9388 -f 9388//9388 8760//8760 8765//8765 -f 9388//9388 8765//8765 9392//9392 -f 9392//9392 8765//8765 8764//8764 -f 9392//9392 8764//8764 9393//9393 -f 9393//9393 8764//8764 8768//8768 -f 9393//9393 8768//8768 9395//9395 -f 9395//9395 8768//8768 8767//8767 -f 9395//9395 8767//8767 9396//9396 -f 9396//9396 8767//8767 8766//8766 -f 9396//9396 8766//8766 9397//9397 -f 9397//9397 8766//8766 8761//8761 -f 9397//9397 8761//8761 9398//9398 -f 9398//9398 8761//8761 8762//8762 -f 9398//9398 8762//8762 9399//9399 -f 9399//9399 8762//8762 8763//8763 -f 9399//9399 8763//8763 9387//9387 -f 9387//9387 8763//8763 8756//8756 -f 9387//9387 8756//8756 9386//9386 -f 9386//9386 8756//8756 8757//8757 -f 9414//9414 8790//8790 9415//9415 -f 9415//9415 8790//8790 8789//8789 -f 9415//9415 8789//8789 9416//9416 -f 9416//9416 8789//8789 8788//8788 -f 9416//9416 8788//8788 9417//9417 -f 9417//9417 8788//8788 8786//8786 -f 9417//9417 8786//8786 9418//9418 -f 9418//9418 8786//8786 8785//8785 -f 9418//9418 8785//8785 9409//9409 -f 9409//9409 8785//8785 8780//8780 -f 9409//9409 8780//8780 9410//9410 -f 9410//9410 8780//8780 8782//8782 -f 9410//9410 8782//8782 9411//9411 -f 9411//9411 8782//8782 8783//8783 -f 9411//9411 8783//8783 9413//9413 -f 9413//9413 8783//8783 8784//8784 -f 9413//9413 8784//8784 9419//9419 -f 9419//9419 8784//8784 8794//8794 -f 9419//9419 8794//8794 9420//9420 -f 9420//9420 8794//8794 8793//8793 -f 9420//9420 8793//8793 9421//9421 -f 9421//9421 8793//8793 8791//8791 -f 9421//9421 8791//8791 9414//9414 -f 9414//9414 8791//8791 8790//8790 -f 9427//9427 9428//9428 9429//9429 -f 9429//9429 9428//9428 9333//9333 -f 9429//9429 9333//9333 8944//8944 -f 8944//8944 9333//9333 9334//9334 -f 9430//9430 9331//9331 9431//9431 -f 9431//9431 9432//9432 9430//9430 -f 9430//9430 9432//9432 9433//9433 -f 9430//9430 9433//9433 9434//9434 -f 9434//9434 9433//9433 9435//9435 -f 9436//9436 9333//9333 9437//9437 -f 9437//9437 9333//9333 9428//9428 -f 9435//9435 9438//9438 9434//9434 -f 9434//9434 9438//9438 9439//9439 -f 9434//9434 9439//9439 9428//9428 -f 9428//9428 9439//9439 9440//9440 -f 9428//9428 9440//9440 9437//9437 -f 9436//9436 9441//9441 9333//9333 -f 9333//9333 9441//9441 9442//9442 -f 9333//9333 9442//9442 9331//9331 -f 9331//9331 9442//9442 9443//9443 -f 9331//9331 9443//9443 9431//9431 -f 8949//8949 9329//9329 9444//9444 -f 9444//9444 9329//9329 9331//9331 -f 9444//9444 9331//9331 9445//9445 -f 9445//9445 9331//9331 9430//9430 -f 9446//9446 9447//9447 9448//9448 -f 9448//9448 9447//9447 9343//9343 -f 9448//9448 9343//9343 8960//8960 -f 8960//8960 9343//9343 9344//9344 -f 9449//9449 9343//9343 9450//9450 -f 9450//9450 9343//9343 9447//9447 -f 9449//9449 9451//9451 9343//9343 -f 9343//9343 9451//9451 9452//9452 -f 9343//9343 9452//9452 9341//9341 -f 9453//9453 9454//9454 9455//9455 -f 9455//9455 9454//9454 9456//9456 -f 9453//9453 9457//9457 9454//9454 -f 9454//9454 9457//9457 9458//9458 -f 9454//9454 9458//9458 9447//9447 -f 9447//9447 9458//9458 9459//9459 -f 9447//9447 9459//9459 9450//9450 -f 9452//9452 9460//9460 9341//9341 -f 9341//9341 9460//9460 9461//9461 -f 9341//9341 9461//9461 9456//9456 -f 9456//9456 9461//9461 9462//9462 -f 9456//9456 9462//9462 9455//9455 -f 8965//8965 9339//9339 9463//9463 -f 9463//9463 9339//9339 9341//9341 -f 9463//9463 9341//9341 9464//9464 -f 9464//9464 9341//9341 9456//9456 -f 9465//9465 9466//9466 9467//9467 -f 9467//9467 9466//9466 9353//9353 -f 9467//9467 9353//9353 8969//8969 -f 8969//8969 9353//9353 9354//9354 -f 9468//9468 9469//9469 9470//9470 -f 9470//9470 9469//9469 9466//9466 -f 9471//9471 9351//9351 9472//9472 -f 9472//9472 9473//9473 9471//9471 -f 9471//9471 9473//9473 9474//9474 -f 9471//9471 9474//9474 9470//9470 -f 9470//9470 9474//9474 9475//9475 -f 9470//9470 9475//9475 9468//9468 -f 9469//9469 9476//9476 9466//9466 -f 9466//9466 9476//9476 9477//9477 -f 9466//9466 9477//9477 9353//9353 -f 9353//9353 9477//9477 9478//9478 -f 9478//9478 9479//9479 9353//9353 -f 9353//9353 9479//9479 9480//9480 -f 9353//9353 9480//9480 9351//9351 -f 9351//9351 9480//9480 9481//9481 -f 9351//9351 9481//9481 9472//9472 -f 8972//8972 9349//9349 9482//9482 -f 9482//9482 9349//9349 9351//9351 -f 9482//9482 9351//9351 9483//9483 -f 9483//9483 9351//9351 9471//9471 -f 9427//9427 9484//9484 9428//9428 -f 9428//9428 9484//9484 9434//9434 -f 9484//9484 9445//9445 9434//9434 -f 9434//9434 9445//9445 9430//9430 -f 9485//9485 9444//9444 9445//9445 -f 9427//9427 9429//9429 9486//9486 -f 9485//9485 9445//9445 9486//9486 -f 9486//9486 9445//9445 9484//9484 -f 9486//9486 9484//9484 9427//9427 -f 9446//9446 9487//9487 9447//9447 -f 9447//9447 9487//9487 9454//9454 -f 9487//9487 9464//9464 9454//9454 -f 9454//9454 9464//9464 9456//9456 -f 9488//9488 9463//9463 9464//9464 -f 9446//9446 9448//9448 9489//9489 -f 9488//9488 9464//9464 9489//9489 -f 9489//9489 9464//9464 9487//9487 -f 9489//9489 9487//9487 9446//9446 -f 9465//9465 9490//9490 9466//9466 -f 9466//9466 9490//9490 9470//9470 -f 9490//9490 9483//9483 9470//9470 -f 9470//9470 9483//9483 9471//9471 -f 9491//9491 9482//9482 9483//9483 -f 9465//9465 9467//9467 9492//9492 -f 9491//9491 9483//9483 9492//9492 -f 9492//9492 9483//9483 9490//9490 -f 9492//9492 9490//9490 9465//9465 -f 8946//8946 9486//9486 8944//8944 -f 8944//8944 9486//9486 9429//9429 -f 8948//8948 9485//9485 8946//8946 -f 8946//8946 9485//9485 9486//9486 -f 8949//8949 9444//9444 8948//8948 -f 8948//8948 9444//9444 9485//9485 -f 8962//8962 9489//9489 8960//8960 -f 8960//8960 9489//9489 9448//9448 -f 8966//8966 9488//9488 8962//8962 -f 8962//8962 9488//9488 9489//9489 -f 8965//8965 9463//9463 8966//8966 -f 8966//8966 9463//9463 9488//9488 -f 8970//8970 9492//9492 8969//8969 -f 8969//8969 9492//9492 9467//9467 -f 8971//8971 9491//9491 8970//8970 -f 8970//8970 9491//9491 9492//9492 -f 8972//8972 9482//9482 8971//8971 -f 8971//8971 9482//9482 9491//9491 -f 9437//9437 8478//8478 9436//9436 -f 9436//9436 8478//8478 8477//8477 -f 9436//9436 8477//8477 9441//9441 -f 9441//9441 8477//8477 8475//8475 -f 9441//9441 8475//8475 9442//9442 -f 9442//9442 8475//8475 8473//8473 -f 9442//9442 8473//8473 9443//9443 -f 9443//9443 8473//8473 8472//8472 -f 9443//9443 8472//8472 9431//9431 -f 9431//9431 8472//8472 8467//8467 -f 9431//9431 8467//8467 9432//9432 -f 9432//9432 8467//8467 8469//8469 -f 9432//9432 8469//8469 9433//9433 -f 9433//9433 8469//8469 8471//8471 -f 9433//9433 8471//8471 9435//9435 -f 9435//9435 8471//8471 8479//8479 -f 9435//9435 8479//8479 9438//9438 -f 9438//9438 8479//8479 8481//8481 -f 9438//9438 8481//8481 9439//9439 -f 9439//9439 8481//8481 8482//8482 -f 9439//9439 8482//8482 9440//9440 -f 9440//9440 8482//8482 8466//8466 -f 9440//9440 8466//8466 9437//9437 -f 9437//9437 8466//8466 8478//8478 -f 9450//9450 8350//8350 9449//9449 -f 9449//9449 8350//8350 8349//8349 -f 9449//9449 8349//8349 9451//9451 -f 9451//9451 8349//8349 8779//8779 -f 9451//9451 8779//8779 9452//9452 -f 9452//9452 8779//8779 8778//8778 -f 9452//9452 8778//8778 9460//9460 -f 9460//9460 8778//8778 8777//8777 -f 9460//9460 8777//8777 9461//9461 -f 9461//9461 8777//8777 8776//8776 -f 9461//9461 8776//8776 9462//9462 -f 9462//9462 8776//8776 8775//8775 -f 9462//9462 8775//8775 9455//9455 -f 9455//9455 8775//8775 8774//8774 -f 9455//9455 8774//8774 9453//9453 -f 9453//9453 8774//8774 8771//8771 -f 9453//9453 8771//8771 9457//9457 -f 9457//9457 8771//8771 8770//8770 -f 9457//9457 8770//8770 9458//9458 -f 9458//9458 8770//8770 8773//8773 -f 9458//9458 8773//8773 9459//9459 -f 9459//9459 8773//8773 8772//8772 -f 9459//9459 8772//8772 9450//9450 -f 9450//9450 8772//8772 8350//8350 -f 9477//9477 8461//8461 9478//9478 -f 9478//9478 8461//8461 8460//8460 -f 9478//9478 8460//8460 9479//9479 -f 9479//9479 8460//8460 8458//8458 -f 9479//9479 8458//8458 9480//9480 -f 9480//9480 8458//8458 8456//8456 -f 9480//9480 8456//8456 9481//9481 -f 9481//9481 8456//8456 8455//8455 -f 9481//9481 8455//8455 9472//9472 -f 9472//9472 8455//8455 8452//8452 -f 9472//9472 8452//8452 9473//9473 -f 9473//9473 8452//8452 8451//8451 -f 9473//9473 8451//8451 9474//9474 -f 9474//9474 8451//8451 8454//8454 -f 9474//9474 8454//8454 9475//9475 -f 9475//9475 8454//8454 8453//8453 -f 9475//9475 8453//8453 9468//9468 -f 9468//9468 8453//8453 8448//8448 -f 9468//9468 8448//8448 9469//9469 -f 9469//9469 8448//8448 8447//8447 -f 9469//9469 8447//8447 9476//9476 -f 9476//9476 8447//8447 8446//8446 -f 9476//9476 8446//8446 9477//9477 -f 9477//9477 8446//8446 8461//8461 -f 9273//9273 9245//9245 9274//9274 -f 9274//9274 9245//9245 9241//9241 -f 9274//9274 9241//9241 9175//9175 -f 9175//9175 9241//9241 9281//9281 -f 8901//8901 9277//9277 9271//9271 -f 9271//9271 9277//9277 9240//9240 -f 9271//9271 9240//9240 9272//9272 -f 9272//9272 9240//9240 9249//9249 -f 9273//9273 9276//9276 9245//9245 -f 9245//9245 9276//9276 9247//9247 -f 9276//9276 9272//9272 9247//9247 -f 9247//9247 9272//9272 9249//9249 -f 9176//9176 9275//9275 9175//9175 -f 9175//9175 9275//9275 9274//9274 -f 8903//8903 9270//9270 9177//9177 -f 9177//9177 9270//9270 9275//9275 -f 9177//9177 9275//9275 9176//9176 -f 8901//8901 9271//9271 8903//8903 -f 8903//8903 9271//9271 9270//9270 -f 9262//9262 9223//9223 9263//9263 -f 9263//9263 9223//9223 9225//9225 -f 9263//9263 9225//9225 9051//9051 -f 9051//9051 9225//9225 9268//9268 -f 8889//8889 9264//9264 9257//9257 -f 9257//9257 9264//9264 9228//9228 -f 9257//9257 9228//9228 9258//9258 -f 9258//9258 9228//9228 9227//9227 -f 9262//9262 9260//9260 9223//9223 -f 9223//9223 9260//9260 9231//9231 -f 9260//9260 9258//9258 9231//9231 -f 9231//9231 9258//9258 9227//9227 -f 9051//9051 8883//8883 9263//9263 -f 9263//9263 8883//8883 9261//9261 -f 8883//8883 8882//8882 9261//9261 -f 9261//9261 8882//8882 9259//9259 -f 8882//8882 8889//8889 9259//9259 -f 9259//9259 8889//8889 9257//9257 -f 9242//9242 8430//8430 9251//9251 -f 9251//9251 8430//8430 8429//8429 -f 9251//9251 8429//8429 9252//9252 -f 9252//9252 8429//8429 8428//8428 -f 9252//9252 8428//8428 9253//9253 -f 9253//9253 8428//8428 8426//8426 -f 9253//9253 8426//8426 9250//9250 -f 9250//9250 8426//8426 8425//8425 -f 9250//9250 8425//8425 9248//9248 -f 9248//9248 8425//8425 8423//8423 -f 9248//9248 8423//8423 9246//9246 -f 9246//9246 8423//8423 8422//8422 -f 9246//9246 8422//8422 9244//9244 -f 9244//9244 8422//8422 8439//8439 -f 9244//9244 8439//8439 9254//9254 -f 9254//9254 8439//8439 8437//8437 -f 9254//9254 8437//8437 9255//9255 -f 9255//9255 8437//8437 8435//8435 -f 9255//9255 8435//8435 9256//9256 -f 9256//9256 8435//8435 8433//8433 -f 9256//9256 8433//8433 9243//9243 -f 9243//9243 8433//8433 8432//8432 -f 9243//9243 8432//8432 9242//9242 -f 9242//9242 8432//8432 8430//8430 -f 9233//9233 8580//8580 9232//9232 -f 9232//9232 8580//8580 8579//8579 -f 9232//9232 8579//8579 9230//9230 -f 9230//9230 8579//8579 8578//8578 -f 9230//9230 8578//8578 9234//9234 -f 9234//9234 8578//8578 8576//8576 -f 9234//9234 8576//8576 9235//9235 -f 9235//9235 8576//8576 8574//8574 -f 9235//9235 8574//8574 9236//9236 -f 9236//9236 8574//8574 8573//8573 -f 9236//9236 8573//8573 9224//9224 -f 9224//9224 8573//8573 8570//8570 -f 9224//9224 8570//8570 9226//9226 -f 9226//9226 8570//8570 8569//8569 -f 9226//9226 8569//8569 9237//9237 -f 9237//9237 8569//8569 8585//8585 -f 9237//9237 8585//8585 9238//9238 -f 9238//9238 8585//8585 8584//8584 -f 9238//9238 8584//8584 9239//9239 -f 9239//9239 8584//8584 8582//8582 -f 9239//9239 8582//8582 9229//9229 -f 9229//9229 8582//8582 8581//8581 -f 9229//9229 8581//8581 9233//9233 -f 9233//9233 8581//8581 8580//8580 -f 9203//9203 8830//8830 9204//9204 -f 9204//9204 8830//8830 8832//8832 -f 9204//9204 8832//8832 8873//8873 -f 8873//8873 8832//8832 9221//9221 -f 9182//9182 9217//9217 9198//9198 -f 9198//9198 9217//9217 8839//8839 -f 9198//9198 8839//8839 9199//9199 -f 9199//9199 8839//8839 8841//8841 -f 9196//9196 8817//8817 9197//9197 -f 9197//9197 8817//8817 8819//8819 -f 9197//9197 8819//8819 8867//8867 -f 8867//8867 8819//8819 9215//9215 -f 8853//8853 9211//9211 9191//9191 -f 9191//9191 9211//9211 8823//8823 -f 9191//9191 8823//8823 9192//9192 -f 9192//9192 8823//8823 8813//8813 -f 9189//9189 8806//8806 9190//9190 -f 9190//9190 8806//8806 8796//8796 -f 9190//9190 8796//8796 8854//8854 -f 8854//8854 8796//8796 9209//9209 -f 8862//8862 9205//9205 9184//9184 -f 9184//9184 9205//9205 8802//8802 -f 9184//9184 8802//8802 9185//9185 -f 9185//9185 8802//8802 8805//8805 -f 9203//9203 9201//9201 8830//8830 -f 8830//8830 9201//9201 8834//8834 -f 9201//9201 9199//9199 8834//8834 -f 8834//8834 9199//9199 8841//8841 -f 9196//9196 9194//9194 8817//8817 -f 8817//8817 9194//9194 8815//8815 -f 9194//9194 9192//9192 8815//8815 -f 8815//8815 9192//9192 8813//8813 -f 9189//9189 9187//9187 8806//8806 -f 8806//8806 9187//9187 8799//8799 -f 9187//9187 9185//9185 8799//8799 -f 8799//8799 9185//9185 8805//8805 -f 8873//8873 8872//8872 9204//9204 -f 9204//9204 8872//8872 9202//9202 -f 8872//8872 8878//8878 9202//9202 -f 9202//9202 8878//8878 9200//9200 -f 8878//8878 9182//9182 9200//9200 -f 9200//9200 9182//9182 9198//9198 -f 8867//8867 8866//8866 9197//9197 -f 9197//9197 8866//8866 9195//9195 -f 8866//8866 8870//8870 9195//9195 -f 9195//9195 8870//8870 9193//9193 -f 8870//8870 8853//8853 9193//9193 -f 9193//9193 8853//8853 9191//9191 -f 8854//8854 8856//8856 9190//9190 -f 9190//9190 8856//8856 9188//9188 -f 8856//8856 8860//8860 9188//9188 -f 9188//9188 8860//8860 9186//9186 -f 8860//8860 8862//8862 9186//9186 -f 9186//9186 8862//8862 9184//9184 -f 8840//8840 8407//8407 8844//8844 -f 8844//8844 8407//8407 8406//8406 -f 8844//8844 8406//8406 8845//8845 -f 8845//8845 8406//8406 8401//8401 -f 8845//8845 8401//8401 8846//8846 -f 8846//8846 8401//8401 8418//8418 -f 8846//8846 8418//8418 8835//8835 -f 8835//8835 8418//8418 8417//8417 -f 8835//8835 8417//8417 8836//8836 -f 8836//8836 8417//8417 8415//8415 -f 8836//8836 8415//8415 8831//8831 -f 8831//8831 8415//8415 8414//8414 -f 8831//8831 8414//8414 8833//8833 -f 8833//8833 8414//8414 8413//8413 -f 8833//8833 8413//8413 8837//8837 -f 8837//8837 8413//8413 8421//8421 -f 8837//8837 8421//8421 8838//8838 -f 8838//8838 8421//8421 8420//8420 -f 8838//8838 8420//8420 8843//8843 -f 8843//8843 8420//8420 8419//8419 -f 8843//8843 8419//8419 8842//8842 -f 8842//8842 8419//8419 8409//8409 -f 8842//8842 8409//8409 8840//8840 -f 8840//8840 8409//8409 8407//8407 -f 8826//8826 8711//8711 8814//8814 -f 8814//8814 8711//8711 8710//8710 -f 8814//8814 8710//8710 8816//8816 -f 8816//8816 8710//8710 8721//8721 -f 8816//8816 8721//8721 8827//8827 -f 8827//8827 8721//8721 8720//8720 -f 8827//8827 8720//8720 8828//8828 -f 8828//8828 8720//8720 8719//8719 -f 8828//8828 8719//8719 8829//8829 -f 8829//8829 8719//8719 8716//8716 -f 8829//8829 8716//8716 8818//8818 -f 8818//8818 8716//8716 8717//8717 -f 8818//8818 8717//8717 8820//8820 -f 8820//8820 8717//8717 8718//8718 -f 8820//8820 8718//8718 8821//8821 -f 8821//8821 8718//8718 8715//8715 -f 8821//8821 8715//8715 8822//8822 -f 8822//8822 8715//8715 8714//8714 -f 8822//8822 8714//8714 8824//8824 -f 8824//8824 8714//8714 8713//8713 -f 8824//8824 8713//8713 8825//8825 -f 8825//8825 8713//8713 8712//8712 -f 8825//8825 8712//8712 8826//8826 -f 8826//8826 8712//8712 8711//8711 -f 8810//8810 8387//8387 8811//8811 -f 8811//8811 8387//8387 8385//8385 -f 8811//8811 8385//8385 8812//8812 -f 8812//8812 8385//8385 8384//8384 -f 8812//8812 8384//8384 8800//8800 -f 8800//8800 8384//8384 8395//8395 -f 8800//8800 8395//8395 8801//8801 -f 8801//8801 8395//8395 8397//8397 -f 8801//8801 8397//8397 8807//8807 -f 8807//8807 8397//8397 8399//8399 -f 8807//8807 8399//8399 8808//8808 -f 8808//8808 8399//8399 8400//8400 -f 8808//8808 8400//8400 8809//8809 -f 8809//8809 8400//8400 8394//8394 -f 8809//8809 8394//8394 8797//8797 -f 8797//8797 8394//8394 8393//8393 -f 8797//8797 8393//8393 8798//8798 -f 8798//8798 8393//8393 8392//8392 -f 8798//8798 8392//8392 8803//8803 -f 8803//8803 8392//8392 8391//8391 -f 8803//8803 8391//8391 8804//8804 -f 8804//8804 8391//8391 8389//8389 -f 8804//8804 8389//8389 8810//8810 -f 8810//8810 8389//8389 8387//8387 -f 9286//9286 7182//7182 9493//9493 -f 9493//9493 7182//7182 7206//7206 -f 9493//9493 7206//7206 9494//9494 -f 9494//9494 7206//7206 9495//9495 -f 9495//9495 7206//7206 7177//7177 -f 9495//9495 7177//7177 9496//9496 -f 9496//9496 7177//7177 9497//9497 -f 9497//9497 7177//7177 7178//7178 -f 9497//9497 7178//7178 9498//9498 -f 9498//9498 7178//7178 9499//9499 -f 9499//9499 7178//7178 7180//7180 -f 9499//9499 7180//7180 9500//9500 -f 9500//9500 7180//7180 9501//9501 -f 9501//9501 7180//7180 7154//7154 -f 9501//9501 7154//7154 9288//9288 -f 9284//9284 7196//7196 9502//9502 -f 9502//9502 7196//7196 7203//7203 -f 9502//9502 7203//7203 9503//9503 -f 9503//9503 7203//7203 9504//9504 -f 9504//9504 7203//7203 7202//7202 -f 9504//9504 7202//7202 9505//9505 -f 9505//9505 7202//7202 9506//9506 -f 9506//9506 7202//7202 7188//7188 -f 9506//9506 7188//7188 9507//9507 -f 9507//9507 7188//7188 9508//9508 -f 9508//9508 7188//7188 7186//7186 -f 9508//9508 7186//7186 9509//9509 -f 9509//9509 7186//7186 9510//9510 -f 9510//9510 7186//7186 7184//7184 -f 9510//9510 7184//7184 9285//9285 -f 9511//9511 8954//8954 8952//8952 -f 8952//8952 8951//8951 9511//9511 -f 9511//9511 8951//8951 9025//9025 -f 9511//9511 9025//9025 9512//9512 -f 9512//9512 9025//9025 9023//9023 -f 9512//9512 9023//9023 9021//9021 -f 8740//8740 9512//9512 8741//8741 -f 8741//8741 9512//9512 8742//8742 -f 9021//9021 9011//9011 9512//9512 -f 9512//9512 9011//9011 9513//9513 -f 9512//9512 9513//9513 8742//8742 -f 8742//8742 9513//9513 8608//8608 -f 9015//9015 9514//9514 9013//9013 -f 9013//9013 9514//9514 9513//9513 -f 9013//9013 9513//9513 9011//9011 -f 9015//9015 9017//9017 9514//9514 -f 9514//9514 9017//9017 9019//9019 -f 9514//9514 9019//9019 9149//9149 -f 9515//9515 9516//9516 9514//9514 -f 9149//9149 8954//8954 9514//9514 -f 9514//9514 8954//8954 9511//9511 -f 9514//9514 9511//9511 9515//9515 -f 9517//9517 9518//9518 9519//9519 -f 9029//9029 9030//9030 9519//9519 -f 9519//9519 9030//9030 9520//9520 -f 9519//9519 9520//9520 9517//9517 -f 9520//9520 9030//9030 9031//9031 -f 9031//9031 9036//9036 9520//9520 -f 9520//9520 9036//9036 9038//9038 -f 9520//9520 9038//9038 9521//9521 -f 9521//9521 9038//9038 9040//9040 -f 9521//9521 9040//9040 9035//9035 -f 8624//8624 9521//9521 8625//8625 -f 8625//8625 9521//9521 8627//8627 -f 9035//9035 9034//9034 9521//9521 -f 9521//9521 9034//9034 9522//9522 -f 9521//9521 9522//9522 8627//8627 -f 8627//8627 9522//9522 8629//8629 -f 9042//9042 9519//9519 9033//9033 -f 9033//9033 9519//9519 9522//9522 -f 9033//9033 9522//9522 9034//9034 -f 9042//9042 9044//9044 9519//9519 -f 9519//9519 9044//9044 9027//9027 -f 9519//9519 9027//9027 9029//9029 -f 9523//9523 8367//8367 8365//8365 -f 8643//8643 9524//9524 8365//8365 -f 8365//8365 9524//9524 9525//9525 -f 8365//8365 9525//9525 9523//9523 -f 8642//8642 9526//9526 8643//8643 -f 8643//8643 9526//9526 9527//9527 -f 8643//8643 9527//9527 9524//9524 -f 8640//8640 9528//9528 8642//8642 -f 8642//8642 9528//9528 9529//9529 -f 8642//8642 9529//9529 9526//9526 -f 8639//8639 9530//9530 8640//8640 -f 8640//8640 9530//9530 9531//9531 -f 8640//8640 9531//9531 9528//9528 -f 8638//8638 9532//9532 8639//8639 -f 8639//8639 9532//9532 9533//9533 -f 8639//8639 9533//9533 9530//9530 -f 8637//8637 9534//9534 8638//8638 -f 8638//8638 9534//9534 9535//9535 -f 8638//8638 9535//9535 9532//9532 -f 8633//8633 9536//9536 8637//8637 -f 8637//8637 9536//9536 9537//9537 -f 8637//8637 9537//9537 9534//9534 -f 8635//8635 9538//9538 8633//8633 -f 8633//8633 9538//9538 9539//9539 -f 8633//8633 9539//9539 9536//9536 -f 8648//8648 9540//9540 8635//8635 -f 8635//8635 9540//9540 9541//9541 -f 8635//8635 9541//9541 9538//9538 -f 8647//8647 9542//9542 8648//8648 -f 8648//8648 9542//9542 9543//9543 -f 8648//8648 9543//9543 9540//9540 -f 8645//8645 9544//9544 8647//8647 -f 8647//8647 9544//9544 9545//9545 -f 8647//8647 9545//9545 9542//9542 -f 8644//8644 9546//9546 8645//8645 -f 8645//8645 9546//9546 9547//9547 -f 8645//8645 9547//9547 9544//9544 -f 8654//8654 9548//9548 8644//8644 -f 8644//8644 9548//9548 9549//9549 -f 8644//8644 9549//9549 9546//9546 -f 8656//8656 9550//9550 8654//8654 -f 8654//8654 9550//9550 9551//9551 -f 8654//8654 9551//9551 9548//9548 -f 8657//8657 9552//9552 8656//8656 -f 8656//8656 9552//9552 9553//9553 -f 8656//8656 9553//9553 9550//9550 -f 8651//8651 9554//9554 8657//8657 -f 8657//8657 9554//9554 9555//9555 -f 8657//8657 9555//9555 9552//9552 -f 8653//8653 9556//9556 8651//8651 -f 8651//8651 9556//9556 9557//9557 -f 8651//8651 9557//9557 9554//9554 -f 8667//8667 9558//9558 8653//8653 -f 8653//8653 9558//9558 9559//9559 -f 8653//8653 9559//9559 9556//9556 -f 9523//9523 9560//9560 8367//8367 -f 8367//8367 9560//9560 9561//9561 -f 8367//8367 9561//9561 8667//8667 -f 8667//8667 9561//9561 9562//9562 -f 8667//8667 9562//9562 9558//9558 -f 9563//9563 9564//9564 9565//9565 -f 9565//9565 9564//9564 9566//9566 -f 9567//9567 9568//9568 9569//9569 -f 9569//9569 9568//9568 9570//9570 -f 9571//9571 9572//9572 9573//9573 -f 9574//9574 9575//9575 9572//9572 -f 9572//9572 9575//9575 9576//9576 -f 9572//9572 9576//9576 9573//9573 -f 9577//9577 9578//9578 9579//9579 -f 9579//9579 9578//9578 9580//9580 -f 9579//9579 9580//9580 9581//9581 -f 9582//9582 9583//9583 9584//9584 -f 9584//9584 9583//9583 9585//9585 -f 9568//9568 9586//9586 9570//9570 -f 9570//9570 9586//9586 9587//9587 -f 9570//9570 9587//9587 9588//9588 -f 9564//9564 9589//9589 9566//9566 -f 9566//9566 9589//9589 9590//9590 -f 9566//9566 9590//9590 9591//9591 -f 9592//9592 9593//9593 9565//9565 -f 9565//9565 9593//9593 9594//9594 -f 9565//9565 9594//9594 9563//9563 -f 9595//9595 9596//9596 9597//9597 -f 9597//9597 9596//9596 9598//9598 -f 9577//9577 9599//9599 9578//9578 -f 9578//9578 9599//9599 9600//9600 -f 9578//9578 9600//9600 9574//9574 -f 9574//9574 9600//9600 9601//9601 -f 9574//9574 9601//9601 9575//9575 -f 9581//9581 9580//9580 9602//9602 -f 9602//9602 9580//9580 9603//9603 -f 9602//9602 9603//9603 9604//9604 -f 9583//9583 9605//9605 9585//9585 -f 9585//9585 9605//9605 9606//9606 -f 9585//9585 9606//9606 9603//9603 -f 9603//9603 9606//9606 9607//9607 -f 9603//9603 9607//9607 9604//9604 -f 9587//9587 9608//9608 9588//9588 -f 9588//9588 9608//9608 9609//9609 -f 9588//9588 9609//9609 9584//9584 -f 9584//9584 9609//9609 9610//9610 -f 9584//9584 9610//9610 9582//9582 -f 9590//9590 9611//9611 9591//9591 -f 9591//9591 9611//9611 9612//9612 -f 9591//9591 9612//9612 9569//9569 -f 9569//9569 9612//9612 9613//9613 -f 9569//9569 9613//9613 9567//9567 -f 9596//9596 9614//9614 9598//9598 -f 9598//9598 9614//9614 9615//9615 -f 9598//9598 9615//9615 9592//9592 -f 9592//9592 9615//9615 9616//9616 -f 9592//9592 9616//9616 9593//9593 -f 9573//9573 9617//9617 9571//9571 -f 9571//9571 9617//9617 9618//9618 -f 9571//9571 9618//9618 9597//9597 -f 9597//9597 9618//9618 9619//9619 -f 9597//9597 9619//9619 9595//9595 -f 9620//9620 9566//9566 9621//9621 -f 9621//9621 9566//9566 9591//9591 -f 9621//9621 9591//9591 9622//9622 -f 9622//9622 9591//9591 9569//9569 -f 9622//9622 9569//9569 9623//9623 -f 9623//9623 9569//9569 9570//9570 -f 9623//9623 9570//9570 9624//9624 -f 9624//9624 9570//9570 9588//9588 -f 9624//9624 9588//9588 9625//9625 -f 9625//9625 9588//9588 9584//9584 -f 9625//9625 9584//9584 9626//9626 -f 9626//9626 9584//9584 9585//9585 -f 9626//9626 9585//9585 9627//9627 -f 9627//9627 9585//9585 9603//9603 -f 9627//9627 9603//9603 9628//9628 -f 9628//9628 9603//9603 9580//9580 -f 9628//9628 9580//9580 9629//9629 -f 9629//9629 9580//9580 9578//9578 -f 9629//9629 9578//9578 9630//9630 -f 9630//9630 9578//9578 9574//9574 -f 9630//9630 9574//9574 9631//9631 -f 9631//9631 9574//9574 9572//9572 -f 9631//9631 9572//9572 9632//9632 -f 9632//9632 9572//9572 9571//9571 -f 9632//9632 9571//9571 9633//9633 -f 9633//9633 9571//9571 9597//9597 -f 9633//9633 9597//9597 9634//9634 -f 9634//9634 9597//9597 9598//9598 -f 9634//9634 9598//9598 9635//9635 -f 9635//9635 9598//9598 9592//9592 -f 9635//9635 9592//9592 9636//9636 -f 9636//9636 9592//9592 9565//9565 -f 9636//9636 9565//9565 9620//9620 -f 9620//9620 9565//9565 9566//9566 -f 9637//9637 9635//9635 9638//9638 -f 9638//9638 9635//9635 9636//9636 -f 9638//9638 9636//9636 9639//9639 -f 9639//9639 9636//9636 9620//9620 -f 9639//9639 9620//9620 9640//9640 -f 9641//9641 9632//9632 9642//9642 -f 9642//9642 9632//9632 9633//9633 -f 9642//9642 9633//9633 9637//9637 -f 9637//9637 9633//9633 9634//9634 -f 9637//9637 9634//9634 9635//9635 -f 9643//9643 9628//9628 9644//9644 -f 9644//9644 9628//9628 9629//9629 -f 9644//9644 9629//9629 9645//9645 -f 9645//9645 9629//9629 9630//9630 -f 9645//9645 9630//9630 9641//9641 -f 9641//9641 9630//9630 9631//9631 -f 9641//9641 9631//9631 9632//9632 -f 9646//9646 9625//9625 9647//9647 -f 9647//9647 9625//9625 9626//9626 -f 9647//9647 9626//9626 9643//9643 -f 9643//9643 9626//9626 9627//9627 -f 9643//9643 9627//9627 9628//9628 -f 9620//9620 9621//9621 9640//9640 -f 9640//9640 9621//9621 9622//9622 -f 9640//9640 9622//9622 9648//9648 -f 9648//9648 9622//9622 9623//9623 -f 9648//9648 9623//9623 9646//9646 -f 9646//9646 9623//9623 9624//9624 -f 9646//9646 9624//9624 9625//9625 -f 9649//9649 9650//9650 9651//9651 -f 9652//9652 9650//9650 9649//9649 -f 9649//9649 9653//9653 9654//9654 -f 9655//9655 9653//9653 9649//9649 -f 9651//9651 9655//9655 9649//9649 -f 9649//9649 9656//9656 9657//9657 -f 9658//9658 9656//9656 9649//9649 -f 9654//9654 9658//9658 9649//9649 -f 9649//9649 9659//9659 9660//9660 -f 9661//9661 9659//9659 9649//9649 -f 9657//9657 9661//9661 9649//9649 -f 9660//9660 9652//9652 9649//9649 -f 9652//9652 9662//9662 9650//9650 -f 9650//9650 9662//9662 9663//9663 -f 9650//9650 9663//9663 9651//9651 -f 9651//9651 9663//9663 9664//9664 -f 9651//9651 9664//9664 9655//9655 -f 9655//9655 9664//9664 9665//9665 -f 9655//9655 9665//9665 9653//9653 -f 9653//9653 9665//9665 9666//9666 -f 9653//9653 9666//9666 9654//9654 -f 9654//9654 9666//9666 9667//9667 -f 9654//9654 9667//9667 9658//9658 -f 9658//9658 9667//9667 9668//9668 -f 9658//9658 9668//9668 9656//9656 -f 9656//9656 9668//9668 9669//9669 -f 9656//9656 9669//9669 9657//9657 -f 9657//9657 9669//9669 9670//9670 -f 9657//9657 9670//9670 9661//9661 -f 9661//9661 9670//9670 9671//9671 -f 9661//9661 9671//9671 9659//9659 -f 9659//9659 9671//9671 9672//9672 -f 9659//9659 9672//9672 9660//9660 -f 9660//9660 9672//9672 9673//9673 -f 9660//9660 9673//9673 9652//9652 -f 9652//9652 9673//9673 9662//9662 -f 9663//9663 9000//9000 9664//9664 -f 9664//9664 9000//9000 8998//8998 -f 9664//9664 8998//8998 9665//9665 -f 9665//9665 8998//8998 8997//8997 -f 9665//9665 8997//8997 9666//9666 -f 9666//9666 8997//8997 8996//8996 -f 9666//9666 8996//8996 9667//9667 -f 9667//9667 8996//8996 8995//8995 -f 9667//9667 8995//8995 9668//9668 -f 9668//9668 8995//8995 8993//8993 -f 9668//9668 8993//8993 9669//9669 -f 9669//9669 8993//8993 9006//9006 -f 9669//9669 9006//9006 9670//9670 -f 9670//9670 9006//9006 9005//9005 -f 9670//9670 9005//9005 9671//9671 -f 9671//9671 9005//9005 9004//9004 -f 9671//9671 9004//9004 9672//9672 -f 9672//9672 9004//9004 9003//9003 -f 9672//9672 9003//9003 9673//9673 -f 9673//9673 9003//9003 9002//9002 -f 9673//9673 9002//9002 9662//9662 -f 9662//9662 9002//9002 9001//9001 -f 9662//9662 9001//9001 9663//9663 -f 9663//9663 9001//9001 9000//9000 -f 9674//9674 9675//9675 9676//9676 -f 9677//9677 9675//9675 9674//9674 -f 9674//9674 9678//9678 9679//9679 -f 9680//9680 9678//9678 9674//9674 -f 9676//9676 9680//9680 9674//9674 -f 9674//9674 9681//9681 9682//9682 -f 9683//9683 9681//9681 9674//9674 -f 9679//9679 9683//9683 9674//9674 -f 9674//9674 9684//9684 9685//9685 -f 9686//9686 9684//9684 9674//9674 -f 9682//9682 9686//9686 9674//9674 -f 9685//9685 9677//9677 9674//9674 -f 9677//9677 9687//9687 9675//9675 -f 9675//9675 9687//9687 9688//9688 -f 9675//9675 9688//9688 9676//9676 -f 9676//9676 9688//9688 9689//9689 -f 9676//9676 9689//9689 9680//9680 -f 9680//9680 9689//9689 9690//9690 -f 9680//9680 9690//9690 9678//9678 -f 9678//9678 9690//9690 9691//9691 -f 9678//9678 9691//9691 9679//9679 -f 9679//9679 9691//9691 9692//9692 -f 9679//9679 9692//9692 9683//9683 -f 9683//9683 9692//9692 9693//9693 -f 9683//9683 9693//9693 9681//9681 -f 9681//9681 9693//9693 9694//9694 -f 9681//9681 9694//9694 9682//9682 -f 9682//9682 9694//9694 9695//9695 -f 9682//9682 9695//9695 9686//9686 -f 9686//9686 9695//9695 9696//9696 -f 9686//9686 9696//9696 9684//9684 -f 9684//9684 9696//9696 9697//9697 -f 9684//9684 9697//9697 9685//9685 -f 9685//9685 9697//9697 9698//9698 -f 9685//9685 9698//9698 9677//9677 -f 9677//9677 9698//9698 9687//9687 -f 9688//9688 8980//8980 9689//9689 -f 9689//9689 8980//8980 8979//8979 -f 9689//9689 8979//8979 9690//9690 -f 9690//9690 8979//8979 8978//8978 -f 9690//9690 8978//8978 9691//9691 -f 9691//9691 8978//8978 8977//8977 -f 9691//9691 8977//8977 9692//9692 -f 9692//9692 8977//8977 8991//8991 -f 9692//9692 8991//8991 9693//9693 -f 9693//9693 8991//8991 8990//8990 -f 9693//9693 8990//8990 9694//9694 -f 9694//9694 8990//8990 8988//8988 -f 9694//9694 8988//8988 9695//9695 -f 9695//9695 8988//8988 8986//8986 -f 9695//9695 8986//8986 9696//9696 -f 9696//9696 8986//8986 8985//8985 -f 9696//9696 8985//8985 9697//9697 -f 9697//9697 8985//8985 8984//8984 -f 9697//9697 8984//8984 9698//9698 -f 9698//9698 8984//8984 8982//8982 -f 9698//9698 8982//8982 9687//9687 -f 9687//9687 8982//8982 8981//8981 -f 9687//9687 8981//8981 9688//9688 -f 9688//9688 8981//8981 8980//8980 -f 9699//9699 9700//9700 9701//9701 -f 9702//9702 9700//9700 9699//9699 -f 9699//9699 9703//9703 9704//9704 -f 9705//9705 9703//9703 9699//9699 -f 9701//9701 9705//9705 9699//9699 -f 9699//9699 9706//9706 9707//9707 -f 9708//9708 9706//9706 9699//9699 -f 9704//9704 9708//9708 9699//9699 -f 9699//9699 9709//9709 9710//9710 -f 9711//9711 9709//9709 9699//9699 -f 9707//9707 9711//9711 9699//9699 -f 9710//9710 9702//9702 9699//9699 -f 9702//9702 9712//9712 9700//9700 -f 9700//9700 9712//9712 9713//9713 -f 9700//9700 9713//9713 9701//9701 -f 9701//9701 9713//9713 9714//9714 -f 9701//9701 9714//9714 9705//9705 -f 9705//9705 9714//9714 9715//9715 -f 9705//9705 9715//9715 9703//9703 -f 9703//9703 9715//9715 9716//9716 -f 9703//9703 9716//9716 9704//9704 -f 9704//9704 9716//9716 9717//9717 -f 9704//9704 9717//9717 9708//9708 -f 9708//9708 9717//9717 9718//9718 -f 9708//9708 9718//9718 9706//9706 -f 9706//9706 9718//9718 9719//9719 -f 9706//9706 9719//9719 9707//9707 -f 9707//9707 9719//9719 9720//9720 -f 9707//9707 9720//9720 9711//9711 -f 9711//9711 9720//9720 9721//9721 -f 9711//9711 9721//9721 9709//9709 -f 9709//9709 9721//9721 9722//9722 -f 9709//9709 9722//9722 9710//9710 -f 9710//9710 9722//9722 9723//9723 -f 9710//9710 9723//9723 9702//9702 -f 9702//9702 9723//9723 9712//9712 -f 9713//9713 9050//9050 9714//9714 -f 9714//9714 9050//9050 9056//9056 -f 9714//9714 9056//9056 9715//9715 -f 9715//9715 9056//9056 9055//9055 -f 9715//9715 9055//9055 9716//9716 -f 9716//9716 9055//9055 9054//9054 -f 9716//9716 9054//9054 9717//9717 -f 9717//9717 9054//9054 9046//9046 -f 9717//9717 9046//9046 9718//9718 -f 9718//9718 9046//9046 9048//9048 -f 9718//9718 9048//9048 9719//9719 -f 9719//9719 9048//9048 8891//8891 -f 9719//9719 8891//8891 9720//9720 -f 9720//9720 8891//8891 8892//8892 -f 9720//9720 8892//8892 9721//9721 -f 9721//9721 8892//8892 8893//8893 -f 9721//9721 8893//8893 9722//9722 -f 9722//9722 8893//8893 8888//8888 -f 9722//9722 8888//8888 9723//9723 -f 9723//9723 8888//8888 8884//8884 -f 9723//9723 8884//8884 9712//9712 -f 9712//9712 8884//8884 9053//9053 -f 9712//9712 9053//9053 9713//9713 -f 9713//9713 9053//9053 9050//9050 -f 9724//9724 9725//9725 9726//9726 -f 9727//9727 9725//9725 9724//9724 -f 9724//9724 9728//9728 9729//9729 -f 9730//9730 9728//9728 9724//9724 -f 9726//9726 9730//9730 9724//9724 -f 9724//9724 9731//9731 9732//9732 -f 9733//9733 9731//9731 9724//9724 -f 9729//9729 9733//9733 9724//9724 -f 9724//9724 9734//9734 9735//9735 -f 9736//9736 9734//9734 9724//9724 -f 9732//9732 9736//9736 9724//9724 -f 9735//9735 9727//9727 9724//9724 -f 9727//9727 9737//9737 9725//9725 -f 9725//9725 9737//9737 9738//9738 -f 9725//9725 9738//9738 9726//9726 -f 9726//9726 9738//9738 9739//9739 -f 9726//9726 9739//9739 9730//9730 -f 9730//9730 9739//9739 9740//9740 -f 9730//9730 9740//9740 9728//9728 -f 9728//9728 9740//9740 9741//9741 -f 9728//9728 9741//9741 9729//9729 -f 9729//9729 9741//9741 9742//9742 -f 9729//9729 9742//9742 9733//9733 -f 9733//9733 9742//9742 9743//9743 -f 9733//9733 9743//9743 9731//9731 -f 9731//9731 9743//9743 9744//9744 -f 9731//9731 9744//9744 9732//9732 -f 9732//9732 9744//9744 9745//9745 -f 9732//9732 9745//9745 9736//9736 -f 9736//9736 9745//9745 9746//9746 -f 9736//9736 9746//9746 9734//9734 -f 9734//9734 9746//9746 9747//9747 -f 9734//9734 9747//9747 9735//9735 -f 9735//9735 9747//9747 9748//9748 -f 9735//9735 9748//9748 9727//9727 -f 9727//9727 9748//9748 9737//9737 -f 9738//9738 8936//8936 9739//9739 -f 9739//9739 8936//8936 8935//8935 -f 9739//9739 8935//8935 9740//9740 -f 9740//9740 8935//8935 8926//8926 -f 9740//9740 8926//8926 9741//9741 -f 9741//9741 8926//8926 8925//8925 -f 9741//9741 8925//8925 9742//9742 -f 9742//9742 8925//8925 8923//8923 -f 9742//9742 8923//8923 9743//9743 -f 9743//9743 8923//8923 8922//8922 -f 9743//9743 8922//8922 9744//9744 -f 9744//9744 8922//8922 8931//8931 -f 9744//9744 8931//8931 9745//9745 -f 9745//9745 8931//8931 8930//8930 -f 9745//9745 8930//8930 9746//9746 -f 9746//9746 8930//8930 8929//8929 -f 9746//9746 8929//8929 9747//9747 -f 9747//9747 8929//8929 8928//8928 -f 9747//9747 8928//8928 9748//9748 -f 9748//9748 8928//8928 8927//8927 -f 9748//9748 8927//8927 9737//9737 -f 9737//9737 8927//8927 8937//8937 -f 9737//9737 8937//8937 9738//9738 -f 9738//9738 8937//8937 8936//8936 -f 9062//9062 9749//9749 9064//9064 -f 9064//9064 9749//9749 9750//9750 -f 9064//9064 9750//9750 9065//9065 -f 9065//9065 9750//9750 9751//9751 -f 9065//9065 9751//9751 9066//9066 -f 9066//9066 9751//9751 9752//9752 -f 9066//9066 9752//9752 9067//9067 -f 9067//9067 9752//9752 9753//9753 -f 9067//9067 9753//9753 9069//9069 -f 9069//9069 9753//9753 9754//9754 -f 9069//9069 9754//9754 9071//9071 -f 9071//9071 9754//9754 9755//9755 -f 9071//9071 9755//9755 9073//9073 -f 9073//9073 9755//9755 9756//9756 -f 9073//9073 9756//9756 9074//9074 -f 9074//9074 9756//9756 9757//9757 -f 9074//9074 9757//9757 9057//9057 -f 9057//9057 9757//9757 9758//9758 -f 9057//9057 9758//9758 9058//9058 -f 9058//9058 9758//9758 9759//9759 -f 9058//9058 9759//9759 9060//9060 -f 9060//9060 9759//9759 9760//9760 -f 9060//9060 9760//9760 9062//9062 -f 9062//9062 9760//9760 9749//9749 -f 9750//9750 9640//9640 9751//9751 -f 9751//9751 9640//9640 9648//9648 -f 9751//9751 9648//9648 9752//9752 -f 9752//9752 9648//9648 9646//9646 -f 9752//9752 9646//9646 9753//9753 -f 9753//9753 9646//9646 9647//9647 -f 9753//9753 9647//9647 9754//9754 -f 9754//9754 9647//9647 9643//9643 -f 9754//9754 9643//9643 9755//9755 -f 9755//9755 9643//9643 9644//9644 -f 9755//9755 9644//9644 9756//9756 -f 9756//9756 9644//9644 9645//9645 -f 9756//9756 9645//9645 9757//9757 -f 9757//9757 9645//9645 9641//9641 -f 9757//9757 9641//9641 9758//9758 -f 9758//9758 9641//9641 9642//9642 -f 9758//9758 9642//9642 9759//9759 -f 9759//9759 9642//9642 9637//9637 -f 9759//9759 9637//9637 9760//9760 -f 9760//9760 9637//9637 9638//9638 -f 9760//9760 9638//9638 9749//9749 -f 9749//9749 9638//9638 9639//9639 -f 9749//9749 9639//9639 9750//9750 -f 9750//9750 9639//9639 9640//9640 -f 9079//9079 9761//9761 9080//9080 -f 9080//9080 9761//9761 9762//9762 -f 9080//9080 9762//9762 9170//9170 -f 9170//9170 9762//9762 9763//9763 -f 9170//9170 9763//9763 9081//9081 -f 9081//9081 9763//9763 9764//9764 -f 9081//9081 9764//9764 9082//9082 -f 9082//9082 9764//9764 9765//9765 -f 9082//9082 9765//9765 9084//9084 -f 9084//9084 9765//9765 9766//9766 -f 9084//9084 9766//9766 9086//9086 -f 9086//9086 9766//9766 9767//9767 -f 9086//9086 9767//9767 9087//9087 -f 9087//9087 9767//9767 9768//9768 -f 9087//9087 9768//9768 9178//9178 -f 9178//9178 9768//9768 9769//9769 -f 9178//9178 9769//9769 9075//9075 -f 9075//9075 9769//9769 9770//9770 -f 9075//9075 9770//9770 9076//9076 -f 9076//9076 9770//9770 9771//9771 -f 9076//9076 9771//9771 9078//9078 -f 9078//9078 9771//9771 9772//9772 -f 9078//9078 9772//9772 9079//9079 -f 9079//9079 9772//9772 9761//9761 -f 9762//9762 8641//8641 9763//9763 -f 9763//9763 8641//8641 8364//8364 -f 9763//9763 8364//8364 9764//9764 -f 9764//9764 8364//8364 8366//8366 -f 9764//9764 8366//8366 9765//9765 -f 9765//9765 8366//8366 8368//8368 -f 9765//9765 8368//8368 9766//9766 -f 9766//9766 8368//8368 8377//8377 -f 9766//9766 8377//8377 9767//9767 -f 9767//9767 8377//8377 8379//8379 -f 9767//9767 8379//8379 9768//9768 -f 9768//9768 8379//8379 8381//8381 -f 9768//9768 8381//8381 9769//9769 -f 9769//9769 8381//8381 8376//8376 -f 9769//9769 8376//8376 9770//9770 -f 9770//9770 8376//8376 8375//8375 -f 9770//9770 8375//8375 9771//9771 -f 9771//9771 8375//8375 8373//8373 -f 9771//9771 8373//8373 9772//9772 -f 9772//9772 8373//8373 8372//8372 -f 9772//9772 8372//8372 9761//9761 -f 9761//9761 8372//8372 8371//8371 -f 9761//9761 8371//8371 9762//9762 -f 9762//9762 8371//8371 8641//8641 -f 9098//9098 9773//9773 9099//9099 -f 9099//9099 9773//9773 9774//9774 -f 9099//9099 9774//9774 9100//9100 -f 9100//9100 9774//9774 9775//9775 -f 9100//9100 9775//9775 9103//9103 -f 9103//9103 9775//9775 9776//9776 -f 9103//9103 9776//9776 9101//9101 -f 9101//9101 9776//9776 9777//9777 -f 9101//9101 9777//9777 9092//9092 -f 9092//9092 9777//9777 9778//9778 -f 9092//9092 9778//9778 9090//9090 -f 9090//9090 9778//9778 9779//9779 -f 9090//9090 9779//9779 9088//9088 -f 9088//9088 9779//9779 9780//9780 -f 9088//9088 9780//9780 9095//9095 -f 9095//9095 9780//9780 9781//9781 -f 9095//9095 9781//9781 9096//9096 -f 9096//9096 9781//9781 9782//9782 -f 9096//9096 9782//9782 9097//9097 -f 9097//9097 9782//9782 9783//9783 -f 9097//9097 9783//9783 9093//9093 -f 9093//9093 9783//9783 9784//9784 -f 9093//9093 9784//9784 9098//9098 -f 9098//9098 9784//9784 9773//9773 -f 9774//9774 8671//8671 9775//9775 -f 9775//9775 8671//8671 8670//8670 -f 9775//9775 8670//8670 9776//9776 -f 9776//9776 8670//8670 8675//8675 -f 9776//9776 8675//8675 9777//9777 -f 9777//9777 8675//8675 8674//8674 -f 9777//9777 8674//8674 9778//9778 -f 9778//9778 8674//8674 8673//8673 -f 9778//9778 8673//8673 9779//9779 -f 9779//9779 8673//8673 8672//8672 -f 9779//9779 8672//8672 9780//9780 -f 9780//9780 8672//8672 8680//8680 -f 9780//9780 8680//8680 9781//9781 -f 9781//9781 8680//8680 8679//8679 -f 9781//9781 8679//8679 9782//9782 -f 9782//9782 8679//8679 8677//8677 -f 9782//9782 8677//8677 9783//9783 -f 9783//9783 8677//8677 8676//8676 -f 9783//9783 8676//8676 9784//9784 -f 9784//9784 8676//8676 8669//8669 -f 9784//9784 8669//8669 9773//9773 -f 9773//9773 8669//8669 8668//8668 -f 9773//9773 8668//8668 9774//9774 -f 9774//9774 8668//8668 8671//8671 -f 9111//9111 9785//9785 9112//9112 -f 9112//9112 9785//9785 9786//9786 -f 9112//9112 9786//9786 9114//9114 -f 9114//9114 9786//9786 9787//9787 -f 9114//9114 9787//9787 9115//9115 -f 9115//9115 9787//9787 9788//9788 -f 9115//9115 9788//9788 9116//9116 -f 9116//9116 9788//9788 9789//9789 -f 9116//9116 9789//9789 9117//9117 -f 9117//9117 9789//9789 9790//9790 -f 9117//9117 9790//9790 9110//9110 -f 9110//9110 9790//9790 9791//9791 -f 9110//9110 9791//9791 9104//9104 -f 9104//9104 9791//9791 9792//9792 -f 9104//9104 9792//9792 9105//9105 -f 9105//9105 9792//9792 9793//9793 -f 9105//9105 9793//9793 9106//9106 -f 9106//9106 9793//9793 9794//9794 -f 9106//9106 9794//9794 9107//9107 -f 9107//9107 9794//9794 9795//9795 -f 9107//9107 9795//9795 9108//9108 -f 9108//9108 9795//9795 9796//9796 -f 9108//9108 9796//9796 9111//9111 -f 9111//9111 9796//9796 9785//9785 -f 9786//9786 8736//8736 9787//9787 -f 9787//9787 8736//8736 8737//8737 -f 9787//9787 8737//8737 9788//9788 -f 9788//9788 8737//8737 8735//8735 -f 9788//9788 8735//8735 9789//9789 -f 9789//9789 8735//8735 8734//8734 -f 9789//9789 8734//8734 9790//9790 -f 9790//9790 8734//8734 8733//8733 -f 9790//9790 8733//8733 9791//9791 -f 9791//9791 8733//8733 8726//8726 -f 9791//9791 8726//8726 9792//9792 -f 9792//9792 8726//8726 8725//8725 -f 9792//9792 8725//8725 9793//9793 -f 9793//9793 8725//8725 8729//8729 -f 9793//9793 8729//8729 9794//9794 -f 9794//9794 8729//8729 8728//8728 -f 9794//9794 8728//8728 9795//9795 -f 9795//9795 8728//8728 8727//8727 -f 9795//9795 8727//8727 9796//9796 -f 9796//9796 8727//8727 8724//8724 -f 9796//9796 8724//8724 9785//9785 -f 9785//9785 8724//8724 8723//8723 -f 9785//9785 8723//8723 9786//9786 -f 9786//9786 8723//8723 8736//8736 -f 9122//9122 9797//9797 9123//9123 -f 9123//9123 9797//9797 9798//9798 -f 9123//9123 9798//9798 9162//9162 -f 9162//9162 9798//9798 9799//9799 -f 9162//9162 9799//9799 9124//9124 -f 9124//9124 9799//9799 9800//9800 -f 9124//9124 9800//9800 9125//9125 -f 9125//9125 9800//9800 9801//9801 -f 9125//9125 9801//9801 9127//9127 -f 9127//9127 9801//9801 9802//9802 -f 9127//9127 9802//9802 9128//9128 -f 9128//9128 9802//9802 9803//9803 -f 9128//9128 9803//9803 9130//9130 -f 9130//9130 9803//9803 9804//9804 -f 9130//9130 9804//9804 9165//9165 -f 9165//9165 9804//9804 9805//9805 -f 9165//9165 9805//9805 9118//9118 -f 9118//9118 9805//9805 9806//9806 -f 9118//9118 9806//9806 9119//9119 -f 9119//9119 9806//9806 9807//9807 -f 9119//9119 9807//9807 9120//9120 -f 9120//9120 9807//9807 9808//9808 -f 9120//9120 9808//9808 9122//9122 -f 9122//9122 9808//9808 9797//9797 -f 9798//9798 8550//8550 9799//9799 -f 9799//9799 8550//8550 8552//8552 -f 9799//9799 8552//8552 9800//9800 -f 9800//9800 8552//8552 8553//8553 -f 9800//9800 8553//8553 9801//9801 -f 9801//9801 8553//8553 8556//8556 -f 9801//9801 8556//8556 9802//9802 -f 9802//9802 8556//8556 8661//8661 -f 9802//9802 8661//8661 9803//9803 -f 9803//9803 8661//8661 8663//8663 -f 9803//9803 8663//8663 9804//9804 -f 9804//9804 8663//8663 8665//8665 -f 9804//9804 8665//8665 9805//9805 -f 9805//9805 8665//8665 8666//8666 -f 9805//9805 8666//8666 9806//9806 -f 9806//9806 8666//8666 8650//8650 -f 9806//9806 8650//8650 9807//9807 -f 9807//9807 8650//8650 8649//8649 -f 9807//9807 8649//8649 9808//9808 -f 9808//9808 8649//8649 8658//8658 -f 9808//9808 8658//8658 9797//9797 -f 9797//9797 8658//8658 8548//8548 -f 9797//9797 8548//8548 9798//9798 -f 9798//9798 8548//8548 8550//8550 -f 9136//9136 9809//9809 9131//9131 -f 9131//9131 9809//9809 9810//9810 -f 9131//9131 9810//9810 9132//9132 -f 9132//9132 9810//9810 9811//9811 -f 9132//9132 9811//9811 9133//9133 -f 9133//9133 9811//9811 9812//9812 -f 9133//9133 9812//9812 9134//9134 -f 9134//9134 9812//9812 9813//9813 -f 9134//9134 9813//9813 9135//9135 -f 9135//9135 9813//9813 9814//9814 -f 9135//9135 9814//9814 9139//9139 -f 9139//9139 9814//9814 9815//9815 -f 9139//9139 9815//9815 9140//9140 -f 9140//9140 9815//9815 9816//9816 -f 9140//9140 9816//9816 9141//9141 -f 9141//9141 9816//9816 9817//9817 -f 9141//9141 9817//9817 9144//9144 -f 9144//9144 9817//9817 9818//9818 -f 9144//9144 9818//9818 9142//9142 -f 9142//9142 9818//9818 9819//9819 -f 9142//9142 9819//9819 9138//9138 -f 9138//9138 9819//9819 9820//9820 -f 9138//9138 9820//9820 9136//9136 -f 9136//9136 9820//9820 9809//9809 -f 9810//9810 8745//8745 9811//9811 -f 9811//9811 8745//8745 8755//8755 -f 9811//9811 8755//8755 9812//9812 -f 9812//9812 8755//8755 8754//8754 -f 9812//9812 8754//8754 9813//9813 -f 9813//9813 8754//8754 8753//8753 -f 9813//9813 8753//8753 9814//9814 -f 9814//9814 8753//8753 8752//8752 -f 9814//9814 8752//8752 9815//9815 -f 9815//9815 8752//8752 8751//8751 -f 9815//9815 8751//8751 9816//9816 -f 9816//9816 8751//8751 8750//8750 -f 9816//9816 8750//8750 9817//9817 -f 9817//9817 8750//8750 8747//8747 -f 9817//9817 8747//8747 9818//9818 -f 9818//9818 8747//8747 8748//8748 -f 9818//9818 8748//8748 9819//9819 -f 9819//9819 8748//8748 8749//8749 -f 9819//9819 8749//8749 9820//9820 -f 9820//9820 8749//8749 8744//8744 -f 9820//9820 8744//8744 9809//9809 -f 9809//9809 8744//8744 8743//8743 -f 9809//9809 8743//8743 9810//9810 -f 9810//9810 8743//8743 8745//8745 -f 9145//9145 9821//9821 9146//9146 -f 9146//9146 9821//9821 9822//9822 -f 9146//9146 9822//9822 9147//9147 -f 9147//9147 9822//9822 9823//9823 -f 9147//9147 9823//9823 9150//9150 -f 9150//9150 9823//9823 9824//9824 -f 9150//9150 9824//9824 9151//9151 -f 9151//9151 9824//9824 9825//9825 -f 9151//9151 9825//9825 9152//9152 -f 9152//9152 9825//9825 9826//9826 -f 9152//9152 9826//9826 9157//9157 -f 9157//9157 9826//9826 9827//9827 -f 9157//9157 9827//9827 9158//9158 -f 9158//9158 9827//9827 9828//9828 -f 9158//9158 9828//9828 9160//9160 -f 9160//9160 9828//9828 9829//9829 -f 9160//9160 9829//9829 9156//9156 -f 9156//9156 9829//9829 9830//9830 -f 9156//9156 9830//9830 9155//9155 -f 9155//9155 9830//9830 9831//9831 -f 9155//9155 9831//9831 9148//9148 -f 9148//9148 9831//9831 9832//9832 -f 9148//9148 9832//9832 9145//9145 -f 9145//9145 9832//9832 9821//9821 -f 9822//9822 8689//8689 9823//9823 -f 9823//9823 8689//8689 8688//8688 -f 9823//9823 8688//8688 9824//9824 -f 9824//9824 8688//8688 8686//8686 -f 9824//9824 8686//8686 9825//9825 -f 9825//9825 8686//8686 8693//8693 -f 9825//9825 8693//8693 9826//9826 -f 9826//9826 8693//8693 8692//8692 -f 9826//9826 8692//8692 9827//9827 -f 9827//9827 8692//8692 8697//8697 -f 9827//9827 8697//8697 9828//9828 -f 9828//9828 8697//8697 8696//8696 -f 9828//9828 8696//8696 9829//9829 -f 9829//9829 8696//8696 8695//8695 -f 9829//9829 8695//8695 9830//9830 -f 9830//9830 8695//8695 8694//8694 -f 9830//9830 8694//8694 9831//9831 -f 9831//9831 8694//8694 8682//8682 -f 9831//9831 8682//8682 9832//9832 -f 9832//9832 8682//8682 8681//8681 -f 9832//9832 8681//8681 9821//9821 -f 9821//9821 8681//8681 8684//8684 -f 9821//9821 8684//8684 9822//9822 -f 9822//9822 8684//8684 8689//8689 -f 9288//9288 9287//9287 9290//9290 -f 9288//9288 9290//9290 9833//9833 -f 9833//9833 9290//9290 9291//9291 -f 9833//9833 9291//9291 9834//9834 -f 9834//9834 9291//9291 8356//8356 -f 9834//9834 8356//8356 8355//8355 -f 8382//8382 9835//9835 9836//9836 -f 9835//9835 9837//9837 9838//9838 -f 9837//9837 9286//9286 9493//9493 -f 9837//9837 9493//9493 9838//9838 -f 9838//9838 9493//9493 9494//9494 -f 9838//9838 9494//9494 9839//9839 -f 9839//9839 9494//9494 9495//9495 -f 9839//9839 9495//9495 9840//9840 -f 9840//9840 9495//9495 9496//9496 -f 9840//9840 9496//9496 9841//9841 -f 9841//9841 9496//9496 9497//9497 -f 9841//9841 9497//9497 9842//9842 -f 9842//9842 9497//9497 9498//9498 -f 9842//9842 9498//9498 9843//9843 -f 9843//9843 9498//9498 9499//9499 -f 9843//9843 9499//9499 9844//9844 -f 9844//9844 9499//9499 9500//9500 -f 9844//9844 9500//9500 9845//9845 -f 9845//9845 9500//9500 9501//9501 -f 9845//9845 9501//9501 9846//9846 -f 9846//9846 9501//9501 9288//9288 -f 9846//9846 9288//9288 9833//9833 -f 9835//9835 9838//9838 9836//9836 -f 9836//9836 9838//9838 9839//9839 -f 9836//9836 9839//9839 9847//9847 -f 9847//9847 9839//9839 9840//9840 -f 9847//9847 9840//9840 9848//9848 -f 9848//9848 9840//9840 9841//9841 -f 9848//9848 9841//9841 9849//9849 -f 9849//9849 9841//9841 9842//9842 -f 9849//9849 9842//9842 9850//9850 -f 9850//9850 9842//9842 9843//9843 -f 9850//9850 9843//9843 9851//9851 -f 9851//9851 9843//9843 9844//9844 -f 9851//9851 9844//9844 9852//9852 -f 9852//9852 9844//9844 9845//9845 -f 9852//9852 9845//9845 9853//9853 -f 9853//9853 9845//9845 9846//9846 -f 9853//9853 9846//9846 9854//9854 -f 9854//9854 9846//9846 9833//9833 -f 9854//9854 9833//9833 9834//9834 -f 8382//8382 9836//9836 8383//8383 -f 8383//8383 9836//9836 9847//9847 -f 8383//8383 9847//9847 8374//8374 -f 8374//8374 9847//9847 9848//9848 -f 8374//8374 9848//9848 8541//8541 -f 8541//8541 9848//9848 9849//9849 -f 8541//8541 9849//9849 8542//8542 -f 8542//8542 9849//9849 9850//9850 -f 8542//8542 9850//9850 8545//8545 -f 8545//8545 9850//9850 9851//9851 -f 8545//8545 9851//9851 8546//8546 -f 8546//8546 9851//9851 9852//9852 -f 8546//8546 9852//9852 8547//8547 -f 8547//8547 9852//9852 9853//9853 -f 8547//8547 9853//9853 8544//8544 -f 8544//8544 9853//9853 9854//9854 -f 8544//8544 9854//9854 8543//8543 -f 8543//8543 9854//9854 9834//9834 -f 8543//8543 9834//9834 8355//8355 -f 8664//8664 8662//8662 9855//9855 -f 9285//9285 9286//9286 9837//9837 -f 9285//9285 9837//9837 9856//9856 -f 9856//9856 9837//9837 9835//9835 -f 9856//9856 9835//9835 9855//9855 -f 8382//8382 8380//8380 9835//9835 -f 9835//9835 8380//8380 8378//8378 -f 9835//9835 8378//8378 9855//9855 -f 9855//9855 8378//8378 8652//8652 -f 9855//9855 8652//8652 8664//8664 -f 8559//8559 9857//9857 9858//9858 -f 9857//9857 9859//9859 9860//9860 -f 9859//9859 9284//9284 9502//9502 -f 9859//9859 9502//9502 9860//9860 -f 9860//9860 9502//9502 9503//9503 -f 9860//9860 9503//9503 9861//9861 -f 9861//9861 9503//9503 9504//9504 -f 9861//9861 9504//9504 9862//9862 -f 9862//9862 9504//9504 9505//9505 -f 9862//9862 9505//9505 9863//9863 -f 9863//9863 9505//9505 9506//9506 -f 9863//9863 9506//9506 9864//9864 -f 9864//9864 9506//9506 9507//9507 -f 9864//9864 9507//9507 9865//9865 -f 9865//9865 9507//9507 9508//9508 -f 9865//9865 9508//9508 9866//9866 -f 9866//9866 9508//9508 9509//9509 -f 9866//9866 9509//9509 9867//9867 -f 9867//9867 9509//9509 9510//9510 -f 9867//9867 9510//9510 9868//9868 -f 9868//9868 9510//9510 9285//9285 -f 9868//9868 9285//9285 9856//9856 -f 9857//9857 9860//9860 9858//9858 -f 9858//9858 9860//9860 9861//9861 -f 9858//9858 9861//9861 9869//9869 -f 9869//9869 9861//9861 9862//9862 -f 9869//9869 9862//9862 9870//9870 -f 9870//9870 9862//9862 9863//9863 -f 9870//9870 9863//9863 9871//9871 -f 9871//9871 9863//9863 9864//9864 -f 9871//9871 9864//9864 9872//9872 -f 9872//9872 9864//9864 9865//9865 -f 9872//9872 9865//9865 9873//9873 -f 9873//9873 9865//9865 9866//9866 -f 9873//9873 9866//9866 9874//9874 -f 9874//9874 9866//9866 9867//9867 -f 9874//9874 9867//9867 9875//9875 -f 9875//9875 9867//9867 9868//9868 -f 9875//9875 9868//9868 9876//9876 -f 9876//9876 9868//9868 9856//9856 -f 9876//9876 9856//9856 9855//9855 -f 8559//8559 9858//9858 8560//8560 -f 8560//8560 9858//9858 9869//9869 -f 8560//8560 9869//9869 8561//8561 -f 8561//8561 9869//9869 9870//9870 -f 8561//8561 9870//9870 8769//8769 -f 8769//8769 9870//9870 9871//9871 -f 8769//8769 9871//9871 8554//8554 -f 8554//8554 9871//9871 9872//9872 -f 8554//8554 9872//9872 8555//8555 -f 8555//8555 9872//9872 9873//9873 -f 8555//8555 9873//9873 8558//8558 -f 8558//8558 9873//9873 9874//9874 -f 8558//8558 9874//9874 8557//8557 -f 8557//8557 9874//9874 9875//9875 -f 8557//8557 9875//9875 8659//8659 -f 8659//8659 9875//9875 9876//9876 -f 8659//8659 9876//9876 8660//8660 -f 8660//8660 9876//9876 9855//9855 -f 8660//8660 9855//9855 8662//8662 -f 9283//9283 9284//9284 9859//9859 -f 9283//9283 9859//9859 9358//9358 -f 9358//9358 9859//9859 9857//9857 -f 9358//9358 9857//9857 9357//9357 -f 9357//9357 9857//9857 8559//8559 -f 9357//9357 8559//8559 8565//8565 -f 9352//9352 8562//8562 8450//8450 -f 9352//9352 8450//8450 9347//9347 -f 9347//9347 8450//8450 8457//8457 -f 9347//9347 8457//8457 8459//8459 -f 9342//9342 8441//8441 8440//8440 -f 9342//9342 8440//8440 9337//9337 -f 9337//9337 8440//8440 8351//8351 -f 9337//9337 8351//8351 8506//8506 -f 9332//9332 8468//8468 9327//9327 -f 9327//9327 8468//8468 8474//8474 -f 9327//9327 8474//8474 8476//8476 -f 9317//9317 9322//9322 8781//8781 -f 8781//8781 8787//8787 9317//9317 -f 9317//9317 8787//8787 8363//8363 -f 9317//9317 8363//8363 8362//8362 -f 8510//8510 8509//8509 9310//9310 -f 9310//9310 8509//8509 8758//8758 -f 9310//9310 8758//8758 9305//9305 -f 9305//9305 8758//8758 8515//8515 -f 9305//9305 8515//8515 8514//8514 -f 8434//8434 8526//8526 9280//9280 -f 9279//9279 8520//8520 8427//8427 -f 9279//9279 8427//8427 9280//9280 -f 9280//9280 8427//8427 8431//8431 -f 9280//9280 8431//8431 8434//8434 -f 8708//8708 9267//9267 8707//8707 -f 8707//8707 9267//9267 9266//9266 -f 8707//8707 9266//9266 8706//8706 -f 8706//8706 9266//9266 8705//8705 -f 8704//8704 9220//9220 8703//8703 -f 8703//8703 9220//9220 9219//9219 -f 8703//8703 9219//9219 8702//8702 -f 8534//8534 8539//8539 9214//9214 -f 8534//8534 9214//9214 8533//8533 -f 8533//8533 9214//9214 9213//9213 -f 8533//8533 9213//9213 8532//8532 -f 9207//9207 8698//8698 8699//8699 -f 9207//9207 8699//8699 9208//9208 -f 9208//9208 8699//8699 8700//8700 -f 9208//9208 8700//8700 8701//8701 -f 8854//8854 9209//9209 8855//8855 -f 8855//8855 9209//9209 9210//9210 -f 8864//8864 9206//9206 8865//8865 -f 8865//8865 9206//9206 9205//9205 -f 8865//8865 9205//9205 8862//8862 -f 8867//8867 9215//9215 8868//8868 -f 8868//8868 9215//9215 9216//9216 -f 8852//8852 9212//9212 8853//8853 -f 8853//8853 9212//9212 9211//9211 -f 8873//8873 9221//9221 8874//8874 -f 8874//8874 9221//9221 9222//9222 -f 9183//9183 9218//9218 9182//9182 -f 9182//9182 9218//9218 9217//9217 -f 9051//9051 9268//9268 9052//9052 -f 9052//9052 9268//9268 9269//9269 -f 8890//8890 9265//9265 8889//8889 -f 8889//8889 9265//9265 9264//9264 -f 8973//8973 9350//9350 8972//8972 -f 8972//8972 9350//9350 9349//9349 -f 8969//8969 9354//9354 8958//8958 -f 8958//8958 9354//9354 9348//9348 -f 8958//8958 9348//9348 8959//8959 -f 8964//8964 9340//9340 8965//8965 -f 8965//8965 9340//9340 9339//9339 -f 8960//8960 9344//9344 8961//8961 -f 8961//8961 9344//9344 9338//9338 -f 8950//8950 9330//9330 8949//8949 -f 8949//8949 9330//9330 9329//9329 -f 8944//8944 9334//9334 8945//8945 -f 8945//8945 9334//9334 9328//9328 -f 8849//8849 9320//9320 8850//8850 -f 8850//8850 9320//9320 9319//9319 -f 8933//8933 9324//9324 8932//8932 -f 8932//8932 9324//9324 9318//9318 -f 9175//9175 9281//9281 8899//8899 -f 8899//8899 9281//9281 9282//9282 -f 8899//8899 9282//9282 8898//8898 -f 8900//8900 9278//9278 8901//8901 -f 8901//8901 9278//9278 9277//9277 -f 8913//8913 9312//9312 8912//8912 -f 8912//8912 9312//9312 9306//9306 -f 8918//8918 9308//9308 8916//8916 -f 8916//8916 9308//9308 9307//9307 -f 9356//9356 8564//8564 9355//9355 -f 9355//9355 8564//8564 8563//8563 -f 9346//9346 8445//8445 9345//9345 -f 9345//9345 8445//8445 8443//8443 -f 9336//9336 8507//8507 9335//9335 -f 9335//9335 8507//8507 8470//8470 -f 9326//9326 8465//8465 9325//9325 -f 9325//9325 8465//8465 8463//8463 -f 9316//9316 8361//8361 9315//9315 -f 9315//9315 8361//8361 8513//8513 -f 9314//9314 8513//8513 9313//9313 -f 9313//9313 8513//8513 8511//8511 -f 9292//9292 8358//8358 9289//9289 -f 9289//9289 8358//8358 8540//8540 -f 9294//9294 8536//8536 9293//9293 -f 9293//9293 8536//8536 8386//8386 -f 9296//9296 8411//8411 9295//9295 -f 9295//9295 8411//8411 8531//8531 -f 9298//9298 8567//8567 9297//9297 -f 9297//9297 8567//8567 8402//8402 -f 9302//9302 8527//8527 9301//9301 -f 9301//9301 8527//8527 8528//8528 -f 9300//9300 8528//8528 9299//9299 -f 9299//9299 8528//8528 8525//8525 -f 8521//8521 9303//9303 8522//8522 -f 8522//8522 9303//9303 9304//9304 -f 8522//8522 9304//9304 8517//8517 -f 8517//8517 9304//9304 8516//8516 -f 9516//9516 8621//8621 8690//8690 -f 8691//8691 8608//8608 9513//9513 -f 8691//8691 9513//9513 8690//8690 -f 8690//8690 9513//9513 9514//9514 -f 8690//8690 9514//9514 9516//9516 -f 8617//8617 9515//9515 8613//8613 -f 8613//8613 9515//9515 9511//9511 -f 8613//8613 9511//9511 8614//8614 -f 8614//8614 9511//9511 9512//9512 -f 8614//8614 9512//9512 8740//8740 -f 8631//8631 8629//8629 9522//9522 -f 8730//8730 8632//8632 9518//9518 -f 9518//9518 8632//8632 8631//8631 -f 9518//9518 8631//8631 9519//9519 -f 9519//9519 8631//8631 9522//9522 -f 9521//9521 8624//8624 9520//9520 -f 9520//9520 8624//8624 8623//8623 -f 9520//9520 8623//8623 9517//9517 -f 9517//9517 8623//8623 8353//8353 -f 9517//9517 8353//8353 8352//8352 -f 9515//9515 8617//8617 8616//8616 -f 9515//9515 8616//8616 9516//9516 -f 9516//9516 8616//8616 8619//8619 -f 9516//9516 8619//8619 8621//8621 -f 9517//9517 8352//8352 8732//8732 -f 9517//9517 8732//8732 9518//9518 -f 9518//9518 8732//8732 8731//8731 -f 9518//9518 8731//8731 8730//8730 -f 9362//9362 8489//8489 8488//8488 -f 9362//9362 8488//8488 9877//9877 -f 9877//9877 8488//8488 8487//8487 -f 9877//9877 8487//8487 9878//9878 -f 9878//9878 8487//8487 8493//8493 -f 9878//9878 8493//8493 9364//9364 -f 9370//9370 9368//9368 9879//9879 -f 9370//9370 9879//9879 9880//9880 -f 9880//9880 9879//9879 9881//9881 -f 9880//9880 9881//9881 9882//9882 -f 9882//9882 9881//9881 9361//9361 -f 9882//9882 9361//9361 9362//9362 -f 9359//9359 8485//8485 8484//8484 -f 9359//9359 8484//8484 9883//9883 -f 9883//9883 8484//8484 8795//8795 -f 9883//9883 8795//8795 9884//9884 -f 9884//9884 8795//8795 8491//8491 -f 9884//9884 8491//8491 9361//9361 -f 9364//9364 9885//9885 9886//9886 -f 9370//9370 9880//9880 9887//9887 -f 9885//9885 9888//9888 9886//9886 -f 9886//9886 9888//9888 9887//9887 -f 9886//9886 9887//9887 9889//9889 -f 9889//9889 9887//9887 9880//9880 -f 9889//9889 9880//9880 9882//9882 -f 9364//9364 9886//9886 9878//9878 -f 9878//9878 9886//9886 9889//9889 -f 9878//9878 9889//9889 9877//9877 -f 9877//9877 9889//9889 9882//9882 -f 9877//9877 9882//9882 9362//9362 -f 9888//9888 9370//9370 9887//9887 -f 9885//9885 9890//9890 9888//9888 -f 9888//9888 9890//9890 9370//9370 -f 9361//9361 9881//9881 9891//9891 -f 9368//9368 9892//9892 9893//9893 -f 9881//9881 9894//9894 9891//9891 -f 9891//9891 9894//9894 9893//9893 -f 9891//9891 9893//9893 9895//9895 -f 9895//9895 9893//9893 9892//9892 -f 9895//9895 9892//9892 9896//9896 -f 9361//9361 9891//9891 9884//9884 -f 9884//9884 9891//9891 9895//9895 -f 9884//9884 9895//9895 9883//9883 -f 9883//9883 9895//9895 9896//9896 -f 9883//9883 9896//9896 9359//9359 -f 9894//9894 9368//9368 9893//9893 -f 9881//9881 9879//9879 9894//9894 -f 9894//9894 9879//9879 9368//9368 -f 9363//9363 8501//8501 8499//8499 -f 9363//9363 8499//8499 9897//9897 -f 9897//9897 8499//8499 8498//8498 -f 9897//9897 8498//8498 9898//9898 -f 9898//9898 8498//8498 8496//8496 -f 9898//9898 8496//8496 9366//9366 -f 9369//9369 9370//9370 9890//9890 -f 9369//9369 9890//9890 9899//9899 -f 9899//9899 9890//9890 9885//9885 -f 9899//9899 9885//9885 9900//9900 -f 9900//9900 9885//9885 9364//9364 -f 9900//9900 9364//9364 9363//9363 -f 9368//9368 9367//9367 9901//9901 -f 9368//9368 9901//9901 9892//9892 -f 9892//9892 9901//9901 9902//9902 -f 9892//9892 9902//9902 9896//9896 -f 9896//9896 9902//9902 9360//9360 -f 9896//9896 9360//9360 9359//9359 -f 9365//9365 8600//8600 8598//8598 -f 9365//9365 8598//8598 9903//9903 -f 9903//9903 8598//8598 8519//8519 -f 9903//9903 8519//8519 9904//9904 -f 9904//9904 8519//8519 8505//8505 -f 9904//9904 8505//8505 9360//9360 -f 9366//9366 9905//9905 9906//9906 -f 9369//9369 9899//9899 9907//9907 -f 9905//9905 9908//9908 9906//9906 -f 9906//9906 9908//9908 9907//9907 -f 9906//9906 9907//9907 9909//9909 -f 9909//9909 9907//9907 9899//9899 -f 9909//9909 9899//9899 9900//9900 -f 9366//9366 9906//9906 9898//9898 -f 9898//9898 9906//9906 9909//9909 -f 9898//9898 9909//9909 9897//9897 -f 9897//9897 9909//9909 9900//9900 -f 9897//9897 9900//9900 9363//9363 -f 9908//9908 9369//9369 9907//9907 -f 9905//9905 9910//9910 9908//9908 -f 9908//9908 9910//9910 9369//9369 -f 9360//9360 9902//9902 9911//9911 -f 9367//9367 9912//9912 9913//9913 -f 9902//9902 9914//9914 9911//9911 -f 9911//9911 9914//9914 9913//9913 -f 9911//9911 9913//9913 9915//9915 -f 9915//9915 9913//9913 9912//9912 -f 9915//9915 9912//9912 9916//9916 -f 9360//9360 9911//9911 9904//9904 -f 9904//9904 9911//9911 9915//9915 -f 9904//9904 9915//9915 9903//9903 -f 9903//9903 9915//9915 9916//9916 -f 9903//9903 9916//9916 9365//9365 -f 9914//9914 9367//9367 9913//9913 -f 9902//9902 9901//9901 9914//9914 -f 9914//9914 9901//9901 9367//9367 -f 9367//9367 9369//9369 9910//9910 -f 9367//9367 9910//9910 9912//9912 -f 9912//9912 9910//9910 9905//9905 -f 9912//9912 9905//9905 9916//9916 -f 9916//9916 9905//9905 9366//9366 -f 9916//9916 9366//9366 9365//9365 -f 9374//9374 8592//8592 8591//8591 -f 9374//9374 8591//8591 9917//9917 -f 9917//9917 8591//8591 8590//8590 -f 9917//9917 8590//8590 9918//9918 -f 9918//9918 8590//8590 8589//8589 -f 9918//9918 8589//8589 9375//9375 -f 9373//9373 9374//9374 9919//9919 -f 9373//9373 9919//9919 9920//9920 -f 9920//9920 9919//9919 9921//9921 -f 9920//9920 9921//9921 9922//9922 -f 9922//9922 9921//9921 9382//9382 -f 9922//9922 9382//9382 9380//9380 -f 9371//9371 8575//8575 8577//8577 -f 9371//9371 8577//8577 9923//9923 -f 9923//9923 8577//8577 8586//8586 -f 9923//9923 8586//8586 9924//9924 -f 9924//9924 8586//8586 8588//8588 -f 9924//9924 8588//8588 9373//9373 -f 9375//9375 9925//9925 9926//9926 -f 9382//9382 9921//9921 9927//9927 -f 9925//9925 9928//9928 9926//9926 -f 9926//9926 9928//9928 9927//9927 -f 9926//9926 9927//9927 9929//9929 -f 9929//9929 9927//9927 9921//9921 -f 9929//9929 9921//9921 9919//9919 -f 9375//9375 9926//9926 9918//9918 -f 9918//9918 9926//9926 9929//9929 -f 9918//9918 9929//9929 9917//9917 -f 9917//9917 9929//9929 9919//9919 -f 9917//9917 9919//9919 9374//9374 -f 9928//9928 9382//9382 9927//9927 -f 9925//9925 9930//9930 9928//9928 -f 9928//9928 9930//9930 9382//9382 -f 9373//9373 9920//9920 9931//9931 -f 9380//9380 9932//9932 9933//9933 -f 9920//9920 9934//9934 9931//9931 -f 9931//9931 9934//9934 9933//9933 -f 9931//9931 9933//9933 9935//9935 -f 9935//9935 9933//9933 9932//9932 -f 9935//9935 9932//9932 9936//9936 -f 9373//9373 9931//9931 9924//9924 -f 9924//9924 9931//9931 9935//9935 -f 9924//9924 9935//9935 9923//9923 -f 9923//9923 9935//9935 9936//9936 -f 9923//9923 9936//9936 9371//9371 -f 9934//9934 9380//9380 9933//9933 -f 9920//9920 9922//9922 9934//9934 -f 9934//9934 9922//9922 9380//9380 -f 9376//9376 8594//8594 8599//8599 -f 9376//9376 8599//8599 9937//9937 -f 9937//9937 8599//8599 8607//8607 -f 9937//9937 8607//8607 9938//9938 -f 9938//9938 8607//8607 8606//8606 -f 9938//9938 8606//8606 9377//9377 -f 9375//9375 9376//9376 9939//9939 -f 9375//9375 9939//9939 9925//9925 -f 9925//9925 9939//9939 9940//9940 -f 9925//9925 9940//9940 9930//9930 -f 9930//9930 9940//9940 9381//9381 -f 9930//9930 9381//9381 9382//9382 -f 9372//9372 9371//9371 9936//9936 -f 9372//9372 9936//9936 9941//9941 -f 9941//9941 9936//9936 9932//9932 -f 9941//9941 9932//9932 9942//9942 -f 9942//9942 9932//9932 9380//9380 -f 9942//9942 9380//9380 9379//9379 -f 9378//9378 8601//8601 8405//8405 -f 9378//9378 8405//8405 9943//9943 -f 9943//9943 8405//8405 8404//8404 -f 9943//9943 8404//8404 9944//9944 -f 9944//9944 8404//8404 8572//8572 -f 9944//9944 8572//8572 9372//9372 -f 9377//9377 9945//9945 9946//9946 -f 9381//9381 9940//9940 9947//9947 -f 9945//9945 9948//9948 9946//9946 -f 9946//9946 9948//9948 9947//9947 -f 9946//9946 9947//9947 9949//9949 -f 9949//9949 9947//9947 9940//9940 -f 9949//9949 9940//9940 9939//9939 -f 9377//9377 9946//9946 9938//9938 -f 9938//9938 9946//9946 9949//9949 -f 9938//9938 9949//9949 9937//9937 -f 9937//9937 9949//9949 9939//9939 -f 9937//9937 9939//9939 9376//9376 -f 9948//9948 9381//9381 9947//9947 -f 9945//9945 9950//9950 9948//9948 -f 9948//9948 9950//9950 9381//9381 -f 9372//9372 9941//9941 9951//9951 -f 9379//9379 9952//9952 9953//9953 -f 9941//9941 9954//9954 9951//9951 -f 9951//9951 9954//9954 9953//9953 -f 9951//9951 9953//9953 9955//9955 -f 9955//9955 9953//9953 9952//9952 -f 9955//9955 9952//9952 9956//9956 -f 9372//9372 9951//9951 9944//9944 -f 9944//9944 9951//9951 9955//9955 -f 9944//9944 9955//9955 9943//9943 -f 9943//9943 9955//9955 9956//9956 -f 9943//9943 9956//9956 9378//9378 -f 9954//9954 9379//9379 9953//9953 -f 9941//9941 9942//9942 9954//9954 -f 9954//9954 9942//9942 9379//9379 -f 9377//9377 9378//9378 9956//9956 -f 9377//9377 9956//9956 9945//9945 -f 9945//9945 9956//9956 9952//9952 -f 9945//9945 9952//9952 9950//9950 -f 9950//9950 9952//9952 9379//9379 -f 9950//9950 9379//9379 9381//9381 -f 9589//9589 9957//9957 9590//9590 -f 9590//9590 9957//9957 9958//9958 -f 9590//9590 9958//9958 9611//9611 -f 9611//9611 9958//9958 9959//9959 -f 9611//9611 9959//9959 9612//9612 -f 9612//9612 9959//9959 9960//9960 -f 9612//9612 9960//9960 9613//9613 -f 9613//9613 9960//9960 9961//9961 -f 9613//9613 9961//9961 9567//9567 -f 9567//9567 9961//9961 9962//9962 -f 9567//9567 9962//9962 9568//9568 -f 9568//9568 9962//9962 9963//9963 -f 9568//9568 9963//9963 9586//9586 -f 9586//9586 9963//9963 9964//9964 -f 9586//9586 9964//9964 9587//9587 -f 9587//9587 9964//9964 9965//9965 -f 9587//9587 9965//9965 9608//9608 -f 9608//9608 9965//9965 9966//9966 -f 9608//9608 9966//9966 9609//9609 -f 9609//9609 9966//9966 9967//9967 -f 9609//9609 9967//9967 9610//9610 -f 9610//9610 9967//9967 9968//9968 -f 9610//9610 9968//9968 9582//9582 -f 9582//9582 9968//9968 9969//9969 -f 9582//9582 9969//9969 9583//9583 -f 9583//9583 9969//9969 9970//9970 -f 9583//9583 9970//9970 9605//9605 -f 9605//9605 9970//9970 9971//9971 -f 9605//9605 9971//9971 9606//9606 -f 9606//9606 9971//9971 9972//9972 -f 9606//9606 9972//9972 9607//9607 -f 9607//9607 9972//9972 9973//9973 -f 9607//9607 9973//9973 9604//9604 -f 9604//9604 9973//9973 9974//9974 -f 9604//9604 9974//9974 9602//9602 -f 9602//9602 9974//9974 9975//9975 -f 9602//9602 9975//9975 9581//9581 -f 9581//9581 9975//9975 9976//9976 -f 9581//9581 9976//9976 9579//9579 -f 9579//9579 9976//9976 9977//9977 -f 9579//9579 9977//9977 9577//9577 -f 9577//9577 9977//9977 9978//9978 -f 9577//9577 9978//9978 9599//9599 -f 9599//9599 9978//9978 9979//9979 -f 9599//9599 9979//9979 9600//9600 -f 9600//9600 9979//9979 9980//9980 -f 9600//9600 9980//9980 9601//9601 -f 9601//9601 9980//9980 9981//9981 -f 9601//9601 9981//9981 9575//9575 -f 9575//9575 9981//9981 9982//9982 -f 9575//9575 9982//9982 9576//9576 -f 9576//9576 9982//9982 9983//9983 -f 9576//9576 9983//9983 9573//9573 -f 9573//9573 9983//9983 9984//9984 -f 9573//9573 9984//9984 9617//9617 -f 9617//9617 9984//9984 9985//9985 -f 9617//9617 9985//9985 9618//9618 -f 9618//9618 9985//9985 9986//9986 -f 9618//9618 9986//9986 9619//9619 -f 9619//9619 9986//9986 9987//9987 -f 9619//9619 9987//9987 9595//9595 -f 9595//9595 9987//9987 9988//9988 -f 9595//9595 9988//9988 9596//9596 -f 9596//9596 9988//9988 9989//9989 -f 9596//9596 9989//9989 9614//9614 -f 9614//9614 9989//9989 9990//9990 -f 9614//9614 9990//9990 9615//9615 -f 9615//9615 9990//9990 9991//9991 -f 9615//9615 9991//9991 9616//9616 -f 9616//9616 9991//9991 9992//9992 -f 9616//9616 9992//9992 9593//9593 -f 9593//9593 9992//9992 9993//9993 -f 9593//9593 9993//9993 9594//9594 -f 9594//9594 9993//9993 9994//9994 -f 9594//9594 9994//9994 9563//9563 -f 9563//9563 9994//9994 9995//9995 -f 9563//9563 9995//9995 9564//9564 -f 9564//9564 9995//9995 9996//9996 -f 9564//9564 9996//9996 9589//9589 -f 9589//9589 9996//9996 9957//9957 -f 9996//9996 9997//9997 9957//9957 -f 9957//9957 9997//9997 9998//9998 -f 9957//9957 9998//9998 9958//9958 -f 9958//9958 9998//9998 9999//9999 -f 9958//9958 9999//9999 9959//9959 -f 9959//9959 9999//9999 10000//10000 -f 9959//9959 10000//10000 9960//9960 -f 9960//9960 10000//10000 10001//10001 -f 9960//9960 10001//10001 9961//9961 -f 9961//9961 10001//10001 10002//10002 -f 9961//9961 10002//10002 9962//9962 -f 9962//9962 10002//10002 10003//10003 -f 9962//9962 10003//10003 9963//9963 -f 9963//9963 10003//10003 10004//10004 -f 9963//9963 10004//10004 9964//9964 -f 9964//9964 10004//10004 10005//10005 -f 9964//9964 10005//10005 9965//9965 -f 9965//9965 10005//10005 10006//10006 -f 9965//9965 10006//10006 9966//9966 -f 9966//9966 10006//10006 10007//10007 -f 9966//9966 10007//10007 9967//9967 -f 9967//9967 10007//10007 10008//10008 -f 9967//9967 10008//10008 9968//9968 -f 9968//9968 10008//10008 10009//10009 -f 9968//9968 10009//10009 9969//9969 -f 9969//9969 10009//10009 10010//10010 -f 9969//9969 10010//10010 9970//9970 -f 9970//9970 10010//10010 10011//10011 -f 9970//9970 10011//10011 9971//9971 -f 9971//9971 10011//10011 10012//10012 -f 9971//9971 10012//10012 9972//9972 -f 9972//9972 10012//10012 10013//10013 -f 9972//9972 10013//10013 9973//9973 -f 9973//9973 10013//10013 10014//10014 -f 9973//9973 10014//10014 9974//9974 -f 9974//9974 10014//10014 10015//10015 -f 9974//9974 10015//10015 9975//9975 -f 9975//9975 10015//10015 10016//10016 -f 9975//9975 10016//10016 9976//9976 -f 9976//9976 10016//10016 10017//10017 -f 9976//9976 10017//10017 9977//9977 -f 9977//9977 10017//10017 10018//10018 -f 9977//9977 10018//10018 9978//9978 -f 9978//9978 10018//10018 10019//10019 -f 9978//9978 10019//10019 9979//9979 -f 9979//9979 10019//10019 10020//10020 -f 9979//9979 10020//10020 9980//9980 -f 9980//9980 10020//10020 10021//10021 -f 9980//9980 10021//10021 9981//9981 -f 9981//9981 10021//10021 10022//10022 -f 9981//9981 10022//10022 9982//9982 -f 9982//9982 10022//10022 10023//10023 -f 9982//9982 10023//10023 9983//9983 -f 9983//9983 10023//10023 10024//10024 -f 9983//9983 10024//10024 9984//9984 -f 9984//9984 10024//10024 10025//10025 -f 9984//9984 10025//10025 9985//9985 -f 9985//9985 10025//10025 10026//10026 -f 9985//9985 10026//10026 9986//9986 -f 9986//9986 10026//10026 10027//10027 -f 9986//9986 10027//10027 9987//9987 -f 9987//9987 10027//10027 10028//10028 -f 9987//9987 10028//10028 9988//9988 -f 9988//9988 10028//10028 10029//10029 -f 9988//9988 10029//10029 9989//9989 -f 9989//9989 10029//10029 10030//10030 -f 9989//9989 10030//10030 9990//9990 -f 9990//9990 10030//10030 10031//10031 -f 9990//9990 10031//10031 9991//9991 -f 9991//9991 10031//10031 10032//10032 -f 9991//9991 10032//10032 9992//9992 -f 9992//9992 10032//10032 10033//10033 -f 9992//9992 10033//10033 9993//9993 -f 9993//9993 10033//10033 10034//10034 -f 9993//9993 10034//10034 9994//9994 -f 9994//9994 10034//10034 10035//10035 -f 9994//9994 10035//10035 9995//9995 -f 9995//9995 10035//10035 10036//10036 -f 9995//9995 10036//10036 9996//9996 -f 9996//9996 10036//10036 9997//9997 -f 10036//10036 9542//9542 9997//9997 -f 9997//9997 9542//9542 9545//9545 -f 9997//9997 9545//9545 9998//9998 -f 9998//9998 9545//9545 9544//9544 -f 9998//9998 9544//9544 9999//9999 -f 9999//9999 9544//9544 9547//9547 -f 9999//9999 9547//9547 10000//10000 -f 10000//10000 9547//9547 9546//9546 -f 10000//10000 9546//9546 10001//10001 -f 10001//10001 9546//9546 9549//9549 -f 10001//10001 9549//9549 10002//10002 -f 10002//10002 9549//9549 9548//9548 -f 10002//10002 9548//9548 10003//10003 -f 10003//10003 9548//9548 9551//9551 -f 10003//10003 9551//9551 10004//10004 -f 10004//10004 9551//9551 9550//9550 -f 10004//10004 9550//9550 10005//10005 -f 10005//10005 9550//9550 9553//9553 -f 10005//10005 9553//9553 10006//10006 -f 10006//10006 9553//9553 9552//9552 -f 10006//10006 9552//9552 10007//10007 -f 10007//10007 9552//9552 9555//9555 -f 10007//10007 9555//9555 10008//10008 -f 10008//10008 9555//9555 9554//9554 -f 10008//10008 9554//9554 10009//10009 -f 10009//10009 9554//9554 9557//9557 -f 10009//10009 9557//9557 10010//10010 -f 10010//10010 9557//9557 9556//9556 -f 10010//10010 9556//9556 10011//10011 -f 10011//10011 9556//9556 9559//9559 -f 10011//10011 9559//9559 10012//10012 -f 10012//10012 9559//9559 9558//9558 -f 10012//10012 9558//9558 10013//10013 -f 10013//10013 9558//9558 9562//9562 -f 10013//10013 9562//9562 10014//10014 -f 10014//10014 9562//9562 9561//9561 -f 10014//10014 9561//9561 10015//10015 -f 10015//10015 9561//9561 9560//9560 -f 10015//10015 9560//9560 10016//10016 -f 10016//10016 9560//9560 9523//9523 -f 10016//10016 9523//9523 10017//10017 -f 10017//10017 9523//9523 9525//9525 -f 10017//10017 9525//9525 10018//10018 -f 10018//10018 9525//9525 9524//9524 -f 10018//10018 9524//9524 10019//10019 -f 10019//10019 9524//9524 9527//9527 -f 10019//10019 9527//9527 10020//10020 -f 10020//10020 9527//9527 9526//9526 -f 10020//10020 9526//9526 10021//10021 -f 10021//10021 9526//9526 9529//9529 -f 10021//10021 9529//9529 10022//10022 -f 10022//10022 9529//9529 9528//9528 -f 10022//10022 9528//9528 10023//10023 -f 10023//10023 9528//9528 9531//9531 -f 10023//10023 9531//9531 10024//10024 -f 10024//10024 9531//9531 9530//9530 -f 10024//10024 9530//9530 10025//10025 -f 10025//10025 9530//9530 9533//9533 -f 10025//10025 9533//9533 10026//10026 -f 10026//10026 9533//9533 9532//9532 -f 10026//10026 9532//9532 10027//10027 -f 10027//10027 9532//9532 9535//9535 -f 10027//10027 9535//9535 10028//10028 -f 10028//10028 9535//9535 9534//9534 -f 10028//10028 9534//9534 10029//10029 -f 10029//10029 9534//9534 9537//9537 -f 10029//10029 9537//9537 10030//10030 -f 10030//10030 9537//9537 9536//9536 -f 10030//10030 9536//9536 10031//10031 -f 10031//10031 9536//9536 9539//9539 -f 10031//10031 9539//9539 10032//10032 -f 10032//10032 9539//9539 9538//9538 -f 10032//10032 9538//9538 10033//10033 -f 10033//10033 9538//9538 9541//9541 -f 10033//10033 9541//9541 10034//10034 -f 10034//10034 9541//9541 9540//9540 -f 10034//10034 9540//9540 10035//10035 -f 10035//10035 9540//9540 9543//9543 -f 10035//10035 9543//9543 10036//10036 -f 10036//10036 9543//9543 9542//9542 -f 10037//10037 10038//10038 10039//10039 -f 10040//10040 10041//10041 10038//10038 -f 10038//10038 10041//10041 10042//10042 -f 10038//10038 10042//10042 10039//10039 -f 10043//10043 10044//10044 10040//10040 -f 10040//10040 10044//10044 10045//10045 -f 10040//10040 10045//10045 10041//10041 -f 10046//10046 10047//10047 10043//10043 -f 10043//10043 10047//10047 10048//10048 -f 10043//10043 10048//10048 10044//10044 -f 10049//10049 10050//10050 10046//10046 -f 10046//10046 10050//10050 10051//10051 -f 10046//10046 10051//10051 10047//10047 -f 10052//10052 10053//10053 10049//10049 -f 10049//10049 10053//10053 10054//10054 -f 10049//10049 10054//10054 10050//10050 -f 10055//10055 10056//10056 10052//10052 -f 10052//10052 10056//10056 10057//10057 -f 10052//10052 10057//10057 10053//10053 -f 10058//10058 10059//10059 10055//10055 -f 10055//10055 10059//10059 10060//10060 -f 10055//10055 10060//10060 10056//10056 -f 10061//10061 10062//10062 10058//10058 -f 10058//10058 10062//10062 10063//10063 -f 10058//10058 10063//10063 10059//10059 -f 10064//10064 10065//10065 10061//10061 -f 10061//10061 10065//10065 10066//10066 -f 10061//10061 10066//10066 10062//10062 -f 10067//10067 10068//10068 10064//10064 -f 10064//10064 10068//10068 10069//10069 -f 10064//10064 10069//10069 10065//10065 -f 10070//10070 10071//10071 10067//10067 -f 10067//10067 10071//10071 10072//10072 -f 10067//10067 10072//10072 10068//10068 -f 10073//10073 10074//10074 10070//10070 -f 10070//10070 10074//10074 10075//10075 -f 10070//10070 10075//10075 10071//10071 -f 10076//10076 10077//10077 10073//10073 -f 10073//10073 10077//10077 10078//10078 -f 10073//10073 10078//10078 10074//10074 -f 10079//10079 10080//10080 10076//10076 -f 10076//10076 10080//10080 10081//10081 -f 10076//10076 10081//10081 10077//10077 -f 10082//10082 10083//10083 10079//10079 -f 10079//10079 10083//10083 10084//10084 -f 10079//10079 10084//10084 10080//10080 -f 10085//10085 10086//10086 10082//10082 -f 10082//10082 10086//10086 10087//10087 -f 10082//10082 10087//10087 10083//10083 -f 10088//10088 10089//10089 10085//10085 -f 10085//10085 10089//10089 10090//10090 -f 10085//10085 10090//10090 10086//10086 -f 10039//10039 10091//10091 10037//10037 -f 10037//10037 10091//10091 10092//10092 -f 10037//10037 10092//10092 10088//10088 -f 10088//10088 10092//10092 10093//10093 -f 10088//10088 10093//10093 10089//10089 -f 10094//10094 10095//10095 10096//10096 -f 10097//10097 10098//10098 10099//10099 -f 10099//10099 10098//10098 10100//10100 -f 10101//10101 10102//10102 10103//10103 -f 10104//10104 10105//10105 10106//10106 -f 10107//10107 10108//10108 10109//10109 -f 10109//10109 10108//10108 10110//10110 -f 10109//10109 10110//10110 10111//10111 -f 10112//10112 10113//10113 10107//10107 -f 10107//10107 10113//10113 10114//10114 -f 10107//10107 10114//10114 10108//10108 -f 10103//10103 10115//10115 10101//10101 -f 10101//10101 10115//10115 10116//10116 -f 10101//10101 10116//10116 10117//10117 -f 10111//10111 10110//10110 10100//10100 -f 10100//10100 10110//10110 10118//10118 -f 10100//10100 10118//10118 10099//10099 -f 10119//10119 10120//10120 10121//10121 -f 10121//10121 10120//10120 10122//10122 -f 10121//10121 10122//10122 10112//10112 -f 10112//10112 10122//10122 10123//10123 -f 10112//10112 10123//10123 10113//10113 -f 10124//10124 10125//10125 10121//10121 -f 10121//10121 10125//10125 10126//10126 -f 10121//10121 10126//10126 10119//10119 -f 10127//10127 10125//10125 10128//10128 -f 10128//10128 10125//10125 10124//10124 -f 10128//10128 10124//10124 10129//10129 -f 10129//10129 10124//10124 10130//10130 -f 10129//10129 10130//10130 10131//10131 -f 10131//10131 10130//10130 10105//10105 -f 10131//10131 10105//10105 10132//10132 -f 10132//10132 10105//10105 10104//10104 -f 10127//10127 10133//10133 10125//10125 -f 10125//10125 10133//10133 10134//10134 -f 10125//10125 10134//10134 10135//10135 -f 10135//10135 10134//10134 10136//10136 -f 10135//10135 10136//10136 10116//10116 -f 10116//10116 10136//10136 10137//10137 -f 10116//10116 10137//10137 10117//10117 -f 10126//10126 10138//10138 10119//10119 -f 10119//10119 10138//10138 10139//10139 -f 10119//10119 10139//10139 10140//10140 -f 10140//10140 10139//10139 10141//10141 -f 10140//10140 10141//10141 10142//10142 -f 10142//10142 10141//10141 10143//10143 -f 10142//10142 10143//10143 10144//10144 -f 10144//10144 10143//10143 10145//10145 -f 10144//10144 10145//10145 10102//10102 -f 10102//10102 10145//10145 10146//10146 -f 10102//10102 10146//10146 10103//10103 -f 10147//10147 10148//10148 10149//10149 -f 10150//10150 10151//10151 10152//10152 -f 10153//10153 10096//10096 10154//10154 -f 10152//10152 10151//10151 10148//10148 -f 10148//10148 10151//10151 10155//10155 -f 10148//10148 10155//10155 10149//10149 -f 10095//10095 10156//10156 10096//10096 -f 10096//10096 10156//10156 10157//10157 -f 10096//10096 10157//10157 10154//10154 -f 10101//10101 10158//10158 10102//10102 -f 10102//10102 10158//10158 10159//10159 -f 10102//10102 10159//10159 10160//10160 -f 10160//10160 10159//10159 10161//10161 -f 10152//10152 10162//10162 10150//10150 -f 10150//10150 10162//10162 10163//10163 -f 10150//10150 10163//10163 10095//10095 -f 10095//10095 10163//10163 10164//10164 -f 10095//10095 10164//10164 10156//10156 -f 10101//10101 10165//10165 10158//10158 -f 10158//10158 10165//10165 10166//10166 -f 10158//10158 10166//10166 10167//10167 -f 10167//10167 10166//10166 10168//10168 -f 10167//10167 10168//10168 10154//10154 -f 10154//10154 10168//10168 10169//10169 -f 10154//10154 10169//10169 10153//10153 -f 10149//10149 10170//10170 10147//10147 -f 10147//10147 10170//10170 10171//10171 -f 10147//10147 10171//10171 10159//10159 -f 10159//10159 10171//10171 10172//10172 -f 10159//10159 10172//10172 10161//10161 -f 10173//10173 10174//10174 10175//10175 -f 10175//10175 10176//10176 10173//10173 -f 10173//10173 10176//10176 10177//10177 -f 10173//10173 10177//10177 10096//10096 -f 10096//10096 10177//10177 10178//10178 -f 10096//10096 10178//10178 10094//10094 -f 10179//10179 10180//10180 10181//10181 -f 10181//10181 10180//10180 10104//10104 -f 10181//10181 10104//10104 10182//10182 -f 10179//10179 10181//10181 10183//10183 -f 10183//10183 10181//10181 10184//10184 -f 10183//10183 10184//10184 10185//10185 -f 10185//10185 10184//10184 10186//10186 -f 10185//10185 10186//10186 10187//10187 -f 10187//10187 10186//10186 10173//10173 -f 10173//10173 10186//10186 10188//10188 -f 10173//10173 10188//10188 10174//10174 -f 10188//10188 10189//10189 10174//10174 -f 10174//10174 10189//10189 10190//10190 -f 10174//10174 10190//10190 10191//10191 -f 10191//10191 10190//10190 10192//10192 -f 10191//10191 10192//10192 10193//10193 -f 10193//10193 10192//10192 10194//10194 -f 10193//10193 10194//10194 10195//10195 -f 10195//10195 10194//10194 10196//10196 -f 10195//10195 10196//10196 10197//10197 -f 10197//10197 10196//10196 10198//10198 -f 10197//10197 10198//10198 10199//10199 -f 10199//10199 10198//10198 10200//10200 -f 10106//10106 10097//10097 10104//10104 -f 10104//10104 10097//10097 10099//10099 -f 10104//10104 10099//10099 10182//10182 -f 10182//10182 10099//10099 10201//10201 -f 10182//10182 10201//10201 10202//10202 -f 10202//10202 10203//10203 10182//10182 -f 10182//10182 10203//10203 10204//10204 -f 10182//10182 10204//10204 10200//10200 -f 10200//10200 10204//10204 10205//10205 -f 10200//10200 10205//10205 10199//10199 -f 10206//10206 10207//10207 10208//10208 -f 10208//10208 10207//10207 10209//10209 -f 10208//10208 10209//10209 10210//10210 -f 10210//10210 10209//10209 10211//10211 -f 10210//10210 10211//10211 10212//10212 -f 10212//10212 10211//10211 10213//10213 -f 10212//10212 10213//10213 10214//10214 -f 10214//10214 10213//10213 10215//10215 -f 10214//10214 10215//10215 10216//10216 -f 10216//10216 10215//10215 10217//10217 -f 10216//10216 10217//10217 10218//10218 -f 10218//10218 10217//10217 10219//10219 -f 10218//10218 10219//10219 10220//10220 -f 10220//10220 10219//10219 10221//10221 -f 10220//10220 10221//10221 10222//10222 -f 10222//10222 10221//10221 10223//10223 -f 10222//10222 10223//10223 10224//10224 -f 10224//10224 10223//10223 10225//10225 -f 10224//10224 10225//10225 10226//10226 -f 10226//10226 10225//10225 10227//10227 -f 10226//10226 10227//10227 10228//10228 -f 10228//10228 10227//10227 10229//10229 -f 10228//10228 10229//10229 10230//10230 -f 10230//10230 10229//10229 10231//10231 -f 10230//10230 10231//10231 10232//10232 -f 10232//10232 10231//10231 10233//10233 -f 10232//10232 10233//10233 10234//10234 -f 10234//10234 10233//10233 10235//10235 -f 10234//10234 10235//10235 10236//10236 -f 10236//10236 10235//10235 10237//10237 -f 10236//10236 10237//10237 10238//10238 -f 10238//10238 10237//10237 10239//10239 -f 10238//10238 10239//10239 10240//10240 -f 10240//10240 10239//10239 10241//10241 -f 10240//10240 10241//10241 10242//10242 -f 10242//10242 10241//10241 10243//10243 -f 10242//10242 10243//10243 10244//10244 -f 10244//10244 10243//10243 10245//10245 -f 10244//10244 10245//10245 10246//10246 -f 10246//10246 10245//10245 10247//10247 -f 10246//10246 10247//10247 10248//10248 -f 10248//10248 10247//10247 10249//10249 -f 10248//10248 10249//10249 10250//10250 -f 10250//10250 10249//10249 10251//10251 -f 10250//10250 10251//10251 10252//10252 -f 10252//10252 10251//10251 10253//10253 -f 10252//10252 10253//10253 10254//10254 -f 10254//10254 10253//10253 10255//10255 -f 10254//10254 10255//10255 10256//10256 -f 10256//10256 10255//10255 10257//10257 -f 10256//10256 10257//10257 10258//10258 -f 10258//10258 10257//10257 10259//10259 -f 10258//10258 10259//10259 10260//10260 -f 10260//10260 10259//10259 10261//10261 -f 10260//10260 10261//10261 10262//10262 -f 10262//10262 10261//10261 10263//10263 -f 10262//10262 10263//10263 10264//10264 -f 10264//10264 10263//10263 10265//10265 -f 10264//10264 10265//10265 10266//10266 -f 10266//10266 10265//10265 10267//10267 -f 10266//10266 10267//10267 10268//10268 -f 10268//10268 10267//10267 10269//10269 -f 10268//10268 10269//10269 10270//10270 -f 10270//10270 10269//10269 10271//10271 -f 10270//10270 10271//10271 10272//10272 -f 10272//10272 10271//10271 10273//10273 -f 10272//10272 10273//10273 10274//10274 -f 10274//10274 10273//10273 10275//10275 -f 10274//10274 10275//10275 10276//10276 -f 10276//10276 10275//10275 10277//10277 -f 10276//10276 10277//10277 10278//10278 -f 10278//10278 10277//10277 10279//10279 -f 10278//10278 10279//10279 10280//10280 -f 10280//10280 10279//10279 10281//10281 -f 10280//10280 10281//10281 10206//10206 -f 10206//10206 10281//10281 10207//10207 -f 10282//10282 10283//10283 10284//10284 -f 10284//10284 10283//10283 10285//10285 -f 10285//10285 10283//10283 10286//10286 -f 10285//10285 10286//10286 10287//10287 -f 10287//10287 10286//10286 10288//10288 -f 10287//10287 10288//10288 10289//10289 -f 10289//10289 10288//10288 10290//10290 -f 10289//10289 10290//10290 10291//10291 -f 10291//10291 10290//10290 10292//10292 -f 10291//10291 10292//10292 10293//10293 -f 10293//10293 10294//10294 10295//10295 -f 10295//10295 10294//10294 10296//10296 -f 10295//10295 10296//10296 10297//10297 -f 10298//10298 10299//10299 10300//10300 -f 10284//10284 10301//10301 10282//10282 -f 10282//10282 10301//10301 10302//10302 -f 10282//10282 10302//10302 10303//10303 -f 10298//10298 10304//10304 10299//10299 -f 10299//10299 10304//10304 10305//10305 -f 10299//10299 10305//10305 10306//10306 -f 10300//10300 10307//10307 10298//10298 -f 10298//10298 10307//10307 10308//10308 -f 10298//10298 10308//10308 10309//10309 -f 10309//10309 10308//10308 10310//10310 -f 10309//10309 10310//10310 10296//10296 -f 10296//10296 10310//10310 10311//10311 -f 10296//10296 10311//10311 10297//10297 -f 10312//10312 10313//10313 10314//10314 -f 10314//10314 10313//10313 10315//10315 -f 10314//10314 10315//10315 10316//10316 -f 10316//10316 10315//10315 10317//10317 -f 10316//10316 10317//10317 10306//10306 -f 10306//10306 10317//10317 10318//10318 -f 10306//10306 10318//10318 10299//10299 -f 10319//10319 10320//10320 10321//10321 -f 10321//10321 10320//10320 10322//10322 -f 10304//10304 10282//10282 10305//10305 -f 10305//10305 10282//10282 10303//10303 -f 10305//10305 10303//10303 10323//10323 -f 10323//10323 10303//10303 10324//10324 -f 10323//10323 10324//10324 10325//10325 -f 10326//10326 10327//10327 10328//10328 -f 10328//10328 10327//10327 10322//10322 -f 10322//10322 10327//10327 10329//10329 -f 10322//10322 10329//10329 10321//10321 -f 10328//10328 10330//10330 10326//10326 -f 10326//10326 10330//10330 10331//10331 -f 10326//10326 10331//10331 10332//10332 -f 10332//10332 10331//10331 10325//10325 -f 10332//10332 10325//10325 10333//10333 -f 10333//10333 10325//10325 10324//10324 -f 10334//10334 10335//10335 10336//10336 -f 10336//10336 10335//10335 10337//10337 -f 10335//10335 10338//10338 10339//10339 -f 10339//10339 10338//10338 10340//10340 -f 10339//10339 10340//10340 10341//10341 -f 10341//10341 10340//10340 10342//10342 -f 10341//10341 10342//10342 10343//10343 -f 10343//10343 10342//10342 10344//10344 -f 10343//10343 10344//10344 10345//10345 -f 10345//10345 10344//10344 10346//10346 -f 10345//10345 10346//10346 10347//10347 -f 10347//10347 10346//10346 10348//10348 -f 10347//10347 10348//10348 10349//10349 -f 10349//10349 10348//10348 10350//10350 -f 10349//10349 10350//10350 10351//10351 -f 10314//10314 10319//10319 10312//10312 -f 10312//10312 10319//10319 10321//10321 -f 10312//10312 10321//10321 10352//10352 -f 10352//10352 10321//10321 10353//10353 -f 10351//10351 10350//10350 10354//10354 -f 10354//10354 10350//10350 10355//10355 -f 10354//10354 10355//10355 10356//10356 -f 10336//10336 10357//10357 10334//10334 -f 10334//10334 10357//10357 10358//10358 -f 10334//10334 10358//10358 10359//10359 -f 10359//10359 10358//10358 10360//10360 -f 10359//10359 10360//10360 10361//10361 -f 10361//10361 10360//10360 10362//10362 -f 10362//10362 10353//10353 10361//10361 -f 10361//10361 10353//10353 10321//10321 -f 10361//10361 10321//10321 10355//10355 -f 10355//10355 10321//10321 10363//10363 -f 10355//10355 10363//10363 10356//10356 -f 10335//10335 10339//10339 10337//10337 -f 10337//10337 10339//10339 10364//10364 -f 10337//10337 10364//10364 10365//10365 -f 10365//10365 10366//10366 10337//10337 -f 10337//10337 10366//10366 10367//10367 -f 10337//10337 10367//10367 10368//10368 -f 10369//10369 10370//10370 10371//10371 -f 10372//10372 10373//10373 10374//10374 -f 10375//10375 10337//10337 10376//10376 -f 10377//10377 10378//10378 10379//10379 -f 10374//10374 10373//10373 10370//10370 -f 10370//10370 10373//10373 10380//10380 -f 10370//10370 10380//10380 10371//10371 -f 10293//10293 10295//10295 10291//10291 -f 10291//10291 10295//10295 10381//10381 -f 10291//10291 10381//10381 10382//10382 -f 10374//10374 10383//10383 10372//10372 -f 10372//10372 10383//10383 10384//10384 -f 10372//10372 10384//10384 10385//10385 -f 10385//10385 10384//10384 10386//10386 -f 10385//10385 10386//10386 10368//10368 -f 10368//10368 10386//10386 10387//10387 -f 10368//10368 10387//10387 10337//10337 -f 10337//10337 10387//10387 10388//10388 -f 10337//10337 10388//10388 10376//10376 -f 10378//10378 10291//10291 10379//10379 -f 10379//10379 10291//10291 10382//10382 -f 10379//10379 10382//10382 10389//10389 -f 10389//10389 10382//10382 10390//10390 -f 10389//10389 10390//10390 10391//10391 -f 10391//10391 10390//10390 10392//10392 -f 10391//10391 10392//10392 10376//10376 -f 10376//10376 10392//10392 10393//10393 -f 10376//10376 10393//10393 10375//10375 -f 10371//10371 10394//10394 10369//10369 -f 10369//10369 10394//10394 10395//10395 -f 10369//10369 10395//10395 10379//10379 -f 10379//10379 10395//10395 10396//10396 -f 10379//10379 10396//10396 10377//10377 -f 10311//10311 10310//10310 10397//10397 -f 10397//10397 10398//10398 10311//10311 -f 10311//10311 10398//10398 10399//10399 -f 10311//10311 10399//10399 10297//10297 -f 10297//10297 10399//10399 10400//10400 -f 10297//10297 10400//10400 10295//10295 -f 10295//10295 10400//10400 10401//10401 -f 10295//10295 10401//10401 10381//10381 -f 10401//10401 10402//10402 10381//10381 -f 10381//10381 10402//10402 10403//10403 -f 10381//10381 10403//10403 10382//10382 -f 10403//10403 10404//10404 10382//10382 -f 10382//10382 10404//10404 10405//10405 -f 10382//10382 10405//10405 10390//10390 -f 10405//10405 10406//10406 10390//10390 -f 10390//10390 10406//10406 10407//10407 -f 10390//10390 10407//10407 10392//10392 -f 10407//10407 10408//10408 10392//10392 -f 10392//10392 10408//10408 10409//10409 -f 10392//10392 10409//10409 10393//10393 -f 10409//10409 10410//10410 10393//10393 -f 10393//10393 10410//10410 10411//10411 -f 10393//10393 10411//10411 10375//10375 -f 10411//10411 10412//10412 10375//10375 -f 10375//10375 10412//10412 10413//10413 -f 10375//10375 10413//10413 10337//10337 -f 10413//10413 10414//10414 10337//10337 -f 10337//10337 10414//10414 10415//10415 -f 10337//10337 10415//10415 10336//10336 -f 10415//10415 10416//10416 10336//10336 -f 10336//10336 10416//10416 10417//10417 -f 10336//10336 10417//10417 10357//10357 -f 10417//10417 10418//10418 10357//10357 -f 10357//10357 10418//10418 10419//10419 -f 10357//10357 10419//10419 10358//10358 -f 10419//10419 10420//10420 10358//10358 -f 10358//10358 10420//10420 10421//10421 -f 10358//10358 10421//10421 10360//10360 -f 10421//10421 10422//10422 10360//10360 -f 10360//10360 10422//10422 10423//10423 -f 10360//10360 10423//10423 10362//10362 -f 10423//10423 10424//10424 10362//10362 -f 10362//10362 10424//10424 10425//10425 -f 10362//10362 10425//10425 10353//10353 -f 10425//10425 10426//10426 10353//10353 -f 10353//10353 10426//10426 10427//10427 -f 10353//10353 10427//10427 10352//10352 -f 10352//10352 10427//10427 10428//10428 -f 10352//10352 10428//10428 10312//10312 -f 10312//10312 10428//10428 10429//10429 -f 10312//10312 10429//10429 10313//10313 -f 10429//10429 10430//10430 10313//10313 -f 10313//10313 10430//10430 10431//10431 -f 10313//10313 10431//10431 10315//10315 -f 10431//10431 10432//10432 10315//10315 -f 10315//10315 10432//10432 10433//10433 -f 10315//10315 10433//10433 10317//10317 -f 10433//10433 10434//10434 10317//10317 -f 10317//10317 10434//10434 10435//10435 -f 10317//10317 10435//10435 10318//10318 -f 10435//10435 10436//10436 10318//10318 -f 10318//10318 10436//10436 10437//10437 -f 10318//10318 10437//10437 10299//10299 -f 10437//10437 10438//10438 10299//10299 -f 10299//10299 10438//10438 10439//10439 -f 10299//10299 10439//10439 10300//10300 -f 10439//10439 10440//10440 10300//10300 -f 10300//10300 10440//10440 10441//10441 -f 10300//10300 10441//10441 10307//10307 -f 10441//10441 10442//10442 10307//10307 -f 10307//10307 10442//10442 10443//10443 -f 10307//10307 10443//10443 10308//10308 -f 10443//10443 10444//10444 10308//10308 -f 10308//10308 10444//10444 10445//10445 -f 10308//10308 10445//10445 10310//10310 -f 10310//10310 10445//10445 10446//10446 -f 10310//10310 10446//10446 10397//10397 -f 10447//10447 10448//10448 10449//10449 -f 10450//10450 10451//10451 10452//10452 -f 10452//10452 10451//10451 10453//10453 -f 10452//10452 10453//10453 10454//10454 -f 10454//10454 10453//10453 10455//10455 -f 10454//10454 10455//10455 10449//10449 -f 10449//10449 10455//10455 10456//10456 -f 10449//10449 10456//10456 10447//10447 -f 10457//10457 10458//10458 10459//10459 -f 10459//10459 10458//10458 10460//10460 -f 10459//10459 10460//10460 10461//10461 -f 10461//10461 10460//10460 10462//10462 -f 10461//10461 10462//10462 10450//10450 -f 10450//10450 10462//10462 10463//10463 -f 10450//10450 10463//10463 10451//10451 -f 10464//10464 10465//10465 10466//10466 -f 10466//10466 10465//10465 10467//10467 -f 10466//10466 10467//10467 10468//10468 -f 10468//10468 10467//10467 10469//10469 -f 10468//10468 10469//10469 10457//10457 -f 10457//10457 10469//10469 10470//10470 -f 10457//10457 10470//10470 10458//10458 -f 10447//10447 10471//10471 10448//10448 -f 10448//10448 10471//10471 10472//10472 -f 10448//10448 10472//10472 10473//10473 -f 10473//10473 10472//10472 10474//10474 -f 10473//10473 10474//10474 10475//10475 -f 10475//10475 10474//10474 10476//10476 -f 10475//10475 10476//10476 10477//10477 -f 10478//10478 10479//10479 10480//10480 -f 10480//10480 10479//10479 10481//10481 -f 10480//10480 10481//10481 10482//10482 -f 10482//10482 10481//10481 10483//10483 -f 10482//10482 10483//10483 10464//10464 -f 10464//10464 10483//10483 10484//10484 -f 10464//10464 10484//10484 10465//10465 -f 10476//10476 10485//10485 10477//10477 -f 10477//10477 10485//10485 10486//10486 -f 10477//10477 10486//10486 10487//10487 -f 10487//10487 10486//10486 10488//10488 -f 10487//10487 10488//10488 10489//10489 -f 10489//10489 10488//10488 10490//10490 -f 10489//10489 10490//10490 10478//10478 -f 10478//10478 10490//10490 10491//10491 -f 10478//10478 10491//10491 10479//10479 -f 10492//10492 10448//10448 10493//10493 -f 10493//10493 10448//10448 10473//10473 -f 10493//10493 10473//10473 10494//10494 -f 10494//10494 10473//10473 10475//10475 -f 10494//10494 10475//10475 10495//10495 -f 10495//10495 10475//10475 10477//10477 -f 10495//10495 10477//10477 10496//10496 -f 10496//10496 10477//10477 10487//10487 -f 10496//10496 10487//10487 10497//10497 -f 10497//10497 10487//10487 10489//10489 -f 10497//10497 10489//10489 10498//10498 -f 10498//10498 10489//10489 10478//10478 -f 10498//10498 10478//10478 10499//10499 -f 10499//10499 10478//10478 10480//10480 -f 10499//10499 10480//10480 10500//10500 -f 10500//10500 10480//10480 10482//10482 -f 10500//10500 10482//10482 10501//10501 -f 10501//10501 10482//10482 10464//10464 -f 10501//10501 10464//10464 10502//10502 -f 10502//10502 10464//10464 10466//10466 -f 10502//10502 10466//10466 10503//10503 -f 10503//10503 10466//10466 10468//10468 -f 10503//10503 10468//10468 10504//10504 -f 10504//10504 10468//10468 10457//10457 -f 10504//10504 10457//10457 10505//10505 -f 10505//10505 10457//10457 10459//10459 -f 10505//10505 10459//10459 10506//10506 -f 10506//10506 10459//10459 10461//10461 -f 10506//10506 10461//10461 10507//10507 -f 10507//10507 10461//10461 10450//10450 -f 10507//10507 10450//10450 10508//10508 -f 10508//10508 10450//10450 10452//10452 -f 10508//10508 10452//10452 10509//10509 -f 10509//10509 10452//10452 10454//10454 -f 10509//10509 10454//10454 10510//10510 -f 10510//10510 10454//10454 10449//10449 -f 10510//10510 10449//10449 10492//10492 -f 10492//10492 10449//10449 10448//10448 -f 10511//10511 10509//10509 10512//10512 -f 10512//10512 10509//10509 10510//10510 -f 10512//10512 10510//10510 10513//10513 -f 10513//10513 10510//10510 10492//10492 -f 10513//10513 10492//10492 10514//10514 -f 10515//10515 10503//10503 10516//10516 -f 10516//10516 10503//10503 10504//10504 -f 10516//10516 10504//10504 10517//10517 -f 10504//10504 10505//10505 10517//10517 -f 10517//10517 10505//10505 10506//10506 -f 10517//10517 10506//10506 10518//10518 -f 10518//10518 10506//10506 10507//10507 -f 10518//10518 10507//10507 10511//10511 -f 10511//10511 10507//10507 10508//10508 -f 10511//10511 10508//10508 10509//10509 -f 10519//10519 10500//10500 10520//10520 -f 10520//10520 10500//10500 10501//10501 -f 10520//10520 10501//10501 10515//10515 -f 10515//10515 10501//10501 10502//10502 -f 10515//10515 10502//10502 10503//10503 -f 10521//10521 10497//10497 10522//10522 -f 10522//10522 10497//10497 10498//10498 -f 10522//10522 10498//10498 10519//10519 -f 10519//10519 10498//10498 10499//10499 -f 10519//10519 10499//10499 10500//10500 -f 10492//10492 10493//10493 10514//10514 -f 10514//10514 10493//10493 10494//10494 -f 10514//10514 10494//10494 10523//10523 -f 10523//10523 10494//10494 10495//10495 -f 10523//10523 10495//10495 10521//10521 -f 10521//10521 10495//10495 10496//10496 -f 10521//10521 10496//10496 10497//10497 -f 10524//10524 10513//10513 10525//10525 -f 10525//10525 10513//10513 10514//10514 -f 10525//10525 10514//10514 10526//10526 -f 10526//10526 10514//10514 10523//10523 -f 10526//10526 10523//10523 10527//10527 -f 10527//10527 10523//10523 10521//10521 -f 10527//10527 10521//10521 10528//10528 -f 10528//10528 10521//10521 10522//10522 -f 10528//10528 10522//10522 10529//10529 -f 10529//10529 10522//10522 10519//10519 -f 10529//10529 10519//10519 10530//10530 -f 10530//10530 10519//10519 10520//10520 -f 10530//10530 10520//10520 10531//10531 -f 10531//10531 10520//10520 10515//10515 -f 10531//10531 10515//10515 10532//10532 -f 10532//10532 10515//10515 10516//10516 -f 10532//10532 10516//10516 10533//10533 -f 10533//10533 10516//10516 10517//10517 -f 10533//10533 10517//10517 10534//10534 -f 10534//10534 10517//10517 10518//10518 -f 10534//10534 10518//10518 10535//10535 -f 10535//10535 10518//10518 10511//10511 -f 10535//10535 10511//10511 10536//10536 -f 10536//10536 10511//10511 10512//10512 -f 10536//10536 10512//10512 10524//10524 -f 10524//10524 10512//10512 10513//10513 -f 10532//10532 10067//10067 10531//10531 -f 10531//10531 10067//10067 10064//10064 -f 10531//10531 10064//10064 10530//10530 -f 10534//10534 10076//10076 10533//10533 -f 10533//10533 10076//10076 10073//10073 -f 10533//10533 10073//10073 10532//10532 -f 10532//10532 10073//10073 10070//10070 -f 10532//10532 10070//10070 10067//10067 -f 10536//10536 10085//10085 10535//10535 -f 10535//10535 10085//10085 10082//10082 -f 10535//10535 10082//10082 10534//10534 -f 10534//10534 10082//10082 10079//10079 -f 10534//10534 10079//10079 10076//10076 -f 10526//10526 10040//10040 10525//10525 -f 10525//10525 10040//10040 10038//10038 -f 10525//10525 10038//10038 10524//10524 -f 10524//10524 10038//10038 10037//10037 -f 10524//10524 10037//10037 10536//10536 -f 10536//10536 10037//10037 10088//10088 -f 10536//10536 10088//10088 10085//10085 -f 10528//10528 10049//10049 10527//10527 -f 10527//10527 10049//10049 10046//10046 -f 10527//10527 10046//10046 10526//10526 -f 10526//10526 10046//10046 10043//10043 -f 10526//10526 10043//10043 10040//10040 -f 10064//10064 10061//10061 10530//10530 -f 10530//10530 10061//10061 10058//10058 -f 10530//10530 10058//10058 10529//10529 -f 10529//10529 10058//10058 10055//10055 -f 10529//10529 10055//10055 10528//10528 -f 10528//10528 10055//10055 10052//10052 -f 10528//10528 10052//10052 10049//10049 -f 10537//10537 10286//10286 10538//10538 -f 10538//10538 10286//10286 10283//10283 -f 10538//10538 10283//10283 10539//10539 -f 10539//10539 10283//10283 10282//10282 -f 10539//10539 10282//10282 10540//10540 -f 10540//10540 10282//10282 10304//10304 -f 10540//10540 10304//10304 10541//10541 -f 10541//10541 10304//10304 10298//10298 -f 10541//10541 10298//10298 10542//10542 -f 10542//10542 10298//10298 10309//10309 -f 10542//10542 10309//10309 10543//10543 -f 10543//10543 10309//10309 10296//10296 -f 10543//10543 10296//10296 10544//10544 -f 10544//10544 10296//10296 10294//10294 -f 10544//10544 10294//10294 10545//10545 -f 10545//10545 10294//10294 10293//10293 -f 10545//10545 10293//10293 10546//10546 -f 10546//10546 10293//10293 10292//10292 -f 10546//10546 10292//10292 10547//10547 -f 10547//10547 10292//10292 10290//10290 -f 10547//10547 10290//10290 10548//10548 -f 10548//10548 10290//10290 10288//10288 -f 10548//10548 10288//10288 10537//10537 -f 10537//10537 10288//10288 10286//10286 -f 10542//10542 10549//10549 10541//10541 -f 10541//10541 10549//10549 10550//10550 -f 10541//10541 10550//10550 10540//10540 -f 10540//10540 10550//10550 10551//10551 -f 10540//10540 10551//10551 10539//10539 -f 10539//10539 10551//10551 10552//10552 -f 10539//10539 10552//10552 10538//10538 -f 10538//10538 10552//10552 10553//10553 -f 10538//10538 10553//10553 10537//10537 -f 10537//10537 10553//10553 10554//10554 -f 10537//10537 10554//10554 10548//10548 -f 10548//10548 10554//10554 10555//10555 -f 10548//10548 10555//10555 10547//10547 -f 10547//10547 10555//10555 10556//10556 -f 10547//10547 10556//10556 10546//10546 -f 10546//10546 10556//10556 10557//10557 -f 10546//10546 10557//10557 10545//10545 -f 10545//10545 10557//10557 10558//10558 -f 10545//10545 10558//10558 10544//10544 -f 10544//10544 10558//10558 10559//10559 -f 10544//10544 10559//10559 10543//10543 -f 10543//10543 10559//10559 10560//10560 -f 10543//10543 10560//10560 10542//10542 -f 10542//10542 10560//10560 10549//10549 -f 10550//10550 10181//10181 10551//10551 -f 10551//10551 10181//10181 10182//10182 -f 10551//10551 10182//10182 10552//10552 -f 10552//10552 10182//10182 10200//10200 -f 10552//10552 10200//10200 10553//10553 -f 10553//10553 10200//10200 10198//10198 -f 10553//10553 10198//10198 10554//10554 -f 10554//10554 10198//10198 10196//10196 -f 10554//10554 10196//10196 10555//10555 -f 10555//10555 10196//10196 10194//10194 -f 10555//10555 10194//10194 10556//10556 -f 10556//10556 10194//10194 10192//10192 -f 10556//10556 10192//10192 10557//10557 -f 10557//10557 10192//10192 10190//10190 -f 10557//10557 10190//10190 10558//10558 -f 10558//10558 10190//10190 10189//10189 -f 10558//10558 10189//10189 10559//10559 -f 10559//10559 10189//10189 10188//10188 -f 10559//10559 10188//10188 10560//10560 -f 10560//10560 10188//10188 10186//10186 -f 10560//10560 10186//10186 10549//10549 -f 10549//10549 10186//10186 10184//10184 -f 10549//10549 10184//10184 10550//10550 -f 10550//10550 10184//10184 10181//10181 -f 10561//10561 10379//10379 10562//10562 -f 10562//10562 10379//10379 10389//10389 -f 10562//10562 10389//10389 10563//10563 -f 10563//10563 10389//10389 10391//10391 -f 10563//10563 10391//10391 10564//10564 -f 10564//10564 10391//10391 10376//10376 -f 10564//10564 10376//10376 10565//10565 -f 10565//10565 10376//10376 10388//10388 -f 10565//10565 10388//10388 10566//10566 -f 10566//10566 10388//10388 10387//10387 -f 10566//10566 10387//10387 10567//10567 -f 10567//10567 10387//10387 10386//10386 -f 10567//10567 10386//10386 10568//10568 -f 10568//10568 10386//10386 10384//10384 -f 10568//10568 10384//10384 10569//10569 -f 10569//10569 10384//10384 10383//10383 -f 10569//10569 10383//10383 10570//10570 -f 10570//10570 10383//10383 10374//10374 -f 10570//10570 10374//10374 10571//10571 -f 10571//10571 10374//10374 10370//10370 -f 10571//10571 10370//10370 10572//10572 -f 10572//10572 10370//10370 10369//10369 -f 10572//10572 10369//10369 10561//10561 -f 10561//10561 10369//10369 10379//10379 -f 10566//10566 10573//10573 10565//10565 -f 10565//10565 10573//10573 10574//10574 -f 10565//10565 10574//10574 10564//10564 -f 10564//10564 10574//10574 10575//10575 -f 10564//10564 10575//10575 10563//10563 -f 10563//10563 10575//10575 10576//10576 -f 10563//10563 10576//10576 10562//10562 -f 10562//10562 10576//10576 10577//10577 -f 10562//10562 10577//10577 10561//10561 -f 10561//10561 10577//10577 10578//10578 -f 10561//10561 10578//10578 10572//10572 -f 10572//10572 10578//10578 10579//10579 -f 10572//10572 10579//10579 10571//10571 -f 10571//10571 10579//10579 10580//10580 -f 10571//10571 10580//10580 10570//10570 -f 10570//10570 10580//10580 10581//10581 -f 10570//10570 10581//10581 10569//10569 -f 10569//10569 10581//10581 10582//10582 -f 10569//10569 10582//10582 10568//10568 -f 10568//10568 10582//10582 10583//10583 -f 10568//10568 10583//10583 10567//10567 -f 10567//10567 10583//10583 10584//10584 -f 10567//10567 10584//10584 10566//10566 -f 10566//10566 10584//10584 10573//10573 -f 10574//10574 10159//10159 10575//10575 -f 10575//10575 10159//10159 10158//10158 -f 10575//10575 10158//10158 10576//10576 -f 10576//10576 10158//10158 10167//10167 -f 10576//10576 10167//10167 10577//10577 -f 10577//10577 10167//10167 10154//10154 -f 10577//10577 10154//10154 10578//10578 -f 10578//10578 10154//10154 10157//10157 -f 10578//10578 10157//10157 10579//10579 -f 10579//10579 10157//10157 10156//10156 -f 10579//10579 10156//10156 10580//10580 -f 10580//10580 10156//10156 10164//10164 -f 10580//10580 10164//10164 10581//10581 -f 10581//10581 10164//10164 10163//10163 -f 10581//10581 10163//10163 10582//10582 -f 10582//10582 10163//10163 10162//10162 -f 10582//10582 10162//10162 10583//10583 -f 10583//10583 10162//10162 10152//10152 -f 10583//10583 10152//10152 10584//10584 -f 10584//10584 10152//10152 10148//10148 -f 10584//10584 10148//10148 10573//10573 -f 10573//10573 10148//10148 10147//10147 -f 10573//10573 10147//10147 10574//10574 -f 10574//10574 10147//10147 10159//10159 -f 10585//10585 10361//10361 10586//10586 -f 10586//10586 10361//10361 10355//10355 -f 10586//10586 10355//10355 10587//10587 -f 10587//10587 10355//10355 10350//10350 -f 10587//10587 10350//10350 10588//10588 -f 10588//10588 10350//10350 10348//10348 -f 10588//10588 10348//10348 10589//10589 -f 10589//10589 10348//10348 10346//10346 -f 10589//10589 10346//10346 10590//10590 -f 10590//10590 10346//10346 10344//10344 -f 10590//10590 10344//10344 10591//10591 -f 10591//10591 10344//10344 10342//10342 -f 10591//10591 10342//10342 10592//10592 -f 10592//10592 10342//10342 10340//10340 -f 10592//10592 10340//10340 10593//10593 -f 10593//10593 10340//10340 10338//10338 -f 10593//10593 10338//10338 10594//10594 -f 10594//10594 10338//10338 10335//10335 -f 10594//10594 10335//10335 10595//10595 -f 10595//10595 10335//10335 10334//10334 -f 10595//10595 10334//10334 10596//10596 -f 10596//10596 10334//10334 10359//10359 -f 10596//10596 10359//10359 10585//10585 -f 10585//10585 10359//10359 10361//10361 -f 10590//10590 10597//10597 10589//10589 -f 10589//10589 10597//10597 10598//10598 -f 10589//10589 10598//10598 10588//10588 -f 10588//10588 10598//10598 10599//10599 -f 10588//10588 10599//10599 10587//10587 -f 10587//10587 10599//10599 10600//10600 -f 10587//10587 10600//10600 10586//10586 -f 10586//10586 10600//10600 10601//10601 -f 10586//10586 10601//10601 10585//10585 -f 10585//10585 10601//10601 10602//10602 -f 10585//10585 10602//10602 10596//10596 -f 10596//10596 10602//10602 10603//10603 -f 10596//10596 10603//10603 10595//10595 -f 10595//10595 10603//10603 10604//10604 -f 10595//10595 10604//10604 10594//10594 -f 10594//10594 10604//10604 10605//10605 -f 10594//10594 10605//10605 10593//10593 -f 10593//10593 10605//10605 10606//10606 -f 10593//10593 10606//10606 10592//10592 -f 10592//10592 10606//10606 10607//10607 -f 10592//10592 10607//10607 10591//10591 -f 10591//10591 10607//10607 10608//10608 -f 10591//10591 10608//10608 10590//10590 -f 10590//10590 10608//10608 10597//10597 -f 10598//10598 10141//10141 10599//10599 -f 10599//10599 10141//10141 10139//10139 -f 10599//10599 10139//10139 10600//10600 -f 10600//10600 10139//10139 10138//10138 -f 10600//10600 10138//10138 10601//10601 -f 10601//10601 10138//10138 10126//10126 -f 10601//10601 10126//10126 10602//10602 -f 10602//10602 10126//10126 10125//10125 -f 10602//10602 10125//10125 10603//10603 -f 10603//10603 10125//10125 10135//10135 -f 10603//10603 10135//10135 10604//10604 -f 10604//10604 10135//10135 10116//10116 -f 10604//10604 10116//10116 10605//10605 -f 10605//10605 10116//10116 10115//10115 -f 10605//10605 10115//10115 10606//10606 -f 10606//10606 10115//10115 10103//10103 -f 10606//10606 10103//10103 10607//10607 -f 10607//10607 10103//10103 10146//10146 -f 10607//10607 10146//10146 10608//10608 -f 10608//10608 10146//10146 10145//10145 -f 10608//10608 10145//10145 10597//10597 -f 10597//10597 10145//10145 10143//10143 -f 10597//10597 10143//10143 10598//10598 -f 10598//10598 10143//10143 10141//10141 -f 10609//10609 10325//10325 10610//10610 -f 10610//10610 10325//10325 10331//10331 -f 10610//10610 10331//10331 10611//10611 -f 10611//10611 10331//10331 10330//10330 -f 10611//10611 10330//10330 10612//10612 -f 10612//10612 10330//10330 10328//10328 -f 10612//10612 10328//10328 10613//10613 -f 10613//10613 10328//10328 10322//10322 -f 10613//10613 10322//10322 10614//10614 -f 10614//10614 10322//10322 10320//10320 -f 10614//10614 10320//10320 10615//10615 -f 10615//10615 10320//10320 10319//10319 -f 10615//10615 10319//10319 10616//10616 -f 10616//10616 10319//10319 10314//10314 -f 10616//10616 10314//10314 10617//10617 -f 10617//10617 10314//10314 10316//10316 -f 10617//10617 10316//10316 10618//10618 -f 10618//10618 10316//10316 10306//10306 -f 10618//10618 10306//10306 10619//10619 -f 10619//10619 10306//10306 10305//10305 -f 10619//10619 10305//10305 10620//10620 -f 10620//10620 10305//10305 10323//10323 -f 10620//10620 10323//10323 10609//10609 -f 10609//10609 10323//10323 10325//10325 -f 10614//10614 10621//10621 10613//10613 -f 10613//10613 10621//10621 10622//10622 -f 10613//10613 10622//10622 10612//10612 -f 10612//10612 10622//10622 10623//10623 -f 10612//10612 10623//10623 10611//10611 -f 10611//10611 10623//10623 10624//10624 -f 10611//10611 10624//10624 10610//10610 -f 10610//10610 10624//10624 10625//10625 -f 10610//10610 10625//10625 10609//10609 -f 10609//10609 10625//10625 10626//10626 -f 10609//10609 10626//10626 10620//10620 -f 10620//10620 10626//10626 10627//10627 -f 10620//10620 10627//10627 10619//10619 -f 10619//10619 10627//10627 10628//10628 -f 10619//10619 10628//10628 10618//10618 -f 10618//10618 10628//10628 10629//10629 -f 10618//10618 10629//10629 10617//10617 -f 10617//10617 10629//10629 10630//10630 -f 10617//10617 10630//10630 10616//10616 -f 10616//10616 10630//10630 10631//10631 -f 10616//10616 10631//10631 10615//10615 -f 10615//10615 10631//10631 10632//10632 -f 10615//10615 10632//10632 10614//10614 -f 10614//10614 10632//10632 10621//10621 -f 10622//10622 10107//10107 10623//10623 -f 10623//10623 10107//10107 10109//10109 -f 10623//10623 10109//10109 10624//10624 -f 10624//10624 10109//10109 10111//10111 -f 10624//10624 10111//10111 10625//10625 -f 10625//10625 10111//10111 10100//10100 -f 10625//10625 10100//10100 10626//10626 -f 10626//10626 10100//10100 10098//10098 -f 10626//10626 10098//10098 10627//10627 -f 10627//10627 10098//10098 10097//10097 -f 10627//10627 10097//10097 10628//10628 -f 10628//10628 10097//10097 10106//10106 -f 10628//10628 10106//10106 10629//10629 -f 10629//10629 10106//10106 10105//10105 -f 10629//10629 10105//10105 10630//10630 -f 10630//10630 10105//10105 10130//10130 -f 10630//10630 10130//10130 10631//10631 -f 10631//10631 10130//10130 10124//10124 -f 10631//10631 10124//10124 10632//10632 -f 10632//10632 10124//10124 10121//10121 -f 10632//10632 10121//10121 10621//10621 -f 10621//10621 10121//10121 10112//10112 -f 10621//10621 10112//10112 10622//10622 -f 10622//10622 10112//10112 10107//10107 -f 10117//10117 10137//10137 10068//10068 -f 10068//10068 10072//10072 10117//10117 -f 10117//10117 10072//10072 10071//10071 -f 10117//10117 10071//10071 10101//10101 -f 10101//10101 10071//10071 10075//10075 -f 10101//10101 10075//10075 10165//10165 -f 10165//10165 10075//10075 10074//10074 -f 10165//10165 10074//10074 10166//10166 -f 10074//10074 10078//10078 10166//10166 -f 10166//10166 10078//10078 10077//10077 -f 10166//10166 10077//10077 10168//10168 -f 10077//10077 10081//10081 10168//10168 -f 10168//10168 10081//10081 10080//10080 -f 10168//10168 10080//10080 10169//10169 -f 10080//10080 10084//10084 10169//10169 -f 10169//10169 10084//10084 10083//10083 -f 10169//10169 10083//10083 10153//10153 -f 10083//10083 10087//10087 10153//10153 -f 10153//10153 10087//10087 10086//10086 -f 10153//10153 10086//10086 10096//10096 -f 10096//10096 10086//10086 10173//10173 -f 10173//10173 10086//10086 10090//10090 -f 10173//10173 10090//10090 10187//10187 -f 10187//10187 10090//10090 10089//10089 -f 10187//10187 10089//10089 10185//10185 -f 10089//10089 10093//10093 10185//10185 -f 10185//10185 10093//10093 10092//10092 -f 10185//10185 10092//10092 10183//10183 -f 10183//10183 10092//10092 10091//10091 -f 10183//10183 10091//10091 10179//10179 -f 10091//10091 10039//10039 10179//10179 -f 10179//10179 10039//10039 10042//10042 -f 10179//10179 10042//10042 10180//10180 -f 10042//10042 10041//10041 10180//10180 -f 10180//10180 10041//10041 10045//10045 -f 10180//10180 10045//10045 10104//10104 -f 10104//10104 10045//10045 10044//10044 -f 10104//10104 10044//10044 10132//10132 -f 10132//10132 10044//10044 10048//10048 -f 10132//10132 10048//10048 10131//10131 -f 10048//10048 10047//10047 10131//10131 -f 10131//10131 10047//10047 10051//10051 -f 10131//10131 10051//10051 10129//10129 -f 10051//10051 10050//10050 10129//10129 -f 10129//10129 10050//10050 10054//10054 -f 10129//10129 10054//10054 10128//10128 -f 10054//10054 10053//10053 10128//10128 -f 10128//10128 10053//10053 10057//10057 -f 10128//10128 10057//10057 10127//10127 -f 10057//10057 10056//10056 10127//10127 -f 10127//10127 10056//10056 10060//10060 -f 10127//10127 10060//10060 10133//10133 -f 10060//10060 10059//10059 10133//10133 -f 10133//10133 10059//10059 10063//10063 -f 10133//10133 10063//10063 10134//10134 -f 10063//10063 10062//10062 10134//10134 -f 10134//10134 10062//10062 10066//10066 -f 10134//10134 10066//10066 10136//10136 -f 10136//10136 10066//10066 10065//10065 -f 10136//10136 10065//10065 10137//10137 -f 10137//10137 10065//10065 10069//10069 -f 10137//10137 10069//10069 10068//10068 -f 10465//10465 10421//10421 10420//10420 -f 10465//10465 10420//10420 10467//10467 -f 10467//10467 10420//10420 10419//10419 -f 10467//10467 10419//10419 10469//10469 -f 10419//10419 10418//10418 10469//10469 -f 10469//10469 10418//10418 10417//10417 -f 10469//10469 10417//10417 10470//10470 -f 10417//10417 10416//10416 10470//10470 -f 10470//10470 10416//10416 10415//10415 -f 10470//10470 10415//10415 10458//10458 -f 10415//10415 10414//10414 10458//10458 -f 10458//10458 10414//10414 10413//10413 -f 10458//10458 10413//10413 10460//10460 -f 10413//10413 10412//10412 10460//10460 -f 10460//10460 10412//10412 10411//10411 -f 10460//10460 10411//10411 10462//10462 -f 10462//10462 10411//10411 10410//10410 -f 10410//10410 10409//10409 10462//10462 -f 10462//10462 10409//10409 10408//10408 -f 10462//10462 10408//10408 10463//10463 -f 10408//10408 10407//10407 10463//10463 -f 10463//10463 10407//10407 10406//10406 -f 10463//10463 10406//10406 10451//10451 -f 10451//10451 10406//10406 10405//10405 -f 10451//10451 10405//10405 10453//10453 -f 10405//10405 10404//10404 10453//10453 -f 10453//10453 10404//10404 10403//10403 -f 10453//10453 10403//10403 10455//10455 -f 10403//10403 10402//10402 10455//10455 -f 10455//10455 10402//10402 10401//10401 -f 10455//10455 10401//10401 10456//10456 -f 10401//10401 10400//10400 10456//10456 -f 10456//10456 10400//10400 10399//10399 -f 10456//10456 10399//10399 10447//10447 -f 10399//10399 10398//10398 10447//10447 -f 10447//10447 10398//10398 10397//10397 -f 10447//10447 10397//10397 10471//10471 -f 10471//10471 10397//10397 10446//10446 -f 10471//10471 10446//10446 10472//10472 -f 10446//10446 10445//10445 10472//10472 -f 10472//10472 10445//10445 10444//10444 -f 10472//10472 10444//10444 10474//10474 -f 10474//10474 10444//10444 10443//10443 -f 10474//10474 10443//10443 10476//10476 -f 10443//10443 10442//10442 10476//10476 -f 10476//10476 10442//10442 10441//10441 -f 10476//10476 10441//10441 10485//10485 -f 10485//10485 10441//10441 10440//10440 -f 10440//10440 10439//10439 10485//10485 -f 10485//10485 10439//10439 10438//10438 -f 10485//10485 10438//10438 10486//10486 -f 10486//10486 10438//10438 10437//10437 -f 10486//10486 10437//10437 10488//10488 -f 10437//10437 10436//10436 10488//10488 -f 10488//10488 10436//10436 10435//10435 -f 10488//10488 10435//10435 10490//10490 -f 10435//10435 10434//10434 10490//10490 -f 10490//10490 10434//10434 10433//10433 -f 10490//10490 10433//10433 10491//10491 -f 10433//10433 10432//10432 10491//10491 -f 10491//10491 10432//10432 10431//10431 -f 10491//10491 10431//10431 10479//10479 -f 10431//10431 10430//10430 10479//10479 -f 10479//10479 10430//10430 10429//10429 -f 10479//10479 10429//10429 10481//10481 -f 10481//10481 10429//10429 10428//10428 -f 10428//10428 10427//10427 10481//10481 -f 10481//10481 10427//10427 10426//10426 -f 10481//10481 10426//10426 10483//10483 -f 10426//10426 10425//10425 10483//10483 -f 10483//10483 10425//10425 10424//10424 -f 10483//10483 10424//10424 10484//10484 -f 10484//10484 10424//10424 10423//10423 -f 10484//10484 10423//10423 10465//10465 -f 10465//10465 10423//10423 10422//10422 -f 10465//10465 10422//10422 10421//10421 -f 10289//10289 10291//10291 10278//10278 -f 10228//10228 10327//10327 10226//10226 -f 10226//10226 10327//10327 10326//10326 -f 10226//10226 10326//10326 10224//10224 -f 10224//10224 10326//10326 10332//10332 -f 10224//10224 10332//10332 10222//10222 -f 10222//10222 10332//10332 10333//10333 -f 10222//10222 10333//10333 10220//10220 -f 10220//10220 10333//10333 10324//10324 -f 10220//10220 10324//10324 10218//10218 -f 10218//10218 10324//10324 10303//10303 -f 10218//10218 10303//10303 10216//10216 -f 10216//10216 10303//10303 10302//10302 -f 10216//10216 10302//10302 10214//10214 -f 10214//10214 10302//10302 10301//10301 -f 10214//10214 10301//10301 10212//10212 -f 10212//10212 10301//10301 10284//10284 -f 10212//10212 10284//10284 10210//10210 -f 10210//10210 10284//10284 10285//10285 -f 10210//10210 10285//10285 10208//10208 -f 10208//10208 10285//10285 10287//10287 -f 10208//10208 10287//10287 10206//10206 -f 10206//10206 10287//10287 10289//10289 -f 10206//10206 10289//10289 10280//10280 -f 10280//10280 10289//10289 10278//10278 -f 10363//10363 10321//10321 10228//10228 -f 10228//10228 10321//10321 10329//10329 -f 10228//10228 10329//10329 10327//10327 -f 10291//10291 10378//10378 10278//10278 -f 10278//10278 10378//10378 10377//10377 -f 10278//10278 10377//10377 10276//10276 -f 10276//10276 10377//10377 10396//10396 -f 10276//10276 10396//10396 10274//10274 -f 10274//10274 10396//10396 10395//10395 -f 10274//10274 10395//10395 10272//10272 -f 10272//10272 10395//10395 10394//10394 -f 10272//10272 10394//10394 10270//10270 -f 10270//10270 10394//10394 10371//10371 -f 10270//10270 10371//10371 10268//10268 -f 10268//10268 10371//10371 10380//10380 -f 10268//10268 10380//10380 10266//10266 -f 10266//10266 10380//10380 10373//10373 -f 10266//10266 10373//10373 10264//10264 -f 10264//10264 10373//10373 10372//10372 -f 10264//10264 10372//10372 10262//10262 -f 10262//10262 10372//10372 10385//10385 -f 10262//10262 10385//10385 10260//10260 -f 10260//10260 10385//10385 10368//10368 -f 10260//10260 10368//10368 10258//10258 -f 10258//10258 10368//10368 10367//10367 -f 10258//10258 10367//10367 10256//10256 -f 10256//10256 10367//10367 10366//10366 -f 10256//10256 10366//10366 10254//10254 -f 10254//10254 10366//10366 10365//10365 -f 10254//10254 10365//10365 10252//10252 -f 10252//10252 10365//10365 10364//10364 -f 10252//10252 10364//10364 10250//10250 -f 10250//10250 10364//10364 10339//10339 -f 10250//10250 10339//10339 10248//10248 -f 10248//10248 10339//10339 10341//10341 -f 10248//10248 10341//10341 10246//10246 -f 10246//10246 10341//10341 10343//10343 -f 10246//10246 10343//10343 10244//10244 -f 10244//10244 10343//10343 10345//10345 -f 10244//10244 10345//10345 10242//10242 -f 10242//10242 10345//10345 10347//10347 -f 10242//10242 10347//10347 10240//10240 -f 10240//10240 10347//10347 10349//10349 -f 10240//10240 10349//10349 10238//10238 -f 10238//10238 10349//10349 10351//10351 -f 10238//10238 10351//10351 10236//10236 -f 10236//10236 10351//10351 10354//10354 -f 10236//10236 10354//10354 10234//10234 -f 10234//10234 10354//10354 10356//10356 -f 10234//10234 10356//10356 10232//10232 -f 10232//10232 10356//10356 10363//10363 -f 10232//10232 10363//10363 10230//10230 -f 10230//10230 10363//10363 10228//10228 -f 10223//10223 10110//10110 10225//10225 -f 10225//10225 10110//10110 10108//10108 -f 10225//10225 10108//10108 10227//10227 -f 10227//10227 10108//10108 10114//10114 -f 10227//10227 10114//10114 10229//10229 -f 10229//10229 10114//10114 10113//10113 -f 10229//10229 10113//10113 10231//10231 -f 10231//10231 10113//10113 10123//10123 -f 10231//10231 10123//10123 10233//10233 -f 10233//10233 10123//10123 10122//10122 -f 10233//10233 10122//10122 10235//10235 -f 10235//10235 10122//10122 10120//10120 -f 10235//10235 10120//10120 10237//10237 -f 10237//10237 10120//10120 10119//10119 -f 10237//10237 10119//10119 10239//10239 -f 10239//10239 10119//10119 10140//10140 -f 10239//10239 10140//10140 10241//10241 -f 10241//10241 10140//10140 10142//10142 -f 10241//10241 10142//10142 10243//10243 -f 10243//10243 10142//10142 10144//10144 -f 10243//10243 10144//10144 10245//10245 -f 10245//10245 10144//10144 10102//10102 -f 10245//10245 10102//10102 10247//10247 -f 10102//10102 10160//10160 10247//10247 -f 10247//10247 10160//10160 10161//10161 -f 10247//10247 10161//10161 10249//10249 -f 10249//10249 10161//10161 10172//10172 -f 10249//10249 10172//10172 10251//10251 -f 10251//10251 10172//10172 10171//10171 -f 10251//10251 10171//10171 10253//10253 -f 10253//10253 10171//10171 10170//10170 -f 10253//10253 10170//10170 10255//10255 -f 10255//10255 10170//10170 10149//10149 -f 10255//10255 10149//10149 10257//10257 -f 10257//10257 10149//10149 10155//10155 -f 10257//10257 10155//10155 10259//10259 -f 10259//10259 10155//10155 10151//10151 -f 10259//10259 10151//10151 10261//10261 -f 10261//10261 10151//10151 10150//10150 -f 10261//10261 10150//10150 10263//10263 -f 10263//10263 10150//10150 10095//10095 -f 10263//10263 10095//10095 10265//10265 -f 10265//10265 10095//10095 10094//10094 -f 10265//10265 10094//10094 10267//10267 -f 10267//10267 10094//10094 10178//10178 -f 10267//10267 10178//10178 10269//10269 -f 10269//10269 10178//10178 10177//10177 -f 10269//10269 10177//10177 10271//10271 -f 10271//10271 10177//10177 10176//10176 -f 10271//10271 10176//10176 10273//10273 -f 10273//10273 10176//10176 10175//10175 -f 10273//10273 10175//10175 10275//10275 -f 10275//10275 10175//10175 10174//10174 -f 10275//10275 10174//10174 10277//10277 -f 10277//10277 10174//10174 10191//10191 -f 10277//10277 10191//10191 10279//10279 -f 10279//10279 10191//10191 10193//10193 -f 10279//10279 10193//10193 10281//10281 -f 10281//10281 10193//10193 10195//10195 -f 10281//10281 10195//10195 10207//10207 -f 10207//10207 10195//10195 10197//10197 -f 10207//10207 10197//10197 10209//10209 -f 10209//10209 10197//10197 10199//10199 -f 10209//10209 10199//10199 10211//10211 -f 10211//10211 10199//10199 10205//10205 -f 10211//10211 10205//10205 10213//10213 -f 10213//10213 10205//10205 10204//10204 -f 10213//10213 10204//10204 10215//10215 -f 10215//10215 10204//10204 10203//10203 -f 10215//10215 10203//10203 10217//10217 -f 10217//10217 10203//10203 10202//10202 -f 10217//10217 10202//10202 10219//10219 -f 10219//10219 10202//10202 10201//10201 -f 10219//10219 10201//10201 10221//10221 -f 10221//10221 10201//10201 10099//10099 -f 10221//10221 10099//10099 10223//10223 -f 10223//10223 10099//10099 10118//10118 -f 10223//10223 10118//10118 10110//10110 -f 10633//10633 10634//10634 10635//10635 -f 10635//10635 10634//10634 10636//10636 -f 10636//10636 10637//10637 10638//10638 -f 10639//10639 10640//10640 10641//10641 -f 10641//10641 10640//10640 10642//10642 -f 10641//10641 10642//10642 10643//10643 -f 10644//10644 10645//10645 10646//10646 -f 10646//10646 10645//10645 10647//10647 -f 10638//10638 10648//10648 10636//10636 -f 10636//10636 10648//10648 10649//10649 -f 10636//10636 10649//10649 10635//10635 -f 10635//10635 10649//10649 10643//10643 -f 10647//10647 10645//10645 10650//10650 -f 10650//10650 10645//10645 10651//10651 -f 10650//10650 10651//10651 10652//10652 -f 10653//10653 10654//10654 10655//10655 -f 10655//10655 10654//10654 10656//10656 -f 10655//10655 10656//10656 10657//10657 -f 10657//10657 10656//10656 10658//10658 -f 10656//10656 10659//10659 10658//10658 -f 10658//10658 10659//10659 10660//10660 -f 10658//10658 10660//10660 10661//10661 -f 10661//10661 10660//10660 10662//10662 -f 10663//10663 10664//10664 10665//10665 -f 10665//10665 10664//10664 10666//10666 -f 10665//10665 10666//10666 10667//10667 -f 10667//10667 10666//10666 10668//10668 -f 10667//10667 10668//10668 10669//10669 -f 10669//10669 10668//10668 10670//10670 -f 10671//10671 10644//10644 10663//10663 -f 10663//10663 10644//10644 10672//10672 -f 10663//10663 10672//10672 10664//10664 -f 10662//10662 10645//10645 10661//10661 -f 10661//10661 10645//10645 10644//10644 -f 10661//10661 10644//10644 10673//10673 -f 10673//10673 10644//10644 10671//10671 -f 10674//10674 10675//10675 10676//10676 -f 10676//10676 10675//10675 10677//10677 -f 10676//10676 10677//10677 10637//10637 -f 10637//10637 10677//10677 10678//10678 -f 10637//10637 10678//10678 10638//10638 -f 10642//10642 10679//10679 10643//10643 -f 10643//10643 10679//10679 10680//10680 -f 10643//10643 10680//10680 10635//10635 -f 10635//10635 10680//10680 10681//10681 -f 10635//10635 10681//10681 10682//10682 -f 10682//10682 10681//10681 10683//10683 -f 10682//10682 10683//10683 10684//10684 -f 10684//10684 10683//10683 10685//10685 -f 10684//10684 10685//10685 10670//10670 -f 10670//10670 10685//10685 10686//10686 -f 10670//10670 10686//10686 10669//10669 -f 10669//10669 10686//10686 10687//10687 -f 10669//10669 10687//10687 10688//10688 -f 10688//10688 10687//10687 10689//10689 -f 10688//10688 10689//10689 10690//10690 -f 10652//10652 10691//10691 10650//10650 -f 10650//10650 10691//10691 10635//10635 -f 10650//10650 10635//10635 10692//10692 -f 10692//10692 10635//10635 10682//10682 -f 10691//10691 10693//10693 10635//10635 -f 10635//10635 10693//10693 10694//10694 -f 10635//10635 10694//10694 10653//10653 -f 10653//10653 10694//10694 10695//10695 -f 10653//10653 10695//10695 10654//10654 -f 10639//10639 10696//10696 10640//10640 -f 10640//10640 10696//10696 10697//10697 -f 10640//10640 10697//10697 10698//10698 -f 10698//10698 10697//10697 10699//10699 -f 10698//10698 10699//10699 10675//10675 -f 10675//10675 10699//10699 10700//10700 -f 10675//10675 10700//10700 10677//10677 -f 10689//10689 10701//10701 10690//10690 -f 10690//10690 10701//10701 10702//10702 -f 10690//10690 10702//10702 10703//10703 -f 10703//10703 10702//10702 10640//10640 -f 10703//10703 10640//10640 10704//10704 -f 10704//10704 10640//10640 10698//10698 -f 10705//10705 10706//10706 10707//10707 -f 10708//10708 10709//10709 10710//10710 -f 10710//10710 10709//10709 10705//10705 -f 10711//10711 10712//10712 10713//10713 -f 10714//10714 10715//10715 10716//10716 -f 10716//10716 10715//10715 10717//10717 -f 10716//10716 10717//10717 10718//10718 -f 10718//10718 10717//10717 10719//10719 -f 10718//10718 10719//10719 10720//10720 -f 10721//10721 10722//10722 10723//10723 -f 10710//10710 10724//10724 10725//10725 -f 10710//10710 10726//10726 10727//10727 -f 10728//10728 10713//10713 10729//10729 -f 10729//10729 10713//10713 10712//10712 -f 10729//10729 10712//10712 10706//10706 -f 10706//10706 10712//10712 10730//10730 -f 10706//10706 10730//10730 10707//10707 -f 10731//10731 10732//10732 10733//10733 -f 10734//10734 10735//10735 10720//10720 -f 10710//10710 10727//10727 10736//10736 -f 10727//10727 10737//10737 10736//10736 -f 10736//10736 10737//10737 10738//10738 -f 10736//10736 10738//10738 10739//10739 -f 10739//10739 10738//10738 10714//10714 -f 10739//10739 10714//10714 10740//10740 -f 10740//10740 10714//10714 10716//10716 -f 10741//10741 10742//10742 10743//10743 -f 10743//10743 10742//10742 10744//10744 -f 10744//10744 10718//10718 10743//10743 -f 10743//10743 10718//10718 10720//10720 -f 10743//10743 10720//10720 10745//10745 -f 10745//10745 10720//10720 10735//10735 -f 10746//10746 10747//10747 10748//10748 -f 10748//10748 10747//10747 10749//10749 -f 10748//10748 10749//10749 10750//10750 -f 10750//10750 10749//10749 10751//10751 -f 10750//10750 10751//10751 10752//10752 -f 10705//10705 10707//10707 10710//10710 -f 10710//10710 10707//10707 10753//10753 -f 10710//10710 10753//10753 10724//10724 -f 10726//10726 10710//10710 10754//10754 -f 10754//10754 10710//10710 10725//10725 -f 10754//10754 10725//10725 10755//10755 -f 10755//10755 10725//10725 10756//10756 -f 10755//10755 10756//10756 10757//10757 -f 10723//10723 10731//10731 10721//10721 -f 10721//10721 10731//10731 10733//10733 -f 10721//10721 10733//10733 10758//10758 -f 10758//10758 10733//10733 10734//10734 -f 10758//10758 10734//10734 10756//10756 -f 10756//10756 10734//10734 10720//10720 -f 10756//10756 10720//10720 10757//10757 -f 10711//10711 10713//10713 10759//10759 -f 10759//10759 10713//10713 10760//10760 -f 10759//10759 10760//10760 10761//10761 -f 10761//10761 10760//10760 10762//10762 -f 10761//10761 10762//10762 10721//10721 -f 10721//10721 10762//10762 10763//10763 -f 10721//10721 10763//10763 10722//10722 -f 10751//10751 10764//10764 10752//10752 -f 10752//10752 10764//10764 10765//10765 -f 10752//10752 10765//10765 10766//10766 -f 10766//10766 10765//10765 10762//10762 -f 10766//10766 10762//10762 10767//10767 -f 10767//10767 10762//10762 10760//10760 -f 10743//10743 10768//10768 10741//10741 -f 10741//10741 10768//10768 10769//10769 -f 10741//10741 10769//10769 10770//10770 -f 10770//10770 10769//10769 10771//10771 -f 10770//10770 10771//10771 10746//10746 -f 10746//10746 10771//10771 10772//10772 -f 10746//10746 10772//10772 10747//10747 -f 10747//10747 10772//10772 10773//10773 -f 10747//10747 10773//10773 10774//10774 -f 10774//10774 10773//10773 10775//10775 -f 10774//10774 10775//10775 10732//10732 -f 10732//10732 10775//10775 10776//10776 -f 10732//10732 10776//10776 10733//10733 -f 10746//10746 10748//10748 10669//10669 -f 10669//10669 10748//10748 10667//10667 -f 10658//10658 10661//10661 10713//10713 -f 10713//10713 10661//10661 10760//10760 -f 10706//10706 10705//10705 10653//10653 -f 10653//10653 10705//10705 10635//10635 -f 10633//10633 10635//10635 10709//10709 -f 10709//10709 10635//10635 10705//10705 -f 10634//10634 10633//10633 10708//10708 -f 10708//10708 10633//10633 10709//10709 -f 10636//10636 10634//10634 10710//10710 -f 10710//10710 10634//10634 10708//10708 -f 10637//10637 10636//10636 10736//10736 -f 10736//10736 10636//10636 10710//10710 -f 10716//10716 10718//10718 10675//10675 -f 10675//10675 10718//10718 10698//10698 -f 10689//10689 10771//10771 10701//10701 -f 10701//10701 10771//10771 10769//10769 -f 10701//10701 10769//10769 10702//10702 -f 10702//10702 10769//10769 10768//10768 -f 10702//10702 10768//10768 10640//10640 -f 10640//10640 10768//10768 10743//10743 -f 10640//10640 10743//10743 10642//10642 -f 10642//10642 10743//10743 10745//10745 -f 10642//10642 10745//10745 10679//10679 -f 10679//10679 10745//10745 10735//10735 -f 10679//10679 10735//10735 10680//10680 -f 10680//10680 10735//10735 10734//10734 -f 10680//10680 10734//10734 10681//10681 -f 10681//10681 10734//10734 10733//10733 -f 10681//10681 10733//10733 10683//10683 -f 10683//10683 10733//10733 10776//10776 -f 10683//10683 10776//10776 10685//10685 -f 10685//10685 10776//10776 10775//10775 -f 10685//10685 10775//10775 10686//10686 -f 10686//10686 10775//10775 10773//10773 -f 10686//10686 10773//10773 10687//10687 -f 10687//10687 10773//10773 10772//10772 -f 10687//10687 10772//10772 10689//10689 -f 10689//10689 10772//10772 10771//10771 -f 10696//10696 10720//10720 10697//10697 -f 10697//10697 10720//10720 10719//10719 -f 10697//10697 10719//10719 10699//10699 -f 10699//10699 10719//10719 10717//10717 -f 10699//10699 10717//10717 10700//10700 -f 10700//10700 10717//10717 10715//10715 -f 10700//10700 10715//10715 10677//10677 -f 10677//10677 10715//10715 10714//10714 -f 10677//10677 10714//10714 10678//10678 -f 10678//10678 10714//10714 10738//10738 -f 10678//10678 10738//10738 10638//10638 -f 10638//10638 10738//10738 10737//10737 -f 10638//10638 10737//10737 10648//10648 -f 10648//10648 10737//10737 10727//10727 -f 10648//10648 10727//10727 10649//10649 -f 10649//10649 10727//10727 10726//10726 -f 10649//10649 10726//10726 10643//10643 -f 10643//10643 10726//10726 10754//10754 -f 10643//10643 10754//10754 10641//10641 -f 10641//10641 10754//10754 10755//10755 -f 10641//10641 10755//10755 10639//10639 -f 10639//10639 10755//10755 10757//10757 -f 10639//10639 10757//10757 10696//10696 -f 10696//10696 10757//10757 10720//10720 -f 10645//10645 10721//10721 10651//10651 -f 10651//10651 10721//10721 10758//10758 -f 10651//10651 10758//10758 10652//10652 -f 10652//10652 10758//10758 10756//10756 -f 10652//10652 10756//10756 10691//10691 -f 10691//10691 10756//10756 10725//10725 -f 10691//10691 10725//10725 10693//10693 -f 10693//10693 10725//10725 10724//10724 -f 10693//10693 10724//10724 10694//10694 -f 10694//10694 10724//10724 10753//10753 -f 10694//10694 10753//10753 10695//10695 -f 10695//10695 10753//10753 10707//10707 -f 10695//10695 10707//10707 10654//10654 -f 10654//10654 10707//10707 10730//10730 -f 10654//10654 10730//10730 10656//10656 -f 10656//10656 10730//10730 10712//10712 -f 10656//10656 10712//10712 10659//10659 -f 10659//10659 10712//10712 10711//10711 -f 10659//10659 10711//10711 10660//10660 -f 10660//10660 10711//10711 10759//10759 -f 10660//10660 10759//10759 10662//10662 -f 10662//10662 10759//10759 10761//10761 -f 10662//10662 10761//10761 10645//10645 -f 10645//10645 10761//10761 10721//10721 -f 10666//10666 10751//10751 10668//10668 -f 10668//10668 10751//10751 10749//10749 -f 10668//10668 10749//10749 10670//10670 -f 10670//10670 10749//10749 10747//10747 -f 10670//10670 10747//10747 10684//10684 -f 10684//10684 10747//10747 10774//10774 -f 10684//10684 10774//10774 10682//10682 -f 10682//10682 10774//10774 10732//10732 -f 10682//10682 10732//10732 10692//10692 -f 10692//10692 10732//10732 10731//10731 -f 10692//10692 10731//10731 10650//10650 -f 10650//10650 10731//10731 10723//10723 -f 10650//10650 10723//10723 10647//10647 -f 10647//10647 10723//10723 10722//10722 -f 10647//10647 10722//10722 10646//10646 -f 10646//10646 10722//10722 10763//10763 -f 10646//10646 10763//10763 10644//10644 -f 10644//10644 10763//10763 10762//10762 -f 10644//10644 10762//10762 10672//10672 -f 10672//10672 10762//10762 10765//10765 -f 10672//10672 10765//10765 10664//10664 -f 10664//10664 10765//10765 10764//10764 -f 10664//10664 10764//10764 10666//10666 -f 10666//10666 10764//10764 10751//10751 -f 10698//10698 10718//10718 10744//10744 -f 10698//10698 10744//10744 10704//10704 -f 10704//10704 10744//10744 10742//10742 -f 10704//10704 10742//10742 10703//10703 -f 10703//10703 10742//10742 10741//10741 -f 10703//10703 10741//10741 10690//10690 -f 10690//10690 10741//10741 10770//10770 -f 10690//10690 10770//10770 10688//10688 -f 10688//10688 10770//10770 10746//10746 -f 10688//10688 10746//10746 10669//10669 -f 10667//10667 10748//10748 10750//10750 -f 10667//10667 10750//10750 10665//10665 -f 10665//10665 10750//10750 10752//10752 -f 10665//10665 10752//10752 10663//10663 -f 10663//10663 10752//10752 10766//10766 -f 10663//10663 10766//10766 10671//10671 -f 10671//10671 10766//10766 10767//10767 -f 10671//10671 10767//10767 10673//10673 -f 10673//10673 10767//10767 10760//10760 -f 10673//10673 10760//10760 10661//10661 -f 10637//10637 10736//10736 10739//10739 -f 10637//10637 10739//10739 10676//10676 -f 10676//10676 10739//10739 10740//10740 -f 10676//10676 10740//10740 10674//10674 -f 10674//10674 10740//10740 10716//10716 -f 10674//10674 10716//10716 10675//10675 -f 10658//10658 10713//10713 10728//10728 -f 10658//10658 10728//10728 10657//10657 -f 10657//10657 10728//10728 10729//10729 -f 10657//10657 10729//10729 10655//10655 -f 10655//10655 10729//10729 10706//10706 -f 10655//10655 10706//10706 10653//10653 -f 10777//10777 10778//10778 10779//10779 -f 10780//10780 10781//10781 10782//10782 -f 10783//10783 10784//10784 10785//10785 -f 10786//10786 10787//10787 10788//10788 -f 10789//10789 10790//10790 10791//10791 -f 10791//10791 10790//10790 10792//10792 -f 10793//10793 10794//10794 10795//10795 -f 10795//10795 10794//10794 10796//10796 -f 10787//10787 10797//10797 10788//10788 -f 10788//10788 10797//10797 10798//10798 -f 10788//10788 10798//10798 10789//10789 -f 10789//10789 10798//10798 10799//10799 -f 10789//10789 10799//10799 10790//10790 -f 10788//10788 10800//10800 10786//10786 -f 10786//10786 10800//10800 10801//10801 -f 10786//10786 10801//10801 10802//10802 -f 10802//10802 10801//10801 10803//10803 -f 10802//10802 10803//10803 10804//10804 -f 10804//10804 10803//10803 10805//10805 -f 10804//10804 10805//10805 10796//10796 -f 10796//10796 10805//10805 10806//10806 -f 10796//10796 10806//10806 10795//10795 -f 10788//10788 10807//10807 10800//10800 -f 10800//10800 10807//10807 10808//10808 -f 10800//10800 10808//10808 10809//10809 -f 10809//10809 10808//10808 10810//10810 -f 10809//10809 10810//10810 10811//10811 -f 10811//10811 10810//10810 10812//10812 -f 10813//10813 10814//10814 10815//10815 -f 10815//10815 10814//10814 10816//10816 -f 10815//10815 10816//10816 10812//10812 -f 10812//10812 10816//10816 10817//10817 -f 10812//10812 10817//10817 10818//10818 -f 10819//10819 10820//10820 10821//10821 -f 10821//10821 10820//10820 10822//10822 -f 10823//10823 10824//10824 10825//10825 -f 10825//10825 10824//10824 10826//10826 -f 10825//10825 10826//10826 10827//10827 -f 10827//10827 10826//10826 10828//10828 -f 10827//10827 10828//10828 10829//10829 -f 10819//10819 10821//10821 10818//10818 -f 10818//10818 10821//10821 10830//10830 -f 10818//10818 10830//10830 10812//10812 -f 10812//10812 10830//10830 10831//10831 -f 10812//10812 10831//10831 10811//10811 -f 10832//10832 10822//10822 10833//10833 -f 10833//10833 10822//10822 10834//10834 -f 10833//10833 10834//10834 10835//10835 -f 10835//10835 10834//10834 10836//10836 -f 10835//10835 10836//10836 10837//10837 -f 10820//10820 10823//10823 10822//10822 -f 10822//10822 10823//10823 10825//10825 -f 10822//10822 10825//10825 10834//10834 -f 10834//10834 10825//10825 10838//10838 -f 10834//10834 10838//10838 10836//10836 -f 10836//10836 10838//10838 10839//10839 -f 10840//10840 10841//10841 10777//10777 -f 10777//10777 10841//10841 10842//10842 -f 10843//10843 10839//10839 10844//10844 -f 10844//10844 10839//10839 10845//10845 -f 10844//10844 10845//10845 10846//10846 -f 10846//10846 10845//10845 10847//10847 -f 10848//10848 10849//10849 10850//10850 -f 10850//10850 10849//10849 10851//10851 -f 10850//10850 10851//10851 10852//10852 -f 10851//10851 10853//10853 10852//10852 -f 10852//10852 10853//10853 10854//10854 -f 10852//10852 10854//10854 10855//10855 -f 10855//10855 10854//10854 10856//10856 -f 10855//10855 10856//10856 10857//10857 -f 10858//10858 10859//10859 10860//10860 -f 10860//10860 10859//10859 10861//10861 -f 10860//10860 10861//10861 10862//10862 -f 10862//10862 10861//10861 10863//10863 -f 10858//10858 10864//10864 10859//10859 -f 10859//10859 10864//10864 10865//10865 -f 10859//10859 10865//10865 10849//10849 -f 10866//10866 10785//10785 10867//10867 -f 10867//10867 10785//10785 10868//10868 -f 10867//10867 10868//10868 10869//10869 -f 10865//10865 10870//10870 10849//10849 -f 10849//10849 10870//10870 10871//10871 -f 10849//10849 10871//10871 10851//10851 -f 10851//10851 10871//10871 10872//10872 -f 10851//10851 10872//10872 10873//10873 -f 10873//10873 10872//10872 10869//10869 -f 10873//10873 10869//10869 10874//10874 -f 10874//10874 10869//10869 10868//10868 -f 10783//10783 10785//10785 10875//10875 -f 10875//10875 10785//10785 10876//10876 -f 10875//10875 10876//10876 10877//10877 -f 10877//10877 10876//10876 10878//10878 -f 10877//10877 10878//10878 10879//10879 -f 10879//10879 10878//10878 10880//10880 -f 10879//10879 10880//10880 10881//10881 -f 10881//10881 10880//10880 10782//10782 -f 10782//10782 10880//10880 10882//10882 -f 10782//10782 10882//10882 10780//10780 -f 10883//10883 10884//10884 10880//10880 -f 10880//10880 10884//10884 10885//10885 -f 10880//10880 10885//10885 10886//10886 -f 10887//10887 10882//10882 10888//10888 -f 10888//10888 10882//10882 10880//10880 -f 10888//10888 10880//10880 10889//10889 -f 10889//10889 10880//10880 10886//10886 -f 10890//10890 10891//10891 10883//10883 -f 10883//10883 10891//10891 10892//10892 -f 10883//10883 10892//10892 10884//10884 -f 10889//10889 10893//10893 10888//10888 -f 10888//10888 10893//10893 10894//10894 -f 10888//10888 10894//10894 10895//10895 -f 10895//10895 10894//10894 10896//10896 -f 10896//10896 10897//10897 10895//10895 -f 10895//10895 10897//10897 10898//10898 -f 10895//10895 10898//10898 10890//10890 -f 10890//10890 10898//10898 10899//10899 -f 10890//10890 10899//10899 10891//10891 -f 10900//10900 10901//10901 10902//10902 -f 10902//10902 10903//10903 10900//10900 -f 10900//10900 10903//10903 10904//10904 -f 10900//10900 10904//10904 10878//10878 -f 10878//10878 10904//10904 10905//10905 -f 10878//10878 10905//10905 10906//10906 -f 10906//10906 10907//10907 10878//10878 -f 10878//10878 10907//10907 10908//10908 -f 10878//10878 10908//10908 10880//10880 -f 10880//10880 10908//10908 10909//10909 -f 10880//10880 10909//10909 10883//10883 -f 10907//10907 10910//10910 10908//10908 -f 10908//10908 10910//10910 10911//10911 -f 10908//10908 10911//10911 10912//10912 -f 10912//10912 10911//10911 10913//10913 -f 10913//10913 10914//10914 10912//10912 -f 10912//10912 10914//10914 10915//10915 -f 10912//10912 10915//10915 10901//10901 -f 10901//10901 10915//10915 10916//10916 -f 10901//10901 10916//10916 10902//10902 -f 10917//10917 10918//10918 10919//10919 -f 10920//10920 10921//10921 10922//10922 -f 10922//10922 10921//10921 10923//10923 -f 10922//10922 10923//10923 10924//10924 -f 10924//10924 10923//10923 10925//10925 -f 10866//10866 10863//10863 10785//10785 -f 10785//10785 10863//10863 10861//10861 -f 10785//10785 10861//10861 10876//10876 -f 10876//10876 10861//10861 10926//10926 -f 10876//10876 10926//10926 10917//10917 -f 10919//10919 10927//10927 10917//10917 -f 10917//10917 10927//10927 10928//10928 -f 10917//10917 10928//10928 10876//10876 -f 10876//10876 10928//10928 10929//10929 -f 10876//10876 10929//10929 10930//10930 -f 10930//10930 10925//10925 10876//10876 -f 10876//10876 10925//10925 10923//10923 -f 10876//10876 10923//10923 10878//10878 -f 10878//10878 10923//10923 10931//10931 -f 10878//10878 10931//10931 10900//10900 -f 10920//10920 10932//10932 10921//10921 -f 10921//10921 10932//10932 10933//10933 -f 10921//10921 10933//10933 10918//10918 -f 10918//10918 10933//10933 10934//10934 -f 10918//10918 10934//10934 10919//10919 -f 10843//10843 10935//10935 10839//10839 -f 10839//10839 10935//10935 10936//10936 -f 10839//10839 10936//10936 10836//10836 -f 10836//10836 10936//10936 10937//10937 -f 10836//10836 10937//10937 10938//10938 -f 10938//10938 10937//10937 10939//10939 -f 10938//10938 10939//10939 10940//10940 -f 10940//10940 10939//10939 10941//10941 -f 10940//10940 10941//10941 10942//10942 -f 10942//10942 10941//10941 10840//10840 -f 10942//10942 10840//10840 10856//10856 -f 10856//10856 10840//10840 10777//10777 -f 10856//10856 10777//10777 10857//10857 -f 10857//10857 10777//10777 10779//10779 -f 10943//10943 10778//10778 10845//10845 -f 10845//10845 10778//10778 10777//10777 -f 10845//10845 10777//10777 10847//10847 -f 10847//10847 10777//10777 10842//10842 -f 10944//10944 10945//10945 10815//10815 -f 10815//10815 10945//10945 10827//10827 -f 10815//10815 10827//10827 10813//10813 -f 10813//10813 10827//10827 10829//10829 -f 10946//10946 10807//10807 10947//10947 -f 10947//10947 10807//10807 10788//10788 -f 10947//10947 10788//10788 10948//10948 -f 10948//10948 10788//10788 10789//10789 -f 10949//10949 10950//10950 10951//10951 -f 10952//10952 10953//10953 10954//10954 -f 10955//10955 10956//10956 10957//10957 -f 10957//10957 10956//10956 10954//10954 -f 10958//10958 10959//10959 10960//10960 -f 10960//10960 10959//10959 10955//10955 -f 10960//10960 10955//10955 10961//10961 -f 10961//10961 10955//10955 10957//10957 -f 10792//10792 10793//10793 10791//10791 -f 10791//10791 10793//10793 10795//10795 -f 10791//10791 10795//10795 10962//10962 -f 10962//10962 10795//10795 10951//10951 -f 10962//10962 10951//10951 10963//10963 -f 10963//10963 10951//10951 10950//10950 -f 10963//10963 10950//10950 10952//10952 -f 10952//10952 10950//10950 10964//10964 -f 10952//10952 10964//10964 10953//10953 -f 10958//10958 10965//10965 10959//10959 -f 10959//10959 10965//10965 10966//10966 -f 10959//10959 10966//10966 10951//10951 -f 10951//10951 10966//10966 10967//10967 -f 10951//10951 10967//10967 10949//10949 -f 10954//10954 10956//10956 10952//10952 -f 10952//10952 10956//10956 10968//10968 -f 10952//10952 10968//10968 10969//10969 -f 10970//10970 10971//10971 10959//10959 -f 10972//10972 10973//10973 10974//10974 -f 10974//10974 10973//10973 10975//10975 -f 10976//10976 10977//10977 10978//10978 -f 10978//10978 10977//10977 10975//10975 -f 10972//10972 10974//10974 10971//10971 -f 10971//10971 10974//10974 10979//10979 -f 10971//10971 10979//10979 10959//10959 -f 10959//10959 10979//10979 10980//10980 -f 10959//10959 10980//10980 10955//10955 -f 10978//10978 10981//10981 10976//10976 -f 10976//10976 10981//10981 10982//10982 -f 10976//10976 10982//10982 10983//10983 -f 10983//10983 10982//10982 10984//10984 -f 10984//10984 10985//10985 10983//10983 -f 10983//10983 10985//10985 10986//10986 -f 10983//10983 10986//10986 10959//10959 -f 10959//10959 10986//10986 10987//10987 -f 10959//10959 10987//10987 10970//10970 -f 10975//10975 10977//10977 10974//10974 -f 10974//10974 10977//10977 10988//10988 -f 10974//10974 10988//10988 10989//10989 -f 10990//10990 10991//10991 10983//10983 -f 10992//10992 10993//10993 10994//10994 -f 10995//10995 10996//10996 10997//10997 -f 10997//10997 10996//10996 10992//10992 -f 10997//10997 10992//10992 10983//10983 -f 10998//10998 10999//10999 10992//10992 -f 10992//10992 10999//10999 11000//11000 -f 10992//10992 11000//11000 11001//11001 -f 11002//11002 11003//11003 11004//11004 -f 11004//11004 11003//11003 11005//11005 -f 10992//10992 10994//10994 10998//10998 -f 10998//10998 10994//10994 11006//11006 -f 10998//10998 11006//11006 11005//11005 -f 11001//11001 11007//11007 10992//10992 -f 10992//10992 11007//11007 11008//11008 -f 10992//10992 11008//11008 10983//10983 -f 10983//10983 11008//11008 11009//11009 -f 10983//10983 11009//11009 10990//10990 -f 11002//11002 11004//11004 10991//10991 -f 10991//10991 11004//11004 11010//11010 -f 10991//10991 11010//11010 10983//10983 -f 10983//10983 11010//11010 11011//11011 -f 10983//10983 11011//11011 10976//10976 -f 11005//11005 11006//11006 11004//11004 -f 11004//11004 11006//11006 11012//11012 -f 11004//11004 11012//11012 11013//11013 -f 10795//10795 11014//11014 11015//11015 -f 11016//11016 11017//11017 11018//11018 -f 11018//11018 11017//11017 10997//10997 -f 11018//11018 10997//10997 11019//11019 -f 11019//11019 10997//10997 10983//10983 -f 11019//11019 10983//10983 11020//11020 -f 11020//11020 10983//10983 10959//10959 -f 11020//11020 10959//10959 11015//11015 -f 11015//11015 10959//10959 10951//10951 -f 11015//11015 10951//10951 10795//10795 -f 11021//11021 11022//11022 10832//10832 -f 11021//11021 10832//10832 11023//11023 -f 11023//11023 10832//10832 10833//10833 -f 11023//11023 10833//10833 10835//10835 -f 11024//11024 11025//11025 11026//11026 -f 11027//11027 11028//11028 11029//11029 -f 11028//11028 11030//11030 11029//11029 -f 11029//11029 11030//11030 11031//11031 -f 11029//11029 11031//11031 11032//11032 -f 11033//11033 11034//11034 11029//11029 -f 11029//11029 11034//11034 11024//11024 -f 11024//11024 11026//11026 11029//11029 -f 11029//11029 11026//11026 11035//11035 -f 11029//11029 11035//11035 11027//11027 -f 11036//11036 11037//11037 11038//11038 -f 11038//11038 11037//11037 11032//11032 -f 11038//11038 11032//11032 11039//11039 -f 11039//11039 11032//11032 11031//11031 -f 10669//10669 10667//10667 11040//11040 -f 11040//11040 10667//10667 11041//11041 -f 11042//11042 10669//10669 11043//11043 -f 11043//11043 10669//10669 11040//11040 -f 11043//11043 11040//11040 11044//11044 -f 11044//11044 11040//11040 11045//11045 -f 11018//11018 11019//11019 11046//11046 -f 11018//11018 11046//11046 11047//11047 -f 11048//11048 11049//11049 11050//11050 -f 11051//11051 11052//11052 11053//11053 -f 11053//11053 11052//11052 11054//11054 -f 11053//11053 11054//11054 11055//11055 -f 11055//11055 11054//11054 11056//11056 -f 11055//11055 11056//11056 11057//11057 -f 11057//11057 11056//11056 11058//11058 -f 11057//11057 11058//11058 11059//11059 -f 11059//11059 11058//11058 11060//11060 -f 11061//11061 11062//11062 11063//11063 -f 11063//11063 11062//11062 11064//11064 -f 11063//11063 11064//11064 11065//11065 -f 11065//11065 11064//11064 11066//11066 -f 11065//11065 11066//11066 11067//11067 -f 11067//11067 11066//11066 11068//11068 -f 11068//11068 11069//11069 11067//11067 -f 11067//11067 11069//11069 11070//11070 -f 11067//11067 11070//11070 11071//11071 -f 11071//11071 11070//11070 11072//11072 -f 11069//11069 11073//11073 11070//11070 -f 11070//11070 11073//11073 11074//11074 -f 11070//11070 11074//11074 11051//11051 -f 11051//11051 11074//11074 11075//11075 -f 11051//11051 11075//11075 11052//11052 -f 11063//11063 11076//11076 11061//11061 -f 11061//11061 11076//11076 11077//11077 -f 11061//11061 11077//11077 11049//11049 -f 11049//11049 11077//11077 11078//11078 -f 11049//11049 11078//11078 11050//11050 -f 11079//11079 11080//11080 11081//11081 -f 11081//11081 11080//11080 11082//11082 -f 11081//11081 11082//11082 11083//11083 -f 11083//11083 11082//11082 11084//11084 -f 11083//11083 11084//11084 11050//11050 -f 11050//11050 11084//11084 11085//11085 -f 11050//11050 11085//11085 11048//11048 -f 11086//11086 11087//11087 11058//11058 -f 11058//11058 11087//11087 11088//11088 -f 11058//11058 11088//11088 11060//11060 -f 11086//11086 11089//11089 11087//11087 -f 11087//11087 11089//11089 11090//11090 -f 11087//11087 11090//11090 11046//11046 -f 11046//11046 11090//11090 11091//11091 -f 11046//11046 11091//11091 11092//11092 -f 11092//11092 11093//11093 11046//11046 -f 11046//11046 11093//11093 11079//11079 -f 11046//11046 11079//11079 11047//11047 -f 11047//11047 11079//11079 11081//11081 -f 10667//10667 10665//10665 11041//11041 -f 11041//11041 10665//10665 11094//11094 -f 11094//11094 10665//10665 11095//11095 -f 11095//11095 10665//10665 10663//10663 -f 11095//11095 10663//10663 11096//11096 -f 11096//11096 10663//10663 11097//11097 -f 11097//11097 10663//10663 10671//10671 -f 11097//11097 10671//10671 11098//11098 -f 11098//11098 10671//10671 11099//11099 -f 11099//11099 10671//10671 10673//10673 -f 11099//11099 10673//10673 11100//11100 -f 11101//11101 11102//11102 11103//11103 -f 11100//11100 10673//10673 11103//11103 -f 11103//11103 10673//10673 10661//10661 -f 11103//11103 10661//10661 11101//11101 -f 11104//11104 11105//11105 11106//11106 -f 11107//11107 11108//11108 11109//11109 -f 11104//11104 11106//11106 11110//11110 -f 11106//11106 11111//11111 11110//11110 -f 11110//11110 11111//11111 11112//11112 -f 11110//11110 11112//11112 11113//11113 -f 11107//11107 11109//11109 11114//11114 -f 11109//11109 11115//11115 11114//11114 -f 11114//11114 11115//11115 11116//11116 -f 11114//11114 11116//11116 11104//11104 -f 11104//11104 11116//11116 11117//11117 -f 11104//11104 11117//11117 11105//11105 -f 11112//11112 11118//11118 11113//11113 -f 11113//11113 11118//11118 11119//11119 -f 11113//11113 11119//11119 11107//11107 -f 11107//11107 11119//11119 11120//11120 -f 11107//11107 11120//11120 11108//11108 -f 11121//11121 11122//11122 11123//11123 -f 11123//11123 11122//11122 11124//11124 -f 11125//11125 11126//11126 11127//11127 -f 11127//11127 11126//11126 11128//11128 -f 11128//11128 11129//11129 11127//11127 -f 11127//11127 11129//11129 11130//11130 -f 11127//11127 11130//11130 11131//11131 -f 11130//11130 11132//11132 11131//11131 -f 11131//11131 11132//11132 11133//11133 -f 11131//11131 11133//11133 11121//11121 -f 11121//11121 11133//11133 11134//11134 -f 11121//11121 11134//11134 11122//11122 -f 11124//11124 11135//11135 11123//11123 -f 11123//11123 11135//11135 11136//11136 -f 11123//11123 11136//11136 11125//11125 -f 11125//11125 11136//11136 11137//11137 -f 11125//11125 11137//11137 11126//11126 -f 11138//11138 11139//11139 11140//11140 -f 11140//11140 11139//11139 11141//11141 -f 11142//11142 11143//11143 11138//11138 -f 11138//11138 11143//11143 11144//11144 -f 11138//11138 11144//11144 11139//11139 -f 11141//11141 11145//11145 11140//11140 -f 11140//11140 11145//11145 11146//11146 -f 11140//11140 11146//11146 11147//11147 -f 11148//11148 11149//11149 11150//11150 -f 11150//11150 11149//11149 11147//11147 -f 11150//11150 11147//11147 11151//11151 -f 11151//11151 11147//11147 11146//11146 -f 11148//11148 11152//11152 11149//11149 -f 11149//11149 11152//11152 11153//11153 -f 11149//11149 11153//11153 11142//11142 -f 11142//11142 11153//11153 11154//11154 -f 11142//11142 11154//11154 11143//11143 -f 11155//11155 11156//11156 11157//11157 -f 11157//11157 11156//11156 11158//11158 -f 11159//11159 11160//11160 11161//11161 -f 10664//10664 10672//10672 10663//10663 -f 11162//11162 11163//11163 11164//11164 -f 11164//11164 11163//11163 11165//11165 -f 10663//10663 10672//10672 10671//10671 -f 10671//10671 10672//10672 10644//10644 -f 10671//10671 10644//10644 10673//10673 -f 11166//11166 11167//11167 11168//11168 -f 11168//11168 11167//11167 11169//11169 -f 11170//11170 11171//11171 11172//11172 -f 11172//11172 11171//11171 11173//11173 -f 11172//11172 11173//11173 11174//11174 -f 11175//11175 11176//11176 11177//11177 -f 11178//11178 11179//11179 11180//11180 -f 11180//11180 11179//11179 11181//11181 -f 11182//11182 11183//11183 11184//11184 -f 11185//11185 10696//10696 10640//10640 -f 11186//11186 11187//11187 11188//11188 -f 11188//11188 11187//11187 11189//11189 -f 10690//10690 10703//10703 10640//10640 -f 11190//11190 11191//11191 11192//11192 -f 11192//11192 11191//11191 11193//11193 -f 10677//10677 11194//11194 11195//11195 -f 11196//11196 11197//11197 11198//11198 -f 11198//11198 11197//11197 11199//11199 -f 11200//11200 11201//11201 11202//11202 -f 11202//11202 11201//11201 11203//11203 -f 10703//10703 10704//10704 10640//10640 -f 10640//10640 10704//10704 10698//10698 -f 10640//10640 10698//10698 11185//11185 -f 11169//11169 11182//11182 10696//10696 -f 11204//11204 11205//11205 11206//11206 -f 11206//11206 11205//11205 11207//11207 -f 10693//10693 11177//11177 10694//10694 -f 10694//10694 11177//11177 10695//10695 -f 11208//11208 11164//11164 11185//11185 -f 11185//11185 11164//11164 11165//11165 -f 11185//11185 11165//11165 10696//10696 -f 10696//10696 11165//11165 11180//11180 -f 10696//10696 11180//11180 11169//11169 -f 11169//11169 11180//11180 11181//11181 -f 11169//11169 11181//11181 11168//11168 -f 11209//11209 11210//11210 11211//11211 -f 11211//11211 11210//11210 11194//11194 -f 11211//11211 11194//11194 11193//11193 -f 11193//11193 11194//11194 10677//10677 -f 11193//11193 10677//10677 10700//10700 -f 11212//11212 11213//11213 11195//11195 -f 11195//11195 11213//11213 11175//11175 -f 11195//11195 11175//11175 10677//10677 -f 10677//10677 11175//11175 11177//11177 -f 10677//10677 11177//11177 10678//10678 -f 11214//11214 11215//11215 11216//11216 -f 11216//11216 11215//11215 11217//11217 -f 10646//10646 10639//10639 10641//10641 -f 11184//11184 11174//11174 11182//11182 -f 11182//11182 11174//11174 11173//11173 -f 11182//11182 11173//11173 10696//10696 -f 10696//10696 11173//11173 11192//11192 -f 10696//10696 11192//11192 10697//10697 -f 10697//10697 11192//11192 11193//11193 -f 10697//10697 11193//11193 10699//10699 -f 10699//10699 11193//11193 10700//10700 -f 10652//10652 10641//10641 10691//10691 -f 10691//10691 10641//10641 10643//10643 -f 10691//10691 10643//10643 10693//10693 -f 10644//10644 10646//10646 10645//10645 -f 10645//10645 10646//10646 10641//10641 -f 10645//10645 10641//10641 10651//10651 -f 10651//10651 10641//10641 10652//10652 -f 10639//10639 10646//10646 10696//10696 -f 10696//10696 10646//10646 10647//10647 -f 10696//10696 10647//10647 10650//10650 -f 11218//11218 11219//11219 11220//11220 -f 11220//11220 11219//11219 11221//11221 -f 11220//11220 11221//11221 11222//11222 -f 10643//10643 10649//10649 10693//10693 -f 10693//10693 10649//10649 10648//10648 -f 10693//10693 10648//10648 11177//11177 -f 11177//11177 10648//10648 10638//10638 -f 11177//11177 10638//10638 10678//10678 -f 10680//10680 10679//10679 10696//10696 -f 10696//10696 10679//10679 10642//10642 -f 10696//10696 10642//10642 10640//10640 -f 10686//10686 10667//10667 10687//10687 -f 10687//10687 10667//10667 10669//10669 -f 10687//10687 10669//10669 10689//10689 -f 10689//10689 10669//10669 10688//10688 -f 10689//10689 10688//10688 10701//10701 -f 10701//10701 10688//10688 10690//10690 -f 10701//10701 10690//10690 10702//10702 -f 10702//10702 10690//10690 10640//10640 -f 11161//11161 11223//11223 11159//11159 -f 11159//11159 11223//11223 11224//11224 -f 11159//11159 11224//11224 11225//11225 -f 11226//11226 11227//11227 10695//10695 -f 10681//10681 10680//10680 10682//10682 -f 10682//10682 10680//10680 10696//10696 -f 10682//10682 10696//10696 10692//10692 -f 10692//10692 10696//10696 10650//10650 -f 10664//10664 10663//10663 10666//10666 -f 10666//10666 10663//10663 10665//10665 -f 10666//10666 10665//10665 10668//10668 -f 10668//10668 10665//10665 10667//10667 -f 10668//10668 10667//10667 10670//10670 -f 10670//10670 10667//10667 10686//10686 -f 10670//10670 10686//10686 10684//10684 -f 10684//10684 10686//10686 10685//10685 -f 10684//10684 10685//10685 10682//10682 -f 10682//10682 10685//10685 10683//10683 -f 10682//10682 10683//10683 10681//10681 -f 11228//11228 11229//11229 11230//11230 -f 11230//11230 11229//11229 11231//11231 -f 11230//11230 11231//11231 11232//11232 -f 11233//11233 11234//11234 11232//11232 -f 11232//11232 11234//11234 11226//11226 -f 11232//11232 11226//11226 11230//11230 -f 11230//11230 11226//11226 10695//10695 -f 11230//11230 10695//10695 11158//11158 -f 11158//11158 10695//10695 11177//11177 -f 11158//11158 11177//11177 11157//11157 -f 11157//11157 11177//11177 11235//11235 -f 11217//11217 10660//10660 11216//11216 -f 11216//11216 10660//10660 10659//10659 -f 11216//11216 10659//10659 10656//10656 -f 11188//11188 10645//10645 11217//11217 -f 11217//11217 10645//10645 10662//10662 -f 11217//11217 10662//10662 10660//10660 -f 11236//11236 11237//11237 11227//11227 -f 11227//11227 11237//11237 11238//11238 -f 11227//11227 11238//11238 10695//10695 -f 10695//10695 11238//11238 11239//11239 -f 11240//11240 11216//11216 11241//11241 -f 11241//11241 11216//11216 10656//10656 -f 11241//11241 10656//10656 11239//11239 -f 11239//11239 10656//10656 10654//10654 -f 11239//11239 10654//10654 10695//10695 -f 11189//11189 11198//11198 11188//11188 -f 11188//11188 11198//11198 11199//11199 -f 11188//11188 11199//11199 10645//10645 -f 10645//10645 11199//11199 11202//11202 -f 11242//11242 11159//11159 10645//10645 -f 10645//10645 11159//11159 11225//11225 -f 10645//10645 11225//11225 10644//10644 -f 10644//10644 11225//11225 10661//10661 -f 10644//10644 10661//10661 10673//10673 -f 11203//11203 11206//11206 11202//11202 -f 11202//11202 11206//11206 11207//11207 -f 11202//11202 11207//11207 10645//10645 -f 10645//10645 11207//11207 11220//11220 -f 10645//10645 11220//11220 11242//11242 -f 11242//11242 11220//11220 11222//11222 -f 11242//11242 11222//11222 11243//11243 -f 11243//11243 11222//11222 11244//11244 -f 11245//11245 11246//11246 11247//11247 -f 11247//11247 11246//11246 11248//11248 -f 11247//11247 11248//11248 11249//11249 -f 11249//11249 11248//11248 11250//11250 -f 11249//11249 11250//11250 11251//11251 -f 11252//11252 11253//11253 11254//11254 -f 11254//11254 11253//11253 11255//11255 -f 11254//11254 11255//11255 11256//11256 -f 11256//11256 11255//11255 11257//11257 -f 11256//11256 11257//11257 11258//11258 -f 11259//11259 11260//11260 11261//11261 -f 11261//11261 11260//11260 11262//11262 -f 11261//11261 11262//11262 11263//11263 -f 11263//11263 11262//11262 11264//11264 -f 11263//11263 11264//11264 11265//11265 -f 11266//11266 11267//11267 11110//11110 -f 11110//11110 11267//11267 11268//11268 -f 11110//11110 11268//11268 11104//11104 -f 11104//11104 11268//11268 11269//11269 -f 11104//11104 11269//11269 11270//11270 -f 11270//11270 11269//11269 11271//11271 -f 11272//11272 11273//11273 11131//11131 -f 11131//11131 11273//11273 11274//11274 -f 11131//11131 11274//11274 11127//11127 -f 11127//11127 11274//11274 11275//11275 -f 11127//11127 11275//11275 11276//11276 -f 11276//11276 11275//11275 11277//11277 -f 11278//11278 11279//11279 11147//11147 -f 11147//11147 11279//11279 11280//11280 -f 11147//11147 11280//11280 11140//11140 -f 11140//11140 11280//11280 11281//11281 -f 11140//11140 11281//11281 11282//11282 -f 11282//11282 11281//11281 11283//11283 -f 11284//11284 11285//11285 11286//11286 -f 11286//11286 11285//11285 11287//11287 -f 11288//11288 11289//11289 11290//11290 -f 11291//11291 11292//11292 11293//11293 -f 11293//11293 11292//11292 11288//11288 -f 11293//11293 11288//11288 11294//11294 -f 11294//11294 11288//11288 11290//11290 -f 11291//11291 11295//11295 11292//11292 -f 11292//11292 11295//11295 11296//11296 -f 11292//11292 11296//11296 11284//11284 -f 11284//11284 11296//11296 11297//11297 -f 11284//11284 11297//11297 11285//11285 -f 11287//11287 11298//11298 11286//11286 -f 11286//11286 11298//11298 11299//11299 -f 11286//11286 11299//11299 11289//11289 -f 11289//11289 11299//11299 11300//11300 -f 11289//11289 11300//11300 11290//11290 -f 11301//11301 11302//11302 11303//11303 -f 11303//11303 11302//11302 11304//11304 -f 11305//11305 11306//11306 11307//11307 -f 11307//11307 11306//11306 11308//11308 -f 11307//11307 11308//11308 11309//11309 -f 11309//11309 11308//11308 11310//11310 -f 11309//11309 11310//11310 11311//11311 -f 11303//11303 11312//11312 11301//11301 -f 11301//11301 11312//11312 11313//11313 -f 11301//11301 11313//11313 11310//11310 -f 11310//11310 11313//11313 11314//11314 -f 11310//11310 11314//11314 11311//11311 -f 11305//11305 11315//11315 11306//11306 -f 11306//11306 11315//11315 11316//11316 -f 11306//11306 11316//11316 11302//11302 -f 11302//11302 11316//11316 11317//11317 -f 11302//11302 11317//11317 11304//11304 -f 11318//11318 11319//11319 11320//11320 -f 11320//11320 11319//11319 11321//11321 -f 11320//11320 11321//11321 11322//11322 -f 11322//11322 11321//11321 11323//11323 -f 11322//11322 11323//11323 11324//11324 -f 11325//11325 11326//11326 11289//11289 -f 11289//11289 11326//11326 11327//11327 -f 11289//11289 11327//11327 11286//11286 -f 11286//11286 11327//11327 11328//11328 -f 11286//11286 11328//11328 11329//11329 -f 11329//11329 11328//11328 11330//11330 -f 11331//11331 11332//11332 11333//11333 -f 11334//11334 11335//11335 11336//11336 -f 11331//11331 11333//11333 11336//11336 -f 11336//11336 11333//11333 11337//11337 -f 11336//11336 11337//11337 11334//11334 -f 11338//11338 11339//11339 11301//11301 -f 11301//11301 11339//11339 11340//11340 -f 11301//11301 11340//11340 11302//11302 -f 11302//11302 11340//11340 11341//11341 -f 11302//11302 11341//11341 11342//11342 -f 11342//11342 11341//11341 11343//11343 -f 11344//11344 11185//11185 11345//11345 -f 11345//11345 11185//11185 10698//10698 -f 11101//11101 10661//10661 11346//11346 -f 11346//11346 10661//10661 11225//11225 -f 11225//11225 11224//11224 11346//11346 -f 11346//11346 11224//11224 11347//11347 -f 11346//11346 11347//11347 11348//11348 -f 11348//11348 11347//11347 10993//10993 -f 11348//11348 10993//10993 11349//11349 -f 11349//11349 10993//10993 10992//10992 -f 11347//11347 11224//11224 11350//11350 -f 11350//11350 11224//11224 11223//11223 -f 11006//11006 10994//10994 11350//11350 -f 11350//11350 11223//11223 11161//11161 -f 11006//11006 11350//11350 11012//11012 -f 11012//11012 11350//11350 11269//11269 -f 11269//11269 11350//11350 11161//11161 -f 11269//11269 11161//11161 11271//11271 -f 11244//11244 11222//11222 11351//11351 -f 11351//11351 11010//11010 11004//11004 -f 11244//11244 11351//11351 11267//11267 -f 11267//11267 11351//11351 11268//11268 -f 11268//11268 11351//11351 11004//11004 -f 11268//11268 11004//11004 11013//11013 -f 11351//11351 11222//11222 11352//11352 -f 11352//11352 11222//11222 11221//11221 -f 10977//10977 10976//10976 11352//11352 -f 11352//11352 11221//11221 11219//11219 -f 10977//10977 11352//11352 10988//10988 -f 10988//10988 11352//11352 11275//11275 -f 11275//11275 11352//11352 11219//11219 -f 11275//11275 11219//11219 11277//11277 -f 11204//11204 11206//11206 11353//11353 -f 11353//11353 10979//10979 10974//10974 -f 11204//11204 11353//11353 11273//11273 -f 11273//11273 11353//11353 11274//11274 -f 11274//11274 11353//11353 10974//10974 -f 11274//11274 10974//10974 10989//10989 -f 11353//11353 11206//11206 11354//11354 -f 11354//11354 11206//11206 11203//11203 -f 10956//10956 10955//10955 11354//11354 -f 11354//11354 11203//11203 11201//11201 -f 10956//10956 11354//11354 10968//10968 -f 10968//10968 11354//11354 11281//11281 -f 11281//11281 11354//11354 11201//11201 -f 11281//11281 11201//11201 11283//11283 -f 11196//11196 11198//11198 11355//11355 -f 11355//11355 10963//10963 10952//10952 -f 11196//11196 11355//11355 11279//11279 -f 11279//11279 11355//11355 11280//11280 -f 11280//11280 11355//11355 10952//10952 -f 11280//11280 10952//10952 10969//10969 -f 11355//11355 11198//11198 11356//11356 -f 11356//11356 11198//11198 11189//11189 -f 10789//10789 10791//10791 11356//11356 -f 11356//11356 11189//11189 11187//11187 -f 10789//10789 11356//11356 10948//10948 -f 10948//10948 11356//11356 11328//11328 -f 11328//11328 11356//11356 11187//11187 -f 11328//11328 11187//11187 11330//11330 -f 11214//11214 11216//11216 11357//11357 -f 11357//11357 10808//10808 10807//10807 -f 11214//11214 11357//11357 11326//11326 -f 11326//11326 11357//11357 11327//11327 -f 11327//11327 11357//11357 10807//10807 -f 11327//11327 10807//10807 10946//10946 -f 11357//11357 11216//11216 11358//11358 -f 11358//11358 11216//11216 11240//11240 -f 11358//11358 11240//11240 10810//10810 -f 10810//10810 11240//11240 11241//11241 -f 10810//10810 11241//11241 11359//11359 -f 11359//11359 11241//11241 11239//11239 -f 11359//11359 11239//11239 11360//11360 -f 11360//11360 11239//11239 11238//11238 -f 10815//10815 10812//10812 11360//11360 -f 11360//11360 11238//11238 11237//11237 -f 10815//10815 11360//11360 10944//10944 -f 10944//10944 11360//11360 11341//11341 -f 11341//11341 11360//11360 11237//11237 -f 11341//11341 11237//11237 11343//11343 -f 11233//11233 11232//11232 11361//11361 -f 11361//11361 10825//10825 10827//10827 -f 11233//11233 11361//11361 11339//11339 -f 11339//11339 11361//11361 11340//11340 -f 11340//11340 11361//11361 10827//10827 -f 11340//11340 10827//10827 10945//10945 -f 11361//11361 11232//11232 11362//11362 -f 11362//11362 11232//11232 11231//11231 -f 10845//10845 10839//10839 11362//11362 -f 11362//11362 11231//11231 11229//11229 -f 10845//10845 11362//11362 10943//10943 -f 10943//10943 11362//11362 11363//11363 -f 11363//11363 11362//11362 11229//11229 -f 11363//11363 11229//11229 11364//11364 -f 11365//11365 11366//11366 11367//11367 -f 11367//11367 11366//11366 11368//11368 -f 11367//11367 11368//11368 11369//11369 -f 11369//11369 11368//11368 11363//11363 -f 11369//11369 11363//11363 11370//11370 -f 11370//11370 11363//11363 11364//11364 -f 11155//11155 11157//11157 11371//11371 -f 11371//11371 10855//10855 10857//10857 -f 11155//11155 11371//11371 11366//11366 -f 11366//11366 11371//11371 11368//11368 -f 11368//11368 11371//11371 10857//10857 -f 11368//11368 10857//10857 10779//10779 -f 11371//11371 11157//11157 11372//11372 -f 11372//11372 11157//11157 11235//11235 -f 11372//11372 11235//11235 10852//10852 -f 10852//10852 11235//11235 11177//11177 -f 10852//10852 11177//11177 11373//11373 -f 11373//11373 11177//11177 11176//11176 -f 11373//11373 11176//11176 11374//11374 -f 11374//11374 11176//11176 11175//11175 -f 11213//11213 11375//11375 11376//11376 -f 11175//11175 11213//11213 11374//11374 -f 11374//11374 11213//11213 11376//11376 -f 11374//11374 11376//11376 10850//10850 -f 10850//10850 11376//11376 10848//10848 -f 11377//11377 11378//11378 11379//11379 -f 11379//11379 11378//11378 11380//11380 -f 11379//11379 11380//11380 11381//11381 -f 11381//11381 11380//11380 11376//11376 -f 11381//11381 11376//11376 11382//11382 -f 11382//11382 11376//11376 11375//11375 -f 10861//10861 10859//10859 11383//11383 -f 11383//11383 10859//10859 11380//11380 -f 11380//11380 11378//11378 11383//11383 -f 11383//11383 11378//11378 11209//11209 -f 11383//11383 11209//11209 11211//11211 -f 11383//11383 11211//11211 11384//11384 -f 11384//11384 11211//11211 11193//11193 -f 11191//11191 11385//11385 11386//11386 -f 11193//11193 11191//11191 11384//11384 -f 11384//11384 11191//11191 11386//11386 -f 11384//11384 11386//11386 10917//10917 -f 10917//10917 11386//11386 10918//10918 -f 11387//11387 11388//11388 11389//11389 -f 11389//11389 11388//11388 11390//11390 -f 11389//11389 11390//11390 11391//11391 -f 11391//11391 11390//11390 11386//11386 -f 11391//11391 11386//11386 11392//11392 -f 11392//11392 11386//11386 11385//11385 -f 10923//10923 10921//10921 11393//11393 -f 11393//11393 10921//10921 11390//11390 -f 11390//11390 11388//11388 11393//11393 -f 11393//11393 11388//11388 11170//11170 -f 11393//11393 11170//11170 11172//11172 -f 11393//11393 11172//11172 11394//11394 -f 11394//11394 11172//11172 11174//11174 -f 11184//11184 11395//11395 11396//11396 -f 11174//11174 11184//11184 11394//11394 -f 11394//11394 11184//11184 11396//11396 -f 11394//11394 11396//11396 10900//10900 -f 10900//10900 11396//11396 10901//10901 -f 11397//11397 11398//11398 11399//11399 -f 11399//11399 11398//11398 11400//11400 -f 11399//11399 11400//11400 11401//11401 -f 11401//11401 11400//11400 11396//11396 -f 11401//11401 11396//11396 11402//11402 -f 11402//11402 11396//11396 11395//11395 -f 10908//10908 10912//10912 11403//11403 -f 11403//11403 10912//10912 11400//11400 -f 11400//11400 11398//11398 11403//11403 -f 11403//11403 11398//11398 11166//11166 -f 11403//11403 11166//11166 11168//11168 -f 11403//11403 11168//11168 11404//11404 -f 11404//11404 11168//11168 11181//11181 -f 11179//11179 11405//11405 11406//11406 -f 11181//11181 11179//11179 11404//11404 -f 11404//11404 11179//11179 11406//11406 -f 11404//11404 11406//11406 10883//10883 -f 10883//10883 11406//11406 10890//10890 -f 11407//11407 11408//11408 11409//11409 -f 11409//11409 11408//11408 11410//11410 -f 11409//11409 11410//11410 11411//11411 -f 11411//11411 11410//11410 11406//11406 -f 11411//11411 11406//11406 11412//11412 -f 11412//11412 11406//11406 11405//11405 -f 10888//10888 10895//10895 11413//11413 -f 11413//11413 10895//10895 11410//11410 -f 11410//11410 11408//11408 11413//11413 -f 11413//11413 11408//11408 11162//11162 -f 11413//11413 11162//11162 11164//11164 -f 11413//11413 11164//11164 11414//11414 -f 11414//11414 11164//11164 11208//11208 -f 11415//11415 10882//10882 10887//10887 -f 11208//11208 11185//11185 11414//11414 -f 11414//11414 11185//11185 11344//11344 -f 11414//11414 11344//11344 10887//10887 -f 10887//10887 11344//11344 11416//11416 -f 10887//10887 11416//11416 11415//11415 -f 10881//10881 11417//11417 11418//11418 -f 10783//10783 10875//10875 11419//11419 -f 11419//11419 10875//10875 10877//10877 -f 11419//11419 10877//10877 11420//11420 -f 11420//11420 10877//10877 10879//10879 -f 11420//11420 10879//10879 11072//11072 -f 11072//11072 10879//10879 10881//10881 -f 11072//11072 10881//10881 11071//11071 -f 11071//11071 10881//10881 11418//11418 -f 11070//11070 11051//11051 11421//11421 -f 11421//11421 11051//11051 11422//11422 -f 11422//11422 11051//11051 11053//11053 -f 11422//11422 11053//11053 11423//11423 -f 11423//11423 11053//11053 11055//11055 -f 11423//11423 11055//11055 11424//11424 -f 11424//11424 11055//11055 11057//11057 -f 11424//11424 11057//11057 11425//11425 -f 11425//11425 11057//11057 11059//11059 -f 11425//11425 11059//11059 11426//11426 -f 11426//11426 11059//11059 11060//11060 -f 11426//11426 11060//11060 11427//11427 -f 11427//11427 11060//11060 11088//11088 -f 11427//11427 11088//11088 11428//11428 -f 11428//11428 11088//11088 11087//11087 -f 11428//11428 11087//11087 11429//11429 -f 11429//11429 11087//11087 11430//11430 -f 11430//11430 11087//11087 11046//11046 -f 11431//11431 11432//11432 11433//11433 -f 11433//11433 11432//11432 11369//11369 -f 11433//11433 11369//11369 11228//11228 -f 11228//11228 11369//11369 11370//11370 -f 11367//11367 11369//11369 11434//11434 -f 11434//11434 11369//11369 11435//11435 -f 11436//11436 11437//11437 11438//11438 -f 11438//11438 11437//11437 11367//11367 -f 11438//11438 11367//11367 11439//11439 -f 11439//11439 11367//11367 11434//11434 -f 11436//11436 11440//11440 11437//11437 -f 11437//11437 11440//11440 11441//11441 -f 11437//11437 11441//11441 11442//11442 -f 11442//11442 11441//11441 11443//11443 -f 11442//11442 11443//11443 11432//11432 -f 11432//11432 11443//11443 11444//11444 -f 11444//11444 11445//11445 11432//11432 -f 11432//11432 11445//11445 11446//11446 -f 11432//11432 11446//11446 11369//11369 -f 11369//11369 11446//11446 11447//11447 -f 11369//11369 11447//11447 11435//11435 -f 11156//11156 11365//11365 11448//11448 -f 11448//11448 11365//11365 11367//11367 -f 11448//11448 11367//11367 11449//11449 -f 11449//11449 11367//11367 11437//11437 -f 11431//11431 11450//11450 11432//11432 -f 11432//11432 11450//11450 11442//11442 -f 11450//11450 11449//11449 11442//11442 -f 11442//11442 11449//11449 11437//11437 -f 11448//11448 11449//11449 11451//11451 -f 11451//11451 11449//11449 11450//11450 -f 11451//11451 11450//11450 11452//11452 -f 11452//11452 11450//11450 11431//11431 -f 11452//11452 11431//11431 11433//11433 -f 11228//11228 11230//11230 11433//11433 -f 11433//11433 11230//11230 11452//11452 -f 11230//11230 11158//11158 11452//11452 -f 11452//11452 11158//11158 11451//11451 -f 11158//11158 11156//11156 11451//11451 -f 11451//11451 11156//11156 11448//11448 -f 11453//11453 11454//11454 11455//11455 -f 11455//11455 11454//11454 11381//11381 -f 11455//11455 11381//11381 11212//11212 -f 11212//11212 11381//11381 11382//11382 -f 11456//11456 11379//11379 11457//11457 -f 11457//11457 11458//11458 11456//11456 -f 11456//11456 11458//11458 11459//11459 -f 11456//11456 11459//11459 11460//11460 -f 11460//11460 11459//11459 11461//11461 -f 11454//11454 11462//11462 11381//11381 -f 11381//11381 11462//11462 11463//11463 -f 11463//11463 11464//11464 11381//11381 -f 11381//11381 11464//11464 11465//11465 -f 11381//11381 11465//11465 11379//11379 -f 11379//11379 11465//11465 11466//11466 -f 11379//11379 11466//11466 11457//11457 -f 11461//11461 11467//11467 11460//11460 -f 11460//11460 11467//11467 11468//11468 -f 11460//11460 11468//11468 11454//11454 -f 11454//11454 11468//11468 11469//11469 -f 11454//11454 11469//11469 11462//11462 -f 11210//11210 11377//11377 11470//11470 -f 11470//11470 11377//11377 11379//11379 -f 11470//11470 11379//11379 11471//11471 -f 11471//11471 11379//11379 11456//11456 -f 11453//11453 11472//11472 11454//11454 -f 11454//11454 11472//11472 11460//11460 -f 11472//11472 11471//11471 11460//11460 -f 11460//11460 11471//11471 11456//11456 -f 11473//11473 11470//11470 11471//11471 -f 11453//11453 11455//11455 11474//11474 -f 11473//11473 11471//11471 11474//11474 -f 11474//11474 11471//11471 11472//11472 -f 11474//11474 11472//11472 11453//11453 -f 11195//11195 11474//11474 11212//11212 -f 11212//11212 11474//11474 11455//11455 -f 11194//11194 11473//11473 11195//11195 -f 11195//11195 11473//11473 11474//11474 -f 11210//11210 11470//11470 11194//11194 -f 11194//11194 11470//11470 11473//11473 -f 11434//11434 10847//10847 11439//11439 -f 11439//11439 10847//10847 10842//10842 -f 11439//11439 10842//10842 11438//11438 -f 11438//11438 10842//10842 10841//10841 -f 11438//11438 10841//10841 11436//11436 -f 11436//11436 10841//10841 10840//10840 -f 11436//11436 10840//10840 11440//11440 -f 11440//11440 10840//10840 10941//10941 -f 11440//11440 10941//10941 11441//11441 -f 11441//11441 10941//10941 10939//10939 -f 11441//11441 10939//10939 11443//11443 -f 11443//11443 10939//10939 10937//10937 -f 11443//11443 10937//10937 11444//11444 -f 11444//11444 10937//10937 10936//10936 -f 11444//11444 10936//10936 11445//11445 -f 11445//11445 10936//10936 10935//10935 -f 11445//11445 10935//10935 11446//11446 -f 11446//11446 10935//10935 10843//10843 -f 11446//11446 10843//10843 11447//11447 -f 11447//11447 10843//10843 10844//10844 -f 11447//11447 10844//10844 11435//11435 -f 11435//11435 10844//10844 10846//10846 -f 11435//11435 10846//10846 11434//11434 -f 11434//11434 10846//10846 10847//10847 -f 11462//11462 10872//10872 11463//11463 -f 11463//11463 10872//10872 10871//10871 -f 11463//11463 10871//10871 11464//11464 -f 11464//11464 10871//10871 10870//10870 -f 11464//11464 10870//10870 11465//11465 -f 11465//11465 10870//10870 10865//10865 -f 11465//11465 10865//10865 11466//11466 -f 11466//11466 10865//10865 10864//10864 -f 11466//11466 10864//10864 11457//11457 -f 11457//11457 10864//10864 10858//10858 -f 11457//11457 10858//10858 11458//11458 -f 11458//11458 10858//10858 10860//10860 -f 11458//11458 10860//10860 11459//11459 -f 11459//11459 10860//10860 10862//10862 -f 11459//11459 10862//10862 11461//11461 -f 11461//11461 10862//10862 10863//10863 -f 11461//11461 10863//10863 11467//11467 -f 11467//11467 10863//10863 10866//10866 -f 11467//11467 10866//10866 11468//11468 -f 11468//11468 10866//10866 10867//10867 -f 11468//11468 10867//10867 11469//11469 -f 11469//11469 10867//10867 10869//10869 -f 11469//11469 10869//10869 11462//11462 -f 11462//11462 10869//10869 10872//10872 -f 11475//11475 11476//11476 11477//11477 -f 11477//11477 11476//11476 11391//11391 -f 11477//11477 11391//11391 11190//11190 -f 11190//11190 11391//11391 11392//11392 -f 11478//11478 11389//11389 11479//11479 -f 11479//11479 11480//11480 11478//11478 -f 11478//11478 11480//11480 11481//11481 -f 11478//11478 11481//11481 11482//11482 -f 11482//11482 11481//11481 11483//11483 -f 11484//11484 11391//11391 11485//11485 -f 11485//11485 11391//11391 11476//11476 -f 11483//11483 11486//11486 11482//11482 -f 11482//11482 11486//11486 11487//11487 -f 11482//11482 11487//11487 11476//11476 -f 11476//11476 11487//11487 11488//11488 -f 11476//11476 11488//11488 11485//11485 -f 11484//11484 11489//11489 11391//11391 -f 11391//11391 11489//11489 11490//11490 -f 11391//11391 11490//11490 11389//11389 -f 11389//11389 11490//11490 11491//11491 -f 11389//11389 11491//11491 11479//11479 -f 11171//11171 11387//11387 11492//11492 -f 11492//11492 11387//11387 11389//11389 -f 11492//11492 11389//11389 11493//11493 -f 11493//11493 11389//11389 11478//11478 -f 11494//11494 11495//11495 11496//11496 -f 11496//11496 11495//11495 11401//11401 -f 11496//11496 11401//11401 11183//11183 -f 11183//11183 11401//11401 11402//11402 -f 11497//11497 11401//11401 11498//11498 -f 11498//11498 11401//11401 11495//11495 -f 11497//11497 11499//11499 11401//11401 -f 11401//11401 11499//11499 11500//11500 -f 11401//11401 11500//11500 11399//11399 -f 11501//11501 11502//11502 11503//11503 -f 11503//11503 11502//11502 11504//11504 -f 11501//11501 11505//11505 11502//11502 -f 11502//11502 11505//11505 11506//11506 -f 11502//11502 11506//11506 11495//11495 -f 11495//11495 11506//11506 11507//11507 -f 11495//11495 11507//11507 11498//11498 -f 11500//11500 11508//11508 11399//11399 -f 11399//11399 11508//11508 11509//11509 -f 11399//11399 11509//11509 11504//11504 -f 11504//11504 11509//11509 11510//11510 -f 11504//11504 11510//11510 11503//11503 -f 11167//11167 11397//11397 11511//11511 -f 11511//11511 11397//11397 11399//11399 -f 11511//11511 11399//11399 11512//11512 -f 11512//11512 11399//11399 11504//11504 -f 11513//11513 11514//11514 11515//11515 -f 11515//11515 11514//11514 11411//11411 -f 11515//11515 11411//11411 11178//11178 -f 11178//11178 11411//11411 11412//11412 -f 11516//11516 11517//11517 11518//11518 -f 11518//11518 11517//11517 11514//11514 -f 11519//11519 11409//11409 11520//11520 -f 11520//11520 11521//11521 11519//11519 -f 11519//11519 11521//11521 11522//11522 -f 11519//11519 11522//11522 11518//11518 -f 11518//11518 11522//11522 11523//11523 -f 11518//11518 11523//11523 11516//11516 -f 11517//11517 11524//11524 11514//11514 -f 11514//11514 11524//11524 11525//11525 -f 11514//11514 11525//11525 11411//11411 -f 11411//11411 11525//11525 11526//11526 -f 11526//11526 11527//11527 11411//11411 -f 11411//11411 11527//11527 11528//11528 -f 11411//11411 11528//11528 11409//11409 -f 11409//11409 11528//11528 11529//11529 -f 11409//11409 11529//11529 11520//11520 -f 11163//11163 11407//11407 11530//11530 -f 11530//11530 11407//11407 11409//11409 -f 11530//11530 11409//11409 11531//11531 -f 11531//11531 11409//11409 11519//11519 -f 11475//11475 11532//11532 11476//11476 -f 11476//11476 11532//11532 11482//11482 -f 11532//11532 11493//11493 11482//11482 -f 11482//11482 11493//11493 11478//11478 -f 11533//11533 11492//11492 11493//11493 -f 11475//11475 11477//11477 11534//11534 -f 11533//11533 11493//11493 11534//11534 -f 11534//11534 11493//11493 11532//11532 -f 11534//11534 11532//11532 11475//11475 -f 11494//11494 11535//11535 11495//11495 -f 11495//11495 11535//11535 11502//11502 -f 11535//11535 11512//11512 11502//11502 -f 11502//11502 11512//11512 11504//11504 -f 11536//11536 11511//11511 11512//11512 -f 11494//11494 11496//11496 11537//11537 -f 11536//11536 11512//11512 11537//11537 -f 11537//11537 11512//11512 11535//11535 -f 11537//11537 11535//11535 11494//11494 -f 11513//11513 11538//11538 11514//11514 -f 11514//11514 11538//11538 11518//11518 -f 11538//11538 11531//11531 11518//11518 -f 11518//11518 11531//11531 11519//11519 -f 11539//11539 11530//11530 11531//11531 -f 11513//11513 11515//11515 11540//11540 -f 11539//11539 11531//11531 11540//11540 -f 11540//11540 11531//11531 11538//11538 -f 11540//11540 11538//11538 11513//11513 -f 11192//11192 11534//11534 11190//11190 -f 11190//11190 11534//11534 11477//11477 -f 11173//11173 11533//11533 11192//11192 -f 11192//11192 11533//11533 11534//11534 -f 11171//11171 11492//11492 11173//11173 -f 11173//11173 11492//11492 11533//11533 -f 11182//11182 11537//11537 11183//11183 -f 11183//11183 11537//11537 11496//11496 -f 11169//11169 11536//11536 11182//11182 -f 11182//11182 11536//11536 11537//11537 -f 11167//11167 11511//11511 11169//11169 -f 11169//11169 11511//11511 11536//11536 -f 11180//11180 11540//11540 11178//11178 -f 11178//11178 11540//11540 11515//11515 -f 11165//11165 11539//11539 11180//11180 -f 11180//11180 11539//11539 11540//11540 -f 11163//11163 11530//11530 11165//11165 -f 11165//11165 11530//11530 11539//11539 -f 11485//11485 10927//10927 11484//11484 -f 11484//11484 10927//10927 10919//10919 -f 11484//11484 10919//10919 11489//11489 -f 11489//11489 10919//10919 10934//10934 -f 11489//11489 10934//10934 11490//11490 -f 11490//11490 10934//10934 10933//10933 -f 11490//11490 10933//10933 11491//11491 -f 11491//11491 10933//10933 10932//10932 -f 11491//11491 10932//10932 11479//11479 -f 11479//11479 10932//10932 10920//10920 -f 11479//11479 10920//10920 11480//11480 -f 11480//11480 10920//10920 10922//10922 -f 11480//11480 10922//10922 11481//11481 -f 11481//11481 10922//10922 10924//10924 -f 11481//11481 10924//10924 11483//11483 -f 11483//11483 10924//10924 10925//10925 -f 11483//11483 10925//10925 11486//11486 -f 11486//11486 10925//10925 10930//10930 -f 11486//11486 10930//10930 11487//11487 -f 11487//11487 10930//10930 10929//10929 -f 11487//11487 10929//10929 11488//11488 -f 11488//11488 10929//10929 10928//10928 -f 11488//11488 10928//10928 11485//11485 -f 11485//11485 10928//10928 10927//10927 -f 11498//11498 10903//10903 11497//11497 -f 11497//11497 10903//10903 10902//10902 -f 11497//11497 10902//10902 11499//11499 -f 11499//11499 10902//10902 10916//10916 -f 11499//11499 10916//10916 11500//11500 -f 11500//11500 10916//10916 10915//10915 -f 11500//11500 10915//10915 11508//11508 -f 11508//11508 10915//10915 10914//10914 -f 11508//11508 10914//10914 11509//11509 -f 11509//11509 10914//10914 10913//10913 -f 11509//11509 10913//10913 11510//11510 -f 11510//11510 10913//10913 10911//10911 -f 11510//11510 10911//10911 11503//11503 -f 11503//11503 10911//10911 10910//10910 -f 11503//11503 10910//10910 11501//11501 -f 11501//11501 10910//10910 10907//10907 -f 11501//11501 10907//10907 11505//11505 -f 11505//11505 10907//10907 10906//10906 -f 11505//11505 10906//10906 11506//11506 -f 11506//11506 10906//10906 10905//10905 -f 11506//11506 10905//10905 11507//11507 -f 11507//11507 10905//10905 10904//10904 -f 11507//11507 10904//10904 11498//11498 -f 11498//11498 10904//10904 10903//10903 -f 11525//11525 10892//10892 11526//11526 -f 11526//11526 10892//10892 10891//10891 -f 11526//11526 10891//10891 11527//11527 -f 11527//11527 10891//10891 10899//10899 -f 11527//11527 10899//10899 11528//11528 -f 11528//11528 10899//10899 10898//10898 -f 11528//11528 10898//10898 11529//11529 -f 11529//11529 10898//10898 10897//10897 -f 11529//11529 10897//10897 11520//11520 -f 11520//11520 10897//10897 10896//10896 -f 11520//11520 10896//10896 11521//11521 -f 11521//11521 10896//10896 10894//10894 -f 11521//11521 10894//10894 11522//11522 -f 11522//11522 10894//10894 10893//10893 -f 11522//11522 10893//10893 11523//11523 -f 11523//11523 10893//10893 10889//10889 -f 11523//11523 10889//10889 11516//11516 -f 11516//11516 10889//10889 10886//10886 -f 11516//11516 10886//10886 11517//11517 -f 11517//11517 10886//10886 10885//10885 -f 11517//11517 10885//10885 11524//11524 -f 11524//11524 10885//10885 10884//10884 -f 11524//11524 10884//10884 11525//11525 -f 11525//11525 10884//10884 10892//10892 -f 11334//11334 11306//11306 11335//11335 -f 11335//11335 11306//11306 11302//11302 -f 11335//11335 11302//11302 11236//11236 -f 11236//11236 11302//11302 11342//11342 -f 11234//11234 11338//11338 11332//11332 -f 11332//11332 11338//11338 11301//11301 -f 11332//11332 11301//11301 11333//11333 -f 11333//11333 11301//11301 11310//11310 -f 11334//11334 11337//11337 11306//11306 -f 11306//11306 11337//11337 11308//11308 -f 11337//11337 11333//11333 11308//11308 -f 11308//11308 11333//11333 11310//11310 -f 11227//11227 11336//11336 11236//11236 -f 11236//11236 11336//11336 11335//11335 -f 11226//11226 11331//11331 11227//11227 -f 11227//11227 11331//11331 11336//11336 -f 11234//11234 11332//11332 11226//11226 -f 11226//11226 11332//11332 11331//11331 -f 11323//11323 11284//11284 11324//11324 -f 11324//11324 11284//11284 11286//11286 -f 11324//11324 11286//11286 11186//11186 -f 11186//11186 11286//11286 11329//11329 -f 11215//11215 11325//11325 11318//11318 -f 11318//11318 11325//11325 11289//11289 -f 11318//11318 11289//11289 11319//11319 -f 11319//11319 11289//11289 11288//11288 -f 11323//11323 11321//11321 11284//11284 -f 11284//11284 11321//11321 11292//11292 -f 11321//11321 11319//11319 11292//11292 -f 11292//11292 11319//11319 11288//11288 -f 11186//11186 11188//11188 11324//11324 -f 11324//11324 11188//11188 11322//11322 -f 11188//11188 11217//11217 11322//11322 -f 11322//11322 11217//11217 11320//11320 -f 11217//11217 11215//11215 11320//11320 -f 11320//11320 11215//11215 11318//11318 -f 11303//11303 10813//10813 11312//11312 -f 11312//11312 10813//10813 10829//10829 -f 11312//11312 10829//10829 11313//11313 -f 11313//11313 10829//10829 10828//10828 -f 11313//11313 10828//10828 11314//11314 -f 11314//11314 10828//10828 10826//10826 -f 11314//11314 10826//10826 11311//11311 -f 11311//11311 10826//10826 10824//10824 -f 11311//11311 10824//10824 11309//11309 -f 11309//11309 10824//10824 10823//10823 -f 11309//11309 10823//10823 11307//11307 -f 11307//11307 10823//10823 10820//10820 -f 11307//11307 10820//10820 11305//11305 -f 11305//11305 10820//10820 10819//10819 -f 11305//11305 10819//10819 11315//11315 -f 11315//11315 10819//10819 10818//10818 -f 11315//11315 10818//10818 11316//11316 -f 11316//11316 10818//10818 10817//10817 -f 11316//11316 10817//10817 11317//11317 -f 11317//11317 10817//10817 10816//10816 -f 11317//11317 10816//10816 11304//11304 -f 11304//11304 10816//10816 10814//10814 -f 11304//11304 10814//10814 11303//11303 -f 11303//11303 10814//10814 10813//10813 -f 11294//11294 10786//10786 11293//11293 -f 11293//11293 10786//10786 10802//10802 -f 11293//11293 10802//10802 11291//11291 -f 11291//11291 10802//10802 10804//10804 -f 11291//11291 10804//10804 11295//11295 -f 11295//11295 10804//10804 10796//10796 -f 11295//11295 10796//10796 11296//11296 -f 11296//11296 10796//10796 10794//10794 -f 11296//11296 10794//10794 11297//11297 -f 11297//11297 10794//10794 10793//10793 -f 11297//11297 10793//10793 11285//11285 -f 11285//11285 10793//10793 10792//10792 -f 11285//11285 10792//10792 11287//11287 -f 11287//11287 10792//10792 10790//10790 -f 11287//11287 10790//10790 11298//11298 -f 11298//11298 10790//10790 10799//10799 -f 11298//11298 10799//10799 11299//11299 -f 11299//11299 10799//10799 10798//10798 -f 11299//11299 10798//10798 11300//11300 -f 11300//11300 10798//10798 10797//10797 -f 11300//11300 10797//10797 11290//11290 -f 11290//11290 10797//10797 10787//10787 -f 11290//11290 10787//10787 11294//11294 -f 11294//11294 10787//10787 10786//10786 -f 11264//11264 11138//11138 11265//11265 -f 11265//11265 11138//11138 11140//11140 -f 11265//11265 11140//11140 11200//11200 -f 11200//11200 11140//11140 11282//11282 -f 11197//11197 11278//11278 11259//11259 -f 11259//11259 11278//11278 11147//11147 -f 11259//11259 11147//11147 11260//11260 -f 11260//11260 11147//11147 11149//11149 -f 11257//11257 11125//11125 11258//11258 -f 11258//11258 11125//11125 11127//11127 -f 11258//11258 11127//11127 11218//11218 -f 11218//11218 11127//11127 11276//11276 -f 11205//11205 11272//11272 11252//11252 -f 11252//11252 11272//11272 11131//11131 -f 11252//11252 11131//11131 11253//11253 -f 11253//11253 11131//11131 11121//11121 -f 11250//11250 11114//11114 11251//11251 -f 11251//11251 11114//11114 11104//11104 -f 11251//11251 11104//11104 11160//11160 -f 11160//11160 11104//11104 11270//11270 -f 11243//11243 11266//11266 11245//11245 -f 11245//11245 11266//11266 11110//11110 -f 11245//11245 11110//11110 11246//11246 -f 11246//11246 11110//11110 11113//11113 -f 11264//11264 11262//11262 11138//11138 -f 11138//11138 11262//11262 11142//11142 -f 11262//11262 11260//11260 11142//11142 -f 11142//11142 11260//11260 11149//11149 -f 11257//11257 11255//11255 11125//11125 -f 11125//11125 11255//11255 11123//11123 -f 11255//11255 11253//11253 11123//11123 -f 11123//11123 11253//11253 11121//11121 -f 11250//11250 11248//11248 11114//11114 -f 11114//11114 11248//11248 11107//11107 -f 11248//11248 11246//11246 11107//11107 -f 11107//11107 11246//11246 11113//11113 -f 11200//11200 11202//11202 11265//11265 -f 11265//11265 11202//11202 11263//11263 -f 11202//11202 11199//11199 11263//11263 -f 11263//11263 11199//11199 11261//11261 -f 11199//11199 11197//11197 11261//11261 -f 11261//11261 11197//11197 11259//11259 -f 11218//11218 11220//11220 11258//11258 -f 11258//11258 11220//11220 11256//11256 -f 11220//11220 11207//11207 11256//11256 -f 11256//11256 11207//11207 11254//11254 -f 11207//11207 11205//11205 11254//11254 -f 11254//11254 11205//11205 11252//11252 -f 11160//11160 11159//11159 11251//11251 -f 11251//11251 11159//11159 11249//11249 -f 11159//11159 11242//11242 11249//11249 -f 11249//11249 11242//11242 11247//11247 -f 11242//11242 11243//11243 11247//11247 -f 11247//11247 11243//11243 11245//11245 -f 11148//11148 10950//10950 11152//11152 -f 11152//11152 10950//10950 10949//10949 -f 11152//11152 10949//10949 11153//11153 -f 11153//11153 10949//10949 10967//10967 -f 11153//11153 10967//10967 11154//11154 -f 11154//11154 10967//10967 10966//10966 -f 11154//11154 10966//10966 11143//11143 -f 11143//11143 10966//10966 10965//10965 -f 11143//11143 10965//10965 11144//11144 -f 11144//11144 10965//10965 10958//10958 -f 11144//11144 10958//10958 11139//11139 -f 11139//11139 10958//10958 10960//10960 -f 11139//11139 10960//10960 11141//11141 -f 11141//11141 10960//10960 10961//10961 -f 11141//11141 10961//10961 11145//11145 -f 11145//11145 10961//10961 10957//10957 -f 11145//11145 10957//10957 11146//11146 -f 11146//11146 10957//10957 10954//10954 -f 11146//11146 10954//10954 11151//11151 -f 11151//11151 10954//10954 10953//10953 -f 11151//11151 10953//10953 11150//11150 -f 11150//11150 10953//10953 10964//10964 -f 11150//11150 10964//10964 11148//11148 -f 11148//11148 10964//10964 10950//10950 -f 11134//11134 10971//10971 11122//11122 -f 11122//11122 10971//10971 10970//10970 -f 11122//11122 10970//10970 11124//11124 -f 11124//11124 10970//10970 10987//10987 -f 11124//11124 10987//10987 11135//11135 -f 11135//11135 10987//10987 10986//10986 -f 11135//11135 10986//10986 11136//11136 -f 11136//11136 10986//10986 10985//10985 -f 11136//11136 10985//10985 11137//11137 -f 11137//11137 10985//10985 10984//10984 -f 11137//11137 10984//10984 11126//11126 -f 11126//11126 10984//10984 10982//10982 -f 11126//11126 10982//10982 11128//11128 -f 11128//11128 10982//10982 10981//10981 -f 11128//11128 10981//10981 11129//11129 -f 11129//11129 10981//10981 10978//10978 -f 11129//11129 10978//10978 11130//11130 -f 11130//11130 10978//10978 10975//10975 -f 11130//11130 10975//10975 11132//11132 -f 11132//11132 10975//10975 10973//10973 -f 11132//11132 10973//10973 11133//11133 -f 11133//11133 10973//10973 10972//10972 -f 11133//11133 10972//10972 11134//11134 -f 11134//11134 10972//10972 10971//10971 -f 11118//11118 10991//10991 11119//11119 -f 11119//11119 10991//10991 10990//10990 -f 11119//11119 10990//10990 11120//11120 -f 11120//11120 10990//10990 11009//11009 -f 11120//11120 11009//11009 11108//11108 -f 11108//11108 11009//11009 11008//11008 -f 11108//11108 11008//11008 11109//11109 -f 11109//11109 11008//11008 11007//11007 -f 11109//11109 11007//11007 11115//11115 -f 11115//11115 11007//11007 11001//11001 -f 11115//11115 11001//11001 11116//11116 -f 11116//11116 11001//11001 11000//11000 -f 11116//11116 11000//11000 11117//11117 -f 11117//11117 11000//11000 10999//10999 -f 11117//11117 10999//10999 11105//11105 -f 11105//11105 10999//10999 10998//10998 -f 11105//11105 10998//10998 11106//11106 -f 11106//11106 10998//10998 11005//11005 -f 11106//11106 11005//11005 11111//11111 -f 11111//11111 11005//11005 11003//11003 -f 11111//11111 11003//11003 11112//11112 -f 11112//11112 11003//11003 11002//11002 -f 11112//11112 11002//11002 11118//11118 -f 11118//11118 11002//11002 10991//10991 -f 11541//11541 11345//11345 11542//11542 -f 11542//11542 11345//11345 10698//10698 -f 11542//11542 10698//10698 11543//11543 -f 11543//11543 10698//10698 10704//10704 -f 11543//11543 10704//10704 11544//11544 -f 11544//11544 10704//10704 10703//10703 -f 11544//11544 10703//10703 11545//11545 -f 11545//11545 10703//10703 11546//11546 -f 11546//11546 10703//10703 10690//10690 -f 11546//11546 10690//10690 11547//11547 -f 11547//11547 10690//10690 11548//11548 -f 11548//11548 10690//10690 10688//10688 -f 11548//11548 10688//10688 11549//11549 -f 11549//11549 10688//10688 10669//10669 -f 11549//11549 10669//10669 11042//11042 -f 11550//11550 11551//11551 11552//11552 -f 11553//11553 11550//11550 11554//11554 -f 11554//11554 11550//11550 11552//11552 -f 11554//11554 11552//11552 11555//11555 -f 11555//11555 11552//11552 11556//11556 -f 11557//11557 11558//11558 11559//11559 -f 11560//11560 11561//11561 11557//11557 -f 11557//11557 11561//11561 11562//11562 -f 11557//11557 11562//11562 11563//11563 -f 11563//11563 11562//11562 11564//11564 -f 11563//11563 11564//11564 11565//11565 -f 11565//11565 11564//11564 11566//11566 -f 11565//11565 11566//11566 11567//11567 -f 11567//11567 11566//11566 11568//11568 -f 11567//11567 11568//11568 11552//11552 -f 11552//11552 11568//11568 11569//11569 -f 11552//11552 11569//11569 11556//11556 -f 11556//11556 11569//11569 11570//11570 -f 11556//11556 11570//11570 11571//11571 -f 11571//11571 11570//11570 11572//11572 -f 11571//11571 11572//11572 11573//11573 -f 11573//11573 11572//11572 11574//11574 -f 11573//11573 11574//11574 11575//11575 -f 11575//11575 11574//11574 11576//11576 -f 11575//11575 11576//11576 11577//11577 -f 11577//11577 11576//11576 11578//11578 -f 11577//11577 11578//11578 11559//11559 -f 11559//11559 11578//11578 11560//11560 -f 11559//11559 11560//11560 11557//11557 -f 11579//11579 11418//11418 11563//11563 -f 11563//11563 11418//11418 11417//11417 -f 11563//11563 11417//11417 11557//11557 -f 11557//11557 11417//11417 11580//11580 -f 11557//11557 11580//11580 11581//11581 -f 11582//11582 11583//11583 11580//11580 -f 11580//11580 11583//11583 11584//11584 -f 11580//11580 11584//11584 11581//11581 -f 11552//11552 11551//11551 11567//11567 -f 11567//11567 11551//11551 11585//11585 -f 11567//11567 11585//11585 11565//11565 -f 11565//11565 11585//11585 11586//11586 -f 11565//11565 11586//11586 11563//11563 -f 11563//11563 11586//11586 11579//11579 -f 11587//11587 11588//11588 11589//11589 -f 11590//11590 11587//11587 11591//11591 -f 11591//11591 11587//11587 11589//11589 -f 11591//11591 11589//11589 11592//11592 -f 11592//11592 11589//11589 11593//11593 -f 11594//11594 11595//11595 11596//11596 -f 11596//11596 11595//11595 11597//11597 -f 11596//11596 11597//11597 11598//11598 -f 11598//11598 11597//11597 11599//11599 -f 11598//11598 11599//11599 11600//11600 -f 11600//11600 11599//11599 11601//11601 -f 11600//11600 11601//11601 11602//11602 -f 11602//11602 11601//11601 11603//11603 -f 11602//11602 11603//11603 11604//11604 -f 11604//11604 11603//11603 11605//11605 -f 11604//11604 11605//11605 11606//11606 -f 11606//11606 11605//11605 11607//11607 -f 11606//11606 11607//11607 11588//11588 -f 11588//11588 11607//11607 11608//11608 -f 11588//11588 11608//11608 11589//11589 -f 11589//11589 11608//11608 11609//11609 -f 11589//11589 11609//11609 11610//11610 -f 11610//11610 11609//11609 11611//11611 -f 11610//11610 11611//11611 11612//11612 -f 11612//11612 11611//11611 11613//11613 -f 11612//11612 11613//11613 11614//11614 -f 11614//11614 11613//11613 11594//11594 -f 11614//11614 11594//11594 11596//11596 -f 11614//11614 11615//11615 11612//11612 -f 11612//11612 11615//11615 11616//11616 -f 11612//11612 11616//11616 11610//11610 -f 11610//11610 11616//11616 11617//11617 -f 11610//11610 11617//11617 11589//11589 -f 11589//11589 11617//11617 11593//11593 -f 11618//11618 11596//11596 11619//11619 -f 11619//11619 11596//11596 11620//11620 -f 11016//11016 11615//11615 11017//11017 -f 11017//11017 11615//11615 11614//11614 -f 11017//11017 11614//11614 11621//11621 -f 11621//11621 11614//11614 11596//11596 -f 11621//11621 11596//11596 11622//11622 -f 11618//11618 11623//11623 11596//11596 -f 11596//11596 11623//11623 11624//11624 -f 11596//11596 11624//11624 11622//11622 -f 11625//11625 11626//11626 11627//11627 -f 11627//11627 11626//11626 11628//11628 -f 11627//11627 11628//11628 11629//11629 -f 11629//11629 11628//11628 11630//11630 -f 11631//11631 11632//11632 11630//11630 -f 11630//11630 11632//11632 11633//11633 -f 11630//11630 11633//11633 11629//11629 -f 11634//11634 11635//11635 11631//11631 -f 11631//11631 11635//11635 11636//11636 -f 11631//11631 11636//11636 11632//11632 -f 11637//11637 11638//11638 11634//11634 -f 11634//11634 11638//11638 11639//11639 -f 11634//11634 11639//11639 11635//11635 -f 11640//11640 11641//11641 11642//11642 -f 11642//11642 11641//11641 11643//11643 -f 11642//11642 11643//11643 11644//11644 -f 11644//11644 11643//11643 11645//11645 -f 11644//11644 11645//11645 11637//11637 -f 11637//11637 11645//11645 11646//11646 -f 11637//11637 11646//11646 11638//11638 -f 11647//11647 11648//11648 11640//11640 -f 11640//11640 11648//11648 11649//11649 -f 11640//11640 11649//11649 11641//11641 -f 11650//11650 11651//11651 11647//11647 -f 11647//11647 11651//11651 11652//11652 -f 11647//11647 11652//11652 11648//11648 -f 11653//11653 11654//11654 11650//11650 -f 11650//11650 11654//11654 11655//11655 -f 11650//11650 11655//11655 11651//11651 -f 11656//11656 11654//11654 11657//11657 -f 11657//11657 11654//11654 11653//11653 -f 11657//11657 11653//11653 11658//11658 -f 11658//11658 11653//11653 11626//11626 -f 11658//11658 11626//11626 11659//11659 -f 11659//11659 11626//11626 11625//11625 -f 11659//11659 11625//11625 11660//11660 -f 11661//11661 11630//11630 11662//11662 -f 11662//11662 11630//11630 11628//11628 -f 11662//11662 11628//11628 11663//11663 -f 11663//11663 11628//11628 11626//11626 -f 11663//11663 11626//11626 11664//11664 -f 11664//11664 11626//11626 11653//11653 -f 11664//11664 11653//11653 11665//11665 -f 11665//11665 11653//11653 11650//11650 -f 11665//11665 11650//11650 11666//11666 -f 11666//11666 11650//11650 11647//11647 -f 11666//11666 11647//11647 11667//11667 -f 11667//11667 11647//11647 11640//11640 -f 11667//11667 11640//11640 11668//11668 -f 11668//11668 11640//11640 11642//11642 -f 11668//11668 11642//11642 11669//11669 -f 11669//11669 11642//11642 11644//11644 -f 11669//11669 11644//11644 11670//11670 -f 11670//11670 11644//11644 11637//11637 -f 11670//11670 11637//11637 11671//11671 -f 11671//11671 11637//11637 11634//11634 -f 11671//11671 11634//11634 11672//11672 -f 11672//11672 11634//11634 11631//11631 -f 11672//11672 11631//11631 11661//11661 -f 11661//11661 11631//11631 11630//11630 -f 11673//11673 11674//11674 11675//11675 -f 11676//11676 11677//11677 11678//11678 -f 11678//11678 11677//11677 11679//11679 -f 11678//11678 11679//11679 11680//11680 -f 11681//11681 11682//11682 11680//11680 -f 11680//11680 11682//11682 11683//11683 -f 11680//11680 11683//11683 11678//11678 -f 11684//11684 11685//11685 11681//11681 -f 11681//11681 11685//11685 11686//11686 -f 11681//11681 11686//11686 11682//11682 -f 11687//11687 11688//11688 11684//11684 -f 11684//11684 11688//11688 11689//11689 -f 11684//11684 11689//11689 11685//11685 -f 11690//11690 11691//11691 11687//11687 -f 11687//11687 11691//11691 11692//11692 -f 11687//11687 11692//11692 11688//11688 -f 11693//11693 11694//11694 11690//11690 -f 11690//11690 11694//11694 11695//11695 -f 11690//11690 11695//11695 11691//11691 -f 11696//11696 11697//11697 11693//11693 -f 11693//11693 11697//11697 11698//11698 -f 11693//11693 11698//11698 11694//11694 -f 11699//11699 11700//11700 11696//11696 -f 11696//11696 11700//11700 11701//11701 -f 11696//11696 11701//11701 11697//11697 -f 11675//11675 11702//11702 11673//11673 -f 11673//11673 11702//11702 11703//11703 -f 11673//11673 11703//11703 11699//11699 -f 11699//11699 11703//11703 11704//11704 -f 11699//11699 11704//11704 11700//11700 -f 11705//11705 11675//11675 11706//11706 -f 11706//11706 11675//11675 11674//11674 -f 11706//11706 11674//11674 11707//11707 -f 11707//11707 11674//11674 11677//11677 -f 11707//11707 11677//11677 11708//11708 -f 11708//11708 11677//11677 11676//11676 -f 11708//11708 11676//11676 11709//11709 -f 11710//11710 11674//11674 11711//11711 -f 11711//11711 11674//11674 11673//11673 -f 11711//11711 11673//11673 11712//11712 -f 11712//11712 11673//11673 11699//11699 -f 11712//11712 11699//11699 11713//11713 -f 11713//11713 11699//11699 11696//11696 -f 11713//11713 11696//11696 11714//11714 -f 11714//11714 11696//11696 11693//11693 -f 11714//11714 11693//11693 11715//11715 -f 11715//11715 11693//11693 11690//11690 -f 11715//11715 11690//11690 11716//11716 -f 11716//11716 11690//11690 11687//11687 -f 11716//11716 11687//11687 11717//11717 -f 11717//11717 11687//11687 11684//11684 -f 11717//11717 11684//11684 11718//11718 -f 11718//11718 11684//11684 11681//11681 -f 11718//11718 11681//11681 11719//11719 -f 11719//11719 11681//11681 11680//11680 -f 11719//11719 11680//11680 11720//11720 -f 11720//11720 11680//11680 11679//11679 -f 11720//11720 11679//11679 11721//11721 -f 11721//11721 11679//11679 11677//11677 -f 11721//11721 11677//11677 11710//11710 -f 11710//11710 11677//11677 11674//11674 -f 10680//10680 11564//11564 10679//10679 -f 10679//10679 11564//11564 11562//11562 -f 10679//10679 11562//11562 10642//10642 -f 10642//10642 11562//11562 11561//11561 -f 10642//10642 11561//11561 10640//10640 -f 10640//10640 11561//11561 11560//11560 -f 10640//10640 11560//11560 10702//10702 -f 10702//10702 11560//11560 11578//11578 -f 10702//10702 11578//11578 10701//10701 -f 10701//10701 11578//11578 11576//11576 -f 10701//10701 11576//11576 10689//10689 -f 10689//10689 11576//11576 11574//11574 -f 10689//10689 11574//11574 10687//10687 -f 10687//10687 11574//11574 11572//11572 -f 10687//10687 11572//11572 10686//10686 -f 10686//10686 11572//11572 11570//11570 -f 10686//10686 11570//11570 10685//10685 -f 10685//10685 11570//11570 11569//11569 -f 10685//10685 11569//11569 10683//10683 -f 10683//10683 11569//11569 11568//11568 -f 10683//10683 11568//11568 10681//10681 -f 10681//10681 11568//11568 11566//11566 -f 10681//10681 11566//11566 10680//10680 -f 10680//10680 11566//11566 11564//11564 -f 10650//10650 11594//11594 10692//10692 -f 10692//10692 11594//11594 11613//11613 -f 10692//10692 11613//11613 10682//10682 -f 10682//10682 11613//11613 11611//11611 -f 10682//10682 11611//11611 10684//10684 -f 10684//10684 11611//11611 11609//11609 -f 10684//10684 11609//11609 10670//10670 -f 10670//10670 11609//11609 11608//11608 -f 10670//10670 11608//11608 10668//10668 -f 10668//10668 11608//11608 11607//11607 -f 10668//10668 11607//11607 10666//10666 -f 10666//10666 11607//11607 11605//11605 -f 10666//10666 11605//11605 10664//10664 -f 10664//10664 11605//11605 11603//11603 -f 10664//10664 11603//11603 10672//10672 -f 10672//10672 11603//11603 11601//11601 -f 10672//10672 11601//11601 10644//10644 -f 10644//10644 11601//11601 11599//11599 -f 10644//10644 11599//11599 10646//10646 -f 10646//10646 11599//11599 11597//11597 -f 10646//10646 11597//11597 10647//10647 -f 10647//10647 11597//11597 11595//11595 -f 10647//10647 11595//11595 10650//10650 -f 10650//10650 11595//11595 11594//11594 -f 10695//10695 11717//11717 10694//10694 -f 10694//10694 11717//11717 11718//11718 -f 10694//10694 11718//11718 10693//10693 -f 10693//10693 11718//11718 11719//11719 -f 10693//10693 11719//11719 10691//10691 -f 10691//10691 11719//11719 11720//11720 -f 10691//10691 11720//11720 10652//10652 -f 10652//10652 11720//11720 11721//11721 -f 10652//10652 11721//11721 10651//10651 -f 10651//10651 11721//11721 11710//11710 -f 10651//10651 11710//11710 10645//10645 -f 10645//10645 11710//11710 11711//11711 -f 10645//10645 11711//11711 10662//10662 -f 10662//10662 11711//11711 11712//11712 -f 10662//10662 11712//11712 10660//10660 -f 10660//10660 11712//11712 11713//11713 -f 10660//10660 11713//11713 10659//10659 -f 10659//10659 11713//11713 11714//11714 -f 10659//10659 11714//11714 10656//10656 -f 10656//10656 11714//11714 11715//11715 -f 10656//10656 11715//11715 10654//10654 -f 10654//10654 11715//11715 11716//11716 -f 10654//10654 11716//11716 10695//10695 -f 10695//10695 11716//11716 11717//11717 -f 10638//10638 11668//11668 10678//10678 -f 10678//10678 11668//11668 11669//11669 -f 10678//10678 11669//11669 10677//10677 -f 10677//10677 11669//11669 11670//11670 -f 10677//10677 11670//11670 10700//10700 -f 10700//10700 11670//11670 11671//11671 -f 10700//10700 11671//11671 10699//10699 -f 10699//10699 11671//11671 11672//11672 -f 10699//10699 11672//11672 10697//10697 -f 10697//10697 11672//11672 11661//11661 -f 10697//10697 11661//11661 10696//10696 -f 10696//10696 11661//11661 11662//11662 -f 10696//10696 11662//11662 10639//10639 -f 10639//10639 11662//11662 11663//11663 -f 10639//10639 11663//11663 10641//10641 -f 10641//10641 11663//11663 11664//11664 -f 10641//10641 11664//11664 10643//10643 -f 10643//10643 11664//11664 11665//11665 -f 10643//10643 11665//11665 10649//10649 -f 10649//10649 11665//11665 11666//11666 -f 10649//10649 11666//11666 10648//10648 -f 10648//10648 11666//11666 11667//11667 -f 10648//10648 11667//11667 10638//10638 -f 10638//10638 11667//11667 11668//11668 -f 11101//11101 11346//11346 11722//11722 -f 11722//11722 11346//11346 11348//11348 -f 11722//11722 11348//11348 11723//11723 -f 11723//11723 11348//11348 11724//11724 -f 11724//11724 11348//11348 11349//11349 -f 11724//11724 11349//11349 11725//11725 -f 11725//11725 11349//11349 11726//11726 -f 11726//11726 11349//11349 10992//10992 -f 11726//11726 10992//10992 10996//10996 -f 10996//10996 10995//10995 11727//11727 -f 10996//10996 11727//11727 11726//11726 -f 11726//11726 11727//11727 11728//11728 -f 11726//11726 11728//11728 11725//11725 -f 11725//11725 11728//11728 11729//11729 -f 11725//11725 11729//11729 11724//11724 -f 11724//11724 11729//11729 11723//11723 -f 11723//11723 11729//11729 11730//11730 -f 11723//11723 11730//11730 11722//11722 -f 11722//11722 11730//11730 11102//11102 -f 11722//11722 11102//11102 11101//11101 -f 11345//11345 11731//11731 11344//11344 -f 11344//11344 11731//11731 11416//11416 -f 11731//11731 11732//11732 11416//11416 -f 11416//11416 11732//11732 11733//11733 -f 11416//11416 11733//11733 11415//11415 -f 10780//10780 10882//10882 11734//11734 -f 11734//11734 10882//10882 11415//11415 -f 11734//11734 11415//11415 11735//11735 -f 11735//11735 11415//11415 11733//11733 -f 11345//11345 11541//11541 11736//11736 -f 11345//11345 11736//11736 11731//11731 -f 11731//11731 11736//11736 11737//11737 -f 11731//11731 11737//11737 11732//11732 -f 11732//11732 11737//11737 11738//11738 -f 11732//11732 11738//11738 11733//11733 -f 11733//11733 11738//11738 11735//11735 -f 11735//11735 11738//11738 11739//11739 -f 11735//11735 11739//11739 11734//11734 -f 11734//11734 11739//11739 10781//10781 -f 11734//11734 10781//10781 10780//10780 -f 11078//11078 11077//11077 11740//11740 -f 11078//11078 11740//11740 11741//11741 -f 11741//11741 11740//11740 11742//11742 -f 11741//11741 11742//11742 11743//11743 -f 11743//11743 11742//11742 11044//11044 -f 11743//11743 11044//11044 11045//11045 -f 11744//11744 11058//11058 11745//11745 -f 11745//11745 11058//11058 11056//11056 -f 11745//11745 11056//11056 11746//11746 -f 11746//11746 11056//11056 11054//11054 -f 11746//11746 11054//11054 11747//11747 -f 11747//11747 11054//11054 11052//11052 -f 11747//11747 11052//11052 11748//11748 -f 11748//11748 11052//11052 11075//11075 -f 11748//11748 11075//11075 11749//11749 -f 11749//11749 11075//11075 11074//11074 -f 11749//11749 11074//11074 11750//11750 -f 11750//11750 11074//11074 11073//11073 -f 11750//11750 11073//11073 11751//11751 -f 11751//11751 11073//11073 11069//11069 -f 11751//11751 11069//11069 11752//11752 -f 11752//11752 11069//11069 11068//11068 -f 11752//11752 11068//11068 11753//11753 -f 11753//11753 11068//11068 11066//11066 -f 11753//11753 11066//11066 11754//11754 -f 11754//11754 11066//11066 11064//11064 -f 11754//11754 11064//11064 11755//11755 -f 11755//11755 11064//11064 11062//11062 -f 11755//11755 11062//11062 11756//11756 -f 11756//11756 11062//11062 11061//11061 -f 11756//11756 11061//11061 11757//11757 -f 11757//11757 11061//11061 11049//11049 -f 11757//11757 11049//11049 11758//11758 -f 11758//11758 11049//11049 11048//11048 -f 11758//11758 11048//11048 11759//11759 -f 11759//11759 11048//11048 11085//11085 -f 11759//11759 11085//11085 11760//11760 -f 11760//11760 11085//11085 11084//11084 -f 11760//11760 11084//11084 11761//11761 -f 11761//11761 11084//11084 11082//11082 -f 11761//11761 11082//11082 11762//11762 -f 11762//11762 11082//11082 11080//11080 -f 11762//11762 11080//11080 11763//11763 -f 11763//11763 11080//11080 11079//11079 -f 11763//11763 11079//11079 11764//11764 -f 11764//11764 11079//11079 11093//11093 -f 11764//11764 11093//11093 11765//11765 -f 11765//11765 11093//11093 11092//11092 -f 11765//11765 11092//11092 11766//11766 -f 11766//11766 11092//11092 11091//11091 -f 11766//11766 11091//11091 11767//11767 -f 11767//11767 11091//11091 11090//11090 -f 11767//11767 11090//11090 11768//11768 -f 11768//11768 11090//11090 11089//11089 -f 11768//11768 11089//11089 11769//11769 -f 11769//11769 11089//11089 11086//11086 -f 11769//11769 11086//11086 11744//11744 -f 11744//11744 11086//11086 11058//11058 -f 11770//11770 11767//11767 11771//11771 -f 11771//11771 11767//11767 11768//11768 -f 11771//11771 11768//11768 11772//11772 -f 11772//11772 11768//11768 11769//11769 -f 11772//11772 11769//11769 11773//11773 -f 11773//11773 11769//11769 11744//11744 -f 11773//11773 11744//11744 11774//11774 -f 11774//11774 11744//11744 11745//11745 -f 11774//11774 11745//11745 11775//11775 -f 11776//11776 11760//11760 11777//11777 -f 11777//11777 11760//11760 11761//11761 -f 11777//11777 11761//11761 11778//11778 -f 11778//11778 11761//11761 11762//11762 -f 11778//11778 11762//11762 11779//11779 -f 11779//11779 11762//11762 11763//11763 -f 11779//11779 11763//11763 11780//11780 -f 11780//11780 11763//11763 11764//11764 -f 11780//11780 11764//11764 11781//11781 -f 11781//11781 11764//11764 11765//11765 -f 11781//11781 11765//11765 11770//11770 -f 11770//11770 11765//11765 11766//11766 -f 11770//11770 11766//11766 11767//11767 -f 11745//11745 11746//11746 11775//11775 -f 11775//11775 11746//11746 11747//11747 -f 11775//11775 11747//11747 11782//11782 -f 11782//11782 11747//11747 11748//11748 -f 11782//11782 11748//11748 11783//11783 -f 11783//11783 11748//11748 11749//11749 -f 11783//11783 11749//11749 11784//11784 -f 11784//11784 11749//11749 11750//11750 -f 11784//11784 11750//11750 11785//11785 -f 11785//11785 11750//11750 11751//11751 -f 11785//11785 11751//11751 11786//11786 -f 11786//11786 11751//11751 11752//11752 -f 11786//11786 11752//11752 11787//11787 -f 11752//11752 11753//11753 11787//11787 -f 11787//11787 11753//11753 11754//11754 -f 11787//11787 11754//11754 11788//11788 -f 11788//11788 11754//11754 11755//11755 -f 11788//11788 11755//11755 11789//11789 -f 11789//11789 11755//11755 11756//11756 -f 11789//11789 11756//11756 11790//11790 -f 11790//11790 11756//11756 11757//11757 -f 11790//11790 11757//11757 11791//11791 -f 11791//11791 11757//11757 11758//11758 -f 11791//11791 11758//11758 11776//11776 -f 11776//11776 11758//11758 11759//11759 -f 11776//11776 11759//11759 11760//11760 -f 11792//11792 11774//11774 11793//11793 -f 11793//11793 11774//11774 11775//11775 -f 11793//11793 11775//11775 11794//11794 -f 11794//11794 11775//11775 11782//11782 -f 11794//11794 11782//11782 11795//11795 -f 11795//11795 11782//11782 11783//11783 -f 11795//11795 11783//11783 11796//11796 -f 11796//11796 11783//11783 11784//11784 -f 11796//11796 11784//11784 11797//11797 -f 11797//11797 11784//11784 11785//11785 -f 11797//11797 11785//11785 11798//11798 -f 11798//11798 11785//11785 11786//11786 -f 11798//11798 11786//11786 11799//11799 -f 11799//11799 11786//11786 11787//11787 -f 11799//11799 11787//11787 11800//11800 -f 11800//11800 11787//11787 11788//11788 -f 11800//11800 11788//11788 11801//11801 -f 11801//11801 11788//11788 11789//11789 -f 11801//11801 11789//11789 11802//11802 -f 11802//11802 11789//11789 11790//11790 -f 11802//11802 11790//11790 11803//11803 -f 11803//11803 11790//11790 11791//11791 -f 11803//11803 11791//11791 11804//11804 -f 11804//11804 11791//11791 11776//11776 -f 11804//11804 11776//11776 11805//11805 -f 11805//11805 11776//11776 11777//11777 -f 11805//11805 11777//11777 11806//11806 -f 11806//11806 11777//11777 11778//11778 -f 11806//11806 11778//11778 11807//11807 -f 11807//11807 11778//11778 11779//11779 -f 11807//11807 11779//11779 11808//11808 -f 11808//11808 11779//11779 11780//11780 -f 11808//11808 11780//11780 11809//11809 -f 11809//11809 11780//11780 11781//11781 -f 11809//11809 11781//11781 11810//11810 -f 11810//11810 11781//11781 11770//11770 -f 11810//11810 11770//11770 11811//11811 -f 11811//11811 11770//11770 11771//11771 -f 11811//11811 11771//11771 11812//11812 -f 11812//11812 11771//11771 11772//11772 -f 11812//11812 11772//11772 11813//11813 -f 11813//11813 11772//11772 11773//11773 -f 11813//11813 11773//11773 11792//11792 -f 11792//11792 11773//11773 11774//11774 -f 11814//11814 11810//11810 11815//11815 -f 11815//11815 11810//11810 11811//11811 -f 11815//11815 11811//11811 11816//11816 -f 11816//11816 11811//11811 11812//11812 -f 11816//11816 11812//11812 11817//11817 -f 11817//11817 11812//11812 11813//11813 -f 11817//11817 11813//11813 11818//11818 -f 11818//11818 11813//11813 11792//11792 -f 11818//11818 11792//11792 11819//11819 -f 11819//11819 11792//11792 11793//11793 -f 11819//11819 11793//11793 11820//11820 -f 11820//11820 11793//11793 11794//11794 -f 11820//11820 11794//11794 11821//11821 -f 11822//11822 11804//11804 11823//11823 -f 11823//11823 11804//11804 11805//11805 -f 11823//11823 11805//11805 11824//11824 -f 11824//11824 11805//11805 11806//11806 -f 11824//11824 11806//11806 11825//11825 -f 11825//11825 11806//11806 11807//11807 -f 11825//11825 11807//11807 11826//11826 -f 11826//11826 11807//11807 11808//11808 -f 11826//11826 11808//11808 11814//11814 -f 11814//11814 11808//11808 11809//11809 -f 11814//11814 11809//11809 11810//11810 -f 11794//11794 11795//11795 11821//11821 -f 11821//11821 11795//11795 11796//11796 -f 11821//11821 11796//11796 11827//11827 -f 11827//11827 11796//11796 11797//11797 -f 11827//11827 11797//11797 11828//11828 -f 11828//11828 11797//11797 11798//11798 -f 11828//11828 11798//11798 11829//11829 -f 11829//11829 11798//11798 11799//11799 -f 11829//11829 11799//11799 11830//11830 -f 11830//11830 11799//11799 11800//11800 -f 11830//11830 11800//11800 11831//11831 -f 11831//11831 11800//11800 11801//11801 -f 11831//11831 11801//11801 11832//11832 -f 11832//11832 11801//11801 11802//11802 -f 11832//11832 11802//11802 11822//11822 -f 11822//11822 11802//11802 11803//11803 -f 11822//11822 11803//11803 11804//11804 -f 11833//11833 11818//11818 11834//11834 -f 11834//11834 11818//11818 11819//11819 -f 11834//11834 11819//11819 11835//11835 -f 11835//11835 11819//11819 11820//11820 -f 11835//11835 11820//11820 11836//11836 -f 11836//11836 11820//11820 11821//11821 -f 11836//11836 11821//11821 11837//11837 -f 11837//11837 11821//11821 11827//11827 -f 11837//11837 11827//11827 11838//11838 -f 11838//11838 11827//11827 11828//11828 -f 11838//11838 11828//11828 11839//11839 -f 11839//11839 11828//11828 11829//11829 -f 11839//11839 11829//11829 11840//11840 -f 11840//11840 11829//11829 11830//11830 -f 11840//11840 11830//11830 11841//11841 -f 11841//11841 11830//11830 11831//11831 -f 11841//11841 11831//11831 11842//11842 -f 11842//11842 11831//11831 11832//11832 -f 11842//11842 11832//11832 11843//11843 -f 11843//11843 11832//11832 11822//11822 -f 11843//11843 11822//11822 11844//11844 -f 11844//11844 11822//11822 11823//11823 -f 11844//11844 11823//11823 11845//11845 -f 11845//11845 11823//11823 11824//11824 -f 11845//11845 11824//11824 11846//11846 -f 11846//11846 11824//11824 11825//11825 -f 11846//11846 11825//11825 11847//11847 -f 11847//11847 11825//11825 11826//11826 -f 11847//11847 11826//11826 11848//11848 -f 11848//11848 11826//11826 11814//11814 -f 11848//11848 11814//11814 11849//11849 -f 11849//11849 11814//11814 11815//11815 -f 11849//11849 11815//11815 11850//11850 -f 11850//11850 11815//11815 11816//11816 -f 11850//11850 11816//11816 11851//11851 -f 11851//11851 11816//11816 11817//11817 -f 11851//11851 11817//11817 11833//11833 -f 11833//11833 11817//11817 11818//11818 -f 11833//11833 11834//11834 11852//11852 -f 11849//11849 11850//11850 11852//11852 -f 11852//11852 11850//11850 11851//11851 -f 11852//11852 11851//11851 11833//11833 -f 11846//11846 11847//11847 11852//11852 -f 11852//11852 11847//11847 11848//11848 -f 11852//11852 11848//11848 11849//11849 -f 11843//11843 11844//11844 11852//11852 -f 11852//11852 11844//11844 11845//11845 -f 11852//11852 11845//11845 11846//11846 -f 11840//11840 11841//11841 11852//11852 -f 11852//11852 11841//11841 11842//11842 -f 11852//11852 11842//11842 11843//11843 -f 11837//11837 11838//11838 11852//11852 -f 11852//11852 11838//11838 11839//11839 -f 11852//11852 11839//11839 11840//11840 -f 11834//11834 11835//11835 11852//11852 -f 11852//11852 11835//11835 11836//11836 -f 11852//11852 11836//11836 11837//11837 -f 11410//11410 10895//10895 11406//11406 -f 11406//11406 10895//10895 10890//10890 -f 11400//11400 10912//10912 11396//11396 -f 11396//11396 10912//10912 10901//10901 -f 11390//11390 10921//10921 11386//11386 -f 11386//11386 10921//10921 10918//10918 -f 10848//10848 11376//11376 10849//10849 -f 10849//10849 11376//11376 11380//11380 -f 10849//10849 11380//11380 10859//10859 -f 10943//10943 11363//11363 10778//10778 -f 10778//10778 11363//11363 11368//11368 -f 10778//10778 11368//11368 10779//10779 -f 11340//11340 10945//10945 11341//11341 -f 11341//11341 10945//10945 10944//10944 -f 10948//10948 11328//11328 10947//10947 -f 10947//10947 11328//11328 11327//11327 -f 10947//10947 11327//11327 10946//10946 -f 11280//11280 10969//10969 11281//11281 -f 11281//11281 10969//10969 10968//10968 -f 11274//11274 10989//10989 11275//11275 -f 11275//11275 10989//10989 10988//10988 -f 11268//11268 11013//11013 11269//11269 -f 11269//11269 11013//11013 11012//11012 -f 11160//11160 11270//11270 11161//11161 -f 11161//11161 11270//11270 11271//11271 -f 11244//11244 11267//11267 11243//11243 -f 11243//11243 11267//11267 11266//11266 -f 11218//11218 11276//11276 11219//11219 -f 11219//11219 11276//11276 11277//11277 -f 11204//11204 11273//11273 11205//11205 -f 11205//11205 11273//11273 11272//11272 -f 11200//11200 11282//11282 11201//11201 -f 11201//11201 11282//11282 11283//11283 -f 11196//11196 11279//11279 11197//11197 -f 11197//11197 11279//11279 11278//11278 -f 11186//11186 11329//11329 11187//11187 -f 11187//11187 11329//11329 11330//11330 -f 11214//11214 11326//11326 11215//11215 -f 11215//11215 11326//11326 11325//11325 -f 11162//11162 11408//11408 11163//11163 -f 11163//11163 11408//11408 11407//11407 -f 11178//11178 11412//11412 11179//11179 -f 11179//11179 11412//11412 11405//11405 -f 11166//11166 11398//11398 11167//11167 -f 11167//11167 11398//11398 11397//11397 -f 11183//11183 11402//11402 11184//11184 -f 11184//11184 11402//11402 11395//11395 -f 11170//11170 11388//11388 11171//11171 -f 11171//11171 11388//11388 11387//11387 -f 11190//11190 11392//11392 11191//11191 -f 11191//11191 11392//11392 11385//11385 -f 11209//11209 11378//11378 11210//11210 -f 11210//11210 11378//11378 11377//11377 -f 11212//11212 11382//11382 11213//11213 -f 11213//11213 11382//11382 11375//11375 -f 11236//11236 11342//11342 11237//11237 -f 11237//11237 11342//11342 11343//11343 -f 11233//11233 11339//11339 11234//11234 -f 11234//11234 11339//11339 11338//11338 -f 11228//11228 11370//11370 11229//11229 -f 11229//11229 11370//11370 11364//11364 -f 11155//11155 11366//11366 11156//11156 -f 11156//11156 11366//11366 11365//11365 -f 11414//11414 10887//10887 11413//11413 -f 11413//11413 10887//10887 10888//10888 -f 10908//10908 11403//11403 10909//10909 -f 10909//10909 11403//11403 11404//11404 -f 10909//10909 11404//11404 10883//10883 -f 10923//10923 11393//11393 10931//10931 -f 10931//10931 11393//11393 11394//11394 -f 10931//10931 11394//11394 10900//10900 -f 10861//10861 11383//11383 10926//10926 -f 10926//10926 11383//11383 11384//11384 -f 10926//10926 11384//11384 10917//10917 -f 11374//11374 10850//10850 11373//11373 -f 11373//11373 10850//10850 10852//10852 -f 11372//11372 10852//10852 11371//11371 -f 11371//11371 10852//10852 10855//10855 -f 11350//11350 10994//10994 11347//11347 -f 11347//11347 10994//10994 10993//10993 -f 11010//11010 11351//11351 11011//11011 -f 11011//11011 11351//11351 11352//11352 -f 11011//11011 11352//11352 10976//10976 -f 10979//10979 11353//11353 10980//10980 -f 10980//10980 11353//11353 11354//11354 -f 10980//10980 11354//11354 10955//10955 -f 10963//10963 11355//11355 10962//10962 -f 10962//10962 11355//11355 11356//11356 -f 10962//10962 11356//11356 10791//10791 -f 11360//11360 10812//10812 11359//11359 -f 11359//11359 10812//10812 10810//10810 -f 11358//11358 10810//10810 11357//11357 -f 11357//11357 10810//10810 10808//10808 -f 11362//11362 10839//10839 11361//11361 -f 11361//11361 10839//10839 10838//10838 -f 11361//11361 10838//10838 10825//10825 -f 11047//11047 11615//11615 11018//11018 -f 11018//11018 11615//11615 11016//11016 -f 11615//11615 11047//11047 11616//11616 -f 11616//11616 11047//11047 11081//11081 -f 11616//11616 11081//11081 11617//11617 -f 11617//11617 11081//11081 11083//11083 -f 11617//11617 11083//11083 11593//11593 -f 11593//11593 11083//11083 11050//11050 -f 11621//11621 10995//10995 11017//11017 -f 11017//11017 10995//10995 10997//10997 -f 11078//11078 11592//11592 11050//11050 -f 11050//11050 11592//11592 11593//11593 -f 11619//11619 11102//11102 11618//11618 -f 11618//11618 11102//11102 11730//11730 -f 11618//11618 11730//11730 11623//11623 -f 11623//11623 11730//11730 11729//11729 -f 11623//11623 11729//11729 11624//11624 -f 11624//11624 11729//11729 11728//11728 -f 11624//11624 11728//11728 11622//11622 -f 11622//11622 11728//11728 11727//11727 -f 11622//11622 11727//11727 11621//11621 -f 11621//11621 11727//11727 10995//10995 -f 11592//11592 11078//11078 11741//11741 -f 11592//11592 11741//11741 11591//11591 -f 11591//11591 11741//11741 11743//11743 -f 11591//11591 11743//11743 11590//11590 -f 11590//11590 11743//11743 11045//11045 -f 11590//11590 11045//11045 11587//11587 -f 11620//11620 11103//11103 11619//11619 -f 11619//11619 11103//11103 11102//11102 -f 11040//11040 11588//11588 11045//11045 -f 11045//11045 11588//11588 11587//11587 -f 11606//11606 11041//11041 11094//11094 -f 11103//11103 11620//11620 11100//11100 -f 11100//11100 11620//11620 11596//11596 -f 11100//11100 11596//11596 11598//11598 -f 11606//11606 11094//11094 11604//11604 -f 11604//11604 11094//11094 11095//11095 -f 11604//11604 11095//11095 11602//11602 -f 11602//11602 11095//11095 11096//11096 -f 11602//11602 11096//11096 11600//11600 -f 11096//11096 11097//11097 11600//11600 -f 11600//11600 11097//11097 11098//11098 -f 11600//11600 11098//11098 11598//11598 -f 11598//11598 11098//11098 11099//11099 -f 11598//11598 11099//11099 11100//11100 -f 11041//11041 11606//11606 11040//11040 -f 11040//11040 11606//11606 11588//11588 -f 11579//11579 11067//11067 11418//11418 -f 11418//11418 11067//11067 11071//11071 -f 11417//11417 10881//10881 11580//11580 -f 11580//11580 10881//10881 10782//10782 -f 11580//11580 10782//10782 10781//10781 -f 11551//11551 11076//11076 11585//11585 -f 11585//11585 11076//11076 11063//11063 -f 11585//11585 11063//11063 11586//11586 -f 11586//11586 11063//11063 11065//11065 -f 11586//11586 11065//11065 11579//11579 -f 11579//11579 11065//11065 11067//11067 -f 11558//11558 11557//11557 11581//11581 -f 11558//11558 11581//11581 11541//11541 -f 11580//11580 10781//10781 11582//11582 -f 11582//11582 10781//10781 11739//11739 -f 11582//11582 11739//11739 11583//11583 -f 11583//11583 11739//11739 11738//11738 -f 11583//11583 11738//11738 11584//11584 -f 11584//11584 11738//11738 11737//11737 -f 11584//11584 11737//11737 11581//11581 -f 11581//11581 11737//11737 11736//11736 -f 11581//11581 11736//11736 11541//11541 -f 11550//11550 11077//11077 11551//11551 -f 11551//11551 11077//11077 11076//11076 -f 11541//11541 11542//11542 11558//11558 -f 11555//11555 11044//11044 11742//11742 -f 11555//11555 11742//11742 11554//11554 -f 11554//11554 11742//11742 11740//11740 -f 11554//11554 11740//11740 11553//11553 -f 11553//11553 11740//11740 11077//11077 -f 11553//11553 11077//11077 11550//11550 -f 11559//11559 11558//11558 11542//11542 -f 11542//11542 11543//11543 11559//11559 -f 11559//11559 11543//11543 11544//11544 -f 11559//11559 11544//11544 11577//11577 -f 11577//11577 11544//11544 11545//11545 -f 11545//11545 11546//11546 11577//11577 -f 11577//11577 11546//11546 11547//11547 -f 11577//11577 11547//11547 11575//11575 -f 11547//11547 11548//11548 11575//11575 -f 11575//11575 11548//11548 11549//11549 -f 11575//11575 11549//11549 11573//11573 -f 11573//11573 11549//11549 11042//11042 -f 11573//11573 11042//11042 11571//11571 -f 11556//11556 11043//11043 11555//11555 -f 11555//11555 11043//11043 11044//11044 -f 11043//11043 11556//11556 11042//11042 -f 11042//11042 11556//11556 11571//11571 -f 11046//11046 11019//11019 11430//11430 -f 11430//11430 11019//11019 11020//11020 -f 11037//11037 11430//11430 11020//11020 -f 11036//11036 11429//11429 11037//11037 -f 11037//11037 11429//11429 11430//11430 -f 11675//11675 11705//11705 11014//11014 -f 11014//11014 11705//11705 11015//11015 -f 11015//11015 11032//11032 11020//11020 -f 11020//11020 11032//11032 11037//11037 -f 11429//11429 11036//11036 11428//11428 -f 11428//11428 11036//11036 11038//11038 -f 11428//11428 11038//11038 11427//11427 -f 11427//11427 11038//11038 11039//11039 -f 11427//11427 11039//11039 11426//11426 -f 11426//11426 11039//11039 11031//11031 -f 11426//11426 11031//11031 11425//11425 -f 11425//11425 11031//11031 11030//11030 -f 11425//11425 11030//11030 11424//11424 -f 11424//11424 11030//11030 11028//11028 -f 11424//11424 11028//11028 11423//11423 -f 11423//11423 11028//11028 11027//11027 -f 11423//11423 11027//11027 11422//11422 -f 11422//11422 11027//11027 11035//11035 -f 11014//11014 10795//10795 10806//10806 -f 10822//10822 10832//10832 11678//11678 -f 11678//11678 10832//10832 11022//11022 -f 11678//11678 11022//11022 11676//11676 -f 10822//10822 11678//11678 10821//10821 -f 10821//10821 11678//11678 11683//11683 -f 10821//10821 11683//11683 10830//10830 -f 11683//11683 11682//11682 10830//10830 -f 10830//10830 11682//11682 11686//11686 -f 10830//10830 11686//11686 10831//10831 -f 11686//11686 11685//11685 10831//10831 -f 10831//10831 11685//11685 11689//11689 -f 10831//10831 11689//11689 10811//10811 -f 11689//11689 11688//11688 10811//10811 -f 10811//10811 11688//11688 11692//11692 -f 10811//10811 11692//11692 10809//10809 -f 11692//11692 11691//11691 10809//10809 -f 10809//10809 11691//11691 11695//11695 -f 10809//10809 11695//11695 10800//10800 -f 10800//10800 11695//11695 11694//11694 -f 10800//10800 11694//11694 10801//10801 -f 10801//10801 11694//11694 11698//11698 -f 10801//10801 11698//11698 10803//10803 -f 11698//11698 11697//11697 10803//10803 -f 10803//10803 11697//11697 11701//11701 -f 10803//10803 11701//11701 10805//10805 -f 11701//11701 11700//11700 10805//10805 -f 10805//10805 11700//11700 11704//11704 -f 10805//10805 11704//11704 10806//10806 -f 10806//10806 11704//11704 11703//11703 -f 10806//10806 11703//11703 11014//11014 -f 11014//11014 11703//11703 11702//11702 -f 11014//11014 11702//11702 11675//11675 -f 11015//11015 11705//11705 11032//11032 -f 11026//11026 11421//11421 11035//11035 -f 11035//11035 11421//11421 11422//11422 -f 11421//11421 11420//11420 11070//11070 -f 11070//11070 11420//11420 11072//11072 -f 11021//11021 11709//11709 11022//11022 -f 11022//11022 11709//11709 11676//11676 -f 11708//11708 11709//11709 11033//11033 -f 11708//11708 11033//11033 11707//11707 -f 11707//11707 11033//11033 11029//11029 -f 11707//11707 11029//11029 11706//11706 -f 11706//11706 11029//11029 11032//11032 -f 11706//11706 11032//11032 11705//11705 -f 11421//11421 11026//11026 11420//11420 -f 11709//11709 11021//11021 11033//11033 -f 11025//11025 11419//11419 11026//11026 -f 11026//11026 11419//11419 11420//11420 -f 11023//11023 11034//11034 11021//11021 -f 11021//11021 11034//11034 11033//11033 -f 11034//11034 11656//11656 11657//11657 -f 11034//11034 11657//11657 11024//11024 -f 11024//11024 11657//11657 11658//11658 -f 11024//11024 11658//11658 11025//11025 -f 11025//11025 11658//11658 11659//11659 -f 11025//11025 11659//11659 11660//11660 -f 11025//11025 11660//11660 11419//11419 -f 11034//11034 11023//11023 11656//11656 -f 10783//10783 11419//11419 10784//10784 -f 10784//10784 11419//11419 11660//11660 -f 10784//10784 11660//11660 11625//11625 -f 11023//11023 10835//10835 11656//11656 -f 11656//11656 10835//10835 10837//10837 -f 11656//11656 10837//10837 11654//11654 -f 11654//11654 10837//10837 11655//11655 -f 11655//11655 10837//10837 10836//10836 -f 10785//10785 10784//10784 11625//11625 -f 11625//11625 11627//11627 10785//10785 -f 10785//10785 11627//11627 11629//11629 -f 10785//10785 11629//11629 10868//10868 -f 11629//11629 11633//11633 10868//10868 -f 10868//10868 11633//11633 11632//11632 -f 10868//10868 11632//11632 10874//10874 -f 11632//11632 11636//11636 10874//10874 -f 10874//10874 11636//11636 11635//11635 -f 10874//10874 11635//11635 10873//10873 -f 11635//11635 11639//11639 10873//10873 -f 10873//10873 11639//11639 11638//11638 -f 10873//10873 11638//11638 10851//10851 -f 10851//10851 11638//11638 10853//10853 -f 11638//11638 11646//11646 10853//10853 -f 10853//10853 11646//11646 11645//11645 -f 10853//10853 11645//11645 10854//10854 -f 10854//10854 11645//11645 11643//11643 -f 10854//10854 11643//11643 10856//10856 -f 10856//10856 11643//11643 11641//11641 -f 10856//10856 11641//11641 10942//10942 -f 10942//10942 11641//11641 10940//10940 -f 10940//10940 11641//11641 11649//11649 -f 10940//10940 11649//11649 10938//10938 -f 11649//11649 11648//11648 10938//10938 -f 10938//10938 11648//11648 11652//11652 -f 10938//10938 11652//11652 10836//10836 -f 10836//10836 11652//11652 11651//11651 -f 10836//10836 11651//11651 11655//11655 -f 11853//11853 11854//11854 11855//11855 -f 11856//11856 11857//11857 11858//11858 -f 11859//11859 11860//11860 11861//11861 -f 11862//11862 11863//11863 11864//11864 -f 11865//11865 11866//11866 11867//11867 -f 11868//11868 11869//11869 11870//11870 -f 11870//11870 11869//11869 11871//11871 -f 11870//11870 11871//11871 11872//11872 -f 11873//11873 11874//11874 11875//11875 -f 11875//11875 11876//11876 11873//11873 -f 11873//11873 11876//11876 11877//11877 -f 11873//11873 11877//11877 11878//11878 -f 11878//11878 11877//11877 11879//11879 -f 11878//11878 11879//11879 11880//11880 -f 11881//11881 11882//11882 11883//11883 -f 11883//11883 11882//11882 11884//11884 -f 11883//11883 11884//11884 11885//11885 -f 11885//11885 11884//11884 11886//11886 -f 11885//11885 11886//11886 11880//11880 -f 11880//11880 11886//11886 11887//11887 -f 11880//11880 11887//11887 11878//11878 -f 11888//11888 11889//11889 11890//11890 -f 11890//11890 11889//11889 11891//11891 -f 11890//11890 11891//11891 11892//11892 -f 11892//11892 11891//11891 11893//11893 -f 11892//11892 11893//11893 11894//11894 -f 11893//11893 11895//11895 11894//11894 -f 11894//11894 11895//11895 11896//11896 -f 11894//11894 11896//11896 11864//11864 -f 11864//11864 11896//11896 11897//11897 -f 11864//11864 11897//11897 11898//11898 -f 11899//11899 11900//11900 11901//11901 -f 11901//11901 11900//11900 11902//11902 -f 11901//11901 11902//11902 11903//11903 -f 11903//11903 11902//11902 11904//11904 -f 11905//11905 11906//11906 11907//11907 -f 11907//11907 11906//11906 11908//11908 -f 11907//11907 11908//11908 11909//11909 -f 11905//11905 11910//11910 11906//11906 -f 11906//11906 11910//11910 11911//11911 -f 11906//11906 11911//11911 11912//11912 -f 11912//11912 11911//11911 11913//11913 -f 11912//11912 11913//11913 11914//11914 -f 11915//11915 11916//11916 11917//11917 -f 11918//11918 11919//11919 11920//11920 -f 11920//11920 11919//11919 11921//11921 -f 11920//11920 11921//11921 11907//11907 -f 11907//11907 11921//11921 11922//11922 -f 11907//11907 11922//11922 11905//11905 -f 11913//11913 11923//11923 11914//11914 -f 11914//11914 11923//11923 11924//11924 -f 11914//11914 11924//11924 11916//11916 -f 11916//11916 11924//11924 11925//11925 -f 11916//11916 11925//11925 11917//11917 -f 11926//11926 11927//11927 11928//11928 -f 11927//11927 11929//11929 11928//11928 -f 11928//11928 11929//11929 11930//11930 -f 11928//11928 11930//11930 11931//11931 -f 11931//11931 11930//11930 11932//11932 -f 11932//11932 11933//11933 11931//11931 -f 11931//11931 11933//11933 11934//11934 -f 11931//11931 11934//11934 11935//11935 -f 11934//11934 11936//11936 11935//11935 -f 11935//11935 11936//11936 11937//11937 -f 11935//11935 11937//11937 11938//11938 -f 11938//11938 11937//11937 11939//11939 -f 11938//11938 11939//11939 11940//11940 -f 11940//11940 11939//11939 11941//11941 -f 11940//11940 11941//11941 11942//11942 -f 11942//11942 11941//11941 11943//11943 -f 11942//11942 11943//11943 11926//11926 -f 11944//11944 11945//11945 11946//11946 -f 11946//11946 11945//11945 11947//11947 -f 11946//11946 11947//11947 11948//11948 -f 11948//11948 11947//11947 11949//11949 -f 11948//11948 11949//11949 11950//11950 -f 11950//11950 11951//11951 11948//11948 -f 11948//11948 11951//11951 11952//11952 -f 11948//11948 11952//11952 11953//11953 -f 11954//11954 11955//11955 11956//11956 -f 11952//11952 11957//11957 11953//11953 -f 11953//11953 11957//11957 11958//11958 -f 11953//11953 11958//11958 11955//11955 -f 11956//11956 11959//11959 11954//11954 -f 11954//11954 11959//11959 11960//11960 -f 11954//11954 11960//11960 11961//11961 -f 11961//11961 11960//11960 11962//11962 -f 11961//11961 11962//11962 11963//11963 -f 11963//11963 11962//11962 11964//11964 -f 11963//11963 11964//11964 11949//11949 -f 11949//11949 11964//11964 11965//11965 -f 11949//11949 11965//11965 11950//11950 -f 11966//11966 11967//11967 11968//11968 -f 11968//11968 11967//11967 11969//11969 -f 11968//11968 11969//11969 11970//11970 -f 11971//11971 11972//11972 11973//11973 -f 11973//11973 11972//11972 11974//11974 -f 11973//11973 11974//11974 11975//11975 -f 11971//11971 11976//11976 11972//11972 -f 11972//11972 11976//11976 11977//11977 -f 11972//11972 11977//11977 11978//11978 -f 11978//11978 11977//11977 11979//11979 -f 11978//11978 11979//11979 11980//11980 -f 11980//11980 11979//11979 11981//11981 -f 11980//11980 11981//11981 11969//11969 -f 11969//11969 11981//11981 11982//11982 -f 11969//11969 11982//11982 11970//11970 -f 11983//11983 11984//11984 11985//11985 -f 11985//11985 11984//11984 11968//11968 -f 11985//11985 11968//11968 11986//11986 -f 11986//11986 11968//11968 11970//11970 -f 11987//11987 11988//11988 11989//11989 -f 11987//11987 11989//11989 11990//11990 -f 11991//11991 11992//11992 11968//11968 -f 11968//11968 11992//11992 11993//11993 -f 11968//11968 11993//11993 11966//11966 -f 11966//11966 11993//11993 11994//11994 -f 11966//11966 11994//11994 11995//11995 -f 11996//11996 11997//11997 11998//11998 -f 11999//11999 12000//12000 12001//12001 -f 12000//12000 12002//12002 12001//12001 -f 12001//12001 12002//12002 12003//12003 -f 12001//12001 12003//12003 12004//12004 -f 12004//12004 12003//12003 12005//12005 -f 11989//11989 12006//12006 11990//11990 -f 11990//11990 12006//12006 12007//12007 -f 11990//11990 12007//12007 12008//12008 -f 12008//12008 12007//12007 12009//12009 -f 12010//12010 11855//11855 12011//12011 -f 12011//12011 11855//11855 12012//12012 -f 12011//12011 12012//12012 11974//11974 -f 11974//11974 12012//12012 11984//11984 -f 11974//11974 11984//11984 11975//11975 -f 11975//11975 11984//11984 11983//11983 -f 12013//12013 12014//12014 12015//12015 -f 12016//12016 12015//12015 12017//12017 -f 12018//12018 12019//12019 12020//12020 -f 12020//12020 12019//12019 11990//11990 -f 12020//12020 11990//11990 12021//12021 -f 12021//12021 11990//11990 12008//12008 -f 12021//12021 12008//12008 12022//12022 -f 12022//12022 12008//12008 12009//12009 -f 12022//12022 12009//12009 12023//12023 -f 11931//11931 12024//12024 11928//11928 -f 11928//11928 12024//12024 12025//12025 -f 11928//11928 12025//12025 12022//12022 -f 12022//12022 12025//12025 12026//12026 -f 12022//12022 12026//12026 12021//12021 -f 12027//12027 12028//12028 12029//12029 -f 12030//12030 11938//11938 12031//12031 -f 12031//12031 11938//11938 11940//11940 -f 12031//12031 11940//11940 12032//12032 -f 12032//12032 11940//11940 12029//12029 -f 12033//12033 12034//12034 12035//12035 -f 12036//12036 12034//12034 12037//12037 -f 12037//12037 12034//12034 12033//12033 -f 12037//12037 12033//12033 12038//12038 -f 11899//11899 11888//11888 11900//11900 -f 11900//11900 11888//11888 11890//11890 -f 11900//11900 11890//11890 12039//12039 -f 12039//12039 11890//11890 12040//12040 -f 12039//12039 12040//12040 12041//12041 -f 12041//12041 12040//12040 12042//12042 -f 12041//12041 12042//12042 12043//12043 -f 11861//11861 11860//11860 11902//11902 -f 11898//11898 11904//11904 11864//11864 -f 11864//11864 11904//11904 11902//11902 -f 11864//11864 11902//11902 11862//11862 -f 11862//11862 11902//11902 11860//11860 -f 11862//11862 11860//11860 12044//12044 -f 11861//11861 12045//12045 11859//11859 -f 11859//11859 12045//12045 12046//12046 -f 11859//11859 12046//12046 12047//12047 -f 12047//12047 12046//12046 12048//12048 -f 12049//12049 12050//12050 12046//12046 -f 12046//12046 12050//12050 12051//12051 -f 12046//12046 12051//12051 12048//12048 -f 12052//12052 12053//12053 12054//12054 -f 12054//12054 12053//12053 12055//12055 -f 12054//12054 12055//12055 12056//12056 -f 12056//12056 12055//12055 12057//12057 -f 12058//12058 12059//12059 12055//12055 -f 12060//12060 12057//12057 12061//12061 -f 12061//12061 12057//12057 12055//12055 -f 12061//12061 12055//12055 12062//12062 -f 12062//12062 12055//12055 12059//12059 -f 12063//12063 12064//12064 12065//12065 -f 11955//11955 11954//11954 11953//11953 -f 11953//11953 11954//11954 12066//12066 -f 11953//11953 12066//12066 12067//12067 -f 12067//12067 12068//12068 11953//11953 -f 11953//11953 12068//12068 12069//12069 -f 11953//11953 12069//12069 12070//12070 -f 12070//12070 12069//12069 12063//12063 -f 12071//12071 12072//12072 12073//12073 -f 12073//12073 12074//12074 12071//12071 -f 12071//12071 12074//12074 12075//12075 -f 12071//12071 12075//12075 11906//11906 -f 11906//11906 12075//12075 12076//12076 -f 11906//11906 12076//12076 11908//11908 -f 12074//12074 12077//12077 12075//12075 -f 12075//12075 12077//12077 12078//12078 -f 12075//12075 12078//12078 12079//12079 -f 12079//12079 12078//12078 12080//12080 -f 12079//12079 12080//12080 12081//12081 -f 12080//12080 12082//12082 12081//12081 -f 12081//12081 12082//12082 12083//12083 -f 12081//12081 12083//12083 12084//12084 -f 12085//12085 12086//12086 12087//12087 -f 12087//12087 12086//12086 12088//12088 -f 12087//12087 12088//12088 12072//12072 -f 12072//12072 12088//12088 12089//12089 -f 12072//12072 12089//12089 12073//12073 -f 11940//11940 12090//12090 12081//12081 -f 12029//12029 11940//11940 12027//12027 -f 12027//12027 11940//11940 12081//12081 -f 12027//12027 12081//12081 12087//12087 -f 12087//12087 12081//12081 12084//12084 -f 12087//12087 12084//12084 12085//12085 -f 11926//11926 11928//11928 11942//11942 -f 11942//11942 11928//11928 12091//12091 -f 11942//11942 12091//12091 11940//11940 -f 11940//11940 12091//12091 12092//12092 -f 11940//11940 12092//12092 12090//12090 -f 12093//12093 12094//12094 12022//12022 -f 12094//12094 12095//12095 12022//12022 -f 12022//12022 12095//12095 12096//12096 -f 12022//12022 12096//12096 11928//11928 -f 11928//11928 12096//12096 12097//12097 -f 11928//11928 12097//12097 12091//12091 -f 12098//12098 12099//12099 12100//12100 -f 12100//12100 12099//12099 12093//12093 -f 12100//12100 12093//12093 12101//12101 -f 12101//12101 12093//12093 12022//12022 -f 12101//12101 12022//12022 12102//12102 -f 12102//12102 12022//12022 12023//12023 -f 12103//12103 12098//12098 12001//12001 -f 12001//12001 12098//12098 12100//12100 -f 12001//12001 12100//12100 11999//11999 -f 11999//11999 12100//12100 12101//12101 -f 11999//11999 12101//12101 12104//12104 -f 12104//12104 12101//12101 12102//12102 -f 12105//12105 12106//12106 12107//12107 -f 12107//12107 12106//12106 12108//12108 -f 12107//12107 12108//12108 12109//12109 -f 12109//12109 12108//12108 12110//12110 -f 12109//12109 12110//12110 12001//12001 -f 12001//12001 12110//12110 12111//12111 -f 12001//12001 12111//12111 12103//12103 -f 12112//12112 12113//12113 12114//12114 -f 12113//12113 12112//12112 12115//12115 -f 12116//12116 12117//12117 12118//12118 -f 12119//12119 12120//12120 12121//12121 -f 12117//12117 12116//12116 12121//12121 -f 12121//12121 12116//12116 12122//12122 -f 12121//12121 12122//12122 12119//12119 -f 12120//12120 12119//12119 12123//12123 -f 12123//12123 12119//12119 12124//12124 -f 12123//12123 12124//12124 12125//12125 -f 12126//12126 12127//12127 12113//12113 -f 12113//12113 12127//12127 12128//12128 -f 12113//12113 12128//12128 12114//12114 -f 12114//12114 12128//12128 12129//12129 -f 12114//12114 12129//12129 12130//12130 -f 12130//12130 12129//12129 12131//12131 -f 12130//12130 12131//12131 12132//12132 -f 12132//12132 12131//12131 12133//12133 -f 12132//12132 12133//12133 12134//12134 -f 12134//12134 12133//12133 12135//12135 -f 12134//12134 12135//12135 12136//12136 -f 12137//12137 12138//12138 12139//12139 -f 12139//12139 12138//12138 12140//12140 -f 12137//12137 12141//12141 12138//12138 -f 12138//12138 12141//12141 12142//12142 -f 12138//12138 12142//12142 11874//11874 -f 11874//11874 12142//12142 12143//12143 -f 11874//11874 12143//12143 11875//11875 -f 11875//11875 12143//12143 12144//12144 -f 11875//11875 12144//12144 12145//12145 -f 12145//12145 12144//12144 12146//12146 -f 12145//12145 12146//12146 11868//11868 -f 11868//11868 12146//12146 12147//12147 -f 11868//11868 12147//12147 11869//11869 -f 12148//12148 12149//12149 12150//12150 -f 12150//12150 12149//12149 12151//12151 -f 12150//12150 12151//12151 12140//12140 -f 12140//12140 12151//12151 12152//12152 -f 12140//12140 12152//12152 12139//12139 -f 12153//12153 12154//12154 12155//12155 -f 12155//12155 12154//12154 12156//12156 -f 12155//12155 12156//12156 12157//12157 -f 12148//12148 12150//12150 12158//12158 -f 12158//12158 12150//12150 12159//12159 -f 12158//12158 12159//12159 12160//12160 -f 12160//12160 12159//12159 12053//12053 -f 12160//12160 12053//12053 12161//12161 -f 12161//12161 12053//12053 12052//12052 -f 12161//12161 12052//12052 12155//12155 -f 12155//12155 12052//12052 12162//12162 -f 12155//12155 12162//12162 12153//12153 -f 12061//12061 12163//12163 12060//12060 -f 12060//12060 12163//12163 12164//12164 -f 12060//12060 12164//12164 12165//12165 -f 12165//12165 12164//12164 12166//12166 -f 12165//12165 12166//12166 12167//12167 -f 12167//12167 12166//12166 12168//12168 -f 12167//12167 12168//12168 12169//12169 -f 12169//12169 12168//12168 12156//12156 -f 12169//12169 12156//12156 12170//12170 -f 12170//12170 12156//12156 12154//12154 -f 11881//11881 11872//11872 11882//11882 -f 11882//11882 11872//11872 11871//11871 -f 11882//11882 11871//11871 12156//12156 -f 12156//12156 11871//11871 12171//12171 -f 12156//12156 12171//12171 12157//12157 -f 11858//11858 12172//12172 12173//12173 -f 12126//12126 12174//12174 12175//12175 -f 11857//11857 12127//12127 11858//11858 -f 11858//11858 12127//12127 12126//12126 -f 11858//11858 12126//12126 12172//12172 -f 12172//12172 12126//12126 12175//12175 -f 11873//11873 12176//12176 11874//11874 -f 11874//11874 12176//12176 12177//12177 -f 11874//11874 12177//12177 12138//12138 -f 12138//12138 12177//12177 12178//12178 -f 12138//12138 12178//12178 12179//12179 -f 12173//12173 12180//12180 11858//11858 -f 11858//11858 12180//12180 12181//12181 -f 11858//11858 12181//12181 12182//12182 -f 12182//12182 12181//12181 12183//12183 -f 12182//12182 12183//12183 11873//11873 -f 11873//11873 12183//12183 12184//12184 -f 11873//11873 12184//12184 12176//12176 -f 12185//12185 12186//12186 12187//12187 -f 12185//12185 12187//12187 12188//12188 -f 12189//12189 12190//12190 12191//12191 -f 12191//12191 12190//12190 12192//12192 -f 12191//12191 12192//12192 12193//12193 -f 12193//12193 12188//12188 12191//12191 -f 12191//12191 12188//12188 12187//12187 -f 12191//12191 12187//12187 12194//12194 -f 12194//12194 12187//12187 12115//12115 -f 12194//12194 12115//12115 12195//12195 -f 12195//12195 12115//12115 12112//12112 -f 12055//12055 12196//12196 12189//12189 -f 12189//12189 12196//12196 12197//12197 -f 12189//12189 12197//12197 12190//12190 -f 12186//12186 12198//12198 12159//12159 -f 12159//12159 12198//12198 12199//12199 -f 12159//12159 12199//12199 12053//12053 -f 12053//12053 12199//12199 12200//12200 -f 12053//12053 12200//12200 12055//12055 -f 12055//12055 12200//12200 12201//12201 -f 12055//12055 12201//12201 12196//12196 -f 12202//12202 11892//11892 12203//12203 -f 12203//12203 11892//11892 11894//11894 -f 12203//12203 11894//11894 12204//12204 -f 12204//12204 11894//11894 11864//11864 -f 12204//12204 11864//11864 12205//12205 -f 12205//12205 11864//11864 11863//11863 -f 12206//12206 11912//11912 12207//12207 -f 12207//12207 11912//11912 11914//11914 -f 12207//12207 11914//11914 12208//12208 -f 12208//12208 11914//11914 11916//11916 -f 12209//12209 12028//12028 12210//12210 -f 12210//12210 12028//12028 12027//12027 -f 12210//12210 12027//12027 12211//12211 -f 12211//12211 12027//12027 12087//12087 -f 12211//12211 12087//12087 12212//12212 -f 12212//12212 12087//12087 12072//12072 -f 11917//11917 11918//11918 11915//11915 -f 11915//11915 11918//11918 11920//11920 -f 11915//11915 11920//11920 12035//12035 -f 12035//12035 11920//11920 12213//12213 -f 12035//12035 12213//12213 12033//12033 -f 12033//12033 12213//12213 12214//12214 -f 12214//12214 12215//12215 12033//12033 -f 12033//12033 12215//12215 12216//12216 -f 12033//12033 12216//12216 12217//12217 -f 12218//12218 12219//12219 12041//12041 -f 12043//12043 12038//12038 12041//12041 -f 12041//12041 12038//12038 12033//12033 -f 12041//12041 12033//12033 12218//12218 -f 12218//12218 12033//12033 12217//12217 -f 12220//12220 12039//12039 12221//12221 -f 12221//12221 12039//12039 12041//12041 -f 12221//12221 12041//12041 12222//12222 -f 12222//12222 12041//12041 12219//12219 -f 12220//12220 12223//12223 12039//12039 -f 12039//12039 12223//12223 12224//12224 -f 12039//12039 12224//12224 12213//12213 -f 12213//12213 12224//12224 12225//12225 -f 12213//12213 12225//12225 12214//12214 -f 12039//12039 11856//11856 11900//11900 -f 11900//11900 11856//11856 11858//11858 -f 11900//11900 11858//11858 11902//11902 -f 11902//11902 11858//11858 12182//12182 -f 11902//11902 12182//12182 11861//11861 -f 11861//11861 12182//12182 11873//11873 -f 11861//11861 11873//11873 12045//12045 -f 12045//12045 11873//11873 11878//11878 -f 11909//11909 12105//12105 11907//11907 -f 11907//11907 12105//12105 12107//12107 -f 11907//11907 12107//12107 11920//11920 -f 11920//11920 12107//12107 12226//12226 -f 12107//12107 12227//12227 12228//12228 -f 12229//12229 12230//12230 12226//12226 -f 12228//12228 12231//12231 12107//12107 -f 12107//12107 12231//12231 12232//12232 -f 12107//12107 12232//12232 12226//12226 -f 12226//12226 12232//12232 12233//12233 -f 12226//12226 12233//12233 12229//12229 -f 12230//12230 12134//12134 12226//12226 -f 12226//12226 12134//12134 12136//12136 -f 12226//12226 12136//12136 11920//11920 -f 11920//11920 12136//12136 12234//12234 -f 11920//11920 12234//12234 12213//12213 -f 12213//12213 12234//12234 12235//12235 -f 12213//12213 12235//12235 12039//12039 -f 12039//12039 12235//12235 12236//12236 -f 12039//12039 12236//12236 11856//11856 -f 12230//12230 12237//12237 12134//12134 -f 12134//12134 12237//12237 12238//12238 -f 12134//12134 12238//12238 12239//12239 -f 12227//12227 12107//12107 12240//12240 -f 12240//12240 12107//12107 12109//12109 -f 12240//12240 12109//12109 12241//12241 -f 12242//12242 12243//12243 12004//12004 -f 12004//12004 12243//12243 12132//12132 -f 12004//12004 12132//12132 12001//12001 -f 12001//12001 12132//12132 12134//12134 -f 12001//12001 12134//12134 12109//12109 -f 12109//12109 12134//12134 12239//12239 -f 12109//12109 12239//12239 12241//12241 -f 12186//12186 12159//12159 12187//12187 -f 12187//12187 12159//12159 12150//12150 -f 12187//12187 12150//12150 12115//12115 -f 12115//12115 12150//12150 12140//12140 -f 12115//12115 12140//12140 12113//12113 -f 12113//12113 12140//12140 12138//12138 -f 12113//12113 12138//12138 12126//12126 -f 12126//12126 12138//12138 12179//12179 -f 12126//12126 12179//12179 12174//12174 -f 12242//12242 12116//12116 12243//12243 -f 12243//12243 12116//12116 12118//12118 -f 12243//12243 12118//12118 12132//12132 -f 12132//12132 12118//12118 12244//12244 -f 12132//12132 12244//12244 12130//12130 -f 12130//12130 12244//12244 12245//12245 -f 12130//12130 12245//12245 12114//12114 -f 12114//12114 12245//12245 12246//12246 -f 12114//12114 12246//12246 12112//12112 -f 12247//12247 12248//12248 12242//12242 -f 12249//12249 12247//12247 11998//11998 -f 11998//11998 12247//12247 12242//12242 -f 11998//11998 12242//12242 11996//11996 -f 11996//11996 12242//12242 12004//12004 -f 11996//11996 12004//12004 12250//12250 -f 12250//12250 12004//12004 12005//12005 -f 12251//12251 12116//12116 12252//12252 -f 12252//12252 12116//12116 12242//12242 -f 12252//12252 12242//12242 12253//12253 -f 12253//12253 12242//12242 12248//12248 -f 12251//12251 12254//12254 12116//12116 -f 12116//12116 12254//12254 12255//12255 -f 12116//12116 12255//12255 12122//12122 -f 12122//12122 12255//12255 12256//12256 -f 12256//12256 12257//12257 12122//12122 -f 12122//12122 12257//12257 12258//12258 -f 12122//12122 12258//12258 11998//11998 -f 11998//11998 12258//12258 12259//12259 -f 11998//11998 12259//12259 12249//12249 -f 12260//12260 12019//12019 12261//12261 -f 12261//12261 12019//12019 12262//12262 -f 12261//12261 12262//12262 12263//12263 -f 12263//12263 12262//12262 12264//12264 -f 12265//12265 11990//11990 12266//12266 -f 12266//12266 11990//11990 12019//12019 -f 12266//12266 12019//12019 12267//12267 -f 12267//12267 12019//12019 12260//12260 -f 11987//11987 12268//12268 12269//12269 -f 12265//12265 12270//12270 11990//11990 -f 11990//11990 12270//12270 12271//12271 -f 11990//11990 12271//12271 11987//11987 -f 11987//11987 12271//12271 12272//12272 -f 11987//11987 12272//12272 12268//12268 -f 12065//12065 12273//12273 12063//12063 -f 12063//12063 12273//12273 12058//12058 -f 12063//12063 12058//12058 12070//12070 -f 12070//12070 12058//12058 12055//12055 -f 12070//12070 12055//12055 11953//11953 -f 11953//11953 12055//12055 12189//12189 -f 11953//11953 12189//12189 11948//11948 -f 11948//11948 12189//12189 12191//12191 -f 11948//11948 12191//12191 11946//11946 -f 11997//11997 11991//11991 11998//11998 -f 11998//11998 11991//11991 11968//11968 -f 11998//11998 11968//11968 12122//12122 -f 12122//12122 11968//11968 11984//11984 -f 12122//12122 11984//11984 12119//12119 -f 12119//12119 11984//11984 12012//12012 -f 12119//12119 12012//12012 12124//12124 -f 12015//12015 12016//12016 12013//12013 -f 12013//12013 12016//12016 11987//11987 -f 12013//12013 11987//11987 12262//12262 -f 12262//12262 11987//11987 12269//12269 -f 12262//12262 12269//12269 12264//12264 -f 12274//12274 12275//12275 11946//11946 -f 11855//11855 11854//11854 12012//12012 -f 12012//12012 11854//11854 12276//12276 -f 12012//12012 12276//12276 12277//12277 -f 12194//12194 12125//12125 12191//12191 -f 12191//12191 12125//12125 12124//12124 -f 12191//12191 12124//12124 11946//11946 -f 11946//11946 12124//12124 12012//12012 -f 11946//11946 12012//12012 12274//12274 -f 12274//12274 12012//12012 12277//12277 -f 12275//12275 12278//12278 11946//11946 -f 11946//11946 12278//12278 12279//12279 -f 11946//11946 12279//12279 11944//11944 -f 11944//11944 12279//12279 12280//12280 -f 12280//12280 12281//12281 11944//11944 -f 11944//11944 12281//12281 12282//12282 -f 11944//11944 12282//12282 11855//11855 -f 11855//11855 12282//12282 12283//12283 -f 11855//11855 12283//12283 11853//11853 -f 12284//12284 12285//12285 12286//12286 -f 12286//12286 12285//12285 11967//11967 -f 12286//12286 11967//11967 12287//12287 -f 12287//12287 11967//11967 11966//11966 -f 12287//12287 11966//11966 12288//12288 -f 12284//12284 12289//12289 12285//12285 -f 12285//12285 12289//12289 12290//12290 -f 12285//12285 12290//12290 12291//12291 -f 12291//12291 12290//12290 12292//12292 -f 12291//12291 12292//12292 12293//12293 -f 12294//12294 12295//12295 12296//12296 -f 12296//12296 12295//12295 12297//12297 -f 12296//12296 12297//12297 12298//12298 -f 11988//11988 11987//11987 12299//12299 -f 12299//12299 11987//11987 12016//12016 -f 12299//12299 12016//12016 11995//11995 -f 11995//11995 12016//12016 12296//12296 -f 11995//11995 12296//12296 11966//11966 -f 11966//11966 12296//12296 12298//12298 -f 11966//11966 12298//12298 12288//12288 -f 12017//12017 11865//11865 12016//12016 -f 12016//12016 11865//11865 11867//11867 -f 12016//12016 11867//11867 12296//12296 -f 12296//12296 11867//11867 12291//12291 -f 12296//12296 12291//12291 12294//12294 -f 12294//12294 12291//12291 12293//12293 -f 12300//12300 12301//12301 12302//12302 -f 12303//12303 12304//12304 12305//12305 -f 12300//12300 12302//12302 12306//12306 -f 12302//12302 12307//12307 12306//12306 -f 12306//12306 12307//12307 12308//12308 -f 12306//12306 12308//12308 12309//12309 -f 12303//12303 12305//12305 12310//12310 -f 12305//12305 12311//12311 12310//12310 -f 12310//12310 12311//12311 12312//12312 -f 12310//12310 12312//12312 12300//12300 -f 12300//12300 12312//12312 12313//12313 -f 12300//12300 12313//12313 12301//12301 -f 12308//12308 12314//12314 12309//12309 -f 12309//12309 12314//12314 12315//12315 -f 12309//12309 12315//12315 12303//12303 -f 12303//12303 12315//12315 12316//12316 -f 12303//12303 12316//12316 12304//12304 -f 12317//12317 12318//12318 12319//12319 -f 12319//12319 12318//12318 12320//12320 -f 12321//12321 12322//12322 12323//12323 -f 12323//12323 12322//12322 12324//12324 -f 12324//12324 12325//12325 12323//12323 -f 12323//12323 12325//12325 12326//12326 -f 12323//12323 12326//12326 12327//12327 -f 12326//12326 12328//12328 12327//12327 -f 12327//12327 12328//12328 12329//12329 -f 12327//12327 12329//12329 12317//12317 -f 12317//12317 12329//12329 12330//12330 -f 12317//12317 12330//12330 12318//12318 -f 12320//12320 12331//12331 12319//12319 -f 12319//12319 12331//12331 12332//12332 -f 12319//12319 12332//12332 12321//12321 -f 12321//12321 12332//12332 12333//12333 -f 12321//12321 12333//12333 12322//12322 -f 12334//12334 12335//12335 12336//12336 -f 12336//12336 12335//12335 12337//12337 -f 12338//12338 12339//12339 12334//12334 -f 12334//12334 12339//12339 12340//12340 -f 12334//12334 12340//12340 12335//12335 -f 12337//12337 12341//12341 12336//12336 -f 12336//12336 12341//12341 12342//12342 -f 12336//12336 12342//12342 12343//12343 -f 12344//12344 12345//12345 12346//12346 -f 12346//12346 12345//12345 12343//12343 -f 12346//12346 12343//12343 12347//12347 -f 12347//12347 12343//12343 12342//12342 -f 12344//12344 12348//12348 12345//12345 -f 12345//12345 12348//12348 12349//12349 -f 12345//12345 12349//12349 12338//12338 -f 12338//12338 12349//12349 12350//12350 -f 12338//12338 12350//12350 12339//12339 -f 10742//10742 10741//10741 12351//12351 -f 12352//12352 12353//12353 12354//12354 -f 12355//12355 12356//12356 12357//12357 -f 12358//12358 12359//12359 12360//12360 -f 12360//12360 12359//12359 12361//12361 -f 12361//12361 12362//12362 12360//12360 -f 12360//12360 12362//12362 12363//12363 -f 12360//12360 12363//12363 12364//12364 -f 12364//12364 12363//12363 12365//12365 -f 12364//12364 12365//12365 12366//12366 -f 12367//12367 12368//12368 12369//12369 -f 12370//12370 12371//12371 12372//12372 -f 12373//12373 12374//12374 12365//12365 -f 12365//12365 12374//12374 12370//12370 -f 12372//12372 12375//12375 12370//12370 -f 12370//12370 12375//12375 12367//12367 -f 12370//12370 12367//12367 12365//12365 -f 12365//12365 12367//12367 12369//12369 -f 12365//12365 12369//12369 12366//12366 -f 12376//12376 12377//12377 12378//12378 -f 12379//12379 12380//12380 12381//12381 -f 12382//12382 12376//12376 12373//12373 -f 12357//12357 12374//12374 12355//12355 -f 12355//12355 12374//12374 12373//12373 -f 12355//12355 12373//12373 12383//12383 -f 12383//12383 12373//12373 12376//12376 -f 12383//12383 12376//12376 12384//12384 -f 12384//12384 12376//12376 12378//12378 -f 12380//12380 12379//12379 12385//12385 -f 12386//12386 12387//12387 12388//12388 -f 12389//12389 12390//12390 12391//12391 -f 12388//12388 12392//12392 12386//12386 -f 12386//12386 12392//12392 12391//12391 -f 12386//12386 12391//12391 12393//12393 -f 12393//12393 12391//12391 12394//12394 -f 12395//12395 12389//12389 12396//12396 -f 12396//12396 12389//12389 12391//12391 -f 12396//12396 12391//12391 12397//12397 -f 12397//12397 12391//12391 12392//12392 -f 12398//12398 12399//12399 12400//12400 -f 12400//12400 12399//12399 12401//12401 -f 12400//12400 12401//12401 12402//12402 -f 12402//12402 12401//12401 12403//12403 -f 12404//12404 12405//12405 12406//12406 -f 12406//12406 12405//12405 12407//12407 -f 12408//12408 12409//12409 12410//12410 -f 12410//12410 12409//12409 12411//12411 -f 12410//12410 12411//12411 12412//12412 -f 12412//12412 12411//12411 12413//12413 -f 12412//12412 12413//12413 12414//12414 -f 12414//12414 12413//12413 12415//12415 -f 12414//12414 12415//12415 12416//12416 -f 12416//12416 12415//12415 12417//12417 -f 12418//12418 12419//12419 12420//12420 -f 12420//12420 12419//12419 12421//12421 -f 12420//12420 12421//12421 12422//12422 -f 12354//12354 12423//12423 12352//12352 -f 12352//12352 12423//12423 12424//12424 -f 12352//12352 12424//12424 12425//12425 -f 12426//12426 12427//12427 12428//12428 -f 12428//12428 12427//12427 12429//12429 -f 12428//12428 12429//12429 12430//12430 -f 12431//12431 12432//12432 12424//12424 -f 12424//12424 12432//12432 12433//12433 -f 12433//12433 12434//12434 12419//12419 -f 12419//12419 12434//12434 12435//12435 -f 12436//12436 12428//12428 12437//12437 -f 12437//12437 12428//12428 12430//12430 -f 12437//12437 12430//12430 12438//12438 -f 12438//12438 12430//12430 12439//12439 -f 12438//12438 12439//12439 12423//12423 -f 12423//12423 12439//12439 12440//12440 -f 12423//12423 12440//12440 12424//12424 -f 12424//12424 12440//12440 12441//12441 -f 12424//12424 12441//12441 12431//12431 -f 12428//12428 12442//12442 12426//12426 -f 12426//12426 12442//12442 12443//12443 -f 12426//12426 12443//12443 12435//12435 -f 12435//12435 12443//12443 12444//12444 -f 12435//12435 12444//12444 12419//12419 -f 12419//12419 12444//12444 12445//12445 -f 12419//12419 12445//12445 12421//12421 -f 12446//12446 12447//12447 12424//12424 -f 12448//12448 12449//12449 12450//12450 -f 12450//12450 12449//12449 12451//12451 -f 12451//12451 12425//12425 12450//12450 -f 12450//12450 12425//12425 12424//12424 -f 12450//12450 12424//12424 12452//12452 -f 12452//12452 12424//12424 12447//12447 -f 12452//12452 12447//12447 12453//12453 -f 12453//12453 12447//12447 12454//12454 -f 12455//12455 12456//12456 12457//12457 -f 12457//12457 12456//12456 12458//12458 -f 12459//12459 12460//12460 12458//12458 -f 12461//12461 12462//12462 12459//12459 -f 12459//12459 12462//12462 12463//12463 -f 12464//12464 12465//12465 12466//12466 -f 12466//12466 12465//12465 12467//12467 -f 12466//12466 12467//12467 12446//12446 -f 12468//12468 12469//12469 12460//12460 -f 12460//12460 12469//12469 12470//12470 -f 12460//12460 12470//12470 12458//12458 -f 12471//12471 12472//12472 12461//12461 -f 12473//12473 12462//12462 12474//12474 -f 12474//12474 12462//12462 12461//12461 -f 12474//12474 12461//12461 12475//12475 -f 12475//12475 12461//12461 12472//12472 -f 12475//12475 12472//12472 12476//12476 -f 12476//12476 12472//12472 12477//12477 -f 12478//12478 12479//12479 12480//12480 -f 10767//10767 12481//12481 10766//10766 -f 10766//10766 12481//12481 12482//12482 -f 10766//10766 12482//12482 10752//10752 -f 12482//12482 12483//12483 10752//10752 -f 10752//10752 12483//12483 12484//12484 -f 10752//10752 12484//12484 10750//10750 -f 10750//10750 12484//12484 12485//12485 -f 10750//10750 12485//12485 10748//10748 -f 10748//10748 12485//12485 12486//12486 -f 10748//10748 12486//12486 12487//12487 -f 12487//12487 12486//12486 12488//12488 -f 12489//12489 12490//12490 12491//12491 -f 12491//12491 12490//12490 12492//12492 -f 12491//12491 12492//12492 12493//12493 -f 12493//12493 12492//12492 12494//12494 -f 12493//12493 12494//12494 10767//10767 -f 10767//10767 12494//12494 12495//12495 -f 10767//10767 12495//12495 12481//12481 -f 12496//12496 12497//12497 12498//12498 -f 12498//12498 12497//12497 12499//12499 -f 12498//12498 12499//12499 12500//12500 -f 12501//12501 12502//12502 12503//12503 -f 12503//12503 12502//12502 12504//12504 -f 12503//12503 12504//12504 10746//10746 -f 10746//10746 12504//12504 12505//12505 -f 12506//12506 10741//10741 12505//12505 -f 12505//12505 10741//10741 10770//10770 -f 12505//12505 10770//10770 10746//10746 -f 12506//12506 12507//12507 10741//10741 -f 10741//10741 12507//12507 12508//12508 -f 10741//10741 12508//12508 12351//12351 -f 12351//12351 12508//12508 12509//12509 -f 12351//12351 12509//12509 12510//12510 -f 12511//12511 10718//10718 12351//12351 -f 12351//12351 10718//10718 10744//10744 -f 12351//12351 10744//10744 10742//10742 -f 12362//12362 12512//12512 12363//12363 -f 12363//12363 12512//12512 12513//12513 -f 12363//12363 12513//12513 12511//12511 -f 12511//12511 12513//12513 12514//12514 -f 12511//12511 12514//12514 10718//10718 -f 12515//12515 12516//12516 12517//12517 -f 12517//12517 12516//12516 12518//12518 -f 12517//12517 12518//12518 12519//12519 -f 12519//12519 12518//12518 12520//12520 -f 12519//12519 12520//12520 12521//12521 -f 12521//12521 12520//12520 12522//12522 -f 12521//12521 12522//12522 12523//12523 -f 12524//12524 12525//12525 12526//12526 -f 12526//12526 12525//12525 12527//12527 -f 12526//12526 12527//12527 12528//12528 -f 12528//12528 12527//12527 12529//12529 -f 12528//12528 12529//12529 12530//12530 -f 12531//12531 12532//12532 12533//12533 -f 12533//12533 12532//12532 12373//12373 -f 12533//12533 12373//12373 12534//12534 -f 12534//12534 12373//12373 12365//12365 -f 12534//12534 12365//12365 12535//12535 -f 12536//12536 12537//12537 12524//12524 -f 12524//12524 12537//12537 12538//12538 -f 12524//12524 12538//12538 12539//12539 -f 12540//12540 12541//12541 12542//12542 -f 12542//12542 12541//12541 12543//12543 -f 12542//12542 12543//12543 12544//12544 -f 12544//12544 12543//12543 12545//12545 -f 12544//12544 12545//12545 12539//12539 -f 12539//12539 12545//12545 12516//12516 -f 12539//12539 12516//12516 12524//12524 -f 12524//12524 12516//12516 12515//12515 -f 12524//12524 12515//12515 12525//12525 -f 12546//12546 12547//12547 12548//12548 -f 12548//12548 12547//12547 12549//12549 -f 12548//12548 12549//12549 12531//12531 -f 12550//12550 12551//12551 12552//12552 -f 12552//12552 12551//12551 12401//12401 -f 12552//12552 12401//12401 12395//12395 -f 12395//12395 12401//12401 12399//12399 -f 12395//12395 12399//12399 12389//12389 -f 12379//12379 12553//12553 12554//12554 -f 12555//12555 12556//12556 12387//12387 -f 12387//12387 12556//12556 12385//12385 -f 12387//12387 12385//12385 12388//12388 -f 12388//12388 12385//12385 12379//12379 -f 12388//12388 12379//12379 12557//12557 -f 12557//12557 12379//12379 12554//12554 -f 12550//12550 12558//12558 12551//12551 -f 12551//12551 12558//12558 12559//12559 -f 12551//12551 12559//12559 12553//12553 -f 12553//12553 12559//12559 12560//12560 -f 12553//12553 12560//12560 12554//12554 -f 12561//12561 12562//12562 12563//12563 -f 12563//12563 12562//12562 12564//12564 -f 12563//12563 12564//12564 12565//12565 -f 12565//12565 12564//12564 12566//12566 -f 12565//12565 12566//12566 12567//12567 -f 12567//12567 12566//12566 12568//12568 -f 12567//12567 12568//12568 12569//12569 -f 12570//12570 12571//12571 12572//12572 -f 12572//12572 12571//12571 12573//12573 -f 12572//12572 12573//12573 12574//12574 -f 12574//12574 12573//12573 12575//12575 -f 12574//12574 12575//12575 12576//12576 -f 12576//12576 12575//12575 12577//12577 -f 12576//12576 12577//12577 12578//12578 -f 12579//12579 12580//12580 12581//12581 -f 12580//12580 12582//12582 12581//12581 -f 12581//12581 12582//12582 12583//12583 -f 12581//12581 12583//12583 12576//12576 -f 12576//12576 12583//12583 12584//12584 -f 12585//12585 12586//12586 12587//12587 -f 12587//12587 12586//12586 12588//12588 -f 12587//12587 12588//12588 12589//12589 -f 12589//12589 12588//12588 12590//12590 -f 12589//12589 12590//12590 12591//12591 -f 12592//12592 12593//12593 12594//12594 -f 12594//12594 12593//12593 12595//12595 -f 12594//12594 12595//12595 12596//12596 -f 12597//12597 12541//12541 12598//12598 -f 12598//12598 12541//12541 12540//12540 -f 12598//12598 12540//12540 12535//12535 -f 12592//12592 12599//12599 12593//12593 -f 12593//12593 12599//12599 12600//12600 -f 12593//12593 12600//12600 12598//12598 -f 12598//12598 12600//12600 12601//12601 -f 12598//12598 12601//12601 12597//12597 -f 12597//12597 12602//12602 12541//12541 -f 12541//12541 12602//12602 12603//12603 -f 12541//12541 12603//12603 12543//12543 -f 12543//12543 12603//12603 12604//12604 -f 12596//12596 12595//12595 12605//12605 -f 12605//12605 12595//12595 12606//12606 -f 12605//12605 12606//12606 12607//12607 -f 12608//12608 12609//12609 12532//12532 -f 12610//12610 12611//12611 12553//12553 -f 12553//12553 12611//12611 12612//12612 -f 12553//12553 12612//12612 12613//12613 -f 12531//12531 12549//12549 12532//12532 -f 12532//12532 12549//12549 12614//12614 -f 12532//12532 12614//12614 12608//12608 -f 12612//12612 12615//12615 12613//12613 -f 12613//12613 12615//12615 12616//12616 -f 12613//12613 12616//12616 12617//12617 -f 12616//12616 12618//12618 12617//12617 -f 12617//12617 12618//12618 12619//12619 -f 12617//12617 12619//12619 12547//12547 -f 12547//12547 12619//12619 12620//12620 -f 12547//12547 12620//12620 12549//12549 -f 12549//12549 12620//12620 12621//12621 -f 12549//12549 12621//12621 12614//12614 -f 12622//12622 12623//12623 12572//12572 -f 12572//12572 12623//12623 12624//12624 -f 12572//12572 12624//12624 12625//12625 -f 12625//12625 12624//12624 12626//12626 -f 12625//12625 12626//12626 12627//12627 -f 12628//12628 12629//12629 12630//12630 -f 12629//12629 12631//12631 12630//12630 -f 12630//12630 12631//12631 12632//12632 -f 12630//12630 12632//12632 12633//12633 -f 12633//12633 12632//12632 12634//12634 -f 12635//12635 12636//12636 12424//12424 -f 12637//12637 12638//12638 12457//12457 -f 12638//12638 12639//12639 12457//12457 -f 12457//12457 12639//12639 12530//12530 -f 12457//12457 12530//12530 12455//12455 -f 12455//12455 12530//12530 12529//12529 -f 12635//12635 12424//12424 12640//12640 -f 12640//12640 12424//12424 12641//12641 -f 12640//12640 12641//12641 12642//12642 -f 12470//12470 12466//12466 12458//12458 -f 12458//12458 12466//12466 12446//12446 -f 12458//12458 12446//12446 12457//12457 -f 12457//12457 12446//12446 12424//12424 -f 12457//12457 12424//12424 12637//12637 -f 12637//12637 12424//12424 12636//12636 -f 12639//12639 12643//12643 12530//12530 -f 12530//12530 12643//12643 12644//12644 -f 12530//12530 12644//12644 12528//12528 -f 12528//12528 12644//12644 12645//12645 -f 12642//12642 12641//12641 12646//12646 -f 12646//12646 12641//12641 12647//12647 -f 12646//12646 12647//12647 12648//12648 -f 12649//12649 12650//12650 12461//12461 -f 12461//12461 12650//12650 12651//12651 -f 12652//12652 12649//12649 12522//12522 -f 12522//12522 12649//12649 12461//12461 -f 12522//12522 12461//12461 12523//12523 -f 12523//12523 12461//12461 12459//12459 -f 12523//12523 12459//12459 12653//12653 -f 12653//12653 12459//12459 12458//12458 -f 12654//12654 12655//12655 12480//12480 -f 12480//12480 12655//12655 12656//12656 -f 12480//12480 12656//12656 12657//12657 -f 12651//12651 12654//12654 12461//12461 -f 12461//12461 12654//12654 12480//12480 -f 12461//12461 12480//12480 12471//12471 -f 12471//12471 12480//12480 12479//12479 -f 12471//12471 12479//12479 12658//12658 -f 12652//12652 12522//12522 12659//12659 -f 12659//12659 12522//12522 12520//12520 -f 12659//12659 12520//12520 12660//12660 -f 12656//12656 12661//12661 12657//12657 -f 12657//12657 12661//12661 12662//12662 -f 12657//12657 12662//12662 12663//12663 -f 12663//12663 12662//12662 12664//12664 -f 12488//12488 12489//12489 12487//12487 -f 12487//12487 12489//12489 12491//12491 -f 12487//12487 12491//12491 12630//12630 -f 12630//12630 12491//12491 12665//12665 -f 12630//12630 12665//12665 12628//12628 -f 12628//12628 12665//12665 12666//12666 -f 10767//10767 10760//10760 12493//12493 -f 12493//12493 10760//10760 12667//12667 -f 12493//12493 12667//12667 12491//12491 -f 12491//12491 12667//12667 12668//12668 -f 12491//12491 12668//12668 12665//12665 -f 12665//12665 12668//12668 12625//12625 -f 12665//12665 12625//12625 12666//12666 -f 12666//12666 12625//12625 12627//12627 -f 10760//10760 12478//12478 12667//12667 -f 12667//12667 12478//12478 12480//12480 -f 12667//12667 12480//12480 12668//12668 -f 12668//12668 12480//12480 12657//12657 -f 12668//12668 12657//12657 12625//12625 -f 12625//12625 12657//12657 12663//12663 -f 12625//12625 12663//12663 12572//12572 -f 12572//12572 12663//12663 12567//12567 -f 12572//12572 12567//12567 12570//12570 -f 12570//12570 12567//12567 12569//12569 -f 12634//12634 12669//12669 12633//12633 -f 12633//12633 12669//12669 12670//12670 -f 12633//12633 12670//12670 12671//12671 -f 12671//12671 12670//12670 12672//12672 -f 12671//12671 12672//12672 12587//12587 -f 12587//12587 12672//12672 12673//12673 -f 12587//12587 12673//12673 12585//12585 -f 12585//12585 12673//12673 12674//12674 -f 12669//12669 12622//12622 12670//12670 -f 12670//12670 12622//12622 12572//12572 -f 12670//12670 12572//12572 12672//12672 -f 12672//12672 12572//12572 12574//12574 -f 12672//12672 12574//12574 12673//12673 -f 12673//12673 12574//12574 12576//12576 -f 12673//12673 12576//12576 12674//12674 -f 12674//12674 12576//12576 12584//12584 -f 12645//12645 12648//12648 12528//12528 -f 12528//12528 12648//12648 12647//12647 -f 12528//12528 12647//12647 12526//12526 -f 12526//12526 12647//12647 12675//12675 -f 12526//12526 12675//12675 12524//12524 -f 12524//12524 12675//12675 12676//12676 -f 12524//12524 12676//12676 12536//12536 -f 12536//12536 12676//12676 12677//12677 -f 12433//12433 12419//12419 12424//12424 -f 12424//12424 12419//12419 12418//12418 -f 12424//12424 12418//12418 12641//12641 -f 12641//12641 12418//12418 12678//12678 -f 12641//12641 12678//12678 12647//12647 -f 12647//12647 12678//12678 12415//12415 -f 12647//12647 12415//12415 12675//12675 -f 12675//12675 12415//12415 12413//12413 -f 12675//12675 12413//12413 12676//12676 -f 12676//12676 12413//12413 12411//12411 -f 12676//12676 12411//12411 12677//12677 -f 12677//12677 12411//12411 12409//12409 -f 12677//12677 12409//12409 12407//12407 -f 12407//12407 12409//12409 12408//12408 -f 12407//12407 12408//12408 12406//12406 -f 12664//12664 12660//12660 12663//12663 -f 12663//12663 12660//12660 12520//12520 -f 12663//12663 12520//12520 12567//12567 -f 12567//12567 12520//12520 12518//12518 -f 12567//12567 12518//12518 12565//12565 -f 12565//12565 12518//12518 12516//12516 -f 12565//12565 12516//12516 12563//12563 -f 12563//12563 12516//12516 12545//12545 -f 12563//12563 12545//12545 12606//12606 -f 12606//12606 12545//12545 12543//12543 -f 12606//12606 12543//12543 12607//12607 -f 12607//12607 12543//12543 12604//12604 -f 12403//12403 12401//12401 12679//12679 -f 12679//12679 12401//12401 12551//12551 -f 12679//12679 12551//12551 12680//12680 -f 12680//12680 12551//12551 12553//12553 -f 12680//12680 12553//12553 12681//12681 -f 12681//12681 12553//12553 12613//12613 -f 12681//12681 12613//12613 12407//12407 -f 12407//12407 12613//12613 12617//12617 -f 12407//12407 12617//12617 12677//12677 -f 12677//12677 12617//12617 12547//12547 -f 12677//12677 12547//12547 12536//12536 -f 12536//12536 12547//12547 12546//12546 -f 12536//12536 12546//12546 12537//12537 -f 12591//12591 12682//12682 12589//12589 -f 12589//12589 12682//12682 12683//12683 -f 12589//12589 12683//12683 12503//12503 -f 12503//12503 12683//12683 12498//12498 -f 12503//12503 12498//12498 12501//12501 -f 12501//12501 12498//12498 12500//12500 -f 12682//12682 12579//12579 12683//12683 -f 12683//12683 12579//12579 12581//12581 -f 12683//12683 12581//12581 12498//12498 -f 12498//12498 12581//12581 12684//12684 -f 12498//12498 12684//12684 12496//12496 -f 12496//12496 12684//12684 12685//12685 -f 12578//12578 12561//12561 12576//12576 -f 12576//12576 12561//12561 12563//12563 -f 12576//12576 12563//12563 12581//12581 -f 12581//12581 12563//12563 12606//12606 -f 12581//12581 12606//12606 12684//12684 -f 12684//12684 12606//12606 12595//12595 -f 12684//12684 12595//12595 12685//12685 -f 12685//12685 12595//12595 12593//12593 -f 12535//12535 12365//12365 12598//12598 -f 12598//12598 12365//12365 12363//12363 -f 12598//12598 12363//12363 12593//12593 -f 12593//12593 12363//12363 12511//12511 -f 12593//12593 12511//12511 12685//12685 -f 12685//12685 12511//12511 12351//12351 -f 12685//12685 12351//12351 12496//12496 -f 12496//12496 12351//12351 12510//12510 -f 12496//12496 12510//12510 12497//12497 -f 12609//12609 12610//12610 12532//12532 -f 12532//12532 12610//12610 12553//12553 -f 12532//12532 12553//12553 12373//12373 -f 12373//12373 12553//12553 12379//12379 -f 12373//12373 12379//12379 12382//12382 -f 12382//12382 12379//12379 12381//12381 -f 12382//12382 12381//12381 12686//12686 -f 12686//12686 12381//12381 12687//12687 -f 12688//12688 12689//12689 12690//12690 -f 12690//12690 12689//12689 12691//12691 -f 12690//12690 12691//12691 12692//12692 -f 12692//12692 12691//12691 12693//12693 -f 12692//12692 12693//12693 12694//12694 -f 12695//12695 12696//12696 12697//12697 -f 12697//12697 12696//12696 12698//12698 -f 12697//12697 12698//12698 12699//12699 -f 12699//12699 12698//12698 12700//12700 -f 12699//12699 12700//12700 12701//12701 -f 12702//12702 12703//12703 12704//12704 -f 12704//12704 12703//12703 12705//12705 -f 12704//12704 12705//12705 12706//12706 -f 12706//12706 12705//12705 12707//12707 -f 12706//12706 12707//12707 12708//12708 -f 12709//12709 12710//12710 12306//12306 -f 12306//12306 12710//12710 12711//12711 -f 12306//12306 12711//12711 12300//12300 -f 12300//12300 12711//12711 12712//12712 -f 12300//12300 12712//12712 12713//12713 -f 12713//12713 12712//12712 12714//12714 -f 12715//12715 12716//12716 12327//12327 -f 12327//12327 12716//12716 12717//12717 -f 12327//12327 12717//12717 12323//12323 -f 12323//12323 12717//12717 12718//12718 -f 12323//12323 12718//12718 12719//12719 -f 12719//12719 12718//12718 12720//12720 -f 12721//12721 12722//12722 12343//12343 -f 12343//12343 12722//12722 12723//12723 -f 12343//12343 12723//12723 12336//12336 -f 12336//12336 12723//12723 12724//12724 -f 12336//12336 12724//12724 12725//12725 -f 12725//12725 12724//12724 12726//12726 -f 12727//12727 12728//12728 12729//12729 -f 12729//12729 12728//12728 12730//12730 -f 12731//12731 12732//12732 12733//12733 -f 12734//12734 12735//12735 12736//12736 -f 12736//12736 12735//12735 12731//12731 -f 12736//12736 12731//12731 12737//12737 -f 12737//12737 12731//12731 12733//12733 -f 12734//12734 12738//12738 12735//12735 -f 12735//12735 12738//12738 12739//12739 -f 12735//12735 12739//12739 12727//12727 -f 12727//12727 12739//12739 12740//12740 -f 12727//12727 12740//12740 12728//12728 -f 12730//12730 12741//12741 12729//12729 -f 12729//12729 12741//12741 12742//12742 -f 12729//12729 12742//12742 12732//12732 -f 12732//12732 12742//12742 12743//12743 -f 12732//12732 12743//12743 12733//12733 -f 12744//12744 12745//12745 12746//12746 -f 12746//12746 12745//12745 12747//12747 -f 12748//12748 12749//12749 12750//12750 -f 12750//12750 12749//12749 12751//12751 -f 12750//12750 12751//12751 12752//12752 -f 12752//12752 12751//12751 12753//12753 -f 12752//12752 12753//12753 12754//12754 -f 12746//12746 12755//12755 12744//12744 -f 12744//12744 12755//12755 12756//12756 -f 12744//12744 12756//12756 12753//12753 -f 12753//12753 12756//12756 12757//12757 -f 12753//12753 12757//12757 12754//12754 -f 12748//12748 12758//12758 12749//12749 -f 12749//12749 12758//12758 12759//12759 -f 12749//12749 12759//12759 12745//12745 -f 12745//12745 12759//12759 12760//12760 -f 12745//12745 12760//12760 12747//12747 -f 12761//12761 12762//12762 12763//12763 -f 12763//12763 12762//12762 12764//12764 -f 12763//12763 12764//12764 12765//12765 -f 12765//12765 12764//12764 12766//12766 -f 12765//12765 12766//12766 12767//12767 -f 12768//12768 12769//12769 12732//12732 -f 12732//12732 12769//12769 12770//12770 -f 12732//12732 12770//12770 12729//12729 -f 12729//12729 12770//12770 12771//12771 -f 12729//12729 12771//12771 12772//12772 -f 12772//12772 12771//12771 12773//12773 -f 12774//12774 12775//12775 12776//12776 -f 12777//12777 12778//12778 12779//12779 -f 12774//12774 12776//12776 12779//12779 -f 12779//12779 12776//12776 12780//12780 -f 12779//12779 12780//12780 12777//12777 -f 12781//12781 12782//12782 12744//12744 -f 12744//12744 12782//12782 12783//12783 -f 12744//12744 12783//12783 12745//12745 -f 12745//12745 12783//12783 12784//12784 -f 12745//12745 12784//12784 12785//12785 -f 12785//12785 12784//12784 12786//12786 -f 12787//12787 12479//12479 12788//12788 -f 12788//12788 12479//12479 12478//12478 -f 12788//12788 12478//12478 10760//10760 -f 10748//10748 12487//12487 12789//12789 -f 12789//12789 12487//12487 12630//12630 -f 12630//12630 12633//12633 12789//12789 -f 12789//12789 12633//12633 12671//12671 -f 12789//12789 12671//12671 12790//12790 -f 12790//12790 12671//12671 12587//12587 -f 12587//12587 12589//12589 12790//12790 -f 12790//12790 12589//12589 12503//12503 -f 12790//12790 12503//12503 10746//10746 -f 12513//12513 12791//12791 12514//12514 -f 12514//12514 12791//12791 12792//12792 -f 12514//12514 12792//12792 10718//10718 -f 12513//12513 12512//12512 12791//12791 -f 12791//12791 12512//12512 12793//12793 -f 12791//12791 12793//12793 12794//12794 -f 12794//12794 12793//12793 12044//12044 -f 12794//12794 12044//12044 12795//12795 -f 12795//12795 12044//12044 11860//11860 -f 12361//12361 12796//12796 12362//12362 -f 12362//12362 12796//12796 12793//12793 -f 12362//12362 12793//12793 12512//12512 -f 12712//12712 12205//12205 12796//12796 -f 12796//12796 12205//12205 11863//11863 -f 12796//12796 11863//11863 11862//11862 -f 12361//12361 12359//12359 12796//12796 -f 12796//12796 12359//12359 12714//12714 -f 12796//12796 12714//12714 12712//12712 -f 12797//12797 11890//11890 11892//11892 -f 12368//12368 12367//12367 12710//12710 -f 12710//12710 12367//12367 12797//12797 -f 12710//12710 12797//12797 12711//12711 -f 12711//12711 12797//12797 11892//11892 -f 12711//12711 11892//11892 12202//12202 -f 12797//12797 12367//12367 12798//12798 -f 12798//12798 12367//12367 12375//12375 -f 12718//12718 12043//12043 12798//12798 -f 12798//12798 12043//12043 12042//12042 -f 12798//12798 12042//12042 12040//12040 -f 12375//12375 12372//12372 12798//12798 -f 12798//12798 12372//12372 12720//12720 -f 12798//12798 12720//12720 12718//12718 -f 12356//12356 12355//12355 12799//12799 -f 12799//12799 12035//12035 12034//12034 -f 12356//12356 12799//12799 12716//12716 -f 12716//12716 12799//12799 12717//12717 -f 12717//12717 12799//12799 12034//12034 -f 12717//12717 12034//12034 12036//12036 -f 12384//12384 12800//12800 12383//12383 -f 12383//12383 12800//12800 12799//12799 -f 12383//12383 12799//12799 12355//12355 -f 12724//12724 12208//12208 12800//12800 -f 12800//12800 12208//12208 11916//11916 -f 12800//12800 11916//11916 11915//11915 -f 12384//12384 12378//12378 12800//12800 -f 12800//12800 12378//12378 12726//12726 -f 12800//12800 12726//12726 12724//12724 -f 12801//12801 11906//11906 11912//11912 -f 12687//12687 12381//12381 12722//12722 -f 12722//12722 12381//12381 12801//12801 -f 12722//12722 12801//12801 12723//12723 -f 12723//12723 12801//12801 11912//11912 -f 12723//12723 11912//11912 12206//12206 -f 12385//12385 12802//12802 12380//12380 -f 12380//12380 12802//12802 12801//12801 -f 12380//12380 12801//12801 12381//12381 -f 12771//12771 12212//12212 12802//12802 -f 12802//12802 12212//12212 12072//12072 -f 12802//12802 12072//12072 12071//12071 -f 12385//12385 12556//12556 12802//12802 -f 12802//12802 12556//12556 12773//12773 -f 12802//12802 12773//12773 12771//12771 -f 12803//12803 12029//12029 12028//12028 -f 12394//12394 12391//12391 12769//12769 -f 12769//12769 12391//12391 12803//12803 -f 12769//12769 12803//12803 12770//12770 -f 12770//12770 12803//12803 12028//12028 -f 12770//12770 12028//12028 12209//12209 -f 12803//12803 12391//12391 12804//12804 -f 12804//12804 12391//12391 12390//12390 -f 12804//12804 12390//12390 12032//12032 -f 12032//12032 12390//12390 12389//12389 -f 12398//12398 12805//12805 12399//12399 -f 12399//12399 12805//12805 12032//12032 -f 12399//12399 12032//12032 12389//12389 -f 12805//12805 12398//12398 12806//12806 -f 12806//12806 12398//12398 12400//12400 -f 12806//12806 12400//12400 12402//12402 -f 12030//12030 12031//12031 12784//12784 -f 12784//12784 12031//12031 12806//12806 -f 12784//12784 12806//12806 12786//12786 -f 12786//12786 12806//12806 12402//12402 -f 12807//12807 12025//12025 12024//12024 -f 12404//12404 12406//12406 12782//12782 -f 12782//12782 12406//12406 12807//12807 -f 12782//12782 12807//12807 12783//12783 -f 12783//12783 12807//12807 12024//12024 -f 12406//12406 12408//12408 12807//12807 -f 12807//12807 12408//12408 12410//12410 -f 12807//12807 12410//12410 12808//12808 -f 12808//12808 12410//12410 12412//12412 -f 12808//12808 12412//12412 12414//12414 -f 12808//12808 12414//12414 12416//12416 -f 12018//12018 12020//12020 12809//12809 -f 12809//12809 12020//12020 12808//12808 -f 12809//12809 12808//12808 12810//12810 -f 12810//12810 12808//12808 12416//12416 -f 12811//12811 12812//12812 12813//12813 -f 12813//12813 12812//12812 12814//12814 -f 12813//12813 12814//12814 12815//12815 -f 12815//12815 12814//12814 12809//12809 -f 12815//12815 12809//12809 12816//12816 -f 12816//12816 12809//12809 12810//12810 -f 12817//12817 12015//12015 12014//12014 -f 12422//12422 12421//12421 12812//12812 -f 12812//12812 12421//12421 12817//12817 -f 12812//12812 12817//12817 12814//12814 -f 12814//12814 12817//12817 12014//12014 -f 12817//12817 12421//12421 12818//12818 -f 12818//12818 12421//12421 12445//12445 -f 12818//12818 12445//12445 12017//12017 -f 12017//12017 12445//12445 12444//12444 -f 12017//12017 12444//12444 12443//12443 -f 12017//12017 12443//12443 12819//12819 -f 12819//12819 12443//12443 12442//12442 -f 12819//12819 12442//12442 12820//12820 -f 12820//12820 12442//12442 12428//12428 -f 12820//12820 12428//12428 12436//12436 -f 11866//11866 11865//11865 12821//12821 -f 12821//12821 11865//11865 12820//12820 -f 12821//12821 12820//12820 12822//12822 -f 12822//12822 12820//12820 12436//12436 -f 12823//12823 12824//12824 12825//12825 -f 12825//12825 12824//12824 12826//12826 -f 12825//12825 12826//12826 12827//12827 -f 12827//12827 12826//12826 12821//12821 -f 12827//12827 12821//12821 12828//12828 -f 12828//12828 12821//12821 12822//12822 -f 12829//12829 11967//11967 12285//12285 -f 12353//12353 12352//12352 12824//12824 -f 12824//12824 12352//12352 12829//12829 -f 12824//12824 12829//12829 12826//12826 -f 12826//12826 12829//12829 12285//12285 -f 12451//12451 12830//12830 12425//12425 -f 12425//12425 12830//12830 12829//12829 -f 12425//12425 12829//12829 12352//12352 -f 12830//12830 12451//12451 12449//12449 -f 11980//11980 11969//11969 12831//12831 -f 12831//12831 11969//11969 12830//12830 -f 12831//12831 12830//12830 12832//12832 -f 12832//12832 12830//12830 12449//12449 -f 12833//12833 12834//12834 12835//12835 -f 12835//12835 12834//12834 12836//12836 -f 12835//12835 12836//12836 12837//12837 -f 12837//12837 12836//12836 12831//12831 -f 12837//12837 12831//12831 12838//12838 -f 12838//12838 12831//12831 12832//12832 -f 12839//12839 11974//11974 11972//11972 -f 12454//12454 12447//12447 12834//12834 -f 12834//12834 12447//12447 12839//12839 -f 12834//12834 12839//12839 12836//12836 -f 12836//12836 12839//12839 11972//11972 -f 12467//12467 12840//12840 12446//12446 -f 12446//12446 12840//12840 12839//12839 -f 12446//12446 12839//12839 12447//12447 -f 12840//12840 12467//12467 12465//12465 -f 12010//12010 12011//12011 12841//12841 -f 12841//12841 12011//12011 12840//12840 -f 12841//12841 12840//12840 12842//12842 -f 12842//12842 12840//12840 12465//12465 -f 12843//12843 12844//12844 12845//12845 -f 12845//12845 12844//12844 12846//12846 -f 12845//12845 12846//12846 12847//12847 -f 12847//12847 12846//12846 12841//12841 -f 12847//12847 12841//12841 12848//12848 -f 12848//12848 12841//12841 12842//12842 -f 11947//11947 11945//11945 12849//12849 -f 12849//12849 11945//11945 12846//12846 -f 12846//12846 12844//12844 12849//12849 -f 12849//12849 12844//12844 12468//12468 -f 12849//12849 12468//12468 12460//12460 -f 12849//12849 12460//12460 12850//12850 -f 12850//12850 12460//12460 12459//12459 -f 12850//12850 12459//12459 12463//12463 -f 11963//11963 11949//11949 12851//12851 -f 12851//12851 11949//11949 12850//12850 -f 12851//12851 12850//12850 12852//12852 -f 12852//12852 12850//12850 12463//12463 -f 12853//12853 12854//12854 12855//12855 -f 12855//12855 12854//12854 12856//12856 -f 12855//12855 12856//12856 12857//12857 -f 12857//12857 12856//12856 12851//12851 -f 12857//12857 12851//12851 12858//12858 -f 12858//12858 12851//12851 12852//12852 -f 12859//12859 12067//12067 12066//12066 -f 12477//12477 12472//12472 12854//12854 -f 12854//12854 12472//12472 12859//12859 -f 12854//12854 12859//12859 12856//12856 -f 12856//12856 12859//12859 12066//12066 -f 12658//12658 12860//12860 12471//12471 -f 12471//12471 12860//12860 12859//12859 -f 12471//12471 12859//12859 12472//12472 -f 12861//12861 12069//12069 12068//12068 -f 12658//12658 12479//12479 12860//12860 -f 12860//12860 12479//12479 12787//12787 -f 12860//12860 12787//12787 12068//12068 -f 12068//12068 12787//12787 12862//12862 -f 12068//12068 12862//12862 12861//12861 -f 11989//11989 12863//12863 12006//12006 -f 12006//12006 12863//12863 12864//12864 -f 12006//12006 12864//12864 12007//12007 -f 12007//12007 12864//12864 12009//12009 -f 12865//12865 11995//11995 12866//12866 -f 12866//12866 11995//11995 11994//11994 -f 12866//12866 11994//11994 11993//11993 -f 12867//12867 12868//12868 11997//11997 -f 11997//11997 11996//11996 12867//12867 -f 12867//12867 11996//11996 12250//12250 -f 12867//12867 12250//12250 12005//12005 -f 12104//12104 12869//12869 11999//11999 -f 11999//11999 12869//12869 12870//12870 -f 11999//11999 12870//12870 12000//12000 -f 12871//12871 12872//12872 12873//12873 -f 12873//12873 12872//12872 12874//12874 -f 12079//12079 12875//12875 12075//12075 -f 12075//12075 12875//12875 12876//12876 -f 12075//12075 12876//12876 12076//12076 -f 12877//12877 12092//12092 12091//12091 -f 12877//12877 12091//12091 12878//12878 -f 12878//12878 12091//12091 12097//12097 -f 12878//12878 12097//12097 12096//12096 -f 12879//12879 12093//12093 12880//12880 -f 12880//12880 12093//12093 12099//12099 -f 12880//12880 12099//12099 12098//12098 -f 12881//12881 12110//12110 12108//12108 -f 12881//12881 12108//12108 12882//12882 -f 12882//12882 12108//12108 12106//12106 -f 12882//12882 12106//12106 12105//12105 -f 12883//12883 12884//12884 12885//12885 -f 12885//12885 12884//12884 12886//12886 -f 12887//12887 12888//12888 12889//12889 -f 12889//12889 12888//12888 12815//12815 -f 12889//12889 12815//12815 12417//12417 -f 12417//12417 12815//12815 12816//12816 -f 12813//12813 12815//12815 12890//12890 -f 12890//12890 12815//12815 12891//12891 -f 12892//12892 12893//12893 12894//12894 -f 12894//12894 12893//12893 12813//12813 -f 12894//12894 12813//12813 12895//12895 -f 12895//12895 12813//12813 12890//12890 -f 12892//12892 12896//12896 12893//12893 -f 12893//12893 12896//12896 12897//12897 -f 12893//12893 12897//12897 12898//12898 -f 12898//12898 12897//12897 12899//12899 -f 12898//12898 12899//12899 12888//12888 -f 12888//12888 12899//12899 12900//12900 -f 12900//12900 12901//12901 12888//12888 -f 12888//12888 12901//12901 12902//12902 -f 12888//12888 12902//12902 12815//12815 -f 12815//12815 12902//12902 12903//12903 -f 12815//12815 12903//12903 12891//12891 -f 12420//12420 12811//12811 12904//12904 -f 12904//12904 12811//12811 12813//12813 -f 12904//12904 12813//12813 12905//12905 -f 12905//12905 12813//12813 12893//12893 -f 12887//12887 12906//12906 12888//12888 -f 12888//12888 12906//12906 12898//12898 -f 12906//12906 12905//12905 12898//12898 -f 12898//12898 12905//12905 12893//12893 -f 12904//12904 12905//12905 12907//12907 -f 12907//12907 12905//12905 12906//12906 -f 12907//12907 12906//12906 12908//12908 -f 12908//12908 12906//12906 12887//12887 -f 12908//12908 12887//12887 12889//12889 -f 12417//12417 12415//12415 12889//12889 -f 12889//12889 12415//12415 12908//12908 -f 12418//12418 12907//12907 12678//12678 -f 12678//12678 12907//12907 12908//12908 -f 12678//12678 12908//12908 12415//12415 -f 12418//12418 12420//12420 12907//12907 -f 12907//12907 12420//12420 12904//12904 -f 12909//12909 12910//12910 12911//12911 -f 12911//12911 12910//12910 12827//12827 -f 12911//12911 12827//12827 12437//12437 -f 12437//12437 12827//12827 12828//12828 -f 12912//12912 12825//12825 12913//12913 -f 12913//12913 12914//12914 12912//12912 -f 12912//12912 12914//12914 12915//12915 -f 12912//12912 12915//12915 12916//12916 -f 12916//12916 12915//12915 12917//12917 -f 12910//12910 12918//12918 12827//12827 -f 12827//12827 12918//12918 12919//12919 -f 12919//12919 12920//12920 12827//12827 -f 12827//12827 12920//12920 12921//12921 -f 12827//12827 12921//12921 12825//12825 -f 12825//12825 12921//12921 12922//12922 -f 12825//12825 12922//12922 12913//12913 -f 12917//12917 12923//12923 12916//12916 -f 12916//12916 12923//12923 12924//12924 -f 12916//12916 12924//12924 12910//12910 -f 12910//12910 12924//12924 12925//12925 -f 12910//12910 12925//12925 12918//12918 -f 12354//12354 12823//12823 12926//12926 -f 12926//12926 12823//12823 12825//12825 -f 12926//12926 12825//12825 12927//12927 -f 12927//12927 12825//12825 12912//12912 -f 12909//12909 12928//12928 12910//12910 -f 12910//12910 12928//12928 12916//12916 -f 12928//12928 12927//12927 12916//12916 -f 12916//12916 12927//12927 12912//12912 -f 12929//12929 12926//12926 12927//12927 -f 12909//12909 12911//12911 12930//12930 -f 12929//12929 12927//12927 12930//12930 -f 12930//12930 12927//12927 12928//12928 -f 12930//12930 12928//12928 12909//12909 -f 12438//12438 12930//12930 12437//12437 -f 12437//12437 12930//12930 12911//12911 -f 12423//12423 12929//12929 12438//12438 -f 12438//12438 12929//12929 12930//12930 -f 12354//12354 12926//12926 12423//12423 -f 12423//12423 12926//12926 12929//12929 -f 12890//12890 12261//12261 12895//12895 -f 12895//12895 12261//12261 12263//12263 -f 12895//12895 12263//12263 12894//12894 -f 12894//12894 12263//12263 12264//12264 -f 12894//12894 12264//12264 12892//12892 -f 12892//12892 12264//12264 12269//12269 -f 12892//12892 12269//12269 12896//12896 -f 12896//12896 12269//12269 12268//12268 -f 12896//12896 12268//12268 12897//12897 -f 12897//12897 12268//12268 12272//12272 -f 12897//12897 12272//12272 12899//12899 -f 12899//12899 12272//12272 12271//12271 -f 12899//12899 12271//12271 12900//12900 -f 12900//12900 12271//12271 12270//12270 -f 12900//12900 12270//12270 12901//12901 -f 12901//12901 12270//12270 12265//12265 -f 12901//12901 12265//12265 12902//12902 -f 12902//12902 12265//12265 12266//12266 -f 12902//12902 12266//12266 12903//12903 -f 12903//12903 12266//12266 12267//12267 -f 12903//12903 12267//12267 12891//12891 -f 12891//12891 12267//12267 12260//12260 -f 12891//12891 12260//12260 12890//12890 -f 12890//12890 12260//12260 12261//12261 -f 12918//12918 12294//12294 12919//12919 -f 12919//12919 12294//12294 12293//12293 -f 12919//12919 12293//12293 12920//12920 -f 12920//12920 12293//12293 12292//12292 -f 12920//12920 12292//12292 12921//12921 -f 12921//12921 12292//12292 12290//12290 -f 12921//12921 12290//12290 12922//12922 -f 12922//12922 12290//12290 12289//12289 -f 12922//12922 12289//12289 12913//12913 -f 12913//12913 12289//12289 12284//12284 -f 12913//12913 12284//12284 12914//12914 -f 12914//12914 12284//12284 12286//12286 -f 12914//12914 12286//12286 12915//12915 -f 12915//12915 12286//12286 12287//12287 -f 12915//12915 12287//12287 12917//12917 -f 12917//12917 12287//12287 12288//12288 -f 12917//12917 12288//12288 12923//12923 -f 12923//12923 12288//12288 12298//12298 -f 12923//12923 12298//12298 12924//12924 -f 12924//12924 12298//12298 12297//12297 -f 12924//12924 12297//12297 12925//12925 -f 12925//12925 12297//12297 12295//12295 -f 12925//12925 12295//12295 12918//12918 -f 12918//12918 12295//12295 12294//12294 -f 12931//12931 12932//12932 12933//12933 -f 12933//12933 12932//12932 12837//12837 -f 12933//12933 12837//12837 12448//12448 -f 12448//12448 12837//12837 12838//12838 -f 12934//12934 12835//12835 12935//12935 -f 12935//12935 12936//12936 12934//12934 -f 12934//12934 12936//12936 12937//12937 -f 12934//12934 12937//12937 12938//12938 -f 12938//12938 12937//12937 12939//12939 -f 12940//12940 12837//12837 12941//12941 -f 12941//12941 12837//12837 12932//12932 -f 12939//12939 12942//12942 12938//12938 -f 12938//12938 12942//12942 12943//12943 -f 12938//12938 12943//12943 12932//12932 -f 12932//12932 12943//12943 12944//12944 -f 12932//12932 12944//12944 12941//12941 -f 12940//12940 12945//12945 12837//12837 -f 12837//12837 12945//12945 12946//12946 -f 12837//12837 12946//12946 12835//12835 -f 12835//12835 12946//12946 12947//12947 -f 12835//12835 12947//12947 12935//12935 -f 12453//12453 12833//12833 12948//12948 -f 12948//12948 12833//12833 12835//12835 -f 12948//12948 12835//12835 12949//12949 -f 12949//12949 12835//12835 12934//12934 -f 12950//12950 12951//12951 12952//12952 -f 12952//12952 12951//12951 12847//12847 -f 12952//12952 12847//12847 12464//12464 -f 12464//12464 12847//12847 12848//12848 -f 12953//12953 12847//12847 12954//12954 -f 12954//12954 12847//12847 12951//12951 -f 12953//12953 12955//12955 12847//12847 -f 12847//12847 12955//12955 12956//12956 -f 12847//12847 12956//12956 12845//12845 -f 12957//12957 12958//12958 12959//12959 -f 12959//12959 12958//12958 12960//12960 -f 12957//12957 12961//12961 12958//12958 -f 12958//12958 12961//12961 12962//12962 -f 12958//12958 12962//12962 12951//12951 -f 12951//12951 12962//12962 12963//12963 -f 12951//12951 12963//12963 12954//12954 -f 12956//12956 12964//12964 12845//12845 -f 12845//12845 12964//12964 12965//12965 -f 12845//12845 12965//12965 12960//12960 -f 12960//12960 12965//12965 12966//12966 -f 12960//12960 12966//12966 12959//12959 -f 12469//12469 12843//12843 12967//12967 -f 12967//12967 12843//12843 12845//12845 -f 12967//12967 12845//12845 12968//12968 -f 12968//12968 12845//12845 12960//12960 -f 12969//12969 12970//12970 12971//12971 -f 12971//12971 12970//12970 12857//12857 -f 12971//12971 12857//12857 12473//12473 -f 12473//12473 12857//12857 12858//12858 -f 12972//12972 12973//12973 12974//12974 -f 12974//12974 12973//12973 12970//12970 -f 12975//12975 12855//12855 12976//12976 -f 12976//12976 12977//12977 12975//12975 -f 12975//12975 12977//12977 12978//12978 -f 12975//12975 12978//12978 12974//12974 -f 12974//12974 12978//12978 12979//12979 -f 12974//12974 12979//12979 12972//12972 -f 12973//12973 12980//12980 12970//12970 -f 12970//12970 12980//12980 12981//12981 -f 12970//12970 12981//12981 12857//12857 -f 12857//12857 12981//12981 12982//12982 -f 12982//12982 12983//12983 12857//12857 -f 12857//12857 12983//12983 12984//12984 -f 12857//12857 12984//12984 12855//12855 -f 12855//12855 12984//12984 12985//12985 -f 12855//12855 12985//12985 12976//12976 -f 12476//12476 12853//12853 12986//12986 -f 12986//12986 12853//12853 12855//12855 -f 12986//12986 12855//12855 12987//12987 -f 12987//12987 12855//12855 12975//12975 -f 12931//12931 12988//12988 12932//12932 -f 12932//12932 12988//12988 12938//12938 -f 12988//12988 12949//12949 12938//12938 -f 12938//12938 12949//12949 12934//12934 -f 12989//12989 12948//12948 12949//12949 -f 12931//12931 12933//12933 12990//12990 -f 12989//12989 12949//12949 12990//12990 -f 12990//12990 12949//12949 12988//12988 -f 12990//12990 12988//12988 12931//12931 -f 12950//12950 12991//12991 12951//12951 -f 12951//12951 12991//12991 12958//12958 -f 12991//12991 12968//12968 12958//12958 -f 12958//12958 12968//12968 12960//12960 -f 12992//12992 12967//12967 12968//12968 -f 12950//12950 12952//12952 12993//12993 -f 12992//12992 12968//12968 12993//12993 -f 12993//12993 12968//12968 12991//12991 -f 12993//12993 12991//12991 12950//12950 -f 12969//12969 12994//12994 12970//12970 -f 12970//12970 12994//12994 12974//12974 -f 12994//12994 12987//12987 12974//12974 -f 12974//12974 12987//12987 12975//12975 -f 12995//12995 12986//12986 12987//12987 -f 12969//12969 12971//12971 12996//12996 -f 12995//12995 12987//12987 12996//12996 -f 12996//12996 12987//12987 12994//12994 -f 12996//12996 12994//12994 12969//12969 -f 12450//12450 12990//12990 12448//12448 -f 12448//12448 12990//12990 12933//12933 -f 12452//12452 12989//12989 12450//12450 -f 12450//12450 12989//12989 12990//12990 -f 12453//12453 12948//12948 12452//12452 -f 12452//12452 12948//12948 12989//12989 -f 12466//12466 12993//12993 12464//12464 -f 12464//12464 12993//12993 12952//12952 -f 12470//12470 12992//12992 12466//12466 -f 12466//12466 12992//12992 12993//12993 -f 12469//12469 12967//12967 12470//12470 -f 12470//12470 12967//12967 12992//12992 -f 12474//12474 12996//12996 12473//12473 -f 12473//12473 12996//12996 12971//12971 -f 12475//12475 12995//12995 12474//12474 -f 12474//12474 12995//12995 12996//12996 -f 12476//12476 12986//12986 12475//12475 -f 12475//12475 12986//12986 12995//12995 -f 12941//12941 11982//11982 12940//12940 -f 12940//12940 11982//11982 11981//11981 -f 12940//12940 11981//11981 12945//12945 -f 12945//12945 11981//11981 11979//11979 -f 12945//12945 11979//11979 12946//12946 -f 12946//12946 11979//11979 11977//11977 -f 12946//12946 11977//11977 12947//12947 -f 12947//12947 11977//11977 11976//11976 -f 12947//12947 11976//11976 12935//12935 -f 12935//12935 11976//11976 11971//11971 -f 12935//12935 11971//11971 12936//12936 -f 12936//12936 11971//11971 11973//11973 -f 12936//12936 11973//11973 12937//12937 -f 12937//12937 11973//11973 11975//11975 -f 12937//12937 11975//11975 12939//12939 -f 12939//12939 11975//11975 11983//11983 -f 12939//12939 11983//11983 12942//12942 -f 12942//12942 11983//11983 11985//11985 -f 12942//12942 11985//11985 12943//12943 -f 12943//12943 11985//11985 11986//11986 -f 12943//12943 11986//11986 12944//12944 -f 12944//12944 11986//11986 11970//11970 -f 12944//12944 11970//11970 12941//12941 -f 12941//12941 11970//11970 11982//11982 -f 12954//12954 11854//11854 12953//12953 -f 12953//12953 11854//11854 11853//11853 -f 12953//12953 11853//11853 12955//12955 -f 12955//12955 11853//11853 12283//12283 -f 12955//12955 12283//12283 12956//12956 -f 12956//12956 12283//12283 12282//12282 -f 12956//12956 12282//12282 12964//12964 -f 12964//12964 12282//12282 12281//12281 -f 12964//12964 12281//12281 12965//12965 -f 12965//12965 12281//12281 12280//12280 -f 12965//12965 12280//12280 12966//12966 -f 12966//12966 12280//12280 12279//12279 -f 12966//12966 12279//12279 12959//12959 -f 12959//12959 12279//12279 12278//12278 -f 12959//12959 12278//12278 12957//12957 -f 12957//12957 12278//12278 12275//12275 -f 12957//12957 12275//12275 12961//12961 -f 12961//12961 12275//12275 12274//12274 -f 12961//12961 12274//12274 12962//12962 -f 12962//12962 12274//12274 12277//12277 -f 12962//12962 12277//12277 12963//12963 -f 12963//12963 12277//12277 12276//12276 -f 12963//12963 12276//12276 12954//12954 -f 12954//12954 12276//12276 11854//11854 -f 12981//12981 11965//11965 12982//12982 -f 12982//12982 11965//11965 11964//11964 -f 12982//12982 11964//11964 12983//12983 -f 12983//12983 11964//11964 11962//11962 -f 12983//12983 11962//11962 12984//12984 -f 12984//12984 11962//11962 11960//11960 -f 12984//12984 11960//11960 12985//12985 -f 12985//12985 11960//11960 11959//11959 -f 12985//12985 11959//11959 12976//12976 -f 12976//12976 11959//11959 11956//11956 -f 12976//12976 11956//11956 12977//12977 -f 12977//12977 11956//11956 11955//11955 -f 12977//12977 11955//11955 12978//12978 -f 12978//12978 11955//11955 11958//11958 -f 12978//12978 11958//11958 12979//12979 -f 12979//12979 11958//11958 11957//11957 -f 12979//12979 11957//11957 12972//12972 -f 12972//12972 11957//11957 11952//11952 -f 12972//12972 11952//11952 12973//12973 -f 12973//12973 11952//11952 11951//11951 -f 12973//12973 11951//11951 12980//12980 -f 12980//12980 11951//11951 11950//11950 -f 12980//12980 11950//11950 12981//12981 -f 12981//12981 11950//11950 11965//11965 -f 12777//12777 12749//12749 12778//12778 -f 12778//12778 12749//12749 12745//12745 -f 12778//12778 12745//12745 12679//12679 -f 12679//12679 12745//12745 12785//12785 -f 12405//12405 12781//12781 12775//12775 -f 12775//12775 12781//12781 12744//12744 -f 12775//12775 12744//12744 12776//12776 -f 12776//12776 12744//12744 12753//12753 -f 12777//12777 12780//12780 12749//12749 -f 12749//12749 12780//12780 12751//12751 -f 12780//12780 12776//12776 12751//12751 -f 12751//12751 12776//12776 12753//12753 -f 12680//12680 12779//12779 12679//12679 -f 12679//12679 12779//12779 12778//12778 -f 12407//12407 12774//12774 12681//12681 -f 12681//12681 12774//12774 12779//12779 -f 12681//12681 12779//12779 12680//12680 -f 12405//12405 12775//12775 12407//12407 -f 12407//12407 12775//12775 12774//12774 -f 12766//12766 12727//12727 12767//12767 -f 12767//12767 12727//12727 12729//12729 -f 12767//12767 12729//12729 12555//12555 -f 12555//12555 12729//12729 12772//12772 -f 12393//12393 12768//12768 12761//12761 -f 12761//12761 12768//12768 12732//12732 -f 12761//12761 12732//12732 12762//12762 -f 12762//12762 12732//12732 12731//12731 -f 12766//12766 12764//12764 12727//12727 -f 12727//12727 12764//12764 12735//12735 -f 12764//12764 12762//12762 12735//12735 -f 12735//12735 12762//12762 12731//12731 -f 12555//12555 12387//12387 12767//12767 -f 12767//12767 12387//12387 12765//12765 -f 12387//12387 12386//12386 12765//12765 -f 12765//12765 12386//12386 12763//12763 -f 12386//12386 12393//12393 12763//12763 -f 12763//12763 12393//12393 12761//12761 -f 12746//12746 11934//11934 12755//12755 -f 12755//12755 11934//11934 11933//11933 -f 12755//12755 11933//11933 12756//12756 -f 12756//12756 11933//11933 11932//11932 -f 12756//12756 11932//11932 12757//12757 -f 12757//12757 11932//11932 11930//11930 -f 12757//12757 11930//11930 12754//12754 -f 12754//12754 11930//11930 11929//11929 -f 12754//12754 11929//11929 12752//12752 -f 12752//12752 11929//11929 11927//11927 -f 12752//12752 11927//11927 12750//12750 -f 12750//12750 11927//11927 11926//11926 -f 12750//12750 11926//11926 12748//12748 -f 12748//12748 11926//11926 11943//11943 -f 12748//12748 11943//11943 12758//12758 -f 12758//12758 11943//11943 11941//11941 -f 12758//12758 11941//11941 12759//12759 -f 12759//12759 11941//11941 11939//11939 -f 12759//12759 11939//11939 12760//12760 -f 12760//12760 11939//11939 11937//11937 -f 12760//12760 11937//11937 12747//12747 -f 12747//12747 11937//11937 11936//11936 -f 12747//12747 11936//11936 12746//12746 -f 12746//12746 11936//11936 11934//11934 -f 12737//12737 12084//12084 12736//12736 -f 12736//12736 12084//12084 12083//12083 -f 12736//12736 12083//12083 12734//12734 -f 12734//12734 12083//12083 12082//12082 -f 12734//12734 12082//12082 12738//12738 -f 12738//12738 12082//12082 12080//12080 -f 12738//12738 12080//12080 12739//12739 -f 12739//12739 12080//12080 12078//12078 -f 12739//12739 12078//12078 12740//12740 -f 12740//12740 12078//12078 12077//12077 -f 12740//12740 12077//12077 12728//12728 -f 12728//12728 12077//12077 12074//12074 -f 12728//12728 12074//12074 12730//12730 -f 12730//12730 12074//12074 12073//12073 -f 12730//12730 12073//12073 12741//12741 -f 12741//12741 12073//12073 12089//12089 -f 12741//12741 12089//12089 12742//12742 -f 12742//12742 12089//12089 12088//12088 -f 12742//12742 12088//12088 12743//12743 -f 12743//12743 12088//12088 12086//12086 -f 12743//12743 12086//12086 12733//12733 -f 12733//12733 12086//12086 12085//12085 -f 12733//12733 12085//12085 12737//12737 -f 12737//12737 12085//12085 12084//12084 -f 12707//12707 12334//12334 12708//12708 -f 12708//12708 12334//12334 12336//12336 -f 12708//12708 12336//12336 12377//12377 -f 12377//12377 12336//12336 12725//12725 -f 12686//12686 12721//12721 12702//12702 -f 12702//12702 12721//12721 12343//12343 -f 12702//12702 12343//12343 12703//12703 -f 12703//12703 12343//12343 12345//12345 -f 12700//12700 12321//12321 12701//12701 -f 12701//12701 12321//12321 12323//12323 -f 12701//12701 12323//12323 12371//12371 -f 12371//12371 12323//12323 12719//12719 -f 12357//12357 12715//12715 12695//12695 -f 12695//12695 12715//12715 12327//12327 -f 12695//12695 12327//12327 12696//12696 -f 12696//12696 12327//12327 12317//12317 -f 12693//12693 12310//12310 12694//12694 -f 12694//12694 12310//12310 12300//12300 -f 12694//12694 12300//12300 12358//12358 -f 12358//12358 12300//12300 12713//12713 -f 12366//12366 12709//12709 12688//12688 -f 12688//12688 12709//12709 12306//12306 -f 12688//12688 12306//12306 12689//12689 -f 12689//12689 12306//12306 12309//12309 -f 12707//12707 12705//12705 12334//12334 -f 12334//12334 12705//12705 12338//12338 -f 12705//12705 12703//12703 12338//12338 -f 12338//12338 12703//12703 12345//12345 -f 12700//12700 12698//12698 12321//12321 -f 12321//12321 12698//12698 12319//12319 -f 12698//12698 12696//12696 12319//12319 -f 12319//12319 12696//12696 12317//12317 -f 12693//12693 12691//12691 12310//12310 -f 12310//12310 12691//12691 12303//12303 -f 12691//12691 12689//12689 12303//12303 -f 12303//12303 12689//12689 12309//12309 -f 12377//12377 12376//12376 12708//12708 -f 12708//12708 12376//12376 12706//12706 -f 12376//12376 12382//12382 12706//12706 -f 12706//12706 12382//12382 12704//12704 -f 12382//12382 12686//12686 12704//12704 -f 12704//12704 12686//12686 12702//12702 -f 12371//12371 12370//12370 12701//12701 -f 12701//12701 12370//12370 12699//12699 -f 12370//12370 12374//12374 12699//12699 -f 12699//12699 12374//12374 12697//12697 -f 12374//12374 12357//12357 12697//12697 -f 12697//12697 12357//12357 12695//12695 -f 12358//12358 12360//12360 12694//12694 -f 12694//12694 12360//12360 12692//12692 -f 12360//12360 12364//12364 12692//12692 -f 12692//12692 12364//12364 12690//12690 -f 12364//12364 12366//12366 12690//12690 -f 12690//12690 12366//12366 12688//12688 -f 12344//12344 11911//11911 12348//12348 -f 12348//12348 11911//11911 11910//11910 -f 12348//12348 11910//11910 12349//12349 -f 12349//12349 11910//11910 11905//11905 -f 12349//12349 11905//11905 12350//12350 -f 12350//12350 11905//11905 11922//11922 -f 12350//12350 11922//11922 12339//12339 -f 12339//12339 11922//11922 11921//11921 -f 12339//12339 11921//11921 12340//12340 -f 12340//12340 11921//11921 11919//11919 -f 12340//12340 11919//11919 12335//12335 -f 12335//12335 11919//11919 11918//11918 -f 12335//12335 11918//11918 12337//12337 -f 12337//12337 11918//11918 11917//11917 -f 12337//12337 11917//11917 12341//12341 -f 12341//12341 11917//11917 11925//11925 -f 12341//12341 11925//11925 12342//12342 -f 12342//12342 11925//11925 11924//11924 -f 12342//12342 11924//11924 12347//12347 -f 12347//12347 11924//11924 11923//11923 -f 12347//12347 11923//11923 12346//12346 -f 12346//12346 11923//11923 11913//11913 -f 12346//12346 11913//11913 12344//12344 -f 12344//12344 11913//11913 11911//11911 -f 12330//12330 12215//12215 12318//12318 -f 12318//12318 12215//12215 12214//12214 -f 12318//12318 12214//12214 12320//12320 -f 12320//12320 12214//12214 12225//12225 -f 12320//12320 12225//12225 12331//12331 -f 12331//12331 12225//12225 12224//12224 -f 12331//12331 12224//12224 12332//12332 -f 12332//12332 12224//12224 12223//12223 -f 12332//12332 12223//12223 12333//12333 -f 12333//12333 12223//12223 12220//12220 -f 12333//12333 12220//12220 12322//12322 -f 12322//12322 12220//12220 12221//12221 -f 12322//12322 12221//12221 12324//12324 -f 12324//12324 12221//12221 12222//12222 -f 12324//12324 12222//12222 12325//12325 -f 12325//12325 12222//12222 12219//12219 -f 12325//12325 12219//12219 12326//12326 -f 12326//12326 12219//12219 12218//12218 -f 12326//12326 12218//12218 12328//12328 -f 12328//12328 12218//12218 12217//12217 -f 12328//12328 12217//12217 12329//12329 -f 12329//12329 12217//12217 12216//12216 -f 12329//12329 12216//12216 12330//12330 -f 12330//12330 12216//12216 12215//12215 -f 12314//12314 11891//11891 12315//12315 -f 12315//12315 11891//11891 11889//11889 -f 12315//12315 11889//11889 12316//12316 -f 12316//12316 11889//11889 11888//11888 -f 12316//12316 11888//11888 12304//12304 -f 12304//12304 11888//11888 11899//11899 -f 12304//12304 11899//11899 12305//12305 -f 12305//12305 11899//11899 11901//11901 -f 12305//12305 11901//11901 12311//12311 -f 12311//12311 11901//11901 11903//11903 -f 12311//12311 11903//11903 12312//12312 -f 12312//12312 11903//11903 11904//11904 -f 12312//12312 11904//11904 12313//12313 -f 12313//12313 11904//11904 11898//11898 -f 12313//12313 11898//11898 12301//12301 -f 12301//12301 11898//11898 11897//11897 -f 12301//12301 11897//11897 12302//12302 -f 12302//12302 11897//11897 11896//11896 -f 12302//12302 11896//11896 12307//12307 -f 12307//12307 11896//11896 11895//11895 -f 12307//12307 11895//11895 12308//12308 -f 12308//12308 11895//11895 11893//11893 -f 12308//12308 11893//11893 12314//12314 -f 12314//12314 11893//11893 11891//11891 -f 12790//12790 10746//10746 12997//12997 -f 12997//12997 10746//10746 10770//10770 -f 12997//12997 10770//10770 12998//12998 -f 12998//12998 10770//10770 12999//12999 -f 12999//12999 10770//10770 10741//10741 -f 12999//12999 10741//10741 13000//13000 -f 13000//13000 10741//10741 13001//13001 -f 13001//13001 10741//10741 10742//10742 -f 13001//13001 10742//10742 13002//13002 -f 13002//13002 10742//10742 13003//13003 -f 13003//13003 10742//10742 10744//10744 -f 13003//13003 10744//10744 13004//13004 -f 13004//13004 10744//10744 13005//13005 -f 13005//13005 10744//10744 10718//10718 -f 13005//13005 10718//10718 12792//12792 -f 12788//12788 10760//10760 13006//13006 -f 13006//13006 10760//10760 10767//10767 -f 13006//13006 10767//10767 13007//13007 -f 13007//13007 10767//10767 13008//13008 -f 13008//13008 10767//10767 10766//10766 -f 13008//13008 10766//10766 13009//13009 -f 13009//13009 10766//10766 13010//13010 -f 13010//13010 10766//10766 10752//10752 -f 13010//13010 10752//10752 13011//13011 -f 13011//13011 10752//10752 13012//13012 -f 13012//13012 10752//10752 10750//10750 -f 13012//13012 10750//10750 13013//13013 -f 13013//13013 10750//10750 13014//13014 -f 13014//13014 10750//10750 10748//10748 -f 13014//13014 10748//10748 12789//12789 -f 13015//13015 12458//12458 12456//12456 -f 12456//12456 12455//12455 13015//13015 -f 13015//13015 12455//12455 12529//12529 -f 13015//13015 12529//12529 13016//13016 -f 13016//13016 12529//12529 12527//12527 -f 13016//13016 12527//12527 12525//12525 -f 12244//12244 13016//13016 12245//12245 -f 12245//12245 13016//13016 12246//12246 -f 12525//12525 12515//12515 13016//13016 -f 13016//13016 12515//12515 13017//13017 -f 13016//13016 13017//13017 12246//12246 -f 12246//12246 13017//13017 12112//12112 -f 12519//12519 13018//13018 12517//12517 -f 12517//12517 13018//13018 13017//13017 -f 12517//12517 13017//13017 12515//12515 -f 12519//12519 12521//12521 13018//13018 -f 13018//13018 12521//12521 12523//12523 -f 13018//13018 12523//12523 12653//12653 -f 13019//13019 13020//13020 13018//13018 -f 12653//12653 12458//12458 13018//13018 -f 13018//13018 12458//12458 13015//13015 -f 13018//13018 13015//13015 13019//13019 -f 13021//13021 13022//13022 13023//13023 -f 12533//12533 12534//12534 13023//13023 -f 13023//13023 12534//12534 13024//13024 -f 13023//13023 13024//13024 13021//13021 -f 13024//13024 12534//12534 12535//12535 -f 12535//12535 12540//12540 13024//13024 -f 13024//13024 12540//12540 12542//12542 -f 13024//13024 12542//12542 13025//13025 -f 13025//13025 12542//12542 12544//12544 -f 13025//13025 12544//12544 12539//12539 -f 12128//12128 13025//13025 12129//12129 -f 12129//12129 13025//13025 12131//12131 -f 12539//12539 12538//12538 13025//13025 -f 13025//13025 12538//12538 13026//13026 -f 13025//13025 13026//13026 12131//12131 -f 12131//12131 13026//13026 12133//12133 -f 12546//12546 13023//13023 12537//12537 -f 12537//12537 13023//13023 13026//13026 -f 12537//12537 13026//13026 12538//12538 -f 12546//12546 12548//12548 13023//13023 -f 13023//13023 12548//12548 12531//12531 -f 13023//13023 12531//12531 12533//12533 -f 13027//13027 11871//11871 11869//11869 -f 12147//12147 13028//13028 11869//11869 -f 11869//11869 13028//13028 13029//13029 -f 11869//11869 13029//13029 13027//13027 -f 12146//12146 13030//13030 12147//12147 -f 12147//12147 13030//13030 13031//13031 -f 12147//12147 13031//13031 13028//13028 -f 12144//12144 13032//13032 12146//12146 -f 12146//12146 13032//13032 13033//13033 -f 12146//12146 13033//13033 13030//13030 -f 12143//12143 13034//13034 12144//12144 -f 12144//12144 13034//13034 13035//13035 -f 12144//12144 13035//13035 13032//13032 -f 12142//12142 13036//13036 12143//12143 -f 12143//12143 13036//13036 13037//13037 -f 12143//12143 13037//13037 13034//13034 -f 12141//12141 13038//13038 12142//12142 -f 12142//12142 13038//13038 13039//13039 -f 12142//12142 13039//13039 13036//13036 -f 12137//12137 13040//13040 12141//12141 -f 12141//12141 13040//13040 13041//13041 -f 12141//12141 13041//13041 13038//13038 -f 12139//12139 13042//13042 12137//12137 -f 12137//12137 13042//13042 13043//13043 -f 12137//12137 13043//13043 13040//13040 -f 12152//12152 13044//13044 12139//12139 -f 12139//12139 13044//13044 13045//13045 -f 12139//12139 13045//13045 13042//13042 -f 12151//12151 13046//13046 12152//12152 -f 12152//12152 13046//13046 13047//13047 -f 12152//12152 13047//13047 13044//13044 -f 12149//12149 13048//13048 12151//12151 -f 12151//12151 13048//13048 13049//13049 -f 12151//12151 13049//13049 13046//13046 -f 12148//12148 13050//13050 12149//12149 -f 12149//12149 13050//13050 13051//13051 -f 12149//12149 13051//13051 13048//13048 -f 12158//12158 13052//13052 12148//12148 -f 12148//12148 13052//13052 13053//13053 -f 12148//12148 13053//13053 13050//13050 -f 12160//12160 13054//13054 12158//12158 -f 12158//12158 13054//13054 13055//13055 -f 12158//12158 13055//13055 13052//13052 -f 12161//12161 13056//13056 12160//12160 -f 12160//12160 13056//13056 13057//13057 -f 12160//12160 13057//13057 13054//13054 -f 12155//12155 13058//13058 12161//12161 -f 12161//12161 13058//13058 13059//13059 -f 12161//12161 13059//13059 13056//13056 -f 12157//12157 13060//13060 12155//12155 -f 12155//12155 13060//13060 13061//13061 -f 12155//12155 13061//13061 13058//13058 -f 12171//12171 13062//13062 12157//12157 -f 12157//12157 13062//13062 13063//13063 -f 12157//12157 13063//13063 13060//13060 -f 13027//13027 13064//13064 11871//11871 -f 11871//11871 13064//13064 13065//13065 -f 11871//11871 13065//13065 12171//12171 -f 12171//12171 13065//13065 13066//13066 -f 12171//12171 13066//13066 13062//13062 -f 13067//13067 13068//13068 13069//13069 -f 13069//13069 13068//13068 13070//13070 -f 13071//13071 13072//13072 13073//13073 -f 13073//13073 13072//13072 13074//13074 -f 13075//13075 13076//13076 13077//13077 -f 13078//13078 13079//13079 13076//13076 -f 13076//13076 13079//13079 13080//13080 -f 13076//13076 13080//13080 13077//13077 -f 13081//13081 13082//13082 13083//13083 -f 13083//13083 13082//13082 13084//13084 -f 13083//13083 13084//13084 13085//13085 -f 13086//13086 13087//13087 13088//13088 -f 13088//13088 13087//13087 13089//13089 -f 13072//13072 13090//13090 13074//13074 -f 13074//13074 13090//13090 13091//13091 -f 13074//13074 13091//13091 13092//13092 -f 13068//13068 13093//13093 13070//13070 -f 13070//13070 13093//13093 13094//13094 -f 13070//13070 13094//13094 13095//13095 -f 13096//13096 13097//13097 13069//13069 -f 13069//13069 13097//13097 13098//13098 -f 13069//13069 13098//13098 13067//13067 -f 13099//13099 13100//13100 13101//13101 -f 13101//13101 13100//13100 13102//13102 -f 13081//13081 13103//13103 13082//13082 -f 13082//13082 13103//13103 13104//13104 -f 13082//13082 13104//13104 13078//13078 -f 13078//13078 13104//13104 13105//13105 -f 13078//13078 13105//13105 13079//13079 -f 13085//13085 13084//13084 13106//13106 -f 13106//13106 13084//13084 13107//13107 -f 13106//13106 13107//13107 13108//13108 -f 13087//13087 13109//13109 13089//13089 -f 13089//13089 13109//13109 13110//13110 -f 13089//13089 13110//13110 13107//13107 -f 13107//13107 13110//13110 13111//13111 -f 13107//13107 13111//13111 13108//13108 -f 13091//13091 13112//13112 13092//13092 -f 13092//13092 13112//13112 13113//13113 -f 13092//13092 13113//13113 13088//13088 -f 13088//13088 13113//13113 13114//13114 -f 13088//13088 13114//13114 13086//13086 -f 13094//13094 13115//13115 13095//13095 -f 13095//13095 13115//13115 13116//13116 -f 13095//13095 13116//13116 13073//13073 -f 13073//13073 13116//13116 13117//13117 -f 13073//13073 13117//13117 13071//13071 -f 13100//13100 13118//13118 13102//13102 -f 13102//13102 13118//13118 13119//13119 -f 13102//13102 13119//13119 13096//13096 -f 13096//13096 13119//13119 13120//13120 -f 13096//13096 13120//13120 13097//13097 -f 13077//13077 13121//13121 13075//13075 -f 13075//13075 13121//13121 13122//13122 -f 13075//13075 13122//13122 13101//13101 -f 13101//13101 13122//13122 13123//13123 -f 13101//13101 13123//13123 13099//13099 -f 13124//13124 13070//13070 13125//13125 -f 13125//13125 13070//13070 13095//13095 -f 13125//13125 13095//13095 13126//13126 -f 13126//13126 13095//13095 13073//13073 -f 13126//13126 13073//13073 13127//13127 -f 13127//13127 13073//13073 13074//13074 -f 13127//13127 13074//13074 13128//13128 -f 13128//13128 13074//13074 13092//13092 -f 13128//13128 13092//13092 13129//13129 -f 13129//13129 13092//13092 13088//13088 -f 13129//13129 13088//13088 13130//13130 -f 13130//13130 13088//13088 13089//13089 -f 13130//13130 13089//13089 13131//13131 -f 13131//13131 13089//13089 13107//13107 -f 13131//13131 13107//13107 13132//13132 -f 13132//13132 13107//13107 13084//13084 -f 13132//13132 13084//13084 13133//13133 -f 13133//13133 13084//13084 13082//13082 -f 13133//13133 13082//13082 13134//13134 -f 13134//13134 13082//13082 13078//13078 -f 13134//13134 13078//13078 13135//13135 -f 13135//13135 13078//13078 13076//13076 -f 13135//13135 13076//13076 13136//13136 -f 13136//13136 13076//13076 13075//13075 -f 13136//13136 13075//13075 13137//13137 -f 13137//13137 13075//13075 13101//13101 -f 13137//13137 13101//13101 13138//13138 -f 13138//13138 13101//13101 13102//13102 -f 13138//13138 13102//13102 13139//13139 -f 13139//13139 13102//13102 13096//13096 -f 13139//13139 13096//13096 13140//13140 -f 13140//13140 13096//13096 13069//13069 -f 13140//13140 13069//13069 13124//13124 -f 13124//13124 13069//13069 13070//13070 -f 13141//13141 13139//13139 13142//13142 -f 13142//13142 13139//13139 13140//13140 -f 13142//13142 13140//13140 13143//13143 -f 13143//13143 13140//13140 13124//13124 -f 13143//13143 13124//13124 13144//13144 -f 13145//13145 13136//13136 13146//13146 -f 13146//13146 13136//13136 13137//13137 -f 13146//13146 13137//13137 13141//13141 -f 13141//13141 13137//13137 13138//13138 -f 13141//13141 13138//13138 13139//13139 -f 13147//13147 13132//13132 13148//13148 -f 13148//13148 13132//13132 13133//13133 -f 13148//13148 13133//13133 13149//13149 -f 13149//13149 13133//13133 13134//13134 -f 13149//13149 13134//13134 13145//13145 -f 13145//13145 13134//13134 13135//13135 -f 13145//13145 13135//13135 13136//13136 -f 13150//13150 13129//13129 13151//13151 -f 13151//13151 13129//13129 13130//13130 -f 13151//13151 13130//13130 13147//13147 -f 13147//13147 13130//13130 13131//13131 -f 13147//13147 13131//13131 13132//13132 -f 13124//13124 13125//13125 13144//13144 -f 13144//13144 13125//13125 13126//13126 -f 13144//13144 13126//13126 13152//13152 -f 13152//13152 13126//13126 13127//13127 -f 13152//13152 13127//13127 13150//13150 -f 13150//13150 13127//13127 13128//13128 -f 13150//13150 13128//13128 13129//13129 -f 13153//13153 13154//13154 13155//13155 -f 13156//13156 13154//13154 13153//13153 -f 13153//13153 13157//13157 13158//13158 -f 13159//13159 13157//13157 13153//13153 -f 13155//13155 13159//13159 13153//13153 -f 13153//13153 13160//13160 13161//13161 -f 13162//13162 13160//13160 13153//13153 -f 13158//13158 13162//13162 13153//13153 -f 13153//13153 13163//13163 13164//13164 -f 13165//13165 13163//13163 13153//13153 -f 13161//13161 13165//13165 13153//13153 -f 13164//13164 13156//13156 13153//13153 -f 13156//13156 13166//13166 13154//13154 -f 13154//13154 13166//13166 13167//13167 -f 13154//13154 13167//13167 13155//13155 -f 13155//13155 13167//13167 13168//13168 -f 13155//13155 13168//13168 13159//13159 -f 13159//13159 13168//13168 13169//13169 -f 13159//13159 13169//13169 13157//13157 -f 13157//13157 13169//13169 13170//13170 -f 13157//13157 13170//13170 13158//13158 -f 13158//13158 13170//13170 13171//13171 -f 13158//13158 13171//13171 13162//13162 -f 13162//13162 13171//13171 13172//13172 -f 13162//13162 13172//13172 13160//13160 -f 13160//13160 13172//13172 13173//13173 -f 13160//13160 13173//13173 13161//13161 -f 13161//13161 13173//13173 13174//13174 -f 13161//13161 13174//13174 13165//13165 -f 13165//13165 13174//13174 13175//13175 -f 13165//13165 13175//13175 13163//13163 -f 13163//13163 13175//13175 13176//13176 -f 13163//13163 13176//13176 13164//13164 -f 13164//13164 13176//13176 13177//13177 -f 13164//13164 13177//13177 13156//13156 -f 13156//13156 13177//13177 13166//13166 -f 13167//13167 12504//12504 13168//13168 -f 13168//13168 12504//12504 12502//12502 -f 13168//13168 12502//12502 13169//13169 -f 13169//13169 12502//12502 12501//12501 -f 13169//13169 12501//12501 13170//13170 -f 13170//13170 12501//12501 12500//12500 -f 13170//13170 12500//12500 13171//13171 -f 13171//13171 12500//12500 12499//12499 -f 13171//13171 12499//12499 13172//13172 -f 13172//13172 12499//12499 12497//12497 -f 13172//13172 12497//12497 13173//13173 -f 13173//13173 12497//12497 12510//12510 -f 13173//13173 12510//12510 13174//13174 -f 13174//13174 12510//12510 12509//12509 -f 13174//13174 12509//12509 13175//13175 -f 13175//13175 12509//12509 12508//12508 -f 13175//13175 12508//12508 13176//13176 -f 13176//13176 12508//12508 12507//12507 -f 13176//13176 12507//12507 13177//13177 -f 13177//13177 12507//12507 12506//12506 -f 13177//13177 12506//12506 13166//13166 -f 13166//13166 12506//12506 12505//12505 -f 13166//13166 12505//12505 13167//13167 -f 13167//13167 12505//12505 12504//12504 -f 13178//13178 13179//13179 13180//13180 -f 13181//13181 13179//13179 13178//13178 -f 13178//13178 13182//13182 13183//13183 -f 13184//13184 13182//13182 13178//13178 -f 13180//13180 13184//13184 13178//13178 -f 13178//13178 13185//13185 13186//13186 -f 13187//13187 13185//13185 13178//13178 -f 13183//13183 13187//13187 13178//13178 -f 13178//13178 13188//13188 13189//13189 -f 13190//13190 13188//13188 13178//13178 -f 13186//13186 13190//13190 13178//13178 -f 13189//13189 13181//13181 13178//13178 -f 13181//13181 13191//13191 13179//13179 -f 13179//13179 13191//13191 13192//13192 -f 13179//13179 13192//13192 13180//13180 -f 13180//13180 13192//13192 13193//13193 -f 13180//13180 13193//13193 13184//13184 -f 13184//13184 13193//13193 13194//13194 -f 13184//13184 13194//13194 13182//13182 -f 13182//13182 13194//13194 13195//13195 -f 13182//13182 13195//13195 13183//13183 -f 13183//13183 13195//13195 13196//13196 -f 13183//13183 13196//13196 13187//13187 -f 13187//13187 13196//13196 13197//13197 -f 13187//13187 13197//13197 13185//13185 -f 13185//13185 13197//13197 13198//13198 -f 13185//13185 13198//13198 13186//13186 -f 13186//13186 13198//13198 13199//13199 -f 13186//13186 13199//13199 13190//13190 -f 13190//13190 13199//13199 13200//13200 -f 13190//13190 13200//13200 13188//13188 -f 13188//13188 13200//13200 13201//13201 -f 13188//13188 13201//13201 13189//13189 -f 13189//13189 13201//13201 13202//13202 -f 13189//13189 13202//13202 13181//13181 -f 13181//13181 13202//13202 13191//13191 -f 13192//13192 12484//12484 13193//13193 -f 13193//13193 12484//12484 12483//12483 -f 13193//13193 12483//12483 13194//13194 -f 13194//13194 12483//12483 12482//12482 -f 13194//13194 12482//12482 13195//13195 -f 13195//13195 12482//12482 12481//12481 -f 13195//13195 12481//12481 13196//13196 -f 13196//13196 12481//12481 12495//12495 -f 13196//13196 12495//12495 13197//13197 -f 13197//13197 12495//12495 12494//12494 -f 13197//13197 12494//12494 13198//13198 -f 13198//13198 12494//12494 12492//12492 -f 13198//13198 12492//12492 13199//13199 -f 13199//13199 12492//12492 12490//12490 -f 13199//13199 12490//12490 13200//13200 -f 13200//13200 12490//12490 12489//12489 -f 13200//13200 12489//12489 13201//13201 -f 13201//13201 12489//12489 12488//12488 -f 13201//13201 12488//12488 13202//13202 -f 13202//13202 12488//12488 12486//12486 -f 13202//13202 12486//12486 13191//13191 -f 13191//13191 12486//12486 12485//12485 -f 13191//13191 12485//12485 13192//13192 -f 13192//13192 12485//12485 12484//12484 -f 13203//13203 13204//13204 13205//13205 -f 13206//13206 13204//13204 13203//13203 -f 13203//13203 13207//13207 13208//13208 -f 13209//13209 13207//13207 13203//13203 -f 13205//13205 13209//13209 13203//13203 -f 13203//13203 13210//13210 13211//13211 -f 13212//13212 13210//13210 13203//13203 -f 13208//13208 13212//13212 13203//13203 -f 13203//13203 13213//13213 13214//13214 -f 13215//13215 13213//13213 13203//13203 -f 13211//13211 13215//13215 13203//13203 -f 13214//13214 13206//13206 13203//13203 -f 13206//13206 13216//13216 13204//13204 -f 13204//13204 13216//13216 13217//13217 -f 13204//13204 13217//13217 13205//13205 -f 13205//13205 13217//13217 13218//13218 -f 13205//13205 13218//13218 13209//13209 -f 13209//13209 13218//13218 13219//13219 -f 13209//13209 13219//13219 13207//13207 -f 13207//13207 13219//13219 13220//13220 -f 13207//13207 13220//13220 13208//13208 -f 13208//13208 13220//13220 13221//13221 -f 13208//13208 13221//13221 13212//13212 -f 13212//13212 13221//13221 13222//13222 -f 13212//13212 13222//13222 13210//13210 -f 13210//13210 13222//13222 13223//13223 -f 13210//13210 13223//13223 13211//13211 -f 13211//13211 13223//13223 13224//13224 -f 13211//13211 13224//13224 13215//13215 -f 13215//13215 13224//13224 13225//13225 -f 13215//13215 13225//13225 13213//13213 -f 13213//13213 13225//13225 13226//13226 -f 13213//13213 13226//13226 13214//13214 -f 13214//13214 13226//13226 13227//13227 -f 13214//13214 13227//13227 13206//13206 -f 13206//13206 13227//13227 13216//13216 -f 13217//13217 12554//12554 13218//13218 -f 13218//13218 12554//12554 12560//12560 -f 13218//13218 12560//12560 13219//13219 -f 13219//13219 12560//12560 12559//12559 -f 13219//13219 12559//12559 13220//13220 -f 13220//13220 12559//12559 12558//12558 -f 13220//13220 12558//12558 13221//13221 -f 13221//13221 12558//12558 12550//12550 -f 13221//13221 12550//12550 13222//13222 -f 13222//13222 12550//12550 12552//12552 -f 13222//13222 12552//12552 13223//13223 -f 13223//13223 12552//12552 12395//12395 -f 13223//13223 12395//12395 13224//13224 -f 13224//13224 12395//12395 12396//12396 -f 13224//13224 12396//12396 13225//13225 -f 13225//13225 12396//12396 12397//12397 -f 13225//13225 12397//12397 13226//13226 -f 13226//13226 12397//12397 12392//12392 -f 13226//13226 12392//12392 13227//13227 -f 13227//13227 12392//12392 12388//12388 -f 13227//13227 12388//12388 13216//13216 -f 13216//13216 12388//12388 12557//12557 -f 13216//13216 12557//12557 13217//13217 -f 13217//13217 12557//12557 12554//12554 -f 13228//13228 13229//13229 13230//13230 -f 13231//13231 13229//13229 13228//13228 -f 13228//13228 13232//13232 13233//13233 -f 13234//13234 13232//13232 13228//13228 -f 13230//13230 13234//13234 13228//13228 -f 13228//13228 13235//13235 13236//13236 -f 13237//13237 13235//13235 13228//13228 -f 13233//13233 13237//13237 13228//13228 -f 13228//13228 13238//13238 13239//13239 -f 13240//13240 13238//13238 13228//13228 -f 13236//13236 13240//13240 13228//13228 -f 13239//13239 13231//13231 13228//13228 -f 13231//13231 13241//13241 13229//13229 -f 13229//13229 13241//13241 13242//13242 -f 13229//13229 13242//13242 13230//13230 -f 13230//13230 13242//13242 13243//13243 -f 13230//13230 13243//13243 13234//13234 -f 13234//13234 13243//13243 13244//13244 -f 13234//13234 13244//13244 13232//13232 -f 13232//13232 13244//13244 13245//13245 -f 13232//13232 13245//13245 13233//13233 -f 13233//13233 13245//13245 13246//13246 -f 13233//13233 13246//13246 13237//13237 -f 13237//13237 13246//13246 13247//13247 -f 13237//13237 13247//13247 13235//13235 -f 13235//13235 13247//13247 13248//13248 -f 13235//13235 13248//13248 13236//13236 -f 13236//13236 13248//13248 13249//13249 -f 13236//13236 13249//13249 13240//13240 -f 13240//13240 13249//13249 13250//13250 -f 13240//13240 13250//13250 13238//13238 -f 13238//13238 13250//13250 13251//13251 -f 13238//13238 13251//13251 13239//13239 -f 13239//13239 13251//13251 13252//13252 -f 13239//13239 13252//13252 13231//13231 -f 13231//13231 13252//13252 13241//13241 -f 13242//13242 12440//12440 13243//13243 -f 13243//13243 12440//12440 12439//12439 -f 13243//13243 12439//12439 13244//13244 -f 13244//13244 12439//12439 12430//12430 -f 13244//13244 12430//12430 13245//13245 -f 13245//13245 12430//12430 12429//12429 -f 13245//13245 12429//12429 13246//13246 -f 13246//13246 12429//12429 12427//12427 -f 13246//13246 12427//12427 13247//13247 -f 13247//13247 12427//12427 12426//12426 -f 13247//13247 12426//12426 13248//13248 -f 13248//13248 12426//12426 12435//12435 -f 13248//13248 12435//12435 13249//13249 -f 13249//13249 12435//12435 12434//12434 -f 13249//13249 12434//12434 13250//13250 -f 13250//13250 12434//12434 12433//12433 -f 13250//13250 12433//12433 13251//13251 -f 13251//13251 12433//12433 12432//12432 -f 13251//13251 12432//12432 13252//13252 -f 13252//13252 12432//12432 12431//12431 -f 13252//13252 12431//12431 13241//13241 -f 13241//13241 12431//12431 12441//12441 -f 13241//13241 12441//12441 13242//13242 -f 13242//13242 12441//12441 12440//12440 -f 12566//12566 13253//13253 12568//12568 -f 12568//12568 13253//13253 13254//13254 -f 12568//12568 13254//13254 12569//12569 -f 12569//12569 13254//13254 13255//13255 -f 12569//12569 13255//13255 12570//12570 -f 12570//12570 13255//13255 13256//13256 -f 12570//12570 13256//13256 12571//12571 -f 12571//12571 13256//13256 13257//13257 -f 12571//12571 13257//13257 12573//12573 -f 12573//12573 13257//13257 13258//13258 -f 12573//12573 13258//13258 12575//12575 -f 12575//12575 13258//13258 13259//13259 -f 12575//12575 13259//13259 12577//12577 -f 12577//12577 13259//13259 13260//13260 -f 12577//12577 13260//13260 12578//12578 -f 12578//12578 13260//13260 13261//13261 -f 12578//12578 13261//13261 12561//12561 -f 12561//12561 13261//13261 13262//13262 -f 12561//12561 13262//13262 12562//12562 -f 12562//12562 13262//13262 13263//13263 -f 12562//12562 13263//13263 12564//12564 -f 12564//12564 13263//13263 13264//13264 -f 12564//12564 13264//13264 12566//12566 -f 12566//12566 13264//13264 13253//13253 -f 13254//13254 13144//13144 13255//13255 -f 13255//13255 13144//13144 13152//13152 -f 13255//13255 13152//13152 13256//13256 -f 13256//13256 13152//13152 13150//13150 -f 13256//13256 13150//13150 13257//13257 -f 13257//13257 13150//13150 13151//13151 -f 13257//13257 13151//13151 13258//13258 -f 13258//13258 13151//13151 13147//13147 -f 13258//13258 13147//13147 13259//13259 -f 13259//13259 13147//13147 13148//13148 -f 13259//13259 13148//13148 13260//13260 -f 13260//13260 13148//13148 13149//13149 -f 13260//13260 13149//13149 13261//13261 -f 13261//13261 13149//13149 13145//13145 -f 13261//13261 13145//13145 13262//13262 -f 13262//13262 13145//13145 13146//13146 -f 13262//13262 13146//13146 13263//13263 -f 13263//13263 13146//13146 13141//13141 -f 13263//13263 13141//13141 13264//13264 -f 13264//13264 13141//13141 13142//13142 -f 13264//13264 13142//13142 13253//13253 -f 13253//13253 13142//13142 13143//13143 -f 13253//13253 13143//13143 13254//13254 -f 13254//13254 13143//13143 13144//13144 -f 12583//12583 13265//13265 12584//12584 -f 12584//12584 13265//13265 13266//13266 -f 12584//12584 13266//13266 12674//12674 -f 12674//12674 13266//13266 13267//13267 -f 12674//12674 13267//13267 12585//12585 -f 12585//12585 13267//13267 13268//13268 -f 12585//12585 13268//13268 12586//12586 -f 12586//12586 13268//13268 13269//13269 -f 12586//12586 13269//13269 12588//12588 -f 12588//12588 13269//13269 13270//13270 -f 12588//12588 13270//13270 12590//12590 -f 12590//12590 13270//13270 13271//13271 -f 12590//12590 13271//13271 12591//12591 -f 12591//12591 13271//13271 13272//13272 -f 12591//12591 13272//13272 12682//12682 -f 12682//12682 13272//13272 13273//13273 -f 12682//12682 13273//13273 12579//12579 -f 12579//12579 13273//13273 13274//13274 -f 12579//12579 13274//13274 12580//12580 -f 12580//12580 13274//13274 13275//13275 -f 12580//12580 13275//13275 12582//12582 -f 12582//12582 13275//13275 13276//13276 -f 12582//12582 13276//13276 12583//12583 -f 12583//12583 13276//13276 13265//13265 -f 13266//13266 12145//12145 13267//13267 -f 13267//13267 12145//12145 11868//11868 -f 13267//13267 11868//11868 13268//13268 -f 13268//13268 11868//11868 11870//11870 -f 13268//13268 11870//11870 13269//13269 -f 13269//13269 11870//11870 11872//11872 -f 13269//13269 11872//11872 13270//13270 -f 13270//13270 11872//11872 11881//11881 -f 13270//13270 11881//11881 13271//13271 -f 13271//13271 11881//11881 11883//11883 -f 13271//13271 11883//11883 13272//13272 -f 13272//13272 11883//11883 11885//11885 -f 13272//13272 11885//11885 13273//13273 -f 13273//13273 11885//11885 11880//11880 -f 13273//13273 11880//11880 13274//13274 -f 13274//13274 11880//11880 11879//11879 -f 13274//13274 11879//11879 13275//13275 -f 13275//13275 11879//11879 11877//11877 -f 13275//13275 11877//11877 13276//13276 -f 13276//13276 11877//11877 11876//11876 -f 13276//13276 11876//11876 13265//13265 -f 13265//13265 11876//11876 11875//11875 -f 13265//13265 11875//11875 13266//13266 -f 13266//13266 11875//11875 12145//12145 -f 12602//12602 13277//13277 12603//12603 -f 12603//12603 13277//13277 13278//13278 -f 12603//12603 13278//13278 12604//12604 -f 12604//12604 13278//13278 13279//13279 -f 12604//12604 13279//13279 12607//12607 -f 12607//12607 13279//13279 13280//13280 -f 12607//12607 13280//13280 12605//12605 -f 12605//12605 13280//13280 13281//13281 -f 12605//12605 13281//13281 12596//12596 -f 12596//12596 13281//13281 13282//13282 -f 12596//12596 13282//13282 12594//12594 -f 12594//12594 13282//13282 13283//13283 -f 12594//12594 13283//13283 12592//12592 -f 12592//12592 13283//13283 13284//13284 -f 12592//12592 13284//13284 12599//12599 -f 12599//12599 13284//13284 13285//13285 -f 12599//12599 13285//13285 12600//12600 -f 12600//12600 13285//13285 13286//13286 -f 12600//12600 13286//13286 12601//12601 -f 12601//12601 13286//13286 13287//13287 -f 12601//12601 13287//13287 12597//12597 -f 12597//12597 13287//13287 13288//13288 -f 12597//12597 13288//13288 12602//12602 -f 12602//12602 13288//13288 13277//13277 -f 13278//13278 12175//12175 13279//13279 -f 13279//13279 12175//12175 12174//12174 -f 13279//13279 12174//12174 13280//13280 -f 13280//13280 12174//12174 12179//12179 -f 13280//13280 12179//12179 13281//13281 -f 13281//13281 12179//12179 12178//12178 -f 13281//13281 12178//12178 13282//13282 -f 13282//13282 12178//12178 12177//12177 -f 13282//13282 12177//12177 13283//13283 -f 13283//13283 12177//12177 12176//12176 -f 13283//13283 12176//12176 13284//13284 -f 13284//13284 12176//12176 12184//12184 -f 13284//13284 12184//12184 13285//13285 -f 13285//13285 12184//12184 12183//12183 -f 13285//13285 12183//12183 13286//13286 -f 13286//13286 12183//12183 12181//12181 -f 13286//13286 12181//12181 13287//13287 -f 13287//13287 12181//12181 12180//12180 -f 13287//13287 12180//12180 13288//13288 -f 13288//13288 12180//12180 12173//12173 -f 13288//13288 12173//12173 13277//13277 -f 13277//13277 12173//12173 12172//12172 -f 13277//13277 12172//12172 13278//13278 -f 13278//13278 12172//12172 12175//12175 -f 12615//12615 13289//13289 12616//12616 -f 12616//12616 13289//13289 13290//13290 -f 12616//12616 13290//13290 12618//12618 -f 12618//12618 13290//13290 13291//13291 -f 12618//12618 13291//13291 12619//12619 -f 12619//12619 13291//13291 13292//13292 -f 12619//12619 13292//13292 12620//12620 -f 12620//12620 13292//13292 13293//13293 -f 12620//12620 13293//13293 12621//12621 -f 12621//12621 13293//13293 13294//13294 -f 12621//12621 13294//13294 12614//12614 -f 12614//12614 13294//13294 13295//13295 -f 12614//12614 13295//13295 12608//12608 -f 12608//12608 13295//13295 13296//13296 -f 12608//12608 13296//13296 12609//12609 -f 12609//12609 13296//13296 13297//13297 -f 12609//12609 13297//13297 12610//12610 -f 12610//12610 13297//13297 13298//13298 -f 12610//12610 13298//13298 12611//12611 -f 12611//12611 13298//13298 13299//13299 -f 12611//12611 13299//13299 12612//12612 -f 12612//12612 13299//13299 13300//13300 -f 12612//12612 13300//13300 12615//12615 -f 12615//12615 13300//13300 13289//13289 -f 13290//13290 12240//12240 13291//13291 -f 13291//13291 12240//12240 12241//12241 -f 13291//13291 12241//12241 13292//13292 -f 13292//13292 12241//12241 12239//12239 -f 13292//13292 12239//12239 13293//13293 -f 13293//13293 12239//12239 12238//12238 -f 13293//13293 12238//12238 13294//13294 -f 13294//13294 12238//12238 12237//12237 -f 13294//13294 12237//12237 13295//13295 -f 13295//13295 12237//12237 12230//12230 -f 13295//13295 12230//12230 13296//13296 -f 13296//13296 12230//12230 12229//12229 -f 13296//13296 12229//12229 13297//13297 -f 13297//13297 12229//12229 12233//12233 -f 13297//13297 12233//12233 13298//13298 -f 13298//13298 12233//12233 12232//12232 -f 13298//13298 12232//12232 13299//13299 -f 13299//13299 12232//12232 12231//12231 -f 13299//13299 12231//12231 13300//13300 -f 13300//13300 12231//12231 12228//12228 -f 13300//13300 12228//12228 13289//13289 -f 13289//13289 12228//12228 12227//12227 -f 13289//13289 12227//12227 13290//13290 -f 13290//13290 12227//12227 12240//12240 -f 12626//12626 13301//13301 12627//12627 -f 12627//12627 13301//13301 13302//13302 -f 12627//12627 13302//13302 12666//12666 -f 12666//12666 13302//13302 13303//13303 -f 12666//12666 13303//13303 12628//12628 -f 12628//12628 13303//13303 13304//13304 -f 12628//12628 13304//13304 12629//12629 -f 12629//12629 13304//13304 13305//13305 -f 12629//12629 13305//13305 12631//12631 -f 12631//12631 13305//13305 13306//13306 -f 12631//12631 13306//13306 12632//12632 -f 12632//12632 13306//13306 13307//13307 -f 12632//12632 13307//13307 12634//12634 -f 12634//12634 13307//13307 13308//13308 -f 12634//12634 13308//13308 12669//12669 -f 12669//12669 13308//13308 13309//13309 -f 12669//12669 13309//13309 12622//12622 -f 12622//12622 13309//13309 13310//13310 -f 12622//12622 13310//13310 12623//12623 -f 12623//12623 13310//13310 13311//13311 -f 12623//12623 13311//13311 12624//12624 -f 12624//12624 13311//13311 13312//13312 -f 12624//12624 13312//13312 12626//12626 -f 12626//12626 13312//13312 13301//13301 -f 13302//13302 12054//12054 13303//13303 -f 13303//13303 12054//12054 12056//12056 -f 13303//13303 12056//12056 13304//13304 -f 13304//13304 12056//12056 12057//12057 -f 13304//13304 12057//12057 13305//13305 -f 13305//13305 12057//12057 12060//12060 -f 13305//13305 12060//12060 13306//13306 -f 13306//13306 12060//12060 12165//12165 -f 13306//13306 12165//12165 13307//13307 -f 13307//13307 12165//12165 12167//12167 -f 13307//13307 12167//12167 13308//13308 -f 13308//13308 12167//12167 12169//12169 -f 13308//13308 12169//12169 13309//13309 -f 13309//13309 12169//12169 12170//12170 -f 13309//13309 12170//12170 13310//13310 -f 13310//13310 12170//12170 12154//12154 -f 13310//13310 12154//12154 13311//13311 -f 13311//13311 12154//12154 12153//12153 -f 13311//13311 12153//12153 13312//13312 -f 13312//13312 12153//12153 12162//12162 -f 13312//13312 12162//12162 13301//13301 -f 13301//13301 12162//12162 12052//12052 -f 13301//13301 12052//12052 13302//13302 -f 13302//13302 12052//12052 12054//12054 -f 12640//12640 13313//13313 12635//12635 -f 12635//12635 13313//13313 13314//13314 -f 12635//12635 13314//13314 12636//12636 -f 12636//12636 13314//13314 13315//13315 -f 12636//12636 13315//13315 12637//12637 -f 12637//12637 13315//13315 13316//13316 -f 12637//12637 13316//13316 12638//12638 -f 12638//12638 13316//13316 13317//13317 -f 12638//12638 13317//13317 12639//12639 -f 12639//12639 13317//13317 13318//13318 -f 12639//12639 13318//13318 12643//12643 -f 12643//12643 13318//13318 13319//13319 -f 12643//12643 13319//13319 12644//12644 -f 12644//12644 13319//13319 13320//13320 -f 12644//12644 13320//13320 12645//12645 -f 12645//12645 13320//13320 13321//13321 -f 12645//12645 13321//13321 12648//12648 -f 12648//12648 13321//13321 13322//13322 -f 12648//12648 13322//13322 12646//12646 -f 12646//12646 13322//13322 13323//13323 -f 12646//12646 13323//13323 12642//12642 -f 12642//12642 13323//13323 13324//13324 -f 12642//12642 13324//13324 12640//12640 -f 12640//12640 13324//13324 13313//13313 -f 13314//13314 12249//12249 13315//13315 -f 13315//13315 12249//12249 12259//12259 -f 13315//13315 12259//12259 13316//13316 -f 13316//13316 12259//12259 12258//12258 -f 13316//13316 12258//12258 13317//13317 -f 13317//13317 12258//12258 12257//12257 -f 13317//13317 12257//12257 13318//13318 -f 13318//13318 12257//12257 12256//12256 -f 13318//13318 12256//12256 13319//13319 -f 13319//13319 12256//12256 12255//12255 -f 13319//13319 12255//12255 13320//13320 -f 13320//13320 12255//12255 12254//12254 -f 13320//13320 12254//12254 13321//13321 -f 13321//13321 12254//12254 12251//12251 -f 13321//13321 12251//12251 13322//13322 -f 13322//13322 12251//12251 12252//12252 -f 13322//13322 12252//12252 13323//13323 -f 13323//13323 12252//12252 12253//12253 -f 13323//13323 12253//12253 13324//13324 -f 13324//13324 12253//12253 12248//12248 -f 13324//13324 12248//12248 13313//13313 -f 13313//13313 12248//12248 12247//12247 -f 13313//13313 12247//12247 13314//13314 -f 13314//13314 12247//12247 12249//12249 -f 12649//12649 13325//13325 12650//12650 -f 12650//12650 13325//13325 13326//13326 -f 12650//12650 13326//13326 12651//12651 -f 12651//12651 13326//13326 13327//13327 -f 12651//12651 13327//13327 12654//12654 -f 12654//12654 13327//13327 13328//13328 -f 12654//12654 13328//13328 12655//12655 -f 12655//12655 13328//13328 13329//13329 -f 12655//12655 13329//13329 12656//12656 -f 12656//12656 13329//13329 13330//13330 -f 12656//12656 13330//13330 12661//12661 -f 12661//12661 13330//13330 13331//13331 -f 12661//12661 13331//13331 12662//12662 -f 12662//12662 13331//13331 13332//13332 -f 12662//12662 13332//13332 12664//12664 -f 12664//12664 13332//13332 13333//13333 -f 12664//12664 13333//13333 12660//12660 -f 12660//12660 13333//13333 13334//13334 -f 12660//12660 13334//13334 12659//12659 -f 12659//12659 13334//13334 13335//13335 -f 12659//12659 13335//13335 12652//12652 -f 12652//12652 13335//13335 13336//13336 -f 12652//12652 13336//13336 12649//12649 -f 12649//12649 13336//13336 13325//13325 -f 13326//13326 12193//12193 13327//13327 -f 13327//13327 12193//12193 12192//12192 -f 13327//13327 12192//12192 13328//13328 -f 13328//13328 12192//12192 12190//12190 -f 13328//13328 12190//12190 13329//13329 -f 13329//13329 12190//12190 12197//12197 -f 13329//13329 12197//12197 13330//13330 -f 13330//13330 12197//12197 12196//12196 -f 13330//13330 12196//12196 13331//13331 -f 13331//13331 12196//12196 12201//12201 -f 13331//13331 12201//12201 13332//13332 -f 13332//13332 12201//12201 12200//12200 -f 13332//13332 12200//12200 13333//13333 -f 13333//13333 12200//12200 12199//12199 -f 13333//13333 12199//12199 13334//13334 -f 13334//13334 12199//12199 12198//12198 -f 13334//13334 12198//12198 13335//13335 -f 13335//13335 12198//12198 12186//12186 -f 13335//13335 12186//12186 13336//13336 -f 13336//13336 12186//12186 12185//12185 -f 13336//13336 12185//12185 13325//13325 -f 13325//13325 12185//12185 12188//12188 -f 13325//13325 12188//12188 13326//13326 -f 13326//13326 12188//12188 12193//12193 -f 12792//12792 12791//12791 12794//12794 -f 12792//12792 12794//12794 13337//13337 -f 13337//13337 12794//12794 12795//12795 -f 13337//13337 12795//12795 13338//13338 -f 13338//13338 12795//12795 11860//11860 -f 13338//13338 11860//11860 11859//11859 -f 11886//11886 13339//13339 13340//13340 -f 13339//13339 13341//13341 13342//13342 -f 13341//13341 12790//12790 12997//12997 -f 13341//13341 12997//12997 13342//13342 -f 13342//13342 12997//12997 12998//12998 -f 13342//13342 12998//12998 13343//13343 -f 13343//13343 12998//12998 12999//12999 -f 13343//13343 12999//12999 13344//13344 -f 13344//13344 12999//12999 13000//13000 -f 13344//13344 13000//13000 13345//13345 -f 13345//13345 13000//13000 13001//13001 -f 13345//13345 13001//13001 13346//13346 -f 13346//13346 13001//13001 13002//13002 -f 13346//13346 13002//13002 13347//13347 -f 13347//13347 13002//13002 13003//13003 -f 13347//13347 13003//13003 13348//13348 -f 13348//13348 13003//13003 13004//13004 -f 13348//13348 13004//13004 13349//13349 -f 13349//13349 13004//13004 13005//13005 -f 13349//13349 13005//13005 13350//13350 -f 13350//13350 13005//13005 12792//12792 -f 13350//13350 12792//12792 13337//13337 -f 13339//13339 13342//13342 13340//13340 -f 13340//13340 13342//13342 13343//13343 -f 13340//13340 13343//13343 13351//13351 -f 13351//13351 13343//13343 13344//13344 -f 13351//13351 13344//13344 13352//13352 -f 13352//13352 13344//13344 13345//13345 -f 13352//13352 13345//13345 13353//13353 -f 13353//13353 13345//13345 13346//13346 -f 13353//13353 13346//13346 13354//13354 -f 13354//13354 13346//13346 13347//13347 -f 13354//13354 13347//13347 13355//13355 -f 13355//13355 13347//13347 13348//13348 -f 13355//13355 13348//13348 13356//13356 -f 13356//13356 13348//13348 13349//13349 -f 13356//13356 13349//13349 13357//13357 -f 13357//13357 13349//13349 13350//13350 -f 13357//13357 13350//13350 13358//13358 -f 13358//13358 13350//13350 13337//13337 -f 13358//13358 13337//13337 13338//13338 -f 11886//11886 13340//13340 11887//11887 -f 11887//11887 13340//13340 13351//13351 -f 11887//11887 13351//13351 11878//11878 -f 11878//11878 13351//13351 13352//13352 -f 11878//11878 13352//13352 12045//12045 -f 12045//12045 13352//13352 13353//13353 -f 12045//12045 13353//13353 12046//12046 -f 12046//12046 13353//13353 13354//13354 -f 12046//12046 13354//13354 12049//12049 -f 12049//12049 13354//13354 13355//13355 -f 12049//12049 13355//13355 12050//12050 -f 12050//12050 13355//13355 13356//13356 -f 12050//12050 13356//13356 12051//12051 -f 12051//12051 13356//13356 13357//13357 -f 12051//12051 13357//13357 12048//12048 -f 12048//12048 13357//13357 13358//13358 -f 12048//12048 13358//13358 12047//12047 -f 12047//12047 13358//13358 13338//13338 -f 12047//12047 13338//13338 11859//11859 -f 12168//12168 12166//12166 13359//13359 -f 12789//12789 12790//12790 13341//13341 -f 12789//12789 13341//13341 13360//13360 -f 13360//13360 13341//13341 13339//13339 -f 13360//13360 13339//13339 13359//13359 -f 11886//11886 11884//11884 13339//13339 -f 13339//13339 11884//11884 11882//11882 -f 13339//13339 11882//11882 13359//13359 -f 13359//13359 11882//11882 12156//12156 -f 13359//13359 12156//12156 12168//12168 -f 12063//12063 13361//13361 13362//13362 -f 13361//13361 13363//13363 13364//13364 -f 13363//13363 12788//12788 13006//13006 -f 13363//13363 13006//13006 13364//13364 -f 13364//13364 13006//13006 13007//13007 -f 13364//13364 13007//13007 13365//13365 -f 13365//13365 13007//13007 13008//13008 -f 13365//13365 13008//13008 13366//13366 -f 13366//13366 13008//13008 13009//13009 -f 13366//13366 13009//13009 13367//13367 -f 13367//13367 13009//13009 13010//13010 -f 13367//13367 13010//13010 13368//13368 -f 13368//13368 13010//13010 13011//13011 -f 13368//13368 13011//13011 13369//13369 -f 13369//13369 13011//13011 13012//13012 -f 13369//13369 13012//13012 13370//13370 -f 13370//13370 13012//13012 13013//13013 -f 13370//13370 13013//13013 13371//13371 -f 13371//13371 13013//13013 13014//13014 -f 13371//13371 13014//13014 13372//13372 -f 13372//13372 13014//13014 12789//12789 -f 13372//13372 12789//12789 13360//13360 -f 13361//13361 13364//13364 13362//13362 -f 13362//13362 13364//13364 13365//13365 -f 13362//13362 13365//13365 13373//13373 -f 13373//13373 13365//13365 13366//13366 -f 13373//13373 13366//13366 13374//13374 -f 13374//13374 13366//13366 13367//13367 -f 13374//13374 13367//13367 13375//13375 -f 13375//13375 13367//13367 13368//13368 -f 13375//13375 13368//13368 13376//13376 -f 13376//13376 13368//13368 13369//13369 -f 13376//13376 13369//13369 13377//13377 -f 13377//13377 13369//13369 13370//13370 -f 13377//13377 13370//13370 13378//13378 -f 13378//13378 13370//13370 13371//13371 -f 13378//13378 13371//13371 13379//13379 -f 13379//13379 13371//13371 13372//13372 -f 13379//13379 13372//13372 13380//13380 -f 13380//13380 13372//13372 13360//13360 -f 13380//13380 13360//13360 13359//13359 -f 12063//12063 13362//13362 12064//12064 -f 12064//12064 13362//13362 13373//13373 -f 12064//12064 13373//13373 12065//12065 -f 12065//12065 13373//13373 13374//13374 -f 12065//12065 13374//13374 12273//12273 -f 12273//12273 13374//13374 13375//13375 -f 12273//12273 13375//13375 12058//12058 -f 12058//12058 13375//13375 13376//13376 -f 12058//12058 13376//13376 12059//12059 -f 12059//12059 13376//13376 13377//13377 -f 12059//12059 13377//13377 12062//12062 -f 12062//12062 13377//13377 13378//13378 -f 12062//12062 13378//13378 12061//12061 -f 12061//12061 13378//13378 13379//13379 -f 12061//12061 13379//13379 12163//12163 -f 12163//12163 13379//13379 13380//13380 -f 12163//12163 13380//13380 12164//12164 -f 12164//12164 13380//13380 13359//13359 -f 12164//12164 13359//13359 12166//12166 -f 12787//12787 12788//12788 13363//13363 -f 12787//12787 13363//13363 12862//12862 -f 12862//12862 13363//13363 13361//13361 -f 12862//12862 13361//13361 12861//12861 -f 12861//12861 13361//13361 12063//12063 -f 12861//12861 12063//12063 12069//12069 -f 12856//12856 12066//12066 11954//11954 -f 12856//12856 11954//11954 12851//12851 -f 12851//12851 11954//11954 11961//11961 -f 12851//12851 11961//11961 11963//11963 -f 12846//12846 11945//11945 11944//11944 -f 12846//12846 11944//11944 12841//12841 -f 12841//12841 11944//11944 11855//11855 -f 12841//12841 11855//11855 12010//12010 -f 12836//12836 11972//11972 12831//12831 -f 12831//12831 11972//11972 11978//11978 -f 12831//12831 11978//11978 11980//11980 -f 12821//12821 12826//12826 12285//12285 -f 12285//12285 12291//12291 12821//12821 -f 12821//12821 12291//12291 11867//11867 -f 12821//12821 11867//11867 11866//11866 -f 12014//12014 12013//12013 12814//12814 -f 12814//12814 12013//12013 12262//12262 -f 12814//12814 12262//12262 12809//12809 -f 12809//12809 12262//12262 12019//12019 -f 12809//12809 12019//12019 12018//12018 -f 11938//11938 12030//12030 12784//12784 -f 12783//12783 12024//12024 11931//11931 -f 12783//12783 11931//11931 12784//12784 -f 12784//12784 11931//11931 11935//11935 -f 12784//12784 11935//11935 11938//11938 -f 12212//12212 12771//12771 12211//12211 -f 12211//12211 12771//12771 12770//12770 -f 12211//12211 12770//12770 12210//12210 -f 12210//12210 12770//12770 12209//12209 -f 12208//12208 12724//12724 12207//12207 -f 12207//12207 12724//12724 12723//12723 -f 12207//12207 12723//12723 12206//12206 -f 12038//12038 12043//12043 12718//12718 -f 12038//12038 12718//12718 12037//12037 -f 12037//12037 12718//12718 12717//12717 -f 12037//12037 12717//12717 12036//12036 -f 12711//12711 12202//12202 12203//12203 -f 12711//12711 12203//12203 12712//12712 -f 12712//12712 12203//12203 12204//12204 -f 12712//12712 12204//12204 12205//12205 -f 12358//12358 12713//12713 12359//12359 -f 12359//12359 12713//12713 12714//12714 -f 12368//12368 12710//12710 12369//12369 -f 12369//12369 12710//12710 12709//12709 -f 12369//12369 12709//12709 12366//12366 -f 12371//12371 12719//12719 12372//12372 -f 12372//12372 12719//12719 12720//12720 -f 12356//12356 12716//12716 12357//12357 -f 12357//12357 12716//12716 12715//12715 -f 12377//12377 12725//12725 12378//12378 -f 12378//12378 12725//12725 12726//12726 -f 12687//12687 12722//12722 12686//12686 -f 12686//12686 12722//12722 12721//12721 -f 12555//12555 12772//12772 12556//12556 -f 12556//12556 12772//12772 12773//12773 -f 12394//12394 12769//12769 12393//12393 -f 12393//12393 12769//12769 12768//12768 -f 12477//12477 12854//12854 12476//12476 -f 12476//12476 12854//12854 12853//12853 -f 12473//12473 12858//12858 12462//12462 -f 12462//12462 12858//12858 12852//12852 -f 12462//12462 12852//12852 12463//12463 -f 12468//12468 12844//12844 12469//12469 -f 12469//12469 12844//12844 12843//12843 -f 12464//12464 12848//12848 12465//12465 -f 12465//12465 12848//12848 12842//12842 -f 12454//12454 12834//12834 12453//12453 -f 12453//12453 12834//12834 12833//12833 -f 12448//12448 12838//12838 12449//12449 -f 12449//12449 12838//12838 12832//12832 -f 12353//12353 12824//12824 12354//12354 -f 12354//12354 12824//12824 12823//12823 -f 12437//12437 12828//12828 12436//12436 -f 12436//12436 12828//12828 12822//12822 -f 12679//12679 12785//12785 12403//12403 -f 12403//12403 12785//12785 12786//12786 -f 12403//12403 12786//12786 12402//12402 -f 12404//12404 12782//12782 12405//12405 -f 12405//12405 12782//12782 12781//12781 -f 12417//12417 12816//12816 12416//12416 -f 12416//12416 12816//12816 12810//12810 -f 12422//12422 12812//12812 12420//12420 -f 12420//12420 12812//12812 12811//12811 -f 12860//12860 12068//12068 12859//12859 -f 12859//12859 12068//12068 12067//12067 -f 12850//12850 11949//11949 12849//12849 -f 12849//12849 11949//11949 11947//11947 -f 12840//12840 12011//12011 12839//12839 -f 12839//12839 12011//12011 11974//11974 -f 12830//12830 11969//11969 12829//12829 -f 12829//12829 11969//11969 11967//11967 -f 12820//12820 11865//11865 12819//12819 -f 12819//12819 11865//11865 12017//12017 -f 12818//12818 12017//12017 12817//12817 -f 12817//12817 12017//12017 12015//12015 -f 12796//12796 11862//11862 12793//12793 -f 12793//12793 11862//11862 12044//12044 -f 12798//12798 12040//12040 12797//12797 -f 12797//12797 12040//12040 11890//11890 -f 12800//12800 11915//11915 12799//12799 -f 12799//12799 11915//11915 12035//12035 -f 12802//12802 12071//12071 12801//12801 -f 12801//12801 12071//12071 11906//11906 -f 12806//12806 12031//12031 12805//12805 -f 12805//12805 12031//12031 12032//12032 -f 12804//12804 12032//12032 12803//12803 -f 12803//12803 12032//12032 12029//12029 -f 12025//12025 12807//12807 12026//12026 -f 12026//12026 12807//12807 12808//12808 -f 12026//12026 12808//12808 12021//12021 -f 12021//12021 12808//12808 12020//12020 -f 13020//13020 12125//12125 12194//12194 -f 12195//12195 12112//12112 13017//13017 -f 12195//12195 13017//13017 12194//12194 -f 12194//12194 13017//13017 13018//13018 -f 12194//12194 13018//13018 13020//13020 -f 12121//12121 13019//13019 12117//12117 -f 12117//12117 13019//13019 13015//13015 -f 12117//12117 13015//13015 12118//12118 -f 12118//12118 13015//13015 13016//13016 -f 12118//12118 13016//13016 12244//12244 -f 12135//12135 12133//12133 13026//13026 -f 12234//12234 12136//12136 13022//13022 -f 13022//13022 12136//12136 12135//12135 -f 13022//13022 12135//12135 13023//13023 -f 13023//13023 12135//12135 13026//13026 -f 13025//13025 12128//12128 13024//13024 -f 13024//13024 12128//12128 12127//12127 -f 13024//13024 12127//12127 13021//13021 -f 13021//13021 12127//12127 11857//11857 -f 13021//13021 11857//11857 11856//11856 -f 13019//13019 12121//12121 12120//12120 -f 13019//13019 12120//12120 13020//13020 -f 13020//13020 12120//12120 12123//12123 -f 13020//13020 12123//12123 12125//12125 -f 13021//13021 11856//11856 12236//12236 -f 13021//13021 12236//12236 13022//13022 -f 13022//13022 12236//12236 12235//12235 -f 13022//13022 12235//12235 12234//12234 -f 12866//12866 11993//11993 11992//11992 -f 12866//12866 11992//11992 13381//13381 -f 13381//13381 11992//11992 11991//11991 -f 13381//13381 11991//11991 13382//13382 -f 13382//13382 11991//11991 11997//11997 -f 13382//13382 11997//11997 12868//12868 -f 12874//12874 12872//12872 13383//13383 -f 12874//12874 13383//13383 13384//13384 -f 13384//13384 13383//13383 13385//13385 -f 13384//13384 13385//13385 13386//13386 -f 13386//13386 13385//13385 12865//12865 -f 13386//13386 12865//12865 12866//12866 -f 12863//12863 11989//11989 11988//11988 -f 12863//12863 11988//11988 13387//13387 -f 13387//13387 11988//11988 12299//12299 -f 13387//13387 12299//12299 13388//13388 -f 13388//13388 12299//12299 11995//11995 -f 13388//13388 11995//11995 12865//12865 -f 12868//12868 13389//13389 13390//13390 -f 12874//12874 13384//13384 13391//13391 -f 13389//13389 13392//13392 13390//13390 -f 13390//13390 13392//13392 13391//13391 -f 13390//13390 13391//13391 13393//13393 -f 13393//13393 13391//13391 13384//13384 -f 13393//13393 13384//13384 13386//13386 -f 12868//12868 13390//13390 13382//13382 -f 13382//13382 13390//13390 13393//13393 -f 13382//13382 13393//13393 13381//13381 -f 13381//13381 13393//13393 13386//13386 -f 13381//13381 13386//13386 12866//12866 -f 13392//13392 12874//12874 13391//13391 -f 13389//13389 13394//13394 13392//13392 -f 13392//13392 13394//13394 12874//12874 -f 12865//12865 13385//13385 13395//13395 -f 12872//12872 13396//13396 13397//13397 -f 13385//13385 13398//13398 13395//13395 -f 13395//13395 13398//13398 13397//13397 -f 13395//13395 13397//13397 13399//13399 -f 13399//13399 13397//13397 13396//13396 -f 13399//13399 13396//13396 13400//13400 -f 12865//12865 13395//13395 13388//13388 -f 13388//13388 13395//13395 13399//13399 -f 13388//13388 13399//13399 13387//13387 -f 13387//13387 13399//13399 13400//13400 -f 13387//13387 13400//13400 12863//12863 -f 13398//13398 12872//12872 13397//13397 -f 13385//13385 13383//13383 13398//13398 -f 13398//13398 13383//13383 12872//12872 -f 12867//12867 12005//12005 12003//12003 -f 12867//12867 12003//12003 13401//13401 -f 13401//13401 12003//12003 12002//12002 -f 13401//13401 12002//12002 13402//13402 -f 13402//13402 12002//12002 12000//12000 -f 13402//13402 12000//12000 12870//12870 -f 12873//12873 12874//12874 13394//13394 -f 12873//12873 13394//13394 13403//13403 -f 13403//13403 13394//13394 13389//13389 -f 13403//13403 13389//13389 13404//13404 -f 13404//13404 13389//13389 12868//12868 -f 13404//13404 12868//12868 12867//12867 -f 12872//12872 12871//12871 13405//13405 -f 12872//12872 13405//13405 13396//13396 -f 13396//13396 13405//13405 13406//13406 -f 13396//13396 13406//13406 13400//13400 -f 13400//13400 13406//13406 12864//12864 -f 13400//13400 12864//12864 12863//12863 -f 12869//12869 12104//12104 12102//12102 -f 12869//12869 12102//12102 13407//13407 -f 13407//13407 12102//12102 12023//12023 -f 13407//13407 12023//12023 13408//13408 -f 13408//13408 12023//12023 12009//12009 -f 13408//13408 12009//12009 12864//12864 -f 12870//12870 13409//13409 13410//13410 -f 12873//12873 13403//13403 13411//13411 -f 13409//13409 13412//13412 13410//13410 -f 13410//13410 13412//13412 13411//13411 -f 13410//13410 13411//13411 13413//13413 -f 13413//13413 13411//13411 13403//13403 -f 13413//13413 13403//13403 13404//13404 -f 12870//12870 13410//13410 13402//13402 -f 13402//13402 13410//13410 13413//13413 -f 13402//13402 13413//13413 13401//13401 -f 13401//13401 13413//13413 13404//13404 -f 13401//13401 13404//13404 12867//12867 -f 13412//13412 12873//12873 13411//13411 -f 13409//13409 13414//13414 13412//13412 -f 13412//13412 13414//13414 12873//12873 -f 12864//12864 13406//13406 13415//13415 -f 12871//12871 13416//13416 13417//13417 -f 13406//13406 13418//13418 13415//13415 -f 13415//13415 13418//13418 13417//13417 -f 13415//13415 13417//13417 13419//13419 -f 13419//13419 13417//13417 13416//13416 -f 13419//13419 13416//13416 13420//13420 -f 12864//12864 13415//13415 13408//13408 -f 13408//13408 13415//13415 13419//13419 -f 13408//13408 13419//13419 13407//13407 -f 13407//13407 13419//13419 13420//13420 -f 13407//13407 13420//13420 12869//12869 -f 13418//13418 12871//12871 13417//13417 -f 13406//13406 13405//13405 13418//13418 -f 13418//13418 13405//13405 12871//12871 -f 12871//12871 12873//12873 13414//13414 -f 12871//12871 13414//13414 13416//13416 -f 13416//13416 13414//13414 13409//13409 -f 13416//13416 13409//13409 13420//13420 -f 13420//13420 13409//13409 12870//12870 -f 13420//13420 12870//12870 12869//12869 -f 12878//12878 12096//12096 12095//12095 -f 12878//12878 12095//12095 13421//13421 -f 13421//13421 12095//12095 12094//12094 -f 13421//13421 12094//12094 13422//13422 -f 13422//13422 12094//12094 12093//12093 -f 13422//13422 12093//12093 12879//12879 -f 12877//12877 12878//12878 13423//13423 -f 12877//12877 13423//13423 13424//13424 -f 13424//13424 13423//13423 13425//13425 -f 13424//13424 13425//13425 13426//13426 -f 13426//13426 13425//13425 12886//12886 -f 13426//13426 12886//12886 12884//12884 -f 12875//12875 12079//12079 12081//12081 -f 12875//12875 12081//12081 13427//13427 -f 13427//13427 12081//12081 12090//12090 -f 13427//13427 12090//12090 13428//13428 -f 13428//13428 12090//12090 12092//12092 -f 13428//13428 12092//12092 12877//12877 -f 12879//12879 13429//13429 13430//13430 -f 12886//12886 13425//13425 13431//13431 -f 13429//13429 13432//13432 13430//13430 -f 13430//13430 13432//13432 13431//13431 -f 13430//13430 13431//13431 13433//13433 -f 13433//13433 13431//13431 13425//13425 -f 13433//13433 13425//13425 13423//13423 -f 12879//12879 13430//13430 13422//13422 -f 13422//13422 13430//13430 13433//13433 -f 13422//13422 13433//13433 13421//13421 -f 13421//13421 13433//13433 13423//13423 -f 13421//13421 13423//13423 12878//12878 -f 13432//13432 12886//12886 13431//13431 -f 13429//13429 13434//13434 13432//13432 -f 13432//13432 13434//13434 12886//12886 -f 12877//12877 13424//13424 13435//13435 -f 12884//12884 13436//13436 13437//13437 -f 13424//13424 13438//13438 13435//13435 -f 13435//13435 13438//13438 13437//13437 -f 13435//13435 13437//13437 13439//13439 -f 13439//13439 13437//13437 13436//13436 -f 13439//13439 13436//13436 13440//13440 -f 12877//12877 13435//13435 13428//13428 -f 13428//13428 13435//13435 13439//13439 -f 13428//13428 13439//13439 13427//13427 -f 13427//13427 13439//13439 13440//13440 -f 13427//13427 13440//13440 12875//12875 -f 13438//13438 12884//12884 13437//13437 -f 13424//13424 13426//13426 13438//13438 -f 13438//13438 13426//13426 12884//12884 -f 12880//12880 12098//12098 12103//12103 -f 12880//12880 12103//12103 13441//13441 -f 13441//13441 12103//12103 12111//12111 -f 13441//13441 12111//12111 13442//13442 -f 13442//13442 12111//12111 12110//12110 -f 13442//13442 12110//12110 12881//12881 -f 12879//12879 12880//12880 13443//13443 -f 12879//12879 13443//13443 13429//13429 -f 13429//13429 13443//13443 13444//13444 -f 13429//13429 13444//13444 13434//13434 -f 13434//13434 13444//13444 12885//12885 -f 13434//13434 12885//12885 12886//12886 -f 12876//12876 12875//12875 13440//13440 -f 12876//12876 13440//13440 13445//13445 -f 13445//13445 13440//13440 13436//13436 -f 13445//13445 13436//13436 13446//13446 -f 13446//13446 13436//13436 12884//12884 -f 13446//13446 12884//12884 12883//12883 -f 12882//12882 12105//12105 11909//11909 -f 12882//12882 11909//11909 13447//13447 -f 13447//13447 11909//11909 11908//11908 -f 13447//13447 11908//11908 13448//13448 -f 13448//13448 11908//11908 12076//12076 -f 13448//13448 12076//12076 12876//12876 -f 12881//12881 13449//13449 13450//13450 -f 12885//12885 13444//13444 13451//13451 -f 13449//13449 13452//13452 13450//13450 -f 13450//13450 13452//13452 13451//13451 -f 13450//13450 13451//13451 13453//13453 -f 13453//13453 13451//13451 13444//13444 -f 13453//13453 13444//13444 13443//13443 -f 12881//12881 13450//13450 13442//13442 -f 13442//13442 13450//13450 13453//13453 -f 13442//13442 13453//13453 13441//13441 -f 13441//13441 13453//13453 13443//13443 -f 13441//13441 13443//13443 12880//12880 -f 13452//13452 12885//12885 13451//13451 -f 13449//13449 13454//13454 13452//13452 -f 13452//13452 13454//13454 12885//12885 -f 12876//12876 13445//13445 13455//13455 -f 12883//12883 13456//13456 13457//13457 -f 13445//13445 13458//13458 13455//13455 -f 13455//13455 13458//13458 13457//13457 -f 13455//13455 13457//13457 13459//13459 -f 13459//13459 13457//13457 13456//13456 -f 13459//13459 13456//13456 13460//13460 -f 12876//12876 13455//13455 13448//13448 -f 13448//13448 13455//13455 13459//13459 -f 13448//13448 13459//13459 13447//13447 -f 13447//13447 13459//13459 13460//13460 -f 13447//13447 13460//13460 12882//12882 -f 13458//13458 12883//12883 13457//13457 -f 13445//13445 13446//13446 13458//13458 -f 13458//13458 13446//13446 12883//12883 -f 12881//12881 12882//12882 13460//13460 -f 12881//12881 13460//13460 13449//13449 -f 13449//13449 13460//13460 13456//13456 -f 13449//13449 13456//13456 13454//13454 -f 13454//13454 13456//13456 12883//12883 -f 13454//13454 12883//12883 12885//12885 -f 13093//13093 13461//13461 13094//13094 -f 13094//13094 13461//13461 13462//13462 -f 13094//13094 13462//13462 13115//13115 -f 13115//13115 13462//13462 13463//13463 -f 13115//13115 13463//13463 13116//13116 -f 13116//13116 13463//13463 13464//13464 -f 13116//13116 13464//13464 13117//13117 -f 13117//13117 13464//13464 13465//13465 -f 13117//13117 13465//13465 13071//13071 -f 13071//13071 13465//13465 13466//13466 -f 13071//13071 13466//13466 13072//13072 -f 13072//13072 13466//13466 13467//13467 -f 13072//13072 13467//13467 13090//13090 -f 13090//13090 13467//13467 13468//13468 -f 13090//13090 13468//13468 13091//13091 -f 13091//13091 13468//13468 13469//13469 -f 13091//13091 13469//13469 13112//13112 -f 13112//13112 13469//13469 13470//13470 -f 13112//13112 13470//13470 13113//13113 -f 13113//13113 13470//13470 13471//13471 -f 13113//13113 13471//13471 13114//13114 -f 13114//13114 13471//13471 13472//13472 -f 13114//13114 13472//13472 13086//13086 -f 13086//13086 13472//13472 13473//13473 -f 13086//13086 13473//13473 13087//13087 -f 13087//13087 13473//13473 13474//13474 -f 13087//13087 13474//13474 13109//13109 -f 13109//13109 13474//13474 13475//13475 -f 13109//13109 13475//13475 13110//13110 -f 13110//13110 13475//13475 13476//13476 -f 13110//13110 13476//13476 13111//13111 -f 13111//13111 13476//13476 13477//13477 -f 13111//13111 13477//13477 13108//13108 -f 13108//13108 13477//13477 13478//13478 -f 13108//13108 13478//13478 13106//13106 -f 13106//13106 13478//13478 13479//13479 -f 13106//13106 13479//13479 13085//13085 -f 13085//13085 13479//13479 13480//13480 -f 13085//13085 13480//13480 13083//13083 -f 13083//13083 13480//13480 13481//13481 -f 13083//13083 13481//13481 13081//13081 -f 13081//13081 13481//13481 13482//13482 -f 13081//13081 13482//13482 13103//13103 -f 13103//13103 13482//13482 13483//13483 -f 13103//13103 13483//13483 13104//13104 -f 13104//13104 13483//13483 13484//13484 -f 13104//13104 13484//13484 13105//13105 -f 13105//13105 13484//13484 13485//13485 -f 13105//13105 13485//13485 13079//13079 -f 13079//13079 13485//13485 13486//13486 -f 13079//13079 13486//13486 13080//13080 -f 13080//13080 13486//13486 13487//13487 -f 13080//13080 13487//13487 13077//13077 -f 13077//13077 13487//13487 13488//13488 -f 13077//13077 13488//13488 13121//13121 -f 13121//13121 13488//13488 13489//13489 -f 13121//13121 13489//13489 13122//13122 -f 13122//13122 13489//13489 13490//13490 -f 13122//13122 13490//13490 13123//13123 -f 13123//13123 13490//13490 13491//13491 -f 13123//13123 13491//13491 13099//13099 -f 13099//13099 13491//13491 13492//13492 -f 13099//13099 13492//13492 13100//13100 -f 13100//13100 13492//13492 13493//13493 -f 13100//13100 13493//13493 13118//13118 -f 13118//13118 13493//13493 13494//13494 -f 13118//13118 13494//13494 13119//13119 -f 13119//13119 13494//13494 13495//13495 -f 13119//13119 13495//13495 13120//13120 -f 13120//13120 13495//13495 13496//13496 -f 13120//13120 13496//13496 13097//13097 -f 13097//13097 13496//13496 13497//13497 -f 13097//13097 13497//13497 13098//13098 -f 13098//13098 13497//13497 13498//13498 -f 13098//13098 13498//13498 13067//13067 -f 13067//13067 13498//13498 13499//13499 -f 13067//13067 13499//13499 13068//13068 -f 13068//13068 13499//13499 13500//13500 -f 13068//13068 13500//13500 13093//13093 -f 13093//13093 13500//13500 13461//13461 -f 13500//13500 13501//13501 13461//13461 -f 13461//13461 13501//13501 13502//13502 -f 13461//13461 13502//13502 13462//13462 -f 13462//13462 13502//13502 13503//13503 -f 13462//13462 13503//13503 13463//13463 -f 13463//13463 13503//13503 13504//13504 -f 13463//13463 13504//13504 13464//13464 -f 13464//13464 13504//13504 13505//13505 -f 13464//13464 13505//13505 13465//13465 -f 13465//13465 13505//13505 13506//13506 -f 13465//13465 13506//13506 13466//13466 -f 13466//13466 13506//13506 13507//13507 -f 13466//13466 13507//13507 13467//13467 -f 13467//13467 13507//13507 13508//13508 -f 13467//13467 13508//13508 13468//13468 -f 13468//13468 13508//13508 13509//13509 -f 13468//13468 13509//13509 13469//13469 -f 13469//13469 13509//13509 13510//13510 -f 13469//13469 13510//13510 13470//13470 -f 13470//13470 13510//13510 13511//13511 -f 13470//13470 13511//13511 13471//13471 -f 13471//13471 13511//13511 13512//13512 -f 13471//13471 13512//13512 13472//13472 -f 13472//13472 13512//13512 13513//13513 -f 13472//13472 13513//13513 13473//13473 -f 13473//13473 13513//13513 13514//13514 -f 13473//13473 13514//13514 13474//13474 -f 13474//13474 13514//13514 13515//13515 -f 13474//13474 13515//13515 13475//13475 -f 13475//13475 13515//13515 13516//13516 -f 13475//13475 13516//13516 13476//13476 -f 13476//13476 13516//13516 13517//13517 -f 13476//13476 13517//13517 13477//13477 -f 13477//13477 13517//13517 13518//13518 -f 13477//13477 13518//13518 13478//13478 -f 13478//13478 13518//13518 13519//13519 -f 13478//13478 13519//13519 13479//13479 -f 13479//13479 13519//13519 13520//13520 -f 13479//13479 13520//13520 13480//13480 -f 13480//13480 13520//13520 13521//13521 -f 13480//13480 13521//13521 13481//13481 -f 13481//13481 13521//13521 13522//13522 -f 13481//13481 13522//13522 13482//13482 -f 13482//13482 13522//13522 13523//13523 -f 13482//13482 13523//13523 13483//13483 -f 13483//13483 13523//13523 13524//13524 -f 13483//13483 13524//13524 13484//13484 -f 13484//13484 13524//13524 13525//13525 -f 13484//13484 13525//13525 13485//13485 -f 13485//13485 13525//13525 13526//13526 -f 13485//13485 13526//13526 13486//13486 -f 13486//13486 13526//13526 13527//13527 -f 13486//13486 13527//13527 13487//13487 -f 13487//13487 13527//13527 13528//13528 -f 13487//13487 13528//13528 13488//13488 -f 13488//13488 13528//13528 13529//13529 -f 13488//13488 13529//13529 13489//13489 -f 13489//13489 13529//13529 13530//13530 -f 13489//13489 13530//13530 13490//13490 -f 13490//13490 13530//13530 13531//13531 -f 13490//13490 13531//13531 13491//13491 -f 13491//13491 13531//13531 13532//13532 -f 13491//13491 13532//13532 13492//13492 -f 13492//13492 13532//13532 13533//13533 -f 13492//13492 13533//13533 13493//13493 -f 13493//13493 13533//13533 13534//13534 -f 13493//13493 13534//13534 13494//13494 -f 13494//13494 13534//13534 13535//13535 -f 13494//13494 13535//13535 13495//13495 -f 13495//13495 13535//13535 13536//13536 -f 13495//13495 13536//13536 13496//13496 -f 13496//13496 13536//13536 13537//13537 -f 13496//13496 13537//13537 13497//13497 -f 13497//13497 13537//13537 13538//13538 -f 13497//13497 13538//13538 13498//13498 -f 13498//13498 13538//13538 13539//13539 -f 13498//13498 13539//13539 13499//13499 -f 13499//13499 13539//13539 13540//13540 -f 13499//13499 13540//13540 13500//13500 -f 13500//13500 13540//13540 13501//13501 -f 13540//13540 13046//13046 13501//13501 -f 13501//13501 13046//13046 13049//13049 -f 13501//13501 13049//13049 13502//13502 -f 13502//13502 13049//13049 13048//13048 -f 13502//13502 13048//13048 13503//13503 -f 13503//13503 13048//13048 13051//13051 -f 13503//13503 13051//13051 13504//13504 -f 13504//13504 13051//13051 13050//13050 -f 13504//13504 13050//13050 13505//13505 -f 13505//13505 13050//13050 13053//13053 -f 13505//13505 13053//13053 13506//13506 -f 13506//13506 13053//13053 13052//13052 -f 13506//13506 13052//13052 13507//13507 -f 13507//13507 13052//13052 13055//13055 -f 13507//13507 13055//13055 13508//13508 -f 13508//13508 13055//13055 13054//13054 -f 13508//13508 13054//13054 13509//13509 -f 13509//13509 13054//13054 13057//13057 -f 13509//13509 13057//13057 13510//13510 -f 13510//13510 13057//13057 13056//13056 -f 13510//13510 13056//13056 13511//13511 -f 13511//13511 13056//13056 13059//13059 -f 13511//13511 13059//13059 13512//13512 -f 13512//13512 13059//13059 13058//13058 -f 13512//13512 13058//13058 13513//13513 -f 13513//13513 13058//13058 13061//13061 -f 13513//13513 13061//13061 13514//13514 -f 13514//13514 13061//13061 13060//13060 -f 13514//13514 13060//13060 13515//13515 -f 13515//13515 13060//13060 13063//13063 -f 13515//13515 13063//13063 13516//13516 -f 13516//13516 13063//13063 13062//13062 -f 13516//13516 13062//13062 13517//13517 -f 13517//13517 13062//13062 13066//13066 -f 13517//13517 13066//13066 13518//13518 -f 13518//13518 13066//13066 13065//13065 -f 13518//13518 13065//13065 13519//13519 -f 13519//13519 13065//13065 13064//13064 -f 13519//13519 13064//13064 13520//13520 -f 13520//13520 13064//13064 13027//13027 -f 13520//13520 13027//13027 13521//13521 -f 13521//13521 13027//13027 13029//13029 -f 13521//13521 13029//13029 13522//13522 -f 13522//13522 13029//13029 13028//13028 -f 13522//13522 13028//13028 13523//13523 -f 13523//13523 13028//13028 13031//13031 -f 13523//13523 13031//13031 13524//13524 -f 13524//13524 13031//13031 13030//13030 -f 13524//13524 13030//13030 13525//13525 -f 13525//13525 13030//13030 13033//13033 -f 13525//13525 13033//13033 13526//13526 -f 13526//13526 13033//13033 13032//13032 -f 13526//13526 13032//13032 13527//13527 -f 13527//13527 13032//13032 13035//13035 -f 13527//13527 13035//13035 13528//13528 -f 13528//13528 13035//13035 13034//13034 -f 13528//13528 13034//13034 13529//13529 -f 13529//13529 13034//13034 13037//13037 -f 13529//13529 13037//13037 13530//13530 -f 13530//13530 13037//13037 13036//13036 -f 13530//13530 13036//13036 13531//13531 -f 13531//13531 13036//13036 13039//13039 -f 13531//13531 13039//13039 13532//13532 -f 13532//13532 13039//13039 13038//13038 -f 13532//13532 13038//13038 13533//13533 -f 13533//13533 13038//13038 13041//13041 -f 13533//13533 13041//13041 13534//13534 -f 13534//13534 13041//13041 13040//13040 -f 13534//13534 13040//13040 13535//13535 -f 13535//13535 13040//13040 13043//13043 -f 13535//13535 13043//13043 13536//13536 -f 13536//13536 13043//13043 13042//13042 -f 13536//13536 13042//13042 13537//13537 -f 13537//13537 13042//13042 13045//13045 -f 13537//13537 13045//13045 13538//13538 -f 13538//13538 13045//13045 13044//13044 -f 13538//13538 13044//13044 13539//13539 -f 13539//13539 13044//13044 13047//13047 -f 13539//13539 13047//13047 13540//13540 -f 13540//13540 13047//13047 13046//13046 -f 13541//13541 13542//13542 13543//13543 -f 13544//13544 13545//13545 13542//13542 -f 13542//13542 13545//13545 13546//13546 -f 13542//13542 13546//13546 13543//13543 -f 13547//13547 13548//13548 13544//13544 -f 13544//13544 13548//13548 13549//13549 -f 13544//13544 13549//13549 13545//13545 -f 13550//13550 13551//13551 13547//13547 -f 13547//13547 13551//13551 13552//13552 -f 13547//13547 13552//13552 13548//13548 -f 13553//13553 13554//13554 13550//13550 -f 13550//13550 13554//13554 13555//13555 -f 13550//13550 13555//13555 13551//13551 -f 13556//13556 13557//13557 13553//13553 -f 13553//13553 13557//13557 13558//13558 -f 13553//13553 13558//13558 13554//13554 -f 13559//13559 13560//13560 13556//13556 -f 13556//13556 13560//13560 13561//13561 -f 13556//13556 13561//13561 13557//13557 -f 13562//13562 13563//13563 13559//13559 -f 13559//13559 13563//13563 13564//13564 -f 13559//13559 13564//13564 13560//13560 -f 13565//13565 13566//13566 13562//13562 -f 13562//13562 13566//13566 13567//13567 -f 13562//13562 13567//13567 13563//13563 -f 13568//13568 13569//13569 13565//13565 -f 13565//13565 13569//13569 13570//13570 -f 13565//13565 13570//13570 13566//13566 -f 13571//13571 13572//13572 13568//13568 -f 13568//13568 13572//13572 13573//13573 -f 13568//13568 13573//13573 13569//13569 -f 13574//13574 13575//13575 13571//13571 -f 13571//13571 13575//13575 13576//13576 -f 13571//13571 13576//13576 13572//13572 -f 13577//13577 13578//13578 13574//13574 -f 13574//13574 13578//13578 13579//13579 -f 13574//13574 13579//13579 13575//13575 -f 13580//13580 13581//13581 13577//13577 -f 13577//13577 13581//13581 13582//13582 -f 13577//13577 13582//13582 13578//13578 -f 13583//13583 13584//13584 13580//13580 -f 13580//13580 13584//13584 13585//13585 -f 13580//13580 13585//13585 13581//13581 -f 13586//13586 13587//13587 13583//13583 -f 13583//13583 13587//13587 13588//13588 -f 13583//13583 13588//13588 13584//13584 -f 13589//13589 13590//13590 13586//13586 -f 13586//13586 13590//13590 13591//13591 -f 13586//13586 13591//13591 13587//13587 -f 13592//13592 13593//13593 13589//13589 -f 13589//13589 13593//13593 13594//13594 -f 13589//13589 13594//13594 13590//13590 -f 13543//13543 13595//13595 13541//13541 -f 13541//13541 13595//13595 13596//13596 -f 13541//13541 13596//13596 13592//13592 -f 13592//13592 13596//13596 13597//13597 -f 13592//13592 13597//13597 13593//13593 -f 13598//13598 13599//13599 13600//13600 -f 13601//13601 13602//13602 13603//13603 -f 13603//13603 13602//13602 13604//13604 -f 13605//13605 13606//13606 13607//13607 -f 13608//13608 13609//13609 13610//13610 -f 13611//13611 13612//13612 13613//13613 -f 13613//13613 13612//13612 13614//13614 -f 13613//13613 13614//13614 13615//13615 -f 13616//13616 13617//13617 13611//13611 -f 13611//13611 13617//13617 13618//13618 -f 13611//13611 13618//13618 13612//13612 -f 13607//13607 13619//13619 13605//13605 -f 13605//13605 13619//13619 13620//13620 -f 13605//13605 13620//13620 13621//13621 -f 13615//13615 13614//13614 13604//13604 -f 13604//13604 13614//13614 13622//13622 -f 13604//13604 13622//13622 13603//13603 -f 13623//13623 13624//13624 13625//13625 -f 13625//13625 13624//13624 13626//13626 -f 13625//13625 13626//13626 13616//13616 -f 13616//13616 13626//13626 13627//13627 -f 13616//13616 13627//13627 13617//13617 -f 13628//13628 13629//13629 13625//13625 -f 13625//13625 13629//13629 13630//13630 -f 13625//13625 13630//13630 13623//13623 -f 13631//13631 13629//13629 13632//13632 -f 13632//13632 13629//13629 13628//13628 -f 13632//13632 13628//13628 13633//13633 -f 13633//13633 13628//13628 13634//13634 -f 13633//13633 13634//13634 13635//13635 -f 13635//13635 13634//13634 13609//13609 -f 13635//13635 13609//13609 13636//13636 -f 13636//13636 13609//13609 13608//13608 -f 13631//13631 13637//13637 13629//13629 -f 13629//13629 13637//13637 13638//13638 -f 13629//13629 13638//13638 13639//13639 -f 13639//13639 13638//13638 13640//13640 -f 13639//13639 13640//13640 13620//13620 -f 13620//13620 13640//13640 13641//13641 -f 13620//13620 13641//13641 13621//13621 -f 13630//13630 13642//13642 13623//13623 -f 13623//13623 13642//13642 13643//13643 -f 13623//13623 13643//13643 13644//13644 -f 13644//13644 13643//13643 13645//13645 -f 13644//13644 13645//13645 13646//13646 -f 13646//13646 13645//13645 13647//13647 -f 13646//13646 13647//13647 13648//13648 -f 13648//13648 13647//13647 13649//13649 -f 13648//13648 13649//13649 13606//13606 -f 13606//13606 13649//13649 13650//13650 -f 13606//13606 13650//13650 13607//13607 -f 13651//13651 13652//13652 13653//13653 -f 13654//13654 13655//13655 13656//13656 -f 13657//13657 13600//13600 13658//13658 -f 13656//13656 13655//13655 13652//13652 -f 13652//13652 13655//13655 13659//13659 -f 13652//13652 13659//13659 13653//13653 -f 13599//13599 13660//13660 13600//13600 -f 13600//13600 13660//13660 13661//13661 -f 13600//13600 13661//13661 13658//13658 -f 13605//13605 13662//13662 13606//13606 -f 13606//13606 13662//13662 13663//13663 -f 13606//13606 13663//13663 13664//13664 -f 13664//13664 13663//13663 13665//13665 -f 13656//13656 13666//13666 13654//13654 -f 13654//13654 13666//13666 13667//13667 -f 13654//13654 13667//13667 13599//13599 -f 13599//13599 13667//13667 13668//13668 -f 13599//13599 13668//13668 13660//13660 -f 13605//13605 13669//13669 13662//13662 -f 13662//13662 13669//13669 13670//13670 -f 13662//13662 13670//13670 13671//13671 -f 13671//13671 13670//13670 13672//13672 -f 13671//13671 13672//13672 13658//13658 -f 13658//13658 13672//13672 13673//13673 -f 13658//13658 13673//13673 13657//13657 -f 13653//13653 13674//13674 13651//13651 -f 13651//13651 13674//13674 13675//13675 -f 13651//13651 13675//13675 13663//13663 -f 13663//13663 13675//13675 13676//13676 -f 13663//13663 13676//13676 13665//13665 -f 13677//13677 13678//13678 13679//13679 -f 13679//13679 13680//13680 13677//13677 -f 13677//13677 13680//13680 13681//13681 -f 13677//13677 13681//13681 13600//13600 -f 13600//13600 13681//13681 13682//13682 -f 13600//13600 13682//13682 13598//13598 -f 13683//13683 13684//13684 13685//13685 -f 13685//13685 13684//13684 13608//13608 -f 13685//13685 13608//13608 13686//13686 -f 13683//13683 13685//13685 13687//13687 -f 13687//13687 13685//13685 13688//13688 -f 13687//13687 13688//13688 13689//13689 -f 13689//13689 13688//13688 13690//13690 -f 13689//13689 13690//13690 13691//13691 -f 13691//13691 13690//13690 13677//13677 -f 13677//13677 13690//13690 13692//13692 -f 13677//13677 13692//13692 13678//13678 -f 13692//13692 13693//13693 13678//13678 -f 13678//13678 13693//13693 13694//13694 -f 13678//13678 13694//13694 13695//13695 -f 13695//13695 13694//13694 13696//13696 -f 13695//13695 13696//13696 13697//13697 -f 13697//13697 13696//13696 13698//13698 -f 13697//13697 13698//13698 13699//13699 -f 13699//13699 13698//13698 13700//13700 -f 13699//13699 13700//13700 13701//13701 -f 13701//13701 13700//13700 13702//13702 -f 13701//13701 13702//13702 13703//13703 -f 13703//13703 13702//13702 13704//13704 -f 13610//13610 13601//13601 13608//13608 -f 13608//13608 13601//13601 13603//13603 -f 13608//13608 13603//13603 13686//13686 -f 13686//13686 13603//13603 13705//13705 -f 13686//13686 13705//13705 13706//13706 -f 13706//13706 13707//13707 13686//13686 -f 13686//13686 13707//13707 13708//13708 -f 13686//13686 13708//13708 13704//13704 -f 13704//13704 13708//13708 13709//13709 -f 13704//13704 13709//13709 13703//13703 -f 13710//13710 13711//13711 13712//13712 -f 13712//13712 13711//13711 13713//13713 -f 13712//13712 13713//13713 13714//13714 -f 13714//13714 13713//13713 13715//13715 -f 13714//13714 13715//13715 13716//13716 -f 13716//13716 13715//13715 13717//13717 -f 13716//13716 13717//13717 13718//13718 -f 13718//13718 13717//13717 13719//13719 -f 13718//13718 13719//13719 13720//13720 -f 13720//13720 13719//13719 13721//13721 -f 13720//13720 13721//13721 13722//13722 -f 13722//13722 13721//13721 13723//13723 -f 13722//13722 13723//13723 13724//13724 -f 13724//13724 13723//13723 13725//13725 -f 13724//13724 13725//13725 13726//13726 -f 13726//13726 13725//13725 13727//13727 -f 13726//13726 13727//13727 13728//13728 -f 13728//13728 13727//13727 13729//13729 -f 13728//13728 13729//13729 13730//13730 -f 13730//13730 13729//13729 13731//13731 -f 13730//13730 13731//13731 13732//13732 -f 13732//13732 13731//13731 13733//13733 -f 13732//13732 13733//13733 13734//13734 -f 13734//13734 13733//13733 13735//13735 -f 13734//13734 13735//13735 13736//13736 -f 13736//13736 13735//13735 13737//13737 -f 13736//13736 13737//13737 13738//13738 -f 13738//13738 13737//13737 13739//13739 -f 13738//13738 13739//13739 13740//13740 -f 13740//13740 13739//13739 13741//13741 -f 13740//13740 13741//13741 13742//13742 -f 13742//13742 13741//13741 13743//13743 -f 13742//13742 13743//13743 13744//13744 -f 13744//13744 13743//13743 13745//13745 -f 13744//13744 13745//13745 13746//13746 -f 13746//13746 13745//13745 13747//13747 -f 13746//13746 13747//13747 13748//13748 -f 13748//13748 13747//13747 13749//13749 -f 13748//13748 13749//13749 13750//13750 -f 13750//13750 13749//13749 13751//13751 -f 13750//13750 13751//13751 13752//13752 -f 13752//13752 13751//13751 13753//13753 -f 13752//13752 13753//13753 13754//13754 -f 13754//13754 13753//13753 13755//13755 -f 13754//13754 13755//13755 13756//13756 -f 13756//13756 13755//13755 13757//13757 -f 13756//13756 13757//13757 13758//13758 -f 13758//13758 13757//13757 13759//13759 -f 13758//13758 13759//13759 13760//13760 -f 13760//13760 13759//13759 13761//13761 -f 13760//13760 13761//13761 13762//13762 -f 13762//13762 13761//13761 13763//13763 -f 13762//13762 13763//13763 13764//13764 -f 13764//13764 13763//13763 13765//13765 -f 13764//13764 13765//13765 13766//13766 -f 13766//13766 13765//13765 13767//13767 -f 13766//13766 13767//13767 13768//13768 -f 13768//13768 13767//13767 13769//13769 -f 13768//13768 13769//13769 13770//13770 -f 13770//13770 13769//13769 13771//13771 -f 13770//13770 13771//13771 13772//13772 -f 13772//13772 13771//13771 13773//13773 -f 13772//13772 13773//13773 13774//13774 -f 13774//13774 13773//13773 13775//13775 -f 13774//13774 13775//13775 13776//13776 -f 13776//13776 13775//13775 13777//13777 -f 13776//13776 13777//13777 13778//13778 -f 13778//13778 13777//13777 13779//13779 -f 13778//13778 13779//13779 13780//13780 -f 13780//13780 13779//13779 13781//13781 -f 13780//13780 13781//13781 13782//13782 -f 13782//13782 13781//13781 13783//13783 -f 13782//13782 13783//13783 13784//13784 -f 13784//13784 13783//13783 13785//13785 -f 13784//13784 13785//13785 13710//13710 -f 13710//13710 13785//13785 13711//13711 -f 13786//13786 13787//13787 13788//13788 -f 13788//13788 13787//13787 13789//13789 -f 13789//13789 13787//13787 13790//13790 -f 13789//13789 13790//13790 13791//13791 -f 13791//13791 13790//13790 13792//13792 -f 13791//13791 13792//13792 13793//13793 -f 13793//13793 13792//13792 13794//13794 -f 13793//13793 13794//13794 13795//13795 -f 13795//13795 13794//13794 13796//13796 -f 13795//13795 13796//13796 13797//13797 -f 13797//13797 13798//13798 13799//13799 -f 13799//13799 13798//13798 13800//13800 -f 13799//13799 13800//13800 13801//13801 -f 13802//13802 13803//13803 13804//13804 -f 13788//13788 13805//13805 13786//13786 -f 13786//13786 13805//13805 13806//13806 -f 13786//13786 13806//13806 13807//13807 -f 13802//13802 13808//13808 13803//13803 -f 13803//13803 13808//13808 13809//13809 -f 13803//13803 13809//13809 13810//13810 -f 13804//13804 13811//13811 13802//13802 -f 13802//13802 13811//13811 13812//13812 -f 13802//13802 13812//13812 13813//13813 -f 13813//13813 13812//13812 13814//13814 -f 13813//13813 13814//13814 13800//13800 -f 13800//13800 13814//13814 13815//13815 -f 13800//13800 13815//13815 13801//13801 -f 13816//13816 13817//13817 13818//13818 -f 13818//13818 13817//13817 13819//13819 -f 13818//13818 13819//13819 13820//13820 -f 13820//13820 13819//13819 13821//13821 -f 13820//13820 13821//13821 13810//13810 -f 13810//13810 13821//13821 13822//13822 -f 13810//13810 13822//13822 13803//13803 -f 13823//13823 13824//13824 13825//13825 -f 13825//13825 13824//13824 13826//13826 -f 13808//13808 13786//13786 13809//13809 -f 13809//13809 13786//13786 13807//13807 -f 13809//13809 13807//13807 13827//13827 -f 13827//13827 13807//13807 13828//13828 -f 13827//13827 13828//13828 13829//13829 -f 13830//13830 13831//13831 13832//13832 -f 13832//13832 13831//13831 13826//13826 -f 13826//13826 13831//13831 13833//13833 -f 13826//13826 13833//13833 13825//13825 -f 13832//13832 13834//13834 13830//13830 -f 13830//13830 13834//13834 13835//13835 -f 13830//13830 13835//13835 13836//13836 -f 13836//13836 13835//13835 13829//13829 -f 13836//13836 13829//13829 13837//13837 -f 13837//13837 13829//13829 13828//13828 -f 13838//13838 13839//13839 13840//13840 -f 13840//13840 13839//13839 13841//13841 -f 13839//13839 13842//13842 13843//13843 -f 13843//13843 13842//13842 13844//13844 -f 13843//13843 13844//13844 13845//13845 -f 13845//13845 13844//13844 13846//13846 -f 13845//13845 13846//13846 13847//13847 -f 13847//13847 13846//13846 13848//13848 -f 13847//13847 13848//13848 13849//13849 -f 13849//13849 13848//13848 13850//13850 -f 13849//13849 13850//13850 13851//13851 -f 13851//13851 13850//13850 13852//13852 -f 13851//13851 13852//13852 13853//13853 -f 13853//13853 13852//13852 13854//13854 -f 13853//13853 13854//13854 13855//13855 -f 13818//13818 13823//13823 13816//13816 -f 13816//13816 13823//13823 13825//13825 -f 13816//13816 13825//13825 13856//13856 -f 13856//13856 13825//13825 13857//13857 -f 13855//13855 13854//13854 13858//13858 -f 13858//13858 13854//13854 13859//13859 -f 13858//13858 13859//13859 13860//13860 -f 13840//13840 13861//13861 13838//13838 -f 13838//13838 13861//13861 13862//13862 -f 13838//13838 13862//13862 13863//13863 -f 13863//13863 13862//13862 13864//13864 -f 13863//13863 13864//13864 13865//13865 -f 13865//13865 13864//13864 13866//13866 -f 13866//13866 13857//13857 13865//13865 -f 13865//13865 13857//13857 13825//13825 -f 13865//13865 13825//13825 13859//13859 -f 13859//13859 13825//13825 13867//13867 -f 13859//13859 13867//13867 13860//13860 -f 13839//13839 13843//13843 13841//13841 -f 13841//13841 13843//13843 13868//13868 -f 13841//13841 13868//13868 13869//13869 -f 13869//13869 13870//13870 13841//13841 -f 13841//13841 13870//13870 13871//13871 -f 13841//13841 13871//13871 13872//13872 -f 13873//13873 13874//13874 13875//13875 -f 13876//13876 13877//13877 13878//13878 -f 13879//13879 13841//13841 13880//13880 -f 13881//13881 13882//13882 13883//13883 -f 13878//13878 13877//13877 13874//13874 -f 13874//13874 13877//13877 13884//13884 -f 13874//13874 13884//13884 13875//13875 -f 13797//13797 13799//13799 13795//13795 -f 13795//13795 13799//13799 13885//13885 -f 13795//13795 13885//13885 13886//13886 -f 13878//13878 13887//13887 13876//13876 -f 13876//13876 13887//13887 13888//13888 -f 13876//13876 13888//13888 13889//13889 -f 13889//13889 13888//13888 13890//13890 -f 13889//13889 13890//13890 13872//13872 -f 13872//13872 13890//13890 13891//13891 -f 13872//13872 13891//13891 13841//13841 -f 13841//13841 13891//13891 13892//13892 -f 13841//13841 13892//13892 13880//13880 -f 13882//13882 13795//13795 13883//13883 -f 13883//13883 13795//13795 13886//13886 -f 13883//13883 13886//13886 13893//13893 -f 13893//13893 13886//13886 13894//13894 -f 13893//13893 13894//13894 13895//13895 -f 13895//13895 13894//13894 13896//13896 -f 13895//13895 13896//13896 13880//13880 -f 13880//13880 13896//13896 13897//13897 -f 13880//13880 13897//13897 13879//13879 -f 13875//13875 13898//13898 13873//13873 -f 13873//13873 13898//13898 13899//13899 -f 13873//13873 13899//13899 13883//13883 -f 13883//13883 13899//13899 13900//13900 -f 13883//13883 13900//13900 13881//13881 -f 13815//13815 13814//13814 13901//13901 -f 13901//13901 13902//13902 13815//13815 -f 13815//13815 13902//13902 13903//13903 -f 13815//13815 13903//13903 13801//13801 -f 13801//13801 13903//13903 13904//13904 -f 13801//13801 13904//13904 13799//13799 -f 13799//13799 13904//13904 13905//13905 -f 13799//13799 13905//13905 13885//13885 -f 13905//13905 13906//13906 13885//13885 -f 13885//13885 13906//13906 13907//13907 -f 13885//13885 13907//13907 13886//13886 -f 13907//13907 13908//13908 13886//13886 -f 13886//13886 13908//13908 13909//13909 -f 13886//13886 13909//13909 13894//13894 -f 13909//13909 13910//13910 13894//13894 -f 13894//13894 13910//13910 13911//13911 -f 13894//13894 13911//13911 13896//13896 -f 13911//13911 13912//13912 13896//13896 -f 13896//13896 13912//13912 13913//13913 -f 13896//13896 13913//13913 13897//13897 -f 13913//13913 13914//13914 13897//13897 -f 13897//13897 13914//13914 13915//13915 -f 13897//13897 13915//13915 13879//13879 -f 13915//13915 13916//13916 13879//13879 -f 13879//13879 13916//13916 13917//13917 -f 13879//13879 13917//13917 13841//13841 -f 13917//13917 13918//13918 13841//13841 -f 13841//13841 13918//13918 13919//13919 -f 13841//13841 13919//13919 13840//13840 -f 13919//13919 13920//13920 13840//13840 -f 13840//13840 13920//13920 13921//13921 -f 13840//13840 13921//13921 13861//13861 -f 13921//13921 13922//13922 13861//13861 -f 13861//13861 13922//13922 13923//13923 -f 13861//13861 13923//13923 13862//13862 -f 13923//13923 13924//13924 13862//13862 -f 13862//13862 13924//13924 13925//13925 -f 13862//13862 13925//13925 13864//13864 -f 13925//13925 13926//13926 13864//13864 -f 13864//13864 13926//13926 13927//13927 -f 13864//13864 13927//13927 13866//13866 -f 13927//13927 13928//13928 13866//13866 -f 13866//13866 13928//13928 13929//13929 -f 13866//13866 13929//13929 13857//13857 -f 13929//13929 13930//13930 13857//13857 -f 13857//13857 13930//13930 13931//13931 -f 13857//13857 13931//13931 13856//13856 -f 13856//13856 13931//13931 13932//13932 -f 13856//13856 13932//13932 13816//13816 -f 13816//13816 13932//13932 13933//13933 -f 13816//13816 13933//13933 13817//13817 -f 13933//13933 13934//13934 13817//13817 -f 13817//13817 13934//13934 13935//13935 -f 13817//13817 13935//13935 13819//13819 -f 13935//13935 13936//13936 13819//13819 -f 13819//13819 13936//13936 13937//13937 -f 13819//13819 13937//13937 13821//13821 -f 13937//13937 13938//13938 13821//13821 -f 13821//13821 13938//13938 13939//13939 -f 13821//13821 13939//13939 13822//13822 -f 13939//13939 13940//13940 13822//13822 -f 13822//13822 13940//13940 13941//13941 -f 13822//13822 13941//13941 13803//13803 -f 13941//13941 13942//13942 13803//13803 -f 13803//13803 13942//13942 13943//13943 -f 13803//13803 13943//13943 13804//13804 -f 13943//13943 13944//13944 13804//13804 -f 13804//13804 13944//13944 13945//13945 -f 13804//13804 13945//13945 13811//13811 -f 13945//13945 13946//13946 13811//13811 -f 13811//13811 13946//13946 13947//13947 -f 13811//13811 13947//13947 13812//13812 -f 13947//13947 13948//13948 13812//13812 -f 13812//13812 13948//13948 13949//13949 -f 13812//13812 13949//13949 13814//13814 -f 13814//13814 13949//13949 13950//13950 -f 13814//13814 13950//13950 13901//13901 -f 13951//13951 13952//13952 13953//13953 -f 13954//13954 13955//13955 13956//13956 -f 13956//13956 13955//13955 13957//13957 -f 13956//13956 13957//13957 13958//13958 -f 13958//13958 13957//13957 13959//13959 -f 13958//13958 13959//13959 13953//13953 -f 13953//13953 13959//13959 13960//13960 -f 13953//13953 13960//13960 13951//13951 -f 13961//13961 13962//13962 13963//13963 -f 13963//13963 13962//13962 13964//13964 -f 13963//13963 13964//13964 13965//13965 -f 13965//13965 13964//13964 13966//13966 -f 13965//13965 13966//13966 13954//13954 -f 13954//13954 13966//13966 13967//13967 -f 13954//13954 13967//13967 13955//13955 -f 13968//13968 13969//13969 13970//13970 -f 13970//13970 13969//13969 13971//13971 -f 13970//13970 13971//13971 13972//13972 -f 13972//13972 13971//13971 13973//13973 -f 13972//13972 13973//13973 13961//13961 -f 13961//13961 13973//13973 13974//13974 -f 13961//13961 13974//13974 13962//13962 -f 13951//13951 13975//13975 13952//13952 -f 13952//13952 13975//13975 13976//13976 -f 13952//13952 13976//13976 13977//13977 -f 13977//13977 13976//13976 13978//13978 -f 13977//13977 13978//13978 13979//13979 -f 13979//13979 13978//13978 13980//13980 -f 13979//13979 13980//13980 13981//13981 -f 13982//13982 13983//13983 13984//13984 -f 13984//13984 13983//13983 13985//13985 -f 13984//13984 13985//13985 13986//13986 -f 13986//13986 13985//13985 13987//13987 -f 13986//13986 13987//13987 13968//13968 -f 13968//13968 13987//13987 13988//13988 -f 13968//13968 13988//13988 13969//13969 -f 13980//13980 13989//13989 13981//13981 -f 13981//13981 13989//13989 13990//13990 -f 13981//13981 13990//13990 13991//13991 -f 13991//13991 13990//13990 13992//13992 -f 13991//13991 13992//13992 13993//13993 -f 13993//13993 13992//13992 13994//13994 -f 13993//13993 13994//13994 13982//13982 -f 13982//13982 13994//13994 13995//13995 -f 13982//13982 13995//13995 13983//13983 -f 13996//13996 13952//13952 13997//13997 -f 13997//13997 13952//13952 13977//13977 -f 13997//13997 13977//13977 13998//13998 -f 13998//13998 13977//13977 13979//13979 -f 13998//13998 13979//13979 13999//13999 -f 13999//13999 13979//13979 13981//13981 -f 13999//13999 13981//13981 14000//14000 -f 14000//14000 13981//13981 13991//13991 -f 14000//14000 13991//13991 14001//14001 -f 14001//14001 13991//13991 13993//13993 -f 14001//14001 13993//13993 14002//14002 -f 14002//14002 13993//13993 13982//13982 -f 14002//14002 13982//13982 14003//14003 -f 14003//14003 13982//13982 13984//13984 -f 14003//14003 13984//13984 14004//14004 -f 14004//14004 13984//13984 13986//13986 -f 14004//14004 13986//13986 14005//14005 -f 14005//14005 13986//13986 13968//13968 -f 14005//14005 13968//13968 14006//14006 -f 14006//14006 13968//13968 13970//13970 -f 14006//14006 13970//13970 14007//14007 -f 14007//14007 13970//13970 13972//13972 -f 14007//14007 13972//13972 14008//14008 -f 14008//14008 13972//13972 13961//13961 -f 14008//14008 13961//13961 14009//14009 -f 14009//14009 13961//13961 13963//13963 -f 14009//14009 13963//13963 14010//14010 -f 14010//14010 13963//13963 13965//13965 -f 14010//14010 13965//13965 14011//14011 -f 14011//14011 13965//13965 13954//13954 -f 14011//14011 13954//13954 14012//14012 -f 14012//14012 13954//13954 13956//13956 -f 14012//14012 13956//13956 14013//14013 -f 14013//14013 13956//13956 13958//13958 -f 14013//14013 13958//13958 14014//14014 -f 14014//14014 13958//13958 13953//13953 -f 14014//14014 13953//13953 13996//13996 -f 13996//13996 13953//13953 13952//13952 -f 14015//14015 14013//14013 14016//14016 -f 14016//14016 14013//14013 14014//14014 -f 14016//14016 14014//14014 14017//14017 -f 14017//14017 14014//14014 13996//13996 -f 14017//14017 13996//13996 14018//14018 -f 14019//14019 14007//14007 14020//14020 -f 14020//14020 14007//14007 14008//14008 -f 14020//14020 14008//14008 14021//14021 -f 14008//14008 14009//14009 14021//14021 -f 14021//14021 14009//14009 14010//14010 -f 14021//14021 14010//14010 14022//14022 -f 14022//14022 14010//14010 14011//14011 -f 14022//14022 14011//14011 14015//14015 -f 14015//14015 14011//14011 14012//14012 -f 14015//14015 14012//14012 14013//14013 -f 14023//14023 14004//14004 14024//14024 -f 14024//14024 14004//14004 14005//14005 -f 14024//14024 14005//14005 14019//14019 -f 14019//14019 14005//14005 14006//14006 -f 14019//14019 14006//14006 14007//14007 -f 14025//14025 14001//14001 14026//14026 -f 14026//14026 14001//14001 14002//14002 -f 14026//14026 14002//14002 14023//14023 -f 14023//14023 14002//14002 14003//14003 -f 14023//14023 14003//14003 14004//14004 -f 13996//13996 13997//13997 14018//14018 -f 14018//14018 13997//13997 13998//13998 -f 14018//14018 13998//13998 14027//14027 -f 14027//14027 13998//13998 13999//13999 -f 14027//14027 13999//13999 14025//14025 -f 14025//14025 13999//13999 14000//14000 -f 14025//14025 14000//14000 14001//14001 -f 14028//14028 14017//14017 14029//14029 -f 14029//14029 14017//14017 14018//14018 -f 14029//14029 14018//14018 14030//14030 -f 14030//14030 14018//14018 14027//14027 -f 14030//14030 14027//14027 14031//14031 -f 14031//14031 14027//14027 14025//14025 -f 14031//14031 14025//14025 14032//14032 -f 14032//14032 14025//14025 14026//14026 -f 14032//14032 14026//14026 14033//14033 -f 14033//14033 14026//14026 14023//14023 -f 14033//14033 14023//14023 14034//14034 -f 14034//14034 14023//14023 14024//14024 -f 14034//14034 14024//14024 14035//14035 -f 14035//14035 14024//14024 14019//14019 -f 14035//14035 14019//14019 14036//14036 -f 14036//14036 14019//14019 14020//14020 -f 14036//14036 14020//14020 14037//14037 -f 14037//14037 14020//14020 14021//14021 -f 14037//14037 14021//14021 14038//14038 -f 14038//14038 14021//14021 14022//14022 -f 14038//14038 14022//14022 14039//14039 -f 14039//14039 14022//14022 14015//14015 -f 14039//14039 14015//14015 14040//14040 -f 14040//14040 14015//14015 14016//14016 -f 14040//14040 14016//14016 14028//14028 -f 14028//14028 14016//14016 14017//14017 -f 14036//14036 13571//13571 14035//14035 -f 14035//14035 13571//13571 13568//13568 -f 14035//14035 13568//13568 14034//14034 -f 14038//14038 13580//13580 14037//14037 -f 14037//14037 13580//13580 13577//13577 -f 14037//14037 13577//13577 14036//14036 -f 14036//14036 13577//13577 13574//13574 -f 14036//14036 13574//13574 13571//13571 -f 14040//14040 13589//13589 14039//14039 -f 14039//14039 13589//13589 13586//13586 -f 14039//14039 13586//13586 14038//14038 -f 14038//14038 13586//13586 13583//13583 -f 14038//14038 13583//13583 13580//13580 -f 14030//14030 13544//13544 14029//14029 -f 14029//14029 13544//13544 13542//13542 -f 14029//14029 13542//13542 14028//14028 -f 14028//14028 13542//13542 13541//13541 -f 14028//14028 13541//13541 14040//14040 -f 14040//14040 13541//13541 13592//13592 -f 14040//14040 13592//13592 13589//13589 -f 14032//14032 13553//13553 14031//14031 -f 14031//14031 13553//13553 13550//13550 -f 14031//14031 13550//13550 14030//14030 -f 14030//14030 13550//13550 13547//13547 -f 14030//14030 13547//13547 13544//13544 -f 13568//13568 13565//13565 14034//14034 -f 14034//14034 13565//13565 13562//13562 -f 14034//14034 13562//13562 14033//14033 -f 14033//14033 13562//13562 13559//13559 -f 14033//14033 13559//13559 14032//14032 -f 14032//14032 13559//13559 13556//13556 -f 14032//14032 13556//13556 13553//13553 -f 14041//14041 13790//13790 14042//14042 -f 14042//14042 13790//13790 13787//13787 -f 14042//14042 13787//13787 14043//14043 -f 14043//14043 13787//13787 13786//13786 -f 14043//14043 13786//13786 14044//14044 -f 14044//14044 13786//13786 13808//13808 -f 14044//14044 13808//13808 14045//14045 -f 14045//14045 13808//13808 13802//13802 -f 14045//14045 13802//13802 14046//14046 -f 14046//14046 13802//13802 13813//13813 -f 14046//14046 13813//13813 14047//14047 -f 14047//14047 13813//13813 13800//13800 -f 14047//14047 13800//13800 14048//14048 -f 14048//14048 13800//13800 13798//13798 -f 14048//14048 13798//13798 14049//14049 -f 14049//14049 13798//13798 13797//13797 -f 14049//14049 13797//13797 14050//14050 -f 14050//14050 13797//13797 13796//13796 -f 14050//14050 13796//13796 14051//14051 -f 14051//14051 13796//13796 13794//13794 -f 14051//14051 13794//13794 14052//14052 -f 14052//14052 13794//13794 13792//13792 -f 14052//14052 13792//13792 14041//14041 -f 14041//14041 13792//13792 13790//13790 -f 14046//14046 14053//14053 14045//14045 -f 14045//14045 14053//14053 14054//14054 -f 14045//14045 14054//14054 14044//14044 -f 14044//14044 14054//14054 14055//14055 -f 14044//14044 14055//14055 14043//14043 -f 14043//14043 14055//14055 14056//14056 -f 14043//14043 14056//14056 14042//14042 -f 14042//14042 14056//14056 14057//14057 -f 14042//14042 14057//14057 14041//14041 -f 14041//14041 14057//14057 14058//14058 -f 14041//14041 14058//14058 14052//14052 -f 14052//14052 14058//14058 14059//14059 -f 14052//14052 14059//14059 14051//14051 -f 14051//14051 14059//14059 14060//14060 -f 14051//14051 14060//14060 14050//14050 -f 14050//14050 14060//14060 14061//14061 -f 14050//14050 14061//14061 14049//14049 -f 14049//14049 14061//14061 14062//14062 -f 14049//14049 14062//14062 14048//14048 -f 14048//14048 14062//14062 14063//14063 -f 14048//14048 14063//14063 14047//14047 -f 14047//14047 14063//14063 14064//14064 -f 14047//14047 14064//14064 14046//14046 -f 14046//14046 14064//14064 14053//14053 -f 14054//14054 13685//13685 14055//14055 -f 14055//14055 13685//13685 13686//13686 -f 14055//14055 13686//13686 14056//14056 -f 14056//14056 13686//13686 13704//13704 -f 14056//14056 13704//13704 14057//14057 -f 14057//14057 13704//13704 13702//13702 -f 14057//14057 13702//13702 14058//14058 -f 14058//14058 13702//13702 13700//13700 -f 14058//14058 13700//13700 14059//14059 -f 14059//14059 13700//13700 13698//13698 -f 14059//14059 13698//13698 14060//14060 -f 14060//14060 13698//13698 13696//13696 -f 14060//14060 13696//13696 14061//14061 -f 14061//14061 13696//13696 13694//13694 -f 14061//14061 13694//13694 14062//14062 -f 14062//14062 13694//13694 13693//13693 -f 14062//14062 13693//13693 14063//14063 -f 14063//14063 13693//13693 13692//13692 -f 14063//14063 13692//13692 14064//14064 -f 14064//14064 13692//13692 13690//13690 -f 14064//14064 13690//13690 14053//14053 -f 14053//14053 13690//13690 13688//13688 -f 14053//14053 13688//13688 14054//14054 -f 14054//14054 13688//13688 13685//13685 -f 14065//14065 13883//13883 14066//14066 -f 14066//14066 13883//13883 13893//13893 -f 14066//14066 13893//13893 14067//14067 -f 14067//14067 13893//13893 13895//13895 -f 14067//14067 13895//13895 14068//14068 -f 14068//14068 13895//13895 13880//13880 -f 14068//14068 13880//13880 14069//14069 -f 14069//14069 13880//13880 13892//13892 -f 14069//14069 13892//13892 14070//14070 -f 14070//14070 13892//13892 13891//13891 -f 14070//14070 13891//13891 14071//14071 -f 14071//14071 13891//13891 13890//13890 -f 14071//14071 13890//13890 14072//14072 -f 14072//14072 13890//13890 13888//13888 -f 14072//14072 13888//13888 14073//14073 -f 14073//14073 13888//13888 13887//13887 -f 14073//14073 13887//13887 14074//14074 -f 14074//14074 13887//13887 13878//13878 -f 14074//14074 13878//13878 14075//14075 -f 14075//14075 13878//13878 13874//13874 -f 14075//14075 13874//13874 14076//14076 -f 14076//14076 13874//13874 13873//13873 -f 14076//14076 13873//13873 14065//14065 -f 14065//14065 13873//13873 13883//13883 -f 14070//14070 14077//14077 14069//14069 -f 14069//14069 14077//14077 14078//14078 -f 14069//14069 14078//14078 14068//14068 -f 14068//14068 14078//14078 14079//14079 -f 14068//14068 14079//14079 14067//14067 -f 14067//14067 14079//14079 14080//14080 -f 14067//14067 14080//14080 14066//14066 -f 14066//14066 14080//14080 14081//14081 -f 14066//14066 14081//14081 14065//14065 -f 14065//14065 14081//14081 14082//14082 -f 14065//14065 14082//14082 14076//14076 -f 14076//14076 14082//14082 14083//14083 -f 14076//14076 14083//14083 14075//14075 -f 14075//14075 14083//14083 14084//14084 -f 14075//14075 14084//14084 14074//14074 -f 14074//14074 14084//14084 14085//14085 -f 14074//14074 14085//14085 14073//14073 -f 14073//14073 14085//14085 14086//14086 -f 14073//14073 14086//14086 14072//14072 -f 14072//14072 14086//14086 14087//14087 -f 14072//14072 14087//14087 14071//14071 -f 14071//14071 14087//14087 14088//14088 -f 14071//14071 14088//14088 14070//14070 -f 14070//14070 14088//14088 14077//14077 -f 14078//14078 13663//13663 14079//14079 -f 14079//14079 13663//13663 13662//13662 -f 14079//14079 13662//13662 14080//14080 -f 14080//14080 13662//13662 13671//13671 -f 14080//14080 13671//13671 14081//14081 -f 14081//14081 13671//13671 13658//13658 -f 14081//14081 13658//13658 14082//14082 -f 14082//14082 13658//13658 13661//13661 -f 14082//14082 13661//13661 14083//14083 -f 14083//14083 13661//13661 13660//13660 -f 14083//14083 13660//13660 14084//14084 -f 14084//14084 13660//13660 13668//13668 -f 14084//14084 13668//13668 14085//14085 -f 14085//14085 13668//13668 13667//13667 -f 14085//14085 13667//13667 14086//14086 -f 14086//14086 13667//13667 13666//13666 -f 14086//14086 13666//13666 14087//14087 -f 14087//14087 13666//13666 13656//13656 -f 14087//14087 13656//13656 14088//14088 -f 14088//14088 13656//13656 13652//13652 -f 14088//14088 13652//13652 14077//14077 -f 14077//14077 13652//13652 13651//13651 -f 14077//14077 13651//13651 14078//14078 -f 14078//14078 13651//13651 13663//13663 -f 14089//14089 13865//13865 14090//14090 -f 14090//14090 13865//13865 13859//13859 -f 14090//14090 13859//13859 14091//14091 -f 14091//14091 13859//13859 13854//13854 -f 14091//14091 13854//13854 14092//14092 -f 14092//14092 13854//13854 13852//13852 -f 14092//14092 13852//13852 14093//14093 -f 14093//14093 13852//13852 13850//13850 -f 14093//14093 13850//13850 14094//14094 -f 14094//14094 13850//13850 13848//13848 -f 14094//14094 13848//13848 14095//14095 -f 14095//14095 13848//13848 13846//13846 -f 14095//14095 13846//13846 14096//14096 -f 14096//14096 13846//13846 13844//13844 -f 14096//14096 13844//13844 14097//14097 -f 14097//14097 13844//13844 13842//13842 -f 14097//14097 13842//13842 14098//14098 -f 14098//14098 13842//13842 13839//13839 -f 14098//14098 13839//13839 14099//14099 -f 14099//14099 13839//13839 13838//13838 -f 14099//14099 13838//13838 14100//14100 -f 14100//14100 13838//13838 13863//13863 -f 14100//14100 13863//13863 14089//14089 -f 14089//14089 13863//13863 13865//13865 -f 14094//14094 14101//14101 14093//14093 -f 14093//14093 14101//14101 14102//14102 -f 14093//14093 14102//14102 14092//14092 -f 14092//14092 14102//14102 14103//14103 -f 14092//14092 14103//14103 14091//14091 -f 14091//14091 14103//14103 14104//14104 -f 14091//14091 14104//14104 14090//14090 -f 14090//14090 14104//14104 14105//14105 -f 14090//14090 14105//14105 14089//14089 -f 14089//14089 14105//14105 14106//14106 -f 14089//14089 14106//14106 14100//14100 -f 14100//14100 14106//14106 14107//14107 -f 14100//14100 14107//14107 14099//14099 -f 14099//14099 14107//14107 14108//14108 -f 14099//14099 14108//14108 14098//14098 -f 14098//14098 14108//14108 14109//14109 -f 14098//14098 14109//14109 14097//14097 -f 14097//14097 14109//14109 14110//14110 -f 14097//14097 14110//14110 14096//14096 -f 14096//14096 14110//14110 14111//14111 -f 14096//14096 14111//14111 14095//14095 -f 14095//14095 14111//14111 14112//14112 -f 14095//14095 14112//14112 14094//14094 -f 14094//14094 14112//14112 14101//14101 -f 14102//14102 13645//13645 14103//14103 -f 14103//14103 13645//13645 13643//13643 -f 14103//14103 13643//13643 14104//14104 -f 14104//14104 13643//13643 13642//13642 -f 14104//14104 13642//13642 14105//14105 -f 14105//14105 13642//13642 13630//13630 -f 14105//14105 13630//13630 14106//14106 -f 14106//14106 13630//13630 13629//13629 -f 14106//14106 13629//13629 14107//14107 -f 14107//14107 13629//13629 13639//13639 -f 14107//14107 13639//13639 14108//14108 -f 14108//14108 13639//13639 13620//13620 -f 14108//14108 13620//13620 14109//14109 -f 14109//14109 13620//13620 13619//13619 -f 14109//14109 13619//13619 14110//14110 -f 14110//14110 13619//13619 13607//13607 -f 14110//14110 13607//13607 14111//14111 -f 14111//14111 13607//13607 13650//13650 -f 14111//14111 13650//13650 14112//14112 -f 14112//14112 13650//13650 13649//13649 -f 14112//14112 13649//13649 14101//14101 -f 14101//14101 13649//13649 13647//13647 -f 14101//14101 13647//13647 14102//14102 -f 14102//14102 13647//13647 13645//13645 -f 14113//14113 13829//13829 14114//14114 -f 14114//14114 13829//13829 13835//13835 -f 14114//14114 13835//13835 14115//14115 -f 14115//14115 13835//13835 13834//13834 -f 14115//14115 13834//13834 14116//14116 -f 14116//14116 13834//13834 13832//13832 -f 14116//14116 13832//13832 14117//14117 -f 14117//14117 13832//13832 13826//13826 -f 14117//14117 13826//13826 14118//14118 -f 14118//14118 13826//13826 13824//13824 -f 14118//14118 13824//13824 14119//14119 -f 14119//14119 13824//13824 13823//13823 -f 14119//14119 13823//13823 14120//14120 -f 14120//14120 13823//13823 13818//13818 -f 14120//14120 13818//13818 14121//14121 -f 14121//14121 13818//13818 13820//13820 -f 14121//14121 13820//13820 14122//14122 -f 14122//14122 13820//13820 13810//13810 -f 14122//14122 13810//13810 14123//14123 -f 14123//14123 13810//13810 13809//13809 -f 14123//14123 13809//13809 14124//14124 -f 14124//14124 13809//13809 13827//13827 -f 14124//14124 13827//13827 14113//14113 -f 14113//14113 13827//13827 13829//13829 -f 14118//14118 14125//14125 14117//14117 -f 14117//14117 14125//14125 14126//14126 -f 14117//14117 14126//14126 14116//14116 -f 14116//14116 14126//14126 14127//14127 -f 14116//14116 14127//14127 14115//14115 -f 14115//14115 14127//14127 14128//14128 -f 14115//14115 14128//14128 14114//14114 -f 14114//14114 14128//14128 14129//14129 -f 14114//14114 14129//14129 14113//14113 -f 14113//14113 14129//14129 14130//14130 -f 14113//14113 14130//14130 14124//14124 -f 14124//14124 14130//14130 14131//14131 -f 14124//14124 14131//14131 14123//14123 -f 14123//14123 14131//14131 14132//14132 -f 14123//14123 14132//14132 14122//14122 -f 14122//14122 14132//14132 14133//14133 -f 14122//14122 14133//14133 14121//14121 -f 14121//14121 14133//14133 14134//14134 -f 14121//14121 14134//14134 14120//14120 -f 14120//14120 14134//14134 14135//14135 -f 14120//14120 14135//14135 14119//14119 -f 14119//14119 14135//14135 14136//14136 -f 14119//14119 14136//14136 14118//14118 -f 14118//14118 14136//14136 14125//14125 -f 14126//14126 13611//13611 14127//14127 -f 14127//14127 13611//13611 13613//13613 -f 14127//14127 13613//13613 14128//14128 -f 14128//14128 13613//13613 13615//13615 -f 14128//14128 13615//13615 14129//14129 -f 14129//14129 13615//13615 13604//13604 -f 14129//14129 13604//13604 14130//14130 -f 14130//14130 13604//13604 13602//13602 -f 14130//14130 13602//13602 14131//14131 -f 14131//14131 13602//13602 13601//13601 -f 14131//14131 13601//13601 14132//14132 -f 14132//14132 13601//13601 13610//13610 -f 14132//14132 13610//13610 14133//14133 -f 14133//14133 13610//13610 13609//13609 -f 14133//14133 13609//13609 14134//14134 -f 14134//14134 13609//13609 13634//13634 -f 14134//14134 13634//13634 14135//14135 -f 14135//14135 13634//13634 13628//13628 -f 14135//14135 13628//13628 14136//14136 -f 14136//14136 13628//13628 13625//13625 -f 14136//14136 13625//13625 14125//14125 -f 14125//14125 13625//13625 13616//13616 -f 14125//14125 13616//13616 14126//14126 -f 14126//14126 13616//13616 13611//13611 -f 13621//13621 13641//13641 13572//13572 -f 13572//13572 13576//13576 13621//13621 -f 13621//13621 13576//13576 13575//13575 -f 13621//13621 13575//13575 13605//13605 -f 13605//13605 13575//13575 13579//13579 -f 13605//13605 13579//13579 13669//13669 -f 13669//13669 13579//13579 13578//13578 -f 13669//13669 13578//13578 13670//13670 -f 13578//13578 13582//13582 13670//13670 -f 13670//13670 13582//13582 13581//13581 -f 13670//13670 13581//13581 13672//13672 -f 13581//13581 13585//13585 13672//13672 -f 13672//13672 13585//13585 13584//13584 -f 13672//13672 13584//13584 13673//13673 -f 13584//13584 13588//13588 13673//13673 -f 13673//13673 13588//13588 13587//13587 -f 13673//13673 13587//13587 13657//13657 -f 13587//13587 13591//13591 13657//13657 -f 13657//13657 13591//13591 13590//13590 -f 13657//13657 13590//13590 13600//13600 -f 13600//13600 13590//13590 13677//13677 -f 13677//13677 13590//13590 13594//13594 -f 13677//13677 13594//13594 13691//13691 -f 13691//13691 13594//13594 13593//13593 -f 13691//13691 13593//13593 13689//13689 -f 13593//13593 13597//13597 13689//13689 -f 13689//13689 13597//13597 13596//13596 -f 13689//13689 13596//13596 13687//13687 -f 13687//13687 13596//13596 13595//13595 -f 13687//13687 13595//13595 13683//13683 -f 13595//13595 13543//13543 13683//13683 -f 13683//13683 13543//13543 13546//13546 -f 13683//13683 13546//13546 13684//13684 -f 13546//13546 13545//13545 13684//13684 -f 13684//13684 13545//13545 13549//13549 -f 13684//13684 13549//13549 13608//13608 -f 13608//13608 13549//13549 13548//13548 -f 13608//13608 13548//13548 13636//13636 -f 13636//13636 13548//13548 13552//13552 -f 13636//13636 13552//13552 13635//13635 -f 13552//13552 13551//13551 13635//13635 -f 13635//13635 13551//13551 13555//13555 -f 13635//13635 13555//13555 13633//13633 -f 13555//13555 13554//13554 13633//13633 -f 13633//13633 13554//13554 13558//13558 -f 13633//13633 13558//13558 13632//13632 -f 13558//13558 13557//13557 13632//13632 -f 13632//13632 13557//13557 13561//13561 -f 13632//13632 13561//13561 13631//13631 -f 13561//13561 13560//13560 13631//13631 -f 13631//13631 13560//13560 13564//13564 -f 13631//13631 13564//13564 13637//13637 -f 13564//13564 13563//13563 13637//13637 -f 13637//13637 13563//13563 13567//13567 -f 13637//13637 13567//13567 13638//13638 -f 13567//13567 13566//13566 13638//13638 -f 13638//13638 13566//13566 13570//13570 -f 13638//13638 13570//13570 13640//13640 -f 13640//13640 13570//13570 13569//13569 -f 13640//13640 13569//13569 13641//13641 -f 13641//13641 13569//13569 13573//13573 -f 13641//13641 13573//13573 13572//13572 -f 13969//13969 13925//13925 13924//13924 -f 13969//13969 13924//13924 13971//13971 -f 13971//13971 13924//13924 13923//13923 -f 13971//13971 13923//13923 13973//13973 -f 13923//13923 13922//13922 13973//13973 -f 13973//13973 13922//13922 13921//13921 -f 13973//13973 13921//13921 13974//13974 -f 13921//13921 13920//13920 13974//13974 -f 13974//13974 13920//13920 13919//13919 -f 13974//13974 13919//13919 13962//13962 -f 13919//13919 13918//13918 13962//13962 -f 13962//13962 13918//13918 13917//13917 -f 13962//13962 13917//13917 13964//13964 -f 13917//13917 13916//13916 13964//13964 -f 13964//13964 13916//13916 13915//13915 -f 13964//13964 13915//13915 13966//13966 -f 13966//13966 13915//13915 13914//13914 -f 13914//13914 13913//13913 13966//13966 -f 13966//13966 13913//13913 13912//13912 -f 13966//13966 13912//13912 13967//13967 -f 13912//13912 13911//13911 13967//13967 -f 13967//13967 13911//13911 13910//13910 -f 13967//13967 13910//13910 13955//13955 -f 13955//13955 13910//13910 13909//13909 -f 13955//13955 13909//13909 13957//13957 -f 13909//13909 13908//13908 13957//13957 -f 13957//13957 13908//13908 13907//13907 -f 13957//13957 13907//13907 13959//13959 -f 13907//13907 13906//13906 13959//13959 -f 13959//13959 13906//13906 13905//13905 -f 13959//13959 13905//13905 13960//13960 -f 13905//13905 13904//13904 13960//13960 -f 13960//13960 13904//13904 13903//13903 -f 13960//13960 13903//13903 13951//13951 -f 13903//13903 13902//13902 13951//13951 -f 13951//13951 13902//13902 13901//13901 -f 13951//13951 13901//13901 13975//13975 -f 13975//13975 13901//13901 13950//13950 -f 13975//13975 13950//13950 13976//13976 -f 13950//13950 13949//13949 13976//13976 -f 13976//13976 13949//13949 13948//13948 -f 13976//13976 13948//13948 13978//13978 -f 13978//13978 13948//13948 13947//13947 -f 13978//13978 13947//13947 13980//13980 -f 13947//13947 13946//13946 13980//13980 -f 13980//13980 13946//13946 13945//13945 -f 13980//13980 13945//13945 13989//13989 -f 13989//13989 13945//13945 13944//13944 -f 13944//13944 13943//13943 13989//13989 -f 13989//13989 13943//13943 13942//13942 -f 13989//13989 13942//13942 13990//13990 -f 13990//13990 13942//13942 13941//13941 -f 13990//13990 13941//13941 13992//13992 -f 13941//13941 13940//13940 13992//13992 -f 13992//13992 13940//13940 13939//13939 -f 13992//13992 13939//13939 13994//13994 -f 13939//13939 13938//13938 13994//13994 -f 13994//13994 13938//13938 13937//13937 -f 13994//13994 13937//13937 13995//13995 -f 13937//13937 13936//13936 13995//13995 -f 13995//13995 13936//13936 13935//13935 -f 13995//13995 13935//13935 13983//13983 -f 13935//13935 13934//13934 13983//13983 -f 13983//13983 13934//13934 13933//13933 -f 13983//13983 13933//13933 13985//13985 -f 13985//13985 13933//13933 13932//13932 -f 13932//13932 13931//13931 13985//13985 -f 13985//13985 13931//13931 13930//13930 -f 13985//13985 13930//13930 13987//13987 -f 13930//13930 13929//13929 13987//13987 -f 13987//13987 13929//13929 13928//13928 -f 13987//13987 13928//13928 13988//13988 -f 13988//13988 13928//13928 13927//13927 -f 13988//13988 13927//13927 13969//13969 -f 13969//13969 13927//13927 13926//13926 -f 13969//13969 13926//13926 13925//13925 -f 13793//13793 13795//13795 13782//13782 -f 13732//13732 13831//13831 13730//13730 -f 13730//13730 13831//13831 13830//13830 -f 13730//13730 13830//13830 13728//13728 -f 13728//13728 13830//13830 13836//13836 -f 13728//13728 13836//13836 13726//13726 -f 13726//13726 13836//13836 13837//13837 -f 13726//13726 13837//13837 13724//13724 -f 13724//13724 13837//13837 13828//13828 -f 13724//13724 13828//13828 13722//13722 -f 13722//13722 13828//13828 13807//13807 -f 13722//13722 13807//13807 13720//13720 -f 13720//13720 13807//13807 13806//13806 -f 13720//13720 13806//13806 13718//13718 -f 13718//13718 13806//13806 13805//13805 -f 13718//13718 13805//13805 13716//13716 -f 13716//13716 13805//13805 13788//13788 -f 13716//13716 13788//13788 13714//13714 -f 13714//13714 13788//13788 13789//13789 -f 13714//13714 13789//13789 13712//13712 -f 13712//13712 13789//13789 13791//13791 -f 13712//13712 13791//13791 13710//13710 -f 13710//13710 13791//13791 13793//13793 -f 13710//13710 13793//13793 13784//13784 -f 13784//13784 13793//13793 13782//13782 -f 13867//13867 13825//13825 13732//13732 -f 13732//13732 13825//13825 13833//13833 -f 13732//13732 13833//13833 13831//13831 -f 13795//13795 13882//13882 13782//13782 -f 13782//13782 13882//13882 13881//13881 -f 13782//13782 13881//13881 13780//13780 -f 13780//13780 13881//13881 13900//13900 -f 13780//13780 13900//13900 13778//13778 -f 13778//13778 13900//13900 13899//13899 -f 13778//13778 13899//13899 13776//13776 -f 13776//13776 13899//13899 13898//13898 -f 13776//13776 13898//13898 13774//13774 -f 13774//13774 13898//13898 13875//13875 -f 13774//13774 13875//13875 13772//13772 -f 13772//13772 13875//13875 13884//13884 -f 13772//13772 13884//13884 13770//13770 -f 13770//13770 13884//13884 13877//13877 -f 13770//13770 13877//13877 13768//13768 -f 13768//13768 13877//13877 13876//13876 -f 13768//13768 13876//13876 13766//13766 -f 13766//13766 13876//13876 13889//13889 -f 13766//13766 13889//13889 13764//13764 -f 13764//13764 13889//13889 13872//13872 -f 13764//13764 13872//13872 13762//13762 -f 13762//13762 13872//13872 13871//13871 -f 13762//13762 13871//13871 13760//13760 -f 13760//13760 13871//13871 13870//13870 -f 13760//13760 13870//13870 13758//13758 -f 13758//13758 13870//13870 13869//13869 -f 13758//13758 13869//13869 13756//13756 -f 13756//13756 13869//13869 13868//13868 -f 13756//13756 13868//13868 13754//13754 -f 13754//13754 13868//13868 13843//13843 -f 13754//13754 13843//13843 13752//13752 -f 13752//13752 13843//13843 13845//13845 -f 13752//13752 13845//13845 13750//13750 -f 13750//13750 13845//13845 13847//13847 -f 13750//13750 13847//13847 13748//13748 -f 13748//13748 13847//13847 13849//13849 -f 13748//13748 13849//13849 13746//13746 -f 13746//13746 13849//13849 13851//13851 -f 13746//13746 13851//13851 13744//13744 -f 13744//13744 13851//13851 13853//13853 -f 13744//13744 13853//13853 13742//13742 -f 13742//13742 13853//13853 13855//13855 -f 13742//13742 13855//13855 13740//13740 -f 13740//13740 13855//13855 13858//13858 -f 13740//13740 13858//13858 13738//13738 -f 13738//13738 13858//13858 13860//13860 -f 13738//13738 13860//13860 13736//13736 -f 13736//13736 13860//13860 13867//13867 -f 13736//13736 13867//13867 13734//13734 -f 13734//13734 13867//13867 13732//13732 -f 13727//13727 13614//13614 13729//13729 -f 13729//13729 13614//13614 13612//13612 -f 13729//13729 13612//13612 13731//13731 -f 13731//13731 13612//13612 13618//13618 -f 13731//13731 13618//13618 13733//13733 -f 13733//13733 13618//13618 13617//13617 -f 13733//13733 13617//13617 13735//13735 -f 13735//13735 13617//13617 13627//13627 -f 13735//13735 13627//13627 13737//13737 -f 13737//13737 13627//13627 13626//13626 -f 13737//13737 13626//13626 13739//13739 -f 13739//13739 13626//13626 13624//13624 -f 13739//13739 13624//13624 13741//13741 -f 13741//13741 13624//13624 13623//13623 -f 13741//13741 13623//13623 13743//13743 -f 13743//13743 13623//13623 13644//13644 -f 13743//13743 13644//13644 13745//13745 -f 13745//13745 13644//13644 13646//13646 -f 13745//13745 13646//13646 13747//13747 -f 13747//13747 13646//13646 13648//13648 -f 13747//13747 13648//13648 13749//13749 -f 13749//13749 13648//13648 13606//13606 -f 13749//13749 13606//13606 13751//13751 -f 13606//13606 13664//13664 13751//13751 -f 13751//13751 13664//13664 13665//13665 -f 13751//13751 13665//13665 13753//13753 -f 13753//13753 13665//13665 13676//13676 -f 13753//13753 13676//13676 13755//13755 -f 13755//13755 13676//13676 13675//13675 -f 13755//13755 13675//13675 13757//13757 -f 13757//13757 13675//13675 13674//13674 -f 13757//13757 13674//13674 13759//13759 -f 13759//13759 13674//13674 13653//13653 -f 13759//13759 13653//13653 13761//13761 -f 13761//13761 13653//13653 13659//13659 -f 13761//13761 13659//13659 13763//13763 -f 13763//13763 13659//13659 13655//13655 -f 13763//13763 13655//13655 13765//13765 -f 13765//13765 13655//13655 13654//13654 -f 13765//13765 13654//13654 13767//13767 -f 13767//13767 13654//13654 13599//13599 -f 13767//13767 13599//13599 13769//13769 -f 13769//13769 13599//13599 13598//13598 -f 13769//13769 13598//13598 13771//13771 -f 13771//13771 13598//13598 13682//13682 -f 13771//13771 13682//13682 13773//13773 -f 13773//13773 13682//13682 13681//13681 -f 13773//13773 13681//13681 13775//13775 -f 13775//13775 13681//13681 13680//13680 -f 13775//13775 13680//13680 13777//13777 -f 13777//13777 13680//13680 13679//13679 -f 13777//13777 13679//13679 13779//13779 -f 13779//13779 13679//13679 13678//13678 -f 13779//13779 13678//13678 13781//13781 -f 13781//13781 13678//13678 13695//13695 -f 13781//13781 13695//13695 13783//13783 -f 13783//13783 13695//13695 13697//13697 -f 13783//13783 13697//13697 13785//13785 -f 13785//13785 13697//13697 13699//13699 -f 13785//13785 13699//13699 13711//13711 -f 13711//13711 13699//13699 13701//13701 -f 13711//13711 13701//13701 13713//13713 -f 13713//13713 13701//13701 13703//13703 -f 13713//13713 13703//13703 13715//13715 -f 13715//13715 13703//13703 13709//13709 -f 13715//13715 13709//13709 13717//13717 -f 13717//13717 13709//13709 13708//13708 -f 13717//13717 13708//13708 13719//13719 -f 13719//13719 13708//13708 13707//13707 -f 13719//13719 13707//13707 13721//13721 -f 13721//13721 13707//13707 13706//13706 -f 13721//13721 13706//13706 13723//13723 -f 13723//13723 13706//13706 13705//13705 -f 13723//13723 13705//13705 13725//13725 -f 13725//13725 13705//13705 13603//13603 -f 13725//13725 13603//13603 13727//13727 -f 13727//13727 13603//13603 13622//13622 -f 13727//13727 13622//13622 13614//13614 -f 14137//14137 14138//14138 14139//14139 -f 14139//14139 14138//14138 14140//14140 -f 14139//14139 14140//14140 14141//14141 -f 14141//14141 14140//14140 14142//14142 -f 14141//14141 14142//14142 14143//14143 -f 14143//14143 14142//14142 14144//14144 -f 14143//14143 14144//14144 14145//14145 -f 14145//14145 14144//14144 14146//14146 -f 14145//14145 14146//14146 14147//14147 -f 14147//14147 14146//14146 14148//14148 -f 14147//14147 14148//14148 14149//14149 -f 14149//14149 14148//14148 14150//14150 -f 14149//14149 14150//14150 14151//14151 -f 14151//14151 14150//14150 14152//14152 -f 14151//14151 14152//14152 14153//14153 -f 14154//14154 14155//14155 14156//14156 -f 14156//14156 14155//14155 14157//14157 -f 14156//14156 14157//14157 14158//14158 -f 14158//14158 14157//14157 14159//14159 -f 14158//14158 14159//14159 14160//14160 -f 14160//14160 14159//14159 14161//14161 -f 14160//14160 14161//14161 14162//14162 -f 14162//14162 14161//14161 14163//14163 -f 14162//14162 14163//14163 14164//14164 -f 14164//14164 14163//14163 14165//14165 -f 14164//14164 14165//14165 14166//14166 -f 14166//14166 14165//14165 14167//14167 -f 14166//14166 14167//14167 14168//14168 -f 14168//14168 14167//14167 14169//14169 -f 14168//14168 14169//14169 14170//14170 -f 14170//14170 14169//14169 14171//14171 -f 14170//14170 14171//14171 14137//14137 -f 14137//14137 14171//14171 14172//14172 -f 14137//14137 14172//14172 14138//14138 -f 14173//14173 14174//14174 14175//14175 -f 14175//14175 14174//14174 14176//14176 -f 14175//14175 14176//14176 14177//14177 -f 14177//14177 14176//14176 14178//14178 -f 14177//14177 14178//14178 14179//14179 -f 14179//14179 14178//14178 14180//14180 -f 14179//14179 14180//14180 14181//14181 -f 14181//14181 14180//14180 14182//14182 -f 14181//14181 14182//14182 14183//14183 -f 14183//14183 14182//14182 14184//14184 -f 14183//14183 14184//14184 14185//14185 -f 14185//14185 14184//14184 14186//14186 -f 14185//14185 14186//14186 14187//14187 -f 14187//14187 14186//14186 14188//14188 -f 14187//14187 14188//14188 14154//14154 -f 14154//14154 14188//14188 14189//14189 -f 14154//14154 14189//14189 14155//14155 -f 14152//14152 14190//14190 14153//14153 -f 14153//14153 14190//14190 14191//14191 -f 14153//14153 14191//14191 14192//14192 -f 14192//14192 14191//14191 14193//14193 -f 14192//14192 14193//14193 14194//14194 -f 14194//14194 14193//14193 14195//14195 -f 14194//14194 14195//14195 14196//14196 -f 14196//14196 14195//14195 14197//14197 -f 14196//14196 14197//14197 14198//14198 -f 14198//14198 14197//14197 14199//14199 -f 14198//14198 14199//14199 14200//14200 -f 14200//14200 14199//14199 14201//14201 -f 14200//14200 14201//14201 14202//14202 -f 14202//14202 14201//14201 14203//14203 -f 14202//14202 14203//14203 14204//14204 -f 14204//14204 14203//14203 14205//14205 -f 14204//14204 14205//14205 14206//14206 -f 14206//14206 14205//14205 14207//14207 -f 14206//14206 14207//14207 14173//14173 -f 14173//14173 14207//14207 14208//14208 -f 14173//14173 14208//14208 14174//14174 -f 14209//14209 14163//14163 14210//14210 -f 14210//14210 14163//14163 14161//14161 -f 14210//14210 14161//14161 14211//14211 -f 14211//14211 14161//14161 14159//14159 -f 14211//14211 14159//14159 14212//14212 -f 14212//14212 14159//14159 14157//14157 -f 14212//14212 14157//14157 14213//14213 -f 14213//14213 14157//14157 14155//14155 -f 14213//14213 14155//14155 14214//14214 -f 14214//14214 14155//14155 14189//14189 -f 14214//14214 14189//14189 14215//14215 -f 14215//14215 14189//14189 14188//14188 -f 14215//14215 14188//14188 14216//14216 -f 14216//14216 14188//14188 14186//14186 -f 14216//14216 14186//14186 14217//14217 -f 14217//14217 14186//14186 14184//14184 -f 14217//14217 14184//14184 14218//14218 -f 14218//14218 14184//14184 14182//14182 -f 14218//14218 14182//14182 14219//14219 -f 14219//14219 14182//14182 14180//14180 -f 14219//14219 14180//14180 14220//14220 -f 14220//14220 14180//14180 14178//14178 -f 14220//14220 14178//14178 14221//14221 -f 14221//14221 14178//14178 14176//14176 -f 14221//14221 14176//14176 14222//14222 -f 14222//14222 14176//14176 14174//14174 -f 14222//14222 14174//14174 14223//14223 -f 14223//14223 14174//14174 14208//14208 -f 14223//14223 14208//14208 14224//14224 -f 14224//14224 14208//14208 14207//14207 -f 14224//14224 14207//14207 14225//14225 -f 14225//14225 14207//14207 14205//14205 -f 14225//14225 14205//14205 14226//14226 -f 14226//14226 14205//14205 14203//14203 -f 14226//14226 14203//14203 14227//14227 -f 14227//14227 14203//14203 14201//14201 -f 14227//14227 14201//14201 14228//14228 -f 14228//14228 14201//14201 14199//14199 -f 14228//14228 14199//14199 14229//14229 -f 14229//14229 14199//14199 14197//14197 -f 14229//14229 14197//14197 14230//14230 -f 14230//14230 14197//14197 14195//14195 -f 14230//14230 14195//14195 14231//14231 -f 14231//14231 14195//14195 14193//14193 -f 14231//14231 14193//14193 14232//14232 -f 14232//14232 14193//14193 14191//14191 -f 14232//14232 14191//14191 14233//14233 -f 14233//14233 14191//14191 14190//14190 -f 14233//14233 14190//14190 14234//14234 -f 14234//14234 14190//14190 14152//14152 -f 14234//14234 14152//14152 14235//14235 -f 14235//14235 14152//14152 14150//14150 -f 14235//14235 14150//14150 14236//14236 -f 14236//14236 14150//14150 14148//14148 -f 14236//14236 14148//14148 14237//14237 -f 14237//14237 14148//14148 14146//14146 -f 14237//14237 14146//14146 14238//14238 -f 14238//14238 14146//14146 14144//14144 -f 14238//14238 14144//14144 14239//14239 -f 14239//14239 14144//14144 14142//14142 -f 14239//14239 14142//14142 14240//14240 -f 14240//14240 14142//14142 14140//14140 -f 14240//14240 14140//14140 14241//14241 -f 14241//14241 14140//14140 14138//14138 -f 14241//14241 14138//14138 14242//14242 -f 14242//14242 14138//14138 14172//14172 -f 14242//14242 14172//14172 14243//14243 -f 14243//14243 14172//14172 14171//14171 -f 14243//14243 14171//14171 14244//14244 -f 14244//14244 14171//14171 14169//14169 -f 14244//14244 14169//14169 14245//14245 -f 14245//14245 14169//14169 14167//14167 -f 14245//14245 14167//14167 14246//14246 -f 14246//14246 14167//14167 14165//14165 -f 14246//14246 14165//14165 14209//14209 -f 14209//14209 14165//14165 14163//14163 -f 14247//14247 14233//14233 14248//14248 -f 14248//14248 14233//14233 14234//14234 -f 14248//14248 14234//14234 14249//14249 -f 14249//14249 14234//14234 14235//14235 -f 14249//14249 14235//14235 14250//14250 -f 14250//14250 14235//14235 14236//14236 -f 14250//14250 14236//14236 14251//14251 -f 14251//14251 14236//14236 14237//14237 -f 14251//14251 14237//14237 14252//14252 -f 14252//14252 14237//14237 14238//14238 -f 14252//14252 14238//14238 14253//14253 -f 14253//14253 14238//14238 14239//14239 -f 14253//14253 14239//14239 14254//14254 -f 14254//14254 14239//14239 14240//14240 -f 14254//14254 14240//14240 14255//14255 -f 14256//14256 14223//14223 14257//14257 -f 14257//14257 14223//14223 14224//14224 -f 14257//14257 14224//14224 14258//14258 -f 14258//14258 14224//14224 14225//14225 -f 14258//14258 14225//14225 14259//14259 -f 14259//14259 14225//14225 14226//14226 -f 14259//14259 14226//14226 14260//14260 -f 14260//14260 14226//14226 14227//14227 -f 14260//14260 14227//14227 14261//14261 -f 14261//14261 14227//14227 14228//14228 -f 14261//14261 14228//14228 14262//14262 -f 14262//14262 14228//14228 14229//14229 -f 14262//14262 14229//14229 14263//14263 -f 14263//14263 14229//14229 14230//14230 -f 14263//14263 14230//14230 14264//14264 -f 14264//14264 14230//14230 14231//14231 -f 14264//14264 14231//14231 14247//14247 -f 14247//14247 14231//14231 14232//14232 -f 14247//14247 14232//14232 14233//14233 -f 14265//14265 14214//14214 14266//14266 -f 14266//14266 14214//14214 14215//14215 -f 14266//14266 14215//14215 14267//14267 -f 14267//14267 14215//14215 14216//14216 -f 14267//14267 14216//14216 14268//14268 -f 14268//14268 14216//14216 14217//14217 -f 14268//14268 14217//14217 14269//14269 -f 14269//14269 14217//14217 14218//14218 -f 14269//14269 14218//14218 14270//14270 -f 14270//14270 14218//14218 14219//14219 -f 14270//14270 14219//14219 14271//14271 -f 14271//14271 14219//14219 14220//14220 -f 14271//14271 14220//14220 14272//14272 -f 14272//14272 14220//14220 14221//14221 -f 14272//14272 14221//14221 14256//14256 -f 14256//14256 14221//14221 14222//14222 -f 14256//14256 14222//14222 14223//14223 -f 14240//14240 14241//14241 14255//14255 -f 14255//14255 14241//14241 14242//14242 -f 14255//14255 14242//14242 14273//14273 -f 14273//14273 14242//14242 14243//14243 -f 14273//14273 14243//14243 14274//14274 -f 14274//14274 14243//14243 14244//14244 -f 14274//14274 14244//14244 14275//14275 -f 14275//14275 14244//14244 14245//14245 -f 14275//14275 14245//14245 14276//14276 -f 14276//14276 14245//14245 14246//14246 -f 14276//14276 14246//14246 14277//14277 -f 14277//14277 14246//14246 14209//14209 -f 14277//14277 14209//14209 14278//14278 -f 14278//14278 14209//14209 14210//14210 -f 14278//14278 14210//14210 14279//14279 -f 14279//14279 14210//14210 14211//14211 -f 14279//14279 14211//14211 14280//14280 -f 14280//14280 14211//14211 14212//14212 -f 14280//14280 14212//14212 14265//14265 -f 14265//14265 14212//14212 14213//14213 -f 14265//14265 14213//14213 14214//14214 -f 14281//14281 14277//14277 14282//14282 -f 14282//14282 14277//14277 14278//14278 -f 14282//14282 14278//14278 14283//14283 -f 14283//14283 14278//14278 14279//14279 -f 14283//14283 14279//14279 14284//14284 -f 14284//14284 14279//14279 14280//14280 -f 14284//14284 14280//14280 14285//14285 -f 14285//14285 14280//14280 14265//14265 -f 14285//14285 14265//14265 14286//14286 -f 14286//14286 14265//14265 14266//14266 -f 14286//14286 14266//14266 14287//14287 -f 14287//14287 14266//14266 14267//14267 -f 14287//14287 14267//14267 14288//14288 -f 14288//14288 14267//14267 14268//14268 -f 14288//14288 14268//14268 14289//14289 -f 14289//14289 14268//14268 14269//14269 -f 14289//14289 14269//14269 14290//14290 -f 14290//14290 14269//14269 14270//14270 -f 14290//14290 14270//14270 14291//14291 -f 14291//14291 14270//14270 14271//14271 -f 14291//14291 14271//14271 14292//14292 -f 14292//14292 14271//14271 14272//14272 -f 14292//14292 14272//14272 14293//14293 -f 14293//14293 14272//14272 14256//14256 -f 14293//14293 14256//14256 14294//14294 -f 14294//14294 14256//14256 14257//14257 -f 14294//14294 14257//14257 14295//14295 -f 14295//14295 14257//14257 14258//14258 -f 14295//14295 14258//14258 14296//14296 -f 14296//14296 14258//14258 14259//14259 -f 14296//14296 14259//14259 14297//14297 -f 14297//14297 14259//14259 14260//14260 -f 14297//14297 14260//14260 14298//14298 -f 14298//14298 14260//14260 14261//14261 -f 14298//14298 14261//14261 14299//14299 -f 14299//14299 14261//14261 14262//14262 -f 14299//14299 14262//14262 14300//14300 -f 14300//14300 14262//14262 14263//14263 -f 14300//14300 14263//14263 14301//14301 -f 14301//14301 14263//14263 14264//14264 -f 14301//14301 14264//14264 14302//14302 -f 14302//14302 14264//14264 14247//14247 -f 14302//14302 14247//14247 14303//14303 -f 14303//14303 14247//14247 14248//14248 -f 14303//14303 14248//14248 14304//14304 -f 14304//14304 14248//14248 14249//14249 -f 14304//14304 14249//14249 14305//14305 -f 14305//14305 14249//14249 14250//14250 -f 14305//14305 14250//14250 14306//14306 -f 14306//14306 14250//14250 14251//14251 -f 14306//14306 14251//14251 14307//14307 -f 14307//14307 14251//14251 14252//14252 -f 14307//14307 14252//14252 14308//14308 -f 14308//14308 14252//14252 14253//14253 -f 14308//14308 14253//14253 14309//14309 -f 14309//14309 14253//14253 14254//14254 -f 14309//14309 14254//14254 14310//14310 -f 14310//14310 14254//14254 14255//14255 -f 14310//14310 14255//14255 14311//14311 -f 14311//14311 14255//14255 14273//14273 -f 14311//14311 14273//14273 14312//14312 -f 14312//14312 14273//14273 14274//14274 -f 14312//14312 14274//14274 14313//14313 -f 14313//14313 14274//14274 14275//14275 -f 14313//14313 14275//14275 14314//14314 -f 14314//14314 14275//14275 14276//14276 -f 14314//14314 14276//14276 14281//14281 -f 14281//14281 14276//14276 14277//14277 -f 14315//14315 14313//14313 14316//14316 -f 14316//14316 14313//14313 14314//14314 -f 14316//14316 14314//14314 14317//14317 -f 14317//14317 14314//14314 14281//14281 -f 14317//14317 14281//14281 14318//14318 -f 14319//14319 14308//14308 14320//14320 -f 14320//14320 14308//14308 14309//14309 -f 14320//14320 14309//14309 14321//14321 -f 14321//14321 14309//14309 14310//14310 -f 14321//14321 14310//14310 14322//14322 -f 14322//14322 14310//14310 14311//14311 -f 14322//14322 14311//14311 14315//14315 -f 14315//14315 14311//14311 14312//14312 -f 14315//14315 14312//14312 14313//14313 -f 14323//14323 14303//14303 14324//14324 -f 14324//14324 14303//14303 14304//14304 -f 14324//14324 14304//14304 14325//14325 -f 14325//14325 14304//14304 14305//14305 -f 14325//14325 14305//14305 14326//14326 -f 14326//14326 14305//14305 14306//14306 -f 14326//14326 14306//14306 14319//14319 -f 14319//14319 14306//14306 14307//14307 -f 14319//14319 14307//14307 14308//14308 -f 14327//14327 14293//14293 14328//14328 -f 14328//14328 14293//14293 14294//14294 -f 14328//14328 14294//14294 14329//14329 -f 14329//14329 14294//14294 14295//14295 -f 14329//14329 14295//14295 14330//14330 -f 14330//14330 14295//14295 14296//14296 -f 14330//14330 14296//14296 14331//14331 -f 14281//14281 14282//14282 14318//14318 -f 14318//14318 14282//14282 14283//14283 -f 14318//14318 14283//14283 14332//14332 -f 14332//14332 14283//14283 14284//14284 -f 14332//14332 14284//14284 14333//14333 -f 14333//14333 14284//14284 14285//14285 -f 14333//14333 14285//14285 14334//14334 -f 14334//14334 14285//14285 14286//14286 -f 14334//14334 14286//14286 14335//14335 -f 14296//14296 14297//14297 14331//14331 -f 14331//14331 14297//14297 14298//14298 -f 14331//14331 14298//14298 14336//14336 -f 14336//14336 14298//14298 14299//14299 -f 14336//14336 14299//14299 14337//14337 -f 14337//14337 14299//14299 14300//14300 -f 14337//14337 14300//14300 14338//14338 -f 14338//14338 14300//14300 14301//14301 -f 14338//14338 14301//14301 14323//14323 -f 14323//14323 14301//14301 14302//14302 -f 14323//14323 14302//14302 14303//14303 -f 14286//14286 14287//14287 14335//14335 -f 14335//14335 14287//14287 14288//14288 -f 14335//14335 14288//14288 14339//14339 -f 14339//14339 14288//14288 14289//14289 -f 14339//14339 14289//14289 14340//14340 -f 14340//14340 14289//14289 14290//14290 -f 14340//14340 14290//14290 14341//14341 -f 14341//14341 14290//14290 14291//14291 -f 14341//14341 14291//14291 14327//14327 -f 14327//14327 14291//14291 14292//14292 -f 14327//14327 14292//14292 14293//14293 -f 14342//14342 14318//14318 14343//14343 -f 14343//14343 14318//14318 14332//14332 -f 14343//14343 14332//14332 14344//14344 -f 14344//14344 14332//14332 14333//14333 -f 14344//14344 14333//14333 14345//14345 -f 14345//14345 14333//14333 14334//14334 -f 14345//14345 14334//14334 14346//14346 -f 14346//14346 14334//14334 14335//14335 -f 14346//14346 14335//14335 14347//14347 -f 14347//14347 14335//14335 14339//14339 -f 14347//14347 14339//14339 14348//14348 -f 14348//14348 14339//14339 14340//14340 -f 14348//14348 14340//14340 14349//14349 -f 14349//14349 14340//14340 14341//14341 -f 14349//14349 14341//14341 14350//14350 -f 14350//14350 14341//14341 14327//14327 -f 14350//14350 14327//14327 14351//14351 -f 14351//14351 14327//14327 14328//14328 -f 14351//14351 14328//14328 14352//14352 -f 14352//14352 14328//14328 14329//14329 -f 14352//14352 14329//14329 14353//14353 -f 14353//14353 14329//14329 14330//14330 -f 14353//14353 14330//14330 14354//14354 -f 14354//14354 14330//14330 14331//14331 -f 14354//14354 14331//14331 14355//14355 -f 14355//14355 14331//14331 14336//14336 -f 14355//14355 14336//14336 14356//14356 -f 14356//14356 14336//14336 14337//14337 -f 14356//14356 14337//14337 14357//14357 -f 14357//14357 14337//14337 14338//14338 -f 14357//14357 14338//14338 14358//14358 -f 14358//14358 14338//14338 14323//14323 -f 14358//14358 14323//14323 14359//14359 -f 14359//14359 14323//14323 14324//14324 -f 14359//14359 14324//14324 14360//14360 -f 14360//14360 14324//14324 14325//14325 -f 14360//14360 14325//14325 14361//14361 -f 14361//14361 14325//14325 14326//14326 -f 14361//14361 14326//14326 14362//14362 -f 14362//14362 14326//14326 14319//14319 -f 14362//14362 14319//14319 14363//14363 -f 14363//14363 14319//14319 14320//14320 -f 14363//14363 14320//14320 14364//14364 -f 14364//14364 14320//14320 14321//14321 -f 14364//14364 14321//14321 14365//14365 -f 14365//14365 14321//14321 14322//14322 -f 14365//14365 14322//14322 14366//14366 -f 14366//14366 14322//14322 14315//14315 -f 14366//14366 14315//14315 14367//14367 -f 14367//14367 14315//14315 14316//14316 -f 14367//14367 14316//14316 14368//14368 -f 14368//14368 14316//14316 14317//14317 -f 14368//14368 14317//14317 14342//14342 -f 14342//14342 14317//14317 14318//14318 -f 14369//14369 14362//14362 14370//14370 -f 14370//14370 14362//14362 14363//14363 -f 14370//14370 14363//14363 14371//14371 -f 14371//14371 14363//14363 14364//14364 -f 14371//14371 14364//14364 14372//14372 -f 14372//14372 14364//14364 14365//14365 -f 14372//14372 14365//14365 14373//14373 -f 14365//14365 14366//14366 14373//14373 -f 14373//14373 14366//14366 14367//14367 -f 14373//14373 14367//14367 14374//14374 -f 14374//14374 14367//14367 14368//14368 -f 14374//14374 14368//14368 14375//14375 -f 14375//14375 14368//14368 14342//14342 -f 14375//14375 14342//14342 14376//14376 -f 14377//14377 14358//14358 14378//14378 -f 14378//14378 14358//14358 14359//14359 -f 14378//14378 14359//14359 14379//14379 -f 14379//14379 14359//14359 14360//14360 -f 14379//14379 14360//14360 14369//14369 -f 14369//14369 14360//14360 14361//14361 -f 14369//14369 14361//14361 14362//14362 -f 14342//14342 14343//14343 14376//14376 -f 14376//14376 14343//14343 14344//14344 -f 14376//14376 14344//14344 14380//14380 -f 14380//14380 14344//14344 14345//14345 -f 14380//14380 14345//14345 14381//14381 -f 14381//14381 14345//14345 14346//14346 -f 14381//14381 14346//14346 14382//14382 -f 14382//14382 14346//14346 14347//14347 -f 14382//14382 14347//14347 14383//14383 -f 14347//14347 14348//14348 14383//14383 -f 14383//14383 14348//14348 14349//14349 -f 14383//14383 14349//14349 14384//14384 -f 14384//14384 14349//14349 14350//14350 -f 14384//14384 14350//14350 14385//14385 -f 14385//14385 14350//14350 14351//14351 -f 14385//14385 14351//14351 14386//14386 -f 14351//14351 14352//14352 14386//14386 -f 14386//14386 14352//14352 14353//14353 -f 14386//14386 14353//14353 14387//14387 -f 14387//14387 14353//14353 14354//14354 -f 14387//14387 14354//14354 14388//14388 -f 14388//14388 14354//14354 14355//14355 -f 14388//14388 14355//14355 14389//14389 -f 14389//14389 14355//14355 14356//14356 -f 14389//14389 14356//14356 14377//14377 -f 14377//14377 14356//14356 14357//14357 -f 14377//14377 14357//14357 14358//14358 -f 14390//14390 14375//14375 14391//14391 -f 14391//14391 14375//14375 14376//14376 -f 14391//14391 14376//14376 14392//14392 -f 14392//14392 14376//14376 14380//14380 -f 14392//14392 14380//14380 14393//14393 -f 14393//14393 14380//14380 14381//14381 -f 14393//14393 14381//14381 14394//14394 -f 14394//14394 14381//14381 14382//14382 -f 14394//14394 14382//14382 14395//14395 -f 14395//14395 14382//14382 14383//14383 -f 14395//14395 14383//14383 14396//14396 -f 14396//14396 14383//14383 14384//14384 -f 14396//14396 14384//14384 14397//14397 -f 14397//14397 14384//14384 14385//14385 -f 14397//14397 14385//14385 14398//14398 -f 14398//14398 14385//14385 14386//14386 -f 14398//14398 14386//14386 14399//14399 -f 14399//14399 14386//14386 14387//14387 -f 14399//14399 14387//14387 14400//14400 -f 14400//14400 14387//14387 14388//14388 -f 14400//14400 14388//14388 14401//14401 -f 14401//14401 14388//14388 14389//14389 -f 14401//14401 14389//14389 14402//14402 -f 14402//14402 14389//14389 14377//14377 -f 14402//14402 14377//14377 14403//14403 -f 14403//14403 14377//14377 14378//14378 -f 14403//14403 14378//14378 14404//14404 -f 14404//14404 14378//14378 14379//14379 -f 14404//14404 14379//14379 14405//14405 -f 14405//14405 14379//14379 14369//14369 -f 14405//14405 14369//14369 14406//14406 -f 14406//14406 14369//14369 14370//14370 -f 14406//14406 14370//14370 14407//14407 -f 14407//14407 14370//14370 14371//14371 -f 14407//14407 14371//14371 14408//14408 -f 14408//14408 14371//14371 14372//14372 -f 14408//14408 14372//14372 14409//14409 -f 14409//14409 14372//14372 14373//14373 -f 14409//14409 14373//14373 14410//14410 -f 14410//14410 14373//14373 14374//14374 -f 14410//14410 14374//14374 14390//14390 -f 14390//14390 14374//14374 14375//14375 -f 14403//14403 14411//14411 14402//14402 -f 14402//14402 14411//14411 14412//14412 -f 14402//14402 14412//14412 14401//14401 -f 14401//14401 14412//14412 14413//14413 -f 14401//14401 14413//14413 14400//14400 -f 14400//14400 14413//14413 14414//14414 -f 14400//14400 14414//14414 14399//14399 -f 14406//14406 14415//14415 14405//14405 -f 14405//14405 14415//14415 14416//14416 -f 14405//14405 14416//14416 14404//14404 -f 14404//14404 14416//14416 14417//14417 -f 14404//14404 14417//14417 14403//14403 -f 14403//14403 14417//14417 14418//14418 -f 14403//14403 14418//14418 14411//14411 -f 14410//14410 14419//14419 14409//14409 -f 14409//14409 14419//14419 14420//14420 -f 14409//14409 14420//14420 14408//14408 -f 14408//14408 14420//14420 14421//14421 -f 14408//14408 14421//14421 14407//14407 -f 14407//14407 14421//14421 14422//14422 -f 14407//14407 14422//14422 14406//14406 -f 14406//14406 14422//14422 14423//14423 -f 14406//14406 14423//14423 14415//14415 -f 14392//14392 14424//14424 14391//14391 -f 14391//14391 14424//14424 14425//14425 -f 14391//14391 14425//14425 14390//14390 -f 14390//14390 14425//14425 14426//14426 -f 14390//14390 14426//14426 14410//14410 -f 14410//14410 14426//14426 14427//14427 -f 14410//14410 14427//14427 14419//14419 -f 14396//14396 14428//14428 14395//14395 -f 14395//14395 14428//14428 14429//14429 -f 14395//14395 14429//14429 14394//14394 -f 14394//14394 14429//14429 14430//14430 -f 14394//14394 14430//14430 14393//14393 -f 14393//14393 14430//14430 14431//14431 -f 14393//14393 14431//14431 14392//14392 -f 14392//14392 14431//14431 14432//14432 -f 14392//14392 14432//14432 14424//14424 -f 14414//14414 14433//14433 14399//14399 -f 14399//14399 14433//14433 14434//14434 -f 14399//14399 14434//14434 14398//14398 -f 14398//14398 14434//14434 14435//14435 -f 14398//14398 14435//14435 14397//14397 -f 14397//14397 14435//14435 14436//14436 -f 14397//14397 14436//14436 14396//14396 -f 14396//14396 14436//14436 14437//14437 -f 14396//14396 14437//14437 14428//14428 -f 14438//14438 14425//14425 14439//14439 -f 14439//14439 14425//14425 14424//14424 -f 14439//14439 14424//14424 14440//14440 -f 14440//14440 14424//14424 14432//14432 -f 14440//14440 14432//14432 14441//14441 -f 14441//14441 14432//14432 14431//14431 -f 14441//14441 14431//14431 14442//14442 -f 14442//14442 14431//14431 14430//14430 -f 14442//14442 14430//14430 14443//14443 -f 14443//14443 14430//14430 14429//14429 -f 14443//14443 14429//14429 14444//14444 -f 14444//14444 14429//14429 14428//14428 -f 14444//14444 14428//14428 14445//14445 -f 14445//14445 14428//14428 14437//14437 -f 14445//14445 14437//14437 14446//14446 -f 14446//14446 14437//14437 14436//14436 -f 14446//14446 14436//14436 14447//14447 -f 14447//14447 14436//14436 14435//14435 -f 14447//14447 14435//14435 14448//14448 -f 14448//14448 14435//14435 14434//14434 -f 14448//14448 14434//14434 14449//14449 -f 14449//14449 14434//14434 14433//14433 -f 14449//14449 14433//14433 14450//14450 -f 14450//14450 14433//14433 14414//14414 -f 14450//14450 14414//14414 14451//14451 -f 14451//14451 14414//14414 14413//14413 -f 14451//14451 14413//14413 14452//14452 -f 14452//14452 14413//14413 14412//14412 -f 14452//14452 14412//14412 14453//14453 -f 14453//14453 14412//14412 14411//14411 -f 14453//14453 14411//14411 14454//14454 -f 14454//14454 14411//14411 14418//14418 -f 14454//14454 14418//14418 14455//14455 -f 14455//14455 14418//14418 14417//14417 -f 14455//14455 14417//14417 14456//14456 -f 14456//14456 14417//14417 14416//14416 -f 14456//14456 14416//14416 14457//14457 -f 14457//14457 14416//14416 14415//14415 -f 14457//14457 14415//14415 14458//14458 -f 14458//14458 14415//14415 14423//14423 -f 14458//14458 14423//14423 14459//14459 -f 14459//14459 14423//14423 14422//14422 -f 14459//14459 14422//14422 14460//14460 -f 14460//14460 14422//14422 14421//14421 -f 14460//14460 14421//14421 14461//14461 -f 14461//14461 14421//14421 14420//14420 -f 14461//14461 14420//14420 14462//14462 -f 14462//14462 14420//14420 14419//14419 -f 14462//14462 14419//14419 14463//14463 -f 14463//14463 14419//14419 14427//14427 -f 14463//14463 14427//14427 14464//14464 -f 14464//14464 14427//14427 14426//14426 -f 14464//14464 14426//14426 14438//14438 -f 14438//14438 14426//14426 14425//14425 -f 14452//14452 14465//14465 14451//14451 -f 14451//14451 14465//14465 14466//14466 -f 14451//14451 14466//14466 14450//14450 -f 14450//14450 14466//14466 14467//14467 -f 14450//14450 14467//14467 14449//14449 -f 14449//14449 14467//14467 14468//14468 -f 14449//14449 14468//14468 14448//14448 -f 14460//14460 14469//14469 14459//14459 -f 14459//14459 14469//14469 14470//14470 -f 14459//14459 14470//14470 14458//14458 -f 14458//14458 14470//14470 14471//14471 -f 14458//14458 14471//14471 14457//14457 -f 14457//14457 14471//14471 14472//14472 -f 14457//14457 14472//14472 14456//14456 -f 14472//14472 14473//14473 14456//14456 -f 14456//14456 14473//14473 14474//14474 -f 14456//14456 14474//14474 14455//14455 -f 14455//14455 14474//14474 14475//14475 -f 14455//14455 14475//14475 14454//14454 -f 14454//14454 14475//14475 14476//14476 -f 14454//14454 14476//14476 14453//14453 -f 14453//14453 14476//14476 14477//14477 -f 14453//14453 14477//14477 14452//14452 -f 14452//14452 14477//14477 14478//14478 -f 14452//14452 14478//14478 14465//14465 -f 14464//14464 14479//14479 14463//14463 -f 14463//14463 14479//14479 14480//14480 -f 14463//14463 14480//14480 14462//14462 -f 14462//14462 14480//14480 14481//14481 -f 14462//14462 14481//14481 14461//14461 -f 14461//14461 14481//14481 14482//14482 -f 14461//14461 14482//14482 14460//14460 -f 14460//14460 14482//14482 14483//14483 -f 14460//14460 14483//14483 14469//14469 -f 14444//14444 14484//14484 14443//14443 -f 14443//14443 14484//14484 14485//14485 -f 14443//14443 14485//14485 14442//14442 -f 14442//14442 14485//14485 14486//14486 -f 14442//14442 14486//14486 14441//14441 -f 14441//14441 14486//14486 14487//14487 -f 14441//14441 14487//14487 14440//14440 -f 14468//14468 14488//14488 14448//14448 -f 14448//14448 14488//14488 14489//14489 -f 14448//14448 14489//14489 14447//14447 -f 14447//14447 14489//14489 14490//14490 -f 14447//14447 14490//14490 14446//14446 -f 14446//14446 14490//14490 14491//14491 -f 14446//14446 14491//14491 14445//14445 -f 14445//14445 14491//14491 14492//14492 -f 14445//14445 14492//14492 14444//14444 -f 14444//14444 14492//14492 14493//14493 -f 14444//14444 14493//14493 14484//14484 -f 14487//14487 14494//14494 14440//14440 -f 14440//14440 14494//14494 14495//14495 -f 14440//14440 14495//14495 14439//14439 -f 14439//14439 14495//14495 14496//14496 -f 14439//14439 14496//14496 14438//14438 -f 14438//14438 14496//14496 14497//14497 -f 14438//14438 14497//14497 14464//14464 -f 14464//14464 14497//14497 14498//14498 -f 14464//14464 14498//14498 14479//14479 -f 14164//14164 14497//14497 14162//14162 -f 14162//14162 14497//14497 14496//14496 -f 14162//14162 14496//14496 14160//14160 -f 14160//14160 14496//14496 14495//14495 -f 14160//14160 14495//14495 14158//14158 -f 14158//14158 14495//14495 14494//14494 -f 14158//14158 14494//14494 14156//14156 -f 14156//14156 14494//14494 14487//14487 -f 14156//14156 14487//14487 14154//14154 -f 14154//14154 14487//14487 14486//14486 -f 14154//14154 14486//14486 14187//14187 -f 14187//14187 14486//14486 14485//14485 -f 14187//14187 14485//14485 14185//14185 -f 14185//14185 14485//14485 14484//14484 -f 14185//14185 14484//14484 14183//14183 -f 14183//14183 14484//14484 14493//14493 -f 14183//14183 14493//14493 14181//14181 -f 14181//14181 14493//14493 14492//14492 -f 14181//14181 14492//14492 14179//14179 -f 14179//14179 14492//14492 14491//14491 -f 14179//14179 14491//14491 14177//14177 -f 14177//14177 14491//14491 14490//14490 -f 14177//14177 14490//14490 14175//14175 -f 14175//14175 14490//14490 14489//14489 -f 14175//14175 14489//14489 14173//14173 -f 14173//14173 14489//14489 14488//14488 -f 14173//14173 14488//14488 14206//14206 -f 14206//14206 14488//14488 14468//14468 -f 14206//14206 14468//14468 14204//14204 -f 14204//14204 14468//14468 14467//14467 -f 14204//14204 14467//14467 14202//14202 -f 14202//14202 14467//14467 14466//14466 -f 14202//14202 14466//14466 14200//14200 -f 14200//14200 14466//14466 14465//14465 -f 14200//14200 14465//14465 14198//14198 -f 14198//14198 14465//14465 14478//14478 -f 14198//14198 14478//14478 14196//14196 -f 14196//14196 14478//14478 14477//14477 -f 14196//14196 14477//14477 14194//14194 -f 14194//14194 14477//14477 14476//14476 -f 14194//14194 14476//14476 14192//14192 -f 14192//14192 14476//14476 14475//14475 -f 14192//14192 14475//14475 14153//14153 -f 14153//14153 14475//14475 14474//14474 -f 14153//14153 14474//14474 14151//14151 -f 14151//14151 14474//14474 14473//14473 -f 14151//14151 14473//14473 14149//14149 -f 14149//14149 14473//14473 14472//14472 -f 14149//14149 14472//14472 14147//14147 -f 14147//14147 14472//14472 14471//14471 -f 14147//14147 14471//14471 14145//14145 -f 14145//14145 14471//14471 14470//14470 -f 14145//14145 14470//14470 14143//14143 -f 14143//14143 14470//14470 14469//14469 -f 14143//14143 14469//14469 14141//14141 -f 14141//14141 14469//14469 14483//14483 -f 14141//14141 14483//14483 14139//14139 -f 14139//14139 14483//14483 14482//14482 -f 14139//14139 14482//14482 14137//14137 -f 14137//14137 14482//14482 14481//14481 -f 14137//14137 14481//14481 14170//14170 -f 14170//14170 14481//14481 14480//14480 -f 14170//14170 14480//14480 14168//14168 -f 14168//14168 14480//14480 14479//14479 -f 14168//14168 14479//14479 14166//14166 -f 14166//14166 14479//14479 14498//14498 -f 14166//14166 14498//14498 14164//14164 -f 14164//14164 14498//14498 14497//14497 -f 14499//14499 14500//14500 14501//14501 -f 14501//14501 14500//14500 14502//14502 -f 14503//14503 14504//14504 14505//14505 -f 14506//14506 14507//14507 14508//14508 -f 14509//14509 14510//14510 14511//14511 -f 14512//14512 14513//14513 14514//14514 -f 14514//14514 14515//14515 14516//14516 -f 14517//14517 14518//14518 14519//14519 -f 14520//14520 14521//14521 14522//14522 -f 14523//14523 14524//14524 14525//14525 -f 14526//14526 14527//14527 14528//14528 -f 14529//14529 14530//14530 14531//14531 -f 14532//14532 14533//14533 14534//14534 -f 14515//14515 14514//14514 14535//14535 -f 14535//14535 14514//14514 14513//14513 -f 14535//14535 14513//14513 14536//14536 -f 14532//14532 14534//14534 14537//14537 -f 14538//14538 14539//14539 14540//14540 -f 14540//14540 14539//14539 14541//14541 -f 14540//14540 14541//14541 14542//14542 -f 14529//14529 14543//14543 14544//14544 -f 14529//14529 14531//14531 14545//14545 -f 14545//14545 14531//14531 14546//14546 -f 14545//14545 14546//14546 14547//14547 -f 14547//14547 14546//14546 14548//14548 -f 14547//14547 14548//14548 14526//14526 -f 14526//14526 14548//14548 14549//14549 -f 14526//14526 14549//14549 14527//14527 -f 14524//14524 14523//14523 14550//14550 -f 14551//14551 14552//14552 14553//14553 -f 14553//14553 14552//14552 14554//14554 -f 14553//14553 14554//14554 14555//14555 -f 14555//14555 14554//14554 14556//14556 -f 14555//14555 14556//14556 14557//14557 -f 14558//14558 14559//14559 14557//14557 -f 14520//14520 14559//14559 14560//14560 -f 14560//14560 14559//14559 14558//14558 -f 14560//14560 14558//14558 14561//14561 -f 14562//14562 14563//14563 14564//14564 -f 14564//14564 14563//14563 14522//14522 -f 14517//14517 14519//14519 14565//14565 -f 14566//14566 14567//14567 14568//14568 -f 14569//14569 14516//14516 14567//14567 -f 14570//14570 14571//14571 14572//14572 -f 14572//14572 14571//14571 14550//14550 -f 14572//14572 14550//14550 14573//14573 -f 14573//14573 14550//14550 14523//14523 -f 14573//14573 14523//14523 14574//14574 -f 14575//14575 14576//14576 14577//14577 -f 14577//14577 14576//14576 14578//14578 -f 14577//14577 14578//14578 14579//14579 -f 14579//14579 14578//14578 14580//14580 -f 14579//14579 14580//14580 14581//14581 -f 14581//14581 14580//14580 14538//14538 -f 14581//14581 14538//14538 14582//14582 -f 14582//14582 14538//14538 14540//14540 -f 14562//14562 14511//14511 14583//14583 -f 14583//14583 14511//14511 14510//14510 -f 14583//14583 14510//14510 14584//14584 -f 14584//14584 14510//14510 14585//14585 -f 14571//14571 14586//14586 14550//14550 -f 14550//14550 14586//14586 14551//14551 -f 14550//14550 14551//14551 14524//14524 -f 14524//14524 14551//14551 14553//14553 -f 14524//14524 14553//14553 14525//14525 -f 14532//14532 14536//14536 14533//14533 -f 14533//14533 14536//14536 14513//14513 -f 14533//14533 14513//14513 14534//14534 -f 14534//14534 14513//14513 14512//14512 -f 14534//14534 14512//14512 14587//14587 -f 14588//14588 14585//14585 14589//14589 -f 14589//14589 14585//14585 14510//14510 -f 14589//14589 14510//14510 14590//14590 -f 14590//14590 14510//14510 14509//14509 -f 14590//14590 14509//14509 14591//14591 -f 14592//14592 14593//14593 14594//14594 -f 14595//14595 14593//14593 14596//14596 -f 14596//14596 14593//14593 14592//14592 -f 14596//14596 14592//14592 14597//14597 -f 14570//14570 14598//14598 14597//14597 -f 14597//14597 14598//14598 14599//14599 -f 14597//14597 14599//14599 14596//14596 -f 14596//14596 14599//14599 14600//14600 -f 14596//14596 14600//14600 14595//14595 -f 14595//14595 14600//14600 14601//14601 -f 14595//14595 14601//14601 14602//14602 -f 14602//14602 14601//14601 14603//14603 -f 14530//14530 14504//14504 14531//14531 -f 14531//14531 14504//14504 14503//14503 -f 14531//14531 14503//14503 14546//14546 -f 14546//14546 14503//14503 14604//14604 -f 14546//14546 14604//14604 14548//14548 -f 14548//14548 14604//14604 14605//14605 -f 14548//14548 14605//14605 14549//14549 -f 14606//14606 14544//14544 14607//14607 -f 14607//14607 14544//14544 14608//14608 -f 14607//14607 14608//14608 14609//14609 -f 14609//14609 14608//14608 14610//14610 -f 14609//14609 14610//14610 14611//14611 -f 14611//14611 14610//14610 14612//14612 -f 14611//14611 14612//14612 14613//14613 -f 14613//14613 14612//14612 14614//14614 -f 14613//14613 14614//14614 14615//14615 -f 14615//14615 14614//14614 14616//14616 -f 14615//14615 14616//14616 14617//14617 -f 14617//14617 14616//14616 14618//14618 -f 14617//14617 14618//14618 14619//14619 -f 14619//14619 14618//14618 14620//14620 -f 14619//14619 14620//14620 14621//14621 -f 14621//14621 14620//14620 14622//14622 -f 14621//14621 14622//14622 14502//14502 -f 14502//14502 14622//14622 14623//14623 -f 14502//14502 14623//14623 14501//14501 -f 14624//14624 14625//14625 14626//14626 -f 14626//14626 14625//14625 14627//14627 -f 14626//14626 14627//14627 14628//14628 -f 14628//14628 14627//14627 14629//14629 -f 14628//14628 14629//14629 14630//14630 -f 14630//14630 14629//14629 14631//14631 -f 14630//14630 14631//14631 14632//14632 -f 14632//14632 14631//14631 14633//14633 -f 14632//14632 14633//14633 14634//14634 -f 14625//14625 14635//14635 14627//14627 -f 14627//14627 14635//14635 14636//14636 -f 14627//14627 14636//14636 14629//14629 -f 14629//14629 14636//14636 14637//14637 -f 14629//14629 14637//14637 14631//14631 -f 14631//14631 14637//14637 14565//14565 -f 14631//14631 14565//14565 14633//14633 -f 14633//14633 14565//14565 14519//14519 -f 14633//14633 14519//14519 14634//14634 -f 14634//14634 14519//14519 14638//14638 -f 14634//14634 14638//14638 14639//14639 -f 14639//14639 14638//14638 14640//14640 -f 14641//14641 14642//14642 14643//14643 -f 14644//14644 14642//14642 14645//14645 -f 14645//14645 14642//14642 14641//14641 -f 14645//14645 14641//14641 14521//14521 -f 14521//14521 14520//14520 14645//14645 -f 14645//14645 14520//14520 14560//14560 -f 14645//14645 14560//14560 14644//14644 -f 14644//14644 14560//14560 14561//14561 -f 14644//14644 14561//14561 14646//14646 -f 14586//14586 14507//14507 14551//14551 -f 14551//14551 14507//14507 14506//14506 -f 14551//14551 14506//14506 14552//14552 -f 14552//14552 14506//14506 14647//14647 -f 14552//14552 14647//14647 14554//14554 -f 14554//14554 14647//14647 14648//14648 -f 14554//14554 14648//14648 14556//14556 -f 14556//14556 14648//14648 14649//14649 -f 14570//14570 14597//14597 14571//14571 -f 14571//14571 14597//14597 14592//14592 -f 14571//14571 14592//14592 14586//14586 -f 14586//14586 14592//14592 14594//14594 -f 14586//14586 14594//14594 14507//14507 -f 14507//14507 14594//14594 14650//14650 -f 14507//14507 14650//14650 14508//14508 -f 14602//14602 14651//14651 14595//14595 -f 14595//14595 14651//14651 14652//14652 -f 14595//14595 14652//14652 14593//14593 -f 14593//14593 14652//14652 14653//14653 -f 14593//14593 14653//14653 14594//14594 -f 14594//14594 14653//14653 14654//14654 -f 14594//14594 14654//14654 14650//14650 -f 14598//14598 14528//14528 14599//14599 -f 14599//14599 14528//14528 14527//14527 -f 14599//14599 14527//14527 14600//14600 -f 14600//14600 14527//14527 14549//14549 -f 14600//14600 14549//14549 14601//14601 -f 14601//14601 14549//14549 14605//14605 -f 14601//14601 14605//14605 14603//14603 -f 14505//14505 14655//14655 14503//14503 -f 14503//14503 14655//14655 14656//14656 -f 14503//14503 14656//14656 14604//14604 -f 14604//14604 14656//14656 14657//14657 -f 14604//14604 14657//14657 14605//14605 -f 14605//14605 14657//14657 14658//14658 -f 14605//14605 14658//14658 14603//14603 -f 14529//14529 14544//14544 14530//14530 -f 14530//14530 14544//14544 14606//14606 -f 14530//14530 14606//14606 14504//14504 -f 14504//14504 14606//14606 14659//14659 -f 14504//14504 14659//14659 14505//14505 -f 14611//14611 14660//14660 14609//14609 -f 14609//14609 14660//14660 14661//14661 -f 14609//14609 14661//14661 14607//14607 -f 14607//14607 14661//14661 14662//14662 -f 14607//14607 14662//14662 14606//14606 -f 14606//14606 14662//14662 14663//14663 -f 14606//14606 14663//14663 14659//14659 -f 14615//14615 14664//14664 14613//14613 -f 14613//14613 14664//14664 14665//14665 -f 14613//14613 14665//14665 14611//14611 -f 14611//14611 14665//14665 14666//14666 -f 14611//14611 14666//14666 14660//14660 -f 14619//14619 14667//14667 14617//14617 -f 14617//14617 14667//14667 14668//14668 -f 14617//14617 14668//14668 14615//14615 -f 14615//14615 14668//14668 14669//14669 -f 14615//14615 14669//14669 14664//14664 -f 14500//14500 14670//14670 14502//14502 -f 14502//14502 14670//14670 14671//14671 -f 14502//14502 14671//14671 14621//14621 -f 14621//14621 14671//14671 14672//14672 -f 14621//14621 14672//14672 14619//14619 -f 14619//14619 14672//14672 14673//14673 -f 14619//14619 14673//14673 14667//14667 -f 14674//14674 14499//14499 14587//14587 -f 14587//14587 14499//14499 14501//14501 -f 14587//14587 14501//14501 14534//14534 -f 14534//14534 14501//14501 14623//14623 -f 14534//14534 14623//14623 14537//14537 -f 14537//14537 14623//14623 14622//14622 -f 14537//14537 14622//14622 14675//14675 -f 14675//14675 14622//14622 14620//14620 -f 14675//14675 14620//14620 14676//14676 -f 14676//14676 14620//14620 14618//14618 -f 14676//14676 14618//14618 14575//14575 -f 14575//14575 14618//14618 14616//14616 -f 14575//14575 14616//14616 14576//14576 -f 14576//14576 14616//14616 14614//14614 -f 14576//14576 14614//14614 14578//14578 -f 14578//14578 14614//14614 14612//14612 -f 14578//14578 14612//14612 14580//14580 -f 14580//14580 14612//14612 14610//14610 -f 14580//14580 14610//14610 14538//14538 -f 14538//14538 14610//14610 14608//14608 -f 14538//14538 14608//14608 14539//14539 -f 14539//14539 14608//14608 14544//14544 -f 14539//14539 14544//14544 14541//14541 -f 14541//14541 14544//14544 14543//14543 -f 14541//14541 14543//14543 14542//14542 -f 14516//14516 14569//14569 14514//14514 -f 14514//14514 14569//14569 14677//14677 -f 14514//14514 14677//14677 14512//14512 -f 14512//14512 14677//14677 14678//14678 -f 14512//14512 14678//14678 14587//14587 -f 14587//14587 14678//14678 14679//14679 -f 14587//14587 14679//14679 14674//14674 -f 14680//14680 14681//14681 14682//14682 -f 14567//14567 14566//14566 14569//14569 -f 14569//14569 14566//14566 14683//14683 -f 14569//14569 14683//14683 14677//14677 -f 14677//14677 14683//14683 14680//14680 -f 14677//14677 14680//14680 14678//14678 -f 14678//14678 14680//14680 14682//14682 -f 14678//14678 14682//14682 14679//14679 -f 14568//14568 14684//14684 14566//14566 -f 14566//14566 14684//14684 14685//14685 -f 14566//14566 14685//14685 14683//14683 -f 14683//14683 14685//14685 14686//14686 -f 14683//14683 14686//14686 14680//14680 -f 14680//14680 14686//14686 14687//14687 -f 14680//14680 14687//14687 14681//14681 -f 14568//14568 14635//14635 14684//14684 -f 14684//14684 14635//14635 14625//14625 -f 14684//14684 14625//14625 14685//14685 -f 14685//14685 14625//14625 14624//14624 -f 14685//14685 14624//14624 14686//14686 -f 14686//14686 14624//14624 14688//14688 -f 14686//14686 14688//14688 14687//14687 -f 14630//14630 14689//14689 14628//14628 -f 14628//14628 14689//14689 14690//14690 -f 14628//14628 14690//14690 14626//14626 -f 14626//14626 14690//14690 14691//14691 -f 14626//14626 14691//14691 14624//14624 -f 14624//14624 14691//14691 14692//14692 -f 14624//14624 14692//14692 14688//14688 -f 14639//14639 14693//14693 14634//14634 -f 14634//14634 14693//14693 14694//14694 -f 14634//14634 14694//14694 14632//14632 -f 14632//14632 14694//14694 14695//14695 -f 14632//14632 14695//14695 14630//14630 -f 14630//14630 14695//14695 14696//14696 -f 14630//14630 14696//14696 14689//14689 -f 14697//14697 14640//14640 14591//14591 -f 14591//14591 14640//14640 14638//14638 -f 14591//14591 14638//14638 14590//14590 -f 14590//14590 14638//14638 14519//14519 -f 14590//14590 14519//14519 14589//14589 -f 14589//14589 14519//14519 14518//14518 -f 14589//14589 14518//14518 14588//14588 -f 14588//14588 14518//14518 14517//14517 -f 14562//14562 14564//14564 14511//14511 -f 14511//14511 14564//14564 14698//14698 -f 14511//14511 14698//14698 14509//14509 -f 14509//14509 14698//14698 14699//14699 -f 14509//14509 14699//14699 14591//14591 -f 14591//14591 14699//14699 14700//14700 -f 14591//14591 14700//14700 14697//14697 -f 14522//14522 14521//14521 14564//14564 -f 14564//14564 14521//14521 14641//14641 -f 14564//14564 14641//14641 14698//14698 -f 14698//14698 14641//14641 14643//14643 -f 14698//14698 14643//14643 14699//14699 -f 14699//14699 14643//14643 14701//14701 -f 14699//14699 14701//14701 14700//14700 -f 14646//14646 14702//14702 14644//14644 -f 14644//14644 14702//14702 14703//14703 -f 14644//14644 14703//14703 14642//14642 -f 14642//14642 14703//14703 14704//14704 -f 14642//14642 14704//14704 14643//14643 -f 14643//14643 14704//14704 14705//14705 -f 14643//14643 14705//14705 14701//14701 -f 14557//14557 14556//14556 14558//14558 -f 14558//14558 14556//14556 14649//14649 -f 14558//14558 14649//14649 14561//14561 -f 14561//14561 14649//14649 14706//14706 -f 14561//14561 14706//14706 14646//14646 -f 14508//14508 14707//14707 14506//14506 -f 14506//14506 14707//14707 14708//14708 -f 14506//14506 14708//14708 14647//14647 -f 14647//14647 14708//14708 14709//14709 -f 14647//14647 14709//14709 14648//14648 -f 14648//14648 14709//14709 14710//14710 -f 14648//14648 14710//14710 14649//14649 -f 14649//14649 14710//14710 14711//14711 -f 14649//14649 14711//14711 14706//14706 -f 14563//14563 14712//14712 14522//14522 -f 14522//14522 14712//14712 14713//14713 -f 14522//14522 14713//14713 14520//14520 -f 14532//14532 14714//14714 14536//14536 -f 14536//14536 14714//14714 14715//14715 -f 14536//14536 14715//14715 14535//14535 -f 14525//14525 14553//14553 14716//14716 -f 14525//14525 14716//14716 14523//14523 -f 14523//14523 14716//14716 14717//14717 -f 14523//14523 14717//14717 14574//14574 -f 14579//14579 14718//14718 14577//14577 -f 14577//14577 14718//14718 14719//14719 -f 14577//14577 14719//14719 14575//14575 -f 14520//14520 14713//14713 14559//14559 -f 14559//14559 14713//14713 14720//14720 -f 14559//14559 14720//14720 14557//14557 -f 14557//14557 14720//14720 14721//14721 -f 14557//14557 14721//14721 14555//14555 -f 14555//14555 14721//14721 14722//14722 -f 14555//14555 14722//14722 14553//14553 -f 14553//14553 14722//14722 14716//14716 -f 14575//14575 14719//14719 14676//14676 -f 14676//14676 14719//14719 14723//14723 -f 14676//14676 14723//14723 14675//14675 -f 14675//14675 14723//14723 14724//14724 -f 14675//14675 14724//14724 14537//14537 -f 14537//14537 14724//14724 14725//14725 -f 14537//14537 14725//14725 14532//14532 -f 14532//14532 14725//14725 14714//14714 -f 14726//14726 14727//14727 14728//14728 -f 14728//14728 14727//14727 14729//14729 -f 14725//14725 14730//14730 14714//14714 -f 14714//14714 14730//14730 14731//14731 -f 14714//14714 14731//14731 14715//14715 -f 14718//14718 14732//14732 14719//14719 -f 14719//14719 14732//14732 14733//14733 -f 14719//14719 14733//14733 14723//14723 -f 14734//14734 14735//14735 14736//14736 -f 14736//14736 14735//14735 14737//14737 -f 14738//14738 14739//14739 14740//14740 -f 14740//14740 14739//14739 14741//14741 -f 14722//14722 14742//14742 14716//14716 -f 14716//14716 14742//14742 14743//14743 -f 14716//14716 14743//14743 14717//14717 -f 14712//14712 14744//14744 14713//14713 -f 14713//14713 14744//14744 14745//14745 -f 14713//14713 14745//14745 14720//14720 -f 14543//14543 14735//14735 14542//14542 -f 14542//14542 14735//14735 14734//14734 -f 14542//14542 14734//14734 14540//14540 -f 14598//14598 14741//14741 14528//14528 -f 14528//14528 14741//14741 14739//14739 -f 14528//14528 14739//14739 14526//14526 -f 14735//14735 14543//14543 14529//14529 -f 14735//14735 14529//14529 14737//14737 -f 14737//14737 14529//14529 14545//14545 -f 14737//14737 14545//14545 14746//14746 -f 14746//14746 14545//14545 14547//14547 -f 14746//14746 14547//14547 14738//14738 -f 14738//14738 14547//14547 14526//14526 -f 14738//14738 14526//14526 14739//14739 -f 14635//14635 14727//14727 14636//14636 -f 14636//14636 14727//14727 14726//14726 -f 14636//14636 14726//14726 14637//14637 -f 14637//14637 14726//14726 14747//14747 -f 14637//14637 14747//14747 14565//14565 -f 14565//14565 14747//14747 14748//14748 -f 14565//14565 14748//14748 14517//14517 -f 14517//14517 14748//14748 14749//14749 -f 14517//14517 14749//14749 14588//14588 -f 14588//14588 14749//14749 14750//14750 -f 14588//14588 14750//14750 14585//14585 -f 14567//14567 14729//14729 14568//14568 -f 14568//14568 14729//14729 14727//14727 -f 14568//14568 14727//14727 14635//14635 -f 14751//14751 14752//14752 14753//14753 -f 14751//14751 14754//14754 14752//14752 -f 14752//14752 14754//14754 14755//14755 -f 14752//14752 14755//14755 14756//14756 -f 14756//14756 14755//14755 14757//14757 -f 14756//14756 14757//14757 14758//14758 -f 14758//14758 14757//14757 14759//14759 -f 14758//14758 14759//14759 14760//14760 -f 14760//14760 14761//14761 14758//14758 -f 14758//14758 14761//14761 14762//14762 -f 14758//14758 14762//14762 14763//14763 -f 14763//14763 14762//14762 14764//14764 -f 14763//14763 14764//14764 14765//14765 -f 14765//14765 14764//14764 14766//14766 -f 14765//14765 14766//14766 14767//14767 -f 14767//14767 14768//14768 14765//14765 -f 14765//14765 14768//14768 14769//14769 -f 14765//14765 14769//14769 14770//14770 -f 14770//14770 14769//14769 14771//14771 -f 14770//14770 14771//14771 14772//14772 -f 14772//14772 14771//14771 14773//14773 -f 14772//14772 14773//14773 14774//14774 -f 14775//14775 14776//14776 14777//14777 -f 14777//14777 14776//14776 14772//14772 -f 14777//14777 14772//14772 14778//14778 -f 14778//14778 14772//14772 14774//14774 -f 14775//14775 14779//14779 14776//14776 -f 14776//14776 14779//14779 14780//14780 -f 14776//14776 14780//14780 14781//14781 -f 14782//14782 14783//14783 14784//14784 -f 14784//14784 14783//14783 14781//14781 -f 14784//14784 14781//14781 14785//14785 -f 14785//14785 14781//14781 14780//14780 -f 14782//14782 14786//14786 14783//14783 -f 14783//14783 14786//14786 14787//14787 -f 14783//14783 14787//14787 14788//14788 -f 14789//14789 14790//14790 14791//14791 -f 14791//14791 14790//14790 14788//14788 -f 14791//14791 14788//14788 14792//14792 -f 14792//14792 14788//14788 14787//14787 -f 14789//14789 14793//14793 14790//14790 -f 14790//14790 14793//14793 14794//14794 -f 14790//14790 14794//14794 14795//14795 -f 14796//14796 14797//14797 14798//14798 -f 14798//14798 14797//14797 14795//14795 -f 14798//14798 14795//14795 14799//14799 -f 14799//14799 14795//14795 14794//14794 -f 14796//14796 14800//14800 14797//14797 -f 14797//14797 14800//14800 14801//14801 -f 14797//14797 14801//14801 14802//14802 -f 14803//14803 14804//14804 14805//14805 -f 14805//14805 14804//14804 14802//14802 -f 14805//14805 14802//14802 14806//14806 -f 14806//14806 14802//14802 14801//14801 -f 14803//14803 14807//14807 14804//14804 -f 14804//14804 14807//14807 14808//14808 -f 14804//14804 14808//14808 14809//14809 -f 14810//14810 14811//14811 14812//14812 -f 14812//14812 14811//14811 14809//14809 -f 14812//14812 14809//14809 14813//14813 -f 14813//14813 14809//14809 14808//14808 -f 14810//14810 14814//14814 14811//14811 -f 14811//14811 14814//14814 14815//14815 -f 14811//14811 14815//14815 14816//14816 -f 14815//14815 14817//14817 14816//14816 -f 14816//14816 14817//14817 14818//14818 -f 14816//14816 14818//14818 14819//14819 -f 14818//14818 14820//14820 14819//14819 -f 14819//14819 14820//14820 14821//14821 -f 14819//14819 14821//14821 14753//14753 -f 14753//14753 14821//14821 14822//14822 -f 14753//14753 14822//14822 14751//14751 -f 14823//14823 14824//14824 14825//14825 -f 14825//14825 14824//14824 14826//14826 -f 14825//14825 14826//14826 14827//14827 -f 14827//14827 14826//14826 14828//14828 -f 14827//14827 14828//14828 14829//14829 -f 14829//14829 14828//14828 14830//14830 -f 14829//14829 14830//14830 14831//14831 -f 14831//14831 14830//14830 14832//14832 -f 14831//14831 14832//14832 14833//14833 -f 14833//14833 14832//14832 14834//14834 -f 14833//14833 14834//14834 14835//14835 -f 14835//14835 14834//14834 14836//14836 -f 14835//14835 14836//14836 14837//14837 -f 14837//14837 14836//14836 14838//14838 -f 14837//14837 14838//14838 14839//14839 -f 14839//14839 14838//14838 14840//14840 -f 14839//14839 14840//14840 14841//14841 -f 14841//14841 14840//14840 14842//14842 -f 14841//14841 14842//14842 14843//14843 -f 14843//14843 14842//14842 14844//14844 -f 14843//14843 14844//14844 14845//14845 -f 14845//14845 14844//14844 14846//14846 -f 14845//14845 14846//14846 14847//14847 -f 14847//14847 14846//14846 14848//14848 -f 14847//14847 14848//14848 14849//14849 -f 14849//14849 14848//14848 14850//14850 -f 14849//14849 14850//14850 14851//14851 -f 14851//14851 14850//14850 14852//14852 -f 14851//14851 14852//14852 14853//14853 -f 14853//14853 14852//14852 14854//14854 -f 14853//14853 14854//14854 14855//14855 -f 14855//14855 14854//14854 14856//14856 -f 14855//14855 14856//14856 14857//14857 -f 14857//14857 14856//14856 14858//14858 -f 14857//14857 14858//14858 14859//14859 -f 14859//14859 14858//14858 14860//14860 -f 14859//14859 14860//14860 14861//14861 -f 14861//14861 14860//14860 14862//14862 -f 14861//14861 14862//14862 14863//14863 -f 14863//14863 14862//14862 14864//14864 -f 14863//14863 14864//14864 14865//14865 -f 14865//14865 14864//14864 14866//14866 -f 14865//14865 14866//14866 14867//14867 -f 14867//14867 14866//14866 14868//14868 -f 14867//14867 14868//14868 14869//14869 -f 14869//14869 14868//14868 14870//14870 -f 14869//14869 14870//14870 14871//14871 -f 14871//14871 14870//14870 14872//14872 -f 14871//14871 14872//14872 14873//14873 -f 14873//14873 14872//14872 14874//14874 -f 14873//14873 14874//14874 14875//14875 -f 14875//14875 14874//14874 14876//14876 -f 14875//14875 14876//14876 14877//14877 -f 14877//14877 14876//14876 14878//14878 -f 14877//14877 14878//14878 14879//14879 -f 14879//14879 14878//14878 14880//14880 -f 14879//14879 14880//14880 14881//14881 -f 14881//14881 14880//14880 14882//14882 -f 14881//14881 14882//14882 14883//14883 -f 14883//14883 14882//14882 14823//14823 -f 14883//14883 14823//14823 14825//14825 -f 14853//14853 14855//14855 14884//14884 -f 14884//14884 14885//14885 14853//14853 -f 14853//14853 14885//14885 14886//14886 -f 14853//14853 14886//14886 14851//14851 -f 14886//14886 14887//14887 14851//14851 -f 14851//14851 14887//14887 14888//14888 -f 14851//14851 14888//14888 14849//14849 -f 14888//14888 14889//14889 14849//14849 -f 14849//14849 14889//14889 14890//14890 -f 14849//14849 14890//14890 14847//14847 -f 14890//14890 14891//14891 14847//14847 -f 14847//14847 14891//14891 14892//14892 -f 14847//14847 14892//14892 14845//14845 -f 14892//14892 14893//14893 14845//14845 -f 14845//14845 14893//14893 14894//14894 -f 14845//14845 14894//14894 14843//14843 -f 14894//14894 14895//14895 14843//14843 -f 14843//14843 14895//14895 14896//14896 -f 14843//14843 14896//14896 14841//14841 -f 14896//14896 14897//14897 14841//14841 -f 14841//14841 14897//14897 14898//14898 -f 14841//14841 14898//14898 14839//14839 -f 14898//14898 14899//14899 14839//14839 -f 14839//14839 14899//14899 14900//14900 -f 14839//14839 14900//14900 14837//14837 -f 14900//14900 14901//14901 14837//14837 -f 14837//14837 14901//14901 14902//14902 -f 14837//14837 14902//14902 14835//14835 -f 14902//14902 14903//14903 14835//14835 -f 14835//14835 14903//14903 14904//14904 -f 14835//14835 14904//14904 14833//14833 -f 14904//14904 14905//14905 14833//14833 -f 14833//14833 14905//14905 14906//14906 -f 14833//14833 14906//14906 14831//14831 -f 14906//14906 14907//14907 14831//14831 -f 14831//14831 14907//14907 14908//14908 -f 14831//14831 14908//14908 14829//14829 -f 14908//14908 14909//14909 14829//14829 -f 14829//14829 14909//14909 14910//14910 -f 14829//14829 14910//14910 14827//14827 -f 14910//14910 14911//14911 14827//14827 -f 14827//14827 14911//14911 14912//14912 -f 14827//14827 14912//14912 14825//14825 -f 14912//14912 14913//14913 14825//14825 -f 14825//14825 14913//14913 14914//14914 -f 14825//14825 14914//14914 14883//14883 -f 14914//14914 14915//14915 14883//14883 -f 14883//14883 14915//14915 14916//14916 -f 14883//14883 14916//14916 14881//14881 -f 14916//14916 14917//14917 14881//14881 -f 14881//14881 14917//14917 14918//14918 -f 14881//14881 14918//14918 14879//14879 -f 14918//14918 14919//14919 14879//14879 -f 14879//14879 14919//14919 14920//14920 -f 14879//14879 14920//14920 14877//14877 -f 14920//14920 14921//14921 14877//14877 -f 14877//14877 14921//14921 14922//14922 -f 14877//14877 14922//14922 14875//14875 -f 14922//14922 14923//14923 14875//14875 -f 14875//14875 14923//14923 14924//14924 -f 14875//14875 14924//14924 14873//14873 -f 14924//14924 14925//14925 14873//14873 -f 14873//14873 14925//14925 14926//14926 -f 14873//14873 14926//14926 14871//14871 -f 14926//14926 14927//14927 14871//14871 -f 14871//14871 14927//14927 14928//14928 -f 14871//14871 14928//14928 14869//14869 -f 14928//14928 14929//14929 14869//14869 -f 14869//14869 14929//14929 14930//14930 -f 14869//14869 14930//14930 14867//14867 -f 14930//14930 14931//14931 14867//14867 -f 14867//14867 14931//14931 14932//14932 -f 14867//14867 14932//14932 14865//14865 -f 14932//14932 14933//14933 14865//14865 -f 14865//14865 14933//14933 14934//14934 -f 14865//14865 14934//14934 14863//14863 -f 14934//14934 14935//14935 14863//14863 -f 14863//14863 14935//14935 14936//14936 -f 14863//14863 14936//14936 14861//14861 -f 14936//14936 14937//14937 14861//14861 -f 14861//14861 14937//14937 14938//14938 -f 14861//14861 14938//14938 14859//14859 -f 14938//14938 14939//14939 14859//14859 -f 14859//14859 14939//14939 14940//14940 -f 14859//14859 14940//14940 14857//14857 -f 14940//14940 14941//14941 14857//14857 -f 14857//14857 14941//14941 14942//14942 -f 14857//14857 14942//14942 14855//14855 -f 14855//14855 14942//14942 14943//14943 -f 14855//14855 14943//14943 14884//14884 -f 14655//14655 14944//14944 14656//14656 -f 14656//14656 14944//14944 14945//14945 -f 14656//14656 14945//14945 14657//14657 -f 14657//14657 14945//14945 14946//14946 -f 14657//14657 14946//14946 14658//14658 -f 14658//14658 14946//14946 14947//14947 -f 14658//14658 14947//14947 14603//14603 -f 14603//14603 14947//14947 14948//14948 -f 14603//14603 14948//14948 14602//14602 -f 14602//14602 14948//14948 14949//14949 -f 14602//14602 14949//14949 14651//14651 -f 14651//14651 14949//14949 14950//14950 -f 14651//14651 14950//14950 14652//14652 -f 14652//14652 14950//14950 14951//14951 -f 14652//14652 14951//14951 14653//14653 -f 14653//14653 14951//14951 14952//14952 -f 14653//14653 14952//14952 14654//14654 -f 14654//14654 14952//14952 14953//14953 -f 14654//14654 14953//14953 14650//14650 -f 14650//14650 14953//14953 14954//14954 -f 14650//14650 14954//14954 14508//14508 -f 14508//14508 14954//14954 14955//14955 -f 14508//14508 14955//14955 14707//14707 -f 14707//14707 14955//14955 14956//14956 -f 14707//14707 14956//14956 14708//14708 -f 14708//14708 14956//14956 14957//14957 -f 14708//14708 14957//14957 14709//14709 -f 14709//14709 14957//14957 14958//14958 -f 14709//14709 14958//14958 14710//14710 -f 14710//14710 14958//14958 14959//14959 -f 14710//14710 14959//14959 14711//14711 -f 14711//14711 14959//14959 14960//14960 -f 14711//14711 14960//14960 14706//14706 -f 14706//14706 14960//14960 14961//14961 -f 14706//14706 14961//14961 14646//14646 -f 14646//14646 14961//14961 14962//14962 -f 14646//14646 14962//14962 14702//14702 -f 14702//14702 14962//14962 14963//14963 -f 14702//14702 14963//14963 14703//14703 -f 14703//14703 14963//14963 14964//14964 -f 14703//14703 14964//14964 14704//14704 -f 14704//14704 14964//14964 14965//14965 -f 14704//14704 14965//14965 14705//14705 -f 14705//14705 14965//14965 14966//14966 -f 14705//14705 14966//14966 14701//14701 -f 14701//14701 14966//14966 14967//14967 -f 14701//14701 14967//14967 14700//14700 -f 14700//14700 14967//14967 14968//14968 -f 14700//14700 14968//14968 14697//14697 -f 14697//14697 14968//14968 14969//14969 -f 14697//14697 14969//14969 14640//14640 -f 14640//14640 14969//14969 14970//14970 -f 14640//14640 14970//14970 14639//14639 -f 14639//14639 14970//14970 14971//14971 -f 14639//14639 14971//14971 14693//14693 -f 14693//14693 14971//14971 14972//14972 -f 14693//14693 14972//14972 14694//14694 -f 14694//14694 14972//14972 14973//14973 -f 14694//14694 14973//14973 14695//14695 -f 14695//14695 14973//14973 14974//14974 -f 14695//14695 14974//14974 14696//14696 -f 14696//14696 14974//14974 14975//14975 -f 14696//14696 14975//14975 14689//14689 -f 14689//14689 14975//14975 14976//14976 -f 14689//14689 14976//14976 14690//14690 -f 14690//14690 14976//14976 14977//14977 -f 14690//14690 14977//14977 14691//14691 -f 14691//14691 14977//14977 14978//14978 -f 14691//14691 14978//14978 14692//14692 -f 14692//14692 14978//14978 14979//14979 -f 14692//14692 14979//14979 14688//14688 -f 14688//14688 14979//14979 14980//14980 -f 14688//14688 14980//14980 14687//14687 -f 14687//14687 14980//14980 14981//14981 -f 14687//14687 14981//14981 14681//14681 -f 14681//14681 14981//14981 14982//14982 -f 14681//14681 14982//14982 14682//14682 -f 14682//14682 14982//14982 14983//14983 -f 14682//14682 14983//14983 14679//14679 -f 14679//14679 14983//14983 14984//14984 -f 14679//14679 14984//14984 14674//14674 -f 14674//14674 14984//14984 14985//14985 -f 14674//14674 14985//14985 14499//14499 -f 14499//14499 14985//14985 14986//14986 -f 14499//14499 14986//14986 14500//14500 -f 14500//14500 14986//14986 14987//14987 -f 14500//14500 14987//14987 14670//14670 -f 14670//14670 14987//14987 14988//14988 -f 14670//14670 14988//14988 14671//14671 -f 14671//14671 14988//14988 14989//14989 -f 14671//14671 14989//14989 14672//14672 -f 14672//14672 14989//14989 14990//14990 -f 14672//14672 14990//14990 14673//14673 -f 14673//14673 14990//14990 14991//14991 -f 14673//14673 14991//14991 14667//14667 -f 14667//14667 14991//14991 14992//14992 -f 14667//14667 14992//14992 14668//14668 -f 14668//14668 14992//14992 14993//14993 -f 14668//14668 14993//14993 14669//14669 -f 14669//14669 14993//14993 14994//14994 -f 14669//14669 14994//14994 14664//14664 -f 14664//14664 14994//14994 14995//14995 -f 14664//14664 14995//14995 14665//14665 -f 14665//14665 14995//14995 14996//14996 -f 14665//14665 14996//14996 14666//14666 -f 14666//14666 14996//14996 14997//14997 -f 14666//14666 14997//14997 14660//14660 -f 14660//14660 14997//14997 14998//14998 -f 14660//14660 14998//14998 14661//14661 -f 14661//14661 14998//14998 14999//14999 -f 14661//14661 14999//14999 14662//14662 -f 14662//14662 14999//14999 15000//15000 -f 14662//14662 15000//15000 14663//14663 -f 14663//14663 15000//15000 15001//15001 -f 14663//14663 15001//15001 14659//14659 -f 14659//14659 15001//15001 15002//15002 -f 14659//14659 15002//15002 14505//14505 -f 14505//14505 15002//15002 15003//15003 -f 14505//14505 15003//15003 14655//14655 -f 14655//14655 15003//15003 14944//14944 -f 15003//15003 14942//14942 14944//14944 -f 14944//14944 14942//14942 14941//14941 -f 14944//14944 14941//14941 14945//14945 -f 14945//14945 14941//14941 14940//14940 -f 14945//14945 14940//14940 14946//14946 -f 14946//14946 14940//14940 14939//14939 -f 14946//14946 14939//14939 14947//14947 -f 14947//14947 14939//14939 14938//14938 -f 14947//14947 14938//14938 14948//14948 -f 14948//14948 14938//14938 14937//14937 -f 14948//14948 14937//14937 14949//14949 -f 14949//14949 14937//14937 14936//14936 -f 14949//14949 14936//14936 14950//14950 -f 14950//14950 14936//14936 14935//14935 -f 14950//14950 14935//14935 14951//14951 -f 14951//14951 14935//14935 14934//14934 -f 14951//14951 14934//14934 14952//14952 -f 14952//14952 14934//14934 14933//14933 -f 14952//14952 14933//14933 14953//14953 -f 14953//14953 14933//14933 14932//14932 -f 14953//14953 14932//14932 14954//14954 -f 14954//14954 14932//14932 14931//14931 -f 14954//14954 14931//14931 14955//14955 -f 14955//14955 14931//14931 14930//14930 -f 14955//14955 14930//14930 14956//14956 -f 14956//14956 14930//14930 14929//14929 -f 14956//14956 14929//14929 14957//14957 -f 14957//14957 14929//14929 14928//14928 -f 14957//14957 14928//14928 14958//14958 -f 14958//14958 14928//14928 14927//14927 -f 14958//14958 14927//14927 14959//14959 -f 14959//14959 14927//14927 14926//14926 -f 14959//14959 14926//14926 14960//14960 -f 14960//14960 14926//14926 14925//14925 -f 14960//14960 14925//14925 14961//14961 -f 14961//14961 14925//14925 14924//14924 -f 14961//14961 14924//14924 14962//14962 -f 14962//14962 14924//14924 14923//14923 -f 14962//14962 14923//14923 14963//14963 -f 14963//14963 14923//14923 14922//14922 -f 14963//14963 14922//14922 14964//14964 -f 14964//14964 14922//14922 14921//14921 -f 14964//14964 14921//14921 14965//14965 -f 14965//14965 14921//14921 14920//14920 -f 14965//14965 14920//14920 14966//14966 -f 14966//14966 14920//14920 14919//14919 -f 14966//14966 14919//14919 14967//14967 -f 14967//14967 14919//14919 14918//14918 -f 14967//14967 14918//14918 14968//14968 -f 14968//14968 14918//14918 14917//14917 -f 14968//14968 14917//14917 14969//14969 -f 14969//14969 14917//14917 14916//14916 -f 14969//14969 14916//14916 14970//14970 -f 14970//14970 14916//14916 14915//14915 -f 14970//14970 14915//14915 14971//14971 -f 14971//14971 14915//14915 14914//14914 -f 14971//14971 14914//14914 14972//14972 -f 14972//14972 14914//14914 14913//14913 -f 14972//14972 14913//14913 14973//14973 -f 14973//14973 14913//14913 14912//14912 -f 14973//14973 14912//14912 14974//14974 -f 14974//14974 14912//14912 14911//14911 -f 14974//14974 14911//14911 14975//14975 -f 14975//14975 14911//14911 14910//14910 -f 14975//14975 14910//14910 14976//14976 -f 14976//14976 14910//14910 14909//14909 -f 14976//14976 14909//14909 14977//14977 -f 14977//14977 14909//14909 14908//14908 -f 14977//14977 14908//14908 14978//14978 -f 14978//14978 14908//14908 14907//14907 -f 14978//14978 14907//14907 14979//14979 -f 14979//14979 14907//14907 14906//14906 -f 14979//14979 14906//14906 14980//14980 -f 14980//14980 14906//14906 14905//14905 -f 14980//14980 14905//14905 14981//14981 -f 14981//14981 14905//14905 14904//14904 -f 14981//14981 14904//14904 14982//14982 -f 14982//14982 14904//14904 14903//14903 -f 14982//14982 14903//14903 14983//14983 -f 14983//14983 14903//14903 14902//14902 -f 14983//14983 14902//14902 14984//14984 -f 14984//14984 14902//14902 14901//14901 -f 14984//14984 14901//14901 14985//14985 -f 14985//14985 14901//14901 14900//14900 -f 14985//14985 14900//14900 14986//14986 -f 14986//14986 14900//14900 14899//14899 -f 14986//14986 14899//14899 14987//14987 -f 14987//14987 14899//14899 14898//14898 -f 14987//14987 14898//14898 14988//14988 -f 14988//14988 14898//14898 14897//14897 -f 14988//14988 14897//14897 14989//14989 -f 14989//14989 14897//14897 14896//14896 -f 14989//14989 14896//14896 14990//14990 -f 14990//14990 14896//14896 14895//14895 -f 14990//14990 14895//14895 14991//14991 -f 14991//14991 14895//14895 14894//14894 -f 14991//14991 14894//14894 14992//14992 -f 14992//14992 14894//14894 14893//14893 -f 14992//14992 14893//14893 14993//14993 -f 14993//14993 14893//14893 14892//14892 -f 14993//14993 14892//14892 14994//14994 -f 14994//14994 14892//14892 14891//14891 -f 14994//14994 14891//14891 14995//14995 -f 14995//14995 14891//14891 14890//14890 -f 14995//14995 14890//14890 14996//14996 -f 14996//14996 14890//14890 14889//14889 -f 14996//14996 14889//14889 14997//14997 -f 14997//14997 14889//14889 14888//14888 -f 14997//14997 14888//14888 14998//14998 -f 14998//14998 14888//14888 14887//14887 -f 14998//14998 14887//14887 14999//14999 -f 14999//14999 14887//14887 14886//14886 -f 14999//14999 14886//14886 15000//15000 -f 15000//15000 14886//14886 14885//14885 -f 15000//15000 14885//14885 15001//15001 -f 15001//15001 14885//14885 14884//14884 -f 15001//15001 14884//14884 15002//15002 -f 15002//15002 14884//14884 14943//14943 -f 15002//15002 14943//14943 15003//15003 -f 15003//15003 14943//14943 14942//14942 -f 14816//14816 14819//14819 15004//15004 -f 15004//15004 14819//14819 14753//14753 -f 15004//15004 14753//14753 14752//14752 -f 14804//14804 14809//14809 15004//15004 -f 15004//15004 14809//14809 14811//14811 -f 15004//15004 14811//14811 14816//14816 -f 14795//14795 14797//14797 15004//15004 -f 15004//15004 14797//14797 14802//14802 -f 15004//15004 14802//14802 14804//14804 -f 14783//14783 14788//14788 15004//15004 -f 15004//15004 14788//14788 14790//14790 -f 15004//15004 14790//14790 14795//14795 -f 14772//14772 14776//14776 15004//15004 -f 15004//15004 14776//14776 14781//14781 -f 15004//15004 14781//14781 14783//14783 -f 14763//14763 14765//14765 15004//15004 -f 15004//15004 14765//14765 14770//14770 -f 15004//15004 14770//14770 14772//14772 -f 14752//14752 14756//14756 15004//15004 -f 15004//15004 14756//14756 14758//14758 -f 15004//15004 14758//14758 14763//14763 -f 14817//14817 14815//14815 15005//15005 -f 15005//15005 14815//14815 15006//15006 -f 15007//15007 15008//15008 14808//14808 -f 15009//15009 15010//15010 14801//14801 -f 15011//15011 15012//15012 14794//14794 -f 15013//15013 15014//15014 14787//14787 -f 15015//15015 15016//15016 14780//14780 -f 15017//15017 15018//15018 14774//14774 -f 15019//15019 15020//15020 14767//14767 -f 14862//14862 14860//14860 15021//15021 -f 14852//14852 14850//14850 15022//15022 -f 14862//14862 15023//15023 14864//14864 -f 14864//14864 15023//15023 15024//15024 -f 14864//14864 15024//15024 14866//14866 -f 14866//14866 15024//15024 15025//15025 -f 14866//14866 15025//15025 14868//14868 -f 14868//14868 15025//15025 15026//15026 -f 14868//14868 15026//15026 14870//14870 -f 14870//14870 15026//15026 15027//15027 -f 14870//14870 15027//15027 14872//14872 -f 14872//14872 15027//15027 15028//15028 -f 14872//14872 15028//15028 14874//14874 -f 14874//14874 15028//15028 15029//15029 -f 14874//14874 15029//15029 14876//14876 -f 14876//14876 15029//15029 15030//15030 -f 14876//14876 15030//15030 14878//14878 -f 14878//14878 15030//15030 15031//15031 -f 14878//14878 15031//15031 14880//14880 -f 14880//14880 15031//15031 15032//15032 -f 14880//14880 15032//15032 14882//14882 -f 14882//14882 15032//15032 15033//15033 -f 14882//14882 15033//15033 14823//14823 -f 14823//14823 15033//15033 15034//15034 -f 14823//14823 15034//15034 14824//14824 -f 14824//14824 15034//15034 15035//15035 -f 14824//14824 15035//15035 14826//14826 -f 14826//14826 15035//15035 15036//15036 -f 14826//14826 15036//15036 14828//14828 -f 14828//14828 15036//15036 15037//15037 -f 14828//14828 15037//15037 14830//14830 -f 14830//14830 15037//15037 15038//15038 -f 14830//14830 15038//15038 14832//14832 -f 14832//14832 15038//15038 15039//15039 -f 14832//14832 15039//15039 14834//14834 -f 14834//14834 15039//15039 15040//15040 -f 14834//14834 15040//15040 14836//14836 -f 14836//14836 15040//15040 15041//15041 -f 14836//14836 15041//15041 14838//14838 -f 14838//14838 15041//15041 15042//15042 -f 14838//14838 15042//15042 14840//14840 -f 14840//14840 15042//15042 15043//15043 -f 14840//14840 15043//15043 14842//14842 -f 14842//14842 15043//15043 15044//15044 -f 14842//14842 15044//15044 14844//14844 -f 14844//14844 15044//15044 15045//15045 -f 14844//14844 15045//15045 14846//14846 -f 14846//14846 15045//15045 15046//15046 -f 14846//14846 15046//15046 14848//14848 -f 14848//14848 15046//15046 15047//15047 -f 14848//14848 15047//15047 14850//14850 -f 14854//14854 15048//15048 14856//14856 -f 14856//14856 15048//15048 15049//15049 -f 14856//14856 15049//15049 14858//14858 -f 14858//14858 15049//15049 15050//15050 -f 14858//14858 15050//15050 14860//14860 -f 15023//15023 15005//15005 15024//15024 -f 15024//15024 15005//15005 15006//15006 -f 15024//15024 15006//15006 15025//15025 -f 15025//15025 15006//15006 15051//15051 -f 15025//15025 15051//15051 15026//15026 -f 15026//15026 15051//15051 15008//15008 -f 15026//15026 15008//15008 15027//15027 -f 15027//15027 15008//15008 15007//15007 -f 15027//15027 15007//15007 15028//15028 -f 15028//15028 15007//15007 15052//15052 -f 15028//15028 15052//15052 15029//15029 -f 15029//15029 15052//15052 15010//15010 -f 15029//15029 15010//15010 15030//15030 -f 15030//15030 15010//15010 15009//15009 -f 15030//15030 15009//15009 15031//15031 -f 15031//15031 15009//15009 15053//15053 -f 15031//15031 15053//15053 15032//15032 -f 15032//15032 15053//15053 15012//15012 -f 15032//15032 15012//15012 15033//15033 -f 15033//15033 15012//15012 15011//15011 -f 15033//15033 15011//15011 15034//15034 -f 15034//15034 15011//15011 15054//15054 -f 15034//15034 15054//15054 15035//15035 -f 15035//15035 15054//15054 15014//15014 -f 15035//15035 15014//15014 15036//15036 -f 15036//15036 15014//15014 15013//15013 -f 15036//15036 15013//15013 15037//15037 -f 15037//15037 15013//15013 15055//15055 -f 15037//15037 15055//15055 15038//15038 -f 15038//15038 15055//15055 15016//15016 -f 15038//15038 15016//15016 15039//15039 -f 15039//15039 15016//15016 15015//15015 -f 15039//15039 15015//15015 15040//15040 -f 15040//15040 15015//15015 15056//15056 -f 15040//15040 15056//15056 15041//15041 -f 15041//15041 15056//15056 15018//15018 -f 15041//15041 15018//15018 15042//15042 -f 15042//15042 15018//15018 15017//15017 -f 15042//15042 15017//15017 15043//15043 -f 15043//15043 15017//15017 15057//15057 -f 15043//15043 15057//15057 15044//15044 -f 15044//15044 15057//15057 15020//15020 -f 15044//15044 15020//15020 15045//15045 -f 15045//15045 15020//15020 15019//15019 -f 15045//15045 15019//15019 15046//15046 -f 15046//15046 15019//15019 15058//15058 -f 15046//15046 15058//15058 15047//15047 -f 15047//15047 15058//15058 15059//15059 -f 15048//15048 15060//15060 15049//15049 -f 15049//15049 15060//15060 15061//15061 -f 15049//15049 15061//15061 15050//15050 -f 15050//15050 15061//15061 15062//15062 -f 14755//14755 15060//15060 15063//15063 -f 15063//15063 15060//15060 15048//15048 -f 15063//15063 15048//15048 15064//15064 -f 15064//15064 15048//15048 14854//14854 -f 15064//15064 14854//14854 14852//14852 -f 15065//15065 14759//14759 14757//14757 -f 14852//14852 15022//15022 15064//15064 -f 15064//15064 15022//15022 15065//15065 -f 15064//15064 15065//15065 15063//15063 -f 15063//15063 15065//15065 14757//14757 -f 15063//15063 14757//14757 14755//14755 -f 14850//14850 15047//15047 15022//15022 -f 15022//15022 15047//15047 15059//15059 -f 15022//15022 15059//15059 15065//15065 -f 15065//15065 15059//15059 14760//14760 -f 15065//15065 14760//14760 14759//14759 -f 14767//14767 14766//14766 15019//15019 -f 15019//15019 14766//14766 14764//14764 -f 15019//15019 14764//14764 15058//15058 -f 15058//15058 14764//14764 14762//14762 -f 15058//15058 14762//14762 15059//15059 -f 15059//15059 14762//14762 14761//14761 -f 15059//15059 14761//14761 14760//14760 -f 14774//14774 14773//14773 15017//15017 -f 15017//15017 14773//14773 14771//14771 -f 15017//15017 14771//14771 15057//15057 -f 15057//15057 14771//14771 14769//14769 -f 15057//15057 14769//14769 15020//15020 -f 15020//15020 14769//14769 14768//14768 -f 15020//15020 14768//14768 14767//14767 -f 14780//14780 14779//14779 15015//15015 -f 15015//15015 14779//14779 14775//14775 -f 15015//15015 14775//14775 15056//15056 -f 15056//15056 14775//14775 14777//14777 -f 15056//15056 14777//14777 15018//15018 -f 15018//15018 14777//14777 14778//14778 -f 15018//15018 14778//14778 14774//14774 -f 14787//14787 14786//14786 15013//15013 -f 15013//15013 14786//14786 14782//14782 -f 15013//15013 14782//14782 15055//15055 -f 15055//15055 14782//14782 14784//14784 -f 15055//15055 14784//14784 15016//15016 -f 15016//15016 14784//14784 14785//14785 -f 15016//15016 14785//14785 14780//14780 -f 14794//14794 14793//14793 15011//15011 -f 15011//15011 14793//14793 14789//14789 -f 15011//15011 14789//14789 15054//15054 -f 15054//15054 14789//14789 14791//14791 -f 15054//15054 14791//14791 15014//15014 -f 15014//15014 14791//14791 14792//14792 -f 15014//15014 14792//14792 14787//14787 -f 14801//14801 14800//14800 15009//15009 -f 15009//15009 14800//14800 14796//14796 -f 15009//15009 14796//14796 15053//15053 -f 15053//15053 14796//14796 14798//14798 -f 15053//15053 14798//14798 15012//15012 -f 15012//15012 14798//14798 14799//14799 -f 15012//15012 14799//14799 14794//14794 -f 14808//14808 14807//14807 15007//15007 -f 15007//15007 14807//14807 14803//14803 -f 15007//15007 14803//14803 15052//15052 -f 15052//15052 14803//14803 14805//14805 -f 15052//15052 14805//14805 15010//15010 -f 15010//15010 14805//14805 14806//14806 -f 15010//15010 14806//14806 14801//14801 -f 14815//14815 14814//14814 15006//15006 -f 15006//15006 14814//14814 14810//14810 -f 15006//15006 14810//14810 15051//15051 -f 15051//15051 14810//14810 14812//14812 -f 15051//15051 14812//14812 15008//15008 -f 15008//15008 14812//14812 14813//14813 -f 15008//15008 14813//14813 14808//14808 -f 14862//14862 15021//15021 15023//15023 -f 15023//15023 15021//15021 15066//15066 -f 15023//15023 15066//15066 15005//15005 -f 15005//15005 15066//15066 14818//14818 -f 15005//15005 14818//14818 14817//14817 -f 14860//14860 15050//15050 15021//15021 -f 15021//15021 15050//15050 15062//15062 -f 15021//15021 15062//15062 15066//15066 -f 15066//15066 15062//15062 14820//14820 -f 15066//15066 14820//14820 14818//14818 -f 14755//14755 14754//14754 15060//15060 -f 15060//15060 14754//14754 14751//14751 -f 15060//15060 14751//14751 15061//15061 -f 15061//15061 14751//14751 14822//14822 -f 15061//15061 14822//14822 15062//15062 -f 15062//15062 14822//14822 14821//14821 -f 15062//15062 14821//14821 14820//14820 -f 14750//14750 14749//14749 15067//15067 -f 15067//15067 14749//14749 14748//14748 -f 14720//14720 14722//14722 14721//14721 -f 14723//14723 14725//14725 14724//14724 -f 14540//14540 14734//14734 14582//14582 -f 14582//14582 14734//14734 14718//14718 -f 14582//14582 14718//14718 14581//14581 -f 14581//14581 14718//14718 14579//14579 -f 14737//14737 14746//14746 15068//15068 -f 15068//15068 14746//14746 14738//14738 -f 14748//14748 14747//14747 15069//15069 -f 15069//15069 14747//14747 14726//14726 -f 14598//14598 14570//14570 14741//14741 -f 14741//14741 14570//14570 14572//14572 -f 14741//14741 14572//14572 14717//14717 -f 14717//14717 14572//14572 14573//14573 -f 14717//14717 14573//14573 14574//14574 -f 14563//14563 14562//14562 14712//14712 -f 14712//14712 14562//14562 14583//14583 -f 14712//14712 14583//14583 14750//14750 -f 14750//14750 14583//14583 14584//14584 -f 14750//14750 14584//14584 14585//14585 -f 14515//14515 14535//14535 14715//14715 -f 14515//14515 14715//14715 14516//14516 -f 14516//14516 14715//14715 14729//14729 -f 14516//14516 14729//14729 14567//14567 -f 14738//14738 14740//14740 15070//15070 -f 14750//14750 15067//15067 15070//15070 -f 14748//14748 15069//15069 15070//15070 -f 14726//14726 14728//14728 15070//15070 -f 15070//15070 14736//14736 14737//14737 -f 15068//15068 15070//15070 14737//14737 -f 14734//14734 14736//14736 15070//15070 -f 15070//15070 14732//14732 14718//14718 -f 14733//14733 14732//14732 15070//15070 -f 14723//14723 14733//14733 15070//15070 -f 14718//14718 14734//14734 15070//15070 -f 15070//15070 14730//14730 14725//14725 -f 14731//14731 14730//14730 15070//15070 -f 14715//14715 14731//14731 15070//15070 -f 14725//14725 14723//14723 15070//15070 -f 14729//14729 14715//14715 15070//15070 -f 14728//14728 14729//14729 15070//15070 -f 15069//15069 14726//14726 15070//15070 -f 15067//15067 14748//14748 15070//15070 -f 15070//15070 14744//14744 14712//14712 -f 14745//14745 14744//14744 15070//15070 -f 14720//14720 14745//14745 15070//15070 -f 14712//14712 14750//14750 15070//15070 -f 15070//15070 14742//14742 14722//14722 -f 14743//14743 14742//14742 15070//15070 -f 14717//14717 14743//14743 15070//15070 -f 14722//14722 14720//14720 15070//15070 -f 14741//14741 14717//14717 15070//15070 -f 14740//14740 14741//14741 15070//15070 -f 15068//15068 14738//14738 15070//15070 -f 15071//15071 15072//15072 15073//15073 -f 15073//15073 15072//15072 15074//15074 -f 15074//15074 15075//15075 15076//15076 -f 15077//15077 15078//15078 15079//15079 -f 15079//15079 15078//15078 15080//15080 -f 15079//15079 15080//15080 15081//15081 -f 15082//15082 15083//15083 15084//15084 -f 15084//15084 15083//15083 15085//15085 -f 15076//15076 15086//15086 15074//15074 -f 15074//15074 15086//15086 15087//15087 -f 15074//15074 15087//15087 15073//15073 -f 15073//15073 15087//15087 15081//15081 -f 15085//15085 15083//15083 15088//15088 -f 15088//15088 15083//15083 15089//15089 -f 15088//15088 15089//15089 15090//15090 -f 15091//15091 15092//15092 15093//15093 -f 15093//15093 15092//15092 15094//15094 -f 15093//15093 15094//15094 15095//15095 -f 15095//15095 15094//15094 15096//15096 -f 15094//15094 15097//15097 15096//15096 -f 15096//15096 15097//15097 15098//15098 -f 15096//15096 15098//15098 15099//15099 -f 15099//15099 15098//15098 15100//15100 -f 15101//15101 15102//15102 15103//15103 -f 15103//15103 15102//15102 15104//15104 -f 15103//15103 15104//15104 15105//15105 -f 15105//15105 15104//15104 15106//15106 -f 15105//15105 15106//15106 15107//15107 -f 15107//15107 15106//15106 15108//15108 -f 15109//15109 15082//15082 15101//15101 -f 15101//15101 15082//15082 15110//15110 -f 15101//15101 15110//15110 15102//15102 -f 15100//15100 15083//15083 15099//15099 -f 15099//15099 15083//15083 15082//15082 -f 15099//15099 15082//15082 15111//15111 -f 15111//15111 15082//15082 15109//15109 -f 15112//15112 15113//15113 15114//15114 -f 15114//15114 15113//15113 15115//15115 -f 15114//15114 15115//15115 15075//15075 -f 15075//15075 15115//15115 15116//15116 -f 15075//15075 15116//15116 15076//15076 -f 15080//15080 15117//15117 15081//15081 -f 15081//15081 15117//15117 15118//15118 -f 15081//15081 15118//15118 15073//15073 -f 15073//15073 15118//15118 15119//15119 -f 15073//15073 15119//15119 15120//15120 -f 15120//15120 15119//15119 15121//15121 -f 15120//15120 15121//15121 15122//15122 -f 15122//15122 15121//15121 15123//15123 -f 15122//15122 15123//15123 15108//15108 -f 15108//15108 15123//15123 15124//15124 -f 15108//15108 15124//15124 15107//15107 -f 15107//15107 15124//15124 15125//15125 -f 15107//15107 15125//15125 15126//15126 -f 15126//15126 15125//15125 15127//15127 -f 15126//15126 15127//15127 15128//15128 -f 15090//15090 15129//15129 15088//15088 -f 15088//15088 15129//15129 15073//15073 -f 15088//15088 15073//15073 15130//15130 -f 15130//15130 15073//15073 15120//15120 -f 15129//15129 15131//15131 15073//15073 -f 15073//15073 15131//15131 15132//15132 -f 15073//15073 15132//15132 15091//15091 -f 15091//15091 15132//15132 15133//15133 -f 15091//15091 15133//15133 15092//15092 -f 15077//15077 15134//15134 15078//15078 -f 15078//15078 15134//15134 15135//15135 -f 15078//15078 15135//15135 15136//15136 -f 15136//15136 15135//15135 15137//15137 -f 15136//15136 15137//15137 15113//15113 -f 15113//15113 15137//15137 15138//15138 -f 15113//15113 15138//15138 15115//15115 -f 15127//15127 15139//15139 15128//15128 -f 15128//15128 15139//15139 15140//15140 -f 15128//15128 15140//15140 15141//15141 -f 15141//15141 15140//15140 15078//15078 -f 15141//15141 15078//15078 15142//15142 -f 15142//15142 15078//15078 15136//15136 -f 15143//15143 15144//15144 15145//15145 -f 15146//15146 15147//15147 15148//15148 -f 15148//15148 15147//15147 15143//15143 -f 15149//15149 15150//15150 15151//15151 -f 15152//15152 15153//15153 15154//15154 -f 15154//15154 15153//15153 15155//15155 -f 15154//15154 15155//15155 15156//15156 -f 15156//15156 15155//15155 15157//15157 -f 15156//15156 15157//15157 15158//15158 -f 15159//15159 15160//15160 15161//15161 -f 15148//15148 15162//15162 15163//15163 -f 15148//15148 15164//15164 15165//15165 -f 15166//15166 15151//15151 15167//15167 -f 15167//15167 15151//15151 15150//15150 -f 15167//15167 15150//15150 15144//15144 -f 15144//15144 15150//15150 15168//15168 -f 15144//15144 15168//15168 15145//15145 -f 15169//15169 15170//15170 15171//15171 -f 15172//15172 15173//15173 15158//15158 -f 15148//15148 15165//15165 15174//15174 -f 15165//15165 15175//15175 15174//15174 -f 15174//15174 15175//15175 15176//15176 -f 15174//15174 15176//15176 15177//15177 -f 15177//15177 15176//15176 15152//15152 -f 15177//15177 15152//15152 15178//15178 -f 15178//15178 15152//15152 15154//15154 -f 15179//15179 15180//15180 15181//15181 -f 15181//15181 15180//15180 15182//15182 -f 15182//15182 15156//15156 15181//15181 -f 15181//15181 15156//15156 15158//15158 -f 15181//15181 15158//15158 15183//15183 -f 15183//15183 15158//15158 15173//15173 -f 15184//15184 15185//15185 15186//15186 -f 15186//15186 15185//15185 15187//15187 -f 15186//15186 15187//15187 15188//15188 -f 15188//15188 15187//15187 15189//15189 -f 15188//15188 15189//15189 15190//15190 -f 15143//15143 15145//15145 15148//15148 -f 15148//15148 15145//15145 15191//15191 -f 15148//15148 15191//15191 15162//15162 -f 15164//15164 15148//15148 15192//15192 -f 15192//15192 15148//15148 15163//15163 -f 15192//15192 15163//15163 15193//15193 -f 15193//15193 15163//15163 15194//15194 -f 15193//15193 15194//15194 15195//15195 -f 15161//15161 15169//15169 15159//15159 -f 15159//15159 15169//15169 15171//15171 -f 15159//15159 15171//15171 15196//15196 -f 15196//15196 15171//15171 15172//15172 -f 15196//15196 15172//15172 15194//15194 -f 15194//15194 15172//15172 15158//15158 -f 15194//15194 15158//15158 15195//15195 -f 15149//15149 15151//15151 15197//15197 -f 15197//15197 15151//15151 15198//15198 -f 15197//15197 15198//15198 15199//15199 -f 15199//15199 15198//15198 15200//15200 -f 15199//15199 15200//15200 15159//15159 -f 15159//15159 15200//15200 15201//15201 -f 15159//15159 15201//15201 15160//15160 -f 15189//15189 15202//15202 15190//15190 -f 15190//15190 15202//15202 15203//15203 -f 15190//15190 15203//15203 15204//15204 -f 15204//15204 15203//15203 15200//15200 -f 15204//15204 15200//15200 15205//15205 -f 15205//15205 15200//15200 15198//15198 -f 15181//15181 15206//15206 15179//15179 -f 15179//15179 15206//15206 15207//15207 -f 15179//15179 15207//15207 15208//15208 -f 15208//15208 15207//15207 15209//15209 -f 15208//15208 15209//15209 15184//15184 -f 15184//15184 15209//15209 15210//15210 -f 15184//15184 15210//15210 15185//15185 -f 15185//15185 15210//15210 15211//15211 -f 15185//15185 15211//15211 15212//15212 -f 15212//15212 15211//15211 15213//15213 -f 15212//15212 15213//15213 15170//15170 -f 15170//15170 15213//15213 15214//15214 -f 15170//15170 15214//15214 15171//15171 -f 15184//15184 15186//15186 15107//15107 -f 15107//15107 15186//15186 15105//15105 -f 15096//15096 15099//15099 15151//15151 -f 15151//15151 15099//15099 15198//15198 -f 15144//15144 15143//15143 15091//15091 -f 15091//15091 15143//15143 15073//15073 -f 15071//15071 15073//15073 15147//15147 -f 15147//15147 15073//15073 15143//15143 -f 15072//15072 15071//15071 15146//15146 -f 15146//15146 15071//15071 15147//15147 -f 15074//15074 15072//15072 15148//15148 -f 15148//15148 15072//15072 15146//15146 -f 15075//15075 15074//15074 15174//15174 -f 15174//15174 15074//15074 15148//15148 -f 15154//15154 15156//15156 15113//15113 -f 15113//15113 15156//15156 15136//15136 -f 15127//15127 15209//15209 15139//15139 -f 15139//15139 15209//15209 15207//15207 -f 15139//15139 15207//15207 15140//15140 -f 15140//15140 15207//15207 15206//15206 -f 15140//15140 15206//15206 15078//15078 -f 15078//15078 15206//15206 15181//15181 -f 15078//15078 15181//15181 15080//15080 -f 15080//15080 15181//15181 15183//15183 -f 15080//15080 15183//15183 15117//15117 -f 15117//15117 15183//15183 15173//15173 -f 15117//15117 15173//15173 15118//15118 -f 15118//15118 15173//15173 15172//15172 -f 15118//15118 15172//15172 15119//15119 -f 15119//15119 15172//15172 15171//15171 -f 15119//15119 15171//15171 15121//15121 -f 15121//15121 15171//15171 15214//15214 -f 15121//15121 15214//15214 15123//15123 -f 15123//15123 15214//15214 15213//15213 -f 15123//15123 15213//15213 15124//15124 -f 15124//15124 15213//15213 15211//15211 -f 15124//15124 15211//15211 15125//15125 -f 15125//15125 15211//15211 15210//15210 -f 15125//15125 15210//15210 15127//15127 -f 15127//15127 15210//15210 15209//15209 -f 15134//15134 15158//15158 15135//15135 -f 15135//15135 15158//15158 15157//15157 -f 15135//15135 15157//15157 15137//15137 -f 15137//15137 15157//15157 15155//15155 -f 15137//15137 15155//15155 15138//15138 -f 15138//15138 15155//15155 15153//15153 -f 15138//15138 15153//15153 15115//15115 -f 15115//15115 15153//15153 15152//15152 -f 15115//15115 15152//15152 15116//15116 -f 15116//15116 15152//15152 15176//15176 -f 15116//15116 15176//15176 15076//15076 -f 15076//15076 15176//15176 15175//15175 -f 15076//15076 15175//15175 15086//15086 -f 15086//15086 15175//15175 15165//15165 -f 15086//15086 15165//15165 15087//15087 -f 15087//15087 15165//15165 15164//15164 -f 15087//15087 15164//15164 15081//15081 -f 15081//15081 15164//15164 15192//15192 -f 15081//15081 15192//15192 15079//15079 -f 15079//15079 15192//15192 15193//15193 -f 15079//15079 15193//15193 15077//15077 -f 15077//15077 15193//15193 15195//15195 -f 15077//15077 15195//15195 15134//15134 -f 15134//15134 15195//15195 15158//15158 -f 15083//15083 15159//15159 15089//15089 -f 15089//15089 15159//15159 15196//15196 -f 15089//15089 15196//15196 15090//15090 -f 15090//15090 15196//15196 15194//15194 -f 15090//15090 15194//15194 15129//15129 -f 15129//15129 15194//15194 15163//15163 -f 15129//15129 15163//15163 15131//15131 -f 15131//15131 15163//15163 15162//15162 -f 15131//15131 15162//15162 15132//15132 -f 15132//15132 15162//15162 15191//15191 -f 15132//15132 15191//15191 15133//15133 -f 15133//15133 15191//15191 15145//15145 -f 15133//15133 15145//15145 15092//15092 -f 15092//15092 15145//15145 15168//15168 -f 15092//15092 15168//15168 15094//15094 -f 15094//15094 15168//15168 15150//15150 -f 15094//15094 15150//15150 15097//15097 -f 15097//15097 15150//15150 15149//15149 -f 15097//15097 15149//15149 15098//15098 -f 15098//15098 15149//15149 15197//15197 -f 15098//15098 15197//15197 15100//15100 -f 15100//15100 15197//15197 15199//15199 -f 15100//15100 15199//15199 15083//15083 -f 15083//15083 15199//15199 15159//15159 -f 15104//15104 15189//15189 15106//15106 -f 15106//15106 15189//15189 15187//15187 -f 15106//15106 15187//15187 15108//15108 -f 15108//15108 15187//15187 15185//15185 -f 15108//15108 15185//15185 15122//15122 -f 15122//15122 15185//15185 15212//15212 -f 15122//15122 15212//15212 15120//15120 -f 15120//15120 15212//15212 15170//15170 -f 15120//15120 15170//15170 15130//15130 -f 15130//15130 15170//15170 15169//15169 -f 15130//15130 15169//15169 15088//15088 -f 15088//15088 15169//15169 15161//15161 -f 15088//15088 15161//15161 15085//15085 -f 15085//15085 15161//15161 15160//15160 -f 15085//15085 15160//15160 15084//15084 -f 15084//15084 15160//15160 15201//15201 -f 15084//15084 15201//15201 15082//15082 -f 15082//15082 15201//15201 15200//15200 -f 15082//15082 15200//15200 15110//15110 -f 15110//15110 15200//15200 15203//15203 -f 15110//15110 15203//15203 15102//15102 -f 15102//15102 15203//15203 15202//15202 -f 15102//15102 15202//15202 15104//15104 -f 15104//15104 15202//15202 15189//15189 -f 15136//15136 15156//15156 15182//15182 -f 15136//15136 15182//15182 15142//15142 -f 15142//15142 15182//15182 15180//15180 -f 15142//15142 15180//15180 15141//15141 -f 15141//15141 15180//15180 15179//15179 -f 15141//15141 15179//15179 15128//15128 -f 15128//15128 15179//15179 15208//15208 -f 15128//15128 15208//15208 15126//15126 -f 15126//15126 15208//15208 15184//15184 -f 15126//15126 15184//15184 15107//15107 -f 15105//15105 15186//15186 15188//15188 -f 15105//15105 15188//15188 15103//15103 -f 15103//15103 15188//15188 15190//15190 -f 15103//15103 15190//15190 15101//15101 -f 15101//15101 15190//15190 15204//15204 -f 15101//15101 15204//15204 15109//15109 -f 15109//15109 15204//15204 15205//15205 -f 15109//15109 15205//15205 15111//15111 -f 15111//15111 15205//15205 15198//15198 -f 15111//15111 15198//15198 15099//15099 -f 15075//15075 15174//15174 15177//15177 -f 15075//15075 15177//15177 15114//15114 -f 15114//15114 15177//15177 15178//15178 -f 15114//15114 15178//15178 15112//15112 -f 15112//15112 15178//15178 15154//15154 -f 15112//15112 15154//15154 15113//15113 -f 15096//15096 15151//15151 15166//15166 -f 15096//15096 15166//15166 15095//15095 -f 15095//15095 15166//15166 15167//15167 -f 15095//15095 15167//15167 15093//15093 -f 15093//15093 15167//15167 15144//15144 -f 15093//15093 15144//15144 15091//15091 -f 15215//15215 15216//15216 15217//15217 -f 15218//15218 15219//15219 15220//15220 -f 15221//15221 15222//15222 15223//15223 -f 15224//15224 15225//15225 15226//15226 -f 15227//15227 15228//15228 15229//15229 -f 15229//15229 15228//15228 15230//15230 -f 15231//15231 15232//15232 15233//15233 -f 15233//15233 15232//15232 15234//15234 -f 15225//15225 15235//15235 15226//15226 -f 15226//15226 15235//15235 15236//15236 -f 15226//15226 15236//15236 15227//15227 -f 15227//15227 15236//15236 15237//15237 -f 15227//15227 15237//15237 15228//15228 -f 15226//15226 15238//15238 15224//15224 -f 15224//15224 15238//15238 15239//15239 -f 15224//15224 15239//15239 15240//15240 -f 15240//15240 15239//15239 15241//15241 -f 15240//15240 15241//15241 15242//15242 -f 15242//15242 15241//15241 15243//15243 -f 15242//15242 15243//15243 15234//15234 -f 15234//15234 15243//15243 15244//15244 -f 15234//15234 15244//15244 15233//15233 -f 15226//15226 15245//15245 15238//15238 -f 15238//15238 15245//15245 15246//15246 -f 15238//15238 15246//15246 15247//15247 -f 15247//15247 15246//15246 15248//15248 -f 15247//15247 15248//15248 15249//15249 -f 15249//15249 15248//15248 15250//15250 -f 15251//15251 15252//15252 15253//15253 -f 15253//15253 15252//15252 15254//15254 -f 15253//15253 15254//15254 15250//15250 -f 15250//15250 15254//15254 15255//15255 -f 15250//15250 15255//15255 15256//15256 -f 15257//15257 15258//15258 15259//15259 -f 15259//15259 15258//15258 15260//15260 -f 15261//15261 15262//15262 15263//15263 -f 15263//15263 15262//15262 15264//15264 -f 15263//15263 15264//15264 15265//15265 -f 15265//15265 15264//15264 15266//15266 -f 15265//15265 15266//15266 15267//15267 -f 15257//15257 15259//15259 15256//15256 -f 15256//15256 15259//15259 15268//15268 -f 15256//15256 15268//15268 15250//15250 -f 15250//15250 15268//15268 15269//15269 -f 15250//15250 15269//15269 15249//15249 -f 15270//15270 15260//15260 15271//15271 -f 15271//15271 15260//15260 15272//15272 -f 15271//15271 15272//15272 15273//15273 -f 15273//15273 15272//15272 15274//15274 -f 15273//15273 15274//15274 15275//15275 -f 15258//15258 15261//15261 15260//15260 -f 15260//15260 15261//15261 15263//15263 -f 15260//15260 15263//15263 15272//15272 -f 15272//15272 15263//15263 15276//15276 -f 15272//15272 15276//15276 15274//15274 -f 15274//15274 15276//15276 15277//15277 -f 15278//15278 15279//15279 15215//15215 -f 15215//15215 15279//15279 15280//15280 -f 15281//15281 15277//15277 15282//15282 -f 15282//15282 15277//15277 15283//15283 -f 15282//15282 15283//15283 15284//15284 -f 15284//15284 15283//15283 15285//15285 -f 15286//15286 15287//15287 15288//15288 -f 15288//15288 15287//15287 15289//15289 -f 15288//15288 15289//15289 15290//15290 -f 15289//15289 15291//15291 15290//15290 -f 15290//15290 15291//15291 15292//15292 -f 15290//15290 15292//15292 15293//15293 -f 15293//15293 15292//15292 15294//15294 -f 15293//15293 15294//15294 15295//15295 -f 15296//15296 15297//15297 15298//15298 -f 15298//15298 15297//15297 15299//15299 -f 15298//15298 15299//15299 15300//15300 -f 15300//15300 15299//15299 15301//15301 -f 15296//15296 15302//15302 15297//15297 -f 15297//15297 15302//15302 15303//15303 -f 15297//15297 15303//15303 15287//15287 -f 15304//15304 15223//15223 15305//15305 -f 15305//15305 15223//15223 15306//15306 -f 15305//15305 15306//15306 15307//15307 -f 15303//15303 15308//15308 15287//15287 -f 15287//15287 15308//15308 15309//15309 -f 15287//15287 15309//15309 15289//15289 -f 15289//15289 15309//15309 15310//15310 -f 15289//15289 15310//15310 15311//15311 -f 15311//15311 15310//15310 15307//15307 -f 15311//15311 15307//15307 15312//15312 -f 15312//15312 15307//15307 15306//15306 -f 15221//15221 15223//15223 15313//15313 -f 15313//15313 15223//15223 15314//15314 -f 15313//15313 15314//15314 15315//15315 -f 15315//15315 15314//15314 15316//15316 -f 15315//15315 15316//15316 15317//15317 -f 15317//15317 15316//15316 15318//15318 -f 15317//15317 15318//15318 15319//15319 -f 15319//15319 15318//15318 15220//15220 -f 15220//15220 15318//15318 15320//15320 -f 15220//15220 15320//15320 15218//15218 -f 15321//15321 15322//15322 15318//15318 -f 15318//15318 15322//15322 15323//15323 -f 15318//15318 15323//15323 15324//15324 -f 15325//15325 15320//15320 15326//15326 -f 15326//15326 15320//15320 15318//15318 -f 15326//15326 15318//15318 15327//15327 -f 15327//15327 15318//15318 15324//15324 -f 15328//15328 15329//15329 15321//15321 -f 15321//15321 15329//15329 15330//15330 -f 15321//15321 15330//15330 15322//15322 -f 15327//15327 15331//15331 15326//15326 -f 15326//15326 15331//15331 15332//15332 -f 15326//15326 15332//15332 15333//15333 -f 15333//15333 15332//15332 15334//15334 -f 15334//15334 15335//15335 15333//15333 -f 15333//15333 15335//15335 15336//15336 -f 15333//15333 15336//15336 15328//15328 -f 15328//15328 15336//15336 15337//15337 -f 15328//15328 15337//15337 15329//15329 -f 15338//15338 15339//15339 15340//15340 -f 15340//15340 15341//15341 15338//15338 -f 15338//15338 15341//15341 15342//15342 -f 15338//15338 15342//15342 15316//15316 -f 15316//15316 15342//15342 15343//15343 -f 15316//15316 15343//15343 15344//15344 -f 15344//15344 15345//15345 15316//15316 -f 15316//15316 15345//15345 15346//15346 -f 15316//15316 15346//15346 15318//15318 -f 15318//15318 15346//15346 15347//15347 -f 15318//15318 15347//15347 15321//15321 -f 15345//15345 15348//15348 15346//15346 -f 15346//15346 15348//15348 15349//15349 -f 15346//15346 15349//15349 15350//15350 -f 15350//15350 15349//15349 15351//15351 -f 15351//15351 15352//15352 15350//15350 -f 15350//15350 15352//15352 15353//15353 -f 15350//15350 15353//15353 15339//15339 -f 15339//15339 15353//15353 15354//15354 -f 15339//15339 15354//15354 15340//15340 -f 15355//15355 15356//15356 15357//15357 -f 15358//15358 15359//15359 15360//15360 -f 15360//15360 15359//15359 15361//15361 -f 15360//15360 15361//15361 15362//15362 -f 15362//15362 15361//15361 15363//15363 -f 15304//15304 15301//15301 15223//15223 -f 15223//15223 15301//15301 15299//15299 -f 15223//15223 15299//15299 15314//15314 -f 15314//15314 15299//15299 15364//15364 -f 15314//15314 15364//15364 15355//15355 -f 15357//15357 15365//15365 15355//15355 -f 15355//15355 15365//15365 15366//15366 -f 15355//15355 15366//15366 15314//15314 -f 15314//15314 15366//15366 15367//15367 -f 15314//15314 15367//15367 15368//15368 -f 15368//15368 15363//15363 15314//15314 -f 15314//15314 15363//15363 15361//15361 -f 15314//15314 15361//15361 15316//15316 -f 15316//15316 15361//15361 15369//15369 -f 15316//15316 15369//15369 15338//15338 -f 15358//15358 15370//15370 15359//15359 -f 15359//15359 15370//15370 15371//15371 -f 15359//15359 15371//15371 15356//15356 -f 15356//15356 15371//15371 15372//15372 -f 15356//15356 15372//15372 15357//15357 -f 15281//15281 15373//15373 15277//15277 -f 15277//15277 15373//15373 15374//15374 -f 15277//15277 15374//15374 15274//15274 -f 15274//15274 15374//15374 15375//15375 -f 15274//15274 15375//15375 15376//15376 -f 15376//15376 15375//15375 15377//15377 -f 15376//15376 15377//15377 15378//15378 -f 15378//15378 15377//15377 15379//15379 -f 15378//15378 15379//15379 15380//15380 -f 15380//15380 15379//15379 15278//15278 -f 15380//15380 15278//15278 15294//15294 -f 15294//15294 15278//15278 15215//15215 -f 15294//15294 15215//15215 15295//15295 -f 15295//15295 15215//15215 15217//15217 -f 15381//15381 15216//15216 15283//15283 -f 15283//15283 15216//15216 15215//15215 -f 15283//15283 15215//15215 15285//15285 -f 15285//15285 15215//15215 15280//15280 -f 15382//15382 15383//15383 15253//15253 -f 15253//15253 15383//15383 15265//15265 -f 15253//15253 15265//15265 15251//15251 -f 15251//15251 15265//15265 15267//15267 -f 15384//15384 15245//15245 15385//15385 -f 15385//15385 15245//15245 15226//15226 -f 15385//15385 15226//15226 15386//15386 -f 15386//15386 15226//15226 15227//15227 -f 15387//15387 15388//15388 15389//15389 -f 15390//15390 15391//15391 15392//15392 -f 15393//15393 15394//15394 15395//15395 -f 15395//15395 15394//15394 15392//15392 -f 15396//15396 15397//15397 15398//15398 -f 15398//15398 15397//15397 15393//15393 -f 15398//15398 15393//15393 15399//15399 -f 15399//15399 15393//15393 15395//15395 -f 15230//15230 15231//15231 15229//15229 -f 15229//15229 15231//15231 15233//15233 -f 15229//15229 15233//15233 15400//15400 -f 15400//15400 15233//15233 15389//15389 -f 15400//15400 15389//15389 15401//15401 -f 15401//15401 15389//15389 15388//15388 -f 15401//15401 15388//15388 15390//15390 -f 15390//15390 15388//15388 15402//15402 -f 15390//15390 15402//15402 15391//15391 -f 15396//15396 15403//15403 15397//15397 -f 15397//15397 15403//15403 15404//15404 -f 15397//15397 15404//15404 15389//15389 -f 15389//15389 15404//15404 15405//15405 -f 15389//15389 15405//15405 15387//15387 -f 15392//15392 15394//15394 15390//15390 -f 15390//15390 15394//15394 15406//15406 -f 15390//15390 15406//15406 15407//15407 -f 15408//15408 15409//15409 15397//15397 -f 15410//15410 15411//15411 15412//15412 -f 15412//15412 15411//15411 15413//15413 -f 15414//15414 15415//15415 15416//15416 -f 15416//15416 15415//15415 15413//15413 -f 15410//15410 15412//15412 15409//15409 -f 15409//15409 15412//15412 15417//15417 -f 15409//15409 15417//15417 15397//15397 -f 15397//15397 15417//15417 15418//15418 -f 15397//15397 15418//15418 15393//15393 -f 15416//15416 15419//15419 15414//15414 -f 15414//15414 15419//15419 15420//15420 -f 15414//15414 15420//15420 15421//15421 -f 15421//15421 15420//15420 15422//15422 -f 15422//15422 15423//15423 15421//15421 -f 15421//15421 15423//15423 15424//15424 -f 15421//15421 15424//15424 15397//15397 -f 15397//15397 15424//15424 15425//15425 -f 15397//15397 15425//15425 15408//15408 -f 15413//15413 15415//15415 15412//15412 -f 15412//15412 15415//15415 15426//15426 -f 15412//15412 15426//15426 15427//15427 -f 15428//15428 15429//15429 15421//15421 -f 15430//15430 15431//15431 15432//15432 -f 15433//15433 15434//15434 15435//15435 -f 15435//15435 15434//15434 15430//15430 -f 15435//15435 15430//15430 15421//15421 -f 15436//15436 15437//15437 15430//15430 -f 15430//15430 15437//15437 15438//15438 -f 15430//15430 15438//15438 15439//15439 -f 15440//15440 15441//15441 15442//15442 -f 15442//15442 15441//15441 15443//15443 -f 15430//15430 15432//15432 15436//15436 -f 15436//15436 15432//15432 15444//15444 -f 15436//15436 15444//15444 15443//15443 -f 15439//15439 15445//15445 15430//15430 -f 15430//15430 15445//15445 15446//15446 -f 15430//15430 15446//15446 15421//15421 -f 15421//15421 15446//15446 15447//15447 -f 15421//15421 15447//15447 15428//15428 -f 15440//15440 15442//15442 15429//15429 -f 15429//15429 15442//15442 15448//15448 -f 15429//15429 15448//15448 15421//15421 -f 15421//15421 15448//15448 15449//15449 -f 15421//15421 15449//15449 15414//15414 -f 15443//15443 15444//15444 15442//15442 -f 15442//15442 15444//15444 15450//15450 -f 15442//15442 15450//15450 15451//15451 -f 15233//15233 15452//15452 15453//15453 -f 15454//15454 15455//15455 15456//15456 -f 15456//15456 15455//15455 15435//15435 -f 15456//15456 15435//15435 15457//15457 -f 15457//15457 15435//15435 15421//15421 -f 15457//15457 15421//15421 15458//15458 -f 15458//15458 15421//15421 15397//15397 -f 15458//15458 15397//15397 15453//15453 -f 15453//15453 15397//15397 15389//15389 -f 15453//15453 15389//15389 15233//15233 -f 15459//15459 15460//15460 15270//15270 -f 15459//15459 15270//15270 15461//15461 -f 15461//15461 15270//15270 15271//15271 -f 15461//15461 15271//15271 15273//15273 -f 15462//15462 15463//15463 15464//15464 -f 15465//15465 15466//15466 15467//15467 -f 15466//15466 15468//15468 15467//15467 -f 15467//15467 15468//15468 15469//15469 -f 15467//15467 15469//15469 15470//15470 -f 15471//15471 15472//15472 15467//15467 -f 15467//15467 15472//15472 15462//15462 -f 15462//15462 15464//15464 15467//15467 -f 15467//15467 15464//15464 15473//15473 -f 15467//15467 15473//15473 15465//15465 -f 15474//15474 15475//15475 15476//15476 -f 15476//15476 15475//15475 15470//15470 -f 15476//15476 15470//15470 15477//15477 -f 15477//15477 15470//15470 15469//15469 -f 15107//15107 15105//15105 15478//15478 -f 15478//15478 15105//15105 15479//15479 -f 15480//15480 15107//15107 15481//15481 -f 15481//15481 15107//15107 15478//15478 -f 15481//15481 15478//15478 15482//15482 -f 15482//15482 15478//15478 15483//15483 -f 15456//15456 15457//15457 15484//15484 -f 15456//15456 15484//15484 15485//15485 -f 15486//15486 15487//15487 15488//15488 -f 15489//15489 15490//15490 15491//15491 -f 15491//15491 15490//15490 15492//15492 -f 15491//15491 15492//15492 15493//15493 -f 15493//15493 15492//15492 15494//15494 -f 15493//15493 15494//15494 15495//15495 -f 15495//15495 15494//15494 15496//15496 -f 15495//15495 15496//15496 15497//15497 -f 15497//15497 15496//15496 15498//15498 -f 15499//15499 15500//15500 15501//15501 -f 15501//15501 15500//15500 15502//15502 -f 15501//15501 15502//15502 15503//15503 -f 15503//15503 15502//15502 15504//15504 -f 15503//15503 15504//15504 15505//15505 -f 15505//15505 15504//15504 15506//15506 -f 15506//15506 15507//15507 15505//15505 -f 15505//15505 15507//15507 15508//15508 -f 15505//15505 15508//15508 15509//15509 -f 15509//15509 15508//15508 15510//15510 -f 15507//15507 15511//15511 15508//15508 -f 15508//15508 15511//15511 15512//15512 -f 15508//15508 15512//15512 15489//15489 -f 15489//15489 15512//15512 15513//15513 -f 15489//15489 15513//15513 15490//15490 -f 15501//15501 15514//15514 15499//15499 -f 15499//15499 15514//15514 15515//15515 -f 15499//15499 15515//15515 15487//15487 -f 15487//15487 15515//15515 15516//15516 -f 15487//15487 15516//15516 15488//15488 -f 15517//15517 15518//15518 15519//15519 -f 15519//15519 15518//15518 15520//15520 -f 15519//15519 15520//15520 15521//15521 -f 15521//15521 15520//15520 15522//15522 -f 15521//15521 15522//15522 15488//15488 -f 15488//15488 15522//15522 15523//15523 -f 15488//15488 15523//15523 15486//15486 -f 15524//15524 15525//15525 15496//15496 -f 15496//15496 15525//15525 15526//15526 -f 15496//15496 15526//15526 15498//15498 -f 15524//15524 15527//15527 15525//15525 -f 15525//15525 15527//15527 15528//15528 -f 15525//15525 15528//15528 15484//15484 -f 15484//15484 15528//15528 15529//15529 -f 15484//15484 15529//15529 15530//15530 -f 15530//15530 15531//15531 15484//15484 -f 15484//15484 15531//15531 15517//15517 -f 15484//15484 15517//15517 15485//15485 -f 15485//15485 15517//15517 15519//15519 -f 15105//15105 15103//15103 15479//15479 -f 15479//15479 15103//15103 15532//15532 -f 15532//15532 15103//15103 15533//15533 -f 15533//15533 15103//15103 15101//15101 -f 15533//15533 15101//15101 15534//15534 -f 15534//15534 15101//15101 15535//15535 -f 15535//15535 15101//15101 15109//15109 -f 15535//15535 15109//15109 15536//15536 -f 15536//15536 15109//15109 15537//15537 -f 15537//15537 15109//15109 15111//15111 -f 15537//15537 15111//15111 15538//15538 -f 15539//15539 15540//15540 15541//15541 -f 15538//15538 15111//15111 15541//15541 -f 15541//15541 15111//15111 15099//15099 -f 15541//15541 15099//15099 15539//15539 -f 15542//15542 15543//15543 15544//15544 -f 15545//15545 15546//15546 15547//15547 -f 15542//15542 15544//15544 15548//15548 -f 15544//15544 15549//15549 15548//15548 -f 15548//15548 15549//15549 15550//15550 -f 15548//15548 15550//15550 15551//15551 -f 15545//15545 15547//15547 15552//15552 -f 15547//15547 15553//15553 15552//15552 -f 15552//15552 15553//15553 15554//15554 -f 15552//15552 15554//15554 15542//15542 -f 15542//15542 15554//15554 15555//15555 -f 15542//15542 15555//15555 15543//15543 -f 15550//15550 15556//15556 15551//15551 -f 15551//15551 15556//15556 15557//15557 -f 15551//15551 15557//15557 15545//15545 -f 15545//15545 15557//15557 15558//15558 -f 15545//15545 15558//15558 15546//15546 -f 15559//15559 15560//15560 15561//15561 -f 15561//15561 15560//15560 15562//15562 -f 15563//15563 15564//15564 15565//15565 -f 15565//15565 15564//15564 15566//15566 -f 15566//15566 15567//15567 15565//15565 -f 15565//15565 15567//15567 15568//15568 -f 15565//15565 15568//15568 15569//15569 -f 15568//15568 15570//15570 15569//15569 -f 15569//15569 15570//15570 15571//15571 -f 15569//15569 15571//15571 15559//15559 -f 15559//15559 15571//15571 15572//15572 -f 15559//15559 15572//15572 15560//15560 -f 15562//15562 15573//15573 15561//15561 -f 15561//15561 15573//15573 15574//15574 -f 15561//15561 15574//15574 15563//15563 -f 15563//15563 15574//15574 15575//15575 -f 15563//15563 15575//15575 15564//15564 -f 15576//15576 15577//15577 15578//15578 -f 15578//15578 15577//15577 15579//15579 -f 15580//15580 15581//15581 15576//15576 -f 15576//15576 15581//15581 15582//15582 -f 15576//15576 15582//15582 15577//15577 -f 15579//15579 15583//15583 15578//15578 -f 15578//15578 15583//15583 15584//15584 -f 15578//15578 15584//15584 15585//15585 -f 15586//15586 15587//15587 15588//15588 -f 15588//15588 15587//15587 15585//15585 -f 15588//15588 15585//15585 15589//15589 -f 15589//15589 15585//15585 15584//15584 -f 15586//15586 15590//15590 15587//15587 -f 15587//15587 15590//15590 15591//15591 -f 15587//15587 15591//15591 15580//15580 -f 15580//15580 15591//15591 15592//15592 -f 15580//15580 15592//15592 15581//15581 -f 15593//15593 15594//15594 15595//15595 -f 15595//15595 15594//15594 15596//15596 -f 15597//15597 15598//15598 15599//15599 -f 15102//15102 15110//15110 15101//15101 -f 15600//15600 15601//15601 15602//15602 -f 15602//15602 15601//15601 15603//15603 -f 15101//15101 15110//15110 15109//15109 -f 15109//15109 15110//15110 15082//15082 -f 15109//15109 15082//15082 15111//15111 -f 15604//15604 15605//15605 15606//15606 -f 15606//15606 15605//15605 15607//15607 -f 15608//15608 15609//15609 15610//15610 -f 15610//15610 15609//15609 15611//15611 -f 15610//15610 15611//15611 15612//15612 -f 15613//15613 15614//15614 15615//15615 -f 15616//15616 15617//15617 15618//15618 -f 15618//15618 15617//15617 15619//15619 -f 15620//15620 15621//15621 15622//15622 -f 15623//15623 15134//15134 15078//15078 -f 15624//15624 15625//15625 15626//15626 -f 15626//15626 15625//15625 15627//15627 -f 15128//15128 15141//15141 15078//15078 -f 15628//15628 15629//15629 15630//15630 -f 15630//15630 15629//15629 15631//15631 -f 15115//15115 15632//15632 15633//15633 -f 15634//15634 15635//15635 15636//15636 -f 15636//15636 15635//15635 15637//15637 -f 15638//15638 15639//15639 15640//15640 -f 15640//15640 15639//15639 15641//15641 -f 15141//15141 15142//15142 15078//15078 -f 15078//15078 15142//15142 15136//15136 -f 15078//15078 15136//15136 15623//15623 -f 15607//15607 15620//15620 15134//15134 -f 15642//15642 15643//15643 15644//15644 -f 15644//15644 15643//15643 15645//15645 -f 15131//15131 15615//15615 15132//15132 -f 15132//15132 15615//15615 15133//15133 -f 15646//15646 15602//15602 15623//15623 -f 15623//15623 15602//15602 15603//15603 -f 15623//15623 15603//15603 15134//15134 -f 15134//15134 15603//15603 15618//15618 -f 15134//15134 15618//15618 15607//15607 -f 15607//15607 15618//15618 15619//15619 -f 15607//15607 15619//15619 15606//15606 -f 15647//15647 15648//15648 15649//15649 -f 15649//15649 15648//15648 15632//15632 -f 15649//15649 15632//15632 15631//15631 -f 15631//15631 15632//15632 15115//15115 -f 15631//15631 15115//15115 15138//15138 -f 15650//15650 15651//15651 15633//15633 -f 15633//15633 15651//15651 15613//15613 -f 15633//15633 15613//15613 15115//15115 -f 15115//15115 15613//15613 15615//15615 -f 15115//15115 15615//15615 15116//15116 -f 15652//15652 15653//15653 15654//15654 -f 15654//15654 15653//15653 15655//15655 -f 15084//15084 15077//15077 15079//15079 -f 15622//15622 15612//15612 15620//15620 -f 15620//15620 15612//15612 15611//15611 -f 15620//15620 15611//15611 15134//15134 -f 15134//15134 15611//15611 15630//15630 -f 15134//15134 15630//15630 15135//15135 -f 15135//15135 15630//15630 15631//15631 -f 15135//15135 15631//15631 15137//15137 -f 15137//15137 15631//15631 15138//15138 -f 15090//15090 15079//15079 15129//15129 -f 15129//15129 15079//15079 15081//15081 -f 15129//15129 15081//15081 15131//15131 -f 15082//15082 15084//15084 15083//15083 -f 15083//15083 15084//15084 15079//15079 -f 15083//15083 15079//15079 15089//15089 -f 15089//15089 15079//15079 15090//15090 -f 15077//15077 15084//15084 15134//15134 -f 15134//15134 15084//15084 15085//15085 -f 15134//15134 15085//15085 15088//15088 -f 15656//15656 15657//15657 15658//15658 -f 15658//15658 15657//15657 15659//15659 -f 15658//15658 15659//15659 15660//15660 -f 15081//15081 15087//15087 15131//15131 -f 15131//15131 15087//15087 15086//15086 -f 15131//15131 15086//15086 15615//15615 -f 15615//15615 15086//15086 15076//15076 -f 15615//15615 15076//15076 15116//15116 -f 15118//15118 15117//15117 15134//15134 -f 15134//15134 15117//15117 15080//15080 -f 15134//15134 15080//15080 15078//15078 -f 15124//15124 15105//15105 15125//15125 -f 15125//15125 15105//15105 15107//15107 -f 15125//15125 15107//15107 15127//15127 -f 15127//15127 15107//15107 15126//15126 -f 15127//15127 15126//15126 15139//15139 -f 15139//15139 15126//15126 15128//15128 -f 15139//15139 15128//15128 15140//15140 -f 15140//15140 15128//15128 15078//15078 -f 15599//15599 15661//15661 15597//15597 -f 15597//15597 15661//15661 15662//15662 -f 15597//15597 15662//15662 15663//15663 -f 15664//15664 15665//15665 15133//15133 -f 15119//15119 15118//15118 15120//15120 -f 15120//15120 15118//15118 15134//15134 -f 15120//15120 15134//15134 15130//15130 -f 15130//15130 15134//15134 15088//15088 -f 15102//15102 15101//15101 15104//15104 -f 15104//15104 15101//15101 15103//15103 -f 15104//15104 15103//15103 15106//15106 -f 15106//15106 15103//15103 15105//15105 -f 15106//15106 15105//15105 15108//15108 -f 15108//15108 15105//15105 15124//15124 -f 15108//15108 15124//15124 15122//15122 -f 15122//15122 15124//15124 15123//15123 -f 15122//15122 15123//15123 15120//15120 -f 15120//15120 15123//15123 15121//15121 -f 15120//15120 15121//15121 15119//15119 -f 15666//15666 15667//15667 15668//15668 -f 15668//15668 15667//15667 15669//15669 -f 15668//15668 15669//15669 15670//15670 -f 15671//15671 15672//15672 15670//15670 -f 15670//15670 15672//15672 15664//15664 -f 15670//15670 15664//15664 15668//15668 -f 15668//15668 15664//15664 15133//15133 -f 15668//15668 15133//15133 15596//15596 -f 15596//15596 15133//15133 15615//15615 -f 15596//15596 15615//15615 15595//15595 -f 15595//15595 15615//15615 15673//15673 -f 15655//15655 15098//15098 15654//15654 -f 15654//15654 15098//15098 15097//15097 -f 15654//15654 15097//15097 15094//15094 -f 15626//15626 15083//15083 15655//15655 -f 15655//15655 15083//15083 15100//15100 -f 15655//15655 15100//15100 15098//15098 -f 15674//15674 15675//15675 15665//15665 -f 15665//15665 15675//15675 15676//15676 -f 15665//15665 15676//15676 15133//15133 -f 15133//15133 15676//15676 15677//15677 -f 15678//15678 15654//15654 15679//15679 -f 15679//15679 15654//15654 15094//15094 -f 15679//15679 15094//15094 15677//15677 -f 15677//15677 15094//15094 15092//15092 -f 15677//15677 15092//15092 15133//15133 -f 15627//15627 15636//15636 15626//15626 -f 15626//15626 15636//15636 15637//15637 -f 15626//15626 15637//15637 15083//15083 -f 15083//15083 15637//15637 15640//15640 -f 15680//15680 15597//15597 15083//15083 -f 15083//15083 15597//15597 15663//15663 -f 15083//15083 15663//15663 15082//15082 -f 15082//15082 15663//15663 15099//15099 -f 15082//15082 15099//15099 15111//15111 -f 15641//15641 15644//15644 15640//15640 -f 15640//15640 15644//15644 15645//15645 -f 15640//15640 15645//15645 15083//15083 -f 15083//15083 15645//15645 15658//15658 -f 15083//15083 15658//15658 15680//15680 -f 15680//15680 15658//15658 15660//15660 -f 15680//15680 15660//15660 15681//15681 -f 15681//15681 15660//15660 15682//15682 -f 15683//15683 15684//15684 15685//15685 -f 15685//15685 15684//15684 15686//15686 -f 15685//15685 15686//15686 15687//15687 -f 15687//15687 15686//15686 15688//15688 -f 15687//15687 15688//15688 15689//15689 -f 15690//15690 15691//15691 15692//15692 -f 15692//15692 15691//15691 15693//15693 -f 15692//15692 15693//15693 15694//15694 -f 15694//15694 15693//15693 15695//15695 -f 15694//15694 15695//15695 15696//15696 -f 15697//15697 15698//15698 15699//15699 -f 15699//15699 15698//15698 15700//15700 -f 15699//15699 15700//15700 15701//15701 -f 15701//15701 15700//15700 15702//15702 -f 15701//15701 15702//15702 15703//15703 -f 15704//15704 15705//15705 15548//15548 -f 15548//15548 15705//15705 15706//15706 -f 15548//15548 15706//15706 15542//15542 -f 15542//15542 15706//15706 15707//15707 -f 15542//15542 15707//15707 15708//15708 -f 15708//15708 15707//15707 15709//15709 -f 15710//15710 15711//15711 15569//15569 -f 15569//15569 15711//15711 15712//15712 -f 15569//15569 15712//15712 15565//15565 -f 15565//15565 15712//15712 15713//15713 -f 15565//15565 15713//15713 15714//15714 -f 15714//15714 15713//15713 15715//15715 -f 15716//15716 15717//15717 15585//15585 -f 15585//15585 15717//15717 15718//15718 -f 15585//15585 15718//15718 15578//15578 -f 15578//15578 15718//15718 15719//15719 -f 15578//15578 15719//15719 15720//15720 -f 15720//15720 15719//15719 15721//15721 -f 15722//15722 15723//15723 15724//15724 -f 15724//15724 15723//15723 15725//15725 -f 15726//15726 15727//15727 15728//15728 -f 15729//15729 15730//15730 15731//15731 -f 15731//15731 15730//15730 15726//15726 -f 15731//15731 15726//15726 15732//15732 -f 15732//15732 15726//15726 15728//15728 -f 15729//15729 15733//15733 15730//15730 -f 15730//15730 15733//15733 15734//15734 -f 15730//15730 15734//15734 15722//15722 -f 15722//15722 15734//15734 15735//15735 -f 15722//15722 15735//15735 15723//15723 -f 15725//15725 15736//15736 15724//15724 -f 15724//15724 15736//15736 15737//15737 -f 15724//15724 15737//15737 15727//15727 -f 15727//15727 15737//15737 15738//15738 -f 15727//15727 15738//15738 15728//15728 -f 15739//15739 15740//15740 15741//15741 -f 15741//15741 15740//15740 15742//15742 -f 15743//15743 15744//15744 15745//15745 -f 15745//15745 15744//15744 15746//15746 -f 15745//15745 15746//15746 15747//15747 -f 15747//15747 15746//15746 15748//15748 -f 15747//15747 15748//15748 15749//15749 -f 15741//15741 15750//15750 15739//15739 -f 15739//15739 15750//15750 15751//15751 -f 15739//15739 15751//15751 15748//15748 -f 15748//15748 15751//15751 15752//15752 -f 15748//15748 15752//15752 15749//15749 -f 15743//15743 15753//15753 15744//15744 -f 15744//15744 15753//15753 15754//15754 -f 15744//15744 15754//15754 15740//15740 -f 15740//15740 15754//15754 15755//15755 -f 15740//15740 15755//15755 15742//15742 -f 15756//15756 15757//15757 15758//15758 -f 15758//15758 15757//15757 15759//15759 -f 15758//15758 15759//15759 15760//15760 -f 15760//15760 15759//15759 15761//15761 -f 15760//15760 15761//15761 15762//15762 -f 15763//15763 15764//15764 15727//15727 -f 15727//15727 15764//15764 15765//15765 -f 15727//15727 15765//15765 15724//15724 -f 15724//15724 15765//15765 15766//15766 -f 15724//15724 15766//15766 15767//15767 -f 15767//15767 15766//15766 15768//15768 -f 15769//15769 15770//15770 15771//15771 -f 15772//15772 15773//15773 15774//15774 -f 15769//15769 15771//15771 15774//15774 -f 15774//15774 15771//15771 15775//15775 -f 15774//15774 15775//15775 15772//15772 -f 15776//15776 15777//15777 15739//15739 -f 15739//15739 15777//15777 15778//15778 -f 15739//15739 15778//15778 15740//15740 -f 15740//15740 15778//15778 15779//15779 -f 15740//15740 15779//15779 15780//15780 -f 15780//15780 15779//15779 15781//15781 -f 15782//15782 15623//15623 15783//15783 -f 15783//15783 15623//15623 15136//15136 -f 15539//15539 15099//15099 15784//15784 -f 15784//15784 15099//15099 15663//15663 -f 15663//15663 15662//15662 15784//15784 -f 15784//15784 15662//15662 15785//15785 -f 15784//15784 15785//15785 15786//15786 -f 15786//15786 15785//15785 15431//15431 -f 15786//15786 15431//15431 15787//15787 -f 15787//15787 15431//15431 15430//15430 -f 15785//15785 15662//15662 15788//15788 -f 15788//15788 15662//15662 15661//15661 -f 15444//15444 15432//15432 15788//15788 -f 15788//15788 15661//15661 15599//15599 -f 15444//15444 15788//15788 15450//15450 -f 15450//15450 15788//15788 15707//15707 -f 15707//15707 15788//15788 15599//15599 -f 15707//15707 15599//15599 15709//15709 -f 15682//15682 15660//15660 15789//15789 -f 15789//15789 15448//15448 15442//15442 -f 15682//15682 15789//15789 15705//15705 -f 15705//15705 15789//15789 15706//15706 -f 15706//15706 15789//15789 15442//15442 -f 15706//15706 15442//15442 15451//15451 -f 15789//15789 15660//15660 15790//15790 -f 15790//15790 15660//15660 15659//15659 -f 15415//15415 15414//15414 15790//15790 -f 15790//15790 15659//15659 15657//15657 -f 15415//15415 15790//15790 15426//15426 -f 15426//15426 15790//15790 15713//15713 -f 15713//15713 15790//15790 15657//15657 -f 15713//15713 15657//15657 15715//15715 -f 15642//15642 15644//15644 15791//15791 -f 15791//15791 15417//15417 15412//15412 -f 15642//15642 15791//15791 15711//15711 -f 15711//15711 15791//15791 15712//15712 -f 15712//15712 15791//15791 15412//15412 -f 15712//15712 15412//15412 15427//15427 -f 15791//15791 15644//15644 15792//15792 -f 15792//15792 15644//15644 15641//15641 -f 15394//15394 15393//15393 15792//15792 -f 15792//15792 15641//15641 15639//15639 -f 15394//15394 15792//15792 15406//15406 -f 15406//15406 15792//15792 15719//15719 -f 15719//15719 15792//15792 15639//15639 -f 15719//15719 15639//15639 15721//15721 -f 15634//15634 15636//15636 15793//15793 -f 15793//15793 15401//15401 15390//15390 -f 15634//15634 15793//15793 15717//15717 -f 15717//15717 15793//15793 15718//15718 -f 15718//15718 15793//15793 15390//15390 -f 15718//15718 15390//15390 15407//15407 -f 15793//15793 15636//15636 15794//15794 -f 15794//15794 15636//15636 15627//15627 -f 15227//15227 15229//15229 15794//15794 -f 15794//15794 15627//15627 15625//15625 -f 15227//15227 15794//15794 15386//15386 -f 15386//15386 15794//15794 15766//15766 -f 15766//15766 15794//15794 15625//15625 -f 15766//15766 15625//15625 15768//15768 -f 15652//15652 15654//15654 15795//15795 -f 15795//15795 15246//15246 15245//15245 -f 15652//15652 15795//15795 15764//15764 -f 15764//15764 15795//15795 15765//15765 -f 15765//15765 15795//15795 15245//15245 -f 15765//15765 15245//15245 15384//15384 -f 15795//15795 15654//15654 15796//15796 -f 15796//15796 15654//15654 15678//15678 -f 15796//15796 15678//15678 15248//15248 -f 15248//15248 15678//15678 15679//15679 -f 15248//15248 15679//15679 15797//15797 -f 15797//15797 15679//15679 15677//15677 -f 15797//15797 15677//15677 15798//15798 -f 15798//15798 15677//15677 15676//15676 -f 15253//15253 15250//15250 15798//15798 -f 15798//15798 15676//15676 15675//15675 -f 15253//15253 15798//15798 15382//15382 -f 15382//15382 15798//15798 15779//15779 -f 15779//15779 15798//15798 15675//15675 -f 15779//15779 15675//15675 15781//15781 -f 15671//15671 15670//15670 15799//15799 -f 15799//15799 15263//15263 15265//15265 -f 15671//15671 15799//15799 15777//15777 -f 15777//15777 15799//15799 15778//15778 -f 15778//15778 15799//15799 15265//15265 -f 15778//15778 15265//15265 15383//15383 -f 15799//15799 15670//15670 15800//15800 -f 15800//15800 15670//15670 15669//15669 -f 15283//15283 15277//15277 15800//15800 -f 15800//15800 15669//15669 15667//15667 -f 15283//15283 15800//15800 15381//15381 -f 15381//15381 15800//15800 15801//15801 -f 15801//15801 15800//15800 15667//15667 -f 15801//15801 15667//15667 15802//15802 -f 15803//15803 15804//15804 15805//15805 -f 15805//15805 15804//15804 15806//15806 -f 15805//15805 15806//15806 15807//15807 -f 15807//15807 15806//15806 15801//15801 -f 15807//15807 15801//15801 15808//15808 -f 15808//15808 15801//15801 15802//15802 -f 15593//15593 15595//15595 15809//15809 -f 15809//15809 15293//15293 15295//15295 -f 15593//15593 15809//15809 15804//15804 -f 15804//15804 15809//15809 15806//15806 -f 15806//15806 15809//15809 15295//15295 -f 15806//15806 15295//15295 15217//15217 -f 15809//15809 15595//15595 15810//15810 -f 15810//15810 15595//15595 15673//15673 -f 15810//15810 15673//15673 15290//15290 -f 15290//15290 15673//15673 15615//15615 -f 15290//15290 15615//15615 15811//15811 -f 15811//15811 15615//15615 15614//15614 -f 15811//15811 15614//15614 15812//15812 -f 15812//15812 15614//15614 15613//15613 -f 15651//15651 15813//15813 15814//15814 -f 15613//15613 15651//15651 15812//15812 -f 15812//15812 15651//15651 15814//15814 -f 15812//15812 15814//15814 15288//15288 -f 15288//15288 15814//15814 15286//15286 -f 15815//15815 15816//15816 15817//15817 -f 15817//15817 15816//15816 15818//15818 -f 15817//15817 15818//15818 15819//15819 -f 15819//15819 15818//15818 15814//15814 -f 15819//15819 15814//15814 15820//15820 -f 15820//15820 15814//15814 15813//15813 -f 15299//15299 15297//15297 15821//15821 -f 15821//15821 15297//15297 15818//15818 -f 15818//15818 15816//15816 15821//15821 -f 15821//15821 15816//15816 15647//15647 -f 15821//15821 15647//15647 15649//15649 -f 15821//15821 15649//15649 15822//15822 -f 15822//15822 15649//15649 15631//15631 -f 15629//15629 15823//15823 15824//15824 -f 15631//15631 15629//15629 15822//15822 -f 15822//15822 15629//15629 15824//15824 -f 15822//15822 15824//15824 15355//15355 -f 15355//15355 15824//15824 15356//15356 -f 15825//15825 15826//15826 15827//15827 -f 15827//15827 15826//15826 15828//15828 -f 15827//15827 15828//15828 15829//15829 -f 15829//15829 15828//15828 15824//15824 -f 15829//15829 15824//15824 15830//15830 -f 15830//15830 15824//15824 15823//15823 -f 15361//15361 15359//15359 15831//15831 -f 15831//15831 15359//15359 15828//15828 -f 15828//15828 15826//15826 15831//15831 -f 15831//15831 15826//15826 15608//15608 -f 15831//15831 15608//15608 15610//15610 -f 15831//15831 15610//15610 15832//15832 -f 15832//15832 15610//15610 15612//15612 -f 15622//15622 15833//15833 15834//15834 -f 15612//15612 15622//15622 15832//15832 -f 15832//15832 15622//15622 15834//15834 -f 15832//15832 15834//15834 15338//15338 -f 15338//15338 15834//15834 15339//15339 -f 15835//15835 15836//15836 15837//15837 -f 15837//15837 15836//15836 15838//15838 -f 15837//15837 15838//15838 15839//15839 -f 15839//15839 15838//15838 15834//15834 -f 15839//15839 15834//15834 15840//15840 -f 15840//15840 15834//15834 15833//15833 -f 15346//15346 15350//15350 15841//15841 -f 15841//15841 15350//15350 15838//15838 -f 15838//15838 15836//15836 15841//15841 -f 15841//15841 15836//15836 15604//15604 -f 15841//15841 15604//15604 15606//15606 -f 15841//15841 15606//15606 15842//15842 -f 15842//15842 15606//15606 15619//15619 -f 15617//15617 15843//15843 15844//15844 -f 15619//15619 15617//15617 15842//15842 -f 15842//15842 15617//15617 15844//15844 -f 15842//15842 15844//15844 15321//15321 -f 15321//15321 15844//15844 15328//15328 -f 15845//15845 15846//15846 15847//15847 -f 15847//15847 15846//15846 15848//15848 -f 15847//15847 15848//15848 15849//15849 -f 15849//15849 15848//15848 15844//15844 -f 15849//15849 15844//15844 15850//15850 -f 15850//15850 15844//15844 15843//15843 -f 15326//15326 15333//15333 15851//15851 -f 15851//15851 15333//15333 15848//15848 -f 15848//15848 15846//15846 15851//15851 -f 15851//15851 15846//15846 15600//15600 -f 15851//15851 15600//15600 15602//15602 -f 15851//15851 15602//15602 15852//15852 -f 15852//15852 15602//15602 15646//15646 -f 15853//15853 15320//15320 15325//15325 -f 15646//15646 15623//15623 15852//15852 -f 15852//15852 15623//15623 15782//15782 -f 15852//15852 15782//15782 15325//15325 -f 15325//15325 15782//15782 15854//15854 -f 15325//15325 15854//15854 15853//15853 -f 15319//15319 15855//15855 15856//15856 -f 15221//15221 15313//15313 15857//15857 -f 15857//15857 15313//15313 15315//15315 -f 15857//15857 15315//15315 15858//15858 -f 15858//15858 15315//15315 15317//15317 -f 15858//15858 15317//15317 15510//15510 -f 15510//15510 15317//15317 15319//15319 -f 15510//15510 15319//15319 15509//15509 -f 15509//15509 15319//15319 15856//15856 -f 15508//15508 15489//15489 15859//15859 -f 15859//15859 15489//15489 15860//15860 -f 15860//15860 15489//15489 15491//15491 -f 15860//15860 15491//15491 15861//15861 -f 15861//15861 15491//15491 15493//15493 -f 15861//15861 15493//15493 15862//15862 -f 15862//15862 15493//15493 15495//15495 -f 15862//15862 15495//15495 15863//15863 -f 15863//15863 15495//15495 15497//15497 -f 15863//15863 15497//15497 15864//15864 -f 15864//15864 15497//15497 15498//15498 -f 15864//15864 15498//15498 15865//15865 -f 15865//15865 15498//15498 15526//15526 -f 15865//15865 15526//15526 15866//15866 -f 15866//15866 15526//15526 15525//15525 -f 15866//15866 15525//15525 15867//15867 -f 15867//15867 15525//15525 15868//15868 -f 15868//15868 15525//15525 15484//15484 -f 15869//15869 15870//15870 15871//15871 -f 15871//15871 15870//15870 15807//15807 -f 15871//15871 15807//15807 15666//15666 -f 15666//15666 15807//15807 15808//15808 -f 15805//15805 15807//15807 15872//15872 -f 15872//15872 15807//15807 15873//15873 -f 15874//15874 15875//15875 15876//15876 -f 15876//15876 15875//15875 15805//15805 -f 15876//15876 15805//15805 15877//15877 -f 15877//15877 15805//15805 15872//15872 -f 15874//15874 15878//15878 15875//15875 -f 15875//15875 15878//15878 15879//15879 -f 15875//15875 15879//15879 15880//15880 -f 15880//15880 15879//15879 15881//15881 -f 15880//15880 15881//15881 15870//15870 -f 15870//15870 15881//15881 15882//15882 -f 15882//15882 15883//15883 15870//15870 -f 15870//15870 15883//15883 15884//15884 -f 15870//15870 15884//15884 15807//15807 -f 15807//15807 15884//15884 15885//15885 -f 15807//15807 15885//15885 15873//15873 -f 15594//15594 15803//15803 15886//15886 -f 15886//15886 15803//15803 15805//15805 -f 15886//15886 15805//15805 15887//15887 -f 15887//15887 15805//15805 15875//15875 -f 15869//15869 15888//15888 15870//15870 -f 15870//15870 15888//15888 15880//15880 -f 15888//15888 15887//15887 15880//15880 -f 15880//15880 15887//15887 15875//15875 -f 15886//15886 15887//15887 15889//15889 -f 15889//15889 15887//15887 15888//15888 -f 15889//15889 15888//15888 15890//15890 -f 15890//15890 15888//15888 15869//15869 -f 15890//15890 15869//15869 15871//15871 -f 15666//15666 15668//15668 15871//15871 -f 15871//15871 15668//15668 15890//15890 -f 15668//15668 15596//15596 15890//15890 -f 15890//15890 15596//15596 15889//15889 -f 15596//15596 15594//15594 15889//15889 -f 15889//15889 15594//15594 15886//15886 -f 15891//15891 15892//15892 15893//15893 -f 15893//15893 15892//15892 15819//15819 -f 15893//15893 15819//15819 15650//15650 -f 15650//15650 15819//15819 15820//15820 -f 15894//15894 15817//15817 15895//15895 -f 15895//15895 15896//15896 15894//15894 -f 15894//15894 15896//15896 15897//15897 -f 15894//15894 15897//15897 15898//15898 -f 15898//15898 15897//15897 15899//15899 -f 15892//15892 15900//15900 15819//15819 -f 15819//15819 15900//15900 15901//15901 -f 15901//15901 15902//15902 15819//15819 -f 15819//15819 15902//15902 15903//15903 -f 15819//15819 15903//15903 15817//15817 -f 15817//15817 15903//15903 15904//15904 -f 15817//15817 15904//15904 15895//15895 -f 15899//15899 15905//15905 15898//15898 -f 15898//15898 15905//15905 15906//15906 -f 15898//15898 15906//15906 15892//15892 -f 15892//15892 15906//15906 15907//15907 -f 15892//15892 15907//15907 15900//15900 -f 15648//15648 15815//15815 15908//15908 -f 15908//15908 15815//15815 15817//15817 -f 15908//15908 15817//15817 15909//15909 -f 15909//15909 15817//15817 15894//15894 -f 15891//15891 15910//15910 15892//15892 -f 15892//15892 15910//15910 15898//15898 -f 15910//15910 15909//15909 15898//15898 -f 15898//15898 15909//15909 15894//15894 -f 15911//15911 15908//15908 15909//15909 -f 15891//15891 15893//15893 15912//15912 -f 15911//15911 15909//15909 15912//15912 -f 15912//15912 15909//15909 15910//15910 -f 15912//15912 15910//15910 15891//15891 -f 15633//15633 15912//15912 15650//15650 -f 15650//15650 15912//15912 15893//15893 -f 15632//15632 15911//15911 15633//15633 -f 15633//15633 15911//15911 15912//15912 -f 15648//15648 15908//15908 15632//15632 -f 15632//15632 15908//15908 15911//15911 -f 15872//15872 15285//15285 15877//15877 -f 15877//15877 15285//15285 15280//15280 -f 15877//15877 15280//15280 15876//15876 -f 15876//15876 15280//15280 15279//15279 -f 15876//15876 15279//15279 15874//15874 -f 15874//15874 15279//15279 15278//15278 -f 15874//15874 15278//15278 15878//15878 -f 15878//15878 15278//15278 15379//15379 -f 15878//15878 15379//15379 15879//15879 -f 15879//15879 15379//15379 15377//15377 -f 15879//15879 15377//15377 15881//15881 -f 15881//15881 15377//15377 15375//15375 -f 15881//15881 15375//15375 15882//15882 -f 15882//15882 15375//15375 15374//15374 -f 15882//15882 15374//15374 15883//15883 -f 15883//15883 15374//15374 15373//15373 -f 15883//15883 15373//15373 15884//15884 -f 15884//15884 15373//15373 15281//15281 -f 15884//15884 15281//15281 15885//15885 -f 15885//15885 15281//15281 15282//15282 -f 15885//15885 15282//15282 15873//15873 -f 15873//15873 15282//15282 15284//15284 -f 15873//15873 15284//15284 15872//15872 -f 15872//15872 15284//15284 15285//15285 -f 15900//15900 15310//15310 15901//15901 -f 15901//15901 15310//15310 15309//15309 -f 15901//15901 15309//15309 15902//15902 -f 15902//15902 15309//15309 15308//15308 -f 15902//15902 15308//15308 15903//15903 -f 15903//15903 15308//15308 15303//15303 -f 15903//15903 15303//15303 15904//15904 -f 15904//15904 15303//15303 15302//15302 -f 15904//15904 15302//15302 15895//15895 -f 15895//15895 15302//15302 15296//15296 -f 15895//15895 15296//15296 15896//15896 -f 15896//15896 15296//15296 15298//15298 -f 15896//15896 15298//15298 15897//15897 -f 15897//15897 15298//15298 15300//15300 -f 15897//15897 15300//15300 15899//15899 -f 15899//15899 15300//15300 15301//15301 -f 15899//15899 15301//15301 15905//15905 -f 15905//15905 15301//15301 15304//15304 -f 15905//15905 15304//15304 15906//15906 -f 15906//15906 15304//15304 15305//15305 -f 15906//15906 15305//15305 15907//15907 -f 15907//15907 15305//15305 15307//15307 -f 15907//15907 15307//15307 15900//15900 -f 15900//15900 15307//15307 15310//15310 -f 15913//15913 15914//15914 15915//15915 -f 15915//15915 15914//15914 15829//15829 -f 15915//15915 15829//15829 15628//15628 -f 15628//15628 15829//15829 15830//15830 -f 15916//15916 15827//15827 15917//15917 -f 15917//15917 15918//15918 15916//15916 -f 15916//15916 15918//15918 15919//15919 -f 15916//15916 15919//15919 15920//15920 -f 15920//15920 15919//15919 15921//15921 -f 15922//15922 15829//15829 15923//15923 -f 15923//15923 15829//15829 15914//15914 -f 15921//15921 15924//15924 15920//15920 -f 15920//15920 15924//15924 15925//15925 -f 15920//15920 15925//15925 15914//15914 -f 15914//15914 15925//15925 15926//15926 -f 15914//15914 15926//15926 15923//15923 -f 15922//15922 15927//15927 15829//15829 -f 15829//15829 15927//15927 15928//15928 -f 15829//15829 15928//15928 15827//15827 -f 15827//15827 15928//15928 15929//15929 -f 15827//15827 15929//15929 15917//15917 -f 15609//15609 15825//15825 15930//15930 -f 15930//15930 15825//15825 15827//15827 -f 15930//15930 15827//15827 15931//15931 -f 15931//15931 15827//15827 15916//15916 -f 15932//15932 15933//15933 15934//15934 -f 15934//15934 15933//15933 15839//15839 -f 15934//15934 15839//15839 15621//15621 -f 15621//15621 15839//15839 15840//15840 -f 15935//15935 15839//15839 15936//15936 -f 15936//15936 15839//15839 15933//15933 -f 15935//15935 15937//15937 15839//15839 -f 15839//15839 15937//15937 15938//15938 -f 15839//15839 15938//15938 15837//15837 -f 15939//15939 15940//15940 15941//15941 -f 15941//15941 15940//15940 15942//15942 -f 15939//15939 15943//15943 15940//15940 -f 15940//15940 15943//15943 15944//15944 -f 15940//15940 15944//15944 15933//15933 -f 15933//15933 15944//15944 15945//15945 -f 15933//15933 15945//15945 15936//15936 -f 15938//15938 15946//15946 15837//15837 -f 15837//15837 15946//15946 15947//15947 -f 15837//15837 15947//15947 15942//15942 -f 15942//15942 15947//15947 15948//15948 -f 15942//15942 15948//15948 15941//15941 -f 15605//15605 15835//15835 15949//15949 -f 15949//15949 15835//15835 15837//15837 -f 15949//15949 15837//15837 15950//15950 -f 15950//15950 15837//15837 15942//15942 -f 15951//15951 15952//15952 15953//15953 -f 15953//15953 15952//15952 15849//15849 -f 15953//15953 15849//15849 15616//15616 -f 15616//15616 15849//15849 15850//15850 -f 15954//15954 15955//15955 15956//15956 -f 15956//15956 15955//15955 15952//15952 -f 15957//15957 15847//15847 15958//15958 -f 15958//15958 15959//15959 15957//15957 -f 15957//15957 15959//15959 15960//15960 -f 15957//15957 15960//15960 15956//15956 -f 15956//15956 15960//15960 15961//15961 -f 15956//15956 15961//15961 15954//15954 -f 15955//15955 15962//15962 15952//15952 -f 15952//15952 15962//15962 15963//15963 -f 15952//15952 15963//15963 15849//15849 -f 15849//15849 15963//15963 15964//15964 -f 15964//15964 15965//15965 15849//15849 -f 15849//15849 15965//15965 15966//15966 -f 15849//15849 15966//15966 15847//15847 -f 15847//15847 15966//15966 15967//15967 -f 15847//15847 15967//15967 15958//15958 -f 15601//15601 15845//15845 15968//15968 -f 15968//15968 15845//15845 15847//15847 -f 15968//15968 15847//15847 15969//15969 -f 15969//15969 15847//15847 15957//15957 -f 15913//15913 15970//15970 15914//15914 -f 15914//15914 15970//15970 15920//15920 -f 15970//15970 15931//15931 15920//15920 -f 15920//15920 15931//15931 15916//15916 -f 15971//15971 15930//15930 15931//15931 -f 15913//15913 15915//15915 15972//15972 -f 15971//15971 15931//15931 15972//15972 -f 15972//15972 15931//15931 15970//15970 -f 15972//15972 15970//15970 15913//15913 -f 15932//15932 15973//15973 15933//15933 -f 15933//15933 15973//15973 15940//15940 -f 15973//15973 15950//15950 15940//15940 -f 15940//15940 15950//15950 15942//15942 -f 15974//15974 15949//15949 15950//15950 -f 15932//15932 15934//15934 15975//15975 -f 15974//15974 15950//15950 15975//15975 -f 15975//15975 15950//15950 15973//15973 -f 15975//15975 15973//15973 15932//15932 -f 15951//15951 15976//15976 15952//15952 -f 15952//15952 15976//15976 15956//15956 -f 15976//15976 15969//15969 15956//15956 -f 15956//15956 15969//15969 15957//15957 -f 15977//15977 15968//15968 15969//15969 -f 15951//15951 15953//15953 15978//15978 -f 15977//15977 15969//15969 15978//15978 -f 15978//15978 15969//15969 15976//15976 -f 15978//15978 15976//15976 15951//15951 -f 15630//15630 15972//15972 15628//15628 -f 15628//15628 15972//15972 15915//15915 -f 15611//15611 15971//15971 15630//15630 -f 15630//15630 15971//15971 15972//15972 -f 15609//15609 15930//15930 15611//15611 -f 15611//15611 15930//15930 15971//15971 -f 15620//15620 15975//15975 15621//15621 -f 15621//15621 15975//15975 15934//15934 -f 15607//15607 15974//15974 15620//15620 -f 15620//15620 15974//15974 15975//15975 -f 15605//15605 15949//15949 15607//15607 -f 15607//15607 15949//15949 15974//15974 -f 15618//15618 15978//15978 15616//15616 -f 15616//15616 15978//15978 15953//15953 -f 15603//15603 15977//15977 15618//15618 -f 15618//15618 15977//15977 15978//15978 -f 15601//15601 15968//15968 15603//15603 -f 15603//15603 15968//15968 15977//15977 -f 15923//15923 15365//15365 15922//15922 -f 15922//15922 15365//15365 15357//15357 -f 15922//15922 15357//15357 15927//15927 -f 15927//15927 15357//15357 15372//15372 -f 15927//15927 15372//15372 15928//15928 -f 15928//15928 15372//15372 15371//15371 -f 15928//15928 15371//15371 15929//15929 -f 15929//15929 15371//15371 15370//15370 -f 15929//15929 15370//15370 15917//15917 -f 15917//15917 15370//15370 15358//15358 -f 15917//15917 15358//15358 15918//15918 -f 15918//15918 15358//15358 15360//15360 -f 15918//15918 15360//15360 15919//15919 -f 15919//15919 15360//15360 15362//15362 -f 15919//15919 15362//15362 15921//15921 -f 15921//15921 15362//15362 15363//15363 -f 15921//15921 15363//15363 15924//15924 -f 15924//15924 15363//15363 15368//15368 -f 15924//15924 15368//15368 15925//15925 -f 15925//15925 15368//15368 15367//15367 -f 15925//15925 15367//15367 15926//15926 -f 15926//15926 15367//15367 15366//15366 -f 15926//15926 15366//15366 15923//15923 -f 15923//15923 15366//15366 15365//15365 -f 15936//15936 15341//15341 15935//15935 -f 15935//15935 15341//15341 15340//15340 -f 15935//15935 15340//15340 15937//15937 -f 15937//15937 15340//15340 15354//15354 -f 15937//15937 15354//15354 15938//15938 -f 15938//15938 15354//15354 15353//15353 -f 15938//15938 15353//15353 15946//15946 -f 15946//15946 15353//15353 15352//15352 -f 15946//15946 15352//15352 15947//15947 -f 15947//15947 15352//15352 15351//15351 -f 15947//15947 15351//15351 15948//15948 -f 15948//15948 15351//15351 15349//15349 -f 15948//15948 15349//15349 15941//15941 -f 15941//15941 15349//15349 15348//15348 -f 15941//15941 15348//15348 15939//15939 -f 15939//15939 15348//15348 15345//15345 -f 15939//15939 15345//15345 15943//15943 -f 15943//15943 15345//15345 15344//15344 -f 15943//15943 15344//15344 15944//15944 -f 15944//15944 15344//15344 15343//15343 -f 15944//15944 15343//15343 15945//15945 -f 15945//15945 15343//15343 15342//15342 -f 15945//15945 15342//15342 15936//15936 -f 15936//15936 15342//15342 15341//15341 -f 15963//15963 15330//15330 15964//15964 -f 15964//15964 15330//15330 15329//15329 -f 15964//15964 15329//15329 15965//15965 -f 15965//15965 15329//15329 15337//15337 -f 15965//15965 15337//15337 15966//15966 -f 15966//15966 15337//15337 15336//15336 -f 15966//15966 15336//15336 15967//15967 -f 15967//15967 15336//15336 15335//15335 -f 15967//15967 15335//15335 15958//15958 -f 15958//15958 15335//15335 15334//15334 -f 15958//15958 15334//15334 15959//15959 -f 15959//15959 15334//15334 15332//15332 -f 15959//15959 15332//15332 15960//15960 -f 15960//15960 15332//15332 15331//15331 -f 15960//15960 15331//15331 15961//15961 -f 15961//15961 15331//15331 15327//15327 -f 15961//15961 15327//15327 15954//15954 -f 15954//15954 15327//15327 15324//15324 -f 15954//15954 15324//15324 15955//15955 -f 15955//15955 15324//15324 15323//15323 -f 15955//15955 15323//15323 15962//15962 -f 15962//15962 15323//15323 15322//15322 -f 15962//15962 15322//15322 15963//15963 -f 15963//15963 15322//15322 15330//15330 -f 15772//15772 15744//15744 15773//15773 -f 15773//15773 15744//15744 15740//15740 -f 15773//15773 15740//15740 15674//15674 -f 15674//15674 15740//15740 15780//15780 -f 15672//15672 15776//15776 15770//15770 -f 15770//15770 15776//15776 15739//15739 -f 15770//15770 15739//15739 15771//15771 -f 15771//15771 15739//15739 15748//15748 -f 15772//15772 15775//15775 15744//15744 -f 15744//15744 15775//15775 15746//15746 -f 15775//15775 15771//15771 15746//15746 -f 15746//15746 15771//15771 15748//15748 -f 15665//15665 15774//15774 15674//15674 -f 15674//15674 15774//15774 15773//15773 -f 15664//15664 15769//15769 15665//15665 -f 15665//15665 15769//15769 15774//15774 -f 15672//15672 15770//15770 15664//15664 -f 15664//15664 15770//15770 15769//15769 -f 15761//15761 15722//15722 15762//15762 -f 15762//15762 15722//15722 15724//15724 -f 15762//15762 15724//15724 15624//15624 -f 15624//15624 15724//15724 15767//15767 -f 15653//15653 15763//15763 15756//15756 -f 15756//15756 15763//15763 15727//15727 -f 15756//15756 15727//15727 15757//15757 -f 15757//15757 15727//15727 15726//15726 -f 15761//15761 15759//15759 15722//15722 -f 15722//15722 15759//15759 15730//15730 -f 15759//15759 15757//15757 15730//15730 -f 15730//15730 15757//15757 15726//15726 -f 15624//15624 15626//15626 15762//15762 -f 15762//15762 15626//15626 15760//15760 -f 15626//15626 15655//15655 15760//15760 -f 15760//15760 15655//15655 15758//15758 -f 15655//15655 15653//15653 15758//15758 -f 15758//15758 15653//15653 15756//15756 -f 15741//15741 15251//15251 15750//15750 -f 15750//15750 15251//15251 15267//15267 -f 15750//15750 15267//15267 15751//15751 -f 15751//15751 15267//15267 15266//15266 -f 15751//15751 15266//15266 15752//15752 -f 15752//15752 15266//15266 15264//15264 -f 15752//15752 15264//15264 15749//15749 -f 15749//15749 15264//15264 15262//15262 -f 15749//15749 15262//15262 15747//15747 -f 15747//15747 15262//15262 15261//15261 -f 15747//15747 15261//15261 15745//15745 -f 15745//15745 15261//15261 15258//15258 -f 15745//15745 15258//15258 15743//15743 -f 15743//15743 15258//15258 15257//15257 -f 15743//15743 15257//15257 15753//15753 -f 15753//15753 15257//15257 15256//15256 -f 15753//15753 15256//15256 15754//15754 -f 15754//15754 15256//15256 15255//15255 -f 15754//15754 15255//15255 15755//15755 -f 15755//15755 15255//15255 15254//15254 -f 15755//15755 15254//15254 15742//15742 -f 15742//15742 15254//15254 15252//15252 -f 15742//15742 15252//15252 15741//15741 -f 15741//15741 15252//15252 15251//15251 -f 15732//15732 15224//15224 15731//15731 -f 15731//15731 15224//15224 15240//15240 -f 15731//15731 15240//15240 15729//15729 -f 15729//15729 15240//15240 15242//15242 -f 15729//15729 15242//15242 15733//15733 -f 15733//15733 15242//15242 15234//15234 -f 15733//15733 15234//15234 15734//15734 -f 15734//15734 15234//15234 15232//15232 -f 15734//15734 15232//15232 15735//15735 -f 15735//15735 15232//15232 15231//15231 -f 15735//15735 15231//15231 15723//15723 -f 15723//15723 15231//15231 15230//15230 -f 15723//15723 15230//15230 15725//15725 -f 15725//15725 15230//15230 15228//15228 -f 15725//15725 15228//15228 15736//15736 -f 15736//15736 15228//15228 15237//15237 -f 15736//15736 15237//15237 15737//15737 -f 15737//15737 15237//15237 15236//15236 -f 15737//15737 15236//15236 15738//15738 -f 15738//15738 15236//15236 15235//15235 -f 15738//15738 15235//15235 15728//15728 -f 15728//15728 15235//15235 15225//15225 -f 15728//15728 15225//15225 15732//15732 -f 15732//15732 15225//15225 15224//15224 -f 15702//15702 15576//15576 15703//15703 -f 15703//15703 15576//15576 15578//15578 -f 15703//15703 15578//15578 15638//15638 -f 15638//15638 15578//15578 15720//15720 -f 15635//15635 15716//15716 15697//15697 -f 15697//15697 15716//15716 15585//15585 -f 15697//15697 15585//15585 15698//15698 -f 15698//15698 15585//15585 15587//15587 -f 15695//15695 15563//15563 15696//15696 -f 15696//15696 15563//15563 15565//15565 -f 15696//15696 15565//15565 15656//15656 -f 15656//15656 15565//15565 15714//15714 -f 15643//15643 15710//15710 15690//15690 -f 15690//15690 15710//15710 15569//15569 -f 15690//15690 15569//15569 15691//15691 -f 15691//15691 15569//15569 15559//15559 -f 15688//15688 15552//15552 15689//15689 -f 15689//15689 15552//15552 15542//15542 -f 15689//15689 15542//15542 15598//15598 -f 15598//15598 15542//15542 15708//15708 -f 15681//15681 15704//15704 15683//15683 -f 15683//15683 15704//15704 15548//15548 -f 15683//15683 15548//15548 15684//15684 -f 15684//15684 15548//15548 15551//15551 -f 15702//15702 15700//15700 15576//15576 -f 15576//15576 15700//15700 15580//15580 -f 15700//15700 15698//15698 15580//15580 -f 15580//15580 15698//15698 15587//15587 -f 15695//15695 15693//15693 15563//15563 -f 15563//15563 15693//15693 15561//15561 -f 15693//15693 15691//15691 15561//15561 -f 15561//15561 15691//15691 15559//15559 -f 15688//15688 15686//15686 15552//15552 -f 15552//15552 15686//15686 15545//15545 -f 15686//15686 15684//15684 15545//15545 -f 15545//15545 15684//15684 15551//15551 -f 15638//15638 15640//15640 15703//15703 -f 15703//15703 15640//15640 15701//15701 -f 15640//15640 15637//15637 15701//15701 -f 15701//15701 15637//15637 15699//15699 -f 15637//15637 15635//15635 15699//15699 -f 15699//15699 15635//15635 15697//15697 -f 15656//15656 15658//15658 15696//15696 -f 15696//15696 15658//15658 15694//15694 -f 15658//15658 15645//15645 15694//15694 -f 15694//15694 15645//15645 15692//15692 -f 15645//15645 15643//15643 15692//15692 -f 15692//15692 15643//15643 15690//15690 -f 15598//15598 15597//15597 15689//15689 -f 15689//15689 15597//15597 15687//15687 -f 15597//15597 15680//15680 15687//15687 -f 15687//15687 15680//15680 15685//15685 -f 15680//15680 15681//15681 15685//15685 -f 15685//15685 15681//15681 15683//15683 -f 15586//15586 15388//15388 15590//15590 -f 15590//15590 15388//15388 15387//15387 -f 15590//15590 15387//15387 15591//15591 -f 15591//15591 15387//15387 15405//15405 -f 15591//15591 15405//15405 15592//15592 -f 15592//15592 15405//15405 15404//15404 -f 15592//15592 15404//15404 15581//15581 -f 15581//15581 15404//15404 15403//15403 -f 15581//15581 15403//15403 15582//15582 -f 15582//15582 15403//15403 15396//15396 -f 15582//15582 15396//15396 15577//15577 -f 15577//15577 15396//15396 15398//15398 -f 15577//15577 15398//15398 15579//15579 -f 15579//15579 15398//15398 15399//15399 -f 15579//15579 15399//15399 15583//15583 -f 15583//15583 15399//15399 15395//15395 -f 15583//15583 15395//15395 15584//15584 -f 15584//15584 15395//15395 15392//15392 -f 15584//15584 15392//15392 15589//15589 -f 15589//15589 15392//15392 15391//15391 -f 15589//15589 15391//15391 15588//15588 -f 15588//15588 15391//15391 15402//15402 -f 15588//15588 15402//15402 15586//15586 -f 15586//15586 15402//15402 15388//15388 -f 15572//15572 15409//15409 15560//15560 -f 15560//15560 15409//15409 15408//15408 -f 15560//15560 15408//15408 15562//15562 -f 15562//15562 15408//15408 15425//15425 -f 15562//15562 15425//15425 15573//15573 -f 15573//15573 15425//15425 15424//15424 -f 15573//15573 15424//15424 15574//15574 -f 15574//15574 15424//15424 15423//15423 -f 15574//15574 15423//15423 15575//15575 -f 15575//15575 15423//15423 15422//15422 -f 15575//15575 15422//15422 15564//15564 -f 15564//15564 15422//15422 15420//15420 -f 15564//15564 15420//15420 15566//15566 -f 15566//15566 15420//15420 15419//15419 -f 15566//15566 15419//15419 15567//15567 -f 15567//15567 15419//15419 15416//15416 -f 15567//15567 15416//15416 15568//15568 -f 15568//15568 15416//15416 15413//15413 -f 15568//15568 15413//15413 15570//15570 -f 15570//15570 15413//15413 15411//15411 -f 15570//15570 15411//15411 15571//15571 -f 15571//15571 15411//15411 15410//15410 -f 15571//15571 15410//15410 15572//15572 -f 15572//15572 15410//15410 15409//15409 -f 15556//15556 15429//15429 15557//15557 -f 15557//15557 15429//15429 15428//15428 -f 15557//15557 15428//15428 15558//15558 -f 15558//15558 15428//15428 15447//15447 -f 15558//15558 15447//15447 15546//15546 -f 15546//15546 15447//15447 15446//15446 -f 15546//15546 15446//15446 15547//15547 -f 15547//15547 15446//15446 15445//15445 -f 15547//15547 15445//15445 15553//15553 -f 15553//15553 15445//15445 15439//15439 -f 15553//15553 15439//15439 15554//15554 -f 15554//15554 15439//15439 15438//15438 -f 15554//15554 15438//15438 15555//15555 -f 15555//15555 15438//15438 15437//15437 -f 15555//15555 15437//15437 15543//15543 -f 15543//15543 15437//15437 15436//15436 -f 15543//15543 15436//15436 15544//15544 -f 15544//15544 15436//15436 15443//15443 -f 15544//15544 15443//15443 15549//15549 -f 15549//15549 15443//15443 15441//15441 -f 15549//15549 15441//15441 15550//15550 -f 15550//15550 15441//15441 15440//15440 -f 15550//15550 15440//15440 15556//15556 -f 15556//15556 15440//15440 15429//15429 -f 15979//15979 15783//15783 15980//15980 -f 15980//15980 15783//15783 15136//15136 -f 15980//15980 15136//15136 15981//15981 -f 15981//15981 15136//15136 15142//15142 -f 15981//15981 15142//15142 15982//15982 -f 15982//15982 15142//15142 15141//15141 -f 15982//15982 15141//15141 15983//15983 -f 15983//15983 15141//15141 15984//15984 -f 15984//15984 15141//15141 15128//15128 -f 15984//15984 15128//15128 15985//15985 -f 15985//15985 15128//15128 15986//15986 -f 15986//15986 15128//15128 15126//15126 -f 15986//15986 15126//15126 15987//15987 -f 15987//15987 15126//15126 15107//15107 -f 15987//15987 15107//15107 15480//15480 -f 15988//15988 15989//15989 15990//15990 -f 15991//15991 15988//15988 15992//15992 -f 15992//15992 15988//15988 15990//15990 -f 15992//15992 15990//15990 15993//15993 -f 15993//15993 15990//15990 15994//15994 -f 15995//15995 15996//15996 15997//15997 -f 15998//15998 15999//15999 15995//15995 -f 15995//15995 15999//15999 16000//16000 -f 15995//15995 16000//16000 16001//16001 -f 16001//16001 16000//16000 16002//16002 -f 16001//16001 16002//16002 16003//16003 -f 16003//16003 16002//16002 16004//16004 -f 16003//16003 16004//16004 16005//16005 -f 16005//16005 16004//16004 16006//16006 -f 16005//16005 16006//16006 15990//15990 -f 15990//15990 16006//16006 16007//16007 -f 15990//15990 16007//16007 15994//15994 -f 15994//15994 16007//16007 16008//16008 -f 15994//15994 16008//16008 16009//16009 -f 16009//16009 16008//16008 16010//16010 -f 16009//16009 16010//16010 16011//16011 -f 16011//16011 16010//16010 16012//16012 -f 16011//16011 16012//16012 16013//16013 -f 16013//16013 16012//16012 16014//16014 -f 16013//16013 16014//16014 16015//16015 -f 16015//16015 16014//16014 16016//16016 -f 16015//16015 16016//16016 15997//15997 -f 15997//15997 16016//16016 15998//15998 -f 15997//15997 15998//15998 15995//15995 -f 16017//16017 15856//15856 16001//16001 -f 16001//16001 15856//15856 15855//15855 -f 16001//16001 15855//15855 15995//15995 -f 15995//15995 15855//15855 16018//16018 -f 15995//15995 16018//16018 16019//16019 -f 16020//16020 16021//16021 16018//16018 -f 16018//16018 16021//16021 16022//16022 -f 16018//16018 16022//16022 16019//16019 -f 15990//15990 15989//15989 16005//16005 -f 16005//16005 15989//15989 16023//16023 -f 16005//16005 16023//16023 16003//16003 -f 16003//16003 16023//16023 16024//16024 -f 16003//16003 16024//16024 16001//16001 -f 16001//16001 16024//16024 16017//16017 -f 16025//16025 16026//16026 16027//16027 -f 16028//16028 16025//16025 16029//16029 -f 16029//16029 16025//16025 16027//16027 -f 16029//16029 16027//16027 16030//16030 -f 16030//16030 16027//16027 16031//16031 -f 16032//16032 16033//16033 16034//16034 -f 16034//16034 16033//16033 16035//16035 -f 16034//16034 16035//16035 16036//16036 -f 16036//16036 16035//16035 16037//16037 -f 16036//16036 16037//16037 16038//16038 -f 16038//16038 16037//16037 16039//16039 -f 16038//16038 16039//16039 16040//16040 -f 16040//16040 16039//16039 16041//16041 -f 16040//16040 16041//16041 16042//16042 -f 16042//16042 16041//16041 16043//16043 -f 16042//16042 16043//16043 16044//16044 -f 16044//16044 16043//16043 16045//16045 -f 16044//16044 16045//16045 16026//16026 -f 16026//16026 16045//16045 16046//16046 -f 16026//16026 16046//16046 16027//16027 -f 16027//16027 16046//16046 16047//16047 -f 16027//16027 16047//16047 16048//16048 -f 16048//16048 16047//16047 16049//16049 -f 16048//16048 16049//16049 16050//16050 -f 16050//16050 16049//16049 16051//16051 -f 16050//16050 16051//16051 16052//16052 -f 16052//16052 16051//16051 16032//16032 -f 16052//16052 16032//16032 16034//16034 -f 16052//16052 16053//16053 16050//16050 -f 16050//16050 16053//16053 16054//16054 -f 16050//16050 16054//16054 16048//16048 -f 16048//16048 16054//16054 16055//16055 -f 16048//16048 16055//16055 16027//16027 -f 16027//16027 16055//16055 16031//16031 -f 16056//16056 16034//16034 16057//16057 -f 16057//16057 16034//16034 16058//16058 -f 15454//15454 16053//16053 15455//15455 -f 15455//15455 16053//16053 16052//16052 -f 15455//15455 16052//16052 16059//16059 -f 16059//16059 16052//16052 16034//16034 -f 16059//16059 16034//16034 16060//16060 -f 16056//16056 16061//16061 16034//16034 -f 16034//16034 16061//16061 16062//16062 -f 16034//16034 16062//16062 16060//16060 -f 16063//16063 16064//16064 16065//16065 -f 16065//16065 16064//16064 16066//16066 -f 16065//16065 16066//16066 16067//16067 -f 16067//16067 16066//16066 16068//16068 -f 16069//16069 16070//16070 16068//16068 -f 16068//16068 16070//16070 16071//16071 -f 16068//16068 16071//16071 16067//16067 -f 16072//16072 16073//16073 16069//16069 -f 16069//16069 16073//16073 16074//16074 -f 16069//16069 16074//16074 16070//16070 -f 16075//16075 16076//16076 16072//16072 -f 16072//16072 16076//16076 16077//16077 -f 16072//16072 16077//16077 16073//16073 -f 16078//16078 16079//16079 16080//16080 -f 16080//16080 16079//16079 16081//16081 -f 16080//16080 16081//16081 16082//16082 -f 16082//16082 16081//16081 16083//16083 -f 16082//16082 16083//16083 16075//16075 -f 16075//16075 16083//16083 16084//16084 -f 16075//16075 16084//16084 16076//16076 -f 16085//16085 16086//16086 16078//16078 -f 16078//16078 16086//16086 16087//16087 -f 16078//16078 16087//16087 16079//16079 -f 16088//16088 16089//16089 16085//16085 -f 16085//16085 16089//16089 16090//16090 -f 16085//16085 16090//16090 16086//16086 -f 16091//16091 16092//16092 16088//16088 -f 16088//16088 16092//16092 16093//16093 -f 16088//16088 16093//16093 16089//16089 -f 16094//16094 16092//16092 16095//16095 -f 16095//16095 16092//16092 16091//16091 -f 16095//16095 16091//16091 16096//16096 -f 16096//16096 16091//16091 16064//16064 -f 16096//16096 16064//16064 16097//16097 -f 16097//16097 16064//16064 16063//16063 -f 16097//16097 16063//16063 16098//16098 -f 16099//16099 16068//16068 16100//16100 -f 16100//16100 16068//16068 16066//16066 -f 16100//16100 16066//16066 16101//16101 -f 16101//16101 16066//16066 16064//16064 -f 16101//16101 16064//16064 16102//16102 -f 16102//16102 16064//16064 16091//16091 -f 16102//16102 16091//16091 16103//16103 -f 16103//16103 16091//16091 16088//16088 -f 16103//16103 16088//16088 16104//16104 -f 16104//16104 16088//16088 16085//16085 -f 16104//16104 16085//16085 16105//16105 -f 16105//16105 16085//16085 16078//16078 -f 16105//16105 16078//16078 16106//16106 -f 16106//16106 16078//16078 16080//16080 -f 16106//16106 16080//16080 16107//16107 -f 16107//16107 16080//16080 16082//16082 -f 16107//16107 16082//16082 16108//16108 -f 16108//16108 16082//16082 16075//16075 -f 16108//16108 16075//16075 16109//16109 -f 16109//16109 16075//16075 16072//16072 -f 16109//16109 16072//16072 16110//16110 -f 16110//16110 16072//16072 16069//16069 -f 16110//16110 16069//16069 16099//16099 -f 16099//16099 16069//16069 16068//16068 -f 16111//16111 16112//16112 16113//16113 -f 16114//16114 16115//16115 16116//16116 -f 16116//16116 16115//16115 16117//16117 -f 16116//16116 16117//16117 16118//16118 -f 16119//16119 16120//16120 16118//16118 -f 16118//16118 16120//16120 16121//16121 -f 16118//16118 16121//16121 16116//16116 -f 16122//16122 16123//16123 16119//16119 -f 16119//16119 16123//16123 16124//16124 -f 16119//16119 16124//16124 16120//16120 -f 16125//16125 16126//16126 16122//16122 -f 16122//16122 16126//16126 16127//16127 -f 16122//16122 16127//16127 16123//16123 -f 16128//16128 16129//16129 16125//16125 -f 16125//16125 16129//16129 16130//16130 -f 16125//16125 16130//16130 16126//16126 -f 16131//16131 16132//16132 16128//16128 -f 16128//16128 16132//16132 16133//16133 -f 16128//16128 16133//16133 16129//16129 -f 16134//16134 16135//16135 16131//16131 -f 16131//16131 16135//16135 16136//16136 -f 16131//16131 16136//16136 16132//16132 -f 16137//16137 16138//16138 16134//16134 -f 16134//16134 16138//16138 16139//16139 -f 16134//16134 16139//16139 16135//16135 -f 16113//16113 16140//16140 16111//16111 -f 16111//16111 16140//16140 16141//16141 -f 16111//16111 16141//16141 16137//16137 -f 16137//16137 16141//16141 16142//16142 -f 16137//16137 16142//16142 16138//16138 -f 16143//16143 16113//16113 16144//16144 -f 16144//16144 16113//16113 16112//16112 -f 16144//16144 16112//16112 16145//16145 -f 16145//16145 16112//16112 16115//16115 -f 16145//16145 16115//16115 16146//16146 -f 16146//16146 16115//16115 16114//16114 -f 16146//16146 16114//16114 16147//16147 -f 16148//16148 16112//16112 16149//16149 -f 16149//16149 16112//16112 16111//16111 -f 16149//16149 16111//16111 16150//16150 -f 16150//16150 16111//16111 16137//16137 -f 16150//16150 16137//16137 16151//16151 -f 16151//16151 16137//16137 16134//16134 -f 16151//16151 16134//16134 16152//16152 -f 16152//16152 16134//16134 16131//16131 -f 16152//16152 16131//16131 16153//16153 -f 16153//16153 16131//16131 16128//16128 -f 16153//16153 16128//16128 16154//16154 -f 16154//16154 16128//16128 16125//16125 -f 16154//16154 16125//16125 16155//16155 -f 16155//16155 16125//16125 16122//16122 -f 16155//16155 16122//16122 16156//16156 -f 16156//16156 16122//16122 16119//16119 -f 16156//16156 16119//16119 16157//16157 -f 16157//16157 16119//16119 16118//16118 -f 16157//16157 16118//16118 16158//16158 -f 16158//16158 16118//16118 16117//16117 -f 16158//16158 16117//16117 16159//16159 -f 16159//16159 16117//16117 16115//16115 -f 16159//16159 16115//16115 16148//16148 -f 16148//16148 16115//16115 16112//16112 -f 15118//15118 16002//16002 15117//15117 -f 15117//15117 16002//16002 16000//16000 -f 15117//15117 16000//16000 15080//15080 -f 15080//15080 16000//16000 15999//15999 -f 15080//15080 15999//15999 15078//15078 -f 15078//15078 15999//15999 15998//15998 -f 15078//15078 15998//15998 15140//15140 -f 15140//15140 15998//15998 16016//16016 -f 15140//15140 16016//16016 15139//15139 -f 15139//15139 16016//16016 16014//16014 -f 15139//15139 16014//16014 15127//15127 -f 15127//15127 16014//16014 16012//16012 -f 15127//15127 16012//16012 15125//15125 -f 15125//15125 16012//16012 16010//16010 -f 15125//15125 16010//16010 15124//15124 -f 15124//15124 16010//16010 16008//16008 -f 15124//15124 16008//16008 15123//15123 -f 15123//15123 16008//16008 16007//16007 -f 15123//15123 16007//16007 15121//15121 -f 15121//15121 16007//16007 16006//16006 -f 15121//15121 16006//16006 15119//15119 -f 15119//15119 16006//16006 16004//16004 -f 15119//15119 16004//16004 15118//15118 -f 15118//15118 16004//16004 16002//16002 -f 15088//15088 16032//16032 15130//15130 -f 15130//15130 16032//16032 16051//16051 -f 15130//15130 16051//16051 15120//15120 -f 15120//15120 16051//16051 16049//16049 -f 15120//15120 16049//16049 15122//15122 -f 15122//15122 16049//16049 16047//16047 -f 15122//15122 16047//16047 15108//15108 -f 15108//15108 16047//16047 16046//16046 -f 15108//15108 16046//16046 15106//15106 -f 15106//15106 16046//16046 16045//16045 -f 15106//15106 16045//16045 15104//15104 -f 15104//15104 16045//16045 16043//16043 -f 15104//15104 16043//16043 15102//15102 -f 15102//15102 16043//16043 16041//16041 -f 15102//15102 16041//16041 15110//15110 -f 15110//15110 16041//16041 16039//16039 -f 15110//15110 16039//16039 15082//15082 -f 15082//15082 16039//16039 16037//16037 -f 15082//15082 16037//16037 15084//15084 -f 15084//15084 16037//16037 16035//16035 -f 15084//15084 16035//16035 15085//15085 -f 15085//15085 16035//16035 16033//16033 -f 15085//15085 16033//16033 15088//15088 -f 15088//15088 16033//16033 16032//16032 -f 15133//15133 16155//16155 15132//15132 -f 15132//15132 16155//16155 16156//16156 -f 15132//15132 16156//16156 15131//15131 -f 15131//15131 16156//16156 16157//16157 -f 15131//15131 16157//16157 15129//15129 -f 15129//15129 16157//16157 16158//16158 -f 15129//15129 16158//16158 15090//15090 -f 15090//15090 16158//16158 16159//16159 -f 15090//15090 16159//16159 15089//15089 -f 15089//15089 16159//16159 16148//16148 -f 15089//15089 16148//16148 15083//15083 -f 15083//15083 16148//16148 16149//16149 -f 15083//15083 16149//16149 15100//15100 -f 15100//15100 16149//16149 16150//16150 -f 15100//15100 16150//16150 15098//15098 -f 15098//15098 16150//16150 16151//16151 -f 15098//15098 16151//16151 15097//15097 -f 15097//15097 16151//16151 16152//16152 -f 15097//15097 16152//16152 15094//15094 -f 15094//15094 16152//16152 16153//16153 -f 15094//15094 16153//16153 15092//15092 -f 15092//15092 16153//16153 16154//16154 -f 15092//15092 16154//16154 15133//15133 -f 15133//15133 16154//16154 16155//16155 -f 15076//15076 16106//16106 15116//15116 -f 15116//15116 16106//16106 16107//16107 -f 15116//15116 16107//16107 15115//15115 -f 15115//15115 16107//16107 16108//16108 -f 15115//15115 16108//16108 15138//15138 -f 15138//15138 16108//16108 16109//16109 -f 15138//15138 16109//16109 15137//15137 -f 15137//15137 16109//16109 16110//16110 -f 15137//15137 16110//16110 15135//15135 -f 15135//15135 16110//16110 16099//16099 -f 15135//15135 16099//16099 15134//15134 -f 15134//15134 16099//16099 16100//16100 -f 15134//15134 16100//16100 15077//15077 -f 15077//15077 16100//16100 16101//16101 -f 15077//15077 16101//16101 15079//15079 -f 15079//15079 16101//16101 16102//16102 -f 15079//15079 16102//16102 15081//15081 -f 15081//15081 16102//16102 16103//16103 -f 15081//15081 16103//16103 15087//15087 -f 15087//15087 16103//16103 16104//16104 -f 15087//15087 16104//16104 15086//15086 -f 15086//15086 16104//16104 16105//16105 -f 15086//15086 16105//16105 15076//15076 -f 15076//15076 16105//16105 16106//16106 -f 15539//15539 15784//15784 16160//16160 -f 16160//16160 15784//15784 15786//15786 -f 16160//16160 15786//15786 16161//16161 -f 16161//16161 15786//15786 16162//16162 -f 16162//16162 15786//15786 15787//15787 -f 16162//16162 15787//15787 16163//16163 -f 16163//16163 15787//15787 16164//16164 -f 16164//16164 15787//15787 15430//15430 -f 16164//16164 15430//15430 15434//15434 -f 15434//15434 15433//15433 16165//16165 -f 15434//15434 16165//16165 16164//16164 -f 16164//16164 16165//16165 16166//16166 -f 16164//16164 16166//16166 16163//16163 -f 16163//16163 16166//16166 16167//16167 -f 16163//16163 16167//16167 16162//16162 -f 16162//16162 16167//16167 16161//16161 -f 16161//16161 16167//16167 16168//16168 -f 16161//16161 16168//16168 16160//16160 -f 16160//16160 16168//16168 15540//15540 -f 16160//16160 15540//15540 15539//15539 -f 15783//15783 16169//16169 15782//15782 -f 15782//15782 16169//16169 15854//15854 -f 16169//16169 16170//16170 15854//15854 -f 15854//15854 16170//16170 16171//16171 -f 15854//15854 16171//16171 15853//15853 -f 15218//15218 15320//15320 16172//16172 -f 16172//16172 15320//15320 15853//15853 -f 16172//16172 15853//15853 16173//16173 -f 16173//16173 15853//15853 16171//16171 -f 15783//15783 15979//15979 16174//16174 -f 15783//15783 16174//16174 16169//16169 -f 16169//16169 16174//16174 16175//16175 -f 16169//16169 16175//16175 16170//16170 -f 16170//16170 16175//16175 16176//16176 -f 16170//16170 16176//16176 16171//16171 -f 16171//16171 16176//16176 16173//16173 -f 16173//16173 16176//16176 16177//16177 -f 16173//16173 16177//16177 16172//16172 -f 16172//16172 16177//16177 15219//15219 -f 16172//16172 15219//15219 15218//15218 -f 15516//15516 15515//15515 16178//16178 -f 15516//15516 16178//16178 16179//16179 -f 16179//16179 16178//16178 16180//16180 -f 16179//16179 16180//16180 16181//16181 -f 16181//16181 16180//16180 15482//15482 -f 16181//16181 15482//15482 15483//15483 -f 16182//16182 15496//15496 16183//16183 -f 16183//16183 15496//15496 15494//15494 -f 16183//16183 15494//15494 16184//16184 -f 16184//16184 15494//15494 15492//15492 -f 16184//16184 15492//15492 16185//16185 -f 16185//16185 15492//15492 15490//15490 -f 16185//16185 15490//15490 16186//16186 -f 16186//16186 15490//15490 15513//15513 -f 16186//16186 15513//15513 16187//16187 -f 16187//16187 15513//15513 15512//15512 -f 16187//16187 15512//15512 16188//16188 -f 16188//16188 15512//15512 15511//15511 -f 16188//16188 15511//15511 16189//16189 -f 16189//16189 15511//15511 15507//15507 -f 16189//16189 15507//15507 16190//16190 -f 16190//16190 15507//15507 15506//15506 -f 16190//16190 15506//15506 16191//16191 -f 16191//16191 15506//15506 15504//15504 -f 16191//16191 15504//15504 16192//16192 -f 16192//16192 15504//15504 15502//15502 -f 16192//16192 15502//15502 16193//16193 -f 16193//16193 15502//15502 15500//15500 -f 16193//16193 15500//15500 16194//16194 -f 16194//16194 15500//15500 15499//15499 -f 16194//16194 15499//15499 16195//16195 -f 16195//16195 15499//15499 15487//15487 -f 16195//16195 15487//15487 16196//16196 -f 16196//16196 15487//15487 15486//15486 -f 16196//16196 15486//15486 16197//16197 -f 16197//16197 15486//15486 15523//15523 -f 16197//16197 15523//15523 16198//16198 -f 16198//16198 15523//15523 15522//15522 -f 16198//16198 15522//15522 16199//16199 -f 16199//16199 15522//15522 15520//15520 -f 16199//16199 15520//15520 16200//16200 -f 16200//16200 15520//15520 15518//15518 -f 16200//16200 15518//15518 16201//16201 -f 16201//16201 15518//15518 15517//15517 -f 16201//16201 15517//15517 16202//16202 -f 16202//16202 15517//15517 15531//15531 -f 16202//16202 15531//15531 16203//16203 -f 16203//16203 15531//15531 15530//15530 -f 16203//16203 15530//15530 16204//16204 -f 16204//16204 15530//15530 15529//15529 -f 16204//16204 15529//15529 16205//16205 -f 16205//16205 15529//15529 15528//15528 -f 16205//16205 15528//15528 16206//16206 -f 16206//16206 15528//15528 15527//15527 -f 16206//16206 15527//15527 16207//16207 -f 16207//16207 15527//15527 15524//15524 -f 16207//16207 15524//15524 16182//16182 -f 16182//16182 15524//15524 15496//15496 -f 16208//16208 16205//16205 16209//16209 -f 16209//16209 16205//16205 16206//16206 -f 16209//16209 16206//16206 16210//16210 -f 16210//16210 16206//16206 16207//16207 -f 16210//16210 16207//16207 16211//16211 -f 16211//16211 16207//16207 16182//16182 -f 16211//16211 16182//16182 16212//16212 -f 16212//16212 16182//16182 16183//16183 -f 16212//16212 16183//16183 16213//16213 -f 16214//16214 16198//16198 16215//16215 -f 16215//16215 16198//16198 16199//16199 -f 16215//16215 16199//16199 16216//16216 -f 16216//16216 16199//16199 16200//16200 -f 16216//16216 16200//16200 16217//16217 -f 16217//16217 16200//16200 16201//16201 -f 16217//16217 16201//16201 16218//16218 -f 16218//16218 16201//16201 16202//16202 -f 16218//16218 16202//16202 16219//16219 -f 16219//16219 16202//16202 16203//16203 -f 16219//16219 16203//16203 16208//16208 -f 16208//16208 16203//16203 16204//16204 -f 16208//16208 16204//16204 16205//16205 -f 16183//16183 16184//16184 16213//16213 -f 16213//16213 16184//16184 16185//16185 -f 16213//16213 16185//16185 16220//16220 -f 16220//16220 16185//16185 16186//16186 -f 16220//16220 16186//16186 16221//16221 -f 16221//16221 16186//16186 16187//16187 -f 16221//16221 16187//16187 16222//16222 -f 16222//16222 16187//16187 16188//16188 -f 16222//16222 16188//16188 16223//16223 -f 16223//16223 16188//16188 16189//16189 -f 16223//16223 16189//16189 16224//16224 -f 16224//16224 16189//16189 16190//16190 -f 16224//16224 16190//16190 16225//16225 -f 16190//16190 16191//16191 16225//16225 -f 16225//16225 16191//16191 16192//16192 -f 16225//16225 16192//16192 16226//16226 -f 16226//16226 16192//16192 16193//16193 -f 16226//16226 16193//16193 16227//16227 -f 16227//16227 16193//16193 16194//16194 -f 16227//16227 16194//16194 16228//16228 -f 16228//16228 16194//16194 16195//16195 -f 16228//16228 16195//16195 16229//16229 -f 16229//16229 16195//16195 16196//16196 -f 16229//16229 16196//16196 16214//16214 -f 16214//16214 16196//16196 16197//16197 -f 16214//16214 16197//16197 16198//16198 -f 16230//16230 16212//16212 16231//16231 -f 16231//16231 16212//16212 16213//16213 -f 16231//16231 16213//16213 16232//16232 -f 16232//16232 16213//16213 16220//16220 -f 16232//16232 16220//16220 16233//16233 -f 16233//16233 16220//16220 16221//16221 -f 16233//16233 16221//16221 16234//16234 -f 16234//16234 16221//16221 16222//16222 -f 16234//16234 16222//16222 16235//16235 -f 16235//16235 16222//16222 16223//16223 -f 16235//16235 16223//16223 16236//16236 -f 16236//16236 16223//16223 16224//16224 -f 16236//16236 16224//16224 16237//16237 -f 16237//16237 16224//16224 16225//16225 -f 16237//16237 16225//16225 16238//16238 -f 16238//16238 16225//16225 16226//16226 -f 16238//16238 16226//16226 16239//16239 -f 16239//16239 16226//16226 16227//16227 -f 16239//16239 16227//16227 16240//16240 -f 16240//16240 16227//16227 16228//16228 -f 16240//16240 16228//16228 16241//16241 -f 16241//16241 16228//16228 16229//16229 -f 16241//16241 16229//16229 16242//16242 -f 16242//16242 16229//16229 16214//16214 -f 16242//16242 16214//16214 16243//16243 -f 16243//16243 16214//16214 16215//16215 -f 16243//16243 16215//16215 16244//16244 -f 16244//16244 16215//16215 16216//16216 -f 16244//16244 16216//16216 16245//16245 -f 16245//16245 16216//16216 16217//16217 -f 16245//16245 16217//16217 16246//16246 -f 16246//16246 16217//16217 16218//16218 -f 16246//16246 16218//16218 16247//16247 -f 16247//16247 16218//16218 16219//16219 -f 16247//16247 16219//16219 16248//16248 -f 16248//16248 16219//16219 16208//16208 -f 16248//16248 16208//16208 16249//16249 -f 16249//16249 16208//16208 16209//16209 -f 16249//16249 16209//16209 16250//16250 -f 16250//16250 16209//16209 16210//16210 -f 16250//16250 16210//16210 16251//16251 -f 16251//16251 16210//16210 16211//16211 -f 16251//16251 16211//16211 16230//16230 -f 16230//16230 16211//16211 16212//16212 -f 16252//16252 16248//16248 16253//16253 -f 16253//16253 16248//16248 16249//16249 -f 16253//16253 16249//16249 16254//16254 -f 16254//16254 16249//16249 16250//16250 -f 16254//16254 16250//16250 16255//16255 -f 16255//16255 16250//16250 16251//16251 -f 16255//16255 16251//16251 16256//16256 -f 16256//16256 16251//16251 16230//16230 -f 16256//16256 16230//16230 16257//16257 -f 16257//16257 16230//16230 16231//16231 -f 16257//16257 16231//16231 16258//16258 -f 16258//16258 16231//16231 16232//16232 -f 16258//16258 16232//16232 16259//16259 -f 16260//16260 16242//16242 16261//16261 -f 16261//16261 16242//16242 16243//16243 -f 16261//16261 16243//16243 16262//16262 -f 16262//16262 16243//16243 16244//16244 -f 16262//16262 16244//16244 16263//16263 -f 16263//16263 16244//16244 16245//16245 -f 16263//16263 16245//16245 16264//16264 -f 16264//16264 16245//16245 16246//16246 -f 16264//16264 16246//16246 16252//16252 -f 16252//16252 16246//16246 16247//16247 -f 16252//16252 16247//16247 16248//16248 -f 16232//16232 16233//16233 16259//16259 -f 16259//16259 16233//16233 16234//16234 -f 16259//16259 16234//16234 16265//16265 -f 16265//16265 16234//16234 16235//16235 -f 16265//16265 16235//16235 16266//16266 -f 16266//16266 16235//16235 16236//16236 -f 16266//16266 16236//16236 16267//16267 -f 16267//16267 16236//16236 16237//16237 -f 16267//16267 16237//16237 16268//16268 -f 16268//16268 16237//16237 16238//16238 -f 16268//16268 16238//16238 16269//16269 -f 16269//16269 16238//16238 16239//16239 -f 16269//16269 16239//16239 16270//16270 -f 16270//16270 16239//16239 16240//16240 -f 16270//16270 16240//16240 16260//16260 -f 16260//16260 16240//16240 16241//16241 -f 16260//16260 16241//16241 16242//16242 -f 16271//16271 16256//16256 16272//16272 -f 16272//16272 16256//16256 16257//16257 -f 16272//16272 16257//16257 16273//16273 -f 16273//16273 16257//16257 16258//16258 -f 16273//16273 16258//16258 16274//16274 -f 16274//16274 16258//16258 16259//16259 -f 16274//16274 16259//16259 16275//16275 -f 16275//16275 16259//16259 16265//16265 -f 16275//16275 16265//16265 16276//16276 -f 16276//16276 16265//16265 16266//16266 -f 16276//16276 16266//16266 16277//16277 -f 16277//16277 16266//16266 16267//16267 -f 16277//16277 16267//16267 16278//16278 -f 16278//16278 16267//16267 16268//16268 -f 16278//16278 16268//16268 16279//16279 -f 16279//16279 16268//16268 16269//16269 -f 16279//16279 16269//16269 16280//16280 -f 16280//16280 16269//16269 16270//16270 -f 16280//16280 16270//16270 16281//16281 -f 16281//16281 16270//16270 16260//16260 -f 16281//16281 16260//16260 16282//16282 -f 16282//16282 16260//16260 16261//16261 -f 16282//16282 16261//16261 16283//16283 -f 16283//16283 16261//16261 16262//16262 -f 16283//16283 16262//16262 16284//16284 -f 16284//16284 16262//16262 16263//16263 -f 16284//16284 16263//16263 16285//16285 -f 16285//16285 16263//16263 16264//16264 -f 16285//16285 16264//16264 16286//16286 -f 16286//16286 16264//16264 16252//16252 -f 16286//16286 16252//16252 16287//16287 -f 16287//16287 16252//16252 16253//16253 -f 16287//16287 16253//16253 16288//16288 -f 16288//16288 16253//16253 16254//16254 -f 16288//16288 16254//16254 16289//16289 -f 16289//16289 16254//16254 16255//16255 -f 16289//16289 16255//16255 16271//16271 -f 16271//16271 16255//16255 16256//16256 -f 16271//16271 16272//16272 16290//16290 -f 16287//16287 16288//16288 16290//16290 -f 16290//16290 16288//16288 16289//16289 -f 16290//16290 16289//16289 16271//16271 -f 16284//16284 16285//16285 16290//16290 -f 16290//16290 16285//16285 16286//16286 -f 16290//16290 16286//16286 16287//16287 -f 16281//16281 16282//16282 16290//16290 -f 16290//16290 16282//16282 16283//16283 -f 16290//16290 16283//16283 16284//16284 -f 16278//16278 16279//16279 16290//16290 -f 16290//16290 16279//16279 16280//16280 -f 16290//16290 16280//16280 16281//16281 -f 16275//16275 16276//16276 16290//16290 -f 16290//16290 16276//16276 16277//16277 -f 16290//16290 16277//16277 16278//16278 -f 16272//16272 16273//16273 16290//16290 -f 16290//16290 16273//16273 16274//16274 -f 16290//16290 16274//16274 16275//16275 -f 15848//15848 15333//15333 15844//15844 -f 15844//15844 15333//15333 15328//15328 -f 15838//15838 15350//15350 15834//15834 -f 15834//15834 15350//15350 15339//15339 -f 15828//15828 15359//15359 15824//15824 -f 15824//15824 15359//15359 15356//15356 -f 15286//15286 15814//15814 15287//15287 -f 15287//15287 15814//15814 15818//15818 -f 15287//15287 15818//15818 15297//15297 -f 15381//15381 15801//15801 15216//15216 -f 15216//15216 15801//15801 15806//15806 -f 15216//15216 15806//15806 15217//15217 -f 15778//15778 15383//15383 15779//15779 -f 15779//15779 15383//15383 15382//15382 -f 15386//15386 15766//15766 15385//15385 -f 15385//15385 15766//15766 15765//15765 -f 15385//15385 15765//15765 15384//15384 -f 15718//15718 15407//15407 15719//15719 -f 15719//15719 15407//15407 15406//15406 -f 15712//15712 15427//15427 15713//15713 -f 15713//15713 15427//15427 15426//15426 -f 15706//15706 15451//15451 15707//15707 -f 15707//15707 15451//15451 15450//15450 -f 15598//15598 15708//15708 15599//15599 -f 15599//15599 15708//15708 15709//15709 -f 15682//15682 15705//15705 15681//15681 -f 15681//15681 15705//15705 15704//15704 -f 15656//15656 15714//15714 15657//15657 -f 15657//15657 15714//15714 15715//15715 -f 15642//15642 15711//15711 15643//15643 -f 15643//15643 15711//15711 15710//15710 -f 15638//15638 15720//15720 15639//15639 -f 15639//15639 15720//15720 15721//15721 -f 15634//15634 15717//15717 15635//15635 -f 15635//15635 15717//15717 15716//15716 -f 15624//15624 15767//15767 15625//15625 -f 15625//15625 15767//15767 15768//15768 -f 15652//15652 15764//15764 15653//15653 -f 15653//15653 15764//15764 15763//15763 -f 15600//15600 15846//15846 15601//15601 -f 15601//15601 15846//15846 15845//15845 -f 15616//15616 15850//15850 15617//15617 -f 15617//15617 15850//15850 15843//15843 -f 15604//15604 15836//15836 15605//15605 -f 15605//15605 15836//15836 15835//15835 -f 15621//15621 15840//15840 15622//15622 -f 15622//15622 15840//15840 15833//15833 -f 15608//15608 15826//15826 15609//15609 -f 15609//15609 15826//15826 15825//15825 -f 15628//15628 15830//15830 15629//15629 -f 15629//15629 15830//15830 15823//15823 -f 15647//15647 15816//15816 15648//15648 -f 15648//15648 15816//15816 15815//15815 -f 15650//15650 15820//15820 15651//15651 -f 15651//15651 15820//15820 15813//15813 -f 15674//15674 15780//15780 15675//15675 -f 15675//15675 15780//15780 15781//15781 -f 15671//15671 15777//15777 15672//15672 -f 15672//15672 15777//15777 15776//15776 -f 15666//15666 15808//15808 15667//15667 -f 15667//15667 15808//15808 15802//15802 -f 15593//15593 15804//15804 15594//15594 -f 15594//15594 15804//15804 15803//15803 -f 15852//15852 15325//15325 15851//15851 -f 15851//15851 15325//15325 15326//15326 -f 15346//15346 15841//15841 15347//15347 -f 15347//15347 15841//15841 15842//15842 -f 15347//15347 15842//15842 15321//15321 -f 15361//15361 15831//15831 15369//15369 -f 15369//15369 15831//15831 15832//15832 -f 15369//15369 15832//15832 15338//15338 -f 15299//15299 15821//15821 15364//15364 -f 15364//15364 15821//15821 15822//15822 -f 15364//15364 15822//15822 15355//15355 -f 15812//15812 15288//15288 15811//15811 -f 15811//15811 15288//15288 15290//15290 -f 15810//15810 15290//15290 15809//15809 -f 15809//15809 15290//15290 15293//15293 -f 15788//15788 15432//15432 15785//15785 -f 15785//15785 15432//15432 15431//15431 -f 15448//15448 15789//15789 15449//15449 -f 15449//15449 15789//15789 15790//15790 -f 15449//15449 15790//15790 15414//15414 -f 15417//15417 15791//15791 15418//15418 -f 15418//15418 15791//15791 15792//15792 -f 15418//15418 15792//15792 15393//15393 -f 15401//15401 15793//15793 15400//15400 -f 15400//15400 15793//15793 15794//15794 -f 15400//15400 15794//15794 15229//15229 -f 15798//15798 15250//15250 15797//15797 -f 15797//15797 15250//15250 15248//15248 -f 15796//15796 15248//15248 15795//15795 -f 15795//15795 15248//15248 15246//15246 -f 15800//15800 15277//15277 15799//15799 -f 15799//15799 15277//15277 15276//15276 -f 15799//15799 15276//15276 15263//15263 -f 15485//15485 16053//16053 15456//15456 -f 15456//15456 16053//16053 15454//15454 -f 16053//16053 15485//15485 16054//16054 -f 16054//16054 15485//15485 15519//15519 -f 16054//16054 15519//15519 16055//16055 -f 16055//16055 15519//15519 15521//15521 -f 16055//16055 15521//15521 16031//16031 -f 16031//16031 15521//15521 15488//15488 -f 16059//16059 15433//15433 15455//15455 -f 15455//15455 15433//15433 15435//15435 -f 15516//15516 16030//16030 15488//15488 -f 15488//15488 16030//16030 16031//16031 -f 16057//16057 15540//15540 16056//16056 -f 16056//16056 15540//15540 16168//16168 -f 16056//16056 16168//16168 16061//16061 -f 16061//16061 16168//16168 16167//16167 -f 16061//16061 16167//16167 16062//16062 -f 16062//16062 16167//16167 16166//16166 -f 16062//16062 16166//16166 16060//16060 -f 16060//16060 16166//16166 16165//16165 -f 16060//16060 16165//16165 16059//16059 -f 16059//16059 16165//16165 15433//15433 -f 16030//16030 15516//15516 16179//16179 -f 16030//16030 16179//16179 16029//16029 -f 16029//16029 16179//16179 16181//16181 -f 16029//16029 16181//16181 16028//16028 -f 16028//16028 16181//16181 15483//15483 -f 16028//16028 15483//15483 16025//16025 -f 16058//16058 15541//15541 16057//16057 -f 16057//16057 15541//15541 15540//15540 -f 15478//15478 16026//16026 15483//15483 -f 15483//15483 16026//16026 16025//16025 -f 16044//16044 15479//15479 15532//15532 -f 15541//15541 16058//16058 15538//15538 -f 15538//15538 16058//16058 16034//16034 -f 15538//15538 16034//16034 16036//16036 -f 16044//16044 15532//15532 16042//16042 -f 16042//16042 15532//15532 15533//15533 -f 16042//16042 15533//15533 16040//16040 -f 16040//16040 15533//15533 15534//15534 -f 16040//16040 15534//15534 16038//16038 -f 15534//15534 15535//15535 16038//16038 -f 16038//16038 15535//15535 15536//15536 -f 16038//16038 15536//15536 16036//16036 -f 16036//16036 15536//15536 15537//15537 -f 16036//16036 15537//15537 15538//15538 -f 15479//15479 16044//16044 15478//15478 -f 15478//15478 16044//16044 16026//16026 -f 16017//16017 15505//15505 15856//15856 -f 15856//15856 15505//15505 15509//15509 -f 15855//15855 15319//15319 16018//16018 -f 16018//16018 15319//15319 15220//15220 -f 16018//16018 15220//15220 15219//15219 -f 15989//15989 15514//15514 16023//16023 -f 16023//16023 15514//15514 15501//15501 -f 16023//16023 15501//15501 16024//16024 -f 16024//16024 15501//15501 15503//15503 -f 16024//16024 15503//15503 16017//16017 -f 16017//16017 15503//15503 15505//15505 -f 15996//15996 15995//15995 16019//16019 -f 15996//15996 16019//16019 15979//15979 -f 16018//16018 15219//15219 16020//16020 -f 16020//16020 15219//15219 16177//16177 -f 16020//16020 16177//16177 16021//16021 -f 16021//16021 16177//16177 16176//16176 -f 16021//16021 16176//16176 16022//16022 -f 16022//16022 16176//16176 16175//16175 -f 16022//16022 16175//16175 16019//16019 -f 16019//16019 16175//16175 16174//16174 -f 16019//16019 16174//16174 15979//15979 -f 15988//15988 15515//15515 15989//15989 -f 15989//15989 15515//15515 15514//15514 -f 15979//15979 15980//15980 15996//15996 -f 15993//15993 15482//15482 16180//16180 -f 15993//15993 16180//16180 15992//15992 -f 15992//15992 16180//16180 16178//16178 -f 15992//15992 16178//16178 15991//15991 -f 15991//15991 16178//16178 15515//15515 -f 15991//15991 15515//15515 15988//15988 -f 15997//15997 15996//15996 15980//15980 -f 15980//15980 15981//15981 15997//15997 -f 15997//15997 15981//15981 15982//15982 -f 15997//15997 15982//15982 16015//16015 -f 16015//16015 15982//15982 15983//15983 -f 15983//15983 15984//15984 16015//16015 -f 16015//16015 15984//15984 15985//15985 -f 16015//16015 15985//15985 16013//16013 -f 15985//15985 15986//15986 16013//16013 -f 16013//16013 15986//15986 15987//15987 -f 16013//16013 15987//15987 16011//16011 -f 16011//16011 15987//15987 15480//15480 -f 16011//16011 15480//15480 16009//16009 -f 15994//15994 15481//15481 15993//15993 -f 15993//15993 15481//15481 15482//15482 -f 15481//15481 15994//15994 15480//15480 -f 15480//15480 15994//15994 16009//16009 -f 15484//15484 15457//15457 15868//15868 -f 15868//15868 15457//15457 15458//15458 -f 15475//15475 15868//15868 15458//15458 -f 15474//15474 15867//15867 15475//15475 -f 15475//15475 15867//15867 15868//15868 -f 16113//16113 16143//16143 15452//15452 -f 15452//15452 16143//16143 15453//15453 -f 15453//15453 15470//15470 15458//15458 -f 15458//15458 15470//15470 15475//15475 -f 15867//15867 15474//15474 15866//15866 -f 15866//15866 15474//15474 15476//15476 -f 15866//15866 15476//15476 15865//15865 -f 15865//15865 15476//15476 15477//15477 -f 15865//15865 15477//15477 15864//15864 -f 15864//15864 15477//15477 15469//15469 -f 15864//15864 15469//15469 15863//15863 -f 15863//15863 15469//15469 15468//15468 -f 15863//15863 15468//15468 15862//15862 -f 15862//15862 15468//15468 15466//15466 -f 15862//15862 15466//15466 15861//15861 -f 15861//15861 15466//15466 15465//15465 -f 15861//15861 15465//15465 15860//15860 -f 15860//15860 15465//15465 15473//15473 -f 15452//15452 15233//15233 15244//15244 -f 15260//15260 15270//15270 16116//16116 -f 16116//16116 15270//15270 15460//15460 -f 16116//16116 15460//15460 16114//16114 -f 15260//15260 16116//16116 15259//15259 -f 15259//15259 16116//16116 16121//16121 -f 15259//15259 16121//16121 15268//15268 -f 16121//16121 16120//16120 15268//15268 -f 15268//15268 16120//16120 16124//16124 -f 15268//15268 16124//16124 15269//15269 -f 16124//16124 16123//16123 15269//15269 -f 15269//15269 16123//16123 16127//16127 -f 15269//15269 16127//16127 15249//15249 -f 16127//16127 16126//16126 15249//15249 -f 15249//15249 16126//16126 16130//16130 -f 15249//15249 16130//16130 15247//15247 -f 16130//16130 16129//16129 15247//15247 -f 15247//15247 16129//16129 16133//16133 -f 15247//15247 16133//16133 15238//15238 -f 15238//15238 16133//16133 16132//16132 -f 15238//15238 16132//16132 15239//15239 -f 15239//15239 16132//16132 16136//16136 -f 15239//15239 16136//16136 15241//15241 -f 16136//16136 16135//16135 15241//15241 -f 15241//15241 16135//16135 16139//16139 -f 15241//15241 16139//16139 15243//15243 -f 16139//16139 16138//16138 15243//15243 -f 15243//15243 16138//16138 16142//16142 -f 15243//15243 16142//16142 15244//15244 -f 15244//15244 16142//16142 16141//16141 -f 15244//15244 16141//16141 15452//15452 -f 15452//15452 16141//16141 16140//16140 -f 15452//15452 16140//16140 16113//16113 -f 15453//15453 16143//16143 15470//15470 -f 15464//15464 15859//15859 15473//15473 -f 15473//15473 15859//15859 15860//15860 -f 15859//15859 15858//15858 15508//15508 -f 15508//15508 15858//15858 15510//15510 -f 15459//15459 16147//16147 15460//15460 -f 15460//15460 16147//16147 16114//16114 -f 16146//16146 16147//16147 15471//15471 -f 16146//16146 15471//15471 16145//16145 -f 16145//16145 15471//15471 15467//15467 -f 16145//16145 15467//15467 16144//16144 -f 16144//16144 15467//15467 15470//15470 -f 16144//16144 15470//15470 16143//16143 -f 15859//15859 15464//15464 15858//15858 -f 16147//16147 15459//15459 15471//15471 -f 15463//15463 15857//15857 15464//15464 -f 15464//15464 15857//15857 15858//15858 -f 15461//15461 15472//15472 15459//15459 -f 15459//15459 15472//15472 15471//15471 -f 15472//15472 16094//16094 16095//16095 -f 15472//15472 16095//16095 15462//15462 -f 15462//15462 16095//16095 16096//16096 -f 15462//15462 16096//16096 15463//15463 -f 15463//15463 16096//16096 16097//16097 -f 15463//15463 16097//16097 16098//16098 -f 15463//15463 16098//16098 15857//15857 -f 15472//15472 15461//15461 16094//16094 -f 15221//15221 15857//15857 15222//15222 -f 15222//15222 15857//15857 16098//16098 -f 15222//15222 16098//16098 16063//16063 -f 15461//15461 15273//15273 16094//16094 -f 16094//16094 15273//15273 15275//15275 -f 16094//16094 15275//15275 16092//16092 -f 16092//16092 15275//15275 16093//16093 -f 16093//16093 15275//15275 15274//15274 -f 15223//15223 15222//15222 16063//16063 -f 16063//16063 16065//16065 15223//15223 -f 15223//15223 16065//16065 16067//16067 -f 15223//15223 16067//16067 15306//15306 -f 16067//16067 16071//16071 15306//15306 -f 15306//15306 16071//16071 16070//16070 -f 15306//15306 16070//16070 15312//15312 -f 16070//16070 16074//16074 15312//15312 -f 15312//15312 16074//16074 16073//16073 -f 15312//15312 16073//16073 15311//15311 -f 16073//16073 16077//16077 15311//15311 -f 15311//15311 16077//16077 16076//16076 -f 15311//15311 16076//16076 15289//15289 -f 15289//15289 16076//16076 15291//15291 -f 16076//16076 16084//16084 15291//15291 -f 15291//15291 16084//16084 16083//16083 -f 15291//15291 16083//16083 15292//15292 -f 15292//15292 16083//16083 16081//16081 -f 15292//15292 16081//16081 15294//15294 -f 15294//15294 16081//16081 16079//16079 -f 15294//15294 16079//16079 15380//15380 -f 15380//15380 16079//16079 15378//15378 -f 15378//15378 16079//16079 16087//16087 -f 15378//15378 16087//16087 15376//15376 -f 16087//16087 16086//16086 15376//15376 -f 15376//15376 16086//16086 16090//16090 -f 15376//15376 16090//16090 15274//15274 -f 15274//15274 16090//16090 16089//16089 -f 15274//15274 16089//16089 16093//16093 -f 16291//16291 16292//16292 16293//16293 -f 16294//16294 16295//16295 16296//16296 -f 16297//16297 16298//16298 16299//16299 -f 16300//16300 16301//16301 16302//16302 -f 16303//16303 16304//16304 16305//16305 -f 16306//16306 16307//16307 16308//16308 -f 16308//16308 16307//16307 16309//16309 -f 16308//16308 16309//16309 16310//16310 -f 16311//16311 16312//16312 16313//16313 -f 16313//16313 16314//16314 16311//16311 -f 16311//16311 16314//16314 16315//16315 -f 16311//16311 16315//16315 16316//16316 -f 16316//16316 16315//16315 16317//16317 -f 16316//16316 16317//16317 16318//16318 -f 16319//16319 16320//16320 16321//16321 -f 16321//16321 16320//16320 16322//16322 -f 16321//16321 16322//16322 16323//16323 -f 16323//16323 16322//16322 16324//16324 -f 16323//16323 16324//16324 16318//16318 -f 16318//16318 16324//16324 16325//16325 -f 16318//16318 16325//16325 16316//16316 -f 16326//16326 16327//16327 16328//16328 -f 16328//16328 16327//16327 16329//16329 -f 16328//16328 16329//16329 16330//16330 -f 16330//16330 16329//16329 16331//16331 -f 16330//16330 16331//16331 16332//16332 -f 16331//16331 16333//16333 16332//16332 -f 16332//16332 16333//16333 16334//16334 -f 16332//16332 16334//16334 16302//16302 -f 16302//16302 16334//16334 16335//16335 -f 16302//16302 16335//16335 16336//16336 -f 16337//16337 16338//16338 16339//16339 -f 16339//16339 16338//16338 16340//16340 -f 16339//16339 16340//16340 16341//16341 -f 16341//16341 16340//16340 16342//16342 -f 16343//16343 16344//16344 16345//16345 -f 16345//16345 16344//16344 16346//16346 -f 16345//16345 16346//16346 16347//16347 -f 16343//16343 16348//16348 16344//16344 -f 16344//16344 16348//16348 16349//16349 -f 16344//16344 16349//16349 16350//16350 -f 16350//16350 16349//16349 16351//16351 -f 16350//16350 16351//16351 16352//16352 -f 16353//16353 16354//16354 16355//16355 -f 16356//16356 16357//16357 16358//16358 -f 16358//16358 16357//16357 16359//16359 -f 16358//16358 16359//16359 16345//16345 -f 16345//16345 16359//16359 16360//16360 -f 16345//16345 16360//16360 16343//16343 -f 16351//16351 16361//16361 16352//16352 -f 16352//16352 16361//16361 16362//16362 -f 16352//16352 16362//16362 16354//16354 -f 16354//16354 16362//16362 16363//16363 -f 16354//16354 16363//16363 16355//16355 -f 16364//16364 16365//16365 16366//16366 -f 16365//16365 16367//16367 16366//16366 -f 16366//16366 16367//16367 16368//16368 -f 16366//16366 16368//16368 16369//16369 -f 16369//16369 16368//16368 16370//16370 -f 16370//16370 16371//16371 16369//16369 -f 16369//16369 16371//16371 16372//16372 -f 16369//16369 16372//16372 16373//16373 -f 16372//16372 16374//16374 16373//16373 -f 16373//16373 16374//16374 16375//16375 -f 16373//16373 16375//16375 16376//16376 -f 16376//16376 16375//16375 16377//16377 -f 16376//16376 16377//16377 16378//16378 -f 16378//16378 16377//16377 16379//16379 -f 16378//16378 16379//16379 16380//16380 -f 16380//16380 16379//16379 16381//16381 -f 16380//16380 16381//16381 16364//16364 -f 16382//16382 16383//16383 16384//16384 -f 16384//16384 16383//16383 16385//16385 -f 16384//16384 16385//16385 16386//16386 -f 16386//16386 16385//16385 16387//16387 -f 16386//16386 16387//16387 16388//16388 -f 16388//16388 16389//16389 16386//16386 -f 16386//16386 16389//16389 16390//16390 -f 16386//16386 16390//16390 16391//16391 -f 16392//16392 16393//16393 16394//16394 -f 16390//16390 16395//16395 16391//16391 -f 16391//16391 16395//16395 16396//16396 -f 16391//16391 16396//16396 16393//16393 -f 16394//16394 16397//16397 16392//16392 -f 16392//16392 16397//16397 16398//16398 -f 16392//16392 16398//16398 16399//16399 -f 16399//16399 16398//16398 16400//16400 -f 16399//16399 16400//16400 16401//16401 -f 16401//16401 16400//16400 16402//16402 -f 16401//16401 16402//16402 16387//16387 -f 16387//16387 16402//16402 16403//16403 -f 16387//16387 16403//16403 16388//16388 -f 16404//16404 16405//16405 16406//16406 -f 16406//16406 16405//16405 16407//16407 -f 16406//16406 16407//16407 16408//16408 -f 16409//16409 16410//16410 16411//16411 -f 16411//16411 16410//16410 16412//16412 -f 16411//16411 16412//16412 16413//16413 -f 16409//16409 16414//16414 16410//16410 -f 16410//16410 16414//16414 16415//16415 -f 16410//16410 16415//16415 16416//16416 -f 16416//16416 16415//16415 16417//16417 -f 16416//16416 16417//16417 16418//16418 -f 16418//16418 16417//16417 16419//16419 -f 16418//16418 16419//16419 16407//16407 -f 16407//16407 16419//16419 16420//16420 -f 16407//16407 16420//16420 16408//16408 -f 16421//16421 16422//16422 16423//16423 -f 16423//16423 16422//16422 16406//16406 -f 16423//16423 16406//16406 16424//16424 -f 16424//16424 16406//16406 16408//16408 -f 16425//16425 16426//16426 16427//16427 -f 16425//16425 16427//16427 16428//16428 -f 16429//16429 16430//16430 16406//16406 -f 16406//16406 16430//16430 16431//16431 -f 16406//16406 16431//16431 16404//16404 -f 16404//16404 16431//16431 16432//16432 -f 16404//16404 16432//16432 16433//16433 -f 16434//16434 16435//16435 16436//16436 -f 16437//16437 16438//16438 16439//16439 -f 16438//16438 16440//16440 16439//16439 -f 16439//16439 16440//16440 16441//16441 -f 16439//16439 16441//16441 16442//16442 -f 16442//16442 16441//16441 16443//16443 -f 16427//16427 16444//16444 16428//16428 -f 16428//16428 16444//16444 16445//16445 -f 16428//16428 16445//16445 16446//16446 -f 16446//16446 16445//16445 16447//16447 -f 16448//16448 16293//16293 16449//16449 -f 16449//16449 16293//16293 16450//16450 -f 16449//16449 16450//16450 16412//16412 -f 16412//16412 16450//16450 16422//16422 -f 16412//16412 16422//16422 16413//16413 -f 16413//16413 16422//16422 16421//16421 -f 16451//16451 16452//16452 16453//16453 -f 16454//16454 16453//16453 16455//16455 -f 16456//16456 16457//16457 16458//16458 -f 16458//16458 16457//16457 16428//16428 -f 16458//16458 16428//16428 16459//16459 -f 16459//16459 16428//16428 16446//16446 -f 16459//16459 16446//16446 16460//16460 -f 16460//16460 16446//16446 16447//16447 -f 16460//16460 16447//16447 16461//16461 -f 16369//16369 16462//16462 16366//16366 -f 16366//16366 16462//16462 16463//16463 -f 16366//16366 16463//16463 16460//16460 -f 16460//16460 16463//16463 16464//16464 -f 16460//16460 16464//16464 16459//16459 -f 16465//16465 16466//16466 16467//16467 -f 16468//16468 16376//16376 16469//16469 -f 16469//16469 16376//16376 16378//16378 -f 16469//16469 16378//16378 16470//16470 -f 16470//16470 16378//16378 16467//16467 -f 16471//16471 16472//16472 16473//16473 -f 16474//16474 16472//16472 16475//16475 -f 16475//16475 16472//16472 16471//16471 -f 16475//16475 16471//16471 16476//16476 -f 16337//16337 16326//16326 16338//16338 -f 16338//16338 16326//16326 16328//16328 -f 16338//16338 16328//16328 16477//16477 -f 16477//16477 16328//16328 16478//16478 -f 16477//16477 16478//16478 16479//16479 -f 16479//16479 16478//16478 16480//16480 -f 16479//16479 16480//16480 16481//16481 -f 16299//16299 16298//16298 16340//16340 -f 16336//16336 16342//16342 16302//16302 -f 16302//16302 16342//16342 16340//16340 -f 16302//16302 16340//16340 16300//16300 -f 16300//16300 16340//16340 16298//16298 -f 16300//16300 16298//16298 16482//16482 -f 16299//16299 16483//16483 16297//16297 -f 16297//16297 16483//16483 16484//16484 -f 16297//16297 16484//16484 16485//16485 -f 16485//16485 16484//16484 16486//16486 -f 16487//16487 16488//16488 16484//16484 -f 16484//16484 16488//16488 16489//16489 -f 16484//16484 16489//16489 16486//16486 -f 16490//16490 16491//16491 16492//16492 -f 16492//16492 16491//16491 16493//16493 -f 16492//16492 16493//16493 16494//16494 -f 16494//16494 16493//16493 16495//16495 -f 16496//16496 16497//16497 16493//16493 -f 16498//16498 16495//16495 16499//16499 -f 16499//16499 16495//16495 16493//16493 -f 16499//16499 16493//16493 16500//16500 -f 16500//16500 16493//16493 16497//16497 -f 16501//16501 16502//16502 16503//16503 -f 16393//16393 16392//16392 16391//16391 -f 16391//16391 16392//16392 16504//16504 -f 16391//16391 16504//16504 16505//16505 -f 16505//16505 16506//16506 16391//16391 -f 16391//16391 16506//16506 16507//16507 -f 16391//16391 16507//16507 16508//16508 -f 16508//16508 16507//16507 16501//16501 -f 16509//16509 16510//16510 16511//16511 -f 16511//16511 16512//16512 16509//16509 -f 16509//16509 16512//16512 16513//16513 -f 16509//16509 16513//16513 16344//16344 -f 16344//16344 16513//16513 16514//16514 -f 16344//16344 16514//16514 16346//16346 -f 16512//16512 16515//16515 16513//16513 -f 16513//16513 16515//16515 16516//16516 -f 16513//16513 16516//16516 16517//16517 -f 16517//16517 16516//16516 16518//16518 -f 16517//16517 16518//16518 16519//16519 -f 16518//16518 16520//16520 16519//16519 -f 16519//16519 16520//16520 16521//16521 -f 16519//16519 16521//16521 16522//16522 -f 16523//16523 16524//16524 16525//16525 -f 16525//16525 16524//16524 16526//16526 -f 16525//16525 16526//16526 16510//16510 -f 16510//16510 16526//16526 16527//16527 -f 16510//16510 16527//16527 16511//16511 -f 16378//16378 16528//16528 16519//16519 -f 16467//16467 16378//16378 16465//16465 -f 16465//16465 16378//16378 16519//16519 -f 16465//16465 16519//16519 16525//16525 -f 16525//16525 16519//16519 16522//16522 -f 16525//16525 16522//16522 16523//16523 -f 16364//16364 16366//16366 16380//16380 -f 16380//16380 16366//16366 16529//16529 -f 16380//16380 16529//16529 16378//16378 -f 16378//16378 16529//16529 16530//16530 -f 16378//16378 16530//16530 16528//16528 -f 16531//16531 16532//16532 16460//16460 -f 16532//16532 16533//16533 16460//16460 -f 16460//16460 16533//16533 16534//16534 -f 16460//16460 16534//16534 16366//16366 -f 16366//16366 16534//16534 16535//16535 -f 16366//16366 16535//16535 16529//16529 -f 16536//16536 16537//16537 16538//16538 -f 16538//16538 16537//16537 16531//16531 -f 16538//16538 16531//16531 16539//16539 -f 16539//16539 16531//16531 16460//16460 -f 16539//16539 16460//16460 16540//16540 -f 16540//16540 16460//16460 16461//16461 -f 16541//16541 16536//16536 16439//16439 -f 16439//16439 16536//16536 16538//16538 -f 16439//16439 16538//16538 16437//16437 -f 16437//16437 16538//16538 16539//16539 -f 16437//16437 16539//16539 16542//16542 -f 16542//16542 16539//16539 16540//16540 -f 16543//16543 16544//16544 16545//16545 -f 16545//16545 16544//16544 16546//16546 -f 16545//16545 16546//16546 16547//16547 -f 16547//16547 16546//16546 16548//16548 -f 16547//16547 16548//16548 16439//16439 -f 16439//16439 16548//16548 16549//16549 -f 16439//16439 16549//16549 16541//16541 -f 16550//16550 16551//16551 16552//16552 -f 16551//16551 16550//16550 16553//16553 -f 16554//16554 16555//16555 16556//16556 -f 16557//16557 16558//16558 16559//16559 -f 16555//16555 16554//16554 16559//16559 -f 16559//16559 16554//16554 16560//16560 -f 16559//16559 16560//16560 16557//16557 -f 16558//16558 16557//16557 16561//16561 -f 16561//16561 16557//16557 16562//16562 -f 16561//16561 16562//16562 16563//16563 -f 16564//16564 16565//16565 16551//16551 -f 16551//16551 16565//16565 16566//16566 -f 16551//16551 16566//16566 16552//16552 -f 16552//16552 16566//16566 16567//16567 -f 16552//16552 16567//16567 16568//16568 -f 16568//16568 16567//16567 16569//16569 -f 16568//16568 16569//16569 16570//16570 -f 16570//16570 16569//16569 16571//16571 -f 16570//16570 16571//16571 16572//16572 -f 16572//16572 16571//16571 16573//16573 -f 16572//16572 16573//16573 16574//16574 -f 16575//16575 16576//16576 16577//16577 -f 16577//16577 16576//16576 16578//16578 -f 16575//16575 16579//16579 16576//16576 -f 16576//16576 16579//16579 16580//16580 -f 16576//16576 16580//16580 16312//16312 -f 16312//16312 16580//16580 16581//16581 -f 16312//16312 16581//16581 16313//16313 -f 16313//16313 16581//16581 16582//16582 -f 16313//16313 16582//16582 16583//16583 -f 16583//16583 16582//16582 16584//16584 -f 16583//16583 16584//16584 16306//16306 -f 16306//16306 16584//16584 16585//16585 -f 16306//16306 16585//16585 16307//16307 -f 16586//16586 16587//16587 16588//16588 -f 16588//16588 16587//16587 16589//16589 -f 16588//16588 16589//16589 16578//16578 -f 16578//16578 16589//16589 16590//16590 -f 16578//16578 16590//16590 16577//16577 -f 16591//16591 16592//16592 16593//16593 -f 16593//16593 16592//16592 16594//16594 -f 16593//16593 16594//16594 16595//16595 -f 16586//16586 16588//16588 16596//16596 -f 16596//16596 16588//16588 16597//16597 -f 16596//16596 16597//16597 16598//16598 -f 16598//16598 16597//16597 16491//16491 -f 16598//16598 16491//16491 16599//16599 -f 16599//16599 16491//16491 16490//16490 -f 16599//16599 16490//16490 16593//16593 -f 16593//16593 16490//16490 16600//16600 -f 16593//16593 16600//16600 16591//16591 -f 16499//16499 16601//16601 16498//16498 -f 16498//16498 16601//16601 16602//16602 -f 16498//16498 16602//16602 16603//16603 -f 16603//16603 16602//16602 16604//16604 -f 16603//16603 16604//16604 16605//16605 -f 16605//16605 16604//16604 16606//16606 -f 16605//16605 16606//16606 16607//16607 -f 16607//16607 16606//16606 16594//16594 -f 16607//16607 16594//16594 16608//16608 -f 16608//16608 16594//16594 16592//16592 -f 16319//16319 16310//16310 16320//16320 -f 16320//16320 16310//16310 16309//16309 -f 16320//16320 16309//16309 16594//16594 -f 16594//16594 16309//16309 16609//16609 -f 16594//16594 16609//16609 16595//16595 -f 16296//16296 16610//16610 16611//16611 -f 16564//16564 16612//16612 16613//16613 -f 16295//16295 16565//16565 16296//16296 -f 16296//16296 16565//16565 16564//16564 -f 16296//16296 16564//16564 16610//16610 -f 16610//16610 16564//16564 16613//16613 -f 16311//16311 16614//16614 16312//16312 -f 16312//16312 16614//16614 16615//16615 -f 16312//16312 16615//16615 16576//16576 -f 16576//16576 16615//16615 16616//16616 -f 16576//16576 16616//16616 16617//16617 -f 16611//16611 16618//16618 16296//16296 -f 16296//16296 16618//16618 16619//16619 -f 16296//16296 16619//16619 16620//16620 -f 16620//16620 16619//16619 16621//16621 -f 16620//16620 16621//16621 16311//16311 -f 16311//16311 16621//16621 16622//16622 -f 16311//16311 16622//16622 16614//16614 -f 16623//16623 16624//16624 16625//16625 -f 16623//16623 16625//16625 16626//16626 -f 16627//16627 16628//16628 16629//16629 -f 16629//16629 16628//16628 16630//16630 -f 16629//16629 16630//16630 16631//16631 -f 16631//16631 16626//16626 16629//16629 -f 16629//16629 16626//16626 16625//16625 -f 16629//16629 16625//16625 16632//16632 -f 16632//16632 16625//16625 16553//16553 -f 16632//16632 16553//16553 16633//16633 -f 16633//16633 16553//16553 16550//16550 -f 16493//16493 16634//16634 16627//16627 -f 16627//16627 16634//16634 16635//16635 -f 16627//16627 16635//16635 16628//16628 -f 16624//16624 16636//16636 16597//16597 -f 16597//16597 16636//16636 16637//16637 -f 16597//16597 16637//16637 16491//16491 -f 16491//16491 16637//16637 16638//16638 -f 16491//16491 16638//16638 16493//16493 -f 16493//16493 16638//16638 16639//16639 -f 16493//16493 16639//16639 16634//16634 -f 16640//16640 16330//16330 16641//16641 -f 16641//16641 16330//16330 16332//16332 -f 16641//16641 16332//16332 16642//16642 -f 16642//16642 16332//16332 16302//16302 -f 16642//16642 16302//16302 16643//16643 -f 16643//16643 16302//16302 16301//16301 -f 16644//16644 16350//16350 16645//16645 -f 16645//16645 16350//16350 16352//16352 -f 16645//16645 16352//16352 16646//16646 -f 16646//16646 16352//16352 16354//16354 -f 16647//16647 16466//16466 16648//16648 -f 16648//16648 16466//16466 16465//16465 -f 16648//16648 16465//16465 16649//16649 -f 16649//16649 16465//16465 16525//16525 -f 16649//16649 16525//16525 16650//16650 -f 16650//16650 16525//16525 16510//16510 -f 16355//16355 16356//16356 16353//16353 -f 16353//16353 16356//16356 16358//16358 -f 16353//16353 16358//16358 16473//16473 -f 16473//16473 16358//16358 16651//16651 -f 16473//16473 16651//16651 16471//16471 -f 16471//16471 16651//16651 16652//16652 -f 16652//16652 16653//16653 16471//16471 -f 16471//16471 16653//16653 16654//16654 -f 16471//16471 16654//16654 16655//16655 -f 16656//16656 16657//16657 16479//16479 -f 16481//16481 16476//16476 16479//16479 -f 16479//16479 16476//16476 16471//16471 -f 16479//16479 16471//16471 16656//16656 -f 16656//16656 16471//16471 16655//16655 -f 16658//16658 16477//16477 16659//16659 -f 16659//16659 16477//16477 16479//16479 -f 16659//16659 16479//16479 16660//16660 -f 16660//16660 16479//16479 16657//16657 -f 16658//16658 16661//16661 16477//16477 -f 16477//16477 16661//16661 16662//16662 -f 16477//16477 16662//16662 16651//16651 -f 16651//16651 16662//16662 16663//16663 -f 16651//16651 16663//16663 16652//16652 -f 16477//16477 16294//16294 16338//16338 -f 16338//16338 16294//16294 16296//16296 -f 16338//16338 16296//16296 16340//16340 -f 16340//16340 16296//16296 16620//16620 -f 16340//16340 16620//16620 16299//16299 -f 16299//16299 16620//16620 16311//16311 -f 16299//16299 16311//16311 16483//16483 -f 16483//16483 16311//16311 16316//16316 -f 16347//16347 16543//16543 16345//16345 -f 16345//16345 16543//16543 16545//16545 -f 16345//16345 16545//16545 16358//16358 -f 16358//16358 16545//16545 16664//16664 -f 16545//16545 16665//16665 16666//16666 -f 16667//16667 16668//16668 16664//16664 -f 16666//16666 16669//16669 16545//16545 -f 16545//16545 16669//16669 16670//16670 -f 16545//16545 16670//16670 16664//16664 -f 16664//16664 16670//16670 16671//16671 -f 16664//16664 16671//16671 16667//16667 -f 16668//16668 16572//16572 16664//16664 -f 16664//16664 16572//16572 16574//16574 -f 16664//16664 16574//16574 16358//16358 -f 16358//16358 16574//16574 16672//16672 -f 16358//16358 16672//16672 16651//16651 -f 16651//16651 16672//16672 16673//16673 -f 16651//16651 16673//16673 16477//16477 -f 16477//16477 16673//16673 16674//16674 -f 16477//16477 16674//16674 16294//16294 -f 16668//16668 16675//16675 16572//16572 -f 16572//16572 16675//16675 16676//16676 -f 16572//16572 16676//16676 16677//16677 -f 16665//16665 16545//16545 16678//16678 -f 16678//16678 16545//16545 16547//16547 -f 16678//16678 16547//16547 16679//16679 -f 16680//16680 16681//16681 16442//16442 -f 16442//16442 16681//16681 16570//16570 -f 16442//16442 16570//16570 16439//16439 -f 16439//16439 16570//16570 16572//16572 -f 16439//16439 16572//16572 16547//16547 -f 16547//16547 16572//16572 16677//16677 -f 16547//16547 16677//16677 16679//16679 -f 16624//16624 16597//16597 16625//16625 -f 16625//16625 16597//16597 16588//16588 -f 16625//16625 16588//16588 16553//16553 -f 16553//16553 16588//16588 16578//16578 -f 16553//16553 16578//16578 16551//16551 -f 16551//16551 16578//16578 16576//16576 -f 16551//16551 16576//16576 16564//16564 -f 16564//16564 16576//16576 16617//16617 -f 16564//16564 16617//16617 16612//16612 -f 16680//16680 16554//16554 16681//16681 -f 16681//16681 16554//16554 16556//16556 -f 16681//16681 16556//16556 16570//16570 -f 16570//16570 16556//16556 16682//16682 -f 16570//16570 16682//16682 16568//16568 -f 16568//16568 16682//16682 16683//16683 -f 16568//16568 16683//16683 16552//16552 -f 16552//16552 16683//16683 16684//16684 -f 16552//16552 16684//16684 16550//16550 -f 16685//16685 16686//16686 16680//16680 -f 16687//16687 16685//16685 16436//16436 -f 16436//16436 16685//16685 16680//16680 -f 16436//16436 16680//16680 16434//16434 -f 16434//16434 16680//16680 16442//16442 -f 16434//16434 16442//16442 16688//16688 -f 16688//16688 16442//16442 16443//16443 -f 16689//16689 16554//16554 16690//16690 -f 16690//16690 16554//16554 16680//16680 -f 16690//16690 16680//16680 16691//16691 -f 16691//16691 16680//16680 16686//16686 -f 16689//16689 16692//16692 16554//16554 -f 16554//16554 16692//16692 16693//16693 -f 16554//16554 16693//16693 16560//16560 -f 16560//16560 16693//16693 16694//16694 -f 16694//16694 16695//16695 16560//16560 -f 16560//16560 16695//16695 16696//16696 -f 16560//16560 16696//16696 16436//16436 -f 16436//16436 16696//16696 16697//16697 -f 16436//16436 16697//16697 16687//16687 -f 16698//16698 16457//16457 16699//16699 -f 16699//16699 16457//16457 16700//16700 -f 16699//16699 16700//16700 16701//16701 -f 16701//16701 16700//16700 16702//16702 -f 16703//16703 16428//16428 16704//16704 -f 16704//16704 16428//16428 16457//16457 -f 16704//16704 16457//16457 16705//16705 -f 16705//16705 16457//16457 16698//16698 -f 16425//16425 16706//16706 16707//16707 -f 16703//16703 16708//16708 16428//16428 -f 16428//16428 16708//16708 16709//16709 -f 16428//16428 16709//16709 16425//16425 -f 16425//16425 16709//16709 16710//16710 -f 16425//16425 16710//16710 16706//16706 -f 16503//16503 16711//16711 16501//16501 -f 16501//16501 16711//16711 16496//16496 -f 16501//16501 16496//16496 16508//16508 -f 16508//16508 16496//16496 16493//16493 -f 16508//16508 16493//16493 16391//16391 -f 16391//16391 16493//16493 16627//16627 -f 16391//16391 16627//16627 16386//16386 -f 16386//16386 16627//16627 16629//16629 -f 16386//16386 16629//16629 16384//16384 -f 16435//16435 16429//16429 16436//16436 -f 16436//16436 16429//16429 16406//16406 -f 16436//16436 16406//16406 16560//16560 -f 16560//16560 16406//16406 16422//16422 -f 16560//16560 16422//16422 16557//16557 -f 16557//16557 16422//16422 16450//16450 -f 16557//16557 16450//16450 16562//16562 -f 16453//16453 16454//16454 16451//16451 -f 16451//16451 16454//16454 16425//16425 -f 16451//16451 16425//16425 16700//16700 -f 16700//16700 16425//16425 16707//16707 -f 16700//16700 16707//16707 16702//16702 -f 16712//16712 16713//16713 16384//16384 -f 16293//16293 16292//16292 16450//16450 -f 16450//16450 16292//16292 16714//16714 -f 16450//16450 16714//16714 16715//16715 -f 16632//16632 16563//16563 16629//16629 -f 16629//16629 16563//16563 16562//16562 -f 16629//16629 16562//16562 16384//16384 -f 16384//16384 16562//16562 16450//16450 -f 16384//16384 16450//16450 16712//16712 -f 16712//16712 16450//16450 16715//16715 -f 16713//16713 16716//16716 16384//16384 -f 16384//16384 16716//16716 16717//16717 -f 16384//16384 16717//16717 16382//16382 -f 16382//16382 16717//16717 16718//16718 -f 16718//16718 16719//16719 16382//16382 -f 16382//16382 16719//16719 16720//16720 -f 16382//16382 16720//16720 16293//16293 -f 16293//16293 16720//16720 16721//16721 -f 16293//16293 16721//16721 16291//16291 -f 16722//16722 16723//16723 16724//16724 -f 16724//16724 16723//16723 16405//16405 -f 16724//16724 16405//16405 16725//16725 -f 16725//16725 16405//16405 16404//16404 -f 16725//16725 16404//16404 16726//16726 -f 16722//16722 16727//16727 16723//16723 -f 16723//16723 16727//16727 16728//16728 -f 16723//16723 16728//16728 16729//16729 -f 16729//16729 16728//16728 16730//16730 -f 16729//16729 16730//16730 16731//16731 -f 16732//16732 16733//16733 16734//16734 -f 16734//16734 16733//16733 16735//16735 -f 16734//16734 16735//16735 16736//16736 -f 16426//16426 16425//16425 16737//16737 -f 16737//16737 16425//16425 16454//16454 -f 16737//16737 16454//16454 16433//16433 -f 16433//16433 16454//16454 16734//16734 -f 16433//16433 16734//16734 16404//16404 -f 16404//16404 16734//16734 16736//16736 -f 16404//16404 16736//16736 16726//16726 -f 16455//16455 16303//16303 16454//16454 -f 16454//16454 16303//16303 16305//16305 -f 16454//16454 16305//16305 16734//16734 -f 16734//16734 16305//16305 16729//16729 -f 16734//16734 16729//16729 16732//16732 -f 16732//16732 16729//16729 16731//16731 -f 16738//16738 16739//16739 16740//16740 -f 16741//16741 16742//16742 16743//16743 -f 16738//16738 16740//16740 16744//16744 -f 16740//16740 16745//16745 16744//16744 -f 16744//16744 16745//16745 16746//16746 -f 16744//16744 16746//16746 16747//16747 -f 16741//16741 16743//16743 16748//16748 -f 16743//16743 16749//16749 16748//16748 -f 16748//16748 16749//16749 16750//16750 -f 16748//16748 16750//16750 16738//16738 -f 16738//16738 16750//16750 16751//16751 -f 16738//16738 16751//16751 16739//16739 -f 16746//16746 16752//16752 16747//16747 -f 16747//16747 16752//16752 16753//16753 -f 16747//16747 16753//16753 16741//16741 -f 16741//16741 16753//16753 16754//16754 -f 16741//16741 16754//16754 16742//16742 -f 16755//16755 16756//16756 16757//16757 -f 16757//16757 16756//16756 16758//16758 -f 16759//16759 16760//16760 16761//16761 -f 16761//16761 16760//16760 16762//16762 -f 16762//16762 16763//16763 16761//16761 -f 16761//16761 16763//16763 16764//16764 -f 16761//16761 16764//16764 16765//16765 -f 16764//16764 16766//16766 16765//16765 -f 16765//16765 16766//16766 16767//16767 -f 16765//16765 16767//16767 16755//16755 -f 16755//16755 16767//16767 16768//16768 -f 16755//16755 16768//16768 16756//16756 -f 16758//16758 16769//16769 16757//16757 -f 16757//16757 16769//16769 16770//16770 -f 16757//16757 16770//16770 16759//16759 -f 16759//16759 16770//16770 16771//16771 -f 16759//16759 16771//16771 16760//16760 -f 16772//16772 16773//16773 16774//16774 -f 16774//16774 16773//16773 16775//16775 -f 16776//16776 16777//16777 16772//16772 -f 16772//16772 16777//16777 16778//16778 -f 16772//16772 16778//16778 16773//16773 -f 16775//16775 16779//16779 16774//16774 -f 16774//16774 16779//16779 16780//16780 -f 16774//16774 16780//16780 16781//16781 -f 16782//16782 16783//16783 16784//16784 -f 16784//16784 16783//16783 16781//16781 -f 16784//16784 16781//16781 16785//16785 -f 16785//16785 16781//16781 16780//16780 -f 16782//16782 16786//16786 16783//16783 -f 16783//16783 16786//16786 16787//16787 -f 16783//16783 16787//16787 16776//16776 -f 16776//16776 16787//16787 16788//16788 -f 16776//16776 16788//16788 16777//16777 -f 15180//15180 15179//15179 16789//16789 -f 16790//16790 16791//16791 16792//16792 -f 16793//16793 16794//16794 16795//16795 -f 16796//16796 16797//16797 16798//16798 -f 16798//16798 16797//16797 16799//16799 -f 16799//16799 16800//16800 16798//16798 -f 16798//16798 16800//16800 16801//16801 -f 16798//16798 16801//16801 16802//16802 -f 16802//16802 16801//16801 16803//16803 -f 16802//16802 16803//16803 16804//16804 -f 16805//16805 16806//16806 16807//16807 -f 16808//16808 16809//16809 16810//16810 -f 16811//16811 16812//16812 16803//16803 -f 16803//16803 16812//16812 16808//16808 -f 16810//16810 16813//16813 16808//16808 -f 16808//16808 16813//16813 16805//16805 -f 16808//16808 16805//16805 16803//16803 -f 16803//16803 16805//16805 16807//16807 -f 16803//16803 16807//16807 16804//16804 -f 16814//16814 16815//16815 16816//16816 -f 16817//16817 16818//16818 16819//16819 -f 16820//16820 16814//16814 16811//16811 -f 16795//16795 16812//16812 16793//16793 -f 16793//16793 16812//16812 16811//16811 -f 16793//16793 16811//16811 16821//16821 -f 16821//16821 16811//16811 16814//16814 -f 16821//16821 16814//16814 16822//16822 -f 16822//16822 16814//16814 16816//16816 -f 16818//16818 16817//16817 16823//16823 -f 16824//16824 16825//16825 16826//16826 -f 16827//16827 16828//16828 16829//16829 -f 16826//16826 16830//16830 16824//16824 -f 16824//16824 16830//16830 16829//16829 -f 16824//16824 16829//16829 16831//16831 -f 16831//16831 16829//16829 16832//16832 -f 16833//16833 16827//16827 16834//16834 -f 16834//16834 16827//16827 16829//16829 -f 16834//16834 16829//16829 16835//16835 -f 16835//16835 16829//16829 16830//16830 -f 16836//16836 16837//16837 16838//16838 -f 16838//16838 16837//16837 16839//16839 -f 16838//16838 16839//16839 16840//16840 -f 16840//16840 16839//16839 16841//16841 -f 16842//16842 16843//16843 16844//16844 -f 16844//16844 16843//16843 16845//16845 -f 16846//16846 16847//16847 16848//16848 -f 16848//16848 16847//16847 16849//16849 -f 16848//16848 16849//16849 16850//16850 -f 16850//16850 16849//16849 16851//16851 -f 16850//16850 16851//16851 16852//16852 -f 16852//16852 16851//16851 16853//16853 -f 16852//16852 16853//16853 16854//16854 -f 16854//16854 16853//16853 16855//16855 -f 16856//16856 16857//16857 16858//16858 -f 16858//16858 16857//16857 16859//16859 -f 16858//16858 16859//16859 16860//16860 -f 16792//16792 16861//16861 16790//16790 -f 16790//16790 16861//16861 16862//16862 -f 16790//16790 16862//16862 16863//16863 -f 16864//16864 16865//16865 16866//16866 -f 16866//16866 16865//16865 16867//16867 -f 16866//16866 16867//16867 16868//16868 -f 16869//16869 16870//16870 16862//16862 -f 16862//16862 16870//16870 16871//16871 -f 16871//16871 16872//16872 16857//16857 -f 16857//16857 16872//16872 16873//16873 -f 16874//16874 16866//16866 16875//16875 -f 16875//16875 16866//16866 16868//16868 -f 16875//16875 16868//16868 16876//16876 -f 16876//16876 16868//16868 16877//16877 -f 16876//16876 16877//16877 16861//16861 -f 16861//16861 16877//16877 16878//16878 -f 16861//16861 16878//16878 16862//16862 -f 16862//16862 16878//16878 16879//16879 -f 16862//16862 16879//16879 16869//16869 -f 16866//16866 16880//16880 16864//16864 -f 16864//16864 16880//16880 16881//16881 -f 16864//16864 16881//16881 16873//16873 -f 16873//16873 16881//16881 16882//16882 -f 16873//16873 16882//16882 16857//16857 -f 16857//16857 16882//16882 16883//16883 -f 16857//16857 16883//16883 16859//16859 -f 16884//16884 16885//16885 16862//16862 -f 16886//16886 16887//16887 16888//16888 -f 16888//16888 16887//16887 16889//16889 -f 16889//16889 16863//16863 16888//16888 -f 16888//16888 16863//16863 16862//16862 -f 16888//16888 16862//16862 16890//16890 -f 16890//16890 16862//16862 16885//16885 -f 16890//16890 16885//16885 16891//16891 -f 16891//16891 16885//16885 16892//16892 -f 16893//16893 16894//16894 16895//16895 -f 16895//16895 16894//16894 16896//16896 -f 16897//16897 16898//16898 16896//16896 -f 16899//16899 16900//16900 16897//16897 -f 16897//16897 16900//16900 16901//16901 -f 16902//16902 16903//16903 16904//16904 -f 16904//16904 16903//16903 16905//16905 -f 16904//16904 16905//16905 16884//16884 -f 16906//16906 16907//16907 16898//16898 -f 16898//16898 16907//16907 16908//16908 -f 16898//16898 16908//16908 16896//16896 -f 16909//16909 16910//16910 16899//16899 -f 16911//16911 16900//16900 16912//16912 -f 16912//16912 16900//16900 16899//16899 -f 16912//16912 16899//16899 16913//16913 -f 16913//16913 16899//16899 16910//16910 -f 16913//16913 16910//16910 16914//16914 -f 16914//16914 16910//16910 16915//16915 -f 16916//16916 16917//16917 16918//16918 -f 15205//15205 16919//16919 15204//15204 -f 15204//15204 16919//16919 16920//16920 -f 15204//15204 16920//16920 15190//15190 -f 16920//16920 16921//16921 15190//15190 -f 15190//15190 16921//16921 16922//16922 -f 15190//15190 16922//16922 15188//15188 -f 15188//15188 16922//16922 16923//16923 -f 15188//15188 16923//16923 15186//15186 -f 15186//15186 16923//16923 16924//16924 -f 15186//15186 16924//16924 16925//16925 -f 16925//16925 16924//16924 16926//16926 -f 16927//16927 16928//16928 16929//16929 -f 16929//16929 16928//16928 16930//16930 -f 16929//16929 16930//16930 16931//16931 -f 16931//16931 16930//16930 16932//16932 -f 16931//16931 16932//16932 15205//15205 -f 15205//15205 16932//16932 16933//16933 -f 15205//15205 16933//16933 16919//16919 -f 16934//16934 16935//16935 16936//16936 -f 16936//16936 16935//16935 16937//16937 -f 16936//16936 16937//16937 16938//16938 -f 16939//16939 16940//16940 16941//16941 -f 16941//16941 16940//16940 16942//16942 -f 16941//16941 16942//16942 15184//15184 -f 15184//15184 16942//16942 16943//16943 -f 16944//16944 15179//15179 16943//16943 -f 16943//16943 15179//15179 15208//15208 -f 16943//16943 15208//15208 15184//15184 -f 16944//16944 16945//16945 15179//15179 -f 15179//15179 16945//16945 16946//16946 -f 15179//15179 16946//16946 16789//16789 -f 16789//16789 16946//16946 16947//16947 -f 16789//16789 16947//16947 16948//16948 -f 16949//16949 15156//15156 16789//16789 -f 16789//16789 15156//15156 15182//15182 -f 16789//16789 15182//15182 15180//15180 -f 16800//16800 16950//16950 16801//16801 -f 16801//16801 16950//16950 16951//16951 -f 16801//16801 16951//16951 16949//16949 -f 16949//16949 16951//16951 16952//16952 -f 16949//16949 16952//16952 15156//15156 -f 16953//16953 16954//16954 16955//16955 -f 16955//16955 16954//16954 16956//16956 -f 16955//16955 16956//16956 16957//16957 -f 16957//16957 16956//16956 16958//16958 -f 16957//16957 16958//16958 16959//16959 -f 16959//16959 16958//16958 16960//16960 -f 16959//16959 16960//16960 16961//16961 -f 16962//16962 16963//16963 16964//16964 -f 16964//16964 16963//16963 16965//16965 -f 16964//16964 16965//16965 16966//16966 -f 16966//16966 16965//16965 16967//16967 -f 16966//16966 16967//16967 16968//16968 -f 16969//16969 16970//16970 16971//16971 -f 16971//16971 16970//16970 16811//16811 -f 16971//16971 16811//16811 16972//16972 -f 16972//16972 16811//16811 16803//16803 -f 16972//16972 16803//16803 16973//16973 -f 16974//16974 16975//16975 16962//16962 -f 16962//16962 16975//16975 16976//16976 -f 16962//16962 16976//16976 16977//16977 -f 16978//16978 16979//16979 16980//16980 -f 16980//16980 16979//16979 16981//16981 -f 16980//16980 16981//16981 16982//16982 -f 16982//16982 16981//16981 16983//16983 -f 16982//16982 16983//16983 16977//16977 -f 16977//16977 16983//16983 16954//16954 -f 16977//16977 16954//16954 16962//16962 -f 16962//16962 16954//16954 16953//16953 -f 16962//16962 16953//16953 16963//16963 -f 16984//16984 16985//16985 16986//16986 -f 16986//16986 16985//16985 16987//16987 -f 16986//16986 16987//16987 16969//16969 -f 16988//16988 16989//16989 16990//16990 -f 16990//16990 16989//16989 16839//16839 -f 16990//16990 16839//16839 16833//16833 -f 16833//16833 16839//16839 16837//16837 -f 16833//16833 16837//16837 16827//16827 -f 16817//16817 16991//16991 16992//16992 -f 16993//16993 16994//16994 16825//16825 -f 16825//16825 16994//16994 16823//16823 -f 16825//16825 16823//16823 16826//16826 -f 16826//16826 16823//16823 16817//16817 -f 16826//16826 16817//16817 16995//16995 -f 16995//16995 16817//16817 16992//16992 -f 16988//16988 16996//16996 16989//16989 -f 16989//16989 16996//16996 16997//16997 -f 16989//16989 16997//16997 16991//16991 -f 16991//16991 16997//16997 16998//16998 -f 16991//16991 16998//16998 16992//16992 -f 16999//16999 17000//17000 17001//17001 -f 17001//17001 17000//17000 17002//17002 -f 17001//17001 17002//17002 17003//17003 -f 17003//17003 17002//17002 17004//17004 -f 17003//17003 17004//17004 17005//17005 -f 17005//17005 17004//17004 17006//17006 -f 17005//17005 17006//17006 17007//17007 -f 17008//17008 17009//17009 17010//17010 -f 17010//17010 17009//17009 17011//17011 -f 17010//17010 17011//17011 17012//17012 -f 17012//17012 17011//17011 17013//17013 -f 17012//17012 17013//17013 17014//17014 -f 17014//17014 17013//17013 17015//17015 -f 17014//17014 17015//17015 17016//17016 -f 17017//17017 17018//17018 17019//17019 -f 17018//17018 17020//17020 17019//17019 -f 17019//17019 17020//17020 17021//17021 -f 17019//17019 17021//17021 17014//17014 -f 17014//17014 17021//17021 17022//17022 -f 17023//17023 17024//17024 17025//17025 -f 17025//17025 17024//17024 17026//17026 -f 17025//17025 17026//17026 17027//17027 -f 17027//17027 17026//17026 17028//17028 -f 17027//17027 17028//17028 17029//17029 -f 17030//17030 17031//17031 17032//17032 -f 17032//17032 17031//17031 17033//17033 -f 17032//17032 17033//17033 17034//17034 -f 17035//17035 16979//16979 17036//17036 -f 17036//17036 16979//16979 16978//16978 -f 17036//17036 16978//16978 16973//16973 -f 17030//17030 17037//17037 17031//17031 -f 17031//17031 17037//17037 17038//17038 -f 17031//17031 17038//17038 17036//17036 -f 17036//17036 17038//17038 17039//17039 -f 17036//17036 17039//17039 17035//17035 -f 17035//17035 17040//17040 16979//16979 -f 16979//16979 17040//17040 17041//17041 -f 16979//16979 17041//17041 16981//16981 -f 16981//16981 17041//17041 17042//17042 -f 17034//17034 17033//17033 17043//17043 -f 17043//17043 17033//17033 17044//17044 -f 17043//17043 17044//17044 17045//17045 -f 17046//17046 17047//17047 16970//16970 -f 17048//17048 17049//17049 16991//16991 -f 16991//16991 17049//17049 17050//17050 -f 16991//16991 17050//17050 17051//17051 -f 16969//16969 16987//16987 16970//16970 -f 16970//16970 16987//16987 17052//17052 -f 16970//16970 17052//17052 17046//17046 -f 17050//17050 17053//17053 17051//17051 -f 17051//17051 17053//17053 17054//17054 -f 17051//17051 17054//17054 17055//17055 -f 17054//17054 17056//17056 17055//17055 -f 17055//17055 17056//17056 17057//17057 -f 17055//17055 17057//17057 16985//16985 -f 16985//16985 17057//17057 17058//17058 -f 16985//16985 17058//17058 16987//16987 -f 16987//16987 17058//17058 17059//17059 -f 16987//16987 17059//17059 17052//17052 -f 17060//17060 17061//17061 17010//17010 -f 17010//17010 17061//17061 17062//17062 -f 17010//17010 17062//17062 17063//17063 -f 17063//17063 17062//17062 17064//17064 -f 17063//17063 17064//17064 17065//17065 -f 17066//17066 17067//17067 17068//17068 -f 17067//17067 17069//17069 17068//17068 -f 17068//17068 17069//17069 17070//17070 -f 17068//17068 17070//17070 17071//17071 -f 17071//17071 17070//17070 17072//17072 -f 17073//17073 17074//17074 16862//16862 -f 17075//17075 17076//17076 16895//16895 -f 17076//17076 17077//17077 16895//16895 -f 16895//16895 17077//17077 16968//16968 -f 16895//16895 16968//16968 16893//16893 -f 16893//16893 16968//16968 16967//16967 -f 17073//17073 16862//16862 17078//17078 -f 17078//17078 16862//16862 17079//17079 -f 17078//17078 17079//17079 17080//17080 -f 16908//16908 16904//16904 16896//16896 -f 16896//16896 16904//16904 16884//16884 -f 16896//16896 16884//16884 16895//16895 -f 16895//16895 16884//16884 16862//16862 -f 16895//16895 16862//16862 17075//17075 -f 17075//17075 16862//16862 17074//17074 -f 17077//17077 17081//17081 16968//16968 -f 16968//16968 17081//17081 17082//17082 -f 16968//16968 17082//17082 16966//16966 -f 16966//16966 17082//17082 17083//17083 -f 17080//17080 17079//17079 17084//17084 -f 17084//17084 17079//17079 17085//17085 -f 17084//17084 17085//17085 17086//17086 -f 17087//17087 17088//17088 16899//16899 -f 16899//16899 17088//17088 17089//17089 -f 17090//17090 17087//17087 16960//16960 -f 16960//16960 17087//17087 16899//16899 -f 16960//16960 16899//16899 16961//16961 -f 16961//16961 16899//16899 16897//16897 -f 16961//16961 16897//16897 17091//17091 -f 17091//17091 16897//16897 16896//16896 -f 17092//17092 17093//17093 16918//16918 -f 16918//16918 17093//17093 17094//17094 -f 16918//16918 17094//17094 17095//17095 -f 17089//17089 17092//17092 16899//16899 -f 16899//16899 17092//17092 16918//16918 -f 16899//16899 16918//16918 16909//16909 -f 16909//16909 16918//16918 16917//16917 -f 16909//16909 16917//16917 17096//17096 -f 17090//17090 16960//16960 17097//17097 -f 17097//17097 16960//16960 16958//16958 -f 17097//17097 16958//16958 17098//17098 -f 17094//17094 17099//17099 17095//17095 -f 17095//17095 17099//17099 17100//17100 -f 17095//17095 17100//17100 17101//17101 -f 17101//17101 17100//17100 17102//17102 -f 16926//16926 16927//16927 16925//16925 -f 16925//16925 16927//16927 16929//16929 -f 16925//16925 16929//16929 17068//17068 -f 17068//17068 16929//16929 17103//17103 -f 17068//17068 17103//17103 17066//17066 -f 17066//17066 17103//17103 17104//17104 -f 15205//15205 15198//15198 16931//16931 -f 16931//16931 15198//15198 17105//17105 -f 16931//16931 17105//17105 16929//16929 -f 16929//16929 17105//17105 17106//17106 -f 16929//16929 17106//17106 17103//17103 -f 17103//17103 17106//17106 17063//17063 -f 17103//17103 17063//17063 17104//17104 -f 17104//17104 17063//17063 17065//17065 -f 15198//15198 16916//16916 17105//17105 -f 17105//17105 16916//16916 16918//16918 -f 17105//17105 16918//16918 17106//17106 -f 17106//17106 16918//16918 17095//17095 -f 17106//17106 17095//17095 17063//17063 -f 17063//17063 17095//17095 17101//17101 -f 17063//17063 17101//17101 17010//17010 -f 17010//17010 17101//17101 17005//17005 -f 17010//17010 17005//17005 17008//17008 -f 17008//17008 17005//17005 17007//17007 -f 17072//17072 17107//17107 17071//17071 -f 17071//17071 17107//17107 17108//17108 -f 17071//17071 17108//17108 17109//17109 -f 17109//17109 17108//17108 17110//17110 -f 17109//17109 17110//17110 17025//17025 -f 17025//17025 17110//17110 17111//17111 -f 17025//17025 17111//17111 17023//17023 -f 17023//17023 17111//17111 17112//17112 -f 17107//17107 17060//17060 17108//17108 -f 17108//17108 17060//17060 17010//17010 -f 17108//17108 17010//17010 17110//17110 -f 17110//17110 17010//17010 17012//17012 -f 17110//17110 17012//17012 17111//17111 -f 17111//17111 17012//17012 17014//17014 -f 17111//17111 17014//17014 17112//17112 -f 17112//17112 17014//17014 17022//17022 -f 17083//17083 17086//17086 16966//16966 -f 16966//16966 17086//17086 17085//17085 -f 16966//16966 17085//17085 16964//16964 -f 16964//16964 17085//17085 17113//17113 -f 16964//16964 17113//17113 16962//16962 -f 16962//16962 17113//17113 17114//17114 -f 16962//16962 17114//17114 16974//16974 -f 16974//16974 17114//17114 17115//17115 -f 16871//16871 16857//16857 16862//16862 -f 16862//16862 16857//16857 16856//16856 -f 16862//16862 16856//16856 17079//17079 -f 17079//17079 16856//16856 17116//17116 -f 17079//17079 17116//17116 17085//17085 -f 17085//17085 17116//17116 16853//16853 -f 17085//17085 16853//16853 17113//17113 -f 17113//17113 16853//16853 16851//16851 -f 17113//17113 16851//16851 17114//17114 -f 17114//17114 16851//16851 16849//16849 -f 17114//17114 16849//16849 17115//17115 -f 17115//17115 16849//16849 16847//16847 -f 17115//17115 16847//16847 16845//16845 -f 16845//16845 16847//16847 16846//16846 -f 16845//16845 16846//16846 16844//16844 -f 17102//17102 17098//17098 17101//17101 -f 17101//17101 17098//17098 16958//16958 -f 17101//17101 16958//16958 17005//17005 -f 17005//17005 16958//16958 16956//16956 -f 17005//17005 16956//16956 17003//17003 -f 17003//17003 16956//16956 16954//16954 -f 17003//17003 16954//16954 17001//17001 -f 17001//17001 16954//16954 16983//16983 -f 17001//17001 16983//16983 17044//17044 -f 17044//17044 16983//16983 16981//16981 -f 17044//17044 16981//16981 17045//17045 -f 17045//17045 16981//16981 17042//17042 -f 16841//16841 16839//16839 17117//17117 -f 17117//17117 16839//16839 16989//16989 -f 17117//17117 16989//16989 17118//17118 -f 17118//17118 16989//16989 16991//16991 -f 17118//17118 16991//16991 17119//17119 -f 17119//17119 16991//16991 17051//17051 -f 17119//17119 17051//17051 16845//16845 -f 16845//16845 17051//17051 17055//17055 -f 16845//16845 17055//17055 17115//17115 -f 17115//17115 17055//17055 16985//16985 -f 17115//17115 16985//16985 16974//16974 -f 16974//16974 16985//16985 16984//16984 -f 16974//16974 16984//16984 16975//16975 -f 17029//17029 17120//17120 17027//17027 -f 17027//17027 17120//17120 17121//17121 -f 17027//17027 17121//17121 16941//16941 -f 16941//16941 17121//17121 16936//16936 -f 16941//16941 16936//16936 16939//16939 -f 16939//16939 16936//16936 16938//16938 -f 17120//17120 17017//17017 17121//17121 -f 17121//17121 17017//17017 17019//17019 -f 17121//17121 17019//17019 16936//16936 -f 16936//16936 17019//17019 17122//17122 -f 16936//16936 17122//17122 16934//16934 -f 16934//16934 17122//17122 17123//17123 -f 17016//17016 16999//16999 17014//17014 -f 17014//17014 16999//16999 17001//17001 -f 17014//17014 17001//17001 17019//17019 -f 17019//17019 17001//17001 17044//17044 -f 17019//17019 17044//17044 17122//17122 -f 17122//17122 17044//17044 17033//17033 -f 17122//17122 17033//17033 17123//17123 -f 17123//17123 17033//17033 17031//17031 -f 16973//16973 16803//16803 17036//17036 -f 17036//17036 16803//16803 16801//16801 -f 17036//17036 16801//16801 17031//17031 -f 17031//17031 16801//16801 16949//16949 -f 17031//17031 16949//16949 17123//17123 -f 17123//17123 16949//16949 16789//16789 -f 17123//17123 16789//16789 16934//16934 -f 16934//16934 16789//16789 16948//16948 -f 16934//16934 16948//16948 16935//16935 -f 17047//17047 17048//17048 16970//16970 -f 16970//16970 17048//17048 16991//16991 -f 16970//16970 16991//16991 16811//16811 -f 16811//16811 16991//16991 16817//16817 -f 16811//16811 16817//16817 16820//16820 -f 16820//16820 16817//16817 16819//16819 -f 16820//16820 16819//16819 17124//17124 -f 17124//17124 16819//16819 17125//17125 -f 17126//17126 17127//17127 17128//17128 -f 17128//17128 17127//17127 17129//17129 -f 17128//17128 17129//17129 17130//17130 -f 17130//17130 17129//17129 17131//17131 -f 17130//17130 17131//17131 17132//17132 -f 17133//17133 17134//17134 17135//17135 -f 17135//17135 17134//17134 17136//17136 -f 17135//17135 17136//17136 17137//17137 -f 17137//17137 17136//17136 17138//17138 -f 17137//17137 17138//17138 17139//17139 -f 17140//17140 17141//17141 17142//17142 -f 17142//17142 17141//17141 17143//17143 -f 17142//17142 17143//17143 17144//17144 -f 17144//17144 17143//17143 17145//17145 -f 17144//17144 17145//17145 17146//17146 -f 17147//17147 17148//17148 16744//16744 -f 16744//16744 17148//17148 17149//17149 -f 16744//16744 17149//17149 16738//16738 -f 16738//16738 17149//17149 17150//17150 -f 16738//16738 17150//17150 17151//17151 -f 17151//17151 17150//17150 17152//17152 -f 17153//17153 17154//17154 16765//16765 -f 16765//16765 17154//17154 17155//17155 -f 16765//16765 17155//17155 16761//16761 -f 16761//16761 17155//17155 17156//17156 -f 16761//16761 17156//17156 17157//17157 -f 17157//17157 17156//17156 17158//17158 -f 17159//17159 17160//17160 16781//16781 -f 16781//16781 17160//17160 17161//17161 -f 16781//16781 17161//17161 16774//16774 -f 16774//16774 17161//17161 17162//17162 -f 16774//16774 17162//17162 17163//17163 -f 17163//17163 17162//17162 17164//17164 -f 17165//17165 17166//17166 17167//17167 -f 17167//17167 17166//17166 17168//17168 -f 17169//17169 17170//17170 17171//17171 -f 17172//17172 17173//17173 17174//17174 -f 17174//17174 17173//17173 17169//17169 -f 17174//17174 17169//17169 17175//17175 -f 17175//17175 17169//17169 17171//17171 -f 17172//17172 17176//17176 17173//17173 -f 17173//17173 17176//17176 17177//17177 -f 17173//17173 17177//17177 17165//17165 -f 17165//17165 17177//17177 17178//17178 -f 17165//17165 17178//17178 17166//17166 -f 17168//17168 17179//17179 17167//17167 -f 17167//17167 17179//17179 17180//17180 -f 17167//17167 17180//17180 17170//17170 -f 17170//17170 17180//17180 17181//17181 -f 17170//17170 17181//17181 17171//17171 -f 17182//17182 17183//17183 17184//17184 -f 17184//17184 17183//17183 17185//17185 -f 17186//17186 17187//17187 17188//17188 -f 17188//17188 17187//17187 17189//17189 -f 17188//17188 17189//17189 17190//17190 -f 17190//17190 17189//17189 17191//17191 -f 17190//17190 17191//17191 17192//17192 -f 17184//17184 17193//17193 17182//17182 -f 17182//17182 17193//17193 17194//17194 -f 17182//17182 17194//17194 17191//17191 -f 17191//17191 17194//17194 17195//17195 -f 17191//17191 17195//17195 17192//17192 -f 17186//17186 17196//17196 17187//17187 -f 17187//17187 17196//17196 17197//17197 -f 17187//17187 17197//17197 17183//17183 -f 17183//17183 17197//17197 17198//17198 -f 17183//17183 17198//17198 17185//17185 -f 17199//17199 17200//17200 17201//17201 -f 17201//17201 17200//17200 17202//17202 -f 17201//17201 17202//17202 17203//17203 -f 17203//17203 17202//17202 17204//17204 -f 17203//17203 17204//17204 17205//17205 -f 17206//17206 17207//17207 17170//17170 -f 17170//17170 17207//17207 17208//17208 -f 17170//17170 17208//17208 17167//17167 -f 17167//17167 17208//17208 17209//17209 -f 17167//17167 17209//17209 17210//17210 -f 17210//17210 17209//17209 17211//17211 -f 17212//17212 17213//17213 17214//17214 -f 17215//17215 17216//17216 17217//17217 -f 17212//17212 17214//17214 17217//17217 -f 17217//17217 17214//17214 17218//17218 -f 17217//17217 17218//17218 17215//17215 -f 17219//17219 17220//17220 17182//17182 -f 17182//17182 17220//17220 17221//17221 -f 17182//17182 17221//17221 17183//17183 -f 17183//17183 17221//17221 17222//17222 -f 17183//17183 17222//17222 17223//17223 -f 17223//17223 17222//17222 17224//17224 -f 17225//17225 16917//16917 17226//17226 -f 17226//17226 16917//16917 16916//16916 -f 17226//17226 16916//16916 15198//15198 -f 15186//15186 16925//16925 17227//17227 -f 17227//17227 16925//16925 17068//17068 -f 17068//17068 17071//17071 17227//17227 -f 17227//17227 17071//17071 17109//17109 -f 17227//17227 17109//17109 17228//17228 -f 17228//17228 17109//17109 17025//17025 -f 17025//17025 17027//17027 17228//17228 -f 17228//17228 17027//17027 16941//16941 -f 17228//17228 16941//16941 15184//15184 -f 16951//16951 17229//17229 16952//16952 -f 16952//16952 17229//17229 17230//17230 -f 16952//16952 17230//17230 15156//15156 -f 16951//16951 16950//16950 17229//17229 -f 17229//17229 16950//16950 17231//17231 -f 17229//17229 17231//17231 17232//17232 -f 17232//17232 17231//17231 16482//16482 -f 17232//17232 16482//16482 17233//17233 -f 17233//17233 16482//16482 16298//16298 -f 16799//16799 17234//17234 16800//16800 -f 16800//16800 17234//17234 17231//17231 -f 16800//16800 17231//17231 16950//16950 -f 17150//17150 16643//16643 17234//17234 -f 17234//17234 16643//16643 16301//16301 -f 17234//17234 16301//16301 16300//16300 -f 16799//16799 16797//16797 17234//17234 -f 17234//17234 16797//16797 17152//17152 -f 17234//17234 17152//17152 17150//17150 -f 17235//17235 16328//16328 16330//16330 -f 16806//16806 16805//16805 17148//17148 -f 17148//17148 16805//16805 17235//17235 -f 17148//17148 17235//17235 17149//17149 -f 17149//17149 17235//17235 16330//16330 -f 17149//17149 16330//16330 16640//16640 -f 17235//17235 16805//16805 17236//17236 -f 17236//17236 16805//16805 16813//16813 -f 17156//17156 16481//16481 17236//17236 -f 17236//17236 16481//16481 16480//16480 -f 17236//17236 16480//16480 16478//16478 -f 16813//16813 16810//16810 17236//17236 -f 17236//17236 16810//16810 17158//17158 -f 17236//17236 17158//17158 17156//17156 -f 16794//16794 16793//16793 17237//17237 -f 17237//17237 16473//16473 16472//16472 -f 16794//16794 17237//17237 17154//17154 -f 17154//17154 17237//17237 17155//17155 -f 17155//17155 17237//17237 16472//16472 -f 17155//17155 16472//16472 16474//16474 -f 16822//16822 17238//17238 16821//16821 -f 16821//16821 17238//17238 17237//17237 -f 16821//16821 17237//17237 16793//16793 -f 17162//17162 16646//16646 17238//17238 -f 17238//17238 16646//16646 16354//16354 -f 17238//17238 16354//16354 16353//16353 -f 16822//16822 16816//16816 17238//17238 -f 17238//17238 16816//16816 17164//17164 -f 17238//17238 17164//17164 17162//17162 -f 17239//17239 16344//16344 16350//16350 -f 17125//17125 16819//16819 17160//17160 -f 17160//17160 16819//16819 17239//17239 -f 17160//17160 17239//17239 17161//17161 -f 17161//17161 17239//17239 16350//16350 -f 17161//17161 16350//16350 16644//16644 -f 16823//16823 17240//17240 16818//16818 -f 16818//16818 17240//17240 17239//17239 -f 16818//16818 17239//17239 16819//16819 -f 17209//17209 16650//16650 17240//17240 -f 17240//17240 16650//16650 16510//16510 -f 17240//17240 16510//16510 16509//16509 -f 16823//16823 16994//16994 17240//17240 -f 17240//17240 16994//16994 17211//17211 -f 17240//17240 17211//17211 17209//17209 -f 17241//17241 16467//16467 16466//16466 -f 16832//16832 16829//16829 17207//17207 -f 17207//17207 16829//16829 17241//17241 -f 17207//17207 17241//17241 17208//17208 -f 17208//17208 17241//17241 16466//16466 -f 17208//17208 16466//16466 16647//16647 -f 17241//17241 16829//16829 17242//17242 -f 17242//17242 16829//16829 16828//16828 -f 17242//17242 16828//16828 16470//16470 -f 16470//16470 16828//16828 16827//16827 -f 16836//16836 17243//17243 16837//16837 -f 16837//16837 17243//17243 16470//16470 -f 16837//16837 16470//16470 16827//16827 -f 17243//17243 16836//16836 17244//17244 -f 17244//17244 16836//16836 16838//16838 -f 17244//17244 16838//16838 16840//16840 -f 16468//16468 16469//16469 17222//17222 -f 17222//17222 16469//16469 17244//17244 -f 17222//17222 17244//17244 17224//17224 -f 17224//17224 17244//17244 16840//16840 -f 17245//17245 16463//16463 16462//16462 -f 16842//16842 16844//16844 17220//17220 -f 17220//17220 16844//16844 17245//17245 -f 17220//17220 17245//17245 17221//17221 -f 17221//17221 17245//17245 16462//16462 -f 16844//16844 16846//16846 17245//17245 -f 17245//17245 16846//16846 16848//16848 -f 17245//17245 16848//16848 17246//17246 -f 17246//17246 16848//16848 16850//16850 -f 17246//17246 16850//16850 16852//16852 -f 17246//17246 16852//16852 16854//16854 -f 16456//16456 16458//16458 17247//17247 -f 17247//17247 16458//16458 17246//17246 -f 17247//17247 17246//17246 17248//17248 -f 17248//17248 17246//17246 16854//16854 -f 17249//17249 17250//17250 17251//17251 -f 17251//17251 17250//17250 17252//17252 -f 17251//17251 17252//17252 17253//17253 -f 17253//17253 17252//17252 17247//17247 -f 17253//17253 17247//17247 17254//17254 -f 17254//17254 17247//17247 17248//17248 -f 17255//17255 16453//16453 16452//16452 -f 16860//16860 16859//16859 17250//17250 -f 17250//17250 16859//16859 17255//17255 -f 17250//17250 17255//17255 17252//17252 -f 17252//17252 17255//17255 16452//16452 -f 17255//17255 16859//16859 17256//17256 -f 17256//17256 16859//16859 16883//16883 -f 17256//17256 16883//16883 16455//16455 -f 16455//16455 16883//16883 16882//16882 -f 16455//16455 16882//16882 16881//16881 -f 16455//16455 16881//16881 17257//17257 -f 17257//17257 16881//16881 16880//16880 -f 17257//17257 16880//16880 17258//17258 -f 17258//17258 16880//16880 16866//16866 -f 17258//17258 16866//16866 16874//16874 -f 16304//16304 16303//16303 17259//17259 -f 17259//17259 16303//16303 17258//17258 -f 17259//17259 17258//17258 17260//17260 -f 17260//17260 17258//17258 16874//16874 -f 17261//17261 17262//17262 17263//17263 -f 17263//17263 17262//17262 17264//17264 -f 17263//17263 17264//17264 17265//17265 -f 17265//17265 17264//17264 17259//17259 -f 17265//17265 17259//17259 17266//17266 -f 17266//17266 17259//17259 17260//17260 -f 17267//17267 16405//16405 16723//16723 -f 16791//16791 16790//16790 17262//17262 -f 17262//17262 16790//16790 17267//17267 -f 17262//17262 17267//17267 17264//17264 -f 17264//17264 17267//17267 16723//16723 -f 16889//16889 17268//17268 16863//16863 -f 16863//16863 17268//17268 17267//17267 -f 16863//16863 17267//17267 16790//16790 -f 17268//17268 16889//16889 16887//16887 -f 16418//16418 16407//16407 17269//17269 -f 17269//17269 16407//16407 17268//17268 -f 17269//17269 17268//17268 17270//17270 -f 17270//17270 17268//17268 16887//16887 -f 17271//17271 17272//17272 17273//17273 -f 17273//17273 17272//17272 17274//17274 -f 17273//17273 17274//17274 17275//17275 -f 17275//17275 17274//17274 17269//17269 -f 17275//17275 17269//17269 17276//17276 -f 17276//17276 17269//17269 17270//17270 -f 17277//17277 16412//16412 16410//16410 -f 16892//16892 16885//16885 17272//17272 -f 17272//17272 16885//16885 17277//17277 -f 17272//17272 17277//17277 17274//17274 -f 17274//17274 17277//17277 16410//16410 -f 16905//16905 17278//17278 16884//16884 -f 16884//16884 17278//17278 17277//17277 -f 16884//16884 17277//17277 16885//16885 -f 17278//17278 16905//16905 16903//16903 -f 16448//16448 16449//16449 17279//17279 -f 17279//17279 16449//16449 17278//17278 -f 17279//17279 17278//17278 17280//17280 -f 17280//17280 17278//17278 16903//16903 -f 17281//17281 17282//17282 17283//17283 -f 17283//17283 17282//17282 17284//17284 -f 17283//17283 17284//17284 17285//17285 -f 17285//17285 17284//17284 17279//17279 -f 17285//17285 17279//17279 17286//17286 -f 17286//17286 17279//17279 17280//17280 -f 16385//16385 16383//16383 17287//17287 -f 17287//17287 16383//16383 17284//17284 -f 17284//17284 17282//17282 17287//17287 -f 17287//17287 17282//17282 16906//16906 -f 17287//17287 16906//16906 16898//16898 -f 17287//17287 16898//16898 17288//17288 -f 17288//17288 16898//16898 16897//16897 -f 17288//17288 16897//16897 16901//16901 -f 16401//16401 16387//16387 17289//17289 -f 17289//17289 16387//16387 17288//17288 -f 17289//17289 17288//17288 17290//17290 -f 17290//17290 17288//17288 16901//16901 -f 17291//17291 17292//17292 17293//17293 -f 17293//17293 17292//17292 17294//17294 -f 17293//17293 17294//17294 17295//17295 -f 17295//17295 17294//17294 17289//17289 -f 17295//17295 17289//17289 17296//17296 -f 17296//17296 17289//17289 17290//17290 -f 17297//17297 16505//16505 16504//16504 -f 16915//16915 16910//16910 17292//17292 -f 17292//17292 16910//16910 17297//17297 -f 17292//17292 17297//17297 17294//17294 -f 17294//17294 17297//17297 16504//16504 -f 17096//17096 17298//17298 16909//16909 -f 16909//16909 17298//17298 17297//17297 -f 16909//16909 17297//17297 16910//16910 -f 17299//17299 16507//16507 16506//16506 -f 17096//17096 16917//16917 17298//17298 -f 17298//17298 16917//16917 17225//17225 -f 17298//17298 17225//17225 16506//16506 -f 16506//16506 17225//17225 17300//17300 -f 16506//16506 17300//17300 17299//17299 -f 16427//16427 17301//17301 16444//16444 -f 16444//16444 17301//17301 17302//17302 -f 16444//16444 17302//17302 16445//16445 -f 16445//16445 17302//17302 16447//16447 -f 17303//17303 16433//16433 17304//17304 -f 17304//17304 16433//16433 16432//16432 -f 17304//17304 16432//16432 16431//16431 -f 17305//17305 17306//17306 16435//16435 -f 16435//16435 16434//16434 17305//17305 -f 17305//17305 16434//16434 16688//16688 -f 17305//17305 16688//16688 16443//16443 -f 16542//16542 17307//17307 16437//16437 -f 16437//16437 17307//17307 17308//17308 -f 16437//16437 17308//17308 16438//16438 -f 17309//17309 17310//17310 17311//17311 -f 17311//17311 17310//17310 17312//17312 -f 16517//16517 17313//17313 16513//16513 -f 16513//16513 17313//17313 17314//17314 -f 16513//16513 17314//17314 16514//16514 -f 17315//17315 16530//16530 16529//16529 -f 17315//17315 16529//16529 17316//17316 -f 17316//17316 16529//16529 16535//16535 -f 17316//17316 16535//16535 16534//16534 -f 17317//17317 16531//16531 17318//17318 -f 17318//17318 16531//16531 16537//16537 -f 17318//17318 16537//16537 16536//16536 -f 17319//17319 16548//16548 16546//16546 -f 17319//17319 16546//16546 17320//17320 -f 17320//17320 16546//16546 16544//16544 -f 17320//17320 16544//16544 16543//16543 -f 17321//17321 17322//17322 17323//17323 -f 17323//17323 17322//17322 17324//17324 -f 17325//17325 17326//17326 17327//17327 -f 17327//17327 17326//17326 17253//17253 -f 17327//17327 17253//17253 16855//16855 -f 16855//16855 17253//17253 17254//17254 -f 17251//17251 17253//17253 17328//17328 -f 17328//17328 17253//17253 17329//17329 -f 17330//17330 17331//17331 17332//17332 -f 17332//17332 17331//17331 17251//17251 -f 17332//17332 17251//17251 17333//17333 -f 17333//17333 17251//17251 17328//17328 -f 17330//17330 17334//17334 17331//17331 -f 17331//17331 17334//17334 17335//17335 -f 17331//17331 17335//17335 17336//17336 -f 17336//17336 17335//17335 17337//17337 -f 17336//17336 17337//17337 17326//17326 -f 17326//17326 17337//17337 17338//17338 -f 17338//17338 17339//17339 17326//17326 -f 17326//17326 17339//17339 17340//17340 -f 17326//17326 17340//17340 17253//17253 -f 17253//17253 17340//17340 17341//17341 -f 17253//17253 17341//17341 17329//17329 -f 16858//16858 17249//17249 17342//17342 -f 17342//17342 17249//17249 17251//17251 -f 17342//17342 17251//17251 17343//17343 -f 17343//17343 17251//17251 17331//17331 -f 17325//17325 17344//17344 17326//17326 -f 17326//17326 17344//17344 17336//17336 -f 17344//17344 17343//17343 17336//17336 -f 17336//17336 17343//17343 17331//17331 -f 17342//17342 17343//17343 17345//17345 -f 17345//17345 17343//17343 17344//17344 -f 17345//17345 17344//17344 17346//17346 -f 17346//17346 17344//17344 17325//17325 -f 17346//17346 17325//17325 17327//17327 -f 16855//16855 16853//16853 17327//17327 -f 17327//17327 16853//16853 17346//17346 -f 16856//16856 17345//17345 17116//17116 -f 17116//17116 17345//17345 17346//17346 -f 17116//17116 17346//17346 16853//16853 -f 16856//16856 16858//16858 17345//17345 -f 17345//17345 16858//16858 17342//17342 -f 17347//17347 17348//17348 17349//17349 -f 17349//17349 17348//17348 17265//17265 -f 17349//17349 17265//17265 16875//16875 -f 16875//16875 17265//17265 17266//17266 -f 17350//17350 17263//17263 17351//17351 -f 17351//17351 17352//17352 17350//17350 -f 17350//17350 17352//17352 17353//17353 -f 17350//17350 17353//17353 17354//17354 -f 17354//17354 17353//17353 17355//17355 -f 17348//17348 17356//17356 17265//17265 -f 17265//17265 17356//17356 17357//17357 -f 17357//17357 17358//17358 17265//17265 -f 17265//17265 17358//17358 17359//17359 -f 17265//17265 17359//17359 17263//17263 -f 17263//17263 17359//17359 17360//17360 -f 17263//17263 17360//17360 17351//17351 -f 17355//17355 17361//17361 17354//17354 -f 17354//17354 17361//17361 17362//17362 -f 17354//17354 17362//17362 17348//17348 -f 17348//17348 17362//17362 17363//17363 -f 17348//17348 17363//17363 17356//17356 -f 16792//16792 17261//17261 17364//17364 -f 17364//17364 17261//17261 17263//17263 -f 17364//17364 17263//17263 17365//17365 -f 17365//17365 17263//17263 17350//17350 -f 17347//17347 17366//17366 17348//17348 -f 17348//17348 17366//17366 17354//17354 -f 17366//17366 17365//17365 17354//17354 -f 17354//17354 17365//17365 17350//17350 -f 17367//17367 17364//17364 17365//17365 -f 17347//17347 17349//17349 17368//17368 -f 17367//17367 17365//17365 17368//17368 -f 17368//17368 17365//17365 17366//17366 -f 17368//17368 17366//17366 17347//17347 -f 16876//16876 17368//17368 16875//16875 -f 16875//16875 17368//17368 17349//17349 -f 16861//16861 17367//17367 16876//16876 -f 16876//16876 17367//17367 17368//17368 -f 16792//16792 17364//17364 16861//16861 -f 16861//16861 17364//17364 17367//17367 -f 17328//17328 16699//16699 17333//17333 -f 17333//17333 16699//16699 16701//16701 -f 17333//17333 16701//16701 17332//17332 -f 17332//17332 16701//16701 16702//16702 -f 17332//17332 16702//16702 17330//17330 -f 17330//17330 16702//16702 16707//16707 -f 17330//17330 16707//16707 17334//17334 -f 17334//17334 16707//16707 16706//16706 -f 17334//17334 16706//16706 17335//17335 -f 17335//17335 16706//16706 16710//16710 -f 17335//17335 16710//16710 17337//17337 -f 17337//17337 16710//16710 16709//16709 -f 17337//17337 16709//16709 17338//17338 -f 17338//17338 16709//16709 16708//16708 -f 17338//17338 16708//16708 17339//17339 -f 17339//17339 16708//16708 16703//16703 -f 17339//17339 16703//16703 17340//17340 -f 17340//17340 16703//16703 16704//16704 -f 17340//17340 16704//16704 17341//17341 -f 17341//17341 16704//16704 16705//16705 -f 17341//17341 16705//16705 17329//17329 -f 17329//17329 16705//16705 16698//16698 -f 17329//17329 16698//16698 17328//17328 -f 17328//17328 16698//16698 16699//16699 -f 17356//17356 16732//16732 17357//17357 -f 17357//17357 16732//16732 16731//16731 -f 17357//17357 16731//16731 17358//17358 -f 17358//17358 16731//16731 16730//16730 -f 17358//17358 16730//16730 17359//17359 -f 17359//17359 16730//16730 16728//16728 -f 17359//17359 16728//16728 17360//17360 -f 17360//17360 16728//16728 16727//16727 -f 17360//17360 16727//16727 17351//17351 -f 17351//17351 16727//16727 16722//16722 -f 17351//17351 16722//16722 17352//17352 -f 17352//17352 16722//16722 16724//16724 -f 17352//17352 16724//16724 17353//17353 -f 17353//17353 16724//16724 16725//16725 -f 17353//17353 16725//16725 17355//17355 -f 17355//17355 16725//16725 16726//16726 -f 17355//17355 16726//16726 17361//17361 -f 17361//17361 16726//16726 16736//16736 -f 17361//17361 16736//16736 17362//17362 -f 17362//17362 16736//16736 16735//16735 -f 17362//17362 16735//16735 17363//17363 -f 17363//17363 16735//16735 16733//16733 -f 17363//17363 16733//16733 17356//17356 -f 17356//17356 16733//16733 16732//16732 -f 17369//17369 17370//17370 17371//17371 -f 17371//17371 17370//17370 17275//17275 -f 17371//17371 17275//17275 16886//16886 -f 16886//16886 17275//17275 17276//17276 -f 17372//17372 17273//17273 17373//17373 -f 17373//17373 17374//17374 17372//17372 -f 17372//17372 17374//17374 17375//17375 -f 17372//17372 17375//17375 17376//17376 -f 17376//17376 17375//17375 17377//17377 -f 17378//17378 17275//17275 17379//17379 -f 17379//17379 17275//17275 17370//17370 -f 17377//17377 17380//17380 17376//17376 -f 17376//17376 17380//17380 17381//17381 -f 17376//17376 17381//17381 17370//17370 -f 17370//17370 17381//17381 17382//17382 -f 17370//17370 17382//17382 17379//17379 -f 17378//17378 17383//17383 17275//17275 -f 17275//17275 17383//17383 17384//17384 -f 17275//17275 17384//17384 17273//17273 -f 17273//17273 17384//17384 17385//17385 -f 17273//17273 17385//17385 17373//17373 -f 16891//16891 17271//17271 17386//17386 -f 17386//17386 17271//17271 17273//17273 -f 17386//17386 17273//17273 17387//17387 -f 17387//17387 17273//17273 17372//17372 -f 17388//17388 17389//17389 17390//17390 -f 17390//17390 17389//17389 17285//17285 -f 17390//17390 17285//17285 16902//16902 -f 16902//16902 17285//17285 17286//17286 -f 17391//17391 17285//17285 17392//17392 -f 17392//17392 17285//17285 17389//17389 -f 17391//17391 17393//17393 17285//17285 -f 17285//17285 17393//17393 17394//17394 -f 17285//17285 17394//17394 17283//17283 -f 17395//17395 17396//17396 17397//17397 -f 17397//17397 17396//17396 17398//17398 -f 17395//17395 17399//17399 17396//17396 -f 17396//17396 17399//17399 17400//17400 -f 17396//17396 17400//17400 17389//17389 -f 17389//17389 17400//17400 17401//17401 -f 17389//17389 17401//17401 17392//17392 -f 17394//17394 17402//17402 17283//17283 -f 17283//17283 17402//17402 17403//17403 -f 17283//17283 17403//17403 17398//17398 -f 17398//17398 17403//17403 17404//17404 -f 17398//17398 17404//17404 17397//17397 -f 16907//16907 17281//17281 17405//17405 -f 17405//17405 17281//17281 17283//17283 -f 17405//17405 17283//17283 17406//17406 -f 17406//17406 17283//17283 17398//17398 -f 17407//17407 17408//17408 17409//17409 -f 17409//17409 17408//17408 17295//17295 -f 17409//17409 17295//17295 16911//16911 -f 16911//16911 17295//17295 17296//17296 -f 17410//17410 17411//17411 17412//17412 -f 17412//17412 17411//17411 17408//17408 -f 17413//17413 17293//17293 17414//17414 -f 17414//17414 17415//17415 17413//17413 -f 17413//17413 17415//17415 17416//17416 -f 17413//17413 17416//17416 17412//17412 -f 17412//17412 17416//17416 17417//17417 -f 17412//17412 17417//17417 17410//17410 -f 17411//17411 17418//17418 17408//17408 -f 17408//17408 17418//17418 17419//17419 -f 17408//17408 17419//17419 17295//17295 -f 17295//17295 17419//17419 17420//17420 -f 17420//17420 17421//17421 17295//17295 -f 17295//17295 17421//17421 17422//17422 -f 17295//17295 17422//17422 17293//17293 -f 17293//17293 17422//17422 17423//17423 -f 17293//17293 17423//17423 17414//17414 -f 16914//16914 17291//17291 17424//17424 -f 17424//17424 17291//17291 17293//17293 -f 17424//17424 17293//17293 17425//17425 -f 17425//17425 17293//17293 17413//17413 -f 17369//17369 17426//17426 17370//17370 -f 17370//17370 17426//17426 17376//17376 -f 17426//17426 17387//17387 17376//17376 -f 17376//17376 17387//17387 17372//17372 -f 17427//17427 17386//17386 17387//17387 -f 17369//17369 17371//17371 17428//17428 -f 17427//17427 17387//17387 17428//17428 -f 17428//17428 17387//17387 17426//17426 -f 17428//17428 17426//17426 17369//17369 -f 17388//17388 17429//17429 17389//17389 -f 17389//17389 17429//17429 17396//17396 -f 17429//17429 17406//17406 17396//17396 -f 17396//17396 17406//17406 17398//17398 -f 17430//17430 17405//17405 17406//17406 -f 17388//17388 17390//17390 17431//17431 -f 17430//17430 17406//17406 17431//17431 -f 17431//17431 17406//17406 17429//17429 -f 17431//17431 17429//17429 17388//17388 -f 17407//17407 17432//17432 17408//17408 -f 17408//17408 17432//17432 17412//17412 -f 17432//17432 17425//17425 17412//17412 -f 17412//17412 17425//17425 17413//17413 -f 17433//17433 17424//17424 17425//17425 -f 17407//17407 17409//17409 17434//17434 -f 17433//17433 17425//17425 17434//17434 -f 17434//17434 17425//17425 17432//17432 -f 17434//17434 17432//17432 17407//17407 -f 16888//16888 17428//17428 16886//16886 -f 16886//16886 17428//17428 17371//17371 -f 16890//16890 17427//17427 16888//16888 -f 16888//16888 17427//17427 17428//17428 -f 16891//16891 17386//17386 16890//16890 -f 16890//16890 17386//17386 17427//17427 -f 16904//16904 17431//17431 16902//16902 -f 16902//16902 17431//17431 17390//17390 -f 16908//16908 17430//17430 16904//16904 -f 16904//16904 17430//17430 17431//17431 -f 16907//16907 17405//17405 16908//16908 -f 16908//16908 17405//17405 17430//17430 -f 16912//16912 17434//17434 16911//16911 -f 16911//16911 17434//17434 17409//17409 -f 16913//16913 17433//17433 16912//16912 -f 16912//16912 17433//17433 17434//17434 -f 16914//16914 17424//17424 16913//16913 -f 16913//16913 17424//17424 17433//17433 -f 17379//17379 16420//16420 17378//17378 -f 17378//17378 16420//16420 16419//16419 -f 17378//17378 16419//16419 17383//17383 -f 17383//17383 16419//16419 16417//16417 -f 17383//17383 16417//16417 17384//17384 -f 17384//17384 16417//16417 16415//16415 -f 17384//17384 16415//16415 17385//17385 -f 17385//17385 16415//16415 16414//16414 -f 17385//17385 16414//16414 17373//17373 -f 17373//17373 16414//16414 16409//16409 -f 17373//17373 16409//16409 17374//17374 -f 17374//17374 16409//16409 16411//16411 -f 17374//17374 16411//16411 17375//17375 -f 17375//17375 16411//16411 16413//16413 -f 17375//17375 16413//16413 17377//17377 -f 17377//17377 16413//16413 16421//16421 -f 17377//17377 16421//16421 17380//17380 -f 17380//17380 16421//16421 16423//16423 -f 17380//17380 16423//16423 17381//17381 -f 17381//17381 16423//16423 16424//16424 -f 17381//17381 16424//16424 17382//17382 -f 17382//17382 16424//16424 16408//16408 -f 17382//17382 16408//16408 17379//17379 -f 17379//17379 16408//16408 16420//16420 -f 17392//17392 16292//16292 17391//17391 -f 17391//17391 16292//16292 16291//16291 -f 17391//17391 16291//16291 17393//17393 -f 17393//17393 16291//16291 16721//16721 -f 17393//17393 16721//16721 17394//17394 -f 17394//17394 16721//16721 16720//16720 -f 17394//17394 16720//16720 17402//17402 -f 17402//17402 16720//16720 16719//16719 -f 17402//17402 16719//16719 17403//17403 -f 17403//17403 16719//16719 16718//16718 -f 17403//17403 16718//16718 17404//17404 -f 17404//17404 16718//16718 16717//16717 -f 17404//17404 16717//16717 17397//17397 -f 17397//17397 16717//16717 16716//16716 -f 17397//17397 16716//16716 17395//17395 -f 17395//17395 16716//16716 16713//16713 -f 17395//17395 16713//16713 17399//17399 -f 17399//17399 16713//16713 16712//16712 -f 17399//17399 16712//16712 17400//17400 -f 17400//17400 16712//16712 16715//16715 -f 17400//17400 16715//16715 17401//17401 -f 17401//17401 16715//16715 16714//16714 -f 17401//17401 16714//16714 17392//17392 -f 17392//17392 16714//16714 16292//16292 -f 17419//17419 16403//16403 17420//17420 -f 17420//17420 16403//16403 16402//16402 -f 17420//17420 16402//16402 17421//17421 -f 17421//17421 16402//16402 16400//16400 -f 17421//17421 16400//16400 17422//17422 -f 17422//17422 16400//16400 16398//16398 -f 17422//17422 16398//16398 17423//17423 -f 17423//17423 16398//16398 16397//16397 -f 17423//17423 16397//16397 17414//17414 -f 17414//17414 16397//16397 16394//16394 -f 17414//17414 16394//16394 17415//17415 -f 17415//17415 16394//16394 16393//16393 -f 17415//17415 16393//16393 17416//17416 -f 17416//17416 16393//16393 16396//16396 -f 17416//17416 16396//16396 17417//17417 -f 17417//17417 16396//16396 16395//16395 -f 17417//17417 16395//16395 17410//17410 -f 17410//17410 16395//16395 16390//16390 -f 17410//17410 16390//16390 17411//17411 -f 17411//17411 16390//16390 16389//16389 -f 17411//17411 16389//16389 17418//17418 -f 17418//17418 16389//16389 16388//16388 -f 17418//17418 16388//16388 17419//17419 -f 17419//17419 16388//16388 16403//16403 -f 17215//17215 17187//17187 17216//17216 -f 17216//17216 17187//17187 17183//17183 -f 17216//17216 17183//17183 17117//17117 -f 17117//17117 17183//17183 17223//17223 -f 16843//16843 17219//17219 17213//17213 -f 17213//17213 17219//17219 17182//17182 -f 17213//17213 17182//17182 17214//17214 -f 17214//17214 17182//17182 17191//17191 -f 17215//17215 17218//17218 17187//17187 -f 17187//17187 17218//17218 17189//17189 -f 17218//17218 17214//17214 17189//17189 -f 17189//17189 17214//17214 17191//17191 -f 17118//17118 17217//17217 17117//17117 -f 17117//17117 17217//17217 17216//17216 -f 16845//16845 17212//17212 17119//17119 -f 17119//17119 17212//17212 17217//17217 -f 17119//17119 17217//17217 17118//17118 -f 16843//16843 17213//17213 16845//16845 -f 16845//16845 17213//17213 17212//17212 -f 17204//17204 17165//17165 17205//17205 -f 17205//17205 17165//17165 17167//17167 -f 17205//17205 17167//17167 16993//16993 -f 16993//16993 17167//17167 17210//17210 -f 16831//16831 17206//17206 17199//17199 -f 17199//17199 17206//17206 17170//17170 -f 17199//17199 17170//17170 17200//17200 -f 17200//17200 17170//17170 17169//17169 -f 17204//17204 17202//17202 17165//17165 -f 17165//17165 17202//17202 17173//17173 -f 17202//17202 17200//17200 17173//17173 -f 17173//17173 17200//17200 17169//17169 -f 16993//16993 16825//16825 17205//17205 -f 17205//17205 16825//16825 17203//17203 -f 16825//16825 16824//16824 17203//17203 -f 17203//17203 16824//16824 17201//17201 -f 16824//16824 16831//16831 17201//17201 -f 17201//17201 16831//16831 17199//17199 -f 17184//17184 16372//16372 17193//17193 -f 17193//17193 16372//16372 16371//16371 -f 17193//17193 16371//16371 17194//17194 -f 17194//17194 16371//16371 16370//16370 -f 17194//17194 16370//16370 17195//17195 -f 17195//17195 16370//16370 16368//16368 -f 17195//17195 16368//16368 17192//17192 -f 17192//17192 16368//16368 16367//16367 -f 17192//17192 16367//16367 17190//17190 -f 17190//17190 16367//16367 16365//16365 -f 17190//17190 16365//16365 17188//17188 -f 17188//17188 16365//16365 16364//16364 -f 17188//17188 16364//16364 17186//17186 -f 17186//17186 16364//16364 16381//16381 -f 17186//17186 16381//16381 17196//17196 -f 17196//17196 16381//16381 16379//16379 -f 17196//17196 16379//16379 17197//17197 -f 17197//17197 16379//16379 16377//16377 -f 17197//17197 16377//16377 17198//17198 -f 17198//17198 16377//16377 16375//16375 -f 17198//17198 16375//16375 17185//17185 -f 17185//17185 16375//16375 16374//16374 -f 17185//17185 16374//16374 17184//17184 -f 17184//17184 16374//16374 16372//16372 -f 17175//17175 16522//16522 17174//17174 -f 17174//17174 16522//16522 16521//16521 -f 17174//17174 16521//16521 17172//17172 -f 17172//17172 16521//16521 16520//16520 -f 17172//17172 16520//16520 17176//17176 -f 17176//17176 16520//16520 16518//16518 -f 17176//17176 16518//16518 17177//17177 -f 17177//17177 16518//16518 16516//16516 -f 17177//17177 16516//16516 17178//17178 -f 17178//17178 16516//16516 16515//16515 -f 17178//17178 16515//16515 17166//17166 -f 17166//17166 16515//16515 16512//16512 -f 17166//17166 16512//16512 17168//17168 -f 17168//17168 16512//16512 16511//16511 -f 17168//17168 16511//16511 17179//17179 -f 17179//17179 16511//16511 16527//16527 -f 17179//17179 16527//16527 17180//17180 -f 17180//17180 16527//16527 16526//16526 -f 17180//17180 16526//16526 17181//17181 -f 17181//17181 16526//16526 16524//16524 -f 17181//17181 16524//16524 17171//17171 -f 17171//17171 16524//16524 16523//16523 -f 17171//17171 16523//16523 17175//17175 -f 17175//17175 16523//16523 16522//16522 -f 17145//17145 16772//16772 17146//17146 -f 17146//17146 16772//16772 16774//16774 -f 17146//17146 16774//16774 16815//16815 -f 16815//16815 16774//16774 17163//17163 -f 17124//17124 17159//17159 17140//17140 -f 17140//17140 17159//17159 16781//16781 -f 17140//17140 16781//16781 17141//17141 -f 17141//17141 16781//16781 16783//16783 -f 17138//17138 16759//16759 17139//17139 -f 17139//17139 16759//16759 16761//16761 -f 17139//17139 16761//16761 16809//16809 -f 16809//16809 16761//16761 17157//17157 -f 16795//16795 17153//17153 17133//17133 -f 17133//17133 17153//17153 16765//16765 -f 17133//17133 16765//16765 17134//17134 -f 17134//17134 16765//16765 16755//16755 -f 17131//17131 16748//16748 17132//17132 -f 17132//17132 16748//16748 16738//16738 -f 17132//17132 16738//16738 16796//16796 -f 16796//16796 16738//16738 17151//17151 -f 16804//16804 17147//17147 17126//17126 -f 17126//17126 17147//17147 16744//16744 -f 17126//17126 16744//16744 17127//17127 -f 17127//17127 16744//16744 16747//16747 -f 17145//17145 17143//17143 16772//16772 -f 16772//16772 17143//17143 16776//16776 -f 17143//17143 17141//17141 16776//16776 -f 16776//16776 17141//17141 16783//16783 -f 17138//17138 17136//17136 16759//16759 -f 16759//16759 17136//17136 16757//16757 -f 17136//17136 17134//17134 16757//16757 -f 16757//16757 17134//17134 16755//16755 -f 17131//17131 17129//17129 16748//16748 -f 16748//16748 17129//17129 16741//16741 -f 17129//17129 17127//17127 16741//16741 -f 16741//16741 17127//17127 16747//16747 -f 16815//16815 16814//16814 17146//17146 -f 17146//17146 16814//16814 17144//17144 -f 16814//16814 16820//16820 17144//17144 -f 17144//17144 16820//16820 17142//17142 -f 16820//16820 17124//17124 17142//17142 -f 17142//17142 17124//17124 17140//17140 -f 16809//16809 16808//16808 17139//17139 -f 17139//17139 16808//16808 17137//17137 -f 16808//16808 16812//16812 17137//17137 -f 17137//17137 16812//16812 17135//17135 -f 16812//16812 16795//16795 17135//17135 -f 17135//17135 16795//16795 17133//17133 -f 16796//16796 16798//16798 17132//17132 -f 17132//17132 16798//16798 17130//17130 -f 16798//16798 16802//16802 17130//17130 -f 17130//17130 16802//16802 17128//17128 -f 16802//16802 16804//16804 17128//17128 -f 17128//17128 16804//16804 17126//17126 -f 16782//16782 16349//16349 16786//16786 -f 16786//16786 16349//16349 16348//16348 -f 16786//16786 16348//16348 16787//16787 -f 16787//16787 16348//16348 16343//16343 -f 16787//16787 16343//16343 16788//16788 -f 16788//16788 16343//16343 16360//16360 -f 16788//16788 16360//16360 16777//16777 -f 16777//16777 16360//16360 16359//16359 -f 16777//16777 16359//16359 16778//16778 -f 16778//16778 16359//16359 16357//16357 -f 16778//16778 16357//16357 16773//16773 -f 16773//16773 16357//16357 16356//16356 -f 16773//16773 16356//16356 16775//16775 -f 16775//16775 16356//16356 16355//16355 -f 16775//16775 16355//16355 16779//16779 -f 16779//16779 16355//16355 16363//16363 -f 16779//16779 16363//16363 16780//16780 -f 16780//16780 16363//16363 16362//16362 -f 16780//16780 16362//16362 16785//16785 -f 16785//16785 16362//16362 16361//16361 -f 16785//16785 16361//16361 16784//16784 -f 16784//16784 16361//16361 16351//16351 -f 16784//16784 16351//16351 16782//16782 -f 16782//16782 16351//16351 16349//16349 -f 16768//16768 16653//16653 16756//16756 -f 16756//16756 16653//16653 16652//16652 -f 16756//16756 16652//16652 16758//16758 -f 16758//16758 16652//16652 16663//16663 -f 16758//16758 16663//16663 16769//16769 -f 16769//16769 16663//16663 16662//16662 -f 16769//16769 16662//16662 16770//16770 -f 16770//16770 16662//16662 16661//16661 -f 16770//16770 16661//16661 16771//16771 -f 16771//16771 16661//16661 16658//16658 -f 16771//16771 16658//16658 16760//16760 -f 16760//16760 16658//16658 16659//16659 -f 16760//16760 16659//16659 16762//16762 -f 16762//16762 16659//16659 16660//16660 -f 16762//16762 16660//16660 16763//16763 -f 16763//16763 16660//16660 16657//16657 -f 16763//16763 16657//16657 16764//16764 -f 16764//16764 16657//16657 16656//16656 -f 16764//16764 16656//16656 16766//16766 -f 16766//16766 16656//16656 16655//16655 -f 16766//16766 16655//16655 16767//16767 -f 16767//16767 16655//16655 16654//16654 -f 16767//16767 16654//16654 16768//16768 -f 16768//16768 16654//16654 16653//16653 -f 16752//16752 16329//16329 16753//16753 -f 16753//16753 16329//16329 16327//16327 -f 16753//16753 16327//16327 16754//16754 -f 16754//16754 16327//16327 16326//16326 -f 16754//16754 16326//16326 16742//16742 -f 16742//16742 16326//16326 16337//16337 -f 16742//16742 16337//16337 16743//16743 -f 16743//16743 16337//16337 16339//16339 -f 16743//16743 16339//16339 16749//16749 -f 16749//16749 16339//16339 16341//16341 -f 16749//16749 16341//16341 16750//16750 -f 16750//16750 16341//16341 16342//16342 -f 16750//16750 16342//16342 16751//16751 -f 16751//16751 16342//16342 16336//16336 -f 16751//16751 16336//16336 16739//16739 -f 16739//16739 16336//16336 16335//16335 -f 16739//16739 16335//16335 16740//16740 -f 16740//16740 16335//16335 16334//16334 -f 16740//16740 16334//16334 16745//16745 -f 16745//16745 16334//16334 16333//16333 -f 16745//16745 16333//16333 16746//16746 -f 16746//16746 16333//16333 16331//16331 -f 16746//16746 16331//16331 16752//16752 -f 16752//16752 16331//16331 16329//16329 -f 17228//17228 15184//15184 17435//17435 -f 17435//17435 15184//15184 15208//15208 -f 17435//17435 15208//15208 17436//17436 -f 17436//17436 15208//15208 17437//17437 -f 17437//17437 15208//15208 15179//15179 -f 17437//17437 15179//15179 17438//17438 -f 17438//17438 15179//15179 17439//17439 -f 17439//17439 15179//15179 15180//15180 -f 17439//17439 15180//15180 17440//17440 -f 17440//17440 15180//15180 17441//17441 -f 17441//17441 15180//15180 15182//15182 -f 17441//17441 15182//15182 17442//17442 -f 17442//17442 15182//15182 17443//17443 -f 17443//17443 15182//15182 15156//15156 -f 17443//17443 15156//15156 17230//17230 -f 17226//17226 15198//15198 17444//17444 -f 17444//17444 15198//15198 15205//15205 -f 17444//17444 15205//15205 17445//17445 -f 17445//17445 15205//15205 17446//17446 -f 17446//17446 15205//15205 15204//15204 -f 17446//17446 15204//15204 17447//17447 -f 17447//17447 15204//15204 17448//17448 -f 17448//17448 15204//15204 15190//15190 -f 17448//17448 15190//15190 17449//17449 -f 17449//17449 15190//15190 17450//17450 -f 17450//17450 15190//15190 15188//15188 -f 17450//17450 15188//15188 17451//17451 -f 17451//17451 15188//15188 17452//17452 -f 17452//17452 15188//15188 15186//15186 -f 17452//17452 15186//15186 17227//17227 -f 17453//17453 16896//16896 16894//16894 -f 16894//16894 16893//16893 17453//17453 -f 17453//17453 16893//16893 16967//16967 -f 17453//17453 16967//16967 17454//17454 -f 17454//17454 16967//16967 16965//16965 -f 17454//17454 16965//16965 16963//16963 -f 16682//16682 17454//17454 16683//16683 -f 16683//16683 17454//17454 16684//16684 -f 16963//16963 16953//16953 17454//17454 -f 17454//17454 16953//16953 17455//17455 -f 17454//17454 17455//17455 16684//16684 -f 16684//16684 17455//17455 16550//16550 -f 16957//16957 17456//17456 16955//16955 -f 16955//16955 17456//17456 17455//17455 -f 16955//16955 17455//17455 16953//16953 -f 16957//16957 16959//16959 17456//17456 -f 17456//17456 16959//16959 16961//16961 -f 17456//17456 16961//16961 17091//17091 -f 17457//17457 17458//17458 17456//17456 -f 17091//17091 16896//16896 17456//17456 -f 17456//17456 16896//16896 17453//17453 -f 17456//17456 17453//17453 17457//17457 -f 17459//17459 17460//17460 17461//17461 -f 16971//16971 16972//16972 17461//17461 -f 17461//17461 16972//16972 17462//17462 -f 17461//17461 17462//17462 17459//17459 -f 17462//17462 16972//16972 16973//16973 -f 16973//16973 16978//16978 17462//17462 -f 17462//17462 16978//16978 16980//16980 -f 17462//17462 16980//16980 17463//17463 -f 17463//17463 16980//16980 16982//16982 -f 17463//17463 16982//16982 16977//16977 -f 16566//16566 17463//17463 16567//16567 -f 16567//16567 17463//17463 16569//16569 -f 16977//16977 16976//16976 17463//17463 -f 17463//17463 16976//16976 17464//17464 -f 17463//17463 17464//17464 16569//16569 -f 16569//16569 17464//17464 16571//16571 -f 16984//16984 17461//17461 16975//16975 -f 16975//16975 17461//17461 17464//17464 -f 16975//16975 17464//17464 16976//16976 -f 16984//16984 16986//16986 17461//17461 -f 17461//17461 16986//16986 16969//16969 -f 17461//17461 16969//16969 16971//16971 -f 17465//17465 16309//16309 16307//16307 -f 16585//16585 17466//17466 16307//16307 -f 16307//16307 17466//17466 17467//17467 -f 16307//16307 17467//17467 17465//17465 -f 16584//16584 17468//17468 16585//16585 -f 16585//16585 17468//17468 17469//17469 -f 16585//16585 17469//17469 17466//17466 -f 16582//16582 17470//17470 16584//16584 -f 16584//16584 17470//17470 17471//17471 -f 16584//16584 17471//17471 17468//17468 -f 16581//16581 17472//17472 16582//16582 -f 16582//16582 17472//17472 17473//17473 -f 16582//16582 17473//17473 17470//17470 -f 16580//16580 17474//17474 16581//16581 -f 16581//16581 17474//17474 17475//17475 -f 16581//16581 17475//17475 17472//17472 -f 16579//16579 17476//17476 16580//16580 -f 16580//16580 17476//17476 17477//17477 -f 16580//16580 17477//17477 17474//17474 -f 16575//16575 17478//17478 16579//16579 -f 16579//16579 17478//17478 17479//17479 -f 16579//16579 17479//17479 17476//17476 -f 16577//16577 17480//17480 16575//16575 -f 16575//16575 17480//17480 17481//17481 -f 16575//16575 17481//17481 17478//17478 -f 16590//16590 17482//17482 16577//16577 -f 16577//16577 17482//17482 17483//17483 -f 16577//16577 17483//17483 17480//17480 -f 16589//16589 17484//17484 16590//16590 -f 16590//16590 17484//17484 17485//17485 -f 16590//16590 17485//17485 17482//17482 -f 16587//16587 17486//17486 16589//16589 -f 16589//16589 17486//17486 17487//17487 -f 16589//16589 17487//17487 17484//17484 -f 16586//16586 17488//17488 16587//16587 -f 16587//16587 17488//17488 17489//17489 -f 16587//16587 17489//17489 17486//17486 -f 16596//16596 17490//17490 16586//16586 -f 16586//16586 17490//17490 17491//17491 -f 16586//16586 17491//17491 17488//17488 -f 16598//16598 17492//17492 16596//16596 -f 16596//16596 17492//17492 17493//17493 -f 16596//16596 17493//17493 17490//17490 -f 16599//16599 17494//17494 16598//16598 -f 16598//16598 17494//17494 17495//17495 -f 16598//16598 17495//17495 17492//17492 -f 16593//16593 17496//17496 16599//16599 -f 16599//16599 17496//17496 17497//17497 -f 16599//16599 17497//17497 17494//17494 -f 16595//16595 17498//17498 16593//16593 -f 16593//16593 17498//17498 17499//17499 -f 16593//16593 17499//17499 17496//17496 -f 16609//16609 17500//17500 16595//16595 -f 16595//16595 17500//17500 17501//17501 -f 16595//16595 17501//17501 17498//17498 -f 17465//17465 17502//17502 16309//16309 -f 16309//16309 17502//17502 17503//17503 -f 16309//16309 17503//17503 16609//16609 -f 16609//16609 17503//17503 17504//17504 -f 16609//16609 17504//17504 17500//17500 -f 17505//17505 17506//17506 17507//17507 -f 17507//17507 17506//17506 17508//17508 -f 17509//17509 17510//17510 17511//17511 -f 17511//17511 17510//17510 17512//17512 -f 17513//17513 17514//17514 17515//17515 -f 17516//17516 17517//17517 17514//17514 -f 17514//17514 17517//17517 17518//17518 -f 17514//17514 17518//17518 17515//17515 -f 17519//17519 17520//17520 17521//17521 -f 17521//17521 17520//17520 17522//17522 -f 17521//17521 17522//17522 17523//17523 -f 17524//17524 17525//17525 17526//17526 -f 17526//17526 17525//17525 17527//17527 -f 17510//17510 17528//17528 17512//17512 -f 17512//17512 17528//17528 17529//17529 -f 17512//17512 17529//17529 17530//17530 -f 17506//17506 17531//17531 17508//17508 -f 17508//17508 17531//17531 17532//17532 -f 17508//17508 17532//17532 17533//17533 -f 17534//17534 17535//17535 17507//17507 -f 17507//17507 17535//17535 17536//17536 -f 17507//17507 17536//17536 17505//17505 -f 17537//17537 17538//17538 17539//17539 -f 17539//17539 17538//17538 17540//17540 -f 17519//17519 17541//17541 17520//17520 -f 17520//17520 17541//17541 17542//17542 -f 17520//17520 17542//17542 17516//17516 -f 17516//17516 17542//17542 17543//17543 -f 17516//17516 17543//17543 17517//17517 -f 17523//17523 17522//17522 17544//17544 -f 17544//17544 17522//17522 17545//17545 -f 17544//17544 17545//17545 17546//17546 -f 17525//17525 17547//17547 17527//17527 -f 17527//17527 17547//17547 17548//17548 -f 17527//17527 17548//17548 17545//17545 -f 17545//17545 17548//17548 17549//17549 -f 17545//17545 17549//17549 17546//17546 -f 17529//17529 17550//17550 17530//17530 -f 17530//17530 17550//17550 17551//17551 -f 17530//17530 17551//17551 17526//17526 -f 17526//17526 17551//17551 17552//17552 -f 17526//17526 17552//17552 17524//17524 -f 17532//17532 17553//17553 17533//17533 -f 17533//17533 17553//17553 17554//17554 -f 17533//17533 17554//17554 17511//17511 -f 17511//17511 17554//17554 17555//17555 -f 17511//17511 17555//17555 17509//17509 -f 17538//17538 17556//17556 17540//17540 -f 17540//17540 17556//17556 17557//17557 -f 17540//17540 17557//17557 17534//17534 -f 17534//17534 17557//17557 17558//17558 -f 17534//17534 17558//17558 17535//17535 -f 17515//17515 17559//17559 17513//17513 -f 17513//17513 17559//17559 17560//17560 -f 17513//17513 17560//17560 17539//17539 -f 17539//17539 17560//17560 17561//17561 -f 17539//17539 17561//17561 17537//17537 -f 17562//17562 17508//17508 17563//17563 -f 17563//17563 17508//17508 17533//17533 -f 17563//17563 17533//17533 17564//17564 -f 17564//17564 17533//17533 17511//17511 -f 17564//17564 17511//17511 17565//17565 -f 17565//17565 17511//17511 17512//17512 -f 17565//17565 17512//17512 17566//17566 -f 17566//17566 17512//17512 17530//17530 -f 17566//17566 17530//17530 17567//17567 -f 17567//17567 17530//17530 17526//17526 -f 17567//17567 17526//17526 17568//17568 -f 17568//17568 17526//17526 17527//17527 -f 17568//17568 17527//17527 17569//17569 -f 17569//17569 17527//17527 17545//17545 -f 17569//17569 17545//17545 17570//17570 -f 17570//17570 17545//17545 17522//17522 -f 17570//17570 17522//17522 17571//17571 -f 17571//17571 17522//17522 17520//17520 -f 17571//17571 17520//17520 17572//17572 -f 17572//17572 17520//17520 17516//17516 -f 17572//17572 17516//17516 17573//17573 -f 17573//17573 17516//17516 17514//17514 -f 17573//17573 17514//17514 17574//17574 -f 17574//17574 17514//17514 17513//17513 -f 17574//17574 17513//17513 17575//17575 -f 17575//17575 17513//17513 17539//17539 -f 17575//17575 17539//17539 17576//17576 -f 17576//17576 17539//17539 17540//17540 -f 17576//17576 17540//17540 17577//17577 -f 17577//17577 17540//17540 17534//17534 -f 17577//17577 17534//17534 17578//17578 -f 17578//17578 17534//17534 17507//17507 -f 17578//17578 17507//17507 17562//17562 -f 17562//17562 17507//17507 17508//17508 -f 17579//17579 17577//17577 17580//17580 -f 17580//17580 17577//17577 17578//17578 -f 17580//17580 17578//17578 17581//17581 -f 17581//17581 17578//17578 17562//17562 -f 17581//17581 17562//17562 17582//17582 -f 17583//17583 17574//17574 17584//17584 -f 17584//17584 17574//17574 17575//17575 -f 17584//17584 17575//17575 17579//17579 -f 17579//17579 17575//17575 17576//17576 -f 17579//17579 17576//17576 17577//17577 -f 17585//17585 17570//17570 17586//17586 -f 17586//17586 17570//17570 17571//17571 -f 17586//17586 17571//17571 17587//17587 -f 17587//17587 17571//17571 17572//17572 -f 17587//17587 17572//17572 17583//17583 -f 17583//17583 17572//17572 17573//17573 -f 17583//17583 17573//17573 17574//17574 -f 17588//17588 17567//17567 17589//17589 -f 17589//17589 17567//17567 17568//17568 -f 17589//17589 17568//17568 17585//17585 -f 17585//17585 17568//17568 17569//17569 -f 17585//17585 17569//17569 17570//17570 -f 17562//17562 17563//17563 17582//17582 -f 17582//17582 17563//17563 17564//17564 -f 17582//17582 17564//17564 17590//17590 -f 17590//17590 17564//17564 17565//17565 -f 17590//17590 17565//17565 17588//17588 -f 17588//17588 17565//17565 17566//17566 -f 17588//17588 17566//17566 17567//17567 -f 17591//17591 17592//17592 17593//17593 -f 17594//17594 17592//17592 17591//17591 -f 17591//17591 17595//17595 17596//17596 -f 17597//17597 17595//17595 17591//17591 -f 17593//17593 17597//17597 17591//17591 -f 17591//17591 17598//17598 17599//17599 -f 17600//17600 17598//17598 17591//17591 -f 17596//17596 17600//17600 17591//17591 -f 17591//17591 17601//17601 17602//17602 -f 17603//17603 17601//17601 17591//17591 -f 17599//17599 17603//17603 17591//17591 -f 17602//17602 17594//17594 17591//17591 -f 17594//17594 17604//17604 17592//17592 -f 17592//17592 17604//17604 17605//17605 -f 17592//17592 17605//17605 17593//17593 -f 17593//17593 17605//17605 17606//17606 -f 17593//17593 17606//17606 17597//17597 -f 17597//17597 17606//17606 17607//17607 -f 17597//17597 17607//17607 17595//17595 -f 17595//17595 17607//17607 17608//17608 -f 17595//17595 17608//17608 17596//17596 -f 17596//17596 17608//17608 17609//17609 -f 17596//17596 17609//17609 17600//17600 -f 17600//17600 17609//17609 17610//17610 -f 17600//17600 17610//17610 17598//17598 -f 17598//17598 17610//17610 17611//17611 -f 17598//17598 17611//17611 17599//17599 -f 17599//17599 17611//17611 17612//17612 -f 17599//17599 17612//17612 17603//17603 -f 17603//17603 17612//17612 17613//17613 -f 17603//17603 17613//17613 17601//17601 -f 17601//17601 17613//17613 17614//17614 -f 17601//17601 17614//17614 17602//17602 -f 17602//17602 17614//17614 17615//17615 -f 17602//17602 17615//17615 17594//17594 -f 17594//17594 17615//17615 17604//17604 -f 17605//17605 16942//16942 17606//17606 -f 17606//17606 16942//16942 16940//16940 -f 17606//17606 16940//16940 17607//17607 -f 17607//17607 16940//16940 16939//16939 -f 17607//17607 16939//16939 17608//17608 -f 17608//17608 16939//16939 16938//16938 -f 17608//17608 16938//16938 17609//17609 -f 17609//17609 16938//16938 16937//16937 -f 17609//17609 16937//16937 17610//17610 -f 17610//17610 16937//16937 16935//16935 -f 17610//17610 16935//16935 17611//17611 -f 17611//17611 16935//16935 16948//16948 -f 17611//17611 16948//16948 17612//17612 -f 17612//17612 16948//16948 16947//16947 -f 17612//17612 16947//16947 17613//17613 -f 17613//17613 16947//16947 16946//16946 -f 17613//17613 16946//16946 17614//17614 -f 17614//17614 16946//16946 16945//16945 -f 17614//17614 16945//16945 17615//17615 -f 17615//17615 16945//16945 16944//16944 -f 17615//17615 16944//16944 17604//17604 -f 17604//17604 16944//16944 16943//16943 -f 17604//17604 16943//16943 17605//17605 -f 17605//17605 16943//16943 16942//16942 -f 17616//17616 17617//17617 17618//17618 -f 17619//17619 17617//17617 17616//17616 -f 17616//17616 17620//17620 17621//17621 -f 17622//17622 17620//17620 17616//17616 -f 17618//17618 17622//17622 17616//17616 -f 17616//17616 17623//17623 17624//17624 -f 17625//17625 17623//17623 17616//17616 -f 17621//17621 17625//17625 17616//17616 -f 17616//17616 17626//17626 17627//17627 -f 17628//17628 17626//17626 17616//17616 -f 17624//17624 17628//17628 17616//17616 -f 17627//17627 17619//17619 17616//17616 -f 17619//17619 17629//17629 17617//17617 -f 17617//17617 17629//17629 17630//17630 -f 17617//17617 17630//17630 17618//17618 -f 17618//17618 17630//17630 17631//17631 -f 17618//17618 17631//17631 17622//17622 -f 17622//17622 17631//17631 17632//17632 -f 17622//17622 17632//17632 17620//17620 -f 17620//17620 17632//17632 17633//17633 -f 17620//17620 17633//17633 17621//17621 -f 17621//17621 17633//17633 17634//17634 -f 17621//17621 17634//17634 17625//17625 -f 17625//17625 17634//17634 17635//17635 -f 17625//17625 17635//17635 17623//17623 -f 17623//17623 17635//17635 17636//17636 -f 17623//17623 17636//17636 17624//17624 -f 17624//17624 17636//17636 17637//17637 -f 17624//17624 17637//17637 17628//17628 -f 17628//17628 17637//17637 17638//17638 -f 17628//17628 17638//17638 17626//17626 -f 17626//17626 17638//17638 17639//17639 -f 17626//17626 17639//17639 17627//17627 -f 17627//17627 17639//17639 17640//17640 -f 17627//17627 17640//17640 17619//17619 -f 17619//17619 17640//17640 17629//17629 -f 17630//17630 16922//16922 17631//17631 -f 17631//17631 16922//16922 16921//16921 -f 17631//17631 16921//16921 17632//17632 -f 17632//17632 16921//16921 16920//16920 -f 17632//17632 16920//16920 17633//17633 -f 17633//17633 16920//16920 16919//16919 -f 17633//17633 16919//16919 17634//17634 -f 17634//17634 16919//16919 16933//16933 -f 17634//17634 16933//16933 17635//17635 -f 17635//17635 16933//16933 16932//16932 -f 17635//17635 16932//16932 17636//17636 -f 17636//17636 16932//16932 16930//16930 -f 17636//17636 16930//16930 17637//17637 -f 17637//17637 16930//16930 16928//16928 -f 17637//17637 16928//16928 17638//17638 -f 17638//17638 16928//16928 16927//16927 -f 17638//17638 16927//16927 17639//17639 -f 17639//17639 16927//16927 16926//16926 -f 17639//17639 16926//16926 17640//17640 -f 17640//17640 16926//16926 16924//16924 -f 17640//17640 16924//16924 17629//17629 -f 17629//17629 16924//16924 16923//16923 -f 17629//17629 16923//16923 17630//17630 -f 17630//17630 16923//16923 16922//16922 -f 17641//17641 17642//17642 17643//17643 -f 17644//17644 17642//17642 17641//17641 -f 17641//17641 17645//17645 17646//17646 -f 17647//17647 17645//17645 17641//17641 -f 17643//17643 17647//17647 17641//17641 -f 17641//17641 17648//17648 17649//17649 -f 17650//17650 17648//17648 17641//17641 -f 17646//17646 17650//17650 17641//17641 -f 17641//17641 17651//17651 17652//17652 -f 17653//17653 17651//17651 17641//17641 -f 17649//17649 17653//17653 17641//17641 -f 17652//17652 17644//17644 17641//17641 -f 17644//17644 17654//17654 17642//17642 -f 17642//17642 17654//17654 17655//17655 -f 17642//17642 17655//17655 17643//17643 -f 17643//17643 17655//17655 17656//17656 -f 17643//17643 17656//17656 17647//17647 -f 17647//17647 17656//17656 17657//17657 -f 17647//17647 17657//17657 17645//17645 -f 17645//17645 17657//17657 17658//17658 -f 17645//17645 17658//17658 17646//17646 -f 17646//17646 17658//17658 17659//17659 -f 17646//17646 17659//17659 17650//17650 -f 17650//17650 17659//17659 17660//17660 -f 17650//17650 17660//17660 17648//17648 -f 17648//17648 17660//17660 17661//17661 -f 17648//17648 17661//17661 17649//17649 -f 17649//17649 17661//17661 17662//17662 -f 17649//17649 17662//17662 17653//17653 -f 17653//17653 17662//17662 17663//17663 -f 17653//17653 17663//17663 17651//17651 -f 17651//17651 17663//17663 17664//17664 -f 17651//17651 17664//17664 17652//17652 -f 17652//17652 17664//17664 17665//17665 -f 17652//17652 17665//17665 17644//17644 -f 17644//17644 17665//17665 17654//17654 -f 17655//17655 16992//16992 17656//17656 -f 17656//17656 16992//16992 16998//16998 -f 17656//17656 16998//16998 17657//17657 -f 17657//17657 16998//16998 16997//16997 -f 17657//17657 16997//16997 17658//17658 -f 17658//17658 16997//16997 16996//16996 -f 17658//17658 16996//16996 17659//17659 -f 17659//17659 16996//16996 16988//16988 -f 17659//17659 16988//16988 17660//17660 -f 17660//17660 16988//16988 16990//16990 -f 17660//17660 16990//16990 17661//17661 -f 17661//17661 16990//16990 16833//16833 -f 17661//17661 16833//16833 17662//17662 -f 17662//17662 16833//16833 16834//16834 -f 17662//17662 16834//16834 17663//17663 -f 17663//17663 16834//16834 16835//16835 -f 17663//17663 16835//16835 17664//17664 -f 17664//17664 16835//16835 16830//16830 -f 17664//17664 16830//16830 17665//17665 -f 17665//17665 16830//16830 16826//16826 -f 17665//17665 16826//16826 17654//17654 -f 17654//17654 16826//16826 16995//16995 -f 17654//17654 16995//16995 17655//17655 -f 17655//17655 16995//16995 16992//16992 -f 17666//17666 17667//17667 17668//17668 -f 17669//17669 17667//17667 17666//17666 -f 17666//17666 17670//17670 17671//17671 -f 17672//17672 17670//17670 17666//17666 -f 17668//17668 17672//17672 17666//17666 -f 17666//17666 17673//17673 17674//17674 -f 17675//17675 17673//17673 17666//17666 -f 17671//17671 17675//17675 17666//17666 -f 17666//17666 17676//17676 17677//17677 -f 17678//17678 17676//17676 17666//17666 -f 17674//17674 17678//17678 17666//17666 -f 17677//17677 17669//17669 17666//17666 -f 17669//17669 17679//17679 17667//17667 -f 17667//17667 17679//17679 17680//17680 -f 17667//17667 17680//17680 17668//17668 -f 17668//17668 17680//17680 17681//17681 -f 17668//17668 17681//17681 17672//17672 -f 17672//17672 17681//17681 17682//17682 -f 17672//17672 17682//17682 17670//17670 -f 17670//17670 17682//17682 17683//17683 -f 17670//17670 17683//17683 17671//17671 -f 17671//17671 17683//17683 17684//17684 -f 17671//17671 17684//17684 17675//17675 -f 17675//17675 17684//17684 17685//17685 -f 17675//17675 17685//17685 17673//17673 -f 17673//17673 17685//17685 17686//17686 -f 17673//17673 17686//17686 17674//17674 -f 17674//17674 17686//17686 17687//17687 -f 17674//17674 17687//17687 17678//17678 -f 17678//17678 17687//17687 17688//17688 -f 17678//17678 17688//17688 17676//17676 -f 17676//17676 17688//17688 17689//17689 -f 17676//17676 17689//17689 17677//17677 -f 17677//17677 17689//17689 17690//17690 -f 17677//17677 17690//17690 17669//17669 -f 17669//17669 17690//17690 17679//17679 -f 17680//17680 16878//16878 17681//17681 -f 17681//17681 16878//16878 16877//16877 -f 17681//17681 16877//16877 17682//17682 -f 17682//17682 16877//16877 16868//16868 -f 17682//17682 16868//16868 17683//17683 -f 17683//17683 16868//16868 16867//16867 -f 17683//17683 16867//16867 17684//17684 -f 17684//17684 16867//16867 16865//16865 -f 17684//17684 16865//16865 17685//17685 -f 17685//17685 16865//16865 16864//16864 -f 17685//17685 16864//16864 17686//17686 -f 17686//17686 16864//16864 16873//16873 -f 17686//17686 16873//16873 17687//17687 -f 17687//17687 16873//16873 16872//16872 -f 17687//17687 16872//16872 17688//17688 -f 17688//17688 16872//16872 16871//16871 -f 17688//17688 16871//16871 17689//17689 -f 17689//17689 16871//16871 16870//16870 -f 17689//17689 16870//16870 17690//17690 -f 17690//17690 16870//16870 16869//16869 -f 17690//17690 16869//16869 17679//17679 -f 17679//17679 16869//16869 16879//16879 -f 17679//17679 16879//16879 17680//17680 -f 17680//17680 16879//16879 16878//16878 -f 17004//17004 17691//17691 17006//17006 -f 17006//17006 17691//17691 17692//17692 -f 17006//17006 17692//17692 17007//17007 -f 17007//17007 17692//17692 17693//17693 -f 17007//17007 17693//17693 17008//17008 -f 17008//17008 17693//17693 17694//17694 -f 17008//17008 17694//17694 17009//17009 -f 17009//17009 17694//17694 17695//17695 -f 17009//17009 17695//17695 17011//17011 -f 17011//17011 17695//17695 17696//17696 -f 17011//17011 17696//17696 17013//17013 -f 17013//17013 17696//17696 17697//17697 -f 17013//17013 17697//17697 17015//17015 -f 17015//17015 17697//17697 17698//17698 -f 17015//17015 17698//17698 17016//17016 -f 17016//17016 17698//17698 17699//17699 -f 17016//17016 17699//17699 16999//16999 -f 16999//16999 17699//17699 17700//17700 -f 16999//16999 17700//17700 17000//17000 -f 17000//17000 17700//17700 17701//17701 -f 17000//17000 17701//17701 17002//17002 -f 17002//17002 17701//17701 17702//17702 -f 17002//17002 17702//17702 17004//17004 -f 17004//17004 17702//17702 17691//17691 -f 17692//17692 17582//17582 17693//17693 -f 17693//17693 17582//17582 17590//17590 -f 17693//17693 17590//17590 17694//17694 -f 17694//17694 17590//17590 17588//17588 -f 17694//17694 17588//17588 17695//17695 -f 17695//17695 17588//17588 17589//17589 -f 17695//17695 17589//17589 17696//17696 -f 17696//17696 17589//17589 17585//17585 -f 17696//17696 17585//17585 17697//17697 -f 17697//17697 17585//17585 17586//17586 -f 17697//17697 17586//17586 17698//17698 -f 17698//17698 17586//17586 17587//17587 -f 17698//17698 17587//17587 17699//17699 -f 17699//17699 17587//17587 17583//17583 -f 17699//17699 17583//17583 17700//17700 -f 17700//17700 17583//17583 17584//17584 -f 17700//17700 17584//17584 17701//17701 -f 17701//17701 17584//17584 17579//17579 -f 17701//17701 17579//17579 17702//17702 -f 17702//17702 17579//17579 17580//17580 -f 17702//17702 17580//17580 17691//17691 -f 17691//17691 17580//17580 17581//17581 -f 17691//17691 17581//17581 17692//17692 -f 17692//17692 17581//17581 17582//17582 -f 17021//17021 17703//17703 17022//17022 -f 17022//17022 17703//17703 17704//17704 -f 17022//17022 17704//17704 17112//17112 -f 17112//17112 17704//17704 17705//17705 -f 17112//17112 17705//17705 17023//17023 -f 17023//17023 17705//17705 17706//17706 -f 17023//17023 17706//17706 17024//17024 -f 17024//17024 17706//17706 17707//17707 -f 17024//17024 17707//17707 17026//17026 -f 17026//17026 17707//17707 17708//17708 -f 17026//17026 17708//17708 17028//17028 -f 17028//17028 17708//17708 17709//17709 -f 17028//17028 17709//17709 17029//17029 -f 17029//17029 17709//17709 17710//17710 -f 17029//17029 17710//17710 17120//17120 -f 17120//17120 17710//17710 17711//17711 -f 17120//17120 17711//17711 17017//17017 -f 17017//17017 17711//17711 17712//17712 -f 17017//17017 17712//17712 17018//17018 -f 17018//17018 17712//17712 17713//17713 -f 17018//17018 17713//17713 17020//17020 -f 17020//17020 17713//17713 17714//17714 -f 17020//17020 17714//17714 17021//17021 -f 17021//17021 17714//17714 17703//17703 -f 17704//17704 16583//16583 17705//17705 -f 17705//17705 16583//16583 16306//16306 -f 17705//17705 16306//16306 17706//17706 -f 17706//17706 16306//16306 16308//16308 -f 17706//17706 16308//16308 17707//17707 -f 17707//17707 16308//16308 16310//16310 -f 17707//17707 16310//16310 17708//17708 -f 17708//17708 16310//16310 16319//16319 -f 17708//17708 16319//16319 17709//17709 -f 17709//17709 16319//16319 16321//16321 -f 17709//17709 16321//16321 17710//17710 -f 17710//17710 16321//16321 16323//16323 -f 17710//17710 16323//16323 17711//17711 -f 17711//17711 16323//16323 16318//16318 -f 17711//17711 16318//16318 17712//17712 -f 17712//17712 16318//16318 16317//16317 -f 17712//17712 16317//16317 17713//17713 -f 17713//17713 16317//16317 16315//16315 -f 17713//17713 16315//16315 17714//17714 -f 17714//17714 16315//16315 16314//16314 -f 17714//17714 16314//16314 17703//17703 -f 17703//17703 16314//16314 16313//16313 -f 17703//17703 16313//16313 17704//17704 -f 17704//17704 16313//16313 16583//16583 -f 17040//17040 17715//17715 17041//17041 -f 17041//17041 17715//17715 17716//17716 -f 17041//17041 17716//17716 17042//17042 -f 17042//17042 17716//17716 17717//17717 -f 17042//17042 17717//17717 17045//17045 -f 17045//17045 17717//17717 17718//17718 -f 17045//17045 17718//17718 17043//17043 -f 17043//17043 17718//17718 17719//17719 -f 17043//17043 17719//17719 17034//17034 -f 17034//17034 17719//17719 17720//17720 -f 17034//17034 17720//17720 17032//17032 -f 17032//17032 17720//17720 17721//17721 -f 17032//17032 17721//17721 17030//17030 -f 17030//17030 17721//17721 17722//17722 -f 17030//17030 17722//17722 17037//17037 -f 17037//17037 17722//17722 17723//17723 -f 17037//17037 17723//17723 17038//17038 -f 17038//17038 17723//17723 17724//17724 -f 17038//17038 17724//17724 17039//17039 -f 17039//17039 17724//17724 17725//17725 -f 17039//17039 17725//17725 17035//17035 -f 17035//17035 17725//17725 17726//17726 -f 17035//17035 17726//17726 17040//17040 -f 17040//17040 17726//17726 17715//17715 -f 17716//17716 16613//16613 17717//17717 -f 17717//17717 16613//16613 16612//16612 -f 17717//17717 16612//16612 17718//17718 -f 17718//17718 16612//16612 16617//16617 -f 17718//17718 16617//16617 17719//17719 -f 17719//17719 16617//16617 16616//16616 -f 17719//17719 16616//16616 17720//17720 -f 17720//17720 16616//16616 16615//16615 -f 17720//17720 16615//16615 17721//17721 -f 17721//17721 16615//16615 16614//16614 -f 17721//17721 16614//16614 17722//17722 -f 17722//17722 16614//16614 16622//16622 -f 17722//17722 16622//16622 17723//17723 -f 17723//17723 16622//16622 16621//16621 -f 17723//17723 16621//16621 17724//17724 -f 17724//17724 16621//16621 16619//16619 -f 17724//17724 16619//16619 17725//17725 -f 17725//17725 16619//16619 16618//16618 -f 17725//17725 16618//16618 17726//17726 -f 17726//17726 16618//16618 16611//16611 -f 17726//17726 16611//16611 17715//17715 -f 17715//17715 16611//16611 16610//16610 -f 17715//17715 16610//16610 17716//17716 -f 17716//17716 16610//16610 16613//16613 -f 17053//17053 17727//17727 17054//17054 -f 17054//17054 17727//17727 17728//17728 -f 17054//17054 17728//17728 17056//17056 -f 17056//17056 17728//17728 17729//17729 -f 17056//17056 17729//17729 17057//17057 -f 17057//17057 17729//17729 17730//17730 -f 17057//17057 17730//17730 17058//17058 -f 17058//17058 17730//17730 17731//17731 -f 17058//17058 17731//17731 17059//17059 -f 17059//17059 17731//17731 17732//17732 -f 17059//17059 17732//17732 17052//17052 -f 17052//17052 17732//17732 17733//17733 -f 17052//17052 17733//17733 17046//17046 -f 17046//17046 17733//17733 17734//17734 -f 17046//17046 17734//17734 17047//17047 -f 17047//17047 17734//17734 17735//17735 -f 17047//17047 17735//17735 17048//17048 -f 17048//17048 17735//17735 17736//17736 -f 17048//17048 17736//17736 17049//17049 -f 17049//17049 17736//17736 17737//17737 -f 17049//17049 17737//17737 17050//17050 -f 17050//17050 17737//17737 17738//17738 -f 17050//17050 17738//17738 17053//17053 -f 17053//17053 17738//17738 17727//17727 -f 17728//17728 16678//16678 17729//17729 -f 17729//17729 16678//16678 16679//16679 -f 17729//17729 16679//16679 17730//17730 -f 17730//17730 16679//16679 16677//16677 -f 17730//17730 16677//16677 17731//17731 -f 17731//17731 16677//16677 16676//16676 -f 17731//17731 16676//16676 17732//17732 -f 17732//17732 16676//16676 16675//16675 -f 17732//17732 16675//16675 17733//17733 -f 17733//17733 16675//16675 16668//16668 -f 17733//17733 16668//16668 17734//17734 -f 17734//17734 16668//16668 16667//16667 -f 17734//17734 16667//16667 17735//17735 -f 17735//17735 16667//16667 16671//16671 -f 17735//17735 16671//16671 17736//17736 -f 17736//17736 16671//16671 16670//16670 -f 17736//17736 16670//16670 17737//17737 -f 17737//17737 16670//16670 16669//16669 -f 17737//17737 16669//16669 17738//17738 -f 17738//17738 16669//16669 16666//16666 -f 17738//17738 16666//16666 17727//17727 -f 17727//17727 16666//16666 16665//16665 -f 17727//17727 16665//16665 17728//17728 -f 17728//17728 16665//16665 16678//16678 -f 17064//17064 17739//17739 17065//17065 -f 17065//17065 17739//17739 17740//17740 -f 17065//17065 17740//17740 17104//17104 -f 17104//17104 17740//17740 17741//17741 -f 17104//17104 17741//17741 17066//17066 -f 17066//17066 17741//17741 17742//17742 -f 17066//17066 17742//17742 17067//17067 -f 17067//17067 17742//17742 17743//17743 -f 17067//17067 17743//17743 17069//17069 -f 17069//17069 17743//17743 17744//17744 -f 17069//17069 17744//17744 17070//17070 -f 17070//17070 17744//17744 17745//17745 -f 17070//17070 17745//17745 17072//17072 -f 17072//17072 17745//17745 17746//17746 -f 17072//17072 17746//17746 17107//17107 -f 17107//17107 17746//17746 17747//17747 -f 17107//17107 17747//17747 17060//17060 -f 17060//17060 17747//17747 17748//17748 -f 17060//17060 17748//17748 17061//17061 -f 17061//17061 17748//17748 17749//17749 -f 17061//17061 17749//17749 17062//17062 -f 17062//17062 17749//17749 17750//17750 -f 17062//17062 17750//17750 17064//17064 -f 17064//17064 17750//17750 17739//17739 -f 17740//17740 16492//16492 17741//17741 -f 17741//17741 16492//16492 16494//16494 -f 17741//17741 16494//16494 17742//17742 -f 17742//17742 16494//16494 16495//16495 -f 17742//17742 16495//16495 17743//17743 -f 17743//17743 16495//16495 16498//16498 -f 17743//17743 16498//16498 17744//17744 -f 17744//17744 16498//16498 16603//16603 -f 17744//17744 16603//16603 17745//17745 -f 17745//17745 16603//16603 16605//16605 -f 17745//17745 16605//16605 17746//17746 -f 17746//17746 16605//16605 16607//16607 -f 17746//17746 16607//16607 17747//17747 -f 17747//17747 16607//16607 16608//16608 -f 17747//17747 16608//16608 17748//17748 -f 17748//17748 16608//16608 16592//16592 -f 17748//17748 16592//16592 17749//17749 -f 17749//17749 16592//16592 16591//16591 -f 17749//17749 16591//16591 17750//17750 -f 17750//17750 16591//16591 16600//16600 -f 17750//17750 16600//16600 17739//17739 -f 17739//17739 16600//16600 16490//16490 -f 17739//17739 16490//16490 17740//17740 -f 17740//17740 16490//16490 16492//16492 -f 17078//17078 17751//17751 17073//17073 -f 17073//17073 17751//17751 17752//17752 -f 17073//17073 17752//17752 17074//17074 -f 17074//17074 17752//17752 17753//17753 -f 17074//17074 17753//17753 17075//17075 -f 17075//17075 17753//17753 17754//17754 -f 17075//17075 17754//17754 17076//17076 -f 17076//17076 17754//17754 17755//17755 -f 17076//17076 17755//17755 17077//17077 -f 17077//17077 17755//17755 17756//17756 -f 17077//17077 17756//17756 17081//17081 -f 17081//17081 17756//17756 17757//17757 -f 17081//17081 17757//17757 17082//17082 -f 17082//17082 17757//17757 17758//17758 -f 17082//17082 17758//17758 17083//17083 -f 17083//17083 17758//17758 17759//17759 -f 17083//17083 17759//17759 17086//17086 -f 17086//17086 17759//17759 17760//17760 -f 17086//17086 17760//17760 17084//17084 -f 17084//17084 17760//17760 17761//17761 -f 17084//17084 17761//17761 17080//17080 -f 17080//17080 17761//17761 17762//17762 -f 17080//17080 17762//17762 17078//17078 -f 17078//17078 17762//17762 17751//17751 -f 17752//17752 16687//16687 17753//17753 -f 17753//17753 16687//16687 16697//16697 -f 17753//17753 16697//16697 17754//17754 -f 17754//17754 16697//16697 16696//16696 -f 17754//17754 16696//16696 17755//17755 -f 17755//17755 16696//16696 16695//16695 -f 17755//17755 16695//16695 17756//17756 -f 17756//17756 16695//16695 16694//16694 -f 17756//17756 16694//16694 17757//17757 -f 17757//17757 16694//16694 16693//16693 -f 17757//17757 16693//16693 17758//17758 -f 17758//17758 16693//16693 16692//16692 -f 17758//17758 16692//16692 17759//17759 -f 17759//17759 16692//16692 16689//16689 -f 17759//17759 16689//16689 17760//17760 -f 17760//17760 16689//16689 16690//16690 -f 17760//17760 16690//16690 17761//17761 -f 17761//17761 16690//16690 16691//16691 -f 17761//17761 16691//16691 17762//17762 -f 17762//17762 16691//16691 16686//16686 -f 17762//17762 16686//16686 17751//17751 -f 17751//17751 16686//16686 16685//16685 -f 17751//17751 16685//16685 17752//17752 -f 17752//17752 16685//16685 16687//16687 -f 17087//17087 17763//17763 17088//17088 -f 17088//17088 17763//17763 17764//17764 -f 17088//17088 17764//17764 17089//17089 -f 17089//17089 17764//17764 17765//17765 -f 17089//17089 17765//17765 17092//17092 -f 17092//17092 17765//17765 17766//17766 -f 17092//17092 17766//17766 17093//17093 -f 17093//17093 17766//17766 17767//17767 -f 17093//17093 17767//17767 17094//17094 -f 17094//17094 17767//17767 17768//17768 -f 17094//17094 17768//17768 17099//17099 -f 17099//17099 17768//17768 17769//17769 -f 17099//17099 17769//17769 17100//17100 -f 17100//17100 17769//17769 17770//17770 -f 17100//17100 17770//17770 17102//17102 -f 17102//17102 17770//17770 17771//17771 -f 17102//17102 17771//17771 17098//17098 -f 17098//17098 17771//17771 17772//17772 -f 17098//17098 17772//17772 17097//17097 -f 17097//17097 17772//17772 17773//17773 -f 17097//17097 17773//17773 17090//17090 -f 17090//17090 17773//17773 17774//17774 -f 17090//17090 17774//17774 17087//17087 -f 17087//17087 17774//17774 17763//17763 -f 17764//17764 16631//16631 17765//17765 -f 17765//17765 16631//16631 16630//16630 -f 17765//17765 16630//16630 17766//17766 -f 17766//17766 16630//16630 16628//16628 -f 17766//17766 16628//16628 17767//17767 -f 17767//17767 16628//16628 16635//16635 -f 17767//17767 16635//16635 17768//17768 -f 17768//17768 16635//16635 16634//16634 -f 17768//17768 16634//16634 17769//17769 -f 17769//17769 16634//16634 16639//16639 -f 17769//17769 16639//16639 17770//17770 -f 17770//17770 16639//16639 16638//16638 -f 17770//17770 16638//16638 17771//17771 -f 17771//17771 16638//16638 16637//16637 -f 17771//17771 16637//16637 17772//17772 -f 17772//17772 16637//16637 16636//16636 -f 17772//17772 16636//16636 17773//17773 -f 17773//17773 16636//16636 16624//16624 -f 17773//17773 16624//16624 17774//17774 -f 17774//17774 16624//16624 16623//16623 -f 17774//17774 16623//16623 17763//17763 -f 17763//17763 16623//16623 16626//16626 -f 17763//17763 16626//16626 17764//17764 -f 17764//17764 16626//16626 16631//16631 -f 17230//17230 17229//17229 17232//17232 -f 17230//17230 17232//17232 17775//17775 -f 17775//17775 17232//17232 17233//17233 -f 17775//17775 17233//17233 17776//17776 -f 17776//17776 17233//17233 16298//16298 -f 17776//17776 16298//16298 16297//16297 -f 16324//16324 17777//17777 17778//17778 -f 17777//17777 17779//17779 17780//17780 -f 17779//17779 17228//17228 17435//17435 -f 17779//17779 17435//17435 17780//17780 -f 17780//17780 17435//17435 17436//17436 -f 17780//17780 17436//17436 17781//17781 -f 17781//17781 17436//17436 17437//17437 -f 17781//17781 17437//17437 17782//17782 -f 17782//17782 17437//17437 17438//17438 -f 17782//17782 17438//17438 17783//17783 -f 17783//17783 17438//17438 17439//17439 -f 17783//17783 17439//17439 17784//17784 -f 17784//17784 17439//17439 17440//17440 -f 17784//17784 17440//17440 17785//17785 -f 17785//17785 17440//17440 17441//17441 -f 17785//17785 17441//17441 17786//17786 -f 17786//17786 17441//17441 17442//17442 -f 17786//17786 17442//17442 17787//17787 -f 17787//17787 17442//17442 17443//17443 -f 17787//17787 17443//17443 17788//17788 -f 17788//17788 17443//17443 17230//17230 -f 17788//17788 17230//17230 17775//17775 -f 17777//17777 17780//17780 17778//17778 -f 17778//17778 17780//17780 17781//17781 -f 17778//17778 17781//17781 17789//17789 -f 17789//17789 17781//17781 17782//17782 -f 17789//17789 17782//17782 17790//17790 -f 17790//17790 17782//17782 17783//17783 -f 17790//17790 17783//17783 17791//17791 -f 17791//17791 17783//17783 17784//17784 -f 17791//17791 17784//17784 17792//17792 -f 17792//17792 17784//17784 17785//17785 -f 17792//17792 17785//17785 17793//17793 -f 17793//17793 17785//17785 17786//17786 -f 17793//17793 17786//17786 17794//17794 -f 17794//17794 17786//17786 17787//17787 -f 17794//17794 17787//17787 17795//17795 -f 17795//17795 17787//17787 17788//17788 -f 17795//17795 17788//17788 17796//17796 -f 17796//17796 17788//17788 17775//17775 -f 17796//17796 17775//17775 17776//17776 -f 16324//16324 17778//17778 16325//16325 -f 16325//16325 17778//17778 17789//17789 -f 16325//16325 17789//17789 16316//16316 -f 16316//16316 17789//17789 17790//17790 -f 16316//16316 17790//17790 16483//16483 -f 16483//16483 17790//17790 17791//17791 -f 16483//16483 17791//17791 16484//16484 -f 16484//16484 17791//17791 17792//17792 -f 16484//16484 17792//17792 16487//16487 -f 16487//16487 17792//17792 17793//17793 -f 16487//16487 17793//17793 16488//16488 -f 16488//16488 17793//17793 17794//17794 -f 16488//16488 17794//17794 16489//16489 -f 16489//16489 17794//17794 17795//17795 -f 16489//16489 17795//17795 16486//16486 -f 16486//16486 17795//17795 17796//17796 -f 16486//16486 17796//17796 16485//16485 -f 16485//16485 17796//17796 17776//17776 -f 16485//16485 17776//17776 16297//16297 -f 16606//16606 16604//16604 17797//17797 -f 17227//17227 17228//17228 17779//17779 -f 17227//17227 17779//17779 17798//17798 -f 17798//17798 17779//17779 17777//17777 -f 17798//17798 17777//17777 17797//17797 -f 16324//16324 16322//16322 17777//17777 -f 17777//17777 16322//16322 16320//16320 -f 17777//17777 16320//16320 17797//17797 -f 17797//17797 16320//16320 16594//16594 -f 17797//17797 16594//16594 16606//16606 -f 16501//16501 17799//17799 17800//17800 -f 17799//17799 17801//17801 17802//17802 -f 17801//17801 17226//17226 17444//17444 -f 17801//17801 17444//17444 17802//17802 -f 17802//17802 17444//17444 17445//17445 -f 17802//17802 17445//17445 17803//17803 -f 17803//17803 17445//17445 17446//17446 -f 17803//17803 17446//17446 17804//17804 -f 17804//17804 17446//17446 17447//17447 -f 17804//17804 17447//17447 17805//17805 -f 17805//17805 17447//17447 17448//17448 -f 17805//17805 17448//17448 17806//17806 -f 17806//17806 17448//17448 17449//17449 -f 17806//17806 17449//17449 17807//17807 -f 17807//17807 17449//17449 17450//17450 -f 17807//17807 17450//17450 17808//17808 -f 17808//17808 17450//17450 17451//17451 -f 17808//17808 17451//17451 17809//17809 -f 17809//17809 17451//17451 17452//17452 -f 17809//17809 17452//17452 17810//17810 -f 17810//17810 17452//17452 17227//17227 -f 17810//17810 17227//17227 17798//17798 -f 17799//17799 17802//17802 17800//17800 -f 17800//17800 17802//17802 17803//17803 -f 17800//17800 17803//17803 17811//17811 -f 17811//17811 17803//17803 17804//17804 -f 17811//17811 17804//17804 17812//17812 -f 17812//17812 17804//17804 17805//17805 -f 17812//17812 17805//17805 17813//17813 -f 17813//17813 17805//17805 17806//17806 -f 17813//17813 17806//17806 17814//17814 -f 17814//17814 17806//17806 17807//17807 -f 17814//17814 17807//17807 17815//17815 -f 17815//17815 17807//17807 17808//17808 -f 17815//17815 17808//17808 17816//17816 -f 17816//17816 17808//17808 17809//17809 -f 17816//17816 17809//17809 17817//17817 -f 17817//17817 17809//17809 17810//17810 -f 17817//17817 17810//17810 17818//17818 -f 17818//17818 17810//17810 17798//17798 -f 17818//17818 17798//17798 17797//17797 -f 16501//16501 17800//17800 16502//16502 -f 16502//16502 17800//17800 17811//17811 -f 16502//16502 17811//17811 16503//16503 -f 16503//16503 17811//17811 17812//17812 -f 16503//16503 17812//17812 16711//16711 -f 16711//16711 17812//17812 17813//17813 -f 16711//16711 17813//17813 16496//16496 -f 16496//16496 17813//17813 17814//17814 -f 16496//16496 17814//17814 16497//16497 -f 16497//16497 17814//17814 17815//17815 -f 16497//16497 17815//17815 16500//16500 -f 16500//16500 17815//17815 17816//17816 -f 16500//16500 17816//17816 16499//16499 -f 16499//16499 17816//17816 17817//17817 -f 16499//16499 17817//17817 16601//16601 -f 16601//16601 17817//17817 17818//17818 -f 16601//16601 17818//17818 16602//16602 -f 16602//16602 17818//17818 17797//17797 -f 16602//16602 17797//17797 16604//16604 -f 17225//17225 17226//17226 17801//17801 -f 17225//17225 17801//17801 17300//17300 -f 17300//17300 17801//17801 17799//17799 -f 17300//17300 17799//17799 17299//17299 -f 17299//17299 17799//17799 16501//16501 -f 17299//17299 16501//16501 16507//16507 -f 17294//17294 16504//16504 16392//16392 -f 17294//17294 16392//16392 17289//17289 -f 17289//17289 16392//16392 16399//16399 -f 17289//17289 16399//16399 16401//16401 -f 17284//17284 16383//16383 16382//16382 -f 17284//17284 16382//16382 17279//17279 -f 17279//17279 16382//16382 16293//16293 -f 17279//17279 16293//16293 16448//16448 -f 17274//17274 16410//16410 17269//17269 -f 17269//17269 16410//16410 16416//16416 -f 17269//17269 16416//16416 16418//16418 -f 17259//17259 17264//17264 16723//16723 -f 16723//16723 16729//16729 17259//17259 -f 17259//17259 16729//16729 16305//16305 -f 17259//17259 16305//16305 16304//16304 -f 16452//16452 16451//16451 17252//17252 -f 17252//17252 16451//16451 16700//16700 -f 17252//17252 16700//16700 17247//17247 -f 17247//17247 16700//16700 16457//16457 -f 17247//17247 16457//16457 16456//16456 -f 16376//16376 16468//16468 17222//17222 -f 17221//17221 16462//16462 16369//16369 -f 17221//17221 16369//16369 17222//17222 -f 17222//17222 16369//16369 16373//16373 -f 17222//17222 16373//16373 16376//16376 -f 16650//16650 17209//17209 16649//16649 -f 16649//16649 17209//17209 17208//17208 -f 16649//16649 17208//17208 16648//16648 -f 16648//16648 17208//17208 16647//16647 -f 16646//16646 17162//17162 16645//16645 -f 16645//16645 17162//17162 17161//17161 -f 16645//16645 17161//17161 16644//16644 -f 16476//16476 16481//16481 17156//17156 -f 16476//16476 17156//17156 16475//16475 -f 16475//16475 17156//17156 17155//17155 -f 16475//16475 17155//17155 16474//16474 -f 17149//17149 16640//16640 16641//16641 -f 17149//17149 16641//16641 17150//17150 -f 17150//17150 16641//16641 16642//16642 -f 17150//17150 16642//16642 16643//16643 -f 16796//16796 17151//17151 16797//16797 -f 16797//16797 17151//17151 17152//17152 -f 16806//16806 17148//17148 16807//16807 -f 16807//16807 17148//17148 17147//17147 -f 16807//16807 17147//17147 16804//16804 -f 16809//16809 17157//17157 16810//16810 -f 16810//16810 17157//17157 17158//17158 -f 16794//16794 17154//17154 16795//16795 -f 16795//16795 17154//17154 17153//17153 -f 16815//16815 17163//17163 16816//16816 -f 16816//16816 17163//17163 17164//17164 -f 17125//17125 17160//17160 17124//17124 -f 17124//17124 17160//17160 17159//17159 -f 16993//16993 17210//17210 16994//16994 -f 16994//16994 17210//17210 17211//17211 -f 16832//16832 17207//17207 16831//16831 -f 16831//16831 17207//17207 17206//17206 -f 16915//16915 17292//17292 16914//16914 -f 16914//16914 17292//17292 17291//17291 -f 16911//16911 17296//17296 16900//16900 -f 16900//16900 17296//17296 17290//17290 -f 16900//16900 17290//17290 16901//16901 -f 16906//16906 17282//17282 16907//16907 -f 16907//16907 17282//17282 17281//17281 -f 16902//16902 17286//17286 16903//16903 -f 16903//16903 17286//17286 17280//17280 -f 16892//16892 17272//17272 16891//16891 -f 16891//16891 17272//17272 17271//17271 -f 16886//16886 17276//17276 16887//16887 -f 16887//16887 17276//17276 17270//17270 -f 16791//16791 17262//17262 16792//16792 -f 16792//16792 17262//17262 17261//17261 -f 16875//16875 17266//17266 16874//16874 -f 16874//16874 17266//17266 17260//17260 -f 17117//17117 17223//17223 16841//16841 -f 16841//16841 17223//17223 17224//17224 -f 16841//16841 17224//17224 16840//16840 -f 16842//16842 17220//17220 16843//16843 -f 16843//16843 17220//17220 17219//17219 -f 16855//16855 17254//17254 16854//16854 -f 16854//16854 17254//17254 17248//17248 -f 16860//16860 17250//17250 16858//16858 -f 16858//16858 17250//17250 17249//17249 -f 17298//17298 16506//16506 17297//17297 -f 17297//17297 16506//16506 16505//16505 -f 17288//17288 16387//16387 17287//17287 -f 17287//17287 16387//16387 16385//16385 -f 17278//17278 16449//16449 17277//17277 -f 17277//17277 16449//16449 16412//16412 -f 17268//17268 16407//16407 17267//17267 -f 17267//17267 16407//16407 16405//16405 -f 17258//17258 16303//16303 17257//17257 -f 17257//17257 16303//16303 16455//16455 -f 17256//17256 16455//16455 17255//17255 -f 17255//17255 16455//16455 16453//16453 -f 17234//17234 16300//16300 17231//17231 -f 17231//17231 16300//16300 16482//16482 -f 17236//17236 16478//16478 17235//17235 -f 17235//17235 16478//16478 16328//16328 -f 17238//17238 16353//16353 17237//17237 -f 17237//17237 16353//16353 16473//16473 -f 17240//17240 16509//16509 17239//17239 -f 17239//17239 16509//16509 16344//16344 -f 17244//17244 16469//16469 17243//17243 -f 17243//17243 16469//16469 16470//16470 -f 17242//17242 16470//16470 17241//17241 -f 17241//17241 16470//16470 16467//16467 -f 16463//16463 17245//17245 16464//16464 -f 16464//16464 17245//17245 17246//17246 -f 16464//16464 17246//17246 16459//16459 -f 16459//16459 17246//17246 16458//16458 -f 17458//17458 16563//16563 16632//16632 -f 16633//16633 16550//16550 17455//17455 -f 16633//16633 17455//17455 16632//16632 -f 16632//16632 17455//17455 17456//17456 -f 16632//16632 17456//17456 17458//17458 -f 16559//16559 17457//17457 16555//16555 -f 16555//16555 17457//17457 17453//17453 -f 16555//16555 17453//17453 16556//16556 -f 16556//16556 17453//17453 17454//17454 -f 16556//16556 17454//17454 16682//16682 -f 16573//16573 16571//16571 17464//17464 -f 16672//16672 16574//16574 17460//17460 -f 17460//17460 16574//16574 16573//16573 -f 17460//17460 16573//16573 17461//17461 -f 17461//17461 16573//16573 17464//17464 -f 17463//17463 16566//16566 17462//17462 -f 17462//17462 16566//16566 16565//16565 -f 17462//17462 16565//16565 17459//17459 -f 17459//17459 16565//16565 16295//16295 -f 17459//17459 16295//16295 16294//16294 -f 17457//17457 16559//16559 16558//16558 -f 17457//17457 16558//16558 17458//17458 -f 17458//17458 16558//16558 16561//16561 -f 17458//17458 16561//16561 16563//16563 -f 17459//17459 16294//16294 16674//16674 -f 17459//17459 16674//16674 17460//17460 -f 17460//17460 16674//16674 16673//16673 -f 17460//17460 16673//16673 16672//16672 -f 17304//17304 16431//16431 16430//16430 -f 17304//17304 16430//16430 17819//17819 -f 17819//17819 16430//16430 16429//16429 -f 17819//17819 16429//16429 17820//17820 -f 17820//17820 16429//16429 16435//16435 -f 17820//17820 16435//16435 17306//17306 -f 17312//17312 17310//17310 17821//17821 -f 17312//17312 17821//17821 17822//17822 -f 17822//17822 17821//17821 17823//17823 -f 17822//17822 17823//17823 17824//17824 -f 17824//17824 17823//17823 17303//17303 -f 17824//17824 17303//17303 17304//17304 -f 17301//17301 16427//16427 16426//16426 -f 17301//17301 16426//16426 17825//17825 -f 17825//17825 16426//16426 16737//16737 -f 17825//17825 16737//16737 17826//17826 -f 17826//17826 16737//16737 16433//16433 -f 17826//17826 16433//16433 17303//17303 -f 17306//17306 17827//17827 17828//17828 -f 17312//17312 17822//17822 17829//17829 -f 17827//17827 17830//17830 17828//17828 -f 17828//17828 17830//17830 17829//17829 -f 17828//17828 17829//17829 17831//17831 -f 17831//17831 17829//17829 17822//17822 -f 17831//17831 17822//17822 17824//17824 -f 17306//17306 17828//17828 17820//17820 -f 17820//17820 17828//17828 17831//17831 -f 17820//17820 17831//17831 17819//17819 -f 17819//17819 17831//17831 17824//17824 -f 17819//17819 17824//17824 17304//17304 -f 17830//17830 17312//17312 17829//17829 -f 17827//17827 17832//17832 17830//17830 -f 17830//17830 17832//17832 17312//17312 -f 17303//17303 17823//17823 17833//17833 -f 17310//17310 17834//17834 17835//17835 -f 17823//17823 17836//17836 17833//17833 -f 17833//17833 17836//17836 17835//17835 -f 17833//17833 17835//17835 17837//17837 -f 17837//17837 17835//17835 17834//17834 -f 17837//17837 17834//17834 17838//17838 -f 17303//17303 17833//17833 17826//17826 -f 17826//17826 17833//17833 17837//17837 -f 17826//17826 17837//17837 17825//17825 -f 17825//17825 17837//17837 17838//17838 -f 17825//17825 17838//17838 17301//17301 -f 17836//17836 17310//17310 17835//17835 -f 17823//17823 17821//17821 17836//17836 -f 17836//17836 17821//17821 17310//17310 -f 17305//17305 16443//16443 16441//16441 -f 17305//17305 16441//16441 17839//17839 -f 17839//17839 16441//16441 16440//16440 -f 17839//17839 16440//16440 17840//17840 -f 17840//17840 16440//16440 16438//16438 -f 17840//17840 16438//16438 17308//17308 -f 17311//17311 17312//17312 17832//17832 -f 17311//17311 17832//17832 17841//17841 -f 17841//17841 17832//17832 17827//17827 -f 17841//17841 17827//17827 17842//17842 -f 17842//17842 17827//17827 17306//17306 -f 17842//17842 17306//17306 17305//17305 -f 17310//17310 17309//17309 17843//17843 -f 17310//17310 17843//17843 17834//17834 -f 17834//17834 17843//17843 17844//17844 -f 17834//17834 17844//17844 17838//17838 -f 17838//17838 17844//17844 17302//17302 -f 17838//17838 17302//17302 17301//17301 -f 17307//17307 16542//16542 16540//16540 -f 17307//17307 16540//16540 17845//17845 -f 17845//17845 16540//16540 16461//16461 -f 17845//17845 16461//16461 17846//17846 -f 17846//17846 16461//16461 16447//16447 -f 17846//17846 16447//16447 17302//17302 -f 17308//17308 17847//17847 17848//17848 -f 17311//17311 17841//17841 17849//17849 -f 17847//17847 17850//17850 17848//17848 -f 17848//17848 17850//17850 17849//17849 -f 17848//17848 17849//17849 17851//17851 -f 17851//17851 17849//17849 17841//17841 -f 17851//17851 17841//17841 17842//17842 -f 17308//17308 17848//17848 17840//17840 -f 17840//17840 17848//17848 17851//17851 -f 17840//17840 17851//17851 17839//17839 -f 17839//17839 17851//17851 17842//17842 -f 17839//17839 17842//17842 17305//17305 -f 17850//17850 17311//17311 17849//17849 -f 17847//17847 17852//17852 17850//17850 -f 17850//17850 17852//17852 17311//17311 -f 17302//17302 17844//17844 17853//17853 -f 17309//17309 17854//17854 17855//17855 -f 17844//17844 17856//17856 17853//17853 -f 17853//17853 17856//17856 17855//17855 -f 17853//17853 17855//17855 17857//17857 -f 17857//17857 17855//17855 17854//17854 -f 17857//17857 17854//17854 17858//17858 -f 17302//17302 17853//17853 17846//17846 -f 17846//17846 17853//17853 17857//17857 -f 17846//17846 17857//17857 17845//17845 -f 17845//17845 17857//17857 17858//17858 -f 17845//17845 17858//17858 17307//17307 -f 17856//17856 17309//17309 17855//17855 -f 17844//17844 17843//17843 17856//17856 -f 17856//17856 17843//17843 17309//17309 -f 17309//17309 17311//17311 17852//17852 -f 17309//17309 17852//17852 17854//17854 -f 17854//17854 17852//17852 17847//17847 -f 17854//17854 17847//17847 17858//17858 -f 17858//17858 17847//17847 17308//17308 -f 17858//17858 17308//17308 17307//17307 -f 17316//17316 16534//16534 16533//16533 -f 17316//17316 16533//16533 17859//17859 -f 17859//17859 16533//16533 16532//16532 -f 17859//17859 16532//16532 17860//17860 -f 17860//17860 16532//16532 16531//16531 -f 17860//17860 16531//16531 17317//17317 -f 17315//17315 17316//17316 17861//17861 -f 17315//17315 17861//17861 17862//17862 -f 17862//17862 17861//17861 17863//17863 -f 17862//17862 17863//17863 17864//17864 -f 17864//17864 17863//17863 17324//17324 -f 17864//17864 17324//17324 17322//17322 -f 17313//17313 16517//16517 16519//16519 -f 17313//17313 16519//16519 17865//17865 -f 17865//17865 16519//16519 16528//16528 -f 17865//17865 16528//16528 17866//17866 -f 17866//17866 16528//16528 16530//16530 -f 17866//17866 16530//16530 17315//17315 -f 17317//17317 17867//17867 17868//17868 -f 17324//17324 17863//17863 17869//17869 -f 17867//17867 17870//17870 17868//17868 -f 17868//17868 17870//17870 17869//17869 -f 17868//17868 17869//17869 17871//17871 -f 17871//17871 17869//17869 17863//17863 -f 17871//17871 17863//17863 17861//17861 -f 17317//17317 17868//17868 17860//17860 -f 17860//17860 17868//17868 17871//17871 -f 17860//17860 17871//17871 17859//17859 -f 17859//17859 17871//17871 17861//17861 -f 17859//17859 17861//17861 17316//17316 -f 17870//17870 17324//17324 17869//17869 -f 17867//17867 17872//17872 17870//17870 -f 17870//17870 17872//17872 17324//17324 -f 17315//17315 17862//17862 17873//17873 -f 17322//17322 17874//17874 17875//17875 -f 17862//17862 17876//17876 17873//17873 -f 17873//17873 17876//17876 17875//17875 -f 17873//17873 17875//17875 17877//17877 -f 17877//17877 17875//17875 17874//17874 -f 17877//17877 17874//17874 17878//17878 -f 17315//17315 17873//17873 17866//17866 -f 17866//17866 17873//17873 17877//17877 -f 17866//17866 17877//17877 17865//17865 -f 17865//17865 17877//17877 17878//17878 -f 17865//17865 17878//17878 17313//17313 -f 17876//17876 17322//17322 17875//17875 -f 17862//17862 17864//17864 17876//17876 -f 17876//17876 17864//17864 17322//17322 -f 17318//17318 16536//16536 16541//16541 -f 17318//17318 16541//16541 17879//17879 -f 17879//17879 16541//16541 16549//16549 -f 17879//17879 16549//16549 17880//17880 -f 17880//17880 16549//16549 16548//16548 -f 17880//17880 16548//16548 17319//17319 -f 17317//17317 17318//17318 17881//17881 -f 17317//17317 17881//17881 17867//17867 -f 17867//17867 17881//17881 17882//17882 -f 17867//17867 17882//17882 17872//17872 -f 17872//17872 17882//17882 17323//17323 -f 17872//17872 17323//17323 17324//17324 -f 17314//17314 17313//17313 17878//17878 -f 17314//17314 17878//17878 17883//17883 -f 17883//17883 17878//17878 17874//17874 -f 17883//17883 17874//17874 17884//17884 -f 17884//17884 17874//17874 17322//17322 -f 17884//17884 17322//17322 17321//17321 -f 17320//17320 16543//16543 16347//16347 -f 17320//17320 16347//16347 17885//17885 -f 17885//17885 16347//16347 16346//16346 -f 17885//17885 16346//16346 17886//17886 -f 17886//17886 16346//16346 16514//16514 -f 17886//17886 16514//16514 17314//17314 -f 17319//17319 17887//17887 17888//17888 -f 17323//17323 17882//17882 17889//17889 -f 17887//17887 17890//17890 17888//17888 -f 17888//17888 17890//17890 17889//17889 -f 17888//17888 17889//17889 17891//17891 -f 17891//17891 17889//17889 17882//17882 -f 17891//17891 17882//17882 17881//17881 -f 17319//17319 17888//17888 17880//17880 -f 17880//17880 17888//17888 17891//17891 -f 17880//17880 17891//17891 17879//17879 -f 17879//17879 17891//17891 17881//17881 -f 17879//17879 17881//17881 17318//17318 -f 17890//17890 17323//17323 17889//17889 -f 17887//17887 17892//17892 17890//17890 -f 17890//17890 17892//17892 17323//17323 -f 17314//17314 17883//17883 17893//17893 -f 17321//17321 17894//17894 17895//17895 -f 17883//17883 17896//17896 17893//17893 -f 17893//17893 17896//17896 17895//17895 -f 17893//17893 17895//17895 17897//17897 -f 17897//17897 17895//17895 17894//17894 -f 17897//17897 17894//17894 17898//17898 -f 17314//17314 17893//17893 17886//17886 -f 17886//17886 17893//17893 17897//17897 -f 17886//17886 17897//17897 17885//17885 -f 17885//17885 17897//17897 17898//17898 -f 17885//17885 17898//17898 17320//17320 -f 17896//17896 17321//17321 17895//17895 -f 17883//17883 17884//17884 17896//17896 -f 17896//17896 17884//17884 17321//17321 -f 17319//17319 17320//17320 17898//17898 -f 17319//17319 17898//17898 17887//17887 -f 17887//17887 17898//17898 17894//17894 -f 17887//17887 17894//17894 17892//17892 -f 17892//17892 17894//17894 17321//17321 -f 17892//17892 17321//17321 17323//17323 -f 17531//17531 17899//17899 17532//17532 -f 17532//17532 17899//17899 17900//17900 -f 17532//17532 17900//17900 17553//17553 -f 17553//17553 17900//17900 17901//17901 -f 17553//17553 17901//17901 17554//17554 -f 17554//17554 17901//17901 17902//17902 -f 17554//17554 17902//17902 17555//17555 -f 17555//17555 17902//17902 17903//17903 -f 17555//17555 17903//17903 17509//17509 -f 17509//17509 17903//17903 17904//17904 -f 17509//17509 17904//17904 17510//17510 -f 17510//17510 17904//17904 17905//17905 -f 17510//17510 17905//17905 17528//17528 -f 17528//17528 17905//17905 17906//17906 -f 17528//17528 17906//17906 17529//17529 -f 17529//17529 17906//17906 17907//17907 -f 17529//17529 17907//17907 17550//17550 -f 17550//17550 17907//17907 17908//17908 -f 17550//17550 17908//17908 17551//17551 -f 17551//17551 17908//17908 17909//17909 -f 17551//17551 17909//17909 17552//17552 -f 17552//17552 17909//17909 17910//17910 -f 17552//17552 17910//17910 17524//17524 -f 17524//17524 17910//17910 17911//17911 -f 17524//17524 17911//17911 17525//17525 -f 17525//17525 17911//17911 17912//17912 -f 17525//17525 17912//17912 17547//17547 -f 17547//17547 17912//17912 17913//17913 -f 17547//17547 17913//17913 17548//17548 -f 17548//17548 17913//17913 17914//17914 -f 17548//17548 17914//17914 17549//17549 -f 17549//17549 17914//17914 17915//17915 -f 17549//17549 17915//17915 17546//17546 -f 17546//17546 17915//17915 17916//17916 -f 17546//17546 17916//17916 17544//17544 -f 17544//17544 17916//17916 17917//17917 -f 17544//17544 17917//17917 17523//17523 -f 17523//17523 17917//17917 17918//17918 -f 17523//17523 17918//17918 17521//17521 -f 17521//17521 17918//17918 17919//17919 -f 17521//17521 17919//17919 17519//17519 -f 17519//17519 17919//17919 17920//17920 -f 17519//17519 17920//17920 17541//17541 -f 17541//17541 17920//17920 17921//17921 -f 17541//17541 17921//17921 17542//17542 -f 17542//17542 17921//17921 17922//17922 -f 17542//17542 17922//17922 17543//17543 -f 17543//17543 17922//17922 17923//17923 -f 17543//17543 17923//17923 17517//17517 -f 17517//17517 17923//17923 17924//17924 -f 17517//17517 17924//17924 17518//17518 -f 17518//17518 17924//17924 17925//17925 -f 17518//17518 17925//17925 17515//17515 -f 17515//17515 17925//17925 17926//17926 -f 17515//17515 17926//17926 17559//17559 -f 17559//17559 17926//17926 17927//17927 -f 17559//17559 17927//17927 17560//17560 -f 17560//17560 17927//17927 17928//17928 -f 17560//17560 17928//17928 17561//17561 -f 17561//17561 17928//17928 17929//17929 -f 17561//17561 17929//17929 17537//17537 -f 17537//17537 17929//17929 17930//17930 -f 17537//17537 17930//17930 17538//17538 -f 17538//17538 17930//17930 17931//17931 -f 17538//17538 17931//17931 17556//17556 -f 17556//17556 17931//17931 17932//17932 -f 17556//17556 17932//17932 17557//17557 -f 17557//17557 17932//17932 17933//17933 -f 17557//17557 17933//17933 17558//17558 -f 17558//17558 17933//17933 17934//17934 -f 17558//17558 17934//17934 17535//17535 -f 17535//17535 17934//17934 17935//17935 -f 17535//17535 17935//17935 17536//17536 -f 17536//17536 17935//17935 17936//17936 -f 17536//17536 17936//17936 17505//17505 -f 17505//17505 17936//17936 17937//17937 -f 17505//17505 17937//17937 17506//17506 -f 17506//17506 17937//17937 17938//17938 -f 17506//17506 17938//17938 17531//17531 -f 17531//17531 17938//17938 17899//17899 -f 17938//17938 17939//17939 17899//17899 -f 17899//17899 17939//17939 17940//17940 -f 17899//17899 17940//17940 17900//17900 -f 17900//17900 17940//17940 17941//17941 -f 17900//17900 17941//17941 17901//17901 -f 17901//17901 17941//17941 17942//17942 -f 17901//17901 17942//17942 17902//17902 -f 17902//17902 17942//17942 17943//17943 -f 17902//17902 17943//17943 17903//17903 -f 17903//17903 17943//17943 17944//17944 -f 17903//17903 17944//17944 17904//17904 -f 17904//17904 17944//17944 17945//17945 -f 17904//17904 17945//17945 17905//17905 -f 17905//17905 17945//17945 17946//17946 -f 17905//17905 17946//17946 17906//17906 -f 17906//17906 17946//17946 17947//17947 -f 17906//17906 17947//17947 17907//17907 -f 17907//17907 17947//17947 17948//17948 -f 17907//17907 17948//17948 17908//17908 -f 17908//17908 17948//17948 17949//17949 -f 17908//17908 17949//17949 17909//17909 -f 17909//17909 17949//17949 17950//17950 -f 17909//17909 17950//17950 17910//17910 -f 17910//17910 17950//17950 17951//17951 -f 17910//17910 17951//17951 17911//17911 -f 17911//17911 17951//17951 17952//17952 -f 17911//17911 17952//17952 17912//17912 -f 17912//17912 17952//17952 17953//17953 -f 17912//17912 17953//17953 17913//17913 -f 17913//17913 17953//17953 17954//17954 -f 17913//17913 17954//17954 17914//17914 -f 17914//17914 17954//17954 17955//17955 -f 17914//17914 17955//17955 17915//17915 -f 17915//17915 17955//17955 17956//17956 -f 17915//17915 17956//17956 17916//17916 -f 17916//17916 17956//17956 17957//17957 -f 17916//17916 17957//17957 17917//17917 -f 17917//17917 17957//17957 17958//17958 -f 17917//17917 17958//17958 17918//17918 -f 17918//17918 17958//17958 17959//17959 -f 17918//17918 17959//17959 17919//17919 -f 17919//17919 17959//17959 17960//17960 -f 17919//17919 17960//17960 17920//17920 -f 17920//17920 17960//17960 17961//17961 -f 17920//17920 17961//17961 17921//17921 -f 17921//17921 17961//17961 17962//17962 -f 17921//17921 17962//17962 17922//17922 -f 17922//17922 17962//17962 17963//17963 -f 17922//17922 17963//17963 17923//17923 -f 17923//17923 17963//17963 17964//17964 -f 17923//17923 17964//17964 17924//17924 -f 17924//17924 17964//17964 17965//17965 -f 17924//17924 17965//17965 17925//17925 -f 17925//17925 17965//17965 17966//17966 -f 17925//17925 17966//17966 17926//17926 -f 17926//17926 17966//17966 17967//17967 -f 17926//17926 17967//17967 17927//17927 -f 17927//17927 17967//17967 17968//17968 -f 17927//17927 17968//17968 17928//17928 -f 17928//17928 17968//17968 17969//17969 -f 17928//17928 17969//17969 17929//17929 -f 17929//17929 17969//17969 17970//17970 -f 17929//17929 17970//17970 17930//17930 -f 17930//17930 17970//17970 17971//17971 -f 17930//17930 17971//17971 17931//17931 -f 17931//17931 17971//17971 17972//17972 -f 17931//17931 17972//17972 17932//17932 -f 17932//17932 17972//17972 17973//17973 -f 17932//17932 17973//17973 17933//17933 -f 17933//17933 17973//17973 17974//17974 -f 17933//17933 17974//17974 17934//17934 -f 17934//17934 17974//17974 17975//17975 -f 17934//17934 17975//17975 17935//17935 -f 17935//17935 17975//17975 17976//17976 -f 17935//17935 17976//17976 17936//17936 -f 17936//17936 17976//17976 17977//17977 -f 17936//17936 17977//17977 17937//17937 -f 17937//17937 17977//17977 17978//17978 -f 17937//17937 17978//17978 17938//17938 -f 17938//17938 17978//17978 17939//17939 -f 17978//17978 17484//17484 17939//17939 -f 17939//17939 17484//17484 17487//17487 -f 17939//17939 17487//17487 17940//17940 -f 17940//17940 17487//17487 17486//17486 -f 17940//17940 17486//17486 17941//17941 -f 17941//17941 17486//17486 17489//17489 -f 17941//17941 17489//17489 17942//17942 -f 17942//17942 17489//17489 17488//17488 -f 17942//17942 17488//17488 17943//17943 -f 17943//17943 17488//17488 17491//17491 -f 17943//17943 17491//17491 17944//17944 -f 17944//17944 17491//17491 17490//17490 -f 17944//17944 17490//17490 17945//17945 -f 17945//17945 17490//17490 17493//17493 -f 17945//17945 17493//17493 17946//17946 -f 17946//17946 17493//17493 17492//17492 -f 17946//17946 17492//17492 17947//17947 -f 17947//17947 17492//17492 17495//17495 -f 17947//17947 17495//17495 17948//17948 -f 17948//17948 17495//17495 17494//17494 -f 17948//17948 17494//17494 17949//17949 -f 17949//17949 17494//17494 17497//17497 -f 17949//17949 17497//17497 17950//17950 -f 17950//17950 17497//17497 17496//17496 -f 17950//17950 17496//17496 17951//17951 -f 17951//17951 17496//17496 17499//17499 -f 17951//17951 17499//17499 17952//17952 -f 17952//17952 17499//17499 17498//17498 -f 17952//17952 17498//17498 17953//17953 -f 17953//17953 17498//17498 17501//17501 -f 17953//17953 17501//17501 17954//17954 -f 17954//17954 17501//17501 17500//17500 -f 17954//17954 17500//17500 17955//17955 -f 17955//17955 17500//17500 17504//17504 -f 17955//17955 17504//17504 17956//17956 -f 17956//17956 17504//17504 17503//17503 -f 17956//17956 17503//17503 17957//17957 -f 17957//17957 17503//17503 17502//17502 -f 17957//17957 17502//17502 17958//17958 -f 17958//17958 17502//17502 17465//17465 -f 17958//17958 17465//17465 17959//17959 -f 17959//17959 17465//17465 17467//17467 -f 17959//17959 17467//17467 17960//17960 -f 17960//17960 17467//17467 17466//17466 -f 17960//17960 17466//17466 17961//17961 -f 17961//17961 17466//17466 17469//17469 -f 17961//17961 17469//17469 17962//17962 -f 17962//17962 17469//17469 17468//17468 -f 17962//17962 17468//17468 17963//17963 -f 17963//17963 17468//17468 17471//17471 -f 17963//17963 17471//17471 17964//17964 -f 17964//17964 17471//17471 17470//17470 -f 17964//17964 17470//17470 17965//17965 -f 17965//17965 17470//17470 17473//17473 -f 17965//17965 17473//17473 17966//17966 -f 17966//17966 17473//17473 17472//17472 -f 17966//17966 17472//17472 17967//17967 -f 17967//17967 17472//17472 17475//17475 -f 17967//17967 17475//17475 17968//17968 -f 17968//17968 17475//17475 17474//17474 -f 17968//17968 17474//17474 17969//17969 -f 17969//17969 17474//17474 17477//17477 -f 17969//17969 17477//17477 17970//17970 -f 17970//17970 17477//17477 17476//17476 -f 17970//17970 17476//17476 17971//17971 -f 17971//17971 17476//17476 17479//17479 -f 17971//17971 17479//17479 17972//17972 -f 17972//17972 17479//17479 17478//17478 -f 17972//17972 17478//17478 17973//17973 -f 17973//17973 17478//17478 17481//17481 -f 17973//17973 17481//17481 17974//17974 -f 17974//17974 17481//17481 17480//17480 -f 17974//17974 17480//17480 17975//17975 -f 17975//17975 17480//17480 17483//17483 -f 17975//17975 17483//17483 17976//17976 -f 17976//17976 17483//17483 17482//17482 -f 17976//17976 17482//17482 17977//17977 -f 17977//17977 17482//17482 17485//17485 -f 17977//17977 17485//17485 17978//17978 -f 17978//17978 17485//17485 17484//17484 -f 17979//17979 17980//17980 17981//17981 -f 17982//17982 17983//17983 17980//17980 -f 17980//17980 17983//17983 17984//17984 -f 17980//17980 17984//17984 17981//17981 -f 17985//17985 17986//17986 17982//17982 -f 17982//17982 17986//17986 17987//17987 -f 17982//17982 17987//17987 17983//17983 -f 17988//17988 17989//17989 17985//17985 -f 17985//17985 17989//17989 17990//17990 -f 17985//17985 17990//17990 17986//17986 -f 17991//17991 17992//17992 17988//17988 -f 17988//17988 17992//17992 17993//17993 -f 17988//17988 17993//17993 17989//17989 -f 17994//17994 17995//17995 17991//17991 -f 17991//17991 17995//17995 17996//17996 -f 17991//17991 17996//17996 17992//17992 -f 17997//17997 17998//17998 17994//17994 -f 17994//17994 17998//17998 17999//17999 -f 17994//17994 17999//17999 17995//17995 -f 18000//18000 18001//18001 17997//17997 -f 17997//17997 18001//18001 18002//18002 -f 17997//17997 18002//18002 17998//17998 -f 18003//18003 18004//18004 18000//18000 -f 18000//18000 18004//18004 18005//18005 -f 18000//18000 18005//18005 18001//18001 -f 18006//18006 18007//18007 18003//18003 -f 18003//18003 18007//18007 18008//18008 -f 18003//18003 18008//18008 18004//18004 -f 18009//18009 18010//18010 18006//18006 -f 18006//18006 18010//18010 18011//18011 -f 18006//18006 18011//18011 18007//18007 -f 18012//18012 18013//18013 18009//18009 -f 18009//18009 18013//18013 18014//18014 -f 18009//18009 18014//18014 18010//18010 -f 18015//18015 18016//18016 18012//18012 -f 18012//18012 18016//18016 18017//18017 -f 18012//18012 18017//18017 18013//18013 -f 18018//18018 18019//18019 18015//18015 -f 18015//18015 18019//18019 18020//18020 -f 18015//18015 18020//18020 18016//18016 -f 18021//18021 18022//18022 18018//18018 -f 18018//18018 18022//18022 18023//18023 -f 18018//18018 18023//18023 18019//18019 -f 18024//18024 18025//18025 18021//18021 -f 18021//18021 18025//18025 18026//18026 -f 18021//18021 18026//18026 18022//18022 -f 18027//18027 18028//18028 18024//18024 -f 18024//18024 18028//18028 18029//18029 -f 18024//18024 18029//18029 18025//18025 -f 18030//18030 18031//18031 18027//18027 -f 18027//18027 18031//18031 18032//18032 -f 18027//18027 18032//18032 18028//18028 -f 17981//17981 18033//18033 17979//17979 -f 17979//17979 18033//18033 18034//18034 -f 17979//17979 18034//18034 18030//18030 -f 18030//18030 18034//18034 18035//18035 -f 18030//18030 18035//18035 18031//18031 -f 18036//18036 18037//18037 18038//18038 -f 18039//18039 18040//18040 18041//18041 -f 18041//18041 18040//18040 18042//18042 -f 18043//18043 18044//18044 18045//18045 -f 18046//18046 18047//18047 18048//18048 -f 18049//18049 18050//18050 18051//18051 -f 18051//18051 18050//18050 18052//18052 -f 18051//18051 18052//18052 18053//18053 -f 18054//18054 18055//18055 18049//18049 -f 18049//18049 18055//18055 18056//18056 -f 18049//18049 18056//18056 18050//18050 -f 18045//18045 18057//18057 18043//18043 -f 18043//18043 18057//18057 18058//18058 -f 18043//18043 18058//18058 18059//18059 -f 18053//18053 18052//18052 18042//18042 -f 18042//18042 18052//18052 18060//18060 -f 18042//18042 18060//18060 18041//18041 -f 18061//18061 18062//18062 18063//18063 -f 18063//18063 18062//18062 18064//18064 -f 18063//18063 18064//18064 18054//18054 -f 18054//18054 18064//18064 18065//18065 -f 18054//18054 18065//18065 18055//18055 -f 18066//18066 18067//18067 18063//18063 -f 18063//18063 18067//18067 18068//18068 -f 18063//18063 18068//18068 18061//18061 -f 18069//18069 18067//18067 18070//18070 -f 18070//18070 18067//18067 18066//18066 -f 18070//18070 18066//18066 18071//18071 -f 18071//18071 18066//18066 18072//18072 -f 18071//18071 18072//18072 18073//18073 -f 18073//18073 18072//18072 18047//18047 -f 18073//18073 18047//18047 18074//18074 -f 18074//18074 18047//18047 18046//18046 -f 18069//18069 18075//18075 18067//18067 -f 18067//18067 18075//18075 18076//18076 -f 18067//18067 18076//18076 18077//18077 -f 18077//18077 18076//18076 18078//18078 -f 18077//18077 18078//18078 18058//18058 -f 18058//18058 18078//18078 18079//18079 -f 18058//18058 18079//18079 18059//18059 -f 18068//18068 18080//18080 18061//18061 -f 18061//18061 18080//18080 18081//18081 -f 18061//18061 18081//18081 18082//18082 -f 18082//18082 18081//18081 18083//18083 -f 18082//18082 18083//18083 18084//18084 -f 18084//18084 18083//18083 18085//18085 -f 18084//18084 18085//18085 18086//18086 -f 18086//18086 18085//18085 18087//18087 -f 18086//18086 18087//18087 18044//18044 -f 18044//18044 18087//18087 18088//18088 -f 18044//18044 18088//18088 18045//18045 -f 18089//18089 18090//18090 18091//18091 -f 18092//18092 18093//18093 18094//18094 -f 18095//18095 18038//18038 18096//18096 -f 18094//18094 18093//18093 18090//18090 -f 18090//18090 18093//18093 18097//18097 -f 18090//18090 18097//18097 18091//18091 -f 18037//18037 18098//18098 18038//18038 -f 18038//18038 18098//18098 18099//18099 -f 18038//18038 18099//18099 18096//18096 -f 18043//18043 18100//18100 18044//18044 -f 18044//18044 18100//18100 18101//18101 -f 18044//18044 18101//18101 18102//18102 -f 18102//18102 18101//18101 18103//18103 -f 18094//18094 18104//18104 18092//18092 -f 18092//18092 18104//18104 18105//18105 -f 18092//18092 18105//18105 18037//18037 -f 18037//18037 18105//18105 18106//18106 -f 18037//18037 18106//18106 18098//18098 -f 18043//18043 18107//18107 18100//18100 -f 18100//18100 18107//18107 18108//18108 -f 18100//18100 18108//18108 18109//18109 -f 18109//18109 18108//18108 18110//18110 -f 18109//18109 18110//18110 18096//18096 -f 18096//18096 18110//18110 18111//18111 -f 18096//18096 18111//18111 18095//18095 -f 18091//18091 18112//18112 18089//18089 -f 18089//18089 18112//18112 18113//18113 -f 18089//18089 18113//18113 18101//18101 -f 18101//18101 18113//18113 18114//18114 -f 18101//18101 18114//18114 18103//18103 -f 18115//18115 18116//18116 18117//18117 -f 18117//18117 18118//18118 18115//18115 -f 18115//18115 18118//18118 18119//18119 -f 18115//18115 18119//18119 18038//18038 -f 18038//18038 18119//18119 18120//18120 -f 18038//18038 18120//18120 18036//18036 -f 18121//18121 18122//18122 18123//18123 -f 18123//18123 18122//18122 18046//18046 -f 18123//18123 18046//18046 18124//18124 -f 18121//18121 18123//18123 18125//18125 -f 18125//18125 18123//18123 18126//18126 -f 18125//18125 18126//18126 18127//18127 -f 18127//18127 18126//18126 18128//18128 -f 18127//18127 18128//18128 18129//18129 -f 18129//18129 18128//18128 18115//18115 -f 18115//18115 18128//18128 18130//18130 -f 18115//18115 18130//18130 18116//18116 -f 18130//18130 18131//18131 18116//18116 -f 18116//18116 18131//18131 18132//18132 -f 18116//18116 18132//18132 18133//18133 -f 18133//18133 18132//18132 18134//18134 -f 18133//18133 18134//18134 18135//18135 -f 18135//18135 18134//18134 18136//18136 -f 18135//18135 18136//18136 18137//18137 -f 18137//18137 18136//18136 18138//18138 -f 18137//18137 18138//18138 18139//18139 -f 18139//18139 18138//18138 18140//18140 -f 18139//18139 18140//18140 18141//18141 -f 18141//18141 18140//18140 18142//18142 -f 18048//18048 18039//18039 18046//18046 -f 18046//18046 18039//18039 18041//18041 -f 18046//18046 18041//18041 18124//18124 -f 18124//18124 18041//18041 18143//18143 -f 18124//18124 18143//18143 18144//18144 -f 18144//18144 18145//18145 18124//18124 -f 18124//18124 18145//18145 18146//18146 -f 18124//18124 18146//18146 18142//18142 -f 18142//18142 18146//18146 18147//18147 -f 18142//18142 18147//18147 18141//18141 -f 18148//18148 18149//18149 18150//18150 -f 18150//18150 18149//18149 18151//18151 -f 18150//18150 18151//18151 18152//18152 -f 18152//18152 18151//18151 18153//18153 -f 18152//18152 18153//18153 18154//18154 -f 18154//18154 18153//18153 18155//18155 -f 18154//18154 18155//18155 18156//18156 -f 18156//18156 18155//18155 18157//18157 -f 18156//18156 18157//18157 18158//18158 -f 18158//18158 18157//18157 18159//18159 -f 18158//18158 18159//18159 18160//18160 -f 18160//18160 18159//18159 18161//18161 -f 18160//18160 18161//18161 18162//18162 -f 18162//18162 18161//18161 18163//18163 -f 18162//18162 18163//18163 18164//18164 -f 18164//18164 18163//18163 18165//18165 -f 18164//18164 18165//18165 18166//18166 -f 18166//18166 18165//18165 18167//18167 -f 18166//18166 18167//18167 18168//18168 -f 18168//18168 18167//18167 18169//18169 -f 18168//18168 18169//18169 18170//18170 -f 18170//18170 18169//18169 18171//18171 -f 18170//18170 18171//18171 18172//18172 -f 18172//18172 18171//18171 18173//18173 -f 18172//18172 18173//18173 18174//18174 -f 18174//18174 18173//18173 18175//18175 -f 18174//18174 18175//18175 18176//18176 -f 18176//18176 18175//18175 18177//18177 -f 18176//18176 18177//18177 18178//18178 -f 18178//18178 18177//18177 18179//18179 -f 18178//18178 18179//18179 18180//18180 -f 18180//18180 18179//18179 18181//18181 -f 18180//18180 18181//18181 18182//18182 -f 18182//18182 18181//18181 18183//18183 -f 18182//18182 18183//18183 18184//18184 -f 18184//18184 18183//18183 18185//18185 -f 18184//18184 18185//18185 18186//18186 -f 18186//18186 18185//18185 18187//18187 -f 18186//18186 18187//18187 18188//18188 -f 18188//18188 18187//18187 18189//18189 -f 18188//18188 18189//18189 18190//18190 -f 18190//18190 18189//18189 18191//18191 -f 18190//18190 18191//18191 18192//18192 -f 18192//18192 18191//18191 18193//18193 -f 18192//18192 18193//18193 18194//18194 -f 18194//18194 18193//18193 18195//18195 -f 18194//18194 18195//18195 18196//18196 -f 18196//18196 18195//18195 18197//18197 -f 18196//18196 18197//18197 18198//18198 -f 18198//18198 18197//18197 18199//18199 -f 18198//18198 18199//18199 18200//18200 -f 18200//18200 18199//18199 18201//18201 -f 18200//18200 18201//18201 18202//18202 -f 18202//18202 18201//18201 18203//18203 -f 18202//18202 18203//18203 18204//18204 -f 18204//18204 18203//18203 18205//18205 -f 18204//18204 18205//18205 18206//18206 -f 18206//18206 18205//18205 18207//18207 -f 18206//18206 18207//18207 18208//18208 -f 18208//18208 18207//18207 18209//18209 -f 18208//18208 18209//18209 18210//18210 -f 18210//18210 18209//18209 18211//18211 -f 18210//18210 18211//18211 18212//18212 -f 18212//18212 18211//18211 18213//18213 -f 18212//18212 18213//18213 18214//18214 -f 18214//18214 18213//18213 18215//18215 -f 18214//18214 18215//18215 18216//18216 -f 18216//18216 18215//18215 18217//18217 -f 18216//18216 18217//18217 18218//18218 -f 18218//18218 18217//18217 18219//18219 -f 18218//18218 18219//18219 18220//18220 -f 18220//18220 18219//18219 18221//18221 -f 18220//18220 18221//18221 18222//18222 -f 18222//18222 18221//18221 18223//18223 -f 18222//18222 18223//18223 18148//18148 -f 18148//18148 18223//18223 18149//18149 -f 18224//18224 18225//18225 18226//18226 -f 18226//18226 18225//18225 18227//18227 -f 18227//18227 18225//18225 18228//18228 -f 18227//18227 18228//18228 18229//18229 -f 18229//18229 18228//18228 18230//18230 -f 18229//18229 18230//18230 18231//18231 -f 18231//18231 18230//18230 18232//18232 -f 18231//18231 18232//18232 18233//18233 -f 18233//18233 18232//18232 18234//18234 -f 18233//18233 18234//18234 18235//18235 -f 18235//18235 18236//18236 18237//18237 -f 18237//18237 18236//18236 18238//18238 -f 18237//18237 18238//18238 18239//18239 -f 18240//18240 18241//18241 18242//18242 -f 18226//18226 18243//18243 18224//18224 -f 18224//18224 18243//18243 18244//18244 -f 18224//18224 18244//18244 18245//18245 -f 18240//18240 18246//18246 18241//18241 -f 18241//18241 18246//18246 18247//18247 -f 18241//18241 18247//18247 18248//18248 -f 18242//18242 18249//18249 18240//18240 -f 18240//18240 18249//18249 18250//18250 -f 18240//18240 18250//18250 18251//18251 -f 18251//18251 18250//18250 18252//18252 -f 18251//18251 18252//18252 18238//18238 -f 18238//18238 18252//18252 18253//18253 -f 18238//18238 18253//18253 18239//18239 -f 18254//18254 18255//18255 18256//18256 -f 18256//18256 18255//18255 18257//18257 -f 18256//18256 18257//18257 18258//18258 -f 18258//18258 18257//18257 18259//18259 -f 18258//18258 18259//18259 18248//18248 -f 18248//18248 18259//18259 18260//18260 -f 18248//18248 18260//18260 18241//18241 -f 18261//18261 18262//18262 18263//18263 -f 18263//18263 18262//18262 18264//18264 -f 18246//18246 18224//18224 18247//18247 -f 18247//18247 18224//18224 18245//18245 -f 18247//18247 18245//18245 18265//18265 -f 18265//18265 18245//18245 18266//18266 -f 18265//18265 18266//18266 18267//18267 -f 18268//18268 18269//18269 18270//18270 -f 18270//18270 18269//18269 18264//18264 -f 18264//18264 18269//18269 18271//18271 -f 18264//18264 18271//18271 18263//18263 -f 18270//18270 18272//18272 18268//18268 -f 18268//18268 18272//18272 18273//18273 -f 18268//18268 18273//18273 18274//18274 -f 18274//18274 18273//18273 18267//18267 -f 18274//18274 18267//18267 18275//18275 -f 18275//18275 18267//18267 18266//18266 -f 18276//18276 18277//18277 18278//18278 -f 18278//18278 18277//18277 18279//18279 -f 18277//18277 18280//18280 18281//18281 -f 18281//18281 18280//18280 18282//18282 -f 18281//18281 18282//18282 18283//18283 -f 18283//18283 18282//18282 18284//18284 -f 18283//18283 18284//18284 18285//18285 -f 18285//18285 18284//18284 18286//18286 -f 18285//18285 18286//18286 18287//18287 -f 18287//18287 18286//18286 18288//18288 -f 18287//18287 18288//18288 18289//18289 -f 18289//18289 18288//18288 18290//18290 -f 18289//18289 18290//18290 18291//18291 -f 18291//18291 18290//18290 18292//18292 -f 18291//18291 18292//18292 18293//18293 -f 18256//18256 18261//18261 18254//18254 -f 18254//18254 18261//18261 18263//18263 -f 18254//18254 18263//18263 18294//18294 -f 18294//18294 18263//18263 18295//18295 -f 18293//18293 18292//18292 18296//18296 -f 18296//18296 18292//18292 18297//18297 -f 18296//18296 18297//18297 18298//18298 -f 18278//18278 18299//18299 18276//18276 -f 18276//18276 18299//18299 18300//18300 -f 18276//18276 18300//18300 18301//18301 -f 18301//18301 18300//18300 18302//18302 -f 18301//18301 18302//18302 18303//18303 -f 18303//18303 18302//18302 18304//18304 -f 18304//18304 18295//18295 18303//18303 -f 18303//18303 18295//18295 18263//18263 -f 18303//18303 18263//18263 18297//18297 -f 18297//18297 18263//18263 18305//18305 -f 18297//18297 18305//18305 18298//18298 -f 18277//18277 18281//18281 18279//18279 -f 18279//18279 18281//18281 18306//18306 -f 18279//18279 18306//18306 18307//18307 -f 18307//18307 18308//18308 18279//18279 -f 18279//18279 18308//18308 18309//18309 -f 18279//18279 18309//18309 18310//18310 -f 18311//18311 18312//18312 18313//18313 -f 18314//18314 18315//18315 18316//18316 -f 18317//18317 18279//18279 18318//18318 -f 18319//18319 18320//18320 18321//18321 -f 18316//18316 18315//18315 18312//18312 -f 18312//18312 18315//18315 18322//18322 -f 18312//18312 18322//18322 18313//18313 -f 18235//18235 18237//18237 18233//18233 -f 18233//18233 18237//18237 18323//18323 -f 18233//18233 18323//18323 18324//18324 -f 18316//18316 18325//18325 18314//18314 -f 18314//18314 18325//18325 18326//18326 -f 18314//18314 18326//18326 18327//18327 -f 18327//18327 18326//18326 18328//18328 -f 18327//18327 18328//18328 18310//18310 -f 18310//18310 18328//18328 18329//18329 -f 18310//18310 18329//18329 18279//18279 -f 18279//18279 18329//18329 18330//18330 -f 18279//18279 18330//18330 18318//18318 -f 18320//18320 18233//18233 18321//18321 -f 18321//18321 18233//18233 18324//18324 -f 18321//18321 18324//18324 18331//18331 -f 18331//18331 18324//18324 18332//18332 -f 18331//18331 18332//18332 18333//18333 -f 18333//18333 18332//18332 18334//18334 -f 18333//18333 18334//18334 18318//18318 -f 18318//18318 18334//18334 18335//18335 -f 18318//18318 18335//18335 18317//18317 -f 18313//18313 18336//18336 18311//18311 -f 18311//18311 18336//18336 18337//18337 -f 18311//18311 18337//18337 18321//18321 -f 18321//18321 18337//18337 18338//18338 -f 18321//18321 18338//18338 18319//18319 -f 18253//18253 18252//18252 18339//18339 -f 18339//18339 18340//18340 18253//18253 -f 18253//18253 18340//18340 18341//18341 -f 18253//18253 18341//18341 18239//18239 -f 18239//18239 18341//18341 18342//18342 -f 18239//18239 18342//18342 18237//18237 -f 18237//18237 18342//18342 18343//18343 -f 18237//18237 18343//18343 18323//18323 -f 18343//18343 18344//18344 18323//18323 -f 18323//18323 18344//18344 18345//18345 -f 18323//18323 18345//18345 18324//18324 -f 18345//18345 18346//18346 18324//18324 -f 18324//18324 18346//18346 18347//18347 -f 18324//18324 18347//18347 18332//18332 -f 18347//18347 18348//18348 18332//18332 -f 18332//18332 18348//18348 18349//18349 -f 18332//18332 18349//18349 18334//18334 -f 18349//18349 18350//18350 18334//18334 -f 18334//18334 18350//18350 18351//18351 -f 18334//18334 18351//18351 18335//18335 -f 18351//18351 18352//18352 18335//18335 -f 18335//18335 18352//18352 18353//18353 -f 18335//18335 18353//18353 18317//18317 -f 18353//18353 18354//18354 18317//18317 -f 18317//18317 18354//18354 18355//18355 -f 18317//18317 18355//18355 18279//18279 -f 18355//18355 18356//18356 18279//18279 -f 18279//18279 18356//18356 18357//18357 -f 18279//18279 18357//18357 18278//18278 -f 18357//18357 18358//18358 18278//18278 -f 18278//18278 18358//18358 18359//18359 -f 18278//18278 18359//18359 18299//18299 -f 18359//18359 18360//18360 18299//18299 -f 18299//18299 18360//18360 18361//18361 -f 18299//18299 18361//18361 18300//18300 -f 18361//18361 18362//18362 18300//18300 -f 18300//18300 18362//18362 18363//18363 -f 18300//18300 18363//18363 18302//18302 -f 18363//18363 18364//18364 18302//18302 -f 18302//18302 18364//18364 18365//18365 -f 18302//18302 18365//18365 18304//18304 -f 18365//18365 18366//18366 18304//18304 -f 18304//18304 18366//18366 18367//18367 -f 18304//18304 18367//18367 18295//18295 -f 18367//18367 18368//18368 18295//18295 -f 18295//18295 18368//18368 18369//18369 -f 18295//18295 18369//18369 18294//18294 -f 18294//18294 18369//18369 18370//18370 -f 18294//18294 18370//18370 18254//18254 -f 18254//18254 18370//18370 18371//18371 -f 18254//18254 18371//18371 18255//18255 -f 18371//18371 18372//18372 18255//18255 -f 18255//18255 18372//18372 18373//18373 -f 18255//18255 18373//18373 18257//18257 -f 18373//18373 18374//18374 18257//18257 -f 18257//18257 18374//18374 18375//18375 -f 18257//18257 18375//18375 18259//18259 -f 18375//18375 18376//18376 18259//18259 -f 18259//18259 18376//18376 18377//18377 -f 18259//18259 18377//18377 18260//18260 -f 18377//18377 18378//18378 18260//18260 -f 18260//18260 18378//18378 18379//18379 -f 18260//18260 18379//18379 18241//18241 -f 18379//18379 18380//18380 18241//18241 -f 18241//18241 18380//18380 18381//18381 -f 18241//18241 18381//18381 18242//18242 -f 18381//18381 18382//18382 18242//18242 -f 18242//18242 18382//18382 18383//18383 -f 18242//18242 18383//18383 18249//18249 -f 18383//18383 18384//18384 18249//18249 -f 18249//18249 18384//18384 18385//18385 -f 18249//18249 18385//18385 18250//18250 -f 18385//18385 18386//18386 18250//18250 -f 18250//18250 18386//18386 18387//18387 -f 18250//18250 18387//18387 18252//18252 -f 18252//18252 18387//18387 18388//18388 -f 18252//18252 18388//18388 18339//18339 -f 18389//18389 18390//18390 18391//18391 -f 18392//18392 18393//18393 18394//18394 -f 18394//18394 18393//18393 18395//18395 -f 18394//18394 18395//18395 18396//18396 -f 18396//18396 18395//18395 18397//18397 -f 18396//18396 18397//18397 18391//18391 -f 18391//18391 18397//18397 18398//18398 -f 18391//18391 18398//18398 18389//18389 -f 18399//18399 18400//18400 18401//18401 -f 18401//18401 18400//18400 18402//18402 -f 18401//18401 18402//18402 18403//18403 -f 18403//18403 18402//18402 18404//18404 -f 18403//18403 18404//18404 18392//18392 -f 18392//18392 18404//18404 18405//18405 -f 18392//18392 18405//18405 18393//18393 -f 18406//18406 18407//18407 18408//18408 -f 18408//18408 18407//18407 18409//18409 -f 18408//18408 18409//18409 18410//18410 -f 18410//18410 18409//18409 18411//18411 -f 18410//18410 18411//18411 18399//18399 -f 18399//18399 18411//18411 18412//18412 -f 18399//18399 18412//18412 18400//18400 -f 18389//18389 18413//18413 18390//18390 -f 18390//18390 18413//18413 18414//18414 -f 18390//18390 18414//18414 18415//18415 -f 18415//18415 18414//18414 18416//18416 -f 18415//18415 18416//18416 18417//18417 -f 18417//18417 18416//18416 18418//18418 -f 18417//18417 18418//18418 18419//18419 -f 18420//18420 18421//18421 18422//18422 -f 18422//18422 18421//18421 18423//18423 -f 18422//18422 18423//18423 18424//18424 -f 18424//18424 18423//18423 18425//18425 -f 18424//18424 18425//18425 18406//18406 -f 18406//18406 18425//18425 18426//18426 -f 18406//18406 18426//18426 18407//18407 -f 18418//18418 18427//18427 18419//18419 -f 18419//18419 18427//18427 18428//18428 -f 18419//18419 18428//18428 18429//18429 -f 18429//18429 18428//18428 18430//18430 -f 18429//18429 18430//18430 18431//18431 -f 18431//18431 18430//18430 18432//18432 -f 18431//18431 18432//18432 18420//18420 -f 18420//18420 18432//18432 18433//18433 -f 18420//18420 18433//18433 18421//18421 -f 18434//18434 18390//18390 18435//18435 -f 18435//18435 18390//18390 18415//18415 -f 18435//18435 18415//18415 18436//18436 -f 18436//18436 18415//18415 18417//18417 -f 18436//18436 18417//18417 18437//18437 -f 18437//18437 18417//18417 18419//18419 -f 18437//18437 18419//18419 18438//18438 -f 18438//18438 18419//18419 18429//18429 -f 18438//18438 18429//18429 18439//18439 -f 18439//18439 18429//18429 18431//18431 -f 18439//18439 18431//18431 18440//18440 -f 18440//18440 18431//18431 18420//18420 -f 18440//18440 18420//18420 18441//18441 -f 18441//18441 18420//18420 18422//18422 -f 18441//18441 18422//18422 18442//18442 -f 18442//18442 18422//18422 18424//18424 -f 18442//18442 18424//18424 18443//18443 -f 18443//18443 18424//18424 18406//18406 -f 18443//18443 18406//18406 18444//18444 -f 18444//18444 18406//18406 18408//18408 -f 18444//18444 18408//18408 18445//18445 -f 18445//18445 18408//18408 18410//18410 -f 18445//18445 18410//18410 18446//18446 -f 18446//18446 18410//18410 18399//18399 -f 18446//18446 18399//18399 18447//18447 -f 18447//18447 18399//18399 18401//18401 -f 18447//18447 18401//18401 18448//18448 -f 18448//18448 18401//18401 18403//18403 -f 18448//18448 18403//18403 18449//18449 -f 18449//18449 18403//18403 18392//18392 -f 18449//18449 18392//18392 18450//18450 -f 18450//18450 18392//18392 18394//18394 -f 18450//18450 18394//18394 18451//18451 -f 18451//18451 18394//18394 18396//18396 -f 18451//18451 18396//18396 18452//18452 -f 18452//18452 18396//18396 18391//18391 -f 18452//18452 18391//18391 18434//18434 -f 18434//18434 18391//18391 18390//18390 -f 18453//18453 18451//18451 18454//18454 -f 18454//18454 18451//18451 18452//18452 -f 18454//18454 18452//18452 18455//18455 -f 18455//18455 18452//18452 18434//18434 -f 18455//18455 18434//18434 18456//18456 -f 18457//18457 18445//18445 18458//18458 -f 18458//18458 18445//18445 18446//18446 -f 18458//18458 18446//18446 18459//18459 -f 18446//18446 18447//18447 18459//18459 -f 18459//18459 18447//18447 18448//18448 -f 18459//18459 18448//18448 18460//18460 -f 18460//18460 18448//18448 18449//18449 -f 18460//18460 18449//18449 18453//18453 -f 18453//18453 18449//18449 18450//18450 -f 18453//18453 18450//18450 18451//18451 -f 18461//18461 18442//18442 18462//18462 -f 18462//18462 18442//18442 18443//18443 -f 18462//18462 18443//18443 18457//18457 -f 18457//18457 18443//18443 18444//18444 -f 18457//18457 18444//18444 18445//18445 -f 18463//18463 18439//18439 18464//18464 -f 18464//18464 18439//18439 18440//18440 -f 18464//18464 18440//18440 18461//18461 -f 18461//18461 18440//18440 18441//18441 -f 18461//18461 18441//18441 18442//18442 -f 18434//18434 18435//18435 18456//18456 -f 18456//18456 18435//18435 18436//18436 -f 18456//18456 18436//18436 18465//18465 -f 18465//18465 18436//18436 18437//18437 -f 18465//18465 18437//18437 18463//18463 -f 18463//18463 18437//18437 18438//18438 -f 18463//18463 18438//18438 18439//18439 -f 18466//18466 18455//18455 18467//18467 -f 18467//18467 18455//18455 18456//18456 -f 18467//18467 18456//18456 18468//18468 -f 18468//18468 18456//18456 18465//18465 -f 18468//18468 18465//18465 18469//18469 -f 18469//18469 18465//18465 18463//18463 -f 18469//18469 18463//18463 18470//18470 -f 18470//18470 18463//18463 18464//18464 -f 18470//18470 18464//18464 18471//18471 -f 18471//18471 18464//18464 18461//18461 -f 18471//18471 18461//18461 18472//18472 -f 18472//18472 18461//18461 18462//18462 -f 18472//18472 18462//18462 18473//18473 -f 18473//18473 18462//18462 18457//18457 -f 18473//18473 18457//18457 18474//18474 -f 18474//18474 18457//18457 18458//18458 -f 18474//18474 18458//18458 18475//18475 -f 18475//18475 18458//18458 18459//18459 -f 18475//18475 18459//18459 18476//18476 -f 18476//18476 18459//18459 18460//18460 -f 18476//18476 18460//18460 18477//18477 -f 18477//18477 18460//18460 18453//18453 -f 18477//18477 18453//18453 18478//18478 -f 18478//18478 18453//18453 18454//18454 -f 18478//18478 18454//18454 18466//18466 -f 18466//18466 18454//18454 18455//18455 -f 18474//18474 18009//18009 18473//18473 -f 18473//18473 18009//18009 18006//18006 -f 18473//18473 18006//18006 18472//18472 -f 18476//18476 18018//18018 18475//18475 -f 18475//18475 18018//18018 18015//18015 -f 18475//18475 18015//18015 18474//18474 -f 18474//18474 18015//18015 18012//18012 -f 18474//18474 18012//18012 18009//18009 -f 18478//18478 18027//18027 18477//18477 -f 18477//18477 18027//18027 18024//18024 -f 18477//18477 18024//18024 18476//18476 -f 18476//18476 18024//18024 18021//18021 -f 18476//18476 18021//18021 18018//18018 -f 18468//18468 17982//17982 18467//18467 -f 18467//18467 17982//17982 17980//17980 -f 18467//18467 17980//17980 18466//18466 -f 18466//18466 17980//17980 17979//17979 -f 18466//18466 17979//17979 18478//18478 -f 18478//18478 17979//17979 18030//18030 -f 18478//18478 18030//18030 18027//18027 -f 18470//18470 17991//17991 18469//18469 -f 18469//18469 17991//17991 17988//17988 -f 18469//18469 17988//17988 18468//18468 -f 18468//18468 17988//17988 17985//17985 -f 18468//18468 17985//17985 17982//17982 -f 18006//18006 18003//18003 18472//18472 -f 18472//18472 18003//18003 18000//18000 -f 18472//18472 18000//18000 18471//18471 -f 18471//18471 18000//18000 17997//17997 -f 18471//18471 17997//17997 18470//18470 -f 18470//18470 17997//17997 17994//17994 -f 18470//18470 17994//17994 17991//17991 -f 18479//18479 18228//18228 18480//18480 -f 18480//18480 18228//18228 18225//18225 -f 18480//18480 18225//18225 18481//18481 -f 18481//18481 18225//18225 18224//18224 -f 18481//18481 18224//18224 18482//18482 -f 18482//18482 18224//18224 18246//18246 -f 18482//18482 18246//18246 18483//18483 -f 18483//18483 18246//18246 18240//18240 -f 18483//18483 18240//18240 18484//18484 -f 18484//18484 18240//18240 18251//18251 -f 18484//18484 18251//18251 18485//18485 -f 18485//18485 18251//18251 18238//18238 -f 18485//18485 18238//18238 18486//18486 -f 18486//18486 18238//18238 18236//18236 -f 18486//18486 18236//18236 18487//18487 -f 18487//18487 18236//18236 18235//18235 -f 18487//18487 18235//18235 18488//18488 -f 18488//18488 18235//18235 18234//18234 -f 18488//18488 18234//18234 18489//18489 -f 18489//18489 18234//18234 18232//18232 -f 18489//18489 18232//18232 18490//18490 -f 18490//18490 18232//18232 18230//18230 -f 18490//18490 18230//18230 18479//18479 -f 18479//18479 18230//18230 18228//18228 -f 18484//18484 18491//18491 18483//18483 -f 18483//18483 18491//18491 18492//18492 -f 18483//18483 18492//18492 18482//18482 -f 18482//18482 18492//18492 18493//18493 -f 18482//18482 18493//18493 18481//18481 -f 18481//18481 18493//18493 18494//18494 -f 18481//18481 18494//18494 18480//18480 -f 18480//18480 18494//18494 18495//18495 -f 18480//18480 18495//18495 18479//18479 -f 18479//18479 18495//18495 18496//18496 -f 18479//18479 18496//18496 18490//18490 -f 18490//18490 18496//18496 18497//18497 -f 18490//18490 18497//18497 18489//18489 -f 18489//18489 18497//18497 18498//18498 -f 18489//18489 18498//18498 18488//18488 -f 18488//18488 18498//18498 18499//18499 -f 18488//18488 18499//18499 18487//18487 -f 18487//18487 18499//18499 18500//18500 -f 18487//18487 18500//18500 18486//18486 -f 18486//18486 18500//18500 18501//18501 -f 18486//18486 18501//18501 18485//18485 -f 18485//18485 18501//18501 18502//18502 -f 18485//18485 18502//18502 18484//18484 -f 18484//18484 18502//18502 18491//18491 -f 18492//18492 18123//18123 18493//18493 -f 18493//18493 18123//18123 18124//18124 -f 18493//18493 18124//18124 18494//18494 -f 18494//18494 18124//18124 18142//18142 -f 18494//18494 18142//18142 18495//18495 -f 18495//18495 18142//18142 18140//18140 -f 18495//18495 18140//18140 18496//18496 -f 18496//18496 18140//18140 18138//18138 -f 18496//18496 18138//18138 18497//18497 -f 18497//18497 18138//18138 18136//18136 -f 18497//18497 18136//18136 18498//18498 -f 18498//18498 18136//18136 18134//18134 -f 18498//18498 18134//18134 18499//18499 -f 18499//18499 18134//18134 18132//18132 -f 18499//18499 18132//18132 18500//18500 -f 18500//18500 18132//18132 18131//18131 -f 18500//18500 18131//18131 18501//18501 -f 18501//18501 18131//18131 18130//18130 -f 18501//18501 18130//18130 18502//18502 -f 18502//18502 18130//18130 18128//18128 -f 18502//18502 18128//18128 18491//18491 -f 18491//18491 18128//18128 18126//18126 -f 18491//18491 18126//18126 18492//18492 -f 18492//18492 18126//18126 18123//18123 -f 18503//18503 18321//18321 18504//18504 -f 18504//18504 18321//18321 18331//18331 -f 18504//18504 18331//18331 18505//18505 -f 18505//18505 18331//18331 18333//18333 -f 18505//18505 18333//18333 18506//18506 -f 18506//18506 18333//18333 18318//18318 -f 18506//18506 18318//18318 18507//18507 -f 18507//18507 18318//18318 18330//18330 -f 18507//18507 18330//18330 18508//18508 -f 18508//18508 18330//18330 18329//18329 -f 18508//18508 18329//18329 18509//18509 -f 18509//18509 18329//18329 18328//18328 -f 18509//18509 18328//18328 18510//18510 -f 18510//18510 18328//18328 18326//18326 -f 18510//18510 18326//18326 18511//18511 -f 18511//18511 18326//18326 18325//18325 -f 18511//18511 18325//18325 18512//18512 -f 18512//18512 18325//18325 18316//18316 -f 18512//18512 18316//18316 18513//18513 -f 18513//18513 18316//18316 18312//18312 -f 18513//18513 18312//18312 18514//18514 -f 18514//18514 18312//18312 18311//18311 -f 18514//18514 18311//18311 18503//18503 -f 18503//18503 18311//18311 18321//18321 -f 18508//18508 18515//18515 18507//18507 -f 18507//18507 18515//18515 18516//18516 -f 18507//18507 18516//18516 18506//18506 -f 18506//18506 18516//18516 18517//18517 -f 18506//18506 18517//18517 18505//18505 -f 18505//18505 18517//18517 18518//18518 -f 18505//18505 18518//18518 18504//18504 -f 18504//18504 18518//18518 18519//18519 -f 18504//18504 18519//18519 18503//18503 -f 18503//18503 18519//18519 18520//18520 -f 18503//18503 18520//18520 18514//18514 -f 18514//18514 18520//18520 18521//18521 -f 18514//18514 18521//18521 18513//18513 -f 18513//18513 18521//18521 18522//18522 -f 18513//18513 18522//18522 18512//18512 -f 18512//18512 18522//18522 18523//18523 -f 18512//18512 18523//18523 18511//18511 -f 18511//18511 18523//18523 18524//18524 -f 18511//18511 18524//18524 18510//18510 -f 18510//18510 18524//18524 18525//18525 -f 18510//18510 18525//18525 18509//18509 -f 18509//18509 18525//18525 18526//18526 -f 18509//18509 18526//18526 18508//18508 -f 18508//18508 18526//18526 18515//18515 -f 18516//18516 18101//18101 18517//18517 -f 18517//18517 18101//18101 18100//18100 -f 18517//18517 18100//18100 18518//18518 -f 18518//18518 18100//18100 18109//18109 -f 18518//18518 18109//18109 18519//18519 -f 18519//18519 18109//18109 18096//18096 -f 18519//18519 18096//18096 18520//18520 -f 18520//18520 18096//18096 18099//18099 -f 18520//18520 18099//18099 18521//18521 -f 18521//18521 18099//18099 18098//18098 -f 18521//18521 18098//18098 18522//18522 -f 18522//18522 18098//18098 18106//18106 -f 18522//18522 18106//18106 18523//18523 -f 18523//18523 18106//18106 18105//18105 -f 18523//18523 18105//18105 18524//18524 -f 18524//18524 18105//18105 18104//18104 -f 18524//18524 18104//18104 18525//18525 -f 18525//18525 18104//18104 18094//18094 -f 18525//18525 18094//18094 18526//18526 -f 18526//18526 18094//18094 18090//18090 -f 18526//18526 18090//18090 18515//18515 -f 18515//18515 18090//18090 18089//18089 -f 18515//18515 18089//18089 18516//18516 -f 18516//18516 18089//18089 18101//18101 -f 18527//18527 18303//18303 18528//18528 -f 18528//18528 18303//18303 18297//18297 -f 18528//18528 18297//18297 18529//18529 -f 18529//18529 18297//18297 18292//18292 -f 18529//18529 18292//18292 18530//18530 -f 18530//18530 18292//18292 18290//18290 -f 18530//18530 18290//18290 18531//18531 -f 18531//18531 18290//18290 18288//18288 -f 18531//18531 18288//18288 18532//18532 -f 18532//18532 18288//18288 18286//18286 -f 18532//18532 18286//18286 18533//18533 -f 18533//18533 18286//18286 18284//18284 -f 18533//18533 18284//18284 18534//18534 -f 18534//18534 18284//18284 18282//18282 -f 18534//18534 18282//18282 18535//18535 -f 18535//18535 18282//18282 18280//18280 -f 18535//18535 18280//18280 18536//18536 -f 18536//18536 18280//18280 18277//18277 -f 18536//18536 18277//18277 18537//18537 -f 18537//18537 18277//18277 18276//18276 -f 18537//18537 18276//18276 18538//18538 -f 18538//18538 18276//18276 18301//18301 -f 18538//18538 18301//18301 18527//18527 -f 18527//18527 18301//18301 18303//18303 -f 18532//18532 18539//18539 18531//18531 -f 18531//18531 18539//18539 18540//18540 -f 18531//18531 18540//18540 18530//18530 -f 18530//18530 18540//18540 18541//18541 -f 18530//18530 18541//18541 18529//18529 -f 18529//18529 18541//18541 18542//18542 -f 18529//18529 18542//18542 18528//18528 -f 18528//18528 18542//18542 18543//18543 -f 18528//18528 18543//18543 18527//18527 -f 18527//18527 18543//18543 18544//18544 -f 18527//18527 18544//18544 18538//18538 -f 18538//18538 18544//18544 18545//18545 -f 18538//18538 18545//18545 18537//18537 -f 18537//18537 18545//18545 18546//18546 -f 18537//18537 18546//18546 18536//18536 -f 18536//18536 18546//18546 18547//18547 -f 18536//18536 18547//18547 18535//18535 -f 18535//18535 18547//18547 18548//18548 -f 18535//18535 18548//18548 18534//18534 -f 18534//18534 18548//18548 18549//18549 -f 18534//18534 18549//18549 18533//18533 -f 18533//18533 18549//18549 18550//18550 -f 18533//18533 18550//18550 18532//18532 -f 18532//18532 18550//18550 18539//18539 -f 18540//18540 18083//18083 18541//18541 -f 18541//18541 18083//18083 18081//18081 -f 18541//18541 18081//18081 18542//18542 -f 18542//18542 18081//18081 18080//18080 -f 18542//18542 18080//18080 18543//18543 -f 18543//18543 18080//18080 18068//18068 -f 18543//18543 18068//18068 18544//18544 -f 18544//18544 18068//18068 18067//18067 -f 18544//18544 18067//18067 18545//18545 -f 18545//18545 18067//18067 18077//18077 -f 18545//18545 18077//18077 18546//18546 -f 18546//18546 18077//18077 18058//18058 -f 18546//18546 18058//18058 18547//18547 -f 18547//18547 18058//18058 18057//18057 -f 18547//18547 18057//18057 18548//18548 -f 18548//18548 18057//18057 18045//18045 -f 18548//18548 18045//18045 18549//18549 -f 18549//18549 18045//18045 18088//18088 -f 18549//18549 18088//18088 18550//18550 -f 18550//18550 18088//18088 18087//18087 -f 18550//18550 18087//18087 18539//18539 -f 18539//18539 18087//18087 18085//18085 -f 18539//18539 18085//18085 18540//18540 -f 18540//18540 18085//18085 18083//18083 -f 18551//18551 18267//18267 18552//18552 -f 18552//18552 18267//18267 18273//18273 -f 18552//18552 18273//18273 18553//18553 -f 18553//18553 18273//18273 18272//18272 -f 18553//18553 18272//18272 18554//18554 -f 18554//18554 18272//18272 18270//18270 -f 18554//18554 18270//18270 18555//18555 -f 18555//18555 18270//18270 18264//18264 -f 18555//18555 18264//18264 18556//18556 -f 18556//18556 18264//18264 18262//18262 -f 18556//18556 18262//18262 18557//18557 -f 18557//18557 18262//18262 18261//18261 -f 18557//18557 18261//18261 18558//18558 -f 18558//18558 18261//18261 18256//18256 -f 18558//18558 18256//18256 18559//18559 -f 18559//18559 18256//18256 18258//18258 -f 18559//18559 18258//18258 18560//18560 -f 18560//18560 18258//18258 18248//18248 -f 18560//18560 18248//18248 18561//18561 -f 18561//18561 18248//18248 18247//18247 -f 18561//18561 18247//18247 18562//18562 -f 18562//18562 18247//18247 18265//18265 -f 18562//18562 18265//18265 18551//18551 -f 18551//18551 18265//18265 18267//18267 -f 18556//18556 18563//18563 18555//18555 -f 18555//18555 18563//18563 18564//18564 -f 18555//18555 18564//18564 18554//18554 -f 18554//18554 18564//18564 18565//18565 -f 18554//18554 18565//18565 18553//18553 -f 18553//18553 18565//18565 18566//18566 -f 18553//18553 18566//18566 18552//18552 -f 18552//18552 18566//18566 18567//18567 -f 18552//18552 18567//18567 18551//18551 -f 18551//18551 18567//18567 18568//18568 -f 18551//18551 18568//18568 18562//18562 -f 18562//18562 18568//18568 18569//18569 -f 18562//18562 18569//18569 18561//18561 -f 18561//18561 18569//18569 18570//18570 -f 18561//18561 18570//18570 18560//18560 -f 18560//18560 18570//18570 18571//18571 -f 18560//18560 18571//18571 18559//18559 -f 18559//18559 18571//18571 18572//18572 -f 18559//18559 18572//18572 18558//18558 -f 18558//18558 18572//18572 18573//18573 -f 18558//18558 18573//18573 18557//18557 -f 18557//18557 18573//18573 18574//18574 -f 18557//18557 18574//18574 18556//18556 -f 18556//18556 18574//18574 18563//18563 -f 18564//18564 18049//18049 18565//18565 -f 18565//18565 18049//18049 18051//18051 -f 18565//18565 18051//18051 18566//18566 -f 18566//18566 18051//18051 18053//18053 -f 18566//18566 18053//18053 18567//18567 -f 18567//18567 18053//18053 18042//18042 -f 18567//18567 18042//18042 18568//18568 -f 18568//18568 18042//18042 18040//18040 -f 18568//18568 18040//18040 18569//18569 -f 18569//18569 18040//18040 18039//18039 -f 18569//18569 18039//18039 18570//18570 -f 18570//18570 18039//18039 18048//18048 -f 18570//18570 18048//18048 18571//18571 -f 18571//18571 18048//18048 18047//18047 -f 18571//18571 18047//18047 18572//18572 -f 18572//18572 18047//18047 18072//18072 -f 18572//18572 18072//18072 18573//18573 -f 18573//18573 18072//18072 18066//18066 -f 18573//18573 18066//18066 18574//18574 -f 18574//18574 18066//18066 18063//18063 -f 18574//18574 18063//18063 18563//18563 -f 18563//18563 18063//18063 18054//18054 -f 18563//18563 18054//18054 18564//18564 -f 18564//18564 18054//18054 18049//18049 -f 18059//18059 18079//18079 18010//18010 -f 18010//18010 18014//18014 18059//18059 -f 18059//18059 18014//18014 18013//18013 -f 18059//18059 18013//18013 18043//18043 -f 18043//18043 18013//18013 18017//18017 -f 18043//18043 18017//18017 18107//18107 -f 18107//18107 18017//18017 18016//18016 -f 18107//18107 18016//18016 18108//18108 -f 18016//18016 18020//18020 18108//18108 -f 18108//18108 18020//18020 18019//18019 -f 18108//18108 18019//18019 18110//18110 -f 18019//18019 18023//18023 18110//18110 -f 18110//18110 18023//18023 18022//18022 -f 18110//18110 18022//18022 18111//18111 -f 18022//18022 18026//18026 18111//18111 -f 18111//18111 18026//18026 18025//18025 -f 18111//18111 18025//18025 18095//18095 -f 18025//18025 18029//18029 18095//18095 -f 18095//18095 18029//18029 18028//18028 -f 18095//18095 18028//18028 18038//18038 -f 18038//18038 18028//18028 18115//18115 -f 18115//18115 18028//18028 18032//18032 -f 18115//18115 18032//18032 18129//18129 -f 18129//18129 18032//18032 18031//18031 -f 18129//18129 18031//18031 18127//18127 -f 18031//18031 18035//18035 18127//18127 -f 18127//18127 18035//18035 18034//18034 -f 18127//18127 18034//18034 18125//18125 -f 18125//18125 18034//18034 18033//18033 -f 18125//18125 18033//18033 18121//18121 -f 18033//18033 17981//17981 18121//18121 -f 18121//18121 17981//17981 17984//17984 -f 18121//18121 17984//17984 18122//18122 -f 17984//17984 17983//17983 18122//18122 -f 18122//18122 17983//17983 17987//17987 -f 18122//18122 17987//17987 18046//18046 -f 18046//18046 17987//17987 17986//17986 -f 18046//18046 17986//17986 18074//18074 -f 18074//18074 17986//17986 17990//17990 -f 18074//18074 17990//17990 18073//18073 -f 17990//17990 17989//17989 18073//18073 -f 18073//18073 17989//17989 17993//17993 -f 18073//18073 17993//17993 18071//18071 -f 17993//17993 17992//17992 18071//18071 -f 18071//18071 17992//17992 17996//17996 -f 18071//18071 17996//17996 18070//18070 -f 17996//17996 17995//17995 18070//18070 -f 18070//18070 17995//17995 17999//17999 -f 18070//18070 17999//17999 18069//18069 -f 17999//17999 17998//17998 18069//18069 -f 18069//18069 17998//17998 18002//18002 -f 18069//18069 18002//18002 18075//18075 -f 18002//18002 18001//18001 18075//18075 -f 18075//18075 18001//18001 18005//18005 -f 18075//18075 18005//18005 18076//18076 -f 18005//18005 18004//18004 18076//18076 -f 18076//18076 18004//18004 18008//18008 -f 18076//18076 18008//18008 18078//18078 -f 18078//18078 18008//18008 18007//18007 -f 18078//18078 18007//18007 18079//18079 -f 18079//18079 18007//18007 18011//18011 -f 18079//18079 18011//18011 18010//18010 -f 18407//18407 18363//18363 18362//18362 -f 18407//18407 18362//18362 18409//18409 -f 18409//18409 18362//18362 18361//18361 -f 18409//18409 18361//18361 18411//18411 -f 18361//18361 18360//18360 18411//18411 -f 18411//18411 18360//18360 18359//18359 -f 18411//18411 18359//18359 18412//18412 -f 18359//18359 18358//18358 18412//18412 -f 18412//18412 18358//18358 18357//18357 -f 18412//18412 18357//18357 18400//18400 -f 18357//18357 18356//18356 18400//18400 -f 18400//18400 18356//18356 18355//18355 -f 18400//18400 18355//18355 18402//18402 -f 18355//18355 18354//18354 18402//18402 -f 18402//18402 18354//18354 18353//18353 -f 18402//18402 18353//18353 18404//18404 -f 18404//18404 18353//18353 18352//18352 -f 18352//18352 18351//18351 18404//18404 -f 18404//18404 18351//18351 18350//18350 -f 18404//18404 18350//18350 18405//18405 -f 18350//18350 18349//18349 18405//18405 -f 18405//18405 18349//18349 18348//18348 -f 18405//18405 18348//18348 18393//18393 -f 18393//18393 18348//18348 18347//18347 -f 18393//18393 18347//18347 18395//18395 -f 18347//18347 18346//18346 18395//18395 -f 18395//18395 18346//18346 18345//18345 -f 18395//18395 18345//18345 18397//18397 -f 18345//18345 18344//18344 18397//18397 -f 18397//18397 18344//18344 18343//18343 -f 18397//18397 18343//18343 18398//18398 -f 18343//18343 18342//18342 18398//18398 -f 18398//18398 18342//18342 18341//18341 -f 18398//18398 18341//18341 18389//18389 -f 18341//18341 18340//18340 18389//18389 -f 18389//18389 18340//18340 18339//18339 -f 18389//18389 18339//18339 18413//18413 -f 18413//18413 18339//18339 18388//18388 -f 18413//18413 18388//18388 18414//18414 -f 18388//18388 18387//18387 18414//18414 -f 18414//18414 18387//18387 18386//18386 -f 18414//18414 18386//18386 18416//18416 -f 18416//18416 18386//18386 18385//18385 -f 18416//18416 18385//18385 18418//18418 -f 18385//18385 18384//18384 18418//18418 -f 18418//18418 18384//18384 18383//18383 -f 18418//18418 18383//18383 18427//18427 -f 18427//18427 18383//18383 18382//18382 -f 18382//18382 18381//18381 18427//18427 -f 18427//18427 18381//18381 18380//18380 -f 18427//18427 18380//18380 18428//18428 -f 18428//18428 18380//18380 18379//18379 -f 18428//18428 18379//18379 18430//18430 -f 18379//18379 18378//18378 18430//18430 -f 18430//18430 18378//18378 18377//18377 -f 18430//18430 18377//18377 18432//18432 -f 18377//18377 18376//18376 18432//18432 -f 18432//18432 18376//18376 18375//18375 -f 18432//18432 18375//18375 18433//18433 -f 18375//18375 18374//18374 18433//18433 -f 18433//18433 18374//18374 18373//18373 -f 18433//18433 18373//18373 18421//18421 -f 18373//18373 18372//18372 18421//18421 -f 18421//18421 18372//18372 18371//18371 -f 18421//18421 18371//18371 18423//18423 -f 18423//18423 18371//18371 18370//18370 -f 18370//18370 18369//18369 18423//18423 -f 18423//18423 18369//18369 18368//18368 -f 18423//18423 18368//18368 18425//18425 -f 18368//18368 18367//18367 18425//18425 -f 18425//18425 18367//18367 18366//18366 -f 18425//18425 18366//18366 18426//18426 -f 18426//18426 18366//18366 18365//18365 -f 18426//18426 18365//18365 18407//18407 -f 18407//18407 18365//18365 18364//18364 -f 18407//18407 18364//18364 18363//18363 -f 18231//18231 18233//18233 18220//18220 -f 18170//18170 18269//18269 18168//18168 -f 18168//18168 18269//18269 18268//18268 -f 18168//18168 18268//18268 18166//18166 -f 18166//18166 18268//18268 18274//18274 -f 18166//18166 18274//18274 18164//18164 -f 18164//18164 18274//18274 18275//18275 -f 18164//18164 18275//18275 18162//18162 -f 18162//18162 18275//18275 18266//18266 -f 18162//18162 18266//18266 18160//18160 -f 18160//18160 18266//18266 18245//18245 -f 18160//18160 18245//18245 18158//18158 -f 18158//18158 18245//18245 18244//18244 -f 18158//18158 18244//18244 18156//18156 -f 18156//18156 18244//18244 18243//18243 -f 18156//18156 18243//18243 18154//18154 -f 18154//18154 18243//18243 18226//18226 -f 18154//18154 18226//18226 18152//18152 -f 18152//18152 18226//18226 18227//18227 -f 18152//18152 18227//18227 18150//18150 -f 18150//18150 18227//18227 18229//18229 -f 18150//18150 18229//18229 18148//18148 -f 18148//18148 18229//18229 18231//18231 -f 18148//18148 18231//18231 18222//18222 -f 18222//18222 18231//18231 18220//18220 -f 18305//18305 18263//18263 18170//18170 -f 18170//18170 18263//18263 18271//18271 -f 18170//18170 18271//18271 18269//18269 -f 18233//18233 18320//18320 18220//18220 -f 18220//18220 18320//18320 18319//18319 -f 18220//18220 18319//18319 18218//18218 -f 18218//18218 18319//18319 18338//18338 -f 18218//18218 18338//18338 18216//18216 -f 18216//18216 18338//18338 18337//18337 -f 18216//18216 18337//18337 18214//18214 -f 18214//18214 18337//18337 18336//18336 -f 18214//18214 18336//18336 18212//18212 -f 18212//18212 18336//18336 18313//18313 -f 18212//18212 18313//18313 18210//18210 -f 18210//18210 18313//18313 18322//18322 -f 18210//18210 18322//18322 18208//18208 -f 18208//18208 18322//18322 18315//18315 -f 18208//18208 18315//18315 18206//18206 -f 18206//18206 18315//18315 18314//18314 -f 18206//18206 18314//18314 18204//18204 -f 18204//18204 18314//18314 18327//18327 -f 18204//18204 18327//18327 18202//18202 -f 18202//18202 18327//18327 18310//18310 -f 18202//18202 18310//18310 18200//18200 -f 18200//18200 18310//18310 18309//18309 -f 18200//18200 18309//18309 18198//18198 -f 18198//18198 18309//18309 18308//18308 -f 18198//18198 18308//18308 18196//18196 -f 18196//18196 18308//18308 18307//18307 -f 18196//18196 18307//18307 18194//18194 -f 18194//18194 18307//18307 18306//18306 -f 18194//18194 18306//18306 18192//18192 -f 18192//18192 18306//18306 18281//18281 -f 18192//18192 18281//18281 18190//18190 -f 18190//18190 18281//18281 18283//18283 -f 18190//18190 18283//18283 18188//18188 -f 18188//18188 18283//18283 18285//18285 -f 18188//18188 18285//18285 18186//18186 -f 18186//18186 18285//18285 18287//18287 -f 18186//18186 18287//18287 18184//18184 -f 18184//18184 18287//18287 18289//18289 -f 18184//18184 18289//18289 18182//18182 -f 18182//18182 18289//18289 18291//18291 -f 18182//18182 18291//18291 18180//18180 -f 18180//18180 18291//18291 18293//18293 -f 18180//18180 18293//18293 18178//18178 -f 18178//18178 18293//18293 18296//18296 -f 18178//18178 18296//18296 18176//18176 -f 18176//18176 18296//18296 18298//18298 -f 18176//18176 18298//18298 18174//18174 -f 18174//18174 18298//18298 18305//18305 -f 18174//18174 18305//18305 18172//18172 -f 18172//18172 18305//18305 18170//18170 -f 18165//18165 18052//18052 18167//18167 -f 18167//18167 18052//18052 18050//18050 -f 18167//18167 18050//18050 18169//18169 -f 18169//18169 18050//18050 18056//18056 -f 18169//18169 18056//18056 18171//18171 -f 18171//18171 18056//18056 18055//18055 -f 18171//18171 18055//18055 18173//18173 -f 18173//18173 18055//18055 18065//18065 -f 18173//18173 18065//18065 18175//18175 -f 18175//18175 18065//18065 18064//18064 -f 18175//18175 18064//18064 18177//18177 -f 18177//18177 18064//18064 18062//18062 -f 18177//18177 18062//18062 18179//18179 -f 18179//18179 18062//18062 18061//18061 -f 18179//18179 18061//18061 18181//18181 -f 18181//18181 18061//18061 18082//18082 -f 18181//18181 18082//18082 18183//18183 -f 18183//18183 18082//18082 18084//18084 -f 18183//18183 18084//18084 18185//18185 -f 18185//18185 18084//18084 18086//18086 -f 18185//18185 18086//18086 18187//18187 -f 18187//18187 18086//18086 18044//18044 -f 18187//18187 18044//18044 18189//18189 -f 18044//18044 18102//18102 18189//18189 -f 18189//18189 18102//18102 18103//18103 -f 18189//18189 18103//18103 18191//18191 -f 18191//18191 18103//18103 18114//18114 -f 18191//18191 18114//18114 18193//18193 -f 18193//18193 18114//18114 18113//18113 -f 18193//18193 18113//18113 18195//18195 -f 18195//18195 18113//18113 18112//18112 -f 18195//18195 18112//18112 18197//18197 -f 18197//18197 18112//18112 18091//18091 -f 18197//18197 18091//18091 18199//18199 -f 18199//18199 18091//18091 18097//18097 -f 18199//18199 18097//18097 18201//18201 -f 18201//18201 18097//18097 18093//18093 -f 18201//18201 18093//18093 18203//18203 -f 18203//18203 18093//18093 18092//18092 -f 18203//18203 18092//18092 18205//18205 -f 18205//18205 18092//18092 18037//18037 -f 18205//18205 18037//18037 18207//18207 -f 18207//18207 18037//18037 18036//18036 -f 18207//18207 18036//18036 18209//18209 -f 18209//18209 18036//18036 18120//18120 -f 18209//18209 18120//18120 18211//18211 -f 18211//18211 18120//18120 18119//18119 -f 18211//18211 18119//18119 18213//18213 -f 18213//18213 18119//18119 18118//18118 -f 18213//18213 18118//18118 18215//18215 -f 18215//18215 18118//18118 18117//18117 -f 18215//18215 18117//18117 18217//18217 -f 18217//18217 18117//18117 18116//18116 -f 18217//18217 18116//18116 18219//18219 -f 18219//18219 18116//18116 18133//18133 -f 18219//18219 18133//18133 18221//18221 -f 18221//18221 18133//18133 18135//18135 -f 18221//18221 18135//18135 18223//18223 -f 18223//18223 18135//18135 18137//18137 -f 18223//18223 18137//18137 18149//18149 -f 18149//18149 18137//18137 18139//18139 -f 18149//18149 18139//18139 18151//18151 -f 18151//18151 18139//18139 18141//18141 -f 18151//18151 18141//18141 18153//18153 -f 18153//18153 18141//18141 18147//18147 -f 18153//18153 18147//18147 18155//18155 -f 18155//18155 18147//18147 18146//18146 -f 18155//18155 18146//18146 18157//18157 -f 18157//18157 18146//18146 18145//18145 -f 18157//18157 18145//18145 18159//18159 -f 18159//18159 18145//18145 18144//18144 -f 18159//18159 18144//18144 18161//18161 -f 18161//18161 18144//18144 18143//18143 -f 18161//18161 18143//18143 18163//18163 -f 18163//18163 18143//18143 18041//18041 -f 18163//18163 18041//18041 18165//18165 -f 18165//18165 18041//18041 18060//18060 -f 18165//18165 18060//18060 18052//18052 -# 38384 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_motori_drzaci.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_motori_drzaci.obj deleted file mode 100644 index 3303fe05b..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_motori_drzaci.obj +++ /dev/null @@ -1,21124 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object robot_motori_drzaci.obj -# -# Vertices: 5180 -# Faces: 10748 -# -#### -vn -0.760789 0.000000 -0.648999 -v 0.026280 -0.007250 0.069050 -vn 0.760789 0.000000 -0.648999 -v 0.034750 -0.007250 0.069050 -vn -0.760788 0.281590 -0.584729 -v 0.026280 -0.008313 0.068807 -vn 0.760788 0.281590 -0.584729 -v 0.034750 -0.008313 0.068807 -vn -0.760789 0.507408 -0.404645 -v 0.026280 -0.009165 0.068128 -vn 0.760789 0.507408 -0.404645 -v 0.034750 -0.009165 0.068128 -vn -0.760788 0.632729 -0.144416 -v 0.026280 -0.009639 0.067145 -vn 0.760788 0.632728 -0.144416 -v 0.034750 -0.009639 0.067145 -vn -0.760789 0.632728 0.144416 -v 0.026280 -0.009639 0.066055 -vn 0.760788 0.632729 0.144416 -v 0.034750 -0.009639 0.066055 -vn -0.760789 0.507408 0.404645 -v 0.026280 -0.009165 0.065072 -vn 0.760789 0.507408 0.404645 -v 0.034750 -0.009165 0.065072 -vn -0.760788 0.281590 0.584729 -v 0.026280 -0.008313 0.064393 -vn 0.760788 0.281590 0.584729 -v 0.034750 -0.008313 0.064393 -vn -0.760789 -0.000000 0.648999 -v 0.026280 -0.007250 0.064150 -vn 0.760789 0.000000 0.648999 -v 0.034750 -0.007250 0.064150 -vn -0.760788 -0.281590 0.584729 -v 0.026280 -0.006187 0.064393 -vn 0.760788 -0.281590 0.584729 -v 0.034750 -0.006187 0.064393 -vn -0.760789 -0.507408 0.404645 -v 0.026280 -0.005335 0.065072 -vn 0.760789 -0.507408 0.404645 -v 0.034750 -0.005335 0.065072 -vn -0.760787 -0.632729 0.144416 -v 0.026280 -0.004861 0.066055 -vn 0.760789 -0.632728 0.144416 -v 0.034750 -0.004861 0.066055 -vn -0.760789 -0.632728 -0.144416 -v 0.026280 -0.004861 0.067145 -vn 0.760789 -0.632728 -0.144416 -v 0.034750 -0.004861 0.067145 -vn -0.760789 -0.507408 -0.404645 -v 0.026280 -0.005335 0.068128 -vn 0.760789 -0.507408 -0.404645 -v 0.034750 -0.005335 0.068128 -vn -0.760788 -0.281590 -0.584729 -v 0.026280 -0.006187 0.068807 -vn 0.760788 -0.281590 -0.584729 -v 0.034750 -0.006187 0.068807 -vn 0.685696 0.724383 0.071346 -v 0.034750 0.025000 0.070961 -vn 0.685697 0.724383 -0.071346 -v 0.034750 0.025000 0.062239 -vn -0.685696 0.724383 0.071346 -v 0.026280 0.025000 0.070961 -vn -0.685696 0.724383 -0.071346 -v 0.026280 0.025000 0.062239 -vn -0.685696 0.071347 0.724383 -v 0.026280 0.023000 0.072961 -vn 0.685696 0.071347 0.724383 -v 0.034750 0.023000 0.072961 -vn 0.665720 0.285560 0.689400 -v 0.034750 0.023765 0.072809 -vn -0.665720 0.285560 0.689400 -v 0.026280 0.023765 0.072809 -vn 0.665718 0.527645 0.527646 -v 0.034750 0.024414 0.072375 -vn -0.665718 0.527645 0.527646 -v 0.026280 0.024414 0.072375 -vn 0.665719 0.689401 0.285559 -v 0.034750 0.024848 0.071726 -vn -0.665719 0.689401 0.285559 -v 0.026280 0.024848 0.071726 -vn 0.685696 -0.071347 0.724383 -v 0.034750 -0.023000 0.072961 -vn -0.685696 -0.071347 0.724383 -v 0.026280 -0.023000 0.072961 -vn -0.685696 -0.724383 0.071347 -v 0.026280 -0.025000 0.070961 -vn 0.685696 -0.724383 0.071347 -v 0.034750 -0.025000 0.070961 -vn 0.665720 -0.689401 0.285559 -v 0.034750 -0.024848 0.071726 -vn -0.665720 -0.689401 0.285559 -v 0.026280 -0.024848 0.071726 -vn 0.665718 -0.527646 0.527646 -v 0.034750 -0.024414 0.072375 -vn -0.665718 -0.527646 0.527646 -v 0.026280 -0.024414 0.072375 -vn 0.665720 -0.285559 0.689401 -v 0.034750 -0.023765 0.072809 -vn -0.665720 -0.285559 0.689401 -v 0.026280 -0.023765 0.072809 -vn 0.685696 -0.724383 -0.071347 -v 0.034750 -0.025000 0.062239 -vn -0.685696 -0.724383 -0.071347 -v 0.026280 -0.025000 0.062239 -vn -0.685696 -0.071346 -0.724383 -v 0.026280 -0.023000 0.060239 -vn 0.685696 -0.071346 -0.724383 -v 0.034750 -0.023000 0.060239 -vn 0.665719 -0.285559 -0.689401 -v 0.034750 -0.023765 0.060391 -vn -0.665719 -0.285559 -0.689401 -v 0.026280 -0.023765 0.060391 -vn 0.665718 -0.527646 -0.527645 -v 0.034750 -0.024414 0.060825 -vn -0.665718 -0.527646 -0.527645 -v 0.026280 -0.024414 0.060825 -vn 0.665720 -0.689400 -0.285560 -v 0.034750 -0.024848 0.061474 -vn -0.665720 -0.689400 -0.285560 -v 0.026280 -0.024848 0.061474 -vn 0.685696 0.071346 -0.724383 -v 0.034750 0.023000 0.060239 -vn -0.685696 0.071346 -0.724384 -v 0.026280 0.023000 0.060239 -vn 0.665719 0.689401 -0.285560 -v 0.034750 0.024848 0.061474 -vn -0.665719 0.689401 -0.285560 -v 0.026280 0.024848 0.061474 -vn 0.665719 0.527645 -0.527645 -v 0.034750 0.024414 0.060825 -vn -0.665719 0.527645 -0.527645 -v 0.026280 0.024414 0.060825 -vn 0.665719 0.285560 -0.689401 -v 0.034750 0.023765 0.060391 -vn -0.665719 0.285560 -0.689401 -v 0.026280 0.023765 0.060391 -vn 0.760789 0.000000 -0.648999 -v 0.034750 0.007250 0.069050 -vn 0.760788 0.281590 -0.584729 -v 0.034750 0.006187 0.068807 -vn 0.760788 0.281590 0.584729 -v 0.034750 0.006187 0.064393 -vn 0.760789 -0.000000 0.648999 -v 0.034750 0.007250 0.064150 -vn 0.760788 -0.281590 0.584729 -v 0.034750 0.008313 0.064393 -vn 0.760789 -0.632728 -0.144416 -v 0.034750 0.009639 0.067145 -vn 0.760789 -0.507408 -0.404645 -v 0.034750 0.009165 0.068128 -vn 0.760788 -0.281590 -0.584729 -v 0.034750 0.008313 0.068807 -vn 0.760789 0.632728 0.144416 -v 0.034750 0.004861 0.066055 -vn 0.760789 0.507408 0.404645 -v 0.034750 0.005335 0.065072 -vn 0.760789 -0.632728 0.144416 -v 0.034750 0.009639 0.066055 -vn 0.760789 -0.507408 0.404645 -v 0.034750 0.009165 0.065072 -vn 0.760789 0.507408 -0.404645 -v 0.034750 0.005335 0.068128 -vn 0.760789 0.632728 -0.144416 -v 0.034750 0.004861 0.067145 -vn -0.760789 -0.000000 -0.648999 -v 0.026280 0.007250 0.069050 -vn -0.760788 0.281590 -0.584729 -v 0.026280 0.006187 0.068807 -vn -0.760789 0.507408 -0.404645 -v 0.026280 0.005335 0.068128 -vn -0.760787 0.632729 -0.144416 -v 0.026280 0.004861 0.067145 -vn -0.760789 0.632728 0.144416 -v 0.026280 0.004861 0.066055 -vn -0.760789 0.507408 0.404645 -v 0.026280 0.005335 0.065072 -vn -0.760788 0.281590 0.584729 -v 0.026280 0.006187 0.064393 -vn -0.760789 -0.000000 0.648999 -v 0.026280 0.007250 0.064150 -vn -0.760788 -0.281590 0.584729 -v 0.026280 0.008313 0.064393 -vn -0.760789 -0.507408 0.404645 -v 0.026280 0.009165 0.065072 -vn -0.760789 -0.632728 0.144416 -v 0.026280 0.009639 0.066055 -vn -0.760788 -0.632729 -0.144416 -v 0.026280 0.009639 0.067145 -vn -0.760789 -0.507408 -0.404645 -v 0.026280 0.009165 0.068128 -vn -0.760788 -0.281591 -0.584730 -v 0.026280 0.008313 0.068807 -vn -0.770262 -0.637727 -0.000001 -v 0.016750 -0.127400 0.151700 -vn 0.770262 -0.637727 -0.000001 -v 0.018750 -0.127400 0.151700 -vn -0.770263 -0.552286 -0.318867 -v 0.016750 -0.127681 0.152750 -vn 0.770263 -0.552285 -0.318867 -v 0.018750 -0.127681 0.152750 -vn -0.770260 -0.318863 -0.552291 -v 0.016750 -0.128450 0.153519 -vn 0.770260 -0.318863 -0.552291 -v 0.018750 -0.128450 0.153519 -vn -0.770263 0.000000 -0.637727 -v 0.016750 -0.129500 0.153800 -vn 0.770263 -0.000000 -0.637727 -v 0.018750 -0.129500 0.153800 -vn -0.770260 0.318863 -0.552291 -v 0.016750 -0.130550 0.153519 -vn 0.770260 0.318863 -0.552291 -v 0.018750 -0.130550 0.153519 -vn -0.770264 0.552286 -0.318862 -v 0.016750 -0.131319 0.152750 -vn 0.770264 0.552286 -0.318862 -v 0.018750 -0.131319 0.152750 -vn -0.770259 0.637731 -0.000001 -v 0.016750 -0.131600 0.151700 -vn 0.770259 0.637732 -0.000001 -v 0.018750 -0.131600 0.151700 -vn -0.770265 0.552286 0.318861 -v 0.016750 -0.131319 0.150650 -vn 0.770265 0.552286 0.318861 -v 0.018750 -0.131319 0.150650 -vn -0.770260 0.318863 0.552291 -v 0.016750 -0.130550 0.149881 -vn 0.770260 0.318863 0.552291 -v 0.018750 -0.130550 0.149881 -vn -0.770263 -0.000000 0.637727 -v 0.016750 -0.129500 0.149600 -vn 0.770263 0.000000 0.637727 -v 0.018750 -0.129500 0.149600 -vn -0.770260 -0.318863 0.552291 -v 0.016750 -0.128450 0.149881 -vn 0.770260 -0.318863 0.552291 -v 0.018750 -0.128450 0.149881 -vn -0.770263 -0.552286 0.318866 -v 0.016750 -0.127681 0.150650 -vn 0.770263 -0.552286 0.318866 -v 0.018750 -0.127681 0.150650 -vn -0.770263 -0.637727 -0.000000 -v 0.016750 -0.127400 0.127700 -vn 0.770263 -0.637727 0.000000 -v 0.018750 -0.127400 0.127700 -vn -0.770261 -0.552288 -0.318865 -v 0.016750 -0.127681 0.128750 -vn 0.770261 -0.552288 -0.318865 -v 0.018750 -0.127681 0.128750 -vn -0.770261 -0.318865 -0.552288 -v 0.016750 -0.128450 0.129519 -vn 0.770261 -0.318865 -0.552288 -v 0.018750 -0.128450 0.129519 -vn -0.770263 0.000000 -0.637727 -v 0.016750 -0.129500 0.129800 -vn 0.770263 -0.000000 -0.637727 -v 0.018750 -0.129500 0.129800 -vn -0.770261 0.318865 -0.552289 -v 0.016750 -0.130550 0.129519 -vn 0.770261 0.318865 -0.552288 -v 0.018750 -0.130550 0.129519 -vn -0.770263 0.552289 -0.318860 -v 0.016750 -0.131319 0.128750 -vn 0.770263 0.552289 -0.318860 -v 0.018750 -0.131319 0.128750 -vn -0.770259 0.637731 0.000000 -v 0.016750 -0.131600 0.127700 -vn 0.770259 0.637731 -0.000000 -v 0.018750 -0.131600 0.127700 -vn -0.770263 0.552289 0.318860 -v 0.016750 -0.131319 0.126650 -vn 0.770263 0.552289 0.318860 -v 0.018750 -0.131319 0.126650 -vn -0.770261 0.318865 0.552288 -v 0.016750 -0.130550 0.125881 -vn 0.770261 0.318865 0.552288 -v 0.018750 -0.130550 0.125881 -vn -0.770263 -0.000000 0.637727 -v 0.016750 -0.129500 0.125600 -vn 0.770263 0.000000 0.637727 -v 0.018750 -0.129500 0.125600 -vn -0.770261 -0.318865 0.552289 -v 0.016750 -0.128450 0.125881 -vn 0.770261 -0.318865 0.552288 -v 0.018750 -0.128450 0.125881 -vn -0.770261 -0.552288 0.318865 -v 0.016750 -0.127681 0.126650 -vn 0.770261 -0.552288 0.318865 -v 0.018750 -0.127681 0.126650 -vn 0.770264 0.637725 -0.000000 -v 0.016750 -0.094750 0.131700 -vn -0.770264 0.637725 0.000000 -v 0.015750 -0.094750 0.131700 -vn 0.770259 0.552293 -0.318864 -v 0.016750 -0.094583 0.132325 -vn -0.770259 0.552293 -0.318864 -v 0.015750 -0.094583 0.132325 -vn 0.770266 0.318861 -0.552284 -v 0.016750 -0.094125 0.132783 -vn -0.770266 0.318861 -0.552284 -v 0.015750 -0.094125 0.132783 -vn 0.770258 -0.000001 -0.637732 -v 0.016750 -0.093500 0.132950 -vn -0.770258 -0.000001 -0.637732 -v 0.015750 -0.093500 0.132950 -vn 0.770266 -0.318862 -0.552284 -v 0.016750 -0.092875 0.132783 -vn -0.770266 -0.318862 -0.552284 -v 0.015750 -0.092875 0.132783 -vn 0.770259 -0.552293 -0.318864 -v 0.016750 -0.092417 0.132325 -vn -0.770259 -0.552293 -0.318864 -v 0.015750 -0.092417 0.132325 -vn 0.770264 -0.637725 0.000000 -v 0.016750 -0.092250 0.131700 -vn -0.770264 -0.637725 -0.000000 -v 0.015750 -0.092250 0.131700 -vn 0.770261 -0.552288 0.318867 -v 0.016750 -0.092417 0.131075 -vn -0.770261 -0.552288 0.318867 -v 0.015750 -0.092417 0.131075 -vn 0.770261 -0.318867 0.552288 -v 0.016750 -0.092875 0.130617 -vn -0.770261 -0.318867 0.552288 -v 0.015750 -0.092875 0.130617 -vn 0.770264 -0.000001 0.637725 -v 0.016750 -0.093500 0.130450 -vn -0.770264 -0.000001 0.637725 -v 0.015750 -0.093500 0.130450 -vn 0.770261 0.318866 0.552288 -v 0.016750 -0.094125 0.130617 -vn -0.770261 0.318866 0.552288 -v 0.015750 -0.094125 0.130617 -vn 0.770261 0.552288 0.318867 -v 0.016750 -0.094583 0.131075 -vn -0.770261 0.552288 0.318867 -v 0.015750 -0.094583 0.131075 -vn 0.770261 0.637728 -0.000000 -v 0.016750 -0.116000 0.126200 -vn -0.770261 0.637728 0.000000 -v 0.015750 -0.116000 0.126200 -vn 0.770263 0.552286 -0.318865 -v 0.016750 -0.115833 0.126825 -vn -0.770263 0.552286 -0.318865 -v 0.015750 -0.115833 0.126825 -vn 0.770260 0.318865 -0.552291 -v 0.016750 -0.115375 0.127283 -vn -0.770260 0.318866 -0.552291 -v 0.015750 -0.115375 0.127283 -vn 0.770264 0.000000 -0.637725 -v 0.016750 -0.114750 0.127450 -vn -0.770264 0.000000 -0.637725 -v 0.015750 -0.114750 0.127450 -vn 0.770260 -0.318865 -0.552291 -v 0.016750 -0.114125 0.127283 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 -0.114125 0.127283 -vn 0.770263 -0.552286 -0.318865 -v 0.016750 -0.113667 0.126825 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 -0.113667 0.126825 -vn 0.770261 -0.637728 0.000000 -v 0.016750 -0.113500 0.126200 -vn -0.770261 -0.637728 -0.000000 -v 0.015750 -0.113500 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.016750 -0.113667 0.125575 -vn -0.770261 -0.552291 0.318862 -v 0.015750 -0.113667 0.125575 -vn 0.770265 -0.318861 0.552286 -v 0.016750 -0.114125 0.125117 -vn -0.770265 -0.318861 0.552286 -v 0.015750 -0.114125 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.016750 -0.114750 0.124950 -vn -0.770258 -0.000000 0.637732 -v 0.015750 -0.114750 0.124950 -vn 0.770265 0.318861 0.552286 -v 0.016750 -0.115375 0.125117 -vn -0.770265 0.318861 0.552286 -v 0.015750 -0.115375 0.125117 -vn 0.770261 0.552291 0.318862 -v 0.016750 -0.115833 0.125575 -vn -0.770261 0.552291 0.318862 -v 0.015750 -0.115833 0.125575 -vn 0.770264 0.637725 -0.000000 -v 0.016750 -0.108000 0.126200 -vn -0.770264 0.637725 0.000000 -v 0.015750 -0.108000 0.126200 -vn 0.770261 0.552288 -0.318867 -v 0.016750 -0.107833 0.126825 -vn -0.770261 0.552288 -0.318867 -v 0.015750 -0.107833 0.126825 -vn 0.770261 0.318866 -0.552288 -v 0.016750 -0.107375 0.127283 -vn -0.770261 0.318866 -0.552288 -v 0.015750 -0.107375 0.127283 -vn 0.770264 0.000000 -0.637725 -v 0.016750 -0.106750 0.127450 -vn -0.770263 -0.000002 -0.637726 -v 0.015750 -0.106750 0.127450 -vn 0.770260 -0.318866 -0.552289 -v 0.016750 -0.106125 0.127283 -vn -0.770261 -0.318868 -0.552288 -v 0.015750 -0.106125 0.127283 -vn 0.770261 -0.552288 -0.318867 -v 0.016750 -0.105667 0.126825 -vn -0.770261 -0.552288 -0.318867 -v 0.015750 -0.105667 0.126825 -vn 0.770264 -0.637725 0.000000 -v 0.016750 -0.105500 0.126200 -vn -0.770264 -0.637725 -0.000000 -v 0.015750 -0.105500 0.126200 -vn 0.770259 -0.552293 0.318864 -v 0.016750 -0.105667 0.125575 -vn -0.770259 -0.552293 0.318864 -v 0.015750 -0.105667 0.125575 -vn 0.770265 -0.318862 0.552285 -v 0.016750 -0.106125 0.125117 -vn -0.770266 -0.318863 0.552284 -v 0.015750 -0.106125 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.016750 -0.106750 0.124950 -vn -0.770256 -0.000002 0.637735 -v 0.015750 -0.106750 0.124950 -vn 0.770266 0.318861 0.552284 -v 0.016750 -0.107375 0.125117 -vn -0.770266 0.318861 0.552284 -v 0.015750 -0.107375 0.125117 -vn 0.770259 0.552293 0.318864 -v 0.016750 -0.107833 0.125575 -vn -0.770259 0.552293 0.318864 -v 0.015750 -0.107833 0.125575 -vn 0.770261 0.637728 -0.000000 -v 0.016750 -0.100000 0.126200 -vn -0.770261 0.637728 0.000000 -v 0.015750 -0.100000 0.126200 -vn 0.770263 0.552286 -0.318865 -v 0.016750 -0.099833 0.126825 -vn -0.770263 0.552286 -0.318865 -v 0.015750 -0.099833 0.126825 -vn 0.770260 0.318865 -0.552291 -v 0.016750 -0.099375 0.127283 -vn -0.770260 0.318865 -0.552291 -v 0.015750 -0.099375 0.127283 -vn 0.770264 0.000001 -0.637725 -v 0.016750 -0.098750 0.127450 -vn -0.770264 0.000001 -0.637725 -v 0.015750 -0.098750 0.127450 -vn 0.770261 -0.318866 -0.552288 -v 0.016750 -0.098125 0.127283 -vn -0.770261 -0.318866 -0.552288 -v 0.015750 -0.098125 0.127283 -vn 0.770261 -0.552288 -0.318867 -v 0.016750 -0.097667 0.126825 -vn -0.770261 -0.552288 -0.318867 -v 0.015750 -0.097667 0.126825 -vn 0.770264 -0.637725 0.000000 -v 0.016750 -0.097500 0.126200 -vn -0.770264 -0.637725 -0.000000 -v 0.015750 -0.097500 0.126200 -vn 0.770259 -0.552293 0.318864 -v 0.016750 -0.097667 0.125575 -vn -0.770259 -0.552293 0.318864 -v 0.015750 -0.097667 0.125575 -vn 0.770266 -0.318861 0.552284 -v 0.016750 -0.098125 0.125117 -vn -0.770266 -0.318861 0.552284 -v 0.015750 -0.098125 0.125117 -vn 0.770258 0.000001 0.637732 -v 0.016750 -0.098750 0.124950 -vn -0.770258 0.000001 0.637732 -v 0.015750 -0.098750 0.124950 -vn 0.770265 0.318861 0.552286 -v 0.016750 -0.099375 0.125117 -vn -0.770265 0.318861 0.552286 -v 0.015750 -0.099375 0.125117 -vn 0.770261 0.552291 0.318862 -v 0.016750 -0.099833 0.125575 -vn -0.770261 0.552291 0.318862 -v 0.015750 -0.099833 0.125575 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.117375 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.111625 0.149550 -vn 1.000000 0.000000 -0.000000 -v 0.018750 -0.111625 0.150082 -vn 0.770258 -0.552295 -0.318862 -v 0.018750 -0.122721 0.132150 -vn 0.770263 -0.637726 0.000000 -v 0.018750 -0.122600 0.131700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.132700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.125900 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.125900 0.132700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.111625 0.129318 -vn 1.000000 0.000001 0.000001 -v 0.018750 -0.105675 0.129318 -vn 1.000000 0.000000 -0.000000 -v 0.018750 -0.105675 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.124132 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.117375 0.124132 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.117375 0.129318 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.124132 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.124132 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.129318 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.150082 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.149550 -vn 0.838628 0.000000 0.544704 -v 0.018750 -0.098750 0.123313 -vn 0.838628 0.471729 0.272352 -v 0.018750 -0.101250 0.124757 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.124132 -vn 0.838628 -0.471728 0.272353 -v 0.018750 -0.091000 0.146257 -vn 0.838627 -0.000000 0.544705 -v 0.018750 -0.093500 0.144813 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.093300 0.144250 -vn 0.770265 -0.318855 0.552289 -v 0.018750 -0.136550 0.144921 -vn 0.770256 -0.000000 0.637735 -v 0.018750 -0.137000 0.144800 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.144250 -vn 0.770261 -0.318866 0.552288 -v 0.018750 -0.136550 0.132921 -vn 0.770263 0.000000 0.637726 -v 0.018750 -0.137000 0.132800 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.132700 -vn 0.770256 -0.637735 -0.000000 -v 0.018750 -0.137600 0.130450 -vn 0.770268 -0.552283 0.318860 -v 0.018750 -0.137721 0.130000 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.129850 -vn 0.748360 0.331647 -0.574428 -v 0.018750 -0.132200 0.144377 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.144250 -vn 0.748361 0.508111 -0.426356 -v 0.018750 -0.133637 0.143171 -vn 0.692678 -0.719703 0.047172 -v 0.018750 -0.146000 0.152200 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.150082 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.150082 -vn 0.737696 0.088113 -0.669358 -v 0.018750 -0.103700 0.149700 -vn 0.565703 0.649074 -0.508609 -v 0.018750 -0.097306 0.149700 -vn 0.735123 0.672941 0.082124 -v 0.018750 -0.097400 0.150080 -vn 0.838628 -0.000002 -0.544704 -v 0.018750 -0.093500 0.150587 -vn 0.707107 -0.353558 -0.612369 -v 0.018750 -0.093300 0.150471 -vn 0.678875 0.190039 0.709235 -v 0.018750 -0.093412 0.161859 -vn 0.764746 0.070010 0.640517 -v 0.018750 -0.096598 0.149205 -vn 0.561186 -0.474782 0.677977 -v 0.018750 -0.097000 0.149352 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.097000 0.146700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.117375 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.111625 0.139700 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.111625 0.140200 -vn 0.770264 0.000000 -0.637725 -v 0.018750 -0.122750 0.127450 -vn 0.770260 -0.318866 -0.552291 -v 0.018750 -0.122125 0.127283 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.129318 -vn 0.838628 0.471728 0.272352 -v 0.018750 -0.109250 0.124757 -vn 0.838628 0.471727 -0.272353 -v 0.018750 -0.109250 0.127643 -vn 0.838629 0.000000 -0.544703 -v 0.018750 -0.106750 0.129087 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 -0.104250 0.127643 -vn 0.838628 0.471727 0.272353 -v 0.018750 -0.096000 0.130257 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.096000 0.132700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.096125 0.132700 -vn 0.838628 0.471727 -0.272353 -v 0.018750 -0.096000 0.133143 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.096125 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.093300 0.124132 -vn 0.707105 -0.353554 0.612374 -v 0.018750 -0.093300 0.128929 -vn 0.838628 -0.000002 0.544704 -v 0.018750 -0.093500 0.128813 -vn 0.764747 -0.232681 0.600850 -v 0.018750 -0.096175 0.128461 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.096125 0.124132 -vn 0.764747 -0.483921 0.425421 -v 0.018750 -0.095824 0.128706 -vn 0.764744 -0.625713 0.153784 -v 0.018750 -0.095626 0.129085 -vn 0.764749 -0.625987 -0.152640 -v 0.018750 -0.095626 0.129513 -vn 0.678874 0.709235 -0.190038 -v 0.018750 -0.086341 0.124612 -vn 0.692678 0.719703 -0.047171 -v 0.018750 -0.086000 0.127200 -vn 0.707108 -0.353552 0.612371 -v 0.018750 -0.092625 0.129318 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.129318 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.129850 -vn 0.707106 -0.353553 0.612373 -v 0.018750 -0.091704 0.129850 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.139700 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 -0.091000 0.133143 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.132700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.091000 0.132700 -vn 0.838628 -0.471727 0.272353 -v 0.018750 -0.091000 0.130257 -vn 0.770261 -0.637728 -0.000000 -v 0.018750 -0.121500 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.018750 -0.121667 0.125575 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.124132 -vn 0.770263 -0.552286 -0.318865 -v 0.018750 -0.121667 0.126825 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.129318 -vn 0.770261 0.552291 0.318862 -v 0.018750 -0.123833 0.125575 -vn 0.770261 0.637728 0.000000 -v 0.018750 -0.124000 0.126200 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.125900 0.124132 -vn 0.770263 0.552286 -0.318865 -v 0.018750 -0.123833 0.126825 -vn 0.770260 0.318865 -0.552291 -v 0.018750 -0.123375 0.127283 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.125900 0.129318 -vn 0.770264 -0.318861 0.552287 -v 0.018750 -0.122125 0.125117 -vn 0.770258 -0.000000 0.637732 -v 0.018750 -0.122750 0.124950 -vn 0.770264 0.318861 0.552287 -v 0.018750 -0.123375 0.125117 -vn 0.770261 -0.637728 -0.000000 -v 0.018750 -0.121500 0.153200 -vn 0.770261 -0.552291 0.318862 -v 0.018750 -0.121667 0.152575 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.150082 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.150082 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.122050 0.162200 -vn 0.770260 -0.318866 -0.552291 -v 0.018750 -0.122125 0.154283 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.119500 0.162200 -vn 0.770263 -0.552286 -0.318865 -v 0.018750 -0.121667 0.153825 -vn 0.770264 -0.318861 0.552287 -v 0.018750 -0.122125 0.152117 -vn 0.770258 -0.000000 0.637732 -v 0.018750 -0.122750 0.151950 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.125900 0.150082 -vn 0.770264 0.318861 0.552287 -v 0.018750 -0.123375 0.152117 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.125900 0.162200 -vn 0.770260 0.318865 -0.552291 -v 0.018750 -0.123375 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.018750 -0.122750 0.154450 -vn 0.770261 0.552291 0.318862 -v 0.018750 -0.123833 0.152575 -vn 0.770261 0.637728 0.000000 -v 0.018750 -0.124000 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.018750 -0.123833 0.153825 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.111625 0.149500 -vn 0.904535 -0.301512 -0.301509 -v 0.018750 -0.111000 0.149500 -vn 0.770265 -0.552285 0.318863 -v 0.018750 -0.107221 0.147250 -vn 0.770260 -0.318864 0.552291 -v 0.018750 -0.107550 0.146921 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.105675 0.146700 -vn 0.770267 0.000000 0.637722 -v 0.018750 -0.108000 0.146800 -vn 0.770261 0.318866 0.552288 -v 0.018750 -0.108450 0.146921 -vn 0.770261 0.552288 0.318866 -v 0.018750 -0.108779 0.147250 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.111000 0.146700 -vn 0.770264 0.637726 0.000000 -v 0.018750 -0.108900 0.147700 -vn 0.770261 0.552288 -0.318866 -v 0.018750 -0.108779 0.148150 -vn 0.770261 0.318866 -0.552288 -v 0.018750 -0.108450 0.148479 -vn 0.770265 0.000000 -0.637725 -v 0.018750 -0.108000 0.148600 -vn 0.770260 -0.318864 -0.552291 -v 0.018750 -0.107550 0.148479 -vn 1.000000 0.000000 0.000001 -v 0.018750 -0.105675 0.149550 -vn 0.770265 -0.552285 -0.318862 -v 0.018750 -0.107221 0.148150 -vn 0.770260 -0.637730 0.000000 -v 0.018750 -0.107100 0.147700 -vn 0.707106 0.000000 -0.707108 -v 0.018750 -0.117375 0.149500 -vn 0.904534 0.301511 -0.301511 -v 0.018750 -0.117500 0.149500 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.146700 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.117500 0.146700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.144250 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.117500 0.144250 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.141950 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.117500 0.141950 -vn 0.904534 0.301511 0.301511 -v 0.018750 -0.117500 0.140200 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.139700 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.117375 0.140200 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.111000 0.141950 -vn 0.904534 -0.301511 0.301511 -v 0.018750 -0.111000 0.140200 -vn 1.000000 0.000000 -0.000000 -v 0.018750 -0.105675 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.105675 0.141950 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.105675 0.144250 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.111000 0.144250 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.146700 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.104000 0.146700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.144250 -vn 0.737697 0.088113 0.669358 -v 0.018750 -0.103700 0.143700 -vn 0.770265 0.318854 0.552289 -v 0.018750 -0.103850 0.143740 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.141950 -vn 0.737697 -0.088113 0.669358 -v 0.018750 -0.097300 0.143700 -vn 0.770264 -0.552289 0.318858 -v 0.018750 -0.097040 0.143850 -vn 0.770266 -0.318854 0.552289 -v 0.018750 -0.097150 0.143740 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.096125 0.141950 -vn 0.770258 0.552288 0.318874 -v 0.018750 -0.103960 0.143850 -vn 0.737704 0.669347 0.088131 -v 0.018750 -0.104000 0.144000 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.104000 0.144250 -vn 0.737698 -0.669355 0.088117 -v 0.018750 -0.097000 0.144000 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.096125 0.144250 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.097000 0.144250 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.096125 0.146700 -vn 0.764747 -0.233779 0.600425 -v 0.018750 -0.096173 0.149261 -vn 0.764744 -0.625713 -0.153784 -v 0.018750 -0.095626 0.150315 -vn 0.764749 -0.625987 0.152640 -v 0.018750 -0.095626 0.149887 -vn 0.764744 -0.484694 0.424544 -v 0.018750 -0.095823 0.149507 -vn 0.707109 0.353556 -0.612369 -v 0.018750 -0.095296 0.149550 -vn 0.760386 -0.495121 -0.420320 -v 0.018750 -0.095824 0.150694 -vn 0.735113 -0.339331 -0.586909 -v 0.018750 -0.096118 0.150915 -vn 0.692678 0.047172 0.719703 -v 0.018750 -0.096000 0.162200 -vn 0.707107 0.000000 0.707106 -v 0.018750 -0.096125 0.162200 -vn 0.838629 0.000000 0.544703 -v 0.018750 -0.098750 0.150313 -vn 0.838627 0.471729 0.272352 -v 0.018750 -0.101250 0.151757 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.150082 -vn 0.838628 -0.471729 -0.272352 -v 0.018750 -0.096250 0.154643 -vn 0.838628 -0.471729 0.272352 -v 0.018750 -0.096250 0.151757 -vn 0.739286 -0.177557 -0.649561 -v 0.018750 -0.096175 0.150939 -vn 0.764746 0.071180 -0.640389 -v 0.018750 -0.096599 0.150994 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.104125 0.162200 -vn 0.838627 0.471729 -0.272352 -v 0.018750 -0.101250 0.154643 -vn 0.838629 0.000000 -0.544704 -v 0.018750 -0.098750 0.156087 -vn 0.764747 0.358941 -0.535092 -v 0.018750 -0.097001 0.150847 -vn 0.764746 0.565526 -0.308779 -v 0.018750 -0.097290 0.150531 -vn 0.737701 0.669352 -0.088123 -v 0.018750 -0.104000 0.149400 -vn 0.770261 0.552288 -0.318866 -v 0.018750 -0.103960 0.149550 -vn 0.770266 0.318854 -0.552289 -v 0.018750 -0.103850 0.149660 -vn 0.737612 0.669601 -0.086966 -v 0.018750 -0.097400 0.150118 -vn 0.678874 0.367127 -0.635883 -v 0.018750 -0.091000 0.118540 -vn 0.678874 0.519196 -0.519196 -v 0.018750 -0.088929 0.120129 -vn 0.678874 0.635883 -0.367127 -v 0.018750 -0.087340 0.122200 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.124132 -vn 0.678875 -0.709235 -0.190039 -v 0.018750 -0.145659 0.124612 -vn 0.678875 -0.635883 -0.367126 -v 0.018750 -0.144660 0.122200 -vn 0.678874 -0.519197 -0.519196 -v 0.018750 -0.143071 0.120129 -vn 0.678874 -0.367127 -0.635883 -v 0.018750 -0.141000 0.118540 -vn 0.678874 -0.190038 -0.709236 -v 0.018750 -0.138588 0.117541 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.129318 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.129318 -vn 0.692678 -0.719703 -0.047173 -v 0.018750 -0.146000 0.127200 -vn 0.678874 -0.709235 0.190040 -v 0.018750 -0.145659 0.154788 -vn 0.678874 -0.367128 0.635883 -v 0.018750 -0.141000 0.160860 -vn 0.678875 -0.190039 0.709235 -v 0.018750 -0.138588 0.161859 -vn 0.692678 -0.047172 0.719703 -v 0.018750 -0.136000 0.162200 -vn 0.678874 -0.519197 0.519195 -v 0.018750 -0.143071 0.159271 -vn 0.678875 -0.635883 0.367127 -v 0.018750 -0.144660 0.157200 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.150082 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.135500 0.162200 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.150082 -vn 0.692678 0.719703 0.047171 -v 0.018750 -0.086000 0.152200 -vn 0.678874 0.709236 0.190039 -v 0.018750 -0.086341 0.154788 -vn 0.678874 0.635883 0.367128 -v 0.018750 -0.087340 0.157200 -vn 0.678875 0.519197 0.519196 -v 0.018750 -0.088929 0.159271 -vn 0.678874 0.367128 0.635883 -v 0.018750 -0.091000 0.160860 -vn 0.737701 0.669352 -0.088124 -v 0.018750 -0.104000 0.135400 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.132700 -vn 0.737697 -0.088113 -0.669358 -v 0.018750 -0.097300 0.135700 -vn 0.770265 -0.318854 -0.552289 -v 0.018750 -0.097150 0.135660 -vn 0.770261 0.552288 -0.318866 -v 0.018750 -0.103960 0.135550 -vn 0.770266 0.318854 -0.552289 -v 0.018750 -0.103850 0.135660 -vn 0.737697 0.088113 -0.669358 -v 0.018750 -0.103700 0.135700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.097000 0.132700 -vn 0.737695 -0.669360 -0.088109 -v 0.018750 -0.097000 0.135400 -vn 0.770267 -0.552290 -0.318849 -v 0.018750 -0.097040 0.135550 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.129850 -vn 0.729850 0.680315 0.067009 -v 0.018750 -0.104000 0.130000 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.104000 0.132700 -vn 0.729841 0.066984 0.680327 -v 0.018750 -0.103700 0.129700 -vn 0.753773 0.251448 0.607125 -v 0.018750 -0.103815 0.129723 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.104125 0.129318 -vn 0.753771 0.464662 0.464671 -v 0.018750 -0.103912 0.129788 -vn 0.753765 0.607121 0.251480 -v 0.018750 -0.103977 0.129885 -vn 0.838628 0.471728 -0.272353 -v 0.018750 -0.101250 0.127643 -vn 0.838628 0.000000 -0.544705 -v 0.018750 -0.098750 0.129087 -vn 0.764746 0.071180 0.640389 -v 0.018750 -0.096599 0.128405 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 -0.096250 0.127643 -vn 0.764747 0.358941 0.535092 -v 0.018750 -0.097001 0.128553 -vn 0.764746 0.565526 0.308779 -v 0.018750 -0.097290 0.128869 -vn 0.764746 0.644208 0.012633 -v 0.018750 -0.097400 0.129282 -vn 0.566634 0.643195 0.515001 -v 0.018750 -0.097306 0.129700 -vn 0.764744 -0.484694 -0.424544 -v 0.018750 -0.095823 0.129893 -vn 0.764742 -0.233791 -0.600425 -v 0.018750 -0.096173 0.130139 -vn 0.764751 0.069998 -0.640513 -v 0.018750 -0.096598 0.130195 -vn 0.561186 -0.474782 -0.677977 -v 0.018750 -0.097000 0.130048 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.117375 0.129850 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.117375 0.129900 -vn 0.904534 0.301511 0.301511 -v 0.018750 -0.117500 0.129900 -vn 0.707106 0.000000 0.707108 -v 0.018750 -0.111625 0.129900 -vn 0.770260 -0.318864 0.552291 -v 0.018750 -0.107550 0.130921 -vn 0.770264 0.000000 0.637725 -v 0.018750 -0.108000 0.130800 -vn 0.770261 0.318866 0.552288 -v 0.018750 -0.108450 0.130921 -vn 0.770261 0.552288 0.318866 -v 0.018750 -0.108779 0.131250 -vn 0.904535 -0.301511 0.301509 -v 0.018750 -0.111000 0.129900 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.111000 0.132700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.105675 0.132700 -vn 0.770259 0.000000 -0.637731 -v 0.018750 -0.108000 0.132600 -vn 0.770267 -0.318857 -0.552285 -v 0.018750 -0.107550 0.132479 -vn 0.770263 0.637726 -0.000000 -v 0.018750 -0.108900 0.131700 -vn 0.770258 0.552295 -0.318862 -v 0.018750 -0.108779 0.132150 -vn 0.770268 0.318860 -0.552283 -v 0.018750 -0.108450 0.132479 -vn 0.770262 -0.552292 -0.318858 -v 0.018750 -0.107221 0.132150 -vn 0.770260 -0.637730 0.000000 -v 0.018750 -0.107100 0.131700 -vn 0.770265 -0.552285 0.318863 -v 0.018750 -0.107221 0.131250 -vn 0.904534 -0.301511 -0.301511 -v 0.018750 -0.111000 0.139200 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.141950 -vn 0.748361 -0.623291 -0.226858 -v 0.018750 -0.124426 0.141547 -vn 0.748360 -0.663293 0.000000 -v 0.018750 -0.124100 0.139700 -vn 0.748361 0.115181 -0.653214 -v 0.018750 -0.130438 0.145018 -vn 0.748361 -0.115181 -0.653214 -v 0.018750 -0.128562 0.145018 -vn 1.000000 -0.000000 0.000000 -v 0.018750 -0.125900 0.146700 -vn 0.748360 -0.331647 -0.574428 -v 0.018750 -0.126800 0.144377 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.125900 0.144250 -vn 0.748361 -0.508111 -0.426356 -v 0.018750 -0.125363 0.143171 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.146700 -vn 0.748360 0.623290 0.226861 -v 0.018750 -0.134574 0.137853 -vn 0.748361 0.663291 0.000000 -v 0.018750 -0.134900 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.139700 -vn 0.748360 0.623291 -0.226860 -v 0.018750 -0.134574 0.141547 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.141950 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.144250 -vn 0.748360 -0.508112 0.426356 -v 0.018750 -0.125363 0.136229 -vn 0.748361 -0.331646 0.574427 -v 0.018750 -0.126800 0.135023 -vn 0.748360 0.115179 0.653216 -v 0.018750 -0.130438 0.134382 -vn 0.748361 0.331646 0.574427 -v 0.018750 -0.132200 0.135023 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.133250 0.132700 -vn 0.748360 -0.115179 0.653216 -v 0.018750 -0.128562 0.134382 -vn 0.748361 -0.623290 0.226859 -v 0.018750 -0.124426 0.137853 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.139700 -vn 0.770261 0.552288 -0.318866 -v 0.018750 -0.139279 0.130900 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.132700 -vn 0.770263 0.637726 -0.000000 -v 0.018750 -0.139400 0.130450 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.129850 -vn 0.770261 0.552288 0.318866 -v 0.018750 -0.139279 0.130000 -vn 0.770261 0.318866 -0.552288 -v 0.018750 -0.138950 0.131229 -vn 0.770263 -0.000000 -0.637726 -v 0.018750 -0.138500 0.131350 -vn 0.770258 -0.318862 -0.552295 -v 0.018750 -0.138050 0.131229 -vn 0.770268 -0.552283 -0.318860 -v 0.018750 -0.137721 0.130900 -vn 0.770261 0.318866 0.552288 -v 0.018750 -0.138950 0.129671 -vn 0.770263 0.000000 0.637726 -v 0.018750 -0.138500 0.129550 -vn 0.770258 -0.318862 0.552295 -v 0.018750 -0.138050 0.129671 -vn 0.770261 -0.318866 -0.552288 -v 0.018750 -0.136550 0.134479 -vn 0.770261 -0.552288 -0.318866 -v 0.018750 -0.136221 0.134150 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.132700 -vn 0.770263 -0.637726 0.000000 -v 0.018750 -0.136100 0.133700 -vn 0.770261 -0.552288 0.318866 -v 0.018750 -0.136221 0.133250 -vn 0.748360 0.508112 0.426356 -v 0.018750 -0.133637 0.136229 -vn 0.770258 0.318862 0.552295 -v 0.018750 -0.137450 0.132921 -vn 0.770268 0.552283 0.318860 -v 0.018750 -0.137779 0.133250 -vn 0.770256 0.637735 0.000000 -v 0.018750 -0.137900 0.133700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.139700 -vn 0.770268 0.552283 -0.318860 -v 0.018750 -0.137779 0.134150 -vn 0.770258 0.318862 -0.552295 -v 0.018750 -0.137450 0.134479 -vn 0.770268 -0.318860 -0.552283 -v 0.018750 -0.136550 0.146479 -vn 0.770258 -0.552295 -0.318862 -v 0.018750 -0.136221 0.146150 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.146700 -vn 0.770263 -0.637726 0.000000 -v 0.018750 -0.136100 0.145700 -vn 0.770261 -0.552288 0.318866 -v 0.018750 -0.136221 0.145250 -vn 0.770256 0.000000 -0.637735 -v 0.018750 -0.137000 0.146600 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.146700 -vn 0.770265 0.318855 -0.552289 -v 0.018750 -0.137450 0.146479 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.146700 -vn 0.770265 0.552289 -0.318855 -v 0.018750 -0.137779 0.146150 -vn 0.770262 0.318851 0.552296 -v 0.018750 -0.137450 0.144921 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.144250 -vn 0.770268 0.552283 0.318860 -v 0.018750 -0.137779 0.145250 -vn 0.770256 0.637735 0.000000 -v 0.018750 -0.137900 0.145700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.149550 -vn 0.770261 0.552288 0.318866 -v 0.018750 -0.139279 0.148500 -vn 1.000000 0.000000 0.000001 -v 0.018750 -0.136850 0.149550 -vn 0.770256 -0.637734 0.000001 -v 0.018750 -0.137600 0.148950 -vn 0.770268 -0.552283 0.318860 -v 0.018750 -0.137721 0.148500 -vn 0.770258 -0.318862 0.552295 -v 0.018750 -0.138050 0.148171 -vn 0.770263 0.000000 0.637726 -v 0.018750 -0.138500 0.148050 -vn 0.770261 0.318866 0.552288 -v 0.018750 -0.138950 0.148171 -vn 0.770264 0.637725 0.000002 -v 0.018750 -0.139400 0.148950 -vn 0.770261 0.552289 -0.318865 -v 0.018750 -0.139279 0.149400 -vn 0.770261 0.318866 -0.552288 -v 0.018750 -0.138950 0.149729 -vn 0.770263 -0.000000 -0.637726 -v 0.018750 -0.138500 0.149850 -vn 0.770258 -0.318862 -0.552295 -v 0.018750 -0.138050 0.149729 -vn 0.770268 -0.552283 -0.318859 -v 0.018750 -0.137721 0.149400 -vn 0.838628 -0.000000 -0.544705 -v 0.018750 -0.114750 0.129087 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 -0.112250 0.127643 -vn 0.838628 -0.000000 0.544705 -v 0.018750 -0.114750 0.123313 -vn 0.838628 0.471728 0.272352 -v 0.018750 -0.117250 0.124757 -vn 0.838628 0.471728 -0.272353 -v 0.018750 -0.117250 0.127643 -vn 0.838627 -0.471729 0.272352 -v 0.018750 -0.104250 0.151757 -vn 0.838630 0.000000 0.544701 -v 0.018750 -0.106750 0.150313 -vn 1.000000 0.000001 -0.000001 -v 0.018750 -0.105675 0.150082 -vn 0.838628 0.471729 0.272352 -v 0.018750 -0.109250 0.151757 -vn 0.838628 0.471729 -0.272352 -v 0.018750 -0.109250 0.154643 -vn 0.838627 -0.471729 -0.272352 -v 0.018750 -0.104250 0.154643 -vn 0.838629 -0.000000 -0.544703 -v 0.018750 -0.106750 0.156087 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.105675 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.111625 0.162200 -vn 0.838626 0.471733 -0.272350 -v 0.018750 -0.096000 0.149143 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.096000 0.146700 -vn 0.838628 0.471728 0.272353 -v 0.018750 -0.096000 0.146257 -vn 0.707102 -0.353554 -0.612377 -v 0.018750 -0.092625 0.150082 -vn 0.707109 -0.353555 -0.612369 -v 0.018750 -0.091704 0.149550 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.149550 -vn 0.838626 -0.471732 -0.272350 -v 0.018750 -0.091000 0.149143 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.146700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.091000 0.146700 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.144250 -vn 0.838628 -0.471728 0.272352 -v 0.018750 -0.096250 0.124757 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.111625 0.124132 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.111625 0.117200 -vn 0.838628 0.000000 0.544704 -v 0.018750 -0.106750 0.123313 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.105675 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.104125 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.096125 0.117200 -vn 0.692678 0.047171 -0.719703 -v 0.018750 -0.096000 0.117200 -vn 0.678874 0.190038 -0.709236 -v 0.018750 -0.093412 0.117541 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.133250 0.162200 -vn 1.000000 -0.000000 0.000000 -v 0.018750 -0.125900 0.149550 -vn 0.838628 -0.471729 0.272352 -v 0.018750 -0.112250 0.124757 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.117375 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.119500 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.122050 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.125900 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.133250 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.135500 0.117200 -vn 0.692678 -0.047171 -0.719703 -v 0.018750 -0.136000 0.117200 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.129318 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.119500 0.132700 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.117500 0.132700 -vn 0.904534 0.301511 -0.301511 -v 0.018750 -0.117500 0.139200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.117375 0.139200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 -0.111625 0.139200 -vn 1.000000 0.000000 -0.000000 -v 0.018750 -0.111625 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.129850 -vn 0.770261 -0.552288 0.318866 -v 0.018750 -0.122721 0.131250 -vn 0.770261 -0.318866 0.552288 -v 0.018750 -0.123050 0.130921 -vn 0.770263 0.000000 0.637726 -v 0.018750 -0.123500 0.130800 -vn 0.770260 0.318864 0.552292 -v 0.018750 -0.123950 0.130921 -vn 0.770264 0.552285 0.318863 -v 0.018750 -0.124279 0.131250 -vn 0.770259 0.637731 -0.000000 -v 0.018750 -0.124400 0.131700 -vn 0.770262 0.552292 -0.318858 -v 0.018750 -0.124279 0.132150 -vn 0.770266 0.318857 -0.552286 -v 0.018750 -0.123950 0.132479 -vn 0.770256 0.000000 -0.637735 -v 0.018750 -0.123500 0.132600 -vn 0.770268 -0.318860 -0.552283 -v 0.018750 -0.123050 0.132479 -vn 0.707107 -0.707107 0.000000 -v 0.018750 -0.146000 0.141950 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.141950 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.136850 0.139700 -vn 0.770263 -0.000000 -0.637726 -v 0.018750 -0.137000 0.134600 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.093300 0.141950 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.093300 0.139700 -vn 0.838627 -0.000000 -0.544705 -v 0.018750 -0.093500 0.134587 -vn 0.707107 0.707107 0.000000 -v 0.018750 -0.086000 0.141950 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.144250 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.146700 -vn 0.770261 -0.318866 0.552288 -v 0.018750 -0.123050 0.146921 -vn 0.770263 0.000000 0.637726 -v 0.018750 -0.123500 0.146800 -vn 0.770264 0.552285 0.318863 -v 0.018750 -0.124279 0.147250 -vn 0.770260 0.637730 0.000000 -v 0.018750 -0.124400 0.147700 -vn 0.770260 0.318864 0.552292 -v 0.018750 -0.123950 0.146921 -vn 0.770262 -0.318866 -0.552288 -v 0.018750 -0.123050 0.148479 -vn 0.770262 -0.552288 -0.318866 -v 0.018750 -0.122721 0.148150 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.122050 0.149550 -vn 0.770264 -0.637725 0.000000 -v 0.018750 -0.122600 0.147700 -vn 0.770261 -0.552288 0.318866 -v 0.018750 -0.122721 0.147250 -vn 0.770265 0.552285 -0.318863 -v 0.018750 -0.124279 0.148150 -vn 0.770260 0.318864 -0.552291 -v 0.018750 -0.123950 0.148479 -vn 0.770265 -0.000000 -0.637725 -v 0.018750 -0.123500 0.148600 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.135500 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 -0.117375 0.150082 -vn 0.838628 -0.471729 0.272352 -v 0.018750 -0.104250 0.124757 -vn 0.707107 0.000000 0.707107 -v 0.018750 -0.117375 0.162200 -vn 0.838629 -0.000000 0.544704 -v 0.018750 -0.114750 0.150313 -vn 0.838628 0.471729 0.272352 -v 0.018750 -0.117250 0.151757 -vn 0.838628 0.471729 -0.272352 -v 0.018750 -0.117250 0.154643 -vn 0.838629 -0.000000 -0.544704 -v 0.018750 -0.114750 0.156087 -vn 0.838627 -0.471729 -0.272352 -v 0.018750 -0.112250 0.154643 -vn 0.838627 -0.471729 0.272352 -v 0.018750 -0.112250 0.151757 -vn -0.770256 0.637735 -0.000000 -v 0.015750 -0.137900 0.133700 -vn -0.770268 0.552283 -0.318860 -v 0.015750 -0.137779 0.134150 -vn -0.770258 0.318862 -0.552295 -v 0.015750 -0.137450 0.134479 -vn -0.770263 0.000000 -0.637726 -v 0.015750 -0.137000 0.134600 -vn -0.770261 -0.318866 -0.552288 -v 0.015750 -0.136550 0.134479 -vn -0.770261 -0.552288 -0.318866 -v 0.015750 -0.136221 0.134150 -vn -0.770263 -0.637726 -0.000000 -v 0.015750 -0.136100 0.133700 -vn -0.770261 -0.552288 0.318866 -v 0.015750 -0.136221 0.133250 -vn -0.770261 -0.318866 0.552288 -v 0.015750 -0.136550 0.132921 -vn -0.770263 -0.000000 0.637726 -v 0.015750 -0.137000 0.132800 -vn -0.770258 0.318862 0.552295 -v 0.015750 -0.137450 0.132921 -vn -0.770268 0.552283 0.318860 -v 0.015750 -0.137779 0.133250 -vn -0.770259 0.637731 0.000000 -v 0.015750 -0.124400 0.131700 -vn -0.770262 0.552292 -0.318858 -v 0.015750 -0.124279 0.132150 -vn -0.770266 0.318857 -0.552286 -v 0.015750 -0.123950 0.132479 -vn -0.770255 -0.000000 -0.637736 -v 0.015750 -0.123500 0.132600 -vn -0.770268 -0.318860 -0.552283 -v 0.015750 -0.123050 0.132479 -vn -0.770258 -0.552295 -0.318862 -v 0.015750 -0.122721 0.132150 -vn -0.770263 -0.637726 -0.000000 -v 0.015750 -0.122600 0.131700 -vn -0.770261 -0.552288 0.318866 -v 0.015750 -0.122721 0.131250 -vn -0.770261 -0.318866 0.552288 -v 0.015750 -0.123050 0.130921 -vn -0.770263 -0.000000 0.637726 -v 0.015750 -0.123500 0.130800 -vn -0.770260 0.318864 0.552292 -v 0.015750 -0.123950 0.130921 -vn -0.770264 0.552285 0.318863 -v 0.015750 -0.124279 0.131250 -vn -0.770263 0.637726 0.000000 -v 0.015750 -0.108900 0.131700 -vn -0.770258 0.552295 -0.318862 -v 0.015750 -0.108779 0.132150 -vn -0.770268 0.318860 -0.552283 -v 0.015750 -0.108450 0.132479 -vn -0.770252 -0.000000 -0.637740 -v 0.015750 -0.108000 0.132600 -vn -0.770265 -0.318858 -0.552287 -v 0.015750 -0.107550 0.132479 -vn -0.770261 -0.552293 -0.318859 -v 0.015750 -0.107221 0.132150 -vn -0.770258 -0.637732 0.000000 -v 0.015750 -0.107100 0.131700 -vn -0.770264 -0.552286 0.318863 -v 0.015750 -0.107221 0.131250 -vn -0.770259 -0.318864 0.552292 -v 0.015750 -0.107550 0.130921 -vn -0.770263 -0.000000 0.637726 -v 0.015750 -0.108000 0.130800 -vn -0.770261 0.318866 0.552288 -v 0.015750 -0.108450 0.130921 -vn -0.770261 0.552288 0.318866 -v 0.015750 -0.108779 0.131250 -vn -0.770256 0.637735 -0.000000 -v 0.015750 -0.137900 0.145700 -vn -0.770265 0.552289 -0.318855 -v 0.015750 -0.137779 0.146150 -vn -0.770265 0.318855 -0.552289 -v 0.015750 -0.137450 0.146479 -vn -0.770256 -0.000000 -0.637735 -v 0.015750 -0.137000 0.146600 -vn -0.770268 -0.318860 -0.552283 -v 0.015750 -0.136550 0.146479 -vn -0.770258 -0.552295 -0.318862 -v 0.015750 -0.136221 0.146150 -vn -0.770263 -0.637726 -0.000000 -v 0.015750 -0.136100 0.145700 -vn -0.770261 -0.552288 0.318866 -v 0.015750 -0.136221 0.145250 -vn -0.770265 -0.318855 0.552289 -v 0.015750 -0.136550 0.144921 -vn -0.770256 0.000000 0.637735 -v 0.015750 -0.137000 0.144800 -vn -0.770262 0.318851 0.552296 -v 0.015750 -0.137450 0.144921 -vn -0.770268 0.552283 0.318860 -v 0.015750 -0.137779 0.145250 -vn -0.770263 0.637726 0.000000 -v 0.015750 -0.108900 0.147700 -vn -0.770261 0.552288 -0.318866 -v 0.015750 -0.108779 0.148150 -vn -0.770261 0.318866 -0.552289 -v 0.015750 -0.108450 0.148479 -vn -0.770263 -0.000000 -0.637727 -v 0.015750 -0.108000 0.148600 -vn -0.770259 -0.318864 -0.552292 -v 0.015750 -0.107550 0.148479 -vn -0.770264 -0.552286 -0.318863 -v 0.015750 -0.107221 0.148150 -vn -0.770258 -0.637732 -0.000000 -v 0.015750 -0.107100 0.147700 -vn -0.770264 -0.552286 0.318863 -v 0.015750 -0.107221 0.147250 -vn -0.770259 -0.318864 0.552293 -v 0.015750 -0.107550 0.146921 -vn -0.770260 -0.000000 0.637730 -v 0.015750 -0.108000 0.146800 -vn -0.770261 0.318866 0.552288 -v 0.015750 -0.108450 0.146921 -vn -0.770261 0.552288 0.318866 -v 0.015750 -0.108779 0.147250 -vn -0.770259 0.637731 0.000000 -v 0.015750 -0.124400 0.147700 -vn -0.770264 0.552286 -0.318863 -v 0.015750 -0.124279 0.148150 -vn -0.770259 0.318864 -0.552292 -v 0.015750 -0.123950 0.148479 -vn -0.770263 0.000000 -0.637726 -v 0.015750 -0.123500 0.148600 -vn -0.770261 -0.318866 -0.552289 -v 0.015750 -0.123050 0.148479 -vn -0.770261 -0.552289 -0.318866 -v 0.015750 -0.122721 0.148150 -vn -0.770263 -0.637726 -0.000000 -v 0.015750 -0.122600 0.147700 -vn -0.770261 -0.552288 0.318866 -v 0.015750 -0.122721 0.147250 -vn -0.770261 -0.318866 0.552288 -v 0.015750 -0.123050 0.146921 -vn -0.770263 -0.000000 0.637726 -v 0.015750 -0.123500 0.146800 -vn -0.770260 0.318864 0.552292 -v 0.015750 -0.123950 0.146921 -vn -0.770264 0.552285 0.318863 -v 0.015750 -0.124279 0.147250 -vn -0.692678 -0.719703 -0.047173 -v 0.010750 -0.146000 0.127200 -vn -0.692678 -0.719703 0.047172 -v 0.010750 -0.146000 0.152200 -vn -0.692678 -0.047172 0.719703 -v 0.010750 -0.136000 0.162200 -vn -0.692678 0.047172 0.719703 -v 0.010750 -0.096000 0.162200 -vn -0.692678 0.719702 0.047171 -v 0.010750 -0.086000 0.152200 -vn -0.692678 0.719703 -0.047171 -v 0.010750 -0.086000 0.127200 -vn -0.692678 0.047171 -0.719702 -v 0.010750 -0.096000 0.117200 -vn -0.692678 -0.047171 -0.719703 -v 0.010750 -0.136000 0.117200 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.093500 0.122700 -vn -0.577350 -0.577350 0.577350 -v 0.010750 -0.093500 0.123200 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.092000 0.123200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 -0.128000 0.156700 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.093500 0.156700 -vn -0.678875 0.190039 0.709235 -v 0.010750 -0.093412 0.161859 -vn -0.678874 0.367128 0.635883 -v 0.010750 -0.091000 0.160860 -vn -0.678875 0.519197 0.519195 -v 0.010750 -0.088929 0.159271 -vn -0.904534 0.301511 0.301511 -v 0.010750 -0.128000 0.122700 -vn -0.678874 0.190038 -0.709236 -v 0.010750 -0.093412 0.117541 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.090500 0.124700 -vn -0.678874 0.635883 -0.367127 -v 0.010750 -0.087340 0.122200 -vn -0.678874 0.519196 -0.519196 -v 0.010750 -0.088929 0.120129 -vn -0.742116 0.540534 -0.396341 -v 0.010750 -0.141663 0.151814 -vn -0.741871 0.638646 -0.204348 -v 0.010750 -0.142657 0.149863 -vn -0.725201 0.686415 -0.054022 -v 0.010750 -0.143000 0.147700 -vn -0.577350 -0.577350 0.577350 -v 0.010750 -0.092000 0.124700 -vn -0.678874 0.367127 -0.635883 -v 0.010750 -0.091000 0.118540 -vn -0.577350 -0.577350 0.577350 -v 0.010750 -0.090500 0.126450 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.090000 0.126450 -vn -0.678874 0.709235 -0.190038 -v 0.010750 -0.086341 0.124612 -vn -0.678874 -0.709235 0.190040 -v 0.010750 -0.145659 0.154788 -vn -0.678875 -0.635883 0.367127 -v 0.010750 -0.144660 0.157200 -vn -0.744072 0.392698 -0.540504 -v 0.010750 -0.140114 0.153363 -vn -0.678874 -0.519198 0.519195 -v 0.010750 -0.143071 0.159271 -vn -0.744070 0.206453 -0.635403 -v 0.010750 -0.138163 0.154357 -vn -0.725201 0.686415 0.054023 -v 0.010750 -0.143000 0.131700 -vn -0.744071 0.635401 0.206455 -v 0.010750 -0.142657 0.129537 -vn -0.678875 -0.709235 -0.190039 -v 0.010750 -0.145659 0.124612 -vn -0.744071 0.540505 0.392700 -v 0.010750 -0.141663 0.127585 -vn -0.678875 -0.635883 -0.367126 -v 0.010750 -0.144660 0.122200 -vn -0.744071 0.392700 0.540505 -v 0.010750 -0.140114 0.126037 -vn -0.678874 -0.519197 -0.519196 -v 0.010750 -0.143071 0.120129 -vn -0.577350 0.577350 -0.577350 -v 0.010750 -0.128000 0.156200 -vn -0.845340 0.278879 -0.455660 -v 0.010750 -0.129500 0.156200 -vn -0.661187 0.577627 -0.478726 -v 0.010750 -0.129897 0.155424 -vn -0.678874 -0.367127 -0.635883 -v 0.010750 -0.141000 0.118540 -vn -0.744072 0.206452 0.635401 -v 0.010750 -0.138163 0.125043 -vn -0.678874 -0.190038 -0.709236 -v 0.010750 -0.138588 0.117541 -vn -0.725200 0.054020 0.686416 -v 0.010750 -0.136000 0.124700 -vn -0.683245 0.080046 0.725788 -v 0.010750 -0.131436 0.124700 -vn -0.661189 0.319122 0.678963 -v 0.010750 -0.130586 0.124510 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 -0.090500 0.136950 -vn -0.577350 -0.577351 0.577350 -v 0.010750 -0.090500 0.142450 -vn -0.904534 -0.301511 -0.301512 -v 0.010750 -0.090000 0.136950 -vn -0.904534 -0.301511 0.301511 -v 0.010750 -0.090000 0.142450 -vn -0.678874 -0.367128 0.635883 -v 0.010750 -0.141000 0.160860 -vn -0.678875 -0.190039 0.709235 -v 0.010750 -0.138588 0.161859 -vn -0.725200 0.054022 -0.686415 -v 0.010750 -0.136000 0.154700 -vn -0.683246 0.080043 -0.725788 -v 0.010750 -0.131436 0.154700 -vn -0.661187 0.319122 -0.678964 -v 0.010750 -0.130586 0.154890 -vn -0.577350 0.577350 0.577350 -v 0.010750 -0.128000 0.123200 -vn -0.845340 0.278879 0.455661 -v 0.010750 -0.129500 0.123200 -vn -0.661187 0.577625 0.478729 -v 0.010750 -0.129897 0.123976 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.090500 0.154700 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 -0.092000 0.154700 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.092000 0.156200 -vn -0.678874 0.709236 0.190039 -v 0.010750 -0.086341 0.154788 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 -0.090000 0.152950 -vn -0.678875 0.635882 0.367128 -v 0.010750 -0.087340 0.157200 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 -0.093500 0.156200 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 -0.090500 0.152950 -vn -0.737698 -0.669356 0.088117 -v 0.015750 -0.097000 0.144000 -vn -0.770264 -0.552289 0.318858 -v 0.015750 -0.097040 0.143850 -vn -0.770265 -0.318854 0.552289 -v 0.015750 -0.097150 0.143740 -vn -0.737697 -0.088113 0.669358 -v 0.015750 -0.097300 0.143700 -vn -0.737697 0.088113 0.669358 -v 0.015750 -0.103700 0.143700 -vn -0.770266 0.318854 0.552289 -v 0.015750 -0.103850 0.143740 -vn -0.770258 0.552288 0.318875 -v 0.015750 -0.103960 0.143850 -vn -0.737704 0.669347 0.088131 -v 0.015750 -0.104000 0.144000 -vn -0.737701 0.669351 -0.088124 -v 0.015750 -0.104000 0.149400 -vn -0.770261 0.552288 -0.318866 -v 0.015750 -0.103960 0.149550 -vn -0.770265 0.318854 -0.552289 -v 0.015750 -0.103850 0.149660 -vn -0.737697 0.088113 -0.669358 -v 0.015750 -0.103700 0.149700 -vn -0.707107 0.707107 -0.000000 -v 0.015750 -0.104000 0.146700 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.104000 0.145775 -vn -0.565925 0.644022 -0.514748 -v 0.015750 -0.097306 0.149700 -vn -0.561186 -0.474782 0.677977 -v 0.015750 -0.097000 0.149352 -vn -0.707107 -0.707107 -0.000000 -v 0.015750 -0.097000 0.146700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.097000 0.145775 -vn -0.748361 0.663291 -0.000000 -v 0.015750 -0.134900 0.139700 -vn -0.748360 0.623291 -0.226860 -v 0.015750 -0.134574 0.141547 -vn -0.748361 0.508111 -0.426356 -v 0.015750 -0.133637 0.143171 -vn -0.748360 0.331647 -0.574428 -v 0.015750 -0.132200 0.144377 -vn -0.748361 0.115181 -0.653214 -v 0.015750 -0.130438 0.145018 -vn -0.748361 -0.115181 -0.653214 -v 0.015750 -0.128562 0.145018 -vn -0.748360 -0.331647 -0.574428 -v 0.015750 -0.126800 0.144377 -vn -0.748361 -0.508111 -0.426356 -v 0.015750 -0.125363 0.143171 -vn -0.748361 -0.623291 -0.226858 -v 0.015750 -0.124426 0.141547 -vn -0.748360 -0.663293 0.000000 -v 0.015750 -0.124100 0.139700 -vn -0.748361 -0.623290 0.226859 -v 0.015750 -0.124426 0.137853 -vn -0.748360 -0.508112 0.426356 -v 0.015750 -0.125363 0.136229 -vn -0.748361 -0.331646 0.574427 -v 0.015750 -0.126800 0.135023 -vn -0.748360 -0.115179 0.653216 -v 0.015750 -0.128562 0.134382 -vn -0.748360 0.115179 0.653216 -v 0.015750 -0.130438 0.134382 -vn -0.748361 0.331646 0.574427 -v 0.015750 -0.132200 0.135023 -vn -0.748360 0.508112 0.426356 -v 0.015750 -0.133637 0.136229 -vn -0.748361 0.623290 0.226861 -v 0.015750 -0.134574 0.137853 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.129725 -vn -1.000000 -0.000000 0.000000 -v 0.015750 -0.112250 0.129725 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.150425 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.151475 -vn -1.000000 -0.000000 0.000000 -v 0.015750 -0.112250 0.151475 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.106300 0.128975 -vn -0.673534 0.228410 -0.702980 -v 0.015750 -0.138163 0.154357 -vn -0.689866 0.056800 -0.721705 -v 0.015750 -0.136000 0.154700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.136850 0.151475 -vn -0.904534 -0.301511 -0.301511 -v 0.015750 -0.090500 0.152950 -vn -0.577350 -0.577350 -0.577350 -v 0.015750 -0.090000 0.152950 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090000 0.151475 -vn -0.904534 -0.301511 0.301511 -v 0.015750 -0.093500 0.123200 -vn -0.577350 -0.577350 0.577350 -v 0.015750 -0.093500 0.122700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.095175 0.122700 -vn -0.942504 -0.074364 0.325815 -v 0.015750 -0.128777 0.124531 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.125325 0.124700 -vn -0.904534 0.301511 0.301511 -v 0.015750 -0.128000 0.123200 -vn -0.606340 0.415114 0.678257 -v 0.015750 -0.129500 0.123200 -vn -0.759605 0.500757 0.415022 -v 0.015750 -0.129897 0.123976 -vn -0.942505 0.074364 0.325814 -v 0.015750 -0.130223 0.124531 -vn -0.577350 -0.577350 0.577350 -v 0.015750 -0.090000 0.126450 -vn -0.904534 -0.301511 0.301511 -v 0.015750 -0.090500 0.126450 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.128975 -vn -0.577350 -0.577350 0.577350 -v 0.015750 -0.090500 0.124700 -vn -0.904534 -0.301511 0.301511 -v 0.015750 -0.092000 0.124700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.124700 -vn -0.577350 -0.577350 0.577350 -v 0.015750 -0.092000 0.123200 -vn -0.577350 -0.577350 -0.577350 -v 0.015750 -0.090000 0.136950 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090000 0.133625 -vn -0.904534 -0.301511 -0.301511 -v 0.015750 -0.090500 0.136950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.133625 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090500 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.139700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090500 0.141950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.141950 -vn -0.904534 -0.301511 0.301511 -v 0.015750 -0.090500 0.142450 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.145775 -vn -0.577350 -0.577350 0.577350 -v 0.015750 -0.090000 0.142450 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090000 0.145775 -vn -0.577350 -0.577350 -0.577350 -v 0.015750 -0.093500 0.156700 -vn -0.904534 -0.301511 -0.301511 -v 0.015750 -0.093500 0.156200 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.151475 -vn -0.577350 -0.577350 -0.577350 -v 0.015750 -0.092000 0.156200 -vn -0.904534 -0.301511 -0.301511 -v 0.015750 -0.092000 0.154700 -vn -0.577350 -0.577350 -0.577350 -v 0.015750 -0.090500 0.154700 -vn -0.577350 0.577350 -0.577350 -v 0.015750 -0.128000 0.156700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.125325 0.156700 -vn -0.904534 0.301511 -0.301511 -v 0.015750 -0.128000 0.156200 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.125325 0.151475 -vn -0.942505 -0.074365 -0.325813 -v 0.015750 -0.128777 0.154868 -vn -0.942505 0.074365 -0.325813 -v 0.015750 -0.130223 0.154868 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.125325 0.150425 -vn -0.942505 -0.334192 -0.000001 -v 0.015750 -0.126250 0.151700 -vn -0.942505 -0.301097 -0.145000 -v 0.015750 -0.126572 0.153110 -vn -0.942506 -0.208364 -0.261281 -v 0.015750 -0.127474 0.154241 -vn -0.606340 0.415115 -0.678256 -v 0.015750 -0.129500 0.156200 -vn -0.759605 0.500759 -0.415019 -v 0.015750 -0.129897 0.155424 -vn -0.759604 0.276655 -0.588611 -v 0.015750 -0.130586 0.154890 -vn -0.942505 0.208366 -0.261283 -v 0.015750 -0.131526 0.154241 -vn -0.732633 0.074610 -0.676522 -v 0.015750 -0.131436 0.154700 -vn -0.770258 -0.318862 0.552295 -v 0.015750 -0.138050 0.148171 -vn -0.770268 -0.552283 0.318860 -v 0.015750 -0.137721 0.148500 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.136850 0.146700 -vn -0.770255 -0.637736 -0.000001 -v 0.015750 -0.137600 0.148950 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.136850 0.150425 -vn -0.770269 -0.552280 -0.318861 -v 0.015750 -0.137721 0.149400 -vn -0.770258 -0.318862 -0.552295 -v 0.015750 -0.138050 0.149729 -vn -0.770263 0.000000 -0.637726 -v 0.015750 -0.138500 0.149850 -vn -0.689140 0.656175 -0.307440 -v 0.015750 -0.142434 0.150457 -vn -0.678153 0.584618 -0.445342 -v 0.015750 -0.141663 0.151814 -vn -0.673532 0.434466 -0.597991 -v 0.015750 -0.140114 0.153363 -vn -0.770261 0.318866 -0.552288 -v 0.015750 -0.138950 0.149729 -vn -0.770261 0.552287 -0.318867 -v 0.015750 -0.139279 0.149400 -vn -0.685056 0.704324 -0.186079 -v 0.015750 -0.142657 0.149863 -vn -0.770263 0.637726 -0.000002 -v 0.015750 -0.139400 0.148950 -vn -0.689866 0.721705 -0.056800 -v 0.015750 -0.143000 0.147700 -vn -0.770261 0.552288 0.318866 -v 0.015750 -0.139279 0.148500 -vn -0.707106 0.707107 0.000000 -v 0.015750 -0.143000 0.146700 -vn -0.770261 0.318866 0.552288 -v 0.015750 -0.138950 0.148171 -vn -0.770263 -0.000000 0.637726 -v 0.015750 -0.138500 0.148050 -vn -0.673534 0.702979 0.228413 -v 0.015750 -0.142657 0.129537 -vn -0.770263 0.637726 0.000000 -v 0.015750 -0.139400 0.130450 -vn -0.770261 0.552288 0.318866 -v 0.015750 -0.139279 0.130000 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.136850 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.136850 0.129725 -vn -0.770256 -0.637735 0.000000 -v 0.015750 -0.137600 0.130450 -vn -0.770268 -0.552283 -0.318860 -v 0.015750 -0.137721 0.130900 -vn -0.770258 -0.318862 -0.552295 -v 0.015750 -0.138050 0.131229 -vn -0.770263 0.000000 -0.637726 -v 0.015750 -0.138500 0.131350 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.143000 0.132700 -vn -0.770261 0.318866 -0.552288 -v 0.015750 -0.138950 0.131229 -vn -0.770261 0.552288 -0.318866 -v 0.015750 -0.139279 0.130900 -vn -0.689866 0.721705 0.056800 -v 0.015750 -0.143000 0.131700 -vn -0.770261 0.318866 0.552288 -v 0.015750 -0.138950 0.129671 -vn -0.770263 -0.000000 0.637726 -v 0.015750 -0.138500 0.129550 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.136850 0.128975 -vn -0.770258 -0.318862 0.552295 -v 0.015750 -0.138050 0.129671 -vn -0.770268 -0.552283 0.318860 -v 0.015750 -0.137721 0.130000 -vn -0.689867 0.056797 0.721705 -v 0.015750 -0.136000 0.124700 -vn -0.673533 0.228410 0.702981 -v 0.015750 -0.138163 0.125043 -vn -0.673533 0.434466 0.597990 -v 0.015750 -0.140114 0.126037 -vn -0.673534 0.597990 0.434466 -v 0.015750 -0.141663 0.127585 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 -0.121667 0.126825 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 -0.122125 0.127283 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.128975 -vn -0.770264 -0.000000 -0.637725 -v 0.015750 -0.122750 0.127450 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.125325 0.128975 -vn -0.770260 0.318866 -0.552291 -v 0.015750 -0.123375 0.127283 -vn -0.770263 0.552286 -0.318865 -v 0.015750 -0.123833 0.126825 -vn -0.770261 0.637728 -0.000000 -v 0.015750 -0.124000 0.126200 -vn -0.770261 0.552291 0.318862 -v 0.015750 -0.123833 0.125575 -vn -0.770265 0.318861 0.552286 -v 0.015750 -0.123375 0.125117 -vn -0.770258 0.000000 0.637732 -v 0.015750 -0.122750 0.124950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.124700 -vn -0.770264 -0.318861 0.552287 -v 0.015750 -0.122125 0.125117 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.124700 -vn -0.770261 -0.552291 0.318862 -v 0.015750 -0.121667 0.125575 -vn -0.770261 -0.637728 0.000000 -v 0.015750 -0.121500 0.126200 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.128975 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.112250 0.128975 -vn -1.000000 -0.000000 0.000000 -v 0.015750 -0.112250 0.124700 -vn -1.000000 -0.000001 0.000001 -v 0.015750 -0.106300 0.124700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.124700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.129725 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090000 0.132700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090000 0.129725 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.095175 0.132700 -vn -0.770264 0.637725 -0.000000 -v 0.015750 -0.094750 0.147700 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.095175 0.146700 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.095175 0.150425 -vn -0.770265 -0.318862 -0.552285 -v 0.015750 -0.092875 0.148783 -vn -0.770258 -0.000001 -0.637733 -v 0.015750 -0.093500 0.148950 -vn -0.770266 0.318862 -0.552285 -v 0.015750 -0.094125 0.148783 -vn -0.770258 0.552294 -0.318864 -v 0.015750 -0.094583 0.148325 -vn -0.707107 -0.707107 -0.000000 -v 0.015750 -0.090000 0.146700 -vn -0.770264 -0.637725 -0.000000 -v 0.015750 -0.092250 0.147700 -vn -0.707107 -0.707107 -0.000000 -v 0.015750 -0.090000 0.150425 -vn -0.770258 -0.552293 -0.318864 -v 0.015750 -0.092417 0.148325 -vn -0.770261 0.552288 0.318867 -v 0.015750 -0.094583 0.147075 -vn -0.770261 0.318866 0.552288 -v 0.015750 -0.094125 0.146617 -vn -0.770264 -0.000001 0.637725 -v 0.015750 -0.093500 0.146450 -vn -0.770261 -0.318867 0.552288 -v 0.015750 -0.092875 0.146617 -vn -0.770261 -0.552288 0.318867 -v 0.015750 -0.092417 0.147075 -vn -0.770261 0.552288 -0.318867 -v 0.015750 -0.107833 0.153825 -vn -0.770264 0.637725 0.000000 -v 0.015750 -0.108000 0.153200 -vn -0.770259 0.552293 0.318864 -v 0.015750 -0.107833 0.152575 -vn -0.770261 0.318866 -0.552288 -v 0.015750 -0.107375 0.154283 -vn -0.707107 -0.000000 -0.707107 -v 0.015750 -0.112250 0.156700 -vn -0.770263 -0.000002 -0.637726 -v 0.015750 -0.106750 0.154450 -vn -0.707107 -0.000000 -0.707107 -v 0.015750 -0.106300 0.156700 -vn -0.770261 -0.318868 -0.552288 -v 0.015750 -0.106125 0.154283 -vn -0.770265 0.318861 0.552285 -v 0.015750 -0.107375 0.152117 -vn -0.770256 -0.000001 0.637734 -v 0.015750 -0.106750 0.151950 -vn -1.000000 -0.000001 0.000001 -v 0.015750 -0.106300 0.151475 -vn -0.770259 -0.552293 0.318864 -v 0.015750 -0.105667 0.152575 -vn -0.770264 -0.637725 -0.000000 -v 0.015750 -0.105500 0.153200 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.151475 -vn -0.770266 -0.318863 0.552284 -v 0.015750 -0.106125 0.152117 -vn -0.770261 -0.552288 -0.318867 -v 0.015750 -0.105667 0.153825 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.104750 0.156700 -vn -0.770265 0.318861 0.552287 -v 0.015750 -0.123375 0.152117 -vn -0.770258 0.000000 0.637732 -v 0.015750 -0.122750 0.151950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.151475 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.122050 0.156700 -vn -0.770264 -0.000000 -0.637725 -v 0.015750 -0.122750 0.154450 -vn -0.770260 0.318866 -0.552291 -v 0.015750 -0.123375 0.154283 -vn -0.770263 0.552286 -0.318865 -v 0.015750 -0.123833 0.153825 -vn -0.770261 0.637728 -0.000000 -v 0.015750 -0.124000 0.153200 -vn -0.770261 0.552291 0.318862 -v 0.015750 -0.123833 0.152575 -vn -0.770264 -0.318861 0.552287 -v 0.015750 -0.122125 0.152117 -vn -0.770261 -0.552291 0.318862 -v 0.015750 -0.121667 0.152575 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.151475 -vn -0.770261 -0.637728 0.000000 -v 0.015750 -0.121500 0.153200 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.119500 0.156700 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 -0.121667 0.153825 -vn -0.770260 -0.318866 -0.552291 -v 0.015750 -0.122125 0.154283 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.143000 0.145775 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.143000 0.141950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.145775 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.135500 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.141950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.133625 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.143000 0.139700 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.143000 0.133625 -vn -0.904534 -0.301511 -0.301512 -v 0.015750 -0.111000 0.149500 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.112250 0.149500 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.112250 0.150425 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.116750 0.149500 -vn -1.000000 -0.000001 0.000000 -v 0.015750 -0.106300 0.146700 -vn -0.707106 -0.707107 -0.000000 -v 0.015750 -0.111000 0.146700 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.106300 0.150425 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.112250 0.139700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.112250 0.140200 -vn -0.904534 -0.301512 0.301512 -v 0.015750 -0.111000 0.140200 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.111000 0.145775 -vn -1.000000 -0.000000 0.000000 -v 0.015750 -0.106300 0.145775 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.111000 0.141950 -vn -1.000000 -0.000000 0.000000 -v 0.015750 -0.106300 0.141950 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.106300 0.139700 -vn -1.000000 -0.000001 -0.000000 -v 0.015750 -0.106300 0.132700 -vn -0.707106 -0.707107 -0.000000 -v 0.015750 -0.111000 0.132700 -vn -0.904534 -0.301512 0.301513 -v 0.015750 -0.111000 0.129900 -vn -1.000000 -0.000000 0.000000 -v 0.015750 -0.106300 0.129725 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.112250 0.129900 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.116750 0.129900 -vn -0.904534 0.301511 0.301511 -v 0.015750 -0.117500 0.129900 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.129725 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.132700 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.117500 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.139700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.116750 0.139200 -vn -0.904534 0.301511 -0.301511 -v 0.015750 -0.117500 0.139200 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.117500 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.139700 -vn -1.000000 -0.000000 0.000000 -v 0.015750 -0.106300 0.133625 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.111000 0.133625 -vn -0.904534 -0.301512 -0.301512 -v 0.015750 -0.111000 0.139200 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.112250 0.139200 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.125325 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.133825 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.133825 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.125325 0.133625 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.096550 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.141950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.096550 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.096550 0.141950 -vn -0.764304 0.644721 -0.013206 -v 0.015750 -0.097400 0.150118 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.104750 0.150425 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.104750 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.145775 -vn -0.764067 -0.232162 -0.601915 -v 0.015750 -0.096175 0.150939 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.096550 0.151475 -vn -0.764746 0.071180 -0.640389 -v 0.015750 -0.096599 0.150994 -vn -0.764747 0.358941 -0.535092 -v 0.015750 -0.097001 0.150847 -vn -0.764746 0.565526 -0.308779 -v 0.015750 -0.097290 0.150531 -vn -0.764747 0.070010 0.640517 -v 0.015750 -0.096598 0.149205 -vn -0.764747 -0.233779 0.600424 -v 0.015750 -0.096173 0.149261 -vn -0.764745 -0.484694 0.424544 -v 0.015750 -0.095823 0.149507 -vn -0.764749 -0.625987 0.152639 -v 0.015750 -0.095626 0.149887 -vn -0.764744 -0.625713 -0.153784 -v 0.015750 -0.095626 0.150315 -vn -0.764105 -0.485063 -0.425274 -v 0.015750 -0.095824 0.150694 -vn -0.729850 0.680315 0.067009 -v 0.015750 -0.104000 0.130000 -vn -0.753766 0.607121 0.251479 -v 0.015750 -0.103977 0.129885 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.129725 -vn -0.566634 0.643195 0.515001 -v 0.015750 -0.097306 0.129700 -vn -0.764746 0.644208 0.012633 -v 0.015750 -0.097400 0.129282 -vn -0.729841 0.066984 0.680327 -v 0.015750 -0.103700 0.129700 -vn -0.753773 0.251448 0.607125 -v 0.015750 -0.103815 0.129723 -vn -0.753771 0.464662 0.464671 -v 0.015750 -0.103912 0.129788 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.104000 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.132700 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.104000 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.133625 -vn -0.737701 0.669352 -0.088124 -v 0.015750 -0.104000 0.135400 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.104750 0.139700 -vn -0.770261 0.552288 -0.318866 -v 0.015750 -0.103960 0.135550 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.096550 0.133625 -vn -0.737695 -0.669360 -0.088109 -v 0.015750 -0.097000 0.135400 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.096550 0.139700 -vn -0.770267 -0.552290 -0.318849 -v 0.015750 -0.097040 0.135550 -vn -0.770266 -0.318854 -0.552289 -v 0.015750 -0.097150 0.135660 -vn -0.737697 -0.088113 -0.669358 -v 0.015750 -0.097300 0.135700 -vn -0.737697 0.088113 -0.669358 -v 0.015750 -0.103700 0.135700 -vn -0.770265 0.318854 -0.552289 -v 0.015750 -0.103850 0.135660 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.096550 0.132700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.097000 0.132700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.097000 0.133625 -vn -0.561186 -0.474782 -0.677977 -v 0.015750 -0.097000 0.130048 -vn -0.764751 0.069998 -0.640513 -v 0.015750 -0.096598 0.130195 -vn -0.764742 -0.233791 -0.600425 -v 0.015750 -0.096173 0.130139 -vn -0.764744 -0.484694 -0.424544 -v 0.015750 -0.095823 0.129893 -vn -0.764747 -0.232681 0.600850 -v 0.015750 -0.096175 0.128461 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.096550 0.124700 -vn -0.764747 -0.483921 0.425421 -v 0.015750 -0.095824 0.128706 -vn -0.764744 -0.625713 0.153784 -v 0.015750 -0.095626 0.129085 -vn -0.764749 -0.625987 -0.152640 -v 0.015750 -0.095626 0.129513 -vn -0.764746 0.565526 0.308779 -v 0.015750 -0.097290 0.128869 -vn -0.764747 0.358941 0.535092 -v 0.015750 -0.097001 0.128553 -vn -0.764745 0.071180 0.640389 -v 0.015750 -0.096599 0.128405 -vn -0.942505 0.074366 0.325812 -v 0.015750 -0.130223 0.148531 -vn -0.942505 -0.074365 0.325813 -v 0.015750 -0.128777 0.148531 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.125325 0.146700 -vn -0.942506 -0.208365 0.261279 -v 0.015750 -0.127474 0.149159 -vn -0.942505 -0.301097 0.145000 -v 0.015750 -0.126572 0.150290 -vn -0.942505 0.208366 0.261283 -v 0.015750 -0.131526 0.149159 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.133825 0.146700 -vn -0.942505 0.301096 0.145000 -v 0.015750 -0.132428 0.150290 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.133825 0.150425 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.133825 0.151475 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.133825 0.154700 -vn -0.942505 0.301096 -0.145001 -v 0.015750 -0.132428 0.153110 -vn -0.942505 0.334191 -0.000000 -v 0.015750 -0.132750 0.151700 -vn -0.759603 0.276656 0.588613 -v 0.015750 -0.130586 0.124510 -vn -0.732634 0.074613 0.676521 -v 0.015750 -0.131436 0.124700 -vn -0.942505 0.208364 0.261282 -v 0.015750 -0.131526 0.125159 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.133825 0.124700 -vn -0.942506 0.301095 0.145000 -v 0.015750 -0.132428 0.126290 -vn -0.942505 0.334192 0.000000 -v 0.015750 -0.132750 0.127700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.133825 0.128975 -vn -0.942506 0.301095 -0.145001 -v 0.015750 -0.132428 0.129110 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.133825 0.129725 -vn -0.942504 0.208366 -0.261286 -v 0.015750 -0.131526 0.130241 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.133825 0.132700 -vn -0.942505 0.074365 -0.325813 -v 0.015750 -0.130223 0.130868 -vn -0.942506 -0.301095 -0.145000 -v 0.015750 -0.126572 0.129110 -vn -0.942505 -0.208366 -0.261282 -v 0.015750 -0.127474 0.130241 -vn -0.942506 -0.208363 0.261280 -v 0.015750 -0.127474 0.125159 -vn -0.942505 -0.301096 0.145000 -v 0.015750 -0.126572 0.126290 -vn -0.942505 -0.334192 -0.000000 -v 0.015750 -0.126250 0.127700 -vn -0.770261 -0.552291 0.318862 -v 0.015750 -0.113667 0.152575 -vn -0.770261 -0.637728 -0.000000 -v 0.015750 -0.113500 0.153200 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 -0.113667 0.153825 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 -0.114125 0.154283 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.116750 0.156700 -vn -0.770264 0.000000 -0.637725 -v 0.015750 -0.114750 0.154450 -vn -0.770260 0.318865 -0.552291 -v 0.015750 -0.115375 0.154283 -vn -0.770263 0.552286 -0.318865 -v 0.015750 -0.115833 0.153825 -vn -0.770261 0.637728 0.000000 -v 0.015750 -0.116000 0.153200 -vn -0.770261 0.552291 0.318862 -v 0.015750 -0.115833 0.152575 -vn -0.770265 0.318861 0.552286 -v 0.015750 -0.115375 0.152117 -vn -0.770258 -0.000000 0.637732 -v 0.015750 -0.114750 0.151950 -vn -0.770265 -0.318861 0.552286 -v 0.015750 -0.114125 0.152117 -vn -0.770261 0.637728 0.000000 -v 0.015750 -0.100000 0.153200 -vn -0.770261 0.552291 0.318862 -v 0.015750 -0.099833 0.152575 -vn -0.770259 -0.552293 0.318864 -v 0.015750 -0.097667 0.152575 -vn -0.770264 -0.637725 -0.000000 -v 0.015750 -0.097500 0.153200 -vn -0.770263 0.552286 -0.318865 -v 0.015750 -0.099833 0.153825 -vn -0.770265 0.318861 0.552286 -v 0.015750 -0.099375 0.152117 -vn -0.770258 0.000001 0.637732 -v 0.015750 -0.098750 0.151950 -vn -0.770266 -0.318861 0.552284 -v 0.015750 -0.098125 0.152117 -vn -0.770261 -0.552288 -0.318867 -v 0.015750 -0.097667 0.153825 -vn -0.770261 -0.318866 -0.552288 -v 0.015750 -0.098125 0.154283 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.096550 0.156700 -vn -0.770264 0.000001 -0.637725 -v 0.015750 -0.098750 0.154450 -vn -0.770260 0.318866 -0.552291 -v 0.015750 -0.099375 0.154283 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.095175 0.156700 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.119500 0.150425 -vn -0.904534 0.301511 -0.301511 -v 0.015750 -0.117500 0.149500 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.119500 0.146700 -vn -0.707107 0.707107 -0.000000 -v 0.015750 -0.117500 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.145775 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.117500 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.119500 0.141950 -vn -0.707107 0.707107 0.000000 -v 0.015750 -0.117500 0.141950 -vn -0.904534 0.301511 0.301511 -v 0.015750 -0.117500 0.140200 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.116750 0.140200 -vn -0.707107 0.000000 -0.707107 -v 0.015750 -0.135500 0.154700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.151475 -vn -1.000000 0.000000 -0.000000 -v 0.015750 -0.135500 0.150425 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.122050 0.150425 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 -0.122050 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.141950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.136850 0.141950 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.136850 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.125325 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.125325 0.129725 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.129725 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.122050 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.129725 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.135500 0.128975 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.135500 0.124700 -vn -0.942505 -0.074364 -0.325814 -v 0.015750 -0.128777 0.130868 -vn -0.707107 -0.707107 0.000000 -v 0.015750 -0.090000 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 -0.116750 0.124700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.096550 0.122700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.104750 0.122700 -vn -0.707107 -0.000000 0.707107 -v 0.015750 -0.106300 0.122700 -vn -0.707107 -0.000000 0.707107 -v 0.015750 -0.112250 0.122700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.116750 0.122700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.119500 0.122700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.122050 0.122700 -vn -0.707107 0.000000 0.707107 -v 0.015750 -0.125325 0.122700 -vn -0.577350 0.577350 0.577350 -v 0.015750 -0.128000 0.122700 -vn 0.770261 0.637728 -0.000000 -v 0.016750 -0.100000 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.016750 -0.099833 0.153825 -vn 0.770260 0.318865 -0.552291 -v 0.016750 -0.099375 0.154283 -vn 0.770264 0.000001 -0.637726 -v 0.016750 -0.098750 0.154450 -vn 0.770261 -0.318866 -0.552288 -v 0.016750 -0.098125 0.154283 -vn 0.770261 -0.552288 -0.318867 -v 0.016750 -0.097667 0.153825 -vn 0.770264 -0.637725 0.000000 -v 0.016750 -0.097500 0.153200 -vn 0.770259 -0.552293 0.318864 -v 0.016750 -0.097667 0.152575 -vn 0.770266 -0.318861 0.552284 -v 0.016750 -0.098125 0.152117 -vn 0.770258 0.000001 0.637732 -v 0.016750 -0.098750 0.151950 -vn 0.770265 0.318861 0.552286 -v 0.016750 -0.099375 0.152117 -vn 0.770261 0.552291 0.318862 -v 0.016750 -0.099833 0.152575 -vn 0.770264 0.637725 -0.000000 -v 0.016750 -0.108000 0.153200 -vn 0.770261 0.552288 -0.318867 -v 0.016750 -0.107833 0.153825 -vn 0.770261 0.318866 -0.552288 -v 0.016750 -0.107375 0.154283 -vn 0.770264 -0.000000 -0.637725 -v 0.016750 -0.106750 0.154450 -vn 0.770259 -0.318866 -0.552291 -v 0.016750 -0.106125 0.154283 -vn 0.770261 -0.552288 -0.318867 -v 0.016750 -0.105667 0.153825 -vn 0.770264 -0.637725 0.000000 -v 0.016750 -0.105500 0.153200 -vn 0.770259 -0.552293 0.318864 -v 0.016750 -0.105667 0.152575 -vn 0.770265 -0.318862 0.552285 -v 0.016750 -0.106125 0.152117 -vn 0.770258 0.000000 0.637732 -v 0.016750 -0.106750 0.151950 -vn 0.770266 0.318861 0.552284 -v 0.016750 -0.107375 0.152117 -vn 0.770259 0.552293 0.318864 -v 0.016750 -0.107833 0.152575 -vn 0.770264 0.637725 0.000000 -v 0.016750 -0.094750 0.147700 -vn 0.770259 0.552293 -0.318864 -v 0.016750 -0.094583 0.148325 -vn 0.770266 0.318861 -0.552284 -v 0.016750 -0.094125 0.148783 -vn 0.770259 -0.000001 -0.637732 -v 0.016750 -0.093500 0.148950 -vn 0.770266 -0.318862 -0.552283 -v 0.016750 -0.092875 0.148783 -vn 0.770259 -0.552293 -0.318864 -v 0.016750 -0.092417 0.148325 -vn 0.770264 -0.637725 0.000000 -v 0.016750 -0.092250 0.147700 -vn 0.770261 -0.552288 0.318867 -v 0.016750 -0.092417 0.147075 -vn 0.770261 -0.318867 0.552288 -v 0.016750 -0.092875 0.146617 -vn 0.770264 -0.000001 0.637725 -v 0.016750 -0.093500 0.146450 -vn 0.770261 0.318866 0.552288 -v 0.016750 -0.094125 0.146617 -vn 0.770261 0.552288 0.318867 -v 0.016750 -0.094583 0.147075 -vn 0.770261 0.637728 -0.000000 -v 0.016750 -0.116000 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.016750 -0.115833 0.153825 -vn 0.770260 0.318865 -0.552291 -v 0.016750 -0.115375 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.016750 -0.114750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v 0.016750 -0.114125 0.154283 -vn 0.770263 -0.552286 -0.318865 -v 0.016750 -0.113667 0.153825 -vn 0.770261 -0.637728 0.000000 -v 0.016750 -0.113500 0.153200 -vn 0.770261 -0.552291 0.318862 -v 0.016750 -0.113667 0.152575 -vn 0.770265 -0.318861 0.552286 -v 0.016750 -0.114125 0.152117 -vn 0.770258 0.000000 0.637732 -v 0.016750 -0.114750 0.151950 -vn 0.770265 0.318861 0.552286 -v 0.016750 -0.115375 0.152117 -vn 0.770261 0.552291 0.318862 -v 0.016750 -0.115833 0.152575 -vn 0.609994 0.686243 -0.396204 -v 0.016750 -0.117250 0.127643 -vn 0.609994 0.686244 0.396203 -v 0.016750 -0.117250 0.124757 -vn 0.609994 -0.686244 0.396202 -v 0.016750 -0.112250 0.124757 -vn 0.609994 -0.686243 -0.396203 -v 0.016750 -0.112250 0.127643 -vn 0.609995 -0.000001 -0.792406 -v 0.016750 -0.114750 0.129087 -vn 0.609994 -0.000000 0.792406 -v 0.016750 -0.114750 0.123313 -vn 0.609995 -0.686244 -0.396202 -v 0.016750 -0.112250 0.154643 -vn 0.609994 -0.000001 -0.792406 -v 0.016750 -0.114750 0.156087 -vn 0.609994 -0.686244 0.396202 -v 0.016750 -0.112250 0.151757 -vn 0.609994 0.686244 0.396202 -v 0.016750 -0.117250 0.151757 -vn 0.609994 -0.000001 0.792406 -v 0.016750 -0.114750 0.150313 -vn 0.609994 0.686244 -0.396202 -v 0.016750 -0.117250 0.154643 -vn 0.609994 0.686244 0.396202 -v 0.016750 -0.109250 0.151757 -vn 0.609994 -0.000000 0.792406 -v 0.016750 -0.106750 0.150313 -vn 0.609994 0.686244 -0.396202 -v 0.016750 -0.109250 0.154643 -vn 0.609994 -0.686244 0.396202 -v 0.016750 -0.104250 0.151757 -vn 0.609995 -0.686244 -0.396202 -v 0.016750 -0.104250 0.154643 -vn 0.609994 -0.000000 -0.792406 -v 0.016750 -0.106750 0.156087 -vn 0.609994 -0.686244 0.396202 -v 0.016750 -0.096250 0.151757 -vn 0.609994 -0.686244 -0.396202 -v 0.016750 -0.096250 0.154643 -vn 0.609994 0.000001 0.792406 -v 0.016750 -0.098750 0.150313 -vn 0.609995 0.686244 -0.396202 -v 0.016750 -0.101250 0.154643 -vn 0.609995 0.686244 0.396202 -v 0.016750 -0.101250 0.151757 -vn 0.609994 0.000001 -0.792406 -v 0.016750 -0.098750 0.156087 -vn 0.609994 -0.686244 0.396203 -v 0.016750 -0.091000 0.146257 -vn 0.609995 -0.686244 -0.396200 -v 0.016750 -0.091000 0.149143 -vn 0.609995 -0.000000 0.792406 -v 0.016750 -0.093500 0.144813 -vn 0.609995 0.686244 -0.396201 -v 0.016750 -0.096000 0.149143 -vn 0.609994 0.686243 0.396204 -v 0.016750 -0.096000 0.146257 -vn 0.609994 -0.000001 -0.792406 -v 0.016750 -0.093500 0.150587 -vn 0.609994 -0.686243 0.396203 -v 0.016750 -0.091000 0.130257 -vn 0.609994 -0.686244 -0.396203 -v 0.016750 -0.091000 0.133143 -vn 0.609994 -0.000001 0.792406 -v 0.016750 -0.093500 0.128813 -vn 0.609994 0.686243 0.396204 -v 0.016750 -0.096000 0.130257 -vn 0.609994 0.686243 -0.396204 -v 0.016750 -0.096000 0.133143 -vn 0.609995 -0.000001 -0.792406 -v 0.016750 -0.093500 0.134587 -vn 0.609994 -0.686244 0.396203 -v 0.016750 -0.096250 0.124757 -vn 0.609994 -0.686243 -0.396204 -v 0.016750 -0.096250 0.127643 -vn 0.609994 0.686244 0.396202 -v 0.016750 -0.101250 0.124757 -vn 0.609994 0.000001 0.792406 -v 0.016750 -0.098750 0.123313 -vn 0.609994 0.686243 -0.396203 -v 0.016750 -0.101250 0.127643 -vn 0.609995 0.000000 -0.792406 -v 0.016750 -0.098750 0.129087 -vn 0.609994 -0.686244 0.396203 -v 0.016750 -0.104250 0.124757 -vn 0.609994 -0.686243 -0.396203 -v 0.016750 -0.104250 0.127643 -vn 0.609994 -0.000000 0.792406 -v 0.016750 -0.106750 0.123313 -vn 0.609994 0.686244 0.396203 -v 0.016750 -0.109250 0.124757 -vn 0.609994 0.686243 -0.396204 -v 0.016750 -0.109250 0.127643 -vn 0.609994 -0.000000 -0.792406 -v 0.016750 -0.106750 0.129087 -vn -0.904093 0.095090 -0.416623 -v 0.016750 -0.130001 0.129894 -vn -0.904093 -0.095090 -0.416623 -v 0.016750 -0.128999 0.129894 -vn -0.904092 -0.266441 -0.334107 -v 0.016750 -0.128097 0.129459 -vn -0.904093 -0.385017 -0.185413 -v 0.016750 -0.127473 0.128676 -vn -0.904093 -0.427335 -0.000000 -v 0.016750 -0.127250 0.127700 -vn -0.904093 -0.385016 0.185412 -v 0.016750 -0.127473 0.126724 -vn -0.904093 -0.266439 0.334105 -v 0.016750 -0.128097 0.125941 -vn -0.904093 -0.095089 0.416623 -v 0.016750 -0.128999 0.125506 -vn -0.904093 0.095087 0.416622 -v 0.016750 -0.130001 0.125506 -vn -0.904092 0.266441 0.334107 -v 0.016750 -0.130903 0.125941 -vn -0.904093 0.385017 0.185413 -v 0.016750 -0.131527 0.126724 -vn -0.904093 0.427335 0.000000 -v 0.016750 -0.131750 0.127700 -vn -0.904093 0.385016 -0.185412 -v 0.016750 -0.131527 0.128676 -vn -0.904091 0.266439 -0.334110 -v 0.016750 -0.130903 0.129459 -vn -0.904093 0.095091 -0.416623 -v 0.016750 -0.130001 0.153894 -vn -0.904092 -0.095093 -0.416623 -v 0.016750 -0.128999 0.153894 -vn -0.904094 -0.266438 -0.334104 -v 0.016750 -0.128097 0.153459 -vn -0.904093 -0.385017 -0.185414 -v 0.016750 -0.127473 0.152676 -vn -0.904093 -0.427335 -0.000001 -v 0.016750 -0.127250 0.151700 -vn -0.904092 -0.385017 0.185415 -v 0.016750 -0.127473 0.150724 -vn -0.904094 -0.266440 0.334103 -v 0.016750 -0.128097 0.149941 -vn -0.904092 -0.095092 0.416622 -v 0.016750 -0.128999 0.149506 -vn -0.904093 0.095091 0.416622 -v 0.016750 -0.130001 0.149506 -vn -0.904093 0.266440 0.334105 -v 0.016750 -0.130903 0.149941 -vn -0.904092 0.385018 0.185415 -v 0.016750 -0.131527 0.150724 -vn -0.904093 0.427335 -0.000000 -v 0.016750 -0.131750 0.151700 -vn -0.904092 0.385017 -0.185416 -v 0.016750 -0.131527 0.152676 -vn -0.904093 0.266440 -0.334105 -v 0.016750 -0.130903 0.153459 -vn 0.770262 -0.637727 0.000000 -v -0.068000 -0.127400 0.105200 -vn -0.770262 -0.637727 0.000000 -v -0.070000 -0.127400 0.105200 -vn 0.770262 -0.552287 0.318865 -v -0.068000 -0.127681 0.104150 -vn -0.770262 -0.552287 0.318865 -v -0.070000 -0.127681 0.104150 -vn 0.770262 -0.318862 0.552290 -v -0.068000 -0.128450 0.103381 -vn -0.770262 -0.318862 0.552290 -v -0.070000 -0.128450 0.103381 -vn 0.770261 0.000000 0.637729 -v -0.068000 -0.129500 0.103100 -vn -0.770261 0.000000 0.637729 -v -0.070000 -0.129500 0.103100 -vn 0.770262 0.318862 0.552290 -v -0.068000 -0.130550 0.103381 -vn -0.770262 0.318862 0.552290 -v -0.070000 -0.130550 0.103381 -vn 0.770264 0.552287 0.318861 -v -0.068000 -0.131319 0.104150 -vn -0.770264 0.552287 0.318861 -v -0.070000 -0.131319 0.104150 -vn 0.770259 0.637731 0.000000 -v -0.068000 -0.131600 0.105200 -vn -0.770259 0.637731 0.000000 -v -0.070000 -0.131600 0.105200 -vn 0.770265 0.552286 -0.318862 -v -0.068000 -0.131319 0.106250 -vn -0.770265 0.552286 -0.318862 -v -0.070000 -0.131319 0.106250 -vn 0.770260 0.318863 -0.552291 -v -0.068000 -0.130550 0.107019 -vn -0.770260 0.318863 -0.552291 -v -0.070000 -0.130550 0.107019 -vn 0.770263 -0.000000 -0.637727 -v -0.068000 -0.129500 0.107300 -vn -0.770262 0.000000 -0.637727 -v -0.070000 -0.129500 0.107300 -vn 0.770260 -0.318863 -0.552291 -v -0.068000 -0.128450 0.107019 -vn -0.770260 -0.318863 -0.552291 -v -0.070000 -0.128450 0.107019 -vn 0.770263 -0.552286 -0.318866 -v -0.068000 -0.127681 0.106250 -vn -0.770263 -0.552286 -0.318866 -v -0.070000 -0.127681 0.106250 -vn 0.770262 -0.637727 0.000001 -v -0.068000 -0.127400 0.129200 -vn -0.770262 -0.637727 0.000001 -v -0.070000 -0.127400 0.129200 -vn 0.770261 -0.552288 0.318865 -v -0.068000 -0.127681 0.128150 -vn -0.770261 -0.552288 0.318865 -v -0.070000 -0.127681 0.128150 -vn 0.770263 -0.318860 0.552289 -v -0.068000 -0.128450 0.127381 -vn -0.770263 -0.318860 0.552289 -v -0.070000 -0.128450 0.127381 -vn 0.770259 0.000000 0.637731 -v -0.068000 -0.129500 0.127100 -vn -0.770259 -0.000000 0.637731 -v -0.070000 -0.129500 0.127100 -vn 0.770263 0.318860 0.552289 -v -0.068000 -0.130550 0.127381 -vn -0.770263 0.318860 0.552289 -v -0.070000 -0.130550 0.127381 -vn 0.770263 0.552289 0.318860 -v -0.068000 -0.131319 0.128150 -vn -0.770263 0.552289 0.318860 -v -0.070000 -0.131319 0.128150 -vn 0.770259 0.637731 0.000001 -v -0.068000 -0.131600 0.129200 -vn -0.770259 0.637732 0.000001 -v -0.070000 -0.131600 0.129200 -vn 0.770265 0.552286 -0.318861 -v -0.068000 -0.131319 0.130250 -vn -0.770265 0.552286 -0.318861 -v -0.070000 -0.131319 0.130250 -vn 0.770260 0.318863 -0.552291 -v -0.068000 -0.130550 0.131019 -vn -0.770260 0.318863 -0.552291 -v -0.070000 -0.130550 0.131019 -vn 0.770263 -0.000000 -0.637727 -v -0.068000 -0.129500 0.131300 -vn -0.770263 0.000000 -0.637727 -v -0.070000 -0.129500 0.131300 -vn 0.770260 -0.318863 -0.552291 -v -0.068000 -0.128450 0.131019 -vn -0.770260 -0.318863 -0.552291 -v -0.070000 -0.128450 0.131019 -vn 0.770263 -0.552286 -0.318866 -v -0.068000 -0.127681 0.130250 -vn -0.770263 -0.552286 -0.318866 -v -0.070000 -0.127681 0.130250 -vn -0.770264 0.637725 -0.000000 -v -0.068000 -0.094750 0.125200 -vn 0.770264 0.637725 0.000000 -v -0.067000 -0.094750 0.125200 -vn -0.770261 0.552288 0.318867 -v -0.068000 -0.094583 0.124575 -vn 0.770261 0.552288 0.318867 -v -0.067000 -0.094583 0.124575 -vn -0.770261 0.318866 0.552288 -v -0.068000 -0.094125 0.124117 -vn 0.770261 0.318866 0.552288 -v -0.067000 -0.094125 0.124117 -vn -0.770264 -0.000001 0.637725 -v -0.068000 -0.093500 0.123950 -vn 0.770264 -0.000001 0.637726 -v -0.067000 -0.093500 0.123950 -vn -0.770261 -0.318867 0.552288 -v -0.068000 -0.092875 0.124117 -vn 0.770261 -0.318867 0.552288 -v -0.067000 -0.092875 0.124117 -vn -0.770261 -0.552288 0.318867 -v -0.068000 -0.092417 0.124575 -vn 0.770261 -0.552288 0.318867 -v -0.067000 -0.092417 0.124575 -vn -0.770264 -0.637725 0.000000 -v -0.068000 -0.092250 0.125200 -vn 0.770264 -0.637725 -0.000000 -v -0.067000 -0.092250 0.125200 -vn -0.770261 -0.552288 -0.318867 -v -0.068000 -0.092417 0.125825 -vn 0.770261 -0.552288 -0.318867 -v -0.067000 -0.092417 0.125825 -vn -0.770261 -0.318867 -0.552288 -v -0.068000 -0.092875 0.126283 -vn 0.770261 -0.318867 -0.552288 -v -0.067000 -0.092875 0.126283 -vn -0.770264 -0.000001 -0.637726 -v -0.068000 -0.093500 0.126450 -vn 0.770264 -0.000001 -0.637725 -v -0.067000 -0.093500 0.126450 -vn -0.770261 0.318866 -0.552288 -v -0.068000 -0.094125 0.126283 -vn 0.770261 0.318866 -0.552288 -v -0.067000 -0.094125 0.126283 -vn -0.770261 0.552288 -0.318867 -v -0.068000 -0.094583 0.125825 -vn 0.770261 0.552288 -0.318867 -v -0.067000 -0.094583 0.125825 -vn -0.770261 0.637729 -0.000002 -v -0.068000 -0.116000 0.130700 -vn 0.770261 0.637729 -0.000002 -v -0.067000 -0.116000 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.068000 -0.115833 0.130075 -vn 0.770264 0.552286 0.318863 -v -0.067000 -0.115833 0.130075 -vn -0.770260 0.318865 0.552291 -v -0.068000 -0.115375 0.129617 -vn 0.770260 0.318865 0.552291 -v -0.067000 -0.115375 0.129617 -vn -0.770264 0.000000 0.637725 -v -0.068000 -0.114750 0.129450 -vn 0.770264 -0.000000 0.637725 -v -0.067000 -0.114750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.068000 -0.114125 0.129617 -vn 0.770260 -0.318865 0.552291 -v -0.067000 -0.114125 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.068000 -0.113667 0.130075 -vn 0.770264 -0.552286 0.318863 -v -0.067000 -0.113667 0.130075 -vn -0.770261 -0.637729 -0.000002 -v -0.068000 -0.113500 0.130700 -vn 0.770261 -0.637729 -0.000002 -v -0.067000 -0.113500 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.068000 -0.113667 0.131325 -vn 0.770263 -0.552286 -0.318865 -v -0.067000 -0.113667 0.131325 -vn -0.770260 -0.318865 -0.552291 -v -0.068000 -0.114125 0.131783 -vn 0.770260 -0.318865 -0.552291 -v -0.067000 -0.114125 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.068000 -0.114750 0.131950 -vn 0.770264 0.000000 -0.637725 -v -0.067000 -0.114750 0.131950 -vn -0.770260 0.318865 -0.552291 -v -0.068000 -0.115375 0.131783 -vn 0.770260 0.318865 -0.552291 -v -0.067000 -0.115375 0.131783 -vn -0.770263 0.552286 -0.318865 -v -0.068000 -0.115833 0.131325 -vn 0.770263 0.552286 -0.318865 -v -0.067000 -0.115833 0.131325 -vn -0.770263 0.637726 -0.000002 -v -0.068000 -0.108000 0.130700 -vn 0.770263 0.637726 -0.000002 -v -0.067000 -0.108000 0.130700 -vn -0.770261 0.552288 0.318865 -v -0.068000 -0.107833 0.130075 -vn 0.770261 0.552288 0.318865 -v -0.067000 -0.107833 0.130075 -vn -0.770261 0.318866 0.552288 -v -0.068000 -0.107375 0.129617 -vn 0.770261 0.318866 0.552288 -v -0.067000 -0.107375 0.129617 -vn -0.770264 -0.000001 0.637725 -v -0.068000 -0.106750 0.129450 -vn 0.770264 -0.000001 0.637726 -v -0.067000 -0.106750 0.129450 -vn -0.770261 -0.318867 0.552288 -v -0.068000 -0.106125 0.129617 -vn 0.770261 -0.318867 0.552288 -v -0.067000 -0.106125 0.129617 -vn -0.770261 -0.552288 0.318865 -v -0.068000 -0.105667 0.130075 -vn 0.770261 -0.552288 0.318865 -v -0.067000 -0.105667 0.130075 -vn -0.770263 -0.637726 -0.000002 -v -0.068000 -0.105500 0.130700 -vn 0.770263 -0.637726 -0.000002 -v -0.067000 -0.105500 0.130700 -vn -0.770261 -0.552288 -0.318867 -v -0.068000 -0.105667 0.131325 -vn 0.770261 -0.552288 -0.318867 -v -0.067000 -0.105667 0.131325 -vn -0.770261 -0.318867 -0.552288 -v -0.068000 -0.106125 0.131783 -vn 0.770261 -0.318867 -0.552288 -v -0.067000 -0.106125 0.131783 -vn -0.770264 -0.000001 -0.637726 -v -0.068000 -0.106750 0.131950 -vn 0.770264 -0.000001 -0.637725 -v -0.067000 -0.106750 0.131950 -vn -0.770261 0.318866 -0.552288 -v -0.068000 -0.107375 0.131783 -vn 0.770261 0.318866 -0.552288 -v -0.067000 -0.107375 0.131783 -vn -0.770261 0.552288 -0.318867 -v -0.068000 -0.107833 0.131325 -vn 0.770261 0.552288 -0.318867 -v -0.067000 -0.107833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.068000 -0.100000 0.130700 -vn 0.770261 0.637729 -0.000002 -v -0.067000 -0.100000 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.068000 -0.099833 0.130075 -vn 0.770264 0.552286 0.318863 -v -0.067000 -0.099833 0.130075 -vn -0.770260 0.318865 0.552291 -v -0.068000 -0.099375 0.129617 -vn 0.770260 0.318865 0.552291 -v -0.067000 -0.099375 0.129617 -vn -0.770264 0.000001 0.637726 -v -0.068000 -0.098750 0.129450 -vn 0.770264 0.000001 0.637725 -v -0.067000 -0.098750 0.129450 -vn -0.770261 -0.318866 0.552288 -v -0.068000 -0.098125 0.129617 -vn 0.770261 -0.318866 0.552288 -v -0.067000 -0.098125 0.129617 -vn -0.770261 -0.552288 0.318865 -v -0.068000 -0.097667 0.130075 -vn 0.770261 -0.552288 0.318865 -v -0.067000 -0.097667 0.130075 -vn -0.770263 -0.637726 -0.000002 -v -0.068000 -0.097500 0.130700 -vn 0.770263 -0.637726 -0.000002 -v -0.067000 -0.097500 0.130700 -vn -0.770261 -0.552288 -0.318867 -v -0.068000 -0.097667 0.131325 -vn 0.770261 -0.552288 -0.318867 -v -0.067000 -0.097667 0.131325 -vn -0.770261 -0.318866 -0.552288 -v -0.068000 -0.098125 0.131783 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 -0.098125 0.131783 -vn -0.770264 0.000001 -0.637725 -v -0.068000 -0.098750 0.131950 -vn 0.770264 0.000001 -0.637725 -v -0.067000 -0.098750 0.131950 -vn -0.770260 0.318866 -0.552291 -v -0.068000 -0.099375 0.131783 -vn 0.770260 0.318865 -0.552291 -v -0.067000 -0.099375 0.131783 -vn -0.770263 0.552286 -0.318865 -v -0.068000 -0.099833 0.131325 -vn 0.770263 0.552286 -0.318865 -v -0.067000 -0.099833 0.131325 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.117375 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.111625 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.111625 0.106818 -vn -0.770259 -0.552292 0.318865 -v -0.070000 -0.122721 0.124750 -vn -0.770264 -0.637725 0.000001 -v -0.070000 -0.122600 0.125200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.124200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.124200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.111625 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.132768 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.117375 0.132768 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.117375 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.132768 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.132768 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.107350 -vn -0.838627 0.000000 -0.544705 -v -0.070000 -0.098750 0.133587 -vn -0.838628 0.471728 -0.272353 -v -0.070000 -0.101250 0.132143 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.132768 -vn -0.838628 -0.471729 -0.272352 -v -0.070000 -0.091000 0.110643 -vn -0.838628 -0.000000 -0.544704 -v -0.070000 -0.093500 0.112087 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.093300 0.112650 -vn -0.770264 -0.318863 -0.552285 -v -0.070000 -0.136550 0.111979 -vn -0.770259 0.000000 -0.637731 -v -0.070000 -0.137000 0.112100 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.112650 -vn -0.770261 -0.318866 -0.552288 -v -0.070000 -0.136550 0.123979 -vn -0.770263 0.000000 -0.637726 -v -0.070000 -0.137000 0.124100 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.124200 -vn -0.770256 -0.637735 0.000000 -v -0.070000 -0.137600 0.126450 -vn -0.770268 -0.552283 -0.318860 -v -0.070000 -0.137721 0.126900 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.127050 -vn -0.748360 0.331647 0.574428 -v -0.070000 -0.132200 0.112523 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.112650 -vn -0.748360 0.508111 0.426356 -v -0.070000 -0.133637 0.113729 -vn -0.692678 -0.719703 -0.047172 -v -0.070000 -0.146000 0.104700 -vn -0.707106 -0.707107 0.000000 -v -0.070000 -0.146000 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.106818 -vn -0.737702 0.088128 0.669350 -v -0.070000 -0.103700 0.107200 -vn -0.565703 0.649075 0.508607 -v -0.070000 -0.097306 0.107200 -vn -0.735124 0.672940 -0.082126 -v -0.070000 -0.097400 0.106820 -vn -0.838628 -0.000002 0.544704 -v -0.070000 -0.093500 0.106313 -vn -0.707106 -0.353556 0.612371 -v -0.070000 -0.093300 0.106429 -vn -0.678874 0.190038 -0.709236 -v -0.070000 -0.093412 0.095041 -vn -0.764744 0.070005 -0.640520 -v -0.070000 -0.096598 0.107695 -vn -0.561187 -0.474787 -0.677973 -v -0.070000 -0.097000 0.107548 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.097000 0.110200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.117375 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.111625 0.117200 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.111625 0.116700 -vn -0.770264 0.000000 0.637725 -v -0.070000 -0.122750 0.129450 -vn -0.770260 -0.318866 0.552291 -v -0.070000 -0.122125 0.129617 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.127582 -vn -0.838628 0.471727 -0.272353 -v -0.070000 -0.109250 0.132143 -vn -0.838628 0.471728 0.272353 -v -0.070000 -0.109250 0.129257 -vn -0.838627 -0.000000 0.544705 -v -0.070000 -0.106750 0.127813 -vn -0.838628 -0.471728 0.272353 -v -0.070000 -0.104250 0.129257 -vn -0.838628 0.471728 -0.272353 -v -0.070000 -0.096000 0.126643 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.096000 0.124200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.096125 0.124200 -vn -0.838628 0.471728 0.272352 -v -0.070000 -0.096000 0.123757 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.096125 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.093300 0.132768 -vn -0.707105 -0.353554 -0.612374 -v -0.070000 -0.093300 0.127971 -vn -0.838628 -0.000002 -0.544704 -v -0.070000 -0.093500 0.128087 -vn -0.764747 -0.232681 -0.600850 -v -0.070000 -0.096175 0.128439 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.096125 0.132768 -vn -0.764747 -0.483921 -0.425422 -v -0.070000 -0.095824 0.128194 -vn -0.764744 -0.625713 -0.153784 -v -0.070000 -0.095626 0.127815 -vn -0.764749 -0.625987 0.152640 -v -0.070000 -0.095626 0.127387 -vn -0.678874 0.709236 0.190038 -v -0.070000 -0.086341 0.132288 -vn -0.692678 0.719703 0.047171 -v -0.070000 -0.086000 0.129700 -vn -0.707108 -0.353552 -0.612371 -v -0.070000 -0.092625 0.127582 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.127582 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.127050 -vn -0.707106 -0.353553 -0.612373 -v -0.070000 -0.091704 0.127050 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.117200 -vn -0.838628 -0.471729 0.272352 -v -0.070000 -0.091000 0.123757 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.124200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.091000 0.124200 -vn -0.838628 -0.471727 -0.272353 -v -0.070000 -0.091000 0.126643 -vn -0.770261 -0.637729 -0.000002 -v -0.070000 -0.121500 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.070000 -0.121667 0.131325 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.132768 -vn -0.770264 -0.552286 0.318863 -v -0.070000 -0.121667 0.130075 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.127582 -vn -0.770263 0.552286 -0.318865 -v -0.070000 -0.123833 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.070000 -0.124000 0.130700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.132768 -vn -0.770264 0.552286 0.318863 -v -0.070000 -0.123833 0.130075 -vn -0.770260 0.318866 0.552291 -v -0.070000 -0.123375 0.129617 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.127582 -vn -0.770260 -0.318866 -0.552291 -v -0.070000 -0.122125 0.131783 -vn -0.770264 -0.000000 -0.637725 -v -0.070000 -0.122750 0.131950 -vn -0.770260 0.318866 -0.552291 -v -0.070000 -0.123375 0.131783 -vn -0.770261 -0.637728 0.000000 -v -0.070000 -0.121500 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.070000 -0.121667 0.104325 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.106818 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.122050 0.094700 -vn -0.770262 -0.318863 0.552289 -v -0.070000 -0.122125 0.102617 -vn -0.707106 0.000000 -0.707108 -v -0.070000 -0.119500 0.094700 -vn -0.770262 -0.552289 0.318863 -v -0.070000 -0.121667 0.103075 -vn -0.770261 -0.318867 -0.552288 -v -0.070000 -0.122125 0.104783 -vn -0.770264 -0.000000 -0.637725 -v -0.070000 -0.122750 0.104950 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.106818 -vn -0.770261 0.318867 -0.552288 -v -0.070000 -0.123375 0.104783 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.125900 0.094700 -vn -0.770262 0.318863 0.552289 -v -0.070000 -0.123375 0.102617 -vn -0.770261 0.000000 0.637728 -v -0.070000 -0.122750 0.102450 -vn -0.770262 0.552289 -0.318863 -v -0.070000 -0.123833 0.104325 -vn -0.770261 0.637728 -0.000000 -v -0.070000 -0.124000 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.070000 -0.123833 0.103075 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.111625 0.107400 -vn -0.904534 -0.301511 0.301511 -v -0.070000 -0.111000 0.107400 -vn -0.770264 -0.552285 -0.318863 -v -0.070000 -0.107221 0.109650 -vn -0.770260 -0.318864 -0.552292 -v -0.070000 -0.107550 0.109979 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.110200 -vn -0.770263 0.000000 -0.637726 -v -0.070000 -0.108000 0.110100 -vn -0.770261 0.318866 -0.552288 -v -0.070000 -0.108450 0.109979 -vn -0.770261 0.552288 -0.318866 -v -0.070000 -0.108779 0.109650 -vn -0.707106 -0.707107 0.000000 -v -0.070000 -0.111000 0.110200 -vn -0.770263 0.637726 0.000000 -v -0.070000 -0.108900 0.109200 -vn -0.770260 0.552292 0.318864 -v -0.070000 -0.108779 0.108750 -vn -0.770264 0.318863 0.552285 -v -0.070000 -0.108450 0.108421 -vn -0.770259 -0.000000 0.637731 -v -0.070000 -0.108000 0.108300 -vn -0.770263 -0.318861 0.552289 -v -0.070000 -0.107550 0.108421 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.107350 -vn -0.770263 -0.552289 0.318861 -v -0.070000 -0.107221 0.108750 -vn -0.770259 -0.637731 -0.000000 -v -0.070000 -0.107100 0.109200 -vn -0.707106 0.000000 0.707108 -v -0.070000 -0.117375 0.107400 -vn -0.904534 0.301511 0.301511 -v -0.070000 -0.117500 0.107400 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.110200 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.117500 0.110200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.112650 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.117500 0.112650 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.114950 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.117500 0.114950 -vn -0.904534 0.301511 -0.301511 -v -0.070000 -0.117500 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.117200 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.117375 0.116700 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.111000 0.114950 -vn -0.904534 -0.301511 -0.301511 -v -0.070000 -0.111000 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.114950 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.112650 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.111000 0.112650 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.110200 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.104000 0.110200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.112650 -vn -0.737702 0.088128 -0.669350 -v -0.070000 -0.103700 0.113200 -vn -0.770259 0.318870 -0.552288 -v -0.070000 -0.103850 0.113160 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.114950 -vn -0.737702 -0.088128 -0.669350 -v -0.070000 -0.097300 0.113200 -vn -0.770265 -0.552289 -0.318854 -v -0.070000 -0.097040 0.113050 -vn -0.770260 -0.318870 -0.552288 -v -0.070000 -0.097150 0.113160 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.096125 0.114950 -vn -0.770260 0.552288 -0.318870 -v -0.070000 -0.103960 0.113050 -vn -0.737702 0.669350 -0.088128 -v -0.070000 -0.104000 0.112900 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.104000 0.112650 -vn -0.737697 -0.669358 -0.088113 -v -0.070000 -0.097000 0.112900 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.096125 0.112650 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.097000 0.112650 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.096125 0.110200 -vn -0.764747 -0.233779 -0.600425 -v -0.070000 -0.096173 0.107639 -vn -0.764744 -0.625713 0.153784 -v -0.070000 -0.095626 0.106585 -vn -0.764748 -0.625989 -0.152637 -v -0.070000 -0.095626 0.107013 -vn -0.764745 -0.484695 -0.424541 -v -0.070000 -0.095823 0.107393 -vn -0.707107 0.353552 0.612373 -v -0.070000 -0.095296 0.107350 -vn -0.760382 -0.495132 0.420315 -v -0.070000 -0.095824 0.106206 -vn -0.735144 -0.339260 0.586913 -v -0.070000 -0.096118 0.105985 -vn -0.692678 0.047171 -0.719703 -v -0.070000 -0.096000 0.094700 -vn -0.707107 0.000000 -0.707106 -v -0.070000 -0.096125 0.094700 -vn -0.838628 0.000000 -0.544705 -v -0.070000 -0.098750 0.106587 -vn -0.838628 0.471729 -0.272352 -v -0.070000 -0.101250 0.105143 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.106818 -vn -0.838628 -0.471728 0.272352 -v -0.070000 -0.096250 0.102257 -vn -0.838628 -0.471728 -0.272352 -v -0.070000 -0.096250 0.105143 -vn -0.739260 -0.177494 0.649608 -v -0.070000 -0.096175 0.105961 -vn -0.764746 0.071180 0.640389 -v -0.070000 -0.096599 0.105906 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.104125 0.094700 -vn -0.838628 0.471729 0.272352 -v -0.070000 -0.101250 0.102257 -vn -0.838628 0.000000 0.544705 -v -0.070000 -0.098750 0.100813 -vn -0.764747 0.358941 0.535092 -v -0.070000 -0.097001 0.106053 -vn -0.764746 0.565526 0.308779 -v -0.070000 -0.097290 0.106369 -vn -0.737702 0.669350 0.088128 -v -0.070000 -0.104000 0.107500 -vn -0.770259 0.552288 0.318870 -v -0.070000 -0.103960 0.107350 -vn -0.770260 0.318870 0.552288 -v -0.070000 -0.103850 0.107240 -vn -0.737612 0.669601 0.086966 -v -0.070000 -0.097400 0.106782 -vn -0.678875 0.367126 0.635883 -v -0.070000 -0.091000 0.138360 -vn -0.678874 0.519196 0.519197 -v -0.070000 -0.088929 0.136771 -vn -0.678874 0.635883 0.367127 -v -0.070000 -0.087340 0.134700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.132768 -vn -0.678875 -0.709235 0.190039 -v -0.070000 -0.145659 0.132288 -vn -0.678875 -0.635883 0.367126 -v -0.070000 -0.144660 0.134700 -vn -0.678874 -0.519197 0.519197 -v -0.070000 -0.143071 0.136771 -vn -0.678875 -0.367126 0.635883 -v -0.070000 -0.141000 0.138360 -vn -0.678875 -0.190039 0.709235 -v -0.070000 -0.138588 0.139359 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.127582 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.146000 0.127582 -vn -0.692678 -0.719703 0.047172 -v -0.070000 -0.146000 0.129700 -vn -0.678875 -0.709235 -0.190039 -v -0.070000 -0.145659 0.102112 -vn -0.678874 -0.367127 -0.635883 -v -0.070000 -0.141000 0.096040 -vn -0.678874 -0.190038 -0.709236 -v -0.070000 -0.138588 0.095041 -vn -0.692678 -0.047171 -0.719703 -v -0.070000 -0.136000 0.094700 -vn -0.678874 -0.519197 -0.519196 -v -0.070000 -0.143071 0.097629 -vn -0.678875 -0.635883 -0.367126 -v -0.070000 -0.144660 0.099700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.106818 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.135500 0.094700 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.106818 -vn -0.692678 0.719703 -0.047171 -v -0.070000 -0.086000 0.104700 -vn -0.678874 0.709236 -0.190038 -v -0.070000 -0.086341 0.102112 -vn -0.678874 0.635883 -0.367127 -v -0.070000 -0.087340 0.099700 -vn -0.678874 0.519196 -0.519196 -v -0.070000 -0.088929 0.097629 -vn -0.678874 0.367127 -0.635883 -v -0.070000 -0.091000 0.096040 -vn -0.737702 0.669350 0.088128 -v -0.070000 -0.104000 0.121500 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.124200 -vn -0.737697 -0.088113 0.669358 -v -0.070000 -0.097300 0.121200 -vn -0.770265 -0.318854 0.552289 -v -0.070000 -0.097150 0.121240 -vn -0.770259 0.552288 0.318870 -v -0.070000 -0.103960 0.121350 -vn -0.770266 0.318854 0.552289 -v -0.070000 -0.103850 0.121240 -vn -0.737697 0.088113 0.669358 -v -0.070000 -0.103700 0.121200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.097000 0.124200 -vn -0.737697 -0.669358 0.088113 -v -0.070000 -0.097000 0.121500 -vn -0.770266 -0.552289 0.318854 -v -0.070000 -0.097040 0.121350 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.127050 -vn -0.729850 0.680315 -0.067009 -v -0.070000 -0.104000 0.126900 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.104000 0.124200 -vn -0.729841 0.066984 -0.680327 -v -0.070000 -0.103700 0.127200 -vn -0.753773 0.251448 -0.607125 -v -0.070000 -0.103815 0.127177 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.104125 0.127582 -vn -0.753771 0.464662 -0.464671 -v -0.070000 -0.103912 0.127112 -vn -0.753766 0.607121 -0.251480 -v -0.070000 -0.103977 0.127015 -vn -0.838628 0.471728 0.272353 -v -0.070000 -0.101250 0.129257 -vn -0.838628 0.000000 0.544705 -v -0.070000 -0.098750 0.127813 -vn -0.764746 0.071180 -0.640389 -v -0.070000 -0.096599 0.128494 -vn -0.838628 -0.471728 0.272353 -v -0.070000 -0.096250 0.129257 -vn -0.764747 0.358941 -0.535092 -v -0.070000 -0.097001 0.128347 -vn -0.764746 0.565526 -0.308779 -v -0.070000 -0.097290 0.128031 -vn -0.764746 0.644208 -0.012633 -v -0.070000 -0.097400 0.127618 -vn -0.566634 0.643195 -0.515001 -v -0.070000 -0.097306 0.127200 -vn -0.764744 -0.484694 0.424544 -v -0.070000 -0.095823 0.127007 -vn -0.764747 -0.233779 0.600425 -v -0.070000 -0.096173 0.126761 -vn -0.764742 0.070000 0.640523 -v -0.070000 -0.096598 0.126705 -vn -0.561187 -0.474792 0.677968 -v -0.070000 -0.097000 0.126852 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.117375 0.127050 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.117375 0.127000 -vn -0.904534 0.301511 -0.301511 -v -0.070000 -0.117500 0.127000 -vn -0.707106 0.000000 -0.707108 -v -0.070000 -0.111625 0.127000 -vn -0.770259 -0.318864 -0.552292 -v -0.070000 -0.107550 0.125979 -vn -0.770263 0.000000 -0.637726 -v -0.070000 -0.108000 0.126100 -vn -0.770261 0.318866 -0.552288 -v -0.070000 -0.108450 0.125979 -vn -0.770261 0.552288 -0.318866 -v -0.070000 -0.108779 0.125650 -vn -0.904534 -0.301511 -0.301511 -v -0.070000 -0.111000 0.127000 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.111000 0.124200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.124200 -vn -0.770259 -0.000000 0.637731 -v -0.070000 -0.108000 0.124300 -vn -0.770263 -0.318861 0.552289 -v -0.070000 -0.107550 0.124421 -vn -0.770264 0.637725 0.000001 -v -0.070000 -0.108900 0.125200 -vn -0.770259 0.552292 0.318865 -v -0.070000 -0.108779 0.124750 -vn -0.770264 0.318863 0.552285 -v -0.070000 -0.108450 0.124421 -vn -0.770262 -0.552289 0.318862 -v -0.070000 -0.107221 0.124750 -vn -0.770260 -0.637730 0.000001 -v -0.070000 -0.107100 0.125200 -vn -0.770264 -0.552285 -0.318863 -v -0.070000 -0.107221 0.125650 -vn -0.904534 -0.301511 0.301511 -v -0.070000 -0.111000 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.114950 -vn -0.748361 -0.623291 0.226859 -v -0.070000 -0.124426 0.115353 -vn -0.748360 -0.663293 0.000000 -v -0.070000 -0.124100 0.117200 -vn -0.748361 0.115180 0.653215 -v -0.070000 -0.130438 0.111882 -vn -0.748361 -0.115180 0.653215 -v -0.070000 -0.128562 0.111882 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.110200 -vn -0.748360 -0.331647 0.574428 -v -0.070000 -0.126800 0.112523 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.112650 -vn -0.748360 -0.508111 0.426356 -v -0.070000 -0.125363 0.113729 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.110200 -vn -0.748360 0.623291 -0.226860 -v -0.070000 -0.134574 0.119047 -vn -0.748361 0.663291 0.000000 -v -0.070000 -0.134900 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.117200 -vn -0.748360 0.623291 0.226860 -v -0.070000 -0.134574 0.115353 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.114950 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.112650 -vn -0.748360 -0.508111 -0.426356 -v -0.070000 -0.125363 0.120671 -vn -0.748361 -0.331645 -0.574428 -v -0.070000 -0.126800 0.121877 -vn -0.748360 0.115179 -0.653216 -v -0.070000 -0.130438 0.122518 -vn -0.748361 0.331645 -0.574428 -v -0.070000 -0.132200 0.121877 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.133250 0.124200 -vn -0.748360 -0.115179 -0.653216 -v -0.070000 -0.128562 0.122518 -vn -0.748361 -0.623291 -0.226859 -v -0.070000 -0.124426 0.119047 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.117200 -vn -0.770261 0.552288 0.318866 -v -0.070000 -0.139279 0.126000 -vn -0.707107 -0.707106 0.000000 -v -0.070000 -0.146000 0.124200 -vn -0.770263 0.637726 0.000000 -v -0.070000 -0.139400 0.126450 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.146000 0.127050 -vn -0.770261 0.552288 -0.318866 -v -0.070000 -0.139279 0.126900 -vn -0.770261 0.318866 0.552288 -v -0.070000 -0.138950 0.125671 -vn -0.770263 -0.000000 0.637726 -v -0.070000 -0.138500 0.125550 -vn -0.770258 -0.318862 0.552295 -v -0.070000 -0.138050 0.125671 -vn -0.770268 -0.552283 0.318860 -v -0.070000 -0.137721 0.126000 -vn -0.770261 0.318866 -0.552288 -v -0.070000 -0.138950 0.127229 -vn -0.770263 0.000000 -0.637726 -v -0.070000 -0.138500 0.127350 -vn -0.770258 -0.318862 -0.552295 -v -0.070000 -0.138050 0.127229 -vn -0.770261 -0.318866 0.552288 -v -0.070000 -0.136550 0.122421 -vn -0.770261 -0.552288 0.318866 -v -0.070000 -0.136221 0.122750 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.124200 -vn -0.770263 -0.637726 -0.000000 -v -0.070000 -0.136100 0.123200 -vn -0.770261 -0.552288 -0.318866 -v -0.070000 -0.136221 0.123650 -vn -0.748361 0.508111 -0.426356 -v -0.070000 -0.133637 0.120671 -vn -0.770258 0.318862 -0.552295 -v -0.070000 -0.137450 0.123979 -vn -0.770268 0.552283 -0.318860 -v -0.070000 -0.137779 0.123650 -vn -0.770256 0.637735 -0.000000 -v -0.070000 -0.137900 0.123200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.146000 0.117200 -vn -0.770268 0.552283 0.318860 -v -0.070000 -0.137779 0.122750 -vn -0.770258 0.318862 0.552295 -v -0.070000 -0.137450 0.122421 -vn -0.770261 -0.318866 0.552288 -v -0.070000 -0.136550 0.110421 -vn -0.770261 -0.552288 0.318866 -v -0.070000 -0.136221 0.110750 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.110200 -vn -0.770263 -0.637726 -0.000000 -v -0.070000 -0.136100 0.111200 -vn -0.770260 -0.552292 -0.318864 -v -0.070000 -0.136221 0.111650 -vn -0.770263 -0.000000 0.637726 -v -0.070000 -0.137000 0.110300 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.110200 -vn -0.770258 0.318862 0.552295 -v -0.070000 -0.137450 0.110421 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.146000 0.110200 -vn -0.770268 0.552283 0.318860 -v -0.070000 -0.137779 0.110750 -vn -0.770262 0.318858 -0.552292 -v -0.070000 -0.137450 0.111979 -vn -0.707106 -0.707107 0.000000 -v -0.070000 -0.146000 0.112650 -vn -0.770266 0.552286 -0.318857 -v -0.070000 -0.137779 0.111650 -vn -0.770256 0.637735 -0.000000 -v -0.070000 -0.137900 0.111200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.146000 0.107350 -vn -0.770261 0.552288 -0.318866 -v -0.070000 -0.139279 0.108400 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.107350 -vn -0.770256 -0.637735 0.000000 -v -0.070000 -0.137600 0.107950 -vn -0.770268 -0.552283 -0.318860 -v -0.070000 -0.137721 0.108400 -vn -0.770258 -0.318862 -0.552295 -v -0.070000 -0.138050 0.108729 -vn -0.770263 0.000000 -0.637726 -v -0.070000 -0.138500 0.108850 -vn -0.770261 0.318866 -0.552288 -v -0.070000 -0.138950 0.108729 -vn -0.770263 0.637726 0.000000 -v -0.070000 -0.139400 0.107950 -vn -0.770260 0.552292 0.318864 -v -0.070000 -0.139279 0.107500 -vn -0.770264 0.318863 0.552285 -v -0.070000 -0.138950 0.107171 -vn -0.770259 -0.000000 0.637731 -v -0.070000 -0.138500 0.107050 -vn -0.770262 -0.318858 0.552292 -v -0.070000 -0.138050 0.107171 -vn -0.770266 -0.552286 0.318857 -v -0.070000 -0.137721 0.107500 -vn -0.838628 -0.000000 0.544705 -v -0.070000 -0.114750 0.127813 -vn -0.838628 -0.471728 0.272353 -v -0.070000 -0.112250 0.129257 -vn -0.838627 -0.000000 -0.544706 -v -0.070000 -0.114750 0.133587 -vn -0.838628 0.471727 -0.272353 -v -0.070000 -0.117250 0.132143 -vn -0.838628 0.471728 0.272353 -v -0.070000 -0.117250 0.129257 -vn -0.838628 -0.471729 -0.272352 -v -0.070000 -0.104250 0.105143 -vn -0.838628 -0.000000 -0.544705 -v -0.070000 -0.106750 0.106587 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.105675 0.106818 -vn -0.838628 0.471728 -0.272352 -v -0.070000 -0.109250 0.105143 -vn -0.838628 0.471728 0.272352 -v -0.070000 -0.109250 0.102257 -vn -0.838628 -0.471729 0.272352 -v -0.070000 -0.104250 0.102257 -vn -0.838628 -0.000000 0.544704 -v -0.070000 -0.106750 0.100813 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.105675 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.111625 0.094700 -vn -0.838628 0.471727 0.272353 -v -0.070000 -0.096000 0.107757 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.096000 0.110200 -vn -0.838628 0.471728 -0.272352 -v -0.070000 -0.096000 0.110643 -vn -0.707105 -0.353553 0.612374 -v -0.070000 -0.092625 0.106818 -vn -0.707106 -0.353552 0.612374 -v -0.070000 -0.091704 0.107350 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.107350 -vn -0.838628 -0.471727 0.272353 -v -0.070000 -0.091000 0.107757 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.110200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.091000 0.110200 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.112650 -vn -0.838628 -0.471728 -0.272353 -v -0.070000 -0.096250 0.132143 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.111625 0.132768 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.111625 0.139700 -vn -0.838628 -0.000000 -0.544705 -v -0.070000 -0.106750 0.133587 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.105675 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.104125 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.096125 0.139700 -vn -0.692678 0.047172 0.719703 -v -0.070000 -0.096000 0.139700 -vn -0.678875 0.190039 0.709235 -v -0.070000 -0.093412 0.139359 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.133250 0.094700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.125900 0.107350 -vn -0.838628 -0.471728 -0.272353 -v -0.070000 -0.112250 0.132143 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.117375 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.119500 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.122050 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.125900 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.133250 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.135500 0.139700 -vn -0.692678 -0.047172 0.719703 -v -0.070000 -0.136000 0.139700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.119500 0.124200 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.117500 0.124200 -vn -0.904534 0.301511 0.301511 -v -0.070000 -0.117500 0.117700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.117375 0.117700 -vn -0.707107 0.000000 0.707107 -v -0.070000 -0.111625 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.111625 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.127050 -vn -0.770261 -0.552288 -0.318866 -v -0.070000 -0.122721 0.125650 -vn -0.770261 -0.318866 -0.552288 -v -0.070000 -0.123050 0.125979 -vn -0.770263 0.000000 -0.637726 -v -0.070000 -0.123500 0.126100 -vn -0.770260 0.318864 -0.552292 -v -0.070000 -0.123950 0.125979 -vn -0.770264 0.552285 -0.318863 -v -0.070000 -0.124279 0.125650 -vn -0.770260 0.637730 0.000001 -v -0.070000 -0.124400 0.125200 -vn -0.770262 0.552289 0.318862 -v -0.070000 -0.124279 0.124750 -vn -0.770263 0.318861 0.552289 -v -0.070000 -0.123950 0.124421 -vn -0.770259 -0.000000 0.637731 -v -0.070000 -0.123500 0.124300 -vn -0.770264 -0.318863 0.552285 -v -0.070000 -0.123050 0.124421 -vn -0.707107 -0.707107 0.000000 -v -0.070000 -0.146000 0.114950 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.114950 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.136850 0.117200 -vn -0.770263 -0.000000 0.637726 -v -0.070000 -0.137000 0.122300 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.093300 0.114950 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.093300 0.117200 -vn -0.838628 -0.000000 0.544705 -v -0.070000 -0.093500 0.122313 -vn -0.707107 0.707107 0.000000 -v -0.070000 -0.086000 0.114950 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.112650 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.110200 -vn -0.770261 -0.318866 -0.552288 -v -0.070000 -0.123050 0.109979 -vn -0.770263 0.000000 -0.637726 -v -0.070000 -0.123500 0.110100 -vn -0.770264 0.552285 -0.318863 -v -0.070000 -0.124279 0.109650 -vn -0.770259 0.637731 0.000000 -v -0.070000 -0.124400 0.109200 -vn -0.770260 0.318864 -0.552292 -v -0.070000 -0.123950 0.109979 -vn -0.770264 -0.318863 0.552285 -v -0.070000 -0.123050 0.108421 -vn -0.770260 -0.552292 0.318864 -v -0.070000 -0.122721 0.108750 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.122050 0.107350 -vn -0.770263 -0.637726 -0.000000 -v -0.070000 -0.122600 0.109200 -vn -0.770261 -0.552288 -0.318866 -v -0.070000 -0.122721 0.109650 -vn -0.770263 0.552289 0.318861 -v -0.070000 -0.124279 0.108750 -vn -0.770263 0.318861 0.552289 -v -0.070000 -0.123950 0.108421 -vn -0.770259 -0.000000 0.637731 -v -0.070000 -0.123500 0.108300 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.135500 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 -0.117375 0.106818 -vn -0.838628 -0.471728 -0.272353 -v -0.070000 -0.104250 0.132143 -vn -0.707107 0.000000 -0.707107 -v -0.070000 -0.117375 0.094700 -vn -0.838628 -0.000000 -0.544704 -v -0.070000 -0.114750 0.106587 -vn -0.838628 0.471728 -0.272352 -v -0.070000 -0.117250 0.105143 -vn -0.838628 0.471728 0.272352 -v -0.070000 -0.117250 0.102257 -vn -0.838628 -0.000000 0.544705 -v -0.070000 -0.114750 0.100813 -vn -0.838628 -0.471729 0.272352 -v -0.070000 -0.112250 0.102257 -vn -0.838628 -0.471729 -0.272352 -v -0.070000 -0.112250 0.105143 -vn 0.770256 0.637735 0.000000 -v -0.067000 -0.137900 0.123200 -vn 0.770268 0.552283 0.318860 -v -0.067000 -0.137779 0.122750 -vn 0.770258 0.318862 0.552295 -v -0.067000 -0.137450 0.122421 -vn 0.770263 0.000000 0.637726 -v -0.067000 -0.137000 0.122300 -vn 0.770261 -0.318866 0.552288 -v -0.067000 -0.136550 0.122421 -vn 0.770261 -0.552288 0.318866 -v -0.067000 -0.136221 0.122750 -vn 0.770263 -0.637726 0.000000 -v -0.067000 -0.136100 0.123200 -vn 0.770261 -0.552288 -0.318866 -v -0.067000 -0.136221 0.123650 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 -0.136550 0.123979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 -0.137000 0.124100 -vn 0.770258 0.318862 -0.552295 -v -0.067000 -0.137450 0.123979 -vn 0.770268 0.552283 -0.318860 -v -0.067000 -0.137779 0.123650 -vn 0.770260 0.637730 0.000001 -v -0.067000 -0.124400 0.125200 -vn 0.770262 0.552289 0.318862 -v -0.067000 -0.124279 0.124750 -vn 0.770263 0.318861 0.552289 -v -0.067000 -0.123950 0.124421 -vn 0.770259 0.000000 0.637731 -v -0.067000 -0.123500 0.124300 -vn 0.770264 -0.318863 0.552285 -v -0.067000 -0.123050 0.124421 -vn 0.770259 -0.552292 0.318865 -v -0.067000 -0.122721 0.124750 -vn 0.770264 -0.637725 0.000001 -v -0.067000 -0.122600 0.125200 -vn 0.770261 -0.552288 -0.318866 -v -0.067000 -0.122721 0.125650 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 -0.123050 0.125979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 -0.123500 0.126100 -vn 0.770260 0.318864 -0.552292 -v -0.067000 -0.123950 0.125979 -vn 0.770264 0.552285 -0.318863 -v -0.067000 -0.124279 0.125650 -vn 0.770264 0.637725 0.000001 -v -0.067000 -0.108900 0.125200 -vn 0.770259 0.552292 0.318865 -v -0.067000 -0.108779 0.124750 -vn 0.770264 0.318863 0.552285 -v -0.067000 -0.108450 0.124421 -vn 0.770259 0.000000 0.637731 -v -0.067000 -0.108000 0.124300 -vn 0.770263 -0.318861 0.552289 -v -0.067000 -0.107550 0.124421 -vn 0.770262 -0.552289 0.318862 -v -0.067000 -0.107221 0.124750 -vn 0.770260 -0.637730 0.000001 -v -0.067000 -0.107100 0.125200 -vn 0.770264 -0.552285 -0.318863 -v -0.067000 -0.107221 0.125650 -vn 0.770260 -0.318864 -0.552292 -v -0.067000 -0.107550 0.125979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 -0.108000 0.126100 -vn 0.770261 0.318866 -0.552288 -v -0.067000 -0.108450 0.125979 -vn 0.770261 0.552288 -0.318866 -v -0.067000 -0.108779 0.125650 -vn 0.770256 0.637735 0.000000 -v -0.067000 -0.137900 0.111200 -vn 0.770268 0.552283 0.318860 -v -0.067000 -0.137779 0.110750 -vn 0.770258 0.318862 0.552295 -v -0.067000 -0.137450 0.110421 -vn 0.770263 0.000000 0.637726 -v -0.067000 -0.137000 0.110300 -vn 0.770261 -0.318866 0.552288 -v -0.067000 -0.136550 0.110421 -vn 0.770261 -0.552288 0.318866 -v -0.067000 -0.136221 0.110750 -vn 0.770263 -0.637726 0.000000 -v -0.067000 -0.136100 0.111200 -vn 0.770259 -0.552292 -0.318864 -v -0.067000 -0.136221 0.111650 -vn 0.770265 -0.318863 -0.552285 -v -0.067000 -0.136550 0.111979 -vn 0.770259 -0.000000 -0.637731 -v -0.067000 -0.137000 0.112100 -vn 0.770262 0.318858 -0.552292 -v -0.067000 -0.137450 0.111979 -vn 0.770266 0.552286 -0.318857 -v -0.067000 -0.137779 0.111650 -vn 0.770263 0.637726 -0.000000 -v -0.067000 -0.108900 0.109200 -vn 0.770260 0.552292 0.318864 -v -0.067000 -0.108779 0.108750 -vn 0.770265 0.318863 0.552285 -v -0.067000 -0.108450 0.108421 -vn 0.770259 0.000000 0.637731 -v -0.067000 -0.108000 0.108300 -vn 0.770263 -0.318861 0.552289 -v -0.067000 -0.107550 0.108421 -vn 0.770263 -0.552289 0.318861 -v -0.067000 -0.107221 0.108750 -vn 0.770259 -0.637731 0.000000 -v -0.067000 -0.107100 0.109200 -vn 0.770264 -0.552285 -0.318863 -v -0.067000 -0.107221 0.109650 -vn 0.770260 -0.318864 -0.552292 -v -0.067000 -0.107550 0.109979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 -0.108000 0.110100 -vn 0.770261 0.318866 -0.552288 -v -0.067000 -0.108450 0.109979 -vn 0.770261 0.552288 -0.318866 -v -0.067000 -0.108779 0.109650 -vn 0.770259 0.637731 -0.000000 -v -0.067000 -0.124400 0.109200 -vn 0.770263 0.552289 0.318861 -v -0.067000 -0.124279 0.108750 -vn 0.770263 0.318861 0.552289 -v -0.067000 -0.123950 0.108421 -vn 0.770259 0.000000 0.637731 -v -0.067000 -0.123500 0.108300 -vn 0.770264 -0.318863 0.552285 -v -0.067000 -0.123050 0.108421 -vn 0.770260 -0.552292 0.318864 -v -0.067000 -0.122721 0.108750 -vn 0.770263 -0.637726 0.000000 -v -0.067000 -0.122600 0.109200 -vn 0.770261 -0.552288 -0.318866 -v -0.067000 -0.122721 0.109650 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 -0.123050 0.109979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 -0.123500 0.110100 -vn 0.770260 0.318864 -0.552292 -v -0.067000 -0.123950 0.109979 -vn 0.770264 0.552285 -0.318863 -v -0.067000 -0.124279 0.109650 -vn 0.692677 -0.719703 0.047172 -v -0.062000 -0.146000 0.129700 -vn 0.692678 -0.719703 -0.047172 -v -0.062000 -0.146000 0.104700 -vn 0.692678 -0.047171 -0.719702 -v -0.062000 -0.136000 0.094700 -vn 0.692679 0.047171 -0.719702 -v -0.062000 -0.096000 0.094700 -vn 0.692679 0.719702 -0.047171 -v -0.062000 -0.086000 0.104700 -vn 0.692678 0.719703 0.047171 -v -0.062000 -0.086000 0.129700 -vn 0.692678 0.047172 0.719702 -v -0.062000 -0.096000 0.139700 -vn 0.692678 -0.047172 0.719703 -v -0.062000 -0.136000 0.139700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.093500 0.134200 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 -0.093500 0.133700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.092000 0.133700 -vn 0.904534 0.301511 0.301511 -v -0.062000 -0.128000 0.100200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.093500 0.100200 -vn 0.678874 0.190038 -0.709236 -v -0.062000 -0.093412 0.095041 -vn 0.678874 0.367127 -0.635883 -v -0.062000 -0.091000 0.096040 -vn 0.678874 0.519196 -0.519196 -v -0.062000 -0.088929 0.097629 -vn 0.904534 0.301511 -0.301511 -v -0.062000 -0.128000 0.134200 -vn 0.678875 0.190039 0.709235 -v -0.062000 -0.093412 0.139359 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.090500 0.132200 -vn 0.678874 0.635883 0.367127 -v -0.062000 -0.087340 0.134700 -vn 0.678874 0.519196 0.519197 -v -0.062000 -0.088929 0.136771 -vn 0.742117 0.540533 0.396340 -v -0.062000 -0.141663 0.105085 -vn 0.741871 0.638647 0.204348 -v -0.062000 -0.142657 0.107037 -vn 0.725200 0.686415 0.054023 -v -0.062000 -0.143000 0.109200 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 -0.092000 0.132200 -vn 0.678875 0.367126 0.635883 -v -0.062000 -0.091000 0.138360 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 -0.090500 0.130450 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.090000 0.130450 -vn 0.678874 0.709236 0.190038 -v -0.062000 -0.086341 0.132288 -vn 0.678875 -0.709235 -0.190039 -v -0.062000 -0.145659 0.102112 -vn 0.678875 -0.635883 -0.367126 -v -0.062000 -0.144660 0.099700 -vn 0.744071 0.392700 0.540505 -v -0.062000 -0.140114 0.103537 -vn 0.678874 -0.519197 -0.519196 -v -0.062000 -0.143071 0.097629 -vn 0.744072 0.206454 0.635401 -v -0.062000 -0.138163 0.102543 -vn 0.725201 0.686415 -0.054023 -v -0.062000 -0.143000 0.125200 -vn 0.744071 0.635401 -0.206455 -v -0.062000 -0.142657 0.127363 -vn 0.678875 -0.709235 0.190039 -v -0.062000 -0.145659 0.132288 -vn 0.744071 0.540505 -0.392699 -v -0.062000 -0.141663 0.129314 -vn 0.678875 -0.635883 0.367126 -v -0.062000 -0.144660 0.134700 -vn 0.744071 0.392700 -0.540504 -v -0.062000 -0.140114 0.130863 -vn 0.678874 -0.519197 0.519197 -v -0.062000 -0.143071 0.136771 -vn 0.577350 0.577350 0.577350 -v -0.062000 -0.128000 0.100700 -vn 0.845340 0.278879 0.455661 -v -0.062000 -0.129500 0.100700 -vn 0.661187 0.577625 0.478729 -v -0.062000 -0.129897 0.101476 -vn 0.678875 -0.367126 0.635883 -v -0.062000 -0.141000 0.138360 -vn 0.744071 0.206455 -0.635401 -v -0.062000 -0.138163 0.131857 -vn 0.678875 -0.190039 0.709235 -v -0.062000 -0.138588 0.139359 -vn 0.725200 0.054022 -0.686415 -v -0.062000 -0.136000 0.132200 -vn 0.683246 0.080043 -0.725788 -v -0.062000 -0.131436 0.132200 -vn 0.661187 0.319122 -0.678964 -v -0.062000 -0.130586 0.132390 -vn 0.577350 -0.577350 0.577350 -v -0.062000 -0.090500 0.119950 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 -0.090500 0.114450 -vn 0.904534 -0.301511 0.301512 -v -0.062000 -0.090000 0.119950 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 -0.090000 0.114450 -vn 0.678874 -0.367127 -0.635883 -v -0.062000 -0.141000 0.096040 -vn 0.678874 -0.190038 -0.709236 -v -0.062000 -0.138588 0.095041 -vn 0.725200 0.054021 0.686416 -v -0.062000 -0.136000 0.102200 -vn 0.683245 0.080046 0.725788 -v -0.062000 -0.131436 0.102200 -vn 0.661189 0.319122 0.678963 -v -0.062000 -0.130586 0.102010 -vn 0.577350 0.577350 -0.577350 -v -0.062000 -0.128000 0.133700 -vn 0.845340 0.278878 -0.455662 -v -0.062000 -0.129500 0.133700 -vn 0.661188 0.577625 -0.478728 -v -0.062000 -0.129897 0.132924 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.090500 0.102200 -vn 0.577350 -0.577350 0.577350 -v -0.062000 -0.092000 0.102200 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.092000 0.100700 -vn 0.678874 0.709236 -0.190038 -v -0.062000 -0.086341 0.102112 -vn 0.904534 -0.301511 0.301511 -v -0.062000 -0.090000 0.103950 -vn 0.678874 0.635883 -0.367127 -v -0.062000 -0.087340 0.099700 -vn 0.577350 -0.577350 0.577350 -v -0.062000 -0.093500 0.100700 -vn 0.577350 -0.577350 0.577350 -v -0.062000 -0.090500 0.103950 -vn 0.737697 -0.669358 -0.088113 -v -0.067000 -0.097000 0.112900 -vn 0.770266 -0.552289 -0.318854 -v -0.067000 -0.097040 0.113050 -vn 0.770259 -0.318870 -0.552288 -v -0.067000 -0.097150 0.113160 -vn 0.737702 -0.088128 -0.669350 -v -0.067000 -0.097300 0.113200 -vn 0.737702 0.088128 -0.669350 -v -0.067000 -0.103700 0.113200 -vn 0.770260 0.318870 -0.552288 -v -0.067000 -0.103850 0.113160 -vn 0.770259 0.552288 -0.318870 -v -0.067000 -0.103960 0.113050 -vn 0.737702 0.669350 -0.088128 -v -0.067000 -0.104000 0.112900 -vn 0.737702 0.669350 0.088128 -v -0.067000 -0.104000 0.107500 -vn 0.770260 0.552288 0.318870 -v -0.067000 -0.103960 0.107350 -vn 0.770259 0.318870 0.552288 -v -0.067000 -0.103850 0.107240 -vn 0.737702 0.088128 0.669350 -v -0.067000 -0.103700 0.107200 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.104000 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.104000 0.111125 -vn 0.565925 0.644023 0.514746 -v -0.067000 -0.097306 0.107200 -vn 0.561187 -0.474787 -0.677972 -v -0.067000 -0.097000 0.107548 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.097000 0.110200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.097000 0.111125 -vn 0.748361 0.663291 0.000000 -v -0.067000 -0.134900 0.117200 -vn 0.748360 0.623291 0.226860 -v -0.067000 -0.134574 0.115353 -vn 0.748361 0.508111 0.426356 -v -0.067000 -0.133637 0.113729 -vn 0.748360 0.331647 0.574428 -v -0.067000 -0.132200 0.112523 -vn 0.748361 0.115180 0.653215 -v -0.067000 -0.130438 0.111882 -vn 0.748361 -0.115180 0.653215 -v -0.067000 -0.128562 0.111882 -vn 0.748360 -0.331647 0.574428 -v -0.067000 -0.126800 0.112523 -vn 0.748360 -0.508111 0.426356 -v -0.067000 -0.125363 0.113729 -vn 0.748361 -0.623291 0.226859 -v -0.067000 -0.124426 0.115353 -vn 0.748360 -0.663293 0.000000 -v -0.067000 -0.124100 0.117200 -vn 0.748361 -0.623291 -0.226859 -v -0.067000 -0.124426 0.119047 -vn 0.748361 -0.508111 -0.426356 -v -0.067000 -0.125363 0.120671 -vn 0.748361 -0.331645 -0.574428 -v -0.067000 -0.126800 0.121877 -vn 0.748360 -0.115179 -0.653216 -v -0.067000 -0.128562 0.122518 -vn 0.748360 0.115179 -0.653216 -v -0.067000 -0.130438 0.122518 -vn 0.748361 0.331645 -0.574428 -v -0.067000 -0.132200 0.121877 -vn 0.748360 0.508111 -0.426356 -v -0.067000 -0.133637 0.120671 -vn 0.748360 0.623291 -0.226860 -v -0.067000 -0.134574 0.119047 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.127175 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.127175 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.105425 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.105425 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.127925 -vn 0.673533 0.228411 0.702980 -v -0.067000 -0.138163 0.102543 -vn 0.689867 0.056798 0.721705 -v -0.067000 -0.136000 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.105425 -vn 0.904534 -0.301511 0.301511 -v -0.067000 -0.090500 0.103950 -vn 0.577350 -0.577350 0.577350 -v -0.067000 -0.090000 0.103950 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.105425 -vn 0.904534 -0.301511 -0.301511 -v -0.067000 -0.093500 0.133700 -vn 0.577350 -0.577350 -0.577350 -v -0.067000 -0.093500 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.095175 0.134200 -vn 0.942506 -0.074364 -0.325811 -v -0.067000 -0.128777 0.132369 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.132200 -vn 0.904534 0.301511 -0.301511 -v -0.067000 -0.128000 0.133700 -vn 0.606340 0.415113 -0.678257 -v -0.067000 -0.129500 0.133700 -vn 0.759604 0.500759 -0.415022 -v -0.067000 -0.129897 0.132924 -vn 0.942506 0.074364 -0.325811 -v -0.067000 -0.130223 0.132369 -vn 0.577350 -0.577350 -0.577350 -v -0.067000 -0.090000 0.130450 -vn 0.904534 -0.301511 -0.301511 -v -0.067000 -0.090500 0.130450 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.127925 -vn 0.577350 -0.577350 -0.577350 -v -0.067000 -0.090500 0.132200 -vn 0.904534 -0.301511 -0.301511 -v -0.067000 -0.092000 0.132200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.132200 -vn 0.577350 -0.577350 -0.577350 -v -0.067000 -0.092000 0.133700 -vn 0.577350 -0.577350 0.577350 -v -0.067000 -0.090000 0.119950 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.123275 -vn 0.904534 -0.301511 0.301511 -v -0.067000 -0.090500 0.119950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.123275 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.117200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090500 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.114950 -vn 0.904534 -0.301511 -0.301511 -v -0.067000 -0.090500 0.114450 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.111125 -vn 0.577350 -0.577350 -0.577350 -v -0.067000 -0.090000 0.114450 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.111125 -vn 0.577350 -0.577350 0.577350 -v -0.067000 -0.093500 0.100200 -vn 0.904534 -0.301511 0.301511 -v -0.067000 -0.093500 0.100700 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.105425 -vn 0.577350 -0.577350 0.577350 -v -0.067000 -0.092000 0.100700 -vn 0.904534 -0.301511 0.301511 -v -0.067000 -0.092000 0.102200 -vn 0.577350 -0.577350 0.577350 -v -0.067000 -0.090500 0.102200 -vn 0.577350 0.577350 0.577350 -v -0.067000 -0.128000 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.125325 0.100200 -vn 0.904534 0.301511 0.301511 -v -0.067000 -0.128000 0.100700 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.105425 -vn 0.942505 -0.074364 0.325813 -v -0.067000 -0.128777 0.102031 -vn 0.942506 0.074365 0.325812 -v -0.067000 -0.130223 0.102031 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.106475 -vn 0.942505 -0.334192 0.000000 -v -0.067000 -0.126250 0.105200 -vn 0.942505 -0.301098 0.145000 -v -0.067000 -0.126572 0.103790 -vn 0.942505 -0.208365 0.261281 -v -0.067000 -0.127474 0.102659 -vn 0.606340 0.415114 0.678257 -v -0.067000 -0.129500 0.100700 -vn 0.759605 0.500757 0.415022 -v -0.067000 -0.129897 0.101476 -vn 0.759603 0.276656 0.588613 -v -0.067000 -0.130586 0.102010 -vn 0.942505 0.208365 0.261283 -v -0.067000 -0.131526 0.102659 -vn 0.732634 0.074613 0.676521 -v -0.067000 -0.131436 0.102200 -vn 0.770258 -0.318862 -0.552295 -v -0.067000 -0.138050 0.108729 -vn 0.770268 -0.552283 -0.318860 -v -0.067000 -0.137721 0.108400 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.110200 -vn 0.770256 -0.637735 -0.000000 -v -0.067000 -0.137600 0.107950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.106475 -vn 0.770266 -0.552286 0.318857 -v -0.067000 -0.137721 0.107500 -vn 0.770262 -0.318858 0.552292 -v -0.067000 -0.138050 0.107171 -vn 0.770259 0.000000 0.637731 -v -0.067000 -0.138500 0.107050 -vn 0.689140 0.656176 0.307438 -v -0.067000 -0.142434 0.106443 -vn 0.678152 0.584619 0.445343 -v -0.067000 -0.141663 0.105085 -vn 0.673533 0.434466 0.597990 -v -0.067000 -0.140114 0.103537 -vn 0.770264 0.318863 0.552285 -v -0.067000 -0.138950 0.107171 -vn 0.770259 0.552292 0.318864 -v -0.067000 -0.139279 0.107500 -vn 0.685057 0.704324 0.186078 -v -0.067000 -0.142657 0.107037 -vn 0.770263 0.637726 -0.000000 -v -0.067000 -0.139400 0.107950 -vn 0.689866 0.721705 0.056800 -v -0.067000 -0.143000 0.109200 -vn 0.770261 0.552288 -0.318866 -v -0.067000 -0.139279 0.108400 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.143000 0.110200 -vn 0.770261 0.318866 -0.552288 -v -0.067000 -0.138950 0.108729 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 -0.138500 0.108850 -vn 0.673534 0.702979 -0.228413 -v -0.067000 -0.142657 0.127363 -vn 0.770263 0.637726 -0.000000 -v -0.067000 -0.139400 0.126450 -vn 0.770261 0.552288 -0.318866 -v -0.067000 -0.139279 0.126900 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.127175 -vn 0.770256 -0.637735 -0.000000 -v -0.067000 -0.137600 0.126450 -vn 0.770268 -0.552283 0.318860 -v -0.067000 -0.137721 0.126000 -vn 0.770258 -0.318862 0.552295 -v -0.067000 -0.138050 0.125671 -vn 0.770263 0.000000 0.637726 -v -0.067000 -0.138500 0.125550 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.143000 0.124200 -vn 0.770261 0.318866 0.552288 -v -0.067000 -0.138950 0.125671 -vn 0.770261 0.552288 0.318866 -v -0.067000 -0.139279 0.126000 -vn 0.689866 0.721705 -0.056800 -v -0.067000 -0.143000 0.125200 -vn 0.770261 0.318866 -0.552288 -v -0.067000 -0.138950 0.127229 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 -0.138500 0.127350 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.127925 -vn 0.770258 -0.318862 -0.552295 -v -0.067000 -0.138050 0.127229 -vn 0.770268 -0.552283 -0.318860 -v -0.067000 -0.137721 0.126900 -vn 0.689866 0.056800 -0.721705 -v -0.067000 -0.136000 0.132200 -vn 0.673533 0.228412 -0.702980 -v -0.067000 -0.138163 0.131857 -vn 0.673533 0.434466 -0.597990 -v -0.067000 -0.140114 0.130863 -vn 0.673534 0.597990 -0.434466 -v -0.067000 -0.141663 0.129314 -vn 0.770264 -0.552286 0.318863 -v -0.067000 -0.121667 0.130075 -vn 0.770260 -0.318866 0.552291 -v -0.067000 -0.122125 0.129617 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.127925 -vn 0.770264 -0.000000 0.637725 -v -0.067000 -0.122750 0.129450 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.127925 -vn 0.770260 0.318866 0.552291 -v -0.067000 -0.123375 0.129617 -vn 0.770264 0.552286 0.318863 -v -0.067000 -0.123833 0.130075 -vn 0.770261 0.637729 -0.000002 -v -0.067000 -0.124000 0.130700 -vn 0.770263 0.552286 -0.318865 -v -0.067000 -0.123833 0.131325 -vn 0.770260 0.318866 -0.552291 -v -0.067000 -0.123375 0.131783 -vn 0.770264 0.000000 -0.637725 -v -0.067000 -0.122750 0.131950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.132200 -vn 0.770260 -0.318866 -0.552291 -v -0.067000 -0.122125 0.131783 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.132200 -vn 0.770263 -0.552286 -0.318865 -v -0.067000 -0.121667 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.067000 -0.121500 0.130700 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.132200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.132200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.132200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.127175 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.127175 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.124200 -vn 0.770264 0.637725 0.000000 -v -0.067000 -0.094750 0.109200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.095175 0.106475 -vn 0.770263 -0.318865 0.552286 -v -0.067000 -0.092875 0.108117 -vn 0.770261 -0.000001 0.637729 -v -0.067000 -0.093500 0.107950 -vn 0.770263 0.318864 0.552286 -v -0.067000 -0.094125 0.108117 -vn 0.770260 0.552291 0.318865 -v -0.067000 -0.094583 0.108575 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.110200 -vn 0.770264 -0.637725 -0.000000 -v -0.067000 -0.092250 0.109200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.106475 -vn 0.770260 -0.552291 0.318865 -v -0.067000 -0.092417 0.108575 -vn 0.770260 0.552291 -0.318865 -v -0.067000 -0.094583 0.109825 -vn 0.770264 0.318864 -0.552286 -v -0.067000 -0.094125 0.110283 -vn 0.770261 -0.000001 -0.637729 -v -0.067000 -0.093500 0.110450 -vn 0.770263 -0.318865 -0.552286 -v -0.067000 -0.092875 0.110283 -vn 0.770260 -0.552291 -0.318865 -v -0.067000 -0.092417 0.109825 -vn 0.770260 0.552291 0.318865 -v -0.067000 -0.107833 0.103075 -vn 0.770264 0.637725 0.000000 -v -0.067000 -0.108000 0.103700 -vn 0.770260 0.552291 -0.318865 -v -0.067000 -0.107833 0.104325 -vn 0.770264 0.318864 0.552286 -v -0.067000 -0.107375 0.102617 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.112250 0.100200 -vn 0.770261 -0.000001 0.637729 -v -0.067000 -0.106750 0.102450 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.106300 0.100200 -vn 0.770263 -0.318865 0.552286 -v -0.067000 -0.106125 0.102617 -vn 0.770262 0.318868 -0.552286 -v -0.067000 -0.107375 0.104783 -vn 0.770264 -0.000001 -0.637725 -v -0.067000 -0.106750 0.104950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.105425 -vn 0.770260 -0.552291 -0.318865 -v -0.067000 -0.105667 0.104325 -vn 0.770264 -0.637725 -0.000000 -v -0.067000 -0.105500 0.103700 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.105425 -vn 0.770262 -0.318869 -0.552286 -v -0.067000 -0.106125 0.104783 -vn 0.770260 -0.552291 0.318865 -v -0.067000 -0.105667 0.103075 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.104750 0.100200 -vn 0.770261 0.318867 -0.552288 -v -0.067000 -0.123375 0.104783 -vn 0.770264 0.000000 -0.637725 -v -0.067000 -0.122750 0.104950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.105425 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.122050 0.100200 -vn 0.770261 -0.000000 0.637728 -v -0.067000 -0.122750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.067000 -0.123375 0.102617 -vn 0.770262 0.552289 0.318863 -v -0.067000 -0.123833 0.103075 -vn 0.770261 0.637728 0.000000 -v -0.067000 -0.124000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.067000 -0.123833 0.104325 -vn 0.770261 -0.318867 -0.552288 -v -0.067000 -0.122125 0.104783 -vn 0.770262 -0.552289 -0.318863 -v -0.067000 -0.121667 0.104325 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.105425 -vn 0.770261 -0.637728 -0.000000 -v -0.067000 -0.121500 0.103700 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.119500 0.100200 -vn 0.770262 -0.552289 0.318863 -v -0.067000 -0.121667 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.067000 -0.122125 0.102617 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.143000 0.111125 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.143000 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.123275 -vn 0.707106 0.707107 0.000000 -v -0.067000 -0.143000 0.117200 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.143000 0.123275 -vn 0.904534 -0.301511 0.301511 -v -0.067000 -0.111000 0.107400 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.112250 0.107400 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.106475 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.116750 0.107400 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.110200 -vn 0.707106 -0.707107 0.000000 -v -0.067000 -0.111000 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.112250 0.117200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.112250 0.116700 -vn 0.904534 -0.301511 -0.301511 -v -0.067000 -0.111000 0.116700 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.111000 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.111125 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.111000 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.111000 0.124200 -vn 0.904534 -0.301511 -0.301511 -v -0.067000 -0.111000 0.127000 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.127175 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.112250 0.127000 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.116750 0.127000 -vn 0.904534 0.301511 -0.301511 -v -0.067000 -0.117500 0.127000 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.127175 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.124200 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.117500 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.117200 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.116750 0.117700 -vn 0.904534 0.301511 0.301512 -v -0.067000 -0.117500 0.117700 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.117500 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.106300 0.123275 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.111000 0.123275 -vn 0.904534 -0.301511 0.301511 -v -0.067000 -0.111000 0.117700 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.112250 0.117700 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.114950 -vn 0.764304 0.644721 0.013205 -v -0.067000 -0.097400 0.106782 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.111125 -vn 0.764067 -0.232161 0.601916 -v -0.067000 -0.096175 0.105961 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.105425 -vn 0.764745 0.071180 0.640389 -v -0.067000 -0.096599 0.105906 -vn 0.764747 0.358941 0.535092 -v -0.067000 -0.097001 0.106053 -vn 0.764746 0.565526 0.308779 -v -0.067000 -0.097290 0.106369 -vn 0.764744 0.070005 -0.640520 -v -0.067000 -0.096598 0.107695 -vn 0.764747 -0.233779 -0.600425 -v -0.067000 -0.096173 0.107639 -vn 0.764745 -0.484695 -0.424541 -v -0.067000 -0.095823 0.107393 -vn 0.764748 -0.625989 -0.152637 -v -0.067000 -0.095626 0.107013 -vn 0.764744 -0.625713 0.153784 -v -0.067000 -0.095626 0.106585 -vn 0.764104 -0.485064 0.425274 -v -0.067000 -0.095824 0.106206 -vn 0.729850 0.680315 -0.067009 -v -0.067000 -0.104000 0.126900 -vn 0.753766 0.607121 -0.251480 -v -0.067000 -0.103977 0.127015 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.127175 -vn 0.566634 0.643195 -0.515001 -v -0.067000 -0.097306 0.127200 -vn 0.764746 0.644208 -0.012633 -v -0.067000 -0.097400 0.127618 -vn 0.729841 0.066984 -0.680327 -v -0.067000 -0.103700 0.127200 -vn 0.753773 0.251448 -0.607125 -v -0.067000 -0.103815 0.127177 -vn 0.753771 0.464662 -0.464671 -v -0.067000 -0.103912 0.127112 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.104000 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.124200 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.104000 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.123275 -vn 0.737702 0.669350 0.088128 -v -0.067000 -0.104000 0.121500 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.104750 0.117200 -vn 0.770260 0.552288 0.318870 -v -0.067000 -0.103960 0.121350 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.123275 -vn 0.737697 -0.669358 0.088113 -v -0.067000 -0.097000 0.121500 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.117200 -vn 0.770265 -0.552289 0.318854 -v -0.067000 -0.097040 0.121350 -vn 0.770266 -0.318854 0.552289 -v -0.067000 -0.097150 0.121240 -vn 0.737697 -0.088113 0.669358 -v -0.067000 -0.097300 0.121200 -vn 0.737697 0.088113 0.669358 -v -0.067000 -0.103700 0.121200 -vn 0.770265 0.318854 0.552289 -v -0.067000 -0.103850 0.121240 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.097000 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.097000 0.123275 -vn 0.561187 -0.474792 0.677968 -v -0.067000 -0.097000 0.126852 -vn 0.764742 0.070000 0.640523 -v -0.067000 -0.096598 0.126705 -vn 0.764747 -0.233779 0.600425 -v -0.067000 -0.096173 0.126761 -vn 0.764744 -0.484694 0.424544 -v -0.067000 -0.095823 0.127007 -vn 0.764747 -0.232681 -0.600850 -v -0.067000 -0.096175 0.128439 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.096550 0.132200 -vn 0.764747 -0.483921 -0.425421 -v -0.067000 -0.095824 0.128194 -vn 0.764744 -0.625713 -0.153784 -v -0.067000 -0.095626 0.127815 -vn 0.764749 -0.625987 0.152640 -v -0.067000 -0.095626 0.127387 -vn 0.764746 0.565526 -0.308779 -v -0.067000 -0.097290 0.128031 -vn 0.764747 0.358941 -0.535092 -v -0.067000 -0.097001 0.128347 -vn 0.764746 0.071180 -0.640389 -v -0.067000 -0.096599 0.128494 -vn 0.942505 0.074365 -0.325812 -v -0.067000 -0.130223 0.108369 -vn 0.942505 -0.074364 -0.325813 -v -0.067000 -0.128777 0.108369 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.110200 -vn 0.942506 -0.208365 -0.261280 -v -0.067000 -0.127474 0.107741 -vn 0.942505 -0.301097 -0.145000 -v -0.067000 -0.126572 0.106610 -vn 0.942504 0.208366 -0.261283 -v -0.067000 -0.131526 0.107741 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.110200 -vn 0.942505 0.301096 -0.145001 -v -0.067000 -0.132428 0.106610 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.105425 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.133825 0.102200 -vn 0.942505 0.301097 0.145001 -v -0.067000 -0.132428 0.103790 -vn 0.942505 0.334192 -0.000000 -v -0.067000 -0.132750 0.105200 -vn 0.759605 0.276655 -0.588611 -v -0.067000 -0.130586 0.132390 -vn 0.732633 0.074610 -0.676522 -v -0.067000 -0.131436 0.132200 -vn 0.942505 0.208366 -0.261283 -v -0.067000 -0.131526 0.131741 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.133825 0.132200 -vn 0.942506 0.301095 -0.145000 -v -0.067000 -0.132428 0.130610 -vn 0.942505 0.334192 0.000000 -v -0.067000 -0.132750 0.129200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.127925 -vn 0.942505 0.301097 0.145001 -v -0.067000 -0.132428 0.127790 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.127175 -vn 0.942504 0.208366 0.261284 -v -0.067000 -0.131526 0.126659 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.133825 0.124200 -vn 0.942505 0.074366 0.325813 -v -0.067000 -0.130223 0.126031 -vn 0.942505 -0.301098 0.145000 -v -0.067000 -0.126572 0.127790 -vn 0.942505 -0.208365 0.261281 -v -0.067000 -0.127474 0.126659 -vn 0.942506 -0.208364 -0.261280 -v -0.067000 -0.127474 0.131741 -vn 0.942505 -0.301097 -0.145000 -v -0.067000 -0.126572 0.130610 -vn 0.942505 -0.334192 0.000000 -v -0.067000 -0.126250 0.129200 -vn 0.770262 -0.552289 -0.318863 -v -0.067000 -0.113667 0.104325 -vn 0.770261 -0.637728 0.000000 -v -0.067000 -0.113500 0.103700 -vn 0.770262 -0.552289 0.318863 -v -0.067000 -0.113667 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.067000 -0.114125 0.102617 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.116750 0.100200 -vn 0.770261 0.000000 0.637728 -v -0.067000 -0.114750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.067000 -0.115375 0.102617 -vn 0.770262 0.552289 0.318863 -v -0.067000 -0.115833 0.103075 -vn 0.770261 0.637728 0.000000 -v -0.067000 -0.116000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.067000 -0.115833 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.067000 -0.115375 0.104783 -vn 0.770264 0.000000 -0.637725 -v -0.067000 -0.114750 0.104950 -vn 0.770261 -0.318867 -0.552288 -v -0.067000 -0.114125 0.104783 -vn 0.770261 0.637728 0.000000 -v -0.067000 -0.100000 0.103700 -vn 0.770262 0.552289 -0.318863 -v -0.067000 -0.099833 0.104325 -vn 0.770260 -0.552291 -0.318865 -v -0.067000 -0.097667 0.104325 -vn 0.770264 -0.637725 -0.000000 -v -0.067000 -0.097500 0.103700 -vn 0.770262 0.552289 0.318863 -v -0.067000 -0.099833 0.103075 -vn 0.770261 0.318867 -0.552288 -v -0.067000 -0.099375 0.104783 -vn 0.770264 0.000001 -0.637725 -v -0.067000 -0.098750 0.104950 -vn 0.770262 -0.318868 -0.552286 -v -0.067000 -0.098125 0.104783 -vn 0.770260 -0.552291 0.318865 -v -0.067000 -0.097667 0.103075 -vn 0.770264 -0.318864 0.552286 -v -0.067000 -0.098125 0.102617 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.096550 0.100200 -vn 0.770261 0.000001 0.637729 -v -0.067000 -0.098750 0.102450 -vn 0.770262 0.318863 0.552289 -v -0.067000 -0.099375 0.102617 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.095175 0.100200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.106475 -vn 0.904534 0.301511 0.301511 -v -0.067000 -0.117500 0.107400 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.117500 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.111125 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.117500 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.119500 0.114950 -vn 0.707107 0.707107 0.000000 -v -0.067000 -0.117500 0.114950 -vn 0.904534 0.301511 -0.301511 -v -0.067000 -0.117500 0.116700 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.116750 0.116700 -vn 0.707107 0.000000 0.707107 -v -0.067000 -0.135500 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.105425 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.114950 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.136850 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.125325 0.127175 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.127175 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.122050 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.127175 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.135500 0.127925 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.135500 0.132200 -vn 0.942505 -0.074365 0.325814 -v -0.067000 -0.128777 0.126031 -vn 0.707107 -0.707107 0.000000 -v -0.067000 -0.090000 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 -0.116750 0.132200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.096550 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.104750 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.106300 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.112250 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.116750 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.119500 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.122050 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 -0.125325 0.134200 -vn 0.577350 0.577350 -0.577350 -v -0.067000 -0.128000 0.134200 -vn -0.770261 0.637728 0.000000 -v -0.068000 -0.100000 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.068000 -0.099833 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.068000 -0.099375 0.102617 -vn -0.770261 0.000001 0.637729 -v -0.068000 -0.098750 0.102450 -vn -0.770263 -0.318864 0.552286 -v -0.068000 -0.098125 0.102617 -vn -0.770260 -0.552291 0.318865 -v -0.068000 -0.097667 0.103075 -vn -0.770264 -0.637725 0.000000 -v -0.068000 -0.097500 0.103700 -vn -0.770260 -0.552291 -0.318865 -v -0.068000 -0.097667 0.104325 -vn -0.770262 -0.318868 -0.552286 -v -0.068000 -0.098125 0.104783 -vn -0.770264 0.000001 -0.637725 -v -0.068000 -0.098750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.068000 -0.099375 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.068000 -0.099833 0.104325 -vn -0.770264 0.637725 -0.000000 -v -0.068000 -0.108000 0.103700 -vn -0.770260 0.552291 0.318866 -v -0.068000 -0.107833 0.103075 -vn -0.770264 0.318864 0.552286 -v -0.068000 -0.107375 0.102617 -vn -0.770261 -0.000001 0.637729 -v -0.068000 -0.106750 0.102450 -vn -0.770263 -0.318865 0.552286 -v -0.068000 -0.106125 0.102617 -vn -0.770260 -0.552291 0.318865 -v -0.068000 -0.105667 0.103075 -vn -0.770264 -0.637725 0.000000 -v -0.068000 -0.105500 0.103700 -vn -0.770260 -0.552291 -0.318865 -v -0.068000 -0.105667 0.104325 -vn -0.770262 -0.318869 -0.552286 -v -0.068000 -0.106125 0.104783 -vn -0.770264 -0.000001 -0.637726 -v -0.068000 -0.106750 0.104950 -vn -0.770262 0.318868 -0.552286 -v -0.068000 -0.107375 0.104783 -vn -0.770260 0.552291 -0.318865 -v -0.068000 -0.107833 0.104325 -vn -0.770264 0.637725 -0.000000 -v -0.068000 -0.094750 0.109200 -vn -0.770260 0.552291 0.318865 -v -0.068000 -0.094583 0.108575 -vn -0.770264 0.318864 0.552286 -v -0.068000 -0.094125 0.108117 -vn -0.770261 -0.000001 0.637729 -v -0.068000 -0.093500 0.107950 -vn -0.770263 -0.318865 0.552286 -v -0.068000 -0.092875 0.108117 -vn -0.770260 -0.552291 0.318865 -v -0.068000 -0.092417 0.108575 -vn -0.770264 -0.637725 0.000000 -v -0.068000 -0.092250 0.109200 -vn -0.770260 -0.552291 -0.318866 -v -0.068000 -0.092417 0.109825 -vn -0.770263 -0.318865 -0.552286 -v -0.068000 -0.092875 0.110283 -vn -0.770261 -0.000001 -0.637729 -v -0.068000 -0.093500 0.110450 -vn -0.770263 0.318864 -0.552286 -v -0.068000 -0.094125 0.110283 -vn -0.770260 0.552291 -0.318865 -v -0.068000 -0.094583 0.109825 -vn -0.770261 0.637728 0.000000 -v -0.068000 -0.116000 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.068000 -0.115833 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.068000 -0.115375 0.102617 -vn -0.770261 0.000000 0.637728 -v -0.068000 -0.114750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.068000 -0.114125 0.102617 -vn -0.770262 -0.552289 0.318863 -v -0.068000 -0.113667 0.103075 -vn -0.770261 -0.637728 0.000000 -v -0.068000 -0.113500 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.068000 -0.113667 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.068000 -0.114125 0.104783 -vn -0.770264 0.000000 -0.637725 -v -0.068000 -0.114750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.068000 -0.115375 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.068000 -0.115833 0.104325 -vn -0.609994 0.686243 0.396204 -v -0.068000 -0.117250 0.129257 -vn -0.609994 0.686243 -0.396204 -v -0.068000 -0.117250 0.132143 -vn -0.609994 -0.686243 -0.396203 -v -0.068000 -0.112250 0.132143 -vn -0.609994 -0.686243 0.396203 -v -0.068000 -0.112250 0.129257 -vn -0.609995 -0.000001 0.792406 -v -0.068000 -0.114750 0.127813 -vn -0.609995 -0.000001 -0.792406 -v -0.068000 -0.114750 0.133587 -vn -0.609994 -0.686244 0.396202 -v -0.068000 -0.112250 0.102257 -vn -0.609994 -0.000001 0.792406 -v -0.068000 -0.114750 0.100813 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 -0.112250 0.105143 -vn -0.609994 0.686244 -0.396203 -v -0.068000 -0.117250 0.105143 -vn -0.609994 -0.000001 -0.792406 -v -0.068000 -0.114750 0.106587 -vn -0.609994 0.686244 0.396203 -v -0.068000 -0.117250 0.102257 -vn -0.609994 0.686244 -0.396203 -v -0.068000 -0.109250 0.105143 -vn -0.609994 -0.000001 -0.792406 -v -0.068000 -0.106750 0.106587 -vn -0.609994 0.686244 0.396203 -v -0.068000 -0.109250 0.102257 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 -0.104250 0.105143 -vn -0.609994 -0.686244 0.396202 -v -0.068000 -0.104250 0.102257 -vn -0.609994 -0.000001 0.792406 -v -0.068000 -0.106750 0.100813 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 -0.096250 0.105143 -vn -0.609994 -0.686244 0.396203 -v -0.068000 -0.096250 0.102257 -vn -0.609994 0.000001 -0.792406 -v -0.068000 -0.098750 0.106587 -vn -0.609994 0.686244 0.396202 -v -0.068000 -0.101250 0.102257 -vn -0.609994 0.686244 -0.396202 -v -0.068000 -0.101250 0.105143 -vn -0.609994 0.000001 0.792406 -v -0.068000 -0.098750 0.100813 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 -0.091000 0.110643 -vn -0.609994 -0.686243 0.396203 -v -0.068000 -0.091000 0.107757 -vn -0.609994 -0.000001 -0.792406 -v -0.068000 -0.093500 0.112087 -vn -0.609994 0.686243 0.396204 -v -0.068000 -0.096000 0.107757 -vn -0.609994 0.686244 -0.396203 -v -0.068000 -0.096000 0.110643 -vn -0.609994 -0.000001 0.792406 -v -0.068000 -0.093500 0.106313 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 -0.091000 0.126643 -vn -0.609994 -0.686244 0.396202 -v -0.068000 -0.091000 0.123757 -vn -0.609995 -0.000001 -0.792406 -v -0.068000 -0.093500 0.128087 -vn -0.609994 0.686243 -0.396204 -v -0.068000 -0.096000 0.126643 -vn -0.609994 0.686244 0.396203 -v -0.068000 -0.096000 0.123757 -vn -0.609994 -0.000001 0.792406 -v -0.068000 -0.093500 0.122313 -vn -0.609994 -0.686243 -0.396204 -v -0.068000 -0.096250 0.132143 -vn -0.609994 -0.686243 0.396204 -v -0.068000 -0.096250 0.129257 -vn -0.609994 0.686243 -0.396203 -v -0.068000 -0.101250 0.132143 -vn -0.609995 0.000001 -0.792406 -v -0.068000 -0.098750 0.133587 -vn -0.609994 0.686243 0.396203 -v -0.068000 -0.101250 0.129257 -vn -0.609995 0.000001 0.792406 -v -0.068000 -0.098750 0.127813 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 -0.104250 0.132143 -vn -0.609994 -0.686243 0.396203 -v -0.068000 -0.104250 0.129257 -vn -0.609995 -0.000001 -0.792406 -v -0.068000 -0.106750 0.133587 -vn -0.609994 0.686243 -0.396204 -v -0.068000 -0.109250 0.132143 -vn -0.609994 0.686243 0.396204 -v -0.068000 -0.109250 0.129257 -vn -0.609995 -0.000001 0.792406 -v -0.068000 -0.106750 0.127813 -vn 0.904092 0.095091 0.416623 -v -0.068000 -0.130001 0.127006 -vn 0.904092 -0.095093 0.416624 -v -0.068000 -0.128999 0.127006 -vn 0.904093 -0.266439 0.334104 -v -0.068000 -0.128097 0.127441 -vn 0.904092 -0.385018 0.185414 -v -0.068000 -0.127473 0.128224 -vn 0.904093 -0.427336 0.000000 -v -0.068000 -0.127250 0.129200 -vn 0.904093 -0.385017 -0.185412 -v -0.068000 -0.127473 0.130176 -vn 0.904093 -0.266439 -0.334105 -v -0.068000 -0.128097 0.130959 -vn 0.904094 -0.095090 -0.416620 -v -0.068000 -0.128999 0.131394 -vn 0.904095 0.095087 -0.416619 -v -0.068000 -0.130001 0.131394 -vn 0.904092 0.266441 -0.334106 -v -0.068000 -0.130903 0.130959 -vn 0.904093 0.385017 -0.185413 -v -0.068000 -0.131527 0.130176 -vn 0.904093 0.427336 -0.000000 -v -0.068000 -0.131750 0.129200 -vn 0.904092 0.385017 0.185416 -v -0.068000 -0.131527 0.128224 -vn 0.904092 0.266440 0.334106 -v -0.068000 -0.130903 0.127441 -vn 0.904093 0.095090 0.416621 -v -0.068000 -0.130001 0.103006 -vn 0.904093 -0.095091 0.416622 -v -0.068000 -0.128999 0.103006 -vn 0.904093 -0.266438 0.334105 -v -0.068000 -0.128097 0.103441 -vn 0.904092 -0.385018 0.185414 -v -0.068000 -0.127473 0.104224 -vn 0.904093 -0.427336 0.000000 -v -0.068000 -0.127250 0.105200 -vn 0.904093 -0.385017 -0.185414 -v -0.068000 -0.127473 0.106176 -vn 0.904093 -0.266440 -0.334104 -v -0.068000 -0.128097 0.106959 -vn 0.904093 -0.095091 -0.416622 -v -0.068000 -0.128999 0.107394 -vn 0.904094 0.095089 -0.416621 -v -0.068000 -0.130001 0.107394 -vn 0.904092 0.266441 -0.334106 -v -0.068000 -0.130903 0.106959 -vn 0.904092 0.385017 -0.185415 -v -0.068000 -0.131527 0.106176 -vn 0.904093 0.427336 -0.000001 -v -0.068000 -0.131750 0.105200 -vn 0.904092 0.385018 0.185416 -v -0.068000 -0.131527 0.104224 -vn 0.904092 0.266439 0.334107 -v -0.068000 -0.130903 0.103441 -vn -0.770263 0.637727 0.000000 -v 0.016750 0.127400 0.127700 -vn 0.770263 0.637727 -0.000000 -v 0.018750 0.127400 0.127700 -vn -0.770261 0.552288 0.318865 -v 0.016750 0.127681 0.126650 -vn 0.770261 0.552288 0.318865 -v 0.018750 0.127681 0.126650 -vn -0.770261 0.318865 0.552288 -v 0.016750 0.128450 0.125881 -vn 0.770261 0.318865 0.552288 -v 0.018750 0.128450 0.125881 -vn -0.770263 -0.000000 0.637727 -v 0.016750 0.129500 0.125600 -vn 0.770263 0.000000 0.637727 -v 0.018750 0.129500 0.125600 -vn -0.770261 -0.318865 0.552289 -v 0.016750 0.130550 0.125881 -vn 0.770261 -0.318865 0.552288 -v 0.018750 0.130550 0.125881 -vn -0.770263 -0.552289 0.318860 -v 0.016750 0.131319 0.126650 -vn 0.770263 -0.552289 0.318860 -v 0.018750 0.131319 0.126650 -vn -0.770259 -0.637731 -0.000000 -v 0.016750 0.131600 0.127700 -vn 0.770259 -0.637731 0.000000 -v 0.018750 0.131600 0.127700 -vn -0.770263 -0.552289 -0.318860 -v 0.016750 0.131319 0.128750 -vn 0.770263 -0.552289 -0.318860 -v 0.018750 0.131319 0.128750 -vn -0.770261 -0.318865 -0.552288 -v 0.016750 0.130550 0.129519 -vn 0.770261 -0.318865 -0.552288 -v 0.018750 0.130550 0.129519 -vn -0.770263 0.000000 -0.637727 -v 0.016750 0.129500 0.129800 -vn 0.770263 -0.000000 -0.637727 -v 0.018750 0.129500 0.129800 -vn -0.770261 0.318865 -0.552289 -v 0.016750 0.128450 0.129519 -vn 0.770261 0.318865 -0.552288 -v 0.018750 0.128450 0.129519 -vn -0.770261 0.552288 -0.318865 -v 0.016750 0.127681 0.128750 -vn 0.770261 0.552288 -0.318865 -v 0.018750 0.127681 0.128750 -vn -0.770262 0.637727 -0.000001 -v 0.016750 0.127400 0.151700 -vn 0.770262 0.637727 -0.000001 -v 0.018750 0.127400 0.151700 -vn -0.770263 0.552286 0.318866 -v 0.016750 0.127681 0.150650 -vn 0.770263 0.552286 0.318866 -v 0.018750 0.127681 0.150650 -vn -0.770260 0.318863 0.552291 -v 0.016750 0.128450 0.149881 -vn 0.770260 0.318863 0.552291 -v 0.018750 0.128450 0.149881 -vn -0.770263 -0.000000 0.637727 -v 0.016750 0.129500 0.149600 -vn 0.770263 0.000000 0.637727 -v 0.018750 0.129500 0.149600 -vn -0.770260 -0.318863 0.552291 -v 0.016750 0.130550 0.149881 -vn 0.770260 -0.318863 0.552291 -v 0.018750 0.130550 0.149881 -vn -0.770265 -0.552286 0.318861 -v 0.016750 0.131319 0.150650 -vn 0.770265 -0.552286 0.318861 -v 0.018750 0.131319 0.150650 -vn -0.770259 -0.637732 -0.000001 -v 0.016750 0.131600 0.151700 -vn 0.770259 -0.637731 -0.000001 -v 0.018750 0.131600 0.151700 -vn -0.770264 -0.552286 -0.318862 -v 0.016750 0.131319 0.152750 -vn 0.770264 -0.552286 -0.318862 -v 0.018750 0.131319 0.152750 -vn -0.770260 -0.318863 -0.552291 -v 0.016750 0.130550 0.153519 -vn 0.770260 -0.318863 -0.552291 -v 0.018750 0.130550 0.153519 -vn -0.770263 0.000000 -0.637727 -v 0.016750 0.129500 0.153800 -vn 0.770263 -0.000000 -0.637727 -v 0.018750 0.129500 0.153800 -vn -0.770260 0.318863 -0.552291 -v 0.016750 0.128450 0.153519 -vn 0.770260 0.318863 -0.552291 -v 0.018750 0.128450 0.153519 -vn -0.770263 0.552286 -0.318867 -v 0.016750 0.127681 0.152750 -vn 0.770263 0.552286 -0.318867 -v 0.018750 0.127681 0.152750 -vn 0.770264 -0.637725 0.000000 -v 0.016750 0.094750 0.147700 -vn -0.770264 -0.637726 -0.000000 -v 0.015750 0.094750 0.147700 -vn 0.770261 -0.552288 0.318867 -v 0.016750 0.094583 0.147075 -vn -0.770261 -0.552288 0.318867 -v 0.015750 0.094583 0.147075 -vn 0.770261 -0.318866 0.552288 -v 0.016750 0.094125 0.146617 -vn -0.770261 -0.318866 0.552288 -v 0.015750 0.094125 0.146617 -vn 0.770264 0.000001 0.637725 -v 0.016750 0.093500 0.146450 -vn -0.770264 0.000001 0.637725 -v 0.015750 0.093500 0.146450 -vn 0.770261 0.318867 0.552288 -v 0.016750 0.092875 0.146617 -vn -0.770261 0.318867 0.552288 -v 0.015750 0.092875 0.146617 -vn 0.770261 0.552288 0.318867 -v 0.016750 0.092417 0.147075 -vn -0.770261 0.552288 0.318867 -v 0.015750 0.092417 0.147075 -vn 0.770264 0.637725 0.000000 -v 0.016750 0.092250 0.147700 -vn -0.770264 0.637725 0.000000 -v 0.015750 0.092250 0.147700 -vn 0.770259 0.552293 -0.318864 -v 0.016750 0.092417 0.148325 -vn -0.770258 0.552293 -0.318864 -v 0.015750 0.092417 0.148325 -vn 0.770266 0.318862 -0.552284 -v 0.016750 0.092875 0.148783 -vn -0.770265 0.318863 -0.552284 -v 0.015750 0.092875 0.148783 -vn 0.770258 0.000001 -0.637732 -v 0.016750 0.093500 0.148950 -vn -0.770257 0.000001 -0.637733 -v 0.015750 0.093500 0.148950 -vn 0.770267 -0.318861 -0.552284 -v 0.016750 0.094125 0.148783 -vn -0.770265 -0.318862 -0.552285 -v 0.015750 0.094125 0.148783 -vn 0.770259 -0.552293 -0.318864 -v 0.016750 0.094583 0.148325 -vn -0.770258 -0.552294 -0.318864 -v 0.015750 0.094583 0.148325 -vn 0.770261 -0.637728 0.000000 -v 0.016750 0.116000 0.153200 -vn -0.770261 -0.637728 -0.000000 -v 0.015750 0.116000 0.153200 -vn 0.770261 -0.552291 0.318862 -v 0.016750 0.115833 0.152575 -vn -0.770261 -0.552291 0.318862 -v 0.015750 0.115833 0.152575 -vn 0.770265 -0.318861 0.552286 -v 0.016750 0.115375 0.152117 -vn -0.770265 -0.318861 0.552286 -v 0.015750 0.115375 0.152117 -vn 0.770258 0.000000 0.637732 -v 0.016750 0.114750 0.151950 -vn -0.770258 -0.000000 0.637732 -v 0.015750 0.114750 0.151950 -vn 0.770265 0.318861 0.552286 -v 0.016750 0.114125 0.152117 -vn -0.770265 0.318861 0.552287 -v 0.015750 0.114125 0.152117 -vn 0.770261 0.552291 0.318862 -v 0.016750 0.113667 0.152575 -vn -0.770261 0.552291 0.318862 -v 0.015750 0.113667 0.152575 -vn 0.770261 0.637728 -0.000000 -v 0.016750 0.113500 0.153200 -vn -0.770261 0.637728 0.000000 -v 0.015750 0.113500 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.016750 0.113667 0.153825 -vn -0.770263 0.552286 -0.318865 -v 0.015750 0.113667 0.153825 -vn 0.770260 0.318865 -0.552291 -v 0.016750 0.114125 0.154283 -vn -0.770260 0.318865 -0.552291 -v 0.015750 0.114125 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.016750 0.114750 0.154450 -vn -0.770264 0.000000 -0.637725 -v 0.015750 0.114750 0.154450 -vn 0.770260 -0.318865 -0.552291 -v 0.016750 0.115375 0.154283 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 0.115375 0.154283 -vn 0.770263 -0.552286 -0.318865 -v 0.016750 0.115833 0.153825 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 0.115833 0.153825 -vn 0.770264 -0.637725 0.000000 -v 0.016750 0.108000 0.153200 -vn -0.770264 -0.637725 0.000000 -v 0.015750 0.108000 0.153200 -vn 0.770259 -0.552293 0.318864 -v 0.016750 0.107833 0.152575 -vn -0.770259 -0.552293 0.318864 -v 0.015750 0.107833 0.152575 -vn 0.770266 -0.318861 0.552284 -v 0.016750 0.107375 0.152117 -vn -0.770266 -0.318861 0.552284 -v 0.015750 0.107375 0.152117 -vn 0.770258 0.000002 0.637733 -v 0.016750 0.106750 0.151950 -vn -0.770259 -0.000000 0.637732 -v 0.015750 0.106750 0.151950 -vn 0.770266 0.318863 0.552283 -v 0.016750 0.106125 0.152117 -vn -0.770266 0.318862 0.552284 -v 0.015750 0.106125 0.152117 -vn 0.770259 0.552293 0.318864 -v 0.016750 0.105667 0.152575 -vn -0.770259 0.552293 0.318864 -v 0.015750 0.105667 0.152575 -vn 0.770264 0.637725 0.000000 -v 0.016750 0.105500 0.153200 -vn -0.770264 0.637725 0.000000 -v 0.015750 0.105500 0.153200 -vn 0.770261 0.552288 -0.318867 -v 0.016750 0.105667 0.153825 -vn -0.770261 0.552288 -0.318867 -v 0.015750 0.105667 0.153825 -vn 0.770261 0.318868 -0.552287 -v 0.016750 0.106125 0.154283 -vn -0.770261 0.318867 -0.552289 -v 0.015750 0.106125 0.154283 -vn 0.770263 0.000002 -0.637726 -v 0.016750 0.106750 0.154450 -vn -0.770266 0.000000 -0.637723 -v 0.015750 0.106750 0.154450 -vn 0.770261 -0.318866 -0.552288 -v 0.016750 0.107375 0.154283 -vn -0.770261 -0.318866 -0.552288 -v 0.015750 0.107375 0.154283 -vn 0.770261 -0.552288 -0.318867 -v 0.016750 0.107833 0.153825 -vn -0.770261 -0.552288 -0.318867 -v 0.015750 0.107833 0.153825 -vn 0.770261 -0.637728 0.000000 -v 0.016750 0.100000 0.153200 -vn -0.770261 -0.637728 -0.000000 -v 0.015750 0.100000 0.153200 -vn 0.770261 -0.552291 0.318862 -v 0.016750 0.099833 0.152575 -vn -0.770261 -0.552291 0.318862 -v 0.015750 0.099833 0.152575 -vn 0.770265 -0.318861 0.552286 -v 0.016750 0.099375 0.152117 -vn -0.770265 -0.318861 0.552286 -v 0.015750 0.099375 0.152117 -vn 0.770258 -0.000001 0.637732 -v 0.016750 0.098750 0.151950 -vn -0.770258 -0.000001 0.637732 -v 0.015750 0.098750 0.151950 -vn 0.770266 0.318861 0.552284 -v 0.016750 0.098125 0.152117 -vn -0.770266 0.318861 0.552284 -v 0.015750 0.098125 0.152117 -vn 0.770259 0.552293 0.318864 -v 0.016750 0.097667 0.152575 -vn -0.770259 0.552293 0.318864 -v 0.015750 0.097667 0.152575 -vn 0.770264 0.637725 0.000000 -v 0.016750 0.097500 0.153200 -vn -0.770264 0.637725 0.000000 -v 0.015750 0.097500 0.153200 -vn 0.770261 0.552288 -0.318867 -v 0.016750 0.097667 0.153825 -vn -0.770261 0.552288 -0.318867 -v 0.015750 0.097667 0.153825 -vn 0.770261 0.318866 -0.552288 -v 0.016750 0.098125 0.154283 -vn -0.770261 0.318866 -0.552288 -v 0.015750 0.098125 0.154283 -vn 0.770264 -0.000001 -0.637725 -v 0.016750 0.098750 0.154450 -vn -0.770264 -0.000001 -0.637725 -v 0.015750 0.098750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v 0.016750 0.099375 0.154283 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 0.099375 0.154283 -vn 0.770263 -0.552286 -0.318865 -v 0.016750 0.099833 0.153825 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 0.099833 0.153825 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.117375 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.111625 0.129850 -vn 1.000000 0.000000 -0.000000 -v 0.018750 0.111625 0.129318 -vn 0.770261 0.552288 0.318866 -v 0.018750 0.122721 0.147250 -vn 0.770264 0.637725 0.000000 -v 0.018750 0.122600 0.147700 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.122050 0.146700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.146700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.111625 0.150082 -vn 1.000000 0.000001 0.000001 -v 0.018750 0.105675 0.150082 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.105675 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.155268 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.117375 0.155268 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.117375 0.150082 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.155268 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.155268 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.150082 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.129318 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.129850 -vn 0.838629 -0.000000 -0.544704 -v 0.018750 0.098750 0.156087 -vn 0.838627 -0.471729 -0.272352 -v 0.018750 0.101250 0.154643 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.155268 -vn 0.838628 0.471728 -0.272353 -v 0.018750 0.091000 0.133143 -vn 0.838627 0.000000 -0.544705 -v 0.018750 0.093500 0.134587 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.093300 0.135150 -vn 0.770261 0.318866 -0.552288 -v 0.018750 0.136550 0.134479 -vn 0.770263 -0.000000 -0.637726 -v 0.018750 0.137000 0.134600 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.135150 -vn 0.770268 0.318860 -0.552283 -v 0.018750 0.136550 0.146479 -vn 0.770256 0.000000 -0.637735 -v 0.018750 0.137000 0.146600 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.136850 0.146700 -vn 0.770257 0.637734 0.000001 -v 0.018750 0.137600 0.148950 -vn 0.770268 0.552283 -0.318859 -v 0.018750 0.137721 0.149400 -vn 1.000000 -0.000000 0.000001 -v 0.018750 0.136850 0.149550 -vn 0.748361 -0.331646 0.574427 -v 0.018750 0.132200 0.135023 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.135150 -vn 0.748360 -0.508112 0.426356 -v 0.018750 0.133637 0.136229 -vn 0.692678 0.719703 -0.047173 -v 0.018750 0.146000 0.127200 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.146000 0.129318 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.129318 -vn 0.737696 -0.088113 0.669358 -v 0.018750 0.103700 0.129700 -vn 0.565703 -0.649074 0.508609 -v 0.018750 0.097306 0.129700 -vn 0.735123 -0.672941 -0.082124 -v 0.018750 0.097400 0.129320 -vn 0.838628 0.000002 0.544704 -v 0.018750 0.093500 0.128813 -vn 0.707105 0.353554 0.612374 -v 0.018750 0.093300 0.128929 -vn 0.678874 -0.190038 -0.709236 -v 0.018750 0.093412 0.117541 -vn 0.764751 -0.069998 -0.640513 -v 0.018750 0.096598 0.130195 -vn 0.561186 0.474782 -0.677977 -v 0.018750 0.097000 0.130048 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.097000 0.132700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.117375 0.139700 -vn 1.000000 0.000000 -0.000000 -v 0.018750 0.111625 0.139700 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.111625 0.139200 -vn 0.770258 -0.000000 0.637732 -v 0.018750 0.122750 0.151950 -vn 0.770264 0.318861 0.552287 -v 0.018750 0.122125 0.152117 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.150082 -vn 0.838628 -0.471729 -0.272352 -v 0.018750 0.109250 0.154643 -vn 0.838628 -0.471729 0.272352 -v 0.018750 0.109250 0.151757 -vn 0.838627 0.000001 0.544706 -v 0.018750 0.106750 0.150313 -vn 0.838627 0.471730 0.272352 -v 0.018750 0.104250 0.151757 -vn 0.838628 -0.471729 -0.272352 -v 0.018750 0.096000 0.149143 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.096000 0.146700 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.096125 0.146700 -vn 0.838628 -0.471727 0.272353 -v 0.018750 0.096000 0.146257 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.096125 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.093300 0.155268 -vn 0.707108 0.353558 -0.612369 -v 0.018750 0.093300 0.150471 -vn 0.838629 0.000001 -0.544703 -v 0.018750 0.093500 0.150587 -vn 0.764747 0.232681 -0.600850 -v 0.018750 0.096175 0.150939 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.096125 0.155268 -vn 0.764747 0.483921 -0.425421 -v 0.018750 0.095824 0.150694 -vn 0.764744 0.625713 -0.153784 -v 0.018750 0.095626 0.150315 -vn 0.764749 0.625987 0.152640 -v 0.018750 0.095626 0.149887 -vn 0.678874 -0.709236 0.190039 -v 0.018750 0.086341 0.154788 -vn 0.692678 -0.719703 0.047171 -v 0.018750 0.086000 0.152200 -vn 0.707102 0.353554 -0.612377 -v 0.018750 0.092625 0.150082 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.150082 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.149550 -vn 0.707109 0.353555 -0.612369 -v 0.018750 0.091704 0.149550 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.139700 -vn 0.838628 0.471728 0.272353 -v 0.018750 0.091000 0.146257 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.146700 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.091000 0.146700 -vn 0.838626 0.471732 -0.272350 -v 0.018750 0.091000 0.149143 -vn 0.770261 0.637728 0.000000 -v 0.018750 0.121500 0.153200 -vn 0.770263 0.552286 -0.318865 -v 0.018750 0.121667 0.153825 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.155268 -vn 0.770261 0.552291 0.318862 -v 0.018750 0.121667 0.152575 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.150082 -vn 0.770263 -0.552286 -0.318865 -v 0.018750 0.123833 0.153825 -vn 0.770261 -0.637728 -0.000000 -v 0.018750 0.124000 0.153200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.155268 -vn 0.770261 -0.552291 0.318862 -v 0.018750 0.123833 0.152575 -vn 0.770264 -0.318861 0.552287 -v 0.018750 0.123375 0.152117 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.150082 -vn 0.770260 0.318866 -0.552291 -v 0.018750 0.122125 0.154283 -vn 0.770264 0.000000 -0.637725 -v 0.018750 0.122750 0.154450 -vn 0.770260 -0.318866 -0.552291 -v 0.018750 0.123375 0.154283 -vn 0.770261 0.637728 0.000000 -v 0.018750 0.121500 0.126200 -vn 0.770263 0.552286 -0.318865 -v 0.018750 0.121667 0.126825 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.129318 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.129318 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.122050 0.117200 -vn 0.770265 0.318861 0.552287 -v 0.018750 0.122125 0.125117 -vn 0.707106 0.000000 -0.707107 -v 0.018750 0.119500 0.117200 -vn 0.770261 0.552291 0.318862 -v 0.018750 0.121667 0.125575 -vn 0.770260 0.318866 -0.552291 -v 0.018750 0.122125 0.127283 -vn 0.770264 0.000000 -0.637725 -v 0.018750 0.122750 0.127450 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.129318 -vn 0.770260 -0.318866 -0.552291 -v 0.018750 0.123375 0.127283 -vn 0.707107 0.000000 -0.707106 -v 0.018750 0.125900 0.117200 -vn 0.770264 -0.318861 0.552287 -v 0.018750 0.123375 0.125117 -vn 0.770258 -0.000000 0.637732 -v 0.018750 0.122750 0.124950 -vn 0.770263 -0.552286 -0.318865 -v 0.018750 0.123833 0.126825 -vn 0.770261 -0.637728 -0.000000 -v 0.018750 0.124000 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.018750 0.123833 0.125575 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.111625 0.129900 -vn 0.904533 0.301511 0.301514 -v 0.018750 0.111000 0.129900 -vn 0.770261 0.552292 -0.318859 -v 0.018750 0.107221 0.132150 -vn 0.770266 0.318858 -0.552287 -v 0.018750 0.107550 0.132479 -vn 1.000000 0.000000 -0.000000 -v 0.018750 0.105675 0.132700 -vn 0.770252 0.000000 -0.637740 -v 0.018750 0.108000 0.132600 -vn 0.770268 -0.318860 -0.552283 -v 0.018750 0.108450 0.132479 -vn 0.770258 -0.552295 -0.318862 -v 0.018750 0.108779 0.132150 -vn 0.707106 0.707107 -0.000000 -v 0.018750 0.111000 0.132700 -vn 0.770263 -0.637726 0.000000 -v 0.018750 0.108900 0.131700 -vn 0.770261 -0.552288 0.318866 -v 0.018750 0.108779 0.131250 -vn 0.770261 -0.318866 0.552288 -v 0.018750 0.108450 0.130921 -vn 0.770263 0.000000 0.637726 -v 0.018750 0.108000 0.130800 -vn 0.770259 0.318864 0.552292 -v 0.018750 0.107550 0.130921 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.105675 0.129850 -vn 0.770264 0.552286 0.318863 -v 0.018750 0.107221 0.131250 -vn 0.770259 0.637731 0.000000 -v 0.018750 0.107100 0.131700 -vn 0.707106 0.000000 0.707108 -v 0.018750 0.117375 0.129900 -vn 0.904534 -0.301511 0.301511 -v 0.018750 0.117500 0.129900 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.132700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.117500 0.132700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.135150 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.117500 0.135150 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.137450 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.117500 0.137450 -vn 0.904534 -0.301511 -0.301511 -v 0.018750 0.117500 0.139200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.119500 0.139700 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.117375 0.139200 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.111000 0.137450 -vn 0.904534 0.301512 -0.301511 -v 0.018750 0.111000 0.139200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.105675 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.105675 0.137450 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.105675 0.135150 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.111000 0.135150 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.132700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.104000 0.132700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.135150 -vn 0.737697 -0.088113 -0.669358 -v 0.018750 0.103700 0.135700 -vn 0.770265 -0.318854 -0.552289 -v 0.018750 0.103850 0.135660 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.137450 -vn 0.737697 0.088113 -0.669358 -v 0.018750 0.097300 0.135700 -vn 0.770267 0.552290 -0.318849 -v 0.018750 0.097040 0.135550 -vn 0.770266 0.318854 -0.552289 -v 0.018750 0.097150 0.135660 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.096125 0.137450 -vn 0.770261 -0.552288 -0.318866 -v 0.018750 0.103960 0.135550 -vn 0.737701 -0.669352 -0.088124 -v 0.018750 0.104000 0.135400 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.104000 0.135150 -vn 0.737695 0.669360 -0.088109 -v 0.018750 0.097000 0.135400 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.096125 0.135150 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.097000 0.135150 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.096125 0.132700 -vn 0.764742 0.233791 -0.600425 -v 0.018750 0.096173 0.130139 -vn 0.764744 0.625713 0.153784 -v 0.018750 0.095626 0.129085 -vn 0.764749 0.625987 -0.152640 -v 0.018750 0.095626 0.129513 -vn 0.764744 0.484694 -0.424544 -v 0.018750 0.095823 0.129893 -vn 0.707107 -0.353552 0.612373 -v 0.018750 0.095296 0.129850 -vn 0.760382 0.495132 0.420315 -v 0.018750 0.095824 0.128706 -vn 0.735143 0.339260 0.586913 -v 0.018750 0.096118 0.128485 -vn 0.692678 -0.047171 -0.719703 -v 0.018750 0.096000 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.096125 0.117200 -vn 0.838628 -0.000000 -0.544705 -v 0.018750 0.098750 0.129087 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 0.101250 0.127643 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.129318 -vn 0.838628 0.471728 0.272352 -v 0.018750 0.096250 0.124757 -vn 0.838628 0.471728 -0.272353 -v 0.018750 0.096250 0.127643 -vn 0.739260 0.177494 0.649608 -v 0.018750 0.096175 0.128461 -vn 0.764746 -0.071180 0.640389 -v 0.018750 0.096599 0.128405 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.104125 0.117200 -vn 0.838628 -0.471729 0.272352 -v 0.018750 0.101250 0.124757 -vn 0.838628 -0.000000 0.544705 -v 0.018750 0.098750 0.123313 -vn 0.764747 -0.358941 0.535092 -v 0.018750 0.097001 0.128553 -vn 0.764746 -0.565526 0.308779 -v 0.018750 0.097290 0.128869 -vn 0.737704 -0.669347 0.088131 -v 0.018750 0.104000 0.130000 -vn 0.770258 -0.552288 0.318875 -v 0.018750 0.103960 0.129850 -vn 0.770266 -0.318854 0.552289 -v 0.018750 0.103850 0.129740 -vn 0.737612 -0.669601 0.086966 -v 0.018750 0.097400 0.129282 -vn 0.678874 -0.367128 0.635883 -v 0.018750 0.091000 0.160860 -vn 0.678875 -0.519197 0.519196 -v 0.018750 0.088929 0.159271 -vn 0.678875 -0.635883 0.367128 -v 0.018750 0.087340 0.157200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.155268 -vn 0.678874 0.709235 0.190040 -v 0.018750 0.145659 0.154788 -vn 0.678875 0.635883 0.367127 -v 0.018750 0.144660 0.157200 -vn 0.678874 0.519197 0.519195 -v 0.018750 0.143071 0.159271 -vn 0.678874 0.367128 0.635883 -v 0.018750 0.141000 0.160860 -vn 0.678875 0.190039 0.709235 -v 0.018750 0.138588 0.161859 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.150082 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.146000 0.150082 -vn 0.692678 0.719703 0.047172 -v 0.018750 0.146000 0.152200 -vn 0.678875 0.709235 -0.190039 -v 0.018750 0.145659 0.124612 -vn 0.678874 0.367127 -0.635883 -v 0.018750 0.141000 0.118540 -vn 0.678874 0.190038 -0.709236 -v 0.018750 0.138588 0.117541 -vn 0.692678 0.047171 -0.719703 -v 0.018750 0.136000 0.117200 -vn 0.678874 0.519197 -0.519196 -v 0.018750 0.143071 0.120129 -vn 0.678875 0.635883 -0.367126 -v 0.018750 0.144660 0.122200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.129318 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.135500 0.117200 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.129318 -vn 0.692678 -0.719703 -0.047171 -v 0.018750 0.086000 0.127200 -vn 0.678874 -0.709235 -0.190038 -v 0.018750 0.086341 0.124612 -vn 0.678874 -0.635883 -0.367127 -v 0.018750 0.087340 0.122200 -vn 0.678874 -0.519196 -0.519196 -v 0.018750 0.088929 0.120129 -vn 0.678874 -0.367127 -0.635883 -v 0.018750 0.091000 0.118540 -vn 0.737704 -0.669347 0.088131 -v 0.018750 0.104000 0.144000 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.139700 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.104125 0.146700 -vn 0.737697 0.088113 0.669358 -v 0.018750 0.097300 0.143700 -vn 0.770265 0.318854 0.552289 -v 0.018750 0.097150 0.143740 -vn 0.770258 -0.552288 0.318875 -v 0.018750 0.103960 0.143850 -vn 0.770266 -0.318854 0.552289 -v 0.018750 0.103850 0.143740 -vn 0.737697 -0.088113 0.669358 -v 0.018750 0.103700 0.143700 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.097000 0.146700 -vn 0.737698 0.669356 0.088117 -v 0.018750 0.097000 0.144000 -vn 0.770264 0.552289 0.318858 -v 0.018750 0.097040 0.143850 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.104125 0.149550 -vn 0.729846 -0.680320 -0.067000 -v 0.018750 0.104000 0.149400 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.104000 0.146700 -vn 0.729856 -0.067025 -0.680307 -v 0.018750 0.103700 0.149700 -vn 0.753757 -0.251493 -0.607126 -v 0.018750 0.103815 0.149677 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.104125 0.150082 -vn 0.753762 -0.464653 -0.464694 -v 0.018750 0.103912 0.149612 -vn 0.753777 -0.607102 -0.251488 -v 0.018750 0.103977 0.149515 -vn 0.838627 -0.471729 0.272352 -v 0.018750 0.101250 0.151757 -vn 0.838629 -0.000000 0.544703 -v 0.018750 0.098750 0.150313 -vn 0.764746 -0.071180 -0.640389 -v 0.018750 0.096599 0.150994 -vn 0.838627 0.471729 0.272352 -v 0.018750 0.096250 0.151757 -vn 0.764747 -0.358941 -0.535092 -v 0.018750 0.097001 0.150847 -vn 0.764746 -0.565526 -0.308779 -v 0.018750 0.097290 0.150531 -vn 0.764746 -0.644208 -0.012633 -v 0.018750 0.097400 0.150118 -vn 0.566634 -0.643195 -0.515001 -v 0.018750 0.097306 0.149700 -vn 0.764744 0.484694 0.424544 -v 0.018750 0.095823 0.149507 -vn 0.764747 0.233779 0.600425 -v 0.018750 0.096173 0.149261 -vn 0.764746 -0.070010 0.640517 -v 0.018750 0.096598 0.149205 -vn 0.561186 0.474782 0.677977 -v 0.018750 0.097000 0.149352 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.117375 0.149550 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.117375 0.149500 -vn 0.904534 -0.301511 -0.301511 -v 0.018750 0.117500 0.149500 -vn 0.707106 0.000000 -0.707108 -v 0.018750 0.111625 0.149500 -vn 0.770260 0.318864 -0.552292 -v 0.018750 0.107550 0.148479 -vn 0.770264 0.000000 -0.637726 -v 0.018750 0.108000 0.148600 -vn 0.770261 -0.318866 -0.552288 -v 0.018750 0.108450 0.148479 -vn 0.770261 -0.552288 -0.318866 -v 0.018750 0.108779 0.148150 -vn 0.904533 0.301512 -0.301513 -v 0.018750 0.111000 0.149500 -vn 0.707106 0.707107 0.000000 -v 0.018750 0.111000 0.146700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.105675 0.146700 -vn 0.770260 0.000000 0.637730 -v 0.018750 0.108000 0.146800 -vn 0.770259 0.318864 0.552293 -v 0.018750 0.107550 0.146921 -vn 0.770263 -0.637726 0.000000 -v 0.018750 0.108900 0.147700 -vn 0.770261 -0.552288 0.318866 -v 0.018750 0.108779 0.147250 -vn 0.770261 -0.318866 0.552288 -v 0.018750 0.108450 0.146921 -vn 0.770264 0.552286 0.318863 -v 0.018750 0.107221 0.147250 -vn 0.770259 0.637731 0.000000 -v 0.018750 0.107100 0.147700 -vn 0.770264 0.552285 -0.318863 -v 0.018750 0.107221 0.148150 -vn 0.904534 0.301512 0.301511 -v 0.018750 0.111000 0.140200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.137450 -vn 0.748361 0.623290 0.226859 -v 0.018750 0.124426 0.137853 -vn 0.748360 0.663293 0.000000 -v 0.018750 0.124100 0.139700 -vn 0.748360 -0.115179 0.653216 -v 0.018750 0.130438 0.134382 -vn 0.748360 0.115179 0.653216 -v 0.018750 0.128562 0.134382 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.132700 -vn 0.748361 0.331646 0.574427 -v 0.018750 0.126800 0.135023 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.135150 -vn 0.748360 0.508112 0.426356 -v 0.018750 0.125363 0.136229 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.132700 -vn 0.748360 -0.623291 -0.226860 -v 0.018750 0.134574 0.141547 -vn 0.748361 -0.663291 -0.000000 -v 0.018750 0.134900 0.139700 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.139700 -vn 0.748360 -0.623290 0.226861 -v 0.018750 0.134574 0.137853 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.137450 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.135150 -vn 0.748361 0.508111 -0.426356 -v 0.018750 0.125363 0.143171 -vn 0.748360 0.331647 -0.574428 -v 0.018750 0.126800 0.144377 -vn 0.748361 -0.115181 -0.653214 -v 0.018750 0.130438 0.145018 -vn 0.748360 -0.331647 -0.574428 -v 0.018750 0.132200 0.144377 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.133250 0.146700 -vn 0.748361 0.115181 -0.653214 -v 0.018750 0.128562 0.145018 -vn 0.748361 0.623291 -0.226858 -v 0.018750 0.124426 0.141547 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.139700 -vn 0.770261 -0.552288 0.318866 -v 0.018750 0.139279 0.148500 -vn 0.707106 0.707107 0.000000 -v 0.018750 0.146000 0.146700 -vn 0.770264 -0.637725 0.000002 -v 0.018750 0.139400 0.148950 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.146000 0.149550 -vn 0.770261 -0.552289 -0.318865 -v 0.018750 0.139279 0.149400 -vn 0.770261 -0.318866 0.552288 -v 0.018750 0.138950 0.148171 -vn 0.770263 0.000000 0.637726 -v 0.018750 0.138500 0.148050 -vn 0.770258 0.318862 0.552295 -v 0.018750 0.138050 0.148171 -vn 0.770268 0.552282 0.318860 -v 0.018750 0.137721 0.148500 -vn 0.770261 -0.318866 -0.552288 -v 0.018750 0.138950 0.149729 -vn 0.770263 -0.000000 -0.637726 -v 0.018750 0.138500 0.149850 -vn 0.770258 0.318862 -0.552295 -v 0.018750 0.138050 0.149729 -vn 0.770265 0.318855 0.552289 -v 0.018750 0.136550 0.144921 -vn 0.770261 0.552288 0.318866 -v 0.018750 0.136221 0.145250 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.146700 -vn 0.770263 0.637726 -0.000000 -v 0.018750 0.136100 0.145700 -vn 0.770258 0.552295 -0.318862 -v 0.018750 0.136221 0.146150 -vn 0.748361 -0.508111 -0.426356 -v 0.018750 0.133637 0.143171 -vn 0.770265 -0.318855 -0.552289 -v 0.018750 0.137450 0.146479 -vn 0.770265 -0.552289 -0.318855 -v 0.018750 0.137779 0.146150 -vn 0.770256 -0.637735 -0.000000 -v 0.018750 0.137900 0.145700 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.146000 0.139700 -vn 0.770268 -0.552283 0.318860 -v 0.018750 0.137779 0.145250 -vn 0.770262 -0.318851 0.552296 -v 0.018750 0.137450 0.144921 -vn 0.770261 0.318866 0.552288 -v 0.018750 0.136550 0.132921 -vn 0.770261 0.552288 0.318866 -v 0.018750 0.136221 0.133250 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.132700 -vn 0.770263 0.637726 -0.000000 -v 0.018750 0.136100 0.133700 -vn 0.770261 0.552288 -0.318866 -v 0.018750 0.136221 0.134150 -vn 0.770263 0.000000 0.637726 -v 0.018750 0.137000 0.132800 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.132700 -vn 0.770258 -0.318862 0.552295 -v 0.018750 0.137450 0.132921 -vn 0.707107 0.707106 0.000000 -v 0.018750 0.146000 0.132700 -vn 0.770268 -0.552283 0.318860 -v 0.018750 0.137779 0.133250 -vn 0.770258 -0.318862 -0.552295 -v 0.018750 0.137450 0.134479 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.146000 0.135150 -vn 0.770268 -0.552283 -0.318860 -v 0.018750 0.137779 0.134150 -vn 0.770256 -0.637735 -0.000000 -v 0.018750 0.137900 0.133700 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.146000 0.129850 -vn 0.770261 -0.552288 -0.318866 -v 0.018750 0.139279 0.130900 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.129850 -vn 0.770256 0.637735 0.000000 -v 0.018750 0.137600 0.130450 -vn 0.770268 0.552283 -0.318860 -v 0.018750 0.137721 0.130900 -vn 0.770258 0.318862 -0.552295 -v 0.018750 0.138050 0.131229 -vn 0.770263 -0.000000 -0.637726 -v 0.018750 0.138500 0.131350 -vn 0.770261 -0.318866 -0.552288 -v 0.018750 0.138950 0.131229 -vn 0.770263 -0.637726 0.000000 -v 0.018750 0.139400 0.130450 -vn 0.770261 -0.552288 0.318866 -v 0.018750 0.139279 0.130000 -vn 0.770261 -0.318866 0.552288 -v 0.018750 0.138950 0.129671 -vn 0.770263 0.000000 0.637726 -v 0.018750 0.138500 0.129550 -vn 0.770258 0.318862 0.552295 -v 0.018750 0.138050 0.129671 -vn 0.770268 0.552283 0.318860 -v 0.018750 0.137721 0.130000 -vn 0.838629 0.000000 0.544704 -v 0.018750 0.114750 0.150313 -vn 0.838627 0.471729 0.272352 -v 0.018750 0.112250 0.151757 -vn 0.838629 0.000000 -0.544704 -v 0.018750 0.114750 0.156087 -vn 0.838628 -0.471729 -0.272352 -v 0.018750 0.117250 0.154643 -vn 0.838627 -0.471729 0.272352 -v 0.018750 0.117250 0.151757 -vn 0.838628 0.471728 -0.272353 -v 0.018750 0.104250 0.127643 -vn 0.838626 0.000001 -0.544708 -v 0.018750 0.106750 0.129087 -vn 1.000000 0.000001 -0.000001 -v 0.018750 0.105675 0.129318 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 0.109250 0.127643 -vn 0.838628 -0.471728 0.272352 -v 0.018750 0.109250 0.124757 -vn 0.838628 0.471729 0.272352 -v 0.018750 0.104250 0.124757 -vn 0.838628 0.000001 0.544705 -v 0.018750 0.106750 0.123313 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.105675 0.117200 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.111625 0.117200 -vn 0.838628 -0.471727 0.272353 -v 0.018750 0.096000 0.130257 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.096000 0.132700 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 0.096000 0.133143 -vn 0.707108 0.353553 0.612371 -v 0.018750 0.092625 0.129318 -vn 0.707106 0.353553 0.612373 -v 0.018750 0.091704 0.129850 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.129850 -vn 0.838628 0.471727 0.272353 -v 0.018750 0.091000 0.130257 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.132700 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.091000 0.132700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.135150 -vn 0.838628 0.471729 -0.272352 -v 0.018750 0.096250 0.154643 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.111625 0.155268 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.111625 0.162200 -vn 0.838629 0.000001 -0.544704 -v 0.018750 0.106750 0.156087 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.105675 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.104125 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.096125 0.162200 -vn 0.692678 -0.047172 0.719703 -v 0.018750 0.096000 0.162200 -vn 0.678875 -0.190039 0.709235 -v 0.018750 0.093412 0.161859 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.133250 0.117200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.125900 0.129850 -vn 0.838627 0.471729 -0.272352 -v 0.018750 0.112250 0.154643 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.117375 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.119500 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.122050 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.125900 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.133250 0.162200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.135500 0.162200 -vn 0.692678 0.047172 0.719703 -v 0.018750 0.136000 0.162200 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.150082 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.119500 0.149550 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.119500 0.146700 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.117500 0.146700 -vn 0.904534 -0.301511 0.301511 -v 0.018750 0.117500 0.140200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.117375 0.140200 -vn 0.707107 0.000000 0.707107 -v 0.018750 0.111625 0.140200 -vn 1.000000 0.000000 -0.000000 -v 0.018750 0.111625 0.149550 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.149550 -vn 1.000000 -0.000000 0.000000 -v 0.018750 0.122050 0.149550 -vn 0.770262 0.552288 -0.318866 -v 0.018750 0.122721 0.148150 -vn 0.770262 0.318866 -0.552288 -v 0.018750 0.123050 0.148479 -vn 0.770264 -0.000000 -0.637725 -v 0.018750 0.123500 0.148600 -vn 0.770260 -0.318864 -0.552291 -v 0.018750 0.123950 0.148479 -vn 0.770265 -0.552285 -0.318863 -v 0.018750 0.124279 0.148150 -vn 0.770259 -0.637731 0.000000 -v 0.018750 0.124400 0.147700 -vn 0.770264 -0.552285 0.318863 -v 0.018750 0.124279 0.147250 -vn 0.770260 -0.318864 0.552292 -v 0.018750 0.123950 0.146921 -vn 0.770263 0.000000 0.637726 -v 0.018750 0.123500 0.146800 -vn 0.770261 0.318866 0.552288 -v 0.018750 0.123050 0.146921 -vn 0.707107 0.707107 0.000000 -v 0.018750 0.146000 0.137450 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.137450 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.136850 0.139700 -vn 0.770256 -0.000000 0.637735 -v 0.018750 0.137000 0.144800 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.093300 0.137450 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.093300 0.139700 -vn 0.838627 0.000000 0.544705 -v 0.018750 0.093500 0.144813 -vn 0.707107 -0.707107 0.000000 -v 0.018750 0.086000 0.137450 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.135150 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.132700 -vn 0.770268 0.318860 -0.552283 -v 0.018750 0.123050 0.132479 -vn 0.770256 0.000000 -0.637735 -v 0.018750 0.123500 0.132600 -vn 0.770262 -0.552292 -0.318858 -v 0.018750 0.124279 0.132150 -vn 0.770259 -0.637731 0.000000 -v 0.018750 0.124400 0.131700 -vn 0.770266 -0.318857 -0.552286 -v 0.018750 0.123950 0.132479 -vn 0.770261 0.318866 0.552288 -v 0.018750 0.123050 0.130921 -vn 0.770261 0.552288 0.318866 -v 0.018750 0.122721 0.131250 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.122050 0.129850 -vn 0.770263 0.637726 -0.000000 -v 0.018750 0.122600 0.131700 -vn 0.770258 0.552295 -0.318862 -v 0.018750 0.122721 0.132150 -vn 0.770264 -0.552285 0.318863 -v 0.018750 0.124279 0.131250 -vn 0.770260 -0.318864 0.552292 -v 0.018750 0.123950 0.130921 -vn 0.770263 0.000000 0.637726 -v 0.018750 0.123500 0.130800 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.135500 0.129850 -vn 1.000000 0.000000 0.000000 -v 0.018750 0.117375 0.129318 -vn 0.838627 0.471729 -0.272352 -v 0.018750 0.104250 0.154643 -vn 0.707107 0.000000 -0.707107 -v 0.018750 0.117375 0.117200 -vn 0.838628 0.000000 -0.544705 -v 0.018750 0.114750 0.129087 -vn 0.838628 -0.471728 -0.272353 -v 0.018750 0.117250 0.127643 -vn 0.838628 -0.471728 0.272352 -v 0.018750 0.117250 0.124757 -vn 0.838628 0.000000 0.544705 -v 0.018750 0.114750 0.123313 -vn 0.838628 0.471729 0.272352 -v 0.018750 0.112250 0.124757 -vn 0.838628 0.471728 -0.272353 -v 0.018750 0.112250 0.127643 -vn -0.770256 -0.637735 0.000000 -v 0.015750 0.137900 0.145700 -vn -0.770268 -0.552283 0.318860 -v 0.015750 0.137779 0.145250 -vn -0.770262 -0.318851 0.552296 -v 0.015750 0.137450 0.144921 -vn -0.770256 0.000000 0.637735 -v 0.015750 0.137000 0.144800 -vn -0.770265 0.318855 0.552289 -v 0.015750 0.136550 0.144921 -vn -0.770261 0.552288 0.318866 -v 0.015750 0.136221 0.145250 -vn -0.770263 0.637726 0.000000 -v 0.015750 0.136100 0.145700 -vn -0.770258 0.552295 -0.318862 -v 0.015750 0.136221 0.146150 -vn -0.770268 0.318860 -0.552283 -v 0.015750 0.136550 0.146479 -vn -0.770256 -0.000000 -0.637735 -v 0.015750 0.137000 0.146600 -vn -0.770265 -0.318855 -0.552289 -v 0.015750 0.137450 0.146479 -vn -0.770265 -0.552289 -0.318855 -v 0.015750 0.137779 0.146150 -vn -0.770259 -0.637731 -0.000000 -v 0.015750 0.124400 0.147700 -vn -0.770264 -0.552285 0.318863 -v 0.015750 0.124279 0.147250 -vn -0.770260 -0.318864 0.552292 -v 0.015750 0.123950 0.146921 -vn -0.770263 -0.000000 0.637726 -v 0.015750 0.123500 0.146800 -vn -0.770261 0.318866 0.552288 -v 0.015750 0.123050 0.146921 -vn -0.770261 0.552288 0.318866 -v 0.015750 0.122721 0.147250 -vn -0.770263 0.637726 -0.000000 -v 0.015750 0.122600 0.147700 -vn -0.770260 0.552289 -0.318866 -v 0.015750 0.122721 0.148150 -vn -0.770261 0.318866 -0.552289 -v 0.015750 0.123050 0.148479 -vn -0.770263 -0.000000 -0.637727 -v 0.015750 0.123500 0.148600 -vn -0.770259 -0.318864 -0.552292 -v 0.015750 0.123950 0.148479 -vn -0.770264 -0.552286 -0.318863 -v 0.015750 0.124279 0.148150 -vn -0.770263 -0.637726 -0.000000 -v 0.015750 0.108900 0.147700 -vn -0.770261 -0.552288 0.318866 -v 0.015750 0.108779 0.147250 -vn -0.770261 -0.318866 0.552288 -v 0.015750 0.108450 0.146921 -vn -0.770267 -0.000000 0.637721 -v 0.015750 0.108000 0.146800 -vn -0.770261 0.318864 0.552290 -v 0.015750 0.107550 0.146921 -vn -0.770265 0.552285 0.318862 -v 0.015750 0.107221 0.147250 -vn -0.770261 0.637729 0.000000 -v 0.015750 0.107100 0.147700 -vn -0.770265 0.552285 -0.318863 -v 0.015750 0.107221 0.148150 -vn -0.770260 0.318864 -0.552292 -v 0.015750 0.107550 0.148479 -vn -0.770263 -0.000000 -0.637726 -v 0.015750 0.108000 0.148600 -vn -0.770261 -0.318866 -0.552289 -v 0.015750 0.108450 0.148479 -vn -0.770261 -0.552289 -0.318866 -v 0.015750 0.108779 0.148150 -vn -0.770256 -0.637735 0.000000 -v 0.015750 0.137900 0.133700 -vn -0.770268 -0.552283 0.318860 -v 0.015750 0.137779 0.133250 -vn -0.770258 -0.318862 0.552295 -v 0.015750 0.137450 0.132921 -vn -0.770263 -0.000000 0.637726 -v 0.015750 0.137000 0.132800 -vn -0.770261 0.318866 0.552288 -v 0.015750 0.136550 0.132921 -vn -0.770261 0.552288 0.318866 -v 0.015750 0.136221 0.133250 -vn -0.770263 0.637726 0.000000 -v 0.015750 0.136100 0.133700 -vn -0.770261 0.552288 -0.318866 -v 0.015750 0.136221 0.134150 -vn -0.770261 0.318866 -0.552288 -v 0.015750 0.136550 0.134479 -vn -0.770263 0.000000 -0.637726 -v 0.015750 0.137000 0.134600 -vn -0.770258 -0.318862 -0.552295 -v 0.015750 0.137450 0.134479 -vn -0.770268 -0.552283 -0.318860 -v 0.015750 0.137779 0.134150 -vn -0.770263 -0.637726 -0.000000 -v 0.015750 0.108900 0.131700 -vn -0.770261 -0.552288 0.318866 -v 0.015750 0.108779 0.131250 -vn -0.770261 -0.318866 0.552288 -v 0.015750 0.108450 0.130921 -vn -0.770264 -0.000000 0.637726 -v 0.015750 0.108000 0.130800 -vn -0.770260 0.318864 0.552291 -v 0.015750 0.107550 0.130921 -vn -0.770265 0.552285 0.318863 -v 0.015750 0.107221 0.131250 -vn -0.770260 0.637730 0.000000 -v 0.015750 0.107100 0.131700 -vn -0.770262 0.552291 -0.318858 -v 0.015750 0.107221 0.132150 -vn -0.770267 0.318857 -0.552285 -v 0.015750 0.107550 0.132479 -vn -0.770259 -0.000000 -0.637731 -v 0.015750 0.108000 0.132600 -vn -0.770268 -0.318860 -0.552283 -v 0.015750 0.108450 0.132479 -vn -0.770258 -0.552295 -0.318862 -v 0.015750 0.108779 0.132150 -vn -0.770259 -0.637731 -0.000000 -v 0.015750 0.124400 0.131700 -vn -0.770264 -0.552285 0.318863 -v 0.015750 0.124279 0.131250 -vn -0.770260 -0.318864 0.552292 -v 0.015750 0.123950 0.130921 -vn -0.770263 -0.000000 0.637726 -v 0.015750 0.123500 0.130800 -vn -0.770261 0.318866 0.552288 -v 0.015750 0.123050 0.130921 -vn -0.770261 0.552288 0.318866 -v 0.015750 0.122721 0.131250 -vn -0.770263 0.637726 0.000000 -v 0.015750 0.122600 0.131700 -vn -0.770258 0.552295 -0.318862 -v 0.015750 0.122721 0.132150 -vn -0.770268 0.318860 -0.552283 -v 0.015750 0.123050 0.132479 -vn -0.770255 -0.000000 -0.637736 -v 0.015750 0.123500 0.132600 -vn -0.770266 -0.318857 -0.552286 -v 0.015750 0.123950 0.132479 -vn -0.770262 -0.552292 -0.318858 -v 0.015750 0.124279 0.132150 -vn -0.692678 0.719703 0.047172 -v 0.010750 0.146000 0.152200 -vn -0.692678 0.719703 -0.047173 -v 0.010750 0.146000 0.127200 -vn -0.692678 0.047171 -0.719703 -v 0.010750 0.136000 0.117200 -vn -0.692679 -0.047171 -0.719702 -v 0.010750 0.096000 0.117200 -vn -0.692678 -0.719703 -0.047171 -v 0.010750 0.086000 0.127200 -vn -0.692678 -0.719703 0.047171 -v 0.010750 0.086000 0.152200 -vn -0.692678 -0.047172 0.719702 -v 0.010750 0.096000 0.162200 -vn -0.692678 0.047172 0.719703 -v 0.010750 0.136000 0.162200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.093500 0.156700 -vn -0.577350 0.577350 -0.577350 -v 0.010750 0.093500 0.156200 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.092000 0.156200 -vn -0.904534 -0.301511 0.301511 -v 0.010750 0.128000 0.122700 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.093500 0.122700 -vn -0.678874 -0.190038 -0.709236 -v 0.010750 0.093412 0.117541 -vn -0.678874 -0.367127 -0.635883 -v 0.010750 0.091000 0.118540 -vn -0.678874 -0.519196 -0.519196 -v 0.010750 0.088929 0.120129 -vn -0.904534 -0.301511 -0.301511 -v 0.010750 0.128000 0.156700 -vn -0.678875 -0.190039 0.709235 -v 0.010750 0.093412 0.161859 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.090500 0.154700 -vn -0.678875 -0.635882 0.367128 -v 0.010750 0.087340 0.157200 -vn -0.678875 -0.519197 0.519195 -v 0.010750 0.088929 0.159271 -vn -0.742117 -0.540533 0.396340 -v 0.010750 0.141663 0.127585 -vn -0.741871 -0.638647 0.204348 -v 0.010750 0.142657 0.129537 -vn -0.725201 -0.686415 0.054023 -v 0.010750 0.143000 0.131700 -vn -0.577350 0.577350 -0.577350 -v 0.010750 0.092000 0.154700 -vn -0.678874 -0.367128 0.635883 -v 0.010750 0.091000 0.160860 -vn -0.577350 0.577350 -0.577350 -v 0.010750 0.090500 0.152950 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.090000 0.152950 -vn -0.678874 -0.709236 0.190039 -v 0.010750 0.086341 0.154788 -vn -0.678875 0.709235 -0.190039 -v 0.010750 0.145659 0.124612 -vn -0.678875 0.635883 -0.367126 -v 0.010750 0.144660 0.122200 -vn -0.744071 -0.392700 0.540504 -v 0.010750 0.140114 0.126037 -vn -0.678874 0.519197 -0.519196 -v 0.010750 0.143071 0.120129 -vn -0.744072 -0.206453 0.635401 -v 0.010750 0.138163 0.125043 -vn -0.725200 -0.686415 -0.054022 -v 0.010750 0.143000 0.147700 -vn -0.744072 -0.635400 -0.206456 -v 0.010750 0.142657 0.149863 -vn -0.678874 0.709235 0.190040 -v 0.010750 0.145659 0.154788 -vn -0.744070 -0.540506 -0.392700 -v 0.010750 0.141663 0.151814 -vn -0.678875 0.635883 0.367127 -v 0.010750 0.144660 0.157200 -vn -0.744072 -0.392699 -0.540504 -v 0.010750 0.140114 0.153363 -vn -0.678874 0.519198 0.519195 -v 0.010750 0.143071 0.159271 -vn -0.577350 -0.577350 0.577350 -v 0.010750 0.128000 0.123200 -vn -0.845340 -0.278879 0.455661 -v 0.010750 0.129500 0.123200 -vn -0.661187 -0.577625 0.478729 -v 0.010750 0.129897 0.123976 -vn -0.678874 0.367128 0.635883 -v 0.010750 0.141000 0.160860 -vn -0.744070 -0.206453 -0.635403 -v 0.010750 0.138163 0.154357 -vn -0.678875 0.190039 0.709235 -v 0.010750 0.138588 0.161859 -vn -0.725200 -0.054022 -0.686415 -v 0.010750 0.136000 0.154700 -vn -0.683246 -0.080043 -0.725788 -v 0.010750 0.131436 0.154700 -vn -0.661187 -0.319122 -0.678964 -v 0.010750 0.130586 0.154890 -vn -0.577350 0.577350 0.577350 -v 0.010750 0.090500 0.142450 -vn -0.577350 0.577350 -0.577350 -v 0.010750 0.090500 0.136950 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.090000 0.142450 -vn -0.904534 0.301511 -0.301511 -v 0.010750 0.090000 0.136950 -vn -0.678874 0.367127 -0.635883 -v 0.010750 0.141000 0.118540 -vn -0.678874 0.190038 -0.709236 -v 0.010750 0.138588 0.117541 -vn -0.725200 -0.054020 0.686416 -v 0.010750 0.136000 0.124700 -vn -0.683245 -0.080046 0.725788 -v 0.010750 0.131436 0.124700 -vn -0.661189 -0.319122 0.678963 -v 0.010750 0.130586 0.124510 -vn -0.577350 -0.577350 -0.577350 -v 0.010750 0.128000 0.156200 -vn -0.845341 -0.278879 -0.455660 -v 0.010750 0.129500 0.156200 -vn -0.661187 -0.577627 -0.478726 -v 0.010750 0.129897 0.155424 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.090500 0.124700 -vn -0.577350 0.577350 0.577350 -v 0.010750 0.092000 0.124700 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.092000 0.123200 -vn -0.678874 -0.709236 -0.190039 -v 0.010750 0.086341 0.124612 -vn -0.904534 0.301511 0.301511 -v 0.010750 0.090000 0.126450 -vn -0.678874 -0.635883 -0.367127 -v 0.010750 0.087340 0.122200 -vn -0.577350 0.577350 0.577350 -v 0.010750 0.093500 0.123200 -vn -0.577350 0.577350 0.577350 -v 0.010750 0.090500 0.126450 -vn -0.737695 0.669360 -0.088109 -v 0.015750 0.097000 0.135400 -vn -0.770267 0.552290 -0.318849 -v 0.015750 0.097040 0.135550 -vn -0.770265 0.318854 -0.552289 -v 0.015750 0.097150 0.135660 -vn -0.737697 0.088113 -0.669358 -v 0.015750 0.097300 0.135700 -vn -0.737697 -0.088113 -0.669358 -v 0.015750 0.103700 0.135700 -vn -0.770266 -0.318854 -0.552289 -v 0.015750 0.103850 0.135660 -vn -0.770261 -0.552288 -0.318866 -v 0.015750 0.103960 0.135550 -vn -0.737701 -0.669352 -0.088124 -v 0.015750 0.104000 0.135400 -vn -0.737704 -0.669347 0.088131 -v 0.015750 0.104000 0.130000 -vn -0.770258 -0.552288 0.318874 -v 0.015750 0.103960 0.129850 -vn -0.770265 -0.318854 0.552289 -v 0.015750 0.103850 0.129740 -vn -0.737697 -0.088113 0.669358 -v 0.015750 0.103700 0.129700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.104000 0.132700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.104000 0.133625 -vn -0.565925 -0.644022 0.514748 -v 0.015750 0.097306 0.129700 -vn -0.561186 0.474782 -0.677977 -v 0.015750 0.097000 0.130048 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.097000 0.132700 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.097000 0.133625 -vn -0.748361 -0.663291 0.000000 -v 0.015750 0.134900 0.139700 -vn -0.748361 -0.623290 0.226861 -v 0.015750 0.134574 0.137853 -vn -0.748360 -0.508112 0.426356 -v 0.015750 0.133637 0.136229 -vn -0.748361 -0.331646 0.574427 -v 0.015750 0.132200 0.135023 -vn -0.748360 -0.115179 0.653216 -v 0.015750 0.130438 0.134382 -vn -0.748360 0.115179 0.653216 -v 0.015750 0.128562 0.134382 -vn -0.748361 0.331646 0.574427 -v 0.015750 0.126800 0.135023 -vn -0.748360 0.508112 0.426356 -v 0.015750 0.125363 0.136229 -vn -0.748361 0.623290 0.226859 -v 0.015750 0.124426 0.137853 -vn -0.748360 0.663293 0.000000 -v 0.015750 0.124100 0.139700 -vn -0.748360 0.623291 -0.226858 -v 0.015750 0.124426 0.141547 -vn -0.748361 0.508111 -0.426356 -v 0.015750 0.125363 0.143171 -vn -0.748360 0.331647 -0.574428 -v 0.015750 0.126800 0.144377 -vn -0.748361 0.115181 -0.653214 -v 0.015750 0.128562 0.145018 -vn -0.748361 -0.115181 -0.653214 -v 0.015750 0.130438 0.145018 -vn -0.748360 -0.331647 -0.574428 -v 0.015750 0.132200 0.144377 -vn -0.748361 -0.508111 -0.426356 -v 0.015750 0.133637 0.143171 -vn -0.748360 -0.623291 -0.226860 -v 0.015750 0.134574 0.141547 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.150425 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.149675 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.112250 0.149675 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.127925 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.112250 0.127925 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.106300 0.150425 -vn -0.673533 -0.228410 0.702981 -v 0.015750 0.138163 0.125043 -vn -0.689867 -0.056797 0.721705 -v 0.015750 0.136000 0.124700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.136850 0.127925 -vn -0.904534 0.301511 0.301511 -v 0.015750 0.090500 0.126450 -vn -0.577350 0.577350 0.577350 -v 0.015750 0.090000 0.126450 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090000 0.127925 -vn -0.904534 0.301511 -0.301511 -v 0.015750 0.093500 0.156200 -vn -0.577350 0.577350 -0.577350 -v 0.015750 0.093500 0.156700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.095175 0.156700 -vn -0.942505 0.074365 -0.325814 -v 0.015750 0.128777 0.154868 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.125325 0.154700 -vn -0.904534 -0.301511 -0.301511 -v 0.015750 0.128000 0.156200 -vn -0.606340 -0.415115 -0.678256 -v 0.015750 0.129500 0.156200 -vn -0.759605 -0.500759 -0.415019 -v 0.015750 0.129897 0.155424 -vn -0.942505 -0.074365 -0.325813 -v 0.015750 0.130223 0.154868 -vn -0.577350 0.577350 -0.577350 -v 0.015750 0.090000 0.152950 -vn -0.904534 0.301511 -0.301511 -v 0.015750 0.090500 0.152950 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.150425 -vn -0.577350 0.577350 -0.577350 -v 0.015750 0.090500 0.154700 -vn -0.904534 0.301511 -0.301511 -v 0.015750 0.092000 0.154700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.154700 -vn -0.577350 0.577350 -0.577350 -v 0.015750 0.092000 0.156200 -vn -0.577350 0.577350 0.577350 -v 0.015750 0.090000 0.142450 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090000 0.145775 -vn -0.904534 0.301511 0.301511 -v 0.015750 0.090500 0.142450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.145775 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090500 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.139700 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090500 0.137450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.137450 -vn -0.904534 0.301511 -0.301511 -v 0.015750 0.090500 0.136950 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.133625 -vn -0.577350 0.577350 -0.577350 -v 0.015750 0.090000 0.136950 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090000 0.133625 -vn -0.577350 0.577350 0.577350 -v 0.015750 0.093500 0.122700 -vn -0.904534 0.301511 0.301511 -v 0.015750 0.093500 0.123200 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.127925 -vn -0.577350 0.577350 0.577350 -v 0.015750 0.092000 0.123200 -vn -0.904534 0.301511 0.301511 -v 0.015750 0.092000 0.124700 -vn -0.577350 0.577350 0.577350 -v 0.015750 0.090500 0.124700 -vn -0.577350 -0.577350 0.577350 -v 0.015750 0.128000 0.122700 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.125325 0.122700 -vn -0.904534 -0.301511 0.301511 -v 0.015750 0.128000 0.123200 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.125325 0.127925 -vn -0.942504 0.074364 0.325815 -v 0.015750 0.128777 0.124531 -vn -0.942505 -0.074364 0.325814 -v 0.015750 0.130223 0.124531 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.125325 0.128975 -vn -0.942505 0.334192 0.000000 -v 0.015750 0.126250 0.127700 -vn -0.942505 0.301096 0.145000 -v 0.015750 0.126572 0.126290 -vn -0.942506 0.208363 0.261280 -v 0.015750 0.127474 0.125159 -vn -0.606340 -0.415114 0.678257 -v 0.015750 0.129500 0.123200 -vn -0.759605 -0.500757 0.415022 -v 0.015750 0.129897 0.123976 -vn -0.759603 -0.276656 0.588613 -v 0.015750 0.130586 0.124510 -vn -0.942505 -0.208364 0.261283 -v 0.015750 0.131526 0.125159 -vn -0.732634 -0.074613 0.676521 -v 0.015750 0.131436 0.124700 -vn -0.770258 0.318862 -0.552295 -v 0.015750 0.138050 0.131229 -vn -0.770268 0.552283 -0.318860 -v 0.015750 0.137721 0.130900 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.136850 0.132700 -vn -0.770256 0.637735 -0.000000 -v 0.015750 0.137600 0.130450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.136850 0.128975 -vn -0.770268 0.552283 0.318860 -v 0.015750 0.137721 0.130000 -vn -0.770258 0.318862 0.552295 -v 0.015750 0.138050 0.129671 -vn -0.770263 -0.000000 0.637726 -v 0.015750 0.138500 0.129550 -vn -0.689140 -0.656176 0.307438 -v 0.015750 0.142434 0.128943 -vn -0.678152 -0.584619 0.445343 -v 0.015750 0.141663 0.127585 -vn -0.673533 -0.434466 0.597990 -v 0.015750 0.140114 0.126037 -vn -0.770261 -0.318866 0.552288 -v 0.015750 0.138950 0.129671 -vn -0.770261 -0.552288 0.318866 -v 0.015750 0.139279 0.130000 -vn -0.685057 -0.704324 0.186079 -v 0.015750 0.142657 0.129537 -vn -0.770263 -0.637726 -0.000000 -v 0.015750 0.139400 0.130450 -vn -0.689866 -0.721705 0.056800 -v 0.015750 0.143000 0.131700 -vn -0.770261 -0.552288 -0.318866 -v 0.015750 0.139279 0.130900 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.143000 0.132700 -vn -0.770261 -0.318866 -0.552288 -v 0.015750 0.138950 0.131229 -vn -0.770263 0.000000 -0.637726 -v 0.015750 0.138500 0.131350 -vn -0.673533 -0.702979 -0.228414 -v 0.015750 0.142657 0.149863 -vn -0.770263 -0.637726 -0.000001 -v 0.015750 0.139400 0.148950 -vn -0.770261 -0.552287 -0.318867 -v 0.015750 0.139279 0.149400 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.136850 0.146700 -vn -1.000000 0.000000 -0.000001 -v 0.015750 0.136850 0.149675 -vn -0.770255 0.637736 -0.000001 -v 0.015750 0.137600 0.148950 -vn -0.770268 0.552283 0.318860 -v 0.015750 0.137721 0.148500 -vn -0.770258 0.318862 0.552295 -v 0.015750 0.138050 0.148171 -vn -0.770263 -0.000000 0.637726 -v 0.015750 0.138500 0.148050 -vn -0.707106 -0.707107 0.000000 -v 0.015750 0.143000 0.146700 -vn -0.770261 -0.318866 0.552288 -v 0.015750 0.138950 0.148171 -vn -0.770261 -0.552288 0.318866 -v 0.015750 0.139279 0.148500 -vn -0.689866 -0.721705 -0.056800 -v 0.015750 0.143000 0.147700 -vn -0.770261 -0.318866 -0.552288 -v 0.015750 0.138950 0.149729 -vn -0.770263 0.000000 -0.637726 -v 0.015750 0.138500 0.149850 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.136850 0.150425 -vn -0.770258 0.318862 -0.552295 -v 0.015750 0.138050 0.149729 -vn -0.770268 0.552281 -0.318861 -v 0.015750 0.137721 0.149400 -vn -0.689866 -0.056800 -0.721705 -v 0.015750 0.136000 0.154700 -vn -0.673534 -0.228410 -0.702980 -v 0.015750 0.138163 0.154357 -vn -0.673532 -0.434466 -0.597991 -v 0.015750 0.140114 0.153363 -vn -0.673534 -0.597990 -0.434465 -v 0.015750 0.141663 0.151814 -vn -0.770261 0.552291 0.318862 -v 0.015750 0.121667 0.152575 -vn -0.770265 0.318861 0.552286 -v 0.015750 0.122125 0.152117 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.150425 -vn -0.770258 0.000000 0.637732 -v 0.015750 0.122750 0.151950 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.125325 0.150425 -vn -0.770264 -0.318861 0.552287 -v 0.015750 0.123375 0.152117 -vn -0.770261 -0.552291 0.318862 -v 0.015750 0.123833 0.152575 -vn -0.770261 -0.637728 0.000000 -v 0.015750 0.124000 0.153200 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 0.123833 0.153825 -vn -0.770260 -0.318866 -0.552291 -v 0.015750 0.123375 0.154283 -vn -0.770264 -0.000000 -0.637725 -v 0.015750 0.122750 0.154450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.154700 -vn -0.770260 0.318866 -0.552291 -v 0.015750 0.122125 0.154283 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.154700 -vn -0.770263 0.552286 -0.318865 -v 0.015750 0.121667 0.153825 -vn -0.770261 0.637728 -0.000000 -v 0.015750 0.121500 0.153200 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.150425 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.112250 0.150425 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.112250 0.154700 -vn -1.000000 -0.000001 0.000001 -v 0.015750 0.106300 0.154700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.154700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.150425 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.095175 0.149675 -vn -0.707107 0.707107 -0.000000 -v 0.015750 0.090000 0.146700 -vn -0.707107 0.707107 -0.000000 -v 0.015750 0.090000 0.149675 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.095175 0.146700 -vn -0.770264 -0.637725 0.000000 -v 0.015750 0.094750 0.131700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.095175 0.128975 -vn -0.770261 0.318867 0.552288 -v 0.015750 0.092875 0.130617 -vn -0.770264 0.000001 0.637725 -v 0.015750 0.093500 0.130450 -vn -0.770261 -0.318866 0.552288 -v 0.015750 0.094125 0.130617 -vn -0.770261 -0.552288 0.318867 -v 0.015750 0.094583 0.131075 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090000 0.132700 -vn -0.770264 0.637725 0.000000 -v 0.015750 0.092250 0.131700 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090000 0.128975 -vn -0.770261 0.552288 0.318867 -v 0.015750 0.092417 0.131075 -vn -0.770259 -0.552293 -0.318864 -v 0.015750 0.094583 0.132325 -vn -0.770266 -0.318861 -0.552284 -v 0.015750 0.094125 0.132783 -vn -0.770258 0.000001 -0.637732 -v 0.015750 0.093500 0.132950 -vn -0.770266 0.318862 -0.552284 -v 0.015750 0.092875 0.132783 -vn -0.770259 0.552293 -0.318864 -v 0.015750 0.092417 0.132325 -vn -0.770259 -0.552293 0.318864 -v 0.015750 0.107833 0.125575 -vn -0.770264 -0.637725 0.000000 -v 0.015750 0.108000 0.126200 -vn -0.770261 -0.552288 -0.318867 -v 0.015750 0.107833 0.126825 -vn -0.770266 -0.318861 0.552284 -v 0.015750 0.107375 0.125117 -vn -0.707107 -0.000000 0.707107 -v 0.015750 0.112250 0.122700 -vn -0.770258 -0.000000 0.637732 -v 0.015750 0.106750 0.124950 -vn -0.707107 -0.000000 0.707107 -v 0.015750 0.106300 0.122700 -vn -0.770266 0.318862 0.552285 -v 0.015750 0.106125 0.125117 -vn -0.770262 -0.318866 -0.552287 -v 0.015750 0.107375 0.127283 -vn -0.770266 0.000001 -0.637723 -v 0.015750 0.106750 0.127450 -vn -1.000000 -0.000001 0.000001 -v 0.015750 0.106300 0.127925 -vn -0.770261 0.552288 -0.318867 -v 0.015750 0.105667 0.126825 -vn -0.770264 0.637725 0.000000 -v 0.015750 0.105500 0.126200 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.127925 -vn -0.770261 0.318867 -0.552289 -v 0.015750 0.106125 0.127283 -vn -0.770259 0.552293 0.318864 -v 0.015750 0.105667 0.125575 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.104750 0.122700 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 0.123375 0.127283 -vn -0.770264 -0.000000 -0.637725 -v 0.015750 0.122750 0.127450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.127925 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.122050 0.122700 -vn -0.770258 0.000000 0.637732 -v 0.015750 0.122750 0.124950 -vn -0.770265 -0.318861 0.552287 -v 0.015750 0.123375 0.125117 -vn -0.770261 -0.552291 0.318862 -v 0.015750 0.123833 0.125575 -vn -0.770261 -0.637728 0.000000 -v 0.015750 0.124000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 0.123833 0.126825 -vn -0.770260 0.318866 -0.552291 -v 0.015750 0.122125 0.127283 -vn -0.770263 0.552286 -0.318865 -v 0.015750 0.121667 0.126825 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.127925 -vn -0.770261 0.637729 -0.000000 -v 0.015750 0.121500 0.126200 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.119500 0.122700 -vn -0.770261 0.552291 0.318862 -v 0.015750 0.121667 0.125575 -vn -0.770265 0.318861 0.552287 -v 0.015750 0.122125 0.125117 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.143000 0.133625 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.143000 0.137450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.137450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.139700 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.135500 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.145775 -vn -0.707106 -0.707107 0.000000 -v 0.015750 0.143000 0.139700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.143000 0.145775 -vn -0.904534 0.301511 0.301511 -v 0.015750 0.111000 0.129900 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.112250 0.129900 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.112250 0.128975 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.116750 0.129900 -vn -1.000000 -0.000001 0.000000 -v 0.015750 0.106300 0.132700 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.111000 0.132700 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.106300 0.128975 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.112250 0.139700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.112250 0.139200 -vn -0.904534 0.301511 -0.301511 -v 0.015750 0.111000 0.139200 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.111000 0.133625 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.106300 0.133625 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.111000 0.137450 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.106300 0.137450 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.106300 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.106300 0.146700 -vn -0.707107 0.707107 -0.000000 -v 0.015750 0.111000 0.146700 -vn -0.904534 0.301511 -0.301511 -v 0.015750 0.111000 0.149500 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.106300 0.149675 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.112250 0.149500 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.116750 0.149500 -vn -0.904534 -0.301511 -0.301512 -v 0.015750 0.117500 0.149500 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.119500 0.149675 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.119500 0.146700 -vn -0.707107 -0.707107 -0.000000 -v 0.015750 0.117500 0.146700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.139700 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.116750 0.140200 -vn -0.904534 -0.301511 0.301511 -v 0.015750 0.117500 0.140200 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.117500 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.139700 -vn -1.000000 -0.000000 0.000000 -v 0.015750 0.106300 0.145775 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.111000 0.145775 -vn -0.904534 0.301511 0.301511 -v 0.015750 0.111000 0.140200 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.112250 0.140200 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.125325 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.133825 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.139700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.133825 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.125325 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.096550 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.137450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.096550 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.096550 0.137450 -vn -0.764304 -0.644721 0.013206 -v 0.015750 0.097400 0.129282 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.133625 -vn -0.764067 0.232161 0.601916 -v 0.015750 0.096175 0.128461 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.096550 0.127925 -vn -0.764745 -0.071180 0.640389 -v 0.015750 0.096599 0.128405 -vn -0.764747 -0.358941 0.535092 -v 0.015750 0.097001 0.128553 -vn -0.764746 -0.565526 0.308779 -v 0.015750 0.097290 0.128869 -vn -0.764751 -0.069998 -0.640513 -v 0.015750 0.096598 0.130195 -vn -0.764742 0.233791 -0.600425 -v 0.015750 0.096173 0.130139 -vn -0.764744 0.484694 -0.424544 -v 0.015750 0.095823 0.129893 -vn -0.764749 0.625987 -0.152640 -v 0.015750 0.095626 0.129513 -vn -0.764744 0.625713 0.153784 -v 0.015750 0.095626 0.129085 -vn -0.764104 0.485064 0.425274 -v 0.015750 0.095824 0.128706 -vn -0.729847 -0.680319 -0.067001 -v 0.015750 0.104000 0.149400 -vn -0.753777 -0.607102 -0.251488 -v 0.015750 0.103977 0.149515 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.104750 0.149675 -vn -0.566634 -0.643195 -0.515001 -v 0.015750 0.097306 0.149700 -vn -0.764746 -0.644208 -0.012633 -v 0.015750 0.097400 0.150118 -vn -0.729856 -0.067025 -0.680307 -v 0.015750 0.103700 0.149700 -vn -0.753757 -0.251493 -0.607126 -v 0.015750 0.103815 0.149677 -vn -0.753762 -0.464653 -0.464694 -v 0.015750 0.103912 0.149612 -vn -0.707107 -0.707107 -0.000000 -v 0.015750 0.104000 0.146700 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.104750 0.146700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.104000 0.145775 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.145775 -vn -0.737704 -0.669347 0.088131 -v 0.015750 0.104000 0.144000 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.104750 0.139700 -vn -0.770258 -0.552288 0.318874 -v 0.015750 0.103960 0.143850 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.096550 0.145775 -vn -0.737698 0.669355 0.088117 -v 0.015750 0.097000 0.144000 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.096550 0.139700 -vn -0.770264 0.552289 0.318858 -v 0.015750 0.097040 0.143850 -vn -0.770266 0.318854 0.552289 -v 0.015750 0.097150 0.143740 -vn -0.737697 0.088113 0.669358 -v 0.015750 0.097300 0.143700 -vn -0.737697 -0.088113 0.669358 -v 0.015750 0.103700 0.143700 -vn -0.770265 -0.318854 0.552289 -v 0.015750 0.103850 0.143740 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.096550 0.146700 -vn -0.707107 0.707107 -0.000000 -v 0.015750 0.097000 0.146700 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.097000 0.145775 -vn -0.561186 0.474782 0.677977 -v 0.015750 0.097000 0.149352 -vn -0.764746 -0.070010 0.640517 -v 0.015750 0.096598 0.149205 -vn -0.764747 0.233779 0.600424 -v 0.015750 0.096173 0.149261 -vn -0.764744 0.484694 0.424544 -v 0.015750 0.095823 0.149507 -vn -0.764747 0.232681 -0.600850 -v 0.015750 0.096175 0.150939 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.096550 0.154700 -vn -0.764747 0.483921 -0.425421 -v 0.015750 0.095824 0.150694 -vn -0.764744 0.625713 -0.153784 -v 0.015750 0.095626 0.150315 -vn -0.764749 0.625987 0.152640 -v 0.015750 0.095626 0.149887 -vn -0.764746 -0.565526 -0.308779 -v 0.015750 0.097290 0.150531 -vn -0.764747 -0.358941 -0.535092 -v 0.015750 0.097001 0.150847 -vn -0.764745 -0.071180 -0.640389 -v 0.015750 0.096599 0.150994 -vn -0.942505 -0.074365 -0.325814 -v 0.015750 0.130223 0.130868 -vn -0.942505 0.074365 -0.325814 -v 0.015750 0.128777 0.130868 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.125325 0.132700 -vn -0.942505 0.208365 -0.261283 -v 0.015750 0.127474 0.130241 -vn -0.942505 0.301096 -0.145000 -v 0.015750 0.126572 0.129110 -vn -0.942504 -0.208367 -0.261285 -v 0.015750 0.131526 0.130241 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.133825 0.132700 -vn -0.942506 -0.301094 -0.145001 -v 0.015750 0.132428 0.129110 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.133825 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.133825 0.127925 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.133825 0.124700 -vn -0.942505 -0.301096 0.145000 -v 0.015750 0.132428 0.126290 -vn -0.942505 -0.334192 -0.000000 -v 0.015750 0.132750 0.127700 -vn -0.759605 -0.276655 -0.588611 -v 0.015750 0.130586 0.154890 -vn -0.732633 -0.074610 -0.676522 -v 0.015750 0.131436 0.154700 -vn -0.942505 -0.208366 -0.261283 -v 0.015750 0.131526 0.154241 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.133825 0.154700 -vn -0.942505 -0.301096 -0.145001 -v 0.015750 0.132428 0.153110 -vn -0.942505 -0.334192 -0.000001 -v 0.015750 0.132750 0.151700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.133825 0.150425 -vn -0.942505 -0.301096 0.145001 -v 0.015750 0.132428 0.150290 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.133825 0.149675 -vn -0.942505 -0.208366 0.261282 -v 0.015750 0.131526 0.149159 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.133825 0.146700 -vn -0.942505 -0.074366 0.325812 -v 0.015750 0.130223 0.148531 -vn -0.942505 0.301097 0.145000 -v 0.015750 0.126572 0.150290 -vn -0.942506 0.208365 0.261280 -v 0.015750 0.127474 0.149159 -vn -0.942505 0.208365 -0.261280 -v 0.015750 0.127474 0.154241 -vn -0.942505 0.301097 -0.145000 -v 0.015750 0.126572 0.153110 -vn -0.942505 0.334191 -0.000000 -v 0.015750 0.126250 0.151700 -vn -0.770263 0.552286 -0.318865 -v 0.015750 0.113667 0.126825 -vn -0.770261 0.637728 0.000000 -v 0.015750 0.113500 0.126200 -vn -0.770261 0.552291 0.318862 -v 0.015750 0.113667 0.125575 -vn -0.770265 0.318861 0.552286 -v 0.015750 0.114125 0.125117 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.116750 0.122700 -vn -0.770258 -0.000000 0.637732 -v 0.015750 0.114750 0.124950 -vn -0.770265 -0.318861 0.552286 -v 0.015750 0.115375 0.125117 -vn -0.770261 -0.552291 0.318862 -v 0.015750 0.115833 0.125575 -vn -0.770261 -0.637728 -0.000000 -v 0.015750 0.116000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 0.115833 0.126825 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 0.115375 0.127283 -vn -0.770264 0.000000 -0.637725 -v 0.015750 0.114750 0.127450 -vn -0.770260 0.318866 -0.552291 -v 0.015750 0.114125 0.127283 -vn -0.770261 -0.637728 -0.000000 -v 0.015750 0.100000 0.126200 -vn -0.770263 -0.552286 -0.318865 -v 0.015750 0.099833 0.126825 -vn -0.770261 0.552288 -0.318867 -v 0.015750 0.097667 0.126825 -vn -0.770264 0.637725 0.000000 -v 0.015750 0.097500 0.126200 -vn -0.770261 -0.552291 0.318862 -v 0.015750 0.099833 0.125575 -vn -0.770260 -0.318865 -0.552291 -v 0.015750 0.099375 0.127283 -vn -0.770264 -0.000001 -0.637725 -v 0.015750 0.098750 0.127450 -vn -0.770261 0.318866 -0.552288 -v 0.015750 0.098125 0.127283 -vn -0.770259 0.552293 0.318864 -v 0.015750 0.097667 0.125575 -vn -0.770266 0.318861 0.552284 -v 0.015750 0.098125 0.125117 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.096550 0.122700 -vn -0.770258 -0.000001 0.637732 -v 0.015750 0.098750 0.124950 -vn -0.770265 -0.318861 0.552286 -v 0.015750 0.099375 0.125117 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.095175 0.122700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.128975 -vn -0.904534 -0.301511 0.301511 -v 0.015750 0.117500 0.129900 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.132700 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.117500 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.133625 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.117500 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.119500 0.137450 -vn -0.707107 -0.707107 0.000000 -v 0.015750 0.117500 0.137450 -vn -0.904534 -0.301511 -0.301511 -v 0.015750 0.117500 0.139200 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.116750 0.139200 -vn -0.707107 0.000000 0.707107 -v 0.015750 0.135500 0.124700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.127925 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.128975 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.132700 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.133625 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.122050 0.137450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.136850 0.137450 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.136850 0.139700 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.125325 0.146700 -vn -1.000000 -0.000000 -0.000000 -v 0.015750 0.125325 0.149675 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.122050 0.149675 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.122050 0.146700 -vn -1.000000 0.000000 -0.000000 -v 0.015750 0.135500 0.149675 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.135500 0.150425 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.135500 0.154700 -vn -0.942505 0.074365 0.325813 -v 0.015750 0.128777 0.148531 -vn -0.707107 0.707107 0.000000 -v 0.015750 0.090000 0.150425 -vn -1.000000 0.000000 0.000000 -v 0.015750 0.116750 0.154700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.096550 0.156700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.104750 0.156700 -vn -0.707107 -0.000000 -0.707107 -v 0.015750 0.106300 0.156700 -vn -0.707107 -0.000000 -0.707107 -v 0.015750 0.112250 0.156700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.116750 0.156700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.119500 0.156700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.122050 0.156700 -vn -0.707107 0.000000 -0.707107 -v 0.015750 0.125325 0.156700 -vn -0.577350 -0.577350 -0.577350 -v 0.015750 0.128000 0.156700 -vn 0.770261 -0.637728 0.000000 -v 0.016750 0.100000 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.016750 0.099833 0.125575 -vn 0.770265 -0.318861 0.552286 -v 0.016750 0.099375 0.125117 -vn 0.770258 -0.000001 0.637732 -v 0.016750 0.098750 0.124950 -vn 0.770266 0.318861 0.552284 -v 0.016750 0.098125 0.125117 -vn 0.770259 0.552293 0.318864 -v 0.016750 0.097667 0.125575 -vn 0.770264 0.637725 0.000000 -v 0.016750 0.097500 0.126200 -vn 0.770261 0.552288 -0.318867 -v 0.016750 0.097667 0.126825 -vn 0.770261 0.318866 -0.552288 -v 0.016750 0.098125 0.127283 -vn 0.770264 -0.000001 -0.637725 -v 0.016750 0.098750 0.127450 -vn 0.770260 -0.318865 -0.552291 -v 0.016750 0.099375 0.127283 -vn 0.770263 -0.552286 -0.318865 -v 0.016750 0.099833 0.126825 -vn 0.770264 -0.637725 0.000000 -v 0.016750 0.108000 0.126200 -vn 0.770259 -0.552293 0.318864 -v 0.016750 0.107833 0.125575 -vn 0.770266 -0.318861 0.552284 -v 0.016750 0.107375 0.125117 -vn 0.770258 0.000001 0.637732 -v 0.016750 0.106750 0.124950 -vn 0.770267 0.318864 0.552281 -v 0.016750 0.106125 0.125117 -vn 0.770259 0.552293 0.318864 -v 0.016750 0.105667 0.125575 -vn 0.770264 0.637725 0.000000 -v 0.016750 0.105500 0.126200 -vn 0.770261 0.552288 -0.318867 -v 0.016750 0.105667 0.126825 -vn 0.770261 0.318868 -0.552287 -v 0.016750 0.106125 0.127283 -vn 0.770263 0.000002 -0.637726 -v 0.016750 0.106750 0.127450 -vn 0.770261 -0.318866 -0.552288 -v 0.016750 0.107375 0.127283 -vn 0.770261 -0.552288 -0.318867 -v 0.016750 0.107833 0.126825 -vn 0.770264 -0.637725 0.000000 -v 0.016750 0.094750 0.131700 -vn 0.770261 -0.552288 0.318867 -v 0.016750 0.094583 0.131075 -vn 0.770261 -0.318866 0.552288 -v 0.016750 0.094125 0.130617 -vn 0.770264 0.000001 0.637725 -v 0.016750 0.093500 0.130450 -vn 0.770261 0.318867 0.552288 -v 0.016750 0.092875 0.130617 -vn 0.770261 0.552288 0.318867 -v 0.016750 0.092417 0.131075 -vn 0.770264 0.637725 0.000000 -v 0.016750 0.092250 0.131700 -vn 0.770259 0.552293 -0.318864 -v 0.016750 0.092417 0.132325 -vn 0.770266 0.318862 -0.552284 -v 0.016750 0.092875 0.132783 -vn 0.770258 0.000001 -0.637732 -v 0.016750 0.093500 0.132950 -vn 0.770266 -0.318861 -0.552284 -v 0.016750 0.094125 0.132783 -vn 0.770259 -0.552293 -0.318864 -v 0.016750 0.094583 0.132325 -vn 0.770261 -0.637728 0.000000 -v 0.016750 0.116000 0.126200 -vn 0.770261 -0.552291 0.318862 -v 0.016750 0.115833 0.125575 -vn 0.770265 -0.318861 0.552286 -v 0.016750 0.115375 0.125117 -vn 0.770258 0.000000 0.637732 -v 0.016750 0.114750 0.124950 -vn 0.770265 0.318861 0.552286 -v 0.016750 0.114125 0.125117 -vn 0.770261 0.552291 0.318862 -v 0.016750 0.113667 0.125575 -vn 0.770261 0.637728 -0.000000 -v 0.016750 0.113500 0.126200 -vn 0.770263 0.552286 -0.318865 -v 0.016750 0.113667 0.126825 -vn 0.770260 0.318865 -0.552291 -v 0.016750 0.114125 0.127283 -vn 0.770264 0.000000 -0.637725 -v 0.016750 0.114750 0.127450 -vn 0.770260 -0.318865 -0.552291 -v 0.016750 0.115375 0.127283 -vn 0.770263 -0.552286 -0.318865 -v 0.016750 0.115833 0.126825 -vn 0.609994 -0.686244 0.396202 -v 0.016750 0.117250 0.151757 -vn 0.609994 -0.686244 -0.396202 -v 0.016750 0.117250 0.154643 -vn 0.609994 0.686244 -0.396202 -v 0.016750 0.112250 0.154643 -vn 0.609995 0.686244 0.396202 -v 0.016750 0.112250 0.151757 -vn 0.609994 0.000001 0.792406 -v 0.016750 0.114750 0.150313 -vn 0.609994 0.000001 -0.792406 -v 0.016750 0.114750 0.156087 -vn 0.609994 0.686244 0.396202 -v 0.016750 0.112250 0.124757 -vn 0.609994 0.000001 0.792406 -v 0.016750 0.114750 0.123313 -vn 0.609994 0.686244 -0.396203 -v 0.016750 0.112250 0.127643 -vn 0.609994 -0.686243 -0.396204 -v 0.016750 0.117250 0.127643 -vn 0.609995 0.000000 -0.792406 -v 0.016750 0.114750 0.129087 -vn 0.609994 -0.686244 0.396203 -v 0.016750 0.117250 0.124757 -vn 0.609994 -0.686243 -0.396204 -v 0.016750 0.109250 0.127643 -vn 0.609995 0.000001 -0.792405 -v 0.016750 0.106750 0.129087 -vn 0.609994 -0.686244 0.396203 -v 0.016750 0.109250 0.124757 -vn 0.609994 0.686244 -0.396203 -v 0.016750 0.104250 0.127643 -vn 0.609994 0.686244 0.396202 -v 0.016750 0.104250 0.124757 -vn 0.609994 0.000001 0.792406 -v 0.016750 0.106750 0.123313 -vn 0.609994 0.686243 -0.396204 -v 0.016750 0.096250 0.127643 -vn 0.609994 0.686244 0.396203 -v 0.016750 0.096250 0.124757 -vn 0.609995 -0.000001 -0.792406 -v 0.016750 0.098750 0.129087 -vn 0.609994 -0.686244 0.396202 -v 0.016750 0.101250 0.124757 -vn 0.609994 -0.686243 -0.396203 -v 0.016750 0.101250 0.127643 -vn 0.609994 -0.000000 0.792406 -v 0.016750 0.098750 0.123313 -vn 0.609994 0.686243 -0.396203 -v 0.016750 0.091000 0.133143 -vn 0.609994 0.686243 0.396203 -v 0.016750 0.091000 0.130257 -vn 0.609995 0.000000 -0.792406 -v 0.016750 0.093500 0.134587 -vn 0.609994 -0.686243 0.396204 -v 0.016750 0.096000 0.130257 -vn 0.609994 -0.686243 -0.396204 -v 0.016750 0.096000 0.133143 -vn 0.609994 0.000001 0.792406 -v 0.016750 0.093500 0.128813 -vn 0.609995 0.686244 -0.396200 -v 0.016750 0.091000 0.149143 -vn 0.609994 0.686244 0.396203 -v 0.016750 0.091000 0.146257 -vn 0.609994 0.000000 -0.792406 -v 0.016750 0.093500 0.150587 -vn 0.609995 -0.686244 -0.396202 -v 0.016750 0.096000 0.149143 -vn 0.609994 -0.686243 0.396204 -v 0.016750 0.096000 0.146257 -vn 0.609995 0.000001 0.792406 -v 0.016750 0.093500 0.144813 -vn 0.609994 0.686244 -0.396202 -v 0.016750 0.096250 0.154643 -vn 0.609994 0.686244 0.396202 -v 0.016750 0.096250 0.151757 -vn 0.609995 -0.686244 -0.396202 -v 0.016750 0.101250 0.154643 -vn 0.609994 -0.000001 -0.792406 -v 0.016750 0.098750 0.156087 -vn 0.609995 -0.686244 0.396202 -v 0.016750 0.101250 0.151757 -vn 0.609994 -0.000001 0.792406 -v 0.016750 0.098750 0.150313 -vn 0.609994 0.686244 -0.396202 -v 0.016750 0.104250 0.154643 -vn 0.609994 0.686244 0.396201 -v 0.016750 0.104250 0.151757 -vn 0.609994 0.000001 -0.792406 -v 0.016750 0.106750 0.156087 -vn 0.609994 -0.686244 -0.396202 -v 0.016750 0.109250 0.154643 -vn 0.609994 -0.686244 0.396202 -v 0.016750 0.109250 0.151757 -vn 0.609994 0.000001 0.792406 -v 0.016750 0.106750 0.150313 -vn -0.904093 -0.095091 0.416622 -v 0.016750 0.130001 0.149506 -vn -0.904092 0.095093 0.416623 -v 0.016750 0.128999 0.149506 -vn -0.904094 0.266439 0.334104 -v 0.016750 0.128097 0.149941 -vn -0.904092 0.385018 0.185414 -v 0.016750 0.127473 0.150724 -vn -0.904093 0.427335 -0.000000 -v 0.016750 0.127250 0.151700 -vn -0.904092 0.385017 -0.185416 -v 0.016750 0.127473 0.152676 -vn -0.904094 0.266440 -0.334103 -v 0.016750 0.128097 0.153459 -vn -0.904092 0.095092 -0.416623 -v 0.016750 0.128999 0.153894 -vn -0.904093 -0.095091 -0.416622 -v 0.016750 0.130001 0.153894 -vn -0.904093 -0.266440 -0.334105 -v 0.016750 0.130903 0.153459 -vn -0.904092 -0.385017 -0.185415 -v 0.016750 0.131527 0.152676 -vn -0.904093 -0.427335 -0.000001 -v 0.016750 0.131750 0.151700 -vn -0.904092 -0.385017 0.185415 -v 0.016750 0.131527 0.150724 -vn -0.904093 -0.266440 0.334105 -v 0.016750 0.130903 0.149941 -vn -0.904093 -0.095088 0.416622 -v 0.016750 0.130001 0.125506 -vn -0.904093 0.095090 0.416623 -v 0.016750 0.128999 0.125506 -vn -0.904093 0.266439 0.334106 -v 0.016750 0.128097 0.125941 -vn -0.904093 0.385016 0.185412 -v 0.016750 0.127473 0.126724 -vn -0.904093 0.427335 0.000000 -v 0.016750 0.127250 0.127700 -vn -0.904093 0.385016 -0.185412 -v 0.016750 0.127473 0.128676 -vn -0.904092 0.266440 -0.334108 -v 0.016750 0.128097 0.129459 -vn -0.904092 0.095091 -0.416623 -v 0.016750 0.128999 0.129894 -vn -0.904093 -0.095087 -0.416622 -v 0.016750 0.130001 0.129894 -vn -0.904091 -0.266443 -0.334108 -v 0.016750 0.130903 0.129459 -vn -0.904093 -0.385017 -0.185414 -v 0.016750 0.131527 0.128676 -vn -0.904093 -0.427335 -0.000000 -v 0.016750 0.131750 0.127700 -vn -0.904093 -0.385016 0.185412 -v 0.016750 0.131527 0.126724 -vn -0.904092 -0.266439 0.334108 -v 0.016750 0.130903 0.125941 -vn 0.770262 0.637727 0.000001 -v -0.068000 0.127400 0.129200 -vn -0.770262 0.637727 0.000001 -v -0.070000 0.127400 0.129200 -vn 0.770263 0.552286 -0.318866 -v -0.068000 0.127681 0.130250 -vn -0.770263 0.552286 -0.318866 -v -0.070000 0.127681 0.130250 -vn 0.770260 0.318863 -0.552291 -v -0.068000 0.128450 0.131019 -vn -0.770260 0.318863 -0.552291 -v -0.070000 0.128450 0.131019 -vn 0.770263 -0.000000 -0.637727 -v -0.068000 0.129500 0.131300 -vn -0.770263 0.000000 -0.637727 -v -0.070000 0.129500 0.131300 -vn 0.770260 -0.318863 -0.552291 -v -0.068000 0.130550 0.131019 -vn -0.770260 -0.318863 -0.552291 -v -0.070000 0.130550 0.131019 -vn 0.770265 -0.552286 -0.318861 -v -0.068000 0.131319 0.130250 -vn -0.770265 -0.552286 -0.318861 -v -0.070000 0.131319 0.130250 -vn 0.770259 -0.637732 0.000001 -v -0.068000 0.131600 0.129200 -vn -0.770259 -0.637731 0.000001 -v -0.070000 0.131600 0.129200 -vn 0.770263 -0.552289 0.318860 -v -0.068000 0.131319 0.128150 -vn -0.770263 -0.552289 0.318860 -v -0.070000 0.131319 0.128150 -vn 0.770263 -0.318860 0.552289 -v -0.068000 0.130550 0.127381 -vn -0.770263 -0.318860 0.552289 -v -0.070000 0.130550 0.127381 -vn 0.770259 0.000000 0.637731 -v -0.068000 0.129500 0.127100 -vn -0.770259 -0.000000 0.637731 -v -0.070000 0.129500 0.127100 -vn 0.770263 0.318860 0.552289 -v -0.068000 0.128450 0.127381 -vn -0.770263 0.318860 0.552289 -v -0.070000 0.128450 0.127381 -vn 0.770261 0.552288 0.318865 -v -0.068000 0.127681 0.128150 -vn -0.770261 0.552288 0.318865 -v -0.070000 0.127681 0.128150 -vn 0.770262 0.637727 -0.000000 -v -0.068000 0.127400 0.105200 -vn -0.770262 0.637727 0.000000 -v -0.070000 0.127400 0.105200 -vn 0.770263 0.552286 -0.318866 -v -0.068000 0.127681 0.106250 -vn -0.770263 0.552286 -0.318866 -v -0.070000 0.127681 0.106250 -vn 0.770260 0.318863 -0.552291 -v -0.068000 0.128450 0.107019 -vn -0.770260 0.318863 -0.552291 -v -0.070000 0.128450 0.107019 -vn 0.770263 -0.000000 -0.637727 -v -0.068000 0.129500 0.107300 -vn -0.770262 0.000000 -0.637727 -v -0.070000 0.129500 0.107300 -vn 0.770260 -0.318863 -0.552291 -v -0.068000 0.130550 0.107019 -vn -0.770260 -0.318863 -0.552291 -v -0.070000 0.130550 0.107019 -vn 0.770265 -0.552286 -0.318862 -v -0.068000 0.131319 0.106250 -vn -0.770265 -0.552286 -0.318862 -v -0.070000 0.131319 0.106250 -vn 0.770259 -0.637732 0.000000 -v -0.068000 0.131600 0.105200 -vn -0.770259 -0.637732 0.000000 -v -0.070000 0.131600 0.105200 -vn 0.770264 -0.552287 0.318861 -v -0.068000 0.131319 0.104150 -vn -0.770264 -0.552287 0.318861 -v -0.070000 0.131319 0.104150 -vn 0.770262 -0.318862 0.552290 -v -0.068000 0.130550 0.103381 -vn -0.770262 -0.318862 0.552290 -v -0.070000 0.130550 0.103381 -vn 0.770261 0.000000 0.637729 -v -0.068000 0.129500 0.103100 -vn -0.770261 0.000000 0.637729 -v -0.070000 0.129500 0.103100 -vn 0.770262 0.318862 0.552290 -v -0.068000 0.128450 0.103381 -vn -0.770262 0.318862 0.552290 -v -0.070000 0.128450 0.103381 -vn 0.770262 0.552287 0.318865 -v -0.068000 0.127681 0.104150 -vn -0.770262 0.552287 0.318865 -v -0.070000 0.127681 0.104150 -vn -0.770264 -0.637725 0.000000 -v -0.068000 0.094750 0.109200 -vn 0.770264 -0.637725 0.000000 -v -0.067000 0.094750 0.109200 -vn -0.770260 -0.552291 -0.318866 -v -0.068000 0.094583 0.109825 -vn 0.770260 -0.552291 -0.318865 -v -0.067000 0.094583 0.109825 -vn -0.770264 -0.318864 -0.552286 -v -0.068000 0.094125 0.110283 -vn 0.770264 -0.318864 -0.552286 -v -0.067000 0.094125 0.110283 -vn -0.770261 0.000001 -0.637729 -v -0.068000 0.093500 0.110450 -vn 0.770261 0.000001 -0.637729 -v -0.067000 0.093500 0.110450 -vn -0.770263 0.318865 -0.552286 -v -0.068000 0.092875 0.110283 -vn 0.770263 0.318865 -0.552286 -v -0.067000 0.092875 0.110283 -vn -0.770260 0.552291 -0.318865 -v -0.068000 0.092417 0.109825 -vn 0.770260 0.552291 -0.318865 -v -0.067000 0.092417 0.109825 -vn -0.770264 0.637725 0.000000 -v -0.068000 0.092250 0.109200 -vn 0.770264 0.637725 0.000000 -v -0.067000 0.092250 0.109200 -vn -0.770260 0.552291 0.318865 -v -0.068000 0.092417 0.108575 -vn 0.770260 0.552291 0.318865 -v -0.067000 0.092417 0.108575 -vn -0.770263 0.318865 0.552286 -v -0.068000 0.092875 0.108117 -vn 0.770263 0.318865 0.552286 -v -0.067000 0.092875 0.108117 -vn -0.770261 0.000001 0.637729 -v -0.068000 0.093500 0.107950 -vn 0.770261 0.000001 0.637729 -v -0.067000 0.093500 0.107950 -vn -0.770263 -0.318864 0.552286 -v -0.068000 0.094125 0.108117 -vn 0.770263 -0.318864 0.552286 -v -0.067000 0.094125 0.108117 -vn -0.770260 -0.552291 0.318865 -v -0.068000 0.094583 0.108575 -vn 0.770260 -0.552291 0.318865 -v -0.067000 0.094583 0.108575 -vn -0.770261 -0.637728 0.000000 -v -0.068000 0.116000 0.103700 -vn 0.770261 -0.637729 0.000000 -v -0.067000 0.116000 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.068000 0.115833 0.104325 -vn 0.770262 -0.552289 -0.318863 -v -0.067000 0.115833 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.068000 0.115375 0.104783 -vn 0.770261 -0.318867 -0.552288 -v -0.067000 0.115375 0.104783 -vn -0.770264 0.000000 -0.637725 -v -0.068000 0.114750 0.104950 -vn 0.770264 0.000000 -0.637725 -v -0.067000 0.114750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.068000 0.114125 0.104783 -vn 0.770261 0.318867 -0.552288 -v -0.067000 0.114125 0.104783 -vn -0.770262 0.552289 -0.318863 -v -0.068000 0.113667 0.104325 -vn 0.770262 0.552289 -0.318863 -v -0.067000 0.113667 0.104325 -vn -0.770261 0.637728 0.000000 -v -0.068000 0.113500 0.103700 -vn 0.770261 0.637728 0.000000 -v -0.067000 0.113500 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.068000 0.113667 0.103075 -vn 0.770262 0.552289 0.318863 -v -0.067000 0.113667 0.103075 -vn -0.770262 0.318863 0.552289 -v -0.068000 0.114125 0.102617 -vn 0.770262 0.318863 0.552289 -v -0.067000 0.114125 0.102617 -vn -0.770261 0.000000 0.637728 -v -0.068000 0.114750 0.102450 -vn 0.770261 0.000000 0.637728 -v -0.067000 0.114750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.068000 0.115375 0.102617 -vn 0.770262 -0.318863 0.552289 -v -0.067000 0.115375 0.102617 -vn -0.770262 -0.552289 0.318863 -v -0.068000 0.115833 0.103075 -vn 0.770262 -0.552289 0.318863 -v -0.067000 0.115833 0.103075 -vn -0.770264 -0.637725 0.000000 -v -0.068000 0.108000 0.103700 -vn 0.770264 -0.637725 0.000000 -v -0.067000 0.108000 0.103700 -vn -0.770260 -0.552291 -0.318865 -v -0.068000 0.107833 0.104325 -vn 0.770260 -0.552291 -0.318865 -v -0.067000 0.107833 0.104325 -vn -0.770262 -0.318868 -0.552286 -v -0.068000 0.107375 0.104783 -vn 0.770262 -0.318868 -0.552286 -v -0.067000 0.107375 0.104783 -vn -0.770264 0.000001 -0.637725 -v -0.068000 0.106750 0.104950 -vn 0.770264 0.000001 -0.637726 -v -0.067000 0.106750 0.104950 -vn -0.770262 0.318869 -0.552286 -v -0.068000 0.106125 0.104783 -vn 0.770262 0.318869 -0.552286 -v -0.067000 0.106125 0.104783 -vn -0.770260 0.552291 -0.318865 -v -0.068000 0.105667 0.104325 -vn 0.770260 0.552291 -0.318865 -v -0.067000 0.105667 0.104325 -vn -0.770264 0.637725 0.000000 -v -0.068000 0.105500 0.103700 -vn 0.770264 0.637725 0.000000 -v -0.067000 0.105500 0.103700 -vn -0.770260 0.552291 0.318866 -v -0.068000 0.105667 0.103075 -vn 0.770260 0.552291 0.318865 -v -0.067000 0.105667 0.103075 -vn -0.770263 0.318865 0.552286 -v -0.068000 0.106125 0.102617 -vn 0.770263 0.318865 0.552286 -v -0.067000 0.106125 0.102617 -vn -0.770261 0.000001 0.637729 -v -0.068000 0.106750 0.102450 -vn 0.770261 0.000001 0.637729 -v -0.067000 0.106750 0.102450 -vn -0.770263 -0.318864 0.552286 -v -0.068000 0.107375 0.102617 -vn 0.770264 -0.318864 0.552286 -v -0.067000 0.107375 0.102617 -vn -0.770260 -0.552291 0.318865 -v -0.068000 0.107833 0.103075 -vn 0.770260 -0.552291 0.318865 -v -0.067000 0.107833 0.103075 -vn -0.770261 -0.637728 0.000000 -v -0.068000 0.100000 0.103700 -vn 0.770261 -0.637728 0.000000 -v -0.067000 0.100000 0.103700 -vn -0.770262 -0.552289 -0.318863 -v -0.068000 0.099833 0.104325 -vn 0.770262 -0.552289 -0.318863 -v -0.067000 0.099833 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.068000 0.099375 0.104783 -vn 0.770261 -0.318867 -0.552288 -v -0.067000 0.099375 0.104783 -vn -0.770264 -0.000001 -0.637726 -v -0.068000 0.098750 0.104950 -vn 0.770264 -0.000001 -0.637725 -v -0.067000 0.098750 0.104950 -vn -0.770262 0.318868 -0.552286 -v -0.068000 0.098125 0.104783 -vn 0.770262 0.318868 -0.552286 -v -0.067000 0.098125 0.104783 -vn -0.770260 0.552291 -0.318865 -v -0.068000 0.097667 0.104325 -vn 0.770259 0.552291 -0.318866 -v -0.067000 0.097667 0.104325 -vn -0.770264 0.637725 0.000000 -v -0.068000 0.097500 0.103700 -vn 0.770264 0.637725 0.000000 -v -0.067000 0.097500 0.103700 -vn -0.770260 0.552291 0.318866 -v -0.068000 0.097667 0.103075 -vn 0.770260 0.552291 0.318865 -v -0.067000 0.097667 0.103075 -vn -0.770264 0.318864 0.552286 -v -0.068000 0.098125 0.102617 -vn 0.770263 0.318864 0.552286 -v -0.067000 0.098125 0.102617 -vn -0.770261 -0.000001 0.637729 -v -0.068000 0.098750 0.102450 -vn 0.770261 -0.000001 0.637729 -v -0.067000 0.098750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.068000 0.099375 0.102617 -vn 0.770262 -0.318863 0.552289 -v -0.067000 0.099375 0.102617 -vn -0.770262 -0.552289 0.318863 -v -0.068000 0.099833 0.103075 -vn 0.770262 -0.552289 0.318863 -v -0.067000 0.099833 0.103075 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.117375 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.111625 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.111625 0.127582 -vn -0.770261 0.552288 -0.318866 -v -0.070000 0.122721 0.109650 -vn -0.770263 0.637726 0.000000 -v -0.070000 0.122600 0.109200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.110200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.110200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.111625 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.101632 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.117375 0.101632 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.117375 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.101632 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.101632 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.127050 -vn -0.838628 -0.000000 0.544704 -v -0.070000 0.098750 0.100813 -vn -0.838628 -0.471729 0.272352 -v -0.070000 0.101250 0.102257 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.101632 -vn -0.838628 0.471729 0.272352 -v -0.070000 0.091000 0.123757 -vn -0.838628 0.000000 0.544704 -v -0.070000 0.093500 0.122313 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.093300 0.121750 -vn -0.770261 0.318866 0.552288 -v -0.070000 0.136550 0.122421 -vn -0.770263 -0.000000 0.637726 -v -0.070000 0.137000 0.122300 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.121750 -vn -0.770261 0.318866 0.552288 -v -0.070000 0.136550 0.110421 -vn -0.770263 -0.000000 0.637726 -v -0.070000 0.137000 0.110300 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.110200 -vn -0.770256 0.637735 -0.000000 -v -0.070000 0.137600 0.107950 -vn -0.770266 0.552286 0.318857 -v -0.070000 0.137721 0.107500 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.107350 -vn -0.748361 -0.331645 -0.574428 -v -0.070000 0.132200 0.121877 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.121750 -vn -0.748361 -0.508111 -0.426356 -v -0.070000 0.133637 0.120671 -vn -0.692678 0.719703 0.047172 -v -0.070000 0.146000 0.129700 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.127582 -vn -0.737696 -0.088113 -0.669358 -v -0.070000 0.103700 0.127200 -vn -0.565703 -0.649074 -0.508609 -v -0.070000 0.097306 0.127200 -vn -0.735123 -0.672941 0.082124 -v -0.070000 0.097400 0.127580 -vn -0.838628 0.000002 -0.544704 -v -0.070000 0.093500 0.128087 -vn -0.707105 0.353554 -0.612374 -v -0.070000 0.093300 0.127971 -vn -0.678875 -0.190039 0.709235 -v -0.070000 0.093412 0.139359 -vn -0.764742 -0.070000 0.640523 -v -0.070000 0.096598 0.126705 -vn -0.561187 0.474792 0.677968 -v -0.070000 0.097000 0.126852 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.097000 0.124200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.117375 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.111625 0.117200 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.111625 0.117700 -vn -0.770264 -0.000000 -0.637725 -v -0.070000 0.122750 0.104950 -vn -0.770261 0.318867 -0.552288 -v -0.070000 0.122125 0.104783 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.106818 -vn -0.838628 -0.471728 0.272352 -v -0.070000 0.109250 0.102257 -vn -0.838628 -0.471728 -0.272352 -v -0.070000 0.109250 0.105143 -vn -0.838628 0.000000 -0.544704 -v -0.070000 0.106750 0.106587 -vn -0.838628 0.471729 -0.272352 -v -0.070000 0.104250 0.105143 -vn -0.838628 -0.471727 0.272353 -v -0.070000 0.096000 0.107757 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.096000 0.110200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.096125 0.110200 -vn -0.838628 -0.471728 -0.272352 -v -0.070000 0.096000 0.110643 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.096125 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.093300 0.101632 -vn -0.707106 0.353556 0.612371 -v -0.070000 0.093300 0.106429 -vn -0.838628 0.000002 0.544704 -v -0.070000 0.093500 0.106313 -vn -0.764747 0.232681 0.600850 -v -0.070000 0.096175 0.105961 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.096125 0.101632 -vn -0.764747 0.483921 0.425422 -v -0.070000 0.095824 0.106206 -vn -0.764744 0.625713 0.153784 -v -0.070000 0.095626 0.106585 -vn -0.764748 0.625989 -0.152637 -v -0.070000 0.095626 0.107013 -vn -0.678874 -0.709236 -0.190038 -v -0.070000 0.086341 0.102112 -vn -0.692678 -0.719703 -0.047171 -v -0.070000 0.086000 0.104700 -vn -0.707105 0.353553 0.612374 -v -0.070000 0.092625 0.106818 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.106818 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.107350 -vn -0.707106 0.353552 0.612374 -v -0.070000 0.091704 0.107350 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.117200 -vn -0.838628 0.471729 -0.272352 -v -0.070000 0.091000 0.110643 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.110200 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.091000 0.110200 -vn -0.838628 0.471727 0.272353 -v -0.070000 0.091000 0.107757 -vn -0.770261 0.637728 -0.000000 -v -0.070000 0.121500 0.103700 -vn -0.770262 0.552289 0.318863 -v -0.070000 0.121667 0.103075 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.101632 -vn -0.770262 0.552289 -0.318863 -v -0.070000 0.121667 0.104325 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.106818 -vn -0.770262 -0.552289 0.318863 -v -0.070000 0.123833 0.103075 -vn -0.770261 -0.637728 0.000000 -v -0.070000 0.124000 0.103700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.101632 -vn -0.770262 -0.552289 -0.318863 -v -0.070000 0.123833 0.104325 -vn -0.770261 -0.318867 -0.552288 -v -0.070000 0.123375 0.104783 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.106818 -vn -0.770262 0.318863 0.552289 -v -0.070000 0.122125 0.102617 -vn -0.770261 0.000000 0.637728 -v -0.070000 0.122750 0.102450 -vn -0.770262 -0.318863 0.552289 -v -0.070000 0.123375 0.102617 -vn -0.770261 0.637729 -0.000002 -v -0.070000 0.121500 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.070000 0.121667 0.130075 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.127582 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.127582 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.122050 0.139700 -vn -0.770259 0.318866 -0.552291 -v -0.070000 0.122125 0.131783 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.119500 0.139700 -vn -0.770263 0.552286 -0.318865 -v -0.070000 0.121667 0.131325 -vn -0.770260 0.318866 0.552291 -v -0.070000 0.122125 0.129617 -vn -0.770264 0.000000 0.637725 -v -0.070000 0.122750 0.129450 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.127582 -vn -0.770260 -0.318866 0.552291 -v -0.070000 0.123375 0.129617 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.125900 0.139700 -vn -0.770260 -0.318866 -0.552291 -v -0.070000 0.123375 0.131783 -vn -0.770264 -0.000000 -0.637725 -v -0.070000 0.122750 0.131950 -vn -0.770264 -0.552286 0.318863 -v -0.070000 0.123833 0.130075 -vn -0.770261 -0.637729 -0.000002 -v -0.070000 0.124000 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.070000 0.123833 0.131325 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.111625 0.127000 -vn -0.904534 0.301511 -0.301512 -v -0.070000 0.111000 0.127000 -vn -0.770262 0.552289 0.318862 -v -0.070000 0.107221 0.124750 -vn -0.770263 0.318861 0.552289 -v -0.070000 0.107550 0.124421 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.124200 -vn -0.770259 -0.000000 0.637731 -v -0.070000 0.108000 0.124300 -vn -0.770264 -0.318863 0.552285 -v -0.070000 0.108450 0.124421 -vn -0.770259 -0.552292 0.318865 -v -0.070000 0.108779 0.124750 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.111000 0.124200 -vn -0.770264 -0.637725 0.000001 -v -0.070000 0.108900 0.125200 -vn -0.770261 -0.552288 -0.318866 -v -0.070000 0.108779 0.125650 -vn -0.770261 -0.318866 -0.552288 -v -0.070000 0.108450 0.125979 -vn -0.770263 0.000000 -0.637726 -v -0.070000 0.108000 0.126100 -vn -0.770260 0.318864 -0.552292 -v -0.070000 0.107550 0.125979 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.127050 -vn -0.770264 0.552285 -0.318863 -v -0.070000 0.107221 0.125650 -vn -0.770260 0.637730 0.000001 -v -0.070000 0.107100 0.125200 -vn -0.707106 0.000000 -0.707108 -v -0.070000 0.117375 0.127000 -vn -0.904534 -0.301511 -0.301511 -v -0.070000 0.117500 0.127000 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.124200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.117500 0.124200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.121750 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.117500 0.121750 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.119450 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.117500 0.119450 -vn -0.904534 -0.301511 0.301511 -v -0.070000 0.117500 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.117200 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.117375 0.117700 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.111000 0.119450 -vn -0.904534 0.301511 0.301511 -v -0.070000 0.111000 0.117700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.119450 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.121750 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.111000 0.121750 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.124200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.104000 0.124200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.121750 -vn -0.737697 -0.088113 0.669358 -v -0.070000 0.103700 0.121200 -vn -0.770265 -0.318854 0.552289 -v -0.070000 0.103850 0.121240 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.119450 -vn -0.737697 0.088113 0.669358 -v -0.070000 0.097300 0.121200 -vn -0.770265 0.552289 0.318854 -v -0.070000 0.097040 0.121350 -vn -0.770266 0.318854 0.552289 -v -0.070000 0.097150 0.121240 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.096125 0.119450 -vn -0.770260 -0.552288 0.318870 -v -0.070000 0.103960 0.121350 -vn -0.737702 -0.669350 0.088128 -v -0.070000 0.104000 0.121500 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.104000 0.121750 -vn -0.737697 0.669358 0.088113 -v -0.070000 0.097000 0.121500 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.096125 0.121750 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.097000 0.121750 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.096125 0.124200 -vn -0.764747 0.233779 0.600425 -v -0.070000 0.096173 0.126761 -vn -0.764744 0.625713 -0.153784 -v -0.070000 0.095626 0.127815 -vn -0.764749 0.625987 0.152640 -v -0.070000 0.095626 0.127387 -vn -0.764744 0.484694 0.424544 -v -0.070000 0.095823 0.127007 -vn -0.707107 -0.353552 -0.612373 -v -0.070000 0.095296 0.127050 -vn -0.760382 0.495132 -0.420315 -v -0.070000 0.095824 0.128194 -vn -0.735144 0.339260 -0.586913 -v -0.070000 0.096118 0.128415 -vn -0.692678 -0.047172 0.719703 -v -0.070000 0.096000 0.139700 -vn -0.707107 0.000000 0.707106 -v -0.070000 0.096125 0.139700 -vn -0.838628 -0.000000 0.544705 -v -0.070000 0.098750 0.127813 -vn -0.838628 -0.471728 0.272353 -v -0.070000 0.101250 0.129257 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.127582 -vn -0.838628 0.471728 -0.272353 -v -0.070000 0.096250 0.132143 -vn -0.838628 0.471728 0.272353 -v -0.070000 0.096250 0.129257 -vn -0.739260 0.177494 -0.649608 -v -0.070000 0.096175 0.128439 -vn -0.764746 -0.071180 -0.640389 -v -0.070000 0.096599 0.128494 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.104125 0.139700 -vn -0.838628 -0.471728 -0.272353 -v -0.070000 0.101250 0.132143 -vn -0.838627 -0.000000 -0.544705 -v -0.070000 0.098750 0.133587 -vn -0.764747 -0.358941 -0.535092 -v -0.070000 0.097001 0.128347 -vn -0.764746 -0.565526 -0.308779 -v -0.070000 0.097290 0.128031 -vn -0.737704 -0.669347 -0.088131 -v -0.070000 0.104000 0.126900 -vn -0.770258 -0.552288 -0.318875 -v -0.070000 0.103960 0.127050 -vn -0.770266 -0.318854 -0.552289 -v -0.070000 0.103850 0.127160 -vn -0.737612 -0.669601 -0.086966 -v -0.070000 0.097400 0.127618 -vn -0.678874 -0.367127 -0.635883 -v -0.070000 0.091000 0.096040 -vn -0.678874 -0.519196 -0.519196 -v -0.070000 0.088929 0.097629 -vn -0.678874 -0.635883 -0.367127 -v -0.070000 0.087340 0.099700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.101632 -vn -0.678875 0.709235 -0.190039 -v -0.070000 0.145659 0.102112 -vn -0.678875 0.635883 -0.367126 -v -0.070000 0.144660 0.099700 -vn -0.678874 0.519197 -0.519196 -v -0.070000 0.143071 0.097629 -vn -0.678874 0.367127 -0.635883 -v -0.070000 0.141000 0.096040 -vn -0.678874 0.190038 -0.709236 -v -0.070000 0.138588 0.095041 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.106818 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.106818 -vn -0.692678 0.719703 -0.047172 -v -0.070000 0.146000 0.104700 -vn -0.678875 0.709235 0.190039 -v -0.070000 0.145659 0.132288 -vn -0.678875 0.367126 0.635883 -v -0.070000 0.141000 0.138360 -vn -0.678875 0.190039 0.709235 -v -0.070000 0.138588 0.139359 -vn -0.692678 0.047172 0.719703 -v -0.070000 0.136000 0.139700 -vn -0.678874 0.519197 0.519197 -v -0.070000 0.143071 0.136771 -vn -0.678875 0.635883 0.367126 -v -0.070000 0.144660 0.134700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.127582 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.135500 0.139700 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.127582 -vn -0.692678 -0.719703 0.047171 -v -0.070000 0.086000 0.129700 -vn -0.678874 -0.709236 0.190038 -v -0.070000 0.086341 0.132288 -vn -0.678874 -0.635883 0.367127 -v -0.070000 0.087340 0.134700 -vn -0.678874 -0.519196 0.519197 -v -0.070000 0.088929 0.136771 -vn -0.678875 -0.367126 0.635883 -v -0.070000 0.091000 0.138360 -vn -0.737702 -0.669350 -0.088128 -v -0.070000 0.104000 0.112900 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.110200 -vn -0.737702 0.088128 -0.669350 -v -0.070000 0.097300 0.113200 -vn -0.770259 0.318870 -0.552288 -v -0.070000 0.097150 0.113160 -vn -0.770259 -0.552288 -0.318870 -v -0.070000 0.103960 0.113050 -vn -0.770260 -0.318870 -0.552288 -v -0.070000 0.103850 0.113160 -vn -0.737702 -0.088128 -0.669350 -v -0.070000 0.103700 0.113200 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.097000 0.110200 -vn -0.737697 0.669358 -0.088113 -v -0.070000 0.097000 0.112900 -vn -0.770266 0.552289 -0.318854 -v -0.070000 0.097040 0.113050 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.107350 -vn -0.729849 -0.680317 0.067005 -v -0.070000 0.104000 0.107500 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.104000 0.110200 -vn -0.729848 -0.067005 0.680317 -v -0.070000 0.103700 0.107200 -vn -0.753772 -0.251484 0.607111 -v -0.070000 0.103815 0.107223 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.104125 0.106818 -vn -0.753760 -0.464675 0.464675 -v -0.070000 0.103912 0.107288 -vn -0.753772 -0.607111 0.251484 -v -0.070000 0.103977 0.107385 -vn -0.838628 -0.471729 -0.272352 -v -0.070000 0.101250 0.105143 -vn -0.838628 -0.000000 -0.544704 -v -0.070000 0.098750 0.106587 -vn -0.764746 -0.071180 0.640389 -v -0.070000 0.096599 0.105906 -vn -0.838628 0.471728 -0.272352 -v -0.070000 0.096250 0.105143 -vn -0.764747 -0.358941 0.535092 -v -0.070000 0.097001 0.106053 -vn -0.764746 -0.565526 0.308779 -v -0.070000 0.097290 0.106369 -vn -0.764746 -0.644208 0.012632 -v -0.070000 0.097400 0.106782 -vn -0.566634 -0.643196 0.514999 -v -0.070000 0.097306 0.107200 -vn -0.764745 0.484695 -0.424541 -v -0.070000 0.095823 0.107393 -vn -0.764747 0.233779 -0.600425 -v -0.070000 0.096173 0.107639 -vn -0.764744 -0.070005 -0.640520 -v -0.070000 0.096598 0.107695 -vn -0.561187 0.474787 -0.677972 -v -0.070000 0.097000 0.107548 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.117375 0.107350 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.117375 0.107400 -vn -0.904534 -0.301511 0.301511 -v -0.070000 0.117500 0.107400 -vn -0.707106 0.000000 0.707108 -v -0.070000 0.111625 0.107400 -vn -0.770263 0.318861 0.552289 -v -0.070000 0.107550 0.108421 -vn -0.770259 -0.000000 0.637731 -v -0.070000 0.108000 0.108300 -vn -0.770265 -0.318863 0.552285 -v -0.070000 0.108450 0.108421 -vn -0.770260 -0.552292 0.318864 -v -0.070000 0.108779 0.108750 -vn -0.904534 0.301511 0.301511 -v -0.070000 0.111000 0.107400 -vn -0.707106 0.707107 0.000000 -v -0.070000 0.111000 0.110200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.110200 -vn -0.770263 0.000000 -0.637726 -v -0.070000 0.108000 0.110100 -vn -0.770260 0.318864 -0.552292 -v -0.070000 0.107550 0.109979 -vn -0.770263 -0.637726 -0.000000 -v -0.070000 0.108900 0.109200 -vn -0.770261 -0.552288 -0.318866 -v -0.070000 0.108779 0.109650 -vn -0.770261 -0.318866 -0.552288 -v -0.070000 0.108450 0.109979 -vn -0.770264 0.552285 -0.318863 -v -0.070000 0.107221 0.109650 -vn -0.770259 0.637731 0.000000 -v -0.070000 0.107100 0.109200 -vn -0.770263 0.552289 0.318861 -v -0.070000 0.107221 0.108750 -vn -0.904534 0.301511 -0.301511 -v -0.070000 0.111000 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.119450 -vn -0.748361 0.623291 -0.226859 -v -0.070000 0.124426 0.119047 -vn -0.748360 0.663293 0.000000 -v -0.070000 0.124100 0.117200 -vn -0.748360 -0.115179 -0.653216 -v -0.070000 0.130438 0.122518 -vn -0.748360 0.115179 -0.653216 -v -0.070000 0.128562 0.122518 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.124200 -vn -0.748361 0.331645 -0.574428 -v -0.070000 0.126800 0.121877 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.121750 -vn -0.748360 0.508111 -0.426356 -v -0.070000 0.125363 0.120671 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.124200 -vn -0.748360 -0.623291 0.226860 -v -0.070000 0.134574 0.115353 -vn -0.748361 -0.663291 0.000000 -v -0.070000 0.134900 0.117200 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.117200 -vn -0.748360 -0.623291 -0.226860 -v -0.070000 0.134574 0.119047 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.119450 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.121750 -vn -0.748360 0.508111 0.426356 -v -0.070000 0.125363 0.113729 -vn -0.748360 0.331647 0.574428 -v -0.070000 0.126800 0.112523 -vn -0.748361 -0.115180 0.653215 -v -0.070000 0.130438 0.111882 -vn -0.748360 -0.331647 0.574428 -v -0.070000 0.132200 0.112523 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.133250 0.110200 -vn -0.748361 0.115180 0.653215 -v -0.070000 0.128562 0.111882 -vn -0.748361 0.623291 0.226859 -v -0.070000 0.124426 0.115353 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.117200 -vn -0.770261 -0.552288 -0.318866 -v -0.070000 0.139279 0.108400 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.110200 -vn -0.770263 -0.637726 -0.000000 -v -0.070000 0.139400 0.107950 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.107350 -vn -0.770260 -0.552292 0.318864 -v -0.070000 0.139279 0.107500 -vn -0.770261 -0.318866 -0.552288 -v -0.070000 0.138950 0.108729 -vn -0.770263 0.000000 -0.637726 -v -0.070000 0.138500 0.108850 -vn -0.770258 0.318862 -0.552295 -v -0.070000 0.138050 0.108729 -vn -0.770268 0.552283 -0.318860 -v -0.070000 0.137721 0.108400 -vn -0.770264 -0.318863 0.552286 -v -0.070000 0.138950 0.107171 -vn -0.770259 -0.000000 0.637731 -v -0.070000 0.138500 0.107050 -vn -0.770262 0.318858 0.552292 -v -0.070000 0.138050 0.107171 -vn -0.770264 0.318863 -0.552285 -v -0.070000 0.136550 0.111979 -vn -0.770259 0.552292 -0.318864 -v -0.070000 0.136221 0.111650 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.110200 -vn -0.770263 0.637726 0.000000 -v -0.070000 0.136100 0.111200 -vn -0.770261 0.552288 0.318866 -v -0.070000 0.136221 0.110750 -vn -0.748361 -0.508111 0.426356 -v -0.070000 0.133637 0.113729 -vn -0.770258 -0.318862 0.552295 -v -0.070000 0.137450 0.110421 -vn -0.770268 -0.552283 0.318860 -v -0.070000 0.137779 0.110750 -vn -0.770256 -0.637735 0.000000 -v -0.070000 0.137900 0.111200 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.117200 -vn -0.770266 -0.552286 -0.318857 -v -0.070000 0.137779 0.111650 -vn -0.770262 -0.318858 -0.552292 -v -0.070000 0.137450 0.111979 -vn -0.770261 0.318866 -0.552288 -v -0.070000 0.136550 0.123979 -vn -0.770261 0.552288 -0.318866 -v -0.070000 0.136221 0.123650 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.124200 -vn -0.770263 0.637726 0.000000 -v -0.070000 0.136100 0.123200 -vn -0.770261 0.552288 0.318866 -v -0.070000 0.136221 0.122750 -vn -0.770263 0.000000 -0.637726 -v -0.070000 0.137000 0.124100 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.124200 -vn -0.770258 -0.318862 -0.552295 -v -0.070000 0.137450 0.123979 -vn -0.707107 0.707106 0.000000 -v -0.070000 0.146000 0.124200 -vn -0.770268 -0.552283 -0.318860 -v -0.070000 0.137779 0.123650 -vn -0.770258 -0.318862 0.552295 -v -0.070000 0.137450 0.122421 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.121750 -vn -0.770268 -0.552283 0.318860 -v -0.070000 0.137779 0.122750 -vn -0.770256 -0.637735 0.000000 -v -0.070000 0.137900 0.123200 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.127050 -vn -0.770261 -0.552288 0.318866 -v -0.070000 0.139279 0.126000 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.127050 -vn -0.770256 0.637735 -0.000000 -v -0.070000 0.137600 0.126450 -vn -0.770268 0.552283 0.318860 -v -0.070000 0.137721 0.126000 -vn -0.770258 0.318862 0.552295 -v -0.070000 0.138050 0.125671 -vn -0.770263 -0.000000 0.637726 -v -0.070000 0.138500 0.125550 -vn -0.770261 -0.318866 0.552288 -v -0.070000 0.138950 0.125671 -vn -0.770263 -0.637726 -0.000000 -v -0.070000 0.139400 0.126450 -vn -0.770261 -0.552288 -0.318866 -v -0.070000 0.139279 0.126900 -vn -0.770261 -0.318866 -0.552288 -v -0.070000 0.138950 0.127229 -vn -0.770263 0.000000 -0.637726 -v -0.070000 0.138500 0.127350 -vn -0.770258 0.318862 -0.552295 -v -0.070000 0.138050 0.127229 -vn -0.770268 0.552283 -0.318860 -v -0.070000 0.137721 0.126900 -vn -0.838628 0.000000 -0.544704 -v -0.070000 0.114750 0.106587 -vn -0.838628 0.471729 -0.272352 -v -0.070000 0.112250 0.105143 -vn -0.838628 0.000000 0.544705 -v -0.070000 0.114750 0.100813 -vn -0.838628 -0.471728 0.272352 -v -0.070000 0.117250 0.102257 -vn -0.838628 -0.471728 -0.272352 -v -0.070000 0.117250 0.105143 -vn -0.838628 0.471728 0.272353 -v -0.070000 0.104250 0.129257 -vn -0.838627 0.000000 0.544705 -v -0.070000 0.106750 0.127813 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.105675 0.127582 -vn -0.838628 -0.471727 0.272353 -v -0.070000 0.109250 0.129257 -vn -0.838628 -0.471728 -0.272353 -v -0.070000 0.109250 0.132143 -vn -0.838628 0.471728 -0.272353 -v -0.070000 0.104250 0.132143 -vn -0.838627 0.000000 -0.544705 -v -0.070000 0.106750 0.133587 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.105675 0.139700 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.111625 0.139700 -vn -0.838628 -0.471727 -0.272353 -v -0.070000 0.096000 0.126643 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.096000 0.124200 -vn -0.838628 -0.471728 0.272352 -v -0.070000 0.096000 0.123757 -vn -0.707108 0.353553 -0.612371 -v -0.070000 0.092625 0.127582 -vn -0.707106 0.353553 -0.612373 -v -0.070000 0.091704 0.127050 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.127050 -vn -0.838628 0.471727 -0.272353 -v -0.070000 0.091000 0.126643 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.124200 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.091000 0.124200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.121750 -vn -0.838628 0.471728 0.272352 -v -0.070000 0.096250 0.102257 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.111625 0.101632 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.111625 0.094700 -vn -0.838628 0.000000 0.544704 -v -0.070000 0.106750 0.100813 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.105675 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.104125 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.096125 0.094700 -vn -0.692678 -0.047171 -0.719703 -v -0.070000 0.096000 0.094700 -vn -0.678874 -0.190038 -0.709236 -v -0.070000 0.093412 0.095041 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.133250 0.139700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.125900 0.127050 -vn -0.838628 0.471729 0.272352 -v -0.070000 0.112250 0.102257 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.117375 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.119500 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.122050 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.125900 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.133250 0.094700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.135500 0.094700 -vn -0.692678 0.047171 -0.719703 -v -0.070000 0.136000 0.094700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.106818 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.119500 0.110200 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.117500 0.110200 -vn -0.904534 -0.301511 -0.301511 -v -0.070000 0.117500 0.116700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.117375 0.116700 -vn -0.707107 0.000000 -0.707107 -v -0.070000 0.111625 0.116700 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.111625 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.107350 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.107350 -vn -0.770260 0.552292 0.318864 -v -0.070000 0.122721 0.108750 -vn -0.770264 0.318863 0.552285 -v -0.070000 0.123050 0.108421 -vn -0.770259 -0.000000 0.637731 -v -0.070000 0.123500 0.108300 -vn -0.770263 -0.318861 0.552289 -v -0.070000 0.123950 0.108421 -vn -0.770263 -0.552289 0.318861 -v -0.070000 0.124279 0.108750 -vn -0.770259 -0.637731 -0.000000 -v -0.070000 0.124400 0.109200 -vn -0.770264 -0.552285 -0.318863 -v -0.070000 0.124279 0.109650 -vn -0.770259 -0.318864 -0.552292 -v -0.070000 0.123950 0.109979 -vn -0.770263 0.000000 -0.637726 -v -0.070000 0.123500 0.110100 -vn -0.770261 0.318866 -0.552288 -v -0.070000 0.123050 0.109979 -vn -0.707107 0.707107 0.000000 -v -0.070000 0.146000 0.119450 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.119450 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.136850 0.117200 -vn -0.770259 0.000000 -0.637731 -v -0.070000 0.137000 0.112100 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.093300 0.119450 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.093300 0.117200 -vn -0.838628 0.000000 -0.544705 -v -0.070000 0.093500 0.112087 -vn -0.707107 -0.707107 0.000000 -v -0.070000 0.086000 0.119450 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.121750 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.124200 -vn -0.770264 0.318863 0.552285 -v -0.070000 0.123050 0.124421 -vn -0.770259 -0.000000 0.637731 -v -0.070000 0.123500 0.124300 -vn -0.770262 -0.552289 0.318862 -v -0.070000 0.124279 0.124750 -vn -0.770260 -0.637730 0.000001 -v -0.070000 0.124400 0.125200 -vn -0.770263 -0.318861 0.552289 -v -0.070000 0.123950 0.124421 -vn -0.770261 0.318866 -0.552288 -v -0.070000 0.123050 0.125979 -vn -0.770261 0.552288 -0.318866 -v -0.070000 0.122721 0.125650 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.122050 0.127050 -vn -0.770264 0.637725 0.000001 -v -0.070000 0.122600 0.125200 -vn -0.770259 0.552292 0.318865 -v -0.070000 0.122721 0.124750 -vn -0.770264 -0.552285 -0.318863 -v -0.070000 0.124279 0.125650 -vn -0.770259 -0.318864 -0.552292 -v -0.070000 0.123950 0.125979 -vn -0.770263 0.000000 -0.637726 -v -0.070000 0.123500 0.126100 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.135500 0.127050 -vn -1.000000 0.000000 0.000000 -v -0.070000 0.117375 0.127582 -vn -0.838628 0.471729 0.272352 -v -0.070000 0.104250 0.102257 -vn -0.707107 0.000000 0.707107 -v -0.070000 0.117375 0.139700 -vn -0.838628 0.000000 0.544705 -v -0.070000 0.114750 0.127813 -vn -0.838628 -0.471727 0.272353 -v -0.070000 0.117250 0.129257 -vn -0.838628 -0.471728 -0.272353 -v -0.070000 0.117250 0.132143 -vn -0.838627 0.000000 -0.544705 -v -0.070000 0.114750 0.133587 -vn -0.838628 0.471728 -0.272353 -v -0.070000 0.112250 0.132143 -vn -0.838628 0.471728 0.272353 -v -0.070000 0.112250 0.129257 -vn 0.770256 -0.637735 -0.000000 -v -0.067000 0.137900 0.111200 -vn 0.770266 -0.552286 -0.318857 -v -0.067000 0.137779 0.111650 -vn 0.770262 -0.318858 -0.552292 -v -0.067000 0.137450 0.111979 -vn 0.770259 -0.000000 -0.637731 -v -0.067000 0.137000 0.112100 -vn 0.770264 0.318863 -0.552285 -v -0.067000 0.136550 0.111979 -vn 0.770260 0.552292 -0.318864 -v -0.067000 0.136221 0.111650 -vn 0.770263 0.637726 -0.000000 -v -0.067000 0.136100 0.111200 -vn 0.770261 0.552288 0.318866 -v -0.067000 0.136221 0.110750 -vn 0.770261 0.318866 0.552288 -v -0.067000 0.136550 0.110421 -vn 0.770263 0.000000 0.637726 -v -0.067000 0.137000 0.110300 -vn 0.770258 -0.318862 0.552295 -v -0.067000 0.137450 0.110421 -vn 0.770268 -0.552283 0.318860 -v -0.067000 0.137779 0.110750 -vn 0.770259 -0.637731 0.000000 -v -0.067000 0.124400 0.109200 -vn 0.770264 -0.552285 -0.318863 -v -0.067000 0.124279 0.109650 -vn 0.770260 -0.318864 -0.552292 -v -0.067000 0.123950 0.109979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 0.123500 0.110100 -vn 0.770261 0.318866 -0.552288 -v -0.067000 0.123050 0.109979 -vn 0.770261 0.552288 -0.318866 -v -0.067000 0.122721 0.109650 -vn 0.770263 0.637726 -0.000000 -v -0.067000 0.122600 0.109200 -vn 0.770259 0.552292 0.318864 -v -0.067000 0.122721 0.108750 -vn 0.770265 0.318863 0.552285 -v -0.067000 0.123050 0.108421 -vn 0.770259 0.000000 0.637731 -v -0.067000 0.123500 0.108300 -vn 0.770263 -0.318861 0.552289 -v -0.067000 0.123950 0.108421 -vn 0.770263 -0.552289 0.318861 -v -0.067000 0.124279 0.108750 -vn 0.770263 -0.637726 0.000000 -v -0.067000 0.108900 0.109200 -vn 0.770261 -0.552288 -0.318866 -v -0.067000 0.108779 0.109650 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 0.108450 0.109979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 0.108000 0.110100 -vn 0.770260 0.318864 -0.552292 -v -0.067000 0.107550 0.109979 -vn 0.770264 0.552285 -0.318863 -v -0.067000 0.107221 0.109650 -vn 0.770259 0.637731 -0.000000 -v -0.067000 0.107100 0.109200 -vn 0.770263 0.552289 0.318861 -v -0.067000 0.107221 0.108750 -vn 0.770263 0.318861 0.552289 -v -0.067000 0.107550 0.108421 -vn 0.770259 0.000000 0.637731 -v -0.067000 0.108000 0.108300 -vn 0.770264 -0.318863 0.552285 -v -0.067000 0.108450 0.108421 -vn 0.770260 -0.552292 0.318864 -v -0.067000 0.108779 0.108750 -vn 0.770256 -0.637735 -0.000000 -v -0.067000 0.137900 0.123200 -vn 0.770268 -0.552283 -0.318860 -v -0.067000 0.137779 0.123650 -vn 0.770258 -0.318862 -0.552295 -v -0.067000 0.137450 0.123979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 0.137000 0.124100 -vn 0.770261 0.318866 -0.552288 -v -0.067000 0.136550 0.123979 -vn 0.770261 0.552288 -0.318866 -v -0.067000 0.136221 0.123650 -vn 0.770263 0.637726 -0.000000 -v -0.067000 0.136100 0.123200 -vn 0.770261 0.552288 0.318866 -v -0.067000 0.136221 0.122750 -vn 0.770261 0.318866 0.552288 -v -0.067000 0.136550 0.122421 -vn 0.770263 0.000000 0.637726 -v -0.067000 0.137000 0.122300 -vn 0.770258 -0.318862 0.552295 -v -0.067000 0.137450 0.122421 -vn 0.770268 -0.552283 0.318860 -v -0.067000 0.137779 0.122750 -vn 0.770264 -0.637725 0.000001 -v -0.067000 0.108900 0.125200 -vn 0.770261 -0.552288 -0.318866 -v -0.067000 0.108779 0.125650 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 0.108450 0.125979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 0.108000 0.126100 -vn 0.770260 0.318864 -0.552292 -v -0.067000 0.107550 0.125979 -vn 0.770265 0.552285 -0.318863 -v -0.067000 0.107221 0.125650 -vn 0.770260 0.637730 0.000001 -v -0.067000 0.107100 0.125200 -vn 0.770262 0.552289 0.318862 -v -0.067000 0.107221 0.124750 -vn 0.770263 0.318861 0.552289 -v -0.067000 0.107550 0.124421 -vn 0.770259 0.000000 0.637731 -v -0.067000 0.108000 0.124300 -vn 0.770264 -0.318863 0.552285 -v -0.067000 0.108450 0.124421 -vn 0.770259 -0.552292 0.318865 -v -0.067000 0.108779 0.124750 -vn 0.770260 -0.637730 0.000001 -v -0.067000 0.124400 0.125200 -vn 0.770264 -0.552285 -0.318863 -v -0.067000 0.124279 0.125650 -vn 0.770260 -0.318864 -0.552292 -v -0.067000 0.123950 0.125979 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 0.123500 0.126100 -vn 0.770261 0.318866 -0.552288 -v -0.067000 0.123050 0.125979 -vn 0.770261 0.552288 -0.318866 -v -0.067000 0.122721 0.125650 -vn 0.770264 0.637725 0.000001 -v -0.067000 0.122600 0.125200 -vn 0.770259 0.552292 0.318865 -v -0.067000 0.122721 0.124750 -vn 0.770264 0.318863 0.552285 -v -0.067000 0.123050 0.124421 -vn 0.770259 0.000000 0.637731 -v -0.067000 0.123500 0.124300 -vn 0.770263 -0.318861 0.552289 -v -0.067000 0.123950 0.124421 -vn 0.770262 -0.552289 0.318862 -v -0.067000 0.124279 0.124750 -vn 0.692678 0.719703 -0.047172 -v -0.062000 0.146000 0.104700 -vn 0.692678 0.719703 0.047173 -v -0.062000 0.146000 0.129700 -vn 0.692677 0.047172 0.719703 -v -0.062000 0.136000 0.139700 -vn 0.692678 -0.047172 0.719703 -v -0.062000 0.096000 0.139700 -vn 0.692678 -0.719703 0.047171 -v -0.062000 0.086000 0.129700 -vn 0.692678 -0.719703 -0.047171 -v -0.062000 0.086000 0.104700 -vn 0.692679 -0.047171 -0.719702 -v -0.062000 0.096000 0.094700 -vn 0.692679 0.047171 -0.719702 -v -0.062000 0.136000 0.094700 -vn 0.904534 0.301511 0.301511 -v -0.062000 0.093500 0.100200 -vn 0.577350 0.577350 0.577350 -v -0.062000 0.093500 0.100700 -vn 0.904534 0.301511 0.301511 -v -0.062000 0.092000 0.100700 -vn 0.904534 -0.301511 -0.301511 -v -0.062000 0.128000 0.134200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.093500 0.134200 -vn 0.678875 -0.190039 0.709235 -v -0.062000 0.093412 0.139359 -vn 0.678875 -0.367126 0.635883 -v -0.062000 0.091000 0.138360 -vn 0.678874 -0.519196 0.519197 -v -0.062000 0.088929 0.136771 -vn 0.904534 -0.301511 0.301512 -v -0.062000 0.128000 0.100200 -vn 0.678874 -0.190038 -0.709236 -v -0.062000 0.093412 0.095041 -vn 0.904534 0.301511 0.301511 -v -0.062000 0.090500 0.102200 -vn 0.678874 -0.635883 -0.367127 -v -0.062000 0.087340 0.099700 -vn 0.678874 -0.519196 -0.519196 -v -0.062000 0.088929 0.097629 -vn 0.742117 -0.540534 -0.396340 -v -0.062000 0.141663 0.129314 -vn 0.741871 -0.638647 -0.204347 -v -0.062000 0.142657 0.127363 -vn 0.725201 -0.686415 -0.054023 -v -0.062000 0.143000 0.125200 -vn 0.577350 0.577350 0.577350 -v -0.062000 0.092000 0.102200 -vn 0.678874 -0.367127 -0.635883 -v -0.062000 0.091000 0.096040 -vn 0.577350 0.577350 0.577350 -v -0.062000 0.090500 0.103950 -vn 0.904534 0.301511 0.301511 -v -0.062000 0.090000 0.103950 -vn 0.678874 -0.709236 -0.190038 -v -0.062000 0.086341 0.102112 -vn 0.678875 0.709235 0.190039 -v -0.062000 0.145659 0.132288 -vn 0.678875 0.635883 0.367126 -v -0.062000 0.144660 0.134700 -vn 0.744071 -0.392700 -0.540505 -v -0.062000 0.140114 0.130863 -vn 0.678874 0.519197 0.519197 -v -0.062000 0.143071 0.136771 -vn 0.744071 -0.206455 -0.635401 -v -0.062000 0.138163 0.131857 -vn 0.725200 -0.686415 0.054023 -v -0.062000 0.143000 0.109200 -vn 0.744071 -0.635401 0.206455 -v -0.062000 0.142657 0.107037 -vn 0.678875 0.709235 -0.190039 -v -0.062000 0.145659 0.102112 -vn 0.744071 -0.540505 0.392700 -v -0.062000 0.141663 0.105085 -vn 0.678875 0.635883 -0.367126 -v -0.062000 0.144660 0.099700 -vn 0.744071 -0.392700 0.540505 -v -0.062000 0.140114 0.103537 -vn 0.678874 0.519197 -0.519196 -v -0.062000 0.143071 0.097629 -vn 0.577350 -0.577350 -0.577350 -v -0.062000 0.128000 0.133700 -vn 0.845339 -0.278878 -0.455662 -v -0.062000 0.129500 0.133700 -vn 0.661188 -0.577625 -0.478728 -v -0.062000 0.129897 0.132924 -vn 0.678874 0.367127 -0.635883 -v -0.062000 0.141000 0.096040 -vn 0.744072 -0.206454 0.635401 -v -0.062000 0.138163 0.102543 -vn 0.678874 0.190038 -0.709236 -v -0.062000 0.138588 0.095041 -vn 0.725200 -0.054021 0.686416 -v -0.062000 0.136000 0.102200 -vn 0.683245 -0.080046 0.725788 -v -0.062000 0.131436 0.102200 -vn 0.661189 -0.319122 0.678963 -v -0.062000 0.130586 0.102010 -vn 0.577350 0.577350 -0.577350 -v -0.062000 0.090500 0.114450 -vn 0.577350 0.577350 0.577350 -v -0.062000 0.090500 0.119950 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.090000 0.114450 -vn 0.904534 0.301511 0.301511 -v -0.062000 0.090000 0.119950 -vn 0.678875 0.367126 0.635883 -v -0.062000 0.141000 0.138360 -vn 0.678875 0.190039 0.709235 -v -0.062000 0.138588 0.139359 -vn 0.725201 -0.054022 -0.686415 -v -0.062000 0.136000 0.132200 -vn 0.683246 -0.080043 -0.725788 -v -0.062000 0.131436 0.132200 -vn 0.661187 -0.319122 -0.678964 -v -0.062000 0.130586 0.132390 -vn 0.577350 -0.577350 0.577350 -v -0.062000 0.128000 0.100700 -vn 0.845340 -0.278879 0.455661 -v -0.062000 0.129500 0.100700 -vn 0.661187 -0.577625 0.478729 -v -0.062000 0.129897 0.101476 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.090500 0.132200 -vn 0.577350 0.577350 -0.577350 -v -0.062000 0.092000 0.132200 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.092000 0.133700 -vn 0.678874 -0.709236 0.190038 -v -0.062000 0.086341 0.132288 -vn 0.904534 0.301511 -0.301511 -v -0.062000 0.090000 0.130450 -vn 0.678874 -0.635883 0.367127 -v -0.062000 0.087340 0.134700 -vn 0.577350 0.577350 -0.577350 -v -0.062000 0.093500 0.133700 -vn 0.577350 0.577350 -0.577350 -v -0.062000 0.090500 0.130450 -vn 0.737697 0.669358 0.088113 -v -0.067000 0.097000 0.121500 -vn 0.770266 0.552289 0.318854 -v -0.067000 0.097040 0.121350 -vn 0.770265 0.318854 0.552289 -v -0.067000 0.097150 0.121240 -vn 0.737697 0.088113 0.669358 -v -0.067000 0.097300 0.121200 -vn 0.737697 -0.088113 0.669358 -v -0.067000 0.103700 0.121200 -vn 0.770266 -0.318854 0.552289 -v -0.067000 0.103850 0.121240 -vn 0.770259 -0.552288 0.318870 -v -0.067000 0.103960 0.121350 -vn 0.737702 -0.669350 0.088128 -v -0.067000 0.104000 0.121500 -vn 0.737704 -0.669347 -0.088131 -v -0.067000 0.104000 0.126900 -vn 0.770258 -0.552288 -0.318874 -v -0.067000 0.103960 0.127050 -vn 0.770265 -0.318854 -0.552289 -v -0.067000 0.103850 0.127160 -vn 0.737697 -0.088113 -0.669358 -v -0.067000 0.103700 0.127200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.104000 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.104000 0.123275 -vn 0.565925 -0.644022 -0.514748 -v -0.067000 0.097306 0.127200 -vn 0.561187 0.474792 0.677968 -v -0.067000 0.097000 0.126852 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.097000 0.124200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.097000 0.123275 -vn 0.748361 -0.663291 0.000000 -v -0.067000 0.134900 0.117200 -vn 0.748360 -0.623291 -0.226860 -v -0.067000 0.134574 0.119047 -vn 0.748361 -0.508111 -0.426356 -v -0.067000 0.133637 0.120671 -vn 0.748361 -0.331645 -0.574428 -v -0.067000 0.132200 0.121877 -vn 0.748360 -0.115179 -0.653216 -v -0.067000 0.130438 0.122518 -vn 0.748360 0.115179 -0.653216 -v -0.067000 0.128562 0.122518 -vn 0.748361 0.331645 -0.574428 -v -0.067000 0.126800 0.121877 -vn 0.748360 0.508111 -0.426356 -v -0.067000 0.125363 0.120671 -vn 0.748361 0.623291 -0.226859 -v -0.067000 0.124426 0.119047 -vn 0.748360 0.663293 0.000000 -v -0.067000 0.124100 0.117200 -vn 0.748361 0.623291 0.226859 -v -0.067000 0.124426 0.115353 -vn 0.748360 0.508111 0.426356 -v -0.067000 0.125363 0.113729 -vn 0.748360 0.331647 0.574428 -v -0.067000 0.126800 0.112523 -vn 0.748361 0.115180 0.653215 -v -0.067000 0.128562 0.111882 -vn 0.748361 -0.115180 0.653215 -v -0.067000 0.130438 0.111882 -vn 0.748360 -0.331647 0.574428 -v -0.067000 0.132200 0.112523 -vn 0.748360 -0.508111 0.426356 -v -0.067000 0.133637 0.113729 -vn 0.748360 -0.623291 0.226860 -v -0.067000 0.134574 0.115353 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.107225 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.107225 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.128975 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.128975 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.106475 -vn 0.673533 -0.228412 -0.702980 -v -0.067000 0.138163 0.131857 -vn 0.689866 -0.056800 -0.721705 -v -0.067000 0.136000 0.132200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.128975 -vn 0.904534 0.301511 -0.301511 -v -0.067000 0.090500 0.130450 -vn 0.577350 0.577350 -0.577350 -v -0.067000 0.090000 0.130450 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.128975 -vn 0.904534 0.301511 0.301511 -v -0.067000 0.093500 0.100700 -vn 0.577350 0.577350 0.577350 -v -0.067000 0.093500 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.095175 0.100200 -vn 0.942505 0.074364 0.325813 -v -0.067000 0.128777 0.102031 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.102200 -vn 0.904534 -0.301511 0.301511 -v -0.067000 0.128000 0.100700 -vn 0.606340 -0.415114 0.678257 -v -0.067000 0.129500 0.100700 -vn 0.759605 -0.500757 0.415022 -v -0.067000 0.129897 0.101476 -vn 0.942505 -0.074365 0.325812 -v -0.067000 0.130223 0.102031 -vn 0.577350 0.577350 0.577350 -v -0.067000 0.090000 0.103950 -vn 0.904534 0.301511 0.301511 -v -0.067000 0.090500 0.103950 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.106475 -vn 0.577350 0.577350 0.577350 -v -0.067000 0.090500 0.102200 -vn 0.904534 0.301511 0.301511 -v -0.067000 0.092000 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.102200 -vn 0.577350 0.577350 0.577350 -v -0.067000 0.092000 0.100700 -vn 0.577350 0.577350 -0.577350 -v -0.067000 0.090000 0.114450 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.111125 -vn 0.904534 0.301511 -0.301511 -v -0.067000 0.090500 0.114450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.111125 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.117200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090500 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.119450 -vn 0.904534 0.301511 0.301511 -v -0.067000 0.090500 0.119950 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.123275 -vn 0.577350 0.577350 0.577350 -v -0.067000 0.090000 0.119950 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.123275 -vn 0.577350 0.577350 -0.577350 -v -0.067000 0.093500 0.134200 -vn 0.904534 0.301511 -0.301511 -v -0.067000 0.093500 0.133700 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.128975 -vn 0.577350 0.577350 -0.577350 -v -0.067000 0.092000 0.133700 -vn 0.904534 0.301511 -0.301511 -v -0.067000 0.092000 0.132200 -vn 0.577350 0.577350 -0.577350 -v -0.067000 0.090500 0.132200 -vn 0.577350 -0.577350 -0.577350 -v -0.067000 0.128000 0.134200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.125325 0.134200 -vn 0.904534 -0.301511 -0.301511 -v -0.067000 0.128000 0.133700 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.128975 -vn 0.942506 0.074364 -0.325812 -v -0.067000 0.128777 0.132369 -vn 0.942506 -0.074365 -0.325810 -v -0.067000 0.130223 0.132369 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.127925 -vn 0.942505 0.334192 0.000000 -v -0.067000 0.126250 0.129200 -vn 0.942505 0.301096 -0.145000 -v -0.067000 0.126572 0.130610 -vn 0.942506 0.208365 -0.261280 -v -0.067000 0.127474 0.131741 -vn 0.606340 -0.415113 -0.678257 -v -0.067000 0.129500 0.133700 -vn 0.759604 -0.500759 -0.415022 -v -0.067000 0.129897 0.132924 -vn 0.759605 -0.276655 -0.588611 -v -0.067000 0.130586 0.132390 -vn 0.942505 -0.208365 -0.261283 -v -0.067000 0.131526 0.131741 -vn 0.732633 -0.074610 -0.676522 -v -0.067000 0.131436 0.132200 -vn 0.770258 0.318862 0.552295 -v -0.067000 0.138050 0.125671 -vn 0.770268 0.552283 0.318860 -v -0.067000 0.137721 0.126000 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.124200 -vn 0.770256 0.637735 0.000000 -v -0.067000 0.137600 0.126450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.127925 -vn 0.770268 0.552283 -0.318860 -v -0.067000 0.137721 0.126900 -vn 0.770258 0.318862 -0.552295 -v -0.067000 0.138050 0.127229 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 0.138500 0.127350 -vn 0.689140 -0.656176 -0.307438 -v -0.067000 0.142434 0.127957 -vn 0.678152 -0.584619 -0.445343 -v -0.067000 0.141663 0.129314 -vn 0.673534 -0.434466 -0.597990 -v -0.067000 0.140114 0.130863 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 0.138950 0.127229 -vn 0.770261 -0.552288 -0.318866 -v -0.067000 0.139279 0.126900 -vn 0.685057 -0.704324 -0.186079 -v -0.067000 0.142657 0.127363 -vn 0.770263 -0.637726 0.000000 -v -0.067000 0.139400 0.126450 -vn 0.689866 -0.721705 -0.056800 -v -0.067000 0.143000 0.125200 -vn 0.770261 -0.552288 0.318866 -v -0.067000 0.139279 0.126000 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.143000 0.124200 -vn 0.770261 -0.318866 0.552288 -v -0.067000 0.138950 0.125671 -vn 0.770263 0.000000 0.637726 -v -0.067000 0.138500 0.125550 -vn 0.673534 -0.702979 0.228413 -v -0.067000 0.142657 0.107037 -vn 0.770263 -0.637726 0.000000 -v -0.067000 0.139400 0.107950 -vn 0.770260 -0.552292 0.318864 -v -0.067000 0.139279 0.107500 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.107225 -vn 0.770256 0.637735 0.000000 -v -0.067000 0.137600 0.107950 -vn 0.770268 0.552283 -0.318860 -v -0.067000 0.137721 0.108400 -vn 0.770258 0.318862 -0.552295 -v -0.067000 0.138050 0.108729 -vn 0.770263 -0.000000 -0.637726 -v -0.067000 0.138500 0.108850 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.143000 0.110200 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 0.138950 0.108729 -vn 0.770261 -0.552288 -0.318866 -v -0.067000 0.139279 0.108400 -vn 0.689866 -0.721705 0.056800 -v -0.067000 0.143000 0.109200 -vn 0.770264 -0.318863 0.552285 -v -0.067000 0.138950 0.107171 -vn 0.770259 0.000000 0.637731 -v -0.067000 0.138500 0.107050 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.106475 -vn 0.770262 0.318858 0.552292 -v -0.067000 0.138050 0.107171 -vn 0.770266 0.552286 0.318857 -v -0.067000 0.137721 0.107500 -vn 0.689867 -0.056798 0.721705 -v -0.067000 0.136000 0.102200 -vn 0.673533 -0.228411 0.702980 -v -0.067000 0.138163 0.102543 -vn 0.673533 -0.434466 0.597990 -v -0.067000 0.140114 0.103537 -vn 0.673533 -0.597990 0.434466 -v -0.067000 0.141663 0.105085 -vn 0.770262 0.552289 -0.318863 -v -0.067000 0.121667 0.104325 -vn 0.770261 0.318867 -0.552288 -v -0.067000 0.122125 0.104783 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.106475 -vn 0.770264 0.000000 -0.637725 -v -0.067000 0.122750 0.104950 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.106475 -vn 0.770261 -0.318867 -0.552288 -v -0.067000 0.123375 0.104783 -vn 0.770262 -0.552289 -0.318863 -v -0.067000 0.123833 0.104325 -vn 0.770261 -0.637728 -0.000000 -v -0.067000 0.124000 0.103700 -vn 0.770262 -0.552289 0.318863 -v -0.067000 0.123833 0.103075 -vn 0.770262 -0.318863 0.552289 -v -0.067000 0.123375 0.102617 -vn 0.770261 -0.000000 0.637728 -v -0.067000 0.122750 0.102450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.102200 -vn 0.770262 0.318863 0.552289 -v -0.067000 0.122125 0.102617 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.102200 -vn 0.770262 0.552289 0.318863 -v -0.067000 0.121667 0.103075 -vn 0.770261 0.637728 0.000000 -v -0.067000 0.121500 0.103700 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.102200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.107225 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.107225 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.110200 -vn 0.770264 -0.637725 0.000000 -v -0.067000 0.094750 0.125200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.095175 0.127925 -vn 0.770261 0.318867 -0.552288 -v -0.067000 0.092875 0.126283 -vn 0.770264 0.000001 -0.637726 -v -0.067000 0.093500 0.126450 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 0.094125 0.126283 -vn 0.770261 -0.552288 -0.318867 -v -0.067000 0.094583 0.125825 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.124200 -vn 0.770264 0.637725 0.000000 -v -0.067000 0.092250 0.125200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.127925 -vn 0.770261 0.552288 -0.318867 -v -0.067000 0.092417 0.125825 -vn 0.770261 -0.552288 0.318867 -v -0.067000 0.094583 0.124575 -vn 0.770261 -0.318866 0.552288 -v -0.067000 0.094125 0.124117 -vn 0.770264 0.000001 0.637725 -v -0.067000 0.093500 0.123950 -vn 0.770261 0.318867 0.552288 -v -0.067000 0.092875 0.124117 -vn 0.770261 0.552288 0.318867 -v -0.067000 0.092417 0.124575 -vn 0.770261 -0.552288 -0.318867 -v -0.067000 0.107833 0.131325 -vn 0.770263 -0.637726 -0.000002 -v -0.067000 0.108000 0.130700 -vn 0.770261 -0.552288 0.318865 -v -0.067000 0.107833 0.130075 -vn 0.770261 -0.318866 -0.552288 -v -0.067000 0.107375 0.131783 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.112250 0.134200 -vn 0.770264 0.000001 -0.637726 -v -0.067000 0.106750 0.131950 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.106300 0.134200 -vn 0.770261 0.318867 -0.552288 -v -0.067000 0.106125 0.131783 -vn 0.770261 -0.318866 0.552288 -v -0.067000 0.107375 0.129617 -vn 0.770264 0.000001 0.637725 -v -0.067000 0.106750 0.129450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.128975 -vn 0.770261 0.552288 0.318865 -v -0.067000 0.105667 0.130075 -vn 0.770263 0.637726 -0.000002 -v -0.067000 0.105500 0.130700 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.128975 -vn 0.770261 0.318867 0.552288 -v -0.067000 0.106125 0.129617 -vn 0.770261 0.552288 -0.318867 -v -0.067000 0.105667 0.131325 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.104750 0.134200 -vn 0.770260 -0.318866 0.552291 -v -0.067000 0.123375 0.129617 -vn 0.770264 -0.000000 0.637725 -v -0.067000 0.122750 0.129450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.128975 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.122050 0.134200 -vn 0.770264 0.000000 -0.637725 -v -0.067000 0.122750 0.131950 -vn 0.770260 -0.318866 -0.552291 -v -0.067000 0.123375 0.131783 -vn 0.770263 -0.552286 -0.318865 -v -0.067000 0.123833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.067000 0.124000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.067000 0.123833 0.130075 -vn 0.770260 0.318865 0.552291 -v -0.067000 0.122125 0.129617 -vn 0.770264 0.552286 0.318863 -v -0.067000 0.121667 0.130075 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.128975 -vn 0.770261 0.637729 -0.000002 -v -0.067000 0.121500 0.130700 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.119500 0.134200 -vn 0.770263 0.552286 -0.318865 -v -0.067000 0.121667 0.131325 -vn 0.770260 0.318866 -0.552291 -v -0.067000 0.122125 0.131783 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.143000 0.123275 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.143000 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.111125 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.143000 0.117200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.143000 0.111125 -vn 0.904534 0.301511 -0.301511 -v -0.067000 0.111000 0.127000 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.112250 0.127000 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.127925 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.116750 0.127000 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.124200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.111000 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.112250 0.117200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.112250 0.117700 -vn 0.904534 0.301511 0.301511 -v -0.067000 0.111000 0.117700 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.111000 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.123275 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.111000 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.111000 0.110200 -vn 0.904534 0.301511 0.301511 -v -0.067000 0.111000 0.107400 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.107225 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.112250 0.107400 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.116750 0.107400 -vn 0.904534 -0.301511 0.301511 -v -0.067000 0.117500 0.107400 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.107225 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.110200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.117500 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.117200 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.116750 0.116700 -vn 0.904534 -0.301511 -0.301512 -v -0.067000 0.117500 0.116700 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.117500 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.106300 0.111125 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.111000 0.111125 -vn 0.904534 0.301511 -0.301511 -v -0.067000 0.111000 0.116700 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.112250 0.116700 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.119450 -vn 0.764304 -0.644722 -0.013206 -v -0.067000 0.097400 0.127618 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.123275 -vn 0.764067 0.232161 -0.601916 -v -0.067000 0.096175 0.128439 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.128975 -vn 0.764745 -0.071180 -0.640389 -v -0.067000 0.096599 0.128494 -vn 0.764747 -0.358941 -0.535092 -v -0.067000 0.097001 0.128347 -vn 0.764746 -0.565526 -0.308779 -v -0.067000 0.097290 0.128031 -vn 0.764742 -0.070000 0.640523 -v -0.067000 0.096598 0.126705 -vn 0.764747 0.233779 0.600425 -v -0.067000 0.096173 0.126761 -vn 0.764744 0.484694 0.424544 -v -0.067000 0.095823 0.127007 -vn 0.764749 0.625987 0.152640 -v -0.067000 0.095626 0.127387 -vn 0.764744 0.625713 -0.153784 -v -0.067000 0.095626 0.127815 -vn 0.764104 0.485064 -0.425274 -v -0.067000 0.095824 0.128194 -vn 0.729848 -0.680317 0.067005 -v -0.067000 0.104000 0.107500 -vn 0.753772 -0.607111 0.251484 -v -0.067000 0.103977 0.107385 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.107225 -vn 0.566634 -0.643196 0.515000 -v -0.067000 0.097306 0.107200 -vn 0.764746 -0.644208 0.012632 -v -0.067000 0.097400 0.106782 -vn 0.729849 -0.067005 0.680317 -v -0.067000 0.103700 0.107200 -vn 0.753772 -0.251484 0.607111 -v -0.067000 0.103815 0.107223 -vn 0.753760 -0.464675 0.464675 -v -0.067000 0.103912 0.107288 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.104000 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.110200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.104000 0.111125 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.111125 -vn 0.737702 -0.669350 -0.088128 -v -0.067000 0.104000 0.112900 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.104750 0.117200 -vn 0.770260 -0.552288 -0.318870 -v -0.067000 0.103960 0.113050 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.111125 -vn 0.737697 0.669358 -0.088113 -v -0.067000 0.097000 0.112900 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.117200 -vn 0.770265 0.552289 -0.318854 -v -0.067000 0.097040 0.113050 -vn 0.770260 0.318870 -0.552288 -v -0.067000 0.097150 0.113160 -vn 0.737702 0.088128 -0.669350 -v -0.067000 0.097300 0.113200 -vn 0.737702 -0.088128 -0.669350 -v -0.067000 0.103700 0.113200 -vn 0.770259 -0.318870 -0.552288 -v -0.067000 0.103850 0.113160 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.097000 0.110200 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.097000 0.111125 -vn 0.561187 0.474787 -0.677973 -v -0.067000 0.097000 0.107548 -vn 0.764744 -0.070005 -0.640520 -v -0.067000 0.096598 0.107695 -vn 0.764747 0.233779 -0.600425 -v -0.067000 0.096173 0.107639 -vn 0.764745 0.484695 -0.424541 -v -0.067000 0.095823 0.107393 -vn 0.764747 0.232681 0.600850 -v -0.067000 0.096175 0.105961 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.096550 0.102200 -vn 0.764747 0.483921 0.425421 -v -0.067000 0.095824 0.106206 -vn 0.764744 0.625713 0.153784 -v -0.067000 0.095626 0.106585 -vn 0.764748 0.625989 -0.152637 -v -0.067000 0.095626 0.107013 -vn 0.764746 -0.565526 0.308779 -v -0.067000 0.097290 0.106369 -vn 0.764747 -0.358941 0.535092 -v -0.067000 0.097001 0.106053 -vn 0.764746 -0.071180 0.640389 -v -0.067000 0.096599 0.105906 -vn 0.942505 -0.074365 0.325813 -v -0.067000 0.130223 0.126031 -vn 0.942505 0.074365 0.325814 -v -0.067000 0.128777 0.126031 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.124200 -vn 0.942505 0.208365 0.261281 -v -0.067000 0.127474 0.126659 -vn 0.942505 0.301097 0.145001 -v -0.067000 0.126572 0.127790 -vn 0.942504 -0.208366 0.261284 -v -0.067000 0.131526 0.126659 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.124200 -vn 0.942505 -0.301096 0.145001 -v -0.067000 0.132428 0.127790 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.128975 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.133825 0.132200 -vn 0.942505 -0.301096 -0.145000 -v -0.067000 0.132428 0.130610 -vn 0.942505 -0.334192 0.000000 -v -0.067000 0.132750 0.129200 -vn 0.759603 -0.276656 0.588613 -v -0.067000 0.130586 0.102010 -vn 0.732634 -0.074613 0.676521 -v -0.067000 0.131436 0.102200 -vn 0.942504 -0.208366 0.261284 -v -0.067000 0.131526 0.102659 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.133825 0.102200 -vn 0.942505 -0.301096 0.145001 -v -0.067000 0.132428 0.103790 -vn 0.942505 -0.334192 0.000000 -v -0.067000 0.132750 0.105200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.106475 -vn 0.942505 -0.301096 -0.145001 -v -0.067000 0.132428 0.106610 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.107225 -vn 0.942505 -0.208365 -0.261283 -v -0.067000 0.131526 0.107741 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.133825 0.110200 -vn 0.942506 -0.074365 -0.325812 -v -0.067000 0.130223 0.108369 -vn 0.942505 0.301097 -0.145000 -v -0.067000 0.126572 0.106610 -vn 0.942505 0.208365 -0.261281 -v -0.067000 0.127474 0.107741 -vn 0.942506 0.208365 0.261280 -v -0.067000 0.127474 0.102659 -vn 0.942505 0.301097 0.145000 -v -0.067000 0.126572 0.103790 -vn 0.942505 0.334192 -0.000000 -v -0.067000 0.126250 0.105200 -vn 0.770264 0.552286 0.318863 -v -0.067000 0.113667 0.130075 -vn 0.770261 0.637729 -0.000002 -v -0.067000 0.113500 0.130700 -vn 0.770263 0.552286 -0.318865 -v -0.067000 0.113667 0.131325 -vn 0.770260 0.318865 -0.552291 -v -0.067000 0.114125 0.131783 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.116750 0.134200 -vn 0.770264 0.000000 -0.637725 -v -0.067000 0.114750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.067000 0.115375 0.131783 -vn 0.770263 -0.552286 -0.318865 -v -0.067000 0.115833 0.131325 -vn 0.770261 -0.637729 -0.000002 -v -0.067000 0.116000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.067000 0.115833 0.130075 -vn 0.770260 -0.318865 0.552291 -v -0.067000 0.115375 0.129617 -vn 0.770264 -0.000000 0.637725 -v -0.067000 0.114750 0.129450 -vn 0.770260 0.318865 0.552291 -v -0.067000 0.114125 0.129617 -vn 0.770261 -0.637729 -0.000002 -v -0.067000 0.100000 0.130700 -vn 0.770264 -0.552286 0.318863 -v -0.067000 0.099833 0.130075 -vn 0.770261 0.552288 0.318865 -v -0.067000 0.097667 0.130075 -vn 0.770263 0.637726 -0.000002 -v -0.067000 0.097500 0.130700 -vn 0.770263 -0.552286 -0.318865 -v -0.067000 0.099833 0.131325 -vn 0.770260 -0.318865 0.552291 -v -0.067000 0.099375 0.129617 -vn 0.770264 -0.000001 0.637725 -v -0.067000 0.098750 0.129450 -vn 0.770261 0.318866 0.552288 -v -0.067000 0.098125 0.129617 -vn 0.770261 0.552288 -0.318867 -v -0.067000 0.097667 0.131325 -vn 0.770261 0.318866 -0.552288 -v -0.067000 0.098125 0.131783 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.096550 0.134200 -vn 0.770264 -0.000001 -0.637725 -v -0.067000 0.098750 0.131950 -vn 0.770260 -0.318865 -0.552291 -v -0.067000 0.099375 0.131783 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.095175 0.134200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.127925 -vn 0.904534 -0.301511 -0.301512 -v -0.067000 0.117500 0.127000 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.124200 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.117500 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.123275 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.117500 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.119500 0.119450 -vn 0.707107 -0.707107 0.000000 -v -0.067000 0.117500 0.119450 -vn 0.904534 -0.301511 0.301511 -v -0.067000 0.117500 0.117700 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.116750 0.117700 -vn 0.707107 0.000000 -0.707107 -v -0.067000 0.135500 0.132200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.128975 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.127925 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.124200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.123275 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.119450 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.136850 0.117200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.125325 0.107225 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.107225 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.122050 0.110200 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.107225 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.135500 0.106475 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.135500 0.102200 -vn 0.942505 0.074364 -0.325813 -v -0.067000 0.128777 0.108369 -vn 0.707107 0.707107 0.000000 -v -0.067000 0.090000 0.106475 -vn 1.000000 0.000000 0.000000 -v -0.067000 0.116750 0.102200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.096550 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.104750 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.106300 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.112250 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.116750 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.119500 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.122050 0.100200 -vn 0.707107 0.000000 0.707107 -v -0.067000 0.125325 0.100200 -vn 0.577350 -0.577350 0.577350 -v -0.067000 0.128000 0.100200 -vn -0.770261 -0.637729 -0.000002 -v -0.068000 0.100000 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.068000 0.099833 0.131325 -vn -0.770260 -0.318865 -0.552291 -v -0.068000 0.099375 0.131783 -vn -0.770264 -0.000001 -0.637726 -v -0.068000 0.098750 0.131950 -vn -0.770261 0.318866 -0.552288 -v -0.068000 0.098125 0.131783 -vn -0.770261 0.552288 -0.318867 -v -0.068000 0.097667 0.131325 -vn -0.770263 0.637726 -0.000002 -v -0.068000 0.097500 0.130700 -vn -0.770261 0.552288 0.318865 -v -0.068000 0.097667 0.130075 -vn -0.770261 0.318866 0.552288 -v -0.068000 0.098125 0.129617 -vn -0.770264 -0.000001 0.637725 -v -0.068000 0.098750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.068000 0.099375 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.068000 0.099833 0.130075 -vn -0.770263 -0.637726 -0.000002 -v -0.068000 0.108000 0.130700 -vn -0.770261 -0.552288 -0.318867 -v -0.068000 0.107833 0.131325 -vn -0.770261 -0.318866 -0.552288 -v -0.068000 0.107375 0.131783 -vn -0.770264 0.000001 -0.637725 -v -0.068000 0.106750 0.131950 -vn -0.770261 0.318867 -0.552288 -v -0.068000 0.106125 0.131783 -vn -0.770261 0.552288 -0.318867 -v -0.068000 0.105667 0.131325 -vn -0.770263 0.637726 -0.000002 -v -0.068000 0.105500 0.130700 -vn -0.770261 0.552288 0.318865 -v -0.068000 0.105667 0.130075 -vn -0.770261 0.318867 0.552288 -v -0.068000 0.106125 0.129617 -vn -0.770264 0.000001 0.637726 -v -0.068000 0.106750 0.129450 -vn -0.770261 -0.318866 0.552288 -v -0.068000 0.107375 0.129617 -vn -0.770261 -0.552288 0.318865 -v -0.068000 0.107833 0.130075 -vn -0.770264 -0.637725 0.000000 -v -0.068000 0.094750 0.125200 -vn -0.770261 -0.552288 -0.318867 -v -0.068000 0.094583 0.125825 -vn -0.770261 -0.318866 -0.552288 -v -0.068000 0.094125 0.126283 -vn -0.770264 0.000001 -0.637725 -v -0.068000 0.093500 0.126450 -vn -0.770261 0.318867 -0.552288 -v -0.068000 0.092875 0.126283 -vn -0.770261 0.552288 -0.318867 -v -0.068000 0.092417 0.125825 -vn -0.770264 0.637725 0.000000 -v -0.068000 0.092250 0.125200 -vn -0.770261 0.552288 0.318867 -v -0.068000 0.092417 0.124575 -vn -0.770261 0.318867 0.552288 -v -0.068000 0.092875 0.124117 -vn -0.770264 0.000001 0.637726 -v -0.068000 0.093500 0.123950 -vn -0.770261 -0.318866 0.552288 -v -0.068000 0.094125 0.124117 -vn -0.770261 -0.552288 0.318867 -v -0.068000 0.094583 0.124575 -vn -0.770261 -0.637729 -0.000002 -v -0.068000 0.116000 0.130700 -vn -0.770263 -0.552286 -0.318865 -v -0.068000 0.115833 0.131325 -vn -0.770260 -0.318865 -0.552291 -v -0.068000 0.115375 0.131783 -vn -0.770264 0.000000 -0.637725 -v -0.068000 0.114750 0.131950 -vn -0.770260 0.318866 -0.552291 -v -0.068000 0.114125 0.131783 -vn -0.770263 0.552286 -0.318865 -v -0.068000 0.113667 0.131325 -vn -0.770261 0.637729 -0.000002 -v -0.068000 0.113500 0.130700 -vn -0.770264 0.552286 0.318863 -v -0.068000 0.113667 0.130075 -vn -0.770260 0.318865 0.552291 -v -0.068000 0.114125 0.129617 -vn -0.770264 0.000000 0.637725 -v -0.068000 0.114750 0.129450 -vn -0.770260 -0.318865 0.552291 -v -0.068000 0.115375 0.129617 -vn -0.770264 -0.552286 0.318863 -v -0.068000 0.115833 0.130075 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 0.117250 0.105143 -vn -0.609994 -0.686244 0.396203 -v -0.068000 0.117250 0.102257 -vn -0.609994 0.686244 0.396203 -v -0.068000 0.112250 0.102257 -vn -0.609994 0.686244 -0.396202 -v -0.068000 0.112250 0.105143 -vn -0.609994 0.000001 -0.792406 -v -0.068000 0.114750 0.106587 -vn -0.609994 0.000001 0.792406 -v -0.068000 0.114750 0.100813 -vn -0.609994 0.686243 -0.396203 -v -0.068000 0.112250 0.132143 -vn -0.609995 0.000001 -0.792406 -v -0.068000 0.114750 0.133587 -vn -0.609994 0.686243 0.396203 -v -0.068000 0.112250 0.129257 -vn -0.609994 -0.686243 0.396204 -v -0.068000 0.117250 0.129257 -vn -0.609995 0.000001 0.792406 -v -0.068000 0.114750 0.127813 -vn -0.609994 -0.686243 -0.396204 -v -0.068000 0.117250 0.132143 -vn -0.609994 -0.686243 0.396204 -v -0.068000 0.109250 0.129257 -vn -0.609995 0.000001 0.792406 -v -0.068000 0.106750 0.127813 -vn -0.609994 -0.686243 -0.396204 -v -0.068000 0.109250 0.132143 -vn -0.609994 0.686243 0.396203 -v -0.068000 0.104250 0.129257 -vn -0.609994 0.686244 -0.396203 -v -0.068000 0.104250 0.132143 -vn -0.609995 0.000001 -0.792406 -v -0.068000 0.106750 0.133587 -vn -0.609994 0.686243 0.396204 -v -0.068000 0.096250 0.129257 -vn -0.609994 0.686243 -0.396204 -v -0.068000 0.096250 0.132143 -vn -0.609995 -0.000001 0.792406 -v -0.068000 0.098750 0.127813 -vn -0.609994 -0.686243 -0.396203 -v -0.068000 0.101250 0.132143 -vn -0.609994 -0.686243 0.396203 -v -0.068000 0.101250 0.129257 -vn -0.609995 -0.000001 -0.792406 -v -0.068000 0.098750 0.133587 -vn -0.609994 0.686244 0.396203 -v -0.068000 0.091000 0.123757 -vn -0.609994 0.686244 -0.396203 -v -0.068000 0.091000 0.126643 -vn -0.609994 0.000001 0.792406 -v -0.068000 0.093500 0.122313 -vn -0.609994 -0.686243 -0.396204 -v -0.068000 0.096000 0.126643 -vn -0.609994 -0.686244 0.396203 -v -0.068000 0.096000 0.123757 -vn -0.609995 0.000001 -0.792406 -v -0.068000 0.093500 0.128087 -vn -0.609994 0.686244 0.396203 -v -0.068000 0.091000 0.107757 -vn -0.609994 0.686244 -0.396202 -v -0.068000 0.091000 0.110643 -vn -0.609994 0.000001 0.792406 -v -0.068000 0.093500 0.106313 -vn -0.609994 -0.686243 0.396204 -v -0.068000 0.096000 0.107757 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 0.096000 0.110643 -vn -0.609994 0.000001 -0.792406 -v -0.068000 0.093500 0.112087 -vn -0.609994 0.686244 0.396203 -v -0.068000 0.096250 0.102257 -vn -0.609994 0.686244 -0.396203 -v -0.068000 0.096250 0.105143 -vn -0.609994 -0.686244 0.396202 -v -0.068000 0.101250 0.102257 -vn -0.609994 -0.000001 0.792406 -v -0.068000 0.098750 0.100813 -vn -0.609994 -0.686244 -0.396202 -v -0.068000 0.101250 0.105143 -vn -0.609994 -0.000001 -0.792406 -v -0.068000 0.098750 0.106587 -vn -0.609994 0.686244 0.396202 -v -0.068000 0.104250 0.102257 -vn -0.609994 0.686244 -0.396202 -v -0.068000 0.104250 0.105143 -vn -0.609994 0.000001 0.792406 -v -0.068000 0.106750 0.100813 -vn -0.609994 -0.686244 0.396203 -v -0.068000 0.109250 0.102257 -vn -0.609994 -0.686244 -0.396203 -v -0.068000 0.109250 0.105143 -vn -0.609994 0.000001 -0.792406 -v -0.068000 0.106750 0.106587 -vn 0.904093 -0.095090 -0.416621 -v -0.068000 0.130001 0.107394 -vn 0.904093 0.095091 -0.416622 -v -0.068000 0.128999 0.107394 -vn 0.904093 0.266439 -0.334104 -v -0.068000 0.128097 0.106959 -vn 0.904093 0.385017 -0.185413 -v -0.068000 0.127473 0.106176 -vn 0.904093 0.427336 -0.000001 -v -0.068000 0.127250 0.105200 -vn 0.904092 0.385018 0.185416 -v -0.068000 0.127473 0.104224 -vn 0.904093 0.266439 0.334104 -v -0.068000 0.128097 0.103441 -vn 0.904093 0.095091 0.416622 -v -0.068000 0.128999 0.103006 -vn 0.904094 -0.095089 0.416621 -v -0.068000 0.130001 0.103006 -vn 0.904092 -0.266440 0.334106 -v -0.068000 0.130903 0.103441 -vn 0.904092 -0.385018 0.185415 -v -0.068000 0.131527 0.104224 -vn 0.904093 -0.427336 0.000000 -v -0.068000 0.131750 0.105200 -vn 0.904093 -0.385017 -0.185414 -v -0.068000 0.131527 0.106176 -vn 0.904092 -0.266440 -0.334107 -v -0.068000 0.130903 0.106959 -vn 0.904094 -0.095089 -0.416620 -v -0.068000 0.130001 0.131394 -vn 0.904094 0.095089 -0.416620 -v -0.068000 0.128999 0.131394 -vn 0.904093 0.266440 -0.334105 -v -0.068000 0.128097 0.130959 -vn 0.904093 0.385017 -0.185412 -v -0.068000 0.127473 0.130176 -vn 0.904093 0.427336 -0.000000 -v -0.068000 0.127250 0.129200 -vn 0.904092 0.385017 0.185416 -v -0.068000 0.127473 0.128224 -vn 0.904093 0.266440 0.334103 -v -0.068000 0.128097 0.127441 -vn 0.904092 0.095092 0.416623 -v -0.068000 0.128999 0.127006 -vn 0.904092 -0.095091 0.416623 -v -0.068000 0.130001 0.127006 -vn 0.904092 -0.266440 0.334106 -v -0.068000 0.130903 0.127441 -vn 0.904092 -0.385018 0.185416 -v -0.068000 0.131527 0.128224 -vn 0.904093 -0.427336 0.000000 -v -0.068000 0.131750 0.129200 -vn 0.904093 -0.385017 -0.185412 -v -0.068000 0.131527 0.130176 -vn 0.904092 -0.266439 -0.334108 -v -0.068000 0.130903 0.130959 -# 5180 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 1//1 -f 1//1 28//28 2//2 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 33//33 34//34 35//35 -f 33//33 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 38//38 -f 38//38 37//37 39//39 -f 38//38 39//39 40//40 -f 40//40 39//39 29//29 -f 40//40 29//29 31//31 -f 41//41 34//34 42//42 -f 42//42 34//34 33//33 -f 43//43 44//44 45//45 -f 43//43 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 48//48 -f 48//48 47//47 49//49 -f 48//48 49//49 50//50 -f 50//50 49//49 41//41 -f 50//50 41//41 42//42 -f 51//51 44//44 52//52 -f 52//52 44//44 43//43 -f 53//53 54//54 55//55 -f 53//53 55//55 56//56 -f 56//56 55//55 57//57 -f 56//56 57//57 58//58 -f 58//58 57//57 59//59 -f 58//58 59//59 60//60 -f 60//60 59//59 51//51 -f 60//60 51//51 52//52 -f 61//61 54//54 62//62 -f 62//62 54//54 53//53 -f 32//32 30//30 63//63 -f 32//32 63//63 64//64 -f 64//64 63//63 65//65 -f 64//64 65//65 66//66 -f 66//66 65//65 67//67 -f 66//66 67//67 68//68 -f 68//68 67//67 61//61 -f 68//68 61//61 62//62 -f 34//34 41//41 69//69 -f 69//69 41//41 70//70 -f 71//71 54//54 72//72 -f 72//72 54//54 61//61 -f 72//72 61//61 73//73 -f 39//39 37//37 35//35 -f 47//47 45//45 44//44 -f 29//29 39//39 74//74 -f 74//74 39//39 35//35 -f 74//74 35//35 75//75 -f 75//75 35//35 34//34 -f 75//75 34//34 76//76 -f 76//76 34//34 69//69 -f 77//77 20//20 78//78 -f 78//78 20//20 18//18 -f 78//78 18//18 71//71 -f 71//71 18//18 16//16 -f 71//71 16//16 54//54 -f 67//67 79//79 61//61 -f 61//61 79//79 80//80 -f 61//61 80//80 73//73 -f 29//29 74//74 30//30 -f 30//30 74//74 79//79 -f 30//30 79//79 63//63 -f 63//63 79//79 67//67 -f 63//63 67//67 65//65 -f 10//10 51//51 59//59 -f 16//16 14//14 54//54 -f 54//54 14//14 12//12 -f 54//54 12//12 55//55 -f 55//55 12//12 10//10 -f 55//55 10//10 57//57 -f 57//57 10//10 59//59 -f 51//51 10//10 44//44 -f 44//44 10//10 8//8 -f 44//44 8//8 47//47 -f 6//6 4//4 41//41 -f 41//41 4//4 2//2 -f 41//41 2//2 70//70 -f 70//70 2//2 28//28 -f 70//70 28//28 81//81 -f 81//81 28//28 26//26 -f 81//81 26//26 82//82 -f 82//82 26//26 24//24 -f 82//82 24//24 77//77 -f 77//77 24//24 22//22 -f 77//77 22//22 20//20 -f 6//6 41//41 8//8 -f 8//8 41//41 49//49 -f 8//8 49//49 47//47 -f 83//83 69//69 84//84 -f 84//84 69//69 70//70 -f 84//84 70//70 85//85 -f 85//85 70//70 81//81 -f 85//85 81//81 86//86 -f 86//86 81//81 82//82 -f 86//86 82//82 87//87 -f 87//87 82//82 77//77 -f 87//87 77//77 88//88 -f 88//88 77//77 78//78 -f 88//88 78//78 89//89 -f 89//89 78//78 71//71 -f 89//89 71//71 90//90 -f 90//90 71//71 72//72 -f 90//90 72//72 91//91 -f 91//91 72//72 73//73 -f 91//91 73//73 92//92 -f 92//92 73//73 80//80 -f 92//92 80//80 93//93 -f 93//93 80//80 79//79 -f 93//93 79//79 94//94 -f 94//94 79//79 74//74 -f 94//94 74//74 95//95 -f 95//95 74//74 75//75 -f 95//95 75//75 96//96 -f 96//96 75//75 76//76 -f 96//96 76//76 83//83 -f 83//83 76//76 69//69 -f 19//19 21//21 62//62 -f 62//62 21//21 90//90 -f 11//11 13//13 53//53 -f 53//53 13//13 15//15 -f 53//53 15//15 62//62 -f 62//62 15//15 17//17 -f 62//62 17//17 19//19 -f 93//93 32//32 64//64 -f 84//84 42//42 83//83 -f 83//83 42//42 33//33 -f 83//83 33//33 96//96 -f 36//36 94//94 33//33 -f 33//33 94//94 95//95 -f 33//33 95//95 96//96 -f 32//32 93//93 31//31 -f 31//31 93//93 94//94 -f 31//31 94//94 40//40 -f 40//40 94//94 36//36 -f 40//40 36//36 38//38 -f 25//25 27//27 86//86 -f 11//11 53//53 9//9 -f 9//9 53//53 56//56 -f 9//9 56//56 58//58 -f 90//90 91//91 62//62 -f 62//62 91//91 92//92 -f 62//62 92//92 68//68 -f 68//68 92//92 93//93 -f 68//68 93//93 66//66 -f 66//66 93//93 64//64 -f 87//87 88//88 21//21 -f 21//21 88//88 89//89 -f 21//21 89//89 90//90 -f 84//84 85//85 42//42 -f 42//42 85//85 86//86 -f 42//42 86//86 1//1 -f 1//1 86//86 27//27 -f 58//58 60//60 9//9 -f 9//9 60//60 52//52 -f 9//9 52//52 7//7 -f 7//7 52//52 43//43 -f 7//7 43//43 46//46 -f 87//87 21//21 86//86 -f 86//86 21//21 23//23 -f 86//86 23//23 25//25 -f 1//1 3//3 42//42 -f 42//42 3//3 5//5 -f 42//42 5//5 50//50 -f 50//50 5//5 7//7 -f 50//50 7//7 48//48 -f 48//48 7//7 46//46 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 97//97 -f 97//97 120//120 98//98 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 131//131 -f 131//131 130//130 132//132 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 141//141 -f 141//141 140//140 142//142 -f 141//141 142//142 143//143 -f 143//143 142//142 144//144 -f 143//143 144//144 121//121 -f 121//121 144//144 122//122 -f 145//145 146//146 147//147 -f 147//147 146//146 148//148 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 151//151 -f 151//151 150//150 152//152 -f 151//151 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 155//155 156//156 157//157 -f 157//157 156//156 158//158 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 159//159 160//160 161//161 -f 161//161 160//160 162//162 -f 161//161 162//162 163//163 -f 163//163 162//162 164//164 -f 163//163 164//164 165//165 -f 165//165 164//164 166//166 -f 165//165 166//166 167//167 -f 167//167 166//166 168//168 -f 167//167 168//168 145//145 -f 145//145 168//168 146//146 -f 169//169 170//170 171//171 -f 171//171 170//170 172//172 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 175//175 176//176 177//177 -f 177//177 176//176 178//178 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 185//185 -f 185//185 184//184 186//186 -f 185//185 186//186 187//187 -f 187//187 186//186 188//188 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 189//189 190//190 191//191 -f 191//191 190//190 192//192 -f 191//191 192//192 169//169 -f 169//169 192//192 170//170 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 197//197 196//196 198//198 -f 197//197 198//198 199//199 -f 199//199 198//198 200//200 -f 199//199 200//200 201//201 -f 201//201 200//200 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 205//205 204//204 206//206 -f 205//205 206//206 207//207 -f 207//207 206//206 208//208 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 213//213 212//212 214//214 -f 213//213 214//214 215//215 -f 215//215 214//214 216//216 -f 215//215 216//216 193//193 -f 193//193 216//216 194//194 -f 217//217 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 225//225 224//224 226//226 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 229//229 -f 229//229 228//228 230//230 -f 229//229 230//230 231//231 -f 231//231 230//230 232//232 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 237//237 -f 237//237 236//236 238//238 -f 237//237 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 217//217 -f 217//217 240//240 218//218 -f 241//241 242//242 243//243 -f 244//244 245//245 246//246 -f 247//247 248//248 249//249 -f 250//250 251//251 252//252 -f 253//253 254//254 255//255 -f 256//256 257//257 258//258 -f 132//132 130//130 258//258 -f 114//114 259//259 260//260 -f 261//261 262//262 263//263 -f 264//264 265//265 266//266 -f 267//267 268//268 269//269 -f 270//270 271//271 272//272 -f 273//273 274//274 275//275 -f 276//276 277//277 278//278 -f 279//279 280//280 281//281 -f 282//282 283//283 284//284 -f 285//285 286//286 287//287 -f 288//288 289//289 290//290 -f 291//291 292//292 293//293 -f 294//294 295//295 296//296 -f 297//297 298//298 250//250 -f 250//250 298//298 299//299 -f 250//250 299//299 251//251 -f 251//251 299//299 300//300 -f 301//301 302//302 303//303 -f 303//303 302//302 304//304 -f 303//303 304//304 305//305 -f 306//306 307//307 308//308 -f 309//309 310//310 311//311 -f 311//311 310//310 306//306 -f 311//311 306//306 312//312 -f 312//312 306//306 308//308 -f 312//312 308//308 313//313 -f 306//306 314//314 307//307 -f 307//307 314//314 315//315 -f 307//307 315//315 316//316 -f 315//315 317//317 316//316 -f 316//316 317//317 318//318 -f 316//316 318//318 319//319 -f 320//320 321//321 322//322 -f 322//322 321//321 323//323 -f 322//322 323//323 318//318 -f 318//318 323//323 324//324 -f 318//318 324//324 319//319 -f 325//325 326//326 253//253 -f 253//253 326//326 327//327 -f 295//295 328//328 329//329 -f 330//330 331//331 332//332 -f 333//333 334//334 335//335 -f 326//326 336//336 327//327 -f 327//327 336//336 337//337 -f 327//327 337//337 332//332 -f 332//332 337//337 338//338 -f 332//332 338//338 330//330 -f 333//333 335//335 331//331 -f 339//339 340//340 341//341 -f 341//341 340//340 342//342 -f 343//343 344//344 345//345 -f 345//345 344//344 346//346 -f 340//340 347//347 342//342 -f 342//342 347//347 348//348 -f 342//342 348//348 349//349 -f 349//349 348//348 350//350 -f 351//351 352//352 343//343 -f 343//343 352//352 353//353 -f 343//343 353//353 344//344 -f 350//350 354//354 349//349 -f 349//349 354//354 355//355 -f 349//349 355//355 351//351 -f 351//351 355//355 356//356 -f 351//351 356//356 352//352 -f 242//242 357//357 358//358 -f 359//359 360//360 361//361 -f 361//361 360//360 362//362 -f 363//363 364//364 365//365 -f 365//365 364//364 366//366 -f 365//365 366//366 358//358 -f 358//358 366//366 367//367 -f 358//358 367//367 368//368 -f 369//369 370//370 371//371 -f 371//371 370//370 372//372 -f 371//371 372//372 361//361 -f 361//361 372//372 373//373 -f 361//361 373//373 359//359 -f 357//357 242//242 374//374 -f 374//374 242//242 241//241 -f 374//374 241//241 375//375 -f 376//376 377//377 378//378 -f 378//378 377//377 379//379 -f 378//378 379//379 380//380 -f 380//380 379//379 381//381 -f 380//380 381//381 382//382 -f 382//382 381//381 383//383 -f 381//381 384//384 383//383 -f 383//383 384//384 291//291 -f 383//383 291//291 385//385 -f 385//385 291//291 293//293 -f 386//386 387//387 388//388 -f 388//388 389//389 386//386 -f 386//386 389//389 390//390 -f 386//386 390//390 391//391 -f 391//391 390//390 361//361 -f 391//391 361//361 365//365 -f 365//365 361//361 362//362 -f 365//365 362//362 363//363 -f 392//392 393//393 394//394 -f 394//394 393//393 395//395 -f 396//396 397//397 398//398 -f 396//396 398//398 399//399 -f 400//400 401//401 402//402 -f 402//402 401//401 399//399 -f 397//397 403//403 398//398 -f 398//398 403//403 404//404 -f 398//398 404//404 395//395 -f 395//395 404//404 405//405 -f 395//395 405//405 394//394 -f 400//400 402//402 406//406 -f 406//406 402//402 407//407 -f 406//406 407//407 408//408 -f 408//408 407//407 409//409 -f 408//408 409//409 290//290 -f 290//290 409//409 410//410 -f 290//290 410//410 288//288 -f 411//411 412//412 285//285 -f 285//285 412//412 413//413 -f 285//285 413//413 414//414 -f 411//411 285//285 415//415 -f 415//415 285//285 287//287 -f 415//415 287//287 416//416 -f 416//416 287//287 417//417 -f 416//416 417//417 418//418 -f 419//419 420//420 421//421 -f 418//418 422//422 416//416 -f 416//416 422//422 423//423 -f 416//416 423//423 424//424 -f 424//424 423//423 425//425 -f 421//421 420//420 426//426 -f 426//426 420//420 427//427 -f 426//426 427//427 418//418 -f 418//418 427//427 428//428 -f 418//418 428//428 422//422 -f 425//425 423//423 429//429 -f 429//429 423//423 419//419 -f 429//429 419//419 430//430 -f 394//394 431//431 392//392 -f 392//392 431//431 432//432 -f 392//392 432//432 421//421 -f 421//421 432//432 433//433 -f 433//433 282//282 421//421 -f 421//421 282//282 284//284 -f 421//421 284//284 419//419 -f 419//419 284//284 434//434 -f 419//419 434//434 430//430 -f 435//435 436//436 306//306 -f 306//306 436//436 437//437 -f 306//306 437//437 314//314 -f 438//438 439//439 440//440 -f 440//440 441//441 438//438 -f 438//438 441//441 442//442 -f 438//438 442//442 443//443 -f 444//444 445//445 446//446 -f 279//279 281//281 447//447 -f 448//448 281//281 449//449 -f 449//449 281//281 450//450 -f 448//448 451//451 281//281 -f 281//281 451//451 452//452 -f 281//281 452//452 447//447 -f 453//453 454//454 450//450 -f 455//455 456//456 286//286 -f 286//286 456//456 457//457 -f 286//286 457//457 458//458 -f 458//458 459//459 286//286 -f 286//286 459//459 460//460 -f 286//286 460//460 287//287 -f 461//461 462//462 463//463 -f 464//464 465//465 305//305 -f 461//461 466//466 462//462 -f 462//462 466//466 467//467 -f 462//462 467//467 468//468 -f 469//469 303//303 470//470 -f 470//470 303//303 305//305 -f 470//470 305//305 471//471 -f 471//471 305//305 465//465 -f 472//472 473//473 463//463 -f 463//463 473//473 474//474 -f 463//463 474//474 461//461 -f 475//475 476//476 477//477 -f 477//477 476//476 478//478 -f 477//477 478//478 472//472 -f 472//472 478//478 479//479 -f 472//472 479//479 473//473 -f 263//263 262//262 477//477 -f 477//477 262//262 480//480 -f 477//477 480//480 481//481 -f 309//309 482//482 483//483 -f 483//483 482//482 484//484 -f 483//483 484//484 481//481 -f 484//484 485//485 481//481 -f 481//481 485//485 486//486 -f 481//481 486//486 477//477 -f 477//477 486//486 487//487 -f 477//477 487//487 475//475 -f 313//313 308//308 488//488 -f 488//488 308//308 301//301 -f 488//488 301//301 489//489 -f 489//489 301//301 303//303 -f 489//489 303//303 490//490 -f 490//490 303//303 469//469 -f 490//490 469//469 491//491 -f 492//492 493//493 494//494 -f 493//493 492//492 495//495 -f 496//496 497//497 252//252 -f 498//498 499//499 500//500 -f 500//500 499//499 501//501 -f 502//502 503//503 504//504 -f 499//499 505//505 501//501 -f 501//501 505//505 506//506 -f 501//501 506//506 507//507 -f 504//504 508//508 502//502 -f 502//502 508//508 509//509 -f 502//502 509//509 252//252 -f 252//252 509//509 510//510 -f 252//252 510//510 496//496 -f 507//507 503//503 501//501 -f 501//501 503//503 502//502 -f 501//501 502//502 511//511 -f 511//511 502//502 388//388 -f 511//511 388//388 292//292 -f 292//292 388//388 387//387 -f 292//292 387//387 293//293 -f 512//512 513//513 514//514 -f 515//515 516//516 517//517 -f 517//517 516//516 518//518 -f 517//517 518//518 519//519 -f 519//519 518//518 520//520 -f 277//277 276//276 521//521 -f 522//522 523//523 524//524 -f 524//524 523//523 525//525 -f 524//524 525//525 526//526 -f 526//526 525//525 278//278 -f 526//526 278//278 527//527 -f 249//249 528//528 529//529 -f 530//530 531//531 532//532 -f 530//530 532//532 533//533 -f 528//528 249//249 534//534 -f 534//534 249//249 246//246 -f 534//534 246//246 514//514 -f 514//514 246//246 535//535 -f 514//514 535//535 512//512 -f 536//536 537//537 538//538 -f 538//538 537//537 539//539 -f 538//538 539//539 540//540 -f 541//541 542//542 272//272 -f 272//272 542//542 543//543 -f 272//272 543//543 544//544 -f 540//540 539//539 545//545 -f 545//545 539//539 445//445 -f 545//545 445//445 546//546 -f 546//546 445//445 444//444 -f 546//546 444//444 547//547 -f 548//548 549//549 524//524 -f 550//550 551//551 552//552 -f 553//553 522//522 550//550 -f 550//550 522//522 524//524 -f 550//550 524//524 551//551 -f 551//551 524//524 549//549 -f 536//536 541//541 537//537 -f 537//537 541//541 272//272 -f 537//537 272//272 554//554 -f 554//554 272//272 271//271 -f 554//554 555//555 537//537 -f 537//537 555//555 556//556 -f 537//537 556//556 557//557 -f 557//557 556//556 558//558 -f 557//557 558//558 559//559 -f 560//560 561//561 562//562 -f 562//562 561//561 563//563 -f 562//562 563//563 527//527 -f 527//527 563//563 564//564 -f 527//527 564//564 267//267 -f 565//565 566//566 567//567 -f 567//567 566//566 568//568 -f 567//567 568//568 569//569 -f 268//268 570//570 571//571 -f 571//571 570//570 572//572 -f 571//571 572//572 568//568 -f 568//568 572//572 573//573 -f 568//568 573//573 569//569 -f 574//574 568//568 575//575 -f 576//576 577//577 566//566 -f 566//566 577//577 578//578 -f 578//578 579//579 566//566 -f 566//566 579//579 580//580 -f 566//566 580//580 568//568 -f 568//568 580//580 581//581 -f 568//568 581//581 575//575 -f 575//575 582//582 574//574 -f 574//574 582//582 583//583 -f 574//574 583//583 280//280 -f 583//583 584//584 280//280 -f 280//280 584//584 585//585 -f 280//280 585//585 281//281 -f 281//281 585//585 586//586 -f 281//281 586//586 576//576 -f 576//576 586//586 587//587 -f 576//576 587//587 577//577 -f 588//588 589//589 250//250 -f 590//590 591//591 254//254 -f 254//254 591//591 592//592 -f 254//254 592//592 255//255 -f 593//593 594//594 595//595 -f 243//243 596//596 597//597 -f 593//593 421//421 598//598 -f 598//598 421//421 426//426 -f 598//598 426//426 599//599 -f 599//599 426//426 600//600 -f 599//599 600//600 597//597 -f 597//597 600//600 601//601 -f 597//597 601//601 243//243 -f 414//414 413//413 602//602 -f 602//602 413//413 410//410 -f 602//602 410//410 603//603 -f 603//603 410//410 409//409 -f 603//603 409//409 604//604 -f 604//604 409//409 407//407 -f 604//604 407//407 265//265 -f 286//286 605//605 455//455 -f 455//455 605//605 606//606 -f 455//455 606//606 607//607 -f 607//607 606//606 608//608 -f 607//607 608//608 609//609 -f 609//609 608//608 610//610 -f 609//609 610//610 611//611 -f 611//611 610//610 264//264 -f 309//309 483//483 310//310 -f 310//310 483//483 612//612 -f 310//310 612//612 261//261 -f 250//250 613//613 297//297 -f 297//297 613//613 614//614 -f 297//297 614//614 615//615 -f 615//615 614//614 616//616 -f 615//615 616//616 263//263 -f 263//263 616//616 617//617 -f 263//263 617//617 261//261 -f 261//261 617//617 618//618 -f 261//261 618//618 310//310 -f 310//310 618//618 619//619 -f 310//310 619//619 306//306 -f 306//306 619//619 620//620 -f 306//306 620//620 435//435 -f 114//114 112//112 259//259 -f 259//259 112//112 110//110 -f 259//259 110//110 621//621 -f 349//349 98//98 120//120 -f 98//98 349//349 100//100 -f 100//100 349//349 351//351 -f 100//100 351//351 102//102 -f 110//110 108//108 621//621 -f 621//621 108//108 106//106 -f 621//621 106//106 351//351 -f 351//351 106//106 104//104 -f 351//351 104//104 102//102 -f 118//118 116//116 622//622 -f 331//331 335//335 332//332 -f 332//332 335//335 122//122 -f 332//332 122//122 144//144 -f 144//144 142//142 332//332 -f 332//332 142//142 140//140 -f 332//332 140//140 257//257 -f 140//140 138//138 257//257 -f 257//257 138//138 136//136 -f 257//257 136//136 258//258 -f 258//258 136//136 134//134 -f 258//258 134//134 132//132 -f 247//247 128//128 248//248 -f 248//248 128//128 126//126 -f 248//248 126//126 335//335 -f 335//335 126//126 124//124 -f 335//335 124//124 122//122 -f 250//250 589//589 613//613 -f 613//613 589//589 623//623 -f 613//613 623//623 614//614 -f 614//614 623//623 590//590 -f 614//614 590//590 624//624 -f 624//624 590//590 254//254 -f 624//624 254//254 625//625 -f 625//625 254//254 253//253 -f 625//625 253//253 626//626 -f 626//626 253//253 327//327 -f 626//626 327//327 627//627 -f 627//627 327//327 332//332 -f 627//627 332//332 628//628 -f 628//628 332//332 257//257 -f 628//628 257//257 629//629 -f 629//629 257//257 256//256 -f 629//629 256//256 630//630 -f 443//443 630//630 438//438 -f 438//438 630//630 256//256 -f 438//438 256//256 631//631 -f 631//631 256//256 258//258 -f 631//631 258//258 247//247 -f 247//247 258//258 130//130 -f 247//247 130//130 128//128 -f 329//329 492//492 632//632 -f 632//632 492//492 494//494 -f 632//632 494//494 633//633 -f 633//633 494//494 634//634 -f 633//633 634//634 384//384 -f 384//384 634//634 635//635 -f 384//384 635//635 291//291 -f 291//291 635//635 636//636 -f 291//291 636//636 292//292 -f 292//292 636//636 637//637 -f 292//292 637//637 511//511 -f 500//500 495//495 638//638 -f 638//638 495//495 492//492 -f 638//638 492//492 255//255 -f 255//255 492//492 329//329 -f 255//255 329//329 253//253 -f 253//253 329//329 328//328 -f 253//253 328//328 325//325 -f 592//592 588//588 255//255 -f 255//255 588//588 250//250 -f 255//255 250//250 638//638 -f 638//638 250//250 252//252 -f 638//638 252//252 500//500 -f 500//500 252//252 497//497 -f 500//500 497//497 498//498 -f 552//552 270//270 550//550 -f 550//550 270//270 272//272 -f 550//550 272//272 275//275 -f 275//275 272//272 544//544 -f 275//275 544//544 273//273 -f 531//531 553//553 532//532 -f 532//532 553//553 550//550 -f 532//532 550//550 639//639 -f 639//639 550//550 275//275 -f 639//639 275//275 444//444 -f 444//444 275//275 274//274 -f 444//444 274//274 547//547 -f 529//529 533//533 249//249 -f 249//249 533//533 532//532 -f 249//249 532//532 247//247 -f 247//247 532//532 639//639 -f 247//247 639//639 631//631 -f 631//631 639//639 444//444 -f 631//631 444//444 438//438 -f 438//438 444//444 446//446 -f 438//438 446//446 439//439 -f 246//246 245//245 640//640 -f 245//245 641//641 640//640 -f 640//640 641//641 642//642 -f 640//640 642//642 643//643 -f 643//643 248//248 640//640 -f 640//640 248//248 335//335 -f 640//640 335//335 296//296 -f 296//296 335//335 334//334 -f 296//296 334//334 294//294 -f 643//643 644//644 248//248 -f 248//248 644//644 645//645 -f 248//248 645//645 249//249 -f 249//249 645//645 646//646 -f 249//249 646//646 647//647 -f 647//647 648//648 249//249 -f 249//249 648//648 649//649 -f 249//249 649//649 246//246 -f 246//246 649//649 650//650 -f 246//246 650//650 244//244 -f 399//399 398//398 402//402 -f 402//402 398//398 462//462 -f 402//402 462//462 305//305 -f 305//305 462//462 468//468 -f 305//305 468//468 464//464 -f 268//268 571//571 269//269 -f 269//269 571//571 651//651 -f 269//269 651//651 652//652 -f 652//652 651//651 557//557 -f 652//652 557//557 653//653 -f 653//653 557//557 559//559 -f 653//653 559//559 654//654 -f 267//267 269//269 527//527 -f 527//527 269//269 652//652 -f 527//527 652//652 526//526 -f 526//526 652//652 653//653 -f 526//526 653//653 524//524 -f 524//524 653//653 654//654 -f 524//524 654//654 548//548 -f 265//265 407//407 266//266 -f 266//266 407//407 402//402 -f 266//266 402//402 655//655 -f 655//655 402//402 305//305 -f 655//655 305//305 656//656 -f 656//656 305//305 304//304 -f 656//656 304//304 657//657 -f 264//264 266//266 611//611 -f 611//611 266//266 655//655 -f 611//611 655//655 658//658 -f 658//658 655//655 656//656 -f 658//658 656//656 320//320 -f 320//320 656//656 657//657 -f 320//320 657//657 321//321 -f 513//513 512//512 520//520 -f 520//520 512//512 659//659 -f 520//520 659//659 519//519 -f 519//519 659//659 660//660 -f 519//519 660//660 517//517 -f 521//521 622//622 260//260 -f 260//260 622//622 116//116 -f 260//260 116//116 114//114 -f 661//661 662//662 660//660 -f 663//663 664//664 517//517 -f 660//660 662//662 517//517 -f 517//517 662//662 665//665 -f 517//517 665//665 663//663 -f 276//276 515//515 521//521 -f 521//521 515//515 517//517 -f 521//521 517//517 622//622 -f 622//622 517//517 664//664 -f 666//666 667//667 668//668 -f 668//668 667//667 669//669 -f 668//668 669//669 660//660 -f 660//660 669//669 670//670 -f 660//660 670//670 661//661 -f 664//664 671//671 622//622 -f 622//622 671//671 672//672 -f 622//622 672//672 668//668 -f 668//668 672//672 673//673 -f 668//668 673//673 666//666 -f 295//295 329//329 296//296 -f 296//296 329//329 632//632 -f 296//296 632//632 640//640 -f 640//640 632//632 633//633 -f 640//640 633//633 246//246 -f 246//246 633//633 384//384 -f 246//246 384//384 535//535 -f 535//535 384//384 381//381 -f 535//535 381//381 512//512 -f 512//512 381//381 379//379 -f 512//512 379//379 659//659 -f 659//659 379//379 377//377 -f 659//659 377//377 660//660 -f 660//660 377//377 376//376 -f 660//660 376//376 668//668 -f 450//450 281//281 453//453 -f 453//453 281//281 576//576 -f 453//453 576//576 674//674 -f 674//674 576//576 566//566 -f 674//674 566//566 562//562 -f 562//562 566//566 565//565 -f 562//562 565//565 560//560 -f 120//120 118//118 349//349 -f 349//349 118//118 622//622 -f 349//349 622//622 342//342 -f 342//342 622//622 668//668 -f 342//342 668//668 341//341 -f 341//341 668//668 376//376 -f 341//341 376//376 675//675 -f 368//368 369//369 358//358 -f 358//358 369//369 371//371 -f 358//358 371//371 242//242 -f 242//242 371//371 595//595 -f 242//242 595//595 243//243 -f 243//243 595//595 594//594 -f 243//243 594//594 596//596 -f 593//593 595//595 421//421 -f 421//421 595//595 371//371 -f 421//421 371//371 392//392 -f 392//392 371//371 361//361 -f 392//392 361//361 393//393 -f 393//393 361//361 390//390 -f 393//393 390//390 395//395 -f 395//395 390//390 389//389 -f 395//395 389//389 398//398 -f 398//398 389//389 388//388 -f 398//398 388//388 462//462 -f 462//462 388//388 502//502 -f 462//462 502//502 463//463 -f 463//463 502//502 252//252 -f 463//463 252//252 472//472 -f 472//472 252//252 251//251 -f 472//472 251//251 477//477 -f 477//477 251//251 300//300 -f 477//477 300//300 263//263 -f 263//263 300//300 676//676 -f 263//263 676//676 615//615 -f 278//278 277//277 527//527 -f 527//527 277//277 521//521 -f 527//527 521//521 562//562 -f 562//562 521//521 260//260 -f 562//562 260//260 674//674 -f 674//674 260//260 259//259 -f 674//674 259//259 453//453 -f 453//453 259//259 621//621 -f 453//453 621//621 454//454 -f 675//675 677//677 341//341 -f 341//341 677//677 345//345 -f 341//341 345//345 339//339 -f 339//339 345//345 346//346 -f 378//378 375//375 376//376 -f 376//376 375//375 241//241 -f 376//376 241//241 675//675 -f 675//675 241//241 243//243 -f 675//675 243//243 678//678 -f 678//678 679//679 675//675 -f 675//675 679//679 680//680 -f 675//675 680//680 677//677 -f 677//677 680//680 681//681 -f 677//677 681//681 601//601 -f 601//601 681//681 682//682 -f 601//601 682//682 243//243 -f 243//243 682//682 683//683 -f 243//243 683//683 678//678 -f 556//556 684//684 558//558 -f 558//558 684//684 685//685 -f 558//558 685//685 559//559 -f 559//559 685//685 686//686 -f 559//559 686//686 654//654 -f 654//654 686//686 687//687 -f 654//654 687//687 548//548 -f 548//548 687//687 688//688 -f 548//548 688//688 549//549 -f 549//549 688//688 689//689 -f 549//549 689//689 551//551 -f 551//551 689//689 690//690 -f 551//551 690//690 552//552 -f 552//552 690//690 691//691 -f 552//552 691//691 270//270 -f 270//270 691//691 692//692 -f 270//270 692//692 271//271 -f 271//271 692//692 693//693 -f 271//271 693//693 554//554 -f 554//554 693//693 694//694 -f 554//554 694//694 555//555 -f 555//555 694//694 695//695 -f 555//555 695//695 556//556 -f 556//556 695//695 684//684 -f 646//646 696//696 647//647 -f 647//647 696//696 697//697 -f 647//647 697//697 648//648 -f 648//648 697//697 698//698 -f 648//648 698//698 649//649 -f 649//649 698//698 699//699 -f 649//649 699//699 650//650 -f 650//650 699//699 700//700 -f 650//650 700//700 244//244 -f 244//244 700//700 701//701 -f 244//244 701//701 245//245 -f 245//245 701//701 702//702 -f 245//245 702//702 641//641 -f 641//641 702//702 703//703 -f 641//641 703//703 642//642 -f 642//642 703//703 704//704 -f 642//642 704//704 643//643 -f 643//643 704//704 705//705 -f 643//643 705//705 644//644 -f 644//644 705//705 706//706 -f 644//644 706//706 645//645 -f 645//645 706//706 707//707 -f 645//645 707//707 646//646 -f 646//646 707//707 696//696 -f 505//505 708//708 506//506 -f 506//506 708//708 709//709 -f 506//506 709//709 507//507 -f 507//507 709//709 710//710 -f 507//507 710//710 503//503 -f 503//503 710//710 711//711 -f 503//503 711//711 504//504 -f 504//504 711//711 712//712 -f 504//504 712//712 508//508 -f 508//508 712//712 713//713 -f 508//508 713//713 509//509 -f 509//509 713//713 714//714 -f 509//509 714//714 510//510 -f 510//510 714//714 715//715 -f 510//510 715//715 496//496 -f 496//496 715//715 716//716 -f 496//496 716//716 497//497 -f 497//497 716//716 717//717 -f 497//497 717//717 498//498 -f 498//498 717//717 718//718 -f 498//498 718//718 499//499 -f 499//499 718//718 719//719 -f 499//499 719//719 505//505 -f 505//505 719//719 708//708 -f 573//573 720//720 569//569 -f 569//569 720//720 721//721 -f 569//569 721//721 567//567 -f 567//567 721//721 722//722 -f 567//567 722//722 565//565 -f 565//565 722//722 723//723 -f 565//565 723//723 560//560 -f 560//560 723//723 724//724 -f 560//560 724//724 561//561 -f 561//561 724//724 725//725 -f 561//561 725//725 563//563 -f 563//563 725//725 726//726 -f 563//563 726//726 564//564 -f 564//564 726//726 727//727 -f 564//564 727//727 267//267 -f 267//267 727//727 728//728 -f 267//267 728//728 268//268 -f 268//268 728//728 729//729 -f 268//268 729//729 570//570 -f 570//570 729//729 730//730 -f 570//570 730//730 572//572 -f 572//572 730//730 731//731 -f 572//572 731//731 573//573 -f 573//573 731//731 720//720 -f 366//366 732//732 367//367 -f 367//367 732//732 733//733 -f 367//367 733//733 368//368 -f 368//368 733//733 734//734 -f 368//368 734//734 369//369 -f 369//369 734//734 735//735 -f 369//369 735//735 370//370 -f 370//370 735//735 736//736 -f 370//370 736//736 372//372 -f 372//372 736//736 737//737 -f 372//372 737//737 373//373 -f 373//373 737//737 738//738 -f 373//373 738//738 359//359 -f 359//359 738//738 739//739 -f 359//359 739//739 360//360 -f 360//360 739//739 740//740 -f 360//360 740//740 362//362 -f 362//362 740//740 741//741 -f 362//362 741//741 363//363 -f 363//363 741//741 742//742 -f 363//363 742//742 364//364 -f 364//364 742//742 743//743 -f 364//364 743//743 366//366 -f 366//366 743//743 732//732 -f 664//664 744//744 671//671 -f 671//671 744//744 745//745 -f 671//671 745//745 672//672 -f 672//672 745//745 746//746 -f 672//672 746//746 673//673 -f 673//673 746//746 747//747 -f 673//673 747//747 666//666 -f 666//666 747//747 748//748 -f 666//666 748//748 667//667 -f 667//667 748//748 749//749 -f 667//667 749//749 669//669 -f 669//669 749//749 750//750 -f 669//669 750//750 670//670 -f 670//670 750//750 751//751 -f 670//670 751//751 661//661 -f 661//661 751//751 752//752 -f 661//661 752//752 662//662 -f 662//662 752//752 753//753 -f 662//662 753//753 665//665 -f 665//665 753//753 754//754 -f 665//665 754//754 663//663 -f 663//663 754//754 755//755 -f 663//663 755//755 664//664 -f 664//664 755//755 744//744 -f 446//446 445//445 756//756 -f 756//756 445//445 539//539 -f 539//539 537//537 756//756 -f 756//756 537//537 557//557 -f 756//756 557//557 757//757 -f 557//557 651//651 757//757 -f 757//757 651//651 571//571 -f 757//757 571//571 568//568 -f 568//568 574//574 757//757 -f 757//757 574//574 280//280 -f 757//757 280//280 279//279 -f 758//758 450//450 454//454 -f 454//454 621//621 758//758 -f 758//758 621//621 351//351 -f 758//758 351//351 343//343 -f 343//343 345//345 758//758 -f 758//758 345//345 677//677 -f 758//758 677//677 759//759 -f 759//759 677//677 601//601 -f 759//759 601//601 600//600 -f 600//600 426//426 759//759 -f 759//759 426//426 418//418 -f 759//759 418//418 417//417 -f 760//760 456//456 455//455 -f 455//455 607//607 760//760 -f 760//760 607//607 609//609 -f 760//760 609//609 611//611 -f 611//611 658//658 760//760 -f 760//760 658//658 320//320 -f 760//760 320//320 761//761 -f 761//761 320//320 322//322 -f 322//322 318//318 761//761 -f 761//761 318//318 317//317 -f 761//761 317//317 315//315 -f 619//619 618//618 762//762 -f 762//762 618//618 617//617 -f 617//617 616//616 762//762 -f 762//762 616//616 614//614 -f 762//762 614//614 763//763 -f 763//763 614//614 624//624 -f 624//624 625//625 763//763 -f 763//763 625//625 626//626 -f 763//763 626//626 627//627 -f 627//627 628//628 763//763 -f 763//763 628//628 629//629 -f 763//763 629//629 630//630 -f 764//764 765//765 766//766 -f 767//767 758//758 768//768 -f 768//768 758//758 759//759 -f 759//759 769//769 768//768 -f 768//768 769//769 770//770 -f 768//768 770//770 771//771 -f 763//763 772//772 762//762 -f 762//762 772//772 764//764 -f 762//762 764//764 773//773 -f 774//774 775//775 776//776 -f 777//777 778//778 757//757 -f 757//757 778//778 779//779 -f 757//757 779//779 756//756 -f 780//780 774//774 766//766 -f 766//766 774//774 776//776 -f 766//766 776//776 764//764 -f 764//764 776//776 781//781 -f 764//764 781//781 773//773 -f 774//774 782//782 775//775 -f 775//775 782//782 783//783 -f 775//775 783//783 784//784 -f 757//757 785//785 777//777 -f 777//777 785//785 786//786 -f 777//777 786//786 787//787 -f 787//787 786//786 788//788 -f 787//787 788//788 789//789 -f 779//779 790//790 756//756 -f 756//756 790//790 791//791 -f 756//756 791//791 792//792 -f 792//792 791//791 793//793 -f 792//792 793//793 794//794 -f 794//794 793//793 795//795 -f 794//794 795//795 796//796 -f 767//767 797//797 758//758 -f 758//758 797//797 798//798 -f 758//758 798//798 799//799 -f 796//796 795//795 800//800 -f 800//800 795//795 801//801 -f 800//800 801//801 802//802 -f 802//802 801//801 803//803 -f 802//802 803//803 763//763 -f 763//763 803//803 804//804 -f 763//763 804//804 805//805 -f 806//806 807//807 808//808 -f 808//808 807//807 809//809 -f 788//788 810//810 789//789 -f 789//789 810//810 811//811 -f 789//789 811//811 812//812 -f 812//812 811//811 758//758 -f 812//812 758//758 813//813 -f 813//813 758//758 799//799 -f 813//813 799//799 814//814 -f 815//815 772//772 816//816 -f 816//816 772//772 763//763 -f 816//816 763//763 817//817 -f 817//817 763//763 805//805 -f 818//818 819//819 820//820 -f 784//784 783//783 761//761 -f 761//761 783//783 808//808 -f 761//761 808//808 760//760 -f 760//760 808//808 809//809 -f 760//760 809//809 821//821 -f 821//821 809//809 822//822 -f 821//821 822//822 823//823 -f 824//824 768//768 820//820 -f 820//820 768//768 771//771 -f 820//820 771//771 818//818 -f 818//818 771//771 823//823 -f 818//818 823//823 825//825 -f 825//825 823//823 822//822 -f 406//406 826//826 400//400 -f 400//400 826//826 827//827 -f 400//400 827//827 401//401 -f 401//401 827//827 828//828 -f 401//401 828//828 399//399 -f 399//399 828//828 829//829 -f 396//396 830//830 397//397 -f 397//397 830//830 831//831 -f 397//397 831//831 403//403 -f 403//403 831//831 832//832 -f 403//403 832//832 404//404 -f 404//404 832//832 833//833 -f 399//399 829//829 396//396 -f 396//396 829//829 830//830 -f 431//431 834//834 432//432 -f 432//432 834//834 835//835 -f 432//432 835//835 433//433 -f 433//433 835//835 836//836 -f 433//433 836//836 282//282 -f 282//282 836//836 837//837 -f 834//834 431//431 838//838 -f 838//838 431//431 394//394 -f 838//838 394//394 839//839 -f 839//839 394//394 405//405 -f 839//839 405//405 833//833 -f 833//833 405//405 404//404 -f 282//282 837//837 283//283 -f 283//283 837//837 840//840 -f 289//289 841//841 842//842 -f 289//289 842//842 290//290 -f 290//290 842//842 843//843 -f 290//290 843//843 408//408 -f 408//408 843//843 826//826 -f 408//408 826//826 406//406 -f 523//523 844//844 525//525 -f 525//525 844//844 845//845 -f 525//525 845//845 278//278 -f 278//278 845//845 846//846 -f 278//278 846//846 276//276 -f 276//276 846//846 847//847 -f 276//276 847//847 515//515 -f 515//515 847//847 848//848 -f 515//515 848//848 516//516 -f 516//516 848//848 849//849 -f 516//516 849//849 518//518 -f 518//518 849//849 850//850 -f 518//518 850//850 520//520 -f 520//520 850//850 851//851 -f 520//520 851//851 513//513 -f 513//513 851//851 852//852 -f 513//513 852//852 514//514 -f 514//514 852//852 853//853 -f 514//514 853//853 534//534 -f 534//534 853//853 854//854 -f 534//534 854//854 528//528 -f 528//528 854//854 855//855 -f 528//528 855//855 529//529 -f 529//529 855//855 856//856 -f 529//529 856//856 533//533 -f 533//533 856//856 857//857 -f 533//533 857//857 530//530 -f 530//530 857//857 858//858 -f 530//530 858//858 531//531 -f 531//531 858//858 859//859 -f 531//531 859//859 553//553 -f 553//553 859//859 860//860 -f 553//553 860//860 522//522 -f 522//522 860//860 861//861 -f 522//522 861//861 523//523 -f 523//523 861//861 844//844 -f 862//862 863//863 864//864 -f 865//865 866//866 867//867 -f 204//204 202//202 868//868 -f 869//869 870//870 871//871 -f 872//872 873//873 874//874 -f 875//875 876//876 877//877 -f 878//878 879//879 880//880 -f 880//880 881//881 878//878 -f 878//878 881//881 882//882 -f 878//878 882//882 883//883 -f 884//884 885//885 886//886 -f 885//885 887//887 886//886 -f 886//886 887//887 888//888 -f 886//886 888//888 889//889 -f 889//889 888//888 890//890 -f 889//889 890//890 875//875 -f 891//891 892//892 893//893 -f 893//893 892//892 894//894 -f 893//893 894//894 895//895 -f 895//895 894//894 896//896 -f 895//895 896//896 897//897 -f 897//897 896//896 898//898 -f 897//897 898//898 899//899 -f 899//899 898//898 900//900 -f 899//899 900//900 901//901 -f 901//901 900//900 902//902 -f 903//903 904//904 905//905 -f 904//904 906//906 905//905 -f 905//905 906//906 907//907 -f 905//905 907//907 908//908 -f 909//909 910//910 911//911 -f 911//911 910//910 912//912 -f 911//911 913//913 914//914 -f 915//915 916//916 912//912 -f 912//912 916//916 917//917 -f 912//912 917//917 911//911 -f 911//911 917//917 918//918 -f 911//911 918//918 913//913 -f 919//919 911//911 920//920 -f 920//920 911//911 914//914 -f 920//920 914//914 921//921 -f 921//921 914//914 922//922 -f 921//921 922//922 923//923 -f 924//924 925//925 926//926 -f 926//926 925//925 927//927 -f 926//926 927//927 928//928 -f 927//927 929//929 928//928 -f 928//928 929//929 930//930 -f 928//928 930//930 931//931 -f 931//931 932//932 928//928 -f 928//928 932//932 933//933 -f 928//928 933//933 871//871 -f 871//871 933//933 934//934 -f 871//871 934//934 869//869 -f 931//931 935//935 932//932 -f 932//932 935//935 936//936 -f 932//932 936//936 937//937 -f 937//937 936//936 938//938 -f 937//937 938//938 939//939 -f 939//939 938//938 940//940 -f 939//939 940//940 941//941 -f 941//941 940//940 942//942 -f 941//941 942//942 926//926 -f 926//926 942//942 943//943 -f 926//926 943//943 924//924 -f 944//944 945//945 946//946 -f 947//947 948//948 949//949 -f 949//949 950//950 947//947 -f 947//947 950//950 951//951 -f 947//947 951//951 952//952 -f 953//953 954//954 955//955 -f 945//945 944//944 955//955 -f 955//955 944//944 956//956 -f 955//955 956//956 953//953 -f 946//946 957//957 944//944 -f 944//944 957//957 958//958 -f 944//944 958//958 959//959 -f 959//959 958//958 960//960 -f 959//959 960//960 948//948 -f 948//948 960//960 961//961 -f 948//948 961//961 949//949 -f 959//959 962//962 963//963 -f 963//963 964//964 959//959 -f 959//959 964//964 965//965 -f 959//959 965//965 944//944 -f 966//966 967//967 968//968 -f 968//968 967//967 969//969 -f 968//968 969//969 970//970 -f 969//969 971//971 970//970 -f 970//970 971//971 972//972 -f 970//970 972//972 879//879 -f 879//879 972//972 973//973 -f 879//879 973//973 974//974 -f 974//974 975//975 879//879 -f 879//879 975//975 976//976 -f 879//879 976//976 977//977 -f 977//977 976//976 978//978 -f 977//977 978//978 979//979 -f 978//978 980//980 979//979 -f 979//979 980//980 981//981 -f 979//979 981//981 982//982 -f 200//200 198//198 983//983 -f 983//983 198//198 196//196 -f 983//983 196//196 984//984 -f 984//984 196//196 194//194 -f 984//984 194//194 216//216 -f 216//216 214//214 984//984 -f 984//984 214//214 212//212 -f 984//984 212//212 985//985 -f 985//985 212//212 210//210 -f 985//985 210//210 986//986 -f 210//210 208//208 986//986 -f 986//986 208//208 206//206 -f 986//986 206//206 987//987 -f 988//988 168//168 166//166 -f 158//158 989//989 160//160 -f 160//160 989//989 990//990 -f 160//160 990//990 162//162 -f 162//162 990//990 164//164 -f 158//158 156//156 989//989 -f 989//989 156//156 154//154 -f 989//989 154//154 892//892 -f 892//892 154//154 152//152 -f 892//892 152//152 894//894 -f 894//894 152//152 150//150 -f 894//894 150//150 991//991 -f 991//991 150//150 148//148 -f 991//991 148//148 146//146 -f 992//992 993//993 994//994 -f 995//995 996//996 994//994 -f 996//996 997//997 994//994 -f 994//994 997//997 998//998 -f 994//994 998//998 992//992 -f 999//999 1000//1000 1001//1001 -f 1001//1001 1000//1000 1002//1002 -f 992//992 1003//1003 993//993 -f 993//993 1003//1003 1004//1004 -f 993//993 1004//1004 900//900 -f 900//900 1004//1004 1005//1005 -f 900//900 1005//1005 902//902 -f 902//902 1005//1005 1006//1006 -f 902//902 1006//1006 999//999 -f 999//999 1006//1006 1007//1007 -f 999//999 1007//1007 1000//1000 -f 1008//1008 1009//1009 867//867 -f 867//867 1009//1009 1010//1010 -f 1011//1011 1012//1012 1013//1013 -f 1013//1013 1012//1012 1014//1014 -f 1013//1013 1014//1014 1015//1015 -f 1016//1016 1017//1017 1018//1018 -f 1019//1019 1020//1020 1021//1021 -f 1019//1019 1021//1021 1022//1022 -f 1015//1015 1014//1014 1023//1023 -f 1023//1023 1014//1014 1024//1024 -f 1023//1023 1024//1024 1020//1020 -f 1025//1025 1026//1026 1027//1027 -f 910//910 1028//1028 1029//1029 -f 1029//1029 1030//1030 910//910 -f 910//910 1030//1030 1031//1031 -f 910//910 1031//1031 912//912 -f 912//912 1031//1031 1032//1032 -f 912//912 1032//1032 1033//1033 -f 1034//1034 1035//1035 1036//1036 -f 1036//1036 1035//1035 1037//1037 -f 1036//1036 1037//1037 1038//1038 -f 1038//1038 1037//1037 1039//1039 -f 1038//1038 1039//1039 1028//1028 -f 1028//1028 1039//1039 1040//1040 -f 1028//1028 1040//1040 1029//1029 -f 724//724 723//723 926//926 -f 926//926 723//723 722//722 -f 926//926 722//722 941//941 -f 941//941 722//722 721//721 -f 941//941 721//721 1041//1041 -f 1041//1041 721//721 720//720 -f 1041//1041 720//720 1042//1042 -f 1042//1042 720//720 731//731 -f 1043//1043 726//726 1044//1044 -f 1044//1044 726//726 725//725 -f 728//728 727//727 1045//1045 -f 728//728 1045//1045 729//729 -f 690//690 689//689 1046//1046 -f 693//693 692//692 1047//1047 -f 1047//1047 692//692 691//691 -f 1047//1047 691//691 1048//1048 -f 694//694 947//947 953//953 -f 953//953 947//947 952//952 -f 953//953 952//952 954//954 -f 687//687 686//686 1049//1049 -f 1049//1049 686//686 685//685 -f 1049//1049 685//685 1050//1050 -f 1050//1050 685//685 684//684 -f 1050//1050 684//684 953//953 -f 953//953 684//684 695//695 -f 953//953 695//695 694//694 -f 1051//1051 1052//1052 1053//1053 -f 1053//1053 1052//1052 1054//1054 -f 741//741 740//740 1055//1055 -f 732//732 743//743 1056//1056 -f 1056//1056 743//743 742//742 -f 1057//1057 736//736 735//735 -f 740//740 739//739 1055//1055 -f 1055//1055 739//739 738//738 -f 1055//1055 738//738 1057//1057 -f 1057//1057 738//738 737//737 -f 1057//1057 737//737 736//736 -f 732//732 1056//1056 733//733 -f 733//733 1056//1056 1051//1051 -f 733//733 1051//1051 734//734 -f 1058//1058 1059//1059 1060//1060 -f 742//742 741//741 1056//1056 -f 1056//1056 741//741 1055//1055 -f 1056//1056 1055//1055 1061//1061 -f 1061//1061 1055//1055 1062//1062 -f 1061//1061 1062//1062 1063//1063 -f 1063//1063 1062//1062 1064//1064 -f 1063//1063 1064//1064 1060//1060 -f 1060//1060 1064//1064 1065//1065 -f 1060//1060 1065//1065 1058//1058 -f 713//713 712//712 1066//1066 -f 1067//1067 708//708 1068//1068 -f 1068//1068 708//708 719//719 -f 1068//1068 719//719 718//718 -f 711//711 710//710 1067//1067 -f 1067//1067 710//710 709//709 -f 1067//1067 709//709 708//708 -f 717//717 716//716 1069//1069 -f 1069//1069 716//716 715//715 -f 1069//1069 715//715 1066//1066 -f 1066//1066 715//715 714//714 -f 1066//1066 714//714 713//713 -f 1068//1068 864//864 1070//1070 -f 1070//1070 864//864 863//863 -f 1070//1070 863//863 1071//1071 -f 1071//1071 863//863 1072//1072 -f 1073//1073 1074//1074 1075//1075 -f 1059//1059 1058//1058 1076//1076 -f 1076//1076 1058//1058 1077//1077 -f 1076//1076 1077//1077 1078//1078 -f 1075//1075 1074//1074 1079//1079 -f 1079//1079 1074//1074 1080//1080 -f 1079//1079 1080//1080 1078//1078 -f 1078//1078 1080//1080 1081//1081 -f 1078//1078 1081//1081 1076//1076 -f 712//712 711//711 1066//1066 -f 1066//1066 711//711 1067//1067 -f 1066//1066 1067//1067 1082//1082 -f 1082//1082 1067//1067 1083//1083 -f 1082//1082 1083//1083 1065//1065 -f 1065//1065 1083//1083 1084//1084 -f 1065//1065 1084//1084 1058//1058 -f 1058//1058 1084//1084 1085//1085 -f 1058//1058 1085//1085 1077//1077 -f 846//846 1045//1045 1043//1043 -f 1043//1043 1045//1045 727//727 -f 1043//1043 727//727 726//726 -f 849//849 1086//1086 850//850 -f 850//850 1086//1086 851//851 -f 848//848 847//847 1087//1087 -f 855//855 854//854 1088//1088 -f 1088//1088 854//854 1089//1089 -f 861//861 860//860 1090//1090 -f 1090//1090 860//860 859//859 -f 858//858 857//857 1091//1091 -f 1091//1091 857//857 856//856 -f 846//846 845//845 1045//1045 -f 1045//1045 845//845 844//844 -f 1045//1045 844//844 1046//1046 -f 1046//1046 844//844 1048//1048 -f 1046//1046 1048//1048 690//690 -f 690//690 1048//1048 691//691 -f 1092//1092 842//842 841//841 -f 1093//1093 832//832 831//831 -f 842//842 1092//1092 843//843 -f 843//843 1092//1092 1094//1094 -f 843//843 1094//1094 826//826 -f 826//826 1094//1094 1095//1095 -f 826//826 1095//1095 827//827 -f 830//830 829//829 1095//1095 -f 1095//1095 829//829 828//828 -f 1095//1095 828//828 827//827 -f 1096//1096 840//840 1097//1097 -f 1097//1097 840//840 837//837 -f 1097//1097 837//837 836//836 -f 836//836 835//835 1097//1097 -f 1097//1097 835//835 834//834 -f 1097//1097 834//834 1098//1098 -f 1098//1098 834//834 838//838 -f 1098//1098 838//838 1099//1099 -f 1099//1099 838//838 839//839 -f 1099//1099 839//839 1093//1093 -f 1093//1093 839//839 833//833 -f 1093//1093 833//833 832//832 -f 905//905 1100//1100 1101//1101 -f 1101//1101 1100//1100 1102//1102 -f 1101//1101 1102//1102 1021//1021 -f 1021//1021 1102//1102 1103//1103 -f 1021//1021 1103//1103 1097//1097 -f 1097//1097 1103//1103 1104//1104 -f 1097//1097 1104//1104 1096//1096 -f 1105//1105 1106//1106 993//993 -f 1106//1106 1107//1107 993//993 -f 993//993 1107//1107 1108//1108 -f 993//993 1108//1108 994//994 -f 994//994 1108//1108 1109//1109 -f 994//994 1109//1109 905//905 -f 905//905 1109//1109 1110//1110 -f 905//905 1110//1110 1100//1100 -f 1111//1111 1112//1112 1113//1113 -f 1114//1114 1115//1115 1116//1116 -f 1116//1116 1115//1115 987//987 -f 1116//1116 987//987 1117//1117 -f 1117//1117 987//987 1113//1113 -f 1117//1117 1113//1113 1118//1118 -f 1118//1118 1113//1113 1112//1112 -f 1111//1111 1113//1113 1119//1119 -f 1119//1119 1113//1113 1120//1120 -f 1119//1119 1120//1120 1121//1121 -f 1121//1121 1120//1120 1122//1122 -f 1121//1121 1122//1122 1123//1123 -f 1123//1123 1122//1122 1124//1124 -f 1123//1123 1124//1124 1125//1125 -f 1126//1126 1127//1127 1128//1128 -f 1128//1128 1127//1127 1129//1129 -f 1128//1128 1129//1129 1130//1130 -f 1131//1131 1132//1132 1124//1124 -f 1124//1124 1132//1132 1133//1133 -f 1124//1124 1133//1133 1125//1125 -f 1134//1134 1135//1135 1126//1126 -f 1126//1126 1135//1135 1136//1136 -f 1126//1126 1136//1136 1127//1127 -f 1137//1137 1135//1135 1138//1138 -f 1138//1138 1135//1135 1134//1134 -f 1138//1138 1134//1134 1139//1139 -f 1140//1140 991//991 988//988 -f 988//988 991//991 146//146 -f 988//988 146//146 168//168 -f 986//986 218//218 240//240 -f 230//230 228//228 1141//1141 -f 218//218 986//986 220//220 -f 220//220 986//986 987//987 -f 220//220 987//987 222//222 -f 222//222 987//987 224//224 -f 224//224 987//987 1115//1115 -f 224//224 1115//1115 226//226 -f 240//240 238//238 986//986 -f 986//986 238//238 236//236 -f 986//986 236//236 1142//1142 -f 1142//1142 236//236 234//234 -f 1142//1142 234//234 232//232 -f 232//232 230//230 1142//1142 -f 1142//1142 230//230 1141//1141 -f 1142//1142 1141//1141 889//889 -f 889//889 1141//1141 1143//1143 -f 889//889 1143//1143 886//886 -f 886//886 1143//1143 1144//1144 -f 886//886 1144//1144 988//988 -f 988//988 1144//1144 1145//1145 -f 988//988 1145//1145 1140//1140 -f 1115//1115 1146//1146 226//226 -f 226//226 1146//1146 1147//1147 -f 226//226 1147//1147 228//228 -f 228//228 1147//1147 1148//1148 -f 228//228 1148//1148 1141//1141 -f 1149//1149 1150//1150 1151//1151 -f 1151//1151 1150//1150 1152//1152 -f 1151//1151 1152//1152 915//915 -f 915//915 1152//1152 1153//1153 -f 915//915 1153//1153 916//916 -f 1154//1154 1155//1155 1156//1156 -f 1156//1156 1155//1155 1157//1157 -f 1156//1156 1157//1157 1158//1158 -f 923//923 922//922 1159//1159 -f 1159//1159 922//922 1160//1160 -f 1159//1159 1160//1160 1158//1158 -f 1158//1158 1160//1160 1161//1161 -f 1158//1158 1161//1161 1156//1156 -f 882//882 1162//1162 883//883 -f 883//883 1162//1162 1163//1163 -f 883//883 1163//1163 1164//1164 -f 1164//1164 1163//1163 1165//1165 -f 1164//1164 1165//1165 1166//1166 -f 1166//1166 1165//1165 1167//1167 -f 1167//1167 1165//1165 1168//1168 -f 1167//1167 1168//1168 1169//1169 -f 1169//1169 1168//1168 1170//1170 -f 1169//1169 1170//1170 1171//1171 -f 1171//1171 1170//1170 1172//1172 -f 1171//1171 1172//1172 1173//1173 -f 970//970 1174//1174 1175//1175 -f 878//878 1176//1176 879//879 -f 879//879 1176//1176 1177//1177 -f 879//879 1177//1177 970//970 -f 970//970 1177//1177 1178//1178 -f 970//970 1178//1178 1174//1174 -f 1179//1179 1180//1180 867//867 -f 867//867 1180//1180 1012//1012 -f 867//867 1012//1012 1008//1008 -f 1008//1008 1012//1012 1011//1011 -f 1180//1180 1181//1181 1012//1012 -f 1012//1012 1181//1181 1182//1182 -f 1012//1012 1182//1182 1183//1183 -f 1183//1183 1182//1182 1184//1184 -f 1183//1183 1184//1184 1185//1185 -f 1185//1185 1186//1186 1183//1183 -f 1183//1183 1186//1186 1187//1187 -f 1183//1183 1187//1187 866//866 -f 866//866 1187//1187 1188//1188 -f 1188//1188 1189//1189 866//866 -f 866//866 1189//1189 1190//1190 -f 866//866 1190//1190 867//867 -f 867//867 1190//1190 1191//1191 -f 867//867 1191//1191 1179//1179 -f 1021//1021 1192//1192 1193//1193 -f 1101//1101 1194//1194 1195//1195 -f 1020//1020 1024//1024 1021//1021 -f 1021//1021 1024//1024 1196//1196 -f 1021//1021 1196//1196 1192//1192 -f 1193//1193 1197//1197 1021//1021 -f 1021//1021 1197//1197 1198//1198 -f 1021//1021 1198//1198 1101//1101 -f 1101//1101 1198//1198 1199//1199 -f 1101//1101 1199//1199 1194//1194 -f 1200//1200 1201//1201 1202//1202 -f 1202//1202 1201//1201 1203//1203 -f 1202//1202 1203//1203 1024//1024 -f 1024//1024 1203//1203 1204//1204 -f 1024//1024 1204//1204 1196//1196 -f 903//903 905//905 1205//1205 -f 1205//1205 905//905 1101//1101 -f 1205//1205 1101//1101 1202//1202 -f 1202//1202 1101//1101 1195//1195 -f 1202//1202 1195//1195 1200//1200 -f 1038//1038 1183//1183 1036//1036 -f 1036//1036 1183//1183 866//866 -f 1036//1036 866//866 1206//1206 -f 1206//1206 866//866 865//865 -f 867//867 1053//1053 865//865 -f 865//865 1053//1053 1054//1054 -f 865//865 1054//1054 1206//1206 -f 1206//1206 1054//1054 1207//1207 -f 1206//1206 1207//1207 1208//1208 -f 1208//1208 1207//1207 1209//1209 -f 1208//1208 1209//1209 1210//1210 -f 1210//1210 1209//1209 1211//1211 -f 1210//1210 1211//1211 1212//1212 -f 1212//1212 1211//1211 1213//1213 -f 1212//1212 1213//1213 1081//1081 -f 1081//1081 1213//1213 1214//1214 -f 1081//1081 1214//1214 1076//1076 -f 1076//1076 1214//1214 1215//1215 -f 1076//1076 1215//1215 1059//1059 -f 1010//1010 1016//1016 867//867 -f 867//867 1016//1016 1018//1018 -f 867//867 1018//1018 1053//1053 -f 1053//1053 1018//1018 1057//1057 -f 1053//1053 1057//1057 1051//1051 -f 1051//1051 1057//1057 735//735 -f 1051//1051 735//735 734//734 -f 908//908 872//872 905//905 -f 905//905 872//872 874//874 -f 905//905 874//874 994//994 -f 994//994 874//874 1001//1001 -f 994//994 1001//1001 995//995 -f 995//995 1001//1001 1002//1002 -f 870//870 1216//1216 871//871 -f 871//871 1216//1216 1217//1217 -f 871//871 1217//1217 928//928 -f 928//928 1217//1217 1218//1218 -f 928//928 1218//1218 926//926 -f 926//926 1218//1218 1044//1044 -f 926//926 1044//1044 724//724 -f 724//724 1044//1044 725//725 -f 755//755 754//754 1151//1151 -f 748//748 747//747 1219//1219 -f 1219//1219 747//747 915//915 -f 1219//1219 915//915 1027//1027 -f 1027//1027 915//915 912//912 -f 1027//1027 912//912 1025//1025 -f 1025//1025 912//912 1033//1033 -f 747//747 746//746 915//915 -f 915//915 746//746 745//745 -f 915//915 745//745 1151//1151 -f 1151//1151 745//745 744//744 -f 1151//1151 744//744 755//755 -f 1220//1220 753//753 752//752 -f 752//752 751//751 1220//1220 -f 1220//1220 751//751 750//750 -f 1220//1220 750//750 1219//1219 -f 1219//1219 750//750 749//749 -f 1219//1219 749//749 748//748 -f 1216//1216 1159//1159 1217//1217 -f 1217//1217 1159//1159 1158//1158 -f 1217//1217 1158//1158 1218//1218 -f 1218//1218 1158//1158 1157//1157 -f 1218//1218 1157//1157 1044//1044 -f 1044//1044 1157//1157 1155//1155 -f 1044//1044 1155//1155 1043//1043 -f 1043//1043 1155//1155 1087//1087 -f 1043//1043 1087//1087 846//846 -f 846//846 1087//1087 847//847 -f 1154//1154 1149//1149 1155//1155 -f 1155//1155 1149//1149 1151//1151 -f 1155//1155 1151//1151 1087//1087 -f 1087//1087 1151//1151 1086//1086 -f 1087//1087 1086//1086 848//848 -f 848//848 1086//1086 849//849 -f 754//754 753//753 1151//1151 -f 1151//1151 753//753 1220//1220 -f 1151//1151 1220//1220 1086//1086 -f 1086//1086 1220//1220 1221//1221 -f 1086//1086 1221//1221 851//851 -f 851//851 1221//1221 1222//1222 -f 851//851 1222//1222 852//852 -f 852//852 1222//1222 1089//1089 -f 852//852 1089//1089 853//853 -f 853//853 1089//1089 854//854 -f 731//731 730//730 1042//1042 -f 1042//1042 730//730 1223//1223 -f 1042//1042 1223//1223 1049//1049 -f 1049//1049 1223//1223 1224//1224 -f 1049//1049 1224//1224 687//687 -f 687//687 1224//1224 688//688 -f 730//730 729//729 1223//1223 -f 1223//1223 729//729 1045//1045 -f 1223//1223 1045//1045 1224//1224 -f 1224//1224 1045//1045 1046//1046 -f 1224//1224 1046//1046 688//688 -f 688//688 1046//1046 689//689 -f 831//831 830//830 1093//1093 -f 1093//1093 830//830 1095//1095 -f 1093//1093 1095//1095 1124//1124 -f 1124//1124 1095//1095 1128//1128 -f 1124//1124 1128//1128 1131//1131 -f 1131//1131 1128//1128 1130//1130 -f 859//859 858//858 1090//1090 -f 1090//1090 858//858 1091//1091 -f 1090//1090 1091//1091 1172//1172 -f 1172//1172 1091//1091 1225//1225 -f 841//841 1105//1105 1092//1092 -f 1092//1092 1105//1105 993//993 -f 1092//1092 993//993 1094//1094 -f 1094//1094 993//993 900//900 -f 1094//1094 900//900 1095//1095 -f 1095//1095 900//900 898//898 -f 1095//1095 898//898 1128//1128 -f 1128//1128 898//898 896//896 -f 1128//1128 896//896 1126//1126 -f 1126//1126 896//896 894//894 -f 1126//1126 894//894 1134//1134 -f 1134//1134 894//894 991//991 -f 1134//1134 991//991 1139//1139 -f 1139//1139 991//991 1140//1140 -f 1226//1226 706//706 1227//1227 -f 1227//1227 706//706 705//705 -f 1227//1227 705//705 704//704 -f 699//699 698//698 1225//1225 -f 704//704 703//703 1227//1227 -f 1227//1227 703//703 702//702 -f 1227//1227 702//702 1228//1228 -f 1228//1228 702//702 701//701 -f 1228//1228 701//701 700//700 -f 700//700 699//699 1228//1228 -f 1228//1228 699//699 1225//1225 -f 1228//1228 1225//1225 1088//1088 -f 1088//1088 1225//1225 1091//1091 -f 1088//1088 1091//1091 855//855 -f 855//855 1091//1091 856//856 -f 698//698 697//697 1225//1225 -f 1225//1225 697//697 696//696 -f 1225//1225 696//696 1226//1226 -f 1226//1226 696//696 707//707 -f 1226//1226 707//707 706//706 -f 694//694 693//693 947//947 -f 947//947 693//693 1047//1047 -f 947//947 1047//1047 948//948 -f 948//948 1047//1047 1229//1229 -f 948//948 1229//1229 959//959 -f 959//959 1229//1229 1230//1230 -f 959//959 1230//1230 962//962 -f 962//962 1230//1230 1231//1231 -f 1173//1173 1172//1172 1232//1232 -f 1232//1232 1172//1172 1225//1225 -f 1232//1232 1225//1225 1175//1175 -f 1175//1175 1225//1225 1226//1226 -f 1175//1175 1226//1226 970//970 -f 970//970 1226//1226 1227//1227 -f 970//970 1227//1227 968//968 -f 1026//1026 1034//1034 1027//1027 -f 1027//1027 1034//1034 1036//1036 -f 1027//1027 1036//1036 1219//1219 -f 1219//1219 1036//1036 1206//1206 -f 1219//1219 1206//1206 1220//1220 -f 1220//1220 1206//1206 1208//1208 -f 1220//1220 1208//1208 1221//1221 -f 1221//1221 1208//1208 1210//1210 -f 1221//1221 1210//1210 1222//1222 -f 1222//1222 1210//1210 1212//1212 -f 1222//1222 1212//1212 1089//1089 -f 1089//1089 1212//1212 1081//1081 -f 1089//1089 1081//1081 1088//1088 -f 1088//1088 1081//1081 1080//1080 -f 1088//1088 1080//1080 1228//1228 -f 1228//1228 1080//1080 1074//1074 -f 1228//1228 1074//1074 1227//1227 -f 1227//1227 1074//1074 1073//1073 -f 1227//1227 1073//1073 968//968 -f 968//968 1073//1073 982//982 -f 968//968 982//982 966//966 -f 966//966 982//982 981//981 -f 202//202 200//200 868//868 -f 868//868 200//200 983//983 -f 868//868 983//983 1069//1069 -f 1017//1017 1022//1022 1018//1018 -f 1018//1018 1022//1022 1021//1021 -f 1018//1018 1021//1021 1057//1057 -f 1057//1057 1021//1021 1097//1097 -f 1057//1057 1097//1097 1055//1055 -f 1055//1055 1097//1097 1098//1098 -f 1055//1055 1098//1098 1062//1062 -f 1062//1062 1098//1098 1099//1099 -f 1062//1062 1099//1099 1064//1064 -f 1064//1064 1099//1099 1093//1093 -f 1064//1064 1093//1093 1065//1065 -f 1065//1065 1093//1093 1124//1124 -f 1065//1065 1124//1124 1082//1082 -f 1082//1082 1124//1124 1122//1122 -f 1082//1082 1122//1122 1066//1066 -f 1066//1066 1122//1122 1120//1120 -f 1066//1066 1120//1120 1069//1069 -f 1069//1069 1120//1120 1113//1113 -f 1069//1069 1113//1113 868//868 -f 868//868 1113//1113 987//987 -f 868//868 987//987 204//204 -f 204//204 987//987 206//206 -f 166//166 164//164 988//988 -f 988//988 164//164 990//990 -f 988//988 990//990 886//886 -f 886//886 990//990 1233//1233 -f 886//886 1233//1233 884//884 -f 844//844 861//861 1048//1048 -f 1048//1048 861//861 1090//1090 -f 1048//1048 1090//1090 1047//1047 -f 1047//1047 1090//1090 1172//1172 -f 1047//1047 1172//1172 1229//1229 -f 1229//1229 1172//1172 1170//1170 -f 1229//1229 1170//1170 1230//1230 -f 1230//1230 1170//1170 1168//1168 -f 1230//1230 1168//1168 1231//1231 -f 1231//1231 1168//1168 1165//1165 -f 1075//1075 1072//1072 1073//1073 -f 1073//1073 1072//1072 863//863 -f 1073//1073 863//863 982//982 -f 982//982 863//863 862//862 -f 982//982 862//862 979//979 -f 979//979 862//862 1234//1234 -f 983//983 180//180 178//178 -f 862//862 176//176 174//174 -f 718//718 717//717 1068//1068 -f 1068//1068 717//717 1069//1069 -f 1068//1068 1069//1069 864//864 -f 864//864 1069//1069 983//983 -f 864//864 983//983 862//862 -f 862//862 983//983 178//178 -f 862//862 178//178 176//176 -f 180//180 983//983 182//182 -f 182//182 983//983 984//984 -f 182//182 984//984 184//184 -f 174//174 172//172 862//862 -f 862//862 172//172 170//170 -f 862//862 170//170 1234//1234 -f 1234//1234 170//170 192//192 -f 192//192 190//190 1234//1234 -f 1234//1234 190//190 188//188 -f 1234//1234 188//188 984//984 -f 984//984 188//188 186//186 -f 984//984 186//186 184//184 -f 875//875 877//877 889//889 -f 889//889 877//877 1235//1235 -f 889//889 1235//1235 1142//1142 -f 1142//1142 1235//1235 1236//1236 -f 1142//1142 1236//1236 986//986 -f 986//986 1236//1236 1237//1237 -f 986//986 1237//1237 985//985 -f 985//985 1237//1237 1238//1238 -f 985//985 1238//1238 984//984 -f 984//984 1238//1238 1239//1239 -f 984//984 1239//1239 1234//1234 -f 1234//1234 1239//1239 1240//1240 -f 1234//1234 1240//1240 979//979 -f 979//979 1240//1240 1241//1241 -f 979//979 1241//1241 977//977 -f 977//977 1241//1241 1242//1242 -f 977//977 1242//1242 879//879 -f 879//879 1242//1242 1243//1243 -f 879//879 1243//1243 880//880 -f 475//475 1116//1116 476//476 -f 476//476 1116//1116 1117//1117 -f 476//476 1117//1117 478//478 -f 478//478 1117//1117 1118//1118 -f 478//478 1118//1118 479//479 -f 479//479 1118//1118 1112//1112 -f 479//479 1112//1112 473//473 -f 473//473 1112//1112 1111//1111 -f 461//461 1123//1123 466//466 -f 466//466 1123//1123 1125//1125 -f 466//466 1125//1125 467//467 -f 467//467 1125//1125 1133//1133 -f 467//467 1133//1133 468//468 -f 468//468 1133//1133 1132//1132 -f 474//474 473//473 1111//1111 -f 1123//1123 461//461 1121//1121 -f 1121//1121 461//461 474//474 -f 1121//1121 474//474 1119//1119 -f 1119//1119 474//474 1111//1111 -f 464//464 1131//1131 465//465 -f 465//465 1131//1131 1130//1130 -f 465//465 1130//1130 471//471 -f 471//471 1130//1130 1129//1129 -f 471//471 1129//1129 470//470 -f 470//470 1129//1129 1127//1127 -f 468//468 1132//1132 464//464 -f 464//464 1132//1132 1131//1131 -f 1137//1137 491//491 1135//1135 -f 1135//1135 491//491 469//469 -f 1135//1135 469//469 1136//1136 -f 1136//1136 469//469 470//470 -f 1136//1136 470//470 1127//1127 -f 1116//1116 475//475 1114//1114 -f 1114//1114 475//475 487//487 -f 491//491 1137//1137 490//490 -f 490//490 1137//1137 1138//1138 -f 490//490 1138//1138 489//489 -f 489//489 1138//1138 1139//1139 -f 489//489 1139//1139 488//488 -f 488//488 1139//1139 1140//1140 -f 488//488 1140//1140 313//313 -f 313//313 1140//1140 1145//1145 -f 313//313 1145//1145 312//312 -f 312//312 1145//1145 1144//1144 -f 312//312 1144//1144 311//311 -f 311//311 1144//1144 1143//1143 -f 311//311 1143//1143 309//309 -f 309//309 1143//1143 1141//1141 -f 309//309 1141//1141 482//482 -f 482//482 1141//1141 1148//1148 -f 482//482 1148//1148 484//484 -f 484//484 1148//1148 1147//1147 -f 484//484 1147//1147 485//485 -f 485//485 1147//1147 1146//1146 -f 485//485 1146//1146 486//486 -f 486//486 1146//1146 1115//1115 -f 486//486 1115//1115 487//487 -f 487//487 1115//1115 1114//1114 -f 283//283 840//840 284//284 -f 284//284 840//840 1096//1096 -f 1110//1110 416//416 1100//1100 -f 1100//1100 416//416 424//424 -f 1100//1100 424//424 1102//1102 -f 1102//1102 424//424 425//425 -f 1102//1102 425//425 1103//1103 -f 1103//1103 425//425 429//429 -f 1103//1103 429//429 1104//1104 -f 1104//1104 429//429 430//430 -f 1104//1104 430//430 1096//1096 -f 1096//1096 430//430 434//434 -f 1096//1096 434//434 284//284 -f 841//841 289//289 1105//1105 -f 1105//1105 289//289 288//288 -f 1105//1105 288//288 1106//1106 -f 1106//1106 288//288 410//410 -f 1106//1106 410//410 1107//1107 -f 1107//1107 410//410 413//413 -f 1107//1107 413//413 1108//1108 -f 1108//1108 413//413 412//412 -f 1108//1108 412//412 1109//1109 -f 1109//1109 412//412 411//411 -f 1109//1109 411//411 1110//1110 -f 1110//1110 411//411 415//415 -f 1110//1110 415//415 416//416 -f 538//538 945//945 536//536 -f 536//536 945//945 955//955 -f 536//536 955//955 541//541 -f 541//541 955//955 954//954 -f 541//541 954//954 542//542 -f 542//542 954//954 952//952 -f 542//542 952//952 543//543 -f 543//543 952//952 951//951 -f 543//543 951//951 544//544 -f 544//544 951//951 950//950 -f 544//544 950//950 273//273 -f 273//273 950//950 949//949 -f 273//273 949//949 274//274 -f 274//274 949//949 961//961 -f 274//274 961//961 547//547 -f 547//547 961//961 960//960 -f 547//547 960//960 546//546 -f 546//546 960//960 958//958 -f 546//546 958//958 545//545 -f 545//545 958//958 957//957 -f 545//545 957//957 540//540 -f 540//540 957//957 946//946 -f 540//540 946//946 538//538 -f 538//538 946//946 945//945 -f 582//582 938//938 583//583 -f 583//583 938//938 936//936 -f 583//583 936//936 584//584 -f 584//584 936//936 935//935 -f 584//584 935//935 585//585 -f 585//585 935//935 931//931 -f 585//585 931//931 586//586 -f 586//586 931//931 930//930 -f 586//586 930//930 587//587 -f 587//587 930//930 929//929 -f 587//587 929//929 577//577 -f 577//577 929//929 927//927 -f 577//577 927//927 578//578 -f 578//578 927//927 925//925 -f 578//578 925//925 579//579 -f 579//579 925//925 924//924 -f 579//579 924//924 580//580 -f 580//580 924//924 943//943 -f 580//580 943//943 581//581 -f 581//581 943//943 942//942 -f 581//581 942//942 575//575 -f 575//575 942//942 940//940 -f 575//575 940//940 582//582 -f 582//582 940//940 938//938 -f 634//634 494//494 1072//1072 -f 1078//1078 635//635 1079//1079 -f 1079//1079 635//635 634//634 -f 1079//1079 634//634 1075//1075 -f 1075//1075 634//634 1072//1072 -f 1072//1072 494//494 1071//1071 -f 1071//1071 494//494 493//493 -f 1071//1071 493//493 1070//1070 -f 1070//1070 493//493 495//495 -f 1070//1070 495//495 1068//1068 -f 1068//1068 495//495 500//500 -f 501//501 511//511 1084//1084 -f 1068//1068 500//500 1067//1067 -f 1067//1067 500//500 501//501 -f 1067//1067 501//501 1083//1083 -f 1083//1083 501//501 1084//1084 -f 1084//1084 511//511 1085//1085 -f 1085//1085 511//511 637//637 -f 1085//1085 637//637 1077//1077 -f 1077//1077 637//637 636//636 -f 1077//1077 636//636 1078//1078 -f 1078//1078 636//636 635//635 -f 383//383 1214//1214 382//382 -f 382//382 1214//1214 1213//1213 -f 382//382 1213//1213 380//380 -f 380//380 1213//1213 1211//1211 -f 380//380 1211//1211 378//378 -f 378//378 1211//1211 1209//1209 -f 378//378 1209//1209 375//375 -f 375//375 1209//1209 1207//1207 -f 1214//1214 383//383 1215//1215 -f 1215//1215 383//383 385//385 -f 1215//1215 385//385 1059//1059 -f 1059//1059 385//385 293//293 -f 1059//1059 293//293 1060//1060 -f 1060//1060 293//293 387//387 -f 1063//1063 1060//1060 387//387 -f 365//365 358//358 1051//1051 -f 1051//1051 1056//1056 365//365 -f 365//365 1056//1056 1061//1061 -f 365//365 1061//1061 391//391 -f 391//391 1061//1061 1063//1063 -f 391//391 1063//1063 386//386 -f 386//386 1063//1063 387//387 -f 1051//1051 358//358 1052//1052 -f 1052//1052 358//358 357//357 -f 1052//1052 357//357 1054//1054 -f 1054//1054 357//357 374//374 -f 1054//1054 374//374 1207//1207 -f 1207//1207 374//374 375//375 -f 1244//1244 1192//1192 1245//1245 -f 1245//1245 1192//1192 1196//1196 -f 1245//1245 1196//1196 1246//1246 -f 1246//1246 1196//1196 1204//1204 -f 1246//1246 1204//1204 1247//1247 -f 1247//1247 1204//1204 1203//1203 -f 1247//1247 1203//1203 1248//1248 -f 1248//1248 1203//1203 1201//1201 -f 1248//1248 1201//1201 1249//1249 -f 1249//1249 1201//1201 1200//1200 -f 1249//1249 1200//1200 1250//1250 -f 1250//1250 1200//1200 1195//1195 -f 1250//1250 1195//1195 1251//1251 -f 1251//1251 1195//1195 1194//1194 -f 1251//1251 1194//1194 1252//1252 -f 1252//1252 1194//1194 1199//1199 -f 1252//1252 1199//1199 1253//1253 -f 1253//1253 1199//1199 1198//1198 -f 1253//1253 1198//1198 1254//1254 -f 1254//1254 1198//1198 1197//1197 -f 1254//1254 1197//1197 1255//1255 -f 1255//1255 1197//1197 1193//1193 -f 1255//1255 1193//1193 1244//1244 -f 1244//1244 1193//1193 1192//1192 -f 1256//1256 1009//1009 1257//1257 -f 1257//1257 1009//1009 1008//1008 -f 1257//1257 1008//1008 1258//1258 -f 1258//1258 1008//1008 1011//1011 -f 1258//1258 1011//1011 1259//1259 -f 1259//1259 1011//1011 1013//1013 -f 1259//1259 1013//1013 1260//1260 -f 1260//1260 1013//1013 1015//1015 -f 1260//1260 1015//1015 1261//1261 -f 1261//1261 1015//1015 1023//1023 -f 1261//1261 1023//1023 1262//1262 -f 1262//1262 1023//1023 1020//1020 -f 1262//1262 1020//1020 1263//1263 -f 1263//1263 1020//1020 1019//1019 -f 1263//1263 1019//1019 1264//1264 -f 1264//1264 1019//1019 1022//1022 -f 1264//1264 1022//1022 1265//1265 -f 1265//1265 1022//1022 1017//1017 -f 1265//1265 1017//1017 1266//1266 -f 1266//1266 1017//1017 1016//1016 -f 1266//1266 1016//1016 1267//1267 -f 1267//1267 1016//1016 1010//1010 -f 1267//1267 1010//1010 1256//1256 -f 1256//1256 1010//1010 1009//1009 -f 1268//1268 992//992 1269//1269 -f 1269//1269 992//992 998//998 -f 1269//1269 998//998 1270//1270 -f 1270//1270 998//998 997//997 -f 1270//1270 997//997 1271//1271 -f 1271//1271 997//997 996//996 -f 1271//1271 996//996 1272//1272 -f 1272//1272 996//996 995//995 -f 1272//1272 995//995 1273//1273 -f 1273//1273 995//995 1002//1002 -f 1273//1273 1002//1002 1274//1274 -f 1274//1274 1002//1002 1000//1000 -f 1274//1274 1000//1000 1275//1275 -f 1275//1275 1000//1000 1007//1007 -f 1275//1275 1007//1007 1276//1276 -f 1276//1276 1007//1007 1006//1006 -f 1276//1276 1006//1006 1277//1277 -f 1277//1277 1006//1006 1005//1005 -f 1277//1277 1005//1005 1278//1278 -f 1278//1278 1005//1005 1004//1004 -f 1278//1278 1004//1004 1279//1279 -f 1279//1279 1004//1004 1003//1003 -f 1279//1279 1003//1003 1268//1268 -f 1268//1268 1003//1003 992//992 -f 1280//1280 1187//1187 1281//1281 -f 1281//1281 1187//1187 1186//1186 -f 1281//1281 1186//1186 1282//1282 -f 1282//1282 1186//1186 1185//1185 -f 1282//1282 1185//1185 1283//1283 -f 1283//1283 1185//1185 1184//1184 -f 1283//1283 1184//1184 1284//1284 -f 1284//1284 1184//1184 1182//1182 -f 1284//1284 1182//1182 1285//1285 -f 1285//1285 1182//1182 1181//1181 -f 1285//1285 1181//1181 1286//1286 -f 1286//1286 1181//1181 1180//1180 -f 1286//1286 1180//1180 1287//1287 -f 1287//1287 1180//1180 1179//1179 -f 1287//1287 1179//1179 1288//1288 -f 1288//1288 1179//1179 1191//1191 -f 1288//1288 1191//1191 1289//1289 -f 1289//1289 1191//1191 1190//1190 -f 1289//1289 1190//1190 1290//1290 -f 1290//1290 1190//1190 1189//1189 -f 1290//1290 1189//1189 1291//1291 -f 1291//1291 1189//1189 1188//1188 -f 1291//1291 1188//1188 1280//1280 -f 1280//1280 1188//1188 1187//1187 -f 355//355 1032//1032 356//356 -f 356//356 1032//1032 1031//1031 -f 356//356 1031//1031 352//352 -f 352//352 1031//1031 1030//1030 -f 352//352 1030//1030 353//353 -f 353//353 1030//1030 1029//1029 -f 353//353 1029//1029 344//344 -f 344//344 1029//1029 1040//1040 -f 344//344 1040//1040 346//346 -f 346//346 1040//1040 1039//1039 -f 346//346 1039//1039 339//339 -f 339//339 1039//1039 1037//1037 -f 339//339 1037//1037 340//340 -f 340//340 1037//1037 1035//1035 -f 340//340 1035//1035 347//347 -f 347//347 1035//1035 1034//1034 -f 347//347 1034//1034 348//348 -f 348//348 1034//1034 1026//1026 -f 348//348 1026//1026 350//350 -f 350//350 1026//1026 1025//1025 -f 350//350 1025//1025 354//354 -f 354//354 1025//1025 1033//1033 -f 354//354 1033//1033 355//355 -f 355//355 1033//1033 1032//1032 -f 331//331 973//973 333//333 -f 333//333 973//973 972//972 -f 333//333 972//972 334//334 -f 334//334 972//972 971//971 -f 334//334 971//971 294//294 -f 294//294 971//971 969//969 -f 294//294 969//969 295//295 -f 295//295 969//969 967//967 -f 295//295 967//967 328//328 -f 328//328 967//967 966//966 -f 328//328 966//966 325//325 -f 325//325 966//966 981//981 -f 325//325 981//981 326//326 -f 326//326 981//981 980//980 -f 326//326 980//980 336//336 -f 336//336 980//980 978//978 -f 336//336 978//978 337//337 -f 337//337 978//978 976//976 -f 337//337 976//976 338//338 -f 338//338 976//976 975//975 -f 338//338 975//975 330//330 -f 330//330 975//975 974//974 -f 330//330 974//974 331//331 -f 331//331 974//974 973//973 -f 772//772 815//815 1243//1243 -f 1243//1243 815//815 880//880 -f 815//815 816//816 880//880 -f 880//880 816//816 881//881 -f 1163//1163 804//804 1165//1165 -f 1165//1165 804//804 803//803 -f 1165//1165 803//803 1231//1231 -f 1231//1231 803//803 962//962 -f 962//962 803//803 963//963 -f 963//963 803//803 801//801 -f 963//963 801//801 964//964 -f 964//964 801//801 795//795 -f 964//964 795//795 965//965 -f 965//965 795//795 793//793 -f 965//965 793//793 944//944 -f 944//944 793//793 791//791 -f 944//944 791//791 956//956 -f 956//956 791//791 790//790 -f 953//953 956//956 790//790 -f 939//939 941//941 779//779 -f 779//779 941//941 1041//1041 -f 1041//1041 1042//1042 779//779 -f 779//779 1042//1042 1049//1049 -f 779//779 1049//1049 790//790 -f 790//790 1049//1049 1050//1050 -f 790//790 1050//1050 953//953 -f 939//939 779//779 937//937 -f 937//937 779//779 778//778 -f 937//937 778//778 932//932 -f 932//932 778//778 777//777 -f 812//812 870//870 789//789 -f 789//789 870//870 869//869 -f 789//789 869//869 787//787 -f 787//787 869//869 934//934 -f 787//787 934//934 777//777 -f 777//777 934//934 933//933 -f 777//777 933//933 932//932 -f 812//812 813//813 923//923 -f 923//923 1159//1159 812//812 -f 812//812 1159//1159 1216//1216 -f 812//812 1216//1216 870//870 -f 798//798 797//797 919//919 -f 919//919 797//797 911//911 -f 797//797 767//767 911//911 -f 911//911 767//767 909//909 -f 903//903 1205//1205 768//768 -f 768//768 1205//1205 1202//1202 -f 768//768 1202//1202 1024//1024 -f 1024//1024 1014//1014 768//768 -f 768//768 1014//1014 1012//1012 -f 768//768 1012//1012 767//767 -f 767//767 1012//1012 1183//1183 -f 767//767 1183//1183 1038//1038 -f 1038//1038 1028//1028 767//767 -f 767//767 1028//1028 910//910 -f 767//767 910//910 909//909 -f 768//768 824//824 903//903 -f 903//903 824//824 904//904 -f 824//824 820//820 904//904 -f 904//904 820//820 906//906 -f 820//820 819//819 906//906 -f 906//906 819//819 907//907 -f 819//819 818//818 907//907 -f 907//907 818//818 908//908 -f 818//818 825//825 908//908 -f 908//908 825//825 872//872 -f 825//825 822//822 872//872 -f 872//872 822//822 873//873 -f 874//874 873//873 822//822 -f 901//901 902//902 809//809 -f 809//809 902//902 999//999 -f 809//809 999//999 822//822 -f 822//822 999//999 1001//1001 -f 822//822 1001//1001 874//874 -f 809//809 807//807 901//901 -f 901//901 807//807 899//899 -f 807//807 806//806 893//893 -f 893//893 895//895 807//807 -f 807//807 895//895 897//897 -f 807//807 897//897 899//899 -f 806//806 808//808 893//893 -f 893//893 808//808 891//891 -f 892//892 891//891 808//808 -f 884//884 1233//1233 783//783 -f 783//783 1233//1233 990//990 -f 783//783 990//990 808//808 -f 808//808 990//990 989//989 -f 808//808 989//989 892//892 -f 783//783 782//782 884//884 -f 884//884 782//782 885//885 -f 782//782 774//774 885//885 -f 885//885 774//774 887//887 -f 774//774 780//780 887//887 -f 887//887 780//780 888//888 -f 780//780 766//766 888//888 -f 888//888 766//766 890//890 -f 766//766 765//765 890//890 -f 890//890 765//765 875//875 -f 765//765 764//764 875//875 -f 875//875 764//764 876//876 -f 1243//1243 1242//1242 772//772 -f 772//772 1242//1242 1241//1241 -f 772//772 1241//1241 1240//1240 -f 1240//1240 1239//1239 772//772 -f 772//772 1239//1239 1238//1238 -f 772//772 1238//1238 764//764 -f 764//764 1238//1238 1237//1237 -f 764//764 1237//1237 1236//1236 -f 1236//1236 1235//1235 764//764 -f 764//764 1235//1235 877//877 -f 764//764 877//877 876//876 -f 759//759 417//417 287//287 -f 759//759 287//287 769//769 -f 769//769 287//287 460//460 -f 769//769 460//460 770//770 -f 770//770 460//460 459//459 -f 770//770 459//459 771//771 -f 771//771 459//459 458//458 -f 771//771 458//458 823//823 -f 823//823 458//458 457//457 -f 823//823 457//457 821//821 -f 821//821 457//457 456//456 -f 821//821 456//456 760//760 -f 761//761 315//315 314//314 -f 761//761 314//314 784//784 -f 784//784 314//314 437//437 -f 784//784 437//437 775//775 -f 775//775 437//437 436//436 -f 775//775 436//436 776//776 -f 776//776 436//436 435//435 -f 776//776 435//435 781//781 -f 781//781 435//435 620//620 -f 781//781 620//620 773//773 -f 773//773 620//620 619//619 -f 773//773 619//619 762//762 -f 757//757 279//279 447//447 -f 757//757 447//447 785//785 -f 785//785 447//447 452//452 -f 785//785 452//452 786//786 -f 786//786 452//452 451//451 -f 786//786 451//451 788//788 -f 788//788 451//451 448//448 -f 788//788 448//448 810//810 -f 810//810 448//448 449//449 -f 810//810 449//449 811//811 -f 811//811 449//449 450//450 -f 811//811 450//450 758//758 -f 763//763 630//630 443//443 -f 763//763 443//443 802//802 -f 802//802 443//443 442//442 -f 802//802 442//442 800//800 -f 800//800 442//442 441//441 -f 800//800 441//441 796//796 -f 796//796 441//441 440//440 -f 796//796 440//440 794//794 -f 794//794 440//440 439//439 -f 794//794 439//439 792//792 -f 792//792 439//439 446//446 -f 792//792 446//446 756//756 -f 1292//1292 1293//1293 169//169 -f 181//181 1294//1294 179//179 -f 179//179 1294//1294 1295//1295 -f 179//179 1295//1295 177//177 -f 177//177 1295//1295 1296//1296 -f 1297//1297 189//189 1293//1293 -f 1293//1293 189//189 191//191 -f 1293//1293 191//191 169//169 -f 181//181 183//183 1294//1294 -f 1294//1294 183//183 185//185 -f 1294//1294 185//185 1297//1297 -f 1297//1297 185//185 187//187 -f 1297//1297 187//187 189//189 -f 169//169 171//171 1292//1292 -f 1292//1292 171//171 173//173 -f 1292//1292 173//173 1296//1296 -f 1296//1296 173//173 175//175 -f 1296//1296 175//175 177//177 -f 1296//1296 1295//1295 588//588 -f 588//588 1295//1295 589//589 -f 1292//1292 1296//1296 592//592 -f 592//592 1296//1296 588//588 -f 1293//1293 1292//1292 591//591 -f 591//591 1292//1292 592//592 -f 1297//1297 1293//1293 590//590 -f 590//590 1293//1293 591//591 -f 1294//1294 1297//1297 623//623 -f 623//623 1297//1297 590//590 -f 1295//1295 1294//1294 589//589 -f 589//589 1294//1294 623//623 -f 1298//1298 1299//1299 1283//1283 -f 1286//1286 1300//1300 1285//1285 -f 1285//1285 1300//1300 1298//1298 -f 1285//1285 1298//1298 1284//1284 -f 1284//1284 1298//1298 1283//1283 -f 1301//1301 1302//1302 1290//1290 -f 1290//1290 1291//1291 1301//1301 -f 1301//1301 1291//1291 1280//1280 -f 1301//1301 1280//1280 1303//1303 -f 1303//1303 1280//1280 1281//1281 -f 1303//1303 1281//1281 1299//1299 -f 1299//1299 1281//1281 1282//1282 -f 1299//1299 1282//1282 1283//1283 -f 1286//1286 1287//1287 1300//1300 -f 1300//1300 1287//1287 1288//1288 -f 1300//1300 1288//1288 1302//1302 -f 1302//1302 1288//1288 1289//1289 -f 1302//1302 1289//1289 1290//1290 -f 1298//1298 1300//1300 682//682 -f 682//682 1300//1300 683//683 -f 1299//1299 1298//1298 681//681 -f 681//681 1298//1298 682//682 -f 1303//1303 1299//1299 680//680 -f 680//680 1299//1299 681//681 -f 1301//1301 1303//1303 679//679 -f 679//679 1303//1303 680//680 -f 1302//1302 1301//1301 678//678 -f 678//678 1301//1301 679//679 -f 1300//1300 1302//1302 683//683 -f 683//683 1302//1302 678//678 -f 1304//1304 1305//1305 1266//1266 -f 1266//1266 1267//1267 1304//1304 -f 1304//1304 1267//1267 1256//1256 -f 1304//1304 1256//1256 1306//1306 -f 1262//1262 1307//1307 1261//1261 -f 1261//1261 1307//1307 1308//1308 -f 1262//1262 1263//1263 1307//1307 -f 1307//1307 1263//1263 1264//1264 -f 1307//1307 1264//1264 1305//1305 -f 1305//1305 1264//1264 1265//1265 -f 1305//1305 1265//1265 1266//1266 -f 1256//1256 1257//1257 1306//1306 -f 1306//1306 1257//1257 1258//1258 -f 1306//1306 1258//1258 1309//1309 -f 1309//1309 1258//1258 1259//1259 -f 1309//1309 1259//1259 1308//1308 -f 1308//1308 1259//1259 1260//1260 -f 1308//1308 1260//1260 1261//1261 -f 1308//1308 1307//1307 598//598 -f 598//598 1307//1307 593//593 -f 1309//1309 1308//1308 599//599 -f 599//599 1308//1308 598//598 -f 1306//1306 1309//1309 597//597 -f 597//597 1309//1309 599//599 -f 1304//1304 1306//1306 596//596 -f 596//596 1306//1306 597//597 -f 1305//1305 1304//1304 594//594 -f 594//594 1304//1304 596//596 -f 1307//1307 1305//1305 593//593 -f 593//593 1305//1305 594//594 -f 1250//1250 1310//1310 1249//1249 -f 1249//1249 1310//1310 1311//1311 -f 1250//1250 1251//1251 1310//1310 -f 1310//1310 1251//1251 1252//1252 -f 1310//1310 1252//1252 1312//1312 -f 1313//1313 1314//1314 1244//1244 -f 1252//1252 1253//1253 1312//1312 -f 1312//1312 1253//1253 1254//1254 -f 1312//1312 1254//1254 1314//1314 -f 1314//1314 1254//1254 1255//1255 -f 1314//1314 1255//1255 1244//1244 -f 1244//1244 1245//1245 1313//1313 -f 1313//1313 1245//1245 1246//1246 -f 1313//1313 1246//1246 1315//1315 -f 1315//1315 1246//1246 1247//1247 -f 1315//1315 1247//1247 1311//1311 -f 1311//1311 1247//1247 1248//1248 -f 1311//1311 1248//1248 1249//1249 -f 1311//1311 1310//1310 422//422 -f 422//422 1310//1310 423//423 -f 1315//1315 1311//1311 428//428 -f 428//428 1311//1311 422//422 -f 1313//1313 1315//1315 427//427 -f 427//427 1315//1315 428//428 -f 1314//1314 1313//1313 420//420 -f 420//420 1313//1313 427//427 -f 1312//1312 1314//1314 419//419 -f 419//419 1314//1314 420//420 -f 1310//1310 1312//1312 423//423 -f 423//423 1312//1312 419//419 -f 1316//1316 1317//1317 1273//1273 -f 1276//1276 1318//1318 1275//1275 -f 1275//1275 1318//1318 1316//1316 -f 1275//1275 1316//1316 1274//1274 -f 1274//1274 1316//1316 1273//1273 -f 1319//1319 1320//1320 1268//1268 -f 1276//1276 1277//1277 1318//1318 -f 1318//1318 1277//1277 1278//1278 -f 1318//1318 1278//1278 1320//1320 -f 1320//1320 1278//1278 1279//1279 -f 1320//1320 1279//1279 1268//1268 -f 1268//1268 1269//1269 1319//1319 -f 1319//1319 1269//1269 1270//1270 -f 1319//1319 1270//1270 1321//1321 -f 1321//1321 1270//1270 1271//1271 -f 1321//1321 1271//1271 1317//1317 -f 1317//1317 1271//1271 1272//1272 -f 1317//1317 1272//1272 1273//1273 -f 608//608 1317//1317 610//610 -f 610//610 1317//1317 1316//1316 -f 610//610 1316//1316 264//264 -f 286//286 285//285 1321//1321 -f 1317//1317 608//608 606//606 -f 1317//1317 606//606 1321//1321 -f 1321//1321 606//606 605//605 -f 1321//1321 605//605 286//286 -f 602//602 1319//1319 414//414 -f 414//414 1319//1319 1321//1321 -f 414//414 1321//1321 285//285 -f 604//604 1320//1320 603//603 -f 603//603 1320//1320 1319//1319 -f 603//603 1319//1319 602//602 -f 1318//1318 1320//1320 265//265 -f 265//265 1320//1320 604//604 -f 1316//1316 1318//1318 264//264 -f 264//264 1318//1318 265//265 -f 1322//1322 1323//1323 157//157 -f 157//157 159//159 1322//1322 -f 1322//1322 159//159 161//161 -f 1322//1322 161//161 1324//1324 -f 161//161 163//163 1324//1324 -f 1324//1324 163//163 165//165 -f 1324//1324 165//165 1325//1325 -f 165//165 167//167 1325//1325 -f 1325//1325 167//167 145//145 -f 1325//1325 145//145 1326//1326 -f 1327//1327 153//153 1323//1323 -f 1323//1323 153//153 155//155 -f 1323//1323 155//155 157//157 -f 145//145 147//147 1326//1326 -f 1326//1326 147//147 149//149 -f 1326//1326 149//149 1327//1327 -f 1327//1327 149//149 151//151 -f 1327//1327 151//151 153//153 -f 1327//1327 1323//1323 657//657 -f 657//657 1323//1323 321//321 -f 1326//1326 1327//1327 304//304 -f 304//304 1327//1327 657//657 -f 301//301 1325//1325 302//302 -f 302//302 1325//1325 1326//1326 -f 302//302 1326//1326 304//304 -f 1324//1324 1325//1325 308//308 -f 308//308 1325//1325 301//301 -f 1324//1324 308//308 307//307 -f 324//324 1322//1322 319//319 -f 319//319 1322//1322 1324//1324 -f 319//319 1324//1324 316//316 -f 316//316 1324//1324 307//307 -f 321//321 1323//1323 323//323 -f 323//323 1323//1323 1322//1322 -f 323//323 1322//1322 324//324 -f 1328//1328 1329//1329 229//229 -f 237//237 1330//1330 235//235 -f 235//235 1330//1330 1331//1331 -f 235//235 1331//1331 233//233 -f 233//233 1331//1331 1328//1328 -f 233//233 1328//1328 231//231 -f 231//231 1328//1328 229//229 -f 237//237 239//239 1330//1330 -f 1330//1330 239//239 217//217 -f 1330//1330 217//217 1332//1332 -f 1333//1333 225//225 1329//1329 -f 1329//1329 225//225 227//227 -f 1329//1329 227//227 229//229 -f 217//217 219//219 1332//1332 -f 1332//1332 219//219 221//221 -f 1332//1332 221//221 1333//1333 -f 1333//1333 221//221 223//223 -f 1333//1333 223//223 225//225 -f 1333//1333 1329//1329 481//481 -f 481//481 1329//1329 483//483 -f 1332//1332 1333//1333 480//480 -f 480//480 1333//1333 481//481 -f 1330//1330 1332//1332 262//262 -f 262//262 1332//1332 480//480 -f 1331//1331 1330//1330 261//261 -f 261//261 1330//1330 262//262 -f 1328//1328 1331//1331 612//612 -f 612//612 1331//1331 261//261 -f 1329//1329 1328//1328 483//483 -f 483//483 1328//1328 612//612 -f 1334//1334 1335//1335 205//205 -f 1336//1336 213//213 1337//1337 -f 1337//1337 213//213 215//215 -f 1337//1337 215//215 1338//1338 -f 1338//1338 215//215 193//193 -f 1339//1339 201//201 1335//1335 -f 1335//1335 201//201 203//203 -f 1335//1335 203//203 205//205 -f 205//205 207//207 1334//1334 -f 1334//1334 207//207 209//209 -f 1334//1334 209//209 1336//1336 -f 1336//1336 209//209 211//211 -f 1336//1336 211//211 213//213 -f 193//193 195//195 1338//1338 -f 1338//1338 195//195 197//197 -f 1338//1338 197//197 1339//1339 -f 1339//1339 197//197 199//199 -f 1339//1339 199//199 201//201 -f 1339//1339 1335//1335 299//299 -f 299//299 1335//1335 300//300 -f 1338//1338 1339//1339 298//298 -f 298//298 1339//1339 299//299 -f 1337//1337 1338//1338 297//297 -f 297//297 1338//1338 298//298 -f 1336//1336 1337//1337 615//615 -f 615//615 1337//1337 297//297 -f 1334//1334 1336//1336 676//676 -f 676//676 1336//1336 615//615 -f 1335//1335 1334//1334 300//300 -f 300//300 1334//1334 676//676 -f 129//129 1340//1340 127//127 -f 127//127 1340//1340 1341//1341 -f 127//127 1341//1341 125//125 -f 125//125 1341//1341 1342//1342 -f 125//125 1342//1342 123//123 -f 123//123 1342//1342 1343//1343 -f 123//123 1343//1343 121//121 -f 121//121 1343//1343 1344//1344 -f 121//121 1344//1344 143//143 -f 143//143 1344//1344 1345//1345 -f 143//143 1345//1345 141//141 -f 1345//1345 1346//1346 141//141 -f 141//141 1346//1346 1347//1347 -f 141//141 1347//1347 139//139 -f 139//139 1347//1347 1348//1348 -f 139//139 1348//1348 137//137 -f 137//137 1348//1348 1349//1349 -f 137//137 1349//1349 135//135 -f 135//135 1349//1349 1350//1350 -f 135//135 1350//1350 133//133 -f 133//133 1350//1350 1351//1351 -f 133//133 1351//1351 131//131 -f 131//131 1351//1351 1352//1352 -f 131//131 1352//1352 129//129 -f 129//129 1352//1352 1353//1353 -f 129//129 1353//1353 1340//1340 -f 1352//1352 1169//1169 1353//1353 -f 1353//1353 1169//1169 1171//1171 -f 1353//1353 1171//1171 1340//1340 -f 1340//1340 1171//1171 1173//1173 -f 1340//1340 1173//1173 1341//1341 -f 1341//1341 1173//1173 1232//1232 -f 1341//1341 1232//1232 1342//1342 -f 1342//1342 1232//1232 1175//1175 -f 1342//1342 1175//1175 1343//1343 -f 1343//1343 1175//1175 1174//1174 -f 1343//1343 1174//1174 1344//1344 -f 1344//1344 1174//1174 1178//1178 -f 1344//1344 1178//1178 1345//1345 -f 1345//1345 1178//1178 1177//1177 -f 1345//1345 1177//1177 1346//1346 -f 1346//1346 1177//1177 1176//1176 -f 1346//1346 1176//1176 1347//1347 -f 1347//1347 1176//1176 878//878 -f 1347//1347 878//878 1348//1348 -f 1348//1348 878//878 883//883 -f 1348//1348 883//883 1349//1349 -f 1349//1349 883//883 1164//1164 -f 1349//1349 1164//1164 1350//1350 -f 1350//1350 1164//1164 1166//1166 -f 1350//1350 1166//1166 1351//1351 -f 1351//1351 1166//1166 1167//1167 -f 1351//1351 1167//1167 1352//1352 -f 1352//1352 1167//1167 1169//1169 -f 105//105 1354//1354 103//103 -f 103//103 1354//1354 1355//1355 -f 103//103 1355//1355 101//101 -f 101//101 1355//1355 1356//1356 -f 101//101 1356//1356 99//99 -f 99//99 1356//1356 1357//1357 -f 99//99 1357//1357 97//97 -f 97//97 1357//1357 1358//1358 -f 97//97 1358//1358 119//119 -f 119//119 1358//1358 1359//1359 -f 119//119 1359//1359 117//117 -f 1359//1359 1360//1360 117//117 -f 117//117 1360//1360 1361//1361 -f 117//117 1361//1361 115//115 -f 115//115 1361//1361 1362//1362 -f 115//115 1362//1362 113//113 -f 113//113 1362//1362 1363//1363 -f 113//113 1363//1363 111//111 -f 111//111 1363//1363 1364//1364 -f 111//111 1364//1364 109//109 -f 109//109 1364//1364 1365//1365 -f 109//109 1365//1365 107//107 -f 107//107 1365//1365 1366//1366 -f 107//107 1366//1366 105//105 -f 105//105 1366//1366 1367//1367 -f 105//105 1367//1367 1354//1354 -f 1366//1366 1160//1160 1367//1367 -f 1367//1367 1160//1160 922//922 -f 1367//1367 922//922 1354//1354 -f 1354//1354 922//922 914//914 -f 1354//1354 914//914 1355//1355 -f 1355//1355 914//914 913//913 -f 1355//1355 913//913 1356//1356 -f 1356//1356 913//913 918//918 -f 1356//1356 918//918 1357//1357 -f 1357//1357 918//918 917//917 -f 1357//1357 917//917 1358//1358 -f 1358//1358 917//917 916//916 -f 1358//1358 916//916 1359//1359 -f 1359//1359 916//916 1153//1153 -f 1359//1359 1153//1153 1360//1360 -f 1360//1360 1153//1153 1152//1152 -f 1360//1360 1152//1152 1361//1361 -f 1361//1361 1152//1152 1150//1150 -f 1361//1361 1150//1150 1362//1362 -f 1362//1362 1150//1150 1149//1149 -f 1362//1362 1149//1149 1363//1363 -f 1363//1363 1149//1149 1154//1154 -f 1363//1363 1154//1154 1364//1364 -f 1364//1364 1154//1154 1156//1156 -f 1364//1364 1156//1156 1365//1365 -f 1365//1365 1156//1156 1161//1161 -f 1365//1365 1161//1161 1366//1366 -f 1366//1366 1161//1161 1160//1160 -f 923//923 813//813 814//814 -f 923//923 814//814 921//921 -f 921//921 814//814 799//799 -f 921//921 799//799 920//920 -f 920//920 799//799 798//798 -f 920//920 798//798 919//919 -f 804//804 1163//1163 1162//1162 -f 804//804 1162//1162 805//805 -f 805//805 1162//1162 882//882 -f 805//805 882//882 817//817 -f 817//817 882//882 881//881 -f 817//817 881//881 816//816 -f 1368//1368 1369//1369 1370//1370 -f 1370//1370 1369//1369 1371//1371 -f 1370//1370 1371//1371 1372//1372 -f 1372//1372 1371//1371 1373//1373 -f 1372//1372 1373//1373 1374//1374 -f 1374//1374 1373//1373 1375//1375 -f 1374//1374 1375//1375 1376//1376 -f 1376//1376 1375//1375 1377//1377 -f 1376//1376 1377//1377 1378//1378 -f 1378//1378 1377//1377 1379//1379 -f 1378//1378 1379//1379 1380//1380 -f 1380//1380 1379//1379 1381//1381 -f 1380//1380 1381//1381 1382//1382 -f 1382//1382 1381//1381 1383//1383 -f 1382//1382 1383//1383 1384//1384 -f 1384//1384 1383//1383 1385//1385 -f 1384//1384 1385//1385 1386//1386 -f 1386//1386 1385//1385 1387//1387 -f 1386//1386 1387//1387 1388//1388 -f 1388//1388 1387//1387 1389//1389 -f 1388//1388 1389//1389 1390//1390 -f 1390//1390 1389//1389 1391//1391 -f 1390//1390 1391//1391 1368//1368 -f 1368//1368 1391//1391 1369//1369 -f 1392//1392 1393//1393 1394//1394 -f 1394//1394 1393//1393 1395//1395 -f 1394//1394 1395//1395 1396//1396 -f 1396//1396 1395//1395 1397//1397 -f 1396//1396 1397//1397 1398//1398 -f 1398//1398 1397//1397 1399//1399 -f 1398//1398 1399//1399 1400//1400 -f 1400//1400 1399//1399 1401//1401 -f 1400//1400 1401//1401 1402//1402 -f 1402//1402 1401//1401 1403//1403 -f 1402//1402 1403//1403 1404//1404 -f 1404//1404 1403//1403 1405//1405 -f 1404//1404 1405//1405 1406//1406 -f 1406//1406 1405//1405 1407//1407 -f 1406//1406 1407//1407 1408//1408 -f 1408//1408 1407//1407 1409//1409 -f 1408//1408 1409//1409 1410//1410 -f 1410//1410 1409//1409 1411//1411 -f 1410//1410 1411//1411 1412//1412 -f 1412//1412 1411//1411 1413//1413 -f 1412//1412 1413//1413 1414//1414 -f 1414//1414 1413//1413 1415//1415 -f 1414//1414 1415//1415 1392//1392 -f 1392//1392 1415//1415 1393//1393 -f 1416//1416 1417//1417 1418//1418 -f 1418//1418 1417//1417 1419//1419 -f 1418//1418 1419//1419 1420//1420 -f 1420//1420 1419//1419 1421//1421 -f 1420//1420 1421//1421 1422//1422 -f 1422//1422 1421//1421 1423//1423 -f 1422//1422 1423//1423 1424//1424 -f 1424//1424 1423//1423 1425//1425 -f 1424//1424 1425//1425 1426//1426 -f 1426//1426 1425//1425 1427//1427 -f 1426//1426 1427//1427 1428//1428 -f 1428//1428 1427//1427 1429//1429 -f 1428//1428 1429//1429 1430//1430 -f 1430//1430 1429//1429 1431//1431 -f 1430//1430 1431//1431 1432//1432 -f 1432//1432 1431//1431 1433//1433 -f 1432//1432 1433//1433 1434//1434 -f 1434//1434 1433//1433 1435//1435 -f 1434//1434 1435//1435 1436//1436 -f 1436//1436 1435//1435 1437//1437 -f 1436//1436 1437//1437 1438//1438 -f 1438//1438 1437//1437 1439//1439 -f 1438//1438 1439//1439 1416//1416 -f 1416//1416 1439//1439 1417//1417 -f 1440//1440 1441//1441 1442//1442 -f 1442//1442 1441//1441 1443//1443 -f 1442//1442 1443//1443 1444//1444 -f 1444//1444 1443//1443 1445//1445 -f 1444//1444 1445//1445 1446//1446 -f 1446//1446 1445//1445 1447//1447 -f 1446//1446 1447//1447 1448//1448 -f 1448//1448 1447//1447 1449//1449 -f 1448//1448 1449//1449 1450//1450 -f 1450//1450 1449//1449 1451//1451 -f 1450//1450 1451//1451 1452//1452 -f 1452//1452 1451//1451 1453//1453 -f 1452//1452 1453//1453 1454//1454 -f 1454//1454 1453//1453 1455//1455 -f 1454//1454 1455//1455 1456//1456 -f 1456//1456 1455//1455 1457//1457 -f 1456//1456 1457//1457 1458//1458 -f 1458//1458 1457//1457 1459//1459 -f 1458//1458 1459//1459 1460//1460 -f 1460//1460 1459//1459 1461//1461 -f 1460//1460 1461//1461 1462//1462 -f 1462//1462 1461//1461 1463//1463 -f 1462//1462 1463//1463 1440//1440 -f 1440//1440 1463//1463 1441//1441 -f 1464//1464 1465//1465 1466//1466 -f 1466//1466 1465//1465 1467//1467 -f 1466//1466 1467//1467 1468//1468 -f 1468//1468 1467//1467 1469//1469 -f 1468//1468 1469//1469 1470//1470 -f 1470//1470 1469//1469 1471//1471 -f 1470//1470 1471//1471 1472//1472 -f 1472//1472 1471//1471 1473//1473 -f 1472//1472 1473//1473 1474//1474 -f 1474//1474 1473//1473 1475//1475 -f 1474//1474 1475//1475 1476//1476 -f 1476//1476 1475//1475 1477//1477 -f 1476//1476 1477//1477 1478//1478 -f 1478//1478 1477//1477 1479//1479 -f 1478//1478 1479//1479 1480//1480 -f 1480//1480 1479//1479 1481//1481 -f 1480//1480 1481//1481 1482//1482 -f 1482//1482 1481//1481 1483//1483 -f 1482//1482 1483//1483 1484//1484 -f 1484//1484 1483//1483 1485//1485 -f 1484//1484 1485//1485 1486//1486 -f 1486//1486 1485//1485 1487//1487 -f 1486//1486 1487//1487 1464//1464 -f 1464//1464 1487//1487 1465//1465 -f 1488//1488 1489//1489 1490//1490 -f 1490//1490 1489//1489 1491//1491 -f 1490//1490 1491//1491 1492//1492 -f 1492//1492 1491//1491 1493//1493 -f 1492//1492 1493//1493 1494//1494 -f 1494//1494 1493//1493 1495//1495 -f 1494//1494 1495//1495 1496//1496 -f 1496//1496 1495//1495 1497//1497 -f 1496//1496 1497//1497 1498//1498 -f 1498//1498 1497//1497 1499//1499 -f 1498//1498 1499//1499 1500//1500 -f 1500//1500 1499//1499 1501//1501 -f 1500//1500 1501//1501 1502//1502 -f 1502//1502 1501//1501 1503//1503 -f 1502//1502 1503//1503 1504//1504 -f 1504//1504 1503//1503 1505//1505 -f 1504//1504 1505//1505 1506//1506 -f 1506//1506 1505//1505 1507//1507 -f 1506//1506 1507//1507 1508//1508 -f 1508//1508 1507//1507 1509//1509 -f 1508//1508 1509//1509 1510//1510 -f 1510//1510 1509//1509 1511//1511 -f 1510//1510 1511//1511 1488//1488 -f 1488//1488 1511//1511 1489//1489 -f 1512//1512 1513//1513 1514//1514 -f 1515//1515 1516//1516 1517//1517 -f 1518//1518 1519//1519 1520//1520 -f 1521//1521 1522//1522 1523//1523 -f 1524//1524 1525//1525 1526//1526 -f 1527//1527 1528//1528 1529//1529 -f 1403//1403 1401//1401 1529//1529 -f 1385//1385 1530//1530 1531//1531 -f 1532//1532 1533//1533 1534//1534 -f 1535//1535 1536//1536 1537//1537 -f 1538//1538 1539//1539 1540//1540 -f 1541//1541 1542//1542 1543//1543 -f 1544//1544 1545//1545 1546//1546 -f 1547//1547 1548//1548 1549//1549 -f 1550//1550 1551//1551 1552//1552 -f 1553//1553 1554//1554 1555//1555 -f 1556//1556 1557//1557 1558//1558 -f 1559//1559 1560//1560 1561//1561 -f 1562//1562 1563//1563 1564//1564 -f 1565//1565 1566//1566 1567//1567 -f 1568//1568 1569//1569 1521//1521 -f 1521//1521 1569//1569 1570//1570 -f 1521//1521 1570//1570 1522//1522 -f 1522//1522 1570//1570 1571//1571 -f 1572//1572 1573//1573 1574//1574 -f 1574//1574 1573//1573 1575//1575 -f 1574//1574 1575//1575 1576//1576 -f 1577//1577 1578//1578 1579//1579 -f 1580//1580 1581//1581 1582//1582 -f 1582//1582 1581//1581 1577//1577 -f 1582//1582 1577//1577 1583//1583 -f 1583//1583 1577//1577 1579//1579 -f 1583//1583 1579//1579 1584//1584 -f 1577//1577 1585//1585 1578//1578 -f 1578//1578 1585//1585 1586//1586 -f 1578//1578 1586//1586 1587//1587 -f 1586//1586 1588//1588 1587//1587 -f 1587//1587 1588//1588 1589//1589 -f 1587//1587 1589//1589 1590//1590 -f 1591//1591 1592//1592 1593//1593 -f 1593//1593 1592//1592 1594//1594 -f 1593//1593 1594//1594 1589//1589 -f 1589//1589 1594//1594 1595//1595 -f 1589//1589 1595//1595 1590//1590 -f 1596//1596 1597//1597 1524//1524 -f 1524//1524 1597//1597 1598//1598 -f 1566//1566 1599//1599 1600//1600 -f 1601//1601 1602//1602 1603//1603 -f 1604//1604 1605//1605 1606//1606 -f 1597//1597 1607//1607 1598//1598 -f 1598//1598 1607//1607 1608//1608 -f 1598//1598 1608//1608 1603//1603 -f 1603//1603 1608//1608 1609//1609 -f 1603//1603 1609//1609 1601//1601 -f 1604//1604 1606//1606 1602//1602 -f 1610//1610 1611//1611 1612//1612 -f 1612//1612 1611//1611 1613//1613 -f 1614//1614 1615//1615 1616//1616 -f 1616//1616 1615//1615 1617//1617 -f 1611//1611 1618//1618 1613//1613 -f 1613//1613 1618//1618 1619//1619 -f 1613//1613 1619//1619 1620//1620 -f 1620//1620 1619//1619 1621//1621 -f 1622//1622 1623//1623 1614//1614 -f 1614//1614 1623//1623 1624//1624 -f 1614//1614 1624//1624 1615//1615 -f 1621//1621 1625//1625 1620//1620 -f 1620//1620 1625//1625 1626//1626 -f 1620//1620 1626//1626 1622//1622 -f 1622//1622 1626//1626 1627//1627 -f 1622//1622 1627//1627 1623//1623 -f 1513//1513 1628//1628 1629//1629 -f 1630//1630 1631//1631 1632//1632 -f 1632//1632 1631//1631 1633//1633 -f 1634//1634 1635//1635 1636//1636 -f 1636//1636 1635//1635 1637//1637 -f 1636//1636 1637//1637 1629//1629 -f 1629//1629 1637//1637 1638//1638 -f 1629//1629 1638//1638 1639//1639 -f 1640//1640 1641//1641 1642//1642 -f 1642//1642 1641//1641 1643//1643 -f 1642//1642 1643//1643 1632//1632 -f 1632//1632 1643//1643 1644//1644 -f 1632//1632 1644//1644 1630//1630 -f 1628//1628 1513//1513 1645//1645 -f 1645//1645 1513//1513 1512//1512 -f 1645//1645 1512//1512 1646//1646 -f 1647//1647 1648//1648 1649//1649 -f 1649//1649 1648//1648 1650//1650 -f 1649//1649 1650//1650 1651//1651 -f 1651//1651 1650//1650 1652//1652 -f 1651//1651 1652//1652 1653//1653 -f 1653//1653 1652//1652 1654//1654 -f 1652//1652 1655//1655 1654//1654 -f 1654//1654 1655//1655 1562//1562 -f 1654//1654 1562//1562 1656//1656 -f 1656//1656 1562//1562 1564//1564 -f 1657//1657 1658//1658 1659//1659 -f 1659//1659 1660//1660 1657//1657 -f 1657//1657 1660//1660 1661//1661 -f 1657//1657 1661//1661 1662//1662 -f 1662//1662 1661//1661 1632//1632 -f 1662//1662 1632//1632 1636//1636 -f 1636//1636 1632//1632 1633//1633 -f 1636//1636 1633//1633 1634//1634 -f 1663//1663 1664//1664 1665//1665 -f 1665//1665 1664//1664 1666//1666 -f 1667//1667 1668//1668 1669//1669 -f 1667//1667 1669//1669 1670//1670 -f 1671//1671 1672//1672 1673//1673 -f 1673//1673 1672//1672 1670//1670 -f 1668//1668 1674//1674 1669//1669 -f 1669//1669 1674//1674 1675//1675 -f 1669//1669 1675//1675 1666//1666 -f 1666//1666 1675//1675 1676//1676 -f 1666//1666 1676//1676 1665//1665 -f 1671//1671 1673//1673 1677//1677 -f 1677//1677 1673//1673 1678//1678 -f 1677//1677 1678//1678 1679//1679 -f 1679//1679 1678//1678 1680//1680 -f 1679//1679 1680//1680 1561//1561 -f 1561//1561 1680//1680 1681//1681 -f 1561//1561 1681//1681 1559//1559 -f 1682//1682 1683//1683 1556//1556 -f 1556//1556 1683//1683 1684//1684 -f 1556//1556 1684//1684 1685//1685 -f 1682//1682 1556//1556 1686//1686 -f 1686//1686 1556//1556 1558//1558 -f 1686//1686 1558//1558 1687//1687 -f 1687//1687 1558//1558 1688//1688 -f 1687//1687 1688//1688 1689//1689 -f 1690//1690 1691//1691 1692//1692 -f 1689//1689 1693//1693 1687//1687 -f 1687//1687 1693//1693 1694//1694 -f 1687//1687 1694//1694 1695//1695 -f 1695//1695 1694//1694 1696//1696 -f 1692//1692 1691//1691 1697//1697 -f 1697//1697 1691//1691 1698//1698 -f 1697//1697 1698//1698 1689//1689 -f 1689//1689 1698//1698 1699//1699 -f 1689//1689 1699//1699 1693//1693 -f 1696//1696 1694//1694 1700//1700 -f 1700//1700 1694//1694 1690//1690 -f 1700//1700 1690//1690 1701//1701 -f 1665//1665 1702//1702 1663//1663 -f 1663//1663 1702//1702 1703//1703 -f 1663//1663 1703//1703 1692//1692 -f 1692//1692 1703//1703 1704//1704 -f 1704//1704 1553//1553 1692//1692 -f 1692//1692 1553//1553 1555//1555 -f 1692//1692 1555//1555 1690//1690 -f 1690//1690 1555//1555 1705//1705 -f 1690//1690 1705//1705 1701//1701 -f 1706//1706 1707//1707 1577//1577 -f 1577//1577 1707//1707 1708//1708 -f 1577//1577 1708//1708 1585//1585 -f 1709//1709 1710//1710 1711//1711 -f 1711//1711 1712//1712 1709//1709 -f 1709//1709 1712//1712 1713//1713 -f 1709//1709 1713//1713 1714//1714 -f 1715//1715 1716//1716 1717//1717 -f 1550//1550 1552//1552 1718//1718 -f 1719//1719 1552//1552 1720//1720 -f 1720//1720 1552//1552 1721//1721 -f 1719//1719 1722//1722 1552//1552 -f 1552//1552 1722//1722 1723//1723 -f 1552//1552 1723//1723 1718//1718 -f 1724//1724 1725//1725 1721//1721 -f 1726//1726 1727//1727 1557//1557 -f 1557//1557 1727//1727 1728//1728 -f 1557//1557 1728//1728 1729//1729 -f 1729//1729 1730//1730 1557//1557 -f 1557//1557 1730//1730 1731//1731 -f 1557//1557 1731//1731 1558//1558 -f 1732//1732 1733//1733 1734//1734 -f 1735//1735 1736//1736 1576//1576 -f 1732//1732 1737//1737 1733//1733 -f 1733//1733 1737//1737 1738//1738 -f 1733//1733 1738//1738 1739//1739 -f 1740//1740 1574//1574 1741//1741 -f 1741//1741 1574//1574 1576//1576 -f 1741//1741 1576//1576 1742//1742 -f 1742//1742 1576//1576 1736//1736 -f 1743//1743 1744//1744 1734//1734 -f 1734//1734 1744//1744 1745//1745 -f 1734//1734 1745//1745 1732//1732 -f 1746//1746 1747//1747 1748//1748 -f 1748//1748 1747//1747 1749//1749 -f 1748//1748 1749//1749 1743//1743 -f 1743//1743 1749//1749 1750//1750 -f 1743//1743 1750//1750 1744//1744 -f 1534//1534 1533//1533 1748//1748 -f 1748//1748 1533//1533 1751//1751 -f 1748//1748 1751//1751 1752//1752 -f 1580//1580 1753//1753 1754//1754 -f 1754//1754 1753//1753 1755//1755 -f 1754//1754 1755//1755 1752//1752 -f 1755//1755 1756//1756 1752//1752 -f 1752//1752 1756//1756 1757//1757 -f 1752//1752 1757//1757 1748//1748 -f 1748//1748 1757//1757 1758//1758 -f 1748//1748 1758//1758 1746//1746 -f 1584//1584 1579//1579 1759//1759 -f 1759//1759 1579//1579 1572//1572 -f 1759//1759 1572//1572 1760//1760 -f 1760//1760 1572//1572 1574//1574 -f 1760//1760 1574//1574 1761//1761 -f 1761//1761 1574//1574 1740//1740 -f 1761//1761 1740//1740 1762//1762 -f 1763//1763 1764//1764 1765//1765 -f 1764//1764 1763//1763 1766//1766 -f 1767//1767 1768//1768 1523//1523 -f 1769//1769 1770//1770 1771//1771 -f 1771//1771 1770//1770 1772//1772 -f 1773//1773 1774//1774 1775//1775 -f 1770//1770 1776//1776 1772//1772 -f 1772//1772 1776//1776 1777//1777 -f 1772//1772 1777//1777 1778//1778 -f 1775//1775 1779//1779 1773//1773 -f 1773//1773 1779//1779 1780//1780 -f 1773//1773 1780//1780 1523//1523 -f 1523//1523 1780//1780 1781//1781 -f 1523//1523 1781//1781 1767//1767 -f 1778//1778 1774//1774 1772//1772 -f 1772//1772 1774//1774 1773//1773 -f 1772//1772 1773//1773 1782//1782 -f 1782//1782 1773//1773 1659//1659 -f 1782//1782 1659//1659 1563//1563 -f 1563//1563 1659//1659 1658//1658 -f 1563//1563 1658//1658 1564//1564 -f 1783//1783 1784//1784 1785//1785 -f 1786//1786 1787//1787 1788//1788 -f 1788//1788 1787//1787 1789//1789 -f 1788//1788 1789//1789 1790//1790 -f 1790//1790 1789//1789 1791//1791 -f 1548//1548 1547//1547 1792//1792 -f 1793//1793 1794//1794 1795//1795 -f 1795//1795 1794//1794 1796//1796 -f 1795//1795 1796//1796 1797//1797 -f 1797//1797 1796//1796 1549//1549 -f 1797//1797 1549//1549 1798//1798 -f 1520//1520 1799//1799 1800//1800 -f 1801//1801 1802//1802 1803//1803 -f 1801//1801 1803//1803 1804//1804 -f 1799//1799 1520//1520 1805//1805 -f 1805//1805 1520//1520 1517//1517 -f 1805//1805 1517//1517 1785//1785 -f 1785//1785 1517//1517 1806//1806 -f 1785//1785 1806//1806 1783//1783 -f 1807//1807 1808//1808 1809//1809 -f 1809//1809 1808//1808 1810//1810 -f 1809//1809 1810//1810 1811//1811 -f 1812//1812 1813//1813 1543//1543 -f 1543//1543 1813//1813 1814//1814 -f 1543//1543 1814//1814 1815//1815 -f 1811//1811 1810//1810 1816//1816 -f 1816//1816 1810//1810 1716//1716 -f 1816//1816 1716//1716 1817//1817 -f 1817//1817 1716//1716 1715//1715 -f 1817//1817 1715//1715 1818//1818 -f 1819//1819 1820//1820 1795//1795 -f 1821//1821 1822//1822 1823//1823 -f 1824//1824 1793//1793 1821//1821 -f 1821//1821 1793//1793 1795//1795 -f 1821//1821 1795//1795 1822//1822 -f 1822//1822 1795//1795 1820//1820 -f 1807//1807 1812//1812 1808//1808 -f 1808//1808 1812//1812 1543//1543 -f 1808//1808 1543//1543 1825//1825 -f 1825//1825 1543//1543 1542//1542 -f 1825//1825 1826//1826 1808//1808 -f 1808//1808 1826//1826 1827//1827 -f 1808//1808 1827//1827 1828//1828 -f 1828//1828 1827//1827 1829//1829 -f 1828//1828 1829//1829 1830//1830 -f 1831//1831 1832//1832 1833//1833 -f 1833//1833 1832//1832 1834//1834 -f 1833//1833 1834//1834 1798//1798 -f 1798//1798 1834//1834 1835//1835 -f 1798//1798 1835//1835 1538//1538 -f 1836//1836 1837//1837 1838//1838 -f 1838//1838 1837//1837 1839//1839 -f 1838//1838 1839//1839 1840//1840 -f 1539//1539 1841//1841 1842//1842 -f 1842//1842 1841//1841 1843//1843 -f 1842//1842 1843//1843 1839//1839 -f 1839//1839 1843//1843 1844//1844 -f 1839//1839 1844//1844 1840//1840 -f 1845//1845 1839//1839 1846//1846 -f 1847//1847 1848//1848 1837//1837 -f 1837//1837 1848//1848 1849//1849 -f 1849//1849 1850//1850 1837//1837 -f 1837//1837 1850//1850 1851//1851 -f 1837//1837 1851//1851 1839//1839 -f 1839//1839 1851//1851 1852//1852 -f 1839//1839 1852//1852 1846//1846 -f 1846//1846 1853//1853 1845//1845 -f 1845//1845 1853//1853 1854//1854 -f 1845//1845 1854//1854 1551//1551 -f 1854//1854 1855//1855 1551//1551 -f 1551//1551 1855//1855 1856//1856 -f 1551//1551 1856//1856 1552//1552 -f 1552//1552 1856//1856 1857//1857 -f 1552//1552 1857//1857 1847//1847 -f 1847//1847 1857//1857 1858//1858 -f 1847//1847 1858//1858 1848//1848 -f 1859//1859 1860//1860 1521//1521 -f 1861//1861 1862//1862 1525//1525 -f 1525//1525 1862//1862 1863//1863 -f 1525//1525 1863//1863 1526//1526 -f 1864//1864 1865//1865 1866//1866 -f 1514//1514 1867//1867 1868//1868 -f 1864//1864 1692//1692 1869//1869 -f 1869//1869 1692//1692 1697//1697 -f 1869//1869 1697//1697 1870//1870 -f 1870//1870 1697//1697 1871//1871 -f 1870//1870 1871//1871 1868//1868 -f 1868//1868 1871//1871 1872//1872 -f 1868//1868 1872//1872 1514//1514 -f 1685//1685 1684//1684 1873//1873 -f 1873//1873 1684//1684 1681//1681 -f 1873//1873 1681//1681 1874//1874 -f 1874//1874 1681//1681 1680//1680 -f 1874//1874 1680//1680 1875//1875 -f 1875//1875 1680//1680 1678//1678 -f 1875//1875 1678//1678 1536//1536 -f 1557//1557 1876//1876 1726//1726 -f 1726//1726 1876//1876 1877//1877 -f 1726//1726 1877//1877 1878//1878 -f 1878//1878 1877//1877 1879//1879 -f 1878//1878 1879//1879 1880//1880 -f 1880//1880 1879//1879 1881//1881 -f 1880//1880 1881//1881 1882//1882 -f 1882//1882 1881//1881 1535//1535 -f 1580//1580 1754//1754 1581//1581 -f 1581//1581 1754//1754 1883//1883 -f 1581//1581 1883//1883 1532//1532 -f 1521//1521 1884//1884 1568//1568 -f 1568//1568 1884//1884 1885//1885 -f 1568//1568 1885//1885 1886//1886 -f 1886//1886 1885//1885 1887//1887 -f 1886//1886 1887//1887 1534//1534 -f 1534//1534 1887//1887 1888//1888 -f 1534//1534 1888//1888 1532//1532 -f 1532//1532 1888//1888 1889//1889 -f 1532//1532 1889//1889 1581//1581 -f 1581//1581 1889//1889 1890//1890 -f 1581//1581 1890//1890 1577//1577 -f 1577//1577 1890//1890 1891//1891 -f 1577//1577 1891//1891 1706//1706 -f 1385//1385 1383//1383 1530//1530 -f 1530//1530 1383//1383 1381//1381 -f 1530//1530 1381//1381 1892//1892 -f 1620//1620 1369//1369 1391//1391 -f 1369//1369 1620//1620 1371//1371 -f 1371//1371 1620//1620 1622//1622 -f 1371//1371 1622//1622 1373//1373 -f 1381//1381 1379//1379 1892//1892 -f 1892//1892 1379//1379 1377//1377 -f 1892//1892 1377//1377 1622//1622 -f 1622//1622 1377//1377 1375//1375 -f 1622//1622 1375//1375 1373//1373 -f 1389//1389 1387//1387 1893//1893 -f 1602//1602 1606//1606 1603//1603 -f 1603//1603 1606//1606 1393//1393 -f 1603//1603 1393//1393 1415//1415 -f 1415//1415 1413//1413 1603//1603 -f 1603//1603 1413//1413 1411//1411 -f 1603//1603 1411//1411 1528//1528 -f 1411//1411 1409//1409 1528//1528 -f 1528//1528 1409//1409 1407//1407 -f 1528//1528 1407//1407 1529//1529 -f 1529//1529 1407//1407 1405//1405 -f 1529//1529 1405//1405 1403//1403 -f 1518//1518 1399//1399 1519//1519 -f 1519//1519 1399//1399 1397//1397 -f 1519//1519 1397//1397 1606//1606 -f 1606//1606 1397//1397 1395//1395 -f 1606//1606 1395//1395 1393//1393 -f 1521//1521 1860//1860 1884//1884 -f 1884//1884 1860//1860 1894//1894 -f 1884//1884 1894//1894 1885//1885 -f 1885//1885 1894//1894 1861//1861 -f 1885//1885 1861//1861 1895//1895 -f 1895//1895 1861//1861 1525//1525 -f 1895//1895 1525//1525 1896//1896 -f 1896//1896 1525//1525 1524//1524 -f 1896//1896 1524//1524 1897//1897 -f 1897//1897 1524//1524 1598//1598 -f 1897//1897 1598//1598 1898//1898 -f 1898//1898 1598//1598 1603//1603 -f 1898//1898 1603//1603 1899//1899 -f 1899//1899 1603//1603 1528//1528 -f 1899//1899 1528//1528 1900//1900 -f 1900//1900 1528//1528 1527//1527 -f 1900//1900 1527//1527 1901//1901 -f 1714//1714 1901//1901 1709//1709 -f 1709//1709 1901//1901 1527//1527 -f 1709//1709 1527//1527 1902//1902 -f 1902//1902 1527//1527 1529//1529 -f 1902//1902 1529//1529 1518//1518 -f 1518//1518 1529//1529 1401//1401 -f 1518//1518 1401//1401 1399//1399 -f 1600//1600 1763//1763 1903//1903 -f 1903//1903 1763//1763 1765//1765 -f 1903//1903 1765//1765 1904//1904 -f 1904//1904 1765//1765 1905//1905 -f 1904//1904 1905//1905 1655//1655 -f 1655//1655 1905//1905 1906//1906 -f 1655//1655 1906//1906 1562//1562 -f 1562//1562 1906//1906 1907//1907 -f 1562//1562 1907//1907 1563//1563 -f 1563//1563 1907//1907 1908//1908 -f 1563//1563 1908//1908 1782//1782 -f 1771//1771 1766//1766 1909//1909 -f 1909//1909 1766//1766 1763//1763 -f 1909//1909 1763//1763 1526//1526 -f 1526//1526 1763//1763 1600//1600 -f 1526//1526 1600//1600 1524//1524 -f 1524//1524 1600//1600 1599//1599 -f 1524//1524 1599//1599 1596//1596 -f 1863//1863 1859//1859 1526//1526 -f 1526//1526 1859//1859 1521//1521 -f 1526//1526 1521//1521 1909//1909 -f 1909//1909 1521//1521 1523//1523 -f 1909//1909 1523//1523 1771//1771 -f 1771//1771 1523//1523 1768//1768 -f 1771//1771 1768//1768 1769//1769 -f 1823//1823 1541//1541 1821//1821 -f 1821//1821 1541//1541 1543//1543 -f 1821//1821 1543//1543 1546//1546 -f 1546//1546 1543//1543 1815//1815 -f 1546//1546 1815//1815 1544//1544 -f 1802//1802 1824//1824 1803//1803 -f 1803//1803 1824//1824 1821//1821 -f 1803//1803 1821//1821 1910//1910 -f 1910//1910 1821//1821 1546//1546 -f 1910//1910 1546//1546 1715//1715 -f 1715//1715 1546//1546 1545//1545 -f 1715//1715 1545//1545 1818//1818 -f 1800//1800 1804//1804 1520//1520 -f 1520//1520 1804//1804 1803//1803 -f 1520//1520 1803//1803 1518//1518 -f 1518//1518 1803//1803 1910//1910 -f 1518//1518 1910//1910 1902//1902 -f 1902//1902 1910//1910 1715//1715 -f 1902//1902 1715//1715 1709//1709 -f 1709//1709 1715//1715 1717//1717 -f 1709//1709 1717//1717 1710//1710 -f 1517//1517 1516//1516 1911//1911 -f 1516//1516 1912//1912 1911//1911 -f 1911//1911 1912//1912 1913//1913 -f 1911//1911 1913//1913 1914//1914 -f 1914//1914 1519//1519 1911//1911 -f 1911//1911 1519//1519 1606//1606 -f 1911//1911 1606//1606 1567//1567 -f 1567//1567 1606//1606 1605//1605 -f 1567//1567 1605//1605 1565//1565 -f 1914//1914 1915//1915 1519//1519 -f 1519//1519 1915//1915 1916//1916 -f 1519//1519 1916//1916 1520//1520 -f 1520//1520 1916//1916 1917//1917 -f 1520//1520 1917//1917 1918//1918 -f 1918//1918 1919//1919 1520//1520 -f 1520//1520 1919//1919 1920//1920 -f 1520//1520 1920//1920 1517//1517 -f 1517//1517 1920//1920 1921//1921 -f 1517//1517 1921//1921 1515//1515 -f 1670//1670 1669//1669 1673//1673 -f 1673//1673 1669//1669 1733//1733 -f 1673//1673 1733//1733 1576//1576 -f 1576//1576 1733//1733 1739//1739 -f 1576//1576 1739//1739 1735//1735 -f 1539//1539 1842//1842 1540//1540 -f 1540//1540 1842//1842 1922//1922 -f 1540//1540 1922//1922 1923//1923 -f 1923//1923 1922//1922 1828//1828 -f 1923//1923 1828//1828 1924//1924 -f 1924//1924 1828//1828 1830//1830 -f 1924//1924 1830//1830 1925//1925 -f 1538//1538 1540//1540 1798//1798 -f 1798//1798 1540//1540 1923//1923 -f 1798//1798 1923//1923 1797//1797 -f 1797//1797 1923//1923 1924//1924 -f 1797//1797 1924//1924 1795//1795 -f 1795//1795 1924//1924 1925//1925 -f 1795//1795 1925//1925 1819//1819 -f 1536//1536 1678//1678 1537//1537 -f 1537//1537 1678//1678 1673//1673 -f 1537//1537 1673//1673 1926//1926 -f 1926//1926 1673//1673 1576//1576 -f 1926//1926 1576//1576 1927//1927 -f 1927//1927 1576//1576 1575//1575 -f 1927//1927 1575//1575 1928//1928 -f 1535//1535 1537//1537 1882//1882 -f 1882//1882 1537//1537 1926//1926 -f 1882//1882 1926//1926 1929//1929 -f 1929//1929 1926//1926 1927//1927 -f 1929//1929 1927//1927 1591//1591 -f 1591//1591 1927//1927 1928//1928 -f 1591//1591 1928//1928 1592//1592 -f 1784//1784 1783//1783 1791//1791 -f 1791//1791 1783//1783 1930//1930 -f 1791//1791 1930//1930 1790//1790 -f 1790//1790 1930//1930 1931//1931 -f 1790//1790 1931//1931 1788//1788 -f 1792//1792 1893//1893 1531//1531 -f 1531//1531 1893//1893 1387//1387 -f 1531//1531 1387//1387 1385//1385 -f 1932//1932 1933//1933 1931//1931 -f 1934//1934 1935//1935 1788//1788 -f 1931//1931 1933//1933 1788//1788 -f 1788//1788 1933//1933 1936//1936 -f 1788//1788 1936//1936 1934//1934 -f 1547//1547 1786//1786 1792//1792 -f 1792//1792 1786//1786 1788//1788 -f 1792//1792 1788//1788 1893//1893 -f 1893//1893 1788//1788 1935//1935 -f 1937//1937 1938//1938 1939//1939 -f 1939//1939 1938//1938 1940//1940 -f 1939//1939 1940//1940 1931//1931 -f 1931//1931 1940//1940 1941//1941 -f 1931//1931 1941//1941 1932//1932 -f 1935//1935 1942//1942 1893//1893 -f 1893//1893 1942//1942 1943//1943 -f 1893//1893 1943//1943 1939//1939 -f 1939//1939 1943//1943 1944//1944 -f 1939//1939 1944//1944 1937//1937 -f 1566//1566 1600//1600 1567//1567 -f 1567//1567 1600//1600 1903//1903 -f 1567//1567 1903//1903 1911//1911 -f 1911//1911 1903//1903 1904//1904 -f 1911//1911 1904//1904 1517//1517 -f 1517//1517 1904//1904 1655//1655 -f 1517//1517 1655//1655 1806//1806 -f 1806//1806 1655//1655 1652//1652 -f 1806//1806 1652//1652 1783//1783 -f 1783//1783 1652//1652 1650//1650 -f 1783//1783 1650//1650 1930//1930 -f 1930//1930 1650//1650 1648//1648 -f 1930//1930 1648//1648 1931//1931 -f 1931//1931 1648//1648 1647//1647 -f 1931//1931 1647//1647 1939//1939 -f 1721//1721 1552//1552 1724//1724 -f 1724//1724 1552//1552 1847//1847 -f 1724//1724 1847//1847 1945//1945 -f 1945//1945 1847//1847 1837//1837 -f 1945//1945 1837//1837 1833//1833 -f 1833//1833 1837//1837 1836//1836 -f 1833//1833 1836//1836 1831//1831 -f 1391//1391 1389//1389 1620//1620 -f 1620//1620 1389//1389 1893//1893 -f 1620//1620 1893//1893 1613//1613 -f 1613//1613 1893//1893 1939//1939 -f 1613//1613 1939//1939 1612//1612 -f 1612//1612 1939//1939 1647//1647 -f 1612//1612 1647//1647 1946//1946 -f 1639//1639 1640//1640 1629//1629 -f 1629//1629 1640//1640 1642//1642 -f 1629//1629 1642//1642 1513//1513 -f 1513//1513 1642//1642 1866//1866 -f 1513//1513 1866//1866 1514//1514 -f 1514//1514 1866//1866 1865//1865 -f 1514//1514 1865//1865 1867//1867 -f 1864//1864 1866//1866 1692//1692 -f 1692//1692 1866//1866 1642//1642 -f 1692//1692 1642//1642 1663//1663 -f 1663//1663 1642//1642 1632//1632 -f 1663//1663 1632//1632 1664//1664 -f 1664//1664 1632//1632 1661//1661 -f 1664//1664 1661//1661 1666//1666 -f 1666//1666 1661//1661 1660//1660 -f 1666//1666 1660//1660 1669//1669 -f 1669//1669 1660//1660 1659//1659 -f 1669//1669 1659//1659 1733//1733 -f 1733//1733 1659//1659 1773//1773 -f 1733//1733 1773//1773 1734//1734 -f 1734//1734 1773//1773 1523//1523 -f 1734//1734 1523//1523 1743//1743 -f 1743//1743 1523//1523 1522//1522 -f 1743//1743 1522//1522 1748//1748 -f 1748//1748 1522//1522 1571//1571 -f 1748//1748 1571//1571 1534//1534 -f 1534//1534 1571//1571 1947//1947 -f 1534//1534 1947//1947 1886//1886 -f 1549//1549 1548//1548 1798//1798 -f 1798//1798 1548//1548 1792//1792 -f 1798//1798 1792//1792 1833//1833 -f 1833//1833 1792//1792 1531//1531 -f 1833//1833 1531//1531 1945//1945 -f 1945//1945 1531//1531 1530//1530 -f 1945//1945 1530//1530 1724//1724 -f 1724//1724 1530//1530 1892//1892 -f 1724//1724 1892//1892 1725//1725 -f 1946//1946 1948//1948 1612//1612 -f 1612//1612 1948//1948 1616//1616 -f 1612//1612 1616//1616 1610//1610 -f 1610//1610 1616//1616 1617//1617 -f 1649//1649 1646//1646 1647//1647 -f 1647//1647 1646//1646 1512//1512 -f 1647//1647 1512//1512 1946//1946 -f 1946//1946 1512//1512 1514//1514 -f 1946//1946 1514//1514 1949//1949 -f 1949//1949 1950//1950 1946//1946 -f 1946//1946 1950//1950 1951//1951 -f 1946//1946 1951//1951 1948//1948 -f 1948//1948 1951//1951 1952//1952 -f 1948//1948 1952//1952 1872//1872 -f 1872//1872 1952//1952 1953//1953 -f 1872//1872 1953//1953 1514//1514 -f 1514//1514 1953//1953 1954//1954 -f 1514//1514 1954//1954 1949//1949 -f 1827//1827 1955//1955 1829//1829 -f 1829//1829 1955//1955 1956//1956 -f 1829//1829 1956//1956 1830//1830 -f 1830//1830 1956//1956 1957//1957 -f 1830//1830 1957//1957 1925//1925 -f 1925//1925 1957//1957 1958//1958 -f 1925//1925 1958//1958 1819//1819 -f 1819//1819 1958//1958 1959//1959 -f 1819//1819 1959//1959 1820//1820 -f 1820//1820 1959//1959 1960//1960 -f 1820//1820 1960//1960 1822//1822 -f 1822//1822 1960//1960 1961//1961 -f 1822//1822 1961//1961 1823//1823 -f 1823//1823 1961//1961 1962//1962 -f 1823//1823 1962//1962 1541//1541 -f 1541//1541 1962//1962 1963//1963 -f 1541//1541 1963//1963 1542//1542 -f 1542//1542 1963//1963 1964//1964 -f 1542//1542 1964//1964 1825//1825 -f 1825//1825 1964//1964 1965//1965 -f 1825//1825 1965//1965 1826//1826 -f 1826//1826 1965//1965 1966//1966 -f 1826//1826 1966//1966 1827//1827 -f 1827//1827 1966//1966 1955//1955 -f 1917//1917 1967//1967 1918//1918 -f 1918//1918 1967//1967 1968//1968 -f 1918//1918 1968//1968 1919//1919 -f 1919//1919 1968//1968 1969//1969 -f 1919//1919 1969//1969 1920//1920 -f 1920//1920 1969//1969 1970//1970 -f 1920//1920 1970//1970 1921//1921 -f 1921//1921 1970//1970 1971//1971 -f 1921//1921 1971//1971 1515//1515 -f 1515//1515 1971//1971 1972//1972 -f 1515//1515 1972//1972 1516//1516 -f 1516//1516 1972//1972 1973//1973 -f 1516//1516 1973//1973 1912//1912 -f 1912//1912 1973//1973 1974//1974 -f 1912//1912 1974//1974 1913//1913 -f 1913//1913 1974//1974 1975//1975 -f 1913//1913 1975//1975 1914//1914 -f 1914//1914 1975//1975 1976//1976 -f 1914//1914 1976//1976 1915//1915 -f 1915//1915 1976//1976 1977//1977 -f 1915//1915 1977//1977 1916//1916 -f 1916//1916 1977//1977 1978//1978 -f 1916//1916 1978//1978 1917//1917 -f 1917//1917 1978//1978 1967//1967 -f 1776//1776 1979//1979 1777//1777 -f 1777//1777 1979//1979 1980//1980 -f 1777//1777 1980//1980 1778//1778 -f 1778//1778 1980//1980 1981//1981 -f 1778//1778 1981//1981 1774//1774 -f 1774//1774 1981//1981 1982//1982 -f 1774//1774 1982//1982 1775//1775 -f 1775//1775 1982//1982 1983//1983 -f 1775//1775 1983//1983 1779//1779 -f 1779//1779 1983//1983 1984//1984 -f 1779//1779 1984//1984 1780//1780 -f 1780//1780 1984//1984 1985//1985 -f 1780//1780 1985//1985 1781//1781 -f 1781//1781 1985//1985 1986//1986 -f 1781//1781 1986//1986 1767//1767 -f 1767//1767 1986//1986 1987//1987 -f 1767//1767 1987//1987 1768//1768 -f 1768//1768 1987//1987 1988//1988 -f 1768//1768 1988//1988 1769//1769 -f 1769//1769 1988//1988 1989//1989 -f 1769//1769 1989//1989 1770//1770 -f 1770//1770 1989//1989 1990//1990 -f 1770//1770 1990//1990 1776//1776 -f 1776//1776 1990//1990 1979//1979 -f 1844//1844 1991//1991 1840//1840 -f 1840//1840 1991//1991 1992//1992 -f 1840//1840 1992//1992 1838//1838 -f 1838//1838 1992//1992 1993//1993 -f 1838//1838 1993//1993 1836//1836 -f 1836//1836 1993//1993 1994//1994 -f 1836//1836 1994//1994 1831//1831 -f 1831//1831 1994//1994 1995//1995 -f 1831//1831 1995//1995 1832//1832 -f 1832//1832 1995//1995 1996//1996 -f 1832//1832 1996//1996 1834//1834 -f 1834//1834 1996//1996 1997//1997 -f 1834//1834 1997//1997 1835//1835 -f 1835//1835 1997//1997 1998//1998 -f 1835//1835 1998//1998 1538//1538 -f 1538//1538 1998//1998 1999//1999 -f 1538//1538 1999//1999 1539//1539 -f 1539//1539 1999//1999 2000//2000 -f 1539//1539 2000//2000 1841//1841 -f 1841//1841 2000//2000 2001//2001 -f 1841//1841 2001//2001 1843//1843 -f 1843//1843 2001//2001 2002//2002 -f 1843//1843 2002//2002 1844//1844 -f 1844//1844 2002//2002 1991//1991 -f 1637//1637 2003//2003 1638//1638 -f 1638//1638 2003//2003 2004//2004 -f 1638//1638 2004//2004 1639//1639 -f 1639//1639 2004//2004 2005//2005 -f 1639//1639 2005//2005 1640//1640 -f 1640//1640 2005//2005 2006//2006 -f 1640//1640 2006//2006 1641//1641 -f 1641//1641 2006//2006 2007//2007 -f 1641//1641 2007//2007 1643//1643 -f 1643//1643 2007//2007 2008//2008 -f 1643//1643 2008//2008 1644//1644 -f 1644//1644 2008//2008 2009//2009 -f 1644//1644 2009//2009 1630//1630 -f 1630//1630 2009//2009 2010//2010 -f 1630//1630 2010//2010 1631//1631 -f 1631//1631 2010//2010 2011//2011 -f 1631//1631 2011//2011 1633//1633 -f 1633//1633 2011//2011 2012//2012 -f 1633//1633 2012//2012 1634//1634 -f 1634//1634 2012//2012 2013//2013 -f 1634//1634 2013//2013 1635//1635 -f 1635//1635 2013//2013 2014//2014 -f 1635//1635 2014//2014 1637//1637 -f 1637//1637 2014//2014 2003//2003 -f 1935//1935 2015//2015 1942//1942 -f 1942//1942 2015//2015 2016//2016 -f 1942//1942 2016//2016 1943//1943 -f 1943//1943 2016//2016 2017//2017 -f 1943//1943 2017//2017 1944//1944 -f 1944//1944 2017//2017 2018//2018 -f 1944//1944 2018//2018 1937//1937 -f 1937//1937 2018//2018 2019//2019 -f 1937//1937 2019//2019 1938//1938 -f 1938//1938 2019//2019 2020//2020 -f 1938//1938 2020//2020 1940//1940 -f 1940//1940 2020//2020 2021//2021 -f 1940//1940 2021//2021 1941//1941 -f 1941//1941 2021//2021 2022//2022 -f 1941//1941 2022//2022 1932//1932 -f 1932//1932 2022//2022 2023//2023 -f 1932//1932 2023//2023 1933//1933 -f 1933//1933 2023//2023 2024//2024 -f 1933//1933 2024//2024 1936//1936 -f 1936//1936 2024//2024 2025//2025 -f 1936//1936 2025//2025 1934//1934 -f 1934//1934 2025//2025 2026//2026 -f 1934//1934 2026//2026 1935//1935 -f 1935//1935 2026//2026 2015//2015 -f 1717//1717 1716//1716 2027//2027 -f 2027//2027 1716//1716 1810//1810 -f 1810//1810 1808//1808 2027//2027 -f 2027//2027 1808//1808 1828//1828 -f 2027//2027 1828//1828 2028//2028 -f 1828//1828 1922//1922 2028//2028 -f 2028//2028 1922//1922 1842//1842 -f 2028//2028 1842//1842 1839//1839 -f 1839//1839 1845//1845 2028//2028 -f 2028//2028 1845//1845 1551//1551 -f 2028//2028 1551//1551 1550//1550 -f 2029//2029 1721//1721 1725//1725 -f 1725//1725 1892//1892 2029//2029 -f 2029//2029 1892//1892 1622//1622 -f 2029//2029 1622//1622 1614//1614 -f 1614//1614 1616//1616 2029//2029 -f 2029//2029 1616//1616 1948//1948 -f 2029//2029 1948//1948 2030//2030 -f 2030//2030 1948//1948 1872//1872 -f 2030//2030 1872//1872 1871//1871 -f 1871//1871 1697//1697 2030//2030 -f 2030//2030 1697//1697 1689//1689 -f 2030//2030 1689//1689 1688//1688 -f 2031//2031 1727//1727 1726//1726 -f 1726//1726 1878//1878 2031//2031 -f 2031//2031 1878//1878 1880//1880 -f 2031//2031 1880//1880 1882//1882 -f 1882//1882 1929//1929 2031//2031 -f 2031//2031 1929//1929 1591//1591 -f 2031//2031 1591//1591 2032//2032 -f 2032//2032 1591//1591 1593//1593 -f 1593//1593 1589//1589 2032//2032 -f 2032//2032 1589//1589 1588//1588 -f 2032//2032 1588//1588 1586//1586 -f 1890//1890 1889//1889 2033//2033 -f 2033//2033 1889//1889 1888//1888 -f 1888//1888 1887//1887 2033//2033 -f 2033//2033 1887//1887 1885//1885 -f 2033//2033 1885//1885 2034//2034 -f 2034//2034 1885//1885 1895//1895 -f 1895//1895 1896//1896 2034//2034 -f 2034//2034 1896//1896 1897//1897 -f 2034//2034 1897//1897 1898//1898 -f 1898//1898 1899//1899 2034//2034 -f 2034//2034 1899//1899 1900//1900 -f 2034//2034 1900//1900 1901//1901 -f 2035//2035 2036//2036 2037//2037 -f 2038//2038 2029//2029 2039//2039 -f 2039//2039 2029//2029 2030//2030 -f 2030//2030 2040//2040 2039//2039 -f 2039//2039 2040//2040 2041//2041 -f 2039//2039 2041//2041 2042//2042 -f 2034//2034 2043//2043 2033//2033 -f 2033//2033 2043//2043 2035//2035 -f 2033//2033 2035//2035 2044//2044 -f 2045//2045 2046//2046 2047//2047 -f 2048//2048 2049//2049 2028//2028 -f 2028//2028 2049//2049 2050//2050 -f 2028//2028 2050//2050 2027//2027 -f 2051//2051 2045//2045 2037//2037 -f 2037//2037 2045//2045 2047//2047 -f 2037//2037 2047//2047 2035//2035 -f 2035//2035 2047//2047 2052//2052 -f 2035//2035 2052//2052 2044//2044 -f 2045//2045 2053//2053 2046//2046 -f 2046//2046 2053//2053 2054//2054 -f 2046//2046 2054//2054 2055//2055 -f 2028//2028 2056//2056 2048//2048 -f 2048//2048 2056//2056 2057//2057 -f 2048//2048 2057//2057 2058//2058 -f 2058//2058 2057//2057 2059//2059 -f 2058//2058 2059//2059 2060//2060 -f 2050//2050 2061//2061 2027//2027 -f 2027//2027 2061//2061 2062//2062 -f 2027//2027 2062//2062 2063//2063 -f 2063//2063 2062//2062 2064//2064 -f 2063//2063 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2065//2065 2066//2066 2067//2067 -f 2038//2038 2068//2068 2029//2029 -f 2029//2029 2068//2068 2069//2069 -f 2029//2029 2069//2069 2070//2070 -f 2067//2067 2066//2066 2071//2071 -f 2071//2071 2066//2066 2072//2072 -f 2071//2071 2072//2072 2073//2073 -f 2073//2073 2072//2072 2074//2074 -f 2073//2073 2074//2074 2034//2034 -f 2034//2034 2074//2074 2075//2075 -f 2034//2034 2075//2075 2076//2076 -f 2077//2077 2078//2078 2079//2079 -f 2079//2079 2078//2078 2080//2080 -f 2059//2059 2081//2081 2060//2060 -f 2060//2060 2081//2081 2082//2082 -f 2060//2060 2082//2082 2083//2083 -f 2083//2083 2082//2082 2029//2029 -f 2083//2083 2029//2029 2084//2084 -f 2084//2084 2029//2029 2070//2070 -f 2084//2084 2070//2070 2085//2085 -f 2086//2086 2043//2043 2087//2087 -f 2087//2087 2043//2043 2034//2034 -f 2087//2087 2034//2034 2088//2088 -f 2088//2088 2034//2034 2076//2076 -f 2089//2089 2090//2090 2091//2091 -f 2055//2055 2054//2054 2032//2032 -f 2032//2032 2054//2054 2079//2079 -f 2032//2032 2079//2079 2031//2031 -f 2031//2031 2079//2079 2080//2080 -f 2031//2031 2080//2080 2092//2092 -f 2092//2092 2080//2080 2093//2093 -f 2092//2092 2093//2093 2094//2094 -f 2095//2095 2039//2039 2091//2091 -f 2091//2091 2039//2039 2042//2042 -f 2091//2091 2042//2042 2089//2089 -f 2089//2089 2042//2042 2094//2094 -f 2089//2089 2094//2094 2096//2096 -f 2096//2096 2094//2094 2093//2093 -f 1677//1677 2097//2097 1671//1671 -f 1671//1671 2097//2097 2098//2098 -f 1671//1671 2098//2098 1672//1672 -f 1672//1672 2098//2098 2099//2099 -f 1672//1672 2099//2099 1670//1670 -f 1670//1670 2099//2099 2100//2100 -f 1667//1667 2101//2101 1668//1668 -f 1668//1668 2101//2101 2102//2102 -f 1668//1668 2102//2102 1674//1674 -f 1674//1674 2102//2102 2103//2103 -f 1674//1674 2103//2103 1675//1675 -f 1675//1675 2103//2103 2104//2104 -f 1670//1670 2100//2100 1667//1667 -f 1667//1667 2100//2100 2101//2101 -f 1702//1702 2105//2105 1703//1703 -f 1703//1703 2105//2105 2106//2106 -f 1703//1703 2106//2106 1704//1704 -f 1704//1704 2106//2106 2107//2107 -f 1704//1704 2107//2107 1553//1553 -f 1553//1553 2107//2107 2108//2108 -f 2105//2105 1702//1702 2109//2109 -f 2109//2109 1702//1702 1665//1665 -f 2109//2109 1665//1665 2110//2110 -f 2110//2110 1665//1665 1676//1676 -f 2110//2110 1676//1676 2104//2104 -f 2104//2104 1676//1676 1675//1675 -f 1553//1553 2108//2108 1554//1554 -f 1554//1554 2108//2108 2111//2111 -f 1560//1560 2112//2112 2113//2113 -f 1560//1560 2113//2113 1561//1561 -f 1561//1561 2113//2113 2114//2114 -f 1561//1561 2114//2114 1679//1679 -f 1679//1679 2114//2114 2097//2097 -f 1679//1679 2097//2097 1677//1677 -f 1794//1794 2115//2115 1796//1796 -f 1796//1796 2115//2115 2116//2116 -f 1796//1796 2116//2116 1549//1549 -f 1549//1549 2116//2116 2117//2117 -f 1549//1549 2117//2117 1547//1547 -f 1547//1547 2117//2117 2118//2118 -f 1547//1547 2118//2118 1786//1786 -f 1786//1786 2118//2118 2119//2119 -f 1786//1786 2119//2119 1787//1787 -f 1787//1787 2119//2119 2120//2120 -f 1787//1787 2120//2120 1789//1789 -f 1789//1789 2120//2120 2121//2121 -f 1789//1789 2121//2121 1791//1791 -f 1791//1791 2121//2121 2122//2122 -f 1791//1791 2122//2122 1784//1784 -f 1784//1784 2122//2122 2123//2123 -f 1784//1784 2123//2123 1785//1785 -f 1785//1785 2123//2123 2124//2124 -f 1785//1785 2124//2124 1805//1805 -f 1805//1805 2124//2124 2125//2125 -f 1805//1805 2125//2125 1799//1799 -f 1799//1799 2125//2125 2126//2126 -f 1799//1799 2126//2126 1800//1800 -f 1800//1800 2126//2126 2127//2127 -f 1800//1800 2127//2127 1804//1804 -f 1804//1804 2127//2127 2128//2128 -f 1804//1804 2128//2128 1801//1801 -f 1801//1801 2128//2128 2129//2129 -f 1801//1801 2129//2129 1802//1802 -f 1802//1802 2129//2129 2130//2130 -f 1802//1802 2130//2130 1824//1824 -f 1824//1824 2130//2130 2131//2131 -f 1824//1824 2131//2131 1793//1793 -f 1793//1793 2131//2131 2132//2132 -f 1793//1793 2132//2132 1794//1794 -f 1794//1794 2132//2132 2115//2115 -f 2133//2133 2134//2134 2135//2135 -f 2136//2136 2137//2137 2138//2138 -f 1475//1475 1473//1473 2139//2139 -f 2140//2140 2141//2141 2142//2142 -f 2143//2143 2144//2144 2145//2145 -f 2146//2146 2147//2147 2148//2148 -f 2149//2149 2150//2150 2151//2151 -f 2151//2151 2152//2152 2149//2149 -f 2149//2149 2152//2152 2153//2153 -f 2149//2149 2153//2153 2154//2154 -f 2155//2155 2156//2156 2157//2157 -f 2156//2156 2158//2158 2157//2157 -f 2157//2157 2158//2158 2159//2159 -f 2157//2157 2159//2159 2160//2160 -f 2160//2160 2159//2159 2161//2161 -f 2160//2160 2161//2161 2146//2146 -f 2162//2162 2163//2163 2164//2164 -f 2164//2164 2163//2163 2165//2165 -f 2164//2164 2165//2165 2166//2166 -f 2166//2166 2165//2165 2167//2167 -f 2166//2166 2167//2167 2168//2168 -f 2168//2168 2167//2167 2169//2169 -f 2168//2168 2169//2169 2170//2170 -f 2170//2170 2169//2169 2171//2171 -f 2170//2170 2171//2171 2172//2172 -f 2172//2172 2171//2171 2173//2173 -f 2174//2174 2175//2175 2176//2176 -f 2175//2175 2177//2177 2176//2176 -f 2176//2176 2177//2177 2178//2178 -f 2176//2176 2178//2178 2179//2179 -f 2180//2180 2181//2181 2182//2182 -f 2182//2182 2181//2181 2183//2183 -f 2182//2182 2184//2184 2185//2185 -f 2186//2186 2187//2187 2183//2183 -f 2183//2183 2187//2187 2188//2188 -f 2183//2183 2188//2188 2182//2182 -f 2182//2182 2188//2188 2189//2189 -f 2182//2182 2189//2189 2184//2184 -f 2190//2190 2182//2182 2191//2191 -f 2191//2191 2182//2182 2185//2185 -f 2191//2191 2185//2185 2192//2192 -f 2192//2192 2185//2185 2193//2193 -f 2192//2192 2193//2193 2194//2194 -f 2195//2195 2196//2196 2197//2197 -f 2197//2197 2196//2196 2198//2198 -f 2197//2197 2198//2198 2199//2199 -f 2198//2198 2200//2200 2199//2199 -f 2199//2199 2200//2200 2201//2201 -f 2199//2199 2201//2201 2202//2202 -f 2202//2202 2203//2203 2199//2199 -f 2199//2199 2203//2203 2204//2204 -f 2199//2199 2204//2204 2142//2142 -f 2142//2142 2204//2204 2205//2205 -f 2142//2142 2205//2205 2140//2140 -f 2202//2202 2206//2206 2203//2203 -f 2203//2203 2206//2206 2207//2207 -f 2203//2203 2207//2207 2208//2208 -f 2208//2208 2207//2207 2209//2209 -f 2208//2208 2209//2209 2210//2210 -f 2210//2210 2209//2209 2211//2211 -f 2210//2210 2211//2211 2212//2212 -f 2212//2212 2211//2211 2213//2213 -f 2212//2212 2213//2213 2197//2197 -f 2197//2197 2213//2213 2214//2214 -f 2197//2197 2214//2214 2195//2195 -f 2215//2215 2216//2216 2217//2217 -f 2218//2218 2219//2219 2220//2220 -f 2220//2220 2221//2221 2218//2218 -f 2218//2218 2221//2221 2222//2222 -f 2218//2218 2222//2222 2223//2223 -f 2224//2224 2225//2225 2226//2226 -f 2216//2216 2215//2215 2226//2226 -f 2226//2226 2215//2215 2227//2227 -f 2226//2226 2227//2227 2224//2224 -f 2217//2217 2228//2228 2215//2215 -f 2215//2215 2228//2228 2229//2229 -f 2215//2215 2229//2229 2230//2230 -f 2230//2230 2229//2229 2231//2231 -f 2230//2230 2231//2231 2219//2219 -f 2219//2219 2231//2231 2232//2232 -f 2219//2219 2232//2232 2220//2220 -f 2230//2230 2233//2233 2234//2234 -f 2234//2234 2235//2235 2230//2230 -f 2230//2230 2235//2235 2236//2236 -f 2230//2230 2236//2236 2215//2215 -f 2237//2237 2238//2238 2239//2239 -f 2239//2239 2238//2238 2240//2240 -f 2239//2239 2240//2240 2241//2241 -f 2240//2240 2242//2242 2241//2241 -f 2241//2241 2242//2242 2243//2243 -f 2241//2241 2243//2243 2150//2150 -f 2150//2150 2243//2243 2244//2244 -f 2150//2150 2244//2244 2245//2245 -f 2245//2245 2246//2246 2150//2150 -f 2150//2150 2246//2246 2247//2247 -f 2150//2150 2247//2247 2248//2248 -f 2248//2248 2247//2247 2249//2249 -f 2248//2248 2249//2249 2250//2250 -f 2249//2249 2251//2251 2250//2250 -f 2250//2250 2251//2251 2252//2252 -f 2250//2250 2252//2252 2253//2253 -f 1471//1471 1469//1469 2254//2254 -f 2254//2254 1469//1469 1467//1467 -f 2254//2254 1467//1467 2255//2255 -f 2255//2255 1467//1467 1465//1465 -f 2255//2255 1465//1465 1487//1487 -f 1487//1487 1485//1485 2255//2255 -f 2255//2255 1485//1485 1483//1483 -f 2255//2255 1483//1483 2256//2256 -f 2256//2256 1483//1483 1481//1481 -f 2256//2256 1481//1481 2257//2257 -f 1481//1481 1479//1479 2257//2257 -f 2257//2257 1479//1479 1477//1477 -f 2257//2257 1477//1477 2258//2258 -f 2259//2259 1439//1439 1437//1437 -f 1429//1429 2260//2260 1431//1431 -f 1431//1431 2260//2260 2261//2261 -f 1431//1431 2261//2261 1433//1433 -f 1433//1433 2261//2261 1435//1435 -f 1429//1429 1427//1427 2260//2260 -f 2260//2260 1427//1427 1425//1425 -f 2260//2260 1425//1425 2163//2163 -f 2163//2163 1425//1425 1423//1423 -f 2163//2163 1423//1423 2165//2165 -f 2165//2165 1423//1423 1421//1421 -f 2165//2165 1421//1421 2262//2262 -f 2262//2262 1421//1421 1419//1419 -f 2262//2262 1419//1419 1417//1417 -f 2263//2263 2264//2264 2265//2265 -f 2266//2266 2267//2267 2265//2265 -f 2267//2267 2268//2268 2265//2265 -f 2265//2265 2268//2268 2269//2269 -f 2265//2265 2269//2269 2263//2263 -f 2270//2270 2271//2271 2272//2272 -f 2272//2272 2271//2271 2273//2273 -f 2263//2263 2274//2274 2264//2264 -f 2264//2264 2274//2274 2275//2275 -f 2264//2264 2275//2275 2171//2171 -f 2171//2171 2275//2275 2276//2276 -f 2171//2171 2276//2276 2173//2173 -f 2173//2173 2276//2276 2277//2277 -f 2173//2173 2277//2277 2270//2270 -f 2270//2270 2277//2277 2278//2278 -f 2270//2270 2278//2278 2271//2271 -f 2279//2279 2280//2280 2138//2138 -f 2138//2138 2280//2280 2281//2281 -f 2282//2282 2283//2283 2284//2284 -f 2284//2284 2283//2283 2285//2285 -f 2284//2284 2285//2285 2286//2286 -f 2287//2287 2288//2288 2289//2289 -f 2290//2290 2291//2291 2292//2292 -f 2290//2290 2292//2292 2293//2293 -f 2286//2286 2285//2285 2294//2294 -f 2294//2294 2285//2285 2295//2295 -f 2294//2294 2295//2295 2291//2291 -f 2296//2296 2297//2297 2298//2298 -f 2181//2181 2299//2299 2300//2300 -f 2300//2300 2301//2301 2181//2181 -f 2181//2181 2301//2301 2302//2302 -f 2181//2181 2302//2302 2183//2183 -f 2183//2183 2302//2302 2303//2303 -f 2183//2183 2303//2303 2304//2304 -f 2305//2305 2306//2306 2307//2307 -f 2307//2307 2306//2306 2308//2308 -f 2307//2307 2308//2308 2309//2309 -f 2309//2309 2308//2308 2310//2310 -f 2309//2309 2310//2310 2299//2299 -f 2299//2299 2310//2310 2311//2311 -f 2299//2299 2311//2311 2300//2300 -f 1995//1995 1994//1994 2197//2197 -f 2197//2197 1994//1994 1993//1993 -f 2197//2197 1993//1993 2212//2212 -f 2212//2212 1993//1993 1992//1992 -f 2212//2212 1992//1992 2312//2312 -f 2312//2312 1992//1992 1991//1991 -f 2312//2312 1991//1991 2313//2313 -f 2313//2313 1991//1991 2002//2002 -f 2314//2314 1997//1997 2315//2315 -f 2315//2315 1997//1997 1996//1996 -f 1999//1999 1998//1998 2316//2316 -f 1999//1999 2316//2316 2000//2000 -f 1961//1961 1960//1960 2317//2317 -f 1964//1964 1963//1963 2318//2318 -f 2318//2318 1963//1963 1962//1962 -f 2318//2318 1962//1962 2319//2319 -f 1965//1965 2218//2218 2224//2224 -f 2224//2224 2218//2218 2223//2223 -f 2224//2224 2223//2223 2225//2225 -f 1958//1958 1957//1957 2320//2320 -f 2320//2320 1957//1957 1956//1956 -f 2320//2320 1956//1956 2321//2321 -f 2321//2321 1956//1956 1955//1955 -f 2321//2321 1955//1955 2224//2224 -f 2224//2224 1955//1955 1966//1966 -f 2224//2224 1966//1966 1965//1965 -f 2322//2322 2323//2323 2324//2324 -f 2324//2324 2323//2323 2325//2325 -f 2012//2012 2011//2011 2326//2326 -f 2003//2003 2014//2014 2327//2327 -f 2327//2327 2014//2014 2013//2013 -f 2328//2328 2007//2007 2006//2006 -f 2011//2011 2010//2010 2326//2326 -f 2326//2326 2010//2010 2009//2009 -f 2326//2326 2009//2009 2328//2328 -f 2328//2328 2009//2009 2008//2008 -f 2328//2328 2008//2008 2007//2007 -f 2003//2003 2327//2327 2004//2004 -f 2004//2004 2327//2327 2322//2322 -f 2004//2004 2322//2322 2005//2005 -f 2329//2329 2330//2330 2331//2331 -f 2013//2013 2012//2012 2327//2327 -f 2327//2327 2012//2012 2326//2326 -f 2327//2327 2326//2326 2332//2332 -f 2332//2332 2326//2326 2333//2333 -f 2332//2332 2333//2333 2334//2334 -f 2334//2334 2333//2333 2335//2335 -f 2334//2334 2335//2335 2331//2331 -f 2331//2331 2335//2335 2336//2336 -f 2331//2331 2336//2336 2329//2329 -f 1984//1984 1983//1983 2337//2337 -f 2338//2338 1979//1979 2339//2339 -f 2339//2339 1979//1979 1990//1990 -f 2339//2339 1990//1990 1989//1989 -f 1982//1982 1981//1981 2338//2338 -f 2338//2338 1981//1981 1980//1980 -f 2338//2338 1980//1980 1979//1979 -f 1988//1988 1987//1987 2340//2340 -f 2340//2340 1987//1987 1986//1986 -f 2340//2340 1986//1986 2337//2337 -f 2337//2337 1986//1986 1985//1985 -f 2337//2337 1985//1985 1984//1984 -f 2339//2339 2135//2135 2341//2341 -f 2341//2341 2135//2135 2134//2134 -f 2341//2341 2134//2134 2342//2342 -f 2342//2342 2134//2134 2343//2343 -f 2344//2344 2345//2345 2346//2346 -f 2330//2330 2329//2329 2347//2347 -f 2347//2347 2329//2329 2348//2348 -f 2347//2347 2348//2348 2349//2349 -f 2346//2346 2345//2345 2350//2350 -f 2350//2350 2345//2345 2351//2351 -f 2350//2350 2351//2351 2349//2349 -f 2349//2349 2351//2351 2352//2352 -f 2349//2349 2352//2352 2347//2347 -f 1983//1983 1982//1982 2337//2337 -f 2337//2337 1982//1982 2338//2338 -f 2337//2337 2338//2338 2353//2353 -f 2353//2353 2338//2338 2354//2354 -f 2353//2353 2354//2354 2336//2336 -f 2336//2336 2354//2354 2355//2355 -f 2336//2336 2355//2355 2329//2329 -f 2329//2329 2355//2355 2356//2356 -f 2329//2329 2356//2356 2348//2348 -f 2117//2117 2316//2316 2314//2314 -f 2314//2314 2316//2316 1998//1998 -f 2314//2314 1998//1998 1997//1997 -f 2120//2120 2357//2357 2121//2121 -f 2121//2121 2357//2357 2122//2122 -f 2119//2119 2118//2118 2358//2358 -f 2126//2126 2125//2125 2359//2359 -f 2359//2359 2125//2125 2360//2360 -f 2132//2132 2131//2131 2361//2361 -f 2361//2361 2131//2131 2130//2130 -f 2129//2129 2128//2128 2362//2362 -f 2362//2362 2128//2128 2127//2127 -f 2117//2117 2116//2116 2316//2316 -f 2316//2316 2116//2116 2115//2115 -f 2316//2316 2115//2115 2317//2317 -f 2317//2317 2115//2115 2319//2319 -f 2317//2317 2319//2319 1961//1961 -f 1961//1961 2319//2319 1962//1962 -f 2363//2363 2113//2113 2112//2112 -f 2364//2364 2103//2103 2102//2102 -f 2113//2113 2363//2363 2114//2114 -f 2114//2114 2363//2363 2365//2365 -f 2114//2114 2365//2365 2097//2097 -f 2097//2097 2365//2365 2366//2366 -f 2097//2097 2366//2366 2098//2098 -f 2101//2101 2100//2100 2366//2366 -f 2366//2366 2100//2100 2099//2099 -f 2366//2366 2099//2099 2098//2098 -f 2367//2367 2111//2111 2368//2368 -f 2368//2368 2111//2111 2108//2108 -f 2368//2368 2108//2108 2107//2107 -f 2107//2107 2106//2106 2368//2368 -f 2368//2368 2106//2106 2105//2105 -f 2368//2368 2105//2105 2369//2369 -f 2369//2369 2105//2105 2109//2109 -f 2369//2369 2109//2109 2370//2370 -f 2370//2370 2109//2109 2110//2110 -f 2370//2370 2110//2110 2364//2364 -f 2364//2364 2110//2110 2104//2104 -f 2364//2364 2104//2104 2103//2103 -f 2176//2176 2371//2371 2372//2372 -f 2372//2372 2371//2371 2373//2373 -f 2372//2372 2373//2373 2292//2292 -f 2292//2292 2373//2373 2374//2374 -f 2292//2292 2374//2374 2368//2368 -f 2368//2368 2374//2374 2375//2375 -f 2368//2368 2375//2375 2367//2367 -f 2376//2376 2377//2377 2264//2264 -f 2377//2377 2378//2378 2264//2264 -f 2264//2264 2378//2378 2379//2379 -f 2264//2264 2379//2379 2265//2265 -f 2265//2265 2379//2379 2380//2380 -f 2265//2265 2380//2380 2176//2176 -f 2176//2176 2380//2380 2381//2381 -f 2176//2176 2381//2381 2371//2371 -f 2382//2382 2383//2383 2384//2384 -f 2385//2385 2386//2386 2387//2387 -f 2387//2387 2386//2386 2258//2258 -f 2387//2387 2258//2258 2388//2388 -f 2388//2388 2258//2258 2384//2384 -f 2388//2388 2384//2384 2389//2389 -f 2389//2389 2384//2384 2383//2383 -f 2382//2382 2384//2384 2390//2390 -f 2390//2390 2384//2384 2391//2391 -f 2390//2390 2391//2391 2392//2392 -f 2392//2392 2391//2391 2393//2393 -f 2392//2392 2393//2393 2394//2394 -f 2394//2394 2393//2393 2395//2395 -f 2394//2394 2395//2395 2396//2396 -f 2397//2397 2398//2398 2399//2399 -f 2399//2399 2398//2398 2400//2400 -f 2399//2399 2400//2400 2401//2401 -f 2402//2402 2403//2403 2395//2395 -f 2395//2395 2403//2403 2404//2404 -f 2395//2395 2404//2404 2396//2396 -f 2405//2405 2406//2406 2397//2397 -f 2397//2397 2406//2406 2407//2407 -f 2397//2397 2407//2407 2398//2398 -f 2408//2408 2406//2406 2409//2409 -f 2409//2409 2406//2406 2405//2405 -f 2409//2409 2405//2405 2410//2410 -f 2411//2411 2262//2262 2259//2259 -f 2259//2259 2262//2262 1417//1417 -f 2259//2259 1417//1417 1439//1439 -f 2257//2257 1489//1489 1511//1511 -f 1501//1501 1499//1499 2412//2412 -f 1489//1489 2257//2257 1491//1491 -f 1491//1491 2257//2257 2258//2258 -f 1491//1491 2258//2258 1493//1493 -f 1493//1493 2258//2258 1495//1495 -f 1495//1495 2258//2258 2386//2386 -f 1495//1495 2386//2386 1497//1497 -f 1511//1511 1509//1509 2257//2257 -f 2257//2257 1509//1509 1507//1507 -f 2257//2257 1507//1507 2413//2413 -f 2413//2413 1507//1507 1505//1505 -f 2413//2413 1505//1505 1503//1503 -f 1503//1503 1501//1501 2413//2413 -f 2413//2413 1501//1501 2412//2412 -f 2413//2413 2412//2412 2160//2160 -f 2160//2160 2412//2412 2414//2414 -f 2160//2160 2414//2414 2157//2157 -f 2157//2157 2414//2414 2415//2415 -f 2157//2157 2415//2415 2259//2259 -f 2259//2259 2415//2415 2416//2416 -f 2259//2259 2416//2416 2411//2411 -f 2386//2386 2417//2417 1497//1497 -f 1497//1497 2417//2417 2418//2418 -f 1497//1497 2418//2418 1499//1499 -f 1499//1499 2418//2418 2419//2419 -f 1499//1499 2419//2419 2412//2412 -f 2420//2420 2421//2421 2422//2422 -f 2422//2422 2421//2421 2423//2423 -f 2422//2422 2423//2423 2186//2186 -f 2186//2186 2423//2423 2424//2424 -f 2186//2186 2424//2424 2187//2187 -f 2425//2425 2426//2426 2427//2427 -f 2427//2427 2426//2426 2428//2428 -f 2427//2427 2428//2428 2429//2429 -f 2194//2194 2193//2193 2430//2430 -f 2430//2430 2193//2193 2431//2431 -f 2430//2430 2431//2431 2429//2429 -f 2429//2429 2431//2431 2432//2432 -f 2429//2429 2432//2432 2427//2427 -f 2153//2153 2433//2433 2154//2154 -f 2154//2154 2433//2433 2434//2434 -f 2154//2154 2434//2434 2435//2435 -f 2435//2435 2434//2434 2436//2436 -f 2435//2435 2436//2436 2437//2437 -f 2437//2437 2436//2436 2438//2438 -f 2438//2438 2436//2436 2439//2439 -f 2438//2438 2439//2439 2440//2440 -f 2440//2440 2439//2439 2441//2441 -f 2440//2440 2441//2441 2442//2442 -f 2442//2442 2441//2441 2443//2443 -f 2442//2442 2443//2443 2444//2444 -f 2241//2241 2445//2445 2446//2446 -f 2149//2149 2447//2447 2150//2150 -f 2150//2150 2447//2447 2448//2448 -f 2150//2150 2448//2448 2241//2241 -f 2241//2241 2448//2448 2449//2449 -f 2241//2241 2449//2449 2445//2445 -f 2450//2450 2451//2451 2138//2138 -f 2138//2138 2451//2451 2283//2283 -f 2138//2138 2283//2283 2279//2279 -f 2279//2279 2283//2283 2282//2282 -f 2451//2451 2452//2452 2283//2283 -f 2283//2283 2452//2452 2453//2453 -f 2283//2283 2453//2453 2454//2454 -f 2454//2454 2453//2453 2455//2455 -f 2454//2454 2455//2455 2456//2456 -f 2456//2456 2457//2457 2454//2454 -f 2454//2454 2457//2457 2458//2458 -f 2454//2454 2458//2458 2137//2137 -f 2137//2137 2458//2458 2459//2459 -f 2459//2459 2460//2460 2137//2137 -f 2137//2137 2460//2460 2461//2461 -f 2137//2137 2461//2461 2138//2138 -f 2138//2138 2461//2461 2462//2462 -f 2138//2138 2462//2462 2450//2450 -f 2292//2292 2463//2463 2464//2464 -f 2372//2372 2465//2465 2466//2466 -f 2291//2291 2295//2295 2292//2292 -f 2292//2292 2295//2295 2467//2467 -f 2292//2292 2467//2467 2463//2463 -f 2464//2464 2468//2468 2292//2292 -f 2292//2292 2468//2468 2469//2469 -f 2292//2292 2469//2469 2372//2372 -f 2372//2372 2469//2469 2470//2470 -f 2372//2372 2470//2470 2465//2465 -f 2471//2471 2472//2472 2473//2473 -f 2473//2473 2472//2472 2474//2474 -f 2473//2473 2474//2474 2295//2295 -f 2295//2295 2474//2474 2475//2475 -f 2295//2295 2475//2475 2467//2467 -f 2174//2174 2176//2176 2476//2476 -f 2476//2476 2176//2176 2372//2372 -f 2476//2476 2372//2372 2473//2473 -f 2473//2473 2372//2372 2466//2466 -f 2473//2473 2466//2466 2471//2471 -f 2309//2309 2454//2454 2307//2307 -f 2307//2307 2454//2454 2137//2137 -f 2307//2307 2137//2137 2477//2477 -f 2477//2477 2137//2137 2136//2136 -f 2138//2138 2324//2324 2136//2136 -f 2136//2136 2324//2324 2325//2325 -f 2136//2136 2325//2325 2477//2477 -f 2477//2477 2325//2325 2478//2478 -f 2477//2477 2478//2478 2479//2479 -f 2479//2479 2478//2478 2480//2480 -f 2479//2479 2480//2480 2481//2481 -f 2481//2481 2480//2480 2482//2482 -f 2481//2481 2482//2482 2483//2483 -f 2483//2483 2482//2482 2484//2484 -f 2483//2483 2484//2484 2352//2352 -f 2352//2352 2484//2484 2485//2485 -f 2352//2352 2485//2485 2347//2347 -f 2347//2347 2485//2485 2486//2486 -f 2347//2347 2486//2486 2330//2330 -f 2281//2281 2287//2287 2138//2138 -f 2138//2138 2287//2287 2289//2289 -f 2138//2138 2289//2289 2324//2324 -f 2324//2324 2289//2289 2328//2328 -f 2324//2324 2328//2328 2322//2322 -f 2322//2322 2328//2328 2006//2006 -f 2322//2322 2006//2006 2005//2005 -f 2179//2179 2143//2143 2176//2176 -f 2176//2176 2143//2143 2145//2145 -f 2176//2176 2145//2145 2265//2265 -f 2265//2265 2145//2145 2272//2272 -f 2265//2265 2272//2272 2266//2266 -f 2266//2266 2272//2272 2273//2273 -f 2141//2141 2487//2487 2142//2142 -f 2142//2142 2487//2487 2488//2488 -f 2142//2142 2488//2488 2199//2199 -f 2199//2199 2488//2488 2489//2489 -f 2199//2199 2489//2489 2197//2197 -f 2197//2197 2489//2489 2315//2315 -f 2197//2197 2315//2315 1995//1995 -f 1995//1995 2315//2315 1996//1996 -f 2026//2026 2025//2025 2422//2422 -f 2019//2019 2018//2018 2490//2490 -f 2490//2490 2018//2018 2186//2186 -f 2490//2490 2186//2186 2298//2298 -f 2298//2298 2186//2186 2183//2183 -f 2298//2298 2183//2183 2296//2296 -f 2296//2296 2183//2183 2304//2304 -f 2018//2018 2017//2017 2186//2186 -f 2186//2186 2017//2017 2016//2016 -f 2186//2186 2016//2016 2422//2422 -f 2422//2422 2016//2016 2015//2015 -f 2422//2422 2015//2015 2026//2026 -f 2491//2491 2024//2024 2023//2023 -f 2023//2023 2022//2022 2491//2491 -f 2491//2491 2022//2022 2021//2021 -f 2491//2491 2021//2021 2490//2490 -f 2490//2490 2021//2021 2020//2020 -f 2490//2490 2020//2020 2019//2019 -f 2487//2487 2430//2430 2488//2488 -f 2488//2488 2430//2430 2429//2429 -f 2488//2488 2429//2429 2489//2489 -f 2489//2489 2429//2429 2428//2428 -f 2489//2489 2428//2428 2315//2315 -f 2315//2315 2428//2428 2426//2426 -f 2315//2315 2426//2426 2314//2314 -f 2314//2314 2426//2426 2358//2358 -f 2314//2314 2358//2358 2117//2117 -f 2117//2117 2358//2358 2118//2118 -f 2425//2425 2420//2420 2426//2426 -f 2426//2426 2420//2420 2422//2422 -f 2426//2426 2422//2422 2358//2358 -f 2358//2358 2422//2422 2357//2357 -f 2358//2358 2357//2357 2119//2119 -f 2119//2119 2357//2357 2120//2120 -f 2025//2025 2024//2024 2422//2422 -f 2422//2422 2024//2024 2491//2491 -f 2422//2422 2491//2491 2357//2357 -f 2357//2357 2491//2491 2492//2492 -f 2357//2357 2492//2492 2122//2122 -f 2122//2122 2492//2492 2493//2493 -f 2122//2122 2493//2493 2123//2123 -f 2123//2123 2493//2493 2360//2360 -f 2123//2123 2360//2360 2124//2124 -f 2124//2124 2360//2360 2125//2125 -f 2002//2002 2001//2001 2313//2313 -f 2313//2313 2001//2001 2494//2494 -f 2313//2313 2494//2494 2320//2320 -f 2320//2320 2494//2494 2495//2495 -f 2320//2320 2495//2495 1958//1958 -f 1958//1958 2495//2495 1959//1959 -f 2001//2001 2000//2000 2494//2494 -f 2494//2494 2000//2000 2316//2316 -f 2494//2494 2316//2316 2495//2495 -f 2495//2495 2316//2316 2317//2317 -f 2495//2495 2317//2317 1959//1959 -f 1959//1959 2317//2317 1960//1960 -f 2102//2102 2101//2101 2364//2364 -f 2364//2364 2101//2101 2366//2366 -f 2364//2364 2366//2366 2395//2395 -f 2395//2395 2366//2366 2399//2399 -f 2395//2395 2399//2399 2402//2402 -f 2402//2402 2399//2399 2401//2401 -f 2130//2130 2129//2129 2361//2361 -f 2361//2361 2129//2129 2362//2362 -f 2361//2361 2362//2362 2443//2443 -f 2443//2443 2362//2362 2496//2496 -f 2112//2112 2376//2376 2363//2363 -f 2363//2363 2376//2376 2264//2264 -f 2363//2363 2264//2264 2365//2365 -f 2365//2365 2264//2264 2171//2171 -f 2365//2365 2171//2171 2366//2366 -f 2366//2366 2171//2171 2169//2169 -f 2366//2366 2169//2169 2399//2399 -f 2399//2399 2169//2169 2167//2167 -f 2399//2399 2167//2167 2397//2397 -f 2397//2397 2167//2167 2165//2165 -f 2397//2397 2165//2165 2405//2405 -f 2405//2405 2165//2165 2262//2262 -f 2405//2405 2262//2262 2410//2410 -f 2410//2410 2262//2262 2411//2411 -f 2497//2497 1977//1977 2498//2498 -f 2498//2498 1977//1977 1976//1976 -f 2498//2498 1976//1976 1975//1975 -f 1970//1970 1969//1969 2496//2496 -f 1975//1975 1974//1974 2498//2498 -f 2498//2498 1974//1974 1973//1973 -f 2498//2498 1973//1973 2499//2499 -f 2499//2499 1973//1973 1972//1972 -f 2499//2499 1972//1972 1971//1971 -f 1971//1971 1970//1970 2499//2499 -f 2499//2499 1970//1970 2496//2496 -f 2499//2499 2496//2496 2359//2359 -f 2359//2359 2496//2496 2362//2362 -f 2359//2359 2362//2362 2126//2126 -f 2126//2126 2362//2362 2127//2127 -f 1969//1969 1968//1968 2496//2496 -f 2496//2496 1968//1968 1967//1967 -f 2496//2496 1967//1967 2497//2497 -f 2497//2497 1967//1967 1978//1978 -f 2497//2497 1978//1978 1977//1977 -f 1965//1965 1964//1964 2218//2218 -f 2218//2218 1964//1964 2318//2318 -f 2218//2218 2318//2318 2219//2219 -f 2219//2219 2318//2318 2500//2500 -f 2219//2219 2500//2500 2230//2230 -f 2230//2230 2500//2500 2501//2501 -f 2230//2230 2501//2501 2233//2233 -f 2233//2233 2501//2501 2502//2502 -f 2444//2444 2443//2443 2503//2503 -f 2503//2503 2443//2443 2496//2496 -f 2503//2503 2496//2496 2446//2446 -f 2446//2446 2496//2496 2497//2497 -f 2446//2446 2497//2497 2241//2241 -f 2241//2241 2497//2497 2498//2498 -f 2241//2241 2498//2498 2239//2239 -f 2297//2297 2305//2305 2298//2298 -f 2298//2298 2305//2305 2307//2307 -f 2298//2298 2307//2307 2490//2490 -f 2490//2490 2307//2307 2477//2477 -f 2490//2490 2477//2477 2491//2491 -f 2491//2491 2477//2477 2479//2479 -f 2491//2491 2479//2479 2492//2492 -f 2492//2492 2479//2479 2481//2481 -f 2492//2492 2481//2481 2493//2493 -f 2493//2493 2481//2481 2483//2483 -f 2493//2493 2483//2483 2360//2360 -f 2360//2360 2483//2483 2352//2352 -f 2360//2360 2352//2352 2359//2359 -f 2359//2359 2352//2352 2351//2351 -f 2359//2359 2351//2351 2499//2499 -f 2499//2499 2351//2351 2345//2345 -f 2499//2499 2345//2345 2498//2498 -f 2498//2498 2345//2345 2344//2344 -f 2498//2498 2344//2344 2239//2239 -f 2239//2239 2344//2344 2253//2253 -f 2239//2239 2253//2253 2237//2237 -f 2237//2237 2253//2253 2252//2252 -f 1473//1473 1471//1471 2139//2139 -f 2139//2139 1471//1471 2254//2254 -f 2139//2139 2254//2254 2340//2340 -f 2288//2288 2293//2293 2289//2289 -f 2289//2289 2293//2293 2292//2292 -f 2289//2289 2292//2292 2328//2328 -f 2328//2328 2292//2292 2368//2368 -f 2328//2328 2368//2368 2326//2326 -f 2326//2326 2368//2368 2369//2369 -f 2326//2326 2369//2369 2333//2333 -f 2333//2333 2369//2369 2370//2370 -f 2333//2333 2370//2370 2335//2335 -f 2335//2335 2370//2370 2364//2364 -f 2335//2335 2364//2364 2336//2336 -f 2336//2336 2364//2364 2395//2395 -f 2336//2336 2395//2395 2353//2353 -f 2353//2353 2395//2395 2393//2393 -f 2353//2353 2393//2393 2337//2337 -f 2337//2337 2393//2393 2391//2391 -f 2337//2337 2391//2391 2340//2340 -f 2340//2340 2391//2391 2384//2384 -f 2340//2340 2384//2384 2139//2139 -f 2139//2139 2384//2384 2258//2258 -f 2139//2139 2258//2258 1475//1475 -f 1475//1475 2258//2258 1477//1477 -f 1437//1437 1435//1435 2259//2259 -f 2259//2259 1435//1435 2261//2261 -f 2259//2259 2261//2261 2157//2157 -f 2157//2157 2261//2261 2504//2504 -f 2157//2157 2504//2504 2155//2155 -f 2115//2115 2132//2132 2319//2319 -f 2319//2319 2132//2132 2361//2361 -f 2319//2319 2361//2361 2318//2318 -f 2318//2318 2361//2361 2443//2443 -f 2318//2318 2443//2443 2500//2500 -f 2500//2500 2443//2443 2441//2441 -f 2500//2500 2441//2441 2501//2501 -f 2501//2501 2441//2441 2439//2439 -f 2501//2501 2439//2439 2502//2502 -f 2502//2502 2439//2439 2436//2436 -f 2346//2346 2343//2343 2344//2344 -f 2344//2344 2343//2343 2134//2134 -f 2344//2344 2134//2134 2253//2253 -f 2253//2253 2134//2134 2133//2133 -f 2253//2253 2133//2133 2250//2250 -f 2250//2250 2133//2133 2505//2505 -f 2254//2254 1451//1451 1449//1449 -f 2133//2133 1447//1447 1445//1445 -f 1989//1989 1988//1988 2339//2339 -f 2339//2339 1988//1988 2340//2340 -f 2339//2339 2340//2340 2135//2135 -f 2135//2135 2340//2340 2254//2254 -f 2135//2135 2254//2254 2133//2133 -f 2133//2133 2254//2254 1449//1449 -f 2133//2133 1449//1449 1447//1447 -f 1451//1451 2254//2254 1453//1453 -f 1453//1453 2254//2254 2255//2255 -f 1453//1453 2255//2255 1455//1455 -f 1445//1445 1443//1443 2133//2133 -f 2133//2133 1443//1443 1441//1441 -f 2133//2133 1441//1441 2505//2505 -f 2505//2505 1441//1441 1463//1463 -f 1463//1463 1461//1461 2505//2505 -f 2505//2505 1461//1461 1459//1459 -f 2505//2505 1459//1459 2255//2255 -f 2255//2255 1459//1459 1457//1457 -f 2255//2255 1457//1457 1455//1455 -f 2146//2146 2148//2148 2160//2160 -f 2160//2160 2148//2148 2506//2506 -f 2160//2160 2506//2506 2413//2413 -f 2413//2413 2506//2506 2507//2507 -f 2413//2413 2507//2507 2257//2257 -f 2257//2257 2507//2507 2508//2508 -f 2257//2257 2508//2508 2256//2256 -f 2256//2256 2508//2508 2509//2509 -f 2256//2256 2509//2509 2255//2255 -f 2255//2255 2509//2509 2510//2510 -f 2255//2255 2510//2510 2505//2505 -f 2505//2505 2510//2510 2511//2511 -f 2505//2505 2511//2511 2250//2250 -f 2250//2250 2511//2511 2512//2512 -f 2250//2250 2512//2512 2248//2248 -f 2248//2248 2512//2512 2513//2513 -f 2248//2248 2513//2513 2150//2150 -f 2150//2150 2513//2513 2514//2514 -f 2150//2150 2514//2514 2151//2151 -f 1746//1746 2387//2387 1747//1747 -f 1747//1747 2387//2387 2388//2388 -f 1747//1747 2388//2388 1749//1749 -f 1749//1749 2388//2388 2389//2389 -f 1749//1749 2389//2389 1750//1750 -f 1750//1750 2389//2389 2383//2383 -f 1750//1750 2383//2383 1744//1744 -f 1744//1744 2383//2383 2382//2382 -f 1732//1732 2394//2394 1737//1737 -f 1737//1737 2394//2394 2396//2396 -f 1737//1737 2396//2396 1738//1738 -f 1738//1738 2396//2396 2404//2404 -f 1738//1738 2404//2404 1739//1739 -f 1739//1739 2404//2404 2403//2403 -f 1745//1745 1744//1744 2382//2382 -f 2394//2394 1732//1732 2392//2392 -f 2392//2392 1732//1732 1745//1745 -f 2392//2392 1745//1745 2390//2390 -f 2390//2390 1745//1745 2382//2382 -f 1735//1735 2402//2402 1736//1736 -f 1736//1736 2402//2402 2401//2401 -f 1736//1736 2401//2401 1742//1742 -f 1742//1742 2401//2401 2400//2400 -f 1742//1742 2400//2400 1741//1741 -f 1741//1741 2400//2400 2398//2398 -f 1739//1739 2403//2403 1735//1735 -f 1735//1735 2403//2403 2402//2402 -f 2408//2408 1762//1762 2406//2406 -f 2406//2406 1762//1762 1740//1740 -f 2406//2406 1740//1740 2407//2407 -f 2407//2407 1740//1740 1741//1741 -f 2407//2407 1741//1741 2398//2398 -f 2387//2387 1746//1746 2385//2385 -f 2385//2385 1746//1746 1758//1758 -f 1762//1762 2408//2408 1761//1761 -f 1761//1761 2408//2408 2409//2409 -f 1761//1761 2409//2409 1760//1760 -f 1760//1760 2409//2409 2410//2410 -f 1760//1760 2410//2410 1759//1759 -f 1759//1759 2410//2410 2411//2411 -f 1759//1759 2411//2411 1584//1584 -f 1584//1584 2411//2411 2416//2416 -f 1584//1584 2416//2416 1583//1583 -f 1583//1583 2416//2416 2415//2415 -f 1583//1583 2415//2415 1582//1582 -f 1582//1582 2415//2415 2414//2414 -f 1582//1582 2414//2414 1580//1580 -f 1580//1580 2414//2414 2412//2412 -f 1580//1580 2412//2412 1753//1753 -f 1753//1753 2412//2412 2419//2419 -f 1753//1753 2419//2419 1755//1755 -f 1755//1755 2419//2419 2418//2418 -f 1755//1755 2418//2418 1756//1756 -f 1756//1756 2418//2418 2417//2417 -f 1756//1756 2417//2417 1757//1757 -f 1757//1757 2417//2417 2386//2386 -f 1757//1757 2386//2386 1758//1758 -f 1758//1758 2386//2386 2385//2385 -f 1554//1554 2111//2111 1555//1555 -f 1555//1555 2111//2111 2367//2367 -f 2381//2381 1687//1687 2371//2371 -f 2371//2371 1687//1687 1695//1695 -f 2371//2371 1695//1695 2373//2373 -f 2373//2373 1695//1695 1696//1696 -f 2373//2373 1696//1696 2374//2374 -f 2374//2374 1696//1696 1700//1700 -f 2374//2374 1700//1700 2375//2375 -f 2375//2375 1700//1700 1701//1701 -f 2375//2375 1701//1701 2367//2367 -f 2367//2367 1701//1701 1705//1705 -f 2367//2367 1705//1705 1555//1555 -f 2112//2112 1560//1560 2376//2376 -f 2376//2376 1560//1560 1559//1559 -f 2376//2376 1559//1559 2377//2377 -f 2377//2377 1559//1559 1681//1681 -f 2377//2377 1681//1681 2378//2378 -f 2378//2378 1681//1681 1684//1684 -f 2378//2378 1684//1684 2379//2379 -f 2379//2379 1684//1684 1683//1683 -f 2379//2379 1683//1683 2380//2380 -f 2380//2380 1683//1683 1682//1682 -f 2380//2380 1682//1682 2381//2381 -f 2381//2381 1682//1682 1686//1686 -f 2381//2381 1686//1686 1687//1687 -f 1809//1809 2216//2216 1807//1807 -f 1807//1807 2216//2216 2226//2226 -f 1807//1807 2226//2226 1812//1812 -f 1812//1812 2226//2226 2225//2225 -f 1812//1812 2225//2225 1813//1813 -f 1813//1813 2225//2225 2223//2223 -f 1813//1813 2223//2223 1814//1814 -f 1814//1814 2223//2223 2222//2222 -f 1814//1814 2222//2222 1815//1815 -f 1815//1815 2222//2222 2221//2221 -f 1815//1815 2221//2221 1544//1544 -f 1544//1544 2221//2221 2220//2220 -f 1544//1544 2220//2220 1545//1545 -f 1545//1545 2220//2220 2232//2232 -f 1545//1545 2232//2232 1818//1818 -f 1818//1818 2232//2232 2231//2231 -f 1818//1818 2231//2231 1817//1817 -f 1817//1817 2231//2231 2229//2229 -f 1817//1817 2229//2229 1816//1816 -f 1816//1816 2229//2229 2228//2228 -f 1816//1816 2228//2228 1811//1811 -f 1811//1811 2228//2228 2217//2217 -f 1811//1811 2217//2217 1809//1809 -f 1809//1809 2217//2217 2216//2216 -f 1853//1853 2209//2209 1854//1854 -f 1854//1854 2209//2209 2207//2207 -f 1854//1854 2207//2207 1855//1855 -f 1855//1855 2207//2207 2206//2206 -f 1855//1855 2206//2206 1856//1856 -f 1856//1856 2206//2206 2202//2202 -f 1856//1856 2202//2202 1857//1857 -f 1857//1857 2202//2202 2201//2201 -f 1857//1857 2201//2201 1858//1858 -f 1858//1858 2201//2201 2200//2200 -f 1858//1858 2200//2200 1848//1848 -f 1848//1848 2200//2200 2198//2198 -f 1848//1848 2198//2198 1849//1849 -f 1849//1849 2198//2198 2196//2196 -f 1849//1849 2196//2196 1850//1850 -f 1850//1850 2196//2196 2195//2195 -f 1850//1850 2195//2195 1851//1851 -f 1851//1851 2195//2195 2214//2214 -f 1851//1851 2214//2214 1852//1852 -f 1852//1852 2214//2214 2213//2213 -f 1852//1852 2213//2213 1846//1846 -f 1846//1846 2213//2213 2211//2211 -f 1846//1846 2211//2211 1853//1853 -f 1853//1853 2211//2211 2209//2209 -f 1905//1905 1765//1765 2343//2343 -f 2349//2349 1906//1906 2350//2350 -f 2350//2350 1906//1906 1905//1905 -f 2350//2350 1905//1905 2346//2346 -f 2346//2346 1905//1905 2343//2343 -f 2343//2343 1765//1765 2342//2342 -f 2342//2342 1765//1765 1764//1764 -f 2342//2342 1764//1764 2341//2341 -f 2341//2341 1764//1764 1766//1766 -f 2341//2341 1766//1766 2339//2339 -f 2339//2339 1766//1766 1771//1771 -f 1772//1772 1782//1782 2355//2355 -f 2339//2339 1771//1771 2338//2338 -f 2338//2338 1771//1771 1772//1772 -f 2338//2338 1772//1772 2354//2354 -f 2354//2354 1772//1772 2355//2355 -f 2355//2355 1782//1782 2356//2356 -f 2356//2356 1782//1782 1908//1908 -f 2356//2356 1908//1908 2348//2348 -f 2348//2348 1908//1908 1907//1907 -f 2348//2348 1907//1907 2349//2349 -f 2349//2349 1907//1907 1906//1906 -f 1654//1654 2485//2485 1653//1653 -f 1653//1653 2485//2485 2484//2484 -f 1653//1653 2484//2484 1651//1651 -f 1651//1651 2484//2484 2482//2482 -f 1651//1651 2482//2482 1649//1649 -f 1649//1649 2482//2482 2480//2480 -f 1649//1649 2480//2480 1646//1646 -f 1646//1646 2480//2480 2478//2478 -f 2485//2485 1654//1654 2486//2486 -f 2486//2486 1654//1654 1656//1656 -f 2486//2486 1656//1656 2330//2330 -f 2330//2330 1656//1656 1564//1564 -f 2330//2330 1564//1564 2331//2331 -f 2331//2331 1564//1564 1658//1658 -f 2334//2334 2331//2331 1658//1658 -f 1636//1636 1629//1629 2322//2322 -f 2322//2322 2327//2327 1636//1636 -f 1636//1636 2327//2327 2332//2332 -f 1636//1636 2332//2332 1662//1662 -f 1662//1662 2332//2332 2334//2334 -f 1662//1662 2334//2334 1657//1657 -f 1657//1657 2334//2334 1658//1658 -f 2322//2322 1629//1629 2323//2323 -f 2323//2323 1629//1629 1628//1628 -f 2323//2323 1628//1628 2325//2325 -f 2325//2325 1628//1628 1645//1645 -f 2325//2325 1645//1645 2478//2478 -f 2478//2478 1645//1645 1646//1646 -f 2515//2515 2463//2463 2516//2516 -f 2516//2516 2463//2463 2467//2467 -f 2516//2516 2467//2467 2517//2517 -f 2517//2517 2467//2467 2475//2475 -f 2517//2517 2475//2475 2518//2518 -f 2518//2518 2475//2475 2474//2474 -f 2518//2518 2474//2474 2519//2519 -f 2519//2519 2474//2474 2472//2472 -f 2519//2519 2472//2472 2520//2520 -f 2520//2520 2472//2472 2471//2471 -f 2520//2520 2471//2471 2521//2521 -f 2521//2521 2471//2471 2466//2466 -f 2521//2521 2466//2466 2522//2522 -f 2522//2522 2466//2466 2465//2465 -f 2522//2522 2465//2465 2523//2523 -f 2523//2523 2465//2465 2470//2470 -f 2523//2523 2470//2470 2524//2524 -f 2524//2524 2470//2470 2469//2469 -f 2524//2524 2469//2469 2525//2525 -f 2525//2525 2469//2469 2468//2468 -f 2525//2525 2468//2468 2526//2526 -f 2526//2526 2468//2468 2464//2464 -f 2526//2526 2464//2464 2515//2515 -f 2515//2515 2464//2464 2463//2463 -f 2527//2527 2280//2280 2528//2528 -f 2528//2528 2280//2280 2279//2279 -f 2528//2528 2279//2279 2529//2529 -f 2529//2529 2279//2279 2282//2282 -f 2529//2529 2282//2282 2530//2530 -f 2530//2530 2282//2282 2284//2284 -f 2530//2530 2284//2284 2531//2531 -f 2531//2531 2284//2284 2286//2286 -f 2531//2531 2286//2286 2532//2532 -f 2532//2532 2286//2286 2294//2294 -f 2532//2532 2294//2294 2533//2533 -f 2533//2533 2294//2294 2291//2291 -f 2533//2533 2291//2291 2534//2534 -f 2534//2534 2291//2291 2290//2290 -f 2534//2534 2290//2290 2535//2535 -f 2535//2535 2290//2290 2293//2293 -f 2535//2535 2293//2293 2536//2536 -f 2536//2536 2293//2293 2288//2288 -f 2536//2536 2288//2288 2537//2537 -f 2537//2537 2288//2288 2287//2287 -f 2537//2537 2287//2287 2538//2538 -f 2538//2538 2287//2287 2281//2281 -f 2538//2538 2281//2281 2527//2527 -f 2527//2527 2281//2281 2280//2280 -f 2539//2539 2263//2263 2540//2540 -f 2540//2540 2263//2263 2269//2269 -f 2540//2540 2269//2269 2541//2541 -f 2541//2541 2269//2269 2268//2268 -f 2541//2541 2268//2268 2542//2542 -f 2542//2542 2268//2268 2267//2267 -f 2542//2542 2267//2267 2543//2543 -f 2543//2543 2267//2267 2266//2266 -f 2543//2543 2266//2266 2544//2544 -f 2544//2544 2266//2266 2273//2273 -f 2544//2544 2273//2273 2545//2545 -f 2545//2545 2273//2273 2271//2271 -f 2545//2545 2271//2271 2546//2546 -f 2546//2546 2271//2271 2278//2278 -f 2546//2546 2278//2278 2547//2547 -f 2547//2547 2278//2278 2277//2277 -f 2547//2547 2277//2277 2548//2548 -f 2548//2548 2277//2277 2276//2276 -f 2548//2548 2276//2276 2549//2549 -f 2549//2549 2276//2276 2275//2275 -f 2549//2549 2275//2275 2550//2550 -f 2550//2550 2275//2275 2274//2274 -f 2550//2550 2274//2274 2539//2539 -f 2539//2539 2274//2274 2263//2263 -f 2551//2551 2458//2458 2552//2552 -f 2552//2552 2458//2458 2457//2457 -f 2552//2552 2457//2457 2553//2553 -f 2553//2553 2457//2457 2456//2456 -f 2553//2553 2456//2456 2554//2554 -f 2554//2554 2456//2456 2455//2455 -f 2554//2554 2455//2455 2555//2555 -f 2555//2555 2455//2455 2453//2453 -f 2555//2555 2453//2453 2556//2556 -f 2556//2556 2453//2453 2452//2452 -f 2556//2556 2452//2452 2557//2557 -f 2557//2557 2452//2452 2451//2451 -f 2557//2557 2451//2451 2558//2558 -f 2558//2558 2451//2451 2450//2450 -f 2558//2558 2450//2450 2559//2559 -f 2559//2559 2450//2450 2462//2462 -f 2559//2559 2462//2462 2560//2560 -f 2560//2560 2462//2462 2461//2461 -f 2560//2560 2461//2461 2561//2561 -f 2561//2561 2461//2461 2460//2460 -f 2561//2561 2460//2460 2562//2562 -f 2562//2562 2460//2460 2459//2459 -f 2562//2562 2459//2459 2551//2551 -f 2551//2551 2459//2459 2458//2458 -f 1626//1626 2303//2303 1627//1627 -f 1627//1627 2303//2303 2302//2302 -f 1627//1627 2302//2302 1623//1623 -f 1623//1623 2302//2302 2301//2301 -f 1623//1623 2301//2301 1624//1624 -f 1624//1624 2301//2301 2300//2300 -f 1624//1624 2300//2300 1615//1615 -f 1615//1615 2300//2300 2311//2311 -f 1615//1615 2311//2311 1617//1617 -f 1617//1617 2311//2311 2310//2310 -f 1617//1617 2310//2310 1610//1610 -f 1610//1610 2310//2310 2308//2308 -f 1610//1610 2308//2308 1611//1611 -f 1611//1611 2308//2308 2306//2306 -f 1611//1611 2306//2306 1618//1618 -f 1618//1618 2306//2306 2305//2305 -f 1618//1618 2305//2305 1619//1619 -f 1619//1619 2305//2305 2297//2297 -f 1619//1619 2297//2297 1621//1621 -f 1621//1621 2297//2297 2296//2296 -f 1621//1621 2296//2296 1625//1625 -f 1625//1625 2296//2296 2304//2304 -f 1625//1625 2304//2304 1626//1626 -f 1626//1626 2304//2304 2303//2303 -f 1602//1602 2244//2244 1604//1604 -f 1604//1604 2244//2244 2243//2243 -f 1604//1604 2243//2243 1605//1605 -f 1605//1605 2243//2243 2242//2242 -f 1605//1605 2242//2242 1565//1565 -f 1565//1565 2242//2242 2240//2240 -f 1565//1565 2240//2240 1566//1566 -f 1566//1566 2240//2240 2238//2238 -f 1566//1566 2238//2238 1599//1599 -f 1599//1599 2238//2238 2237//2237 -f 1599//1599 2237//2237 1596//1596 -f 1596//1596 2237//2237 2252//2252 -f 1596//1596 2252//2252 1597//1597 -f 1597//1597 2252//2252 2251//2251 -f 1597//1597 2251//2251 1607//1607 -f 1607//1607 2251//2251 2249//2249 -f 1607//1607 2249//2249 1608//1608 -f 1608//1608 2249//2249 2247//2247 -f 1608//1608 2247//2247 1609//1609 -f 1609//1609 2247//2247 2246//2246 -f 1609//1609 2246//2246 1601//1601 -f 1601//1601 2246//2246 2245//2245 -f 1601//1601 2245//2245 1602//1602 -f 1602//1602 2245//2245 2244//2244 -f 2043//2043 2086//2086 2514//2514 -f 2514//2514 2086//2086 2151//2151 -f 2086//2086 2087//2087 2151//2151 -f 2151//2151 2087//2087 2152//2152 -f 2434//2434 2075//2075 2436//2436 -f 2436//2436 2075//2075 2074//2074 -f 2436//2436 2074//2074 2502//2502 -f 2502//2502 2074//2074 2233//2233 -f 2233//2233 2074//2074 2234//2234 -f 2234//2234 2074//2074 2072//2072 -f 2234//2234 2072//2072 2235//2235 -f 2235//2235 2072//2072 2066//2066 -f 2235//2235 2066//2066 2236//2236 -f 2236//2236 2066//2066 2064//2064 -f 2236//2236 2064//2064 2215//2215 -f 2215//2215 2064//2064 2062//2062 -f 2215//2215 2062//2062 2227//2227 -f 2227//2227 2062//2062 2061//2061 -f 2224//2224 2227//2227 2061//2061 -f 2210//2210 2212//2212 2050//2050 -f 2050//2050 2212//2212 2312//2312 -f 2312//2312 2313//2313 2050//2050 -f 2050//2050 2313//2313 2320//2320 -f 2050//2050 2320//2320 2061//2061 -f 2061//2061 2320//2320 2321//2321 -f 2061//2061 2321//2321 2224//2224 -f 2210//2210 2050//2050 2208//2208 -f 2208//2208 2050//2050 2049//2049 -f 2208//2208 2049//2049 2203//2203 -f 2203//2203 2049//2049 2048//2048 -f 2083//2083 2141//2141 2060//2060 -f 2060//2060 2141//2141 2140//2140 -f 2060//2060 2140//2140 2058//2058 -f 2058//2058 2140//2140 2205//2205 -f 2058//2058 2205//2205 2048//2048 -f 2048//2048 2205//2205 2204//2204 -f 2048//2048 2204//2204 2203//2203 -f 2083//2083 2084//2084 2194//2194 -f 2194//2194 2430//2430 2083//2083 -f 2083//2083 2430//2430 2487//2487 -f 2083//2083 2487//2487 2141//2141 -f 2069//2069 2068//2068 2190//2190 -f 2190//2190 2068//2068 2182//2182 -f 2068//2068 2038//2038 2182//2182 -f 2182//2182 2038//2038 2180//2180 -f 2174//2174 2476//2476 2039//2039 -f 2039//2039 2476//2476 2473//2473 -f 2039//2039 2473//2473 2295//2295 -f 2295//2295 2285//2285 2039//2039 -f 2039//2039 2285//2285 2283//2283 -f 2039//2039 2283//2283 2038//2038 -f 2038//2038 2283//2283 2454//2454 -f 2038//2038 2454//2454 2309//2309 -f 2309//2309 2299//2299 2038//2038 -f 2038//2038 2299//2299 2181//2181 -f 2038//2038 2181//2181 2180//2180 -f 2039//2039 2095//2095 2174//2174 -f 2174//2174 2095//2095 2175//2175 -f 2095//2095 2091//2091 2175//2175 -f 2175//2175 2091//2091 2177//2177 -f 2091//2091 2090//2090 2177//2177 -f 2177//2177 2090//2090 2178//2178 -f 2090//2090 2089//2089 2178//2178 -f 2178//2178 2089//2089 2179//2179 -f 2089//2089 2096//2096 2179//2179 -f 2179//2179 2096//2096 2143//2143 -f 2096//2096 2093//2093 2143//2143 -f 2143//2143 2093//2093 2144//2144 -f 2145//2145 2144//2144 2093//2093 -f 2172//2172 2173//2173 2080//2080 -f 2080//2080 2173//2173 2270//2270 -f 2080//2080 2270//2270 2093//2093 -f 2093//2093 2270//2270 2272//2272 -f 2093//2093 2272//2272 2145//2145 -f 2080//2080 2078//2078 2172//2172 -f 2172//2172 2078//2078 2170//2170 -f 2078//2078 2077//2077 2164//2164 -f 2164//2164 2166//2166 2078//2078 -f 2078//2078 2166//2166 2168//2168 -f 2078//2078 2168//2168 2170//2170 -f 2077//2077 2079//2079 2164//2164 -f 2164//2164 2079//2079 2162//2162 -f 2163//2163 2162//2162 2079//2079 -f 2155//2155 2504//2504 2054//2054 -f 2054//2054 2504//2504 2261//2261 -f 2054//2054 2261//2261 2079//2079 -f 2079//2079 2261//2261 2260//2260 -f 2079//2079 2260//2260 2163//2163 -f 2054//2054 2053//2053 2155//2155 -f 2155//2155 2053//2053 2156//2156 -f 2053//2053 2045//2045 2156//2156 -f 2156//2156 2045//2045 2158//2158 -f 2045//2045 2051//2051 2158//2158 -f 2158//2158 2051//2051 2159//2159 -f 2051//2051 2037//2037 2159//2159 -f 2159//2159 2037//2037 2161//2161 -f 2037//2037 2036//2036 2161//2161 -f 2161//2161 2036//2036 2146//2146 -f 2036//2036 2035//2035 2146//2146 -f 2146//2146 2035//2035 2147//2147 -f 2514//2514 2513//2513 2043//2043 -f 2043//2043 2513//2513 2512//2512 -f 2043//2043 2512//2512 2511//2511 -f 2511//2511 2510//2510 2043//2043 -f 2043//2043 2510//2510 2509//2509 -f 2043//2043 2509//2509 2035//2035 -f 2035//2035 2509//2509 2508//2508 -f 2035//2035 2508//2508 2507//2507 -f 2507//2507 2506//2506 2035//2035 -f 2035//2035 2506//2506 2148//2148 -f 2035//2035 2148//2148 2147//2147 -f 2030//2030 1688//1688 1558//1558 -f 2030//2030 1558//1558 2040//2040 -f 2040//2040 1558//1558 1731//1731 -f 2040//2040 1731//1731 2041//2041 -f 2041//2041 1731//1731 1730//1730 -f 2041//2041 1730//1730 2042//2042 -f 2042//2042 1730//1730 1729//1729 -f 2042//2042 1729//1729 2094//2094 -f 2094//2094 1729//1729 1728//1728 -f 2094//2094 1728//1728 2092//2092 -f 2092//2092 1728//1728 1727//1727 -f 2092//2092 1727//1727 2031//2031 -f 2032//2032 1586//1586 1585//1585 -f 2032//2032 1585//1585 2055//2055 -f 2055//2055 1585//1585 1708//1708 -f 2055//2055 1708//1708 2046//2046 -f 2046//2046 1708//1708 1707//1707 -f 2046//2046 1707//1707 2047//2047 -f 2047//2047 1707//1707 1706//1706 -f 2047//2047 1706//1706 2052//2052 -f 2052//2052 1706//1706 1891//1891 -f 2052//2052 1891//1891 2044//2044 -f 2044//2044 1891//1891 1890//1890 -f 2044//2044 1890//1890 2033//2033 -f 2028//2028 1550//1550 1718//1718 -f 2028//2028 1718//1718 2056//2056 -f 2056//2056 1718//1718 1723//1723 -f 2056//2056 1723//1723 2057//2057 -f 2057//2057 1723//1723 1722//1722 -f 2057//2057 1722//1722 2059//2059 -f 2059//2059 1722//1722 1719//1719 -f 2059//2059 1719//1719 2081//2081 -f 2081//2081 1719//1719 1720//1720 -f 2081//2081 1720//1720 2082//2082 -f 2082//2082 1720//1720 1721//1721 -f 2082//2082 1721//1721 2029//2029 -f 2034//2034 1901//1901 1714//1714 -f 2034//2034 1714//1714 2073//2073 -f 2073//2073 1714//1714 1713//1713 -f 2073//2073 1713//1713 2071//2071 -f 2071//2071 1713//1713 1712//1712 -f 2071//2071 1712//1712 2067//2067 -f 2067//2067 1712//1712 1711//1711 -f 2067//2067 1711//1711 2065//2065 -f 2065//2065 1711//1711 1710//1710 -f 2065//2065 1710//1710 2063//2063 -f 2063//2063 1710//1710 1717//1717 -f 2063//2063 1717//1717 2027//2027 -f 2563//2563 2564//2564 1440//1440 -f 1452//1452 2565//2565 1450//1450 -f 1450//1450 2565//2565 2566//2566 -f 1450//1450 2566//2566 1448//1448 -f 1448//1448 2566//2566 2567//2567 -f 2568//2568 1460//1460 2564//2564 -f 2564//2564 1460//1460 1462//1462 -f 2564//2564 1462//1462 1440//1440 -f 1452//1452 1454//1454 2565//2565 -f 2565//2565 1454//1454 1456//1456 -f 2565//2565 1456//1456 2568//2568 -f 2568//2568 1456//1456 1458//1458 -f 2568//2568 1458//1458 1460//1460 -f 1440//1440 1442//1442 2563//2563 -f 2563//2563 1442//1442 1444//1444 -f 2563//2563 1444//1444 2567//2567 -f 2567//2567 1444//1444 1446//1446 -f 2567//2567 1446//1446 1448//1448 -f 2567//2567 2566//2566 1859//1859 -f 1859//1859 2566//2566 1860//1860 -f 2563//2563 2567//2567 1863//1863 -f 1863//1863 2567//2567 1859//1859 -f 2564//2564 2563//2563 1862//1862 -f 1862//1862 2563//2563 1863//1863 -f 2568//2568 2564//2564 1861//1861 -f 1861//1861 2564//2564 1862//1862 -f 2565//2565 2568//2568 1894//1894 -f 1894//1894 2568//2568 1861//1861 -f 2566//2566 2565//2565 1860//1860 -f 1860//1860 2565//2565 1894//1894 -f 2569//2569 2570//2570 2554//2554 -f 2557//2557 2571//2571 2556//2556 -f 2556//2556 2571//2571 2569//2569 -f 2556//2556 2569//2569 2555//2555 -f 2555//2555 2569//2569 2554//2554 -f 2572//2572 2573//2573 2561//2561 -f 2561//2561 2562//2562 2572//2572 -f 2572//2572 2562//2562 2551//2551 -f 2572//2572 2551//2551 2574//2574 -f 2574//2574 2551//2551 2552//2552 -f 2574//2574 2552//2552 2570//2570 -f 2570//2570 2552//2552 2553//2553 -f 2570//2570 2553//2553 2554//2554 -f 2557//2557 2558//2558 2571//2571 -f 2571//2571 2558//2558 2559//2559 -f 2571//2571 2559//2559 2573//2573 -f 2573//2573 2559//2559 2560//2560 -f 2573//2573 2560//2560 2561//2561 -f 2569//2569 2571//2571 1953//1953 -f 1953//1953 2571//2571 1954//1954 -f 2570//2570 2569//2569 1952//1952 -f 1952//1952 2569//2569 1953//1953 -f 2574//2574 2570//2570 1951//1951 -f 1951//1951 2570//2570 1952//1952 -f 2572//2572 2574//2574 1950//1950 -f 1950//1950 2574//2574 1951//1951 -f 2573//2573 2572//2572 1949//1949 -f 1949//1949 2572//2572 1950//1950 -f 2571//2571 2573//2573 1954//1954 -f 1954//1954 2573//2573 1949//1949 -f 2575//2575 2576//2576 2537//2537 -f 2537//2537 2538//2538 2575//2575 -f 2575//2575 2538//2538 2527//2527 -f 2575//2575 2527//2527 2577//2577 -f 2533//2533 2578//2578 2532//2532 -f 2532//2532 2578//2578 2579//2579 -f 2533//2533 2534//2534 2578//2578 -f 2578//2578 2534//2534 2535//2535 -f 2578//2578 2535//2535 2576//2576 -f 2576//2576 2535//2535 2536//2536 -f 2576//2576 2536//2536 2537//2537 -f 2527//2527 2528//2528 2577//2577 -f 2577//2577 2528//2528 2529//2529 -f 2577//2577 2529//2529 2580//2580 -f 2580//2580 2529//2529 2530//2530 -f 2580//2580 2530//2530 2579//2579 -f 2579//2579 2530//2530 2531//2531 -f 2579//2579 2531//2531 2532//2532 -f 2579//2579 2578//2578 1869//1869 -f 1869//1869 2578//2578 1864//1864 -f 2580//2580 2579//2579 1870//1870 -f 1870//1870 2579//2579 1869//1869 -f 2577//2577 2580//2580 1868//1868 -f 1868//1868 2580//2580 1870//1870 -f 2575//2575 2577//2577 1867//1867 -f 1867//1867 2577//2577 1868//1868 -f 2576//2576 2575//2575 1865//1865 -f 1865//1865 2575//2575 1867//1867 -f 2578//2578 2576//2576 1864//1864 -f 1864//1864 2576//2576 1865//1865 -f 2521//2521 2581//2581 2520//2520 -f 2520//2520 2581//2581 2582//2582 -f 2521//2521 2522//2522 2581//2581 -f 2581//2581 2522//2522 2523//2523 -f 2581//2581 2523//2523 2583//2583 -f 2584//2584 2585//2585 2515//2515 -f 2523//2523 2524//2524 2583//2583 -f 2583//2583 2524//2524 2525//2525 -f 2583//2583 2525//2525 2585//2585 -f 2585//2585 2525//2525 2526//2526 -f 2585//2585 2526//2526 2515//2515 -f 2515//2515 2516//2516 2584//2584 -f 2584//2584 2516//2516 2517//2517 -f 2584//2584 2517//2517 2586//2586 -f 2586//2586 2517//2517 2518//2518 -f 2586//2586 2518//2518 2582//2582 -f 2582//2582 2518//2518 2519//2519 -f 2582//2582 2519//2519 2520//2520 -f 2582//2582 2581//2581 1693//1693 -f 1693//1693 2581//2581 1694//1694 -f 2586//2586 2582//2582 1699//1699 -f 1699//1699 2582//2582 1693//1693 -f 2584//2584 2586//2586 1698//1698 -f 1698//1698 2586//2586 1699//1699 -f 2585//2585 2584//2584 1691//1691 -f 1691//1691 2584//2584 1698//1698 -f 2583//2583 2585//2585 1690//1690 -f 1690//1690 2585//2585 1691//1691 -f 2581//2581 2583//2583 1694//1694 -f 1694//1694 2583//2583 1690//1690 -f 2587//2587 2588//2588 2544//2544 -f 2547//2547 2589//2589 2546//2546 -f 2546//2546 2589//2589 2587//2587 -f 2546//2546 2587//2587 2545//2545 -f 2545//2545 2587//2587 2544//2544 -f 2590//2590 2591//2591 2539//2539 -f 2547//2547 2548//2548 2589//2589 -f 2589//2589 2548//2548 2549//2549 -f 2589//2589 2549//2549 2591//2591 -f 2591//2591 2549//2549 2550//2550 -f 2591//2591 2550//2550 2539//2539 -f 2539//2539 2540//2540 2590//2590 -f 2590//2590 2540//2540 2541//2541 -f 2590//2590 2541//2541 2592//2592 -f 2592//2592 2541//2541 2542//2542 -f 2592//2592 2542//2542 2588//2588 -f 2588//2588 2542//2542 2543//2543 -f 2588//2588 2543//2543 2544//2544 -f 1879//1879 2588//2588 1881//1881 -f 1881//1881 2588//2588 2587//2587 -f 1881//1881 2587//2587 1535//1535 -f 1557//1557 1556//1556 2592//2592 -f 2588//2588 1879//1879 1877//1877 -f 2588//2588 1877//1877 2592//2592 -f 2592//2592 1877//1877 1876//1876 -f 2592//2592 1876//1876 1557//1557 -f 1873//1873 2590//2590 1685//1685 -f 1685//1685 2590//2590 2592//2592 -f 1685//1685 2592//2592 1556//1556 -f 1875//1875 2591//2591 1874//1874 -f 1874//1874 2591//2591 2590//2590 -f 1874//1874 2590//2590 1873//1873 -f 2589//2589 2591//2591 1536//1536 -f 1536//1536 2591//2591 1875//1875 -f 2587//2587 2589//2589 1535//1535 -f 1535//1535 2589//2589 1536//1536 -f 2593//2593 2594//2594 1428//1428 -f 1428//1428 1430//1430 2593//2593 -f 2593//2593 1430//1430 1432//1432 -f 2593//2593 1432//1432 2595//2595 -f 1432//1432 1434//1434 2595//2595 -f 2595//2595 1434//1434 1436//1436 -f 2595//2595 1436//1436 2596//2596 -f 1436//1436 1438//1438 2596//2596 -f 2596//2596 1438//1438 1416//1416 -f 2596//2596 1416//1416 2597//2597 -f 2598//2598 1424//1424 2594//2594 -f 2594//2594 1424//1424 1426//1426 -f 2594//2594 1426//1426 1428//1428 -f 1416//1416 1418//1418 2597//2597 -f 2597//2597 1418//1418 1420//1420 -f 2597//2597 1420//1420 2598//2598 -f 2598//2598 1420//1420 1422//1422 -f 2598//2598 1422//1422 1424//1424 -f 2598//2598 2594//2594 1928//1928 -f 1928//1928 2594//2594 1592//1592 -f 2597//2597 2598//2598 1575//1575 -f 1575//1575 2598//2598 1928//1928 -f 1572//1572 2596//2596 1573//1573 -f 1573//1573 2596//2596 2597//2597 -f 1573//1573 2597//2597 1575//1575 -f 2595//2595 2596//2596 1579//1579 -f 1579//1579 2596//2596 1572//1572 -f 2595//2595 1579//1579 1578//1578 -f 1595//1595 2593//2593 1590//1590 -f 1590//1590 2593//2593 2595//2595 -f 1590//1590 2595//2595 1587//1587 -f 1587//1587 2595//2595 1578//1578 -f 1592//1592 2594//2594 1594//1594 -f 1594//1594 2594//2594 2593//2593 -f 1594//1594 2593//2593 1595//1595 -f 2599//2599 2600//2600 1500//1500 -f 1508//1508 2601//2601 1506//1506 -f 1506//1506 2601//2601 2602//2602 -f 1506//1506 2602//2602 1504//1504 -f 1504//1504 2602//2602 2599//2599 -f 1504//1504 2599//2599 1502//1502 -f 1502//1502 2599//2599 1500//1500 -f 1508//1508 1510//1510 2601//2601 -f 2601//2601 1510//1510 1488//1488 -f 2601//2601 1488//1488 2603//2603 -f 2604//2604 1496//1496 2600//2600 -f 2600//2600 1496//1496 1498//1498 -f 2600//2600 1498//1498 1500//1500 -f 1488//1488 1490//1490 2603//2603 -f 2603//2603 1490//1490 1492//1492 -f 2603//2603 1492//1492 2604//2604 -f 2604//2604 1492//1492 1494//1494 -f 2604//2604 1494//1494 1496//1496 -f 2604//2604 2600//2600 1752//1752 -f 1752//1752 2600//2600 1754//1754 -f 2603//2603 2604//2604 1751//1751 -f 1751//1751 2604//2604 1752//1752 -f 2601//2601 2603//2603 1533//1533 -f 1533//1533 2603//2603 1751//1751 -f 2602//2602 2601//2601 1532//1532 -f 1532//1532 2601//2601 1533//1533 -f 2599//2599 2602//2602 1883//1883 -f 1883//1883 2602//2602 1532//1532 -f 2600//2600 2599//2599 1754//1754 -f 1754//1754 2599//2599 1883//1883 -f 2605//2605 2606//2606 1476//1476 -f 2607//2607 1484//1484 2608//2608 -f 2608//2608 1484//1484 1486//1486 -f 2608//2608 1486//1486 2609//2609 -f 2609//2609 1486//1486 1464//1464 -f 2610//2610 1472//1472 2606//2606 -f 2606//2606 1472//1472 1474//1474 -f 2606//2606 1474//1474 1476//1476 -f 1476//1476 1478//1478 2605//2605 -f 2605//2605 1478//1478 1480//1480 -f 2605//2605 1480//1480 2607//2607 -f 2607//2607 1480//1480 1482//1482 -f 2607//2607 1482//1482 1484//1484 -f 1464//1464 1466//1466 2609//2609 -f 2609//2609 1466//1466 1468//1468 -f 2609//2609 1468//1468 2610//2610 -f 2610//2610 1468//1468 1470//1470 -f 2610//2610 1470//1470 1472//1472 -f 2610//2610 2606//2606 1570//1570 -f 1570//1570 2606//2606 1571//1571 -f 2609//2609 2610//2610 1569//1569 -f 1569//1569 2610//2610 1570//1570 -f 2608//2608 2609//2609 1568//1568 -f 1568//1568 2609//2609 1569//1569 -f 2607//2607 2608//2608 1886//1886 -f 1886//1886 2608//2608 1568//1568 -f 2605//2605 2607//2607 1947//1947 -f 1947//1947 2607//2607 1886//1886 -f 2606//2606 2605//2605 1571//1571 -f 1571//1571 2605//2605 1947//1947 -f 1400//1400 2611//2611 1398//1398 -f 1398//1398 2611//2611 2612//2612 -f 1398//1398 2612//2612 1396//1396 -f 1396//1396 2612//2612 2613//2613 -f 1396//1396 2613//2613 1394//1394 -f 1394//1394 2613//2613 2614//2614 -f 1394//1394 2614//2614 1392//1392 -f 1392//1392 2614//2614 2615//2615 -f 1392//1392 2615//2615 1414//1414 -f 1414//1414 2615//2615 2616//2616 -f 1414//1414 2616//2616 1412//1412 -f 2616//2616 2617//2617 1412//1412 -f 1412//1412 2617//2617 2618//2618 -f 1412//1412 2618//2618 1410//1410 -f 1410//1410 2618//2618 2619//2619 -f 1410//1410 2619//2619 1408//1408 -f 1408//1408 2619//2619 2620//2620 -f 1408//1408 2620//2620 1406//1406 -f 1406//1406 2620//2620 2621//2621 -f 1406//1406 2621//2621 1404//1404 -f 1404//1404 2621//2621 2622//2622 -f 1404//1404 2622//2622 1402//1402 -f 1402//1402 2622//2622 2623//2623 -f 1402//1402 2623//2623 1400//1400 -f 1400//1400 2623//2623 2624//2624 -f 1400//1400 2624//2624 2611//2611 -f 2623//2623 2440//2440 2624//2624 -f 2624//2624 2440//2440 2442//2442 -f 2624//2624 2442//2442 2611//2611 -f 2611//2611 2442//2442 2444//2444 -f 2611//2611 2444//2444 2612//2612 -f 2612//2612 2444//2444 2503//2503 -f 2612//2612 2503//2503 2613//2613 -f 2613//2613 2503//2503 2446//2446 -f 2613//2613 2446//2446 2614//2614 -f 2614//2614 2446//2446 2445//2445 -f 2614//2614 2445//2445 2615//2615 -f 2615//2615 2445//2445 2449//2449 -f 2615//2615 2449//2449 2616//2616 -f 2616//2616 2449//2449 2448//2448 -f 2616//2616 2448//2448 2617//2617 -f 2617//2617 2448//2448 2447//2447 -f 2617//2617 2447//2447 2618//2618 -f 2618//2618 2447//2447 2149//2149 -f 2618//2618 2149//2149 2619//2619 -f 2619//2619 2149//2149 2154//2154 -f 2619//2619 2154//2154 2620//2620 -f 2620//2620 2154//2154 2435//2435 -f 2620//2620 2435//2435 2621//2621 -f 2621//2621 2435//2435 2437//2437 -f 2621//2621 2437//2437 2622//2622 -f 2622//2622 2437//2437 2438//2438 -f 2622//2622 2438//2438 2623//2623 -f 2623//2623 2438//2438 2440//2440 -f 1376//1376 2625//2625 1374//1374 -f 1374//1374 2625//2625 2626//2626 -f 1374//1374 2626//2626 1372//1372 -f 1372//1372 2626//2626 2627//2627 -f 1372//1372 2627//2627 1370//1370 -f 1370//1370 2627//2627 2628//2628 -f 1370//1370 2628//2628 1368//1368 -f 1368//1368 2628//2628 2629//2629 -f 1368//1368 2629//2629 1390//1390 -f 1390//1390 2629//2629 2630//2630 -f 1390//1390 2630//2630 1388//1388 -f 2630//2630 2631//2631 1388//1388 -f 1388//1388 2631//2631 2632//2632 -f 1388//1388 2632//2632 1386//1386 -f 1386//1386 2632//2632 2633//2633 -f 1386//1386 2633//2633 1384//1384 -f 1384//1384 2633//2633 2634//2634 -f 1384//1384 2634//2634 1382//1382 -f 1382//1382 2634//2634 2635//2635 -f 1382//1382 2635//2635 1380//1380 -f 1380//1380 2635//2635 2636//2636 -f 1380//1380 2636//2636 1378//1378 -f 1378//1378 2636//2636 2637//2637 -f 1378//1378 2637//2637 1376//1376 -f 1376//1376 2637//2637 2638//2638 -f 1376//1376 2638//2638 2625//2625 -f 2637//2637 2431//2431 2638//2638 -f 2638//2638 2431//2431 2193//2193 -f 2638//2638 2193//2193 2625//2625 -f 2625//2625 2193//2193 2185//2185 -f 2625//2625 2185//2185 2626//2626 -f 2626//2626 2185//2185 2184//2184 -f 2626//2626 2184//2184 2627//2627 -f 2627//2627 2184//2184 2189//2189 -f 2627//2627 2189//2189 2628//2628 -f 2628//2628 2189//2189 2188//2188 -f 2628//2628 2188//2188 2629//2629 -f 2629//2629 2188//2188 2187//2187 -f 2629//2629 2187//2187 2630//2630 -f 2630//2630 2187//2187 2424//2424 -f 2630//2630 2424//2424 2631//2631 -f 2631//2631 2424//2424 2423//2423 -f 2631//2631 2423//2423 2632//2632 -f 2632//2632 2423//2423 2421//2421 -f 2632//2632 2421//2421 2633//2633 -f 2633//2633 2421//2421 2420//2420 -f 2633//2633 2420//2420 2634//2634 -f 2634//2634 2420//2420 2425//2425 -f 2634//2634 2425//2425 2635//2635 -f 2635//2635 2425//2425 2427//2427 -f 2635//2635 2427//2427 2636//2636 -f 2636//2636 2427//2427 2432//2432 -f 2636//2636 2432//2432 2637//2637 -f 2637//2637 2432//2432 2431//2431 -f 2194//2194 2084//2084 2085//2085 -f 2194//2194 2085//2085 2192//2192 -f 2192//2192 2085//2085 2070//2070 -f 2192//2192 2070//2070 2191//2191 -f 2191//2191 2070//2070 2069//2069 -f 2191//2191 2069//2069 2190//2190 -f 2075//2075 2434//2434 2433//2433 -f 2075//2075 2433//2433 2076//2076 -f 2076//2076 2433//2433 2153//2153 -f 2076//2076 2153//2153 2088//2088 -f 2088//2088 2153//2153 2152//2152 -f 2088//2088 2152//2152 2087//2087 -f 2639//2639 2640//2640 2641//2641 -f 2641//2641 2640//2640 2642//2642 -f 2641//2641 2642//2642 2643//2643 -f 2643//2643 2642//2642 2644//2644 -f 2643//2643 2644//2644 2645//2645 -f 2645//2645 2644//2644 2646//2646 -f 2645//2645 2646//2646 2647//2647 -f 2647//2647 2646//2646 2648//2648 -f 2647//2647 2648//2648 2649//2649 -f 2649//2649 2648//2648 2650//2650 -f 2649//2649 2650//2650 2651//2651 -f 2651//2651 2650//2650 2652//2652 -f 2651//2651 2652//2652 2653//2653 -f 2653//2653 2652//2652 2654//2654 -f 2653//2653 2654//2654 2655//2655 -f 2655//2655 2654//2654 2656//2656 -f 2655//2655 2656//2656 2657//2657 -f 2657//2657 2656//2656 2658//2658 -f 2657//2657 2658//2658 2659//2659 -f 2659//2659 2658//2658 2660//2660 -f 2659//2659 2660//2660 2661//2661 -f 2661//2661 2660//2660 2662//2662 -f 2661//2661 2662//2662 2639//2639 -f 2639//2639 2662//2662 2640//2640 -f 2663//2663 2664//2664 2665//2665 -f 2665//2665 2664//2664 2666//2666 -f 2665//2665 2666//2666 2667//2667 -f 2667//2667 2666//2666 2668//2668 -f 2667//2667 2668//2668 2669//2669 -f 2669//2669 2668//2668 2670//2670 -f 2669//2669 2670//2670 2671//2671 -f 2671//2671 2670//2670 2672//2672 -f 2671//2671 2672//2672 2673//2673 -f 2673//2673 2672//2672 2674//2674 -f 2673//2673 2674//2674 2675//2675 -f 2675//2675 2674//2674 2676//2676 -f 2675//2675 2676//2676 2677//2677 -f 2677//2677 2676//2676 2678//2678 -f 2677//2677 2678//2678 2679//2679 -f 2679//2679 2678//2678 2680//2680 -f 2679//2679 2680//2680 2681//2681 -f 2681//2681 2680//2680 2682//2682 -f 2681//2681 2682//2682 2683//2683 -f 2683//2683 2682//2682 2684//2684 -f 2683//2683 2684//2684 2685//2685 -f 2685//2685 2684//2684 2686//2686 -f 2685//2685 2686//2686 2663//2663 -f 2663//2663 2686//2686 2664//2664 -f 2687//2687 2688//2688 2689//2689 -f 2689//2689 2688//2688 2690//2690 -f 2689//2689 2690//2690 2691//2691 -f 2691//2691 2690//2690 2692//2692 -f 2691//2691 2692//2692 2693//2693 -f 2693//2693 2692//2692 2694//2694 -f 2693//2693 2694//2694 2695//2695 -f 2695//2695 2694//2694 2696//2696 -f 2695//2695 2696//2696 2697//2697 -f 2697//2697 2696//2696 2698//2698 -f 2697//2697 2698//2698 2699//2699 -f 2699//2699 2698//2698 2700//2700 -f 2699//2699 2700//2700 2701//2701 -f 2701//2701 2700//2700 2702//2702 -f 2701//2701 2702//2702 2703//2703 -f 2703//2703 2702//2702 2704//2704 -f 2703//2703 2704//2704 2705//2705 -f 2705//2705 2704//2704 2706//2706 -f 2705//2705 2706//2706 2707//2707 -f 2707//2707 2706//2706 2708//2708 -f 2707//2707 2708//2708 2709//2709 -f 2709//2709 2708//2708 2710//2710 -f 2709//2709 2710//2710 2687//2687 -f 2687//2687 2710//2710 2688//2688 -f 2711//2711 2712//2712 2713//2713 -f 2713//2713 2712//2712 2714//2714 -f 2713//2713 2714//2714 2715//2715 -f 2715//2715 2714//2714 2716//2716 -f 2715//2715 2716//2716 2717//2717 -f 2717//2717 2716//2716 2718//2718 -f 2717//2717 2718//2718 2719//2719 -f 2719//2719 2718//2718 2720//2720 -f 2719//2719 2720//2720 2721//2721 -f 2721//2721 2720//2720 2722//2722 -f 2721//2721 2722//2722 2723//2723 -f 2723//2723 2722//2722 2724//2724 -f 2723//2723 2724//2724 2725//2725 -f 2725//2725 2724//2724 2726//2726 -f 2725//2725 2726//2726 2727//2727 -f 2727//2727 2726//2726 2728//2728 -f 2727//2727 2728//2728 2729//2729 -f 2729//2729 2728//2728 2730//2730 -f 2729//2729 2730//2730 2731//2731 -f 2731//2731 2730//2730 2732//2732 -f 2731//2731 2732//2732 2733//2733 -f 2733//2733 2732//2732 2734//2734 -f 2733//2733 2734//2734 2711//2711 -f 2711//2711 2734//2734 2712//2712 -f 2735//2735 2736//2736 2737//2737 -f 2737//2737 2736//2736 2738//2738 -f 2737//2737 2738//2738 2739//2739 -f 2739//2739 2738//2738 2740//2740 -f 2739//2739 2740//2740 2741//2741 -f 2741//2741 2740//2740 2742//2742 -f 2741//2741 2742//2742 2743//2743 -f 2743//2743 2742//2742 2744//2744 -f 2743//2743 2744//2744 2745//2745 -f 2745//2745 2744//2744 2746//2746 -f 2745//2745 2746//2746 2747//2747 -f 2747//2747 2746//2746 2748//2748 -f 2747//2747 2748//2748 2749//2749 -f 2749//2749 2748//2748 2750//2750 -f 2749//2749 2750//2750 2751//2751 -f 2751//2751 2750//2750 2752//2752 -f 2751//2751 2752//2752 2753//2753 -f 2753//2753 2752//2752 2754//2754 -f 2753//2753 2754//2754 2755//2755 -f 2755//2755 2754//2754 2756//2756 -f 2755//2755 2756//2756 2757//2757 -f 2757//2757 2756//2756 2758//2758 -f 2757//2757 2758//2758 2735//2735 -f 2735//2735 2758//2758 2736//2736 -f 2759//2759 2760//2760 2761//2761 -f 2761//2761 2760//2760 2762//2762 -f 2761//2761 2762//2762 2763//2763 -f 2763//2763 2762//2762 2764//2764 -f 2763//2763 2764//2764 2765//2765 -f 2765//2765 2764//2764 2766//2766 -f 2765//2765 2766//2766 2767//2767 -f 2767//2767 2766//2766 2768//2768 -f 2767//2767 2768//2768 2769//2769 -f 2769//2769 2768//2768 2770//2770 -f 2769//2769 2770//2770 2771//2771 -f 2771//2771 2770//2770 2772//2772 -f 2771//2771 2772//2772 2773//2773 -f 2773//2773 2772//2772 2774//2774 -f 2773//2773 2774//2774 2775//2775 -f 2775//2775 2774//2774 2776//2776 -f 2775//2775 2776//2776 2777//2777 -f 2777//2777 2776//2776 2778//2778 -f 2777//2777 2778//2778 2779//2779 -f 2779//2779 2778//2778 2780//2780 -f 2779//2779 2780//2780 2781//2781 -f 2781//2781 2780//2780 2782//2782 -f 2781//2781 2782//2782 2759//2759 -f 2759//2759 2782//2782 2760//2760 -f 2783//2783 2784//2784 2785//2785 -f 2786//2786 2787//2787 2788//2788 -f 2789//2789 2790//2790 2791//2791 -f 2792//2792 2793//2793 2794//2794 -f 2795//2795 2796//2796 2797//2797 -f 2798//2798 2799//2799 2800//2800 -f 2674//2674 2672//2672 2800//2800 -f 2656//2656 2801//2801 2802//2802 -f 2803//2803 2804//2804 2805//2805 -f 2806//2806 2807//2807 2808//2808 -f 2809//2809 2810//2810 2811//2811 -f 2812//2812 2813//2813 2814//2814 -f 2815//2815 2816//2816 2817//2817 -f 2818//2818 2819//2819 2820//2820 -f 2821//2821 2822//2822 2823//2823 -f 2824//2824 2825//2825 2826//2826 -f 2827//2827 2828//2828 2829//2829 -f 2830//2830 2831//2831 2832//2832 -f 2833//2833 2834//2834 2835//2835 -f 2836//2836 2837//2837 2838//2838 -f 2839//2839 2840//2840 2792//2792 -f 2792//2792 2840//2840 2841//2841 -f 2792//2792 2841//2841 2793//2793 -f 2793//2793 2841//2841 2842//2842 -f 2843//2843 2844//2844 2845//2845 -f 2845//2845 2844//2844 2846//2846 -f 2845//2845 2846//2846 2847//2847 -f 2848//2848 2849//2849 2850//2850 -f 2851//2851 2852//2852 2853//2853 -f 2853//2853 2852//2852 2848//2848 -f 2853//2853 2848//2848 2854//2854 -f 2854//2854 2848//2848 2850//2850 -f 2854//2854 2850//2850 2855//2855 -f 2848//2848 2856//2856 2849//2849 -f 2849//2849 2856//2856 2857//2857 -f 2849//2849 2857//2857 2858//2858 -f 2857//2857 2859//2859 2858//2858 -f 2858//2858 2859//2859 2860//2860 -f 2858//2858 2860//2860 2861//2861 -f 2862//2862 2863//2863 2864//2864 -f 2864//2864 2863//2863 2865//2865 -f 2864//2864 2865//2865 2860//2860 -f 2860//2860 2865//2865 2866//2866 -f 2860//2860 2866//2866 2861//2861 -f 2867//2867 2868//2868 2795//2795 -f 2795//2795 2868//2868 2869//2869 -f 2837//2837 2870//2870 2871//2871 -f 2872//2872 2873//2873 2874//2874 -f 2875//2875 2876//2876 2877//2877 -f 2868//2868 2878//2878 2869//2869 -f 2869//2869 2878//2878 2879//2879 -f 2869//2869 2879//2879 2874//2874 -f 2874//2874 2879//2879 2880//2880 -f 2874//2874 2880//2880 2872//2872 -f 2875//2875 2877//2877 2873//2873 -f 2881//2881 2882//2882 2883//2883 -f 2883//2883 2882//2882 2884//2884 -f 2885//2885 2886//2886 2887//2887 -f 2887//2887 2886//2886 2888//2888 -f 2882//2882 2889//2889 2884//2884 -f 2884//2884 2889//2889 2890//2890 -f 2884//2884 2890//2890 2891//2891 -f 2891//2891 2890//2890 2892//2892 -f 2893//2893 2894//2894 2885//2885 -f 2885//2885 2894//2894 2895//2895 -f 2885//2885 2895//2895 2886//2886 -f 2892//2892 2896//2896 2891//2891 -f 2891//2891 2896//2896 2897//2897 -f 2891//2891 2897//2897 2893//2893 -f 2893//2893 2897//2897 2898//2898 -f 2893//2893 2898//2898 2894//2894 -f 2784//2784 2899//2899 2900//2900 -f 2901//2901 2902//2902 2903//2903 -f 2903//2903 2902//2902 2904//2904 -f 2905//2905 2906//2906 2907//2907 -f 2907//2907 2906//2906 2908//2908 -f 2907//2907 2908//2908 2900//2900 -f 2900//2900 2908//2908 2909//2909 -f 2900//2900 2909//2909 2910//2910 -f 2911//2911 2912//2912 2913//2913 -f 2913//2913 2912//2912 2914//2914 -f 2913//2913 2914//2914 2903//2903 -f 2903//2903 2914//2914 2915//2915 -f 2903//2903 2915//2915 2901//2901 -f 2899//2899 2784//2784 2916//2916 -f 2916//2916 2784//2784 2783//2783 -f 2916//2916 2783//2783 2917//2917 -f 2918//2918 2919//2919 2920//2920 -f 2920//2920 2919//2919 2921//2921 -f 2920//2920 2921//2921 2922//2922 -f 2922//2922 2921//2921 2923//2923 -f 2922//2922 2923//2923 2924//2924 -f 2924//2924 2923//2923 2925//2925 -f 2923//2923 2926//2926 2925//2925 -f 2925//2925 2926//2926 2833//2833 -f 2925//2925 2833//2833 2927//2927 -f 2927//2927 2833//2833 2835//2835 -f 2928//2928 2929//2929 2930//2930 -f 2930//2930 2931//2931 2928//2928 -f 2928//2928 2931//2931 2932//2932 -f 2928//2928 2932//2932 2933//2933 -f 2933//2933 2932//2932 2903//2903 -f 2933//2933 2903//2903 2907//2907 -f 2907//2907 2903//2903 2904//2904 -f 2907//2907 2904//2904 2905//2905 -f 2934//2934 2935//2935 2936//2936 -f 2936//2936 2935//2935 2937//2937 -f 2938//2938 2939//2939 2940//2940 -f 2938//2938 2940//2940 2941//2941 -f 2942//2942 2943//2943 2944//2944 -f 2944//2944 2943//2943 2941//2941 -f 2939//2939 2945//2945 2940//2940 -f 2940//2940 2945//2945 2946//2946 -f 2940//2940 2946//2946 2937//2937 -f 2937//2937 2946//2946 2947//2947 -f 2937//2937 2947//2947 2936//2936 -f 2942//2942 2944//2944 2948//2948 -f 2948//2948 2944//2944 2949//2949 -f 2948//2948 2949//2949 2950//2950 -f 2950//2950 2949//2949 2951//2951 -f 2950//2950 2951//2951 2832//2832 -f 2832//2832 2951//2951 2952//2952 -f 2832//2832 2952//2952 2830//2830 -f 2953//2953 2954//2954 2827//2827 -f 2827//2827 2954//2954 2955//2955 -f 2827//2827 2955//2955 2956//2956 -f 2953//2953 2827//2827 2957//2957 -f 2957//2957 2827//2827 2829//2829 -f 2957//2957 2829//2829 2958//2958 -f 2958//2958 2829//2829 2959//2959 -f 2958//2958 2959//2959 2960//2960 -f 2961//2961 2962//2962 2963//2963 -f 2960//2960 2964//2964 2958//2958 -f 2958//2958 2964//2964 2965//2965 -f 2958//2958 2965//2965 2966//2966 -f 2966//2966 2965//2965 2967//2967 -f 2963//2963 2962//2962 2968//2968 -f 2968//2968 2962//2962 2969//2969 -f 2968//2968 2969//2969 2960//2960 -f 2960//2960 2969//2969 2970//2970 -f 2960//2960 2970//2970 2964//2964 -f 2967//2967 2965//2965 2971//2971 -f 2971//2971 2965//2965 2961//2961 -f 2971//2971 2961//2961 2972//2972 -f 2936//2936 2973//2973 2934//2934 -f 2934//2934 2973//2973 2974//2974 -f 2934//2934 2974//2974 2963//2963 -f 2963//2963 2974//2974 2975//2975 -f 2975//2975 2824//2824 2963//2963 -f 2963//2963 2824//2824 2826//2826 -f 2963//2963 2826//2826 2961//2961 -f 2961//2961 2826//2826 2976//2976 -f 2961//2961 2976//2976 2972//2972 -f 2977//2977 2978//2978 2848//2848 -f 2848//2848 2978//2978 2979//2979 -f 2848//2848 2979//2979 2856//2856 -f 2980//2980 2981//2981 2982//2982 -f 2982//2982 2983//2983 2980//2980 -f 2980//2980 2983//2983 2984//2984 -f 2980//2980 2984//2984 2985//2985 -f 2986//2986 2987//2987 2988//2988 -f 2821//2821 2823//2823 2989//2989 -f 2990//2990 2823//2823 2991//2991 -f 2991//2991 2823//2823 2992//2992 -f 2990//2990 2993//2993 2823//2823 -f 2823//2823 2993//2993 2994//2994 -f 2823//2823 2994//2994 2989//2989 -f 2995//2995 2996//2996 2992//2992 -f 2997//2997 2998//2998 2828//2828 -f 2828//2828 2998//2998 2999//2999 -f 2828//2828 2999//2999 3000//3000 -f 3000//3000 3001//3001 2828//2828 -f 2828//2828 3001//3001 3002//3002 -f 2828//2828 3002//3002 2829//2829 -f 3003//3003 3004//3004 3005//3005 -f 3006//3006 3007//3007 2847//2847 -f 3003//3003 3008//3008 3004//3004 -f 3004//3004 3008//3008 3009//3009 -f 3004//3004 3009//3009 3010//3010 -f 3011//3011 2845//2845 3012//3012 -f 3012//3012 2845//2845 2847//2847 -f 3012//3012 2847//2847 3013//3013 -f 3013//3013 2847//2847 3007//3007 -f 3014//3014 3015//3015 3005//3005 -f 3005//3005 3015//3015 3016//3016 -f 3005//3005 3016//3016 3003//3003 -f 3017//3017 3018//3018 3019//3019 -f 3019//3019 3018//3018 3020//3020 -f 3019//3019 3020//3020 3014//3014 -f 3014//3014 3020//3020 3021//3021 -f 3014//3014 3021//3021 3015//3015 -f 2805//2805 2804//2804 3019//3019 -f 3019//3019 2804//2804 3022//3022 -f 3019//3019 3022//3022 3023//3023 -f 2851//2851 3024//3024 3025//3025 -f 3025//3025 3024//3024 3026//3026 -f 3025//3025 3026//3026 3023//3023 -f 3026//3026 3027//3027 3023//3023 -f 3023//3023 3027//3027 3028//3028 -f 3023//3023 3028//3028 3019//3019 -f 3019//3019 3028//3028 3029//3029 -f 3019//3019 3029//3029 3017//3017 -f 2855//2855 2850//2850 3030//3030 -f 3030//3030 2850//2850 2843//2843 -f 3030//3030 2843//2843 3031//3031 -f 3031//3031 2843//2843 2845//2845 -f 3031//3031 2845//2845 3032//3032 -f 3032//3032 2845//2845 3011//3011 -f 3032//3032 3011//3011 3033//3033 -f 3034//3034 3035//3035 3036//3036 -f 3035//3035 3034//3034 3037//3037 -f 3038//3038 3039//3039 2794//2794 -f 3040//3040 3041//3041 3042//3042 -f 3042//3042 3041//3041 3043//3043 -f 3044//3044 3045//3045 3046//3046 -f 3041//3041 3047//3047 3043//3043 -f 3043//3043 3047//3047 3048//3048 -f 3043//3043 3048//3048 3049//3049 -f 3046//3046 3050//3050 3044//3044 -f 3044//3044 3050//3050 3051//3051 -f 3044//3044 3051//3051 2794//2794 -f 2794//2794 3051//3051 3052//3052 -f 2794//2794 3052//3052 3038//3038 -f 3049//3049 3045//3045 3043//3043 -f 3043//3043 3045//3045 3044//3044 -f 3043//3043 3044//3044 3053//3053 -f 3053//3053 3044//3044 2930//2930 -f 3053//3053 2930//2930 2834//2834 -f 2834//2834 2930//2930 2929//2929 -f 2834//2834 2929//2929 2835//2835 -f 3054//3054 3055//3055 3056//3056 -f 3057//3057 3058//3058 3059//3059 -f 3059//3059 3058//3058 3060//3060 -f 3059//3059 3060//3060 3061//3061 -f 3061//3061 3060//3060 3062//3062 -f 2819//2819 2818//2818 3063//3063 -f 3064//3064 3065//3065 3066//3066 -f 3066//3066 3065//3065 3067//3067 -f 3066//3066 3067//3067 3068//3068 -f 3068//3068 3067//3067 2820//2820 -f 3068//3068 2820//2820 3069//3069 -f 2791//2791 3070//3070 3071//3071 -f 3072//3072 3073//3073 3074//3074 -f 3072//3072 3074//3074 3075//3075 -f 3070//3070 2791//2791 3076//3076 -f 3076//3076 2791//2791 2788//2788 -f 3076//3076 2788//2788 3056//3056 -f 3056//3056 2788//2788 3077//3077 -f 3056//3056 3077//3077 3054//3054 -f 3078//3078 3079//3079 3080//3080 -f 3080//3080 3079//3079 3081//3081 -f 3080//3080 3081//3081 3082//3082 -f 3083//3083 3084//3084 2814//2814 -f 2814//2814 3084//3084 3085//3085 -f 2814//2814 3085//3085 3086//3086 -f 3082//3082 3081//3081 3087//3087 -f 3087//3087 3081//3081 2987//2987 -f 3087//3087 2987//2987 3088//3088 -f 3088//3088 2987//2987 2986//2986 -f 3088//3088 2986//2986 3089//3089 -f 3090//3090 3091//3091 3066//3066 -f 3092//3092 3093//3093 3094//3094 -f 3095//3095 3064//3064 3092//3092 -f 3092//3092 3064//3064 3066//3066 -f 3092//3092 3066//3066 3093//3093 -f 3093//3093 3066//3066 3091//3091 -f 3078//3078 3083//3083 3079//3079 -f 3079//3079 3083//3083 2814//2814 -f 3079//3079 2814//2814 3096//3096 -f 3096//3096 2814//2814 2813//2813 -f 3096//3096 3097//3097 3079//3079 -f 3079//3079 3097//3097 3098//3098 -f 3079//3079 3098//3098 3099//3099 -f 3099//3099 3098//3098 3100//3100 -f 3099//3099 3100//3100 3101//3101 -f 3102//3102 3103//3103 3104//3104 -f 3104//3104 3103//3103 3105//3105 -f 3104//3104 3105//3105 3069//3069 -f 3069//3069 3105//3105 3106//3106 -f 3069//3069 3106//3106 2809//2809 -f 3107//3107 3108//3108 3109//3109 -f 3109//3109 3108//3108 3110//3110 -f 3109//3109 3110//3110 3111//3111 -f 2810//2810 3112//3112 3113//3113 -f 3113//3113 3112//3112 3114//3114 -f 3113//3113 3114//3114 3110//3110 -f 3110//3110 3114//3114 3115//3115 -f 3110//3110 3115//3115 3111//3111 -f 3116//3116 3110//3110 3117//3117 -f 3118//3118 3119//3119 3108//3108 -f 3108//3108 3119//3119 3120//3120 -f 3120//3120 3121//3121 3108//3108 -f 3108//3108 3121//3121 3122//3122 -f 3108//3108 3122//3122 3110//3110 -f 3110//3110 3122//3122 3123//3123 -f 3110//3110 3123//3123 3117//3117 -f 3117//3117 3124//3124 3116//3116 -f 3116//3116 3124//3124 3125//3125 -f 3116//3116 3125//3125 2822//2822 -f 3125//3125 3126//3126 2822//2822 -f 2822//2822 3126//3126 3127//3127 -f 2822//2822 3127//3127 2823//2823 -f 2823//2823 3127//3127 3128//3128 -f 2823//2823 3128//3128 3118//3118 -f 3118//3118 3128//3128 3129//3129 -f 3118//3118 3129//3129 3119//3119 -f 3130//3130 3131//3131 2792//2792 -f 3132//3132 3133//3133 2796//2796 -f 2796//2796 3133//3133 3134//3134 -f 2796//2796 3134//3134 2797//2797 -f 3135//3135 3136//3136 3137//3137 -f 2785//2785 3138//3138 3139//3139 -f 3135//3135 2963//2963 3140//3140 -f 3140//3140 2963//2963 2968//2968 -f 3140//3140 2968//2968 3141//3141 -f 3141//3141 2968//2968 3142//3142 -f 3141//3141 3142//3142 3139//3139 -f 3139//3139 3142//3142 3143//3143 -f 3139//3139 3143//3143 2785//2785 -f 2956//2956 2955//2955 3144//3144 -f 3144//3144 2955//2955 2952//2952 -f 3144//3144 2952//2952 3145//3145 -f 3145//3145 2952//2952 2951//2951 -f 3145//3145 2951//2951 3146//3146 -f 3146//3146 2951//2951 2949//2949 -f 3146//3146 2949//2949 2807//2807 -f 2828//2828 3147//3147 2997//2997 -f 2997//2997 3147//3147 3148//3148 -f 2997//2997 3148//3148 3149//3149 -f 3149//3149 3148//3148 3150//3150 -f 3149//3149 3150//3150 3151//3151 -f 3151//3151 3150//3150 3152//3152 -f 3151//3151 3152//3152 3153//3153 -f 3153//3153 3152//3152 2806//2806 -f 2851//2851 3025//3025 2852//2852 -f 2852//2852 3025//3025 3154//3154 -f 2852//2852 3154//3154 2803//2803 -f 2792//2792 3155//3155 2839//2839 -f 2839//2839 3155//3155 3156//3156 -f 2839//2839 3156//3156 3157//3157 -f 3157//3157 3156//3156 3158//3158 -f 3157//3157 3158//3158 2805//2805 -f 2805//2805 3158//3158 3159//3159 -f 2805//2805 3159//3159 2803//2803 -f 2803//2803 3159//3159 3160//3160 -f 2803//2803 3160//3160 2852//2852 -f 2852//2852 3160//3160 3161//3161 -f 2852//2852 3161//3161 2848//2848 -f 2848//2848 3161//3161 3162//3162 -f 2848//2848 3162//3162 2977//2977 -f 2656//2656 2654//2654 2801//2801 -f 2801//2801 2654//2654 2652//2652 -f 2801//2801 2652//2652 3163//3163 -f 2891//2891 2640//2640 2662//2662 -f 2640//2640 2891//2891 2642//2642 -f 2642//2642 2891//2891 2893//2893 -f 2642//2642 2893//2893 2644//2644 -f 2652//2652 2650//2650 3163//3163 -f 3163//3163 2650//2650 2648//2648 -f 3163//3163 2648//2648 2893//2893 -f 2893//2893 2648//2648 2646//2646 -f 2893//2893 2646//2646 2644//2644 -f 2660//2660 2658//2658 3164//3164 -f 2873//2873 2877//2877 2874//2874 -f 2874//2874 2877//2877 2664//2664 -f 2874//2874 2664//2664 2686//2686 -f 2686//2686 2684//2684 2874//2874 -f 2874//2874 2684//2684 2682//2682 -f 2874//2874 2682//2682 2799//2799 -f 2682//2682 2680//2680 2799//2799 -f 2799//2799 2680//2680 2678//2678 -f 2799//2799 2678//2678 2800//2800 -f 2800//2800 2678//2678 2676//2676 -f 2800//2800 2676//2676 2674//2674 -f 2789//2789 2670//2670 2790//2790 -f 2790//2790 2670//2670 2668//2668 -f 2790//2790 2668//2668 2877//2877 -f 2877//2877 2668//2668 2666//2666 -f 2877//2877 2666//2666 2664//2664 -f 2792//2792 3131//3131 3155//3155 -f 3155//3155 3131//3131 3165//3165 -f 3155//3155 3165//3165 3156//3156 -f 3156//3156 3165//3165 3132//3132 -f 3156//3156 3132//3132 3166//3166 -f 3166//3166 3132//3132 2796//2796 -f 3166//3166 2796//2796 3167//3167 -f 3167//3167 2796//2796 2795//2795 -f 3167//3167 2795//2795 3168//3168 -f 3168//3168 2795//2795 2869//2869 -f 3168//3168 2869//2869 3169//3169 -f 3169//3169 2869//2869 2874//2874 -f 3169//3169 2874//2874 3170//3170 -f 3170//3170 2874//2874 2799//2799 -f 3170//3170 2799//2799 3171//3171 -f 3171//3171 2799//2799 2798//2798 -f 3171//3171 2798//2798 3172//3172 -f 2985//2985 3172//3172 2980//2980 -f 2980//2980 3172//3172 2798//2798 -f 2980//2980 2798//2798 3173//3173 -f 3173//3173 2798//2798 2800//2800 -f 3173//3173 2800//2800 2789//2789 -f 2789//2789 2800//2800 2672//2672 -f 2789//2789 2672//2672 2670//2670 -f 2871//2871 3034//3034 3174//3174 -f 3174//3174 3034//3034 3036//3036 -f 3174//3174 3036//3036 3175//3175 -f 3175//3175 3036//3036 3176//3176 -f 3175//3175 3176//3176 2926//2926 -f 2926//2926 3176//3176 3177//3177 -f 2926//2926 3177//3177 2833//2833 -f 2833//2833 3177//3177 3178//3178 -f 2833//2833 3178//3178 2834//2834 -f 2834//2834 3178//3178 3179//3179 -f 2834//2834 3179//3179 3053//3053 -f 3042//3042 3037//3037 3180//3180 -f 3180//3180 3037//3037 3034//3034 -f 3180//3180 3034//3034 2797//2797 -f 2797//2797 3034//3034 2871//2871 -f 2797//2797 2871//2871 2795//2795 -f 2795//2795 2871//2871 2870//2870 -f 2795//2795 2870//2870 2867//2867 -f 3134//3134 3130//3130 2797//2797 -f 2797//2797 3130//3130 2792//2792 -f 2797//2797 2792//2792 3180//3180 -f 3180//3180 2792//2792 2794//2794 -f 3180//3180 2794//2794 3042//3042 -f 3042//3042 2794//2794 3039//3039 -f 3042//3042 3039//3039 3040//3040 -f 3094//3094 2812//2812 3092//3092 -f 3092//3092 2812//2812 2814//2814 -f 3092//3092 2814//2814 2817//2817 -f 2817//2817 2814//2814 3086//3086 -f 2817//2817 3086//3086 2815//2815 -f 3073//3073 3095//3095 3074//3074 -f 3074//3074 3095//3095 3092//3092 -f 3074//3074 3092//3092 3181//3181 -f 3181//3181 3092//3092 2817//2817 -f 3181//3181 2817//2817 2986//2986 -f 2986//2986 2817//2817 2816//2816 -f 2986//2986 2816//2816 3089//3089 -f 3071//3071 3075//3075 2791//2791 -f 2791//2791 3075//3075 3074//3074 -f 2791//2791 3074//3074 2789//2789 -f 2789//2789 3074//3074 3181//3181 -f 2789//2789 3181//3181 3173//3173 -f 3173//3173 3181//3181 2986//2986 -f 3173//3173 2986//2986 2980//2980 -f 2980//2980 2986//2986 2988//2988 -f 2980//2980 2988//2988 2981//2981 -f 2788//2788 2787//2787 3182//3182 -f 2787//2787 3183//3183 3182//3182 -f 3182//3182 3183//3183 3184//3184 -f 3182//3182 3184//3184 3185//3185 -f 3185//3185 2790//2790 3182//3182 -f 3182//3182 2790//2790 2877//2877 -f 3182//3182 2877//2877 2838//2838 -f 2838//2838 2877//2877 2876//2876 -f 2838//2838 2876//2876 2836//2836 -f 3185//3185 3186//3186 2790//2790 -f 2790//2790 3186//3186 3187//3187 -f 2790//2790 3187//3187 2791//2791 -f 2791//2791 3187//3187 3188//3188 -f 2791//2791 3188//3188 3189//3189 -f 3189//3189 3190//3190 2791//2791 -f 2791//2791 3190//3190 3191//3191 -f 2791//2791 3191//3191 2788//2788 -f 2788//2788 3191//3191 3192//3192 -f 2788//2788 3192//3192 2786//2786 -f 2941//2941 2940//2940 2944//2944 -f 2944//2944 2940//2940 3004//3004 -f 2944//2944 3004//3004 2847//2847 -f 2847//2847 3004//3004 3010//3010 -f 2847//2847 3010//3010 3006//3006 -f 2810//2810 3113//3113 2811//2811 -f 2811//2811 3113//3113 3193//3193 -f 2811//2811 3193//3193 3194//3194 -f 3194//3194 3193//3193 3099//3099 -f 3194//3194 3099//3099 3195//3195 -f 3195//3195 3099//3099 3101//3101 -f 3195//3195 3101//3101 3196//3196 -f 2809//2809 2811//2811 3069//3069 -f 3069//3069 2811//2811 3194//3194 -f 3069//3069 3194//3194 3068//3068 -f 3068//3068 3194//3194 3195//3195 -f 3068//3068 3195//3195 3066//3066 -f 3066//3066 3195//3195 3196//3196 -f 3066//3066 3196//3196 3090//3090 -f 2807//2807 2949//2949 2808//2808 -f 2808//2808 2949//2949 2944//2944 -f 2808//2808 2944//2944 3197//3197 -f 3197//3197 2944//2944 2847//2847 -f 3197//3197 2847//2847 3198//3198 -f 3198//3198 2847//2847 2846//2846 -f 3198//3198 2846//2846 3199//3199 -f 2806//2806 2808//2808 3153//3153 -f 3153//3153 2808//2808 3197//3197 -f 3153//3153 3197//3197 3200//3200 -f 3200//3200 3197//3197 3198//3198 -f 3200//3200 3198//3198 2862//2862 -f 2862//2862 3198//3198 3199//3199 -f 2862//2862 3199//3199 2863//2863 -f 3055//3055 3054//3054 3062//3062 -f 3062//3062 3054//3054 3201//3201 -f 3062//3062 3201//3201 3061//3061 -f 3061//3061 3201//3201 3202//3202 -f 3061//3061 3202//3202 3059//3059 -f 3063//3063 3164//3164 2802//2802 -f 2802//2802 3164//3164 2658//2658 -f 2802//2802 2658//2658 2656//2656 -f 3203//3203 3204//3204 3202//3202 -f 3205//3205 3206//3206 3059//3059 -f 3202//3202 3204//3204 3059//3059 -f 3059//3059 3204//3204 3207//3207 -f 3059//3059 3207//3207 3205//3205 -f 2818//2818 3057//3057 3063//3063 -f 3063//3063 3057//3057 3059//3059 -f 3063//3063 3059//3059 3164//3164 -f 3164//3164 3059//3059 3206//3206 -f 3208//3208 3209//3209 3210//3210 -f 3210//3210 3209//3209 3211//3211 -f 3210//3210 3211//3211 3202//3202 -f 3202//3202 3211//3211 3212//3212 -f 3202//3202 3212//3212 3203//3203 -f 3206//3206 3213//3213 3164//3164 -f 3164//3164 3213//3213 3214//3214 -f 3164//3164 3214//3214 3210//3210 -f 3210//3210 3214//3214 3215//3215 -f 3210//3210 3215//3215 3208//3208 -f 2837//2837 2871//2871 2838//2838 -f 2838//2838 2871//2871 3174//3174 -f 2838//2838 3174//3174 3182//3182 -f 3182//3182 3174//3174 3175//3175 -f 3182//3182 3175//3175 2788//2788 -f 2788//2788 3175//3175 2926//2926 -f 2788//2788 2926//2926 3077//3077 -f 3077//3077 2926//2926 2923//2923 -f 3077//3077 2923//2923 3054//3054 -f 3054//3054 2923//2923 2921//2921 -f 3054//3054 2921//2921 3201//3201 -f 3201//3201 2921//2921 2919//2919 -f 3201//3201 2919//2919 3202//3202 -f 3202//3202 2919//2919 2918//2918 -f 3202//3202 2918//2918 3210//3210 -f 2992//2992 2823//2823 2995//2995 -f 2995//2995 2823//2823 3118//3118 -f 2995//2995 3118//3118 3216//3216 -f 3216//3216 3118//3118 3108//3108 -f 3216//3216 3108//3108 3104//3104 -f 3104//3104 3108//3108 3107//3107 -f 3104//3104 3107//3107 3102//3102 -f 2662//2662 2660//2660 2891//2891 -f 2891//2891 2660//2660 3164//3164 -f 2891//2891 3164//3164 2884//2884 -f 2884//2884 3164//3164 3210//3210 -f 2884//2884 3210//3210 2883//2883 -f 2883//2883 3210//3210 2918//2918 -f 2883//2883 2918//2918 3217//3217 -f 2910//2910 2911//2911 2900//2900 -f 2900//2900 2911//2911 2913//2913 -f 2900//2900 2913//2913 2784//2784 -f 2784//2784 2913//2913 3137//3137 -f 2784//2784 3137//3137 2785//2785 -f 2785//2785 3137//3137 3136//3136 -f 2785//2785 3136//3136 3138//3138 -f 3135//3135 3137//3137 2963//2963 -f 2963//2963 3137//3137 2913//2913 -f 2963//2963 2913//2913 2934//2934 -f 2934//2934 2913//2913 2903//2903 -f 2934//2934 2903//2903 2935//2935 -f 2935//2935 2903//2903 2932//2932 -f 2935//2935 2932//2932 2937//2937 -f 2937//2937 2932//2932 2931//2931 -f 2937//2937 2931//2931 2940//2940 -f 2940//2940 2931//2931 2930//2930 -f 2940//2940 2930//2930 3004//3004 -f 3004//3004 2930//2930 3044//3044 -f 3004//3004 3044//3044 3005//3005 -f 3005//3005 3044//3044 2794//2794 -f 3005//3005 2794//2794 3014//3014 -f 3014//3014 2794//2794 2793//2793 -f 3014//3014 2793//2793 3019//3019 -f 3019//3019 2793//2793 2842//2842 -f 3019//3019 2842//2842 2805//2805 -f 2805//2805 2842//2842 3218//3218 -f 2805//2805 3218//3218 3157//3157 -f 2820//2820 2819//2819 3069//3069 -f 3069//3069 2819//2819 3063//3063 -f 3069//3069 3063//3063 3104//3104 -f 3104//3104 3063//3063 2802//2802 -f 3104//3104 2802//2802 3216//3216 -f 3216//3216 2802//2802 2801//2801 -f 3216//3216 2801//2801 2995//2995 -f 2995//2995 2801//2801 3163//3163 -f 2995//2995 3163//3163 2996//2996 -f 3217//3217 3219//3219 2883//2883 -f 2883//2883 3219//3219 2887//2887 -f 2883//2883 2887//2887 2881//2881 -f 2881//2881 2887//2887 2888//2888 -f 2920//2920 2917//2917 2918//2918 -f 2918//2918 2917//2917 2783//2783 -f 2918//2918 2783//2783 3217//3217 -f 3217//3217 2783//2783 2785//2785 -f 3217//3217 2785//2785 3220//3220 -f 3220//3220 3221//3221 3217//3217 -f 3217//3217 3221//3221 3222//3222 -f 3217//3217 3222//3222 3219//3219 -f 3219//3219 3222//3222 3223//3223 -f 3219//3219 3223//3223 3143//3143 -f 3143//3143 3223//3223 3224//3224 -f 3143//3143 3224//3224 2785//2785 -f 2785//2785 3224//3224 3225//3225 -f 2785//2785 3225//3225 3220//3220 -f 3098//3098 3226//3226 3100//3100 -f 3100//3100 3226//3226 3227//3227 -f 3100//3100 3227//3227 3101//3101 -f 3101//3101 3227//3227 3228//3228 -f 3101//3101 3228//3228 3196//3196 -f 3196//3196 3228//3228 3229//3229 -f 3196//3196 3229//3229 3090//3090 -f 3090//3090 3229//3229 3230//3230 -f 3090//3090 3230//3230 3091//3091 -f 3091//3091 3230//3230 3231//3231 -f 3091//3091 3231//3231 3093//3093 -f 3093//3093 3231//3231 3232//3232 -f 3093//3093 3232//3232 3094//3094 -f 3094//3094 3232//3232 3233//3233 -f 3094//3094 3233//3233 2812//2812 -f 2812//2812 3233//3233 3234//3234 -f 2812//2812 3234//3234 2813//2813 -f 2813//2813 3234//3234 3235//3235 -f 2813//2813 3235//3235 3096//3096 -f 3096//3096 3235//3235 3236//3236 -f 3096//3096 3236//3236 3097//3097 -f 3097//3097 3236//3236 3237//3237 -f 3097//3097 3237//3237 3098//3098 -f 3098//3098 3237//3237 3226//3226 -f 3188//3188 3238//3238 3189//3189 -f 3189//3189 3238//3238 3239//3239 -f 3189//3189 3239//3239 3190//3190 -f 3190//3190 3239//3239 3240//3240 -f 3190//3190 3240//3240 3191//3191 -f 3191//3191 3240//3240 3241//3241 -f 3191//3191 3241//3241 3192//3192 -f 3192//3192 3241//3241 3242//3242 -f 3192//3192 3242//3242 2786//2786 -f 2786//2786 3242//3242 3243//3243 -f 2786//2786 3243//3243 2787//2787 -f 2787//2787 3243//3243 3244//3244 -f 2787//2787 3244//3244 3183//3183 -f 3183//3183 3244//3244 3245//3245 -f 3183//3183 3245//3245 3184//3184 -f 3184//3184 3245//3245 3246//3246 -f 3184//3184 3246//3246 3185//3185 -f 3185//3185 3246//3246 3247//3247 -f 3185//3185 3247//3247 3186//3186 -f 3186//3186 3247//3247 3248//3248 -f 3186//3186 3248//3248 3187//3187 -f 3187//3187 3248//3248 3249//3249 -f 3187//3187 3249//3249 3188//3188 -f 3188//3188 3249//3249 3238//3238 -f 3047//3047 3250//3250 3048//3048 -f 3048//3048 3250//3250 3251//3251 -f 3048//3048 3251//3251 3049//3049 -f 3049//3049 3251//3251 3252//3252 -f 3049//3049 3252//3252 3045//3045 -f 3045//3045 3252//3252 3253//3253 -f 3045//3045 3253//3253 3046//3046 -f 3046//3046 3253//3253 3254//3254 -f 3046//3046 3254//3254 3050//3050 -f 3050//3050 3254//3254 3255//3255 -f 3050//3050 3255//3255 3051//3051 -f 3051//3051 3255//3255 3256//3256 -f 3051//3051 3256//3256 3052//3052 -f 3052//3052 3256//3256 3257//3257 -f 3052//3052 3257//3257 3038//3038 -f 3038//3038 3257//3257 3258//3258 -f 3038//3038 3258//3258 3039//3039 -f 3039//3039 3258//3258 3259//3259 -f 3039//3039 3259//3259 3040//3040 -f 3040//3040 3259//3259 3260//3260 -f 3040//3040 3260//3260 3041//3041 -f 3041//3041 3260//3260 3261//3261 -f 3041//3041 3261//3261 3047//3047 -f 3047//3047 3261//3261 3250//3250 -f 3115//3115 3262//3262 3111//3111 -f 3111//3111 3262//3262 3263//3263 -f 3111//3111 3263//3263 3109//3109 -f 3109//3109 3263//3263 3264//3264 -f 3109//3109 3264//3264 3107//3107 -f 3107//3107 3264//3264 3265//3265 -f 3107//3107 3265//3265 3102//3102 -f 3102//3102 3265//3265 3266//3266 -f 3102//3102 3266//3266 3103//3103 -f 3103//3103 3266//3266 3267//3267 -f 3103//3103 3267//3267 3105//3105 -f 3105//3105 3267//3267 3268//3268 -f 3105//3105 3268//3268 3106//3106 -f 3106//3106 3268//3268 3269//3269 -f 3106//3106 3269//3269 2809//2809 -f 2809//2809 3269//3269 3270//3270 -f 2809//2809 3270//3270 2810//2810 -f 2810//2810 3270//3270 3271//3271 -f 2810//2810 3271//3271 3112//3112 -f 3112//3112 3271//3271 3272//3272 -f 3112//3112 3272//3272 3114//3114 -f 3114//3114 3272//3272 3273//3273 -f 3114//3114 3273//3273 3115//3115 -f 3115//3115 3273//3273 3262//3262 -f 2908//2908 3274//3274 2909//2909 -f 2909//2909 3274//3274 3275//3275 -f 2909//2909 3275//3275 2910//2910 -f 2910//2910 3275//3275 3276//3276 -f 2910//2910 3276//3276 2911//2911 -f 2911//2911 3276//3276 3277//3277 -f 2911//2911 3277//3277 2912//2912 -f 2912//2912 3277//3277 3278//3278 -f 2912//2912 3278//3278 2914//2914 -f 2914//2914 3278//3278 3279//3279 -f 2914//2914 3279//3279 2915//2915 -f 2915//2915 3279//3279 3280//3280 -f 2915//2915 3280//3280 2901//2901 -f 2901//2901 3280//3280 3281//3281 -f 2901//2901 3281//3281 2902//2902 -f 2902//2902 3281//3281 3282//3282 -f 2902//2902 3282//3282 2904//2904 -f 2904//2904 3282//3282 3283//3283 -f 2904//2904 3283//3283 2905//2905 -f 2905//2905 3283//3283 3284//3284 -f 2905//2905 3284//3284 2906//2906 -f 2906//2906 3284//3284 3285//3285 -f 2906//2906 3285//3285 2908//2908 -f 2908//2908 3285//3285 3274//3274 -f 3206//3206 3286//3286 3213//3213 -f 3213//3213 3286//3286 3287//3287 -f 3213//3213 3287//3287 3214//3214 -f 3214//3214 3287//3287 3288//3288 -f 3214//3214 3288//3288 3215//3215 -f 3215//3215 3288//3288 3289//3289 -f 3215//3215 3289//3289 3208//3208 -f 3208//3208 3289//3289 3290//3290 -f 3208//3208 3290//3290 3209//3209 -f 3209//3209 3290//3290 3291//3291 -f 3209//3209 3291//3291 3211//3211 -f 3211//3211 3291//3291 3292//3292 -f 3211//3211 3292//3292 3212//3212 -f 3212//3212 3292//3292 3293//3293 -f 3212//3212 3293//3293 3203//3203 -f 3203//3203 3293//3293 3294//3294 -f 3203//3203 3294//3294 3204//3204 -f 3204//3204 3294//3294 3295//3295 -f 3204//3204 3295//3295 3207//3207 -f 3207//3207 3295//3295 3296//3296 -f 3207//3207 3296//3296 3205//3205 -f 3205//3205 3296//3296 3297//3297 -f 3205//3205 3297//3297 3206//3206 -f 3206//3206 3297//3297 3286//3286 -f 2988//2988 2987//2987 3298//3298 -f 3298//3298 2987//2987 3081//3081 -f 3081//3081 3079//3079 3298//3298 -f 3298//3298 3079//3079 3099//3099 -f 3298//3298 3099//3099 3299//3299 -f 3099//3099 3193//3193 3299//3299 -f 3299//3299 3193//3193 3113//3113 -f 3299//3299 3113//3113 3110//3110 -f 3110//3110 3116//3116 3299//3299 -f 3299//3299 3116//3116 2822//2822 -f 3299//3299 2822//2822 2821//2821 -f 3300//3300 2992//2992 2996//2996 -f 2996//2996 3163//3163 3300//3300 -f 3300//3300 3163//3163 2893//2893 -f 3300//3300 2893//2893 2885//2885 -f 2885//2885 2887//2887 3300//3300 -f 3300//3300 2887//2887 3219//3219 -f 3300//3300 3219//3219 3301//3301 -f 3301//3301 3219//3219 3143//3143 -f 3301//3301 3143//3143 3142//3142 -f 3142//3142 2968//2968 3301//3301 -f 3301//3301 2968//2968 2960//2960 -f 3301//3301 2960//2960 2959//2959 -f 3302//3302 2998//2998 2997//2997 -f 2997//2997 3149//3149 3302//3302 -f 3302//3302 3149//3149 3151//3151 -f 3302//3302 3151//3151 3153//3153 -f 3153//3153 3200//3200 3302//3302 -f 3302//3302 3200//3200 2862//2862 -f 3302//3302 2862//2862 3303//3303 -f 3303//3303 2862//2862 2864//2864 -f 2864//2864 2860//2860 3303//3303 -f 3303//3303 2860//2860 2859//2859 -f 3303//3303 2859//2859 2857//2857 -f 3161//3161 3160//3160 3304//3304 -f 3304//3304 3160//3160 3159//3159 -f 3159//3159 3158//3158 3304//3304 -f 3304//3304 3158//3158 3156//3156 -f 3304//3304 3156//3156 3305//3305 -f 3305//3305 3156//3156 3166//3166 -f 3166//3166 3167//3167 3305//3305 -f 3305//3305 3167//3167 3168//3168 -f 3305//3305 3168//3168 3169//3169 -f 3169//3169 3170//3170 3305//3305 -f 3305//3305 3170//3170 3171//3171 -f 3305//3305 3171//3171 3172//3172 -f 3306//3306 3307//3307 3308//3308 -f 3309//3309 3300//3300 3310//3310 -f 3310//3310 3300//3300 3301//3301 -f 3301//3301 3311//3311 3310//3310 -f 3310//3310 3311//3311 3312//3312 -f 3310//3310 3312//3312 3313//3313 -f 3305//3305 3314//3314 3304//3304 -f 3304//3304 3314//3314 3306//3306 -f 3304//3304 3306//3306 3315//3315 -f 3316//3316 3317//3317 3318//3318 -f 3319//3319 3320//3320 3299//3299 -f 3299//3299 3320//3320 3321//3321 -f 3299//3299 3321//3321 3298//3298 -f 3322//3322 3316//3316 3308//3308 -f 3308//3308 3316//3316 3318//3318 -f 3308//3308 3318//3318 3306//3306 -f 3306//3306 3318//3318 3323//3323 -f 3306//3306 3323//3323 3315//3315 -f 3316//3316 3324//3324 3317//3317 -f 3317//3317 3324//3324 3325//3325 -f 3317//3317 3325//3325 3326//3326 -f 3299//3299 3327//3327 3319//3319 -f 3319//3319 3327//3327 3328//3328 -f 3319//3319 3328//3328 3329//3329 -f 3329//3329 3328//3328 3330//3330 -f 3329//3329 3330//3330 3331//3331 -f 3321//3321 3332//3332 3298//3298 -f 3298//3298 3332//3332 3333//3333 -f 3298//3298 3333//3333 3334//3334 -f 3334//3334 3333//3333 3335//3335 -f 3334//3334 3335//3335 3336//3336 -f 3336//3336 3335//3335 3337//3337 -f 3336//3336 3337//3337 3338//3338 -f 3309//3309 3339//3339 3300//3300 -f 3300//3300 3339//3339 3340//3340 -f 3300//3300 3340//3340 3341//3341 -f 3338//3338 3337//3337 3342//3342 -f 3342//3342 3337//3337 3343//3343 -f 3342//3342 3343//3343 3344//3344 -f 3344//3344 3343//3343 3345//3345 -f 3344//3344 3345//3345 3305//3305 -f 3305//3305 3345//3345 3346//3346 -f 3305//3305 3346//3346 3347//3347 -f 3348//3348 3349//3349 3350//3350 -f 3350//3350 3349//3349 3351//3351 -f 3330//3330 3352//3352 3331//3331 -f 3331//3331 3352//3352 3353//3353 -f 3331//3331 3353//3353 3354//3354 -f 3354//3354 3353//3353 3300//3300 -f 3354//3354 3300//3300 3355//3355 -f 3355//3355 3300//3300 3341//3341 -f 3355//3355 3341//3341 3356//3356 -f 3357//3357 3314//3314 3358//3358 -f 3358//3358 3314//3314 3305//3305 -f 3358//3358 3305//3305 3359//3359 -f 3359//3359 3305//3305 3347//3347 -f 3360//3360 3361//3361 3362//3362 -f 3326//3326 3325//3325 3303//3303 -f 3303//3303 3325//3325 3350//3350 -f 3303//3303 3350//3350 3302//3302 -f 3302//3302 3350//3350 3351//3351 -f 3302//3302 3351//3351 3363//3363 -f 3363//3363 3351//3351 3364//3364 -f 3363//3363 3364//3364 3365//3365 -f 3366//3366 3310//3310 3362//3362 -f 3362//3362 3310//3310 3313//3313 -f 3362//3362 3313//3313 3360//3360 -f 3360//3360 3313//3313 3365//3365 -f 3360//3360 3365//3365 3367//3367 -f 3367//3367 3365//3365 3364//3364 -f 2948//2948 3368//3368 2942//2942 -f 2942//2942 3368//3368 3369//3369 -f 2942//2942 3369//3369 2943//2943 -f 2943//2943 3369//3369 3370//3370 -f 2943//2943 3370//3370 2941//2941 -f 2941//2941 3370//3370 3371//3371 -f 2938//2938 3372//3372 2939//2939 -f 2939//2939 3372//3372 3373//3373 -f 2939//2939 3373//3373 2945//2945 -f 2945//2945 3373//3373 3374//3374 -f 2945//2945 3374//3374 2946//2946 -f 2946//2946 3374//3374 3375//3375 -f 2941//2941 3371//3371 2938//2938 -f 2938//2938 3371//3371 3372//3372 -f 2973//2973 3376//3376 2974//2974 -f 2974//2974 3376//3376 3377//3377 -f 2974//2974 3377//3377 2975//2975 -f 2975//2975 3377//3377 3378//3378 -f 2975//2975 3378//3378 2824//2824 -f 2824//2824 3378//3378 3379//3379 -f 3376//3376 2973//2973 3380//3380 -f 3380//3380 2973//2973 2936//2936 -f 3380//3380 2936//2936 3381//3381 -f 3381//3381 2936//2936 2947//2947 -f 3381//3381 2947//2947 3375//3375 -f 3375//3375 2947//2947 2946//2946 -f 2824//2824 3379//3379 2825//2825 -f 2825//2825 3379//3379 3382//3382 -f 2831//2831 3383//3383 3384//3384 -f 2831//2831 3384//3384 2832//2832 -f 2832//2832 3384//3384 3385//3385 -f 2832//2832 3385//3385 2950//2950 -f 2950//2950 3385//3385 3368//3368 -f 2950//2950 3368//3368 2948//2948 -f 3065//3065 3386//3386 3067//3067 -f 3067//3067 3386//3386 3387//3387 -f 3067//3067 3387//3387 2820//2820 -f 2820//2820 3387//3387 3388//3388 -f 2820//2820 3388//3388 2818//2818 -f 2818//2818 3388//3388 3389//3389 -f 2818//2818 3389//3389 3057//3057 -f 3057//3057 3389//3389 3390//3390 -f 3057//3057 3390//3390 3058//3058 -f 3058//3058 3390//3390 3391//3391 -f 3058//3058 3391//3391 3060//3060 -f 3060//3060 3391//3391 3392//3392 -f 3060//3060 3392//3392 3062//3062 -f 3062//3062 3392//3392 3393//3393 -f 3062//3062 3393//3393 3055//3055 -f 3055//3055 3393//3393 3394//3394 -f 3055//3055 3394//3394 3056//3056 -f 3056//3056 3394//3394 3395//3395 -f 3056//3056 3395//3395 3076//3076 -f 3076//3076 3395//3395 3396//3396 -f 3076//3076 3396//3396 3070//3070 -f 3070//3070 3396//3396 3397//3397 -f 3070//3070 3397//3397 3071//3071 -f 3071//3071 3397//3397 3398//3398 -f 3071//3071 3398//3398 3075//3075 -f 3075//3075 3398//3398 3399//3399 -f 3075//3075 3399//3399 3072//3072 -f 3072//3072 3399//3399 3400//3400 -f 3072//3072 3400//3400 3073//3073 -f 3073//3073 3400//3400 3401//3401 -f 3073//3073 3401//3401 3095//3095 -f 3095//3095 3401//3401 3402//3402 -f 3095//3095 3402//3402 3064//3064 -f 3064//3064 3402//3402 3403//3403 -f 3064//3064 3403//3403 3065//3065 -f 3065//3065 3403//3403 3386//3386 -f 3404//3404 3405//3405 3406//3406 -f 3407//3407 3408//3408 3409//3409 -f 2746//2746 2744//2744 3410//3410 -f 3411//3411 3412//3412 3413//3413 -f 3414//3414 3415//3415 3416//3416 -f 3417//3417 3418//3418 3419//3419 -f 3420//3420 3421//3421 3422//3422 -f 3422//3422 3423//3423 3420//3420 -f 3420//3420 3423//3423 3424//3424 -f 3420//3420 3424//3424 3425//3425 -f 3426//3426 3427//3427 3428//3428 -f 3427//3427 3429//3429 3428//3428 -f 3428//3428 3429//3429 3430//3430 -f 3428//3428 3430//3430 3431//3431 -f 3431//3431 3430//3430 3432//3432 -f 3431//3431 3432//3432 3417//3417 -f 3433//3433 3434//3434 3435//3435 -f 3435//3435 3434//3434 3436//3436 -f 3435//3435 3436//3436 3437//3437 -f 3437//3437 3436//3436 3438//3438 -f 3437//3437 3438//3438 3439//3439 -f 3439//3439 3438//3438 3440//3440 -f 3439//3439 3440//3440 3441//3441 -f 3441//3441 3440//3440 3442//3442 -f 3441//3441 3442//3442 3443//3443 -f 3443//3443 3442//3442 3444//3444 -f 3445//3445 3446//3446 3447//3447 -f 3446//3446 3448//3448 3447//3447 -f 3447//3447 3448//3448 3449//3449 -f 3447//3447 3449//3449 3450//3450 -f 3451//3451 3452//3452 3453//3453 -f 3453//3453 3452//3452 3454//3454 -f 3453//3453 3455//3455 3456//3456 -f 3457//3457 3458//3458 3454//3454 -f 3454//3454 3458//3458 3459//3459 -f 3454//3454 3459//3459 3453//3453 -f 3453//3453 3459//3459 3460//3460 -f 3453//3453 3460//3460 3455//3455 -f 3461//3461 3453//3453 3462//3462 -f 3462//3462 3453//3453 3456//3456 -f 3462//3462 3456//3456 3463//3463 -f 3463//3463 3456//3456 3464//3464 -f 3463//3463 3464//3464 3465//3465 -f 3466//3466 3467//3467 3468//3468 -f 3468//3468 3467//3467 3469//3469 -f 3468//3468 3469//3469 3470//3470 -f 3469//3469 3471//3471 3470//3470 -f 3470//3470 3471//3471 3472//3472 -f 3470//3470 3472//3472 3473//3473 -f 3473//3473 3474//3474 3470//3470 -f 3470//3470 3474//3474 3475//3475 -f 3470//3470 3475//3475 3413//3413 -f 3413//3413 3475//3475 3476//3476 -f 3413//3413 3476//3476 3411//3411 -f 3473//3473 3477//3477 3474//3474 -f 3474//3474 3477//3477 3478//3478 -f 3474//3474 3478//3478 3479//3479 -f 3479//3479 3478//3478 3480//3480 -f 3479//3479 3480//3480 3481//3481 -f 3481//3481 3480//3480 3482//3482 -f 3481//3481 3482//3482 3483//3483 -f 3483//3483 3482//3482 3484//3484 -f 3483//3483 3484//3484 3468//3468 -f 3468//3468 3484//3484 3485//3485 -f 3468//3468 3485//3485 3466//3466 -f 3486//3486 3487//3487 3488//3488 -f 3489//3489 3490//3490 3491//3491 -f 3491//3491 3492//3492 3489//3489 -f 3489//3489 3492//3492 3493//3493 -f 3489//3489 3493//3493 3494//3494 -f 3495//3495 3496//3496 3497//3497 -f 3487//3487 3486//3486 3497//3497 -f 3497//3497 3486//3486 3498//3498 -f 3497//3497 3498//3498 3495//3495 -f 3488//3488 3499//3499 3486//3486 -f 3486//3486 3499//3499 3500//3500 -f 3486//3486 3500//3500 3501//3501 -f 3501//3501 3500//3500 3502//3502 -f 3501//3501 3502//3502 3490//3490 -f 3490//3490 3502//3502 3503//3503 -f 3490//3490 3503//3503 3491//3491 -f 3501//3501 3504//3504 3505//3505 -f 3505//3505 3506//3506 3501//3501 -f 3501//3501 3506//3506 3507//3507 -f 3501//3501 3507//3507 3486//3486 -f 3508//3508 3509//3509 3510//3510 -f 3510//3510 3509//3509 3511//3511 -f 3510//3510 3511//3511 3512//3512 -f 3511//3511 3513//3513 3512//3512 -f 3512//3512 3513//3513 3514//3514 -f 3512//3512 3514//3514 3421//3421 -f 3421//3421 3514//3514 3515//3515 -f 3421//3421 3515//3515 3516//3516 -f 3516//3516 3517//3517 3421//3421 -f 3421//3421 3517//3517 3518//3518 -f 3421//3421 3518//3518 3519//3519 -f 3519//3519 3518//3518 3520//3520 -f 3519//3519 3520//3520 3521//3521 -f 3520//3520 3522//3522 3521//3521 -f 3521//3521 3522//3522 3523//3523 -f 3521//3521 3523//3523 3524//3524 -f 2742//2742 2740//2740 3525//3525 -f 3525//3525 2740//2740 2738//2738 -f 3525//3525 2738//2738 3526//3526 -f 3526//3526 2738//2738 2736//2736 -f 3526//3526 2736//2736 2758//2758 -f 2758//2758 2756//2756 3526//3526 -f 3526//3526 2756//2756 2754//2754 -f 3526//3526 2754//2754 3527//3527 -f 3527//3527 2754//2754 2752//2752 -f 3527//3527 2752//2752 3528//3528 -f 2752//2752 2750//2750 3528//3528 -f 3528//3528 2750//2750 2748//2748 -f 3528//3528 2748//2748 3529//3529 -f 3530//3530 2710//2710 2708//2708 -f 2700//2700 3531//3531 2702//2702 -f 2702//2702 3531//3531 3532//3532 -f 2702//2702 3532//3532 2704//2704 -f 2704//2704 3532//3532 2706//2706 -f 2700//2700 2698//2698 3531//3531 -f 3531//3531 2698//2698 2696//2696 -f 3531//3531 2696//2696 3434//3434 -f 3434//3434 2696//2696 2694//2694 -f 3434//3434 2694//2694 3436//3436 -f 3436//3436 2694//2694 2692//2692 -f 3436//3436 2692//2692 3533//3533 -f 3533//3533 2692//2692 2690//2690 -f 3533//3533 2690//2690 2688//2688 -f 3534//3534 3535//3535 3536//3536 -f 3537//3537 3538//3538 3536//3536 -f 3538//3538 3539//3539 3536//3536 -f 3536//3536 3539//3539 3540//3540 -f 3536//3536 3540//3540 3534//3534 -f 3541//3541 3542//3542 3543//3543 -f 3543//3543 3542//3542 3544//3544 -f 3534//3534 3545//3545 3535//3535 -f 3535//3535 3545//3545 3546//3546 -f 3535//3535 3546//3546 3442//3442 -f 3442//3442 3546//3546 3547//3547 -f 3442//3442 3547//3547 3444//3444 -f 3444//3444 3547//3547 3548//3548 -f 3444//3444 3548//3548 3541//3541 -f 3541//3541 3548//3548 3549//3549 -f 3541//3541 3549//3549 3542//3542 -f 3550//3550 3551//3551 3409//3409 -f 3409//3409 3551//3551 3552//3552 -f 3553//3553 3554//3554 3555//3555 -f 3555//3555 3554//3554 3556//3556 -f 3555//3555 3556//3556 3557//3557 -f 3558//3558 3559//3559 3560//3560 -f 3561//3561 3562//3562 3563//3563 -f 3561//3561 3563//3563 3564//3564 -f 3557//3557 3556//3556 3565//3565 -f 3565//3565 3556//3556 3566//3566 -f 3565//3565 3566//3566 3562//3562 -f 3567//3567 3568//3568 3569//3569 -f 3452//3452 3570//3570 3571//3571 -f 3571//3571 3572//3572 3452//3452 -f 3452//3452 3572//3572 3573//3573 -f 3452//3452 3573//3573 3454//3454 -f 3454//3454 3573//3573 3574//3574 -f 3454//3454 3574//3574 3575//3575 -f 3576//3576 3577//3577 3578//3578 -f 3578//3578 3577//3577 3579//3579 -f 3578//3578 3579//3579 3580//3580 -f 3580//3580 3579//3579 3581//3581 -f 3580//3580 3581//3581 3570//3570 -f 3570//3570 3581//3581 3582//3582 -f 3570//3570 3582//3582 3571//3571 -f 3266//3266 3265//3265 3468//3468 -f 3468//3468 3265//3265 3264//3264 -f 3468//3468 3264//3264 3483//3483 -f 3483//3483 3264//3264 3263//3263 -f 3483//3483 3263//3263 3583//3583 -f 3583//3583 3263//3263 3262//3262 -f 3583//3583 3262//3262 3584//3584 -f 3584//3584 3262//3262 3273//3273 -f 3585//3585 3268//3268 3586//3586 -f 3586//3586 3268//3268 3267//3267 -f 3270//3270 3269//3269 3587//3587 -f 3270//3270 3587//3587 3271//3271 -f 3232//3232 3231//3231 3588//3588 -f 3235//3235 3234//3234 3589//3589 -f 3589//3589 3234//3234 3233//3233 -f 3589//3589 3233//3233 3590//3590 -f 3236//3236 3489//3489 3495//3495 -f 3495//3495 3489//3489 3494//3494 -f 3495//3495 3494//3494 3496//3496 -f 3229//3229 3228//3228 3591//3591 -f 3591//3591 3228//3228 3227//3227 -f 3591//3591 3227//3227 3592//3592 -f 3592//3592 3227//3227 3226//3226 -f 3592//3592 3226//3226 3495//3495 -f 3495//3495 3226//3226 3237//3237 -f 3495//3495 3237//3237 3236//3236 -f 3593//3593 3594//3594 3595//3595 -f 3595//3595 3594//3594 3596//3596 -f 3283//3283 3282//3282 3597//3597 -f 3274//3274 3285//3285 3598//3598 -f 3598//3598 3285//3285 3284//3284 -f 3599//3599 3278//3278 3277//3277 -f 3282//3282 3281//3281 3597//3597 -f 3597//3597 3281//3281 3280//3280 -f 3597//3597 3280//3280 3599//3599 -f 3599//3599 3280//3280 3279//3279 -f 3599//3599 3279//3279 3278//3278 -f 3274//3274 3598//3598 3275//3275 -f 3275//3275 3598//3598 3593//3593 -f 3275//3275 3593//3593 3276//3276 -f 3600//3600 3601//3601 3602//3602 -f 3284//3284 3283//3283 3598//3598 -f 3598//3598 3283//3283 3597//3597 -f 3598//3598 3597//3597 3603//3603 -f 3603//3603 3597//3597 3604//3604 -f 3603//3603 3604//3604 3605//3605 -f 3605//3605 3604//3604 3606//3606 -f 3605//3605 3606//3606 3602//3602 -f 3602//3602 3606//3606 3607//3607 -f 3602//3602 3607//3607 3600//3600 -f 3255//3255 3254//3254 3608//3608 -f 3609//3609 3250//3250 3610//3610 -f 3610//3610 3250//3250 3261//3261 -f 3610//3610 3261//3261 3260//3260 -f 3253//3253 3252//3252 3609//3609 -f 3609//3609 3252//3252 3251//3251 -f 3609//3609 3251//3251 3250//3250 -f 3259//3259 3258//3258 3611//3611 -f 3611//3611 3258//3258 3257//3257 -f 3611//3611 3257//3257 3608//3608 -f 3608//3608 3257//3257 3256//3256 -f 3608//3608 3256//3256 3255//3255 -f 3610//3610 3406//3406 3612//3612 -f 3612//3612 3406//3406 3405//3405 -f 3612//3612 3405//3405 3613//3613 -f 3613//3613 3405//3405 3614//3614 -f 3615//3615 3616//3616 3617//3617 -f 3601//3601 3600//3600 3618//3618 -f 3618//3618 3600//3600 3619//3619 -f 3618//3618 3619//3619 3620//3620 -f 3617//3617 3616//3616 3621//3621 -f 3621//3621 3616//3616 3622//3622 -f 3621//3621 3622//3622 3620//3620 -f 3620//3620 3622//3622 3623//3623 -f 3620//3620 3623//3623 3618//3618 -f 3254//3254 3253//3253 3608//3608 -f 3608//3608 3253//3253 3609//3609 -f 3608//3608 3609//3609 3624//3624 -f 3624//3624 3609//3609 3625//3625 -f 3624//3624 3625//3625 3607//3607 -f 3607//3607 3625//3625 3626//3626 -f 3607//3607 3626//3626 3600//3600 -f 3600//3600 3626//3626 3627//3627 -f 3600//3600 3627//3627 3619//3619 -f 3388//3388 3587//3587 3585//3585 -f 3585//3585 3587//3587 3269//3269 -f 3585//3585 3269//3269 3268//3268 -f 3391//3391 3628//3628 3392//3392 -f 3392//3392 3628//3628 3393//3393 -f 3390//3390 3389//3389 3629//3629 -f 3397//3397 3396//3396 3630//3630 -f 3630//3630 3396//3396 3631//3631 -f 3403//3403 3402//3402 3632//3632 -f 3632//3632 3402//3402 3401//3401 -f 3400//3400 3399//3399 3633//3633 -f 3633//3633 3399//3399 3398//3398 -f 3388//3388 3387//3387 3587//3587 -f 3587//3587 3387//3387 3386//3386 -f 3587//3587 3386//3386 3588//3588 -f 3588//3588 3386//3386 3590//3590 -f 3588//3588 3590//3590 3232//3232 -f 3232//3232 3590//3590 3233//3233 -f 3634//3634 3384//3384 3383//3383 -f 3635//3635 3374//3374 3373//3373 -f 3384//3384 3634//3634 3385//3385 -f 3385//3385 3634//3634 3636//3636 -f 3385//3385 3636//3636 3368//3368 -f 3368//3368 3636//3636 3637//3637 -f 3368//3368 3637//3637 3369//3369 -f 3372//3372 3371//3371 3637//3637 -f 3637//3637 3371//3371 3370//3370 -f 3637//3637 3370//3370 3369//3369 -f 3638//3638 3382//3382 3639//3639 -f 3639//3639 3382//3382 3379//3379 -f 3639//3639 3379//3379 3378//3378 -f 3378//3378 3377//3377 3639//3639 -f 3639//3639 3377//3377 3376//3376 -f 3639//3639 3376//3376 3640//3640 -f 3640//3640 3376//3376 3380//3380 -f 3640//3640 3380//3380 3641//3641 -f 3641//3641 3380//3380 3381//3381 -f 3641//3641 3381//3381 3635//3635 -f 3635//3635 3381//3381 3375//3375 -f 3635//3635 3375//3375 3374//3374 -f 3447//3447 3642//3642 3643//3643 -f 3643//3643 3642//3642 3644//3644 -f 3643//3643 3644//3644 3563//3563 -f 3563//3563 3644//3644 3645//3645 -f 3563//3563 3645//3645 3639//3639 -f 3639//3639 3645//3645 3646//3646 -f 3639//3639 3646//3646 3638//3638 -f 3647//3647 3648//3648 3535//3535 -f 3648//3648 3649//3649 3535//3535 -f 3535//3535 3649//3649 3650//3650 -f 3535//3535 3650//3650 3536//3536 -f 3536//3536 3650//3650 3651//3651 -f 3536//3536 3651//3651 3447//3447 -f 3447//3447 3651//3651 3652//3652 -f 3447//3447 3652//3652 3642//3642 -f 3653//3653 3654//3654 3655//3655 -f 3656//3656 3657//3657 3658//3658 -f 3658//3658 3657//3657 3529//3529 -f 3658//3658 3529//3529 3659//3659 -f 3659//3659 3529//3529 3655//3655 -f 3659//3659 3655//3655 3660//3660 -f 3660//3660 3655//3655 3654//3654 -f 3653//3653 3655//3655 3661//3661 -f 3661//3661 3655//3655 3662//3662 -f 3661//3661 3662//3662 3663//3663 -f 3663//3663 3662//3662 3664//3664 -f 3663//3663 3664//3664 3665//3665 -f 3665//3665 3664//3664 3666//3666 -f 3665//3665 3666//3666 3667//3667 -f 3668//3668 3669//3669 3670//3670 -f 3670//3670 3669//3669 3671//3671 -f 3670//3670 3671//3671 3672//3672 -f 3673//3673 3674//3674 3666//3666 -f 3666//3666 3674//3674 3675//3675 -f 3666//3666 3675//3675 3667//3667 -f 3676//3676 3677//3677 3668//3668 -f 3668//3668 3677//3677 3678//3678 -f 3668//3668 3678//3678 3669//3669 -f 3679//3679 3677//3677 3680//3680 -f 3680//3680 3677//3677 3676//3676 -f 3680//3680 3676//3676 3681//3681 -f 3682//3682 3533//3533 3530//3530 -f 3530//3530 3533//3533 2688//2688 -f 3530//3530 2688//2688 2710//2710 -f 3528//3528 2760//2760 2782//2782 -f 2772//2772 2770//2770 3683//3683 -f 2760//2760 3528//3528 2762//2762 -f 2762//2762 3528//3528 3529//3529 -f 2762//2762 3529//3529 2764//2764 -f 2764//2764 3529//3529 2766//2766 -f 2766//2766 3529//3529 3657//3657 -f 2766//2766 3657//3657 2768//2768 -f 2782//2782 2780//2780 3528//3528 -f 3528//3528 2780//2780 2778//2778 -f 3528//3528 2778//2778 3684//3684 -f 3684//3684 2778//2778 2776//2776 -f 3684//3684 2776//2776 2774//2774 -f 2774//2774 2772//2772 3684//3684 -f 3684//3684 2772//2772 3683//3683 -f 3684//3684 3683//3683 3431//3431 -f 3431//3431 3683//3683 3685//3685 -f 3431//3431 3685//3685 3428//3428 -f 3428//3428 3685//3685 3686//3686 -f 3428//3428 3686//3686 3530//3530 -f 3530//3530 3686//3686 3687//3687 -f 3530//3530 3687//3687 3682//3682 -f 3657//3657 3688//3688 2768//2768 -f 2768//2768 3688//3688 3689//3689 -f 2768//2768 3689//3689 2770//2770 -f 2770//2770 3689//3689 3690//3690 -f 2770//2770 3690//3690 3683//3683 -f 3691//3691 3692//3692 3693//3693 -f 3693//3693 3692//3692 3694//3694 -f 3693//3693 3694//3694 3457//3457 -f 3457//3457 3694//3694 3695//3695 -f 3457//3457 3695//3695 3458//3458 -f 3696//3696 3697//3697 3698//3698 -f 3698//3698 3697//3697 3699//3699 -f 3698//3698 3699//3699 3700//3700 -f 3465//3465 3464//3464 3701//3701 -f 3701//3701 3464//3464 3702//3702 -f 3701//3701 3702//3702 3700//3700 -f 3700//3700 3702//3702 3703//3703 -f 3700//3700 3703//3703 3698//3698 -f 3424//3424 3704//3704 3425//3425 -f 3425//3425 3704//3704 3705//3705 -f 3425//3425 3705//3705 3706//3706 -f 3706//3706 3705//3705 3707//3707 -f 3706//3706 3707//3707 3708//3708 -f 3708//3708 3707//3707 3709//3709 -f 3709//3709 3707//3707 3710//3710 -f 3709//3709 3710//3710 3711//3711 -f 3711//3711 3710//3710 3712//3712 -f 3711//3711 3712//3712 3713//3713 -f 3713//3713 3712//3712 3714//3714 -f 3713//3713 3714//3714 3715//3715 -f 3512//3512 3716//3716 3717//3717 -f 3420//3420 3718//3718 3421//3421 -f 3421//3421 3718//3718 3719//3719 -f 3421//3421 3719//3719 3512//3512 -f 3512//3512 3719//3719 3720//3720 -f 3512//3512 3720//3720 3716//3716 -f 3721//3721 3722//3722 3409//3409 -f 3409//3409 3722//3722 3554//3554 -f 3409//3409 3554//3554 3550//3550 -f 3550//3550 3554//3554 3553//3553 -f 3722//3722 3723//3723 3554//3554 -f 3554//3554 3723//3723 3724//3724 -f 3554//3554 3724//3724 3725//3725 -f 3725//3725 3724//3724 3726//3726 -f 3725//3725 3726//3726 3727//3727 -f 3727//3727 3728//3728 3725//3725 -f 3725//3725 3728//3728 3729//3729 -f 3725//3725 3729//3729 3408//3408 -f 3408//3408 3729//3729 3730//3730 -f 3730//3730 3731//3731 3408//3408 -f 3408//3408 3731//3731 3732//3732 -f 3408//3408 3732//3732 3409//3409 -f 3409//3409 3732//3732 3733//3733 -f 3409//3409 3733//3733 3721//3721 -f 3563//3563 3734//3734 3735//3735 -f 3643//3643 3736//3736 3737//3737 -f 3562//3562 3566//3566 3563//3563 -f 3563//3563 3566//3566 3738//3738 -f 3563//3563 3738//3738 3734//3734 -f 3735//3735 3739//3739 3563//3563 -f 3563//3563 3739//3739 3740//3740 -f 3563//3563 3740//3740 3643//3643 -f 3643//3643 3740//3740 3741//3741 -f 3643//3643 3741//3741 3736//3736 -f 3742//3742 3743//3743 3744//3744 -f 3744//3744 3743//3743 3745//3745 -f 3744//3744 3745//3745 3566//3566 -f 3566//3566 3745//3745 3746//3746 -f 3566//3566 3746//3746 3738//3738 -f 3445//3445 3447//3447 3747//3747 -f 3747//3747 3447//3447 3643//3643 -f 3747//3747 3643//3643 3744//3744 -f 3744//3744 3643//3643 3737//3737 -f 3744//3744 3737//3737 3742//3742 -f 3580//3580 3725//3725 3578//3578 -f 3578//3578 3725//3725 3408//3408 -f 3578//3578 3408//3408 3748//3748 -f 3748//3748 3408//3408 3407//3407 -f 3409//3409 3595//3595 3407//3407 -f 3407//3407 3595//3595 3596//3596 -f 3407//3407 3596//3596 3748//3748 -f 3748//3748 3596//3596 3749//3749 -f 3748//3748 3749//3749 3750//3750 -f 3750//3750 3749//3749 3751//3751 -f 3750//3750 3751//3751 3752//3752 -f 3752//3752 3751//3751 3753//3753 -f 3752//3752 3753//3753 3754//3754 -f 3754//3754 3753//3753 3755//3755 -f 3754//3754 3755//3755 3623//3623 -f 3623//3623 3755//3755 3756//3756 -f 3623//3623 3756//3756 3618//3618 -f 3618//3618 3756//3756 3757//3757 -f 3618//3618 3757//3757 3601//3601 -f 3552//3552 3558//3558 3409//3409 -f 3409//3409 3558//3558 3560//3560 -f 3409//3409 3560//3560 3595//3595 -f 3595//3595 3560//3560 3599//3599 -f 3595//3595 3599//3599 3593//3593 -f 3593//3593 3599//3599 3277//3277 -f 3593//3593 3277//3277 3276//3276 -f 3450//3450 3414//3414 3447//3447 -f 3447//3447 3414//3414 3416//3416 -f 3447//3447 3416//3416 3536//3536 -f 3536//3536 3416//3416 3543//3543 -f 3536//3536 3543//3543 3537//3537 -f 3537//3537 3543//3543 3544//3544 -f 3412//3412 3758//3758 3413//3413 -f 3413//3413 3758//3758 3759//3759 -f 3413//3413 3759//3759 3470//3470 -f 3470//3470 3759//3759 3760//3760 -f 3470//3470 3760//3760 3468//3468 -f 3468//3468 3760//3760 3586//3586 -f 3468//3468 3586//3586 3266//3266 -f 3266//3266 3586//3586 3267//3267 -f 3297//3297 3296//3296 3693//3693 -f 3290//3290 3289//3289 3761//3761 -f 3761//3761 3289//3289 3457//3457 -f 3761//3761 3457//3457 3569//3569 -f 3569//3569 3457//3457 3454//3454 -f 3569//3569 3454//3454 3567//3567 -f 3567//3567 3454//3454 3575//3575 -f 3289//3289 3288//3288 3457//3457 -f 3457//3457 3288//3288 3287//3287 -f 3457//3457 3287//3287 3693//3693 -f 3693//3693 3287//3287 3286//3286 -f 3693//3693 3286//3286 3297//3297 -f 3762//3762 3295//3295 3294//3294 -f 3294//3294 3293//3293 3762//3762 -f 3762//3762 3293//3293 3292//3292 -f 3762//3762 3292//3292 3761//3761 -f 3761//3761 3292//3292 3291//3291 -f 3761//3761 3291//3291 3290//3290 -f 3758//3758 3701//3701 3759//3759 -f 3759//3759 3701//3701 3700//3700 -f 3759//3759 3700//3700 3760//3760 -f 3760//3760 3700//3700 3699//3699 -f 3760//3760 3699//3699 3586//3586 -f 3586//3586 3699//3699 3697//3697 -f 3586//3586 3697//3697 3585//3585 -f 3585//3585 3697//3697 3629//3629 -f 3585//3585 3629//3629 3388//3388 -f 3388//3388 3629//3629 3389//3389 -f 3696//3696 3691//3691 3697//3697 -f 3697//3697 3691//3691 3693//3693 -f 3697//3697 3693//3693 3629//3629 -f 3629//3629 3693//3693 3628//3628 -f 3629//3629 3628//3628 3390//3390 -f 3390//3390 3628//3628 3391//3391 -f 3296//3296 3295//3295 3693//3693 -f 3693//3693 3295//3295 3762//3762 -f 3693//3693 3762//3762 3628//3628 -f 3628//3628 3762//3762 3763//3763 -f 3628//3628 3763//3763 3393//3393 -f 3393//3393 3763//3763 3764//3764 -f 3393//3393 3764//3764 3394//3394 -f 3394//3394 3764//3764 3631//3631 -f 3394//3394 3631//3631 3395//3395 -f 3395//3395 3631//3631 3396//3396 -f 3273//3273 3272//3272 3584//3584 -f 3584//3584 3272//3272 3765//3765 -f 3584//3584 3765//3765 3591//3591 -f 3591//3591 3765//3765 3766//3766 -f 3591//3591 3766//3766 3229//3229 -f 3229//3229 3766//3766 3230//3230 -f 3272//3272 3271//3271 3765//3765 -f 3765//3765 3271//3271 3587//3587 -f 3765//3765 3587//3587 3766//3766 -f 3766//3766 3587//3587 3588//3588 -f 3766//3766 3588//3588 3230//3230 -f 3230//3230 3588//3588 3231//3231 -f 3373//3373 3372//3372 3635//3635 -f 3635//3635 3372//3372 3637//3637 -f 3635//3635 3637//3637 3666//3666 -f 3666//3666 3637//3637 3670//3670 -f 3666//3666 3670//3670 3673//3673 -f 3673//3673 3670//3670 3672//3672 -f 3401//3401 3400//3400 3632//3632 -f 3632//3632 3400//3400 3633//3633 -f 3632//3632 3633//3633 3714//3714 -f 3714//3714 3633//3633 3767//3767 -f 3383//3383 3647//3647 3634//3634 -f 3634//3634 3647//3647 3535//3535 -f 3634//3634 3535//3535 3636//3636 -f 3636//3636 3535//3535 3442//3442 -f 3636//3636 3442//3442 3637//3637 -f 3637//3637 3442//3442 3440//3440 -f 3637//3637 3440//3440 3670//3670 -f 3670//3670 3440//3440 3438//3438 -f 3670//3670 3438//3438 3668//3668 -f 3668//3668 3438//3438 3436//3436 -f 3668//3668 3436//3436 3676//3676 -f 3676//3676 3436//3436 3533//3533 -f 3676//3676 3533//3533 3681//3681 -f 3681//3681 3533//3533 3682//3682 -f 3768//3768 3248//3248 3769//3769 -f 3769//3769 3248//3248 3247//3247 -f 3769//3769 3247//3247 3246//3246 -f 3241//3241 3240//3240 3767//3767 -f 3246//3246 3245//3245 3769//3769 -f 3769//3769 3245//3245 3244//3244 -f 3769//3769 3244//3244 3770//3770 -f 3770//3770 3244//3244 3243//3243 -f 3770//3770 3243//3243 3242//3242 -f 3242//3242 3241//3241 3770//3770 -f 3770//3770 3241//3241 3767//3767 -f 3770//3770 3767//3767 3630//3630 -f 3630//3630 3767//3767 3633//3633 -f 3630//3630 3633//3633 3397//3397 -f 3397//3397 3633//3633 3398//3398 -f 3240//3240 3239//3239 3767//3767 -f 3767//3767 3239//3239 3238//3238 -f 3767//3767 3238//3238 3768//3768 -f 3768//3768 3238//3238 3249//3249 -f 3768//3768 3249//3249 3248//3248 -f 3236//3236 3235//3235 3489//3489 -f 3489//3489 3235//3235 3589//3589 -f 3489//3489 3589//3589 3490//3490 -f 3490//3490 3589//3589 3771//3771 -f 3490//3490 3771//3771 3501//3501 -f 3501//3501 3771//3771 3772//3772 -f 3501//3501 3772//3772 3504//3504 -f 3504//3504 3772//3772 3773//3773 -f 3715//3715 3714//3714 3774//3774 -f 3774//3774 3714//3714 3767//3767 -f 3774//3774 3767//3767 3717//3717 -f 3717//3717 3767//3767 3768//3768 -f 3717//3717 3768//3768 3512//3512 -f 3512//3512 3768//3768 3769//3769 -f 3512//3512 3769//3769 3510//3510 -f 3568//3568 3576//3576 3569//3569 -f 3569//3569 3576//3576 3578//3578 -f 3569//3569 3578//3578 3761//3761 -f 3761//3761 3578//3578 3748//3748 -f 3761//3761 3748//3748 3762//3762 -f 3762//3762 3748//3748 3750//3750 -f 3762//3762 3750//3750 3763//3763 -f 3763//3763 3750//3750 3752//3752 -f 3763//3763 3752//3752 3764//3764 -f 3764//3764 3752//3752 3754//3754 -f 3764//3764 3754//3754 3631//3631 -f 3631//3631 3754//3754 3623//3623 -f 3631//3631 3623//3623 3630//3630 -f 3630//3630 3623//3623 3622//3622 -f 3630//3630 3622//3622 3770//3770 -f 3770//3770 3622//3622 3616//3616 -f 3770//3770 3616//3616 3769//3769 -f 3769//3769 3616//3616 3615//3615 -f 3769//3769 3615//3615 3510//3510 -f 3510//3510 3615//3615 3524//3524 -f 3510//3510 3524//3524 3508//3508 -f 3508//3508 3524//3524 3523//3523 -f 2744//2744 2742//2742 3410//3410 -f 3410//3410 2742//2742 3525//3525 -f 3410//3410 3525//3525 3611//3611 -f 3559//3559 3564//3564 3560//3560 -f 3560//3560 3564//3564 3563//3563 -f 3560//3560 3563//3563 3599//3599 -f 3599//3599 3563//3563 3639//3639 -f 3599//3599 3639//3639 3597//3597 -f 3597//3597 3639//3639 3640//3640 -f 3597//3597 3640//3640 3604//3604 -f 3604//3604 3640//3640 3641//3641 -f 3604//3604 3641//3641 3606//3606 -f 3606//3606 3641//3641 3635//3635 -f 3606//3606 3635//3635 3607//3607 -f 3607//3607 3635//3635 3666//3666 -f 3607//3607 3666//3666 3624//3624 -f 3624//3624 3666//3666 3664//3664 -f 3624//3624 3664//3664 3608//3608 -f 3608//3608 3664//3664 3662//3662 -f 3608//3608 3662//3662 3611//3611 -f 3611//3611 3662//3662 3655//3655 -f 3611//3611 3655//3655 3410//3410 -f 3410//3410 3655//3655 3529//3529 -f 3410//3410 3529//3529 2746//2746 -f 2746//2746 3529//3529 2748//2748 -f 2708//2708 2706//2706 3530//3530 -f 3530//3530 2706//2706 3532//3532 -f 3530//3530 3532//3532 3428//3428 -f 3428//3428 3532//3532 3775//3775 -f 3428//3428 3775//3775 3426//3426 -f 3386//3386 3403//3403 3590//3590 -f 3590//3590 3403//3403 3632//3632 -f 3590//3590 3632//3632 3589//3589 -f 3589//3589 3632//3632 3714//3714 -f 3589//3589 3714//3714 3771//3771 -f 3771//3771 3714//3714 3712//3712 -f 3771//3771 3712//3712 3772//3772 -f 3772//3772 3712//3712 3710//3710 -f 3772//3772 3710//3710 3773//3773 -f 3773//3773 3710//3710 3707//3707 -f 3617//3617 3614//3614 3615//3615 -f 3615//3615 3614//3614 3405//3405 -f 3615//3615 3405//3405 3524//3524 -f 3524//3524 3405//3405 3404//3404 -f 3524//3524 3404//3404 3521//3521 -f 3521//3521 3404//3404 3776//3776 -f 3525//3525 2722//2722 2720//2720 -f 3404//3404 2718//2718 2716//2716 -f 3260//3260 3259//3259 3610//3610 -f 3610//3610 3259//3259 3611//3611 -f 3610//3610 3611//3611 3406//3406 -f 3406//3406 3611//3611 3525//3525 -f 3406//3406 3525//3525 3404//3404 -f 3404//3404 3525//3525 2720//2720 -f 3404//3404 2720//2720 2718//2718 -f 2722//2722 3525//3525 2724//2724 -f 2724//2724 3525//3525 3526//3526 -f 2724//2724 3526//3526 2726//2726 -f 2716//2716 2714//2714 3404//3404 -f 3404//3404 2714//2714 2712//2712 -f 3404//3404 2712//2712 3776//3776 -f 3776//3776 2712//2712 2734//2734 -f 2734//2734 2732//2732 3776//3776 -f 3776//3776 2732//2732 2730//2730 -f 3776//3776 2730//2730 3526//3526 -f 3526//3526 2730//2730 2728//2728 -f 3526//3526 2728//2728 2726//2726 -f 3417//3417 3419//3419 3431//3431 -f 3431//3431 3419//3419 3777//3777 -f 3431//3431 3777//3777 3684//3684 -f 3684//3684 3777//3777 3778//3778 -f 3684//3684 3778//3778 3528//3528 -f 3528//3528 3778//3778 3779//3779 -f 3528//3528 3779//3779 3527//3527 -f 3527//3527 3779//3779 3780//3780 -f 3527//3527 3780//3780 3526//3526 -f 3526//3526 3780//3780 3781//3781 -f 3526//3526 3781//3781 3776//3776 -f 3776//3776 3781//3781 3782//3782 -f 3776//3776 3782//3782 3521//3521 -f 3521//3521 3782//3782 3783//3783 -f 3521//3521 3783//3783 3519//3519 -f 3519//3519 3783//3783 3784//3784 -f 3519//3519 3784//3784 3421//3421 -f 3421//3421 3784//3784 3785//3785 -f 3421//3421 3785//3785 3422//3422 -f 3017//3017 3658//3658 3018//3018 -f 3018//3018 3658//3658 3659//3659 -f 3018//3018 3659//3659 3020//3020 -f 3020//3020 3659//3659 3660//3660 -f 3020//3020 3660//3660 3021//3021 -f 3021//3021 3660//3660 3654//3654 -f 3021//3021 3654//3654 3015//3015 -f 3015//3015 3654//3654 3653//3653 -f 3003//3003 3665//3665 3008//3008 -f 3008//3008 3665//3665 3667//3667 -f 3008//3008 3667//3667 3009//3009 -f 3009//3009 3667//3667 3675//3675 -f 3009//3009 3675//3675 3010//3010 -f 3010//3010 3675//3675 3674//3674 -f 3016//3016 3015//3015 3653//3653 -f 3665//3665 3003//3003 3663//3663 -f 3663//3663 3003//3003 3016//3016 -f 3663//3663 3016//3016 3661//3661 -f 3661//3661 3016//3016 3653//3653 -f 3006//3006 3673//3673 3007//3007 -f 3007//3007 3673//3673 3672//3672 -f 3007//3007 3672//3672 3013//3013 -f 3013//3013 3672//3672 3671//3671 -f 3013//3013 3671//3671 3012//3012 -f 3012//3012 3671//3671 3669//3669 -f 3010//3010 3674//3674 3006//3006 -f 3006//3006 3674//3674 3673//3673 -f 3679//3679 3033//3033 3677//3677 -f 3677//3677 3033//3033 3011//3011 -f 3677//3677 3011//3011 3678//3678 -f 3678//3678 3011//3011 3012//3012 -f 3678//3678 3012//3012 3669//3669 -f 3658//3658 3017//3017 3656//3656 -f 3656//3656 3017//3017 3029//3029 -f 3033//3033 3679//3679 3032//3032 -f 3032//3032 3679//3679 3680//3680 -f 3032//3032 3680//3680 3031//3031 -f 3031//3031 3680//3680 3681//3681 -f 3031//3031 3681//3681 3030//3030 -f 3030//3030 3681//3681 3682//3682 -f 3030//3030 3682//3682 2855//2855 -f 2855//2855 3682//3682 3687//3687 -f 2855//2855 3687//3687 2854//2854 -f 2854//2854 3687//3687 3686//3686 -f 2854//2854 3686//3686 2853//2853 -f 2853//2853 3686//3686 3685//3685 -f 2853//2853 3685//3685 2851//2851 -f 2851//2851 3685//3685 3683//3683 -f 2851//2851 3683//3683 3024//3024 -f 3024//3024 3683//3683 3690//3690 -f 3024//3024 3690//3690 3026//3026 -f 3026//3026 3690//3690 3689//3689 -f 3026//3026 3689//3689 3027//3027 -f 3027//3027 3689//3689 3688//3688 -f 3027//3027 3688//3688 3028//3028 -f 3028//3028 3688//3688 3657//3657 -f 3028//3028 3657//3657 3029//3029 -f 3029//3029 3657//3657 3656//3656 -f 2825//2825 3382//3382 2826//2826 -f 2826//2826 3382//3382 3638//3638 -f 3652//3652 2958//2958 3642//3642 -f 3642//3642 2958//2958 2966//2966 -f 3642//3642 2966//2966 3644//3644 -f 3644//3644 2966//2966 2967//2967 -f 3644//3644 2967//2967 3645//3645 -f 3645//3645 2967//2967 2971//2971 -f 3645//3645 2971//2971 3646//3646 -f 3646//3646 2971//2971 2972//2972 -f 3646//3646 2972//2972 3638//3638 -f 3638//3638 2972//2972 2976//2976 -f 3638//3638 2976//2976 2826//2826 -f 3383//3383 2831//2831 3647//3647 -f 3647//3647 2831//2831 2830//2830 -f 3647//3647 2830//2830 3648//3648 -f 3648//3648 2830//2830 2952//2952 -f 3648//3648 2952//2952 3649//3649 -f 3649//3649 2952//2952 2955//2955 -f 3649//3649 2955//2955 3650//3650 -f 3650//3650 2955//2955 2954//2954 -f 3650//3650 2954//2954 3651//3651 -f 3651//3651 2954//2954 2953//2953 -f 3651//3651 2953//2953 3652//3652 -f 3652//3652 2953//2953 2957//2957 -f 3652//3652 2957//2957 2958//2958 -f 3080//3080 3487//3487 3078//3078 -f 3078//3078 3487//3487 3497//3497 -f 3078//3078 3497//3497 3083//3083 -f 3083//3083 3497//3497 3496//3496 -f 3083//3083 3496//3496 3084//3084 -f 3084//3084 3496//3496 3494//3494 -f 3084//3084 3494//3494 3085//3085 -f 3085//3085 3494//3494 3493//3493 -f 3085//3085 3493//3493 3086//3086 -f 3086//3086 3493//3493 3492//3492 -f 3086//3086 3492//3492 2815//2815 -f 2815//2815 3492//3492 3491//3491 -f 2815//2815 3491//3491 2816//2816 -f 2816//2816 3491//3491 3503//3503 -f 2816//2816 3503//3503 3089//3089 -f 3089//3089 3503//3503 3502//3502 -f 3089//3089 3502//3502 3088//3088 -f 3088//3088 3502//3502 3500//3500 -f 3088//3088 3500//3500 3087//3087 -f 3087//3087 3500//3500 3499//3499 -f 3087//3087 3499//3499 3082//3082 -f 3082//3082 3499//3499 3488//3488 -f 3082//3082 3488//3488 3080//3080 -f 3080//3080 3488//3488 3487//3487 -f 3124//3124 3480//3480 3125//3125 -f 3125//3125 3480//3480 3478//3478 -f 3125//3125 3478//3478 3126//3126 -f 3126//3126 3478//3478 3477//3477 -f 3126//3126 3477//3477 3127//3127 -f 3127//3127 3477//3477 3473//3473 -f 3127//3127 3473//3473 3128//3128 -f 3128//3128 3473//3473 3472//3472 -f 3128//3128 3472//3472 3129//3129 -f 3129//3129 3472//3472 3471//3471 -f 3129//3129 3471//3471 3119//3119 -f 3119//3119 3471//3471 3469//3469 -f 3119//3119 3469//3469 3120//3120 -f 3120//3120 3469//3469 3467//3467 -f 3120//3120 3467//3467 3121//3121 -f 3121//3121 3467//3467 3466//3466 -f 3121//3121 3466//3466 3122//3122 -f 3122//3122 3466//3466 3485//3485 -f 3122//3122 3485//3485 3123//3123 -f 3123//3123 3485//3485 3484//3484 -f 3123//3123 3484//3484 3117//3117 -f 3117//3117 3484//3484 3482//3482 -f 3117//3117 3482//3482 3124//3124 -f 3124//3124 3482//3482 3480//3480 -f 3176//3176 3036//3036 3614//3614 -f 3620//3620 3177//3177 3621//3621 -f 3621//3621 3177//3177 3176//3176 -f 3621//3621 3176//3176 3617//3617 -f 3617//3617 3176//3176 3614//3614 -f 3614//3614 3036//3036 3613//3613 -f 3613//3613 3036//3036 3035//3035 -f 3613//3613 3035//3035 3612//3612 -f 3612//3612 3035//3035 3037//3037 -f 3612//3612 3037//3037 3610//3610 -f 3610//3610 3037//3037 3042//3042 -f 3043//3043 3053//3053 3626//3626 -f 3610//3610 3042//3042 3609//3609 -f 3609//3609 3042//3042 3043//3043 -f 3609//3609 3043//3043 3625//3625 -f 3625//3625 3043//3043 3626//3626 -f 3626//3626 3053//3053 3627//3627 -f 3627//3627 3053//3053 3179//3179 -f 3627//3627 3179//3179 3619//3619 -f 3619//3619 3179//3179 3178//3178 -f 3619//3619 3178//3178 3620//3620 -f 3620//3620 3178//3178 3177//3177 -f 2925//2925 3756//3756 2924//2924 -f 2924//2924 3756//3756 3755//3755 -f 2924//2924 3755//3755 2922//2922 -f 2922//2922 3755//3755 3753//3753 -f 2922//2922 3753//3753 2920//2920 -f 2920//2920 3753//3753 3751//3751 -f 2920//2920 3751//3751 2917//2917 -f 2917//2917 3751//3751 3749//3749 -f 3756//3756 2925//2925 3757//3757 -f 3757//3757 2925//2925 2927//2927 -f 3757//3757 2927//2927 3601//3601 -f 3601//3601 2927//2927 2835//2835 -f 3601//3601 2835//2835 3602//3602 -f 3602//3602 2835//2835 2929//2929 -f 3605//3605 3602//3602 2929//2929 -f 2907//2907 2900//2900 3593//3593 -f 3593//3593 3598//3598 2907//2907 -f 2907//2907 3598//3598 3603//3603 -f 2907//2907 3603//3603 2933//2933 -f 2933//2933 3603//3603 3605//3605 -f 2933//2933 3605//3605 2928//2928 -f 2928//2928 3605//3605 2929//2929 -f 3593//3593 2900//2900 3594//3594 -f 3594//3594 2900//2900 2899//2899 -f 3594//3594 2899//2899 3596//3596 -f 3596//3596 2899//2899 2916//2916 -f 3596//3596 2916//2916 3749//3749 -f 3749//3749 2916//2916 2917//2917 -f 3786//3786 3734//3734 3787//3787 -f 3787//3787 3734//3734 3738//3738 -f 3787//3787 3738//3738 3788//3788 -f 3788//3788 3738//3738 3746//3746 -f 3788//3788 3746//3746 3789//3789 -f 3789//3789 3746//3746 3745//3745 -f 3789//3789 3745//3745 3790//3790 -f 3790//3790 3745//3745 3743//3743 -f 3790//3790 3743//3743 3791//3791 -f 3791//3791 3743//3743 3742//3742 -f 3791//3791 3742//3742 3792//3792 -f 3792//3792 3742//3742 3737//3737 -f 3792//3792 3737//3737 3793//3793 -f 3793//3793 3737//3737 3736//3736 -f 3793//3793 3736//3736 3794//3794 -f 3794//3794 3736//3736 3741//3741 -f 3794//3794 3741//3741 3795//3795 -f 3795//3795 3741//3741 3740//3740 -f 3795//3795 3740//3740 3796//3796 -f 3796//3796 3740//3740 3739//3739 -f 3796//3796 3739//3739 3797//3797 -f 3797//3797 3739//3739 3735//3735 -f 3797//3797 3735//3735 3786//3786 -f 3786//3786 3735//3735 3734//3734 -f 3798//3798 3551//3551 3799//3799 -f 3799//3799 3551//3551 3550//3550 -f 3799//3799 3550//3550 3800//3800 -f 3800//3800 3550//3550 3553//3553 -f 3800//3800 3553//3553 3801//3801 -f 3801//3801 3553//3553 3555//3555 -f 3801//3801 3555//3555 3802//3802 -f 3802//3802 3555//3555 3557//3557 -f 3802//3802 3557//3557 3803//3803 -f 3803//3803 3557//3557 3565//3565 -f 3803//3803 3565//3565 3804//3804 -f 3804//3804 3565//3565 3562//3562 -f 3804//3804 3562//3562 3805//3805 -f 3805//3805 3562//3562 3561//3561 -f 3805//3805 3561//3561 3806//3806 -f 3806//3806 3561//3561 3564//3564 -f 3806//3806 3564//3564 3807//3807 -f 3807//3807 3564//3564 3559//3559 -f 3807//3807 3559//3559 3808//3808 -f 3808//3808 3559//3559 3558//3558 -f 3808//3808 3558//3558 3809//3809 -f 3809//3809 3558//3558 3552//3552 -f 3809//3809 3552//3552 3798//3798 -f 3798//3798 3552//3552 3551//3551 -f 3810//3810 3534//3534 3811//3811 -f 3811//3811 3534//3534 3540//3540 -f 3811//3811 3540//3540 3812//3812 -f 3812//3812 3540//3540 3539//3539 -f 3812//3812 3539//3539 3813//3813 -f 3813//3813 3539//3539 3538//3538 -f 3813//3813 3538//3538 3814//3814 -f 3814//3814 3538//3538 3537//3537 -f 3814//3814 3537//3537 3815//3815 -f 3815//3815 3537//3537 3544//3544 -f 3815//3815 3544//3544 3816//3816 -f 3816//3816 3544//3544 3542//3542 -f 3816//3816 3542//3542 3817//3817 -f 3817//3817 3542//3542 3549//3549 -f 3817//3817 3549//3549 3818//3818 -f 3818//3818 3549//3549 3548//3548 -f 3818//3818 3548//3548 3819//3819 -f 3819//3819 3548//3548 3547//3547 -f 3819//3819 3547//3547 3820//3820 -f 3820//3820 3547//3547 3546//3546 -f 3820//3820 3546//3546 3821//3821 -f 3821//3821 3546//3546 3545//3545 -f 3821//3821 3545//3545 3810//3810 -f 3810//3810 3545//3545 3534//3534 -f 3822//3822 3729//3729 3823//3823 -f 3823//3823 3729//3729 3728//3728 -f 3823//3823 3728//3728 3824//3824 -f 3824//3824 3728//3728 3727//3727 -f 3824//3824 3727//3727 3825//3825 -f 3825//3825 3727//3727 3726//3726 -f 3825//3825 3726//3726 3826//3826 -f 3826//3826 3726//3726 3724//3724 -f 3826//3826 3724//3724 3827//3827 -f 3827//3827 3724//3724 3723//3723 -f 3827//3827 3723//3723 3828//3828 -f 3828//3828 3723//3723 3722//3722 -f 3828//3828 3722//3722 3829//3829 -f 3829//3829 3722//3722 3721//3721 -f 3829//3829 3721//3721 3830//3830 -f 3830//3830 3721//3721 3733//3733 -f 3830//3830 3733//3733 3831//3831 -f 3831//3831 3733//3733 3732//3732 -f 3831//3831 3732//3732 3832//3832 -f 3832//3832 3732//3732 3731//3731 -f 3832//3832 3731//3731 3833//3833 -f 3833//3833 3731//3731 3730//3730 -f 3833//3833 3730//3730 3822//3822 -f 3822//3822 3730//3730 3729//3729 -f 2897//2897 3574//3574 2898//2898 -f 2898//2898 3574//3574 3573//3573 -f 2898//2898 3573//3573 2894//2894 -f 2894//2894 3573//3573 3572//3572 -f 2894//2894 3572//3572 2895//2895 -f 2895//2895 3572//3572 3571//3571 -f 2895//2895 3571//3571 2886//2886 -f 2886//2886 3571//3571 3582//3582 -f 2886//2886 3582//3582 2888//2888 -f 2888//2888 3582//3582 3581//3581 -f 2888//2888 3581//3581 2881//2881 -f 2881//2881 3581//3581 3579//3579 -f 2881//2881 3579//3579 2882//2882 -f 2882//2882 3579//3579 3577//3577 -f 2882//2882 3577//3577 2889//2889 -f 2889//2889 3577//3577 3576//3576 -f 2889//2889 3576//3576 2890//2890 -f 2890//2890 3576//3576 3568//3568 -f 2890//2890 3568//3568 2892//2892 -f 2892//2892 3568//3568 3567//3567 -f 2892//2892 3567//3567 2896//2896 -f 2896//2896 3567//3567 3575//3575 -f 2896//2896 3575//3575 2897//2897 -f 2897//2897 3575//3575 3574//3574 -f 2873//2873 3515//3515 2875//2875 -f 2875//2875 3515//3515 3514//3514 -f 2875//2875 3514//3514 2876//2876 -f 2876//2876 3514//3514 3513//3513 -f 2876//2876 3513//3513 2836//2836 -f 2836//2836 3513//3513 3511//3511 -f 2836//2836 3511//3511 2837//2837 -f 2837//2837 3511//3511 3509//3509 -f 2837//2837 3509//3509 2870//2870 -f 2870//2870 3509//3509 3508//3508 -f 2870//2870 3508//3508 2867//2867 -f 2867//2867 3508//3508 3523//3523 -f 2867//2867 3523//3523 2868//2868 -f 2868//2868 3523//3523 3522//3522 -f 2868//2868 3522//3522 2878//2878 -f 2878//2878 3522//3522 3520//3520 -f 2878//2878 3520//3520 2879//2879 -f 2879//2879 3520//3520 3518//3518 -f 2879//2879 3518//3518 2880//2880 -f 2880//2880 3518//3518 3517//3517 -f 2880//2880 3517//3517 2872//2872 -f 2872//2872 3517//3517 3516//3516 -f 2872//2872 3516//3516 2873//2873 -f 2873//2873 3516//3516 3515//3515 -f 3314//3314 3357//3357 3785//3785 -f 3785//3785 3357//3357 3422//3422 -f 3357//3357 3358//3358 3422//3422 -f 3422//3422 3358//3358 3423//3423 -f 3705//3705 3346//3346 3707//3707 -f 3707//3707 3346//3346 3345//3345 -f 3707//3707 3345//3345 3773//3773 -f 3773//3773 3345//3345 3504//3504 -f 3504//3504 3345//3345 3505//3505 -f 3505//3505 3345//3345 3343//3343 -f 3505//3505 3343//3343 3506//3506 -f 3506//3506 3343//3343 3337//3337 -f 3506//3506 3337//3337 3507//3507 -f 3507//3507 3337//3337 3335//3335 -f 3507//3507 3335//3335 3486//3486 -f 3486//3486 3335//3335 3333//3333 -f 3486//3486 3333//3333 3498//3498 -f 3498//3498 3333//3333 3332//3332 -f 3495//3495 3498//3498 3332//3332 -f 3481//3481 3483//3483 3321//3321 -f 3321//3321 3483//3483 3583//3583 -f 3583//3583 3584//3584 3321//3321 -f 3321//3321 3584//3584 3591//3591 -f 3321//3321 3591//3591 3332//3332 -f 3332//3332 3591//3591 3592//3592 -f 3332//3332 3592//3592 3495//3495 -f 3481//3481 3321//3321 3479//3479 -f 3479//3479 3321//3321 3320//3320 -f 3479//3479 3320//3320 3474//3474 -f 3474//3474 3320//3320 3319//3319 -f 3354//3354 3412//3412 3331//3331 -f 3331//3331 3412//3412 3411//3411 -f 3331//3331 3411//3411 3329//3329 -f 3329//3329 3411//3411 3476//3476 -f 3329//3329 3476//3476 3319//3319 -f 3319//3319 3476//3476 3475//3475 -f 3319//3319 3475//3475 3474//3474 -f 3354//3354 3355//3355 3465//3465 -f 3465//3465 3701//3701 3354//3354 -f 3354//3354 3701//3701 3758//3758 -f 3354//3354 3758//3758 3412//3412 -f 3340//3340 3339//3339 3461//3461 -f 3461//3461 3339//3339 3453//3453 -f 3339//3339 3309//3309 3453//3453 -f 3453//3453 3309//3309 3451//3451 -f 3445//3445 3747//3747 3310//3310 -f 3310//3310 3747//3747 3744//3744 -f 3310//3310 3744//3744 3566//3566 -f 3566//3566 3556//3556 3310//3310 -f 3310//3310 3556//3556 3554//3554 -f 3310//3310 3554//3554 3309//3309 -f 3309//3309 3554//3554 3725//3725 -f 3309//3309 3725//3725 3580//3580 -f 3580//3580 3570//3570 3309//3309 -f 3309//3309 3570//3570 3452//3452 -f 3309//3309 3452//3452 3451//3451 -f 3310//3310 3366//3366 3445//3445 -f 3445//3445 3366//3366 3446//3446 -f 3366//3366 3362//3362 3446//3446 -f 3446//3446 3362//3362 3448//3448 -f 3362//3362 3361//3361 3448//3448 -f 3448//3448 3361//3361 3449//3449 -f 3361//3361 3360//3360 3449//3449 -f 3449//3449 3360//3360 3450//3450 -f 3360//3360 3367//3367 3450//3450 -f 3450//3450 3367//3367 3414//3414 -f 3367//3367 3364//3364 3414//3414 -f 3414//3414 3364//3364 3415//3415 -f 3416//3416 3415//3415 3364//3364 -f 3443//3443 3444//3444 3351//3351 -f 3351//3351 3444//3444 3541//3541 -f 3351//3351 3541//3541 3364//3364 -f 3364//3364 3541//3541 3543//3543 -f 3364//3364 3543//3543 3416//3416 -f 3351//3351 3349//3349 3443//3443 -f 3443//3443 3349//3349 3441//3441 -f 3349//3349 3348//3348 3435//3435 -f 3435//3435 3437//3437 3349//3349 -f 3349//3349 3437//3437 3439//3439 -f 3349//3349 3439//3439 3441//3441 -f 3348//3348 3350//3350 3435//3435 -f 3435//3435 3350//3350 3433//3433 -f 3434//3434 3433//3433 3350//3350 -f 3426//3426 3775//3775 3325//3325 -f 3325//3325 3775//3775 3532//3532 -f 3325//3325 3532//3532 3350//3350 -f 3350//3350 3532//3532 3531//3531 -f 3350//3350 3531//3531 3434//3434 -f 3325//3325 3324//3324 3426//3426 -f 3426//3426 3324//3324 3427//3427 -f 3324//3324 3316//3316 3427//3427 -f 3427//3427 3316//3316 3429//3429 -f 3316//3316 3322//3322 3429//3429 -f 3429//3429 3322//3322 3430//3430 -f 3322//3322 3308//3308 3430//3430 -f 3430//3430 3308//3308 3432//3432 -f 3308//3308 3307//3307 3432//3432 -f 3432//3432 3307//3307 3417//3417 -f 3307//3307 3306//3306 3417//3417 -f 3417//3417 3306//3306 3418//3418 -f 3785//3785 3784//3784 3314//3314 -f 3314//3314 3784//3784 3783//3783 -f 3314//3314 3783//3783 3782//3782 -f 3782//3782 3781//3781 3314//3314 -f 3314//3314 3781//3781 3780//3780 -f 3314//3314 3780//3780 3306//3306 -f 3306//3306 3780//3780 3779//3779 -f 3306//3306 3779//3779 3778//3778 -f 3778//3778 3777//3777 3306//3306 -f 3306//3306 3777//3777 3419//3419 -f 3306//3306 3419//3419 3418//3418 -f 3301//3301 2959//2959 2829//2829 -f 3301//3301 2829//2829 3311//3311 -f 3311//3311 2829//2829 3002//3002 -f 3311//3311 3002//3002 3312//3312 -f 3312//3312 3002//3002 3001//3001 -f 3312//3312 3001//3001 3313//3313 -f 3313//3313 3001//3001 3000//3000 -f 3313//3313 3000//3000 3365//3365 -f 3365//3365 3000//3000 2999//2999 -f 3365//3365 2999//2999 3363//3363 -f 3363//3363 2999//2999 2998//2998 -f 3363//3363 2998//2998 3302//3302 -f 3303//3303 2857//2857 2856//2856 -f 3303//3303 2856//2856 3326//3326 -f 3326//3326 2856//2856 2979//2979 -f 3326//3326 2979//2979 3317//3317 -f 3317//3317 2979//2979 2978//2978 -f 3317//3317 2978//2978 3318//3318 -f 3318//3318 2978//2978 2977//2977 -f 3318//3318 2977//2977 3323//3323 -f 3323//3323 2977//2977 3162//3162 -f 3323//3323 3162//3162 3315//3315 -f 3315//3315 3162//3162 3161//3161 -f 3315//3315 3161//3161 3304//3304 -f 3299//3299 2821//2821 2989//2989 -f 3299//3299 2989//2989 3327//3327 -f 3327//3327 2989//2989 2994//2994 -f 3327//3327 2994//2994 3328//3328 -f 3328//3328 2994//2994 2993//2993 -f 3328//3328 2993//2993 3330//3330 -f 3330//3330 2993//2993 2990//2990 -f 3330//3330 2990//2990 3352//3352 -f 3352//3352 2990//2990 2991//2991 -f 3352//3352 2991//2991 3353//3353 -f 3353//3353 2991//2991 2992//2992 -f 3353//3353 2992//2992 3300//3300 -f 3305//3305 3172//3172 2985//2985 -f 3305//3305 2985//2985 3344//3344 -f 3344//3344 2985//2985 2984//2984 -f 3344//3344 2984//2984 3342//3342 -f 3342//3342 2984//2984 2983//2983 -f 3342//3342 2983//2983 3338//3338 -f 3338//3338 2983//2983 2982//2982 -f 3338//3338 2982//2982 3336//3336 -f 3336//3336 2982//2982 2981//2981 -f 3336//3336 2981//2981 3334//3334 -f 3334//3334 2981//2981 2988//2988 -f 3334//3334 2988//2988 3298//3298 -f 3834//3834 3835//3835 2711//2711 -f 2723//2723 3836//3836 2721//2721 -f 2721//2721 3836//3836 3837//3837 -f 2721//2721 3837//3837 2719//2719 -f 2719//2719 3837//3837 3838//3838 -f 3839//3839 2731//2731 3835//3835 -f 3835//3835 2731//2731 2733//2733 -f 3835//3835 2733//2733 2711//2711 -f 2723//2723 2725//2725 3836//3836 -f 3836//3836 2725//2725 2727//2727 -f 3836//3836 2727//2727 3839//3839 -f 3839//3839 2727//2727 2729//2729 -f 3839//3839 2729//2729 2731//2731 -f 2711//2711 2713//2713 3834//3834 -f 3834//3834 2713//2713 2715//2715 -f 3834//3834 2715//2715 3838//3838 -f 3838//3838 2715//2715 2717//2717 -f 3838//3838 2717//2717 2719//2719 -f 3838//3838 3837//3837 3130//3130 -f 3130//3130 3837//3837 3131//3131 -f 3834//3834 3838//3838 3134//3134 -f 3134//3134 3838//3838 3130//3130 -f 3835//3835 3834//3834 3133//3133 -f 3133//3133 3834//3834 3134//3134 -f 3839//3839 3835//3835 3132//3132 -f 3132//3132 3835//3835 3133//3133 -f 3836//3836 3839//3839 3165//3165 -f 3165//3165 3839//3839 3132//3132 -f 3837//3837 3836//3836 3131//3131 -f 3131//3131 3836//3836 3165//3165 -f 3840//3840 3841//3841 3825//3825 -f 3828//3828 3842//3842 3827//3827 -f 3827//3827 3842//3842 3840//3840 -f 3827//3827 3840//3840 3826//3826 -f 3826//3826 3840//3840 3825//3825 -f 3843//3843 3844//3844 3832//3832 -f 3832//3832 3833//3833 3843//3843 -f 3843//3843 3833//3833 3822//3822 -f 3843//3843 3822//3822 3845//3845 -f 3845//3845 3822//3822 3823//3823 -f 3845//3845 3823//3823 3841//3841 -f 3841//3841 3823//3823 3824//3824 -f 3841//3841 3824//3824 3825//3825 -f 3828//3828 3829//3829 3842//3842 -f 3842//3842 3829//3829 3830//3830 -f 3842//3842 3830//3830 3844//3844 -f 3844//3844 3830//3830 3831//3831 -f 3844//3844 3831//3831 3832//3832 -f 3840//3840 3842//3842 3224//3224 -f 3224//3224 3842//3842 3225//3225 -f 3841//3841 3840//3840 3223//3223 -f 3223//3223 3840//3840 3224//3224 -f 3845//3845 3841//3841 3222//3222 -f 3222//3222 3841//3841 3223//3223 -f 3843//3843 3845//3845 3221//3221 -f 3221//3221 3845//3845 3222//3222 -f 3844//3844 3843//3843 3220//3220 -f 3220//3220 3843//3843 3221//3221 -f 3842//3842 3844//3844 3225//3225 -f 3225//3225 3844//3844 3220//3220 -f 3846//3846 3847//3847 3808//3808 -f 3808//3808 3809//3809 3846//3846 -f 3846//3846 3809//3809 3798//3798 -f 3846//3846 3798//3798 3848//3848 -f 3804//3804 3849//3849 3803//3803 -f 3803//3803 3849//3849 3850//3850 -f 3804//3804 3805//3805 3849//3849 -f 3849//3849 3805//3805 3806//3806 -f 3849//3849 3806//3806 3847//3847 -f 3847//3847 3806//3806 3807//3807 -f 3847//3847 3807//3807 3808//3808 -f 3798//3798 3799//3799 3848//3848 -f 3848//3848 3799//3799 3800//3800 -f 3848//3848 3800//3800 3851//3851 -f 3851//3851 3800//3800 3801//3801 -f 3851//3851 3801//3801 3850//3850 -f 3850//3850 3801//3801 3802//3802 -f 3850//3850 3802//3802 3803//3803 -f 3850//3850 3849//3849 3140//3140 -f 3140//3140 3849//3849 3135//3135 -f 3851//3851 3850//3850 3141//3141 -f 3141//3141 3850//3850 3140//3140 -f 3848//3848 3851//3851 3139//3139 -f 3139//3139 3851//3851 3141//3141 -f 3846//3846 3848//3848 3138//3138 -f 3138//3138 3848//3848 3139//3139 -f 3847//3847 3846//3846 3136//3136 -f 3136//3136 3846//3846 3138//3138 -f 3849//3849 3847//3847 3135//3135 -f 3135//3135 3847//3847 3136//3136 -f 3792//3792 3852//3852 3791//3791 -f 3791//3791 3852//3852 3853//3853 -f 3792//3792 3793//3793 3852//3852 -f 3852//3852 3793//3793 3794//3794 -f 3852//3852 3794//3794 3854//3854 -f 3855//3855 3856//3856 3786//3786 -f 3794//3794 3795//3795 3854//3854 -f 3854//3854 3795//3795 3796//3796 -f 3854//3854 3796//3796 3856//3856 -f 3856//3856 3796//3796 3797//3797 -f 3856//3856 3797//3797 3786//3786 -f 3786//3786 3787//3787 3855//3855 -f 3855//3855 3787//3787 3788//3788 -f 3855//3855 3788//3788 3857//3857 -f 3857//3857 3788//3788 3789//3789 -f 3857//3857 3789//3789 3853//3853 -f 3853//3853 3789//3789 3790//3790 -f 3853//3853 3790//3790 3791//3791 -f 3853//3853 3852//3852 2964//2964 -f 2964//2964 3852//3852 2965//2965 -f 3857//3857 3853//3853 2970//2970 -f 2970//2970 3853//3853 2964//2964 -f 3855//3855 3857//3857 2969//2969 -f 2969//2969 3857//3857 2970//2970 -f 3856//3856 3855//3855 2962//2962 -f 2962//2962 3855//3855 2969//2969 -f 3854//3854 3856//3856 2961//2961 -f 2961//2961 3856//3856 2962//2962 -f 3852//3852 3854//3854 2965//2965 -f 2965//2965 3854//3854 2961//2961 -f 3858//3858 3859//3859 3815//3815 -f 3818//3818 3860//3860 3817//3817 -f 3817//3817 3860//3860 3858//3858 -f 3817//3817 3858//3858 3816//3816 -f 3816//3816 3858//3858 3815//3815 -f 3861//3861 3862//3862 3810//3810 -f 3818//3818 3819//3819 3860//3860 -f 3860//3860 3819//3819 3820//3820 -f 3860//3860 3820//3820 3862//3862 -f 3862//3862 3820//3820 3821//3821 -f 3862//3862 3821//3821 3810//3810 -f 3810//3810 3811//3811 3861//3861 -f 3861//3861 3811//3811 3812//3812 -f 3861//3861 3812//3812 3863//3863 -f 3863//3863 3812//3812 3813//3813 -f 3863//3863 3813//3813 3859//3859 -f 3859//3859 3813//3813 3814//3814 -f 3859//3859 3814//3814 3815//3815 -f 3150//3150 3859//3859 3152//3152 -f 3152//3152 3859//3859 3858//3858 -f 3152//3152 3858//3858 2806//2806 -f 2828//2828 2827//2827 3863//3863 -f 3859//3859 3150//3150 3148//3148 -f 3859//3859 3148//3148 3863//3863 -f 3863//3863 3148//3148 3147//3147 -f 3863//3863 3147//3147 2828//2828 -f 3144//3144 3861//3861 2956//2956 -f 2956//2956 3861//3861 3863//3863 -f 2956//2956 3863//3863 2827//2827 -f 3146//3146 3862//3862 3145//3145 -f 3145//3145 3862//3862 3861//3861 -f 3145//3145 3861//3861 3144//3144 -f 3860//3860 3862//3862 2807//2807 -f 2807//2807 3862//3862 3146//3146 -f 3858//3858 3860//3860 2806//2806 -f 2806//2806 3860//3860 2807//2807 -f 3864//3864 3865//3865 2699//2699 -f 2699//2699 2701//2701 3864//3864 -f 3864//3864 2701//2701 2703//2703 -f 3864//3864 2703//2703 3866//3866 -f 2703//2703 2705//2705 3866//3866 -f 3866//3866 2705//2705 2707//2707 -f 3866//3866 2707//2707 3867//3867 -f 2707//2707 2709//2709 3867//3867 -f 3867//3867 2709//2709 2687//2687 -f 3867//3867 2687//2687 3868//3868 -f 3869//3869 2695//2695 3865//3865 -f 3865//3865 2695//2695 2697//2697 -f 3865//3865 2697//2697 2699//2699 -f 2687//2687 2689//2689 3868//3868 -f 3868//3868 2689//2689 2691//2691 -f 3868//3868 2691//2691 3869//3869 -f 3869//3869 2691//2691 2693//2693 -f 3869//3869 2693//2693 2695//2695 -f 3869//3869 3865//3865 3199//3199 -f 3199//3199 3865//3865 2863//2863 -f 3868//3868 3869//3869 2846//2846 -f 2846//2846 3869//3869 3199//3199 -f 2843//2843 3867//3867 2844//2844 -f 2844//2844 3867//3867 3868//3868 -f 2844//2844 3868//3868 2846//2846 -f 3866//3866 3867//3867 2850//2850 -f 2850//2850 3867//3867 2843//2843 -f 3866//3866 2850//2850 2849//2849 -f 2866//2866 3864//3864 2861//2861 -f 2861//2861 3864//3864 3866//3866 -f 2861//2861 3866//3866 2858//2858 -f 2858//2858 3866//3866 2849//2849 -f 2863//2863 3865//3865 2865//2865 -f 2865//2865 3865//3865 3864//3864 -f 2865//2865 3864//3864 2866//2866 -f 3870//3870 3871//3871 2771//2771 -f 2779//2779 3872//3872 2777//2777 -f 2777//2777 3872//3872 3873//3873 -f 2777//2777 3873//3873 2775//2775 -f 2775//2775 3873//3873 3870//3870 -f 2775//2775 3870//3870 2773//2773 -f 2773//2773 3870//3870 2771//2771 -f 2779//2779 2781//2781 3872//3872 -f 3872//3872 2781//2781 2759//2759 -f 3872//3872 2759//2759 3874//3874 -f 3875//3875 2767//2767 3871//3871 -f 3871//3871 2767//2767 2769//2769 -f 3871//3871 2769//2769 2771//2771 -f 2759//2759 2761//2761 3874//3874 -f 3874//3874 2761//2761 2763//2763 -f 3874//3874 2763//2763 3875//3875 -f 3875//3875 2763//2763 2765//2765 -f 3875//3875 2765//2765 2767//2767 -f 3875//3875 3871//3871 3023//3023 -f 3023//3023 3871//3871 3025//3025 -f 3874//3874 3875//3875 3022//3022 -f 3022//3022 3875//3875 3023//3023 -f 3872//3872 3874//3874 2804//2804 -f 2804//2804 3874//3874 3022//3022 -f 3873//3873 3872//3872 2803//2803 -f 2803//2803 3872//3872 2804//2804 -f 3870//3870 3873//3873 3154//3154 -f 3154//3154 3873//3873 2803//2803 -f 3871//3871 3870//3870 3025//3025 -f 3025//3025 3870//3870 3154//3154 -f 3876//3876 3877//3877 2747//2747 -f 3878//3878 2755//2755 3879//3879 -f 3879//3879 2755//2755 2757//2757 -f 3879//3879 2757//2757 3880//3880 -f 3880//3880 2757//2757 2735//2735 -f 3881//3881 2743//2743 3877//3877 -f 3877//3877 2743//2743 2745//2745 -f 3877//3877 2745//2745 2747//2747 -f 2747//2747 2749//2749 3876//3876 -f 3876//3876 2749//2749 2751//2751 -f 3876//3876 2751//2751 3878//3878 -f 3878//3878 2751//2751 2753//2753 -f 3878//3878 2753//2753 2755//2755 -f 2735//2735 2737//2737 3880//3880 -f 3880//3880 2737//2737 2739//2739 -f 3880//3880 2739//2739 3881//3881 -f 3881//3881 2739//2739 2741//2741 -f 3881//3881 2741//2741 2743//2743 -f 3881//3881 3877//3877 2841//2841 -f 2841//2841 3877//3877 2842//2842 -f 3880//3880 3881//3881 2840//2840 -f 2840//2840 3881//3881 2841//2841 -f 3879//3879 3880//3880 2839//2839 -f 2839//2839 3880//3880 2840//2840 -f 3878//3878 3879//3879 3157//3157 -f 3157//3157 3879//3879 2839//2839 -f 3876//3876 3878//3878 3218//3218 -f 3218//3218 3878//3878 3157//3157 -f 3877//3877 3876//3876 2842//2842 -f 2842//2842 3876//3876 3218//3218 -f 2671//2671 3882//3882 2669//2669 -f 2669//2669 3882//3882 3883//3883 -f 2669//2669 3883//3883 2667//2667 -f 2667//2667 3883//3883 3884//3884 -f 2667//2667 3884//3884 2665//2665 -f 2665//2665 3884//3884 3885//3885 -f 2665//2665 3885//3885 2663//2663 -f 2663//2663 3885//3885 3886//3886 -f 2663//2663 3886//3886 2685//2685 -f 2685//2685 3886//3886 3887//3887 -f 2685//2685 3887//3887 2683//2683 -f 3887//3887 3888//3888 2683//2683 -f 2683//2683 3888//3888 3889//3889 -f 2683//2683 3889//3889 2681//2681 -f 2681//2681 3889//3889 3890//3890 -f 2681//2681 3890//3890 2679//2679 -f 2679//2679 3890//3890 3891//3891 -f 2679//2679 3891//3891 2677//2677 -f 2677//2677 3891//3891 3892//3892 -f 2677//2677 3892//3892 2675//2675 -f 2675//2675 3892//3892 3893//3893 -f 2675//2675 3893//3893 2673//2673 -f 2673//2673 3893//3893 3894//3894 -f 2673//2673 3894//3894 2671//2671 -f 2671//2671 3894//3894 3895//3895 -f 2671//2671 3895//3895 3882//3882 -f 3894//3894 3711//3711 3895//3895 -f 3895//3895 3711//3711 3713//3713 -f 3895//3895 3713//3713 3882//3882 -f 3882//3882 3713//3713 3715//3715 -f 3882//3882 3715//3715 3883//3883 -f 3883//3883 3715//3715 3774//3774 -f 3883//3883 3774//3774 3884//3884 -f 3884//3884 3774//3774 3717//3717 -f 3884//3884 3717//3717 3885//3885 -f 3885//3885 3717//3717 3716//3716 -f 3885//3885 3716//3716 3886//3886 -f 3886//3886 3716//3716 3720//3720 -f 3886//3886 3720//3720 3887//3887 -f 3887//3887 3720//3720 3719//3719 -f 3887//3887 3719//3719 3888//3888 -f 3888//3888 3719//3719 3718//3718 -f 3888//3888 3718//3718 3889//3889 -f 3889//3889 3718//3718 3420//3420 -f 3889//3889 3420//3420 3890//3890 -f 3890//3890 3420//3420 3425//3425 -f 3890//3890 3425//3425 3891//3891 -f 3891//3891 3425//3425 3706//3706 -f 3891//3891 3706//3706 3892//3892 -f 3892//3892 3706//3706 3708//3708 -f 3892//3892 3708//3708 3893//3893 -f 3893//3893 3708//3708 3709//3709 -f 3893//3893 3709//3709 3894//3894 -f 3894//3894 3709//3709 3711//3711 -f 2647//2647 3896//3896 2645//2645 -f 2645//2645 3896//3896 3897//3897 -f 2645//2645 3897//3897 2643//2643 -f 2643//2643 3897//3897 3898//3898 -f 2643//2643 3898//3898 2641//2641 -f 2641//2641 3898//3898 3899//3899 -f 2641//2641 3899//3899 2639//2639 -f 2639//2639 3899//3899 3900//3900 -f 2639//2639 3900//3900 2661//2661 -f 2661//2661 3900//3900 3901//3901 -f 2661//2661 3901//3901 2659//2659 -f 3901//3901 3902//3902 2659//2659 -f 2659//2659 3902//3902 3903//3903 -f 2659//2659 3903//3903 2657//2657 -f 2657//2657 3903//3903 3904//3904 -f 2657//2657 3904//3904 2655//2655 -f 2655//2655 3904//3904 3905//3905 -f 2655//2655 3905//3905 2653//2653 -f 2653//2653 3905//3905 3906//3906 -f 2653//2653 3906//3906 2651//2651 -f 2651//2651 3906//3906 3907//3907 -f 2651//2651 3907//3907 2649//2649 -f 2649//2649 3907//3907 3908//3908 -f 2649//2649 3908//3908 2647//2647 -f 2647//2647 3908//3908 3909//3909 -f 2647//2647 3909//3909 3896//3896 -f 3908//3908 3702//3702 3909//3909 -f 3909//3909 3702//3702 3464//3464 -f 3909//3909 3464//3464 3896//3896 -f 3896//3896 3464//3464 3456//3456 -f 3896//3896 3456//3456 3897//3897 -f 3897//3897 3456//3456 3455//3455 -f 3897//3897 3455//3455 3898//3898 -f 3898//3898 3455//3455 3460//3460 -f 3898//3898 3460//3460 3899//3899 -f 3899//3899 3460//3460 3459//3459 -f 3899//3899 3459//3459 3900//3900 -f 3900//3900 3459//3459 3458//3458 -f 3900//3900 3458//3458 3901//3901 -f 3901//3901 3458//3458 3695//3695 -f 3901//3901 3695//3695 3902//3902 -f 3902//3902 3695//3695 3694//3694 -f 3902//3902 3694//3694 3903//3903 -f 3903//3903 3694//3694 3692//3692 -f 3903//3903 3692//3692 3904//3904 -f 3904//3904 3692//3692 3691//3691 -f 3904//3904 3691//3691 3905//3905 -f 3905//3905 3691//3691 3696//3696 -f 3905//3905 3696//3696 3906//3906 -f 3906//3906 3696//3696 3698//3698 -f 3906//3906 3698//3698 3907//3907 -f 3907//3907 3698//3698 3703//3703 -f 3907//3907 3703//3703 3908//3908 -f 3908//3908 3703//3703 3702//3702 -f 3465//3465 3355//3355 3356//3356 -f 3465//3465 3356//3356 3463//3463 -f 3463//3463 3356//3356 3341//3341 -f 3463//3463 3341//3341 3462//3462 -f 3462//3462 3341//3341 3340//3340 -f 3462//3462 3340//3340 3461//3461 -f 3346//3346 3705//3705 3704//3704 -f 3346//3346 3704//3704 3347//3347 -f 3347//3347 3704//3704 3424//3424 -f 3347//3347 3424//3424 3359//3359 -f 3359//3359 3424//3424 3423//3423 -f 3359//3359 3423//3423 3358//3358 -f 3910//3910 3911//3911 3912//3912 -f 3912//3912 3911//3911 3913//3913 -f 3912//3912 3913//3913 3914//3914 -f 3914//3914 3913//3913 3915//3915 -f 3914//3914 3915//3915 3916//3916 -f 3916//3916 3915//3915 3917//3917 -f 3916//3916 3917//3917 3918//3918 -f 3918//3918 3917//3917 3919//3919 -f 3918//3918 3919//3919 3920//3920 -f 3920//3920 3919//3919 3921//3921 -f 3920//3920 3921//3921 3922//3922 -f 3922//3922 3921//3921 3923//3923 -f 3922//3922 3923//3923 3924//3924 -f 3924//3924 3923//3923 3925//3925 -f 3924//3924 3925//3925 3926//3926 -f 3926//3926 3925//3925 3927//3927 -f 3926//3926 3927//3927 3928//3928 -f 3928//3928 3927//3927 3929//3929 -f 3928//3928 3929//3929 3930//3930 -f 3930//3930 3929//3929 3931//3931 -f 3930//3930 3931//3931 3932//3932 -f 3932//3932 3931//3931 3933//3933 -f 3932//3932 3933//3933 3910//3910 -f 3910//3910 3933//3933 3911//3911 -f 3934//3934 3935//3935 3936//3936 -f 3936//3936 3935//3935 3937//3937 -f 3936//3936 3937//3937 3938//3938 -f 3938//3938 3937//3937 3939//3939 -f 3938//3938 3939//3939 3940//3940 -f 3940//3940 3939//3939 3941//3941 -f 3940//3940 3941//3941 3942//3942 -f 3942//3942 3941//3941 3943//3943 -f 3942//3942 3943//3943 3944//3944 -f 3944//3944 3943//3943 3945//3945 -f 3944//3944 3945//3945 3946//3946 -f 3946//3946 3945//3945 3947//3947 -f 3946//3946 3947//3947 3948//3948 -f 3948//3948 3947//3947 3949//3949 -f 3948//3948 3949//3949 3950//3950 -f 3950//3950 3949//3949 3951//3951 -f 3950//3950 3951//3951 3952//3952 -f 3952//3952 3951//3951 3953//3953 -f 3952//3952 3953//3953 3954//3954 -f 3954//3954 3953//3953 3955//3955 -f 3954//3954 3955//3955 3956//3956 -f 3956//3956 3955//3955 3957//3957 -f 3956//3956 3957//3957 3934//3934 -f 3934//3934 3957//3957 3935//3935 -f 3958//3958 3959//3959 3960//3960 -f 3960//3960 3959//3959 3961//3961 -f 3960//3960 3961//3961 3962//3962 -f 3962//3962 3961//3961 3963//3963 -f 3962//3962 3963//3963 3964//3964 -f 3964//3964 3963//3963 3965//3965 -f 3964//3964 3965//3965 3966//3966 -f 3966//3966 3965//3965 3967//3967 -f 3966//3966 3967//3967 3968//3968 -f 3968//3968 3967//3967 3969//3969 -f 3968//3968 3969//3969 3970//3970 -f 3970//3970 3969//3969 3971//3971 -f 3970//3970 3971//3971 3972//3972 -f 3972//3972 3971//3971 3973//3973 -f 3972//3972 3973//3973 3974//3974 -f 3974//3974 3973//3973 3975//3975 -f 3974//3974 3975//3975 3976//3976 -f 3976//3976 3975//3975 3977//3977 -f 3976//3976 3977//3977 3978//3978 -f 3978//3978 3977//3977 3979//3979 -f 3978//3978 3979//3979 3980//3980 -f 3980//3980 3979//3979 3981//3981 -f 3980//3980 3981//3981 3958//3958 -f 3958//3958 3981//3981 3959//3959 -f 3982//3982 3983//3983 3984//3984 -f 3984//3984 3983//3983 3985//3985 -f 3984//3984 3985//3985 3986//3986 -f 3986//3986 3985//3985 3987//3987 -f 3986//3986 3987//3987 3988//3988 -f 3988//3988 3987//3987 3989//3989 -f 3988//3988 3989//3989 3990//3990 -f 3990//3990 3989//3989 3991//3991 -f 3990//3990 3991//3991 3992//3992 -f 3992//3992 3991//3991 3993//3993 -f 3992//3992 3993//3993 3994//3994 -f 3994//3994 3993//3993 3995//3995 -f 3994//3994 3995//3995 3996//3996 -f 3996//3996 3995//3995 3997//3997 -f 3996//3996 3997//3997 3998//3998 -f 3998//3998 3997//3997 3999//3999 -f 3998//3998 3999//3999 4000//4000 -f 4000//4000 3999//3999 4001//4001 -f 4000//4000 4001//4001 4002//4002 -f 4002//4002 4001//4001 4003//4003 -f 4002//4002 4003//4003 4004//4004 -f 4004//4004 4003//4003 4005//4005 -f 4004//4004 4005//4005 3982//3982 -f 3982//3982 4005//4005 3983//3983 -f 4006//4006 4007//4007 4008//4008 -f 4008//4008 4007//4007 4009//4009 -f 4008//4008 4009//4009 4010//4010 -f 4010//4010 4009//4009 4011//4011 -f 4010//4010 4011//4011 4012//4012 -f 4012//4012 4011//4011 4013//4013 -f 4012//4012 4013//4013 4014//4014 -f 4014//4014 4013//4013 4015//4015 -f 4014//4014 4015//4015 4016//4016 -f 4016//4016 4015//4015 4017//4017 -f 4016//4016 4017//4017 4018//4018 -f 4018//4018 4017//4017 4019//4019 -f 4018//4018 4019//4019 4020//4020 -f 4020//4020 4019//4019 4021//4021 -f 4020//4020 4021//4021 4022//4022 -f 4022//4022 4021//4021 4023//4023 -f 4022//4022 4023//4023 4024//4024 -f 4024//4024 4023//4023 4025//4025 -f 4024//4024 4025//4025 4026//4026 -f 4026//4026 4025//4025 4027//4027 -f 4026//4026 4027//4027 4028//4028 -f 4028//4028 4027//4027 4029//4029 -f 4028//4028 4029//4029 4006//4006 -f 4006//4006 4029//4029 4007//4007 -f 4030//4030 4031//4031 4032//4032 -f 4032//4032 4031//4031 4033//4033 -f 4032//4032 4033//4033 4034//4034 -f 4034//4034 4033//4033 4035//4035 -f 4034//4034 4035//4035 4036//4036 -f 4036//4036 4035//4035 4037//4037 -f 4036//4036 4037//4037 4038//4038 -f 4038//4038 4037//4037 4039//4039 -f 4038//4038 4039//4039 4040//4040 -f 4040//4040 4039//4039 4041//4041 -f 4040//4040 4041//4041 4042//4042 -f 4042//4042 4041//4041 4043//4043 -f 4042//4042 4043//4043 4044//4044 -f 4044//4044 4043//4043 4045//4045 -f 4044//4044 4045//4045 4046//4046 -f 4046//4046 4045//4045 4047//4047 -f 4046//4046 4047//4047 4048//4048 -f 4048//4048 4047//4047 4049//4049 -f 4048//4048 4049//4049 4050//4050 -f 4050//4050 4049//4049 4051//4051 -f 4050//4050 4051//4051 4052//4052 -f 4052//4052 4051//4051 4053//4053 -f 4052//4052 4053//4053 4030//4030 -f 4030//4030 4053//4053 4031//4031 -f 4054//4054 4055//4055 4056//4056 -f 4057//4057 4058//4058 4059//4059 -f 4060//4060 4061//4061 4062//4062 -f 4063//4063 4064//4064 4065//4065 -f 4066//4066 4067//4067 4068//4068 -f 4069//4069 4070//4070 4071//4071 -f 3945//3945 3943//3943 4071//4071 -f 3927//3927 4072//4072 4073//4073 -f 4074//4074 4075//4075 4076//4076 -f 4077//4077 4078//4078 4079//4079 -f 4080//4080 4081//4081 4082//4082 -f 4083//4083 4084//4084 4085//4085 -f 4086//4086 4087//4087 4088//4088 -f 4089//4089 4090//4090 4091//4091 -f 4092//4092 4093//4093 4094//4094 -f 4095//4095 4096//4096 4097//4097 -f 4098//4098 4099//4099 4100//4100 -f 4101//4101 4102//4102 4103//4103 -f 4104//4104 4105//4105 4106//4106 -f 4107//4107 4108//4108 4109//4109 -f 4110//4110 4111//4111 4063//4063 -f 4063//4063 4111//4111 4112//4112 -f 4063//4063 4112//4112 4064//4064 -f 4064//4064 4112//4112 4113//4113 -f 4114//4114 4115//4115 4116//4116 -f 4116//4116 4115//4115 4117//4117 -f 4116//4116 4117//4117 4118//4118 -f 4119//4119 4120//4120 4121//4121 -f 4122//4122 4123//4123 4124//4124 -f 4124//4124 4123//4123 4119//4119 -f 4124//4124 4119//4119 4125//4125 -f 4125//4125 4119//4119 4121//4121 -f 4125//4125 4121//4121 4126//4126 -f 4119//4119 4127//4127 4120//4120 -f 4120//4120 4127//4127 4128//4128 -f 4120//4120 4128//4128 4129//4129 -f 4128//4128 4130//4130 4129//4129 -f 4129//4129 4130//4130 4131//4131 -f 4129//4129 4131//4131 4132//4132 -f 4133//4133 4134//4134 4135//4135 -f 4135//4135 4134//4134 4136//4136 -f 4135//4135 4136//4136 4131//4131 -f 4131//4131 4136//4136 4137//4137 -f 4131//4131 4137//4137 4132//4132 -f 4138//4138 4139//4139 4066//4066 -f 4066//4066 4139//4139 4140//4140 -f 4108//4108 4141//4141 4142//4142 -f 4143//4143 4144//4144 4145//4145 -f 4146//4146 4147//4147 4148//4148 -f 4139//4139 4149//4149 4140//4140 -f 4140//4140 4149//4149 4150//4150 -f 4140//4140 4150//4150 4145//4145 -f 4145//4145 4150//4150 4151//4151 -f 4145//4145 4151//4151 4143//4143 -f 4146//4146 4148//4148 4144//4144 -f 4152//4152 4153//4153 4154//4154 -f 4154//4154 4153//4153 4155//4155 -f 4156//4156 4157//4157 4158//4158 -f 4158//4158 4157//4157 4159//4159 -f 4153//4153 4160//4160 4155//4155 -f 4155//4155 4160//4160 4161//4161 -f 4155//4155 4161//4161 4162//4162 -f 4162//4162 4161//4161 4163//4163 -f 4164//4164 4165//4165 4156//4156 -f 4156//4156 4165//4165 4166//4166 -f 4156//4156 4166//4166 4157//4157 -f 4163//4163 4167//4167 4162//4162 -f 4162//4162 4167//4167 4168//4168 -f 4162//4162 4168//4168 4164//4164 -f 4164//4164 4168//4168 4169//4169 -f 4164//4164 4169//4169 4165//4165 -f 4055//4055 4170//4170 4171//4171 -f 4172//4172 4173//4173 4174//4174 -f 4174//4174 4173//4173 4175//4175 -f 4176//4176 4177//4177 4178//4178 -f 4178//4178 4177//4177 4179//4179 -f 4178//4178 4179//4179 4171//4171 -f 4171//4171 4179//4179 4180//4180 -f 4171//4171 4180//4180 4181//4181 -f 4182//4182 4183//4183 4184//4184 -f 4184//4184 4183//4183 4185//4185 -f 4184//4184 4185//4185 4174//4174 -f 4174//4174 4185//4185 4186//4186 -f 4174//4174 4186//4186 4172//4172 -f 4170//4170 4055//4055 4187//4187 -f 4187//4187 4055//4055 4054//4054 -f 4187//4187 4054//4054 4188//4188 -f 4189//4189 4190//4190 4191//4191 -f 4191//4191 4190//4190 4192//4192 -f 4191//4191 4192//4192 4193//4193 -f 4193//4193 4192//4192 4194//4194 -f 4193//4193 4194//4194 4195//4195 -f 4195//4195 4194//4194 4196//4196 -f 4194//4194 4197//4197 4196//4196 -f 4196//4196 4197//4197 4104//4104 -f 4196//4196 4104//4104 4198//4198 -f 4198//4198 4104//4104 4106//4106 -f 4199//4199 4200//4200 4201//4201 -f 4201//4201 4202//4202 4199//4199 -f 4199//4199 4202//4202 4203//4203 -f 4199//4199 4203//4203 4204//4204 -f 4204//4204 4203//4203 4174//4174 -f 4204//4204 4174//4174 4178//4178 -f 4178//4178 4174//4174 4175//4175 -f 4178//4178 4175//4175 4176//4176 -f 4205//4205 4206//4206 4207//4207 -f 4207//4207 4206//4206 4208//4208 -f 4209//4209 4210//4210 4211//4211 -f 4209//4209 4211//4211 4212//4212 -f 4213//4213 4214//4214 4215//4215 -f 4215//4215 4214//4214 4212//4212 -f 4210//4210 4216//4216 4211//4211 -f 4211//4211 4216//4216 4217//4217 -f 4211//4211 4217//4217 4208//4208 -f 4208//4208 4217//4217 4218//4218 -f 4208//4208 4218//4218 4207//4207 -f 4213//4213 4215//4215 4219//4219 -f 4219//4219 4215//4215 4220//4220 -f 4219//4219 4220//4220 4221//4221 -f 4221//4221 4220//4220 4222//4222 -f 4221//4221 4222//4222 4103//4103 -f 4103//4103 4222//4222 4223//4223 -f 4103//4103 4223//4223 4101//4101 -f 4224//4224 4225//4225 4098//4098 -f 4098//4098 4225//4225 4226//4226 -f 4098//4098 4226//4226 4227//4227 -f 4224//4224 4098//4098 4228//4228 -f 4228//4228 4098//4098 4100//4100 -f 4228//4228 4100//4100 4229//4229 -f 4229//4229 4100//4100 4230//4230 -f 4229//4229 4230//4230 4231//4231 -f 4232//4232 4233//4233 4234//4234 -f 4231//4231 4235//4235 4229//4229 -f 4229//4229 4235//4235 4236//4236 -f 4229//4229 4236//4236 4237//4237 -f 4237//4237 4236//4236 4238//4238 -f 4234//4234 4233//4233 4239//4239 -f 4239//4239 4233//4233 4240//4240 -f 4239//4239 4240//4240 4231//4231 -f 4231//4231 4240//4240 4241//4241 -f 4231//4231 4241//4241 4235//4235 -f 4238//4238 4236//4236 4242//4242 -f 4242//4242 4236//4236 4232//4232 -f 4242//4242 4232//4232 4243//4243 -f 4207//4207 4244//4244 4205//4205 -f 4205//4205 4244//4244 4245//4245 -f 4205//4205 4245//4245 4234//4234 -f 4234//4234 4245//4245 4246//4246 -f 4246//4246 4095//4095 4234//4234 -f 4234//4234 4095//4095 4097//4097 -f 4234//4234 4097//4097 4232//4232 -f 4232//4232 4097//4097 4247//4247 -f 4232//4232 4247//4247 4243//4243 -f 4248//4248 4249//4249 4119//4119 -f 4119//4119 4249//4249 4250//4250 -f 4119//4119 4250//4250 4127//4127 -f 4251//4251 4252//4252 4253//4253 -f 4253//4253 4254//4254 4251//4251 -f 4251//4251 4254//4254 4255//4255 -f 4251//4251 4255//4255 4256//4256 -f 4257//4257 4258//4258 4259//4259 -f 4092//4092 4094//4094 4260//4260 -f 4261//4261 4094//4094 4262//4262 -f 4262//4262 4094//4094 4263//4263 -f 4261//4261 4264//4264 4094//4094 -f 4094//4094 4264//4264 4265//4265 -f 4094//4094 4265//4265 4260//4260 -f 4266//4266 4267//4267 4263//4263 -f 4268//4268 4269//4269 4099//4099 -f 4099//4099 4269//4269 4270//4270 -f 4099//4099 4270//4270 4271//4271 -f 4271//4271 4272//4272 4099//4099 -f 4099//4099 4272//4272 4273//4273 -f 4099//4099 4273//4273 4100//4100 -f 4274//4274 4275//4275 4276//4276 -f 4277//4277 4278//4278 4118//4118 -f 4274//4274 4279//4279 4275//4275 -f 4275//4275 4279//4279 4280//4280 -f 4275//4275 4280//4280 4281//4281 -f 4282//4282 4116//4116 4283//4283 -f 4283//4283 4116//4116 4118//4118 -f 4283//4283 4118//4118 4284//4284 -f 4284//4284 4118//4118 4278//4278 -f 4285//4285 4286//4286 4276//4276 -f 4276//4276 4286//4286 4287//4287 -f 4276//4276 4287//4287 4274//4274 -f 4288//4288 4289//4289 4290//4290 -f 4290//4290 4289//4289 4291//4291 -f 4290//4290 4291//4291 4285//4285 -f 4285//4285 4291//4291 4292//4292 -f 4285//4285 4292//4292 4286//4286 -f 4076//4076 4075//4075 4290//4290 -f 4290//4290 4075//4075 4293//4293 -f 4290//4290 4293//4293 4294//4294 -f 4122//4122 4295//4295 4296//4296 -f 4296//4296 4295//4295 4297//4297 -f 4296//4296 4297//4297 4294//4294 -f 4297//4297 4298//4298 4294//4294 -f 4294//4294 4298//4298 4299//4299 -f 4294//4294 4299//4299 4290//4290 -f 4290//4290 4299//4299 4300//4300 -f 4290//4290 4300//4300 4288//4288 -f 4126//4126 4121//4121 4301//4301 -f 4301//4301 4121//4121 4114//4114 -f 4301//4301 4114//4114 4302//4302 -f 4302//4302 4114//4114 4116//4116 -f 4302//4302 4116//4116 4303//4303 -f 4303//4303 4116//4116 4282//4282 -f 4303//4303 4282//4282 4304//4304 -f 4305//4305 4306//4306 4307//4307 -f 4306//4306 4305//4305 4308//4308 -f 4309//4309 4310//4310 4065//4065 -f 4311//4311 4312//4312 4313//4313 -f 4313//4313 4312//4312 4314//4314 -f 4315//4315 4316//4316 4317//4317 -f 4312//4312 4318//4318 4314//4314 -f 4314//4314 4318//4318 4319//4319 -f 4314//4314 4319//4319 4320//4320 -f 4317//4317 4321//4321 4315//4315 -f 4315//4315 4321//4321 4322//4322 -f 4315//4315 4322//4322 4065//4065 -f 4065//4065 4322//4322 4323//4323 -f 4065//4065 4323//4323 4309//4309 -f 4320//4320 4316//4316 4314//4314 -f 4314//4314 4316//4316 4315//4315 -f 4314//4314 4315//4315 4324//4324 -f 4324//4324 4315//4315 4201//4201 -f 4324//4324 4201//4201 4105//4105 -f 4105//4105 4201//4201 4200//4200 -f 4105//4105 4200//4200 4106//4106 -f 4325//4325 4326//4326 4327//4327 -f 4328//4328 4329//4329 4330//4330 -f 4330//4330 4329//4329 4331//4331 -f 4330//4330 4331//4331 4332//4332 -f 4332//4332 4331//4331 4333//4333 -f 4090//4090 4089//4089 4334//4334 -f 4335//4335 4336//4336 4337//4337 -f 4337//4337 4336//4336 4338//4338 -f 4337//4337 4338//4338 4339//4339 -f 4339//4339 4338//4338 4091//4091 -f 4339//4339 4091//4091 4340//4340 -f 4062//4062 4341//4341 4342//4342 -f 4343//4343 4344//4344 4345//4345 -f 4343//4343 4345//4345 4346//4346 -f 4341//4341 4062//4062 4347//4347 -f 4347//4347 4062//4062 4059//4059 -f 4347//4347 4059//4059 4327//4327 -f 4327//4327 4059//4059 4348//4348 -f 4327//4327 4348//4348 4325//4325 -f 4349//4349 4350//4350 4351//4351 -f 4351//4351 4350//4350 4352//4352 -f 4351//4351 4352//4352 4353//4353 -f 4354//4354 4355//4355 4085//4085 -f 4085//4085 4355//4355 4356//4356 -f 4085//4085 4356//4356 4357//4357 -f 4353//4353 4352//4352 4358//4358 -f 4358//4358 4352//4352 4258//4258 -f 4358//4358 4258//4258 4359//4359 -f 4359//4359 4258//4258 4257//4257 -f 4359//4359 4257//4257 4360//4360 -f 4361//4361 4362//4362 4337//4337 -f 4363//4363 4364//4364 4365//4365 -f 4366//4366 4335//4335 4363//4363 -f 4363//4363 4335//4335 4337//4337 -f 4363//4363 4337//4337 4364//4364 -f 4364//4364 4337//4337 4362//4362 -f 4349//4349 4354//4354 4350//4350 -f 4350//4350 4354//4354 4085//4085 -f 4350//4350 4085//4085 4367//4367 -f 4367//4367 4085//4085 4084//4084 -f 4367//4367 4368//4368 4350//4350 -f 4350//4350 4368//4368 4369//4369 -f 4350//4350 4369//4369 4370//4370 -f 4370//4370 4369//4369 4371//4371 -f 4370//4370 4371//4371 4372//4372 -f 4373//4373 4374//4374 4375//4375 -f 4375//4375 4374//4374 4376//4376 -f 4375//4375 4376//4376 4340//4340 -f 4340//4340 4376//4376 4377//4377 -f 4340//4340 4377//4377 4080//4080 -f 4378//4378 4379//4379 4380//4380 -f 4380//4380 4379//4379 4381//4381 -f 4380//4380 4381//4381 4382//4382 -f 4081//4081 4383//4383 4384//4384 -f 4384//4384 4383//4383 4385//4385 -f 4384//4384 4385//4385 4381//4381 -f 4381//4381 4385//4385 4386//4386 -f 4381//4381 4386//4386 4382//4382 -f 4387//4387 4381//4381 4388//4388 -f 4389//4389 4390//4390 4379//4379 -f 4379//4379 4390//4390 4391//4391 -f 4391//4391 4392//4392 4379//4379 -f 4379//4379 4392//4392 4393//4393 -f 4379//4379 4393//4393 4381//4381 -f 4381//4381 4393//4393 4394//4394 -f 4381//4381 4394//4394 4388//4388 -f 4388//4388 4395//4395 4387//4387 -f 4387//4387 4395//4395 4396//4396 -f 4387//4387 4396//4396 4093//4093 -f 4396//4396 4397//4397 4093//4093 -f 4093//4093 4397//4397 4398//4398 -f 4093//4093 4398//4398 4094//4094 -f 4094//4094 4398//4398 4399//4399 -f 4094//4094 4399//4399 4389//4389 -f 4389//4389 4399//4399 4400//4400 -f 4389//4389 4400//4400 4390//4390 -f 4401//4401 4402//4402 4063//4063 -f 4403//4403 4404//4404 4067//4067 -f 4067//4067 4404//4404 4405//4405 -f 4067//4067 4405//4405 4068//4068 -f 4406//4406 4407//4407 4408//4408 -f 4056//4056 4409//4409 4410//4410 -f 4406//4406 4234//4234 4411//4411 -f 4411//4411 4234//4234 4239//4239 -f 4411//4411 4239//4239 4412//4412 -f 4412//4412 4239//4239 4413//4413 -f 4412//4412 4413//4413 4410//4410 -f 4410//4410 4413//4413 4414//4414 -f 4410//4410 4414//4414 4056//4056 -f 4227//4227 4226//4226 4415//4415 -f 4415//4415 4226//4226 4223//4223 -f 4415//4415 4223//4223 4416//4416 -f 4416//4416 4223//4223 4222//4222 -f 4416//4416 4222//4222 4417//4417 -f 4417//4417 4222//4222 4220//4220 -f 4417//4417 4220//4220 4078//4078 -f 4099//4099 4418//4418 4268//4268 -f 4268//4268 4418//4418 4419//4419 -f 4268//4268 4419//4419 4420//4420 -f 4420//4420 4419//4419 4421//4421 -f 4420//4420 4421//4421 4422//4422 -f 4422//4422 4421//4421 4423//4423 -f 4422//4422 4423//4423 4424//4424 -f 4424//4424 4423//4423 4077//4077 -f 4122//4122 4296//4296 4123//4123 -f 4123//4123 4296//4296 4425//4425 -f 4123//4123 4425//4425 4074//4074 -f 4063//4063 4426//4426 4110//4110 -f 4110//4110 4426//4426 4427//4427 -f 4110//4110 4427//4427 4428//4428 -f 4428//4428 4427//4427 4429//4429 -f 4428//4428 4429//4429 4076//4076 -f 4076//4076 4429//4429 4430//4430 -f 4076//4076 4430//4430 4074//4074 -f 4074//4074 4430//4430 4431//4431 -f 4074//4074 4431//4431 4123//4123 -f 4123//4123 4431//4431 4432//4432 -f 4123//4123 4432//4432 4119//4119 -f 4119//4119 4432//4432 4433//4433 -f 4119//4119 4433//4433 4248//4248 -f 3927//3927 3925//3925 4072//4072 -f 4072//4072 3925//3925 3923//3923 -f 4072//4072 3923//3923 4434//4434 -f 4162//4162 3911//3911 3933//3933 -f 3911//3911 4162//4162 3913//3913 -f 3913//3913 4162//4162 4164//4164 -f 3913//3913 4164//4164 3915//3915 -f 3923//3923 3921//3921 4434//4434 -f 4434//4434 3921//3921 3919//3919 -f 4434//4434 3919//3919 4164//4164 -f 4164//4164 3919//3919 3917//3917 -f 4164//4164 3917//3917 3915//3915 -f 3931//3931 3929//3929 4435//4435 -f 4144//4144 4148//4148 4145//4145 -f 4145//4145 4148//4148 3935//3935 -f 4145//4145 3935//3935 3957//3957 -f 3957//3957 3955//3955 4145//4145 -f 4145//4145 3955//3955 3953//3953 -f 4145//4145 3953//3953 4070//4070 -f 3953//3953 3951//3951 4070//4070 -f 4070//4070 3951//3951 3949//3949 -f 4070//4070 3949//3949 4071//4071 -f 4071//4071 3949//3949 3947//3947 -f 4071//4071 3947//3947 3945//3945 -f 4060//4060 3941//3941 4061//4061 -f 4061//4061 3941//3941 3939//3939 -f 4061//4061 3939//3939 4148//4148 -f 4148//4148 3939//3939 3937//3937 -f 4148//4148 3937//3937 3935//3935 -f 4063//4063 4402//4402 4426//4426 -f 4426//4426 4402//4402 4436//4436 -f 4426//4426 4436//4436 4427//4427 -f 4427//4427 4436//4436 4403//4403 -f 4427//4427 4403//4403 4437//4437 -f 4437//4437 4403//4403 4067//4067 -f 4437//4437 4067//4067 4438//4438 -f 4438//4438 4067//4067 4066//4066 -f 4438//4438 4066//4066 4439//4439 -f 4439//4439 4066//4066 4140//4140 -f 4439//4439 4140//4140 4440//4440 -f 4440//4440 4140//4140 4145//4145 -f 4440//4440 4145//4145 4441//4441 -f 4441//4441 4145//4145 4070//4070 -f 4441//4441 4070//4070 4442//4442 -f 4442//4442 4070//4070 4069//4069 -f 4442//4442 4069//4069 4443//4443 -f 4256//4256 4443//4443 4251//4251 -f 4251//4251 4443//4443 4069//4069 -f 4251//4251 4069//4069 4444//4444 -f 4444//4444 4069//4069 4071//4071 -f 4444//4444 4071//4071 4060//4060 -f 4060//4060 4071//4071 3943//3943 -f 4060//4060 3943//3943 3941//3941 -f 4142//4142 4305//4305 4445//4445 -f 4445//4445 4305//4305 4307//4307 -f 4445//4445 4307//4307 4446//4446 -f 4446//4446 4307//4307 4447//4447 -f 4446//4446 4447//4447 4197//4197 -f 4197//4197 4447//4447 4448//4448 -f 4197//4197 4448//4448 4104//4104 -f 4104//4104 4448//4448 4449//4449 -f 4104//4104 4449//4449 4105//4105 -f 4105//4105 4449//4449 4450//4450 -f 4105//4105 4450//4450 4324//4324 -f 4313//4313 4308//4308 4451//4451 -f 4451//4451 4308//4308 4305//4305 -f 4451//4451 4305//4305 4068//4068 -f 4068//4068 4305//4305 4142//4142 -f 4068//4068 4142//4142 4066//4066 -f 4066//4066 4142//4142 4141//4141 -f 4066//4066 4141//4141 4138//4138 -f 4405//4405 4401//4401 4068//4068 -f 4068//4068 4401//4401 4063//4063 -f 4068//4068 4063//4063 4451//4451 -f 4451//4451 4063//4063 4065//4065 -f 4451//4451 4065//4065 4313//4313 -f 4313//4313 4065//4065 4310//4310 -f 4313//4313 4310//4310 4311//4311 -f 4365//4365 4083//4083 4363//4363 -f 4363//4363 4083//4083 4085//4085 -f 4363//4363 4085//4085 4088//4088 -f 4088//4088 4085//4085 4357//4357 -f 4088//4088 4357//4357 4086//4086 -f 4344//4344 4366//4366 4345//4345 -f 4345//4345 4366//4366 4363//4363 -f 4345//4345 4363//4363 4452//4452 -f 4452//4452 4363//4363 4088//4088 -f 4452//4452 4088//4088 4257//4257 -f 4257//4257 4088//4088 4087//4087 -f 4257//4257 4087//4087 4360//4360 -f 4342//4342 4346//4346 4062//4062 -f 4062//4062 4346//4346 4345//4345 -f 4062//4062 4345//4345 4060//4060 -f 4060//4060 4345//4345 4452//4452 -f 4060//4060 4452//4452 4444//4444 -f 4444//4444 4452//4452 4257//4257 -f 4444//4444 4257//4257 4251//4251 -f 4251//4251 4257//4257 4259//4259 -f 4251//4251 4259//4259 4252//4252 -f 4059//4059 4058//4058 4453//4453 -f 4058//4058 4454//4454 4453//4453 -f 4453//4453 4454//4454 4455//4455 -f 4453//4453 4455//4455 4456//4456 -f 4456//4456 4061//4061 4453//4453 -f 4453//4453 4061//4061 4148//4148 -f 4453//4453 4148//4148 4109//4109 -f 4109//4109 4148//4148 4147//4147 -f 4109//4109 4147//4147 4107//4107 -f 4456//4456 4457//4457 4061//4061 -f 4061//4061 4457//4457 4458//4458 -f 4061//4061 4458//4458 4062//4062 -f 4062//4062 4458//4458 4459//4459 -f 4062//4062 4459//4459 4460//4460 -f 4460//4460 4461//4461 4062//4062 -f 4062//4062 4461//4461 4462//4462 -f 4062//4062 4462//4462 4059//4059 -f 4059//4059 4462//4462 4463//4463 -f 4059//4059 4463//4463 4057//4057 -f 4212//4212 4211//4211 4215//4215 -f 4215//4215 4211//4211 4275//4275 -f 4215//4215 4275//4275 4118//4118 -f 4118//4118 4275//4275 4281//4281 -f 4118//4118 4281//4281 4277//4277 -f 4081//4081 4384//4384 4082//4082 -f 4082//4082 4384//4384 4464//4464 -f 4082//4082 4464//4464 4465//4465 -f 4465//4465 4464//4464 4370//4370 -f 4465//4465 4370//4370 4466//4466 -f 4466//4466 4370//4370 4372//4372 -f 4466//4466 4372//4372 4467//4467 -f 4080//4080 4082//4082 4340//4340 -f 4340//4340 4082//4082 4465//4465 -f 4340//4340 4465//4465 4339//4339 -f 4339//4339 4465//4465 4466//4466 -f 4339//4339 4466//4466 4337//4337 -f 4337//4337 4466//4466 4467//4467 -f 4337//4337 4467//4467 4361//4361 -f 4078//4078 4220//4220 4079//4079 -f 4079//4079 4220//4220 4215//4215 -f 4079//4079 4215//4215 4468//4468 -f 4468//4468 4215//4215 4118//4118 -f 4468//4468 4118//4118 4469//4469 -f 4469//4469 4118//4118 4117//4117 -f 4469//4469 4117//4117 4470//4470 -f 4077//4077 4079//4079 4424//4424 -f 4424//4424 4079//4079 4468//4468 -f 4424//4424 4468//4468 4471//4471 -f 4471//4471 4468//4468 4469//4469 -f 4471//4471 4469//4469 4133//4133 -f 4133//4133 4469//4469 4470//4470 -f 4133//4133 4470//4470 4134//4134 -f 4326//4326 4325//4325 4333//4333 -f 4333//4333 4325//4325 4472//4472 -f 4333//4333 4472//4472 4332//4332 -f 4332//4332 4472//4472 4473//4473 -f 4332//4332 4473//4473 4330//4330 -f 4334//4334 4435//4435 4073//4073 -f 4073//4073 4435//4435 3929//3929 -f 4073//4073 3929//3929 3927//3927 -f 4474//4474 4475//4475 4473//4473 -f 4476//4476 4477//4477 4330//4330 -f 4473//4473 4475//4475 4330//4330 -f 4330//4330 4475//4475 4478//4478 -f 4330//4330 4478//4478 4476//4476 -f 4089//4089 4328//4328 4334//4334 -f 4334//4334 4328//4328 4330//4330 -f 4334//4334 4330//4330 4435//4435 -f 4435//4435 4330//4330 4477//4477 -f 4479//4479 4480//4480 4481//4481 -f 4481//4481 4480//4480 4482//4482 -f 4481//4481 4482//4482 4473//4473 -f 4473//4473 4482//4482 4483//4483 -f 4473//4473 4483//4483 4474//4474 -f 4477//4477 4484//4484 4435//4435 -f 4435//4435 4484//4484 4485//4485 -f 4435//4435 4485//4485 4481//4481 -f 4481//4481 4485//4485 4486//4486 -f 4481//4481 4486//4486 4479//4479 -f 4108//4108 4142//4142 4109//4109 -f 4109//4109 4142//4142 4445//4445 -f 4109//4109 4445//4445 4453//4453 -f 4453//4453 4445//4445 4446//4446 -f 4453//4453 4446//4446 4059//4059 -f 4059//4059 4446//4446 4197//4197 -f 4059//4059 4197//4197 4348//4348 -f 4348//4348 4197//4197 4194//4194 -f 4348//4348 4194//4194 4325//4325 -f 4325//4325 4194//4194 4192//4192 -f 4325//4325 4192//4192 4472//4472 -f 4472//4472 4192//4192 4190//4190 -f 4472//4472 4190//4190 4473//4473 -f 4473//4473 4190//4190 4189//4189 -f 4473//4473 4189//4189 4481//4481 -f 4263//4263 4094//4094 4266//4266 -f 4266//4266 4094//4094 4389//4389 -f 4266//4266 4389//4389 4487//4487 -f 4487//4487 4389//4389 4379//4379 -f 4487//4487 4379//4379 4375//4375 -f 4375//4375 4379//4379 4378//4378 -f 4375//4375 4378//4378 4373//4373 -f 3933//3933 3931//3931 4162//4162 -f 4162//4162 3931//3931 4435//4435 -f 4162//4162 4435//4435 4155//4155 -f 4155//4155 4435//4435 4481//4481 -f 4155//4155 4481//4481 4154//4154 -f 4154//4154 4481//4481 4189//4189 -f 4154//4154 4189//4189 4488//4488 -f 4181//4181 4182//4182 4171//4171 -f 4171//4171 4182//4182 4184//4184 -f 4171//4171 4184//4184 4055//4055 -f 4055//4055 4184//4184 4408//4408 -f 4055//4055 4408//4408 4056//4056 -f 4056//4056 4408//4408 4407//4407 -f 4056//4056 4407//4407 4409//4409 -f 4406//4406 4408//4408 4234//4234 -f 4234//4234 4408//4408 4184//4184 -f 4234//4234 4184//4184 4205//4205 -f 4205//4205 4184//4184 4174//4174 -f 4205//4205 4174//4174 4206//4206 -f 4206//4206 4174//4174 4203//4203 -f 4206//4206 4203//4203 4208//4208 -f 4208//4208 4203//4203 4202//4202 -f 4208//4208 4202//4202 4211//4211 -f 4211//4211 4202//4202 4201//4201 -f 4211//4211 4201//4201 4275//4275 -f 4275//4275 4201//4201 4315//4315 -f 4275//4275 4315//4315 4276//4276 -f 4276//4276 4315//4315 4065//4065 -f 4276//4276 4065//4065 4285//4285 -f 4285//4285 4065//4065 4064//4064 -f 4285//4285 4064//4064 4290//4290 -f 4290//4290 4064//4064 4113//4113 -f 4290//4290 4113//4113 4076//4076 -f 4076//4076 4113//4113 4489//4489 -f 4076//4076 4489//4489 4428//4428 -f 4091//4091 4090//4090 4340//4340 -f 4340//4340 4090//4090 4334//4334 -f 4340//4340 4334//4334 4375//4375 -f 4375//4375 4334//4334 4073//4073 -f 4375//4375 4073//4073 4487//4487 -f 4487//4487 4073//4073 4072//4072 -f 4487//4487 4072//4072 4266//4266 -f 4266//4266 4072//4072 4434//4434 -f 4266//4266 4434//4434 4267//4267 -f 4488//4488 4490//4490 4154//4154 -f 4154//4154 4490//4490 4158//4158 -f 4154//4154 4158//4158 4152//4152 -f 4152//4152 4158//4158 4159//4159 -f 4191//4191 4188//4188 4189//4189 -f 4189//4189 4188//4188 4054//4054 -f 4189//4189 4054//4054 4488//4488 -f 4488//4488 4054//4054 4056//4056 -f 4488//4488 4056//4056 4491//4491 -f 4491//4491 4492//4492 4488//4488 -f 4488//4488 4492//4492 4493//4493 -f 4488//4488 4493//4493 4490//4490 -f 4490//4490 4493//4493 4494//4494 -f 4490//4490 4494//4494 4414//4414 -f 4414//4414 4494//4494 4495//4495 -f 4414//4414 4495//4495 4056//4056 -f 4056//4056 4495//4495 4496//4496 -f 4056//4056 4496//4496 4491//4491 -f 4369//4369 4497//4497 4371//4371 -f 4371//4371 4497//4497 4498//4498 -f 4371//4371 4498//4498 4372//4372 -f 4372//4372 4498//4498 4499//4499 -f 4372//4372 4499//4499 4467//4467 -f 4467//4467 4499//4499 4500//4500 -f 4467//4467 4500//4500 4361//4361 -f 4361//4361 4500//4500 4501//4501 -f 4361//4361 4501//4501 4362//4362 -f 4362//4362 4501//4501 4502//4502 -f 4362//4362 4502//4502 4364//4364 -f 4364//4364 4502//4502 4503//4503 -f 4364//4364 4503//4503 4365//4365 -f 4365//4365 4503//4503 4504//4504 -f 4365//4365 4504//4504 4083//4083 -f 4083//4083 4504//4504 4505//4505 -f 4083//4083 4505//4505 4084//4084 -f 4084//4084 4505//4505 4506//4506 -f 4084//4084 4506//4506 4367//4367 -f 4367//4367 4506//4506 4507//4507 -f 4367//4367 4507//4507 4368//4368 -f 4368//4368 4507//4507 4508//4508 -f 4368//4368 4508//4508 4369//4369 -f 4369//4369 4508//4508 4497//4497 -f 4459//4459 4509//4509 4460//4460 -f 4460//4460 4509//4509 4510//4510 -f 4460//4460 4510//4510 4461//4461 -f 4461//4461 4510//4510 4511//4511 -f 4461//4461 4511//4511 4462//4462 -f 4462//4462 4511//4511 4512//4512 -f 4462//4462 4512//4512 4463//4463 -f 4463//4463 4512//4512 4513//4513 -f 4463//4463 4513//4513 4057//4057 -f 4057//4057 4513//4513 4514//4514 -f 4057//4057 4514//4514 4058//4058 -f 4058//4058 4514//4514 4515//4515 -f 4058//4058 4515//4515 4454//4454 -f 4454//4454 4515//4515 4516//4516 -f 4454//4454 4516//4516 4455//4455 -f 4455//4455 4516//4516 4517//4517 -f 4455//4455 4517//4517 4456//4456 -f 4456//4456 4517//4517 4518//4518 -f 4456//4456 4518//4518 4457//4457 -f 4457//4457 4518//4518 4519//4519 -f 4457//4457 4519//4519 4458//4458 -f 4458//4458 4519//4519 4520//4520 -f 4458//4458 4520//4520 4459//4459 -f 4459//4459 4520//4520 4509//4509 -f 4318//4318 4521//4521 4319//4319 -f 4319//4319 4521//4521 4522//4522 -f 4319//4319 4522//4522 4320//4320 -f 4320//4320 4522//4522 4523//4523 -f 4320//4320 4523//4523 4316//4316 -f 4316//4316 4523//4523 4524//4524 -f 4316//4316 4524//4524 4317//4317 -f 4317//4317 4524//4524 4525//4525 -f 4317//4317 4525//4525 4321//4321 -f 4321//4321 4525//4525 4526//4526 -f 4321//4321 4526//4526 4322//4322 -f 4322//4322 4526//4526 4527//4527 -f 4322//4322 4527//4527 4323//4323 -f 4323//4323 4527//4527 4528//4528 -f 4323//4323 4528//4528 4309//4309 -f 4309//4309 4528//4528 4529//4529 -f 4309//4309 4529//4529 4310//4310 -f 4310//4310 4529//4529 4530//4530 -f 4310//4310 4530//4530 4311//4311 -f 4311//4311 4530//4530 4531//4531 -f 4311//4311 4531//4531 4312//4312 -f 4312//4312 4531//4531 4532//4532 -f 4312//4312 4532//4532 4318//4318 -f 4318//4318 4532//4532 4521//4521 -f 4386//4386 4533//4533 4382//4382 -f 4382//4382 4533//4533 4534//4534 -f 4382//4382 4534//4534 4380//4380 -f 4380//4380 4534//4534 4535//4535 -f 4380//4380 4535//4535 4378//4378 -f 4378//4378 4535//4535 4536//4536 -f 4378//4378 4536//4536 4373//4373 -f 4373//4373 4536//4536 4537//4537 -f 4373//4373 4537//4537 4374//4374 -f 4374//4374 4537//4537 4538//4538 -f 4374//4374 4538//4538 4376//4376 -f 4376//4376 4538//4538 4539//4539 -f 4376//4376 4539//4539 4377//4377 -f 4377//4377 4539//4539 4540//4540 -f 4377//4377 4540//4540 4080//4080 -f 4080//4080 4540//4540 4541//4541 -f 4080//4080 4541//4541 4081//4081 -f 4081//4081 4541//4541 4542//4542 -f 4081//4081 4542//4542 4383//4383 -f 4383//4383 4542//4542 4543//4543 -f 4383//4383 4543//4543 4385//4385 -f 4385//4385 4543//4543 4544//4544 -f 4385//4385 4544//4544 4386//4386 -f 4386//4386 4544//4544 4533//4533 -f 4179//4179 4545//4545 4180//4180 -f 4180//4180 4545//4545 4546//4546 -f 4180//4180 4546//4546 4181//4181 -f 4181//4181 4546//4546 4547//4547 -f 4181//4181 4547//4547 4182//4182 -f 4182//4182 4547//4547 4548//4548 -f 4182//4182 4548//4548 4183//4183 -f 4183//4183 4548//4548 4549//4549 -f 4183//4183 4549//4549 4185//4185 -f 4185//4185 4549//4549 4550//4550 -f 4185//4185 4550//4550 4186//4186 -f 4186//4186 4550//4550 4551//4551 -f 4186//4186 4551//4551 4172//4172 -f 4172//4172 4551//4551 4552//4552 -f 4172//4172 4552//4552 4173//4173 -f 4173//4173 4552//4552 4553//4553 -f 4173//4173 4553//4553 4175//4175 -f 4175//4175 4553//4553 4554//4554 -f 4175//4175 4554//4554 4176//4176 -f 4176//4176 4554//4554 4555//4555 -f 4176//4176 4555//4555 4177//4177 -f 4177//4177 4555//4555 4556//4556 -f 4177//4177 4556//4556 4179//4179 -f 4179//4179 4556//4556 4545//4545 -f 4477//4477 4557//4557 4484//4484 -f 4484//4484 4557//4557 4558//4558 -f 4484//4484 4558//4558 4485//4485 -f 4485//4485 4558//4558 4559//4559 -f 4485//4485 4559//4559 4486//4486 -f 4486//4486 4559//4559 4560//4560 -f 4486//4486 4560//4560 4479//4479 -f 4479//4479 4560//4560 4561//4561 -f 4479//4479 4561//4561 4480//4480 -f 4480//4480 4561//4561 4562//4562 -f 4480//4480 4562//4562 4482//4482 -f 4482//4482 4562//4562 4563//4563 -f 4482//4482 4563//4563 4483//4483 -f 4483//4483 4563//4563 4564//4564 -f 4483//4483 4564//4564 4474//4474 -f 4474//4474 4564//4564 4565//4565 -f 4474//4474 4565//4565 4475//4475 -f 4475//4475 4565//4565 4566//4566 -f 4475//4475 4566//4566 4478//4478 -f 4478//4478 4566//4566 4567//4567 -f 4478//4478 4567//4567 4476//4476 -f 4476//4476 4567//4567 4568//4568 -f 4476//4476 4568//4568 4477//4477 -f 4477//4477 4568//4568 4557//4557 -f 4259//4259 4258//4258 4569//4569 -f 4569//4569 4258//4258 4352//4352 -f 4352//4352 4350//4350 4569//4569 -f 4569//4569 4350//4350 4370//4370 -f 4569//4569 4370//4370 4570//4570 -f 4370//4370 4464//4464 4570//4570 -f 4570//4570 4464//4464 4384//4384 -f 4570//4570 4384//4384 4381//4381 -f 4381//4381 4387//4387 4570//4570 -f 4570//4570 4387//4387 4093//4093 -f 4570//4570 4093//4093 4092//4092 -f 4571//4571 4263//4263 4267//4267 -f 4267//4267 4434//4434 4571//4571 -f 4571//4571 4434//4434 4164//4164 -f 4571//4571 4164//4164 4156//4156 -f 4156//4156 4158//4158 4571//4571 -f 4571//4571 4158//4158 4490//4490 -f 4571//4571 4490//4490 4572//4572 -f 4572//4572 4490//4490 4414//4414 -f 4572//4572 4414//4414 4413//4413 -f 4413//4413 4239//4239 4572//4572 -f 4572//4572 4239//4239 4231//4231 -f 4572//4572 4231//4231 4230//4230 -f 4573//4573 4269//4269 4268//4268 -f 4268//4268 4420//4420 4573//4573 -f 4573//4573 4420//4420 4422//4422 -f 4573//4573 4422//4422 4424//4424 -f 4424//4424 4471//4471 4573//4573 -f 4573//4573 4471//4471 4133//4133 -f 4573//4573 4133//4133 4574//4574 -f 4574//4574 4133//4133 4135//4135 -f 4135//4135 4131//4131 4574//4574 -f 4574//4574 4131//4131 4130//4130 -f 4574//4574 4130//4130 4128//4128 -f 4432//4432 4431//4431 4575//4575 -f 4575//4575 4431//4431 4430//4430 -f 4430//4430 4429//4429 4575//4575 -f 4575//4575 4429//4429 4427//4427 -f 4575//4575 4427//4427 4576//4576 -f 4576//4576 4427//4427 4437//4437 -f 4437//4437 4438//4438 4576//4576 -f 4576//4576 4438//4438 4439//4439 -f 4576//4576 4439//4439 4440//4440 -f 4440//4440 4441//4441 4576//4576 -f 4576//4576 4441//4441 4442//4442 -f 4576//4576 4442//4442 4443//4443 -f 4577//4577 4578//4578 4579//4579 -f 4580//4580 4571//4571 4581//4581 -f 4581//4581 4571//4571 4572//4572 -f 4572//4572 4582//4582 4581//4581 -f 4581//4581 4582//4582 4583//4583 -f 4581//4581 4583//4583 4584//4584 -f 4576//4576 4585//4585 4575//4575 -f 4575//4575 4585//4585 4577//4577 -f 4575//4575 4577//4577 4586//4586 -f 4587//4587 4588//4588 4589//4589 -f 4590//4590 4591//4591 4570//4570 -f 4570//4570 4591//4591 4592//4592 -f 4570//4570 4592//4592 4569//4569 -f 4593//4593 4587//4587 4579//4579 -f 4579//4579 4587//4587 4589//4589 -f 4579//4579 4589//4589 4577//4577 -f 4577//4577 4589//4589 4594//4594 -f 4577//4577 4594//4594 4586//4586 -f 4587//4587 4595//4595 4588//4588 -f 4588//4588 4595//4595 4596//4596 -f 4588//4588 4596//4596 4597//4597 -f 4570//4570 4598//4598 4590//4590 -f 4590//4590 4598//4598 4599//4599 -f 4590//4590 4599//4599 4600//4600 -f 4600//4600 4599//4599 4601//4601 -f 4600//4600 4601//4601 4602//4602 -f 4592//4592 4603//4603 4569//4569 -f 4569//4569 4603//4603 4604//4604 -f 4569//4569 4604//4604 4605//4605 -f 4605//4605 4604//4604 4606//4606 -f 4605//4605 4606//4606 4607//4607 -f 4607//4607 4606//4606 4608//4608 -f 4607//4607 4608//4608 4609//4609 -f 4580//4580 4610//4610 4571//4571 -f 4571//4571 4610//4610 4611//4611 -f 4571//4571 4611//4611 4612//4612 -f 4609//4609 4608//4608 4613//4613 -f 4613//4613 4608//4608 4614//4614 -f 4613//4613 4614//4614 4615//4615 -f 4615//4615 4614//4614 4616//4616 -f 4615//4615 4616//4616 4576//4576 -f 4576//4576 4616//4616 4617//4617 -f 4576//4576 4617//4617 4618//4618 -f 4619//4619 4620//4620 4621//4621 -f 4621//4621 4620//4620 4622//4622 -f 4601//4601 4623//4623 4602//4602 -f 4602//4602 4623//4623 4624//4624 -f 4602//4602 4624//4624 4625//4625 -f 4625//4625 4624//4624 4571//4571 -f 4625//4625 4571//4571 4626//4626 -f 4626//4626 4571//4571 4612//4612 -f 4626//4626 4612//4612 4627//4627 -f 4628//4628 4585//4585 4629//4629 -f 4629//4629 4585//4585 4576//4576 -f 4629//4629 4576//4576 4630//4630 -f 4630//4630 4576//4576 4618//4618 -f 4631//4631 4632//4632 4633//4633 -f 4597//4597 4596//4596 4574//4574 -f 4574//4574 4596//4596 4621//4621 -f 4574//4574 4621//4621 4573//4573 -f 4573//4573 4621//4621 4622//4622 -f 4573//4573 4622//4622 4634//4634 -f 4634//4634 4622//4622 4635//4635 -f 4634//4634 4635//4635 4636//4636 -f 4637//4637 4581//4581 4633//4633 -f 4633//4633 4581//4581 4584//4584 -f 4633//4633 4584//4584 4631//4631 -f 4631//4631 4584//4584 4636//4636 -f 4631//4631 4636//4636 4638//4638 -f 4638//4638 4636//4636 4635//4635 -f 4219//4219 4639//4639 4213//4213 -f 4213//4213 4639//4639 4640//4640 -f 4213//4213 4640//4640 4214//4214 -f 4214//4214 4640//4640 4641//4641 -f 4214//4214 4641//4641 4212//4212 -f 4212//4212 4641//4641 4642//4642 -f 4209//4209 4643//4643 4210//4210 -f 4210//4210 4643//4643 4644//4644 -f 4210//4210 4644//4644 4216//4216 -f 4216//4216 4644//4644 4645//4645 -f 4216//4216 4645//4645 4217//4217 -f 4217//4217 4645//4645 4646//4646 -f 4212//4212 4642//4642 4209//4209 -f 4209//4209 4642//4642 4643//4643 -f 4244//4244 4647//4647 4245//4245 -f 4245//4245 4647//4647 4648//4648 -f 4245//4245 4648//4648 4246//4246 -f 4246//4246 4648//4648 4649//4649 -f 4246//4246 4649//4649 4095//4095 -f 4095//4095 4649//4649 4650//4650 -f 4647//4647 4244//4244 4651//4651 -f 4651//4651 4244//4244 4207//4207 -f 4651//4651 4207//4207 4652//4652 -f 4652//4652 4207//4207 4218//4218 -f 4652//4652 4218//4218 4646//4646 -f 4646//4646 4218//4218 4217//4217 -f 4095//4095 4650//4650 4096//4096 -f 4096//4096 4650//4650 4653//4653 -f 4102//4102 4654//4654 4655//4655 -f 4102//4102 4655//4655 4103//4103 -f 4103//4103 4655//4655 4656//4656 -f 4103//4103 4656//4656 4221//4221 -f 4221//4221 4656//4656 4639//4639 -f 4221//4221 4639//4639 4219//4219 -f 4336//4336 4657//4657 4338//4338 -f 4338//4338 4657//4657 4658//4658 -f 4338//4338 4658//4658 4091//4091 -f 4091//4091 4658//4658 4659//4659 -f 4091//4091 4659//4659 4089//4089 -f 4089//4089 4659//4659 4660//4660 -f 4089//4089 4660//4660 4328//4328 -f 4328//4328 4660//4660 4661//4661 -f 4328//4328 4661//4661 4329//4329 -f 4329//4329 4661//4661 4662//4662 -f 4329//4329 4662//4662 4331//4331 -f 4331//4331 4662//4662 4663//4663 -f 4331//4331 4663//4663 4333//4333 -f 4333//4333 4663//4663 4664//4664 -f 4333//4333 4664//4664 4326//4326 -f 4326//4326 4664//4664 4665//4665 -f 4326//4326 4665//4665 4327//4327 -f 4327//4327 4665//4665 4666//4666 -f 4327//4327 4666//4666 4347//4347 -f 4347//4347 4666//4666 4667//4667 -f 4347//4347 4667//4667 4341//4341 -f 4341//4341 4667//4667 4668//4668 -f 4341//4341 4668//4668 4342//4342 -f 4342//4342 4668//4668 4669//4669 -f 4342//4342 4669//4669 4346//4346 -f 4346//4346 4669//4669 4670//4670 -f 4346//4346 4670//4670 4343//4343 -f 4343//4343 4670//4670 4671//4671 -f 4343//4343 4671//4671 4344//4344 -f 4344//4344 4671//4671 4672//4672 -f 4344//4344 4672//4672 4366//4366 -f 4366//4366 4672//4672 4673//4673 -f 4366//4366 4673//4673 4335//4335 -f 4335//4335 4673//4673 4674//4674 -f 4335//4335 4674//4674 4336//4336 -f 4336//4336 4674//4674 4657//4657 -f 4675//4675 4676//4676 4677//4677 -f 4678//4678 4679//4679 4680//4680 -f 4017//4017 4015//4015 4681//4681 -f 4682//4682 4683//4683 4684//4684 -f 4685//4685 4686//4686 4687//4687 -f 4688//4688 4689//4689 4690//4690 -f 4691//4691 4692//4692 4693//4693 -f 4693//4693 4694//4694 4691//4691 -f 4691//4691 4694//4694 4695//4695 -f 4691//4691 4695//4695 4696//4696 -f 4697//4697 4698//4698 4699//4699 -f 4698//4698 4700//4700 4699//4699 -f 4699//4699 4700//4700 4701//4701 -f 4699//4699 4701//4701 4702//4702 -f 4702//4702 4701//4701 4703//4703 -f 4702//4702 4703//4703 4688//4688 -f 4704//4704 4705//4705 4706//4706 -f 4706//4706 4705//4705 4707//4707 -f 4706//4706 4707//4707 4708//4708 -f 4708//4708 4707//4707 4709//4709 -f 4708//4708 4709//4709 4710//4710 -f 4710//4710 4709//4709 4711//4711 -f 4710//4710 4711//4711 4712//4712 -f 4712//4712 4711//4711 4713//4713 -f 4712//4712 4713//4713 4714//4714 -f 4714//4714 4713//4713 4715//4715 -f 4716//4716 4717//4717 4718//4718 -f 4717//4717 4719//4719 4718//4718 -f 4718//4718 4719//4719 4720//4720 -f 4718//4718 4720//4720 4721//4721 -f 4722//4722 4723//4723 4724//4724 -f 4724//4724 4723//4723 4725//4725 -f 4724//4724 4726//4726 4727//4727 -f 4728//4728 4729//4729 4725//4725 -f 4725//4725 4729//4729 4730//4730 -f 4725//4725 4730//4730 4724//4724 -f 4724//4724 4730//4730 4731//4731 -f 4724//4724 4731//4731 4726//4726 -f 4732//4732 4724//4724 4733//4733 -f 4733//4733 4724//4724 4727//4727 -f 4733//4733 4727//4727 4734//4734 -f 4734//4734 4727//4727 4735//4735 -f 4734//4734 4735//4735 4736//4736 -f 4737//4737 4738//4738 4739//4739 -f 4739//4739 4738//4738 4740//4740 -f 4739//4739 4740//4740 4741//4741 -f 4740//4740 4742//4742 4741//4741 -f 4741//4741 4742//4742 4743//4743 -f 4741//4741 4743//4743 4744//4744 -f 4744//4744 4745//4745 4741//4741 -f 4741//4741 4745//4745 4746//4746 -f 4741//4741 4746//4746 4684//4684 -f 4684//4684 4746//4746 4747//4747 -f 4684//4684 4747//4747 4682//4682 -f 4744//4744 4748//4748 4745//4745 -f 4745//4745 4748//4748 4749//4749 -f 4745//4745 4749//4749 4750//4750 -f 4750//4750 4749//4749 4751//4751 -f 4750//4750 4751//4751 4752//4752 -f 4752//4752 4751//4751 4753//4753 -f 4752//4752 4753//4753 4754//4754 -f 4754//4754 4753//4753 4755//4755 -f 4754//4754 4755//4755 4739//4739 -f 4739//4739 4755//4755 4756//4756 -f 4739//4739 4756//4756 4737//4737 -f 4757//4757 4758//4758 4759//4759 -f 4760//4760 4761//4761 4762//4762 -f 4762//4762 4763//4763 4760//4760 -f 4760//4760 4763//4763 4764//4764 -f 4760//4760 4764//4764 4765//4765 -f 4766//4766 4767//4767 4768//4768 -f 4758//4758 4757//4757 4768//4768 -f 4768//4768 4757//4757 4769//4769 -f 4768//4768 4769//4769 4766//4766 -f 4759//4759 4770//4770 4757//4757 -f 4757//4757 4770//4770 4771//4771 -f 4757//4757 4771//4771 4772//4772 -f 4772//4772 4771//4771 4773//4773 -f 4772//4772 4773//4773 4761//4761 -f 4761//4761 4773//4773 4774//4774 -f 4761//4761 4774//4774 4762//4762 -f 4772//4772 4775//4775 4776//4776 -f 4776//4776 4777//4777 4772//4772 -f 4772//4772 4777//4777 4778//4778 -f 4772//4772 4778//4778 4757//4757 -f 4779//4779 4780//4780 4781//4781 -f 4781//4781 4780//4780 4782//4782 -f 4781//4781 4782//4782 4783//4783 -f 4782//4782 4784//4784 4783//4783 -f 4783//4783 4784//4784 4785//4785 -f 4783//4783 4785//4785 4692//4692 -f 4692//4692 4785//4785 4786//4786 -f 4692//4692 4786//4786 4787//4787 -f 4787//4787 4788//4788 4692//4692 -f 4692//4692 4788//4788 4789//4789 -f 4692//4692 4789//4789 4790//4790 -f 4790//4790 4789//4789 4791//4791 -f 4790//4790 4791//4791 4792//4792 -f 4791//4791 4793//4793 4792//4792 -f 4792//4792 4793//4793 4794//4794 -f 4792//4792 4794//4794 4795//4795 -f 4013//4013 4011//4011 4796//4796 -f 4796//4796 4011//4011 4009//4009 -f 4796//4796 4009//4009 4797//4797 -f 4797//4797 4009//4009 4007//4007 -f 4797//4797 4007//4007 4029//4029 -f 4029//4029 4027//4027 4797//4797 -f 4797//4797 4027//4027 4025//4025 -f 4797//4797 4025//4025 4798//4798 -f 4798//4798 4025//4025 4023//4023 -f 4798//4798 4023//4023 4799//4799 -f 4023//4023 4021//4021 4799//4799 -f 4799//4799 4021//4021 4019//4019 -f 4799//4799 4019//4019 4800//4800 -f 4801//4801 3981//3981 3979//3979 -f 3971//3971 4802//4802 3973//3973 -f 3973//3973 4802//4802 4803//4803 -f 3973//3973 4803//4803 3975//3975 -f 3975//3975 4803//4803 3977//3977 -f 3971//3971 3969//3969 4802//4802 -f 4802//4802 3969//3969 3967//3967 -f 4802//4802 3967//3967 4705//4705 -f 4705//4705 3967//3967 3965//3965 -f 4705//4705 3965//3965 4707//4707 -f 4707//4707 3965//3965 3963//3963 -f 4707//4707 3963//3963 4804//4804 -f 4804//4804 3963//3963 3961//3961 -f 4804//4804 3961//3961 3959//3959 -f 4805//4805 4806//4806 4807//4807 -f 4808//4808 4809//4809 4807//4807 -f 4809//4809 4810//4810 4807//4807 -f 4807//4807 4810//4810 4811//4811 -f 4807//4807 4811//4811 4805//4805 -f 4812//4812 4813//4813 4814//4814 -f 4814//4814 4813//4813 4815//4815 -f 4805//4805 4816//4816 4806//4806 -f 4806//4806 4816//4816 4817//4817 -f 4806//4806 4817//4817 4713//4713 -f 4713//4713 4817//4817 4818//4818 -f 4713//4713 4818//4818 4715//4715 -f 4715//4715 4818//4818 4819//4819 -f 4715//4715 4819//4819 4812//4812 -f 4812//4812 4819//4819 4820//4820 -f 4812//4812 4820//4820 4813//4813 -f 4821//4821 4822//4822 4680//4680 -f 4680//4680 4822//4822 4823//4823 -f 4824//4824 4825//4825 4826//4826 -f 4826//4826 4825//4825 4827//4827 -f 4826//4826 4827//4827 4828//4828 -f 4829//4829 4830//4830 4831//4831 -f 4832//4832 4833//4833 4834//4834 -f 4832//4832 4834//4834 4835//4835 -f 4828//4828 4827//4827 4836//4836 -f 4836//4836 4827//4827 4837//4837 -f 4836//4836 4837//4837 4833//4833 -f 4838//4838 4839//4839 4840//4840 -f 4723//4723 4841//4841 4842//4842 -f 4842//4842 4843//4843 4723//4723 -f 4723//4723 4843//4843 4844//4844 -f 4723//4723 4844//4844 4725//4725 -f 4725//4725 4844//4844 4845//4845 -f 4725//4725 4845//4845 4846//4846 -f 4847//4847 4848//4848 4849//4849 -f 4849//4849 4848//4848 4850//4850 -f 4849//4849 4850//4850 4851//4851 -f 4851//4851 4850//4850 4852//4852 -f 4851//4851 4852//4852 4841//4841 -f 4841//4841 4852//4852 4853//4853 -f 4841//4841 4853//4853 4842//4842 -f 4537//4537 4536//4536 4739//4739 -f 4739//4739 4536//4536 4535//4535 -f 4739//4739 4535//4535 4754//4754 -f 4754//4754 4535//4535 4534//4534 -f 4754//4754 4534//4534 4854//4854 -f 4854//4854 4534//4534 4533//4533 -f 4854//4854 4533//4533 4855//4855 -f 4855//4855 4533//4533 4544//4544 -f 4856//4856 4539//4539 4857//4857 -f 4857//4857 4539//4539 4538//4538 -f 4541//4541 4540//4540 4858//4858 -f 4541//4541 4858//4858 4542//4542 -f 4503//4503 4502//4502 4859//4859 -f 4506//4506 4505//4505 4860//4860 -f 4860//4860 4505//4505 4504//4504 -f 4860//4860 4504//4504 4861//4861 -f 4507//4507 4760//4760 4766//4766 -f 4766//4766 4760//4760 4765//4765 -f 4766//4766 4765//4765 4767//4767 -f 4500//4500 4499//4499 4862//4862 -f 4862//4862 4499//4499 4498//4498 -f 4862//4862 4498//4498 4863//4863 -f 4863//4863 4498//4498 4497//4497 -f 4863//4863 4497//4497 4766//4766 -f 4766//4766 4497//4497 4508//4508 -f 4766//4766 4508//4508 4507//4507 -f 4864//4864 4865//4865 4866//4866 -f 4866//4866 4865//4865 4867//4867 -f 4554//4554 4553//4553 4868//4868 -f 4545//4545 4556//4556 4869//4869 -f 4869//4869 4556//4556 4555//4555 -f 4870//4870 4549//4549 4548//4548 -f 4553//4553 4552//4552 4868//4868 -f 4868//4868 4552//4552 4551//4551 -f 4868//4868 4551//4551 4870//4870 -f 4870//4870 4551//4551 4550//4550 -f 4870//4870 4550//4550 4549//4549 -f 4545//4545 4869//4869 4546//4546 -f 4546//4546 4869//4869 4864//4864 -f 4546//4546 4864//4864 4547//4547 -f 4871//4871 4872//4872 4873//4873 -f 4555//4555 4554//4554 4869//4869 -f 4869//4869 4554//4554 4868//4868 -f 4869//4869 4868//4868 4874//4874 -f 4874//4874 4868//4868 4875//4875 -f 4874//4874 4875//4875 4876//4876 -f 4876//4876 4875//4875 4877//4877 -f 4876//4876 4877//4877 4873//4873 -f 4873//4873 4877//4877 4878//4878 -f 4873//4873 4878//4878 4871//4871 -f 4526//4526 4525//4525 4879//4879 -f 4880//4880 4521//4521 4881//4881 -f 4881//4881 4521//4521 4532//4532 -f 4881//4881 4532//4532 4531//4531 -f 4524//4524 4523//4523 4880//4880 -f 4880//4880 4523//4523 4522//4522 -f 4880//4880 4522//4522 4521//4521 -f 4530//4530 4529//4529 4882//4882 -f 4882//4882 4529//4529 4528//4528 -f 4882//4882 4528//4528 4879//4879 -f 4879//4879 4528//4528 4527//4527 -f 4879//4879 4527//4527 4526//4526 -f 4881//4881 4677//4677 4883//4883 -f 4883//4883 4677//4677 4676//4676 -f 4883//4883 4676//4676 4884//4884 -f 4884//4884 4676//4676 4885//4885 -f 4886//4886 4887//4887 4888//4888 -f 4872//4872 4871//4871 4889//4889 -f 4889//4889 4871//4871 4890//4890 -f 4889//4889 4890//4890 4891//4891 -f 4888//4888 4887//4887 4892//4892 -f 4892//4892 4887//4887 4893//4893 -f 4892//4892 4893//4893 4891//4891 -f 4891//4891 4893//4893 4894//4894 -f 4891//4891 4894//4894 4889//4889 -f 4525//4525 4524//4524 4879//4879 -f 4879//4879 4524//4524 4880//4880 -f 4879//4879 4880//4880 4895//4895 -f 4895//4895 4880//4880 4896//4896 -f 4895//4895 4896//4896 4878//4878 -f 4878//4878 4896//4896 4897//4897 -f 4878//4878 4897//4897 4871//4871 -f 4871//4871 4897//4897 4898//4898 -f 4871//4871 4898//4898 4890//4890 -f 4659//4659 4858//4858 4856//4856 -f 4856//4856 4858//4858 4540//4540 -f 4856//4856 4540//4540 4539//4539 -f 4662//4662 4899//4899 4663//4663 -f 4663//4663 4899//4899 4664//4664 -f 4661//4661 4660//4660 4900//4900 -f 4668//4668 4667//4667 4901//4901 -f 4901//4901 4667//4667 4902//4902 -f 4674//4674 4673//4673 4903//4903 -f 4903//4903 4673//4673 4672//4672 -f 4671//4671 4670//4670 4904//4904 -f 4904//4904 4670//4670 4669//4669 -f 4659//4659 4658//4658 4858//4858 -f 4858//4858 4658//4658 4657//4657 -f 4858//4858 4657//4657 4859//4859 -f 4859//4859 4657//4657 4861//4861 -f 4859//4859 4861//4861 4503//4503 -f 4503//4503 4861//4861 4504//4504 -f 4905//4905 4655//4655 4654//4654 -f 4906//4906 4645//4645 4644//4644 -f 4655//4655 4905//4905 4656//4656 -f 4656//4656 4905//4905 4907//4907 -f 4656//4656 4907//4907 4639//4639 -f 4639//4639 4907//4907 4908//4908 -f 4639//4639 4908//4908 4640//4640 -f 4643//4643 4642//4642 4908//4908 -f 4908//4908 4642//4642 4641//4641 -f 4908//4908 4641//4641 4640//4640 -f 4909//4909 4653//4653 4910//4910 -f 4910//4910 4653//4653 4650//4650 -f 4910//4910 4650//4650 4649//4649 -f 4649//4649 4648//4648 4910//4910 -f 4910//4910 4648//4648 4647//4647 -f 4910//4910 4647//4647 4911//4911 -f 4911//4911 4647//4647 4651//4651 -f 4911//4911 4651//4651 4912//4912 -f 4912//4912 4651//4651 4652//4652 -f 4912//4912 4652//4652 4906//4906 -f 4906//4906 4652//4652 4646//4646 -f 4906//4906 4646//4646 4645//4645 -f 4718//4718 4913//4913 4914//4914 -f 4914//4914 4913//4913 4915//4915 -f 4914//4914 4915//4915 4834//4834 -f 4834//4834 4915//4915 4916//4916 -f 4834//4834 4916//4916 4910//4910 -f 4910//4910 4916//4916 4917//4917 -f 4910//4910 4917//4917 4909//4909 -f 4918//4918 4919//4919 4806//4806 -f 4919//4919 4920//4920 4806//4806 -f 4806//4806 4920//4920 4921//4921 -f 4806//4806 4921//4921 4807//4807 -f 4807//4807 4921//4921 4922//4922 -f 4807//4807 4922//4922 4718//4718 -f 4718//4718 4922//4922 4923//4923 -f 4718//4718 4923//4923 4913//4913 -f 4924//4924 4925//4925 4926//4926 -f 4927//4927 4928//4928 4929//4929 -f 4929//4929 4928//4928 4800//4800 -f 4929//4929 4800//4800 4930//4930 -f 4930//4930 4800//4800 4926//4926 -f 4930//4930 4926//4926 4931//4931 -f 4931//4931 4926//4926 4925//4925 -f 4924//4924 4926//4926 4932//4932 -f 4932//4932 4926//4926 4933//4933 -f 4932//4932 4933//4933 4934//4934 -f 4934//4934 4933//4933 4935//4935 -f 4934//4934 4935//4935 4936//4936 -f 4936//4936 4935//4935 4937//4937 -f 4936//4936 4937//4937 4938//4938 -f 4939//4939 4940//4940 4941//4941 -f 4941//4941 4940//4940 4942//4942 -f 4941//4941 4942//4942 4943//4943 -f 4944//4944 4945//4945 4937//4937 -f 4937//4937 4945//4945 4946//4946 -f 4937//4937 4946//4946 4938//4938 -f 4947//4947 4948//4948 4939//4939 -f 4939//4939 4948//4948 4949//4949 -f 4939//4939 4949//4949 4940//4940 -f 4950//4950 4948//4948 4951//4951 -f 4951//4951 4948//4948 4947//4947 -f 4951//4951 4947//4947 4952//4952 -f 4953//4953 4804//4804 4801//4801 -f 4801//4801 4804//4804 3959//3959 -f 4801//4801 3959//3959 3981//3981 -f 4799//4799 4031//4031 4053//4053 -f 4043//4043 4041//4041 4954//4954 -f 4031//4031 4799//4799 4033//4033 -f 4033//4033 4799//4799 4800//4800 -f 4033//4033 4800//4800 4035//4035 -f 4035//4035 4800//4800 4037//4037 -f 4037//4037 4800//4800 4928//4928 -f 4037//4037 4928//4928 4039//4039 -f 4053//4053 4051//4051 4799//4799 -f 4799//4799 4051//4051 4049//4049 -f 4799//4799 4049//4049 4955//4955 -f 4955//4955 4049//4049 4047//4047 -f 4955//4955 4047//4047 4045//4045 -f 4045//4045 4043//4043 4955//4955 -f 4955//4955 4043//4043 4954//4954 -f 4955//4955 4954//4954 4702//4702 -f 4702//4702 4954//4954 4956//4956 -f 4702//4702 4956//4956 4699//4699 -f 4699//4699 4956//4956 4957//4957 -f 4699//4699 4957//4957 4801//4801 -f 4801//4801 4957//4957 4958//4958 -f 4801//4801 4958//4958 4953//4953 -f 4928//4928 4959//4959 4039//4039 -f 4039//4039 4959//4959 4960//4960 -f 4039//4039 4960//4960 4041//4041 -f 4041//4041 4960//4960 4961//4961 -f 4041//4041 4961//4961 4954//4954 -f 4962//4962 4963//4963 4964//4964 -f 4964//4964 4963//4963 4965//4965 -f 4964//4964 4965//4965 4728//4728 -f 4728//4728 4965//4965 4966//4966 -f 4728//4728 4966//4966 4729//4729 -f 4967//4967 4968//4968 4969//4969 -f 4969//4969 4968//4968 4970//4970 -f 4969//4969 4970//4970 4971//4971 -f 4736//4736 4735//4735 4972//4972 -f 4972//4972 4735//4735 4973//4973 -f 4972//4972 4973//4973 4971//4971 -f 4971//4971 4973//4973 4974//4974 -f 4971//4971 4974//4974 4969//4969 -f 4695//4695 4975//4975 4696//4696 -f 4696//4696 4975//4975 4976//4976 -f 4696//4696 4976//4976 4977//4977 -f 4977//4977 4976//4976 4978//4978 -f 4977//4977 4978//4978 4979//4979 -f 4979//4979 4978//4978 4980//4980 -f 4980//4980 4978//4978 4981//4981 -f 4980//4980 4981//4981 4982//4982 -f 4982//4982 4981//4981 4983//4983 -f 4982//4982 4983//4983 4984//4984 -f 4984//4984 4983//4983 4985//4985 -f 4984//4984 4985//4985 4986//4986 -f 4783//4783 4987//4987 4988//4988 -f 4691//4691 4989//4989 4692//4692 -f 4692//4692 4989//4989 4990//4990 -f 4692//4692 4990//4990 4783//4783 -f 4783//4783 4990//4990 4991//4991 -f 4783//4783 4991//4991 4987//4987 -f 4992//4992 4993//4993 4680//4680 -f 4680//4680 4993//4993 4825//4825 -f 4680//4680 4825//4825 4821//4821 -f 4821//4821 4825//4825 4824//4824 -f 4993//4993 4994//4994 4825//4825 -f 4825//4825 4994//4994 4995//4995 -f 4825//4825 4995//4995 4996//4996 -f 4996//4996 4995//4995 4997//4997 -f 4996//4996 4997//4997 4998//4998 -f 4998//4998 4999//4999 4996//4996 -f 4996//4996 4999//4999 5000//5000 -f 4996//4996 5000//5000 4679//4679 -f 4679//4679 5000//5000 5001//5001 -f 5001//5001 5002//5002 4679//4679 -f 4679//4679 5002//5002 5003//5003 -f 4679//4679 5003//5003 4680//4680 -f 4680//4680 5003//5003 5004//5004 -f 4680//4680 5004//5004 4992//4992 -f 4834//4834 5005//5005 5006//5006 -f 4914//4914 5007//5007 5008//5008 -f 4833//4833 4837//4837 4834//4834 -f 4834//4834 4837//4837 5009//5009 -f 4834//4834 5009//5009 5005//5005 -f 5006//5006 5010//5010 4834//4834 -f 4834//4834 5010//5010 5011//5011 -f 4834//4834 5011//5011 4914//4914 -f 4914//4914 5011//5011 5012//5012 -f 4914//4914 5012//5012 5007//5007 -f 5013//5013 5014//5014 5015//5015 -f 5015//5015 5014//5014 5016//5016 -f 5015//5015 5016//5016 4837//4837 -f 4837//4837 5016//5016 5017//5017 -f 4837//4837 5017//5017 5009//5009 -f 4716//4716 4718//4718 5018//5018 -f 5018//5018 4718//4718 4914//4914 -f 5018//5018 4914//4914 5015//5015 -f 5015//5015 4914//4914 5008//5008 -f 5015//5015 5008//5008 5013//5013 -f 4851//4851 4996//4996 4849//4849 -f 4849//4849 4996//4996 4679//4679 -f 4849//4849 4679//4679 5019//5019 -f 5019//5019 4679//4679 4678//4678 -f 4680//4680 4866//4866 4678//4678 -f 4678//4678 4866//4866 4867//4867 -f 4678//4678 4867//4867 5019//5019 -f 5019//5019 4867//4867 5020//5020 -f 5019//5019 5020//5020 5021//5021 -f 5021//5021 5020//5020 5022//5022 -f 5021//5021 5022//5022 5023//5023 -f 5023//5023 5022//5022 5024//5024 -f 5023//5023 5024//5024 5025//5025 -f 5025//5025 5024//5024 5026//5026 -f 5025//5025 5026//5026 4894//4894 -f 4894//4894 5026//5026 5027//5027 -f 4894//4894 5027//5027 4889//4889 -f 4889//4889 5027//5027 5028//5028 -f 4889//4889 5028//5028 4872//4872 -f 4823//4823 4829//4829 4680//4680 -f 4680//4680 4829//4829 4831//4831 -f 4680//4680 4831//4831 4866//4866 -f 4866//4866 4831//4831 4870//4870 -f 4866//4866 4870//4870 4864//4864 -f 4864//4864 4870//4870 4548//4548 -f 4864//4864 4548//4548 4547//4547 -f 4721//4721 4685//4685 4718//4718 -f 4718//4718 4685//4685 4687//4687 -f 4718//4718 4687//4687 4807//4807 -f 4807//4807 4687//4687 4814//4814 -f 4807//4807 4814//4814 4808//4808 -f 4808//4808 4814//4814 4815//4815 -f 4683//4683 5029//5029 4684//4684 -f 4684//4684 5029//5029 5030//5030 -f 4684//4684 5030//5030 4741//4741 -f 4741//4741 5030//5030 5031//5031 -f 4741//4741 5031//5031 4739//4739 -f 4739//4739 5031//5031 4857//4857 -f 4739//4739 4857//4857 4537//4537 -f 4537//4537 4857//4857 4538//4538 -f 4568//4568 4567//4567 4964//4964 -f 4561//4561 4560//4560 5032//5032 -f 5032//5032 4560//4560 4728//4728 -f 5032//5032 4728//4728 4840//4840 -f 4840//4840 4728//4728 4725//4725 -f 4840//4840 4725//4725 4838//4838 -f 4838//4838 4725//4725 4846//4846 -f 4560//4560 4559//4559 4728//4728 -f 4728//4728 4559//4559 4558//4558 -f 4728//4728 4558//4558 4964//4964 -f 4964//4964 4558//4558 4557//4557 -f 4964//4964 4557//4557 4568//4568 -f 5033//5033 4566//4566 4565//4565 -f 4565//4565 4564//4564 5033//5033 -f 5033//5033 4564//4564 4563//4563 -f 5033//5033 4563//4563 5032//5032 -f 5032//5032 4563//4563 4562//4562 -f 5032//5032 4562//4562 4561//4561 -f 5029//5029 4972//4972 5030//5030 -f 5030//5030 4972//4972 4971//4971 -f 5030//5030 4971//4971 5031//5031 -f 5031//5031 4971//4971 4970//4970 -f 5031//5031 4970//4970 4857//4857 -f 4857//4857 4970//4970 4968//4968 -f 4857//4857 4968//4968 4856//4856 -f 4856//4856 4968//4968 4900//4900 -f 4856//4856 4900//4900 4659//4659 -f 4659//4659 4900//4900 4660//4660 -f 4967//4967 4962//4962 4968//4968 -f 4968//4968 4962//4962 4964//4964 -f 4968//4968 4964//4964 4900//4900 -f 4900//4900 4964//4964 4899//4899 -f 4900//4900 4899//4899 4661//4661 -f 4661//4661 4899//4899 4662//4662 -f 4567//4567 4566//4566 4964//4964 -f 4964//4964 4566//4566 5033//5033 -f 4964//4964 5033//5033 4899//4899 -f 4899//4899 5033//5033 5034//5034 -f 4899//4899 5034//5034 4664//4664 -f 4664//4664 5034//5034 5035//5035 -f 4664//4664 5035//5035 4665//4665 -f 4665//4665 5035//5035 4902//4902 -f 4665//4665 4902//4902 4666//4666 -f 4666//4666 4902//4902 4667//4667 -f 4544//4544 4543//4543 4855//4855 -f 4855//4855 4543//4543 5036//5036 -f 4855//4855 5036//5036 4862//4862 -f 4862//4862 5036//5036 5037//5037 -f 4862//4862 5037//5037 4500//4500 -f 4500//4500 5037//5037 4501//4501 -f 4543//4543 4542//4542 5036//5036 -f 5036//5036 4542//4542 4858//4858 -f 5036//5036 4858//4858 5037//5037 -f 5037//5037 4858//4858 4859//4859 -f 5037//5037 4859//4859 4501//4501 -f 4501//4501 4859//4859 4502//4502 -f 4644//4644 4643//4643 4906//4906 -f 4906//4906 4643//4643 4908//4908 -f 4906//4906 4908//4908 4937//4937 -f 4937//4937 4908//4908 4941//4941 -f 4937//4937 4941//4941 4944//4944 -f 4944//4944 4941//4941 4943//4943 -f 4672//4672 4671//4671 4903//4903 -f 4903//4903 4671//4671 4904//4904 -f 4903//4903 4904//4904 4985//4985 -f 4985//4985 4904//4904 5038//5038 -f 4654//4654 4918//4918 4905//4905 -f 4905//4905 4918//4918 4806//4806 -f 4905//4905 4806//4806 4907//4907 -f 4907//4907 4806//4806 4713//4713 -f 4907//4907 4713//4713 4908//4908 -f 4908//4908 4713//4713 4711//4711 -f 4908//4908 4711//4711 4941//4941 -f 4941//4941 4711//4711 4709//4709 -f 4941//4941 4709//4709 4939//4939 -f 4939//4939 4709//4709 4707//4707 -f 4939//4939 4707//4707 4947//4947 -f 4947//4947 4707//4707 4804//4804 -f 4947//4947 4804//4804 4952//4952 -f 4952//4952 4804//4804 4953//4953 -f 5039//5039 4519//4519 5040//5040 -f 5040//5040 4519//4519 4518//4518 -f 5040//5040 4518//4518 4517//4517 -f 4512//4512 4511//4511 5038//5038 -f 4517//4517 4516//4516 5040//5040 -f 5040//5040 4516//4516 4515//4515 -f 5040//5040 4515//4515 5041//5041 -f 5041//5041 4515//4515 4514//4514 -f 5041//5041 4514//4514 4513//4513 -f 4513//4513 4512//4512 5041//5041 -f 5041//5041 4512//4512 5038//5038 -f 5041//5041 5038//5038 4901//4901 -f 4901//4901 5038//5038 4904//4904 -f 4901//4901 4904//4904 4668//4668 -f 4668//4668 4904//4904 4669//4669 -f 4511//4511 4510//4510 5038//5038 -f 5038//5038 4510//4510 4509//4509 -f 5038//5038 4509//4509 5039//5039 -f 5039//5039 4509//4509 4520//4520 -f 5039//5039 4520//4520 4519//4519 -f 4507//4507 4506//4506 4760//4760 -f 4760//4760 4506//4506 4860//4860 -f 4760//4760 4860//4860 4761//4761 -f 4761//4761 4860//4860 5042//5042 -f 4761//4761 5042//5042 4772//4772 -f 4772//4772 5042//5042 5043//5043 -f 4772//4772 5043//5043 4775//4775 -f 4775//4775 5043//5043 5044//5044 -f 4986//4986 4985//4985 5045//5045 -f 5045//5045 4985//4985 5038//5038 -f 5045//5045 5038//5038 4988//4988 -f 4988//4988 5038//5038 5039//5039 -f 4988//4988 5039//5039 4783//4783 -f 4783//4783 5039//5039 5040//5040 -f 4783//4783 5040//5040 4781//4781 -f 4839//4839 4847//4847 4840//4840 -f 4840//4840 4847//4847 4849//4849 -f 4840//4840 4849//4849 5032//5032 -f 5032//5032 4849//4849 5019//5019 -f 5032//5032 5019//5019 5033//5033 -f 5033//5033 5019//5019 5021//5021 -f 5033//5033 5021//5021 5034//5034 -f 5034//5034 5021//5021 5023//5023 -f 5034//5034 5023//5023 5035//5035 -f 5035//5035 5023//5023 5025//5025 -f 5035//5035 5025//5025 4902//4902 -f 4902//4902 5025//5025 4894//4894 -f 4902//4902 4894//4894 4901//4901 -f 4901//4901 4894//4894 4893//4893 -f 4901//4901 4893//4893 5041//5041 -f 5041//5041 4893//4893 4887//4887 -f 5041//5041 4887//4887 5040//5040 -f 5040//5040 4887//4887 4886//4886 -f 5040//5040 4886//4886 4781//4781 -f 4781//4781 4886//4886 4795//4795 -f 4781//4781 4795//4795 4779//4779 -f 4779//4779 4795//4795 4794//4794 -f 4015//4015 4013//4013 4681//4681 -f 4681//4681 4013//4013 4796//4796 -f 4681//4681 4796//4796 4882//4882 -f 4830//4830 4835//4835 4831//4831 -f 4831//4831 4835//4835 4834//4834 -f 4831//4831 4834//4834 4870//4870 -f 4870//4870 4834//4834 4910//4910 -f 4870//4870 4910//4910 4868//4868 -f 4868//4868 4910//4910 4911//4911 -f 4868//4868 4911//4911 4875//4875 -f 4875//4875 4911//4911 4912//4912 -f 4875//4875 4912//4912 4877//4877 -f 4877//4877 4912//4912 4906//4906 -f 4877//4877 4906//4906 4878//4878 -f 4878//4878 4906//4906 4937//4937 -f 4878//4878 4937//4937 4895//4895 -f 4895//4895 4937//4937 4935//4935 -f 4895//4895 4935//4935 4879//4879 -f 4879//4879 4935//4935 4933//4933 -f 4879//4879 4933//4933 4882//4882 -f 4882//4882 4933//4933 4926//4926 -f 4882//4882 4926//4926 4681//4681 -f 4681//4681 4926//4926 4800//4800 -f 4681//4681 4800//4800 4017//4017 -f 4017//4017 4800//4800 4019//4019 -f 3979//3979 3977//3977 4801//4801 -f 4801//4801 3977//3977 4803//4803 -f 4801//4801 4803//4803 4699//4699 -f 4699//4699 4803//4803 5046//5046 -f 4699//4699 5046//5046 4697//4697 -f 4657//4657 4674//4674 4861//4861 -f 4861//4861 4674//4674 4903//4903 -f 4861//4861 4903//4903 4860//4860 -f 4860//4860 4903//4903 4985//4985 -f 4860//4860 4985//4985 5042//5042 -f 5042//5042 4985//4985 4983//4983 -f 5042//5042 4983//4983 5043//5043 -f 5043//5043 4983//4983 4981//4981 -f 5043//5043 4981//4981 5044//5044 -f 5044//5044 4981//4981 4978//4978 -f 4888//4888 4885//4885 4886//4886 -f 4886//4886 4885//4885 4676//4676 -f 4886//4886 4676//4676 4795//4795 -f 4795//4795 4676//4676 4675//4675 -f 4795//4795 4675//4675 4792//4792 -f 4792//4792 4675//4675 5047//5047 -f 4796//4796 3993//3993 3991//3991 -f 4675//4675 3989//3989 3987//3987 -f 4531//4531 4530//4530 4881//4881 -f 4881//4881 4530//4530 4882//4882 -f 4881//4881 4882//4882 4677//4677 -f 4677//4677 4882//4882 4796//4796 -f 4677//4677 4796//4796 4675//4675 -f 4675//4675 4796//4796 3991//3991 -f 4675//4675 3991//3991 3989//3989 -f 3993//3993 4796//4796 3995//3995 -f 3995//3995 4796//4796 4797//4797 -f 3995//3995 4797//4797 3997//3997 -f 3987//3987 3985//3985 4675//4675 -f 4675//4675 3985//3985 3983//3983 -f 4675//4675 3983//3983 5047//5047 -f 5047//5047 3983//3983 4005//4005 -f 4005//4005 4003//4003 5047//5047 -f 5047//5047 4003//4003 4001//4001 -f 5047//5047 4001//4001 4797//4797 -f 4797//4797 4001//4001 3999//3999 -f 4797//4797 3999//3999 3997//3997 -f 4688//4688 4690//4690 4702//4702 -f 4702//4702 4690//4690 5048//5048 -f 4702//4702 5048//5048 4955//4955 -f 4955//4955 5048//5048 5049//5049 -f 4955//4955 5049//5049 4799//4799 -f 4799//4799 5049//5049 5050//5050 -f 4799//4799 5050//5050 4798//4798 -f 4798//4798 5050//5050 5051//5051 -f 4798//4798 5051//5051 4797//4797 -f 4797//4797 5051//5051 5052//5052 -f 4797//4797 5052//5052 5047//5047 -f 5047//5047 5052//5052 5053//5053 -f 5047//5047 5053//5053 4792//4792 -f 4792//4792 5053//5053 5054//5054 -f 4792//4792 5054//5054 4790//4790 -f 4790//4790 5054//5054 5055//5055 -f 4790//4790 5055//5055 4692//4692 -f 4692//4692 5055//5055 5056//5056 -f 4692//4692 5056//5056 4693//4693 -f 4288//4288 4929//4929 4289//4289 -f 4289//4289 4929//4929 4930//4930 -f 4289//4289 4930//4930 4291//4291 -f 4291//4291 4930//4930 4931//4931 -f 4291//4291 4931//4931 4292//4292 -f 4292//4292 4931//4931 4925//4925 -f 4292//4292 4925//4925 4286//4286 -f 4286//4286 4925//4925 4924//4924 -f 4274//4274 4936//4936 4279//4279 -f 4279//4279 4936//4936 4938//4938 -f 4279//4279 4938//4938 4280//4280 -f 4280//4280 4938//4938 4946//4946 -f 4280//4280 4946//4946 4281//4281 -f 4281//4281 4946//4946 4945//4945 -f 4287//4287 4286//4286 4924//4924 -f 4936//4936 4274//4274 4934//4934 -f 4934//4934 4274//4274 4287//4287 -f 4934//4934 4287//4287 4932//4932 -f 4932//4932 4287//4287 4924//4924 -f 4277//4277 4944//4944 4278//4278 -f 4278//4278 4944//4944 4943//4943 -f 4278//4278 4943//4943 4284//4284 -f 4284//4284 4943//4943 4942//4942 -f 4284//4284 4942//4942 4283//4283 -f 4283//4283 4942//4942 4940//4940 -f 4281//4281 4945//4945 4277//4277 -f 4277//4277 4945//4945 4944//4944 -f 4950//4950 4304//4304 4948//4948 -f 4948//4948 4304//4304 4282//4282 -f 4948//4948 4282//4282 4949//4949 -f 4949//4949 4282//4282 4283//4283 -f 4949//4949 4283//4283 4940//4940 -f 4929//4929 4288//4288 4927//4927 -f 4927//4927 4288//4288 4300//4300 -f 4304//4304 4950//4950 4303//4303 -f 4303//4303 4950//4950 4951//4951 -f 4303//4303 4951//4951 4302//4302 -f 4302//4302 4951//4951 4952//4952 -f 4302//4302 4952//4952 4301//4301 -f 4301//4301 4952//4952 4953//4953 -f 4301//4301 4953//4953 4126//4126 -f 4126//4126 4953//4953 4958//4958 -f 4126//4126 4958//4958 4125//4125 -f 4125//4125 4958//4958 4957//4957 -f 4125//4125 4957//4957 4124//4124 -f 4124//4124 4957//4957 4956//4956 -f 4124//4124 4956//4956 4122//4122 -f 4122//4122 4956//4956 4954//4954 -f 4122//4122 4954//4954 4295//4295 -f 4295//4295 4954//4954 4961//4961 -f 4295//4295 4961//4961 4297//4297 -f 4297//4297 4961//4961 4960//4960 -f 4297//4297 4960//4960 4298//4298 -f 4298//4298 4960//4960 4959//4959 -f 4298//4298 4959//4959 4299//4299 -f 4299//4299 4959//4959 4928//4928 -f 4299//4299 4928//4928 4300//4300 -f 4300//4300 4928//4928 4927//4927 -f 4096//4096 4653//4653 4097//4097 -f 4097//4097 4653//4653 4909//4909 -f 4923//4923 4229//4229 4913//4913 -f 4913//4913 4229//4229 4237//4237 -f 4913//4913 4237//4237 4915//4915 -f 4915//4915 4237//4237 4238//4238 -f 4915//4915 4238//4238 4916//4916 -f 4916//4916 4238//4238 4242//4242 -f 4916//4916 4242//4242 4917//4917 -f 4917//4917 4242//4242 4243//4243 -f 4917//4917 4243//4243 4909//4909 -f 4909//4909 4243//4243 4247//4247 -f 4909//4909 4247//4247 4097//4097 -f 4654//4654 4102//4102 4918//4918 -f 4918//4918 4102//4102 4101//4101 -f 4918//4918 4101//4101 4919//4919 -f 4919//4919 4101//4101 4223//4223 -f 4919//4919 4223//4223 4920//4920 -f 4920//4920 4223//4223 4226//4226 -f 4920//4920 4226//4226 4921//4921 -f 4921//4921 4226//4226 4225//4225 -f 4921//4921 4225//4225 4922//4922 -f 4922//4922 4225//4225 4224//4224 -f 4922//4922 4224//4224 4923//4923 -f 4923//4923 4224//4224 4228//4228 -f 4923//4923 4228//4228 4229//4229 -f 4351//4351 4758//4758 4349//4349 -f 4349//4349 4758//4758 4768//4768 -f 4349//4349 4768//4768 4354//4354 -f 4354//4354 4768//4768 4767//4767 -f 4354//4354 4767//4767 4355//4355 -f 4355//4355 4767//4767 4765//4765 -f 4355//4355 4765//4765 4356//4356 -f 4356//4356 4765//4765 4764//4764 -f 4356//4356 4764//4764 4357//4357 -f 4357//4357 4764//4764 4763//4763 -f 4357//4357 4763//4763 4086//4086 -f 4086//4086 4763//4763 4762//4762 -f 4086//4086 4762//4762 4087//4087 -f 4087//4087 4762//4762 4774//4774 -f 4087//4087 4774//4774 4360//4360 -f 4360//4360 4774//4774 4773//4773 -f 4360//4360 4773//4773 4359//4359 -f 4359//4359 4773//4773 4771//4771 -f 4359//4359 4771//4771 4358//4358 -f 4358//4358 4771//4771 4770//4770 -f 4358//4358 4770//4770 4353//4353 -f 4353//4353 4770//4770 4759//4759 -f 4353//4353 4759//4759 4351//4351 -f 4351//4351 4759//4759 4758//4758 -f 4395//4395 4751//4751 4396//4396 -f 4396//4396 4751//4751 4749//4749 -f 4396//4396 4749//4749 4397//4397 -f 4397//4397 4749//4749 4748//4748 -f 4397//4397 4748//4748 4398//4398 -f 4398//4398 4748//4748 4744//4744 -f 4398//4398 4744//4744 4399//4399 -f 4399//4399 4744//4744 4743//4743 -f 4399//4399 4743//4743 4400//4400 -f 4400//4400 4743//4743 4742//4742 -f 4400//4400 4742//4742 4390//4390 -f 4390//4390 4742//4742 4740//4740 -f 4390//4390 4740//4740 4391//4391 -f 4391//4391 4740//4740 4738//4738 -f 4391//4391 4738//4738 4392//4392 -f 4392//4392 4738//4738 4737//4737 -f 4392//4392 4737//4737 4393//4393 -f 4393//4393 4737//4737 4756//4756 -f 4393//4393 4756//4756 4394//4394 -f 4394//4394 4756//4756 4755//4755 -f 4394//4394 4755//4755 4388//4388 -f 4388//4388 4755//4755 4753//4753 -f 4388//4388 4753//4753 4395//4395 -f 4395//4395 4753//4753 4751//4751 -f 4447//4447 4307//4307 4885//4885 -f 4891//4891 4448//4448 4892//4892 -f 4892//4892 4448//4448 4447//4447 -f 4892//4892 4447//4447 4888//4888 -f 4888//4888 4447//4447 4885//4885 -f 4885//4885 4307//4307 4884//4884 -f 4884//4884 4307//4307 4306//4306 -f 4884//4884 4306//4306 4883//4883 -f 4883//4883 4306//4306 4308//4308 -f 4883//4883 4308//4308 4881//4881 -f 4881//4881 4308//4308 4313//4313 -f 4314//4314 4324//4324 4897//4897 -f 4881//4881 4313//4313 4880//4880 -f 4880//4880 4313//4313 4314//4314 -f 4880//4880 4314//4314 4896//4896 -f 4896//4896 4314//4314 4897//4897 -f 4897//4897 4324//4324 4898//4898 -f 4898//4898 4324//4324 4450//4450 -f 4898//4898 4450//4450 4890//4890 -f 4890//4890 4450//4450 4449//4449 -f 4890//4890 4449//4449 4891//4891 -f 4891//4891 4449//4449 4448//4448 -f 4196//4196 5027//5027 4195//4195 -f 4195//4195 5027//5027 5026//5026 -f 4195//4195 5026//5026 4193//4193 -f 4193//4193 5026//5026 5024//5024 -f 4193//4193 5024//5024 4191//4191 -f 4191//4191 5024//5024 5022//5022 -f 4191//4191 5022//5022 4188//4188 -f 4188//4188 5022//5022 5020//5020 -f 5027//5027 4196//4196 5028//5028 -f 5028//5028 4196//4196 4198//4198 -f 5028//5028 4198//4198 4872//4872 -f 4872//4872 4198//4198 4106//4106 -f 4872//4872 4106//4106 4873//4873 -f 4873//4873 4106//4106 4200//4200 -f 4876//4876 4873//4873 4200//4200 -f 4178//4178 4171//4171 4864//4864 -f 4864//4864 4869//4869 4178//4178 -f 4178//4178 4869//4869 4874//4874 -f 4178//4178 4874//4874 4204//4204 -f 4204//4204 4874//4874 4876//4876 -f 4204//4204 4876//4876 4199//4199 -f 4199//4199 4876//4876 4200//4200 -f 4864//4864 4171//4171 4865//4865 -f 4865//4865 4171//4171 4170//4170 -f 4865//4865 4170//4170 4867//4867 -f 4867//4867 4170//4170 4187//4187 -f 4867//4867 4187//4187 5020//5020 -f 5020//5020 4187//4187 4188//4188 -f 5057//5057 5005//5005 5058//5058 -f 5058//5058 5005//5005 5009//5009 -f 5058//5058 5009//5009 5059//5059 -f 5059//5059 5009//5009 5017//5017 -f 5059//5059 5017//5017 5060//5060 -f 5060//5060 5017//5017 5016//5016 -f 5060//5060 5016//5016 5061//5061 -f 5061//5061 5016//5016 5014//5014 -f 5061//5061 5014//5014 5062//5062 -f 5062//5062 5014//5014 5013//5013 -f 5062//5062 5013//5013 5063//5063 -f 5063//5063 5013//5013 5008//5008 -f 5063//5063 5008//5008 5064//5064 -f 5064//5064 5008//5008 5007//5007 -f 5064//5064 5007//5007 5065//5065 -f 5065//5065 5007//5007 5012//5012 -f 5065//5065 5012//5012 5066//5066 -f 5066//5066 5012//5012 5011//5011 -f 5066//5066 5011//5011 5067//5067 -f 5067//5067 5011//5011 5010//5010 -f 5067//5067 5010//5010 5068//5068 -f 5068//5068 5010//5010 5006//5006 -f 5068//5068 5006//5006 5057//5057 -f 5057//5057 5006//5006 5005//5005 -f 5069//5069 4822//4822 5070//5070 -f 5070//5070 4822//4822 4821//4821 -f 5070//5070 4821//4821 5071//5071 -f 5071//5071 4821//4821 4824//4824 -f 5071//5071 4824//4824 5072//5072 -f 5072//5072 4824//4824 4826//4826 -f 5072//5072 4826//4826 5073//5073 -f 5073//5073 4826//4826 4828//4828 -f 5073//5073 4828//4828 5074//5074 -f 5074//5074 4828//4828 4836//4836 -f 5074//5074 4836//4836 5075//5075 -f 5075//5075 4836//4836 4833//4833 -f 5075//5075 4833//4833 5076//5076 -f 5076//5076 4833//4833 4832//4832 -f 5076//5076 4832//4832 5077//5077 -f 5077//5077 4832//4832 4835//4835 -f 5077//5077 4835//4835 5078//5078 -f 5078//5078 4835//4835 4830//4830 -f 5078//5078 4830//4830 5079//5079 -f 5079//5079 4830//4830 4829//4829 -f 5079//5079 4829//4829 5080//5080 -f 5080//5080 4829//4829 4823//4823 -f 5080//5080 4823//4823 5069//5069 -f 5069//5069 4823//4823 4822//4822 -f 5081//5081 4805//4805 5082//5082 -f 5082//5082 4805//4805 4811//4811 -f 5082//5082 4811//4811 5083//5083 -f 5083//5083 4811//4811 4810//4810 -f 5083//5083 4810//4810 5084//5084 -f 5084//5084 4810//4810 4809//4809 -f 5084//5084 4809//4809 5085//5085 -f 5085//5085 4809//4809 4808//4808 -f 5085//5085 4808//4808 5086//5086 -f 5086//5086 4808//4808 4815//4815 -f 5086//5086 4815//4815 5087//5087 -f 5087//5087 4815//4815 4813//4813 -f 5087//5087 4813//4813 5088//5088 -f 5088//5088 4813//4813 4820//4820 -f 5088//5088 4820//4820 5089//5089 -f 5089//5089 4820//4820 4819//4819 -f 5089//5089 4819//4819 5090//5090 -f 5090//5090 4819//4819 4818//4818 -f 5090//5090 4818//4818 5091//5091 -f 5091//5091 4818//4818 4817//4817 -f 5091//5091 4817//4817 5092//5092 -f 5092//5092 4817//4817 4816//4816 -f 5092//5092 4816//4816 5081//5081 -f 5081//5081 4816//4816 4805//4805 -f 5093//5093 5000//5000 5094//5094 -f 5094//5094 5000//5000 4999//4999 -f 5094//5094 4999//4999 5095//5095 -f 5095//5095 4999//4999 4998//4998 -f 5095//5095 4998//4998 5096//5096 -f 5096//5096 4998//4998 4997//4997 -f 5096//5096 4997//4997 5097//5097 -f 5097//5097 4997//4997 4995//4995 -f 5097//5097 4995//4995 5098//5098 -f 5098//5098 4995//4995 4994//4994 -f 5098//5098 4994//4994 5099//5099 -f 5099//5099 4994//4994 4993//4993 -f 5099//5099 4993//4993 5100//5100 -f 5100//5100 4993//4993 4992//4992 -f 5100//5100 4992//4992 5101//5101 -f 5101//5101 4992//4992 5004//5004 -f 5101//5101 5004//5004 5102//5102 -f 5102//5102 5004//5004 5003//5003 -f 5102//5102 5003//5003 5103//5103 -f 5103//5103 5003//5003 5002//5002 -f 5103//5103 5002//5002 5104//5104 -f 5104//5104 5002//5002 5001//5001 -f 5104//5104 5001//5001 5093//5093 -f 5093//5093 5001//5001 5000//5000 -f 4168//4168 4845//4845 4169//4169 -f 4169//4169 4845//4845 4844//4844 -f 4169//4169 4844//4844 4165//4165 -f 4165//4165 4844//4844 4843//4843 -f 4165//4165 4843//4843 4166//4166 -f 4166//4166 4843//4843 4842//4842 -f 4166//4166 4842//4842 4157//4157 -f 4157//4157 4842//4842 4853//4853 -f 4157//4157 4853//4853 4159//4159 -f 4159//4159 4853//4853 4852//4852 -f 4159//4159 4852//4852 4152//4152 -f 4152//4152 4852//4852 4850//4850 -f 4152//4152 4850//4850 4153//4153 -f 4153//4153 4850//4850 4848//4848 -f 4153//4153 4848//4848 4160//4160 -f 4160//4160 4848//4848 4847//4847 -f 4160//4160 4847//4847 4161//4161 -f 4161//4161 4847//4847 4839//4839 -f 4161//4161 4839//4839 4163//4163 -f 4163//4163 4839//4839 4838//4838 -f 4163//4163 4838//4838 4167//4167 -f 4167//4167 4838//4838 4846//4846 -f 4167//4167 4846//4846 4168//4168 -f 4168//4168 4846//4846 4845//4845 -f 4144//4144 4786//4786 4146//4146 -f 4146//4146 4786//4786 4785//4785 -f 4146//4146 4785//4785 4147//4147 -f 4147//4147 4785//4785 4784//4784 -f 4147//4147 4784//4784 4107//4107 -f 4107//4107 4784//4784 4782//4782 -f 4107//4107 4782//4782 4108//4108 -f 4108//4108 4782//4782 4780//4780 -f 4108//4108 4780//4780 4141//4141 -f 4141//4141 4780//4780 4779//4779 -f 4141//4141 4779//4779 4138//4138 -f 4138//4138 4779//4779 4794//4794 -f 4138//4138 4794//4794 4139//4139 -f 4139//4139 4794//4794 4793//4793 -f 4139//4139 4793//4793 4149//4149 -f 4149//4149 4793//4793 4791//4791 -f 4149//4149 4791//4791 4150//4150 -f 4150//4150 4791//4791 4789//4789 -f 4150//4150 4789//4789 4151//4151 -f 4151//4151 4789//4789 4788//4788 -f 4151//4151 4788//4788 4143//4143 -f 4143//4143 4788//4788 4787//4787 -f 4143//4143 4787//4787 4144//4144 -f 4144//4144 4787//4787 4786//4786 -f 4585//4585 4628//4628 5056//5056 -f 5056//5056 4628//4628 4693//4693 -f 4628//4628 4629//4629 4693//4693 -f 4693//4693 4629//4629 4694//4694 -f 4976//4976 4617//4617 4978//4978 -f 4978//4978 4617//4617 4616//4616 -f 4978//4978 4616//4616 5044//5044 -f 5044//5044 4616//4616 4775//4775 -f 4775//4775 4616//4616 4776//4776 -f 4776//4776 4616//4616 4614//4614 -f 4776//4776 4614//4614 4777//4777 -f 4777//4777 4614//4614 4608//4608 -f 4777//4777 4608//4608 4778//4778 -f 4778//4778 4608//4608 4606//4606 -f 4778//4778 4606//4606 4757//4757 -f 4757//4757 4606//4606 4604//4604 -f 4757//4757 4604//4604 4769//4769 -f 4769//4769 4604//4604 4603//4603 -f 4766//4766 4769//4769 4603//4603 -f 4752//4752 4754//4754 4592//4592 -f 4592//4592 4754//4754 4854//4854 -f 4854//4854 4855//4855 4592//4592 -f 4592//4592 4855//4855 4862//4862 -f 4592//4592 4862//4862 4603//4603 -f 4603//4603 4862//4862 4863//4863 -f 4603//4603 4863//4863 4766//4766 -f 4752//4752 4592//4592 4750//4750 -f 4750//4750 4592//4592 4591//4591 -f 4750//4750 4591//4591 4745//4745 -f 4745//4745 4591//4591 4590//4590 -f 4625//4625 4683//4683 4602//4602 -f 4602//4602 4683//4683 4682//4682 -f 4602//4602 4682//4682 4600//4600 -f 4600//4600 4682//4682 4747//4747 -f 4600//4600 4747//4747 4590//4590 -f 4590//4590 4747//4747 4746//4746 -f 4590//4590 4746//4746 4745//4745 -f 4625//4625 4626//4626 4736//4736 -f 4736//4736 4972//4972 4625//4625 -f 4625//4625 4972//4972 5029//5029 -f 4625//4625 5029//5029 4683//4683 -f 4611//4611 4610//4610 4732//4732 -f 4732//4732 4610//4610 4724//4724 -f 4610//4610 4580//4580 4724//4724 -f 4724//4724 4580//4580 4722//4722 -f 4716//4716 5018//5018 4581//4581 -f 4581//4581 5018//5018 5015//5015 -f 4581//4581 5015//5015 4837//4837 -f 4837//4837 4827//4827 4581//4581 -f 4581//4581 4827//4827 4825//4825 -f 4581//4581 4825//4825 4580//4580 -f 4580//4580 4825//4825 4996//4996 -f 4580//4580 4996//4996 4851//4851 -f 4851//4851 4841//4841 4580//4580 -f 4580//4580 4841//4841 4723//4723 -f 4580//4580 4723//4723 4722//4722 -f 4581//4581 4637//4637 4716//4716 -f 4716//4716 4637//4637 4717//4717 -f 4637//4637 4633//4633 4717//4717 -f 4717//4717 4633//4633 4719//4719 -f 4633//4633 4632//4632 4719//4719 -f 4719//4719 4632//4632 4720//4720 -f 4632//4632 4631//4631 4720//4720 -f 4720//4720 4631//4631 4721//4721 -f 4631//4631 4638//4638 4721//4721 -f 4721//4721 4638//4638 4685//4685 -f 4638//4638 4635//4635 4685//4685 -f 4685//4685 4635//4635 4686//4686 -f 4687//4687 4686//4686 4635//4635 -f 4714//4714 4715//4715 4622//4622 -f 4622//4622 4715//4715 4812//4812 -f 4622//4622 4812//4812 4635//4635 -f 4635//4635 4812//4812 4814//4814 -f 4635//4635 4814//4814 4687//4687 -f 4622//4622 4620//4620 4714//4714 -f 4714//4714 4620//4620 4712//4712 -f 4620//4620 4619//4619 4706//4706 -f 4706//4706 4708//4708 4620//4620 -f 4620//4620 4708//4708 4710//4710 -f 4620//4620 4710//4710 4712//4712 -f 4619//4619 4621//4621 4706//4706 -f 4706//4706 4621//4621 4704//4704 -f 4705//4705 4704//4704 4621//4621 -f 4697//4697 5046//5046 4596//4596 -f 4596//4596 5046//5046 4803//4803 -f 4596//4596 4803//4803 4621//4621 -f 4621//4621 4803//4803 4802//4802 -f 4621//4621 4802//4802 4705//4705 -f 4596//4596 4595//4595 4697//4697 -f 4697//4697 4595//4595 4698//4698 -f 4595//4595 4587//4587 4698//4698 -f 4698//4698 4587//4587 4700//4700 -f 4587//4587 4593//4593 4700//4700 -f 4700//4700 4593//4593 4701//4701 -f 4593//4593 4579//4579 4701//4701 -f 4701//4701 4579//4579 4703//4703 -f 4579//4579 4578//4578 4703//4703 -f 4703//4703 4578//4578 4688//4688 -f 4578//4578 4577//4577 4688//4688 -f 4688//4688 4577//4577 4689//4689 -f 5056//5056 5055//5055 4585//4585 -f 4585//4585 5055//5055 5054//5054 -f 4585//4585 5054//5054 5053//5053 -f 5053//5053 5052//5052 4585//4585 -f 4585//4585 5052//5052 5051//5051 -f 4585//4585 5051//5051 4577//4577 -f 4577//4577 5051//5051 5050//5050 -f 4577//4577 5050//5050 5049//5049 -f 5049//5049 5048//5048 4577//4577 -f 4577//4577 5048//5048 4690//4690 -f 4577//4577 4690//4690 4689//4689 -f 4572//4572 4230//4230 4100//4100 -f 4572//4572 4100//4100 4582//4582 -f 4582//4582 4100//4100 4273//4273 -f 4582//4582 4273//4273 4583//4583 -f 4583//4583 4273//4273 4272//4272 -f 4583//4583 4272//4272 4584//4584 -f 4584//4584 4272//4272 4271//4271 -f 4584//4584 4271//4271 4636//4636 -f 4636//4636 4271//4271 4270//4270 -f 4636//4636 4270//4270 4634//4634 -f 4634//4634 4270//4270 4269//4269 -f 4634//4634 4269//4269 4573//4573 -f 4574//4574 4128//4128 4127//4127 -f 4574//4574 4127//4127 4597//4597 -f 4597//4597 4127//4127 4250//4250 -f 4597//4597 4250//4250 4588//4588 -f 4588//4588 4250//4250 4249//4249 -f 4588//4588 4249//4249 4589//4589 -f 4589//4589 4249//4249 4248//4248 -f 4589//4589 4248//4248 4594//4594 -f 4594//4594 4248//4248 4433//4433 -f 4594//4594 4433//4433 4586//4586 -f 4586//4586 4433//4433 4432//4432 -f 4586//4586 4432//4432 4575//4575 -f 4570//4570 4092//4092 4260//4260 -f 4570//4570 4260//4260 4598//4598 -f 4598//4598 4260//4260 4265//4265 -f 4598//4598 4265//4265 4599//4599 -f 4599//4599 4265//4265 4264//4264 -f 4599//4599 4264//4264 4601//4601 -f 4601//4601 4264//4264 4261//4261 -f 4601//4601 4261//4261 4623//4623 -f 4623//4623 4261//4261 4262//4262 -f 4623//4623 4262//4262 4624//4624 -f 4624//4624 4262//4262 4263//4263 -f 4624//4624 4263//4263 4571//4571 -f 4576//4576 4443//4443 4256//4256 -f 4576//4576 4256//4256 4615//4615 -f 4615//4615 4256//4256 4255//4255 -f 4615//4615 4255//4255 4613//4613 -f 4613//4613 4255//4255 4254//4254 -f 4613//4613 4254//4254 4609//4609 -f 4609//4609 4254//4254 4253//4253 -f 4609//4609 4253//4253 4607//4607 -f 4607//4607 4253//4253 4252//4252 -f 4607//4607 4252//4252 4605//4605 -f 4605//4605 4252//4252 4259//4259 -f 4605//4605 4259//4259 4569//4569 -f 5105//5105 5106//5106 3982//3982 -f 3994//3994 5107//5107 3992//3992 -f 3992//3992 5107//5107 5108//5108 -f 3992//3992 5108//5108 3990//3990 -f 3990//3990 5108//5108 5109//5109 -f 5110//5110 4002//4002 5106//5106 -f 5106//5106 4002//4002 4004//4004 -f 5106//5106 4004//4004 3982//3982 -f 3994//3994 3996//3996 5107//5107 -f 5107//5107 3996//3996 3998//3998 -f 5107//5107 3998//3998 5110//5110 -f 5110//5110 3998//3998 4000//4000 -f 5110//5110 4000//4000 4002//4002 -f 3982//3982 3984//3984 5105//5105 -f 5105//5105 3984//3984 3986//3986 -f 5105//5105 3986//3986 5109//5109 -f 5109//5109 3986//3986 3988//3988 -f 5109//5109 3988//3988 3990//3990 -f 5109//5109 5108//5108 4401//4401 -f 4401//4401 5108//5108 4402//4402 -f 5105//5105 5109//5109 4405//4405 -f 4405//4405 5109//5109 4401//4401 -f 5106//5106 5105//5105 4404//4404 -f 4404//4404 5105//5105 4405//4405 -f 5110//5110 5106//5106 4403//4403 -f 4403//4403 5106//5106 4404//4404 -f 5107//5107 5110//5110 4436//4436 -f 4436//4436 5110//5110 4403//4403 -f 5108//5108 5107//5107 4402//4402 -f 4402//4402 5107//5107 4436//4436 -f 5111//5111 5112//5112 5096//5096 -f 5099//5099 5113//5113 5098//5098 -f 5098//5098 5113//5113 5111//5111 -f 5098//5098 5111//5111 5097//5097 -f 5097//5097 5111//5111 5096//5096 -f 5114//5114 5115//5115 5103//5103 -f 5103//5103 5104//5104 5114//5114 -f 5114//5114 5104//5104 5093//5093 -f 5114//5114 5093//5093 5116//5116 -f 5116//5116 5093//5093 5094//5094 -f 5116//5116 5094//5094 5112//5112 -f 5112//5112 5094//5094 5095//5095 -f 5112//5112 5095//5095 5096//5096 -f 5099//5099 5100//5100 5113//5113 -f 5113//5113 5100//5100 5101//5101 -f 5113//5113 5101//5101 5115//5115 -f 5115//5115 5101//5101 5102//5102 -f 5115//5115 5102//5102 5103//5103 -f 5111//5111 5113//5113 4495//4495 -f 4495//4495 5113//5113 4496//4496 -f 5112//5112 5111//5111 4494//4494 -f 4494//4494 5111//5111 4495//4495 -f 5116//5116 5112//5112 4493//4493 -f 4493//4493 5112//5112 4494//4494 -f 5114//5114 5116//5116 4492//4492 -f 4492//4492 5116//5116 4493//4493 -f 5115//5115 5114//5114 4491//4491 -f 4491//4491 5114//5114 4492//4492 -f 5113//5113 5115//5115 4496//4496 -f 4496//4496 5115//5115 4491//4491 -f 5117//5117 5118//5118 5079//5079 -f 5079//5079 5080//5080 5117//5117 -f 5117//5117 5080//5080 5069//5069 -f 5117//5117 5069//5069 5119//5119 -f 5075//5075 5120//5120 5074//5074 -f 5074//5074 5120//5120 5121//5121 -f 5075//5075 5076//5076 5120//5120 -f 5120//5120 5076//5076 5077//5077 -f 5120//5120 5077//5077 5118//5118 -f 5118//5118 5077//5077 5078//5078 -f 5118//5118 5078//5078 5079//5079 -f 5069//5069 5070//5070 5119//5119 -f 5119//5119 5070//5070 5071//5071 -f 5119//5119 5071//5071 5122//5122 -f 5122//5122 5071//5071 5072//5072 -f 5122//5122 5072//5072 5121//5121 -f 5121//5121 5072//5072 5073//5073 -f 5121//5121 5073//5073 5074//5074 -f 5121//5121 5120//5120 4411//4411 -f 4411//4411 5120//5120 4406//4406 -f 5122//5122 5121//5121 4412//4412 -f 4412//4412 5121//5121 4411//4411 -f 5119//5119 5122//5122 4410//4410 -f 4410//4410 5122//5122 4412//4412 -f 5117//5117 5119//5119 4409//4409 -f 4409//4409 5119//5119 4410//4410 -f 5118//5118 5117//5117 4407//4407 -f 4407//4407 5117//5117 4409//4409 -f 5120//5120 5118//5118 4406//4406 -f 4406//4406 5118//5118 4407//4407 -f 5063//5063 5123//5123 5062//5062 -f 5062//5062 5123//5123 5124//5124 -f 5063//5063 5064//5064 5123//5123 -f 5123//5123 5064//5064 5065//5065 -f 5123//5123 5065//5065 5125//5125 -f 5126//5126 5127//5127 5057//5057 -f 5065//5065 5066//5066 5125//5125 -f 5125//5125 5066//5066 5067//5067 -f 5125//5125 5067//5067 5127//5127 -f 5127//5127 5067//5067 5068//5068 -f 5127//5127 5068//5068 5057//5057 -f 5057//5057 5058//5058 5126//5126 -f 5126//5126 5058//5058 5059//5059 -f 5126//5126 5059//5059 5128//5128 -f 5128//5128 5059//5059 5060//5060 -f 5128//5128 5060//5060 5124//5124 -f 5124//5124 5060//5060 5061//5061 -f 5124//5124 5061//5061 5062//5062 -f 5124//5124 5123//5123 4235//4235 -f 4235//4235 5123//5123 4236//4236 -f 5128//5128 5124//5124 4241//4241 -f 4241//4241 5124//5124 4235//4235 -f 5126//5126 5128//5128 4240//4240 -f 4240//4240 5128//5128 4241//4241 -f 5127//5127 5126//5126 4233//4233 -f 4233//4233 5126//5126 4240//4240 -f 5125//5125 5127//5127 4232//4232 -f 4232//4232 5127//5127 4233//4233 -f 5123//5123 5125//5125 4236//4236 -f 4236//4236 5125//5125 4232//4232 -f 5129//5129 5130//5130 5086//5086 -f 5089//5089 5131//5131 5088//5088 -f 5088//5088 5131//5131 5129//5129 -f 5088//5088 5129//5129 5087//5087 -f 5087//5087 5129//5129 5086//5086 -f 5132//5132 5133//5133 5081//5081 -f 5089//5089 5090//5090 5131//5131 -f 5131//5131 5090//5090 5091//5091 -f 5131//5131 5091//5091 5133//5133 -f 5133//5133 5091//5091 5092//5092 -f 5133//5133 5092//5092 5081//5081 -f 5081//5081 5082//5082 5132//5132 -f 5132//5132 5082//5082 5083//5083 -f 5132//5132 5083//5083 5134//5134 -f 5134//5134 5083//5083 5084//5084 -f 5134//5134 5084//5084 5130//5130 -f 5130//5130 5084//5084 5085//5085 -f 5130//5130 5085//5085 5086//5086 -f 4421//4421 5130//5130 4423//4423 -f 4423//4423 5130//5130 5129//5129 -f 4423//4423 5129//5129 4077//4077 -f 4099//4099 4098//4098 5134//5134 -f 5130//5130 4421//4421 4419//4419 -f 5130//5130 4419//4419 5134//5134 -f 5134//5134 4419//4419 4418//4418 -f 5134//5134 4418//4418 4099//4099 -f 4415//4415 5132//5132 4227//4227 -f 4227//4227 5132//5132 5134//5134 -f 4227//4227 5134//5134 4098//4098 -f 4417//4417 5133//5133 4416//4416 -f 4416//4416 5133//5133 5132//5132 -f 4416//4416 5132//5132 4415//4415 -f 5131//5131 5133//5133 4078//4078 -f 4078//4078 5133//5133 4417//4417 -f 5129//5129 5131//5131 4077//4077 -f 4077//4077 5131//5131 4078//4078 -f 5135//5135 5136//5136 3970//3970 -f 3970//3970 3972//3972 5135//5135 -f 5135//5135 3972//3972 3974//3974 -f 5135//5135 3974//3974 5137//5137 -f 3974//3974 3976//3976 5137//5137 -f 5137//5137 3976//3976 3978//3978 -f 5137//5137 3978//3978 5138//5138 -f 3978//3978 3980//3980 5138//5138 -f 5138//5138 3980//3980 3958//3958 -f 5138//5138 3958//3958 5139//5139 -f 5140//5140 3966//3966 5136//5136 -f 5136//5136 3966//3966 3968//3968 -f 5136//5136 3968//3968 3970//3970 -f 3958//3958 3960//3960 5139//5139 -f 5139//5139 3960//3960 3962//3962 -f 5139//5139 3962//3962 5140//5140 -f 5140//5140 3962//3962 3964//3964 -f 5140//5140 3964//3964 3966//3966 -f 5140//5140 5136//5136 4470//4470 -f 4470//4470 5136//5136 4134//4134 -f 5139//5139 5140//5140 4117//4117 -f 4117//4117 5140//5140 4470//4470 -f 4114//4114 5138//5138 4115//4115 -f 4115//4115 5138//5138 5139//5139 -f 4115//4115 5139//5139 4117//4117 -f 5137//5137 5138//5138 4121//4121 -f 4121//4121 5138//5138 4114//4114 -f 5137//5137 4121//4121 4120//4120 -f 4137//4137 5135//5135 4132//4132 -f 4132//4132 5135//5135 5137//5137 -f 4132//4132 5137//5137 4129//4129 -f 4129//4129 5137//5137 4120//4120 -f 4134//4134 5136//5136 4136//4136 -f 4136//4136 5136//5136 5135//5135 -f 4136//4136 5135//5135 4137//4137 -f 5141//5141 5142//5142 4042//4042 -f 4050//4050 5143//5143 4048//4048 -f 4048//4048 5143//5143 5144//5144 -f 4048//4048 5144//5144 4046//4046 -f 4046//4046 5144//5144 5141//5141 -f 4046//4046 5141//5141 4044//4044 -f 4044//4044 5141//5141 4042//4042 -f 4050//4050 4052//4052 5143//5143 -f 5143//5143 4052//4052 4030//4030 -f 5143//5143 4030//4030 5145//5145 -f 5146//5146 4038//4038 5142//5142 -f 5142//5142 4038//4038 4040//4040 -f 5142//5142 4040//4040 4042//4042 -f 4030//4030 4032//4032 5145//5145 -f 5145//5145 4032//4032 4034//4034 -f 5145//5145 4034//4034 5146//5146 -f 5146//5146 4034//4034 4036//4036 -f 5146//5146 4036//4036 4038//4038 -f 5146//5146 5142//5142 4294//4294 -f 4294//4294 5142//5142 4296//4296 -f 5145//5145 5146//5146 4293//4293 -f 4293//4293 5146//5146 4294//4294 -f 5143//5143 5145//5145 4075//4075 -f 4075//4075 5145//5145 4293//4293 -f 5144//5144 5143//5143 4074//4074 -f 4074//4074 5143//5143 4075//4075 -f 5141//5141 5144//5144 4425//4425 -f 4425//4425 5144//5144 4074//4074 -f 5142//5142 5141//5141 4296//4296 -f 4296//4296 5141//5141 4425//4425 -f 5147//5147 5148//5148 4018//4018 -f 5149//5149 4026//4026 5150//5150 -f 5150//5150 4026//4026 4028//4028 -f 5150//5150 4028//4028 5151//5151 -f 5151//5151 4028//4028 4006//4006 -f 5152//5152 4014//4014 5148//5148 -f 5148//5148 4014//4014 4016//4016 -f 5148//5148 4016//4016 4018//4018 -f 4018//4018 4020//4020 5147//5147 -f 5147//5147 4020//4020 4022//4022 -f 5147//5147 4022//4022 5149//5149 -f 5149//5149 4022//4022 4024//4024 -f 5149//5149 4024//4024 4026//4026 -f 4006//4006 4008//4008 5151//5151 -f 5151//5151 4008//4008 4010//4010 -f 5151//5151 4010//4010 5152//5152 -f 5152//5152 4010//4010 4012//4012 -f 5152//5152 4012//4012 4014//4014 -f 5152//5152 5148//5148 4112//4112 -f 4112//4112 5148//5148 4113//4113 -f 5151//5151 5152//5152 4111//4111 -f 4111//4111 5152//5152 4112//4112 -f 5150//5150 5151//5151 4110//4110 -f 4110//4110 5151//5151 4111//4111 -f 5149//5149 5150//5150 4428//4428 -f 4428//4428 5150//5150 4110//4110 -f 5147//5147 5149//5149 4489//4489 -f 4489//4489 5149//5149 4428//4428 -f 5148//5148 5147//5147 4113//4113 -f 4113//4113 5147//5147 4489//4489 -f 3942//3942 5153//5153 3940//3940 -f 3940//3940 5153//5153 5154//5154 -f 3940//3940 5154//5154 3938//3938 -f 3938//3938 5154//5154 5155//5155 -f 3938//3938 5155//5155 3936//3936 -f 3936//3936 5155//5155 5156//5156 -f 3936//3936 5156//5156 3934//3934 -f 3934//3934 5156//5156 5157//5157 -f 3934//3934 5157//5157 3956//3956 -f 3956//3956 5157//5157 5158//5158 -f 3956//3956 5158//5158 3954//3954 -f 5158//5158 5159//5159 3954//3954 -f 3954//3954 5159//5159 5160//5160 -f 3954//3954 5160//5160 3952//3952 -f 3952//3952 5160//5160 5161//5161 -f 3952//3952 5161//5161 3950//3950 -f 3950//3950 5161//5161 5162//5162 -f 3950//3950 5162//5162 3948//3948 -f 3948//3948 5162//5162 5163//5163 -f 3948//3948 5163//5163 3946//3946 -f 3946//3946 5163//5163 5164//5164 -f 3946//3946 5164//5164 3944//3944 -f 3944//3944 5164//5164 5165//5165 -f 3944//3944 5165//5165 3942//3942 -f 3942//3942 5165//5165 5166//5166 -f 3942//3942 5166//5166 5153//5153 -f 5165//5165 4982//4982 5166//5166 -f 5166//5166 4982//4982 4984//4984 -f 5166//5166 4984//4984 5153//5153 -f 5153//5153 4984//4984 4986//4986 -f 5153//5153 4986//4986 5154//5154 -f 5154//5154 4986//4986 5045//5045 -f 5154//5154 5045//5045 5155//5155 -f 5155//5155 5045//5045 4988//4988 -f 5155//5155 4988//4988 5156//5156 -f 5156//5156 4988//4988 4987//4987 -f 5156//5156 4987//4987 5157//5157 -f 5157//5157 4987//4987 4991//4991 -f 5157//5157 4991//4991 5158//5158 -f 5158//5158 4991//4991 4990//4990 -f 5158//5158 4990//4990 5159//5159 -f 5159//5159 4990//4990 4989//4989 -f 5159//5159 4989//4989 5160//5160 -f 5160//5160 4989//4989 4691//4691 -f 5160//5160 4691//4691 5161//5161 -f 5161//5161 4691//4691 4696//4696 -f 5161//5161 4696//4696 5162//5162 -f 5162//5162 4696//4696 4977//4977 -f 5162//5162 4977//4977 5163//5163 -f 5163//5163 4977//4977 4979//4979 -f 5163//5163 4979//4979 5164//5164 -f 5164//5164 4979//4979 4980//4980 -f 5164//5164 4980//4980 5165//5165 -f 5165//5165 4980//4980 4982//4982 -f 3918//3918 5167//5167 3916//3916 -f 3916//3916 5167//5167 5168//5168 -f 3916//3916 5168//5168 3914//3914 -f 3914//3914 5168//5168 5169//5169 -f 3914//3914 5169//5169 3912//3912 -f 3912//3912 5169//5169 5170//5170 -f 3912//3912 5170//5170 3910//3910 -f 3910//3910 5170//5170 5171//5171 -f 3910//3910 5171//5171 3932//3932 -f 3932//3932 5171//5171 5172//5172 -f 3932//3932 5172//5172 3930//3930 -f 5172//5172 5173//5173 3930//3930 -f 3930//3930 5173//5173 5174//5174 -f 3930//3930 5174//5174 3928//3928 -f 3928//3928 5174//5174 5175//5175 -f 3928//3928 5175//5175 3926//3926 -f 3926//3926 5175//5175 5176//5176 -f 3926//3926 5176//5176 3924//3924 -f 3924//3924 5176//5176 5177//5177 -f 3924//3924 5177//5177 3922//3922 -f 3922//3922 5177//5177 5178//5178 -f 3922//3922 5178//5178 3920//3920 -f 3920//3920 5178//5178 5179//5179 -f 3920//3920 5179//5179 3918//3918 -f 3918//3918 5179//5179 5180//5180 -f 3918//3918 5180//5180 5167//5167 -f 5179//5179 4973//4973 5180//5180 -f 5180//5180 4973//4973 4735//4735 -f 5180//5180 4735//4735 5167//5167 -f 5167//5167 4735//4735 4727//4727 -f 5167//5167 4727//4727 5168//5168 -f 5168//5168 4727//4727 4726//4726 -f 5168//5168 4726//4726 5169//5169 -f 5169//5169 4726//4726 4731//4731 -f 5169//5169 4731//4731 5170//5170 -f 5170//5170 4731//4731 4730//4730 -f 5170//5170 4730//4730 5171//5171 -f 5171//5171 4730//4730 4729//4729 -f 5171//5171 4729//4729 5172//5172 -f 5172//5172 4729//4729 4966//4966 -f 5172//5172 4966//4966 5173//5173 -f 5173//5173 4966//4966 4965//4965 -f 5173//5173 4965//4965 5174//5174 -f 5174//5174 4965//4965 4963//4963 -f 5174//5174 4963//4963 5175//5175 -f 5175//5175 4963//4963 4962//4962 -f 5175//5175 4962//4962 5176//5176 -f 5176//5176 4962//4962 4967//4967 -f 5176//5176 4967//4967 5177//5177 -f 5177//5177 4967//4967 4969//4969 -f 5177//5177 4969//4969 5178//5178 -f 5178//5178 4969//4969 4974//4974 -f 5178//5178 4974//4974 5179//5179 -f 5179//5179 4974//4974 4973//4973 -f 4736//4736 4626//4626 4627//4627 -f 4736//4736 4627//4627 4734//4734 -f 4734//4734 4627//4627 4612//4612 -f 4734//4734 4612//4612 4733//4733 -f 4733//4733 4612//4612 4611//4611 -f 4733//4733 4611//4611 4732//4732 -f 4617//4617 4976//4976 4975//4975 -f 4617//4617 4975//4975 4618//4618 -f 4618//4618 4975//4975 4695//4695 -f 4618//4618 4695//4695 4630//4630 -f 4630//4630 4695//4695 4694//4694 -f 4630//4630 4694//4694 4629//4629 -# 10748 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_osnovno.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_osnovno.obj deleted file mode 100644 index aab17d9e7..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_osnovno.obj +++ /dev/null @@ -1,33664 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object robot_osnovno.obj -# -# Vertices: 8228 -# Faces: 17192 -# -#### -vn -0.000000 0.707107 0.707107 -v 0.085500 0.145000 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.074200 0.145000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.133625 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.067250 0.145000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.133625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.019605 -0.119575 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.127675 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 -0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.029625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 -0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.029625 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.029625 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.039625 0.005000 -vn 0.552289 -0.318864 0.770261 -v -0.042598 -0.138500 0.005000 -vn 0.318865 -0.552288 0.770262 -v -0.041500 -0.137402 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.137875 0.005000 -vn -0.683013 -0.183013 0.707107 -v 0.042000 -0.140000 0.005000 -vn -0.655722 -0.378581 0.653227 -v 0.042670 -0.142500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.142050 0.005000 -vn 0.655722 -0.378581 0.653227 -v 0.099330 -0.142500 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.142050 0.005000 -vn 0.378581 -0.655722 0.653227 -v 0.097500 -0.144330 0.005000 -vn 0.095838 0.727973 0.678875 -v -0.048000 0.145000 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.054485 0.145000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 0.133625 0.005000 -vn 0.637727 0.000000 0.770262 -v 0.065600 -0.021000 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.066022 -0.019425 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.019250 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.050600 -0.021000 0.005000 -vn 0.552288 -0.318864 0.770262 -v 0.051022 -0.019425 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 -0.019250 0.005000 -vn 0.318864 0.552289 0.770262 -v 0.052175 0.018272 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.051022 0.019425 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 0.019250 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.062801 0.015125 0.005000 -vn 0.637728 0.000000 0.770262 -v 0.062500 0.016250 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 0.015925 0.005000 -vn 0.552289 0.318864 0.770262 -v 0.076801 0.015125 0.005000 -vn 0.637728 0.000000 0.770262 -v 0.076500 0.016250 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 0.015925 0.005000 -vn 0.000000 -0.637728 0.770262 -v 0.078750 0.011250 0.005000 -vn -0.318864 -0.552289 0.770262 -v 0.084375 0.009743 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.012625 0.005000 -vn -0.552288 0.318864 0.770262 -v 0.088493 -0.005625 0.005000 -vn -0.318864 0.552289 0.770262 -v 0.084375 -0.009743 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.012625 0.005000 -vn 0.000000 -0.637728 0.770262 -v -0.080000 -0.085000 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.074375 -0.086507 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.083500 0.005000 -vn -0.318865 -0.552288 0.770261 -v 0.058440 -0.133768 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.133625 0.005000 -vn -0.000000 -0.637727 0.770262 -v 0.057440 -0.133500 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 -0.131075 0.005000 -vn -0.637727 0.000000 0.770262 -v -0.021990 -0.127500 0.005000 -vn -0.552291 0.318863 0.770260 -v -0.022224 -0.128375 0.005000 -vn -0.637727 -0.000000 0.770262 -v 0.025490 -0.127500 0.005000 -vn -0.552291 0.318863 0.770260 -v 0.025256 -0.128375 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 -0.127675 0.005000 -vn 0.318866 0.552285 0.770263 -v 0.022865 -0.129016 0.005000 -vn 0.552291 0.318863 0.770260 -v 0.022224 -0.128375 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.127675 0.005000 -vn 0.318865 0.552288 0.770262 -v -0.029790 0.122181 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.030559 0.122950 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 0.123825 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.006675 -0.023750 0.005000 -vn -0.318864 0.552289 0.770262 -v -0.007590 -0.024665 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.024575 0.005000 -vn -0.000000 0.637728 0.770261 -v -0.038720 -0.039750 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.039625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.044875 0.005000 -vn 0.318864 0.552289 0.770262 -v -0.040095 0.034618 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 0.034375 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.038720 0.034250 0.005000 -vn -0.000000 -0.637727 0.770263 -v 0.057440 0.082000 0.005000 -vn -0.318865 -0.552288 0.770261 -v 0.058440 0.081732 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.083500 0.005000 -vn 0.680317 0.067005 0.729849 -v -0.040000 0.052000 0.005000 -vn 0.707107 0.000000 0.707107 -v -0.040000 0.073200 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 0.073200 0.005000 -vn -0.251478 -0.607119 0.753768 -v 0.038765 -0.050152 0.005000 -vn -0.464669 -0.464669 0.753767 -v 0.039414 -0.050586 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 -0.044875 0.005000 -vn -0.067006 -0.680317 0.729849 -v 0.038000 -0.050000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 -0.044875 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.044875 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.000150 -0.050000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.044875 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.015970 -0.050000 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.037245 -0.050000 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.019605 -0.050000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.044875 0.005000 -vn 0.067005 -0.680317 0.729849 -v -0.038000 -0.050000 0.005000 -vn 0.251478 -0.607119 0.753768 -v -0.038765 -0.050152 0.005000 -vn 0.464669 -0.464669 0.753767 -v -0.039414 -0.050586 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 -0.083500 0.005000 -vn 0.707107 0.000000 0.707107 -v -0.040000 -0.073200 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 -0.073200 0.005000 -vn 0.707107 0.000000 0.707107 -v -0.040000 -0.057425 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 -0.057425 0.005000 -vn 0.680317 -0.067005 0.729849 -v -0.040000 -0.052000 0.005000 -vn 0.607119 -0.251478 0.753768 -v -0.039848 -0.051235 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 -0.098450 0.005000 -vn 0.251477 0.607118 0.753769 -v -0.038765 -0.094848 0.005000 -vn 0.464670 0.464670 0.753766 -v -0.039414 -0.094414 0.005000 -vn 0.607118 0.251478 0.753768 -v -0.039848 -0.093765 0.005000 -vn 0.680317 0.067005 0.729849 -v -0.040000 -0.093000 0.005000 -vn 0.707107 0.000000 0.707107 -v -0.040000 -0.083500 0.005000 -vn -0.680317 0.067005 0.729849 -v 0.040000 -0.093000 0.005000 -vn -0.607118 0.251478 0.753768 -v 0.039848 -0.093765 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.098450 0.005000 -vn -0.464670 0.464670 0.753766 -v 0.039414 -0.094414 0.005000 -vn -0.251477 0.607118 0.753769 -v 0.038765 -0.094848 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 -0.098450 0.005000 -vn -0.067004 0.680318 0.729848 -v 0.038000 -0.095000 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.037245 -0.095000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 -0.098450 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.015970 -0.095000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.098450 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.000150 -0.095000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.098450 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.019605 -0.095000 0.005000 -vn 0.067004 0.680318 0.729848 -v -0.038000 -0.095000 0.005000 -vn -0.552288 0.318865 0.770262 -v 0.059172 -0.081000 0.005000 -vn -0.318866 0.552288 0.770261 -v 0.058440 -0.081732 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.083500 0.005000 -vn -0.000000 0.637727 0.770263 -v 0.057440 -0.082000 0.005000 -vn -0.707107 -0.000000 0.707107 -v 0.040000 -0.083500 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.056440 -0.081732 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.055708 -0.081000 0.005000 -vn 0.637728 -0.000001 0.770262 -v 0.055440 -0.080000 0.005000 -vn -0.707108 -0.000000 0.707106 -v 0.040000 -0.073200 0.005000 -vn -0.000000 -0.637729 0.770261 -v 0.057440 -0.078000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.073200 0.005000 -vn 0.318863 -0.552287 0.770263 -v 0.056440 -0.078268 0.005000 -vn 0.552290 -0.318863 0.770261 -v 0.055708 -0.079000 0.005000 -vn 0.318863 -0.552288 0.770262 -v 0.052175 -0.065272 0.005000 -vn 0.000000 -0.637729 0.770261 -v 0.053750 -0.064850 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 -0.057425 0.005000 -vn -0.318864 -0.552288 0.770263 -v 0.055325 -0.065272 0.005000 -vn -0.552289 -0.318863 0.770261 -v 0.056478 -0.066425 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.056900 -0.068000 0.005000 -vn -0.552289 0.318864 0.770261 -v 0.056478 -0.069575 0.005000 -vn -0.607119 -0.251478 0.753767 -v 0.039848 -0.051235 0.005000 -vn -0.680317 -0.067005 0.729849 -v 0.040000 -0.052000 0.005000 -vn -0.707107 0.000000 0.707107 -v 0.040000 -0.057425 0.005000 -vn 0.318863 0.552288 0.770262 -v 0.052175 -0.070728 0.005000 -vn -0.000000 0.637729 0.770261 -v 0.053750 -0.071150 0.005000 -vn -0.318864 0.552288 0.770263 -v 0.055325 -0.070728 0.005000 -vn 0.552289 0.318864 0.770262 -v 0.051022 -0.069575 0.005000 -vn 0.637728 0.000000 0.770262 -v 0.050600 -0.068000 0.005000 -vn 0.552289 -0.318863 0.770262 -v 0.051022 -0.066425 0.005000 -vn 0.680317 -0.067005 0.729849 -v -0.040000 0.093000 0.005000 -vn 0.607118 -0.251478 0.753768 -v -0.039848 0.093765 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 0.098450 0.005000 -vn 0.464670 -0.464670 0.753766 -v -0.039414 0.094414 0.005000 -vn 0.067005 0.680317 0.729849 -v -0.038000 0.050000 0.005000 -vn 0.251478 0.607119 0.753767 -v -0.038765 0.050152 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.039625 0.005000 -vn 0.464669 0.464669 0.753767 -v -0.039414 0.050586 0.005000 -vn 0.607119 0.251478 0.753768 -v -0.039848 0.051235 0.005000 -vn -0.318864 -0.552288 0.770263 -v 0.055325 0.070728 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.073200 0.005000 -vn -0.000000 -0.637729 0.770261 -v 0.053750 0.071150 0.005000 -vn -0.707107 0.000000 0.707106 -v 0.040000 0.073200 0.005000 -vn 0.318863 -0.552288 0.770262 -v 0.052175 0.070728 0.005000 -vn -0.552289 0.318863 0.770261 -v 0.056478 0.066425 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 0.039625 0.005000 -vn -0.637728 -0.000000 0.770262 -v 0.056900 0.068000 0.005000 -vn -0.552289 -0.318864 0.770261 -v 0.056478 0.069575 0.005000 -vn -0.318864 0.552288 0.770263 -v 0.055325 0.065272 0.005000 -vn -0.000000 0.637729 0.770261 -v 0.053750 0.064850 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 0.039625 0.005000 -vn 0.318863 0.552288 0.770262 -v 0.052175 0.065272 0.005000 -vn 0.552289 0.318863 0.770262 -v 0.051022 0.066425 0.005000 -vn -0.251478 0.607119 0.753768 -v 0.038765 0.050152 0.005000 -vn -0.067006 0.680317 0.729849 -v 0.038000 0.050000 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.037245 0.050000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 0.039625 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.015970 0.050000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.039625 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.000150 0.050000 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.019605 0.050000 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.050600 0.068000 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.051022 0.069575 0.005000 -vn -0.680317 0.067005 0.729849 -v 0.040000 0.052000 0.005000 -vn -0.607119 0.251477 0.753767 -v 0.039848 0.051235 0.005000 -vn -0.464669 0.464669 0.753767 -v 0.039414 0.050586 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 0.076625 0.005000 -vn -0.000000 0.637729 0.770261 -v 0.057440 0.078000 0.005000 -vn -0.707106 -0.000000 0.707107 -v 0.040000 0.076625 0.005000 -vn 0.318863 0.552287 0.770263 -v 0.056440 0.078268 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.055708 0.081000 0.005000 -vn -0.707107 0.000000 0.707107 -v 0.040000 0.083500 0.005000 -vn 0.637728 0.000001 0.770262 -v 0.055440 0.080000 0.005000 -vn 0.552290 0.318863 0.770261 -v 0.055708 0.079000 0.005000 -vn 0.318865 -0.552288 0.770262 -v 0.056440 0.081732 0.005000 -vn -0.251477 -0.607118 0.753769 -v 0.038765 0.094848 0.005000 -vn -0.464670 -0.464670 0.753766 -v 0.039414 0.094414 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.098450 0.005000 -vn -0.680317 -0.067005 0.729849 -v 0.040000 0.093000 0.005000 -vn -0.607118 -0.251478 0.753768 -v 0.039848 0.093765 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.015970 0.095000 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.037245 0.095000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 0.098450 0.005000 -vn -0.067004 -0.680318 0.729848 -v 0.038000 0.095000 0.005000 -vn 0.251477 -0.607118 0.753769 -v -0.038765 0.094848 0.005000 -vn 0.067004 -0.680318 0.729848 -v -0.038000 0.095000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 0.098450 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.019605 0.095000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.098450 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.000150 0.095000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 0.098450 0.005000 -vn 0.637728 0.000000 0.770262 -v -0.052220 0.037000 0.005000 -vn 0.552288 -0.318864 0.770262 -v -0.051885 0.038250 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 0.039625 0.005000 -vn -0.318864 0.552289 0.770262 -v -0.048470 0.034835 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.049720 0.034500 0.005000 -vn 0.552288 0.318863 0.770262 -v -0.041102 0.035625 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.050970 0.039165 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.049720 0.039500 0.005000 -vn -0.318864 -0.552289 0.770262 -v -0.048470 0.039165 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.047555 0.038250 0.005000 -vn 0.552289 -0.318863 0.770262 -v -0.041102 0.038375 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.034375 0.005000 -vn 0.318864 0.552288 0.770262 -v -0.050970 0.034835 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.051885 0.035750 0.005000 -vn 0.637728 0.000000 0.770261 -v -0.041470 0.037000 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.047220 0.037000 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.047555 0.035750 0.005000 -vn 0.088122 0.669352 0.737701 -v -0.030220 0.034250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.029625 0.005000 -vn -0.088122 0.669352 0.737700 -v -0.019970 0.034250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.019605 0.029625 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.018595 0.034618 0.005000 -vn -0.000000 -0.637728 0.770261 -v -0.038720 0.039750 0.005000 -vn -0.318863 -0.552289 0.770262 -v -0.037345 0.039382 0.005000 -vn 0.088121 -0.669353 0.737700 -v -0.030220 0.039750 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.036338 0.038375 0.005000 -vn 0.318864 -0.552289 0.770262 -v -0.031595 0.039382 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.032602 0.038375 0.005000 -vn 0.637728 0.000000 0.770262 -v -0.032970 0.037000 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.035970 0.037000 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.032602 0.035625 0.005000 -vn -0.552288 0.318864 0.770262 -v -0.036338 0.035625 0.005000 -vn -0.318864 0.552289 0.770262 -v -0.037345 0.034618 0.005000 -vn 0.318863 0.552288 0.770262 -v -0.031595 -0.039382 0.005000 -vn 0.088121 0.669353 0.737700 -v -0.030220 -0.039750 0.005000 -vn -0.088121 0.669353 0.737700 -v -0.019970 -0.039750 0.005000 -vn -0.318864 -0.552289 0.770262 -v -0.037345 -0.034618 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.036338 -0.035625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.029625 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.035970 -0.037000 0.005000 -vn 0.637728 0.000000 0.770262 -v -0.032970 -0.037000 0.005000 -vn 0.552289 0.318864 0.770262 -v -0.032602 -0.038375 0.005000 -vn -0.552288 0.318864 0.770262 -v -0.036338 -0.038375 0.005000 -vn -0.318863 0.552289 0.770262 -v -0.037345 -0.039382 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.038720 -0.034250 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.032602 -0.035625 0.005000 -vn 0.318864 -0.552289 0.770262 -v -0.031595 -0.034618 0.005000 -vn 0.088122 -0.669353 0.737700 -v -0.030220 -0.034250 0.005000 -vn -0.088122 -0.669352 0.737700 -v -0.019970 -0.034250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.039625 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.049720 -0.039500 0.005000 -vn 0.318864 0.552288 0.770262 -v -0.050970 -0.039165 0.005000 -vn -0.318864 0.552289 0.770262 -v -0.048470 -0.039165 0.005000 -vn 0.552288 0.318863 0.770262 -v -0.041102 -0.038375 0.005000 -vn 0.318863 0.552289 0.770262 -v -0.040095 -0.039382 0.005000 -vn 0.318864 -0.552289 0.770262 -v -0.040095 -0.034618 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.029625 0.005000 -vn 0.552289 -0.318863 0.770262 -v -0.041102 -0.035625 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.051885 -0.038250 0.005000 -vn 0.637728 0.000000 0.770262 -v -0.052220 -0.037000 0.005000 -vn 0.552288 -0.318864 0.770262 -v -0.051885 -0.035750 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.050970 -0.034835 0.005000 -vn 0.000000 -0.637728 0.770262 -v -0.049720 -0.034500 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.048470 -0.034835 0.005000 -vn -0.552288 -0.318864 0.770262 -v -0.047555 -0.035750 0.005000 -vn 0.637728 0.000000 0.770261 -v -0.041470 -0.037000 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.047220 -0.037000 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.047555 -0.038250 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.024970 -0.024665 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.026220 -0.025000 0.005000 -vn -0.000000 -0.637727 0.770262 -v -0.026220 -0.020000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.019605 -0.019250 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.019250 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.024575 0.005000 -vn 0.318864 0.552289 0.770262 -v -0.027470 -0.024665 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.028385 -0.023750 0.005000 -vn -0.318864 -0.552289 0.770262 -v -0.024970 -0.020335 0.005000 -vn -0.552288 -0.318865 0.770262 -v -0.024055 -0.021250 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.024575 0.005000 -vn -0.637727 -0.000000 0.770262 -v -0.023720 -0.022500 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.024055 -0.023750 0.005000 -vn 0.637728 0.000001 0.770262 -v -0.028720 -0.022500 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.028385 -0.021250 0.005000 -vn 0.318864 -0.552289 0.770262 -v -0.027470 -0.020335 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.029625 0.005000 -vn 0.318864 0.552288 0.770262 -v -0.010090 -0.024665 0.005000 -vn 0.000000 0.637728 0.770262 -v -0.008840 -0.025000 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.011005 -0.023750 0.005000 -vn 0.637728 0.000000 0.770262 -v -0.011340 -0.022500 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.011005 -0.021250 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.010090 -0.020335 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.008840 -0.020000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.000150 -0.019250 0.005000 -vn -0.318864 -0.552289 0.770262 -v -0.007590 -0.020335 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.006675 -0.021250 0.005000 -vn -0.637728 0.000000 0.770262 -v -0.006340 -0.022500 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 -0.019250 0.005000 -vn -0.552288 -0.318864 0.770262 -v 0.010705 -0.021250 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.024575 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.011040 -0.022500 0.005000 -vn -0.552289 0.318864 0.770262 -v 0.010705 -0.023750 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.009790 -0.024665 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.029625 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.008540 -0.025000 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.007290 -0.024665 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.006375 -0.023750 0.005000 -vn 0.637728 0.000000 0.770262 -v 0.006040 -0.022500 0.005000 -vn 0.552288 -0.318864 0.770262 -v 0.006375 -0.021250 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.007290 -0.020335 0.005000 -vn -0.000000 -0.637727 0.770262 -v 0.008540 -0.020000 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.009790 -0.020335 0.005000 -vn -0.552288 0.318864 0.770262 -v -0.026921 0.122950 0.005000 -vn -0.318865 0.552288 0.770262 -v -0.027690 0.122181 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.019605 0.119575 0.005000 -vn -0.000000 0.637727 0.770262 -v -0.028740 0.121900 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.119575 0.005000 -vn -0.318866 -0.552285 0.770263 -v -0.022865 0.129016 0.005000 -vn -0.552291 -0.318863 0.770260 -v -0.022224 0.128375 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.019605 0.131075 0.005000 -vn -0.637727 0.000000 0.770262 -v -0.021990 0.127500 0.005000 -vn -0.552288 0.318865 0.770262 -v -0.022224 0.126625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 0.123825 0.005000 -vn -0.318863 0.552289 0.770262 -v -0.022865 0.125984 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.023740 0.129250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.131075 0.005000 -vn 0.318865 -0.552286 0.770263 -v -0.024615 0.129016 0.005000 -vn -0.637727 -0.000001 0.770262 -v -0.026640 0.124000 0.005000 -vn 0.000000 0.637728 0.770262 -v -0.023740 0.125750 0.005000 -vn 0.637727 -0.000001 0.770262 -v -0.030840 0.124000 0.005000 -vn 0.552290 -0.318864 0.770261 -v -0.030559 0.125050 0.005000 -vn 0.318866 -0.552287 0.770262 -v -0.029790 0.125819 0.005000 -vn 0.000000 -0.637727 0.770262 -v -0.028740 0.126100 0.005000 -vn 0.552291 -0.318863 0.770261 -v -0.025256 0.128375 0.005000 -vn -0.318866 -0.552287 0.770262 -v -0.027690 0.125819 0.005000 -vn 0.637727 0.000000 0.770263 -v -0.025490 0.127500 0.005000 -vn -0.552290 -0.318864 0.770261 -v -0.026921 0.125050 0.005000 -vn 0.318863 0.552289 0.770262 -v -0.024615 0.125984 0.005000 -vn 0.552288 0.318865 0.770262 -v -0.025256 0.126625 0.005000 -vn -0.552291 -0.318863 0.770260 -v 0.025256 0.128375 0.005000 -vn 0.318866 -0.552287 0.770262 -v 0.027690 0.125819 0.005000 -vn -0.000000 -0.637727 0.770262 -v 0.028740 0.126100 0.005000 -vn -0.318866 -0.552287 0.770262 -v 0.029790 0.125819 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 0.131075 0.005000 -vn -0.552290 -0.318864 0.770261 -v 0.030559 0.125050 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 0.123825 0.005000 -vn -0.318865 -0.552286 0.770263 -v 0.024615 0.129016 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.023740 0.129250 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 0.131075 0.005000 -vn 0.318866 -0.552285 0.770263 -v 0.022865 0.129016 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.023740 0.125750 0.005000 -vn 0.318863 0.552289 0.770262 -v 0.022865 0.125984 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 0.123825 0.005000 -vn 0.552288 0.318865 0.770262 -v 0.022224 0.126625 0.005000 -vn 0.637727 -0.000000 0.770262 -v 0.021990 0.127500 0.005000 -vn 0.552291 -0.318863 0.770260 -v 0.022224 0.128375 0.005000 -vn -0.637727 -0.000000 0.770262 -v 0.025490 0.127500 0.005000 -vn -0.552288 0.318865 0.770262 -v 0.025256 0.126625 0.005000 -vn 0.552290 -0.318864 0.770261 -v 0.026921 0.125050 0.005000 -vn -0.318863 0.552289 0.770261 -v 0.024615 0.125984 0.005000 -vn 0.637727 -0.000001 0.770262 -v 0.026640 0.124000 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.026921 0.122950 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.027690 0.122181 0.005000 -vn -0.637727 -0.000001 0.770262 -v 0.030840 0.124000 0.005000 -vn -0.552288 0.318864 0.770262 -v 0.030559 0.122950 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 0.119575 0.005000 -vn -0.318865 0.552288 0.770262 -v 0.029790 0.122181 0.005000 -vn -0.000000 0.637727 0.770262 -v 0.028740 0.121900 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 0.119575 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.023740 -0.129250 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.131075 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 -0.131075 0.005000 -vn -0.318865 0.552286 0.770263 -v 0.024615 -0.129016 0.005000 -vn 0.637727 -0.000000 0.770262 -v 0.021990 -0.127500 0.005000 -vn 0.552288 -0.318865 0.770262 -v 0.022224 -0.126625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 -0.119575 0.005000 -vn 0.318863 -0.552289 0.770262 -v 0.022865 -0.125984 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.027690 -0.122181 0.005000 -vn 0.000000 -0.637728 0.770262 -v 0.023740 -0.125750 0.005000 -vn 0.552288 -0.318864 0.770262 -v 0.026921 -0.122950 0.005000 -vn -0.318863 -0.552289 0.770261 -v 0.024615 -0.125984 0.005000 -vn -0.000000 -0.637727 0.770262 -v 0.028740 -0.121900 0.005000 -vn -0.318865 -0.552288 0.770262 -v 0.029790 -0.122181 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 -0.119575 0.005000 -vn -0.552288 -0.318864 0.770262 -v 0.030559 -0.122950 0.005000 -vn 0.318866 0.552287 0.770262 -v 0.027690 -0.125819 0.005000 -vn 0.552290 0.318864 0.770261 -v 0.026921 -0.125050 0.005000 -vn 0.637727 0.000001 0.770263 -v 0.026640 -0.124000 0.005000 -vn -0.637727 0.000001 0.770262 -v 0.030840 -0.124000 0.005000 -vn -0.552290 0.318864 0.770261 -v 0.030559 -0.125050 0.005000 -vn -0.318866 0.552287 0.770262 -v 0.029790 -0.125819 0.005000 -vn -0.000000 0.637727 0.770262 -v 0.028740 -0.126100 0.005000 -vn -0.552288 -0.318865 0.770262 -v 0.025256 -0.126625 0.005000 -vn 0.318865 0.552286 0.770263 -v -0.024615 -0.129016 0.005000 -vn 0.552291 0.318863 0.770260 -v -0.025256 -0.128375 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 -0.127675 0.005000 -vn 0.637727 0.000000 0.770262 -v -0.025490 -0.127500 0.005000 -vn -0.552288 -0.318865 0.770262 -v -0.022224 -0.126625 0.005000 -vn -0.318863 -0.552289 0.770262 -v -0.022865 -0.125984 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 -0.119575 0.005000 -vn -0.000000 -0.637727 0.770262 -v -0.028740 -0.121900 0.005000 -vn -0.318865 -0.552289 0.770262 -v -0.027690 -0.122181 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.026921 -0.122950 0.005000 -vn 0.318863 -0.552289 0.770262 -v -0.024615 -0.125984 0.005000 -vn -0.552290 0.318864 0.770261 -v -0.026921 -0.125050 0.005000 -vn 0.552287 -0.318865 0.770262 -v -0.025256 -0.126625 0.005000 -vn -0.318866 0.552287 0.770262 -v -0.027690 -0.125819 0.005000 -vn -0.000000 0.637727 0.770262 -v -0.028740 -0.126100 0.005000 -vn 0.318866 0.552287 0.770262 -v -0.029790 -0.125819 0.005000 -vn 0.552290 0.318864 0.770261 -v -0.030559 -0.125050 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.023740 -0.125750 0.005000 -vn -0.637727 0.000001 0.770262 -v -0.026640 -0.124000 0.005000 -vn 0.637727 0.000001 0.770262 -v -0.030840 -0.124000 0.005000 -vn 0.552288 -0.318864 0.770262 -v -0.030559 -0.122950 0.005000 -vn 0.318865 -0.552288 0.770262 -v -0.029790 -0.122181 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.131075 0.005000 -vn -0.318866 0.552285 0.770263 -v -0.022865 -0.129016 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.023740 -0.129250 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.131075 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.018595 -0.034618 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.017588 -0.035625 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.017220 -0.037000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.000150 -0.039625 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.017588 -0.038375 0.005000 -vn -0.318863 0.552289 0.770262 -v -0.018595 -0.039382 0.005000 -vn 0.318863 -0.552289 0.770262 -v -0.040095 0.039382 0.005000 -vn -0.088121 -0.669353 0.737700 -v -0.019970 0.039750 0.005000 -vn -0.318863 -0.552289 0.770262 -v -0.018595 0.039382 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.017588 0.038375 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.017220 0.037000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.000150 0.034375 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.017588 0.035625 0.005000 -vn -0.552288 -0.318865 0.770261 -v -0.077315 0.137550 0.005000 -vn -0.637727 -0.000001 0.770263 -v -0.076900 0.136000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.133625 0.005000 -vn -0.552288 0.318865 0.770262 -v -0.077315 0.134450 0.005000 -vn -0.318865 -0.552288 0.770261 -v -0.078450 0.138685 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.072825 0.145000 0.005000 -vn -0.000000 -0.637727 0.770262 -v -0.080000 0.139100 0.005000 -vn -0.095838 0.727973 0.678875 -v -0.087000 0.145000 0.005000 -vn 0.318865 -0.552288 0.770262 -v -0.081550 0.138685 0.005000 -vn -0.378581 0.655722 0.653226 -v -0.089500 0.144330 0.005000 -vn 0.552288 -0.318864 0.770262 -v -0.082685 0.137550 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 0.133625 0.005000 -vn 0.637728 -0.000001 0.770261 -v -0.083100 0.136000 0.005000 -vn -0.727973 0.095840 0.678874 -v -0.092000 0.140000 0.005000 -vn -0.655722 0.378581 0.653227 -v -0.091330 0.142500 0.005000 -vn -0.318865 0.552288 0.770262 -v -0.078450 0.133315 0.005000 -vn -0.000000 0.637727 0.770262 -v -0.080000 0.132900 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 0.131075 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.131075 0.005000 -vn 0.318865 0.552288 0.770262 -v -0.081550 0.133315 0.005000 -vn 0.552289 0.318863 0.770262 -v -0.082685 0.134450 0.005000 -vn 0.318863 -0.552289 0.770262 -v 0.022450 0.107685 0.005000 -vn -0.000000 -0.637728 0.770261 -v 0.024000 0.108100 0.005000 -vn -0.318863 -0.552289 0.770262 -v 0.025550 0.107685 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 0.107800 0.005000 -vn -0.000000 0.637727 0.770262 -v 0.024000 0.101900 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.022450 0.102315 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.026685 0.106550 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.027100 0.105000 0.005000 -vn -0.552288 0.318864 0.770262 -v 0.026685 0.103450 0.005000 -vn -0.318865 0.552288 0.770262 -v 0.025550 0.102315 0.005000 -vn 0.637728 0.000001 0.770262 -v 0.020900 0.105000 0.005000 -vn 0.552289 -0.318863 0.770262 -v 0.021315 0.106550 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 0.107800 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.021315 0.103450 0.005000 -vn -0.318862 0.552289 0.770263 -v -0.057875 -0.137949 0.005000 -vn -0.000000 0.637730 0.770260 -v -0.059000 -0.138250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.142050 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.137875 0.005000 -vn 0.318862 0.552289 0.770263 -v -0.060125 -0.137949 0.005000 -vn 0.552288 0.318865 0.770262 -v -0.060949 -0.137125 0.005000 -vn 0.637728 0.000001 0.770262 -v -0.061250 -0.136000 0.005000 -vn 0.552289 -0.318863 0.770262 -v -0.060949 -0.134875 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 -0.133625 0.005000 -vn 0.318862 -0.552289 0.770263 -v -0.060125 -0.134051 0.005000 -vn -0.000000 -0.637730 0.770260 -v -0.059000 -0.133750 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.133625 0.005000 -vn -0.318862 -0.552288 0.770263 -v -0.057875 -0.134051 0.005000 -vn -0.552289 -0.318863 0.770262 -v -0.057051 -0.134875 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 -0.142050 0.005000 -vn -0.552288 0.318865 0.770262 -v -0.057051 -0.137125 0.005000 -vn -0.637728 0.000001 0.770262 -v -0.056750 -0.136000 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 -0.137875 0.005000 -vn -0.727973 -0.095840 0.678874 -v -0.092000 -0.140000 0.005000 -vn 0.318865 0.552288 0.770262 -v -0.081550 -0.138685 0.005000 -vn -0.655722 -0.378581 0.653227 -v -0.091330 -0.142500 0.005000 -vn -0.000000 0.637727 0.770262 -v -0.080000 -0.139100 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 -0.142050 0.005000 -vn -0.318865 0.552288 0.770262 -v -0.078450 -0.138685 0.005000 -vn -0.552288 0.318865 0.770261 -v -0.077315 -0.137550 0.005000 -vn -0.552288 -0.318865 0.770262 -v -0.077315 -0.134450 0.005000 -vn -0.637727 0.000001 0.770263 -v -0.076900 -0.136000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.137875 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.133625 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.081550 -0.133315 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 -0.131075 0.005000 -vn -0.000000 -0.637727 0.770262 -v -0.080000 -0.132900 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.131075 0.005000 -vn 0.552289 0.318864 0.770262 -v -0.082685 -0.137550 0.005000 -vn 0.637728 0.000001 0.770261 -v -0.083100 -0.136000 0.005000 -vn 0.552289 -0.318863 0.770262 -v -0.082685 -0.134450 0.005000 -vn -0.552288 0.318865 0.770261 -v 0.094302 0.134500 0.005000 -vn -0.318865 0.552288 0.770262 -v 0.093570 0.133768 0.005000 -vn 0.000000 0.000000 1.000000 -v 0.097285 0.133625 0.005000 -vn -0.000000 0.637727 0.770263 -v 0.092570 0.133500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.097285 0.131075 0.005000 -vn 0.378581 0.655722 0.653227 -v 0.097500 0.144330 0.005000 -vn -0.552288 -0.318865 0.770262 -v 0.094302 0.136500 0.005000 -vn -0.637727 0.000000 0.770263 -v 0.094570 0.135500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 0.133625 0.005000 -vn 0.552289 0.318862 0.770262 -v 0.090838 0.134500 0.005000 -vn 0.637729 0.000000 0.770261 -v 0.090570 0.135500 0.005000 -vn 0.552289 -0.318862 0.770262 -v 0.090838 0.136500 0.005000 -vn 0.318865 -0.552288 0.770262 -v 0.091570 0.137232 0.005000 -vn 0.095839 0.727973 0.678875 -v 0.095000 0.145000 0.005000 -vn -0.000000 -0.637727 0.770263 -v 0.092570 0.137500 0.005000 -vn -0.318865 -0.552288 0.770262 -v 0.093570 0.137232 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 -0.133625 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.037245 -0.137000 0.005000 -vn -0.088123 -0.669352 0.737701 -v 0.039000 -0.137000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.137875 0.005000 -vn -0.318866 0.552289 0.770261 -v 0.058440 -0.137232 0.005000 -vn -0.000000 0.637727 0.770263 -v 0.057440 -0.137500 0.005000 -vn -0.552289 -0.318863 0.770262 -v 0.041598 -0.138500 0.005000 -vn -0.318866 -0.552289 0.770261 -v 0.040500 -0.137402 0.005000 -vn 0.318865 -0.552288 0.770262 -v 0.056440 -0.133768 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.055708 -0.134500 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.056440 -0.137232 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.055708 -0.136500 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.055440 -0.135500 0.005000 -vn -0.552288 0.318865 0.770262 -v 0.059172 -0.136500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 -0.137875 0.005000 -vn -0.637727 0.000000 0.770263 -v 0.059440 -0.135500 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.133625 0.005000 -vn -0.552288 -0.318865 0.770262 -v 0.059172 -0.134500 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.131075 0.005000 -vn -0.000000 -0.637727 0.770263 -v 0.092570 -0.133500 0.005000 -vn 0.000000 0.000000 1.000000 -v 0.097285 -0.133625 0.005000 -vn -0.318865 -0.552288 0.770262 -v 0.093570 -0.133768 0.005000 -vn -0.552288 -0.318865 0.770262 -v 0.094302 -0.134500 0.005000 -vn -0.637727 0.000000 0.770263 -v 0.094570 -0.135500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.097285 -0.137875 0.005000 -vn -0.552288 0.318865 0.770262 -v 0.094302 -0.136500 0.005000 -vn -0.318865 0.552288 0.770262 -v 0.093570 -0.137232 0.005000 -vn -0.000000 0.637727 0.770263 -v 0.092570 -0.137500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 -0.137875 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.133625 0.005000 -vn 0.552289 -0.318862 0.770262 -v 0.090838 -0.134500 0.005000 -vn 0.318865 -0.552288 0.770262 -v 0.091570 -0.133768 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.091570 -0.137232 0.005000 -vn 0.552289 0.318862 0.770262 -v 0.090838 -0.136500 0.005000 -vn 0.637729 0.000000 0.770261 -v 0.090570 -0.135500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 0.131075 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.133625 0.005000 -vn -0.000000 0.637727 0.770263 -v 0.057440 0.133500 0.005000 -vn -0.552288 0.318865 0.770262 -v 0.059172 0.134500 0.005000 -vn -0.318865 0.552288 0.770261 -v 0.058440 0.133768 0.005000 -vn -0.683013 0.183013 0.707107 -v 0.042000 0.140000 0.005000 -vn -0.552289 0.318863 0.770262 -v 0.041598 0.138500 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.056440 0.133768 0.005000 -vn -0.318866 0.552288 0.770261 -v 0.040500 0.137402 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.055440 0.135500 0.005000 -vn -0.095839 0.727972 0.678875 -v 0.047000 0.145000 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.055708 0.134500 0.005000 -vn -0.378580 0.655721 0.653228 -v 0.044500 0.144330 0.005000 -vn -0.655722 0.378581 0.653227 -v 0.042670 0.142500 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.055708 0.136500 0.005000 -vn 0.318865 -0.552288 0.770262 -v 0.056440 0.137232 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.058170 0.145000 0.005000 -vn -0.000000 -0.637727 0.770263 -v 0.057440 0.137500 0.005000 -vn -0.318865 -0.552288 0.770261 -v 0.058440 0.137232 0.005000 -vn -0.552288 -0.318865 0.770261 -v 0.059172 0.136500 0.005000 -vn -0.637727 0.000000 0.770263 -v 0.059440 0.135500 0.005000 -vn -0.552288 -0.318865 0.770262 -v 0.059172 0.081000 0.005000 -vn -0.637727 0.000001 0.770263 -v 0.059440 0.080000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.076625 0.005000 -vn -0.552290 0.318864 0.770261 -v 0.059172 0.079000 0.005000 -vn -0.318864 0.552287 0.770263 -v 0.058440 0.078268 0.005000 -vn -0.318864 -0.552287 0.770263 -v 0.058440 -0.078268 0.005000 -vn -0.552290 -0.318864 0.770261 -v 0.059172 -0.079000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.073200 0.005000 -vn -0.637727 -0.000001 0.770263 -v 0.059440 -0.080000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 -0.083500 0.005000 -vn -0.000001 0.637728 0.770262 -v -0.080000 0.085000 0.005000 -vn 0.318863 0.552288 0.770262 -v -0.085625 0.086507 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 0.083500 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.089743 0.090625 0.005000 -vn 0.637728 0.000000 0.770262 -v -0.091250 0.096250 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 0.098450 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.074375 0.086507 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.083500 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.070257 0.090625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 0.083500 0.005000 -vn -0.637728 0.000000 0.770262 -v -0.068750 0.096250 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 0.107800 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.107800 0.005000 -vn -0.318864 -0.552289 0.770262 -v -0.074375 0.105993 0.005000 -vn 0.000000 -0.637728 0.770262 -v -0.080000 0.107500 0.005000 -vn -0.707107 0.000000 0.707106 -v -0.092000 0.107800 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.085625 0.105993 0.005000 -vn 0.552288 -0.318864 0.770262 -v -0.089743 0.101875 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.110425 0.005000 -vn -0.318864 0.552289 0.770262 -v -0.074375 -0.105993 0.005000 -vn -0.000001 0.637728 0.770262 -v -0.080000 -0.107500 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 -0.110425 0.005000 -vn 0.318864 0.552288 0.770262 -v -0.085625 -0.105993 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.089743 -0.101875 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 -0.098450 0.005000 -vn 0.637728 -0.000000 0.770262 -v -0.091250 -0.096250 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 -0.083500 0.005000 -vn 0.552288 -0.318864 0.770262 -v -0.089743 -0.090625 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.085625 -0.086507 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.070257 -0.101875 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 -0.110425 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.068750 -0.096250 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.070257 -0.090625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 -0.083500 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.098450 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.078051 0.076375 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.078875 0.075551 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 0.073200 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.080000 0.075250 0.005000 -vn -0.707107 0.000000 0.707106 -v -0.092000 0.073200 0.005000 -vn 0.318864 0.552289 0.770262 -v -0.081125 0.075551 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 0.076625 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.080000 0.079750 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.078875 0.079449 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.081949 0.076375 0.005000 -vn 0.637728 0.000000 0.770262 -v -0.082250 0.077500 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.081949 0.078625 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.081125 0.079449 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.078051 0.078625 0.005000 -vn -0.637728 0.000000 0.770262 -v -0.077750 0.077500 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.076625 0.005000 -vn -0.552288 -0.318864 0.770262 -v 0.088493 0.005625 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.097285 0.012625 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.090000 0.000000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.012625 0.005000 -vn 0.552289 0.318864 0.770262 -v 0.069007 -0.005625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.012625 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.073125 -0.009743 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 -0.012625 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.078750 -0.011250 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.073125 0.009743 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.012625 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.069007 0.005625 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.012625 0.005000 -vn 0.637727 0.000000 0.770262 -v 0.067500 0.000000 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.078750 0.014000 0.005000 -vn 0.318864 0.552289 0.770262 -v 0.077625 0.014301 0.005000 -vn -0.318864 0.552289 0.770262 -v 0.079875 0.014301 0.005000 -vn 0.318864 -0.552289 0.770262 -v 0.077625 0.018199 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.078750 0.018500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 0.019250 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.076801 0.017375 0.005000 -vn -0.318864 -0.552289 0.770262 -v 0.079875 0.018199 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.019250 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.080699 0.017375 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.015925 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.081000 0.016250 0.005000 -vn -0.552288 0.318864 0.770262 -v 0.080699 0.015125 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.067000 0.016250 0.005000 -vn -0.552288 0.318864 0.770262 -v 0.066699 0.015125 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.063625 0.014301 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 0.012625 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.064750 0.014000 0.005000 -vn -0.318864 0.552289 0.770262 -v 0.065875 0.014301 0.005000 -vn 0.000000 -0.637728 0.770262 -v 0.064750 0.018500 0.005000 -vn -0.318864 -0.552289 0.770262 -v 0.065875 0.018199 0.005000 -vn 0.552289 0.318864 0.770261 -v 0.066022 0.019425 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.019250 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.062801 0.017375 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.063625 0.018199 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.067175 0.018272 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.066699 0.017375 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 0.015925 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.073200 0.005000 -vn -0.000000 -0.637729 0.770261 -v 0.068750 0.071150 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.073200 0.005000 -vn -0.318864 -0.552287 0.770263 -v 0.070325 0.070728 0.005000 -vn -0.552289 -0.318864 0.770261 -v 0.071478 0.069575 0.005000 -vn -0.637727 -0.000000 0.770262 -v 0.071900 0.068000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 0.039625 0.005000 -vn -0.552289 0.318864 0.770261 -v 0.071478 0.066425 0.005000 -vn -0.318864 0.552288 0.770263 -v 0.070325 0.065272 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.039625 0.005000 -vn 0.552289 -0.318864 0.770261 -v 0.066022 0.069575 0.005000 -vn 0.318864 -0.552288 0.770263 -v 0.067175 0.070728 0.005000 -vn -0.000000 0.637729 0.770261 -v 0.068750 0.064850 0.005000 -vn 0.318864 0.552288 0.770263 -v 0.067175 0.065272 0.005000 -vn 0.552289 0.318864 0.770261 -v 0.066022 0.066425 0.005000 -vn 0.637727 -0.000000 0.770262 -v 0.065600 0.068000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 0.015925 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.053750 0.017850 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.055325 0.023728 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.056478 0.022575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.029625 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.056900 0.021000 0.005000 -vn -0.552289 0.318864 0.770262 -v 0.056478 0.019425 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.055325 0.018272 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.050600 0.021000 0.005000 -vn 0.552288 -0.318864 0.770262 -v 0.051022 0.022575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 0.029625 0.005000 -vn 0.318864 -0.552289 0.770262 -v 0.052175 0.023728 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.053750 0.024150 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 -0.012625 0.005000 -vn 0.318864 -0.552289 0.770262 -v 0.052175 -0.018272 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 -0.012625 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.053750 -0.017850 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.055325 -0.018272 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.056478 -0.019425 0.005000 -vn -0.637728 0.000000 0.770262 -v 0.056900 -0.021000 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.051022 -0.022575 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 -0.024575 0.005000 -vn 0.318864 0.552289 0.770262 -v 0.052175 -0.023728 0.005000 -vn -0.552289 0.318864 0.770262 -v 0.056478 -0.022575 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.024575 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.055325 -0.023728 0.005000 -vn -0.000000 0.637727 0.770262 -v 0.053750 -0.024150 0.005000 -vn 0.552289 -0.318864 0.770261 -v 0.066022 -0.066425 0.005000 -vn 0.318864 -0.552288 0.770263 -v 0.067175 -0.065272 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 -0.057425 0.005000 -vn -0.000000 -0.637729 0.770261 -v 0.068750 -0.064850 0.005000 -vn -0.318864 0.552288 0.770263 -v 0.070325 -0.070728 0.005000 -vn -0.000000 0.637729 0.770261 -v 0.068750 -0.071150 0.005000 -vn -0.318864 -0.552288 0.770263 -v 0.070325 -0.065272 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.057425 0.005000 -vn -0.552289 -0.318864 0.770261 -v 0.071478 -0.066425 0.005000 -vn -0.637727 0.000000 0.770262 -v 0.071900 -0.068000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 -0.073200 0.005000 -vn -0.552289 0.318864 0.770261 -v 0.071478 -0.069575 0.005000 -vn 0.318864 0.552288 0.770263 -v 0.067175 -0.070728 0.005000 -vn 0.637727 0.000000 0.770263 -v 0.065600 -0.068000 0.005000 -vn 0.552289 0.318864 0.770261 -v 0.066022 -0.069575 0.005000 -vn -0.318864 -0.552289 0.770262 -v 0.065875 -0.014301 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.066699 -0.015125 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.068750 -0.017850 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.070325 -0.018272 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.019250 0.005000 -vn 0.318863 0.552289 0.770262 -v 0.063625 -0.018199 0.005000 -vn -0.000001 0.637728 0.770262 -v 0.064750 -0.018500 0.005000 -vn -0.318864 0.552289 0.770262 -v 0.065875 -0.018199 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.067175 -0.018272 0.005000 -vn -0.552288 0.318864 0.770262 -v 0.066699 -0.017375 0.005000 -vn -0.637728 -0.000000 0.770262 -v 0.067000 -0.016250 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.064750 -0.014000 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.063625 -0.014301 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.062801 -0.017375 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.062500 -0.016250 0.005000 -vn 0.552288 -0.318864 0.770262 -v 0.062801 -0.015125 0.005000 -vn 0.552289 0.318864 0.770262 -v 0.066022 -0.022575 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 -0.024575 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.070325 -0.023728 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.068750 -0.024150 0.005000 -vn -0.552289 -0.318864 0.770261 -v 0.071478 -0.019425 0.005000 -vn -0.637727 0.000000 0.770262 -v 0.071900 -0.021000 0.005000 -vn -0.552289 0.318864 0.770261 -v 0.071478 -0.022575 0.005000 -vn -0.552289 0.318864 0.770261 -v 0.071478 0.019425 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.070325 0.018272 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.068750 0.017850 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.029625 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.067175 0.023728 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.068750 0.024150 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.029625 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.070325 0.023728 0.005000 -vn -0.552289 -0.318864 0.770261 -v 0.071478 0.022575 0.005000 -vn -0.637727 0.000000 0.770262 -v 0.071900 0.021000 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.066022 0.022575 0.005000 -vn 0.637727 0.000000 0.770262 -v 0.065600 0.021000 0.005000 -vn 0.552289 0.318864 0.770261 -v -0.042598 0.138500 0.005000 -vn 0.683012 0.183013 0.707107 -v -0.043000 0.140000 0.005000 -vn 0.655722 0.378581 0.653227 -v -0.043670 0.142500 0.005000 -vn 0.378581 0.655722 0.653226 -v -0.045500 0.144330 0.005000 -vn 0.318865 0.552288 0.770262 -v -0.041500 0.137402 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.133625 0.005000 -vn 0.088123 0.669352 0.737701 -v -0.040000 0.137000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.019605 0.133625 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.019605 0.137000 0.005000 -vn -0.000000 0.707107 0.707107 -v -0.000150 0.137000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.133625 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.015970 0.137000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 0.133625 0.005000 -vn -0.000000 0.707107 0.707107 -v 0.037245 0.137000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 0.133625 0.005000 -vn -0.088123 0.669352 0.737701 -v 0.039000 0.137000 0.005000 -vn -0.378581 -0.655722 0.653226 -v 0.044500 -0.144330 0.005000 -vn -0.095839 -0.727973 0.678875 -v 0.047000 -0.145000 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.015970 -0.137000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.133625 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.000150 -0.137000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.133625 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.019605 -0.137000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.133625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.133625 0.005000 -vn 0.088123 -0.669352 0.737701 -v -0.040000 -0.137000 0.005000 -vn 0.683012 -0.183013 0.707107 -v -0.043000 -0.140000 0.005000 -vn 0.655722 -0.378581 0.653227 -v -0.043670 -0.142500 0.005000 -vn 0.095838 -0.727973 0.678875 -v -0.048000 -0.145000 0.005000 -vn 0.378581 -0.655722 0.653227 -v -0.045500 -0.144330 0.005000 -vn -0.378581 -0.655722 0.653226 -v -0.089500 -0.144330 0.005000 -vn -0.095838 -0.727973 0.678875 -v -0.087000 -0.145000 0.005000 -vn -0.637728 0.000000 0.770262 -v -0.077750 0.115000 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.078051 0.113875 0.005000 -vn 0.552289 0.318864 0.770262 -v -0.081949 0.113875 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 0.119575 0.005000 -vn 0.637728 -0.000000 0.770262 -v -0.082250 0.115000 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.081949 0.116125 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.081125 0.116949 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.080000 0.117250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.119575 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.078875 0.116949 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.078051 0.116125 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.078875 0.113051 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.080000 0.112750 0.005000 -vn 0.318864 0.552289 0.770262 -v -0.081125 0.113051 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.039625 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.034375 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.039625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 0.034375 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 -0.039625 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.044875 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 -0.044875 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.057425 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.057425 0.005000 -vn -0.707107 -0.000000 0.707107 -v -0.092000 -0.073200 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.073200 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.078051 -0.076375 0.005000 -vn -0.637728 0.000000 0.770262 -v -0.077750 -0.077500 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.078051 -0.078625 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.078875 -0.079449 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.080000 -0.079750 0.005000 -vn 0.318864 0.552289 0.770262 -v -0.081125 -0.079449 0.005000 -vn 0.552289 0.318864 0.770262 -v -0.081949 -0.078625 0.005000 -vn 0.637728 -0.000000 0.770262 -v -0.082250 -0.077500 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.081949 -0.076375 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.081125 -0.075551 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.080000 -0.075250 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.078875 -0.075551 0.005000 -vn -0.637728 0.000000 0.770262 -v -0.077750 -0.115000 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.078051 -0.116125 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 -0.119575 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.078875 -0.116949 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.080000 -0.117250 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.119575 0.005000 -vn 0.318864 0.552289 0.770262 -v -0.081125 -0.116949 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.081949 -0.116125 0.005000 -vn 0.637728 -0.000000 0.770262 -v -0.082250 -0.115000 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.081949 -0.113875 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.081125 -0.113051 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.080000 -0.112750 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.078875 -0.113051 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.078051 -0.113875 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.063470 0.039165 0.005000 -vn -0.552289 -0.318863 0.770262 -v -0.062555 0.038250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.039625 0.005000 -vn -0.000001 -0.637727 0.770262 -v -0.064720 0.039500 0.005000 -vn 0.318864 -0.552287 0.770262 -v -0.065970 0.039165 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 0.034375 0.005000 -vn -0.637728 0.000000 0.770261 -v -0.062220 0.037000 0.005000 -vn -0.552289 0.318863 0.770262 -v -0.062555 0.035750 0.005000 -vn 0.318864 0.552287 0.770262 -v -0.065970 0.034835 0.005000 -vn -0.000001 0.637727 0.770262 -v -0.064720 0.034500 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.063470 0.034835 0.005000 -vn 0.552290 0.318864 0.770261 -v -0.066885 0.035750 0.005000 -vn 0.637727 0.000000 0.770263 -v -0.067220 0.037000 0.005000 -vn 0.552290 -0.318864 0.770261 -v -0.066885 0.038250 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.063470 -0.039165 0.005000 -vn -0.000001 0.637727 0.770262 -v -0.064720 -0.039500 0.005000 -vn -0.318864 -0.552288 0.770262 -v -0.063470 -0.034835 0.005000 -vn -0.552289 -0.318863 0.770262 -v -0.062555 -0.035750 0.005000 -vn -0.637728 0.000000 0.770261 -v -0.062220 -0.037000 0.005000 -vn -0.552289 0.318863 0.770262 -v -0.062555 -0.038250 0.005000 -vn 0.318864 0.552287 0.770262 -v -0.065970 -0.039165 0.005000 -vn 0.552290 0.318864 0.770261 -v -0.066885 -0.038250 0.005000 -vn 0.637727 0.000000 0.770263 -v -0.067220 -0.037000 0.005000 -vn 0.552290 -0.318864 0.770261 -v -0.066885 -0.035750 0.005000 -vn 0.318864 -0.552287 0.770262 -v -0.065970 -0.034835 0.005000 -vn -0.000000 -0.637728 0.770262 -v -0.064720 -0.034500 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.073200 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.057425 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 -0.044875 0.005000 -vn -0.318865 -0.552288 0.770262 -v -0.078450 -0.133315 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.133625 0.005000 -vn 0.637728 -0.000001 0.770262 -v -0.061250 0.136000 0.005000 -vn 0.552288 -0.318865 0.770262 -v -0.060949 0.137125 0.005000 -vn -0.000000 0.707106 0.707107 -v -0.061735 0.145000 0.005000 -vn 0.318862 -0.552289 0.770263 -v -0.060125 0.137949 0.005000 -vn -0.000000 -0.637730 0.770260 -v -0.059000 0.138250 0.005000 -vn -0.552289 0.318863 0.770262 -v -0.057051 0.134875 0.005000 -vn -0.318862 0.552288 0.770263 -v -0.057875 0.134051 0.005000 -vn -0.000000 0.637730 0.770260 -v -0.059000 0.133750 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.133625 0.005000 -vn 0.318862 0.552289 0.770263 -v -0.060125 0.134051 0.005000 -vn 0.552289 0.318863 0.770262 -v -0.060949 0.134875 0.005000 -vn -0.318862 -0.552289 0.770263 -v -0.057875 0.137949 0.005000 -vn -0.552288 -0.318865 0.770262 -v -0.057051 0.137125 0.005000 -vn -0.637728 -0.000001 0.770262 -v -0.056750 0.136000 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 -0.044875 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.057425 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.073200 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.083500 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.098450 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.072825 -0.145000 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.061735 -0.145000 0.005000 -vn -0.000000 -0.707107 0.707107 -v -0.054485 -0.145000 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.123825 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.072825 0.123825 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 0.131075 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 0.123825 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 0.131075 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 0.123825 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.119575 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.070257 0.101875 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.098450 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.098450 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.083500 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.083500 0.005000 -vn 0.707107 0.000000 0.707107 -v -0.040000 0.083500 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.076625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.076625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.076625 0.005000 -vn 0.707107 0.000000 0.707107 -v -0.040000 0.076625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 0.073200 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 0.073200 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.029625 0.005000 -vn 0.318864 0.552288 0.770262 -v -0.031595 0.034618 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.019250 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.024575 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.024575 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.024575 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.024575 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.119575 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.119575 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 -0.127675 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.061735 -0.131075 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.054485 -0.131075 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 0.019250 0.005000 -vn -0.637728 -0.000001 0.770262 -v -0.023720 0.022500 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.024055 0.021250 0.005000 -vn 0.552288 0.318864 0.770262 -v -0.028385 0.021250 0.005000 -vn 0.637727 0.000000 0.770262 -v -0.028720 0.022500 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.019250 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.019250 0.005000 -vn -0.552288 -0.318864 0.770262 -v -0.024055 0.023750 0.005000 -vn -0.318864 -0.552289 0.770262 -v -0.024970 0.024665 0.005000 -vn -0.318864 0.552288 0.770262 -v -0.024970 0.020335 0.005000 -vn -0.000000 0.637728 0.770262 -v -0.026220 0.020000 0.005000 -vn 0.318864 0.552289 0.770262 -v -0.027470 0.020335 0.005000 -vn 0.552288 -0.318864 0.770262 -v -0.028385 0.023750 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.027470 0.024665 0.005000 -vn -0.000000 -0.637727 0.770262 -v -0.026220 0.025000 0.005000 -vn 0.318864 -0.552288 0.770262 -v -0.010090 0.024665 0.005000 -vn 0.000000 -0.637728 0.770262 -v -0.008840 0.025000 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.000150 0.029625 0.005000 -vn -0.318864 -0.552289 0.770262 -v -0.007590 0.024665 0.005000 -vn -0.552289 -0.318864 0.770262 -v -0.006675 0.023750 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.019250 0.005000 -vn -0.637728 -0.000000 0.770262 -v -0.006340 0.022500 0.005000 -vn -0.552289 0.318864 0.770262 -v -0.006675 0.021250 0.005000 -vn 0.318864 0.552288 0.770262 -v -0.010090 0.020335 0.005000 -vn 0.000000 0.637728 0.770262 -v -0.008840 0.020000 0.005000 -vn -0.318864 0.552289 0.770262 -v -0.007590 0.020335 0.005000 -vn 0.552289 0.318864 0.770262 -v -0.011005 0.021250 0.005000 -vn 0.637728 -0.000000 0.770262 -v -0.011340 0.022500 0.005000 -vn 0.552289 -0.318864 0.770262 -v -0.011005 0.023750 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.110425 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.040735 -0.110425 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.110425 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.110425 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.110425 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.131075 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.123825 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.107800 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.107800 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 0.107800 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.107800 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 0.034375 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.007290 0.020335 0.005000 -vn -0.000000 0.637727 0.770262 -v 0.008540 0.020000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 0.019250 0.005000 -vn -0.552288 -0.318864 0.770262 -v 0.010705 0.023750 0.005000 -vn -0.637728 -0.000000 0.770262 -v 0.011040 0.022500 0.005000 -vn -0.552289 0.318864 0.770262 -v 0.010705 0.021250 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.009790 0.020335 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.006375 0.023750 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.006040 0.022500 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.006375 0.021250 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.007290 0.024665 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.008540 0.025000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.015970 0.029625 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.009790 0.024665 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 -0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 -0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 -0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 -0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 -0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 -0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.127675 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 -0.131075 0.005000 -vn -0.637728 -0.000000 0.770262 -v 0.034490 0.037000 0.005000 -vn -0.552289 0.318864 0.770261 -v 0.034155 0.035750 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 0.034375 0.005000 -vn 0.552289 0.318864 0.770262 -v 0.029825 0.035750 0.005000 -vn 0.637728 0.000000 0.770262 -v 0.029490 0.037000 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.029825 0.038250 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.030740 0.039165 0.005000 -vn 0.000000 -0.637727 0.770262 -v 0.031990 0.039500 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.033240 0.039165 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.034155 0.038250 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.033240 0.034835 0.005000 -vn 0.000000 0.637727 0.770262 -v 0.031990 0.034500 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.030740 0.034835 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.015925 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.015925 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.015925 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.015925 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.015925 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 0.015925 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.015925 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 0.015925 0.005000 -vn 0.637728 0.000000 0.770262 -v 0.029490 -0.037000 0.005000 -vn 0.552289 -0.318864 0.770262 -v 0.029825 -0.035750 0.005000 -vn 0.318864 -0.552288 0.770262 -v 0.030740 -0.034835 0.005000 -vn 0.552289 0.318864 0.770262 -v 0.029825 -0.038250 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 -0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 -0.029625 0.005000 -vn 0.000000 -0.637728 0.770262 -v 0.031990 -0.034500 0.005000 -vn -0.318864 -0.552288 0.770262 -v 0.033240 -0.034835 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.034155 -0.035750 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 -0.039625 0.005000 -vn -0.637728 -0.000000 0.770262 -v 0.034490 -0.037000 0.005000 -vn -0.552289 0.318864 0.770261 -v 0.034155 -0.038250 0.005000 -vn -0.318864 0.552288 0.770262 -v 0.033240 -0.039165 0.005000 -vn 0.000000 0.637727 0.770262 -v 0.031990 -0.039500 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.030740 -0.039165 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.037245 -0.110425 0.005000 -vn -0.552288 -0.318864 0.770262 -v 0.026685 -0.103450 0.005000 -vn 0.552288 0.318864 0.770262 -v 0.021315 -0.106550 0.005000 -vn 0.318863 0.552289 0.770262 -v 0.022450 -0.107685 0.005000 -vn -0.000000 0.637729 0.770261 -v 0.024000 -0.108100 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.020900 -0.105000 0.005000 -vn 0.552288 -0.318864 0.770262 -v 0.021315 -0.103450 0.005000 -vn 0.318865 -0.552288 0.770262 -v 0.022450 -0.102315 0.005000 -vn -0.000000 -0.637727 0.770262 -v 0.024000 -0.101900 0.005000 -vn -0.318865 -0.552288 0.770262 -v 0.025550 -0.102315 0.005000 -vn -0.637728 -0.000001 0.770262 -v 0.027100 -0.105000 0.005000 -vn -0.552289 0.318863 0.770262 -v 0.026685 -0.106550 0.005000 -vn -0.318863 0.552289 0.770262 -v 0.025550 -0.107685 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.107800 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.119575 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 0.123825 0.005000 -vn -0.707107 0.000000 0.707107 -v -0.092000 0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.072825 0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.061735 0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.054485 0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v -0.040735 0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.019605 0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v -0.000150 0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.015970 0.012625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.037245 0.012625 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 -0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 -0.119575 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.058170 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 0.083500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.098450 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 0.107800 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 0.123825 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 0.131075 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.044875 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 -0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.024575 0.005000 -vn 0.318864 0.552288 0.770262 -v 0.067175 -0.023728 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.110425 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.119575 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.131075 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.131075 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.123825 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.107800 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 0.098450 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 0.083500 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.076625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 0.034375 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 0.034375 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 0.034375 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.044875 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.058170 -0.110425 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.067250 -0.098450 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 -0.083500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.074200 -0.098450 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.110425 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.131075 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.133625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.137875 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 0.131075 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.123825 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.107800 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 0.098450 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.083500 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.034375 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 0.073200 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 0.076625 0.005000 -vn 0.318864 -0.552289 0.770262 -v 0.077625 -0.014301 0.005000 -vn -0.000000 -0.637728 0.770262 -v 0.078750 -0.014000 0.005000 -vn -0.318864 -0.552289 0.770262 -v 0.079875 -0.014301 0.005000 -vn -0.552289 -0.318864 0.770262 -v 0.080699 -0.015125 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 -0.019250 0.005000 -vn -0.637728 -0.000000 0.770262 -v 0.081000 -0.016250 0.005000 -vn -0.552289 0.318864 0.770262 -v 0.080699 -0.017375 0.005000 -vn -0.318864 0.552289 0.770262 -v 0.079875 -0.018199 0.005000 -vn -0.000000 0.637728 0.770262 -v 0.078750 -0.018500 0.005000 -vn 0.318864 0.552289 0.770262 -v 0.077625 -0.018199 0.005000 -vn 0.552289 0.318864 0.770262 -v 0.076801 -0.017375 0.005000 -vn 0.637728 -0.000000 0.770262 -v 0.076500 -0.016250 0.005000 -vn 0.552288 -0.318864 0.770262 -v 0.076801 -0.015125 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.073200 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.057425 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.044875 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.024575 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 -0.083500 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.085500 -0.098450 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.110425 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.131075 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.058170 -0.145000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.067250 -0.142050 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.067250 -0.145000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.074200 -0.142050 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.074200 -0.145000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.085500 -0.142050 0.005000 -vn -0.000000 -0.707107 0.707107 -v 0.085500 -0.145000 0.005000 -vn 0.095839 -0.727973 0.678875 -v 0.095000 -0.145000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.097285 0.098450 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.107800 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.123825 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.091570 0.133768 0.005000 -vn 0.318863 0.552287 0.770263 -v 0.091570 0.078268 0.005000 -vn 0.552290 0.318862 0.770262 -v 0.090838 0.079000 0.005000 -vn -0.000000 0.637729 0.770261 -v 0.092570 0.078000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.097285 0.076625 0.005000 -vn -0.318863 0.552287 0.770263 -v 0.093570 0.078268 0.005000 -vn -0.552290 0.318865 0.770261 -v 0.094302 0.079000 0.005000 -vn 0.637729 0.000001 0.770261 -v 0.090570 0.080000 0.005000 -vn 0.552289 -0.318862 0.770262 -v 0.090838 0.081000 0.005000 -vn 0.318865 -0.552288 0.770262 -v 0.091570 0.081732 0.005000 -vn -0.000000 -0.637727 0.770263 -v 0.092570 0.082000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.083500 0.005000 -vn -0.318865 -0.552288 0.770262 -v 0.093570 0.081732 0.005000 -vn -0.552288 -0.318865 0.770262 -v 0.094302 0.081000 0.005000 -vn -0.637727 0.000001 0.770263 -v 0.094570 0.080000 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.015925 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.034375 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 0.073200 0.005000 -vn 0.000000 -0.637729 0.770261 -v 0.092570 -0.078000 0.005000 -vn -0.318863 -0.552287 0.770263 -v 0.093570 -0.078268 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.073200 0.005000 -vn -0.552290 -0.318864 0.770261 -v 0.094302 -0.079000 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.097285 -0.083500 0.005000 -vn -0.637727 -0.000001 0.770263 -v 0.094570 -0.080000 0.005000 -vn -0.552288 0.318865 0.770262 -v 0.094302 -0.081000 0.005000 -vn -0.318865 0.552288 0.770262 -v 0.093570 -0.081732 0.005000 -vn -0.000000 0.637727 0.770263 -v 0.092570 -0.082000 0.005000 -vn 0.318865 0.552288 0.770262 -v 0.091570 -0.081732 0.005000 -vn 0.552289 0.318862 0.770262 -v 0.090838 -0.081000 0.005000 -vn 0.637729 -0.000001 0.770261 -v 0.090570 -0.080000 0.005000 -vn 0.552290 -0.318862 0.770262 -v 0.090838 -0.079000 0.005000 -vn 0.318863 -0.552287 0.770263 -v 0.091570 -0.078268 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.019250 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.024575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.029625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.039625 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.044875 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.057425 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.127675 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.119575 0.005000 -vn -0.000000 0.000000 1.000000 -v 0.097285 -0.110425 0.005000 -vn -0.000000 -0.000000 1.000000 -v 0.097285 -0.098450 0.005000 -vn 0.727973 -0.095840 0.678874 -v 0.100000 -0.140000 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.137875 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.133625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.131075 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.127675 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.119575 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.110425 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.098450 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.083500 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.073200 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.057425 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.044875 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.039625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.029625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.024575 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.019250 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 -0.012625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.012625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.015925 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.019250 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.029625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.034375 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.039625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.073200 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.076625 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.083500 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.098450 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.107800 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.119575 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.123825 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.131075 0.005000 -vn 0.707107 0.000000 0.707107 -v 0.100000 0.133625 0.005000 -vn 0.727973 0.095840 0.678874 -v 0.100000 0.140000 0.005000 -vn 0.655722 0.378581 0.653227 -v 0.099330 0.142500 0.005000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.131075 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.123825 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.123825 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.015970 0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.123825 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.123825 -0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.019250 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.019250 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.133625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.131075 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.085500 -0.142050 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.085500 -0.145000 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.074200 -0.145000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.083500 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.085500 0.076625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.076625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.110425 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.119575 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.098450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.110425 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.029625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.039625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.012625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.019250 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.019250 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.083500 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.076625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.076625 0.000000 -vn -0.637727 0.000000 -0.770262 -v 0.071900 -0.021000 0.000000 -vn -0.552289 -0.318864 -0.770262 -v 0.071478 -0.019425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.019250 0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.070257 -0.101875 -0.000000 -vn -0.637728 -0.000000 -0.770262 -v -0.068750 -0.096250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.098450 -0.000000 -vn -0.552290 -0.318865 -0.770261 -v 0.059172 -0.079000 0.000000 -vn -0.318864 -0.552287 -0.770263 -v 0.058440 -0.078268 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.073200 0.000000 -vn -0.318865 0.552288 -0.770261 -v 0.058440 0.133768 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 0.133625 0.000000 -vn -0.000000 0.637727 -0.770262 -v 0.057440 0.133500 0.000000 -vn -0.318865 -0.552288 -0.770262 -v 0.093570 -0.133768 0.000000 -vn 0.000000 -0.637727 -0.770263 -v 0.092570 -0.133500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.133625 0.000000 -vn 0.637727 0.000000 -0.770262 -v 0.021990 -0.127500 0.000000 -vn 0.552291 0.318863 -0.770260 -v 0.022224 -0.128375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.127675 0.000000 -vn -0.318865 0.552288 -0.770262 -v 0.029790 0.122181 0.000000 -vn -0.552288 0.318864 -0.770262 -v 0.030559 0.122950 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.123825 0.000000 -vn 0.318865 0.552288 -0.770262 -v 0.056440 0.133768 0.000000 -vn -0.318866 0.552289 -0.770261 -v 0.040500 0.137402 0.000000 -vn 0.318865 0.552288 -0.770262 -v 0.091570 0.133768 0.000000 -vn 0.000000 0.637727 -0.770263 -v 0.092570 0.133500 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.085500 0.133625 0.000000 -vn -0.683013 -0.183013 -0.707107 -v 0.042000 -0.140000 0.000000 -vn -0.552289 -0.318863 -0.770262 -v 0.041598 -0.138500 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 -0.137875 0.000000 -vn 0.683012 -0.183013 -0.707107 -v -0.043000 -0.140000 -0.000000 -vn 0.655722 -0.378581 -0.653227 -v -0.043670 -0.142500 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.054485 -0.142050 -0.000000 -vn -0.095838 -0.727973 -0.678875 -v -0.087000 -0.145000 -0.000000 -vn -0.378581 -0.655722 -0.653226 -v -0.089500 -0.144330 -0.000000 -vn -0.655722 -0.378581 -0.653227 -v -0.091330 -0.142500 -0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.006375 -0.023750 0.000000 -vn 0.318864 0.552288 -0.770262 -v 0.007290 -0.024665 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.024575 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.007590 -0.024665 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.029625 -0.000000 -vn -0.680317 0.067005 -0.729849 -v 0.040000 -0.093000 0.000000 -vn -0.707107 0.000000 -0.707107 -v 0.040000 -0.083500 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 -0.083500 0.000000 -vn 0.088122 -0.669353 -0.737700 -v -0.030220 0.039750 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.036338 0.038375 -0.000000 -vn -0.318863 -0.552289 -0.770262 -v -0.037345 0.039382 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.031595 0.039382 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.032602 0.038375 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.035970 0.037000 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.032970 0.037000 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.036338 0.035625 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.032602 0.035625 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.037345 0.034618 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.031595 0.034618 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.038720 0.034250 -0.000000 -vn 0.088122 0.669352 -0.737700 -v -0.030220 0.034250 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.040735 0.039625 -0.000000 -vn 0.464669 0.464669 -0.753767 -v -0.039414 0.050586 -0.000000 -vn 0.251478 0.607119 -0.753767 -v -0.038765 0.050152 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.073200 -0.000000 -vn 0.680317 0.067005 -0.729849 -v -0.040000 0.052000 -0.000000 -vn 0.607119 0.251478 -0.753767 -v -0.039848 0.051235 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.019605 0.050000 -0.000000 -vn -0.088121 -0.669353 -0.737700 -v -0.019970 0.039750 -0.000000 -vn 0.067005 0.680317 -0.729849 -v -0.038000 0.050000 -0.000000 -vn 0.000000 -0.637728 -0.770261 -v -0.038720 0.039750 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.000150 0.050000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.039625 -0.000000 -vn -0.318863 -0.552289 -0.770262 -v -0.018595 0.039382 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.034375 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.017220 0.037000 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.017588 0.038375 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.029625 -0.000000 -vn -0.088122 0.669352 -0.737700 -v -0.019970 0.034250 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.018595 0.034618 -0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.037245 -0.095000 0.000000 -vn -0.067004 0.680318 -0.729848 -v 0.038000 -0.095000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.098450 0.000000 -vn -0.251477 0.607118 -0.753769 -v 0.038765 -0.094848 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.098450 0.000000 -vn -0.464670 0.464670 -0.753766 -v 0.039414 -0.094414 0.000000 -vn -0.607118 0.251478 -0.753768 -v 0.039848 -0.093765 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 -0.098450 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.000150 -0.095000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.098450 -0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.015970 -0.095000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.098450 0.000000 -vn 0.707107 0.000000 -0.707107 -v -0.040000 -0.073200 -0.000000 -vn 0.707107 0.000000 -0.707107 -v -0.040000 -0.083500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.083500 -0.000000 -vn 0.680317 0.067005 -0.729849 -v -0.040000 -0.093000 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.040735 -0.098450 -0.000000 -vn 0.607118 0.251478 -0.753768 -v -0.039848 -0.093765 -0.000000 -vn 0.464670 0.464670 -0.753766 -v -0.039414 -0.094414 -0.000000 -vn 0.251477 0.607118 -0.753769 -v -0.038765 -0.094848 -0.000000 -vn 0.067004 0.680318 -0.729848 -v -0.038000 -0.095000 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.019605 -0.095000 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.019605 -0.050000 -0.000000 -vn 0.067005 -0.680317 -0.729849 -v -0.038000 -0.050000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.044875 -0.000000 -vn 0.251478 -0.607119 -0.753767 -v -0.038765 -0.050152 -0.000000 -vn 0.464669 -0.464669 -0.753767 -v -0.039414 -0.050586 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.073200 -0.000000 -vn 0.707107 0.000000 -0.707107 -v -0.040000 -0.057425 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.057425 -0.000000 -vn 0.680317 -0.067005 -0.729849 -v -0.040000 -0.052000 -0.000000 -vn 0.607119 -0.251478 -0.753768 -v -0.039848 -0.051235 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.019605 -0.044875 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.044875 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.000150 -0.050000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.044875 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.015970 -0.050000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.044875 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.044875 0.000000 -vn -0.464669 -0.464669 -0.753767 -v 0.039414 -0.050586 0.000000 -vn -0.251477 -0.607119 -0.753768 -v 0.038765 -0.050152 0.000000 -vn -0.067005 -0.680317 -0.729849 -v 0.038000 -0.050000 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.037245 -0.050000 0.000000 -vn -0.707107 0.000000 -0.707107 -v 0.040000 -0.057425 0.000000 -vn -0.680317 -0.067005 -0.729849 -v 0.040000 -0.052000 0.000000 -vn -0.607119 -0.251478 -0.753767 -v 0.039848 -0.051235 0.000000 -vn 0.000000 0.637729 -0.770261 -v 0.053750 -0.071150 0.000000 -vn -0.318864 0.552288 -0.770263 -v 0.055325 -0.070728 0.000000 -vn -0.552289 -0.318863 -0.770261 -v 0.056478 -0.066425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.057425 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.056900 -0.068000 0.000000 -vn -0.552289 0.318864 -0.770261 -v 0.056478 -0.069575 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.051022 -0.069575 0.000000 -vn 0.318863 0.552288 -0.770262 -v 0.052175 -0.070728 0.000000 -vn -0.707107 -0.000000 -0.707106 -v 0.040000 -0.073200 0.000000 -vn -0.318864 -0.552288 -0.770263 -v 0.055325 -0.065272 0.000000 -vn 0.000000 -0.637729 -0.770261 -v 0.053750 -0.064850 0.000000 -vn 0.318863 -0.552288 -0.770262 -v 0.052175 -0.065272 0.000000 -vn 0.552289 -0.318863 -0.770262 -v 0.051022 -0.066425 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.050600 -0.068000 0.000000 -vn -0.000000 -0.637729 -0.770261 -v 0.057440 -0.078000 0.000000 -vn 0.318863 -0.552287 -0.770263 -v 0.056440 -0.078268 0.000000 -vn 0.552290 -0.318863 -0.770261 -v 0.055708 -0.079000 0.000000 -vn 0.637728 -0.000001 -0.770262 -v 0.055440 -0.080000 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.055708 -0.081000 0.000000 -vn 0.318865 0.552288 -0.770261 -v 0.056440 -0.081732 0.000000 -vn -0.707107 -0.000000 -0.707107 -v 0.040000 0.083500 0.000000 -vn -0.680317 -0.067005 -0.729849 -v 0.040000 0.093000 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 0.098450 0.000000 -vn -0.607118 -0.251478 -0.753768 -v 0.039848 0.093765 0.000000 -vn -0.464670 -0.464670 -0.753766 -v 0.039414 0.094414 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.037245 0.098450 0.000000 -vn -0.251477 -0.607118 -0.753769 -v 0.038765 0.094848 0.000000 -vn -0.067004 -0.680318 -0.729848 -v 0.038000 0.095000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.083500 0.000000 -vn -0.318865 -0.552288 -0.770261 -v 0.058440 0.081732 0.000000 -vn -0.000000 -0.637727 -0.770263 -v 0.057440 0.082000 0.000000 -vn 0.318865 -0.552288 -0.770262 -v 0.056440 0.081732 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.055708 0.081000 0.000000 -vn -0.707107 0.000000 -0.707107 -v 0.040000 0.076625 0.000000 -vn 0.637728 0.000001 -0.770262 -v 0.055440 0.080000 0.000000 -vn 0.552290 0.318863 -0.770261 -v 0.055708 0.079000 0.000000 -vn 0.318863 0.552287 -0.770263 -v 0.056440 0.078268 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 0.076625 0.000000 -vn -0.707107 0.000000 -0.707106 -v 0.040000 0.073200 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.051022 0.069575 0.000000 -vn 0.637728 -0.000000 -0.770262 -v 0.050600 0.068000 0.000000 -vn 0.318863 0.552288 -0.770262 -v 0.052175 0.065272 0.000000 -vn 0.000000 0.637729 -0.770261 -v 0.053750 0.064850 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.039625 0.000000 -vn -0.318864 0.552288 -0.770263 -v 0.055325 0.065272 0.000000 -vn -0.680317 0.067005 -0.729849 -v 0.040000 0.052000 0.000000 -vn -0.552289 0.318863 -0.770261 -v 0.056478 0.066425 0.000000 -vn -0.637728 -0.000000 -0.770262 -v 0.056900 0.068000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.073200 0.000000 -vn -0.552289 -0.318864 -0.770261 -v 0.056478 0.069575 0.000000 -vn -0.318864 -0.552288 -0.770263 -v 0.055325 0.070728 0.000000 -vn 0.000000 -0.637729 -0.770261 -v 0.053750 0.071150 0.000000 -vn 0.318863 -0.552288 -0.770262 -v 0.052175 0.070728 0.000000 -vn -0.067005 0.680317 -0.729849 -v 0.038000 0.050000 0.000000 -vn -0.251477 0.607119 -0.753767 -v 0.038765 0.050152 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.039625 0.000000 -vn -0.464669 0.464669 -0.753767 -v 0.039414 0.050586 0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.037245 0.050000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.039625 0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.015970 0.050000 0.000000 -vn 0.464670 -0.464670 -0.753766 -v -0.039414 0.094414 -0.000000 -vn 0.607118 -0.251478 -0.753768 -v -0.039848 0.093765 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.098450 -0.000000 -vn 0.680317 -0.067005 -0.729849 -v -0.040000 0.093000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.083500 -0.000000 -vn 0.707107 0.000000 -0.707107 -v -0.040000 0.083500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.076625 -0.000000 -vn 0.707107 0.000000 -0.707107 -v -0.040000 0.076625 -0.000000 -vn 0.707107 0.000000 -0.707107 -v -0.040000 0.073200 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.019605 0.095000 -0.000000 -vn 0.067004 -0.680318 -0.729848 -v -0.038000 0.095000 -0.000000 -vn 0.251477 -0.607118 -0.753769 -v -0.038765 0.094848 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.047555 0.038250 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.048470 0.039165 -0.000000 -vn 0.000000 -0.637727 -0.770262 -v -0.049720 0.039500 -0.000000 -vn 0.318864 -0.552288 -0.770262 -v -0.050970 0.039165 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.054485 0.039625 -0.000000 -vn 0.552288 -0.318864 -0.770262 -v -0.051885 0.038250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.034375 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.040735 0.029625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.034375 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.040095 0.034618 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.049720 0.034500 -0.000000 -vn 0.552288 0.318863 -0.770262 -v -0.041102 0.035625 -0.000000 -vn 0.637728 -0.000000 -0.770262 -v -0.052220 0.037000 -0.000000 -vn 0.552288 0.318864 -0.770262 -v -0.051885 0.035750 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.050970 0.034835 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.048470 0.034835 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.047555 0.035750 -0.000000 -vn 0.637728 0.000000 -0.770261 -v -0.041470 0.037000 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.047220 0.037000 -0.000000 -vn 0.552289 -0.318863 -0.770262 -v -0.041102 0.038375 -0.000000 -vn 0.318863 -0.552289 -0.770262 -v -0.040095 0.039382 -0.000000 -vn 0.318864 -0.552288 -0.770262 -v -0.050970 -0.034835 -0.000000 -vn 0.552288 -0.318864 -0.770262 -v -0.051885 -0.035750 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.054485 -0.029625 -0.000000 -vn 0.318864 -0.552288 -0.770262 -v -0.040095 -0.034618 -0.000000 -vn 0.552289 -0.318863 -0.770262 -v -0.041102 -0.035625 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.048470 -0.039165 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.047555 -0.038250 -0.000000 -vn 0.552288 0.318863 -0.770262 -v -0.041102 -0.038375 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.039625 -0.000000 -vn 0.552288 0.318864 -0.770262 -v -0.051885 -0.038250 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.050970 -0.039165 -0.000000 -vn 0.637728 -0.000000 -0.770262 -v -0.052220 -0.037000 -0.000000 -vn 0.637728 0.000000 -0.770261 -v -0.041470 -0.037000 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.047220 -0.037000 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.047555 -0.035750 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.048470 -0.034835 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.049720 -0.034500 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.037345 -0.034618 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.038720 -0.034250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.029625 -0.000000 -vn 0.088121 0.669353 -0.737700 -v -0.030220 -0.039750 -0.000000 -vn 0.000000 0.637728 -0.770261 -v -0.038720 -0.039750 -0.000000 -vn 0.318863 0.552289 -0.770262 -v -0.031595 -0.039382 -0.000000 -vn -0.318863 0.552289 -0.770262 -v -0.037345 -0.039382 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.036338 -0.038375 -0.000000 -vn -0.088122 -0.669352 -0.737700 -v -0.019970 -0.034250 -0.000000 -vn 0.088122 -0.669353 -0.737700 -v -0.030220 -0.034250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 -0.029625 -0.000000 -vn 0.318864 -0.552288 -0.770262 -v -0.031595 -0.034618 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.036338 -0.035625 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.032602 -0.035625 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.035970 -0.037000 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.032970 -0.037000 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.032602 -0.038375 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.017220 -0.037000 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.017588 -0.035625 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.018595 -0.034618 -0.000000 -vn -0.088121 0.669353 -0.737700 -v -0.019970 -0.039750 -0.000000 -vn -0.318863 0.552289 -0.770262 -v -0.018595 -0.039382 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.039625 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.017588 -0.038375 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.049720 -0.039500 -0.000000 -vn 0.318863 0.552289 -0.770262 -v -0.040095 -0.039382 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.039625 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.027470 -0.024665 -0.000000 -vn -0.000000 0.637728 -0.770262 -v -0.026220 -0.025000 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.024970 -0.024665 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 -0.024575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.024575 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.028385 -0.023750 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.024055 -0.023750 -0.000000 -vn -0.637727 -0.000000 -0.770262 -v -0.023720 -0.022500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 -0.019250 -0.000000 -vn -0.552288 -0.318865 -0.770262 -v -0.024055 -0.021250 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.024970 -0.020335 -0.000000 -vn -0.000000 -0.637728 -0.770262 -v -0.026220 -0.020000 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.027470 -0.020335 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.040735 -0.019250 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.028385 -0.021250 -0.000000 -vn 0.637728 0.000001 -0.770262 -v -0.028720 -0.022500 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.008840 -0.025000 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.010090 -0.024665 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.011005 -0.023750 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.006675 -0.023750 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.006340 -0.022500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.019250 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.006675 -0.021250 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.007590 -0.020335 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.008840 -0.020000 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.010090 -0.020335 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.011005 -0.021250 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.011340 -0.022500 -0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.008540 -0.025000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.029625 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.009790 -0.024665 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.024575 0.000000 -vn -0.552288 0.318864 -0.770262 -v 0.010705 -0.023750 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.011040 -0.022500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.019250 0.000000 -vn -0.552289 -0.318864 -0.770262 -v 0.010705 -0.021250 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.009790 -0.020335 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.008540 -0.020000 0.000000 -vn 0.318864 -0.552289 -0.770262 -v 0.007290 -0.020335 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.006375 -0.021250 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.006040 -0.022500 0.000000 -vn -0.000000 0.637727 -0.770262 -v -0.080000 -0.139100 -0.000000 -vn -0.318865 0.552288 -0.770262 -v -0.078450 -0.138685 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 -0.142050 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.137875 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 -0.137875 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.082685 -0.137550 -0.000000 -vn -0.727973 -0.095840 -0.678874 -v -0.092000 -0.140000 -0.000000 -vn 0.318865 0.552288 -0.770262 -v -0.081550 -0.138685 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.072825 -0.145000 -0.000000 -vn 0.378581 -0.655722 -0.653226 -v -0.045500 -0.144330 -0.000000 -vn 0.095839 -0.727973 -0.678875 -v -0.048000 -0.145000 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.054485 -0.145000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.137875 -0.000000 -vn 0.318866 -0.552288 -0.770262 -v -0.041500 -0.137402 -0.000000 -vn 0.552289 -0.318864 -0.770261 -v -0.042598 -0.138500 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.054485 -0.133625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.133625 -0.000000 -vn 0.088123 -0.669352 -0.737701 -v -0.040000 -0.137000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 -0.133625 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.019605 -0.137000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.133625 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.000150 -0.137000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.133625 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.015970 -0.137000 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.037245 -0.133625 0.000000 -vn -0.318866 -0.552288 -0.770261 -v 0.040500 -0.137402 0.000000 -vn -0.088123 -0.669352 -0.737701 -v 0.039000 -0.137000 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.037245 -0.137000 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.055708 -0.136500 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.055440 -0.135500 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.055708 -0.134500 0.000000 -vn 0.318865 0.552288 -0.770262 -v 0.056440 -0.137232 0.000000 -vn -0.000000 0.637727 -0.770263 -v 0.057440 -0.137500 0.000000 -vn -0.318865 0.552288 -0.770261 -v 0.058440 -0.137232 0.000000 -vn 0.727973 -0.095840 -0.678874 -v 0.100000 -0.140000 0.000000 -vn 0.655722 -0.378581 -0.653227 -v 0.099330 -0.142500 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.097285 -0.142050 0.000000 -vn 0.378581 -0.655722 -0.653227 -v 0.097500 -0.144330 0.000000 -vn 0.095839 -0.727973 -0.678875 -v 0.095000 -0.145000 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.137875 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.097285 -0.137875 0.000000 -vn -0.552288 0.318865 -0.770261 -v 0.094302 0.134500 0.000000 -vn -0.637727 -0.000000 -0.770263 -v 0.094570 0.135500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.133625 0.000000 -vn 0.378581 0.655722 -0.653227 -v 0.097500 0.144330 0.000000 -vn 0.655722 0.378581 -0.653227 -v 0.099330 0.142500 0.000000 -vn 0.318865 -0.552288 -0.770262 -v 0.091570 0.137232 0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.085500 0.145000 0.000000 -vn 0.000000 -0.637727 -0.770263 -v 0.092570 0.137500 0.000000 -vn 0.095839 0.727973 -0.678875 -v 0.095000 0.145000 0.000000 -vn -0.318865 -0.552288 -0.770262 -v 0.093570 0.137232 0.000000 -vn -0.552288 -0.318865 -0.770261 -v 0.094302 0.136500 0.000000 -vn 0.552289 -0.318862 -0.770262 -v 0.090838 0.136500 0.000000 -vn 0.637729 -0.000000 -0.770261 -v 0.090570 0.135500 0.000000 -vn 0.552289 0.318862 -0.770262 -v 0.090838 0.134500 0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.058170 0.145000 0.000000 -vn -0.000000 -0.637727 -0.770263 -v 0.057440 0.137500 0.000000 -vn -0.095839 0.727973 -0.678874 -v 0.047000 0.145000 0.000000 -vn 0.318865 -0.552288 -0.770261 -v 0.056440 0.137232 0.000000 -vn -0.378581 0.655722 -0.653227 -v 0.044500 0.144330 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.055708 0.136500 0.000000 -vn -0.655722 0.378581 -0.653227 -v 0.042670 0.142500 0.000000 -vn -0.683013 0.183013 -0.707107 -v 0.042000 0.140000 0.000000 -vn -0.552289 0.318863 -0.770262 -v 0.041598 0.138500 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.055440 0.135500 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.055708 0.134500 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.133625 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.000150 0.137000 -0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.015970 0.137000 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.133625 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.019605 0.137000 -0.000000 -vn 0.552289 0.318864 -0.770261 -v -0.042598 0.138500 -0.000000 -vn 0.318866 0.552288 -0.770262 -v -0.041500 0.137402 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.040735 0.133625 -0.000000 -vn 0.088123 0.669352 -0.737701 -v -0.040000 0.137000 -0.000000 -vn 0.683012 0.183013 -0.707107 -v -0.043000 0.140000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.133625 -0.000000 -vn 0.655722 0.378581 -0.653227 -v -0.043670 0.142500 -0.000000 -vn 0.378581 0.655722 -0.653226 -v -0.045500 0.144330 -0.000000 -vn 0.095839 0.727973 -0.678875 -v -0.048000 0.145000 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.054485 0.145000 -0.000000 -vn -0.637727 -0.000001 -0.770263 -v -0.076900 0.136000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.133625 -0.000000 -vn -0.552288 0.318865 -0.770262 -v -0.077315 0.134450 -0.000000 -vn -0.318865 0.552288 -0.770262 -v -0.078450 0.133315 -0.000000 -vn -0.552288 -0.318865 -0.770261 -v -0.077315 0.137550 -0.000000 -vn -0.318865 -0.552288 -0.770261 -v -0.078450 0.138685 -0.000000 -vn 0.000000 0.707107 -0.707107 -v -0.072825 0.145000 -0.000000 -vn -0.095838 0.727973 -0.678875 -v -0.087000 0.145000 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 0.133625 -0.000000 -vn -0.727973 0.095840 -0.678874 -v -0.092000 0.140000 -0.000000 -vn 0.637728 -0.000001 -0.770261 -v -0.083100 0.136000 -0.000000 -vn 0.552288 -0.318864 -0.770262 -v -0.082685 0.137550 -0.000000 -vn -0.000000 -0.637727 -0.770262 -v -0.080000 0.139100 -0.000000 -vn 0.318865 -0.552288 -0.770262 -v -0.081550 0.138685 -0.000000 -vn -0.378581 0.655722 -0.653226 -v -0.089500 0.144330 -0.000000 -vn -0.655722 0.378581 -0.653227 -v -0.091330 0.142500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.119575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.119575 -0.000000 -vn 0.000000 0.637727 -0.770262 -v -0.028740 0.121900 -0.000000 -vn 0.318865 0.552288 -0.770262 -v -0.029790 0.122181 -0.000000 -vn -0.552288 0.318865 -0.770262 -v -0.022224 0.126625 -0.000000 -vn -0.637727 -0.000000 -0.770262 -v -0.021990 0.127500 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.019605 0.131075 -0.000000 -vn -0.552291 -0.318863 -0.770260 -v -0.022224 0.128375 -0.000000 -vn -0.318866 -0.552285 -0.770263 -v -0.022865 0.129016 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.023740 0.129250 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.023740 0.125750 -0.000000 -vn -0.318863 0.552289 -0.770262 -v -0.022865 0.125984 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.123825 -0.000000 -vn 0.318865 -0.552286 -0.770263 -v -0.024615 0.129016 -0.000000 -vn 0.000000 -0.637727 -0.770262 -v -0.028740 0.126100 -0.000000 -vn 0.552291 -0.318863 -0.770260 -v -0.025256 0.128375 -0.000000 -vn -0.318866 -0.552287 -0.770262 -v -0.027690 0.125819 -0.000000 -vn 0.318866 -0.552287 -0.770262 -v -0.029790 0.125819 -0.000000 -vn 0.552290 -0.318864 -0.770261 -v -0.030559 0.125050 -0.000000 -vn 0.637727 -0.000001 -0.770262 -v -0.030840 0.124000 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.030559 0.122950 -0.000000 -vn 0.637727 0.000000 -0.770262 -v -0.025490 0.127500 -0.000000 -vn 0.552288 0.318865 -0.770262 -v -0.025256 0.126625 -0.000000 -vn -0.552290 -0.318864 -0.770261 -v -0.026921 0.125050 -0.000000 -vn 0.318863 0.552289 -0.770262 -v -0.024615 0.125984 -0.000000 -vn -0.637727 -0.000001 -0.770262 -v -0.026640 0.124000 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.026921 0.122950 -0.000000 -vn -0.318865 0.552288 -0.770262 -v -0.027690 0.122181 -0.000000 -vn 0.318866 -0.552285 -0.770263 -v 0.022865 0.129016 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.023740 0.129250 0.000000 -vn -0.318865 -0.552286 -0.770263 -v 0.024615 0.129016 0.000000 -vn -0.637727 -0.000001 -0.770262 -v 0.030840 0.124000 0.000000 -vn -0.552290 -0.318864 -0.770261 -v 0.030559 0.125050 0.000000 -vn -0.318866 -0.552287 -0.770262 -v 0.029790 0.125819 0.000000 -vn 0.000000 -0.637727 -0.770262 -v 0.028740 0.126100 0.000000 -vn -0.552291 -0.318863 -0.770260 -v 0.025256 0.128375 0.000000 -vn 0.318866 -0.552287 -0.770262 -v 0.027690 0.125819 0.000000 -vn -0.637727 -0.000000 -0.770262 -v 0.025490 0.127500 0.000000 -vn -0.552288 0.318865 -0.770262 -v 0.025256 0.126625 0.000000 -vn -0.318863 0.552289 -0.770262 -v 0.024615 0.125984 0.000000 -vn 0.552290 -0.318864 -0.770261 -v 0.026921 0.125050 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.023740 0.125750 0.000000 -vn 0.552292 -0.318863 -0.770260 -v 0.022224 0.128375 0.000000 -vn 0.637727 0.000000 -0.770262 -v 0.021990 0.127500 0.000000 -vn 0.637727 -0.000001 -0.770262 -v 0.026640 0.124000 0.000000 -vn 0.552288 0.318864 -0.770262 -v 0.026921 0.122950 0.000000 -vn 0.318863 0.552289 -0.770262 -v 0.022865 0.125984 0.000000 -vn 0.552288 0.318865 -0.770262 -v 0.022224 0.126625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.119575 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.015970 0.119575 0.000000 -vn 0.000000 0.637727 -0.770262 -v 0.028740 0.121900 0.000000 -vn 0.318865 0.552288 -0.770262 -v 0.027690 0.122181 0.000000 -vn -0.318865 0.552286 -0.770263 -v 0.024615 -0.129016 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.131075 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.023740 -0.129250 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.015970 -0.131075 0.000000 -vn 0.318866 0.552285 -0.770263 -v 0.022865 -0.129016 0.000000 -vn 0.318863 -0.552289 -0.770262 -v 0.022865 -0.125984 0.000000 -vn 0.552288 -0.318865 -0.770262 -v 0.022224 -0.126625 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.015970 -0.119575 0.000000 -vn 0.000000 0.637727 -0.770262 -v 0.028740 -0.126100 0.000000 -vn -0.318866 0.552287 -0.770262 -v 0.029790 -0.125819 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.127675 0.000000 -vn -0.552290 0.318864 -0.770261 -v 0.030559 -0.125050 0.000000 -vn -0.637727 0.000001 -0.770262 -v 0.030840 -0.124000 0.000000 -vn -0.552288 -0.318864 -0.770262 -v 0.030559 -0.122950 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.119575 0.000000 -vn -0.318863 -0.552289 -0.770261 -v 0.024615 -0.125984 0.000000 -vn 0.552290 0.318864 -0.770261 -v 0.026921 -0.125050 0.000000 -vn -0.552288 -0.318865 -0.770262 -v 0.025256 -0.126625 0.000000 -vn 0.318866 0.552287 -0.770262 -v 0.027690 -0.125819 0.000000 -vn -0.637727 -0.000000 -0.770262 -v 0.025490 -0.127500 0.000000 -vn -0.552291 0.318863 -0.770260 -v 0.025256 -0.128375 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.023740 -0.125750 0.000000 -vn -0.318865 -0.552288 -0.770262 -v 0.029790 -0.122181 0.000000 -vn 0.000000 -0.637727 -0.770262 -v 0.028740 -0.121900 0.000000 -vn 0.318865 -0.552288 -0.770262 -v 0.027690 -0.122181 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.026921 -0.122950 0.000000 -vn 0.637727 0.000001 -0.770262 -v 0.026640 -0.124000 0.000000 -vn -0.637727 -0.000000 -0.770262 -v -0.021990 -0.127500 -0.000000 -vn -0.552288 -0.318865 -0.770262 -v -0.022224 -0.126625 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.019605 -0.119575 -0.000000 -vn -0.318866 0.552285 -0.770263 -v -0.022865 -0.129016 -0.000000 -vn -0.552291 0.318863 -0.770260 -v -0.022224 -0.128375 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.019605 -0.127675 -0.000000 -vn 0.552288 -0.318864 -0.770262 -v -0.030559 -0.122950 -0.000000 -vn 0.637727 0.000001 -0.770262 -v -0.030840 -0.124000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.127675 -0.000000 -vn -0.318866 0.552287 -0.770262 -v -0.027690 -0.125819 -0.000000 -vn 0.637727 0.000000 -0.770262 -v -0.025490 -0.127500 -0.000000 -vn 0.000000 0.637727 -0.770262 -v -0.028740 -0.126100 -0.000000 -vn 0.552291 0.318863 -0.770260 -v -0.025256 -0.128375 -0.000000 -vn 0.318866 0.552287 -0.770262 -v -0.029790 -0.125819 -0.000000 -vn 0.552290 0.318864 -0.770261 -v -0.030559 -0.125050 -0.000000 -vn -0.318863 -0.552289 -0.770262 -v -0.022865 -0.125984 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.023740 -0.125750 -0.000000 -vn 0.318863 -0.552289 -0.770261 -v -0.024615 -0.125984 -0.000000 -vn -0.552290 0.318864 -0.770261 -v -0.026921 -0.125050 -0.000000 -vn 0.552288 -0.318865 -0.770262 -v -0.025256 -0.126625 -0.000000 -vn 0.000000 -0.637727 -0.770262 -v -0.028740 -0.121900 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.119575 -0.000000 -vn 0.318865 -0.552288 -0.770262 -v -0.029790 -0.122181 -0.000000 -vn -0.637727 0.000001 -0.770262 -v -0.026640 -0.124000 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.026921 -0.122950 -0.000000 -vn -0.318865 -0.552288 -0.770262 -v -0.027690 -0.122181 -0.000000 -vn 0.318865 0.552286 -0.770263 -v -0.024615 -0.129016 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.131075 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.023740 -0.129250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 -0.131075 -0.000000 -vn 0.552289 0.318863 -0.770262 -v -0.082685 0.134450 -0.000000 -vn 0.318865 0.552288 -0.770262 -v -0.081550 0.133315 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 0.131075 -0.000000 -vn -0.318863 -0.552289 -0.770262 -v 0.025550 0.107685 0.000000 -vn 0.000000 -0.637728 -0.770261 -v 0.024000 0.108100 0.000000 -vn 0.318863 -0.552289 -0.770262 -v 0.022450 0.107685 0.000000 -vn 0.637728 0.000001 -0.770262 -v 0.020900 0.105000 0.000000 -vn 0.552288 0.318864 -0.770262 -v 0.021315 0.103450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.098450 0.000000 -vn -0.552288 0.318864 -0.770262 -v 0.026685 0.103450 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.027100 0.105000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.107800 0.000000 -vn -0.552288 -0.318864 -0.770262 -v 0.026685 0.106550 0.000000 -vn 0.552289 -0.318863 -0.770262 -v 0.021315 0.106550 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.107800 0.000000 -vn -0.318865 0.552288 -0.770262 -v 0.025550 0.102315 0.000000 -vn 0.000000 0.637727 -0.770262 -v 0.024000 0.101900 0.000000 -vn 0.318865 0.552288 -0.770262 -v 0.022450 0.102315 0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.061735 -0.142050 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.137875 -0.000000 -vn 0.318862 0.552289 -0.770263 -v -0.060125 -0.137949 -0.000000 -vn -0.318862 0.552289 -0.770263 -v -0.057875 -0.137949 -0.000000 -vn 0.000000 0.637730 -0.770260 -v -0.059000 -0.138250 -0.000000 -vn -0.552288 0.318865 -0.770262 -v -0.057051 -0.137125 -0.000000 -vn -0.637728 0.000001 -0.770262 -v -0.056750 -0.136000 -0.000000 -vn -0.552289 -0.318863 -0.770262 -v -0.057051 -0.134875 -0.000000 -vn -0.318862 -0.552289 -0.770263 -v -0.057875 -0.134051 -0.000000 -vn 0.000000 -0.637730 -0.770260 -v -0.059000 -0.133750 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.061735 -0.133625 -0.000000 -vn 0.318862 -0.552289 -0.770263 -v -0.060125 -0.134051 -0.000000 -vn 0.552289 -0.318863 -0.770262 -v -0.060949 -0.134875 -0.000000 -vn 0.637728 0.000001 -0.770262 -v -0.061250 -0.136000 -0.000000 -vn 0.552288 0.318865 -0.770262 -v -0.060949 -0.137125 -0.000000 -vn -0.552288 0.318865 -0.770261 -v -0.077315 -0.137550 -0.000000 -vn -0.637727 0.000001 -0.770263 -v -0.076900 -0.136000 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 -0.133625 -0.000000 -vn -0.552288 -0.318865 -0.770262 -v -0.077315 -0.134450 -0.000000 -vn -0.318865 -0.552288 -0.770261 -v -0.078450 -0.133315 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.131075 -0.000000 -vn -0.000000 -0.637727 -0.770262 -v -0.080000 -0.132900 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.131075 -0.000000 -vn 0.318865 -0.552288 -0.770262 -v -0.081550 -0.133315 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.133625 -0.000000 -vn 0.552289 -0.318863 -0.770262 -v -0.082685 -0.134450 -0.000000 -vn 0.637728 0.000001 -0.770261 -v -0.083100 -0.136000 -0.000000 -vn -0.637727 -0.000000 -0.770263 -v 0.059440 -0.135500 0.000000 -vn -0.552288 -0.318865 -0.770262 -v 0.059172 -0.134500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.133625 0.000000 -vn -0.318865 -0.552288 -0.770261 -v 0.058440 -0.133768 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.133625 0.000000 -vn -0.000000 -0.637727 -0.770263 -v 0.057440 -0.133500 0.000000 -vn -0.552288 -0.318865 -0.770261 -v 0.094302 -0.134500 0.000000 -vn 0.318865 -0.552288 -0.770262 -v 0.091570 -0.133768 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.085500 -0.133625 0.000000 -vn 0.552289 -0.318862 -0.770262 -v 0.090838 -0.134500 0.000000 -vn 0.000000 0.637727 -0.770263 -v 0.092570 -0.137500 0.000000 -vn -0.318865 0.552288 -0.770262 -v 0.093570 -0.137232 0.000000 -vn -0.552288 0.318865 -0.770262 -v 0.094302 -0.136500 0.000000 -vn -0.637727 -0.000000 -0.770263 -v 0.094570 -0.135500 0.000000 -vn 0.637729 -0.000000 -0.770261 -v 0.090570 -0.135500 0.000000 -vn 0.552289 0.318862 -0.770262 -v 0.090838 -0.136500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.137875 0.000000 -vn 0.318865 0.552288 -0.770261 -v 0.091570 -0.137232 0.000000 -vn -0.552288 0.318865 -0.770262 -v 0.059172 0.134500 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.067250 0.133625 0.000000 -vn -0.637727 -0.000000 -0.770263 -v 0.059440 0.135500 0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.067250 0.145000 0.000000 -vn -0.552288 -0.318865 -0.770262 -v 0.059172 0.136500 0.000000 -vn -0.318865 -0.552288 -0.770261 -v 0.058440 0.137232 0.000000 -vn -0.000000 0.637729 -0.770261 -v 0.057440 0.078000 0.000000 -vn -0.318864 0.552287 -0.770263 -v 0.058440 0.078268 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.076625 0.000000 -vn -0.552290 0.318865 -0.770261 -v 0.059172 0.079000 0.000000 -vn -0.637727 0.000001 -0.770263 -v 0.059440 0.080000 0.000000 -vn -0.552288 -0.318865 -0.770261 -v 0.059172 0.081000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.083500 0.000000 -vn -0.000000 0.637727 -0.770263 -v 0.057440 -0.082000 0.000000 -vn -0.318865 0.552288 -0.770261 -v 0.058440 -0.081732 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.083500 0.000000 -vn -0.552288 0.318865 -0.770262 -v 0.059172 -0.081000 0.000000 -vn -0.637727 -0.000001 -0.770263 -v 0.059440 -0.080000 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.067250 -0.073200 0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 0.107800 -0.000000 -vn -0.318864 -0.552289 -0.770262 -v -0.074375 0.105993 -0.000000 -vn 0.000000 -0.637727 -0.770262 -v -0.080000 0.107500 -0.000000 -vn -0.707107 -0.000000 -0.707106 -v -0.092000 0.107800 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.070257 0.101875 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.061735 0.107800 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.068750 0.096250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.098450 -0.000000 -vn -0.552289 0.318864 -0.770262 -v -0.070257 0.090625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.083500 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.074375 0.086507 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.089743 0.090625 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 0.083500 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.091250 0.096250 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 0.098450 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.089743 0.101875 -0.000000 -vn 0.318864 -0.552288 -0.770262 -v -0.085625 0.105993 -0.000000 -vn 0.318863 0.552289 -0.770262 -v -0.085625 0.086507 -0.000000 -vn -0.000001 0.637728 -0.770262 -v -0.080000 0.085000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.083500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.083500 -0.000000 -vn -0.318864 -0.552289 -0.770262 -v -0.074375 -0.086507 -0.000000 -vn 0.000001 -0.637728 -0.770262 -v -0.080000 -0.085000 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 -0.083500 -0.000000 -vn 0.318865 -0.552288 -0.770262 -v -0.085625 -0.086507 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.089743 -0.090625 -0.000000 -vn 0.637728 -0.000000 -0.770262 -v -0.091250 -0.096250 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.070257 -0.090625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.083500 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.089743 -0.101875 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.110425 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 -0.098450 -0.000000 -vn 0.318864 0.552289 -0.770262 -v -0.085625 -0.105993 -0.000000 -vn -0.000000 0.637728 -0.770262 -v -0.080000 -0.107500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.110425 -0.000000 -vn -0.318864 0.552289 -0.770262 -v -0.074375 -0.105993 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.061735 -0.110425 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 0.076625 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.081949 0.078625 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.078051 0.078625 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.077750 0.077500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.076625 -0.000000 -vn -0.552289 0.318864 -0.770262 -v -0.078051 0.076375 -0.000000 -vn -0.318864 -0.552289 -0.770262 -v -0.078875 0.079449 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 0.079750 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.081125 0.079449 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.082250 0.077500 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.081949 0.076375 -0.000000 -vn -0.707107 -0.000000 -0.707106 -v -0.092000 0.073200 -0.000000 -vn 0.318864 0.552289 -0.770262 -v -0.081125 0.075551 -0.000000 -vn -0.318864 0.552289 -0.770262 -v -0.078875 0.075551 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 0.073200 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.080000 0.075250 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v 0.088493 0.005625 0.000000 -vn -0.318864 -0.552289 -0.770262 -v 0.084375 0.009743 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.085500 0.012625 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.078750 0.011250 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.012625 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.097285 0.012625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.012625 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.090000 0.000000 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.069007 -0.005625 0.000000 -vn 0.318864 0.552288 -0.770262 -v 0.073125 -0.009743 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.074200 -0.012625 0.000000 -vn -0.000000 0.637728 -0.770262 -v 0.078750 -0.011250 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.012625 0.000000 -vn -0.318864 0.552289 -0.770262 -v 0.084375 -0.009743 0.000000 -vn -0.552288 0.318864 -0.770262 -v 0.088493 -0.005625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.012625 0.000000 -vn 0.637727 -0.000000 -0.770262 -v 0.067500 0.000000 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.067250 0.012625 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.069007 0.005625 0.000000 -vn 0.318864 -0.552288 -0.770262 -v 0.073125 0.009743 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.074200 0.019250 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.085500 0.019250 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.078750 0.018500 0.000000 -vn -0.318864 -0.552289 -0.770262 -v 0.079875 0.018199 0.000000 -vn 0.318864 -0.552289 -0.770262 -v 0.077625 0.018199 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.076801 0.017375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.015925 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.076500 0.016250 0.000000 -vn 0.552288 0.318864 -0.770262 -v 0.076801 0.015125 0.000000 -vn -0.552288 0.318864 -0.770262 -v 0.080699 0.015125 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.015925 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.081000 0.016250 0.000000 -vn -0.552289 -0.318864 -0.770262 -v 0.080699 0.017375 0.000000 -vn 0.318864 0.552289 -0.770262 -v 0.077625 0.014301 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.078750 0.014000 0.000000 -vn -0.318864 0.552289 -0.770262 -v 0.079875 0.014301 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.019250 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.066022 0.019425 0.000000 -vn 0.000001 -0.637728 -0.770262 -v 0.064750 0.018500 0.000000 -vn 0.318865 -0.552288 -0.770262 -v 0.063625 0.018199 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.062801 0.017375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.015925 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.062500 0.016250 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 0.012625 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.062801 0.015125 0.000000 -vn 0.318864 0.552288 -0.770262 -v 0.063625 0.014301 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.064750 0.014000 0.000000 -vn -0.318864 0.552289 -0.770262 -v 0.065875 0.014301 0.000000 -vn -0.552289 0.318864 -0.770262 -v 0.066699 0.015125 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.015925 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.067000 0.016250 0.000000 -vn 0.318864 0.552288 -0.770262 -v 0.067175 0.018272 0.000000 -vn -0.552288 -0.318864 -0.770262 -v 0.066699 0.017375 0.000000 -vn -0.318864 -0.552289 -0.770262 -v 0.065875 0.018199 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.067250 0.039625 0.000000 -vn 0.318864 0.552288 -0.770263 -v 0.067175 0.065272 0.000000 -vn 0.000000 0.637729 -0.770261 -v 0.068750 0.064850 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.074200 0.039625 0.000000 -vn -0.318864 0.552288 -0.770263 -v 0.070325 0.065272 0.000000 -vn -0.552289 0.318864 -0.770261 -v 0.071478 0.066425 0.000000 -vn -0.637727 -0.000000 -0.770262 -v 0.071900 0.068000 0.000000 -vn -0.552289 -0.318864 -0.770261 -v 0.071478 0.069575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.073200 0.000000 -vn -0.318864 -0.552288 -0.770263 -v 0.070325 0.070728 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.073200 0.000000 -vn 0.000000 -0.637729 -0.770261 -v 0.068750 0.071150 0.000000 -vn 0.318864 -0.552288 -0.770262 -v 0.067175 0.070728 0.000000 -vn 0.552289 0.318864 -0.770261 -v 0.066022 0.066425 0.000000 -vn 0.637727 -0.000000 -0.770262 -v 0.065600 0.068000 0.000000 -vn 0.552289 -0.318864 -0.770261 -v 0.066022 0.069575 0.000000 -vn -0.552289 -0.318864 -0.770262 -v 0.056478 0.022575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.029625 0.000000 -vn -0.637728 -0.000000 -0.770262 -v 0.056900 0.021000 0.000000 -vn -0.552289 0.318864 -0.770262 -v 0.056478 0.019425 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.055325 0.023728 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.053750 0.024150 0.000000 -vn 0.318864 -0.552289 -0.770262 -v 0.052175 0.023728 0.000000 -vn 0.552288 -0.318864 -0.770262 -v 0.051022 0.022575 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.050600 0.021000 0.000000 -vn 0.552288 0.318864 -0.770262 -v 0.051022 0.019425 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.037245 0.015925 0.000000 -vn 0.318864 0.552289 -0.770262 -v 0.052175 0.018272 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.055325 0.018272 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.053750 0.017850 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 -0.019250 0.000000 -vn -0.552289 -0.318864 -0.770262 -v 0.056478 -0.019425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.012625 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.055325 -0.018272 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.053750 -0.017850 0.000000 -vn 0.318864 -0.552289 -0.770262 -v 0.052175 -0.018272 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.012625 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.037245 -0.019250 0.000000 -vn 0.552288 -0.318864 -0.770262 -v 0.051022 -0.019425 0.000000 -vn 0.637728 0.000000 -0.770262 -v 0.050600 -0.021000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.024575 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.053750 -0.024150 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.055325 -0.023728 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.058170 -0.024575 0.000000 -vn -0.552289 0.318864 -0.770262 -v 0.056478 -0.022575 0.000000 -vn -0.637728 -0.000000 -0.770262 -v 0.056900 -0.021000 0.000000 -vn 0.552288 0.318864 -0.770262 -v 0.051022 -0.022575 0.000000 -vn 0.318864 0.552289 -0.770262 -v 0.052175 -0.023728 0.000000 -vn 0.318864 0.552288 -0.770263 -v 0.067175 -0.070728 0.000000 -vn 0.000000 0.637729 -0.770261 -v 0.068750 -0.071150 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.074200 -0.073200 0.000000 -vn -0.552289 0.318864 -0.770261 -v 0.071478 -0.069575 0.000000 -vn -0.637727 0.000000 -0.770262 -v 0.071900 -0.068000 0.000000 -vn -0.318864 0.552288 -0.770263 -v 0.070325 -0.070728 0.000000 -vn -0.552289 -0.318864 -0.770261 -v 0.071478 -0.066425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.057425 0.000000 -vn -0.318864 -0.552288 -0.770263 -v 0.070325 -0.065272 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.057425 0.000000 -vn 0.552289 0.318864 -0.770261 -v 0.066022 -0.069575 0.000000 -vn 0.000000 -0.637729 -0.770261 -v 0.068750 -0.064850 0.000000 -vn 0.318864 -0.552288 -0.770263 -v 0.067175 -0.065272 0.000000 -vn 0.552289 -0.318864 -0.770261 -v 0.066022 -0.066425 0.000000 -vn 0.637727 0.000000 -0.770262 -v 0.065600 -0.068000 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.070325 -0.018272 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.068750 -0.017850 0.000000 -vn -0.552289 0.318864 -0.770261 -v 0.071478 -0.022575 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.067250 -0.024575 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.068750 -0.024150 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.074200 -0.024575 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.070325 -0.023728 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.062801 -0.017375 0.000000 -vn 0.318863 0.552288 -0.770262 -v 0.063625 -0.018199 0.000000 -vn 0.552289 -0.318864 -0.770261 -v 0.066022 -0.019425 0.000000 -vn 0.637727 0.000000 -0.770262 -v 0.065600 -0.021000 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.066022 -0.022575 0.000000 -vn 0.318864 0.552288 -0.770262 -v 0.067175 -0.023728 0.000000 -vn -0.000000 0.637728 -0.770262 -v 0.064750 -0.018500 0.000000 -vn -0.318864 0.552289 -0.770262 -v 0.065875 -0.018199 0.000000 -vn 0.318864 -0.552288 -0.770262 -v 0.067175 -0.018272 0.000000 -vn -0.552288 0.318864 -0.770262 -v 0.066699 -0.017375 0.000000 -vn -0.637728 -0.000000 -0.770262 -v 0.067000 -0.016250 0.000000 -vn -0.552289 -0.318864 -0.770262 -v 0.066699 -0.015125 0.000000 -vn -0.318864 -0.552289 -0.770262 -v 0.065875 -0.014301 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.064750 -0.014000 0.000000 -vn 0.318864 -0.552289 -0.770262 -v 0.063625 -0.014301 0.000000 -vn 0.552288 -0.318864 -0.770262 -v 0.062801 -0.015125 0.000000 -vn 0.637728 -0.000000 -0.770262 -v 0.062500 -0.016250 0.000000 -vn -0.552289 0.318864 -0.770261 -v 0.071478 0.019425 0.000000 -vn -0.637727 0.000000 -0.770262 -v 0.071900 0.021000 0.000000 -vn -0.552289 -0.318864 -0.770262 -v 0.071478 0.022575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.029625 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.070325 0.023728 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.029625 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.070325 0.018272 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.068750 0.017850 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.068750 0.024150 0.000000 -vn 0.318864 -0.552288 -0.770262 -v 0.067175 0.023728 0.000000 -vn 0.552289 -0.318864 -0.770261 -v 0.066022 0.022575 0.000000 -vn 0.637727 0.000000 -0.770262 -v 0.065600 0.021000 0.000000 -vn 0.727973 0.095840 -0.678874 -v 0.100000 0.140000 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.133625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.131075 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.012625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.015925 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.015925 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.019250 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.019250 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.083500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.083500 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.073200 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.097285 -0.073200 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.133625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.123825 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.131075 0.000000 -vn 0.552290 0.318862 -0.770262 -v 0.090838 0.079000 0.000000 -vn 0.318863 0.552287 -0.770263 -v 0.091570 0.078268 0.000000 -vn 0.000000 0.637729 -0.770261 -v 0.092570 0.078000 0.000000 -vn -0.318863 0.552287 -0.770263 -v 0.093570 0.078268 0.000000 -vn -0.552290 0.318864 -0.770261 -v 0.094302 0.079000 0.000000 -vn -0.637727 0.000001 -0.770263 -v 0.094570 0.080000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.083500 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.098450 0.000000 -vn -0.552288 -0.318865 -0.770262 -v 0.094302 0.081000 0.000000 -vn -0.318865 -0.552288 -0.770262 -v 0.093570 0.081732 0.000000 -vn 0.000000 -0.637727 -0.770263 -v 0.092570 0.082000 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.107800 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.098450 0.000000 -vn 0.318865 -0.552288 -0.770261 -v 0.091570 0.081732 0.000000 -vn 0.552289 -0.318862 -0.770262 -v 0.090838 0.081000 0.000000 -vn 0.637729 0.000001 -0.770261 -v 0.090570 0.080000 0.000000 -vn 0.637729 -0.000001 -0.770261 -v 0.090570 -0.080000 0.000000 -vn 0.552289 0.318862 -0.770262 -v 0.090838 -0.081000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.083500 0.000000 -vn 0.318865 0.552288 -0.770261 -v 0.091570 -0.081732 0.000000 -vn 0.000000 0.637727 -0.770263 -v 0.092570 -0.082000 0.000000 -vn -0.318865 0.552288 -0.770262 -v 0.093570 -0.081732 0.000000 -vn -0.552290 -0.318865 -0.770261 -v 0.094302 -0.079000 0.000000 -vn -0.637727 -0.000001 -0.770263 -v 0.094570 -0.080000 0.000000 -vn -0.552288 0.318865 -0.770262 -v 0.094302 -0.081000 0.000000 -vn -0.318863 -0.552287 -0.770263 -v 0.093570 -0.078268 0.000000 -vn 0.000000 -0.637729 -0.770261 -v 0.092570 -0.078000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.073200 0.000000 -vn 0.318863 -0.552287 -0.770263 -v 0.091570 -0.078268 0.000000 -vn 0.552290 -0.318862 -0.770261 -v 0.090838 -0.079000 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.107800 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.098450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.083500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.073200 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.073200 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.039625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.073200 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.029625 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.019250 0.000000 -vn -0.552289 0.318864 -0.770262 -v 0.080699 -0.017375 0.000000 -vn -0.637728 -0.000000 -0.770262 -v 0.081000 -0.016250 0.000000 -vn 0.637728 -0.000000 -0.770262 -v 0.076500 -0.016250 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.076801 -0.017375 0.000000 -vn -0.552288 -0.318864 -0.770262 -v 0.080699 -0.015125 0.000000 -vn 0.318864 0.552289 -0.770262 -v 0.077625 -0.018199 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.078750 -0.018500 0.000000 -vn -0.318864 0.552289 -0.770262 -v 0.079875 -0.018199 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.076801 -0.015125 0.000000 -vn -0.318864 -0.552289 -0.770262 -v 0.079875 -0.014301 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.078750 -0.014000 0.000000 -vn 0.318864 -0.552289 -0.770262 -v 0.077625 -0.014301 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.024575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.024575 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.024575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.057425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.057425 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.057425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.142050 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.067250 -0.145000 0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.074200 0.145000 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.131075 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.123825 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.123825 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.107800 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.107800 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.098450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.098450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.034375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.034375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.034375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 0.034375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 0.034375 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 0.034375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.083500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.133625 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.067250 -0.137875 0.000000 -vn -0.552288 0.318865 -0.770261 -v 0.059172 -0.136500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.137875 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.142050 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.058170 -0.145000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.123825 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.107800 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.107800 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.037245 -0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.044875 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.044875 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.044875 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.044875 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.044875 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.098450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.098450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.098450 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.098450 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.085500 -0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.131075 0.000000 -vn -0.655722 -0.378581 -0.653227 -v 0.042670 -0.142500 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.142050 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.097285 -0.131075 0.000000 -vn -0.095839 -0.727973 -0.678875 -v 0.047000 -0.145000 0.000000 -vn -0.378581 -0.655722 -0.653226 -v 0.044500 -0.144330 0.000000 -vn -0.088123 0.669352 -0.737701 -v 0.039000 0.137000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.123825 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.133625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 0.131075 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 0.123825 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 0.119575 0.000000 -vn -0.318865 0.552288 -0.770262 -v 0.093570 0.133768 0.000000 -vn -0.607119 0.251478 -0.753767 -v 0.039848 0.051235 0.000000 -vn 0.552280 0.318858 -0.770270 -v 0.051022 0.066425 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.037245 0.034375 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 0.012625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.037245 -0.039625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.110425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.110425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.110425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.110425 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.037245 -0.110425 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.058170 -0.127675 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.067250 -0.127675 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.074200 -0.127675 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.119575 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.085500 -0.127675 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.097285 -0.127675 0.000000 -vn 0.707107 0.000000 -0.707107 -v 0.100000 -0.127675 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.031990 0.034500 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.033240 0.034835 0.000000 -vn -0.552289 0.318864 -0.770262 -v 0.034155 0.035750 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.034490 0.037000 0.000000 -vn -0.552289 -0.318864 -0.770261 -v 0.034155 0.038250 0.000000 -vn 0.318864 -0.552288 -0.770262 -v 0.030740 0.039165 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.031990 0.039500 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.033240 0.039165 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.029825 0.038250 0.000000 -vn 0.637728 -0.000000 -0.770262 -v 0.029490 0.037000 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.034375 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.029825 0.035750 0.000000 -vn 0.318864 0.552288 -0.770262 -v 0.030740 0.034835 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.029625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.015925 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.012625 0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 -0.012625 0.000000 -vn -0.552289 0.318864 -0.770262 -v 0.034155 -0.038250 0.000000 -vn -0.637728 0.000000 -0.770262 -v 0.034490 -0.037000 0.000000 -vn 0.318864 -0.552288 -0.770262 -v 0.030740 -0.034835 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.029825 -0.035750 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.033240 -0.034835 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.031990 -0.034500 0.000000 -vn 0.637728 -0.000000 -0.770262 -v 0.029490 -0.037000 0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.029825 -0.038250 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.015970 -0.039625 0.000000 -vn -0.552289 -0.318864 -0.770261 -v 0.034155 -0.035750 0.000000 -vn 0.318865 0.552288 -0.770262 -v 0.030740 -0.039165 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.031990 -0.039500 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.033240 -0.039165 0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.021315 -0.103450 0.000000 -vn 0.318865 -0.552288 -0.770262 -v 0.022450 -0.102315 0.000000 -vn 0.000000 -0.637727 -0.770262 -v 0.024000 -0.101900 0.000000 -vn 0.637728 -0.000000 -0.770262 -v 0.020900 -0.105000 0.000000 -vn 0.552288 0.318864 -0.770262 -v 0.021315 -0.106550 0.000000 -vn 0.000000 -0.000000 -1.000000 -v 0.015970 -0.110425 0.000000 -vn -0.318865 -0.552288 -0.770262 -v 0.025550 -0.102315 0.000000 -vn -0.318863 0.552289 -0.770262 -v 0.025550 -0.107685 0.000000 -vn 0.000000 0.637729 -0.770261 -v 0.024000 -0.108100 0.000000 -vn 0.318863 0.552289 -0.770262 -v 0.022450 -0.107685 0.000000 -vn -0.552289 0.318863 -0.770262 -v 0.026685 -0.106550 0.000000 -vn -0.637728 -0.000001 -0.770262 -v 0.027100 -0.105000 0.000000 -vn -0.552288 -0.318864 -0.770262 -v 0.026685 -0.103450 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.119575 -0.000000 -vn 0.552289 0.318864 -0.770262 -v 0.006375 0.021250 0.000000 -vn 0.318864 0.552288 -0.770262 -v 0.007290 0.020335 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.019250 -0.000000 -vn -0.637728 -0.000000 -0.770262 -v 0.011040 0.022500 0.000000 -vn -0.552288 -0.318864 -0.770262 -v 0.010705 0.023750 0.000000 -vn -0.318864 -0.552288 -0.770262 -v 0.009790 0.024665 0.000000 -vn 0.000000 0.637728 -0.770262 -v 0.008540 0.020000 0.000000 -vn -0.318864 0.552288 -0.770262 -v 0.009790 0.020335 0.000000 -vn -0.552288 0.318864 -0.770262 -v 0.010705 0.021250 0.000000 -vn 0.000000 -0.637728 -0.770262 -v 0.008540 0.025000 0.000000 -vn 0.318864 -0.552289 -0.770262 -v 0.007290 0.024665 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.029625 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v 0.006375 0.023750 0.000000 -vn 0.637728 -0.000000 -0.770262 -v 0.006040 0.022500 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.015925 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.131075 -0.000000 -vn 0.000000 0.000000 -1.000000 -v 0.015970 0.133625 0.000000 -vn 0.000000 0.707107 -0.707107 -v 0.037245 0.137000 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.098450 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 0.107800 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.098450 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.107800 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.011005 0.021250 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.010090 0.020335 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.019250 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.007590 0.024665 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.008840 0.025000 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.008840 0.020000 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.007590 0.020335 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.017588 0.035625 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.010090 0.024665 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.011005 0.023750 -0.000000 -vn 0.637728 -0.000000 -0.770262 -v -0.011340 0.022500 -0.000000 -vn -0.552289 0.318864 -0.770262 -v -0.006675 0.021250 -0.000000 -vn -0.637728 -0.000000 -0.770262 -v -0.006340 0.022500 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.006675 0.023750 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 -0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.019605 0.015925 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.119575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.127675 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.131075 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.037245 0.095000 0.000000 -vn 0.000000 -0.707107 -0.707107 -v 0.015970 0.095000 0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.000150 0.095000 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.040735 0.107800 -0.000000 -vn -0.000000 0.637728 -0.770262 -v -0.026220 0.020000 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.024970 0.020335 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.019250 -0.000000 -vn 0.552288 -0.318864 -0.770262 -v -0.028385 0.023750 -0.000000 -vn 0.637727 0.000000 -0.770262 -v -0.028720 0.022500 -0.000000 -vn 0.552288 0.318864 -0.770262 -v -0.028385 0.021250 -0.000000 -vn 0.318864 0.552288 -0.770262 -v -0.027470 0.020335 -0.000000 -vn -0.552289 0.318864 -0.770262 -v -0.024055 0.021250 -0.000000 -vn -0.637728 -0.000001 -0.770262 -v -0.023720 0.022500 -0.000000 -vn -0.552288 -0.318864 -0.770262 -v -0.024055 0.023750 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.024970 0.024665 -0.000000 -vn -0.000000 -0.637728 -0.770262 -v -0.026220 0.025000 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.027470 0.024665 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 0.015925 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.119575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.119575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.073200 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.076625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.083500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.098450 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.107800 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.024575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.019250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.015925 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.019250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.029625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.073200 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.057425 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.044875 -0.000000 -vn 0.318862 -0.552289 -0.770263 -v -0.060125 0.137949 -0.000000 -vn 0.552288 -0.318865 -0.770262 -v -0.060949 0.137125 -0.000000 -vn 0.000000 0.707106 -0.707107 -v -0.061735 0.145000 -0.000000 -vn -0.318862 0.552289 -0.770263 -v -0.057875 0.134051 -0.000000 -vn -0.552289 0.318863 -0.770262 -v -0.057051 0.134875 -0.000000 -vn -0.637728 -0.000001 -0.770262 -v -0.056750 0.136000 -0.000000 -vn -0.552288 -0.318865 -0.770262 -v -0.057051 0.137125 -0.000000 -vn -0.318862 -0.552289 -0.770263 -v -0.057875 0.137949 -0.000000 -vn 0.000000 -0.637730 -0.770260 -v -0.059000 0.138250 -0.000000 -vn 0.637728 -0.000001 -0.770262 -v -0.061250 0.136000 -0.000000 -vn 0.552289 0.318863 -0.770262 -v -0.060949 0.134875 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.133625 -0.000000 -vn 0.318862 0.552289 -0.770263 -v -0.060125 0.134051 -0.000000 -vn 0.000000 0.637730 -0.770260 -v -0.059000 0.133750 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 0.131075 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.123825 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.119575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.073200 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.057425 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.044875 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.061735 -0.039625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.029625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.024575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.019250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.015925 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.019250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.029625 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.061735 0.034375 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.039625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.073200 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.076625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.083500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.098450 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.110425 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.040735 -0.110425 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.019605 -0.110425 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.000150 -0.110425 -0.000000 -vn 0.318865 -0.552288 -0.770262 -v 0.056440 -0.133768 0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.131075 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.131075 -0.000000 -vn 0.000000 -0.707107 -0.707107 -v -0.061735 -0.145000 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 0.131075 -0.000000 -vn -0.000000 0.637727 -0.770262 -v -0.080000 0.132900 -0.000000 -vn -0.000000 0.637728 -0.770262 -v -0.064720 0.034500 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.063470 0.034835 -0.000000 -vn -0.552289 0.318863 -0.770262 -v -0.062555 0.035750 -0.000000 -vn -0.637728 -0.000000 -0.770261 -v -0.062220 0.037000 -0.000000 -vn -0.552289 -0.318863 -0.770262 -v -0.062555 0.038250 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.063470 0.039165 -0.000000 -vn 0.552290 0.318864 -0.770261 -v -0.066885 0.035750 -0.000000 -vn 0.318865 0.552287 -0.770262 -v -0.065970 0.034835 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 0.034375 -0.000000 -vn -0.000000 -0.637728 -0.770262 -v -0.064720 0.039500 -0.000000 -vn 0.318864 -0.552287 -0.770262 -v -0.065970 0.039165 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.039625 -0.000000 -vn 0.552290 -0.318864 -0.770261 -v -0.066885 0.038250 -0.000000 -vn 0.637727 0.000000 -0.770263 -v -0.067220 0.037000 -0.000000 -vn -0.000000 0.637728 -0.770262 -v -0.064720 -0.039500 -0.000000 -vn -0.318864 0.552288 -0.770262 -v -0.063470 -0.039165 -0.000000 -vn -0.552289 0.318863 -0.770262 -v -0.062555 -0.038250 -0.000000 -vn -0.637728 -0.000000 -0.770261 -v -0.062220 -0.037000 -0.000000 -vn -0.552289 -0.318863 -0.770262 -v -0.062555 -0.035750 -0.000000 -vn -0.318864 -0.552288 -0.770262 -v -0.063470 -0.034835 -0.000000 -vn -0.000000 -0.637728 -0.770262 -v -0.064720 -0.034500 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.029625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.024575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.019250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.012625 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.015925 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.019250 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.029625 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 -0.039625 -0.000000 -vn 0.552290 0.318864 -0.770261 -v -0.066885 -0.038250 -0.000000 -vn 0.318865 0.552287 -0.770262 -v -0.065970 -0.039165 -0.000000 -vn 0.318864 -0.552287 -0.770262 -v -0.065970 -0.034835 -0.000000 -vn 0.552290 -0.318864 -0.770261 -v -0.066885 -0.035750 -0.000000 -vn 0.637727 0.000000 -0.770263 -v -0.067220 -0.037000 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.073200 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.057425 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.044875 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.123825 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.119575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 0.123825 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 0.131075 -0.000000 -vn -0.318864 0.552289 -0.770262 -v -0.078875 0.113051 -0.000000 -vn -0.552289 0.318864 -0.770262 -v -0.078051 0.113875 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.077750 0.115000 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.078051 0.116125 -0.000000 -vn -0.318864 -0.552289 -0.770262 -v -0.078875 0.116949 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 0.117250 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.081125 0.116949 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.081949 0.116125 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.082250 0.115000 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.081949 0.113875 -0.000000 -vn 0.318864 0.552289 -0.770262 -v -0.081125 0.113051 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.080000 0.112750 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 -0.075250 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.081125 -0.075551 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.073200 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.077750 -0.077500 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.078051 -0.076375 -0.000000 -vn -0.318864 -0.552289 -0.770262 -v -0.078875 -0.075551 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.081949 -0.078625 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.082250 -0.077500 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.081949 -0.076375 -0.000000 -vn 0.318864 0.552289 -0.770262 -v -0.081125 -0.079449 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.080000 -0.079750 -0.000000 -vn -0.318864 0.552289 -0.770262 -v -0.078875 -0.079449 -0.000000 -vn -0.552288 0.318864 -0.770262 -v -0.078051 -0.078625 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.057425 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.044875 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.039625 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.029625 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.024575 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.019250 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.012625 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.012625 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.015925 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.019250 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.029625 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.034375 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 0.039625 -0.000000 -vn -0.637728 0.000000 -0.770262 -v -0.077750 -0.115000 -0.000000 -vn -0.552289 -0.318864 -0.770262 -v -0.078051 -0.113875 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.119575 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.119575 -0.000000 -vn 0.000000 -0.000000 -1.000000 -v -0.072825 -0.119575 -0.000000 -vn -0.552289 0.318864 -0.770262 -v -0.078051 -0.116125 -0.000000 -vn 0.318864 -0.552289 -0.770262 -v -0.081125 -0.113051 -0.000000 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 -0.112750 -0.000000 -vn -0.318864 -0.552289 -0.770262 -v -0.078875 -0.113051 -0.000000 -vn 0.552289 -0.318864 -0.770262 -v -0.081949 -0.113875 -0.000000 -vn 0.637728 0.000000 -0.770262 -v -0.082250 -0.115000 -0.000000 -vn -0.707107 -0.000000 -0.707107 -v -0.092000 -0.119575 -0.000000 -vn 0.552289 0.318864 -0.770262 -v -0.081949 -0.116125 -0.000000 -vn 0.318864 0.552289 -0.770262 -v -0.081125 -0.116949 -0.000000 -vn 0.000000 0.637728 -0.770262 -v -0.080000 -0.117250 -0.000000 -vn -0.318864 0.552289 -0.770262 -v -0.078875 -0.116949 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.054485 -0.127675 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.061735 -0.127675 -0.000000 -vn 0.000000 0.000000 -1.000000 -v -0.072825 -0.127675 -0.000000 -vn -0.707107 0.000000 -0.707107 -v -0.092000 -0.127675 -0.000000 -vn 0.059901 -0.722311 -0.688970 -v -0.069135 0.001000 0.337300 -vn 0.059901 -0.722310 0.688970 -v -0.069135 0.001000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v -0.082675 0.001000 0.337300 -vn 0.000000 -0.707107 0.707107 -v -0.082675 0.001000 0.339300 -vn -0.577350 -0.577350 -0.577350 -v -0.090000 0.001000 0.337300 -vn -0.577350 -0.577350 0.577350 -v -0.090000 0.001000 0.339300 -vn -0.059901 -0.722311 0.688969 -v 0.018135 0.001000 0.339300 -vn -0.059901 -0.722311 -0.688969 -v 0.018135 0.001000 0.337300 -vn 0.000000 -0.707107 0.707106 -v 0.019950 0.001000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v 0.019950 0.001000 0.337300 -vn 0.000000 -0.707107 0.707107 -v 0.026325 0.001000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v 0.026325 0.001000 0.337300 -vn 0.577350 -0.577350 0.577350 -v 0.039000 0.001000 0.339300 -vn 0.577350 -0.577350 -0.577350 -v 0.039000 0.001000 0.337300 -vn 0.724383 0.071345 -0.685697 -v 0.039000 0.141000 0.337300 -vn 0.724383 0.071345 0.685697 -v 0.039000 0.141000 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 0.129742 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 0.129742 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 0.099417 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 0.099417 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 0.068500 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 0.068500 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 0.041675 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 0.041675 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 0.029950 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 0.029950 0.339300 -vn 0.689402 0.285558 -0.665719 -v 0.038619 0.142913 0.337300 -vn 0.689402 0.285558 0.665719 -v 0.038619 0.142913 0.339300 -vn 0.527646 0.527644 -0.665719 -v 0.037536 0.144536 0.337300 -vn 0.527646 0.527644 0.665719 -v 0.037536 0.144536 0.339300 -vn 0.285558 0.689403 -0.665718 -v 0.035913 0.145619 0.337300 -vn 0.285558 0.689403 0.665718 -v 0.035913 0.145619 0.339300 -vn 0.071343 0.724382 -0.685697 -v 0.034000 0.146000 0.337300 -vn 0.071343 0.724382 0.685697 -v 0.034000 0.146000 0.339300 -vn -0.071343 0.724382 -0.685697 -v -0.085000 0.146000 0.337300 -vn -0.071343 0.724382 0.685697 -v -0.085000 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v -0.082675 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v -0.082675 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v -0.067450 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v -0.067450 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v -0.041050 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v -0.041050 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v -0.020450 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v -0.020450 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v -0.001500 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v -0.001500 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v 0.002750 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v 0.002750 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v 0.019950 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v 0.019950 0.146000 0.339300 -vn 0.000000 0.707107 -0.707107 -v 0.026325 0.146000 0.337300 -vn 0.000000 0.707107 0.707107 -v 0.026325 0.146000 0.339300 -vn -0.285558 0.689403 -0.665718 -v -0.086913 0.145619 0.337300 -vn -0.285558 0.689403 0.665718 -v -0.086913 0.145619 0.339300 -vn -0.527646 0.527644 -0.665719 -v -0.088536 0.144536 0.337300 -vn -0.527646 0.527644 0.665719 -v -0.088536 0.144536 0.339300 -vn -0.689402 0.285558 -0.665719 -v -0.089619 0.142913 0.337300 -vn -0.689402 0.285558 0.665719 -v -0.089619 0.142913 0.339300 -vn -0.724383 0.071345 -0.685697 -v -0.090000 0.141000 0.337300 -vn -0.724383 0.071345 0.685697 -v -0.090000 0.141000 0.339300 -vn -0.707107 0.000000 -0.707107 -v -0.090000 0.029950 0.337300 -vn -0.707107 0.000000 0.707107 -v -0.090000 0.029950 0.339300 -vn -0.707107 0.000000 -0.707107 -v -0.090000 0.041675 0.337300 -vn -0.707107 0.000000 0.707107 -v -0.090000 0.041675 0.339300 -vn -0.707107 -0.000000 -0.707107 -v -0.090000 0.068500 0.337300 -vn -0.707107 -0.000000 0.707107 -v -0.090000 0.068500 0.339300 -vn -0.707107 -0.000000 -0.707107 -v -0.090000 0.099417 0.337300 -vn -0.707107 -0.000000 0.707107 -v -0.090000 0.099417 0.339300 -vn -0.707107 0.000000 -0.707107 -v -0.090000 0.129742 0.337300 -vn -0.707107 0.000000 0.707107 -v -0.090000 0.129742 0.339300 -vn 0.318865 0.552288 0.770262 -v -0.081550 0.133315 0.339300 -vn 0.552289 0.318863 0.770262 -v -0.082685 0.134450 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.082675 0.129742 0.339300 -vn 0.552289 -0.318864 0.770262 -v -0.082685 0.137550 0.339300 -vn 0.318865 -0.552288 0.770262 -v -0.081550 0.138685 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.082675 0.142550 0.339300 -vn -0.000000 -0.637727 0.770262 -v -0.080000 0.139100 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.067450 0.142550 0.339300 -vn -0.318865 -0.552288 0.770261 -v -0.078450 0.138685 0.339300 -vn -0.552288 -0.318865 0.770261 -v -0.077315 0.137550 0.339300 -vn -0.637727 -0.000001 0.770263 -v -0.076900 0.136000 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.067450 0.129742 0.339300 -vn -0.552288 0.318865 0.770262 -v -0.077315 0.134450 0.339300 -vn -0.318865 0.552288 0.770261 -v -0.078450 0.133315 0.339300 -vn -0.000000 0.637727 0.770262 -v -0.080000 0.132900 0.339300 -vn 0.318865 -0.552288 0.770262 -v 0.027450 0.138685 0.339300 -vn 0.000000 -0.637727 0.770262 -v 0.029000 0.139100 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.026325 0.142550 0.339300 -vn -0.318865 0.552288 0.770262 -v 0.030550 0.133315 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.026325 0.129742 0.339300 -vn 0.000000 0.637727 0.770262 -v 0.029000 0.132900 0.339300 -vn -0.318865 -0.552288 0.770262 -v 0.030550 0.138685 0.339300 -vn -0.552289 -0.318864 0.770261 -v 0.031685 0.137550 0.339300 -vn -0.637728 -0.000001 0.770262 -v 0.032100 0.136000 0.339300 -vn -0.552289 0.318864 0.770262 -v 0.031685 0.134450 0.339300 -vn 0.318865 0.552288 0.770262 -v 0.027450 0.133315 0.339300 -vn 0.552289 0.318864 0.770262 -v 0.026315 0.134450 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019950 0.129742 0.339300 -vn 0.552288 -0.318865 0.770262 -v 0.026315 0.137550 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019950 0.142550 0.339300 -vn 0.637728 -0.000001 0.770262 -v 0.025900 0.136000 0.339300 -vn 0.637728 -0.000001 0.770261 -v -0.083100 0.136000 0.339300 -vn -0.525599 -0.432234 0.732748 -v 0.001533 0.022231 0.339300 -vn 0.637728 0.000000 0.770261 -v 0.004000 0.022000 0.339300 -vn 0.552288 -0.318864 0.770262 -v 0.004201 0.022750 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019950 0.029950 0.339300 -vn -0.318863 -0.552289 0.770262 -v 0.006250 0.023299 0.339300 -vn -0.552289 -0.318863 0.770262 -v 0.006799 0.022750 0.339300 -vn 0.000000 -0.637728 0.770261 -v 0.005500 0.023500 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.002750 0.029950 0.339300 -vn 0.318863 -0.552289 0.770262 -v 0.004750 0.023299 0.339300 -vn -0.637728 -0.000000 0.770261 -v 0.007000 0.022000 0.339300 -vn -0.552289 0.318863 0.770262 -v 0.006799 0.021250 0.339300 -vn -0.318863 0.552289 0.770262 -v 0.006250 0.020701 0.339300 -vn 0.000000 0.637728 0.770261 -v 0.005500 0.020500 0.339300 -vn -0.607454 -0.306725 0.732748 -v 0.005743 0.015776 0.339300 -vn 0.318863 0.552289 0.770262 -v 0.004750 0.020701 0.339300 -vn 0.552288 0.318864 0.770262 -v 0.004201 0.021250 0.339300 -vn -0.455258 -0.584268 0.671841 -v 0.011988 0.003112 0.339300 -vn -0.240691 -0.700497 0.671842 -v 0.014885 0.001543 0.339300 -vn -0.620411 -0.404622 0.671842 -v 0.009759 0.005537 0.339300 -vn -0.661041 -0.267751 0.700952 -v 0.008438 0.008556 0.339300 -vn -0.290642 -0.615311 0.732748 -v -0.010552 0.031647 0.339300 -vn -0.418260 -0.536786 0.732748 -v -0.003988 0.027608 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.001500 0.029950 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.001500 0.041675 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.020450 0.041675 0.339300 -vn -0.148931 -0.664003 0.732748 -v -0.017840 0.034151 0.339300 -vn 0.148931 -0.664003 0.732748 -v -0.033160 0.034151 0.339300 -vn 0.318863 0.552288 0.770262 -v -0.026300 0.036614 0.339300 -vn 0.552289 0.318864 0.770261 -v -0.026886 0.037200 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.041050 0.041675 0.339300 -vn 0.637727 0.000000 0.770262 -v -0.027100 0.038000 0.339300 -vn 0.552288 -0.318865 0.770262 -v -0.026886 0.038800 0.339300 -vn -0.000000 0.637729 0.770261 -v -0.025500 0.036400 0.339300 -vn 0.000000 -0.680500 0.732748 -v -0.025500 0.035000 0.339300 -vn -0.318863 0.552289 0.770262 -v -0.024700 0.036614 0.339300 -vn -0.552289 0.318864 0.770262 -v -0.024114 0.037200 0.339300 -vn 0.264246 -0.640674 0.720910 -v -0.040449 0.031647 0.339300 -vn 0.320723 -0.624240 0.712363 -v -0.041087 0.031337 0.339300 -vn 0.318864 -0.552289 0.770261 -v -0.026300 0.039386 0.339300 -vn -0.000000 -0.637727 0.770262 -v -0.025500 0.039600 0.339300 -vn -0.318864 -0.552289 0.770261 -v -0.024700 0.039386 0.339300 -vn -0.552288 -0.318864 0.770262 -v -0.024114 0.038800 0.339300 -vn -0.637728 0.000000 0.770262 -v -0.023900 0.038000 0.339300 -vn 0.362263 -0.593674 0.718552 -v -0.043315 0.030127 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.067450 0.041675 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.067450 0.029950 0.339300 -vn 0.240691 -0.700497 0.671842 -v -0.065885 0.001543 0.339300 -vn 0.455258 -0.584268 0.671842 -v -0.062989 0.003112 0.339300 -vn 0.637728 0.000000 0.770261 -v -0.058000 0.022000 0.339300 -vn 0.552289 -0.318863 0.770262 -v -0.057799 0.022750 0.339300 -vn -0.000000 0.637728 0.770262 -v -0.056500 0.020500 0.339300 -vn 0.318863 0.552289 0.770262 -v -0.057250 0.020701 0.339300 -vn 0.607454 -0.306725 0.732748 -v -0.056743 0.015776 0.339300 -vn 0.661041 -0.267751 0.700952 -v -0.059438 0.008556 0.339300 -vn 0.620411 -0.404623 0.671842 -v -0.060759 0.005537 0.339300 -vn 0.525599 -0.432234 0.732748 -v -0.052533 0.022231 0.339300 -vn -0.552288 0.318864 0.770262 -v -0.055201 0.021250 0.339300 -vn -0.318863 0.552289 0.770261 -v -0.055750 0.020701 0.339300 -vn 0.552289 0.318863 0.770262 -v -0.057799 0.021250 0.339300 -vn 0.318863 -0.552289 0.770262 -v -0.057250 0.023299 0.339300 -vn -0.000000 -0.637728 0.770261 -v -0.056500 0.023500 0.339300 -vn -0.318863 -0.552290 0.770261 -v -0.055750 0.023299 0.339300 -vn 0.434323 -0.531509 0.727229 -v -0.047012 0.027608 0.339300 -vn -0.552288 -0.318864 0.770263 -v -0.055201 0.022750 0.339300 -vn -0.637728 -0.000000 0.770261 -v -0.055000 0.022000 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.082675 0.029950 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.002750 0.129742 0.339300 -vn 0.000000 -0.707107 0.707107 -v 0.002750 0.126585 0.339300 -vn 0.301511 -0.301511 0.904534 -v 0.001500 0.126585 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.001500 0.129742 0.339300 -vn 0.301511 0.301511 0.904534 -v 0.001500 0.105585 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.001500 0.099417 0.339300 -vn 0.000000 0.707107 0.707107 -v 0.002750 0.105585 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.002750 0.099417 0.339300 -vn -0.301511 0.301511 0.904534 -v 0.014000 0.105585 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019950 0.099417 0.339300 -vn -0.301511 -0.301511 0.904534 -v 0.014000 0.126585 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.026325 0.041675 0.339300 -vn 0.318864 0.552288 0.770262 -v 0.027875 0.044051 0.339300 -vn 0.552289 0.318864 0.770262 -v 0.027051 0.044875 0.339300 -vn 0.637728 -0.000000 0.770262 -v 0.026750 0.046000 0.339300 -vn 0.552289 -0.318863 0.770262 -v 0.027051 0.047125 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.026325 0.068500 0.339300 -vn 0.318864 -0.552288 0.770262 -v 0.027875 0.047949 0.339300 -vn -0.000000 -0.637728 0.770262 -v 0.029000 0.048250 0.339300 -vn -0.637728 0.000000 0.770262 -v 0.031250 0.046000 0.339300 -vn -0.552289 -0.318864 0.770262 -v 0.030949 0.047125 0.339300 -vn -0.318864 -0.552289 0.770262 -v 0.030125 0.047949 0.339300 -vn -0.552289 0.318864 0.770262 -v 0.030949 0.044875 0.339300 -vn -0.318864 0.552288 0.770262 -v 0.030125 0.044051 0.339300 -vn 0.000000 0.637728 0.770262 -v 0.029000 0.043750 0.339300 -vn -0.552289 -0.318864 0.770262 -v 0.030949 0.092125 0.339300 -vn -0.637728 0.000000 0.770262 -v 0.031250 0.091000 0.339300 -vn 0.318864 0.552288 0.770262 -v 0.027875 0.089051 0.339300 -vn 0.552289 0.318864 0.770262 -v 0.027051 0.089875 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.026325 0.099417 0.339300 -vn 0.637728 -0.000000 0.770262 -v 0.026750 0.091000 0.339300 -vn 0.552289 -0.318863 0.770262 -v 0.027051 0.092125 0.339300 -vn -0.552289 0.318864 0.770262 -v 0.030949 0.089875 0.339300 -vn -0.318864 0.552289 0.770262 -v 0.030125 0.089051 0.339300 -vn 0.000000 0.637728 0.770262 -v 0.029000 0.088750 0.339300 -vn 0.318864 -0.552288 0.770262 -v 0.027875 0.092949 0.339300 -vn -0.000000 -0.637728 0.770262 -v 0.029000 0.093250 0.339300 -vn -0.318864 -0.552289 0.770262 -v 0.030125 0.092949 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.026325 0.029950 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019950 0.041675 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.002750 0.041675 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.020450 0.099417 0.339300 -vn -0.301511 0.301511 0.904534 -v -0.004500 0.105585 0.339300 -vn -0.301511 -0.301511 0.904534 -v -0.004500 0.126585 0.339300 -vn 0.301511 -0.301511 0.904534 -v -0.017000 0.126585 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.020450 0.129742 0.339300 -vn 0.301511 0.301511 0.904534 -v -0.017000 0.105585 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019950 0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.002750 0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.001500 0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.020450 0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.041050 0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.067450 0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.002750 0.142550 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.001500 0.142550 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.020450 0.142550 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.041050 0.129742 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.041050 0.142550 0.339300 -vn 0.318864 -0.552288 0.770262 -v -0.081125 0.047949 0.339300 -vn -0.000000 -0.637728 0.770262 -v -0.080000 0.048250 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.082675 0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.082675 0.041675 0.339300 -vn 0.000000 0.637728 0.770262 -v -0.080000 0.043750 0.339300 -vn 0.318864 0.552289 0.770262 -v -0.081125 0.044051 0.339300 -vn -0.552290 0.318863 0.770261 -v -0.078051 0.044875 0.339300 -vn -0.318865 0.552287 0.770262 -v -0.078875 0.044051 0.339300 -vn 0.552289 0.318864 0.770262 -v -0.081949 0.044875 0.339300 -vn 0.637728 -0.000000 0.770262 -v -0.082250 0.046000 0.339300 -vn 0.552288 -0.318864 0.770262 -v -0.081949 0.047125 0.339300 -vn -0.318865 -0.552287 0.770262 -v -0.078875 0.047949 0.339300 -vn -0.552290 -0.318863 0.770261 -v -0.078051 0.047125 0.339300 -vn -0.637728 0.000000 0.770262 -v -0.077750 0.046000 0.339300 -vn -0.552290 -0.318863 0.770261 -v -0.078051 0.092125 0.339300 -vn -0.637728 0.000000 0.770262 -v -0.077750 0.091000 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.067450 0.099417 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.041050 0.099417 0.339300 -vn -0.552290 0.318863 0.770261 -v -0.078051 0.089875 0.339300 -vn -0.318865 0.552287 0.770262 -v -0.078875 0.089051 0.339300 -vn 0.000000 0.637728 0.770262 -v -0.080000 0.088750 0.339300 -vn 0.318864 0.552289 0.770262 -v -0.081125 0.089051 0.339300 -vn 0.552289 0.318864 0.770262 -v -0.081949 0.089875 0.339300 -vn 0.637728 -0.000000 0.770262 -v -0.082250 0.091000 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.082675 0.099417 0.339300 -vn 0.552289 -0.318864 0.770262 -v -0.081949 0.092125 0.339300 -vn 0.318864 -0.552289 0.770262 -v -0.081125 0.092949 0.339300 -vn -0.000000 -0.637728 0.770262 -v -0.080000 0.093250 0.339300 -vn -0.318865 -0.552287 0.770262 -v -0.078875 0.092949 0.339300 -vn -0.318864 -0.552289 -0.770262 -v 0.030125 0.092949 0.337300 -vn 0.000000 -0.637728 -0.770262 -v 0.029000 0.093250 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.026325 0.099417 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.082675 0.129742 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.082675 0.029950 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.002750 0.029950 0.337300 -vn 0.000000 -0.637728 -0.770261 -v 0.005500 0.023500 0.337300 -vn 0.318863 -0.552289 -0.770262 -v 0.004750 0.023299 0.337300 -vn -0.318863 0.552289 -0.770262 -v 0.006250 0.020701 0.337300 -vn 0.552288 -0.318864 -0.770262 -v 0.004201 0.022750 0.337300 -vn 0.637728 -0.000000 -0.770261 -v 0.004000 0.022000 0.337300 -vn -0.525599 -0.432234 -0.732748 -v 0.001533 0.022231 0.337300 -vn 0.552288 0.318864 -0.770262 -v 0.004201 0.021250 0.337300 -vn -0.607454 -0.306725 -0.732748 -v 0.005743 0.015776 0.337300 -vn 0.318863 0.552289 -0.770262 -v 0.004750 0.020701 0.337300 -vn 0.000000 0.637728 -0.770261 -v 0.005500 0.020500 0.337300 -vn -0.240691 -0.700497 -0.671842 -v 0.014885 0.001543 0.337300 -vn -0.455258 -0.584268 -0.671841 -v 0.011988 0.003112 0.337300 -vn -0.620411 -0.404622 -0.671842 -v 0.009759 0.005537 0.337300 -vn -0.661041 -0.267751 -0.700952 -v 0.008438 0.008556 0.337300 -vn -0.552289 0.318863 -0.770262 -v 0.006799 0.021250 0.337300 -vn -0.637728 0.000000 -0.770261 -v 0.007000 0.022000 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019950 0.029950 0.337300 -vn -0.552289 -0.318863 -0.770262 -v 0.006799 0.022750 0.337300 -vn -0.318863 -0.552289 -0.770262 -v 0.006250 0.023299 0.337300 -vn -0.318865 -0.552288 -0.770262 -v 0.030550 0.138685 0.337300 -vn 0.000000 -0.637727 -0.770262 -v 0.029000 0.139100 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.026325 0.142550 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.026325 0.129742 0.337300 -vn 0.552289 0.318864 -0.770262 -v 0.026315 0.134450 0.337300 -vn 0.318865 0.552288 -0.770262 -v 0.027450 0.133315 0.337300 -vn 0.000000 0.637727 -0.770262 -v 0.029000 0.132900 0.337300 -vn -0.318865 0.552288 -0.770262 -v 0.030550 0.133315 0.337300 -vn -0.552289 0.318864 -0.770262 -v 0.031685 0.134450 0.337300 -vn -0.637728 -0.000001 -0.770262 -v 0.032100 0.136000 0.337300 -vn -0.552289 -0.318864 -0.770261 -v 0.031685 0.137550 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.082675 0.142550 0.337300 -vn 0.552289 -0.318864 -0.770262 -v -0.082685 0.137550 0.337300 -vn 0.637728 -0.000001 -0.770261 -v -0.083100 0.136000 0.337300 -vn 0.552289 0.318863 -0.770262 -v -0.082685 0.134450 0.337300 -vn 0.434324 -0.531509 -0.727229 -v -0.047012 0.027608 0.337300 -vn 0.525599 -0.432234 -0.732748 -v -0.052533 0.022231 0.337300 -vn -0.637728 0.000000 -0.770261 -v -0.055000 0.022000 0.337300 -vn -0.000000 -0.637728 -0.770262 -v -0.056500 0.023500 0.337300 -vn 0.362263 -0.593674 -0.718552 -v -0.043315 0.030127 0.337300 -vn -0.318863 -0.552290 -0.770261 -v -0.055750 0.023299 0.337300 -vn -0.552288 -0.318864 -0.770262 -v -0.055201 0.022750 0.337300 -vn 0.318863 -0.552289 -0.770262 -v -0.057250 0.023299 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.067450 0.029950 0.337300 -vn 0.552289 -0.318863 -0.770262 -v -0.057799 0.022750 0.337300 -vn 0.637728 -0.000000 -0.770261 -v -0.058000 0.022000 0.337300 -vn 0.607454 -0.306725 -0.732748 -v -0.056743 0.015776 0.337300 -vn 0.661041 -0.267751 -0.700952 -v -0.059438 0.008556 0.337300 -vn 0.552289 0.318863 -0.770262 -v -0.057799 0.021250 0.337300 -vn 0.318863 0.552289 -0.770262 -v -0.057250 0.020701 0.337300 -vn -0.000000 0.637728 -0.770261 -v -0.056500 0.020500 0.337300 -vn -0.318863 0.552289 -0.770261 -v -0.055750 0.020701 0.337300 -vn -0.552288 0.318864 -0.770263 -v -0.055201 0.021250 0.337300 -vn 0.620411 -0.404623 -0.671842 -v -0.060759 0.005537 0.337300 -vn 0.455258 -0.584268 -0.671842 -v -0.062989 0.003112 0.337300 -vn 0.240691 -0.700497 -0.671842 -v -0.065885 0.001543 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.067450 0.041675 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.041050 0.041675 0.337300 -vn 0.318864 -0.552289 -0.770261 -v -0.026300 0.039386 0.337300 -vn -0.000000 -0.637727 -0.770262 -v -0.025500 0.039600 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.020450 0.041675 0.337300 -vn 0.148931 -0.664003 -0.732748 -v -0.033160 0.034151 0.337300 -vn 0.264246 -0.640674 -0.720910 -v -0.040449 0.031647 0.337300 -vn 0.320723 -0.624240 -0.712363 -v -0.041087 0.031337 0.337300 -vn 0.552288 -0.318865 -0.770262 -v -0.026886 0.038800 0.337300 -vn 0.637727 0.000000 -0.770262 -v -0.027100 0.038000 0.337300 -vn 0.552289 0.318864 -0.770261 -v -0.026886 0.037200 0.337300 -vn 0.318863 0.552288 -0.770262 -v -0.026300 0.036614 0.337300 -vn 0.000000 -0.680500 -0.732748 -v -0.025500 0.035000 0.337300 -vn -0.000000 0.637729 -0.770261 -v -0.025500 0.036400 0.337300 -vn -0.148931 -0.664003 -0.732748 -v -0.017840 0.034151 0.337300 -vn -0.318863 0.552289 -0.770262 -v -0.024700 0.036614 0.337300 -vn -0.552289 0.318864 -0.770262 -v -0.024114 0.037200 0.337300 -vn -0.637728 0.000000 -0.770262 -v -0.023900 0.038000 0.337300 -vn -0.552288 -0.318864 -0.770262 -v -0.024114 0.038800 0.337300 -vn -0.318864 -0.552289 -0.770261 -v -0.024700 0.039386 0.337300 -vn -0.290642 -0.615311 -0.732748 -v -0.010552 0.031647 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.001500 0.029950 0.337300 -vn -0.418260 -0.536786 -0.732748 -v -0.003988 0.027608 0.337300 -vn 0.318865 -0.552288 -0.770262 -v -0.081550 0.138685 0.337300 -vn -0.000000 -0.637727 -0.770262 -v -0.080000 0.139100 0.337300 -vn 0.318865 0.552288 -0.770262 -v -0.081550 0.133315 0.337300 -vn -0.000000 0.637727 -0.770262 -v -0.080000 0.132900 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.067450 0.129742 0.337300 -vn -0.318865 0.552288 -0.770261 -v -0.078450 0.133315 0.337300 -vn -0.552288 0.318865 -0.770262 -v -0.077315 0.134450 0.337300 -vn -0.637727 -0.000001 -0.770263 -v -0.076900 0.136000 0.337300 -vn -0.318865 -0.552288 -0.770261 -v -0.078450 0.138685 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.067450 0.142550 0.337300 -vn -0.552288 -0.318865 -0.770261 -v -0.077315 0.137550 0.337300 -vn 0.552288 -0.318865 -0.770262 -v 0.026315 0.137550 0.337300 -vn 0.637728 -0.000001 -0.770262 -v 0.025900 0.136000 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019950 0.129742 0.337300 -vn 0.318865 -0.552288 -0.770262 -v 0.027450 0.138685 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019950 0.142550 0.337300 -vn -0.301511 -0.301511 -0.904534 -v 0.014000 0.126585 0.337300 -vn -0.301511 0.301511 -0.904534 -v 0.014000 0.105585 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019950 0.099417 0.337300 -vn 0.000000 0.707107 -0.707107 -v 0.002750 0.105585 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.002750 0.099417 0.337300 -vn 0.301511 0.301511 -0.904534 -v 0.001500 0.105585 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.001500 0.099417 0.337300 -vn 0.301511 -0.301511 -0.904534 -v 0.001500 0.126585 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.001500 0.129742 0.337300 -vn 0.000000 -0.707107 -0.707107 -v 0.002750 0.126585 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.002750 0.129742 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.082675 0.099417 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.082675 0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.082675 0.041675 0.337300 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 0.048250 0.337300 -vn 0.318864 -0.552288 -0.770262 -v -0.081125 0.047949 0.337300 -vn 0.318864 0.552289 -0.770262 -v -0.081125 0.044051 0.337300 -vn -0.000000 0.637728 -0.770262 -v -0.080000 0.043750 0.337300 -vn -0.318865 0.552287 -0.770262 -v -0.078875 0.044051 0.337300 -vn -0.552290 0.318863 -0.770261 -v -0.078051 0.044875 0.337300 -vn -0.637728 -0.000000 -0.770262 -v -0.077750 0.046000 0.337300 -vn 0.552288 -0.318864 -0.770262 -v -0.081949 0.047125 0.337300 -vn 0.637728 0.000000 -0.770262 -v -0.082250 0.046000 0.337300 -vn 0.552289 0.318864 -0.770262 -v -0.081949 0.044875 0.337300 -vn -0.318865 -0.552287 -0.770262 -v -0.078875 0.047949 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.067450 0.068500 0.337300 -vn -0.552290 -0.318863 -0.770261 -v -0.078051 0.047125 0.337300 -vn 0.552289 0.318864 -0.770262 -v -0.081949 0.089875 0.337300 -vn 0.637728 0.000000 -0.770262 -v -0.082250 0.091000 0.337300 -vn 0.552289 -0.318864 -0.770262 -v -0.081949 0.092125 0.337300 -vn 0.318864 -0.552289 -0.770262 -v -0.081125 0.092949 0.337300 -vn 0.318864 0.552289 -0.770262 -v -0.081125 0.089051 0.337300 -vn -0.000000 0.637728 -0.770262 -v -0.080000 0.088750 0.337300 -vn -0.318865 0.552287 -0.770262 -v -0.078875 0.089051 0.337300 -vn -0.552290 0.318863 -0.770261 -v -0.078051 0.089875 0.337300 -vn -0.637728 -0.000000 -0.770262 -v -0.077750 0.091000 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.067450 0.099417 0.337300 -vn -0.552290 -0.318863 -0.770261 -v -0.078051 0.092125 0.337300 -vn -0.318865 -0.552287 -0.770262 -v -0.078875 0.092949 0.337300 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 0.093250 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.041050 0.129742 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.041050 0.099417 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.020450 0.129742 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.020450 0.099417 0.337300 -vn -0.301511 -0.301511 -0.904534 -v -0.004500 0.126585 0.337300 -vn -0.301511 0.301511 -0.904534 -v -0.004500 0.105585 0.337300 -vn 0.301511 0.301511 -0.904534 -v -0.017000 0.105585 0.337300 -vn 0.301511 -0.301511 -0.904534 -v -0.017000 0.126585 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019950 0.041675 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.002750 0.041675 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.001500 0.041675 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.026325 0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019950 0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.002750 0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.001500 0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.020450 0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.041050 0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.002750 0.142550 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.001500 0.142550 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.020450 0.142550 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.041050 0.142550 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.026325 0.029950 0.337300 -vn -0.318864 -0.552289 -0.770262 -v 0.030125 0.047949 0.337300 -vn 0.000000 -0.637728 -0.770262 -v 0.029000 0.048250 0.337300 -vn 0.318864 -0.552288 -0.770262 -v 0.027875 0.047949 0.337300 -vn 0.552289 -0.318864 -0.770262 -v 0.027051 0.047125 0.337300 -vn 0.637728 0.000000 -0.770262 -v 0.026750 0.046000 0.337300 -vn 0.552289 0.318863 -0.770262 -v 0.027051 0.044875 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.026325 0.041675 0.337300 -vn 0.318864 0.552288 -0.770262 -v 0.027875 0.044051 0.337300 -vn -0.000000 0.637728 -0.770262 -v 0.029000 0.043750 0.337300 -vn -0.318864 0.552289 -0.770262 -v 0.030125 0.044051 0.337300 -vn -0.552289 0.318864 -0.770262 -v 0.030949 0.044875 0.337300 -vn -0.637728 -0.000000 -0.770262 -v 0.031250 0.046000 0.337300 -vn -0.552289 -0.318864 -0.770262 -v 0.030949 0.047125 0.337300 -vn 0.552289 0.318863 -0.770262 -v 0.027051 0.089875 0.337300 -vn 0.318864 0.552288 -0.770262 -v 0.027875 0.089051 0.337300 -vn 0.318864 -0.552288 -0.770262 -v 0.027875 0.092949 0.337300 -vn 0.552289 -0.318864 -0.770262 -v 0.027051 0.092125 0.337300 -vn 0.637728 0.000000 -0.770262 -v 0.026750 0.091000 0.337300 -vn -0.000000 0.637728 -0.770262 -v 0.029000 0.088750 0.337300 -vn -0.318864 0.552289 -0.770262 -v 0.030125 0.089051 0.337300 -vn -0.552289 0.318864 -0.770262 -v 0.030949 0.089875 0.337300 -vn -0.637728 -0.000000 -0.770262 -v 0.031250 0.091000 0.337300 -vn -0.552289 -0.318864 -0.770262 -v 0.030949 0.092125 0.337300 -vn -0.059901 0.722311 -0.688969 -v 0.018135 -0.001000 0.337300 -vn -0.059901 0.722311 0.688969 -v 0.018135 -0.001000 0.339300 -vn -0.000000 0.707107 -0.707107 -v 0.019575 -0.001000 0.337300 -vn -0.000000 0.707107 0.707107 -v 0.019575 -0.001000 0.339300 -vn -0.000000 0.707107 -0.707107 -v 0.031675 -0.001000 0.337300 -vn -0.000000 0.707107 0.707107 -v 0.031675 -0.001000 0.339300 -vn 0.577350 0.577350 -0.577350 -v 0.039000 -0.001000 0.337300 -vn 0.577350 0.577350 0.577350 -v 0.039000 -0.001000 0.339300 -vn 0.059901 0.722311 0.688970 -v -0.069135 -0.001000 0.339300 -vn 0.059901 0.722311 -0.688969 -v -0.069135 -0.001000 0.337300 -vn -0.000000 0.707107 0.707107 -v -0.077325 -0.001000 0.339300 -vn -0.000000 0.707107 -0.707107 -v -0.077325 -0.001000 0.337300 -vn -0.577350 0.577350 0.577350 -v -0.090000 -0.001000 0.339300 -vn -0.577350 0.577350 -0.577350 -v -0.090000 -0.001000 0.337300 -vn -0.724383 -0.071345 -0.685697 -v -0.090000 -0.141000 0.337300 -vn -0.724383 -0.071345 0.685697 -v -0.090000 -0.141000 0.339300 -vn -0.707107 0.000000 -0.707107 -v -0.090000 -0.122825 0.337300 -vn -0.707107 0.000000 0.707107 -v -0.090000 -0.122825 0.339300 -vn -0.707107 -0.000000 -0.707107 -v -0.090000 -0.103000 0.337300 -vn -0.707107 -0.000000 0.707107 -v -0.090000 -0.103000 0.339300 -vn -0.707106 -0.000000 -0.707107 -v -0.090000 -0.068500 0.337300 -vn -0.707107 -0.000000 0.707107 -v -0.090000 -0.068500 0.339300 -vn -0.707107 0.000000 -0.707107 -v -0.090000 -0.040125 0.337300 -vn -0.707107 0.000000 0.707107 -v -0.090000 -0.040125 0.339300 -vn -0.707107 0.000000 -0.707107 -v -0.090000 -0.027050 0.337300 -vn -0.707107 0.000000 0.707107 -v -0.090000 -0.027050 0.339300 -vn -0.689402 -0.285558 -0.665719 -v -0.089619 -0.142913 0.337300 -vn -0.689402 -0.285558 0.665719 -v -0.089619 -0.142913 0.339300 -vn -0.527646 -0.527644 -0.665719 -v -0.088536 -0.144536 0.337300 -vn -0.527646 -0.527644 0.665719 -v -0.088536 -0.144536 0.339300 -vn -0.285558 -0.689403 -0.665718 -v -0.086913 -0.145619 0.337300 -vn -0.285558 -0.689403 0.665718 -v -0.086913 -0.145619 0.339300 -vn -0.071343 -0.724382 -0.685697 -v -0.085000 -0.146000 0.337300 -vn -0.071343 -0.724382 0.685697 -v -0.085000 -0.146000 0.339300 -vn 0.071343 -0.724382 -0.685697 -v 0.034000 -0.146000 0.337300 -vn 0.071343 -0.724382 0.685697 -v 0.034000 -0.146000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v 0.031675 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v 0.031675 -0.146000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v 0.019575 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v 0.019575 -0.146000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v 0.011129 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v 0.011129 -0.146000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v 0.003404 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v 0.003404 -0.146000 0.339300 -vn 0.000000 -0.707106 -0.707107 -v -0.029125 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v -0.029125 -0.146000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v -0.054404 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v -0.054404 -0.146000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v -0.068454 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v -0.068454 -0.146000 0.339300 -vn 0.000000 -0.707107 -0.707107 -v -0.077325 -0.146000 0.337300 -vn 0.000000 -0.707107 0.707107 -v -0.077325 -0.146000 0.339300 -vn 0.285558 -0.689403 -0.665718 -v 0.035913 -0.145619 0.337300 -vn 0.285558 -0.689403 0.665718 -v 0.035913 -0.145619 0.339300 -vn 0.527646 -0.527644 -0.665719 -v 0.037536 -0.144536 0.337300 -vn 0.527646 -0.527644 0.665719 -v 0.037536 -0.144536 0.339300 -vn 0.689402 -0.285558 -0.665719 -v 0.038619 -0.142913 0.337300 -vn 0.689402 -0.285558 0.665719 -v 0.038619 -0.142913 0.339300 -vn 0.724383 -0.071345 -0.685697 -v 0.039000 -0.141000 0.337300 -vn 0.724383 -0.071345 0.685697 -v 0.039000 -0.141000 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 -0.027050 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 -0.027050 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 -0.040125 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 -0.040125 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 -0.068500 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 -0.068500 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 -0.103000 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 -0.103000 0.339300 -vn 0.707107 0.000000 -0.707107 -v 0.039000 -0.122825 0.337300 -vn 0.707107 0.000000 0.707107 -v 0.039000 -0.122825 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019575 -0.027050 0.339300 -vn -0.517948 0.453236 0.725470 -v 0.001533 -0.022231 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.003404 -0.027050 0.339300 -vn -0.579186 0.382798 0.719729 -v 0.003580 -0.019476 0.339300 -vn 0.529219 0.430139 0.731374 -v -0.052533 -0.022231 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.054404 -0.027050 0.339300 -vn 0.462239 0.518001 0.719729 -v -0.047641 -0.027107 0.339300 -vn 0.000000 0.637727 0.770262 -v 0.029000 -0.139100 0.339300 -vn 0.318865 0.552288 0.770262 -v 0.027450 -0.138685 0.339300 -vn 0.552288 0.318865 0.770262 -v 0.026315 -0.137550 0.339300 -vn 0.637728 0.000001 0.770262 -v 0.025900 -0.136000 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019575 -0.122825 0.339300 -vn 0.552288 -0.318864 0.770262 -v 0.026315 -0.134450 0.339300 -vn 0.318865 -0.552288 0.770262 -v 0.027450 -0.133315 0.339300 -vn 0.000000 -0.637727 0.770262 -v 0.029000 -0.132900 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.031675 -0.122825 0.339300 -vn -0.637728 0.000001 0.770262 -v 0.032100 -0.136000 0.339300 -vn -0.552288 0.318865 0.770262 -v 0.031685 -0.137550 0.339300 -vn -0.318865 0.552289 0.770261 -v 0.030550 -0.138685 0.339300 -vn -0.552288 -0.318864 0.770262 -v 0.031685 -0.134450 0.339300 -vn -0.318865 -0.552289 0.770261 -v 0.030550 -0.133315 0.339300 -vn -0.000000 -0.637727 0.770262 -v -0.080000 -0.132900 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.077325 -0.122825 0.339300 -vn 0.318865 -0.552288 0.770262 -v -0.081550 -0.133315 0.339300 -vn 0.552289 -0.318863 0.770262 -v -0.082685 -0.134450 0.339300 -vn -0.000000 0.637727 0.770262 -v -0.080000 -0.139100 0.339300 -vn 0.318865 0.552288 0.770262 -v -0.081550 -0.138685 0.339300 -vn 0.552289 0.318864 0.770262 -v -0.082685 -0.137550 0.339300 -vn 0.637728 0.000001 0.770261 -v -0.083100 -0.136000 0.339300 -vn -0.552288 -0.318865 0.770262 -v -0.077315 -0.134450 0.339300 -vn -0.637727 0.000001 0.770263 -v -0.076900 -0.136000 0.339300 -vn -0.552288 0.318865 0.770261 -v -0.077315 -0.137550 0.339300 -vn -0.318865 0.552288 0.770261 -v -0.078450 -0.138685 0.339300 -vn 0.607454 0.306725 0.732748 -v -0.056743 -0.015776 0.339300 -vn -0.552288 -0.318865 0.770262 -v -0.057023 -0.018200 0.339300 -vn 0.000000 0.637729 0.770261 -v -0.058409 -0.020600 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.068454 -0.027050 0.339300 -vn 0.318863 0.552288 0.770262 -v -0.059209 -0.020386 0.339300 -vn 0.552288 0.318865 0.770262 -v -0.059795 -0.019800 0.339300 -vn 0.637727 0.000000 0.770262 -v -0.060009 -0.019000 0.339300 -vn 0.552288 -0.318865 0.770262 -v -0.059795 -0.018200 0.339300 -vn 0.318864 -0.552289 0.770261 -v -0.059209 -0.017614 0.339300 -vn 0.000000 -0.637727 0.770262 -v -0.058409 -0.017400 0.339300 -vn 0.455258 0.584268 0.671842 -v -0.062989 -0.003112 0.339300 -vn 0.240691 0.700497 0.671842 -v -0.065885 -0.001543 0.339300 -vn 0.620411 0.404623 0.671842 -v -0.060759 -0.005537 0.339300 -vn 0.661041 0.267751 0.700952 -v -0.059438 -0.008556 0.339300 -vn -0.318864 -0.552289 0.770261 -v -0.057609 -0.017614 0.339300 -vn -0.637727 0.000000 0.770262 -v -0.056809 -0.019000 0.339300 -vn -0.552288 0.318865 0.770262 -v -0.057023 -0.019800 0.339300 -vn -0.318863 0.552289 0.770262 -v -0.057609 -0.020386 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.054404 -0.040125 0.339300 -vn 0.318863 0.552289 0.770262 -v -0.051250 -0.036299 0.339300 -vn 0.552288 0.318864 0.770262 -v -0.051799 -0.035750 0.339300 -vn -0.637727 0.000000 0.770263 -v -0.049000 -0.035000 0.339300 -vn -0.552288 0.318865 0.770262 -v -0.049201 -0.035750 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.029125 -0.040125 0.339300 -vn -0.318863 0.552289 0.770262 -v -0.049750 -0.036299 0.339300 -vn 0.000000 0.637728 0.770261 -v -0.050500 -0.036500 0.339300 -vn -0.318863 -0.552289 0.770262 -v 0.000250 -0.033701 0.339300 -vn -0.552288 -0.318864 0.770262 -v 0.000799 -0.034250 0.339300 -vn -0.637728 -0.000000 0.770261 -v 0.001000 -0.035000 0.339300 -vn -0.552288 0.318864 0.770262 -v 0.000799 -0.035750 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.003404 -0.040125 0.339300 -vn 0.552288 0.318864 0.770262 -v -0.001799 -0.035750 0.339300 -vn 0.637728 -0.000000 0.770262 -v -0.002000 -0.035000 0.339300 -vn 0.000000 -0.637728 0.770261 -v -0.000500 -0.033500 0.339300 -vn 0.318863 -0.552289 0.770262 -v -0.001250 -0.033701 0.339300 -vn -0.418260 0.536786 0.732748 -v -0.003988 -0.027608 0.339300 -vn 0.552288 -0.318864 0.770262 -v -0.001799 -0.034250 0.339300 -vn -0.290642 0.615311 0.732748 -v -0.010552 -0.031647 0.339300 -vn 0.637728 0.000000 0.770261 -v -0.052000 -0.035000 0.339300 -vn 0.552288 -0.318864 0.770262 -v -0.051799 -0.034250 0.339300 -vn 0.318863 -0.552290 0.770261 -v -0.051250 -0.033701 0.339300 -vn 0.000000 -0.637728 0.770261 -v -0.050500 -0.033500 0.339300 -vn 0.398343 0.566908 0.721067 -v -0.047012 -0.027608 0.339300 -vn -0.318863 -0.552289 0.770262 -v -0.049750 -0.033701 0.339300 -vn 0.290642 0.615311 0.732748 -v -0.040449 -0.031647 0.339300 -vn -0.552288 -0.318865 0.770262 -v -0.049201 -0.034250 0.339300 -vn 0.167832 0.666314 0.726539 -v -0.033160 -0.034151 0.339300 -vn 0.074402 0.690257 0.719729 -v -0.029148 -0.034809 0.339300 -vn -0.019982 0.687570 0.725843 -v -0.025500 -0.035000 0.339300 -vn -0.148931 0.664003 0.732748 -v -0.017840 -0.034151 0.339300 -vn -0.318863 0.552289 0.770262 -v 0.000250 -0.036299 0.339300 -vn 0.000000 0.637728 0.770261 -v -0.000500 -0.036500 0.339300 -vn 0.318863 0.552289 0.770262 -v -0.001250 -0.036299 0.339300 -vn -0.620411 0.404622 0.671842 -v 0.009759 -0.005537 0.339300 -vn -0.661041 0.267751 0.700952 -v 0.008438 -0.008556 0.339300 -vn -0.455258 0.584268 0.671842 -v 0.011988 -0.003112 0.339300 -vn -0.318864 -0.552289 0.770261 -v 0.008209 -0.017614 0.339300 -vn -0.552288 -0.318865 0.770262 -v 0.008795 -0.018200 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.011129 -0.027050 0.339300 -vn -0.637727 0.000000 0.770262 -v 0.009009 -0.019000 0.339300 -vn -0.552288 0.318865 0.770262 -v 0.008795 -0.019800 0.339300 -vn -0.318863 0.552289 0.770262 -v 0.008209 -0.020386 0.339300 -vn -0.000000 0.637729 0.770261 -v 0.007409 -0.020600 0.339300 -vn 0.318863 0.552288 0.770262 -v 0.006609 -0.020386 0.339300 -vn -0.620422 0.294406 0.726912 -v 0.005743 -0.015776 0.339300 -vn 0.318864 -0.552289 0.770261 -v 0.006609 -0.017614 0.339300 -vn -0.000000 -0.637727 0.770262 -v 0.007409 -0.017400 0.339300 -vn 0.552288 0.318865 0.770262 -v 0.006023 -0.019800 0.339300 -vn 0.637727 0.000000 0.770262 -v 0.005809 -0.019000 0.339300 -vn 0.552288 -0.318865 0.770262 -v 0.006023 -0.018200 0.339300 -vn -0.240691 0.700497 0.671842 -v 0.014885 -0.001543 0.339300 -vn 0.657141 0.000000 0.753767 -v -0.009250 -0.124000 0.339300 -vn 0.607120 -0.251477 0.753767 -v -0.008394 -0.119695 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.029125 -0.103000 0.339300 -vn -0.251477 0.607119 0.753767 -v 0.006305 -0.134394 0.339300 -vn 0.000000 0.657141 0.753767 -v 0.002000 -0.135250 0.339300 -vn 0.251477 0.607119 0.753767 -v -0.002305 -0.134394 0.339300 -vn 0.464669 0.464669 0.753767 -v -0.005955 -0.131955 0.339300 -vn 0.464669 -0.464669 0.753767 -v -0.005955 -0.116045 0.339300 -vn 0.251477 -0.607119 0.753767 -v -0.002305 -0.113606 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.003404 -0.103000 0.339300 -vn 0.000000 -0.657141 0.753767 -v 0.002000 -0.112750 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.011129 -0.103000 0.339300 -vn -0.251477 -0.607119 0.753767 -v 0.006305 -0.113606 0.339300 -vn -0.464669 -0.464669 0.753767 -v 0.009955 -0.116045 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019575 -0.103000 0.339300 -vn -0.607119 -0.251477 0.753767 -v 0.012394 -0.119695 0.339300 -vn -0.657141 0.000000 0.753767 -v 0.013250 -0.124000 0.339300 -vn -0.607119 0.251477 0.753768 -v 0.012394 -0.128305 0.339300 -vn -0.464669 0.464669 0.753767 -v 0.009955 -0.131955 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.077325 -0.027050 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.077325 -0.040125 0.339300 -vn -0.318865 -0.552287 0.770262 -v -0.078875 -0.044051 0.339300 -vn -0.552290 -0.318863 0.770261 -v -0.078051 -0.044875 0.339300 -vn -0.637728 0.000000 0.770262 -v -0.077750 -0.046000 0.339300 -vn -0.552290 0.318863 0.770261 -v -0.078051 -0.047125 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.077325 -0.068500 0.339300 -vn -0.318865 0.552287 0.770262 -v -0.078875 -0.047949 0.339300 -vn 0.000000 0.637728 0.770262 -v -0.080000 -0.048250 0.339300 -vn 0.637728 -0.000000 0.770262 -v -0.082250 -0.046000 0.339300 -vn 0.552289 0.318864 0.770262 -v -0.081949 -0.047125 0.339300 -vn 0.318864 0.552289 0.770262 -v -0.081125 -0.047949 0.339300 -vn 0.552289 -0.318864 0.770262 -v -0.081949 -0.044875 0.339300 -vn 0.318864 -0.552289 0.770262 -v -0.081125 -0.044051 0.339300 -vn -0.000000 -0.637728 0.770262 -v -0.080000 -0.043750 0.339300 -vn -0.000000 -0.637728 0.770262 -v -0.080000 -0.088750 0.339300 -vn -0.318865 -0.552287 0.770262 -v -0.078875 -0.089051 0.339300 -vn -0.552290 -0.318863 0.770261 -v -0.078051 -0.089875 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.077325 -0.103000 0.339300 -vn -0.637728 0.000000 0.770262 -v -0.077750 -0.091000 0.339300 -vn -0.552290 0.318863 0.770261 -v -0.078051 -0.092125 0.339300 -vn 0.318864 -0.552289 0.770262 -v -0.081125 -0.089051 0.339300 -vn 0.552289 -0.318864 0.770262 -v -0.081949 -0.089875 0.339300 -vn 0.637728 -0.000000 0.770262 -v -0.082250 -0.091000 0.339300 -vn 0.552289 0.318864 0.770262 -v -0.081949 -0.092125 0.339300 -vn -0.318865 0.552287 0.770262 -v -0.078875 -0.092949 0.339300 -vn 0.000000 0.637728 0.770262 -v -0.080000 -0.093250 0.339300 -vn 0.318864 0.552289 0.770262 -v -0.081125 -0.092949 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.068454 -0.040125 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.068454 -0.103000 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.068454 -0.122825 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.054404 -0.103000 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.054404 -0.122825 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.029125 -0.122825 0.339300 -vn 0.607119 0.251477 0.753767 -v -0.008394 -0.128305 0.339300 -vn -0.318865 -0.552288 0.770261 -v -0.078450 -0.133315 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.011129 -0.040125 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019575 -0.040125 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.068454 -0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.054404 -0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v -0.029125 -0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.003404 -0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.011129 -0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.019575 -0.068500 0.339300 -vn -0.318864 0.552289 0.770262 -v 0.030125 -0.047949 0.339300 -vn 0.000000 0.637728 0.770262 -v 0.029000 -0.048250 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.031675 -0.068500 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.031675 -0.040125 0.339300 -vn -0.000000 -0.637728 0.770262 -v 0.029000 -0.043750 0.339300 -vn -0.318864 -0.552289 0.770262 -v 0.030125 -0.044051 0.339300 -vn 0.552289 -0.318863 0.770262 -v 0.027051 -0.044875 0.339300 -vn 0.318864 -0.552288 0.770262 -v 0.027875 -0.044051 0.339300 -vn -0.552289 -0.318864 0.770262 -v 0.030949 -0.044875 0.339300 -vn -0.637728 0.000000 0.770262 -v 0.031250 -0.046000 0.339300 -vn -0.552289 0.318864 0.770262 -v 0.030949 -0.047125 0.339300 -vn 0.318864 0.552288 0.770262 -v 0.027875 -0.047949 0.339300 -vn 0.552289 0.318864 0.770262 -v 0.027051 -0.047125 0.339300 -vn 0.637728 -0.000000 0.770262 -v 0.026750 -0.046000 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.031675 -0.027050 0.339300 -vn 0.318864 0.552288 0.770262 -v 0.027875 -0.092949 0.339300 -vn 0.552289 0.318864 0.770262 -v 0.027051 -0.092125 0.339300 -vn 0.637728 -0.000000 0.770262 -v 0.026750 -0.091000 0.339300 -vn 0.552289 -0.318863 0.770262 -v 0.027051 -0.089875 0.339300 -vn 0.318864 -0.552288 0.770262 -v 0.027875 -0.089051 0.339300 -vn -0.000000 -0.637728 0.770262 -v 0.029000 -0.088750 0.339300 -vn -0.318864 -0.552289 0.770262 -v 0.030125 -0.089051 0.339300 -vn -0.552288 -0.318864 0.770262 -v 0.030949 -0.089875 0.339300 -vn -0.637728 0.000000 0.770262 -v 0.031250 -0.091000 0.339300 -vn 0.000000 0.000000 1.000000 -v 0.031675 -0.103000 0.339300 -vn -0.552288 0.318864 0.770262 -v 0.030949 -0.092125 0.339300 -vn -0.318864 0.552289 0.770262 -v 0.030125 -0.092949 0.339300 -vn 0.000000 0.637728 0.770262 -v 0.029000 -0.093250 0.339300 -vn 0.000000 0.000000 -1.000000 -v -0.054404 -0.027050 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.054404 -0.040125 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.068454 -0.040125 0.337300 -vn 0.607120 -0.251477 -0.753767 -v -0.008394 -0.119695 0.337300 -vn 0.657141 0.000000 -0.753767 -v -0.009250 -0.124000 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.029125 -0.122825 0.337300 -vn 0.318863 0.552289 -0.770262 -v -0.051250 -0.036299 0.337300 -vn 0.000000 0.637728 -0.770262 -v -0.050500 -0.036500 0.337300 -vn -0.579186 0.382798 -0.719729 -v 0.003581 -0.019476 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.003404 -0.027050 0.337300 -vn -0.517948 0.453235 -0.725471 -v 0.001533 -0.022231 0.337300 -vn -0.000000 0.637729 -0.770261 -v -0.058409 -0.020600 0.337300 -vn -0.318863 0.552289 -0.770262 -v -0.057609 -0.020386 0.337300 -vn 0.529218 0.430139 -0.731375 -v -0.052533 -0.022231 0.337300 -vn 0.462239 0.518001 -0.719729 -v -0.047641 -0.027107 0.337300 -vn 0.552288 -0.318865 -0.770262 -v -0.059795 -0.018200 0.337300 -vn 0.637727 0.000000 -0.770262 -v -0.060009 -0.019000 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.068454 -0.027050 0.337300 -vn 0.552288 0.318865 -0.770262 -v -0.059795 -0.019800 0.337300 -vn 0.318863 0.552289 -0.770262 -v -0.059209 -0.020386 0.337300 -vn -0.552288 0.318865 -0.770262 -v -0.057023 -0.019800 0.337300 -vn -0.637727 0.000000 -0.770262 -v -0.056809 -0.019000 0.337300 -vn 0.607454 0.306725 -0.732748 -v -0.056743 -0.015776 0.337300 -vn -0.000000 -0.637727 -0.770262 -v -0.058409 -0.017400 0.337300 -vn 0.661041 0.267752 -0.700952 -v -0.059438 -0.008556 0.337300 -vn -0.318864 -0.552289 -0.770261 -v -0.057609 -0.017614 0.337300 -vn -0.552288 -0.318865 -0.770262 -v -0.057023 -0.018200 0.337300 -vn 0.240691 0.700497 -0.671842 -v -0.065885 -0.001543 0.337300 -vn 0.455258 0.584268 -0.671842 -v -0.062989 -0.003112 0.337300 -vn 0.318864 -0.552289 -0.770261 -v -0.059209 -0.017614 0.337300 -vn 0.620411 0.404623 -0.671842 -v -0.060759 -0.005537 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.077325 -0.027050 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.077325 -0.122825 0.337300 -vn -0.318865 -0.552288 -0.770261 -v -0.078450 -0.133315 0.337300 -vn -0.000000 -0.637727 -0.770262 -v -0.080000 -0.132900 0.337300 -vn 0.318865 -0.552288 -0.770262 -v -0.081550 -0.133315 0.337300 -vn 0.552289 -0.318863 -0.770262 -v -0.082685 -0.134450 0.337300 -vn 0.637728 0.000001 -0.770261 -v -0.083100 -0.136000 0.337300 -vn 0.552289 0.318864 -0.770262 -v -0.082685 -0.137550 0.337300 -vn -0.000000 0.637727 -0.770262 -v -0.080000 -0.139100 0.337300 -vn 0.318865 0.552288 -0.770262 -v -0.081550 -0.138685 0.337300 -vn -0.637727 0.000001 -0.770262 -v 0.032100 -0.136000 0.337300 -vn -0.552288 0.318865 -0.770262 -v 0.031685 -0.137550 0.337300 -vn -0.318865 0.552289 -0.770261 -v 0.030550 -0.138685 0.337300 -vn -0.637727 0.000000 -0.770262 -v 0.009009 -0.019000 0.337300 -vn -0.552288 -0.318865 -0.770262 -v 0.008795 -0.018200 0.337300 -vn -0.455258 0.584268 -0.671842 -v 0.011988 -0.003112 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.011129 -0.027050 0.337300 -vn -0.318863 0.552289 -0.770262 -v 0.008209 -0.020386 0.337300 -vn -0.552288 0.318865 -0.770262 -v 0.008795 -0.019800 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019575 -0.027050 0.337300 -vn -0.240691 0.700497 -0.671842 -v 0.014885 -0.001543 0.337300 -vn -0.661041 0.267751 -0.700952 -v 0.008438 -0.008556 0.337300 -vn -0.620411 0.404622 -0.671842 -v 0.009759 -0.005537 0.337300 -vn 0.552288 0.318865 -0.770262 -v 0.006023 -0.019800 0.337300 -vn 0.318863 0.552289 -0.770262 -v 0.006609 -0.020386 0.337300 -vn -0.000000 0.637729 -0.770261 -v 0.007409 -0.020600 0.337300 -vn -0.620422 0.294406 -0.726912 -v 0.005743 -0.015776 0.337300 -vn -0.000000 -0.637727 -0.770262 -v 0.007409 -0.017400 0.337300 -vn -0.318864 -0.552289 -0.770261 -v 0.008209 -0.017614 0.337300 -vn 0.318864 -0.552289 -0.770261 -v 0.006609 -0.017614 0.337300 -vn 0.552288 -0.318865 -0.770262 -v 0.006023 -0.018200 0.337300 -vn 0.637727 0.000000 -0.770262 -v 0.005809 -0.019000 0.337300 -vn 0.000000 0.637728 -0.770261 -v -0.000500 -0.036500 0.337300 -vn -0.318863 0.552289 -0.770262 -v 0.000250 -0.036299 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.003404 -0.040125 0.337300 -vn -0.552288 0.318864 -0.770262 -v 0.000799 -0.035750 0.337300 -vn -0.637728 -0.000000 -0.770261 -v 0.001000 -0.035000 0.337300 -vn 0.318863 0.552289 -0.770262 -v -0.001250 -0.036299 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.029125 -0.040125 0.337300 -vn 0.552288 0.318864 -0.770262 -v -0.001799 -0.035750 0.337300 -vn -0.552288 -0.318864 -0.770262 -v 0.000799 -0.034250 0.337300 -vn -0.318863 -0.552289 -0.770262 -v 0.000250 -0.033701 0.337300 -vn -0.000000 -0.637728 -0.770261 -v -0.000500 -0.033500 0.337300 -vn -0.418260 0.536786 -0.732748 -v -0.003988 -0.027608 0.337300 -vn 0.318863 -0.552289 -0.770262 -v -0.001250 -0.033701 0.337300 -vn -0.290642 0.615311 -0.732748 -v -0.010552 -0.031647 0.337300 -vn 0.552288 -0.318864 -0.770262 -v -0.001799 -0.034250 0.337300 -vn -0.148931 0.664003 -0.732748 -v -0.017840 -0.034151 0.337300 -vn 0.637728 -0.000000 -0.770262 -v -0.002000 -0.035000 0.337300 -vn -0.019982 0.687570 -0.725843 -v -0.025500 -0.035000 0.337300 -vn -0.318863 0.552289 -0.770262 -v -0.049750 -0.036299 0.337300 -vn -0.552288 0.318865 -0.770262 -v -0.049201 -0.035750 0.337300 -vn 0.318863 -0.552289 -0.770262 -v -0.051250 -0.033701 0.337300 -vn 0.552288 -0.318864 -0.770263 -v -0.051799 -0.034250 0.337300 -vn 0.637728 -0.000000 -0.770261 -v -0.052000 -0.035000 0.337300 -vn 0.552288 0.318864 -0.770262 -v -0.051799 -0.035750 0.337300 -vn 0.074402 0.690257 -0.719729 -v -0.029148 -0.034809 0.337300 -vn -0.637727 0.000000 -0.770263 -v -0.049000 -0.035000 0.337300 -vn 0.000000 -0.637728 -0.770261 -v -0.050500 -0.033500 0.337300 -vn -0.318863 -0.552289 -0.770262 -v -0.049750 -0.033701 0.337300 -vn 0.398343 0.566908 -0.721067 -v -0.047012 -0.027608 0.337300 -vn -0.552288 -0.318865 -0.770261 -v -0.049201 -0.034250 0.337300 -vn 0.290642 0.615311 -0.732748 -v -0.040449 -0.031647 0.337300 -vn 0.167832 0.666314 -0.726539 -v -0.033160 -0.034151 0.337300 -vn 0.000000 -0.637727 -0.770262 -v 0.029000 -0.132900 0.337300 -vn 0.318865 -0.552288 -0.770262 -v 0.027450 -0.133315 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019575 -0.122825 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.031675 -0.122825 0.337300 -vn -0.552288 -0.318864 -0.770262 -v 0.031685 -0.134450 0.337300 -vn -0.318865 -0.552289 -0.770261 -v 0.030550 -0.133315 0.337300 -vn 0.552288 -0.318864 -0.770262 -v 0.026315 -0.134450 0.337300 -vn 0.637728 0.000001 -0.770262 -v 0.025900 -0.136000 0.337300 -vn 0.552288 0.318865 -0.770262 -v 0.026315 -0.137550 0.337300 -vn 0.318865 0.552288 -0.770262 -v 0.027450 -0.138685 0.337300 -vn 0.000000 0.637727 -0.770262 -v 0.029000 -0.139100 0.337300 -vn -0.637727 0.000001 -0.770263 -v -0.076900 -0.136000 0.337300 -vn -0.552288 0.318865 -0.770261 -v -0.077315 -0.137550 0.337300 -vn -0.318865 0.552288 -0.770261 -v -0.078450 -0.138685 0.337300 -vn -0.552288 -0.318865 -0.770262 -v -0.077315 -0.134450 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.068454 -0.122825 0.337300 -vn 0.464669 -0.464669 -0.753767 -v -0.005955 -0.116045 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.029125 -0.103000 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.011129 -0.103000 0.337300 -vn -0.251477 -0.607119 -0.753767 -v 0.006305 -0.113606 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.003404 -0.103000 0.337300 -vn -0.000000 -0.657141 -0.753767 -v 0.002000 -0.112750 0.337300 -vn 0.251477 -0.607119 -0.753767 -v -0.002305 -0.113606 0.337300 -vn 0.607119 0.251477 -0.753767 -v -0.008394 -0.128305 0.337300 -vn 0.464669 0.464669 -0.753767 -v -0.005955 -0.131955 0.337300 -vn 0.251477 0.607119 -0.753767 -v -0.002305 -0.134394 0.337300 -vn -0.000000 0.657141 -0.753767 -v 0.002000 -0.135250 0.337300 -vn -0.251477 0.607119 -0.753767 -v 0.006305 -0.134394 0.337300 -vn -0.464669 0.464669 -0.753767 -v 0.009955 -0.131955 0.337300 -vn -0.607119 0.251477 -0.753768 -v 0.012394 -0.128305 0.337300 -vn -0.657141 0.000000 -0.753767 -v 0.013250 -0.124000 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019575 -0.103000 0.337300 -vn -0.607119 -0.251477 -0.753768 -v 0.012394 -0.119695 0.337300 -vn -0.464669 -0.464669 -0.753767 -v 0.009955 -0.116045 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.031675 -0.040125 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.031675 -0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.031675 -0.103000 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.031675 -0.027050 0.337300 -vn -0.318864 -0.552289 -0.770262 -v 0.030125 -0.044051 0.337300 -vn 0.000000 -0.637728 -0.770262 -v 0.029000 -0.043750 0.337300 -vn 0.318864 0.552288 -0.770262 -v 0.027875 -0.047949 0.337300 -vn -0.000000 0.637728 -0.770262 -v 0.029000 -0.048250 0.337300 -vn -0.318864 0.552289 -0.770262 -v 0.030125 -0.047949 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019575 -0.040125 0.337300 -vn 0.318864 -0.552288 -0.770262 -v 0.027875 -0.044051 0.337300 -vn 0.552289 -0.318864 -0.770262 -v 0.027051 -0.044875 0.337300 -vn 0.637728 0.000000 -0.770262 -v 0.026750 -0.046000 0.337300 -vn -0.552289 0.318864 -0.770262 -v 0.030949 -0.047125 0.337300 -vn -0.637728 -0.000000 -0.770262 -v 0.031250 -0.046000 0.337300 -vn -0.552289 -0.318864 -0.770262 -v 0.030949 -0.044875 0.337300 -vn 0.318864 0.552288 -0.770262 -v 0.027875 -0.092949 0.337300 -vn -0.000000 0.637728 -0.770262 -v 0.029000 -0.093250 0.337300 -vn -0.318864 0.552289 -0.770262 -v 0.030125 -0.092949 0.337300 -vn -0.552288 0.318864 -0.770262 -v 0.030949 -0.092125 0.337300 -vn -0.637728 -0.000000 -0.770262 -v 0.031250 -0.091000 0.337300 -vn -0.552288 -0.318864 -0.770262 -v 0.030949 -0.089875 0.337300 -vn -0.318864 -0.552289 -0.770262 -v 0.030125 -0.089051 0.337300 -vn 0.000000 -0.637728 -0.770262 -v 0.029000 -0.088750 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.019575 -0.068500 0.337300 -vn 0.552289 0.318863 -0.770262 -v 0.027051 -0.047125 0.337300 -vn 0.637728 0.000000 -0.770262 -v 0.026750 -0.091000 0.337300 -vn 0.552289 0.318863 -0.770262 -v 0.027051 -0.092125 0.337300 -vn 0.318864 -0.552288 -0.770262 -v 0.027875 -0.089051 0.337300 -vn 0.552289 -0.318864 -0.770262 -v 0.027051 -0.089875 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.011129 -0.040125 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.077325 -0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.068454 -0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.054404 -0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.029125 -0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.003404 -0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v 0.011129 -0.068500 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.054404 -0.122825 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.077325 -0.040125 0.337300 -vn 0.552289 -0.318864 -0.770262 -v -0.081949 -0.044875 0.337300 -vn 0.637728 0.000000 -0.770262 -v -0.082250 -0.046000 0.337300 -vn -0.637728 -0.000000 -0.770262 -v -0.077750 -0.046000 0.337300 -vn -0.552290 -0.318863 -0.770261 -v -0.078051 -0.044875 0.337300 -vn -0.318865 0.552287 -0.770262 -v -0.078875 -0.047949 0.337300 -vn -0.552290 0.318863 -0.770261 -v -0.078051 -0.047125 0.337300 -vn -0.318865 -0.552287 -0.770262 -v -0.078875 -0.044051 0.337300 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 -0.043750 0.337300 -vn 0.318864 -0.552289 -0.770262 -v -0.081125 -0.044051 0.337300 -vn 0.552289 0.318864 -0.770262 -v -0.081949 -0.047125 0.337300 -vn 0.318864 0.552289 -0.770262 -v -0.081125 -0.047949 0.337300 -vn -0.000000 0.637728 -0.770262 -v -0.080000 -0.048250 0.337300 -vn -0.000000 0.637728 -0.770262 -v -0.080000 -0.093250 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.077325 -0.103000 0.337300 -vn 0.318864 0.552289 -0.770262 -v -0.081125 -0.092949 0.337300 -vn -0.318865 0.552287 -0.770262 -v -0.078875 -0.092949 0.337300 -vn -0.552290 0.318863 -0.770261 -v -0.078051 -0.092125 0.337300 -vn -0.637728 -0.000000 -0.770262 -v -0.077750 -0.091000 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.054404 -0.103000 0.337300 -vn 0.000000 0.000000 -1.000000 -v -0.068454 -0.103000 0.337300 -vn -0.552290 -0.318863 -0.770261 -v -0.078051 -0.089875 0.337300 -vn 0.318864 -0.552289 -0.770262 -v -0.081125 -0.089051 0.337300 -vn 0.000000 -0.637728 -0.770262 -v -0.080000 -0.088750 0.337300 -vn -0.318865 -0.552287 -0.770262 -v -0.078875 -0.089051 0.337300 -vn 0.552289 -0.318864 -0.770262 -v -0.081949 -0.089875 0.337300 -vn 0.637728 0.000000 -0.770262 -v -0.082250 -0.091000 0.337300 -vn 0.552289 0.318864 -0.770262 -v -0.081949 -0.092125 0.337300 -vn 0.727973 0.095840 -0.678874 -v 0.038750 0.140000 0.164800 -vn 0.727973 0.095840 0.678874 -v 0.038750 0.140000 0.166800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.138625 0.164800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.138625 0.166800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.125125 0.164800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.125125 0.166800 -vn 0.727973 -0.095840 -0.678874 -v 0.038750 0.109773 0.164800 -vn 0.727973 -0.095840 0.678874 -v 0.038750 0.109773 0.166800 -vn 0.727973 -0.095840 0.678874 -v 0.038750 -0.140000 0.166800 -vn 0.727973 -0.095840 -0.678874 -v 0.038750 -0.140000 0.164800 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.125125 0.166800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.125125 0.164800 -vn 0.727973 0.095840 0.678874 -v 0.038750 -0.109773 0.166800 -vn 0.727973 0.095840 -0.678875 -v 0.038750 -0.109773 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 0.098020 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 0.089244 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 0.089244 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 0.066000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 0.066000 0.164800 -vn -0.552286 0.318862 -0.770265 -v -0.073384 0.051583 0.164800 -vn -0.669355 0.088118 -0.737699 -v -0.073250 0.052083 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 0.049323 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 0.049323 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 0.049323 0.164800 -vn -0.552286 0.318862 -0.770265 -v -0.073384 -0.080417 0.164800 -vn -0.669355 0.088118 -0.737699 -v -0.073250 -0.079917 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 -0.098020 0.164800 -vn -0.727973 -0.095838 -0.678875 -v -0.078250 0.043312 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.078250 0.049323 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.049323 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.066000 0.164800 -vn -0.727973 0.095840 -0.678874 -v -0.090250 0.119000 0.164800 -vn -0.655722 0.378581 -0.653227 -v -0.089580 0.121500 0.164800 -vn -0.378581 0.655722 -0.653227 -v -0.087750 0.123330 0.164800 -vn 0.727973 0.095839 -0.678875 -v -0.039250 0.140000 0.164800 -vn 0.707106 0.000000 -0.707107 -v -0.039250 0.138625 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 0.138625 0.164800 -vn -0.655722 0.378581 -0.653227 -v 0.012420 0.142500 0.164800 -vn -0.378581 0.655722 -0.653226 -v 0.014250 0.144330 0.164800 -vn -0.095839 0.727973 -0.678875 -v 0.016750 0.145000 0.164800 -vn 0.318864 0.552288 -0.770262 -v 0.003750 0.066472 0.164800 -vn 0.639172 0.490453 -0.592381 -v 0.008750 0.065132 0.164800 -vn 0.707107 0.000000 -0.707107 -v 0.008750 0.049323 0.164800 -vn 0.353554 0.612372 -0.707107 -v 0.028392 -0.098020 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 -0.098020 0.164800 -vn 0.353554 0.612372 -0.707107 -v 0.026125 -0.096711 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.108310 0.164800 -vn 0.000000 -0.707107 -0.707107 -v -0.007200 -0.115000 0.164800 -vn 0.000000 -0.707107 -0.707107 -v -0.019900 -0.115000 0.164800 -vn -0.669353 -0.088121 -0.737700 -v -0.069250 -0.126000 0.164800 -vn -0.552287 -0.318864 -0.770263 -v -0.069518 -0.125000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 -0.125125 0.164800 -vn -0.552289 -0.318863 -0.770262 -v 0.006478 -0.099145 0.164800 -vn -0.318863 -0.552288 -0.770262 -v 0.005325 -0.097992 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 -0.098020 0.164800 -vn 0.552287 -0.318865 -0.770262 -v 0.026152 0.137500 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 0.138625 0.164800 -vn 0.318864 -0.552289 -0.770261 -v 0.027250 0.138598 0.164800 -vn 0.552287 0.318865 -0.770262 -v 0.026152 -0.137500 0.164800 -vn 0.000000 -0.707107 -0.707107 -v 0.026125 -0.145000 0.164800 -vn -0.095839 -0.727973 -0.678874 -v 0.016750 -0.145000 0.164800 -vn -0.318864 -0.552290 -0.770261 -v 0.030250 -0.133402 0.164800 -vn -0.000000 -0.637727 -0.770263 -v 0.028750 -0.133000 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 -0.125125 0.164800 -vn 0.318864 -0.552289 -0.770261 -v 0.027250 -0.133402 0.164800 -vn -0.552287 -0.318865 -0.770263 -v 0.031348 -0.134500 0.164800 -vn -0.637728 0.000001 -0.770262 -v 0.031750 -0.136000 0.164800 -vn -0.552287 0.318866 -0.770262 -v 0.031348 -0.137500 0.164800 -vn 0.318864 0.552289 -0.770261 -v 0.027250 -0.138598 0.164800 -vn -0.000000 0.637727 -0.770263 -v 0.028750 -0.139000 0.164800 -vn 0.095838 -0.727973 -0.678875 -v 0.033750 -0.145000 0.164800 -vn -0.318864 0.552290 -0.770261 -v 0.030250 -0.138598 0.164800 -vn 0.378581 -0.655722 -0.653226 -v 0.036250 -0.144330 0.164800 -vn 0.655722 -0.378581 -0.653227 -v 0.038080 -0.142500 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 -0.125125 0.164800 -vn 0.552288 -0.318864 -0.770262 -v 0.026152 -0.134500 0.164800 -vn 0.637728 0.000001 -0.770262 -v 0.025750 -0.136000 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 0.138625 0.164800 -vn 0.378581 0.655722 -0.653226 -v 0.036250 0.144330 0.164800 -vn 0.655722 0.378581 -0.653227 -v 0.038080 0.142500 0.164800 -vn -0.000000 -0.637727 -0.770263 -v 0.028750 0.139000 0.164800 -vn 0.000000 0.707107 -0.707107 -v 0.026125 0.145000 0.164800 -vn 0.095838 0.727973 -0.678875 -v 0.033750 0.145000 0.164800 -vn -0.552288 0.318864 -0.770262 -v 0.031348 0.134500 0.164800 -vn -0.637728 -0.000001 -0.770262 -v 0.031750 0.136000 0.164800 -vn -0.318864 -0.552289 -0.770261 -v 0.030250 0.138598 0.164800 -vn -0.552287 -0.318865 -0.770262 -v 0.031348 0.137500 0.164800 -vn 0.552288 0.318864 -0.770262 -v 0.026152 0.134500 0.164800 -vn 0.318864 0.552289 -0.770261 -v 0.027250 0.133402 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 0.125125 0.164800 -vn -0.000000 0.637727 -0.770263 -v 0.028750 0.133000 0.164800 -vn -0.318864 0.552289 -0.770261 -v 0.030250 0.133402 0.164800 -vn -0.318863 -0.552288 -0.770262 -v 0.005325 0.103448 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 0.103420 0.164800 -vn -0.552289 -0.318864 -0.770262 -v 0.006478 0.102295 0.164800 -vn -0.637728 -0.000000 -0.770262 -v 0.006900 0.100720 0.164800 -vn 0.318864 0.552288 -0.770263 -v 0.002175 0.097992 0.164800 -vn 0.000000 0.637729 -0.770261 -v 0.003750 0.097570 0.164800 -vn 0.353554 -0.612373 -0.707107 -v 0.013191 0.089244 0.164800 -vn -0.318863 0.552288 -0.770262 -v 0.005325 0.097992 0.164800 -vn -0.552289 0.318863 -0.770262 -v 0.006478 0.099145 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 0.098020 0.164800 -vn 0.353554 -0.612372 -0.707107 -v 0.016325 0.091053 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.089244 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.098020 0.164800 -vn 0.552289 0.318863 -0.770262 -v 0.001022 0.099145 0.164800 -vn 0.637728 -0.000000 -0.770262 -v 0.000600 0.100720 0.164800 -vn 0.552289 -0.318864 -0.770261 -v 0.001022 0.102295 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.103420 0.164800 -vn 0.318864 -0.552288 -0.770263 -v 0.002175 0.103448 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 0.125125 0.164800 -vn -0.552289 0.318864 -0.770262 -v 0.010410 0.120000 0.164800 -vn -0.318864 0.552289 -0.770262 -v 0.006750 0.116340 0.164800 -vn -0.088122 0.669353 -0.737700 -v 0.001750 0.115000 0.164800 -vn 0.000000 -0.637729 -0.770261 -v 0.003750 0.103870 0.164800 -vn 0.000000 0.707107 -0.707107 -v -0.007200 0.115000 0.164800 -vn 0.637728 0.000000 -0.770262 -v -0.001250 -0.075132 0.164800 -vn 0.552289 0.318864 -0.770262 -v 0.000090 -0.080132 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.098020 0.164800 -vn 0.318864 -0.552288 -0.770262 -v 0.003750 -0.066472 0.164800 -vn 0.552289 -0.318864 -0.770262 -v 0.000090 -0.070132 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.066000 0.164800 -vn 0.410992 0.535615 -0.737700 -v 0.003750 -0.083793 0.164800 -vn 0.353553 0.612372 -0.707107 -v 0.016325 -0.091053 0.164800 -vn 0.000000 -0.637729 -0.770261 -v 0.003750 -0.097570 0.164800 -vn 0.318864 -0.552288 -0.770263 -v 0.002175 -0.097992 0.164800 -vn 0.552289 -0.318863 -0.770261 -v 0.001022 -0.099145 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.103420 0.164800 -vn 0.637728 0.000000 -0.770262 -v 0.000600 -0.100720 0.164800 -vn 0.552289 0.318864 -0.770261 -v 0.001022 -0.102295 0.164800 -vn 0.318864 0.552288 -0.770263 -v 0.002175 -0.103448 0.164800 -vn -0.000000 0.637729 -0.770261 -v 0.003750 -0.103870 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 -0.108310 0.164800 -vn -0.318863 0.552288 -0.770262 -v 0.005325 -0.103448 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.016325 -0.103420 0.164800 -vn -0.552289 0.318864 -0.770262 -v 0.006478 -0.102295 0.164800 -vn -0.637728 0.000000 -0.770262 -v 0.006900 -0.100720 0.164800 -vn 0.000000 -0.707107 -0.707107 -v -0.019900 0.041312 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.018049 0.043062 0.164800 -vn -0.069844 -0.678920 -0.730882 -v -0.012049 0.041312 0.164800 -vn -0.318864 0.552289 -0.770262 -v -0.016924 0.043364 0.164800 -vn -0.260984 -0.600379 -0.755932 -v -0.011152 0.041126 0.164800 -vn -0.318864 -0.552289 -0.770262 -v -0.016924 0.047261 0.164800 -vn 0.000000 -0.637728 -0.770262 -v -0.018049 0.047562 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.049323 0.164800 -vn -0.478695 -0.446562 -0.755932 -v -0.010404 0.040597 0.164800 -vn -0.552289 -0.318864 -0.770262 -v -0.016101 0.046437 0.164800 -vn -0.637728 -0.000000 -0.770262 -v -0.015799 0.045312 0.164800 -vn -0.552289 0.318864 -0.770262 -v -0.016101 0.044187 0.164800 -vn -0.707107 -0.000000 -0.707107 -v -0.012049 -0.000000 0.164800 -vn -0.626968 0.510002 -0.588905 -v -0.012049 0.036500 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.000000 0.164800 -vn -0.260984 0.600379 -0.755932 -v -0.011152 0.036687 0.164800 -vn -0.478695 0.446562 -0.755932 -v -0.010404 0.037215 0.164800 -vn -0.617038 0.218703 -0.755932 -v -0.009929 0.037998 0.164800 -vn -0.673884 -0.000000 -0.738837 -v -0.009805 0.038906 0.164800 -vn -0.617038 -0.218703 -0.755932 -v -0.009929 0.039814 0.164800 -vn -0.318864 0.552289 -0.770262 -v -0.016924 -0.046949 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.049166 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.018049 -0.047250 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 -0.049166 0.164800 -vn -0.626968 -0.510002 -0.588905 -v -0.012049 -0.036188 0.164800 -vn -0.260984 -0.600379 -0.755931 -v -0.011152 -0.036374 0.164800 -vn -0.478695 -0.446562 -0.755932 -v -0.010404 -0.036903 0.164800 -vn -0.617038 -0.218703 -0.755932 -v -0.009929 -0.037686 0.164800 -vn -0.552288 0.318864 -0.770262 -v -0.016101 -0.046125 0.164800 -vn -0.637728 0.000000 -0.770262 -v -0.015799 -0.045000 0.164800 -vn -0.552289 -0.318864 -0.770262 -v -0.016101 -0.043875 0.164800 -vn -0.673884 0.000000 -0.738837 -v -0.009805 -0.038594 0.164800 -vn -0.617038 0.218703 -0.755932 -v -0.009929 -0.039502 0.164800 -vn 0.000000 -0.637728 -0.770262 -v -0.018049 -0.042750 0.164800 -vn 0.000000 0.707107 -0.707107 -v -0.019900 -0.041000 0.164800 -vn -0.318864 -0.552289 -0.770262 -v -0.016924 -0.043051 0.164800 -vn -0.069844 0.678920 -0.730882 -v -0.012049 -0.041000 0.164800 -vn -0.260984 0.600378 -0.755932 -v -0.011152 -0.040813 0.164800 -vn -0.478696 0.446562 -0.755931 -v -0.010404 -0.040285 0.164800 -vn -0.000000 0.707107 -0.707107 -v -0.023049 -0.040688 0.164800 -vn 0.577350 0.577350 -0.577350 -v -0.022049 -0.040688 0.164800 -vn 0.301511 0.301511 -0.904534 -v -0.022049 -0.041000 0.164800 -vn 0.552289 -0.318863 -0.770262 -v -0.019998 -0.043875 0.164800 -vn 0.637728 0.000000 -0.770262 -v -0.020299 -0.045000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 -0.049166 0.164800 -vn 0.552289 0.318864 -0.770262 -v -0.019998 -0.046125 0.164800 -vn 0.318864 0.552289 -0.770262 -v -0.019174 -0.046949 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.028049 -0.047250 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 -0.049166 0.164800 -vn -0.318864 0.552289 -0.770262 -v -0.026924 -0.046949 0.164800 -vn -0.552288 0.318864 -0.770262 -v -0.026101 -0.046125 0.164800 -vn -0.637728 0.000000 -0.770262 -v -0.025799 -0.045000 0.164800 -vn 0.318864 -0.552289 -0.770262 -v -0.019174 -0.043051 0.164800 -vn -0.552289 -0.318864 -0.770262 -v -0.026101 -0.043875 0.164800 -vn -0.318864 -0.552289 -0.770262 -v -0.026924 -0.043051 0.164800 -vn 0.000000 -0.637728 -0.770262 -v -0.028049 -0.042750 0.164800 -vn -0.000000 0.707106 -0.707108 -v -0.067375 -0.040688 0.164800 -vn 0.318864 -0.552288 -0.770262 -v -0.029174 -0.043051 0.164800 -vn 0.552289 -0.318864 -0.770262 -v -0.029998 -0.043875 0.164800 -vn 0.637728 0.000000 -0.770262 -v -0.030299 -0.045000 0.164800 -vn 0.552289 0.318864 -0.770262 -v -0.029998 -0.046125 0.164800 -vn 0.318864 0.552288 -0.770262 -v -0.029174 -0.046949 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.049166 0.164800 -vn -0.095839 0.727973 -0.678874 -v -0.076250 -0.040688 0.164800 -vn -0.271528 0.623295 -0.733332 -v -0.088113 -0.086766 0.164800 -vn -0.410993 0.535615 -0.737700 -v -0.079250 -0.081649 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.098020 0.164800 -vn -0.655723 0.378579 -0.653227 -v -0.077982 -0.041688 0.164800 -vn -0.378582 0.655722 -0.653226 -v -0.077250 -0.040956 0.164800 -vn -0.727973 0.095838 -0.678875 -v -0.078250 -0.042688 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.078250 -0.049166 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.078250 -0.066000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.066000 0.164800 -vn -0.669352 0.088123 -0.737701 -v -0.078250 -0.079917 0.164800 -vn -0.552288 0.318865 -0.770261 -v -0.078518 -0.080917 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 -0.098020 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 -0.098020 0.164800 -vn -0.646609 0.477776 -0.594666 -v -0.090250 -0.087423 0.164800 -vn -0.378581 -0.655722 -0.653227 -v -0.087750 -0.123330 0.164800 -vn -0.655722 -0.378581 -0.653227 -v -0.089580 -0.121500 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 -0.108310 0.164800 -vn -0.727973 -0.095840 -0.678874 -v -0.090250 -0.119000 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 -0.108310 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.108310 0.164800 -vn -0.637728 -0.000000 -0.770262 -v -0.078000 -0.115000 0.164800 -vn -0.552289 -0.318864 -0.770262 -v -0.078301 -0.113875 0.164800 -vn -0.318864 -0.552289 -0.770262 -v -0.079125 -0.113051 0.164800 -vn 0.000000 -0.637728 -0.770262 -v -0.080250 -0.112750 0.164800 -vn 0.318864 -0.552289 -0.770262 -v -0.081375 -0.113051 0.164800 -vn 0.000000 -0.707107 -0.707107 -v -0.076625 -0.124000 0.164800 -vn -0.318864 0.552289 -0.770262 -v -0.079125 -0.116949 0.164800 -vn -0.552289 0.318864 -0.770262 -v -0.078301 -0.116125 0.164800 -vn 0.552289 -0.318864 -0.770262 -v -0.082199 -0.113875 0.164800 -vn 0.637728 0.000000 -0.770262 -v -0.082500 -0.115000 0.164800 -vn 0.552289 0.318864 -0.770262 -v -0.082199 -0.116125 0.164800 -vn -0.095839 -0.727973 -0.678874 -v -0.085250 -0.124000 0.164800 -vn 0.318864 0.552289 -0.770262 -v -0.081375 -0.116949 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.080250 -0.117250 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 -0.108310 0.164800 -vn -0.088123 -0.669352 -0.737701 -v -0.071250 -0.124000 0.164800 -vn -0.318865 -0.552290 -0.770261 -v -0.070250 -0.124268 0.164800 -vn 0.707107 0.000000 -0.707107 -v -0.039250 -0.125125 0.164800 -vn 0.727973 -0.095839 -0.678874 -v -0.039250 -0.140000 0.164800 -vn -0.637728 0.000001 -0.770262 -v -0.057000 -0.136000 0.164800 -vn 0.318862 -0.552289 -0.770263 -v -0.060375 -0.134051 0.164800 -vn 0.552289 -0.318863 -0.770262 -v -0.061199 -0.134875 0.164800 -vn -0.655722 -0.378581 -0.653227 -v -0.068580 -0.142500 0.164800 -vn -0.727973 -0.095840 -0.678874 -v -0.069250 -0.140000 0.164800 -vn 0.095839 -0.727973 -0.678874 -v -0.044250 -0.145000 0.164800 -vn -0.552288 0.318865 -0.770262 -v -0.057301 -0.137125 0.164800 -vn 0.378581 -0.655722 -0.653226 -v -0.041750 -0.144330 0.164800 -vn 0.655722 -0.378581 -0.653227 -v -0.039920 -0.142500 0.164800 -vn -0.552289 -0.318863 -0.770262 -v -0.057301 -0.134875 0.164800 -vn -0.318862 -0.552289 -0.770263 -v -0.058125 -0.134051 0.164800 -vn 0.000000 -0.637730 -0.770260 -v -0.059250 -0.133750 0.164800 -vn 0.637728 0.000001 -0.770262 -v -0.061500 -0.136000 0.164800 -vn 0.552288 0.318865 -0.770262 -v -0.061199 -0.137125 0.164800 -vn -0.378581 -0.655722 -0.653227 -v -0.066750 -0.144330 0.164800 -vn 0.318862 0.552289 -0.770263 -v -0.060375 -0.137949 0.164800 -vn -0.095839 -0.727973 -0.678875 -v -0.064250 -0.145000 0.164800 -vn -0.000000 0.637730 -0.770260 -v -0.059250 -0.138250 0.164800 -vn -0.318862 0.552289 -0.770263 -v -0.058125 -0.137949 0.164800 -vn 0.318864 -0.552288 -0.770262 -v -0.034250 -0.116340 0.164800 -vn 0.552289 -0.318864 -0.770262 -v -0.037910 -0.120000 0.164800 -vn 0.669353 -0.088122 -0.737700 -v -0.039250 -0.125000 0.164800 -vn 0.088122 -0.669353 -0.737700 -v -0.029250 -0.115000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 -0.108310 0.164800 -vn 0.000000 -0.707107 -0.707107 -v -0.023049 -0.115000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 -0.108310 0.164800 -vn -0.088122 -0.669353 -0.737700 -v 0.001750 -0.115000 0.164800 -vn -0.318864 -0.552289 -0.770262 -v 0.006750 -0.116340 0.164800 -vn -0.669353 -0.088122 -0.737700 -v 0.011750 -0.125000 0.164800 -vn -0.552288 -0.318864 -0.770262 -v 0.010410 -0.120000 0.164800 -vn -0.378581 -0.655722 -0.653226 -v 0.014250 -0.144330 0.164800 -vn -0.655722 -0.378581 -0.653227 -v 0.012420 -0.142500 0.164800 -vn -0.727973 -0.095840 -0.678874 -v 0.011750 -0.140000 0.164800 -vn -0.707107 -0.000000 -0.707107 -v 0.011750 -0.125125 0.164800 -vn -0.552289 -0.318864 -0.770262 -v 0.030699 -0.113875 0.164800 -vn 0.655722 0.378582 -0.653227 -v 0.037410 -0.104773 0.164800 -vn -0.318864 -0.552288 -0.770262 -v 0.029875 -0.113051 0.164800 -vn 0.318864 0.552289 -0.770262 -v 0.027625 -0.116949 0.164800 -vn -0.000000 0.637728 -0.770262 -v 0.028750 -0.117250 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 -0.108310 0.164800 -vn 0.000000 -0.637728 -0.770262 -v 0.028750 -0.112750 0.164800 -vn 0.318864 -0.552289 -0.770262 -v 0.027625 -0.113051 0.164800 -vn -0.318864 0.552288 -0.770262 -v 0.029875 -0.116949 0.164800 -vn -0.552289 0.318864 -0.770262 -v 0.030699 -0.116125 0.164800 -vn -0.637728 -0.000000 -0.770262 -v 0.031000 -0.115000 0.164800 -vn 0.552289 -0.318864 -0.770262 -v 0.026801 -0.113875 0.164800 -vn 0.637728 0.000000 -0.770262 -v 0.026500 -0.115000 0.164800 -vn 0.552289 0.318864 -0.770262 -v 0.026801 -0.116125 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 -0.103420 0.164800 -vn 0.446985 0.582523 -0.678875 -v 0.033750 -0.101113 0.164800 -vn 0.639172 -0.490454 -0.592381 -v 0.008750 -0.065132 0.164800 -vn 0.707107 0.000000 -0.707107 -v 0.008750 -0.049166 0.164800 -vn 0.707107 0.000000 -0.707107 -v 0.008750 0.000000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.066000 0.164800 -vn 0.552289 0.318864 -0.770262 -v 0.000090 0.070132 0.164800 -vn 0.410992 -0.535615 -0.737700 -v 0.003750 0.083793 0.164800 -vn 0.552289 -0.318864 -0.770262 -v 0.000090 0.080132 0.164800 -vn 0.637728 -0.000000 -0.770262 -v -0.001250 0.075132 0.164800 -vn 0.353554 -0.612372 -0.707107 -v 0.026125 0.096711 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 0.098020 0.164800 -vn 0.353554 -0.612372 -0.707107 -v 0.028392 0.098020 0.164800 -vn 0.000000 0.000000 -1.000000 -v 0.026125 0.103420 0.164800 -vn 0.446986 -0.582523 -0.678874 -v 0.033750 0.101113 0.164800 -vn 0.318864 0.552289 -0.770262 -v 0.027625 0.113051 0.164800 -vn -0.000000 0.637728 -0.770262 -v 0.028750 0.112750 0.164800 -vn -0.318864 0.552288 -0.770262 -v 0.029875 0.113051 0.164800 -vn 0.655722 -0.378582 -0.653227 -v 0.037410 0.104773 0.164800 -vn -0.552289 0.318864 -0.770262 -v 0.030699 0.113875 0.164800 -vn -0.637728 -0.000000 -0.770262 -v 0.031000 0.115000 0.164800 -vn -0.552289 -0.318863 -0.770262 -v 0.030699 0.116125 0.164800 -vn -0.318864 -0.552288 -0.770262 -v 0.029875 0.116949 0.164800 -vn 0.000000 -0.637728 -0.770262 -v 0.028750 0.117250 0.164800 -vn 0.318864 -0.552289 -0.770262 -v 0.027625 0.116949 0.164800 -vn 0.552289 -0.318864 -0.770262 -v 0.026801 0.116125 0.164800 -vn 0.637728 0.000000 -0.770262 -v 0.026500 0.115000 0.164800 -vn 0.552289 0.318864 -0.770262 -v 0.026801 0.113875 0.164800 -vn -0.727973 0.095840 -0.678874 -v 0.011750 0.140000 0.164800 -vn -0.669353 0.088122 -0.737700 -v 0.011750 0.125000 0.164800 -vn -0.707107 -0.000000 -0.707107 -v 0.011750 0.125125 0.164800 -vn -0.707107 -0.000000 -0.707107 -v 0.011750 0.138625 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 0.103420 0.164800 -vn 0.000000 0.707107 -0.707107 -v -0.019900 0.115000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 0.103420 0.164800 -vn 0.000000 0.707107 -0.707107 -v -0.023049 0.115000 0.164800 -vn 0.707107 0.000000 -0.707106 -v -0.039250 0.125125 0.164800 -vn 0.669353 0.088122 -0.737700 -v -0.039250 0.125000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 0.103420 0.164800 -vn 0.552288 0.318864 -0.770262 -v -0.037910 0.120000 0.164800 -vn 0.318864 0.552289 -0.770262 -v -0.034250 0.116340 0.164800 -vn 0.088122 0.669353 -0.737700 -v -0.029250 0.115000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 0.125125 0.164800 -vn 0.318862 0.552289 -0.770263 -v -0.060375 0.134051 0.164800 -vn -0.000000 0.637730 -0.770260 -v -0.059250 0.133750 0.164800 -vn -0.318862 0.552289 -0.770263 -v -0.058125 0.134051 0.164800 -vn -0.552289 0.318863 -0.770262 -v -0.057301 0.134875 0.164800 -vn -0.637728 -0.000001 -0.770262 -v -0.057000 0.136000 0.164800 -vn -0.552288 -0.318865 -0.770262 -v -0.057301 0.137125 0.164800 -vn -0.318862 -0.552289 -0.770263 -v -0.058125 0.137949 0.164800 -vn 0.000000 -0.637730 -0.770260 -v -0.059250 0.138250 0.164800 -vn 0.318862 -0.552289 -0.770263 -v -0.060375 0.137949 0.164800 -vn 0.552288 -0.318865 -0.770262 -v -0.061199 0.137125 0.164800 -vn 0.637728 -0.000001 -0.770262 -v -0.061500 0.136000 0.164800 -vn 0.552289 0.318863 -0.770262 -v -0.061199 0.134875 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.069250 0.138625 0.164800 -vn -0.727973 0.095840 -0.678874 -v -0.069250 0.140000 0.164800 -vn 0.378581 0.655722 -0.653226 -v -0.041750 0.144330 0.164800 -vn 0.655722 0.378581 -0.653227 -v -0.039920 0.142500 0.164800 -vn 0.095839 0.727973 -0.678875 -v -0.044250 0.145000 0.164800 -vn -0.095839 0.727973 -0.678875 -v -0.064250 0.145000 0.164800 -vn -0.378581 0.655722 -0.653226 -v -0.066750 0.144330 0.164800 -vn -0.655722 0.378581 -0.653227 -v -0.068580 0.142500 0.164800 -vn -0.669353 0.088121 -0.737700 -v -0.069250 0.126000 0.164800 -vn -0.552287 0.318864 -0.770263 -v -0.069518 0.125000 0.164800 -vn -0.318865 0.552290 -0.770261 -v -0.070250 0.124268 0.164800 -vn -0.000000 0.707107 -0.707107 -v -0.076625 0.124000 0.164800 -vn -0.637728 -0.000000 -0.770262 -v -0.078000 0.115000 0.164800 -vn -0.552289 -0.318864 -0.770262 -v -0.078301 0.116125 0.164800 -vn -0.318864 0.552289 -0.770262 -v -0.079125 0.113051 0.164800 -vn -0.552289 0.318864 -0.770262 -v -0.078301 0.113875 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.103420 0.164800 -vn -0.088123 0.669352 -0.737701 -v -0.071250 0.124000 0.164800 -vn -0.318864 -0.552289 -0.770262 -v -0.079125 0.116949 0.164800 -vn 0.000000 -0.637728 -0.770262 -v -0.080250 0.117250 0.164800 -vn -0.095840 0.727973 -0.678875 -v -0.085250 0.124000 0.164800 -vn 0.318864 -0.552289 -0.770262 -v -0.081375 0.116949 0.164800 -vn 0.552288 -0.318864 -0.770262 -v -0.082199 0.116125 0.164800 -vn 0.637728 0.000000 -0.770262 -v -0.082500 0.115000 0.164800 -vn 0.552289 0.318864 -0.770262 -v -0.082199 0.113875 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 0.103420 0.164800 -vn 0.318864 0.552289 -0.770262 -v -0.081375 0.113051 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.080250 0.112750 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 0.103420 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 0.089244 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 0.089244 0.164800 -vn -0.646608 -0.477776 -0.594666 -v -0.090250 0.087423 0.164800 -vn -0.271527 -0.623296 -0.733332 -v -0.088113 0.086766 0.164800 -vn -0.393680 -0.562235 -0.727260 -v -0.079250 0.081649 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.089244 0.164800 -vn -0.508111 -0.426354 -0.748361 -v -0.078718 0.081203 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.078250 0.066000 0.164800 -vn -0.683749 -0.059822 -0.727261 -v -0.078250 0.079917 0.164800 -vn -0.623292 -0.226860 -0.748359 -v -0.078371 0.080601 0.164800 -vn -0.378581 -0.655722 -0.653227 -v -0.077250 0.041580 0.164800 -vn -0.655723 -0.378580 -0.653226 -v -0.077982 0.042312 0.164800 -vn -0.095839 -0.727973 -0.678874 -v -0.076250 0.041312 0.164800 -vn 0.000000 -0.707108 -0.707105 -v -0.067375 0.041312 0.164800 -vn -0.637728 -0.000000 -0.770262 -v -0.025799 0.045000 0.164800 -vn -0.552288 -0.318864 -0.770262 -v -0.026101 0.046125 0.164800 -vn -0.318864 -0.552289 -0.770262 -v -0.026924 0.046949 0.164800 -vn 0.000000 -0.637728 -0.770262 -v -0.028049 0.047250 0.164800 -vn 0.318864 -0.552288 -0.770262 -v -0.029174 0.046949 0.164800 -vn 0.552289 -0.318864 -0.770262 -v -0.029998 0.046125 0.164800 -vn 0.637728 -0.000000 -0.770262 -v -0.030299 0.045000 0.164800 -vn 0.552289 0.318864 -0.770262 -v -0.029998 0.043875 0.164800 -vn 0.318864 0.552288 -0.770262 -v -0.029174 0.043051 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.028049 0.042750 0.164800 -vn 0.000000 -0.707107 -0.707107 -v -0.023049 0.041312 0.164800 -vn -0.318864 0.552288 -0.770262 -v -0.026924 0.043051 0.164800 -vn -0.552289 0.318864 -0.770262 -v -0.026101 0.043875 0.164800 -vn 0.552289 -0.318863 -0.770262 -v -0.019998 0.046437 0.164800 -vn 0.637728 -0.000000 -0.770261 -v -0.020299 0.045312 0.164800 -vn 0.552289 0.318863 -0.770262 -v -0.019998 0.044187 0.164800 -vn 0.318864 0.552289 -0.770262 -v -0.019174 0.043364 0.164800 -vn 0.318864 -0.552289 -0.770262 -v -0.019174 0.047261 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 -0.103420 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 -0.103420 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 -0.103420 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.103420 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 -0.103420 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 -0.103420 0.164800 -vn 0.637728 0.000000 -0.770262 -v -0.019500 -0.100720 0.164800 -vn 0.552287 0.318865 -0.770262 -v -0.019199 -0.101845 0.164800 -vn 0.318863 0.552290 -0.770261 -v -0.018375 -0.102669 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.017250 -0.102970 0.164800 -vn -0.318863 0.552290 -0.770261 -v -0.016125 -0.102669 0.164800 -vn -0.552287 0.318865 -0.770262 -v -0.015301 -0.101845 0.164800 -vn -0.637728 -0.000000 -0.770262 -v -0.015000 -0.100720 0.164800 -vn -0.552288 -0.318864 -0.770262 -v -0.015301 -0.099595 0.164800 -vn -0.318864 -0.552289 -0.770262 -v -0.016125 -0.098771 0.164800 -vn -0.000000 -0.637728 -0.770262 -v -0.017250 -0.098470 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 -0.098020 0.164800 -vn 0.318864 -0.552289 -0.770262 -v -0.018375 -0.098771 0.164800 -vn 0.552289 -0.318864 -0.770262 -v -0.019199 -0.099595 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 -0.098020 0.164800 -vn 0.318865 0.552288 -0.770261 -v -0.074750 -0.080783 0.164800 -vn -0.000001 0.637726 -0.770263 -v -0.074250 -0.080917 0.164800 -vn -0.675742 -0.076134 -0.733196 -v -0.073250 -0.075417 0.164800 -vn -0.584725 -0.281589 -0.760792 -v -0.073349 -0.074983 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 -0.066000 0.164800 -vn -0.404643 -0.507412 -0.760787 -v -0.073627 -0.074635 0.164800 -vn -0.144416 -0.632728 -0.760789 -v -0.074027 -0.074442 0.164800 -vn 0.144416 -0.632728 -0.760789 -v -0.074473 -0.074442 0.164800 -vn 0.404645 -0.507408 -0.760788 -v -0.074873 -0.074635 0.164800 -vn 0.584729 -0.281592 -0.760788 -v -0.075151 -0.074983 0.164800 -vn -0.318864 0.552291 -0.770260 -v -0.073750 -0.080783 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.019900 -0.066000 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 -0.066000 0.164800 -vn 0.675739 -0.076139 -0.733198 -v -0.075250 -0.075417 0.164800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 -0.079917 0.164800 -vn 0.552288 0.318865 -0.770261 -v -0.075116 -0.080417 0.164800 -vn -0.675742 -0.076134 -0.733196 -v -0.073250 -0.052083 0.164800 -vn -0.584727 -0.281588 -0.760791 -v -0.073349 -0.051649 0.164800 -vn 0.318865 0.552288 -0.770261 -v -0.074750 -0.057449 0.164800 -vn -0.000001 0.637726 -0.770263 -v -0.074250 -0.057583 0.164800 -vn 0.404646 -0.507407 -0.760789 -v -0.074873 -0.051301 0.164800 -vn 0.584730 -0.281591 -0.760787 -v -0.075151 -0.051649 0.164800 -vn -0.318864 0.552291 -0.770260 -v -0.073750 -0.057449 0.164800 -vn -0.552286 0.318863 -0.770264 -v -0.073384 -0.057083 0.164800 -vn -0.669354 0.088119 -0.737699 -v -0.073250 -0.056583 0.164800 -vn -0.404644 -0.507411 -0.760787 -v -0.073627 -0.051301 0.164800 -vn -0.144416 -0.632728 -0.760789 -v -0.074027 -0.051108 0.164800 -vn 0.144416 -0.632728 -0.760789 -v -0.074473 -0.051108 0.164800 -vn 0.675739 -0.076139 -0.733198 -v -0.075250 -0.052083 0.164800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 -0.056583 0.164800 -vn 0.552288 0.318866 -0.770261 -v -0.075116 -0.057083 0.164800 -vn -0.669354 -0.088119 -0.737699 -v -0.073250 0.056583 0.164800 -vn -0.552286 -0.318863 -0.770264 -v -0.073384 0.057083 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 0.066000 0.164800 -vn -0.000001 -0.637726 -0.770263 -v -0.074250 0.057583 0.164800 -vn 0.318865 -0.552288 -0.770261 -v -0.074750 0.057449 0.164800 -vn 0.552288 0.318865 -0.770261 -v -0.075116 0.051583 0.164800 -vn 0.318862 0.552289 -0.770262 -v -0.074750 0.051217 0.164800 -vn -0.000001 0.637729 -0.770261 -v -0.074250 0.051083 0.164800 -vn -0.318862 0.552292 -0.770261 -v -0.073750 0.051217 0.164800 -vn -0.318864 -0.552291 -0.770260 -v -0.073750 0.057449 0.164800 -vn 0.552288 -0.318866 -0.770261 -v -0.075116 0.057083 0.164800 -vn 0.669352 -0.088123 -0.737701 -v -0.075250 0.056583 0.164800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 0.052083 0.164800 -vn 0.318865 -0.552288 -0.770261 -v -0.074750 0.080783 0.164800 -vn 0.552288 -0.318865 -0.770261 -v -0.075116 0.080417 0.164800 -vn -0.669355 -0.088118 -0.737699 -v -0.073250 0.079917 0.164800 -vn -0.552286 -0.318862 -0.770265 -v -0.073384 0.080417 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 0.089244 0.164800 -vn -0.318864 -0.552291 -0.770260 -v -0.073750 0.080783 0.164800 -vn -0.000001 -0.637726 -0.770263 -v -0.074250 0.080917 0.164800 -vn 0.669352 -0.088123 -0.737701 -v -0.075250 0.079917 0.164800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 0.075417 0.164800 -vn 0.552288 0.318865 -0.770261 -v -0.075116 0.074917 0.164800 -vn 0.318860 0.552289 -0.770263 -v -0.074750 0.074551 0.164800 -vn -0.000001 0.637731 -0.770259 -v -0.074250 0.074417 0.164800 -vn -0.318859 0.552292 -0.770261 -v -0.073750 0.074551 0.164800 -vn -0.552286 0.318862 -0.770265 -v -0.073384 0.074917 0.164800 -vn -0.669355 0.088118 -0.737699 -v -0.073250 0.075417 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.023049 0.098020 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.067375 0.098020 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.098020 0.164800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 0.098020 0.164800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 0.098020 0.164800 -vn -0.000000 0.637728 -0.770262 -v -0.017250 0.098470 0.164800 -vn -0.318864 0.552289 -0.770262 -v -0.016125 0.098771 0.164800 -vn 0.552289 0.318864 -0.770262 -v -0.019199 0.099595 0.164800 -vn 0.318864 0.552289 -0.770262 -v -0.018375 0.098771 0.164800 -vn -0.552287 -0.318865 -0.770262 -v -0.015301 0.101845 0.164800 -vn -0.637728 -0.000000 -0.770262 -v -0.015000 0.100720 0.164800 -vn -0.552289 0.318864 -0.770262 -v -0.015301 0.099595 0.164800 -vn 0.552287 -0.318865 -0.770262 -v -0.019199 0.101845 0.164800 -vn 0.637728 0.000000 -0.770262 -v -0.019500 0.100720 0.164800 -vn -0.318863 -0.552290 -0.770261 -v -0.016125 0.102669 0.164800 -vn -0.000000 -0.637728 -0.770262 -v -0.017250 0.102970 0.164800 -vn 0.318863 -0.552290 -0.770261 -v -0.018375 0.102669 0.164800 -vn 0.637728 -0.000001 -0.770262 -v 0.025750 0.136000 0.164800 -vn 0.552288 0.318865 0.770261 -v -0.075116 0.074917 0.166800 -vn 0.669352 0.088123 0.737701 -v -0.075250 0.075417 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.066000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 0.103420 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 0.103420 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 0.098020 0.166800 -vn 0.552289 0.318864 0.770262 -v -0.029998 -0.046125 0.166800 -vn 0.637728 0.000000 0.770262 -v -0.030299 -0.045000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 -0.049166 0.166800 -vn -0.646608 0.477776 0.594666 -v -0.090250 -0.087423 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.090250 -0.098020 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.086375 -0.098020 0.166800 -vn 0.318864 -0.552288 0.770262 -v 0.003750 -0.066472 0.166800 -vn 0.639172 -0.490453 0.592381 -v 0.008750 -0.065132 0.166800 -vn 0.707107 0.000000 0.707107 -v 0.008750 -0.049166 0.166800 -vn -0.088123 0.669352 0.737701 -v -0.071250 0.124000 0.166800 -vn -0.000000 0.707107 0.707107 -v -0.076625 0.124000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.103420 0.166800 -vn 0.000000 -0.707108 0.707106 -v -0.067375 0.041312 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 0.049323 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.049323 0.166800 -vn 0.552289 0.318864 0.770262 -v -0.029998 0.043875 0.166800 -vn 0.637728 -0.000000 0.770262 -v -0.030299 0.045000 0.166800 -vn 0.318864 0.552289 0.770261 -v 0.027250 0.133402 0.166800 -vn 0.552288 0.318864 0.770262 -v 0.026152 0.134500 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 0.125125 0.166800 -vn 0.318864 -0.552289 0.770261 -v 0.027250 0.138598 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 0.138625 0.166800 -vn 0.552287 -0.318865 0.770262 -v 0.026152 0.137500 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 0.138625 0.166800 -vn -0.318864 0.552290 0.770261 -v 0.030250 -0.138598 0.166800 -vn -0.000000 0.637727 0.770263 -v 0.028750 -0.139000 0.166800 -vn 0.000000 -0.707107 0.707107 -v 0.026125 -0.145000 0.166800 -vn 0.318864 -0.552289 0.770261 -v 0.027250 -0.133402 0.166800 -vn -0.000000 -0.637727 0.770263 -v 0.028750 -0.133000 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 -0.125125 0.166800 -vn -0.318864 -0.552290 0.770261 -v 0.030250 -0.133402 0.166800 -vn -0.552287 -0.318865 0.770263 -v 0.031348 -0.134500 0.166800 -vn -0.637728 0.000001 0.770262 -v 0.031750 -0.136000 0.166800 -vn 0.655722 -0.378581 0.653227 -v 0.038080 -0.142500 0.166800 -vn -0.552287 0.318866 0.770262 -v 0.031348 -0.137500 0.166800 -vn 0.378581 -0.655722 0.653226 -v 0.036250 -0.144330 0.166800 -vn 0.095838 -0.727973 0.678875 -v 0.033750 -0.145000 0.166800 -vn 0.318864 0.552289 0.770261 -v 0.027250 -0.138598 0.166800 -vn 0.552287 0.318865 0.770262 -v 0.026152 -0.137500 0.166800 -vn -0.095839 -0.727973 0.678875 -v 0.016750 -0.145000 0.166800 -vn 0.637728 0.000001 0.770262 -v 0.025750 -0.136000 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 -0.125125 0.166800 -vn 0.552288 -0.318864 0.770262 -v 0.026152 -0.134500 0.166800 -vn -0.552287 -0.318865 0.770262 -v 0.031348 0.137500 0.166800 -vn -0.637728 -0.000001 0.770262 -v 0.031750 0.136000 0.166800 -vn -0.552288 0.318864 0.770262 -v 0.031348 0.134500 0.166800 -vn -0.318864 0.552289 0.770261 -v 0.030250 0.133402 0.166800 -vn -0.000000 0.637727 0.770263 -v 0.028750 0.133000 0.166800 -vn 0.378581 0.655722 0.653226 -v 0.036250 0.144330 0.166800 -vn 0.095838 0.727973 0.678875 -v 0.033750 0.145000 0.166800 -vn -0.000000 -0.637727 0.770263 -v 0.028750 0.139000 0.166800 -vn 0.000000 0.707107 0.707107 -v 0.026125 0.145000 0.166800 -vn -0.318864 -0.552289 0.770261 -v 0.030250 0.138598 0.166800 -vn 0.655722 0.378581 0.653227 -v 0.038080 0.142500 0.166800 -vn -0.552289 -0.318864 0.770261 -v 0.006478 0.102295 0.166800 -vn -0.637728 -0.000000 0.770262 -v 0.006900 0.100720 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 0.103420 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 0.098020 0.166800 -vn -0.552289 0.318864 0.770262 -v 0.006478 0.099145 0.166800 -vn -0.318863 0.552288 0.770262 -v 0.005325 0.097992 0.166800 -vn -0.318863 -0.552288 0.770262 -v 0.005325 0.103448 0.166800 -vn -0.318864 0.552289 0.770262 -v 0.006750 0.116340 0.166800 -vn -0.088122 0.669353 0.737700 -v 0.001750 0.115000 0.166800 -vn 0.552289 0.318863 0.770262 -v 0.001022 0.099145 0.166800 -vn 0.637728 -0.000000 0.770262 -v 0.000600 0.100720 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.098020 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.103420 0.166800 -vn 0.552289 -0.318864 0.770261 -v 0.001022 0.102295 0.166800 -vn 0.318864 -0.552288 0.770263 -v 0.002175 0.103448 0.166800 -vn 0.000000 0.637729 0.770261 -v 0.003750 0.097570 0.166800 -vn 0.318864 0.552288 0.770263 -v 0.002175 0.097992 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.089244 0.166800 -vn -0.318863 -0.552288 0.770262 -v 0.005325 -0.097992 0.166800 -vn -0.552289 -0.318864 0.770262 -v 0.006478 -0.099145 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 -0.098020 0.166800 -vn -0.637728 0.000000 0.770262 -v 0.006900 -0.100720 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 -0.103420 0.166800 -vn 0.410992 0.535615 0.737700 -v 0.003750 -0.083793 0.166800 -vn 0.552289 0.318864 0.770262 -v 0.000090 -0.080132 0.166800 -vn 0.318864 -0.552288 0.770263 -v 0.002175 -0.097992 0.166800 -vn 0.637728 0.000000 0.770262 -v -0.001250 -0.075132 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.066000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.098020 0.166800 -vn 0.318864 0.552288 0.770263 -v 0.002175 -0.103448 0.166800 -vn 0.552289 0.318864 0.770261 -v 0.001022 -0.102295 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.103420 0.166800 -vn 0.637728 0.000000 0.770262 -v 0.000600 -0.100720 0.166800 -vn 0.552289 -0.318863 0.770262 -v 0.001022 -0.099145 0.166800 -vn -0.552289 0.318864 0.770261 -v 0.006478 -0.102295 0.166800 -vn -0.318863 0.552288 0.770262 -v 0.005325 -0.103448 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 -0.108310 0.166800 -vn -0.000000 0.637729 0.770261 -v 0.003750 -0.103870 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.108310 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 0.049323 0.166800 -vn 0.552289 -0.318863 0.770262 -v -0.019998 0.046437 0.166800 -vn 0.318864 -0.552289 0.770262 -v -0.019174 0.047261 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.018049 0.047562 0.166800 -vn -0.318864 -0.552289 0.770262 -v -0.016924 0.047261 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.049323 0.166800 -vn -0.552289 -0.318864 0.770262 -v -0.016101 0.046437 0.166800 -vn -0.637728 0.000000 0.770262 -v -0.015799 0.045312 0.166800 -vn -0.552289 0.318864 0.770262 -v -0.016101 0.044187 0.166800 -vn 0.000000 0.637728 0.770262 -v -0.018049 0.043062 0.166800 -vn 0.000000 -0.707107 0.707107 -v -0.019900 0.041312 0.166800 -vn -0.318864 0.552289 0.770262 -v -0.016924 0.043364 0.166800 -vn -0.069844 -0.678920 0.730882 -v -0.012049 0.041312 0.166800 -vn -0.260984 -0.600379 0.755932 -v -0.011152 0.041126 0.166800 -vn -0.478695 -0.446562 0.755932 -v -0.010404 0.040597 0.166800 -vn -0.617038 -0.218703 0.755932 -v -0.009929 0.039814 0.166800 -vn -0.673884 -0.000000 0.738837 -v -0.009805 0.038906 0.166800 -vn -0.617038 0.218703 0.755932 -v -0.009929 0.037998 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.000000 0.166800 -vn -0.478695 0.446562 0.755932 -v -0.010404 0.037215 0.166800 -vn -0.260984 0.600379 0.755931 -v -0.011152 0.036687 0.166800 -vn 0.318864 0.552289 0.770262 -v -0.019174 0.043364 0.166800 -vn 0.552289 0.318863 0.770262 -v -0.019998 0.044187 0.166800 -vn 0.000000 -0.707107 0.707107 -v -0.023049 0.041312 0.166800 -vn 0.637728 0.000000 0.770261 -v -0.020299 0.045312 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 0.049323 0.166800 -vn 0.552289 -0.318864 0.770262 -v -0.029998 0.046125 0.166800 -vn 0.318864 -0.552288 0.770262 -v -0.029174 0.046949 0.166800 -vn -0.552289 0.318864 0.770262 -v -0.026101 0.043875 0.166800 -vn -0.318864 0.552288 0.770262 -v -0.026924 0.043051 0.166800 -vn 0.000000 0.637728 0.770262 -v -0.028049 0.042750 0.166800 -vn 0.318864 0.552288 0.770262 -v -0.029174 0.043051 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.028049 0.047250 0.166800 -vn -0.318864 -0.552289 0.770262 -v -0.026924 0.046949 0.166800 -vn -0.552288 -0.318864 0.770262 -v -0.026101 0.046125 0.166800 -vn -0.637728 -0.000000 0.770262 -v -0.025799 0.045000 0.166800 -vn -0.655723 -0.378580 0.653226 -v -0.077982 0.042312 0.166800 -vn -0.378581 -0.655722 0.653227 -v -0.077250 0.041580 0.166800 -vn -0.727973 -0.095838 0.678875 -v -0.078250 0.043312 0.166800 -vn -0.095839 -0.727973 0.678874 -v -0.076250 0.041312 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.078250 0.049323 0.166800 -vn -0.683749 -0.059822 0.727261 -v -0.078250 0.079917 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.078250 0.066000 0.166800 -vn -0.508111 -0.426355 0.748361 -v -0.078718 0.081203 0.166800 -vn -0.623292 -0.226860 0.748359 -v -0.078371 0.080601 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.089244 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.090250 0.089244 0.166800 -vn -0.646608 -0.477776 0.594666 -v -0.090250 0.087423 0.166800 -vn -0.271527 -0.623296 0.733332 -v -0.088113 0.086766 0.166800 -vn -0.378581 0.655722 0.653227 -v -0.087750 0.123330 0.166800 -vn -0.655722 0.378581 0.653227 -v -0.089580 0.121500 0.166800 -vn -0.727973 0.095840 0.678874 -v -0.090250 0.119000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.086375 0.103420 0.166800 -vn -0.318864 0.552289 0.770262 -v -0.079125 0.113051 0.166800 -vn 0.000000 0.637728 0.770262 -v -0.080250 0.112750 0.166800 -vn 0.637728 -0.000000 0.770262 -v -0.082500 0.115000 0.166800 -vn 0.552289 -0.318864 0.770262 -v -0.082199 0.116125 0.166800 -vn -0.095840 0.727973 0.678874 -v -0.085250 0.124000 0.166800 -vn 0.318864 -0.552289 0.770262 -v -0.081375 0.116949 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.080250 0.117250 0.166800 -vn -0.318864 -0.552289 0.770262 -v -0.079125 0.116949 0.166800 -vn 0.318864 0.552289 0.770262 -v -0.081375 0.113051 0.166800 -vn 0.552289 0.318864 0.770262 -v -0.082199 0.113875 0.166800 -vn -0.552289 -0.318864 0.770262 -v -0.078301 0.116125 0.166800 -vn -0.637728 0.000000 0.770262 -v -0.078000 0.115000 0.166800 -vn -0.552289 0.318864 0.770262 -v -0.078301 0.113875 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 0.125125 0.166800 -vn -0.552287 0.318864 0.770263 -v -0.069518 0.125000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 0.103420 0.166800 -vn -0.318865 0.552290 0.770261 -v -0.070250 0.124268 0.166800 -vn -0.655722 0.378581 0.653227 -v -0.068580 0.142500 0.166800 -vn -0.727973 0.095840 0.678874 -v -0.069250 0.140000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 0.138625 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.069250 0.138625 0.166800 -vn -0.669353 0.088121 0.737700 -v -0.069250 0.126000 0.166800 -vn 0.727973 0.095839 0.678874 -v -0.039250 0.140000 0.166800 -vn 0.655722 0.378581 0.653227 -v -0.039920 0.142500 0.166800 -vn 0.378581 0.655722 0.653226 -v -0.041750 0.144330 0.166800 -vn 0.095839 0.727973 0.678875 -v -0.044250 0.145000 0.166800 -vn -0.095839 0.727973 0.678875 -v -0.064250 0.145000 0.166800 -vn -0.378581 0.655722 0.653227 -v -0.066750 0.144330 0.166800 -vn -0.000000 -0.637730 0.770260 -v -0.059250 0.138250 0.166800 -vn 0.318862 -0.552289 0.770263 -v -0.060375 0.137949 0.166800 -vn 0.552288 -0.318865 0.770262 -v -0.061199 0.137125 0.166800 -vn 0.707107 0.000000 0.707107 -v -0.039250 0.125125 0.166800 -vn -0.318862 0.552289 0.770263 -v -0.058125 0.134051 0.166800 -vn 0.000000 0.637730 0.770260 -v -0.059250 0.133750 0.166800 -vn 0.318862 0.552289 0.770263 -v -0.060375 0.134051 0.166800 -vn 0.552289 0.318863 0.770262 -v -0.061199 0.134875 0.166800 -vn 0.637728 -0.000001 0.770262 -v -0.061500 0.136000 0.166800 -vn 0.707106 0.000000 0.707107 -v -0.039250 0.138625 0.166800 -vn -0.318862 -0.552289 0.770263 -v -0.058125 0.137949 0.166800 -vn -0.552288 -0.318865 0.770262 -v -0.057301 0.137125 0.166800 -vn -0.637728 -0.000001 0.770262 -v -0.057000 0.136000 0.166800 -vn -0.552289 0.318863 0.770262 -v -0.057301 0.134875 0.166800 -vn 0.318864 0.552289 0.770262 -v -0.034250 0.116340 0.166800 -vn 0.552288 0.318864 0.770262 -v -0.037910 0.120000 0.166800 -vn 0.000000 0.707107 0.707107 -v -0.023049 0.115000 0.166800 -vn 0.088122 0.669353 0.737700 -v -0.029250 0.115000 0.166800 -vn 0.669353 0.088122 0.737700 -v -0.039250 0.125000 0.166800 -vn 0.000000 0.707107 0.707107 -v -0.019900 0.115000 0.166800 -vn 0.000000 0.707107 0.707107 -v -0.007200 0.115000 0.166800 -vn -0.707107 -0.000000 0.707107 -v 0.011750 0.125125 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.016325 0.125125 0.166800 -vn -0.669353 0.088122 0.737700 -v 0.011750 0.125000 0.166800 -vn -0.552289 0.318864 0.770262 -v 0.010410 0.120000 0.166800 -vn -0.655722 0.378581 0.653227 -v 0.012420 0.142500 0.166800 -vn -0.727973 0.095840 0.678874 -v 0.011750 0.140000 0.166800 -vn -0.707107 -0.000000 0.707107 -v 0.011750 0.138625 0.166800 -vn -0.095839 0.727973 0.678875 -v 0.016750 0.145000 0.166800 -vn -0.378581 0.655722 0.653226 -v 0.014250 0.144330 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 0.103420 0.166800 -vn 0.000000 0.637728 0.770262 -v 0.028750 0.112750 0.166800 -vn 0.318864 0.552289 0.770262 -v 0.027625 0.113051 0.166800 -vn 0.552289 0.318864 0.770262 -v 0.026801 0.113875 0.166800 -vn 0.637728 -0.000000 0.770262 -v 0.026500 0.115000 0.166800 -vn 0.552289 -0.318864 0.770262 -v 0.026801 0.116125 0.166800 -vn -0.552289 -0.318864 0.770262 -v 0.030699 0.116125 0.166800 -vn 0.318864 -0.552289 0.770262 -v 0.027625 0.116949 0.166800 -vn -0.000000 -0.637728 0.770262 -v 0.028750 0.117250 0.166800 -vn -0.318864 -0.552288 0.770262 -v 0.029875 0.116949 0.166800 -vn -0.637728 0.000000 0.770262 -v 0.031000 0.115000 0.166800 -vn -0.552289 0.318863 0.770262 -v 0.030699 0.113875 0.166800 -vn 0.655722 -0.378582 0.653227 -v 0.037410 0.104773 0.166800 -vn -0.318864 0.552288 0.770262 -v 0.029875 0.113051 0.166800 -vn 0.446986 -0.582523 0.678875 -v 0.033750 0.101113 0.166800 -vn 0.353554 -0.612372 0.707107 -v 0.026125 0.096711 0.166800 -vn 0.353554 -0.612372 0.707107 -v 0.028392 0.098020 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 0.098020 0.166800 -vn 0.353554 -0.612373 0.707107 -v 0.013191 0.089244 0.166800 -vn 0.353553 -0.612372 0.707107 -v 0.016325 0.091053 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.066000 0.166800 -vn 0.552289 0.318864 0.770262 -v 0.000090 0.070132 0.166800 -vn 0.637728 -0.000000 0.770262 -v -0.001250 0.075132 0.166800 -vn 0.410992 -0.535615 0.737700 -v 0.003750 0.083793 0.166800 -vn 0.552289 -0.318864 0.770262 -v 0.000090 0.080132 0.166800 -vn 0.707107 0.000000 0.707107 -v 0.008750 0.049323 0.166800 -vn 0.639172 0.490453 0.592381 -v 0.008750 0.065132 0.166800 -vn 0.318864 0.552288 0.770262 -v 0.003750 0.066472 0.166800 -vn 0.707107 0.000000 0.707107 -v 0.008750 0.000000 0.166800 -vn 0.552289 -0.318864 0.770262 -v 0.000090 -0.070132 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.049166 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 -0.098020 0.166800 -vn 0.353554 0.612372 0.707107 -v 0.026125 -0.096711 0.166800 -vn 0.353553 0.612373 0.707107 -v 0.016325 -0.091053 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 -0.108310 0.166800 -vn 0.655722 0.378582 0.653227 -v 0.037410 -0.104773 0.166800 -vn 0.000000 0.000000 1.000000 -v 0.026125 -0.103420 0.166800 -vn 0.446986 0.582523 0.678874 -v 0.033750 -0.101113 0.166800 -vn 0.353554 0.612372 0.707107 -v 0.028392 -0.098020 0.166800 -vn 0.318864 0.552289 0.770262 -v 0.027625 -0.116949 0.166800 -vn 0.552289 0.318864 0.770262 -v 0.026801 -0.116125 0.166800 -vn 0.637728 -0.000000 0.770262 -v 0.026500 -0.115000 0.166800 -vn 0.552289 -0.318864 0.770262 -v 0.026801 -0.113875 0.166800 -vn 0.318864 -0.552289 0.770262 -v 0.027625 -0.113051 0.166800 -vn -0.000000 -0.637728 0.770262 -v 0.028750 -0.112750 0.166800 -vn -0.318864 -0.552288 0.770262 -v 0.029875 -0.113051 0.166800 -vn -0.552289 -0.318864 0.770262 -v 0.030699 -0.113875 0.166800 -vn -0.637728 0.000000 0.770262 -v 0.031000 -0.115000 0.166800 -vn -0.552289 0.318863 0.770262 -v 0.030699 -0.116125 0.166800 -vn -0.318864 0.552288 0.770262 -v 0.029875 -0.116949 0.166800 -vn 0.000000 0.637728 0.770262 -v 0.028750 -0.117250 0.166800 -vn -0.318864 -0.552289 0.770262 -v 0.006750 -0.116340 0.166800 -vn -0.552288 -0.318864 0.770262 -v 0.010410 -0.120000 0.166800 -vn -0.655722 -0.378581 0.653227 -v 0.012420 -0.142500 0.166800 -vn -0.378581 -0.655722 0.653226 -v 0.014250 -0.144330 0.166800 -vn -0.727973 -0.095840 0.678874 -v 0.011750 -0.140000 0.166800 -vn -0.707107 -0.000000 0.707107 -v 0.011750 -0.125125 0.166800 -vn -0.669353 -0.088122 0.737700 -v 0.011750 -0.125000 0.166800 -vn 0.707106 0.000000 0.707107 -v -0.039250 -0.125125 0.166800 -vn 0.669353 -0.088122 0.737700 -v -0.039250 -0.125000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 -0.108310 0.166800 -vn 0.552288 -0.318864 0.770262 -v -0.037910 -0.120000 0.166800 -vn 0.318864 -0.552289 0.770262 -v -0.034250 -0.116340 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 -0.108310 0.166800 -vn 0.088122 -0.669353 0.737700 -v -0.029250 -0.115000 0.166800 -vn 0.000000 -0.707107 0.707107 -v -0.023049 -0.115000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 -0.108310 0.166800 -vn 0.000000 -0.707107 0.707107 -v -0.019900 -0.115000 0.166800 -vn 0.000000 -0.707107 0.707107 -v -0.007200 -0.115000 0.166800 -vn -0.088122 -0.669353 0.737700 -v 0.001750 -0.115000 0.166800 -vn 0.378581 -0.655722 0.653226 -v -0.041750 -0.144330 0.166800 -vn 0.655722 -0.378581 0.653227 -v -0.039920 -0.142500 0.166800 -vn 0.727973 -0.095839 0.678874 -v -0.039250 -0.140000 0.166800 -vn 0.637728 0.000001 0.770262 -v -0.061500 -0.136000 0.166800 -vn 0.552289 -0.318863 0.770262 -v -0.061199 -0.134875 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 -0.125125 0.166800 -vn 0.095839 -0.727973 0.678875 -v -0.044250 -0.145000 0.166800 -vn -0.637728 0.000001 0.770262 -v -0.057000 -0.136000 0.166800 -vn -0.552289 -0.318863 0.770262 -v -0.057301 -0.134875 0.166800 -vn -0.552288 0.318865 0.770262 -v -0.057301 -0.137125 0.166800 -vn -0.318862 0.552289 0.770263 -v -0.058125 -0.137949 0.166800 -vn -0.095839 -0.727973 0.678875 -v -0.064250 -0.145000 0.166800 -vn 0.000000 0.637730 0.770260 -v -0.059250 -0.138250 0.166800 -vn 0.318862 0.552289 0.770263 -v -0.060375 -0.137949 0.166800 -vn -0.378581 -0.655722 0.653227 -v -0.066750 -0.144330 0.166800 -vn 0.552288 0.318865 0.770262 -v -0.061199 -0.137125 0.166800 -vn -0.655722 -0.378581 0.653227 -v -0.068580 -0.142500 0.166800 -vn 0.318862 -0.552289 0.770263 -v -0.060375 -0.134051 0.166800 -vn -0.000000 -0.637730 0.770260 -v -0.059250 -0.133750 0.166800 -vn -0.318862 -0.552289 0.770263 -v -0.058125 -0.134051 0.166800 -vn -0.552287 -0.318864 0.770263 -v -0.069518 -0.125000 0.166800 -vn -0.669353 -0.088121 0.737700 -v -0.069250 -0.126000 0.166800 -vn -0.727973 -0.095840 0.678874 -v -0.069250 -0.140000 0.166800 -vn -0.318865 -0.552290 0.770261 -v -0.070250 -0.124268 0.166800 -vn -0.318864 -0.552289 0.770262 -v -0.079125 -0.113051 0.166800 -vn -0.552289 -0.318864 0.770262 -v -0.078301 -0.113875 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.108310 0.166800 -vn 0.637728 -0.000000 0.770262 -v -0.082500 -0.115000 0.166800 -vn 0.552289 -0.318864 0.770262 -v -0.082199 -0.113875 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.086375 -0.108310 0.166800 -vn 0.318864 -0.552289 0.770262 -v -0.081375 -0.113051 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.080250 -0.112750 0.166800 -vn -0.637728 0.000000 0.770262 -v -0.078000 -0.115000 0.166800 -vn -0.552289 0.318864 0.770262 -v -0.078301 -0.116125 0.166800 -vn 0.000000 -0.707107 0.707107 -v -0.076625 -0.124000 0.166800 -vn -0.088123 -0.669352 0.737701 -v -0.071250 -0.124000 0.166800 -vn -0.318864 0.552289 0.770262 -v -0.079125 -0.116949 0.166800 -vn 0.000000 0.637728 0.770262 -v -0.080250 -0.117250 0.166800 -vn -0.095839 -0.727973 0.678874 -v -0.085250 -0.124000 0.166800 -vn 0.318864 0.552288 0.770262 -v -0.081375 -0.116949 0.166800 -vn -0.378581 -0.655722 0.653227 -v -0.087750 -0.123330 0.166800 -vn 0.552289 0.318864 0.770262 -v -0.082199 -0.116125 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.090250 -0.108310 0.166800 -vn -0.727973 -0.095840 0.678874 -v -0.090250 -0.119000 0.166800 -vn -0.655722 -0.378581 0.653227 -v -0.089580 -0.121500 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.098020 0.166800 -vn -0.410993 0.535615 0.737700 -v -0.079250 -0.081649 0.166800 -vn -0.271528 0.623295 0.733332 -v -0.088113 -0.086766 0.166800 -vn -0.727973 0.095838 0.678875 -v -0.078250 -0.042688 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.078250 -0.049166 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.049166 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.078250 -0.066000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.066000 0.166800 -vn -0.669352 0.088123 0.737701 -v -0.078250 -0.079917 0.166800 -vn -0.552288 0.318865 0.770261 -v -0.078518 -0.080917 0.166800 -vn -0.378582 0.655722 0.653226 -v -0.077250 -0.040956 0.166800 -vn -0.655723 0.378579 0.653227 -v -0.077982 -0.041688 0.166800 -vn -0.095839 0.727973 0.678875 -v -0.076250 -0.040688 0.166800 -vn -0.000000 0.707106 0.707108 -v -0.067375 -0.040688 0.166800 -vn 0.552289 -0.318864 0.770262 -v -0.029998 -0.043875 0.166800 -vn -0.552289 -0.318864 0.770262 -v -0.026101 -0.043875 0.166800 -vn -0.637728 0.000000 0.770262 -v -0.025799 -0.045000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 -0.049166 0.166800 -vn -0.552288 0.318864 0.770262 -v -0.026101 -0.046125 0.166800 -vn -0.318864 0.552289 0.770262 -v -0.026924 -0.046949 0.166800 -vn 0.000000 0.637728 0.770262 -v -0.028049 -0.047250 0.166800 -vn 0.318864 0.552288 0.770262 -v -0.029174 -0.046949 0.166800 -vn 0.318864 -0.552288 0.770262 -v -0.029174 -0.043051 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.028049 -0.042750 0.166800 -vn -0.000000 0.707107 0.707107 -v -0.023049 -0.040688 0.166800 -vn -0.318864 -0.552289 0.770262 -v -0.026924 -0.043051 0.166800 -vn 0.301511 0.301511 0.904534 -v -0.022049 -0.041000 0.166800 -vn 0.577350 0.577350 0.577350 -v -0.022049 -0.040688 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 -0.049166 0.166800 -vn 0.552289 0.318864 0.770262 -v -0.019998 -0.046125 0.166800 -vn 0.637728 0.000000 0.770262 -v -0.020299 -0.045000 0.166800 -vn 0.552289 -0.318863 0.770262 -v -0.019998 -0.043875 0.166800 -vn 0.000000 0.707107 0.707107 -v -0.019900 -0.041000 0.166800 -vn -0.318864 0.552289 0.770262 -v -0.016924 -0.046949 0.166800 -vn 0.000000 0.637728 0.770262 -v -0.018049 -0.047250 0.166800 -vn 0.318864 0.552289 0.770262 -v -0.019174 -0.046949 0.166800 -vn 0.318864 -0.552289 0.770262 -v -0.019174 -0.043051 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.018049 -0.042750 0.166800 -vn -0.069844 0.678920 0.730882 -v -0.012049 -0.041000 0.166800 -vn -0.318864 -0.552289 0.770262 -v -0.016924 -0.043051 0.166800 -vn -0.260984 0.600378 0.755932 -v -0.011152 -0.040813 0.166800 -vn -0.626968 -0.510002 0.588905 -v -0.012049 -0.036188 0.166800 -vn -0.707107 -0.000000 0.707107 -v -0.012049 -0.000000 0.166800 -vn -0.626968 0.510002 0.588905 -v -0.012049 0.036500 0.166800 -vn -0.260984 -0.600379 0.755932 -v -0.011152 -0.036374 0.166800 -vn -0.478695 -0.446562 0.755932 -v -0.010404 -0.036903 0.166800 -vn -0.617038 -0.218703 0.755932 -v -0.009929 -0.037686 0.166800 -vn -0.673884 0.000000 0.738837 -v -0.009805 -0.038594 0.166800 -vn -0.617038 0.218703 0.755932 -v -0.009929 -0.039502 0.166800 -vn -0.478696 0.446562 0.755931 -v -0.010404 -0.040285 0.166800 -vn -0.552289 -0.318864 0.770262 -v -0.016101 -0.043875 0.166800 -vn -0.637728 0.000000 0.770262 -v -0.015799 -0.045000 0.166800 -vn -0.552288 0.318864 0.770262 -v -0.016101 -0.046125 0.166800 -vn 0.637728 -0.000001 0.770262 -v 0.025750 0.136000 0.166800 -vn 0.552287 -0.318865 0.770262 -v -0.019199 0.101845 0.166800 -vn 0.318863 -0.552290 0.770261 -v -0.018375 0.102669 0.166800 -vn 0.637728 -0.000000 0.770262 -v -0.019500 0.100720 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.017250 0.102970 0.166800 -vn -0.318863 -0.552290 0.770261 -v -0.016125 0.102669 0.166800 -vn -0.000000 0.637728 0.770262 -v -0.017250 0.098470 0.166800 -vn 0.318864 0.552289 0.770262 -v -0.018375 0.098771 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 0.098020 0.166800 -vn 0.552289 0.318864 0.770262 -v -0.019199 0.099595 0.166800 -vn 0.000000 -0.637729 0.770261 -v 0.003750 0.103870 0.166800 -vn -0.552287 -0.318865 0.770262 -v -0.015301 0.101845 0.166800 -vn -0.637728 0.000000 0.770262 -v -0.015000 0.100720 0.166800 -vn -0.552289 0.318864 0.770262 -v -0.015301 0.099595 0.166800 -vn -0.318864 0.552289 0.770262 -v -0.016125 0.098771 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 0.089244 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 0.098020 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.086375 0.098020 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.098020 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.086375 0.089244 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.090250 0.103420 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.090250 0.098020 0.166800 -vn -0.393680 -0.562235 0.727260 -v -0.079250 0.081649 0.166800 -vn -0.669355 0.088118 0.737699 -v -0.073250 0.075417 0.166800 -vn -0.552286 0.318862 0.770265 -v -0.073384 0.074917 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 0.066000 0.166800 -vn 0.669352 -0.088123 0.737701 -v -0.075250 0.079917 0.166800 -vn 0.552288 -0.318865 0.770261 -v -0.075116 0.080417 0.166800 -vn 0.318865 -0.552288 0.770261 -v -0.074750 0.080783 0.166800 -vn -0.000001 -0.637726 0.770263 -v -0.074250 0.080917 0.166800 -vn -0.318864 -0.552291 0.770260 -v -0.073750 0.080783 0.166800 -vn -0.552286 -0.318862 0.770265 -v -0.073384 0.080417 0.166800 -vn -0.669355 -0.088118 0.737699 -v -0.073250 0.079917 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 0.089244 0.166800 -vn -0.318859 0.552292 0.770261 -v -0.073750 0.074551 0.166800 -vn -0.000001 0.637731 0.770259 -v -0.074250 0.074417 0.166800 -vn 0.318860 0.552289 0.770263 -v -0.074750 0.074551 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 0.066000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 0.066000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 0.089244 0.166800 -vn 0.669352 -0.088123 0.737701 -v -0.075250 0.056583 0.166800 -vn 0.552288 -0.318866 0.770261 -v -0.075116 0.057083 0.166800 -vn 0.318865 -0.552288 0.770261 -v -0.074750 0.057449 0.166800 -vn 0.318862 0.552289 0.770262 -v -0.074750 0.051217 0.166800 -vn 0.552288 0.318865 0.770261 -v -0.075116 0.051583 0.166800 -vn 0.669352 0.088123 0.737701 -v -0.075250 0.052083 0.166800 -vn -0.669355 0.088118 0.737699 -v -0.073250 0.052083 0.166800 -vn -0.552286 0.318862 0.770265 -v -0.073384 0.051583 0.166800 -vn -0.318862 0.552292 0.770261 -v -0.073750 0.051217 0.166800 -vn -0.000001 0.637729 0.770261 -v -0.074250 0.051083 0.166800 -vn -0.000001 -0.637726 0.770263 -v -0.074250 0.057583 0.166800 -vn -0.318864 -0.552291 0.770260 -v -0.073750 0.057449 0.166800 -vn -0.552286 -0.318863 0.770264 -v -0.073384 0.057083 0.166800 -vn -0.669354 -0.088119 0.737699 -v -0.073250 0.056583 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 -0.066000 0.166800 -vn -0.318864 0.552291 0.770260 -v -0.073750 -0.057449 0.166800 -vn -0.000001 0.637726 0.770263 -v -0.074250 -0.057583 0.166800 -vn 0.318865 0.552288 0.770261 -v -0.074750 -0.057449 0.166800 -vn 0.584730 -0.281591 0.760787 -v -0.075151 -0.051649 0.166800 -vn 0.404646 -0.507407 0.760789 -v -0.074873 -0.051301 0.166800 -vn -0.675742 -0.076134 0.733196 -v -0.073250 -0.052083 0.166800 -vn -0.669354 0.088119 0.737699 -v -0.073250 -0.056583 0.166800 -vn -0.552286 0.318863 0.770264 -v -0.073384 -0.057083 0.166800 -vn 0.552288 0.318866 0.770261 -v -0.075116 -0.057083 0.166800 -vn 0.669352 0.088123 0.737701 -v -0.075250 -0.056583 0.166800 -vn 0.675739 -0.076139 0.733198 -v -0.075250 -0.052083 0.166800 -vn 0.144416 -0.632728 0.760789 -v -0.074473 -0.051108 0.166800 -vn -0.144416 -0.632728 0.760789 -v -0.074027 -0.051108 0.166800 -vn -0.404644 -0.507411 0.760787 -v -0.073627 -0.051301 0.166800 -vn -0.584727 -0.281588 0.760791 -v -0.073349 -0.051649 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 -0.066000 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 -0.066000 0.166800 -vn -0.669355 0.088118 0.737699 -v -0.073250 -0.079917 0.166800 -vn -0.552286 0.318862 0.770265 -v -0.073384 -0.080417 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 -0.098020 0.166800 -vn -0.318864 0.552291 0.770260 -v -0.073750 -0.080783 0.166800 -vn -0.000001 0.637726 0.770263 -v -0.074250 -0.080917 0.166800 -vn 0.318865 0.552288 0.770261 -v -0.074750 -0.080783 0.166800 -vn 0.552288 0.318865 0.770261 -v -0.075116 -0.080417 0.166800 -vn 0.669352 0.088123 0.737701 -v -0.075250 -0.079917 0.166800 -vn 0.675739 -0.076139 0.733198 -v -0.075250 -0.075417 0.166800 -vn 0.584729 -0.281592 0.760788 -v -0.075151 -0.074983 0.166800 -vn -0.404643 -0.507412 0.760787 -v -0.073627 -0.074635 0.166800 -vn -0.584725 -0.281589 0.760792 -v -0.073349 -0.074983 0.166800 -vn -0.675742 -0.076134 0.733196 -v -0.073250 -0.075417 0.166800 -vn 0.404645 -0.507408 0.760788 -v -0.074873 -0.074635 0.166800 -vn 0.144416 -0.632728 0.760789 -v -0.074473 -0.074442 0.166800 -vn -0.144416 -0.632728 0.760789 -v -0.074027 -0.074442 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 -0.098020 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 -0.098020 0.166800 -vn 0.637728 -0.000000 0.770262 -v -0.019500 -0.100720 0.166800 -vn 0.552289 -0.318864 0.770262 -v -0.019199 -0.099595 0.166800 -vn 0.318864 -0.552289 0.770262 -v -0.018375 -0.098771 0.166800 -vn -0.000000 -0.637728 0.770262 -v -0.017250 -0.098470 0.166800 -vn -0.318864 -0.552289 0.770262 -v -0.016125 -0.098771 0.166800 -vn -0.552288 -0.318864 0.770262 -v -0.015301 -0.099595 0.166800 -vn -0.637728 0.000000 0.770262 -v -0.015000 -0.100720 0.166800 -vn -0.552287 0.318865 0.770262 -v -0.015301 -0.101845 0.166800 -vn -0.318863 0.552290 0.770261 -v -0.016125 -0.102669 0.166800 -vn -0.000000 0.637728 0.770262 -v -0.017250 -0.102970 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.019900 -0.103420 0.166800 -vn 0.318863 0.552290 0.770261 -v -0.018375 -0.102669 0.166800 -vn 0.552287 0.318865 0.770262 -v -0.019199 -0.101845 0.166800 -vn -0.707107 0.000000 0.707107 -v -0.090250 -0.103420 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.086375 -0.103420 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.103420 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.067375 -0.103420 0.166800 -vn 0.000000 0.000000 1.000000 -v -0.023049 -0.103420 0.166800 -vn -0.000000 -0.637729 0.770261 -v 0.003750 -0.097570 0.166800 -vn -0.727973 -0.095840 -0.678874 -v -0.089450 -0.042845 0.071250 -vn -0.727973 -0.095840 0.678874 -v -0.089450 -0.042845 0.073750 -vn -0.707107 -0.000000 -0.707107 -v -0.089450 -0.033000 0.071250 -vn -0.707107 0.000000 0.707107 -v -0.089450 -0.033000 0.073750 -vn -0.707107 0.000000 -0.707107 -v -0.089450 -0.018344 0.071250 -vn -0.707107 0.000000 0.707107 -v -0.089450 -0.018344 0.073750 -vn -0.707107 0.000000 -0.707107 -v -0.089450 -0.007344 0.071250 -vn -0.707107 0.000000 0.707107 -v -0.089450 -0.007344 0.073750 -vn -0.707107 0.000000 -0.707107 -v -0.089450 0.007656 0.071250 -vn -0.707107 0.000000 0.707107 -v -0.089450 0.007656 0.073750 -vn -0.707107 0.000000 -0.707107 -v -0.089450 0.033000 0.071250 -vn -0.707107 -0.000000 0.707107 -v -0.089450 0.033000 0.073750 -vn -0.727973 0.095840 -0.678874 -v -0.089450 0.042845 0.071250 -vn -0.727973 0.095840 0.678874 -v -0.089450 0.042845 0.073750 -vn -0.727973 0.095841 0.678874 -v -0.089450 -0.089155 0.073750 -vn -0.727973 0.095841 -0.678874 -v -0.089450 -0.089155 0.071250 -vn -0.707107 -0.000000 0.707106 -v -0.089450 -0.090225 0.073750 -vn -0.707107 0.000000 -0.707107 -v -0.089450 -0.090225 0.071250 -vn -0.707107 0.000000 0.707107 -v -0.089450 -0.095500 0.073750 -vn -0.707107 -0.000000 -0.707107 -v -0.089450 -0.095500 0.071250 -vn -0.707107 -0.000000 0.707106 -v -0.089450 -0.109000 0.073750 -vn -0.707107 -0.000000 -0.707107 -v -0.089450 -0.109000 0.071250 -vn -0.727973 -0.095841 0.678874 -v -0.089450 -0.123200 0.073750 -vn -0.727973 -0.095840 -0.678874 -v -0.089450 -0.123200 0.071250 -vn -0.727973 0.095841 0.678874 -v -0.089450 0.123200 0.073750 -vn -0.727973 0.095840 -0.678874 -v -0.089450 0.123200 0.071250 -vn -0.707107 -0.000000 0.707106 -v -0.089450 0.109000 0.073750 -vn -0.707107 -0.000000 -0.707107 -v -0.089450 0.109000 0.071250 -vn -0.707107 -0.000000 0.707107 -v -0.089450 0.095500 0.073750 -vn -0.707107 0.000000 -0.707107 -v -0.089450 0.095500 0.071250 -vn -0.707107 0.000000 0.707107 -v -0.089450 0.090225 0.073750 -vn -0.707107 -0.000000 -0.707107 -v -0.089450 0.090225 0.071250 -vn -0.727973 -0.095840 0.678874 -v -0.089450 0.089155 0.073750 -vn -0.727973 -0.095840 -0.678874 -v -0.089450 0.089155 0.071250 -vn -0.095835 -0.727973 0.678875 -v -0.087450 -0.125200 0.073750 -vn -0.095835 -0.727972 -0.678876 -v -0.087450 -0.125200 0.071250 -vn -0.000000 -0.707107 0.707107 -v -0.074092 -0.125200 0.073750 -vn 0.000000 -0.707107 -0.707107 -v -0.074092 -0.125200 0.071250 -vn 0.095838 -0.727973 0.678875 -v -0.071450 -0.125200 0.073750 -vn 0.095838 -0.727973 -0.678875 -v -0.071450 -0.125200 0.071250 -vn 0.727973 -0.095840 0.678874 -v 0.034750 -0.114500 0.073750 -vn 0.727973 -0.095840 -0.678874 -v 0.034750 -0.114500 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 -0.109000 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 -0.109000 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 -0.095500 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 -0.095500 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 -0.090225 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 -0.090225 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 -0.085525 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 -0.085525 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 -0.074609 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 -0.074609 0.071250 -vn 0.727973 0.095840 0.678874 -v 0.034750 -0.050500 0.073750 -vn 0.727973 0.095840 -0.678874 -v 0.034750 -0.050500 0.071250 -vn 0.095840 0.727973 -0.678874 -v 0.032750 -0.048500 0.071250 -vn 0.301511 0.301512 -0.904534 -v 0.022080 -0.048500 0.071250 -vn 0.095840 0.727973 0.678874 -v 0.032750 -0.048500 0.073750 -vn 0.301511 0.301511 0.904534 -v 0.022080 -0.048500 0.073750 -vn 0.301511 -0.301511 -0.904534 -v 0.022080 0.048500 0.071250 -vn 0.301511 -0.301511 0.904534 -v 0.022080 0.048500 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.022080 0.033000 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.022080 0.033000 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.022080 0.007656 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.022080 0.007656 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.022080 -0.007344 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.022080 -0.007344 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.022080 -0.018344 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.022080 -0.018344 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.022080 -0.033000 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.022080 -0.033000 0.073750 -vn 0.095840 -0.727973 0.678874 -v 0.032750 0.048500 0.073750 -vn 0.095840 -0.727973 -0.678874 -v 0.032750 0.048500 0.071250 -vn 0.727973 -0.095842 0.678874 -v 0.034750 0.050500 0.073750 -vn 0.727973 -0.095842 -0.678874 -v 0.034750 0.050500 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 0.066000 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 0.066000 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 0.083109 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 0.083109 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 0.085525 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 0.085525 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 0.090225 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 0.090225 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 0.095500 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 0.095500 0.071250 -vn 0.707107 0.000000 0.707107 -v 0.034750 0.109000 0.073750 -vn 0.707107 0.000000 -0.707107 -v 0.034750 0.109000 0.071250 -vn 0.727973 0.095840 0.678874 -v 0.034750 0.114500 0.073750 -vn 0.727973 0.095840 -0.678874 -v 0.034750 0.114500 0.071250 -vn 0.095838 0.727973 0.678875 -v -0.071450 0.125200 0.073750 -vn 0.095838 0.727973 -0.678875 -v -0.071450 0.125200 0.071250 -vn -0.000000 0.707107 0.707107 -v -0.074092 0.125200 0.073750 -vn 0.000000 0.707107 -0.707107 -v -0.074092 0.125200 0.071250 -vn -0.095841 0.727973 0.678874 -v -0.087450 0.125200 0.073750 -vn -0.095840 0.727973 -0.678874 -v -0.087450 0.125200 0.071250 -vn -0.000000 0.000000 1.000000 -v -0.074092 0.007656 0.073750 -vn -0.000000 0.000000 1.000000 -v -0.074092 -0.007344 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.007344 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.095500 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.109000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.109000 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.081399 -0.104125 0.073750 -vn 0.637727 -0.000000 0.770262 -v -0.081700 -0.103000 0.073750 -vn 0.144417 -0.632728 0.760789 -v -0.073673 -0.074442 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 -0.074609 0.073750 -vn 0.404643 -0.507412 0.760787 -v -0.074073 -0.074635 0.073750 -vn -0.552288 0.318865 0.770262 -v -0.077718 -0.080917 0.073750 -vn -0.410992 0.535615 0.737700 -v -0.078450 -0.081649 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 -0.085525 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.033000 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 0.048666 0.073750 -vn 0.378582 -0.655721 0.653227 -v 0.033750 0.048768 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.054325 -0.089949 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.055450 -0.090250 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.090225 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.056575 0.089949 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.055450 0.090250 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.090225 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.023575 0.089949 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.022450 0.090250 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.090225 0.073750 -vn 0.552289 -0.318863 0.770262 -v 0.026628 -0.086525 0.073750 -vn 0.318865 -0.552288 0.770261 -v 0.027525 -0.085628 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.085525 0.073750 -vn -0.318865 -0.552288 0.770261 -v 0.029975 -0.085628 0.073750 -vn -0.552288 -0.318865 0.770261 -v 0.030872 -0.086525 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 -0.085525 0.073750 -vn -0.637727 0.000000 0.770263 -v 0.031200 -0.087750 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 -0.090225 0.073750 -vn -0.552290 0.318865 0.770261 -v 0.030872 -0.088975 0.073750 -vn -0.318864 0.552287 0.770263 -v 0.029975 -0.089872 0.073750 -vn 0.000000 0.637729 0.770261 -v 0.028750 -0.090200 0.073750 -vn 0.318864 0.552287 0.770263 -v 0.027525 -0.089872 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.090225 0.073750 -vn 0.552290 0.318863 0.770261 -v 0.026628 -0.088975 0.073750 -vn 0.637728 0.000000 0.770261 -v 0.026300 -0.087750 0.073750 -vn -0.000000 -0.637729 0.770261 -v 0.028750 -0.074800 0.073750 -vn -0.318864 -0.552287 0.770263 -v 0.029975 -0.075128 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 -0.074609 0.073750 -vn 0.637728 0.000000 0.770261 -v 0.026300 -0.077250 0.073750 -vn 0.552290 -0.318862 0.770262 -v 0.026628 -0.076025 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.074609 0.073750 -vn 0.318864 -0.552287 0.770263 -v 0.027525 -0.075128 0.073750 -vn -0.552290 -0.318864 0.770261 -v 0.030872 -0.076025 0.073750 -vn -0.637727 0.000000 0.770263 -v 0.031200 -0.077250 0.073750 -vn 0.552290 0.318863 0.770261 -v 0.026628 -0.078475 0.073750 -vn 0.318864 0.552287 0.770263 -v 0.027525 -0.079372 0.073750 -vn 0.000000 0.637728 0.770261 -v 0.028750 -0.079700 0.073750 -vn -0.552290 0.318865 0.770261 -v 0.030872 -0.078475 0.073750 -vn -0.318864 0.552287 0.770263 -v 0.029975 -0.079372 0.073750 -vn 0.000000 -0.637727 0.770263 -v 0.028750 -0.085300 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.085525 0.073750 -vn 0.637729 -0.000001 0.770261 -v 0.026300 0.087750 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.090225 0.073750 -vn 0.552290 -0.318863 0.770261 -v 0.026628 0.088975 0.073750 -vn 0.318862 -0.552288 0.770263 -v 0.027525 0.089872 0.073750 -vn -0.000000 -0.637730 0.770260 -v 0.028750 0.090200 0.073750 -vn -0.318862 -0.552288 0.770263 -v 0.029975 0.089872 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 0.090225 0.073750 -vn -0.552290 -0.318865 0.770261 -v 0.030872 0.088975 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 0.085525 0.073750 -vn -0.637727 -0.000001 0.770263 -v 0.031200 0.087750 0.073750 -vn -0.552287 0.318865 0.770262 -v 0.030872 0.086525 0.073750 -vn -0.318864 0.552290 0.770261 -v 0.029975 0.085628 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 0.083109 0.073750 -vn 0.000000 0.637727 0.770263 -v 0.028750 0.085300 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.083109 0.073750 -vn 0.318864 0.552290 0.770261 -v 0.027525 0.085628 0.073750 -vn 0.552287 0.318863 0.770263 -v 0.026628 0.086525 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 0.085525 0.073750 -vn -0.318862 0.552289 0.770263 -v -0.076325 0.086051 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.077450 0.085750 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.076325 0.089949 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.075501 0.089125 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 0.090225 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.075200 0.088000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.075501 0.086875 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.078575 0.086051 0.073750 -vn -0.353554 -0.612371 0.707108 -v -0.085163 0.085525 0.073750 -vn 0.552288 0.318863 0.770262 -v -0.079399 0.086875 0.073750 -vn -0.446987 -0.582523 0.678874 -v -0.088450 0.087423 0.073750 -vn 0.637727 -0.000001 0.770262 -v -0.079700 0.088000 0.073750 -vn 0.318866 -0.552287 0.770262 -v -0.078575 0.089949 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.079399 0.089125 0.073750 -vn -0.655721 -0.378582 0.653227 -v -0.089182 0.088155 0.073750 -vn 0.318864 0.552288 0.770263 -v -0.078575 -0.089949 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.079399 -0.089125 0.073750 -vn 0.637727 0.000000 0.770262 -v -0.079700 -0.088000 0.073750 -vn -0.655721 0.378581 0.653227 -v -0.089182 -0.088155 0.073750 -vn -0.446988 0.582522 0.678874 -v -0.088450 -0.087423 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.079399 -0.086875 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.078575 -0.086051 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.077450 -0.085750 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.076325 -0.086051 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.075501 -0.086875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.075200 -0.088000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 -0.090225 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.075501 -0.089125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.076325 -0.089949 0.073750 -vn -0.000000 0.637728 0.770262 -v -0.077450 -0.090250 0.073750 -vn -0.000000 0.000000 1.000000 -v -0.074092 -0.095500 0.073750 -vn -0.318867 -0.552288 0.770261 -v 0.000675 0.089949 0.073750 -vn -0.552288 -0.318865 0.770262 -v 0.001499 0.089125 0.073750 -vn -0.637728 -0.000001 0.770262 -v 0.001800 0.088000 0.073750 -vn -0.552289 0.318863 0.770262 -v 0.001499 0.086875 0.073750 -vn -0.318862 0.552289 0.770262 -v 0.000675 0.086051 0.073750 -vn -0.000001 0.637730 0.770260 -v -0.000450 0.085750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.001575 0.086051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.085525 0.073750 -vn 0.552288 0.318863 0.770262 -v -0.002399 0.086875 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.090225 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.002700 0.088000 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.002399 0.089125 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.001575 0.089949 0.073750 -vn -0.000001 -0.637726 0.770264 -v -0.000450 0.090250 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.095500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.095500 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.024399 0.089125 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.021325 0.089949 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.020501 0.089125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.020200 0.088000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.020501 0.086875 0.073750 -vn -0.318862 0.552289 0.770263 -v -0.021325 0.086051 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.022450 0.085750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.023575 0.086051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.085525 0.073750 -vn 0.552289 0.318863 0.770262 -v -0.024399 0.086875 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.024700 0.088000 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.054325 0.089949 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.057399 0.089125 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.053501 0.089125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.053200 0.088000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.053501 0.086875 0.073750 -vn -0.318862 0.552289 0.770263 -v -0.054325 0.086051 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.055450 0.085750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.056575 0.086051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.085525 0.073750 -vn 0.552289 0.318863 0.770262 -v -0.057399 0.086875 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.057700 0.088000 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.053501 -0.089125 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.085525 0.073750 -vn 0.552289 -0.318864 0.770262 -v -0.057399 -0.086875 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.056575 -0.086051 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.057700 -0.088000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.090225 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.057399 -0.089125 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.055450 -0.085750 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.054325 -0.086051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.085525 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.053501 -0.086875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.053200 -0.088000 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.022450 -0.090250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.023575 -0.089949 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.024399 -0.089125 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.024700 -0.088000 0.073750 -vn 0.552289 -0.318864 0.770262 -v -0.024399 -0.086875 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.023575 -0.086051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.090225 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.020501 -0.089125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.021325 -0.089949 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.022450 -0.085750 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.021325 -0.086051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.085525 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.020501 -0.086875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.020200 -0.088000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.095500 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.095500 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.056575 -0.089949 0.073750 -vn -0.000001 0.637728 0.770262 -v -0.000450 -0.090250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.001575 -0.089949 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.002399 -0.089125 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.002700 -0.088000 0.073750 -vn 0.552289 -0.318864 0.770262 -v -0.002399 -0.086875 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.001575 -0.086051 0.073750 -vn -0.000001 -0.637728 0.770262 -v -0.000450 -0.085750 0.073750 -vn -0.318864 -0.552288 0.770262 -v 0.000675 -0.086051 0.073750 -vn -0.552288 -0.318864 0.770262 -v 0.001499 -0.086875 0.073750 -vn -0.637728 0.000000 0.770262 -v 0.001800 -0.088000 0.073750 -vn -0.552289 0.318864 0.770262 -v 0.001499 -0.089125 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.095500 0.073750 -vn -0.318865 0.552288 0.770262 -v 0.000675 -0.089949 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.075501 0.042875 0.073750 -vn -0.318862 0.552289 0.770263 -v -0.076325 0.042051 0.073750 -vn -0.000000 -0.000000 1.000000 -v -0.074092 0.033000 0.073750 -vn 0.637727 -0.000001 0.770262 -v -0.079700 0.044000 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.079399 0.045125 0.073750 -vn -0.446986 0.582523 0.678874 -v -0.088450 0.044577 0.073750 -vn -0.393682 0.562232 0.727261 -v -0.078450 0.050351 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.075501 0.045125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.075200 0.044000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 0.048666 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.078575 0.045949 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.077450 0.046250 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.076325 0.045949 0.073750 -vn -0.000000 0.637730 0.770260 -v -0.077450 0.041750 0.073750 -vn 0.318862 0.552288 0.770263 -v -0.078575 0.042051 0.073750 -vn 0.552288 0.318863 0.770262 -v -0.079399 0.042875 0.073750 -vn -0.655721 0.378582 0.653227 -v -0.089182 0.043845 0.073750 -vn 0.318863 -0.552291 0.770260 -v -0.073950 0.057449 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 0.066000 0.073750 -vn 0.552286 -0.318866 0.770263 -v -0.074316 0.057083 0.073750 -vn -0.707107 0.000000 0.707107 -v -0.077450 0.066000 0.073750 -vn 0.669353 -0.088122 0.737700 -v -0.074450 0.056583 0.073750 -vn -0.683749 0.059822 0.727261 -v -0.077450 0.052083 0.073750 -vn 0.669351 0.088124 0.737701 -v -0.074450 0.052083 0.073750 -vn -0.623291 0.226861 0.748360 -v -0.077571 0.051399 0.073750 -vn 0.552291 0.318864 0.770260 -v -0.074316 0.051583 0.073750 -vn -0.410992 -0.535615 0.737700 -v -0.078450 0.081649 0.073750 -vn -0.552288 -0.318865 0.770262 -v -0.077718 0.080917 0.073750 -vn 0.552285 -0.318866 0.770263 -v -0.074316 0.080417 0.073750 -vn -0.669352 -0.088123 0.737701 -v -0.077450 0.079917 0.073750 -vn 0.669353 -0.088122 0.737700 -v -0.074450 0.079917 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 0.083109 0.073750 -vn 0.318863 -0.552291 0.770260 -v -0.073950 0.080783 0.073750 -vn -0.000001 0.637725 0.770264 -v -0.079450 0.112750 0.073750 -vn 0.318866 0.552288 0.770261 -v -0.080575 0.113051 0.073750 -vn -0.000000 0.000000 1.000000 -v -0.074092 0.109000 0.073750 -vn -0.318867 0.552288 0.770261 -v -0.078325 0.113051 0.073750 -vn -0.378578 0.655722 0.653228 -v -0.088450 0.124932 0.073750 -vn 0.318862 -0.552288 0.770263 -v -0.080575 0.116949 0.073750 -vn -0.655720 0.378586 0.653226 -v -0.089182 0.124200 0.073750 -vn 0.552288 -0.318863 0.770262 -v -0.081399 0.116125 0.073750 -vn 0.637727 0.000001 0.770262 -v -0.081700 0.115000 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.081399 0.113875 0.073750 -vn -0.000001 -0.637729 0.770261 -v -0.079450 0.117250 0.073750 -vn -0.318862 -0.552289 0.770262 -v -0.078325 0.116949 0.073750 -vn -0.552289 -0.318863 0.770262 -v -0.077501 0.116125 0.073750 -vn -0.637728 0.000001 0.770262 -v -0.077200 0.115000 0.073750 -vn -0.552288 0.318864 0.770262 -v -0.077501 0.113875 0.073750 -vn 0.655720 0.378586 0.653226 -v -0.069718 0.124200 0.073750 -vn 0.378576 0.655724 0.653227 -v -0.070450 0.124932 0.073750 -vn 0.727973 0.095840 0.678874 -v -0.069450 0.123200 0.073750 -vn 0.680317 0.067005 0.729849 -v -0.069450 0.121500 0.073750 -vn 0.607120 0.251476 0.753767 -v -0.069069 0.119587 0.073750 -vn 0.464670 0.464668 0.753768 -v -0.067986 0.117964 0.073750 -vn 0.251475 0.607119 0.753768 -v -0.066363 0.116881 0.073750 -vn 0.067004 0.680318 0.729848 -v -0.064450 0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.109000 0.073750 -vn 0.000000 0.707107 0.707107 -v -0.063467 0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.109000 0.073750 -vn 0.000000 0.707107 0.707107 -v -0.038950 0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.109000 0.073750 -vn 0.000000 0.707107 0.707107 -v -0.011450 0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.109000 0.073750 -vn 0.000000 0.707107 0.707107 -v 0.014050 0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 0.109000 0.073750 -vn 0.095840 0.727973 0.678874 -v 0.032750 0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.048666 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.033000 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.007656 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.018344 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.007344 0.073750 -vn 0.000000 -0.707107 0.707107 -v -0.038950 -0.116500 0.073750 -vn 0.000000 -0.707107 0.707107 -v -0.011450 -0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.109000 0.073750 -vn 0.000000 -0.707107 0.707107 -v 0.014050 -0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.109000 0.073750 -vn 0.680317 -0.067005 0.729848 -v -0.069450 -0.121500 0.073750 -vn 0.607119 -0.251477 0.753768 -v -0.069069 -0.119587 0.073750 -vn -0.000000 0.000000 1.000000 -v -0.074092 -0.109000 0.073750 -vn 0.464669 -0.464670 0.753767 -v -0.067986 -0.117964 0.073750 -vn 0.251478 -0.607119 0.753767 -v -0.066363 -0.116881 0.073750 -vn 0.067006 -0.680317 0.729849 -v -0.064450 -0.116500 0.073750 -vn 0.000000 -0.707107 0.707107 -v -0.063467 -0.116500 0.073750 -vn 0.378580 -0.655723 0.653226 -v -0.070450 -0.124932 0.073750 -vn 0.655721 -0.378582 0.653227 -v -0.069718 -0.124200 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.077200 -0.115000 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.077501 -0.116125 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.077501 -0.113875 0.073750 -vn -0.318864 -0.552288 0.770262 -v -0.078325 -0.113051 0.073750 -vn -0.000001 -0.637728 0.770262 -v -0.079450 -0.112750 0.073750 -vn 0.727973 -0.095840 0.678874 -v -0.069450 -0.123200 0.073750 -vn 0.318864 -0.552288 0.770262 -v -0.080575 -0.113051 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.081399 -0.113875 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.081399 -0.116125 0.073750 -vn 0.637727 -0.000000 0.770262 -v -0.081700 -0.115000 0.073750 -vn -0.318864 0.552288 0.770262 -v -0.078325 -0.116949 0.073750 -vn -0.000001 0.637727 0.770262 -v -0.079450 -0.117250 0.073750 -vn 0.318864 0.552288 0.770262 -v -0.080575 -0.116949 0.073750 -vn -0.378578 -0.655725 0.653225 -v -0.088450 -0.124932 0.073750 -vn -0.655721 -0.378582 0.653227 -v -0.089182 -0.124200 0.073750 -vn 0.584725 -0.281595 0.760790 -v -0.074351 -0.074983 0.073750 -vn 0.318860 -0.552289 0.770263 -v -0.073950 -0.051217 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.074092 -0.048666 0.073750 -vn 0.552288 -0.318865 0.770261 -v -0.074316 -0.051583 0.073750 -vn -0.393681 -0.562235 0.727260 -v -0.078450 -0.050351 0.073750 -vn -0.508111 -0.426354 0.748361 -v -0.077918 -0.050797 0.073750 -vn -0.623292 -0.226860 0.748359 -v -0.077571 -0.051399 0.073750 -vn 0.669352 -0.088123 0.737701 -v -0.074450 -0.052083 0.073750 -vn 0.669352 0.088123 0.737700 -v -0.074450 -0.056583 0.073750 -vn -0.683749 -0.059822 0.727261 -v -0.077450 -0.052083 0.073750 -vn 0.552288 0.318865 0.770261 -v -0.074316 -0.057083 0.073750 -vn -0.707107 0.000000 0.707107 -v -0.077450 -0.074609 0.073750 -vn 0.318865 0.552289 0.770261 -v -0.073950 -0.057449 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.077450 -0.041750 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.076325 -0.042051 0.073750 -vn -0.000000 0.000000 1.000000 -v -0.074092 -0.033000 0.073750 -vn 0.318864 -0.552288 0.770262 -v -0.078575 -0.042051 0.073750 -vn 0.318864 0.552288 0.770262 -v -0.078575 -0.045949 0.073750 -vn -0.446986 -0.582524 0.678874 -v -0.088450 -0.044577 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.079399 -0.045125 0.073750 -vn -0.655721 -0.378582 0.653227 -v -0.089182 -0.043845 0.073750 -vn 0.637727 -0.000000 0.770262 -v -0.079700 -0.044000 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.079399 -0.042875 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.075501 -0.042875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.075200 -0.044000 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.075501 -0.045125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.076325 -0.045949 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.077450 -0.046250 0.073750 -vn -0.318860 -0.552289 0.770263 -v -0.072950 -0.051217 0.073750 -vn -0.552288 -0.318865 0.770262 -v -0.072584 -0.051583 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.048666 0.073750 -vn 0.000000 -0.637731 0.770259 -v -0.073450 -0.051083 0.073750 -vn -0.669352 -0.088123 0.737701 -v -0.072450 -0.052083 0.073750 -vn -0.669352 0.088123 0.737701 -v -0.072450 -0.056583 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.074609 0.073750 -vn -0.552288 0.318865 0.770261 -v -0.072584 -0.057083 0.073750 -vn -0.318865 0.552288 0.770262 -v -0.072950 -0.057449 0.073750 -vn -0.404643 -0.507412 0.760787 -v -0.072827 -0.074635 0.073750 -vn -0.000000 0.637728 0.770262 -v -0.073450 -0.057583 0.073750 -vn -0.144416 -0.632728 0.760789 -v -0.073227 -0.074442 0.073750 -vn 0.000000 -0.637727 0.770262 -v -0.073450 0.057583 0.073750 -vn -0.318863 -0.552291 0.770260 -v -0.072950 0.057449 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.066000 0.073750 -vn -0.552291 0.318864 0.770260 -v -0.072584 0.051583 0.073750 -vn -0.318857 0.552286 0.770266 -v -0.072950 0.051217 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.048666 0.073750 -vn -0.508114 0.426355 0.748360 -v -0.077918 0.050797 0.073750 -vn 0.318857 0.552286 0.770266 -v -0.073950 0.051217 0.073750 -vn 0.000000 0.637736 0.770255 -v -0.073450 0.051083 0.073750 -vn -0.552286 -0.318866 0.770263 -v -0.072584 0.057083 0.073750 -vn -0.669353 -0.088122 0.737700 -v -0.072450 0.056583 0.073750 -vn -0.669352 0.088124 0.737701 -v -0.072450 0.052083 0.073750 -vn -0.318865 0.552288 0.770262 -v -0.072950 -0.080783 0.073750 -vn -0.000000 0.637727 0.770262 -v -0.073450 -0.080917 0.073750 -vn 0.318865 0.552288 0.770261 -v -0.073950 -0.080783 0.073750 -vn 0.552288 0.318865 0.770262 -v -0.074316 -0.080417 0.073750 -vn -0.669352 0.088123 0.737701 -v -0.077450 -0.079917 0.073750 -vn 0.669352 0.088123 0.737701 -v -0.074450 -0.079917 0.073750 -vn 0.675739 -0.076139 0.733198 -v -0.074450 -0.075417 0.073750 -vn -0.584725 -0.281595 0.760790 -v -0.072549 -0.074983 0.073750 -vn -0.675739 -0.076139 0.733198 -v -0.072450 -0.075417 0.073750 -vn -0.669352 0.088123 0.737701 -v -0.072450 -0.079917 0.073750 -vn -0.552288 0.318865 0.770261 -v -0.072584 -0.080417 0.073750 -vn 0.000000 -0.637727 0.770262 -v -0.073450 0.080917 0.073750 -vn -0.318863 -0.552291 0.770260 -v -0.072950 0.080783 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.083109 0.073750 -vn -0.552286 0.318866 0.770263 -v -0.072584 0.074917 0.073750 -vn -0.318863 0.552291 0.770260 -v -0.072950 0.074551 0.073750 -vn -0.000000 0.637727 0.770262 -v -0.073450 0.074417 0.073750 -vn 0.318863 0.552291 0.770260 -v -0.073950 0.074551 0.073750 -vn 0.552286 0.318866 0.770263 -v -0.074316 0.074917 0.073750 -vn 0.669353 0.088122 0.737700 -v -0.074450 0.075417 0.073750 -vn -0.552286 -0.318866 0.770263 -v -0.072584 0.080417 0.073750 -vn -0.669353 -0.088122 0.737700 -v -0.072450 0.079917 0.073750 -vn -0.669353 0.088122 0.737700 -v -0.072450 0.075417 0.073750 -vn -0.000001 -0.637728 0.770262 -v -0.079450 -0.100750 0.073750 -vn -0.318864 -0.552288 0.770262 -v -0.078325 -0.101051 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.081399 -0.101875 0.073750 -vn 0.318864 -0.552288 0.770262 -v -0.080575 -0.101051 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.077501 -0.101875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.077200 -0.103000 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.077501 -0.104125 0.073750 -vn -0.318864 0.552288 0.770262 -v -0.078325 -0.104949 0.073750 -vn -0.000001 0.637727 0.770262 -v -0.079450 -0.105250 0.073750 -vn 0.318864 0.552288 0.770262 -v -0.080575 -0.104949 0.073750 -vn 0.095838 -0.727973 0.678875 -v 0.032750 -0.116500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 -0.109000 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 -0.095500 0.073750 -vn 0.378580 -0.655723 0.653226 -v 0.033750 -0.116232 0.073750 -vn 0.655721 -0.378582 0.653227 -v 0.034482 -0.115500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 -0.048666 0.073750 -vn 0.378582 0.655721 0.653227 -v 0.033750 -0.048768 0.073750 -vn 0.655721 0.378582 0.653227 -v 0.034482 -0.049500 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 -0.048666 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.057700 -0.044000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.033000 0.073750 -vn 0.552289 -0.318863 0.770262 -v -0.057399 -0.042875 0.073750 -vn 0.318864 -0.552288 0.770262 -v -0.056575 -0.042051 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.055450 -0.041750 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.033000 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.055450 -0.046250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.056575 -0.045949 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.057399 -0.045125 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.048666 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.053501 -0.045125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.054325 -0.045949 0.073750 -vn -0.318863 -0.552289 0.770262 -v -0.054325 -0.042051 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.053501 -0.042875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.053200 -0.044000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.074609 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.020501 -0.045125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.021325 -0.045949 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.048666 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.023575 -0.042051 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.022450 -0.041750 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.033000 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.022450 -0.046250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.023575 -0.045949 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.024399 -0.045125 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.024700 -0.044000 0.073750 -vn 0.552289 -0.318864 0.770262 -v -0.024399 -0.042875 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.021325 -0.042051 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.020501 -0.042875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.020200 -0.044000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.074609 0.073750 -vn -0.318865 -0.552288 0.770262 -v 0.000675 -0.042051 0.073750 -vn -0.000001 -0.637728 0.770262 -v -0.000450 -0.041750 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.001575 -0.042051 0.073750 -vn -0.000001 0.637728 0.770262 -v -0.000450 -0.046250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.001575 -0.045949 0.073750 -vn -0.552289 -0.318864 0.770262 -v 0.001499 -0.042875 0.073750 -vn -0.637728 -0.000000 0.770262 -v 0.001800 -0.044000 0.073750 -vn -0.552289 0.318864 0.770262 -v 0.001499 -0.045125 0.073750 -vn -0.318864 0.552288 0.770262 -v 0.000675 -0.045949 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.002399 -0.045125 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.002700 -0.044000 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.002399 -0.042875 0.073750 -vn -0.000000 0.000000 1.000000 -v -0.074092 -0.018344 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 -0.018344 0.073750 -vn 0.552289 -0.318864 0.770262 -v -0.057399 -0.020875 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.056575 -0.020051 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.055450 -0.019750 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.054325 -0.020051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.018344 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.053501 -0.020875 0.073750 -vn -0.637728 0.000000 0.770262 -v -0.053200 -0.022000 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.053501 -0.023125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.054325 -0.023949 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.055450 -0.024250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.056575 -0.023949 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.057399 -0.023125 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.057700 -0.022000 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.022450 -0.019750 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.021325 -0.020051 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.018344 0.073750 -vn -0.318864 0.552288 0.770262 -v -0.021325 -0.023949 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.022450 -0.024250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.023575 -0.023949 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.024399 -0.023125 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.024700 -0.022000 0.073750 -vn 0.552289 -0.318863 0.770262 -v -0.024399 -0.020875 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.023575 -0.020051 0.073750 -vn -0.552288 -0.318865 0.770262 -v -0.020501 -0.020875 0.073750 -vn -0.637728 -0.000000 0.770262 -v -0.020200 -0.022000 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.020501 -0.023125 0.073750 -vn -0.000001 -0.637728 0.770262 -v -0.000450 -0.019750 0.073750 -vn -0.318864 -0.552288 0.770262 -v 0.000675 -0.020051 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.002399 -0.020875 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.001575 -0.020051 0.073750 -vn -0.552288 -0.318864 0.770262 -v 0.001499 -0.020875 0.073750 -vn -0.637728 -0.000000 0.770262 -v 0.001800 -0.022000 0.073750 -vn -0.000001 0.637728 0.770262 -v -0.000450 -0.024250 0.073750 -vn -0.318864 0.552288 0.770262 -v 0.000675 -0.023949 0.073750 -vn -0.552289 0.318864 0.770262 -v 0.001499 -0.023125 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.001575 -0.023949 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.002399 -0.023125 0.073750 -vn 0.637728 0.000000 0.770262 -v -0.002700 -0.022000 0.073750 -vn 0.552289 -0.318864 0.770262 -v -0.073433 -0.013563 0.073750 -vn 0.637728 0.000001 0.770262 -v -0.073735 -0.014688 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.073433 -0.015813 0.073750 -vn 0.318864 -0.552289 0.770262 -v -0.072610 -0.012739 0.073750 -vn 0.000000 -0.637728 0.770262 -v -0.071485 -0.012438 0.073750 -vn -0.318864 -0.552289 0.770262 -v -0.070360 -0.012739 0.073750 -vn -0.552289 -0.318864 0.770262 -v -0.069536 -0.013563 0.073750 -vn -0.637728 0.000001 0.770262 -v -0.069235 -0.014688 0.073750 -vn -0.552288 0.318864 0.770262 -v -0.069536 -0.015813 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.070360 -0.016636 0.073750 -vn 0.000000 0.637728 0.770262 -v -0.071485 -0.016938 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.072610 -0.016636 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.057700 -0.000000 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.057399 0.001125 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.007656 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.057399 -0.001125 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.056575 -0.001949 0.073750 -vn -0.000000 0.637728 0.770262 -v -0.055450 -0.002250 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.056575 0.001949 0.073750 -vn 0.000000 -0.637726 0.770263 -v -0.055450 0.002250 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.007656 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 -0.007344 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.053501 -0.001125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.054325 -0.001949 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.054325 0.001949 0.073750 -vn -0.552288 -0.318865 0.770262 -v -0.053501 0.001125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.053200 -0.000000 0.073750 -vn -0.552289 0.318864 0.770262 -v -0.020501 -0.001125 0.073750 -vn -0.318864 0.552289 0.770262 -v -0.021325 -0.001949 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 -0.007344 0.073750 -vn -0.000000 0.637728 0.770262 -v -0.022450 -0.002250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.023575 -0.001949 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.024399 -0.001125 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.024700 0.000000 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.024399 0.001125 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.023575 0.001949 0.073750 -vn 0.000000 -0.637726 0.770263 -v -0.022450 0.002250 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.021325 0.001949 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.007656 0.073750 -vn -0.552288 -0.318865 0.770262 -v -0.020501 0.001125 0.073750 -vn -0.637727 -0.000001 0.770262 -v -0.020200 0.000000 0.073750 -vn -0.000001 -0.637726 0.770264 -v -0.000450 0.002250 0.073750 -vn -0.318867 -0.552288 0.770261 -v 0.000675 0.001949 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.001575 0.001949 0.073750 -vn -0.552288 -0.318865 0.770262 -v 0.001499 0.001125 0.073750 -vn -0.000001 0.637728 0.770262 -v -0.000450 -0.002250 0.073750 -vn 0.318864 0.552289 0.770262 -v -0.001575 -0.001949 0.073750 -vn -0.637728 -0.000001 0.770262 -v 0.001800 0.000000 0.073750 -vn -0.552289 0.318864 0.770262 -v 0.001499 -0.001125 0.073750 -vn -0.318864 0.552288 0.770262 -v 0.000675 -0.001949 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.002399 -0.001125 0.073750 -vn 0.637727 -0.000001 0.770262 -v -0.002700 0.000000 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.002399 0.001125 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.071485 0.013062 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.072610 0.013364 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.073433 0.016437 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.073735 0.015312 0.073750 -vn 0.552289 0.318863 0.770262 -v -0.073433 0.014187 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.069536 0.014187 0.073750 -vn -0.318862 0.552289 0.770263 -v -0.070360 0.013364 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.072610 0.017261 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.071485 0.017562 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.033000 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.070360 0.017261 0.073750 -vn -0.552288 -0.318865 0.770262 -v -0.069536 0.016437 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.069235 0.015312 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.055450 0.024250 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.054325 0.023949 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.033000 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.056575 0.023949 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.053501 0.023125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.053200 0.022000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.053501 0.020875 0.073750 -vn -0.318862 0.552289 0.770263 -v -0.054325 0.020051 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.055450 0.019750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.056575 0.020051 0.073750 -vn 0.552289 0.318863 0.770262 -v -0.057399 0.020875 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.057700 0.022000 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.057399 0.023125 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.022450 0.024250 0.073750 -vn -0.318866 -0.552289 0.770261 -v -0.021325 0.023949 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.033000 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.023575 0.023949 0.073750 -vn -0.552288 -0.318865 0.770262 -v -0.020501 0.023125 0.073750 -vn -0.637728 -0.000002 0.770262 -v -0.020200 0.022000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.020501 0.020875 0.073750 -vn -0.318862 0.552288 0.770263 -v -0.021325 0.020051 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.022450 0.019750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.023575 0.020051 0.073750 -vn 0.552289 0.318864 0.770262 -v -0.024399 0.020875 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.024700 0.022000 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.024399 0.023125 0.073750 -vn -0.000001 -0.637726 0.770264 -v -0.000450 0.024250 0.073750 -vn -0.318867 -0.552288 0.770261 -v 0.000675 0.023949 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.002399 0.023125 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.001575 0.023949 0.073750 -vn -0.318862 0.552289 0.770262 -v 0.000675 0.020051 0.073750 -vn -0.000001 0.637729 0.770260 -v -0.000450 0.019750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.001575 0.020051 0.073750 -vn 0.552289 0.318863 0.770262 -v -0.002399 0.020875 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.002700 0.022000 0.073750 -vn -0.552288 -0.318865 0.770262 -v 0.001499 0.023125 0.073750 -vn -0.637728 -0.000001 0.770262 -v 0.001800 0.022000 0.073750 -vn -0.552289 0.318863 0.770262 -v 0.001499 0.020875 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.056575 0.045949 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.057399 0.045125 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.057700 0.044000 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.055450 0.046250 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.054325 0.045949 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.048666 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.055450 0.041750 0.073750 -vn 0.318861 0.552289 0.770262 -v -0.056575 0.042051 0.073750 -vn 0.552288 0.318864 0.770262 -v -0.057399 0.042875 0.073750 -vn -0.318862 0.552288 0.770263 -v -0.054325 0.042051 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.053501 0.045125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.053200 0.044000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.053501 0.042875 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.024399 0.045125 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.023575 0.045949 0.073750 -vn -0.000000 -0.637726 0.770263 -v -0.022450 0.046250 0.073750 -vn -0.318866 -0.552288 0.770261 -v -0.021325 0.045949 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.048666 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.020501 0.045125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.020200 0.044000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.020501 0.042875 0.073750 -vn -0.318862 0.552289 0.770263 -v -0.021325 0.042051 0.073750 -vn 0.000000 0.637730 0.770260 -v -0.022450 0.041750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.023575 0.042051 0.073750 -vn 0.552289 0.318863 0.770262 -v -0.024399 0.042875 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.024700 0.044000 0.073750 -vn 0.552288 -0.318865 0.770262 -v -0.002399 0.045125 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.001575 0.045949 0.073750 -vn -0.000001 -0.637726 0.770264 -v -0.000450 0.046250 0.073750 -vn -0.318867 -0.552288 0.770261 -v 0.000675 0.045949 0.073750 -vn -0.318862 0.552289 0.770262 -v 0.000675 0.042051 0.073750 -vn -0.000001 0.637729 0.770260 -v -0.000450 0.041750 0.073750 -vn 0.318862 0.552289 0.770263 -v -0.001575 0.042051 0.073750 -vn 0.552289 0.318863 0.770262 -v -0.002399 0.042875 0.073750 -vn 0.637728 -0.000001 0.770262 -v -0.002700 0.044000 0.073750 -vn -0.552288 -0.318865 0.770262 -v 0.001499 0.045125 0.073750 -vn -0.637728 -0.000001 0.770262 -v 0.001800 0.044000 0.073750 -vn -0.552289 0.318863 0.770262 -v 0.001499 0.042875 0.073750 -vn -0.318864 0.552290 0.770261 -v 0.029975 0.075128 0.073750 -vn 0.000000 0.637727 0.770263 -v 0.028750 0.074800 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 0.066000 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.014050 0.066000 0.073750 -vn 0.637729 -0.000001 0.770261 -v 0.026300 0.077250 0.073750 -vn 0.552287 0.318863 0.770263 -v 0.026628 0.076025 0.073750 -vn 0.318864 0.552290 0.770261 -v 0.027525 0.075128 0.073750 -vn 0.552290 -0.318863 0.770261 -v 0.026628 0.078475 0.073750 -vn 0.318862 -0.552288 0.770263 -v 0.027525 0.079372 0.073750 -vn -0.000000 -0.637730 0.770260 -v 0.028750 0.079700 0.073750 -vn -0.318862 -0.552288 0.770263 -v 0.029975 0.079372 0.073750 -vn -0.552290 -0.318865 0.770261 -v 0.030872 0.078475 0.073750 -vn -0.637727 -0.000001 0.770263 -v 0.031200 0.077250 0.073750 -vn -0.552287 0.318865 0.770262 -v 0.030872 0.076025 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.066000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.083109 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.066000 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.011450 0.083109 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.038950 0.095500 0.073750 -vn 0.000000 0.000000 1.000000 -v -0.063467 0.095500 0.073750 -vn -0.000000 -0.000000 1.000000 -v -0.074092 0.095500 0.073750 -vn -0.000000 -0.637726 0.770264 -v -0.077450 0.090250 0.073750 -vn 0.000000 0.000000 1.000000 -v 0.032975 0.095500 0.073750 -vn 0.552288 -0.318864 0.770262 -v -0.081399 0.104125 0.073750 -vn 0.318866 -0.552288 0.770261 -v -0.080575 0.104949 0.073750 -vn -0.000001 -0.637726 0.770264 -v -0.079450 0.105250 0.073750 -vn -0.318867 -0.552288 0.770261 -v -0.078325 0.104949 0.073750 -vn -0.552288 -0.318864 0.770262 -v -0.077501 0.104125 0.073750 -vn -0.637728 -0.000001 0.770262 -v -0.077200 0.103000 0.073750 -vn -0.000001 0.637729 0.770261 -v -0.079450 0.100750 0.073750 -vn 0.318862 0.552288 0.770263 -v -0.080575 0.101051 0.073750 -vn 0.552288 0.318863 0.770262 -v -0.081399 0.101875 0.073750 -vn 0.637727 -0.000001 0.770262 -v -0.081700 0.103000 0.073750 -vn -0.552289 0.318863 0.770262 -v -0.077501 0.101875 0.073750 -vn -0.318862 0.552289 0.770262 -v -0.078325 0.101051 0.073750 -vn 0.655720 -0.378583 0.653227 -v 0.034482 0.049500 0.073750 -vn 0.378582 0.655721 0.653227 -v 0.033750 0.116232 0.073750 -vn 0.655721 0.378582 0.653227 -v 0.034482 0.115500 0.073750 -vn -0.552289 0.318864 -0.770262 -v -0.053501 -0.045125 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.053200 -0.044000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.048666 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 -0.018344 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.018344 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.033000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.007344 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.007344 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.018344 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.090225 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.090225 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.085525 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.056575 -0.089949 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.055450 -0.090250 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.090225 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.021325 0.089949 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.022450 0.090250 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.090225 0.071250 -vn 0.552287 0.318863 -0.770263 -v 0.026628 0.086525 0.071250 -vn 0.318864 0.552290 -0.770261 -v 0.027525 0.085628 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.085525 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.075501 -0.045125 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.075200 -0.044000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 -0.048666 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 -0.085525 0.071250 -vn -0.410992 0.535615 -0.737700 -v -0.078450 -0.081649 0.071250 -vn -0.552288 0.318865 -0.770262 -v -0.077718 -0.080917 0.071250 -vn 0.000000 -0.000000 -1.000000 -v -0.074092 -0.095500 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.077450 -0.090250 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 -0.090225 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.076325 -0.089949 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.075501 -0.089125 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.075200 -0.088000 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.075501 -0.086875 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.076325 -0.086051 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.077450 -0.085750 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.078575 -0.086051 0.071250 -vn -0.446987 0.582522 -0.678875 -v -0.088450 -0.087423 0.071250 -vn 0.552289 -0.318864 -0.770261 -v -0.079399 -0.086875 0.071250 -vn -0.655721 0.378581 -0.653228 -v -0.089182 -0.088155 0.071250 -vn 0.637728 -0.000000 -0.770262 -v -0.079700 -0.088000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.079399 -0.089125 0.071250 -vn 0.318864 0.552289 -0.770261 -v -0.078575 -0.089949 0.071250 -vn -0.318864 0.552288 -0.770262 -v -0.078325 -0.116949 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.077501 -0.116125 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.077200 -0.115000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 -0.109000 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.077501 -0.113875 0.071250 -vn -0.318865 -0.552288 -0.770262 -v -0.078325 -0.113051 0.071250 -vn -0.000000 -0.637728 -0.770262 -v -0.079450 -0.112750 0.071250 -vn 0.318864 -0.552289 -0.770261 -v -0.080575 -0.113051 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.081399 -0.116125 0.071250 -vn 0.637728 -0.000000 -0.770262 -v -0.081700 -0.115000 0.071250 -vn 0.552289 -0.318864 -0.770261 -v -0.081399 -0.113875 0.071250 -vn -0.655721 -0.378582 -0.653227 -v -0.089182 -0.124200 0.071250 -vn -0.378578 -0.655725 -0.653226 -v -0.088450 -0.124932 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.080575 -0.116949 0.071250 -vn -0.000001 0.637728 -0.770262 -v -0.079450 -0.117250 0.071250 -vn 0.251478 -0.607119 -0.753767 -v -0.066363 -0.116881 0.071250 -vn 0.067006 -0.680317 -0.729849 -v -0.064450 -0.116500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.109000 0.071250 -vn 0.000000 -0.707107 -0.707107 -v -0.063467 -0.116500 0.071250 -vn 0.655721 -0.378582 -0.653227 -v -0.069718 -0.124200 0.071250 -vn 0.378580 -0.655723 -0.653226 -v -0.070450 -0.124932 0.071250 -vn 0.727973 -0.095840 -0.678874 -v -0.069450 -0.123200 0.071250 -vn 0.680317 -0.067005 -0.729848 -v -0.069450 -0.121500 0.071250 -vn 0.607119 -0.251477 -0.753768 -v -0.069069 -0.119587 0.071250 -vn 0.464669 -0.464670 -0.753767 -v -0.067986 -0.117964 0.071250 -vn 0.000000 -0.707107 -0.707107 -v -0.038950 -0.116500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.109000 0.071250 -vn 0.000000 -0.707107 -0.707107 -v -0.011450 -0.116500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.109000 0.071250 -vn 0.000000 -0.707107 -0.707107 -v 0.014050 -0.116500 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.109000 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 -0.109000 0.071250 -vn 0.095838 -0.727973 -0.678875 -v 0.032750 -0.116500 0.071250 -vn 0.655721 -0.378582 -0.653227 -v 0.034482 -0.115500 0.071250 -vn 0.378580 -0.655723 -0.653226 -v 0.033750 -0.116232 0.071250 -vn 0.378582 0.655721 -0.653227 -v 0.033750 -0.048768 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 -0.048666 0.071250 -vn 0.655721 0.378582 -0.653227 -v 0.034482 -0.049500 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.048666 0.071250 -vn 0.655720 -0.378583 -0.653227 -v 0.034482 0.049500 0.071250 -vn 0.378582 -0.655721 -0.653227 -v 0.033750 0.048768 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 0.048666 0.071250 -vn 0.095840 0.727973 -0.678874 -v 0.032750 0.116500 0.071250 -vn 0.378582 0.655721 -0.653227 -v 0.033750 0.116232 0.071250 -vn 0.655721 0.378582 -0.653227 -v 0.034482 0.115500 0.071250 -vn 0.680317 0.067005 -0.729849 -v -0.069450 0.121500 0.071250 -vn 0.607120 0.251476 -0.753767 -v -0.069069 0.119587 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.109000 0.071250 -vn 0.464669 0.464669 -0.753768 -v -0.067986 0.117964 0.071250 -vn 0.251475 0.607119 -0.753768 -v -0.066363 0.116881 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.109000 0.071250 -vn 0.067004 0.680318 -0.729848 -v -0.064450 0.116500 0.071250 -vn 0.000000 0.707107 -0.707107 -v -0.063467 0.116500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.109000 0.071250 -vn 0.000000 0.707107 -0.707107 -v -0.038950 0.116500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.109000 0.071250 -vn 0.000000 0.707107 -0.707107 -v -0.011450 0.116500 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.109000 0.071250 -vn 0.000000 0.707107 -0.707107 -v 0.014050 0.116500 0.071250 -vn 0.378576 0.655724 -0.653227 -v -0.070450 0.124932 0.071250 -vn 0.655720 0.378586 -0.653226 -v -0.069718 0.124200 0.071250 -vn -0.318867 0.552288 -0.770261 -v -0.078325 0.113051 0.071250 -vn -0.552288 0.318865 -0.770262 -v -0.077501 0.113875 0.071250 -vn 0.552289 0.318865 -0.770261 -v -0.081399 0.113875 0.071250 -vn 0.318866 0.552289 -0.770261 -v -0.080575 0.113051 0.071250 -vn -0.637728 0.000001 -0.770262 -v -0.077200 0.115000 0.071250 -vn -0.552289 -0.318863 -0.770262 -v -0.077501 0.116125 0.071250 -vn 0.727973 0.095840 -0.678874 -v -0.069450 0.123200 0.071250 -vn 0.318862 -0.552289 -0.770262 -v -0.080575 0.116949 0.071250 -vn -0.000000 -0.637730 -0.770260 -v -0.079450 0.117250 0.071250 -vn -0.318862 -0.552289 -0.770262 -v -0.078325 0.116949 0.071250 -vn -0.000001 0.637726 -0.770264 -v -0.079450 0.112750 0.071250 -vn -0.378578 0.655722 -0.653228 -v -0.088450 0.124932 0.071250 -vn -0.655720 0.378586 -0.653226 -v -0.089182 0.124200 0.071250 -vn 0.552289 -0.318863 -0.770262 -v -0.081399 0.116125 0.071250 -vn 0.637728 0.000001 -0.770261 -v -0.081700 0.115000 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.075501 0.089125 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.076325 0.089949 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.079399 0.086875 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.078575 0.086051 0.071250 -vn -0.353553 -0.612373 -0.707106 -v -0.085163 0.085525 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.077450 0.085750 0.071250 -vn -0.318862 0.552289 -0.770263 -v -0.076325 0.086051 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.085525 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.075501 0.086875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.075200 0.088000 0.071250 -vn 0.318866 -0.552289 -0.770260 -v -0.078575 0.089949 0.071250 -vn 0.552289 -0.318865 -0.770261 -v -0.079399 0.089125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.079700 0.088000 0.071250 -vn -0.655721 -0.378582 -0.653227 -v -0.089182 0.088155 0.071250 -vn -0.446986 -0.582523 -0.678875 -v -0.088450 0.087423 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.083109 0.071250 -vn -0.410992 -0.535616 -0.737700 -v -0.078450 0.081649 0.071250 -vn 0.318863 0.552291 -0.770260 -v -0.073950 0.074551 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.066000 0.071250 -vn 0.552286 0.318866 -0.770263 -v -0.074316 0.074917 0.071250 -vn -0.707107 0.000000 -0.707107 -v -0.077450 0.066000 0.071250 -vn 0.669353 0.088122 -0.737700 -v -0.074450 0.075417 0.071250 -vn -0.669352 -0.088123 -0.737701 -v -0.077450 0.079917 0.071250 -vn 0.669353 -0.088122 -0.737700 -v -0.074450 0.079917 0.071250 -vn 0.552285 -0.318866 -0.770263 -v -0.074316 0.080417 0.071250 -vn -0.623291 0.226861 -0.748360 -v -0.077571 0.051399 0.071250 -vn 0.552291 0.318864 -0.770260 -v -0.074316 0.051583 0.071250 -vn -0.508114 0.426355 -0.748360 -v -0.077918 0.050797 0.071250 -vn -0.393682 0.562233 -0.727261 -v -0.078450 0.050351 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.075501 0.045125 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.076325 0.045949 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.048666 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.075200 0.044000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.033000 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.075501 0.042875 0.071250 -vn 0.318862 0.552289 -0.770262 -v -0.078575 0.042051 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.077450 0.041750 0.071250 -vn -0.318862 0.552289 -0.770263 -v -0.076325 0.042051 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.077450 0.046250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.078575 0.045949 0.071250 -vn -0.446985 0.582523 -0.678875 -v -0.088450 0.044577 0.071250 -vn 0.552289 -0.318865 -0.770261 -v -0.079399 0.045125 0.071250 -vn -0.655721 0.378582 -0.653227 -v -0.089182 0.043845 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.079700 0.044000 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.079399 0.042875 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.078575 -0.042051 0.071250 -vn 0.552289 -0.318864 -0.770262 -v -0.079399 -0.042875 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.075501 -0.042875 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.076325 -0.042051 0.071250 -vn 0.000000 -0.000000 -1.000000 -v -0.074092 -0.033000 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.077450 -0.041750 0.071250 -vn -0.393681 -0.562235 -0.727260 -v -0.078450 -0.050351 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.077450 -0.046250 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.076325 -0.045949 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.079700 -0.044000 0.071250 -vn -0.655721 -0.378582 -0.653227 -v -0.089182 -0.043845 0.071250 -vn -0.446985 -0.582523 -0.678875 -v -0.088450 -0.044577 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.079399 -0.045125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.078575 -0.045949 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 -0.085525 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 -0.090225 0.071250 -vn -0.552290 0.318865 -0.770261 -v 0.030872 -0.088975 0.071250 -vn 0.552290 0.318863 -0.770261 -v 0.026628 -0.088975 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.090225 0.071250 -vn 0.637728 0.000000 -0.770261 -v 0.026300 -0.087750 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.085525 0.071250 -vn 0.552289 -0.318863 -0.770262 -v 0.026628 -0.086525 0.071250 -vn 0.318865 -0.552288 -0.770261 -v 0.027525 -0.085628 0.071250 -vn -0.637727 0.000000 -0.770263 -v 0.031200 -0.087750 0.071250 -vn -0.552288 -0.318865 -0.770261 -v 0.030872 -0.086525 0.071250 -vn -0.318865 -0.552288 -0.770261 -v 0.029975 -0.085628 0.071250 -vn 0.318864 0.552287 -0.770263 -v 0.027525 -0.089872 0.071250 -vn -0.000000 0.637729 -0.770261 -v 0.028750 -0.090200 0.071250 -vn -0.318864 0.552287 -0.770263 -v 0.029975 -0.089872 0.071250 -vn 0.637728 0.000000 -0.770261 -v 0.026300 -0.077250 0.071250 -vn 0.552290 0.318863 -0.770261 -v 0.026628 -0.078475 0.071250 -vn -0.552290 -0.318864 -0.770261 -v 0.030872 -0.076025 0.071250 -vn -0.318864 -0.552287 -0.770263 -v 0.029975 -0.075128 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 -0.074609 0.071250 -vn 0.000000 -0.637729 -0.770261 -v 0.028750 -0.074800 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.074609 0.071250 -vn 0.318864 -0.552287 -0.770263 -v 0.027525 -0.075128 0.071250 -vn 0.552290 -0.318862 -0.770262 -v 0.026628 -0.076025 0.071250 -vn 0.318864 0.552287 -0.770263 -v 0.027525 -0.079372 0.071250 -vn 0.000000 -0.637727 -0.770263 -v 0.028750 -0.085300 0.071250 -vn -0.000000 0.637728 -0.770261 -v 0.028750 -0.079700 0.071250 -vn -0.318864 0.552287 -0.770263 -v 0.029975 -0.079372 0.071250 -vn -0.552290 0.318865 -0.770261 -v 0.030872 -0.078475 0.071250 -vn -0.637727 0.000000 -0.770263 -v 0.031200 -0.077250 0.071250 -vn -0.552290 -0.318865 -0.770261 -v 0.030872 0.088975 0.071250 -vn -0.318862 -0.552288 -0.770263 -v 0.029975 0.089872 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 0.090225 0.071250 -vn 0.000000 -0.637730 -0.770260 -v 0.028750 0.090200 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.090225 0.071250 -vn 0.318862 -0.552288 -0.770263 -v 0.027525 0.089872 0.071250 -vn 0.552290 -0.318863 -0.770261 -v 0.026628 0.088975 0.071250 -vn 0.637729 -0.000001 -0.770261 -v 0.026300 0.087750 0.071250 -vn -0.637727 -0.000001 -0.770263 -v 0.031200 0.087750 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 0.085525 0.071250 -vn -0.552287 0.318865 -0.770262 -v 0.030872 0.086525 0.071250 -vn -0.318864 0.552290 -0.770261 -v 0.029975 0.085628 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 0.083109 0.071250 -vn 0.000000 0.637727 -0.770263 -v 0.028750 0.085300 0.071250 -vn -0.000001 -0.637726 -0.770264 -v -0.000450 0.090250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.001575 0.089949 0.071250 -vn -0.552288 -0.318865 -0.770262 -v 0.001499 0.089125 0.071250 -vn -0.318867 -0.552288 -0.770261 -v 0.000675 0.089949 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.001575 0.086051 0.071250 -vn -0.000001 0.637730 -0.770260 -v -0.000450 0.085750 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.085525 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.083109 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.002399 0.089125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.002700 0.088000 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.002399 0.086875 0.071250 -vn -0.318862 0.552289 -0.770262 -v 0.000675 0.086051 0.071250 -vn -0.552289 0.318863 -0.770262 -v 0.001499 0.086875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v 0.001800 0.088000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.090225 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.023575 0.089949 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.020501 0.089125 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.024399 0.089125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.024700 0.088000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.085525 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.024399 0.086875 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.023575 0.086051 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.022450 0.085750 0.071250 -vn -0.318862 0.552289 -0.770263 -v -0.021325 0.086051 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.020501 0.086875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.020200 0.088000 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.055450 0.090250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.056575 0.089949 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.057399 0.089125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.057700 0.088000 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.057399 0.086875 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.056575 0.086051 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.055450 0.085750 0.071250 -vn -0.318862 0.552289 -0.770263 -v -0.054325 0.086051 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.053501 0.086875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.053200 0.088000 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.053501 0.089125 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.090225 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.054325 -0.089949 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.057399 -0.089125 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.053501 -0.086875 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.085525 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.053200 -0.088000 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.053501 -0.089125 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.054325 -0.086051 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.055450 -0.085750 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.085525 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.056575 -0.086051 0.071250 -vn 0.552289 -0.318864 -0.770262 -v -0.057399 -0.086875 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.057700 -0.088000 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.022450 -0.090250 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.023575 -0.089949 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.024399 -0.089125 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.020200 -0.088000 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.020501 -0.086875 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.085525 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.021325 -0.089949 0.071250 -vn -0.552288 0.318864 -0.770262 -v -0.020501 -0.089125 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.090225 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.021325 -0.086051 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.022450 -0.085750 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.023575 -0.086051 0.071250 -vn 0.552289 -0.318864 -0.770262 -v -0.024399 -0.086875 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.024700 -0.088000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.095500 0.071250 -vn -0.000001 0.637727 -0.770262 -v -0.000450 -0.090250 0.071250 -vn -0.318865 0.552288 -0.770262 -v 0.000675 -0.089949 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.002700 -0.088000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.002399 -0.089125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.001575 -0.089949 0.071250 -vn 0.552289 -0.318864 -0.770262 -v -0.002399 -0.086875 0.071250 -vn -0.552289 0.318864 -0.770262 -v 0.001499 -0.089125 0.071250 -vn -0.637728 0.000000 -0.770262 -v 0.001800 -0.088000 0.071250 -vn -0.552288 -0.318864 -0.770262 -v 0.001499 -0.086875 0.071250 -vn -0.318865 -0.552288 -0.770262 -v 0.000675 -0.086051 0.071250 -vn -0.000001 -0.637728 -0.770262 -v -0.000450 -0.085750 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.001575 -0.086051 0.071250 -vn -0.318860 -0.552289 -0.770263 -v -0.072950 -0.051217 0.071250 -vn 0.000000 -0.637731 -0.770259 -v -0.073450 -0.051083 0.071250 -vn 0.318860 -0.552289 -0.770263 -v -0.073950 -0.051217 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.074316 -0.051583 0.071250 -vn -0.508111 -0.426354 -0.748361 -v -0.077918 -0.050797 0.071250 -vn -0.552288 0.318865 -0.770262 -v -0.072584 -0.057083 0.071250 -vn -0.669352 0.088123 -0.737701 -v -0.072450 -0.056583 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.048666 0.071250 -vn -0.669352 -0.088123 -0.737701 -v -0.072450 -0.052083 0.071250 -vn -0.552288 -0.318865 -0.770261 -v -0.072584 -0.051583 0.071250 -vn -0.623292 -0.226860 -0.748359 -v -0.077571 -0.051399 0.071250 -vn 0.669352 -0.088123 -0.737701 -v -0.074450 -0.052083 0.071250 -vn -0.683749 -0.059822 -0.727261 -v -0.077450 -0.052083 0.071250 -vn 0.669352 0.088123 -0.737701 -v -0.074450 -0.056583 0.071250 -vn -0.707107 0.000000 -0.707106 -v -0.077450 -0.074609 0.071250 -vn 0.552288 0.318865 -0.770261 -v -0.074316 -0.057083 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 -0.074609 0.071250 -vn 0.318865 0.552288 -0.770262 -v -0.073950 -0.057449 0.071250 -vn 0.144416 -0.632728 -0.760789 -v -0.073673 -0.074442 0.071250 -vn -0.144416 -0.632728 -0.760789 -v -0.073227 -0.074442 0.071250 -vn 0.000000 0.637727 -0.770262 -v -0.073450 -0.057583 0.071250 -vn -0.404643 -0.507412 -0.760787 -v -0.072827 -0.074635 0.071250 -vn -0.318865 0.552288 -0.770261 -v -0.072950 -0.057449 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.074609 0.071250 -vn 0.318857 0.552286 -0.770266 -v -0.073950 0.051217 0.071250 -vn 0.000000 0.637736 -0.770255 -v -0.073450 0.051083 0.071250 -vn -0.669353 -0.088122 -0.737700 -v -0.072450 0.056583 0.071250 -vn -0.552286 -0.318866 -0.770263 -v -0.072584 0.057083 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.066000 0.071250 -vn -0.318863 -0.552291 -0.770260 -v -0.072950 0.057449 0.071250 -vn -0.000000 -0.637727 -0.770262 -v -0.073450 0.057583 0.071250 -vn 0.318863 -0.552291 -0.770260 -v -0.073950 0.057449 0.071250 -vn 0.552286 -0.318866 -0.770263 -v -0.074316 0.057083 0.071250 -vn -0.683749 0.059822 -0.727261 -v -0.077450 0.052083 0.071250 -vn 0.669353 -0.088122 -0.737700 -v -0.074450 0.056583 0.071250 -vn 0.669352 0.088124 -0.737701 -v -0.074450 0.052083 0.071250 -vn -0.318857 0.552286 -0.770266 -v -0.072950 0.051217 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.048666 0.071250 -vn -0.552291 0.318864 -0.770260 -v -0.072584 0.051583 0.071250 -vn -0.669351 0.088124 -0.737701 -v -0.072450 0.052083 0.071250 -vn -0.318865 0.552288 -0.770261 -v -0.072950 -0.080783 0.071250 -vn -0.552288 0.318865 -0.770262 -v -0.072584 -0.080417 0.071250 -vn 0.000000 0.637727 -0.770262 -v -0.073450 -0.080917 0.071250 -vn 0.404643 -0.507413 -0.760787 -v -0.074073 -0.074635 0.071250 -vn 0.584725 -0.281595 -0.760790 -v -0.074351 -0.074983 0.071250 -vn 0.675739 -0.076139 -0.733198 -v -0.074450 -0.075417 0.071250 -vn -0.669352 0.088123 -0.737701 -v -0.077450 -0.079917 0.071250 -vn 0.669352 0.088123 -0.737701 -v -0.074450 -0.079917 0.071250 -vn 0.552288 0.318865 -0.770261 -v -0.074316 -0.080417 0.071250 -vn 0.318865 0.552288 -0.770262 -v -0.073950 -0.080783 0.071250 -vn -0.669352 0.088123 -0.737701 -v -0.072450 -0.079917 0.071250 -vn -0.675739 -0.076139 -0.733198 -v -0.072450 -0.075417 0.071250 -vn -0.584725 -0.281595 -0.760790 -v -0.072549 -0.074983 0.071250 -vn 0.000000 0.637727 -0.770262 -v -0.073450 0.074417 0.071250 -vn -0.669353 -0.088122 -0.737700 -v -0.072450 0.079917 0.071250 -vn -0.552286 -0.318866 -0.770263 -v -0.072584 0.080417 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.083109 0.071250 -vn -0.552288 -0.318865 -0.770262 -v -0.077718 0.080917 0.071250 -vn 0.318863 -0.552291 -0.770260 -v -0.073950 0.080783 0.071250 -vn -0.000000 -0.637727 -0.770262 -v -0.073450 0.080917 0.071250 -vn -0.318863 -0.552291 -0.770260 -v -0.072950 0.080783 0.071250 -vn -0.318863 0.552291 -0.770260 -v -0.072950 0.074551 0.071250 -vn -0.552286 0.318866 -0.770263 -v -0.072584 0.074917 0.071250 -vn -0.669353 0.088122 -0.737700 -v -0.072450 0.075417 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.077200 0.103000 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.077501 0.104125 0.071250 -vn -0.000001 0.637729 -0.770261 -v -0.079450 0.100750 0.071250 -vn -0.318862 0.552289 -0.770262 -v -0.078325 0.101051 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.095500 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.077501 0.101875 0.071250 -vn 0.318866 -0.552289 -0.770261 -v -0.080575 0.104949 0.071250 -vn -0.000000 -0.637726 -0.770263 -v -0.079450 0.105250 0.071250 -vn -0.318867 -0.552288 -0.770261 -v -0.078325 0.104949 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.077450 0.090250 0.071250 -vn 0.318862 0.552289 -0.770262 -v -0.080575 0.101051 0.071250 -vn 0.552289 -0.318865 -0.770261 -v -0.081399 0.104125 0.071250 -vn 0.637728 -0.000001 -0.770261 -v -0.081700 0.103000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.081399 0.101875 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.054325 0.089949 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 0.109000 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.083109 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.083109 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.066000 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.066000 0.071250 -vn 0.552287 0.318863 -0.770263 -v 0.026628 0.076025 0.071250 -vn 0.318864 0.552290 -0.770261 -v 0.027525 0.075128 0.071250 -vn -0.318864 0.552290 -0.770261 -v 0.029975 0.075128 0.071250 -vn -0.552287 0.318865 -0.770262 -v 0.030872 0.076025 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 0.066000 0.071250 -vn -0.637727 -0.000001 -0.770263 -v 0.031200 0.077250 0.071250 -vn -0.552290 -0.318865 -0.770261 -v 0.030872 0.078475 0.071250 -vn -0.318862 -0.552288 -0.770263 -v 0.029975 0.079372 0.071250 -vn 0.000000 -0.637730 -0.770260 -v 0.028750 0.079700 0.071250 -vn 0.000000 0.637727 -0.770263 -v 0.028750 0.074800 0.071250 -vn 0.318862 -0.552288 -0.770263 -v 0.027525 0.079372 0.071250 -vn 0.552290 -0.318863 -0.770261 -v 0.026628 0.078475 0.071250 -vn 0.637729 -0.000001 -0.770261 -v 0.026300 0.077250 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.048666 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.048666 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.066000 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.048666 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.055450 0.046250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.056575 0.045949 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.053501 0.042875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.053200 0.044000 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.053501 0.045125 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.054325 0.045949 0.071250 -vn -0.318862 0.552288 -0.770263 -v -0.054325 0.042051 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.033000 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.055450 0.041750 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.033000 0.071250 -vn 0.318861 0.552289 -0.770262 -v -0.056575 0.042051 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.057399 0.045125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.057700 0.044000 0.071250 -vn 0.552288 0.318864 -0.770262 -v -0.057399 0.042875 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.020501 0.045125 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.021325 0.045949 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.022450 0.046250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.023575 0.045949 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.024399 0.045125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.024700 0.044000 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.024399 0.042875 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.023575 0.042051 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.033000 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.022450 0.041750 0.071250 -vn -0.318862 0.552289 -0.770263 -v -0.021325 0.042051 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.020501 0.042875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.020200 0.044000 0.071250 -vn -0.552289 0.318863 -0.770262 -v 0.001499 0.042875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v 0.001800 0.044000 0.071250 -vn -0.552288 -0.318865 -0.770262 -v 0.001499 0.045125 0.071250 -vn -0.318867 -0.552288 -0.770261 -v 0.000675 0.045949 0.071250 -vn -0.000001 -0.637726 -0.770264 -v -0.000450 0.046250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.001575 0.045949 0.071250 -vn -0.318862 0.552289 -0.770262 -v 0.000675 0.042051 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.033000 0.071250 -vn -0.000001 0.637729 -0.770261 -v -0.000450 0.041750 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.001575 0.042051 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.002399 0.045125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.002700 0.044000 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.002399 0.042875 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.071485 0.017562 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.072610 0.017261 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.071485 0.013062 0.071250 -vn -0.318862 0.552289 -0.770263 -v -0.070360 0.013364 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 0.007656 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.070360 0.017261 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 0.007656 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.072610 0.013364 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.069536 0.014187 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.069235 0.015312 0.071250 -vn -0.552288 -0.318865 -0.770262 -v -0.069536 0.016437 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.073433 0.016437 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.073735 0.015312 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.073433 0.014187 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.053501 0.023125 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.054325 0.023949 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.055450 0.024250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.056575 0.023949 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.057399 0.020875 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.057700 0.022000 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.057399 0.023125 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.056575 0.020051 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.055450 0.019750 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 0.007656 0.071250 -vn -0.318862 0.552289 -0.770263 -v -0.054325 0.020051 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.053501 0.020875 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.053200 0.022000 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.023575 0.023949 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.022450 0.024250 0.071250 -vn -0.318866 -0.552289 -0.770261 -v -0.021325 0.023949 0.071250 -vn -0.552288 -0.318865 -0.770262 -v -0.020501 0.023125 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.024399 0.023125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.024700 0.022000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.024399 0.020875 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.023575 0.020051 0.071250 -vn -0.000000 0.637730 -0.770260 -v -0.022450 0.019750 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 0.007656 0.071250 -vn -0.318862 0.552288 -0.770263 -v -0.021325 0.020051 0.071250 -vn -0.552289 0.318863 -0.770262 -v -0.020501 0.020875 0.071250 -vn -0.637728 -0.000002 -0.770262 -v -0.020200 0.022000 0.071250 -vn -0.637728 -0.000001 -0.770262 -v 0.001800 0.022000 0.071250 -vn -0.552289 0.318863 -0.770262 -v 0.001499 0.020875 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 0.007656 0.071250 -vn -0.318862 0.552289 -0.770262 -v 0.000675 0.020051 0.071250 -vn -0.000001 0.637729 -0.770260 -v -0.000450 0.019750 0.071250 -vn -0.552288 -0.318865 -0.770262 -v 0.001499 0.023125 0.071250 -vn -0.318867 -0.552288 -0.770261 -v 0.000675 0.023949 0.071250 -vn -0.000001 -0.637726 -0.770264 -v -0.000450 0.024250 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.001575 0.023949 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.002399 0.023125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.002700 0.022000 0.071250 -vn 0.552289 0.318863 -0.770262 -v -0.002399 0.020875 0.071250 -vn 0.318862 0.552289 -0.770263 -v -0.001575 0.020051 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.074092 -0.007344 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.007344 0.071250 -vn -0.637728 -0.000001 -0.770262 -v -0.053200 -0.000000 0.071250 -vn -0.552288 -0.318865 -0.770262 -v -0.053501 0.001125 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.054325 0.001949 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.055450 0.002250 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.063467 -0.007344 0.071250 -vn 0.552288 0.318864 -0.770262 -v -0.057399 -0.001125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.056575 -0.001949 0.071250 -vn -0.000000 0.637728 -0.770262 -v -0.055450 -0.002250 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.054325 -0.001949 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.053501 -0.001125 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.056575 0.001949 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.057399 0.001125 0.071250 -vn 0.637727 -0.000001 -0.770262 -v -0.057700 -0.000000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.024399 -0.001125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.023575 -0.001949 0.071250 -vn -0.000000 0.637728 -0.770262 -v -0.022450 -0.002250 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.021325 -0.001949 0.071250 -vn -0.318866 -0.552288 -0.770261 -v -0.021325 0.001949 0.071250 -vn 0.000000 -0.637726 -0.770263 -v -0.022450 0.002250 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.020501 -0.001125 0.071250 -vn -0.637727 -0.000001 -0.770262 -v -0.020200 0.000000 0.071250 -vn -0.552288 -0.318865 -0.770262 -v -0.020501 0.001125 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.023575 0.001949 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.024399 0.001125 0.071250 -vn 0.637727 -0.000001 -0.770262 -v -0.024700 0.000000 0.071250 -vn -0.000001 -0.637726 -0.770264 -v -0.000450 0.002250 0.071250 -vn -0.318867 -0.552288 -0.770261 -v 0.000675 0.001949 0.071250 -vn 0.318866 -0.552288 -0.770261 -v -0.001575 0.001949 0.071250 -vn 0.552288 -0.318865 -0.770262 -v -0.002399 0.001125 0.071250 -vn 0.637728 -0.000001 -0.770262 -v -0.002700 0.000000 0.071250 -vn 0.552288 0.318864 -0.770262 -v -0.002399 -0.001125 0.071250 -vn -0.318865 0.552288 -0.770262 -v 0.000675 -0.001949 0.071250 -vn -0.000001 0.637728 -0.770262 -v -0.000450 -0.002250 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.001575 -0.001949 0.071250 -vn -0.552289 0.318864 -0.770262 -v 0.001499 -0.001125 0.071250 -vn -0.637728 -0.000001 -0.770262 -v 0.001800 0.000000 0.071250 -vn -0.552288 -0.318865 -0.770262 -v 0.001499 0.001125 0.071250 -vn 0.637728 0.000001 -0.770262 -v -0.073735 -0.014688 0.071250 -vn 0.552288 0.318864 -0.770262 -v -0.073433 -0.015813 0.071250 -vn -0.637728 0.000001 -0.770262 -v -0.069235 -0.014688 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.069536 -0.013563 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.070360 -0.012739 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.071485 -0.012438 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.072610 -0.012739 0.071250 -vn 0.552289 -0.318864 -0.770262 -v -0.073433 -0.013563 0.071250 -vn 0.318864 0.552288 -0.770262 -v -0.072610 -0.016636 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.071485 -0.016938 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.070360 -0.016636 0.071250 -vn -0.552288 0.318865 -0.770262 -v -0.069536 -0.015813 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.018344 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.056575 -0.023949 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.055450 -0.024250 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.053501 -0.020875 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.054325 -0.020051 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.055450 -0.019750 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.056575 -0.020051 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.033000 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.054325 -0.023949 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.053501 -0.023125 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.053200 -0.022000 0.071250 -vn 0.552289 -0.318864 -0.770262 -v -0.057399 -0.020875 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.057700 -0.022000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.057399 -0.023125 0.071250 -vn -0.552288 -0.318865 -0.770262 -v -0.020501 -0.020875 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.021325 -0.020051 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.018344 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.023575 -0.023949 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.033000 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.022450 -0.024250 0.071250 -vn -0.318864 0.552288 -0.770262 -v -0.021325 -0.023949 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.020501 -0.023125 0.071250 -vn -0.637728 -0.000000 -0.770262 -v -0.020200 -0.022000 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.022450 -0.019750 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.023575 -0.020051 0.071250 -vn 0.552289 -0.318863 -0.770262 -v -0.024399 -0.020875 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.024700 -0.022000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.024399 -0.023125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.001575 -0.023949 0.071250 -vn -0.000001 0.637728 -0.770262 -v -0.000450 -0.024250 0.071250 -vn -0.000001 -0.637728 -0.770262 -v -0.000450 -0.019750 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.001575 -0.020051 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.033000 0.071250 -vn -0.552288 -0.318864 -0.770262 -v 0.001499 -0.020875 0.071250 -vn -0.318865 -0.552288 -0.770262 -v 0.000675 -0.020051 0.071250 -vn 0.552288 -0.318864 -0.770262 -v -0.002399 -0.020875 0.071250 -vn 0.637728 -0.000000 -0.770262 -v -0.002700 -0.022000 0.071250 -vn 0.552288 0.318864 -0.770262 -v -0.002399 -0.023125 0.071250 -vn -0.318864 0.552288 -0.770262 -v 0.000675 -0.023949 0.071250 -vn -0.552288 0.318864 -0.770262 -v 0.001499 -0.023125 0.071250 -vn -0.637728 -0.000000 -0.770262 -v 0.001800 -0.022000 0.071250 -vn 0.318864 -0.552288 -0.770262 -v -0.056575 -0.042051 0.071250 -vn 0.552289 -0.318863 -0.770262 -v -0.057399 -0.042875 0.071250 -vn -0.552288 -0.318864 -0.770262 -v -0.053501 -0.042875 0.071250 -vn -0.318863 -0.552289 -0.770262 -v -0.054325 -0.042051 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.055450 -0.041750 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.057700 -0.044000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.057399 -0.045125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.056575 -0.045949 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.055450 -0.046250 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.054325 -0.045949 0.071250 -vn -0.318864 0.552289 -0.770262 -v -0.021325 -0.045949 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.048666 0.071250 -vn 0.000000 0.637728 -0.770262 -v -0.022450 -0.046250 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.020501 -0.045125 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.020200 -0.044000 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.020501 -0.042875 0.071250 -vn 0.552288 -0.318864 -0.770262 -v -0.024399 -0.042875 0.071250 -vn 0.637728 0.000000 -0.770262 -v -0.024700 -0.044000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.024399 -0.045125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.023575 -0.045949 0.071250 -vn -0.318864 -0.552289 -0.770262 -v -0.021325 -0.042051 0.071250 -vn 0.000000 -0.637728 -0.770262 -v -0.022450 -0.041750 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.023575 -0.042051 0.071250 -vn -0.552288 0.318864 -0.770262 -v 0.001499 -0.045125 0.071250 -vn -0.637728 -0.000000 -0.770262 -v 0.001800 -0.044000 0.071250 -vn 0.552288 0.318864 -0.770262 -v -0.002399 -0.045125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.001575 -0.045949 0.071250 -vn -0.000001 0.637728 -0.770262 -v -0.000450 -0.046250 0.071250 -vn -0.318864 0.552288 -0.770262 -v 0.000675 -0.045949 0.071250 -vn -0.000001 -0.637727 -0.770262 -v -0.000450 -0.041750 0.071250 -vn -0.318865 -0.552288 -0.770262 -v 0.000675 -0.042051 0.071250 -vn -0.552288 -0.318864 -0.770262 -v 0.001499 -0.042875 0.071250 -vn 0.318864 -0.552289 -0.770262 -v -0.001575 -0.042051 0.071250 -vn 0.552289 -0.318864 -0.770262 -v -0.002399 -0.042875 0.071250 -vn 0.637728 -0.000000 -0.770262 -v -0.002700 -0.044000 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.011450 -0.074609 0.071250 -vn 0.000000 0.000000 -1.000000 -v -0.038950 -0.074609 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.032975 -0.095500 0.071250 -vn 0.000000 0.000000 -1.000000 -v 0.014050 -0.095500 0.071250 -vn -0.637728 0.000000 -0.770262 -v -0.077200 -0.103000 0.071250 -vn -0.552289 -0.318864 -0.770262 -v -0.077501 -0.101875 0.071250 -vn -0.318865 -0.552288 -0.770262 -v -0.078325 -0.101051 0.071250 -vn -0.000000 -0.637728 -0.770262 -v -0.079450 -0.100750 0.071250 -vn -0.318864 0.552288 -0.770262 -v -0.078325 -0.104949 0.071250 -vn -0.552289 0.318864 -0.770262 -v -0.077501 -0.104125 0.071250 -vn 0.318864 -0.552289 -0.770261 -v -0.080575 -0.101051 0.071250 -vn 0.552289 -0.318864 -0.770261 -v -0.081399 -0.101875 0.071250 -vn 0.637728 -0.000000 -0.770261 -v -0.081700 -0.103000 0.071250 -vn 0.552289 0.318864 -0.770262 -v -0.081399 -0.104125 0.071250 -vn 0.318864 0.552289 -0.770262 -v -0.080575 -0.104949 0.071250 -vn -0.000001 0.637728 -0.770262 -v -0.079450 -0.105250 0.071250 -vn -0.678874 -0.095839 0.727973 -v 0.034750 0.054309 0.092600 -vn 0.678874 -0.095839 0.727973 -v 0.038750 0.054309 0.092600 -vn -0.707107 0.000000 0.707107 -v 0.034750 0.070000 0.092600 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.070000 0.092600 -vn -0.707107 0.000000 0.707107 -v 0.034750 0.093750 0.092600 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.093750 0.092600 -vn -0.707107 0.000000 0.707107 -v 0.034750 0.108700 0.092600 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.108700 0.092600 -vn -0.678874 0.095840 0.727973 -v 0.034750 0.114000 0.092600 -vn 0.678874 0.095840 0.727973 -v 0.038750 0.114000 0.092600 -vn 0.737700 0.088122 -0.669353 -v 0.038750 0.057993 0.067600 -vn -0.737700 0.088122 -0.669353 -v 0.034750 0.057993 0.067600 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.070000 0.067600 -vn -0.707107 0.000000 -0.707107 -v 0.034750 0.070000 0.067600 -vn 0.729849 -0.067005 -0.680317 -v 0.038750 0.078858 0.067600 -vn -0.729849 -0.067005 -0.680317 -v 0.034750 0.078858 0.067600 -vn -0.737700 -0.088122 -0.669352 -v 0.034750 -0.057993 0.067600 -vn 0.737700 -0.088122 -0.669352 -v 0.038750 -0.057993 0.067600 -vn -0.707107 0.000000 -0.707107 -v 0.034750 -0.070000 0.067600 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.070000 0.067600 -vn -0.729849 0.067005 -0.680317 -v 0.034750 -0.078858 0.067600 -vn 0.729849 0.067005 -0.680317 -v 0.038750 -0.078858 0.067600 -vn 0.678875 -0.727973 0.095839 -v 0.038750 -0.120000 0.086600 -vn -0.678875 -0.727973 0.095839 -v 0.034750 -0.120000 0.086600 -vn 0.707107 -0.707107 0.000000 -v 0.038750 -0.120000 0.074300 -vn -0.707107 -0.707107 0.000000 -v 0.034750 -0.120000 0.074300 -vn 0.707107 -0.707107 0.000000 -v 0.038750 -0.120000 0.069050 -vn -0.707107 -0.707107 0.000000 -v 0.034750 -0.120000 0.069050 -vn 0.707107 -0.707107 0.000000 -v 0.038750 -0.120000 0.060800 -vn -0.707107 -0.707107 -0.000000 -v 0.034750 -0.120000 0.060800 -vn 0.707107 -0.707107 0.000000 -v 0.038750 -0.120000 0.036850 -vn -0.707107 -0.707107 -0.000000 -v 0.034750 -0.120000 0.036850 -vn 0.678875 -0.727973 -0.095839 -v 0.038750 -0.120000 0.009000 -vn -0.678875 -0.727973 -0.095839 -v 0.034750 -0.120000 0.009000 -vn 0.678874 -0.095839 -0.727973 -v 0.038750 -0.114000 0.003000 -vn -0.678874 -0.095839 -0.727973 -v 0.034750 -0.114000 0.003000 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.103800 0.003000 -vn -0.707107 0.000000 -0.707107 -v 0.034750 -0.103800 0.003000 -vn 0.678874 0.095839 -0.727973 -v 0.038750 -0.101000 0.003000 -vn -0.678874 0.095839 -0.727973 -v 0.034750 -0.101000 0.003000 -vn -0.729849 0.680317 -0.067006 -v 0.034750 -0.095000 0.051458 -vn 0.729849 0.680317 -0.067006 -v 0.038750 -0.095000 0.051458 -vn -0.707107 0.707107 -0.000000 -v 0.034750 -0.095000 0.036850 -vn 0.707107 0.707107 0.000000 -v 0.038750 -0.095000 0.036850 -vn -0.678875 0.727973 -0.095839 -v 0.034750 -0.095000 0.009000 -vn 0.678875 0.727973 -0.095839 -v 0.038750 -0.095000 0.009000 -vn 0.729849 0.433677 -0.528437 -v 0.038750 -0.085929 0.064671 -vn 0.729849 0.528437 -0.433677 -v 0.038750 -0.092071 0.058529 -vn -0.729849 0.433677 -0.528437 -v 0.034750 -0.085929 0.064671 -vn -0.729849 0.528437 -0.433677 -v 0.034750 -0.092071 0.058529 -vn 0.729849 -0.528437 -0.433677 -v 0.038750 0.092071 0.058529 -vn 0.729849 -0.433676 -0.528437 -v 0.038750 0.085929 0.064671 -vn -0.729849 -0.528437 -0.433677 -v 0.034750 0.092071 0.058529 -vn -0.729849 -0.433676 -0.528437 -v 0.034750 0.085929 0.064671 -vn 0.729849 -0.680317 -0.067005 -v 0.038750 0.095000 0.051458 -vn -0.729849 -0.680317 -0.067005 -v 0.034750 0.095000 0.051458 -vn 0.707107 -0.707107 0.000000 -v 0.038750 0.095000 0.036850 -vn -0.707107 -0.707107 -0.000000 -v 0.034750 0.095000 0.036850 -vn 0.678874 -0.727973 -0.095840 -v 0.038750 0.095000 0.009000 -vn -0.678874 -0.727973 -0.095840 -v 0.034750 0.095000 0.009000 -vn 0.678874 -0.095839 -0.727973 -v 0.038750 0.101000 0.003000 -vn -0.678875 -0.095839 -0.727973 -v 0.034750 0.101000 0.003000 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.108700 0.003000 -vn -0.707107 0.000000 -0.707107 -v 0.034750 0.108700 0.003000 -vn 0.678874 0.095839 -0.727973 -v 0.038750 0.114000 0.003000 -vn -0.678874 0.095839 -0.727973 -v 0.034750 0.114000 0.003000 -vn 0.678875 0.727973 -0.095839 -v 0.038750 0.120000 0.009000 -vn -0.678875 0.727973 -0.095839 -v 0.034750 0.120000 0.009000 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.120000 0.036850 -vn -0.707107 0.707107 -0.000000 -v 0.034750 0.120000 0.036850 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.120000 0.060800 -vn -0.707107 0.707107 -0.000000 -v 0.034750 0.120000 0.060800 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.120000 0.069050 -vn -0.707107 0.707107 0.000000 -v 0.034750 0.120000 0.069050 -vn 0.707107 0.707107 0.000000 -v 0.038750 0.120000 0.074300 -vn -0.707107 0.707107 0.000000 -v 0.034750 0.120000 0.074300 -vn 0.678875 0.727973 0.095839 -v 0.038750 0.120000 0.086600 -vn -0.678875 0.727973 0.095839 -v 0.034750 0.120000 0.086600 -vn 0.678875 0.095839 0.727973 -v 0.038750 -0.054309 0.092600 -vn -0.678875 0.095839 0.727973 -v 0.034750 -0.054309 0.092600 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.070000 0.092600 -vn -0.707107 0.000000 0.707107 -v 0.034750 -0.070000 0.092600 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.093750 0.092600 -vn -0.707107 0.000000 0.707107 -v 0.034750 -0.093750 0.092600 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.103800 0.092600 -vn -0.707107 0.000000 0.707107 -v 0.034750 -0.103800 0.092600 -vn 0.678874 -0.095840 0.727973 -v 0.038750 -0.114000 0.092600 -vn -0.678874 -0.095840 0.727973 -v 0.034750 -0.114000 0.092600 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.093750 0.069050 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.093750 0.060800 -vn 1.000000 -0.000000 0.000000 -v 0.038750 0.108700 0.060800 -vn 1.000000 -0.000000 0.000000 -v 0.038750 0.108700 0.036850 -vn 0.770261 0.318864 -0.552289 -v 0.038750 -0.040000 0.068446 -vn 0.770262 0.000001 -0.637728 -v 0.038750 -0.037000 0.069250 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.049025 0.069050 -vn 0.737700 0.535615 -0.410992 -v 0.038750 0.054529 0.065600 -vn 1.000000 0.000000 -0.000000 -v 0.038750 0.049025 0.060800 -vn 0.678874 0.582523 -0.446986 -v 0.038750 0.046655 0.051961 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.070000 0.069050 -vn 0.653227 -0.378582 0.655722 -v 0.038750 0.052309 0.092064 -vn 0.678875 -0.582523 0.446985 -v 0.038750 0.050845 0.090600 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.093750 0.060800 -vn 0.753767 0.607119 -0.251478 -v 0.038750 -0.094239 0.055285 -vn 0.770262 -0.552289 0.318864 -v 0.038750 0.109622 0.080575 -vn 0.770262 -0.318864 0.552288 -v 0.038750 0.108725 0.079678 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.108700 0.074300 -vn 0.770261 -0.318865 -0.552290 -v 0.038750 0.108725 0.083922 -vn 0.770263 -0.552287 -0.318864 -v 0.038750 0.109622 0.083025 -vn 0.653226 0.655722 0.378581 -v 0.038750 0.119196 0.089600 -vn 0.770261 -0.637728 0.000000 -v 0.038750 0.109950 0.081800 -vn 0.770261 -0.000000 0.637728 -v 0.038750 0.107500 0.079350 -vn 0.770263 0.318864 0.552287 -v 0.038750 0.106275 0.079678 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.093750 0.074300 -vn 0.770261 0.552290 0.318865 -v 0.038750 0.105378 0.080575 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.093750 0.088425 -vn 0.770263 0.637727 0.000000 -v 0.038750 0.105050 0.081800 -vn 0.770261 0.552288 -0.318865 -v 0.038750 0.105378 0.083025 -vn 0.770261 0.318865 -0.552288 -v 0.038750 0.106275 0.083922 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.108700 0.088425 -vn 0.770263 -0.000000 -0.637727 -v 0.038750 0.107500 0.084250 -vn 0.770263 0.318864 -0.552287 -v 0.038750 -0.106225 0.016122 -vn 0.770262 -0.000001 -0.637728 -v 0.038750 -0.105000 0.016450 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.103800 0.036850 -vn 0.770261 0.552290 -0.318864 -v 0.038750 -0.107122 0.015225 -vn 0.770263 0.637727 0.000000 -v 0.038750 -0.107450 0.014000 -vn 0.770261 0.552290 0.318864 -v 0.038750 -0.107122 0.012775 -vn 0.653227 -0.655722 -0.378580 -v 0.038750 -0.119196 0.006000 -vn 0.653227 -0.378581 -0.655722 -v 0.038750 -0.117000 0.003804 -vn 0.770263 0.318864 0.552287 -v 0.038750 -0.106225 0.011878 -vn 0.770262 -0.000001 0.637728 -v 0.038750 -0.105000 0.011550 -vn 0.770261 -0.318864 0.552289 -v 0.038750 -0.103775 0.011878 -vn 0.770261 -0.318864 -0.552289 -v 0.038750 -0.103775 0.016122 -vn 0.770263 -0.552288 -0.318862 -v 0.038750 -0.102878 0.015225 -vn 0.770263 -0.552288 0.318862 -v 0.038750 -0.102878 0.012775 -vn 0.653227 0.378581 -0.655722 -v 0.038750 -0.098000 0.003804 -vn 0.770260 -0.637730 0.000000 -v 0.038750 -0.102550 0.014000 -vn 0.653227 0.655722 -0.378580 -v 0.038750 -0.095804 0.006000 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.070000 0.069050 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.093750 0.069050 -vn 0.753767 0.251477 -0.607120 -v 0.038750 -0.082685 0.066839 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.103800 0.060800 -vn 0.770262 -0.318865 -0.552287 -v 0.038750 -0.106275 0.083922 -vn 0.770261 -0.552290 -0.318864 -v 0.038750 -0.105378 0.083025 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.103800 0.088425 -vn 0.770263 -0.637727 0.000000 -v 0.038750 -0.105050 0.081800 -vn 0.653227 -0.655722 0.378581 -v 0.038750 -0.119196 0.089600 -vn 0.770261 0.318865 -0.552290 -v 0.038750 -0.108725 0.083922 -vn 0.770263 0.000001 -0.637727 -v 0.038750 -0.107500 0.084250 -vn 0.770260 -0.552291 0.318864 -v 0.038750 -0.105378 0.080575 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.103800 0.074300 -vn 0.770263 -0.318864 0.552286 -v 0.038750 -0.106275 0.079678 -vn 0.770261 0.000001 0.637729 -v 0.038750 -0.107500 0.079350 -vn 0.770262 0.318864 0.552289 -v 0.038750 -0.108725 0.079678 -vn 0.770263 0.552289 0.318862 -v 0.038750 -0.109622 0.080575 -vn 0.770260 0.637730 0.000000 -v 0.038750 -0.109950 0.081800 -vn 0.770263 0.552288 -0.318862 -v 0.038750 -0.109622 0.083025 -vn 0.770262 0.318865 -0.552287 -v 0.038750 -0.058725 0.083922 -vn 0.770263 -0.000001 -0.637727 -v 0.038750 -0.057500 0.084250 -vn 0.678875 0.582523 0.446985 -v 0.038750 -0.050845 0.090600 -vn 0.770261 0.552290 -0.318864 -v 0.038750 -0.059622 0.083025 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.070000 0.088425 -vn 0.653226 0.378582 0.655722 -v 0.038750 -0.052309 0.092064 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.070000 0.074300 -vn 0.770260 0.552291 0.318864 -v 0.038750 -0.059622 0.080575 -vn 0.770263 0.637727 0.000000 -v 0.038750 -0.059950 0.081800 -vn 0.770260 -0.637730 0.000000 -v 0.038750 -0.055050 0.081800 -vn 0.727261 0.562235 0.393680 -v 0.038750 -0.042971 0.076961 -vn 0.770263 -0.552288 -0.318862 -v 0.038750 -0.055378 0.083025 -vn 0.770261 -0.318865 -0.552290 -v 0.038750 -0.056275 0.083922 -vn 0.770263 -0.552289 0.318862 -v 0.038750 -0.055378 0.080575 -vn 0.770262 -0.318864 0.552288 -v 0.038750 -0.056275 0.079678 -vn 1.000000 0.000000 -0.000000 -v 0.038750 -0.049025 0.074300 -vn 0.770261 -0.000001 0.637729 -v 0.038750 -0.057500 0.079350 -vn 0.770263 0.318864 0.552286 -v 0.038750 -0.058725 0.079678 -vn 0.748360 0.426357 0.508111 -v 0.038750 -0.042078 0.075897 -vn 0.748360 0.226860 0.623291 -v 0.038750 -0.040875 0.075202 -vn 0.727259 0.059821 0.683751 -v 0.038750 -0.039507 0.074961 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.020250 0.074300 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.020250 0.074961 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.049025 0.074300 -vn 0.737702 -0.088122 0.669351 -v 0.038750 0.039507 0.074961 -vn 1.000000 0.000000 -0.000000 -v 0.038750 0.000000 0.074300 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.000000 0.074961 -vn 0.770263 -0.000000 -0.637727 -v 0.038750 0.057500 0.084250 -vn 0.770261 -0.318865 -0.552289 -v 0.038750 0.058725 0.083922 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.070000 0.088425 -vn 0.770262 -0.552288 -0.318865 -v 0.038750 0.059622 0.083025 -vn 0.770262 -0.637727 0.000000 -v 0.038750 0.059950 0.081800 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.070000 0.074300 -vn 0.770261 -0.552289 0.318864 -v 0.038750 0.059622 0.080575 -vn 0.770262 -0.318864 0.552288 -v 0.038750 0.058725 0.079678 -vn 0.770261 -0.000000 0.637728 -v 0.038750 0.057500 0.079350 -vn 0.770263 0.318864 0.552287 -v 0.038750 0.056275 0.079678 -vn 0.737700 -0.535616 0.410993 -v 0.038750 0.042971 0.076961 -vn 0.770262 -0.318864 0.552288 -v 0.038750 0.041507 0.075497 -vn 0.770261 0.552290 0.318864 -v 0.038750 0.055378 0.080575 -vn 0.770262 0.637727 0.000000 -v 0.038750 0.055050 0.081800 -vn 0.770262 0.552289 -0.318864 -v 0.038750 0.055378 0.083025 -vn 0.770261 0.318865 -0.552288 -v 0.038750 0.056275 0.083922 -vn 0.653227 0.378581 0.655722 -v 0.038750 0.117000 0.091796 -vn 0.653227 0.378581 -0.655722 -v 0.038750 0.117000 0.003804 -vn 0.653227 0.655722 -0.378581 -v 0.038750 0.119196 0.006000 -vn 0.770261 0.318864 -0.552289 -v 0.038750 0.103775 0.016122 -vn 0.770262 0.000000 -0.637728 -v 0.038750 0.105000 0.016450 -vn 0.770262 -0.318863 -0.552289 -v 0.038750 0.106225 0.016122 -vn 0.770262 -0.552288 -0.318864 -v 0.038750 0.107122 0.015225 -vn 0.770261 -0.637728 0.000000 -v 0.038750 0.107450 0.014000 -vn 0.770262 -0.552288 0.318864 -v 0.038750 0.107122 0.012775 -vn 0.770262 0.552288 -0.318864 -v 0.038750 0.102878 0.015225 -vn 0.770261 0.637728 -0.000000 -v 0.038750 0.102550 0.014000 -vn 0.770262 0.552288 0.318864 -v 0.038750 0.102878 0.012775 -vn 0.653227 -0.655722 -0.378581 -v 0.038750 0.095804 0.006000 -vn 0.770261 0.318864 0.552289 -v 0.038750 0.103775 0.011878 -vn 0.770262 -0.318863 0.552289 -v 0.038750 0.106225 0.011878 -vn 0.770262 0.000001 0.637728 -v 0.038750 0.105000 0.011550 -vn 0.653227 -0.378581 -0.655722 -v 0.038750 0.098000 0.003804 -vn 0.753767 -0.607120 -0.251477 -v 0.038750 0.094239 0.055285 -vn 0.753767 -0.251477 -0.607120 -v 0.038750 0.082685 0.066839 -vn 0.770262 0.318864 0.552288 -v 0.038750 0.034000 0.058054 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.000000 0.049961 -vn 0.770262 0.000000 0.637728 -v 0.038750 0.037000 0.057250 -vn 0.678874 0.095839 -0.727973 -v 0.038750 0.043191 0.049961 -vn 0.770262 -0.318864 0.552288 -v 0.038750 0.040000 0.058054 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.000000 0.060800 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.020250 0.060800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.020250 0.049961 -vn 0.770261 0.318864 0.552289 -v 0.038750 -0.040000 0.058054 -vn 0.770262 0.552288 0.318864 -v 0.038750 -0.042196 0.060250 -vn 1.000000 0.000000 -0.000000 -v 0.038750 -0.049025 0.060800 -vn 0.770262 0.637728 -0.000000 -v 0.038750 -0.043000 0.063250 -vn 0.770262 0.552289 -0.318864 -v 0.038750 -0.042196 0.066250 -vn 0.770262 -0.552289 -0.318863 -v 0.038750 -0.031804 0.066250 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.020250 0.069050 -vn 0.770262 -0.318864 -0.552288 -v 0.038750 -0.034000 0.068446 -vn 0.770261 -0.318863 -0.552290 -v 0.038750 -0.055993 0.067064 -vn 0.737701 -0.535614 -0.410993 -v 0.038750 -0.054529 0.065600 -vn 0.678874 -0.582523 -0.446987 -v 0.038750 -0.046655 0.051961 -vn 0.653227 -0.378580 -0.655722 -v 0.038750 -0.045191 0.050497 -vn 0.770262 0.000000 0.637728 -v 0.038750 -0.037000 0.057250 -vn 0.678874 -0.095840 -0.727973 -v 0.038750 -0.043191 0.049961 -vn 0.770262 -0.318864 0.552288 -v 0.038750 -0.034000 0.058054 -vn 0.770262 -0.552289 0.318863 -v 0.038750 -0.031804 0.060250 -vn 0.770262 -0.637728 0.000000 -v 0.038750 -0.031000 0.063250 -vn 0.770262 -0.318864 0.552288 -v 0.038750 0.008375 0.064651 -vn 0.770262 -0.000000 0.637728 -v 0.038750 0.007250 0.064350 -vn 0.770261 0.637728 0.000000 -v 0.038750 0.031000 0.063250 -vn 0.770262 0.552289 0.318864 -v 0.038750 0.031804 0.060250 -vn 0.770262 0.318864 0.552289 -v 0.038750 0.006125 0.064651 -vn 0.770262 0.552289 0.318864 -v 0.038750 0.005301 0.065475 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.000000 0.069050 -vn 0.770262 0.637728 -0.000000 -v 0.038750 0.005000 0.066600 -vn 0.770262 0.552289 -0.318864 -v 0.038750 0.005301 0.067725 -vn 0.770262 0.318864 -0.552288 -v 0.038750 0.006125 0.068549 -vn 0.770262 -0.000000 -0.637728 -v 0.038750 0.007250 0.068850 -vn 0.770264 0.000000 -0.637725 -v 0.038750 0.037000 0.069250 -vn 0.770262 -0.318864 -0.552288 -v 0.038750 0.008375 0.068549 -vn 0.770262 0.318865 -0.552288 -v 0.038750 0.034000 0.068446 -vn 0.770262 -0.552289 -0.318864 -v 0.038750 0.009199 0.067725 -vn 0.770262 0.552289 -0.318863 -v 0.038750 0.031804 0.066250 -vn 0.770262 -0.637728 0.000000 -v 0.038750 0.009500 0.066600 -vn 0.770262 -0.552289 0.318864 -v 0.038750 0.009199 0.065475 -vn 0.770262 -0.552289 -0.318864 -v 0.038750 0.042196 0.066250 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.049025 0.069050 -vn 0.770262 0.318864 -0.552289 -v 0.038750 0.055993 0.067064 -vn 0.653227 0.378581 -0.655722 -v 0.038750 0.045191 0.050497 -vn 0.770262 -0.552288 0.318864 -v 0.038750 0.042196 0.060250 -vn 0.770262 -0.637728 -0.000000 -v 0.038750 0.043000 0.063250 -vn 0.770262 0.000000 -0.637728 -v 0.038750 -0.007250 0.068850 -vn 0.770262 -0.318864 -0.552288 -v 0.038750 -0.006125 0.068549 -vn 0.770262 0.552288 0.318864 -v 0.038750 -0.009199 0.065475 -vn 0.770262 0.637728 0.000000 -v 0.038750 -0.009500 0.066600 -vn 0.770262 0.552289 -0.318864 -v 0.038750 -0.009199 0.067725 -vn 0.770262 0.318864 -0.552288 -v 0.038750 -0.008375 0.068549 -vn 0.770262 -0.552288 -0.318864 -v 0.038750 -0.005301 0.067725 -vn 0.770262 -0.637728 -0.000000 -v 0.038750 -0.005000 0.066600 -vn 0.770262 -0.552288 0.318864 -v 0.038750 -0.005301 0.065475 -vn 0.770262 -0.318864 0.552288 -v 0.038750 -0.006125 0.064651 -vn 0.770262 0.000000 0.637728 -v 0.038750 -0.007250 0.064350 -vn 0.770262 0.318864 0.552289 -v 0.038750 -0.008375 0.064651 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.103800 0.069050 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.093750 0.074300 -vn 0.770262 -0.318864 -0.552288 -v 0.038750 0.040000 0.068446 -vn 1.000000 0.000000 0.000000 -v 0.038750 0.108700 0.069050 -vn 0.770262 -0.552287 -0.318866 -v 0.038750 -0.080378 0.083025 -vn 0.770263 -0.637727 0.000000 -v 0.038750 -0.080050 0.081800 -vn 1.000000 0.000000 0.000000 -v 0.038750 -0.093750 0.088425 -vn 0.770263 0.637727 0.000000 -v 0.038750 -0.084950 0.081800 -vn 0.770262 0.552287 -0.318866 -v 0.038750 -0.084622 0.083025 -vn 0.770261 -0.552288 0.318866 -v 0.038750 -0.080378 0.080575 -vn 0.770262 -0.318864 0.552288 -v 0.038750 -0.081275 0.079678 -vn 0.770262 -0.000000 0.637728 -v 0.038750 -0.082500 0.079350 -vn 0.770262 0.318864 0.552289 -v 0.038750 -0.083725 0.079678 -vn 0.770261 0.552288 0.318866 -v 0.038750 -0.084622 0.080575 -vn 0.770261 0.318865 -0.552290 -v 0.038750 -0.083725 0.083922 -vn 0.770263 0.000000 -0.637726 -v 0.038750 -0.082500 0.084250 -vn 0.770261 -0.318865 -0.552290 -v 0.038750 -0.081275 0.083922 -vn 0.770262 -0.318863 0.552289 -v 0.038750 0.083725 0.079678 -vn 0.770261 0.000000 0.637728 -v 0.038750 0.082500 0.079350 -vn 0.770261 0.637728 0.000000 -v 0.038750 0.080050 0.081800 -vn 0.770263 0.552287 -0.318864 -v 0.038750 0.080378 0.083025 -vn 0.770262 0.552289 0.318864 -v 0.038750 0.080378 0.080575 -vn 0.770262 0.318864 0.552289 -v 0.038750 0.081275 0.079678 -vn 0.770261 0.318865 -0.552290 -v 0.038750 0.081275 0.083922 -vn 0.770263 0.000000 -0.637727 -v 0.038750 0.082500 0.084250 -vn 0.770261 -0.318864 -0.552290 -v 0.038750 0.083725 0.083922 -vn 0.770263 -0.552287 -0.318864 -v 0.038750 0.084622 0.083025 -vn 0.770261 -0.637728 0.000000 -v 0.038750 0.084950 0.081800 -vn 0.770262 -0.552289 0.318864 -v 0.038750 0.084622 0.080575 -vn 0.653227 -0.378581 0.655722 -v 0.038750 -0.117000 0.091796 -vn -0.770261 -0.552289 0.318864 -v 0.034750 0.059622 0.080575 -vn -0.770262 -0.637727 0.000000 -v 0.034750 0.059950 0.081800 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.070000 0.088425 -vn -0.770261 -0.000000 0.637728 -v 0.034750 0.107500 0.079350 -vn -0.770262 -0.318864 0.552289 -v 0.034750 0.108725 0.079678 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.108700 0.074300 -vn -0.770263 -0.552288 -0.318862 -v 0.034750 -0.102878 0.015225 -vn -0.770261 -0.318864 -0.552289 -v 0.034750 -0.103775 0.016122 -vn -1.000000 -0.000000 -0.000000 -v 0.034750 -0.103800 0.036850 -vn -0.770262 -0.000001 -0.637728 -v 0.034750 -0.105000 0.016450 -vn -0.770263 0.318864 -0.552287 -v 0.034750 -0.106225 0.016122 -vn -0.770261 0.552290 -0.318864 -v 0.034750 -0.107122 0.015225 -vn -0.770263 0.637727 -0.000000 -v 0.034750 -0.107450 0.014000 -vn -0.653227 -0.655722 -0.378581 -v 0.034750 -0.119196 0.006000 -vn -0.770261 0.552290 0.318864 -v 0.034750 -0.107122 0.012775 -vn -0.653227 -0.378581 -0.655722 -v 0.034750 -0.117000 0.003804 -vn -0.770263 0.318864 0.552287 -v 0.034750 -0.106225 0.011878 -vn -0.770263 -0.552288 0.318862 -v 0.034750 -0.102878 0.012775 -vn -0.770260 -0.637730 -0.000000 -v 0.034750 -0.102550 0.014000 -vn -0.653227 0.655722 -0.378580 -v 0.034750 -0.095804 0.006000 -vn -0.653227 0.378581 -0.655722 -v 0.034750 -0.098000 0.003804 -vn -0.770261 -0.318864 0.552289 -v 0.034750 -0.103775 0.011878 -vn -0.770262 -0.000001 0.637728 -v 0.034750 -0.105000 0.011550 -vn -0.770263 -0.552287 -0.318864 -v 0.034750 0.109622 0.083025 -vn -0.653227 0.655722 0.378581 -v 0.034750 0.119196 0.089600 -vn -0.770261 -0.637728 0.000000 -v 0.034750 0.109950 0.081800 -vn -0.770262 -0.552289 0.318864 -v 0.034750 0.109622 0.080575 -vn -0.770263 0.637727 0.000000 -v 0.034750 0.105050 0.081800 -vn -0.770261 0.552290 0.318865 -v 0.034750 0.105378 0.080575 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.093750 0.074300 -vn -0.770263 0.318864 0.552287 -v 0.034750 0.106275 0.079678 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.093750 0.088425 -vn -0.770261 0.552288 -0.318865 -v 0.034750 0.105378 0.083025 -vn -0.770261 -0.318865 -0.552290 -v 0.034750 0.108725 0.083922 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.108700 0.088425 -vn -0.770263 -0.000000 -0.637727 -v 0.034750 0.107500 0.084250 -vn -0.770261 0.318865 -0.552288 -v 0.034750 0.106275 0.083922 -vn -1.000000 -0.000000 0.000000 -v 0.034750 0.049025 0.069050 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.070000 0.069050 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.093750 0.069050 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.093750 0.060800 -vn -0.753767 -0.607120 -0.251477 -v 0.034750 0.094239 0.055285 -vn -0.753767 -0.251477 -0.607120 -v 0.034750 0.082685 0.066839 -vn -0.770261 -0.637728 -0.000000 -v 0.034750 0.107450 0.014000 -vn -0.770262 -0.552288 -0.318864 -v 0.034750 0.107122 0.015225 -vn -1.000000 0.000000 -0.000000 -v 0.034750 0.108700 0.036850 -vn -0.770262 -0.318863 -0.552289 -v 0.034750 0.106225 0.016122 -vn -0.770262 0.000001 -0.637728 -v 0.034750 0.105000 0.016450 -vn -1.000000 0.000000 -0.000000 -v 0.034750 0.108700 0.060800 -vn -0.770261 0.318864 -0.552289 -v 0.034750 0.103775 0.016122 -vn -0.770262 0.552288 -0.318864 -v 0.034750 0.102878 0.015225 -vn -0.770261 0.637728 0.000000 -v 0.034750 0.102550 0.014000 -vn -0.770262 0.552288 0.318864 -v 0.034750 0.102878 0.012775 -vn -0.653227 -0.655722 -0.378581 -v 0.034750 0.095804 0.006000 -vn -0.770261 0.318864 0.552289 -v 0.034750 0.103775 0.011878 -vn -0.653227 -0.378581 -0.655722 -v 0.034750 0.098000 0.003804 -vn -0.770262 0.000000 0.637728 -v 0.034750 0.105000 0.011550 -vn -0.770262 -0.318863 0.552289 -v 0.034750 0.106225 0.011878 -vn -0.770262 -0.552288 0.318864 -v 0.034750 0.107122 0.012775 -vn -0.653227 0.655722 -0.378581 -v 0.034750 0.119196 0.006000 -vn -0.653227 0.378581 -0.655722 -v 0.034750 0.117000 0.003804 -vn -0.653227 0.378581 0.655722 -v 0.034750 0.117000 0.091796 -vn -0.770262 -0.552288 -0.318865 -v 0.034750 0.059622 0.083025 -vn -0.770261 -0.318865 -0.552289 -v 0.034750 0.058725 0.083922 -vn -0.678875 -0.582523 0.446985 -v 0.034750 0.050845 0.090600 -vn -0.770263 -0.000000 -0.637727 -v 0.034750 0.057500 0.084250 -vn -0.770261 0.318865 -0.552288 -v 0.034750 0.056275 0.083922 -vn -0.770262 0.552288 -0.318864 -v 0.034750 0.055378 0.083025 -vn -0.737701 -0.535616 0.410991 -v 0.034750 0.042971 0.076961 -vn -0.770262 0.637727 0.000000 -v 0.034750 0.055050 0.081800 -vn -0.770261 0.552290 0.318864 -v 0.034750 0.055378 0.080575 -vn -0.770263 0.318864 0.552287 -v 0.034750 0.056275 0.079678 -vn -1.000000 -0.000000 -0.000000 -v 0.034750 0.049025 0.074300 -vn -0.770261 -0.000000 0.637728 -v 0.034750 0.057500 0.079350 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.070000 0.074300 -vn -0.770262 -0.318864 0.552288 -v 0.034750 0.058725 0.079678 -vn -0.770262 -0.318865 0.552288 -v 0.034750 0.041507 0.075497 -vn -0.737699 -0.088122 0.669354 -v 0.034750 0.039507 0.074961 -vn -0.707107 0.000000 0.707107 -v 0.034750 -0.020250 0.074961 -vn -0.707107 0.000000 0.707107 -v 0.034750 0.000000 0.074961 -vn -1.000000 -0.000000 0.000000 -v 0.034750 0.000000 0.074300 -vn -0.727260 0.562235 0.393682 -v 0.034750 -0.042971 0.076961 -vn -0.748361 0.426356 0.508111 -v 0.034750 -0.042078 0.075897 -vn -1.000000 -0.000000 0.000000 -v 0.034750 -0.049025 0.074300 -vn -0.748361 0.226860 0.623290 -v 0.034750 -0.040875 0.075202 -vn -0.727262 0.059821 0.683748 -v 0.034750 -0.039507 0.074961 -vn -0.770260 -0.637730 0.000000 -v 0.034750 -0.055050 0.081800 -vn -0.678875 0.582523 0.446985 -v 0.034750 -0.050845 0.090600 -vn -0.770263 -0.552288 -0.318862 -v 0.034750 -0.055378 0.083025 -vn -0.770261 -0.318865 -0.552290 -v 0.034750 -0.056275 0.083922 -vn -0.770263 -0.000001 -0.637727 -v 0.034750 -0.057500 0.084250 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.070000 0.088425 -vn -0.770262 0.318865 -0.552287 -v 0.034750 -0.058725 0.083922 -vn -0.770261 0.552290 -0.318864 -v 0.034750 -0.059622 0.083025 -vn -0.770263 0.637727 0.000000 -v 0.034750 -0.059950 0.081800 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.070000 0.074300 -vn -0.770260 0.552291 0.318864 -v 0.034750 -0.059622 0.080575 -vn -0.770263 0.318864 0.552286 -v 0.034750 -0.058725 0.079678 -vn -0.770261 -0.000001 0.637729 -v 0.034750 -0.057500 0.079350 -vn -0.770262 -0.318864 0.552289 -v 0.034750 -0.056275 0.079678 -vn -0.770263 -0.552289 0.318862 -v 0.034750 -0.055378 0.080575 -vn -0.653226 -0.655722 0.378581 -v 0.034750 -0.119196 0.089600 -vn -0.653227 -0.378581 0.655722 -v 0.034750 -0.117000 0.091796 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.103800 0.088425 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.103800 0.074300 -vn -0.770263 -0.637727 0.000000 -v 0.034750 -0.105050 0.081800 -vn -0.770261 -0.552290 -0.318864 -v 0.034750 -0.105378 0.083025 -vn -0.770261 0.000001 0.637729 -v 0.034750 -0.107500 0.079350 -vn -0.770263 -0.318864 0.552286 -v 0.034750 -0.106275 0.079678 -vn -0.770260 -0.552291 0.318864 -v 0.034750 -0.105378 0.080575 -vn -0.770262 -0.318865 -0.552287 -v 0.034750 -0.106275 0.083922 -vn -0.770263 0.000001 -0.637727 -v 0.034750 -0.107500 0.084250 -vn -0.770261 0.318865 -0.552290 -v 0.034750 -0.108725 0.083922 -vn -0.770263 0.552288 -0.318862 -v 0.034750 -0.109622 0.083025 -vn -0.770260 0.637730 0.000000 -v 0.034750 -0.109950 0.081800 -vn -0.770263 0.552289 0.318862 -v 0.034750 -0.109622 0.080575 -vn -0.770262 0.318864 0.552288 -v 0.034750 -0.108725 0.079678 -vn -1.000000 -0.000000 -0.000000 -v 0.034750 -0.103800 0.060800 -vn -0.753767 0.607119 -0.251478 -v 0.034750 -0.094239 0.055285 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.093750 0.069050 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.070000 0.069050 -vn -0.753767 0.251477 -0.607120 -v 0.034750 -0.082685 0.066839 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.093750 0.060800 -vn -0.737701 -0.535614 -0.410993 -v 0.034750 -0.054529 0.065600 -vn -0.770261 -0.318863 -0.552290 -v 0.034750 -0.055993 0.067064 -vn -1.000000 -0.000000 0.000000 -v 0.034750 -0.049025 0.069050 -vn -0.770262 0.318864 0.552289 -v 0.034750 -0.040000 0.058054 -vn -0.770262 0.000000 0.637728 -v 0.034750 -0.037000 0.057250 -vn -0.678874 -0.095840 -0.727973 -v 0.034750 -0.043191 0.049961 -vn -0.707107 -0.000000 -0.707107 -v 0.034750 -0.020250 0.049961 -vn -0.770262 -0.318864 0.552288 -v 0.034750 -0.034000 0.058054 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.020250 0.060800 -vn -0.707107 -0.000000 -0.707107 -v 0.034750 0.000000 0.049961 -vn -0.770262 0.318864 -0.552289 -v 0.034750 0.055993 0.067064 -vn -0.737700 0.535615 -0.410992 -v 0.034750 0.054529 0.065600 -vn -1.000000 -0.000000 -0.000000 -v 0.034750 0.049025 0.060800 -vn -0.678875 0.582523 -0.446986 -v 0.034750 0.046655 0.051961 -vn -0.770262 -0.318864 0.552288 -v 0.034750 0.040000 0.058054 -vn -0.653227 0.378581 -0.655722 -v 0.034750 0.045191 0.050497 -vn -0.770261 0.000000 0.637728 -v 0.034750 0.037000 0.057250 -vn -0.678875 0.095839 -0.727973 -v 0.034750 0.043191 0.049961 -vn -0.770262 0.318864 0.552288 -v 0.034750 0.034000 0.058054 -vn -0.770262 0.000000 -0.637727 -v 0.034750 -0.037000 0.069250 -vn -0.770262 0.318864 -0.552288 -v 0.034750 -0.040000 0.068446 -vn -0.770262 0.552288 -0.318864 -v 0.034750 -0.042196 0.066250 -vn -1.000000 -0.000000 -0.000000 -v 0.034750 -0.049025 0.060800 -vn -0.678874 -0.582523 -0.446987 -v 0.034750 -0.046655 0.051961 -vn -0.653227 -0.378580 -0.655722 -v 0.034750 -0.045191 0.050497 -vn -0.770262 0.552287 0.318864 -v 0.034750 -0.042196 0.060250 -vn -0.770261 0.637729 -0.000000 -v 0.034750 -0.043000 0.063250 -vn -1.000000 -0.000000 0.000000 -v 0.034750 -0.020250 0.069050 -vn -1.000000 -0.000000 -0.000000 -v 0.034750 -0.020250 0.074300 -vn -0.770262 -0.552289 -0.318863 -v 0.034750 -0.031804 0.066250 -vn -0.770262 -0.637728 0.000000 -v 0.034750 -0.031000 0.063250 -vn -0.770262 -0.552289 0.318863 -v 0.034750 -0.031804 0.060250 -vn -0.770262 0.318865 -0.552288 -v 0.034750 0.034000 0.068446 -vn -0.770262 -0.318864 -0.552288 -v 0.034750 0.008375 0.068549 -vn -0.770264 0.000000 -0.637726 -v 0.034750 0.037000 0.069250 -vn -0.770262 0.000000 -0.637728 -v 0.034750 0.007250 0.068850 -vn -0.770262 0.000000 0.637728 -v 0.034750 0.007250 0.064350 -vn -0.770262 -0.318864 0.552288 -v 0.034750 0.008375 0.064651 -vn -0.770262 0.637728 0.000000 -v 0.034750 0.031000 0.063250 -vn -0.770262 -0.552288 0.318864 -v 0.034750 0.009199 0.065475 -vn -0.770262 0.552289 -0.318863 -v 0.034750 0.031804 0.066250 -vn -0.770262 -0.637728 0.000000 -v 0.034750 0.009500 0.066600 -vn -0.770262 -0.552289 -0.318864 -v 0.034750 0.009199 0.067725 -vn -0.770262 0.318864 -0.552288 -v 0.034750 0.006125 0.068549 -vn -0.770262 0.552288 -0.318864 -v 0.034750 0.005301 0.067725 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.000000 0.069050 -vn -0.770262 0.637728 0.000000 -v 0.034750 0.005000 0.066600 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.000000 0.060800 -vn -0.770262 0.552288 0.318864 -v 0.034750 0.005301 0.065475 -vn -0.770262 0.552289 0.318864 -v 0.034750 0.031804 0.060250 -vn -0.770262 0.318864 0.552288 -v 0.034750 0.006125 0.064651 -vn -0.770261 -0.552289 0.318864 -v 0.034750 0.042196 0.060250 -vn -0.770262 -0.637727 -0.000000 -v 0.034750 0.043000 0.063250 -vn -0.770261 -0.552290 -0.318864 -v 0.034750 0.042196 0.066250 -vn -0.770262 -0.318864 -0.552289 -v 0.034750 0.040000 0.068446 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.093750 0.088425 -vn -0.653226 0.378582 0.655722 -v 0.034750 -0.052309 0.092064 -vn -0.653227 -0.378582 0.655722 -v 0.034750 0.052309 0.092064 -vn -0.770261 0.552288 0.318866 -v 0.034750 -0.084622 0.080575 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.093750 0.074300 -vn -0.770263 0.637727 0.000000 -v 0.034750 -0.084950 0.081800 -vn -0.770262 0.552287 -0.318866 -v 0.034750 -0.084622 0.083025 -vn -0.770262 -0.552287 -0.318866 -v 0.034750 -0.080378 0.083025 -vn -0.770261 -0.318865 -0.552290 -v 0.034750 -0.081275 0.083922 -vn -0.770263 0.000000 -0.637726 -v 0.034750 -0.082500 0.084250 -vn -0.770261 0.318865 -0.552290 -v 0.034750 -0.083725 0.083922 -vn -0.770262 0.318864 0.552288 -v 0.034750 -0.083725 0.079678 -vn -0.770262 0.000000 0.637728 -v 0.034750 -0.082500 0.079350 -vn -0.770262 -0.318864 0.552289 -v 0.034750 -0.081275 0.079678 -vn -0.770261 -0.552288 0.318866 -v 0.034750 -0.080378 0.080575 -vn -0.770263 -0.637727 0.000000 -v 0.034750 -0.080050 0.081800 -vn -0.770261 -0.637728 0.000000 -v 0.034750 0.084950 0.081800 -vn -0.770263 -0.552287 -0.318864 -v 0.034750 0.084622 0.083025 -vn -0.770262 -0.552288 0.318864 -v 0.034750 0.084622 0.080575 -vn -0.770263 0.552287 -0.318864 -v 0.034750 0.080378 0.083025 -vn -0.770261 0.637728 0.000000 -v 0.034750 0.080050 0.081800 -vn -0.770262 0.552289 0.318864 -v 0.034750 0.080378 0.080575 -vn -0.770262 0.318864 0.552288 -v 0.034750 0.081275 0.079678 -vn -0.770261 0.000000 0.637728 -v 0.034750 0.082500 0.079350 -vn -0.770262 -0.318863 0.552289 -v 0.034750 0.083725 0.079678 -vn -0.770261 -0.318864 -0.552290 -v 0.034750 0.083725 0.083922 -vn -0.770263 0.000000 -0.637727 -v 0.034750 0.082500 0.084250 -vn -0.770261 0.318865 -0.552290 -v 0.034750 0.081275 0.083922 -vn -0.770262 -0.318864 -0.552288 -v 0.034750 -0.034000 0.068446 -vn -1.000000 0.000000 0.000000 -v 0.034750 -0.103800 0.069050 -vn -0.770262 -0.552288 -0.318864 -v 0.034750 -0.005301 0.067725 -vn -0.770262 -0.318864 -0.552289 -v 0.034750 -0.006125 0.068549 -vn -0.770262 0.000000 -0.637728 -v 0.034750 -0.007250 0.068850 -vn -0.770262 0.318864 -0.552288 -v 0.034750 -0.008375 0.068549 -vn -0.770262 0.552288 -0.318864 -v 0.034750 -0.009199 0.067725 -vn -0.770262 0.637728 0.000000 -v 0.034750 -0.009500 0.066600 -vn -0.770262 0.552289 0.318864 -v 0.034750 -0.009199 0.065475 -vn -0.770262 0.318864 0.552288 -v 0.034750 -0.008375 0.064651 -vn -0.770262 0.000000 0.637728 -v 0.034750 -0.007250 0.064350 -vn -0.770262 -0.318864 0.552289 -v 0.034750 -0.006125 0.064651 -vn -0.770262 -0.552288 0.318864 -v 0.034750 -0.005301 0.065475 -vn -0.770262 -0.637728 -0.000000 -v 0.034750 -0.005000 0.066600 -vn -1.000000 0.000000 0.000000 -v 0.034750 0.108700 0.069050 -vn -1.000000 -0.000000 0.000000 -v 0.022280 0.000000 0.056750 -vn -1.000000 -0.000000 0.000000 -v 0.022280 0.014975 0.056750 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.014975 0.051500 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 0.023625 0.035324 -vn -0.770262 -0.000000 -0.637728 -v 0.022280 0.022500 0.035625 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.029500 0.046500 -vn -0.770262 -0.318863 0.552289 -v 0.022280 -0.035625 0.060868 -vn -0.770262 -0.552288 0.318864 -v 0.022280 -0.034618 0.061875 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.029500 0.062325 -vn -0.770262 0.552288 -0.318864 -v 0.022280 0.034618 0.064625 -vn -0.770262 0.637728 -0.000000 -v 0.022280 0.034250 0.063250 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.029500 0.062325 -vn -0.770262 0.318864 -0.552288 -v 0.022280 0.035625 0.065632 -vn -0.707107 -0.000000 0.707107 -v 0.022280 0.029500 0.074600 -vn -0.770262 0.000000 -0.637728 -v 0.022280 0.037000 0.066000 -vn -0.685696 0.071346 0.724383 -v 0.022280 0.041500 0.074600 -vn -0.770262 -0.318864 -0.552289 -v 0.022280 0.038375 0.065632 -vn -0.665719 0.285560 0.689401 -v 0.022280 0.043031 0.074296 -vn -0.707107 0.707107 -0.000000 -v 0.022280 0.045500 0.062325 -vn -0.770262 -0.637728 0.000000 -v 0.022280 0.039750 0.063250 -vn -0.685696 0.724383 0.071346 -v 0.022280 0.045500 0.070600 -vn -0.770262 -0.552288 -0.318864 -v 0.022280 0.039382 0.064625 -vn -0.665719 0.689401 0.285559 -v 0.022280 0.045196 0.072131 -vn -0.665719 0.527646 0.527644 -v 0.022280 0.044328 0.073428 -vn -0.770262 0.318864 0.552288 -v 0.022280 0.035625 0.060868 -vn -0.770261 0.000000 0.637728 -v 0.022280 0.037000 0.060500 -vn -1.000000 -0.000000 0.000000 -v 0.022280 0.029500 0.056750 -vn -0.770261 0.552289 0.318864 -v 0.022280 0.034618 0.061875 -vn -0.707107 0.707107 0.000000 -v 0.022280 0.045500 0.056750 -vn -0.770262 -0.318863 0.552288 -v 0.022280 0.038375 0.060868 -vn -0.770261 -0.552289 0.318864 -v 0.022280 0.039382 0.061875 -vn -0.770262 0.000000 -0.637728 -v 0.022280 -0.037000 0.050000 -vn -0.770262 0.318864 -0.552288 -v 0.022280 -0.038375 0.049632 -vn -1.000000 0.000000 0.000000 -v 0.022280 -0.042625 0.051500 -vn -0.770262 0.552289 -0.318863 -v 0.022280 -0.039382 0.048625 -vn -1.000000 0.000000 0.000000 -v 0.022280 -0.042625 0.046500 -vn -0.770262 -0.552288 -0.318864 -v 0.022280 -0.034618 0.048625 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 -0.035625 0.049632 -vn -1.000000 0.000000 0.000000 -v 0.022280 -0.029500 0.051500 -vn -0.770261 0.637728 0.000000 -v 0.022280 -0.039750 0.047250 -vn -0.770262 0.552289 0.318863 -v 0.022280 -0.039382 0.045875 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.042625 0.024688 -vn -0.770262 0.318863 0.552289 -v 0.022280 -0.038375 0.044868 -vn -0.770261 -0.000000 0.637728 -v 0.022280 -0.037000 0.044500 -vn -1.000000 0.000000 -0.000000 -v 0.022280 -0.029500 0.024688 -vn -0.770262 -0.318863 0.552289 -v 0.022280 -0.035625 0.044868 -vn -1.000000 0.000000 0.000000 -v 0.022280 -0.029500 0.046500 -vn -0.770262 -0.552288 0.318864 -v 0.022280 -0.034618 0.045875 -vn -0.770262 -0.637728 0.000000 -v 0.022280 -0.034250 0.047250 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.000000 0.046500 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.000000 0.024688 -vn -0.770262 -0.637728 0.000000 -v 0.022280 -0.020250 0.033375 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.022500 0.024688 -vn -0.770262 -0.318863 0.552289 -v 0.022280 -0.021375 0.031426 -vn -0.770262 -0.552288 0.318864 -v 0.022280 -0.020551 0.032250 -vn -0.770262 -0.552289 -0.318863 -v 0.022280 -0.020551 0.034500 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 -0.021375 0.035324 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.022500 0.046500 -vn -0.770262 0.000000 -0.637728 -v 0.022280 -0.022500 0.035625 -vn -0.770262 0.318864 -0.552289 -v 0.022280 -0.023625 0.035324 -vn -0.770262 0.318863 0.552289 -v 0.022280 -0.023625 0.031426 -vn -0.770261 0.000000 0.637728 -v 0.022280 -0.022500 0.031125 -vn -0.770262 0.552288 -0.318864 -v 0.022280 -0.024449 0.034500 -vn -0.770262 0.637728 0.000000 -v 0.022280 -0.024750 0.033375 -vn -0.770262 0.552288 0.318864 -v 0.022280 -0.024449 0.032250 -vn -0.770262 -0.000000 -0.637728 -v 0.022280 0.022500 0.053000 -vn -0.770262 0.318864 -0.552288 -v 0.022280 0.021375 0.052699 -vn -0.770262 -0.000000 0.637728 -v 0.022280 0.022500 0.048500 -vn -0.770262 -0.318864 0.552289 -v 0.022280 0.023625 0.048801 -vn -0.770261 0.552288 -0.318865 -v 0.022280 0.020551 0.051875 -vn -0.770262 0.637728 0.000000 -v 0.022280 0.020250 0.050750 -vn -1.000000 -0.000000 0.000000 -v 0.022280 0.014975 0.046500 -vn -0.770262 -0.552288 0.318864 -v 0.022280 0.024449 0.049625 -vn -0.770262 -0.637728 0.000000 -v 0.022280 0.024750 0.050750 -vn -1.000000 0.000000 0.000000 -v 0.022280 0.029500 0.051500 -vn -0.770262 -0.552289 -0.318864 -v 0.022280 0.024449 0.051875 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 0.023625 0.052699 -vn -0.770262 0.552288 0.318865 -v 0.022280 0.020551 0.049625 -vn -0.770262 0.318863 0.552288 -v 0.022280 0.021375 0.048801 -vn -1.000000 0.000000 0.000000 -v 0.022280 0.000000 0.051500 -vn -0.770262 -0.552289 0.318863 -v 0.022280 -0.020551 0.049625 -vn -0.770262 0.637728 0.000000 -v 0.022280 -0.024750 0.050750 -vn -0.770262 0.552289 0.318864 -v 0.022280 -0.024449 0.049625 -vn -0.770262 0.318864 0.552288 -v 0.022280 -0.023625 0.048801 -vn -0.770262 0.000000 0.637728 -v 0.022280 -0.022500 0.048500 -vn -0.770262 -0.318864 0.552288 -v 0.022280 -0.021375 0.048801 -vn -0.770262 -0.637728 0.000000 -v 0.022280 -0.020250 0.050750 -vn -0.770262 -0.552289 -0.318863 -v 0.022280 -0.020551 0.051875 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 -0.021375 0.052699 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.022500 0.056750 -vn -0.770262 0.000000 -0.637728 -v 0.022280 -0.022500 0.053000 -vn -1.000000 0.000000 0.000000 -v 0.022280 -0.029500 0.056750 -vn -0.770262 0.318864 -0.552289 -v 0.022280 -0.023625 0.052699 -vn -0.770262 0.552288 -0.318864 -v 0.022280 -0.024449 0.051875 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.000000 0.009875 -vn -1.000000 -0.000000 0.000000 -v 0.022280 -0.022500 0.009875 -vn -0.770262 -0.318864 0.552288 -v 0.022280 -0.021375 0.014051 -vn -0.770262 -0.552289 0.318863 -v 0.022280 -0.020551 0.014875 -vn -0.770262 -0.637728 -0.000000 -v 0.022280 -0.020250 0.016000 -vn -0.770262 -0.552289 -0.318864 -v 0.022280 -0.020551 0.017125 -vn -1.000000 0.000000 -0.000000 -v 0.022280 -0.029500 0.009875 -vn -0.770262 0.318864 0.552288 -v 0.022280 -0.023625 0.014051 -vn -0.770262 0.000000 0.637728 -v 0.022280 -0.022500 0.013750 -vn -0.770261 -0.318865 -0.552289 -v 0.022280 -0.021375 0.017949 -vn -0.770262 0.000000 -0.637728 -v 0.022280 -0.022500 0.018250 -vn -0.770262 0.318864 -0.552289 -v 0.022280 -0.023625 0.017949 -vn -0.770262 0.552289 -0.318864 -v 0.022280 -0.024449 0.017125 -vn -0.770262 0.637728 -0.000000 -v 0.022280 -0.024750 0.016000 -vn -0.770262 0.552289 0.318864 -v 0.022280 -0.024449 0.014875 -vn -0.770262 0.318864 -0.552289 -v 0.022280 -0.038375 0.065632 -vn -0.665719 -0.285560 0.689401 -v 0.022280 -0.043031 0.074296 -vn -0.770262 0.000000 -0.637728 -v 0.022280 -0.037000 0.066000 -vn -0.685696 -0.071346 0.724383 -v 0.022280 -0.041500 0.074600 -vn -0.770262 -0.318864 -0.552289 -v 0.022280 -0.035625 0.065632 -vn -0.707107 0.000000 0.707107 -v 0.022280 -0.029500 0.074600 -vn -0.770262 -0.552287 -0.318865 -v 0.022280 -0.034618 0.064625 -vn -0.770262 -0.637728 0.000000 -v 0.022280 -0.034250 0.063250 -vn -0.770263 0.552288 -0.318864 -v 0.022280 -0.039382 0.064625 -vn -0.770261 0.637729 -0.000000 -v 0.022280 -0.039750 0.063250 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.042625 0.062325 -vn -0.770262 0.552289 0.318863 -v 0.022280 -0.039382 0.061875 -vn -1.000000 0.000000 0.000000 -v 0.022280 -0.042625 0.056750 -vn -0.770262 0.318863 0.552289 -v 0.022280 -0.038375 0.060868 -vn -0.770261 -0.000000 0.637728 -v 0.022280 -0.037000 0.060500 -vn -0.707107 0.707107 0.000000 -v 0.022280 0.045500 0.046500 -vn -0.770262 -0.552289 0.318864 -v 0.022280 0.039382 0.045875 -vn -0.770262 -0.637728 0.000000 -v 0.022280 0.039750 0.047250 -vn -0.707107 0.707107 0.000000 -v 0.022280 0.045500 0.051500 -vn -0.770262 0.000000 -0.637728 -v 0.022280 0.037000 0.050000 -vn -0.770262 0.318865 -0.552288 -v 0.022280 0.035625 0.049632 -vn -0.770262 -0.552289 -0.318864 -v 0.022280 0.039382 0.048625 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 0.038375 0.049632 -vn -0.770262 0.552289 -0.318864 -v 0.022280 0.034618 0.048625 -vn -0.770262 0.637728 0.000000 -v 0.022280 0.034250 0.047250 -vn -0.770262 0.552289 0.318864 -v 0.022280 0.034618 0.045875 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.029500 0.024688 -vn -0.770262 0.318864 0.552288 -v 0.022280 0.035625 0.044868 -vn -0.770261 0.000000 0.637728 -v 0.022280 0.037000 0.044500 -vn -0.770262 -0.318863 0.552288 -v 0.022280 0.038375 0.044868 -vn -0.707107 0.707107 -0.000000 -v 0.022280 0.045500 0.024688 -vn -0.685697 -0.071345 -0.724383 -v 0.022280 -0.041500 0.006000 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.042625 0.009875 -vn -0.665719 -0.285559 -0.689402 -v 0.022280 -0.043031 0.006304 -vn -0.665719 -0.527645 -0.527645 -v 0.022280 -0.044328 0.007172 -vn -0.685696 0.724383 -0.071346 -v 0.022280 0.045500 0.010000 -vn -0.665719 0.689401 -0.285560 -v 0.022280 0.045196 0.008469 -vn -0.685697 0.071345 -0.724383 -v 0.022280 0.041500 0.006000 -vn -0.665719 0.527645 -0.527645 -v 0.022280 0.044328 0.007172 -vn -0.665719 0.285560 -0.689402 -v 0.022280 0.043031 0.006304 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.029500 0.009875 -vn -0.665719 -0.689402 0.285558 -v 0.022280 -0.045196 0.072131 -vn -0.665719 -0.527645 0.527645 -v 0.022280 -0.044328 0.073428 -vn -0.685697 -0.724383 0.071345 -v 0.022280 -0.045500 0.070600 -vn -0.707107 -0.707107 -0.000000 -v 0.022280 -0.045500 0.062325 -vn -0.707107 -0.000000 0.707107 -v 0.022280 0.014975 0.074600 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.014975 0.062325 -vn -0.770262 0.318863 -0.552289 -v 0.022280 0.021375 0.035324 -vn -0.770262 0.552288 -0.318864 -v 0.022280 0.020551 0.034500 -vn -0.770262 0.637728 0.000000 -v 0.022280 0.020250 0.033375 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.014975 0.024688 -vn -0.770262 0.552288 0.318865 -v 0.022280 0.020551 0.032250 -vn -0.770262 0.318862 0.552289 -v 0.022280 0.021375 0.031426 -vn -0.770261 -0.000000 0.637728 -v 0.022280 0.022500 0.031125 -vn -0.770262 -0.318863 0.552289 -v 0.022280 0.023625 0.031426 -vn -0.770262 -0.552288 0.318864 -v 0.022280 0.024449 0.032250 -vn -0.770262 -0.637728 0.000000 -v 0.022280 0.024750 0.033375 -vn -0.770262 -0.552289 -0.318864 -v 0.022280 0.024449 0.034500 -vn -0.770262 -0.552289 -0.318864 -v 0.022280 0.024449 0.017125 -vn -0.770262 -0.318864 -0.552289 -v 0.022280 0.023625 0.017949 -vn -0.770262 -0.000000 -0.637728 -v 0.022280 0.022500 0.018250 -vn -0.770262 -0.637728 -0.000000 -v 0.022280 0.024750 0.016000 -vn -0.770262 -0.552288 0.318864 -v 0.022280 0.024449 0.014875 -vn -0.770262 0.552288 0.318865 -v 0.022280 0.020551 0.014875 -vn -0.770262 0.318863 0.552289 -v 0.022280 0.021375 0.014051 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.014975 0.009875 -vn -0.770262 -0.000000 0.637728 -v 0.022280 0.022500 0.013750 -vn -0.770262 -0.318864 0.552289 -v 0.022280 0.023625 0.014051 -vn -0.770262 0.318863 -0.552289 -v 0.022280 0.021375 0.017949 -vn -0.770262 0.552288 -0.318865 -v 0.022280 0.020551 0.017125 -vn -0.770262 0.637728 -0.000000 -v 0.022280 0.020250 0.016000 -vn -0.770261 -0.000000 -0.637728 -v 0.022280 0.007250 0.069050 -vn -0.707107 -0.000000 0.707106 -v 0.022280 0.000000 0.074600 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 0.008475 0.068722 -vn -0.770261 -0.318865 0.552289 -v 0.022280 0.008475 0.064478 -vn -0.770263 -0.000000 0.637726 -v 0.022280 0.007250 0.064150 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 0.000000 0.062325 -vn -0.770261 0.318865 0.552289 -v 0.022280 0.006025 0.064478 -vn -0.770262 0.552288 0.318864 -v 0.022280 0.005128 0.065375 -vn -0.770262 0.318864 -0.552288 -v 0.022280 0.006025 0.068722 -vn -0.770261 0.552289 -0.318864 -v 0.022280 0.005128 0.067825 -vn -0.770262 0.637727 -0.000000 -v 0.022280 0.004800 0.066600 -vn -0.770262 -0.552288 0.318864 -v 0.022280 0.009372 0.065375 -vn -0.770262 -0.637727 -0.000001 -v 0.022280 0.009700 0.066600 -vn -0.770261 -0.552289 -0.318864 -v 0.022280 0.009372 0.067825 -vn -0.770263 0.318864 -0.552287 -v 0.022280 -0.008475 0.068722 -vn -0.707107 -0.000000 0.707107 -v 0.022280 -0.022500 0.074600 -vn -0.770261 -0.000000 -0.637728 -v 0.022280 -0.007250 0.069050 -vn -0.770262 -0.318864 -0.552288 -v 0.022280 -0.006025 0.068722 -vn -0.770262 0.637727 -0.000000 -v 0.022280 -0.009700 0.066600 -vn -0.770262 0.552288 0.318864 -v 0.022280 -0.009372 0.065375 -vn -1.000000 -0.000000 -0.000000 -v 0.022280 -0.022500 0.062325 -vn -0.770261 0.552290 -0.318864 -v 0.022280 -0.009372 0.067825 -vn -0.770262 0.318865 0.552288 -v 0.022280 -0.008475 0.064478 -vn -0.770263 -0.000000 0.637726 -v 0.022280 -0.007250 0.064150 -vn -0.770261 -0.318865 0.552289 -v 0.022280 -0.006025 0.064478 -vn -0.770262 -0.552288 0.318864 -v 0.022280 -0.005128 0.065375 -vn -0.770262 -0.637727 -0.000001 -v 0.022280 -0.004800 0.066600 -vn -0.770261 -0.552289 -0.318864 -v 0.022280 -0.005128 0.067825 -vn -0.707107 -0.000000 -0.707107 -v 0.022280 0.029500 0.006000 -vn -0.707107 -0.000000 -0.707107 -v 0.022280 0.014975 0.006000 -vn -0.707107 -0.000000 -0.707107 -v 0.022280 0.000000 0.006000 -vn -0.707107 -0.000000 -0.707107 -v 0.022280 -0.022500 0.006000 -vn -0.707107 0.000000 -0.707107 -v 0.022280 -0.029500 0.006000 -vn -0.685697 -0.724383 -0.071345 -v 0.022280 -0.045500 0.010000 -vn -0.665719 -0.689402 -0.285559 -v 0.022280 -0.045196 0.008469 -vn -0.707107 -0.707107 -0.000000 -v 0.022280 -0.045500 0.024688 -vn -0.707107 -0.707107 0.000000 -v 0.022280 -0.045500 0.046500 -vn -0.707107 -0.707107 0.000000 -v 0.022280 -0.045500 0.051500 -vn -0.707107 -0.707107 0.000000 -v 0.022280 -0.045500 0.056750 -vn 0.770262 -0.318863 0.552289 -v 0.026280 0.023625 0.031426 -vn 0.770261 0.000000 0.637728 -v 0.026280 0.022500 0.031125 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.029500 0.024688 -vn 0.685697 -0.724383 -0.071345 -v 0.026280 -0.045500 0.010000 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.042625 0.009875 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.042625 0.024688 -vn 0.770262 -0.318864 -0.552289 -v 0.026280 -0.021375 0.052699 -vn 0.770261 -0.552288 -0.318865 -v 0.026280 -0.020551 0.051875 -vn 1.000000 0.000000 -0.000000 -v 0.026280 0.000000 0.051500 -vn 0.770262 0.637728 0.000000 -v 0.026280 -0.024750 0.050750 -vn 0.770262 0.552289 -0.318864 -v 0.026280 -0.024449 0.051875 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.029500 0.051500 -vn 0.770262 0.637728 0.000000 -v 0.026280 0.020250 0.050750 -vn 0.770262 0.552289 -0.318863 -v 0.026280 0.020551 0.051875 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.014975 0.051500 -vn 0.770262 -0.637727 0.000001 -v 0.026280 -0.034250 0.063250 -vn 0.770262 -0.552288 0.318864 -v 0.026280 -0.034618 0.061875 -vn 1.000000 -0.000000 0.000000 -v 0.026280 -0.029500 0.062325 -vn 0.770262 0.318864 0.552288 -v 0.026280 0.035625 0.060868 -vn 0.770261 0.552289 0.318864 -v 0.026280 0.034618 0.061875 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.029500 0.062325 -vn 0.770262 0.637728 0.000001 -v 0.026280 0.034250 0.063250 -vn 0.665719 0.689401 0.285559 -v 0.026280 0.045196 0.072131 -vn 0.665719 0.527646 0.527644 -v 0.026280 0.044328 0.073428 -vn 0.665719 0.285560 0.689401 -v 0.026280 0.043031 0.074296 -vn 0.770262 -0.318864 -0.552289 -v 0.026280 0.038375 0.065632 -vn 0.770262 -0.552289 -0.318864 -v 0.026280 0.039382 0.064625 -vn 0.685696 0.724383 0.071346 -v 0.026280 0.045500 0.070600 -vn 0.707107 0.707107 0.000000 -v 0.026280 0.045500 0.062325 -vn 0.770262 0.000000 -0.637728 -v 0.026280 0.037000 0.066000 -vn 0.685696 0.071346 0.724383 -v 0.026280 0.041500 0.074600 -vn 0.770262 0.318864 -0.552288 -v 0.026280 0.035625 0.065632 -vn 0.707107 0.000000 0.707107 -v 0.026280 0.029500 0.074600 -vn 0.770261 0.552289 -0.318863 -v 0.026280 0.034618 0.064625 -vn 1.000000 0.000000 -0.000000 -v 0.026280 0.029500 0.056750 -vn 0.770261 0.000000 0.637728 -v 0.026280 0.037000 0.060500 -vn 0.770262 -0.637727 0.000001 -v 0.026280 0.039750 0.063250 -vn 0.770261 -0.552289 0.318864 -v 0.026280 0.039382 0.061875 -vn 0.707107 0.707107 0.000000 -v 0.026280 0.045500 0.056750 -vn 0.770262 -0.318863 0.552288 -v 0.026280 0.038375 0.060868 -vn 0.770262 0.000000 -0.637728 -v 0.026280 0.037000 0.050000 -vn 0.770262 -0.318864 -0.552288 -v 0.026280 0.038375 0.049632 -vn 0.707107 0.707107 0.000000 -v 0.026280 0.045500 0.051500 -vn 0.770262 -0.552289 -0.318864 -v 0.026280 0.039382 0.048625 -vn 0.707107 0.707107 0.000000 -v 0.026280 0.045500 0.046500 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.029500 0.046500 -vn 0.770262 0.637728 -0.000000 -v 0.026280 0.034250 0.047250 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.029500 0.051500 -vn 0.770262 0.552289 -0.318864 -v 0.026280 0.034618 0.048625 -vn 0.770262 0.318865 -0.552288 -v 0.026280 0.035625 0.049632 -vn 0.770262 -0.637728 0.000000 -v 0.026280 0.039750 0.047250 -vn 0.770262 -0.552289 0.318864 -v 0.026280 0.039382 0.045875 -vn 0.707107 0.707107 0.000000 -v 0.026280 0.045500 0.024688 -vn 0.770262 -0.318863 0.552288 -v 0.026280 0.038375 0.044868 -vn 0.770261 0.000000 0.637728 -v 0.026280 0.037000 0.044500 -vn 0.770262 0.318864 0.552288 -v 0.026280 0.035625 0.044868 -vn 0.770262 0.552289 0.318864 -v 0.026280 0.034618 0.045875 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.042625 0.046500 -vn 0.770261 0.637728 -0.000000 -v 0.026280 -0.039750 0.047250 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.042625 0.051500 -vn 0.770262 0.552289 -0.318863 -v 0.026280 -0.039382 0.048625 -vn 0.770262 -0.552288 -0.318864 -v 0.026280 -0.034618 0.048625 -vn 0.770262 -0.637728 0.000000 -v 0.026280 -0.034250 0.047250 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.029500 0.046500 -vn 0.770262 0.318864 -0.552288 -v 0.026280 -0.038375 0.049632 -vn 0.770262 -0.000000 -0.637728 -v 0.026280 -0.037000 0.050000 -vn 0.770262 -0.318864 -0.552288 -v 0.026280 -0.035625 0.049632 -vn 0.770262 -0.318863 0.552289 -v 0.026280 -0.035625 0.044868 -vn 0.770261 0.000000 0.637728 -v 0.026280 -0.037000 0.044500 -vn 0.770262 0.318863 0.552289 -v 0.026280 -0.038375 0.044868 -vn 0.770262 0.552289 0.318863 -v 0.026280 -0.039382 0.045875 -vn 0.770262 -0.552288 -0.318864 -v 0.026280 -0.034618 0.064625 -vn 0.665719 -0.285559 0.689401 -v 0.026280 -0.043031 0.074296 -vn 1.000000 -0.000000 0.000000 -v 0.026280 -0.042625 0.062325 -vn 0.770261 0.637728 0.000001 -v 0.026280 -0.039750 0.063250 -vn 0.770262 0.552289 -0.318863 -v 0.026280 -0.039382 0.064625 -vn 0.770262 0.318864 -0.552289 -v 0.026280 -0.038375 0.065632 -vn 0.685696 -0.071346 0.724383 -v 0.026280 -0.041500 0.074600 -vn 0.770262 -0.000000 -0.637728 -v 0.026280 -0.037000 0.066000 -vn 0.707107 -0.000000 0.707107 -v 0.026280 -0.029500 0.074600 -vn 0.770262 -0.318864 -0.552289 -v 0.026280 -0.035625 0.065632 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.042625 0.056750 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.029500 0.056750 -vn 0.770262 -0.318863 0.552289 -v 0.026280 -0.035625 0.060868 -vn 0.770261 0.000000 0.637728 -v 0.026280 -0.037000 0.060500 -vn 0.770262 0.318863 0.552289 -v 0.026280 -0.038375 0.060868 -vn 0.770262 0.552289 0.318863 -v 0.026280 -0.039382 0.061875 -vn 1.000000 -0.000000 0.000000 -v 0.026280 -0.029500 0.024688 -vn 0.770262 0.318863 0.552289 -v 0.026280 -0.023625 0.031426 -vn 0.770262 0.552288 0.318864 -v 0.026280 -0.024449 0.032250 -vn 0.770262 0.637728 0.000000 -v 0.026280 -0.024750 0.033375 -vn 0.770262 -0.552288 0.318864 -v 0.026280 -0.034618 0.045875 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.014975 0.024688 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.000000 0.046500 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.000000 0.024688 -vn 0.770262 -0.552288 -0.318865 -v 0.026280 -0.020551 0.034500 -vn 0.770262 0.552289 -0.318864 -v 0.026280 -0.024449 0.034500 -vn 0.770262 0.318864 -0.552288 -v 0.026280 -0.023625 0.035324 -vn 1.000000 0.000000 -0.000000 -v 0.026280 -0.022500 0.046500 -vn 0.770262 0.000000 -0.637728 -v 0.026280 -0.022500 0.035625 -vn 0.770262 -0.318863 -0.552289 -v 0.026280 -0.021375 0.035324 -vn 0.770262 -0.637728 0.000000 -v 0.026280 -0.020250 0.033375 -vn 0.770262 -0.552288 0.318865 -v 0.026280 -0.020551 0.032250 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.022500 0.024688 -vn 0.770262 -0.318861 0.552289 -v 0.026280 -0.021375 0.031426 -vn 0.770262 0.000000 0.637728 -v 0.026280 -0.022500 0.031125 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.022500 0.009875 -vn 0.770262 0.000000 0.637728 -v 0.026280 -0.022500 0.013750 -vn 1.000000 -0.000000 0.000000 -v 0.026280 -0.029500 0.009875 -vn 0.770262 0.318864 0.552289 -v 0.026280 -0.023625 0.014051 -vn 0.770262 0.318864 -0.552288 -v 0.026280 -0.023625 0.017949 -vn 0.770262 0.552288 0.318864 -v 0.026280 -0.024449 0.014875 -vn 0.770262 0.637728 -0.000000 -v 0.026280 -0.024750 0.016000 -vn 0.770262 0.552288 -0.318864 -v 0.026280 -0.024449 0.017125 -vn 0.770262 -0.552288 -0.318865 -v 0.026280 -0.020551 0.017125 -vn 0.770262 -0.318864 -0.552289 -v 0.026280 -0.021375 0.017949 -vn 0.770262 0.000000 -0.637728 -v 0.026280 -0.022500 0.018250 -vn 0.770262 -0.637728 -0.000000 -v 0.026280 -0.020250 0.016000 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.000000 0.009875 -vn 0.770262 -0.552288 0.318864 -v 0.026280 -0.020551 0.014875 -vn 0.770263 -0.318862 0.552288 -v 0.026280 -0.021375 0.014051 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.014975 0.056750 -vn 0.770262 0.318864 -0.552288 -v 0.026280 0.021375 0.052699 -vn 0.770262 0.000000 -0.637728 -v 0.026280 0.022500 0.053000 -vn 0.770262 -0.318864 -0.552289 -v 0.026280 0.023625 0.052699 -vn 0.770262 0.552289 0.318863 -v 0.026280 0.020551 0.049625 -vn 0.770262 -0.552288 -0.318864 -v 0.026280 0.024449 0.051875 -vn 0.770262 -0.637728 0.000000 -v 0.026280 0.024750 0.050750 -vn 0.770262 -0.552289 0.318864 -v 0.026280 0.024449 0.049625 -vn 0.770262 0.318864 0.552289 -v 0.026280 0.021375 0.048801 -vn 1.000000 0.000000 -0.000000 -v 0.026280 0.014975 0.046500 -vn 0.770262 0.000000 0.637728 -v 0.026280 0.022500 0.048500 -vn 0.770262 -0.318864 0.552288 -v 0.026280 0.023625 0.048801 -vn 0.770262 0.318864 -0.552288 -v 0.026280 -0.023625 0.052699 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.022500 0.056750 -vn 0.770262 0.552288 0.318864 -v 0.026280 -0.024449 0.049625 -vn 0.770262 -0.637728 0.000000 -v 0.026280 -0.020250 0.050750 -vn 0.770262 -0.552288 0.318865 -v 0.026280 -0.020551 0.049625 -vn 0.770262 -0.318864 0.552289 -v 0.026280 -0.021375 0.048801 -vn 0.770262 0.000000 0.637728 -v 0.026280 -0.022500 0.048500 -vn 0.770262 0.318864 0.552289 -v 0.026280 -0.023625 0.048801 -vn 0.707107 0.000000 -0.707107 -v 0.026280 0.029500 0.006000 -vn 0.685697 0.071345 -0.724383 -v 0.026280 0.041500 0.006000 -vn 0.685696 0.724383 -0.071346 -v 0.026280 0.045500 0.010000 -vn 0.665719 0.285560 -0.689401 -v 0.026280 0.043031 0.006304 -vn 0.665719 0.527645 -0.527645 -v 0.026280 0.044328 0.007172 -vn 0.665719 0.689401 -0.285560 -v 0.026280 0.045196 0.008469 -vn 0.665719 -0.689402 -0.285559 -v 0.026280 -0.045196 0.008469 -vn 0.665719 -0.527645 -0.527645 -v 0.026280 -0.044328 0.007172 -vn 0.665719 -0.285559 -0.689402 -v 0.026280 -0.043031 0.006304 -vn 0.707107 -0.707107 0.000000 -v 0.026280 -0.045500 0.056750 -vn 0.707107 -0.707107 0.000000 -v 0.026280 -0.045500 0.062325 -vn 0.685696 -0.724383 0.071345 -v 0.026280 -0.045500 0.070600 -vn 0.665719 -0.689402 0.285559 -v 0.026280 -0.045196 0.072131 -vn 0.665719 -0.527645 0.527645 -v 0.026280 -0.044328 0.073428 -vn 0.707107 -0.707107 0.000000 -v 0.026280 -0.045500 0.051500 -vn 0.707107 -0.707107 0.000000 -v 0.026280 -0.045500 0.046500 -vn 0.707107 -0.707107 0.000000 -v 0.026280 -0.045500 0.024688 -vn 0.685697 -0.071345 -0.724383 -v 0.026280 -0.041500 0.006000 -vn 0.770261 0.552290 -0.318864 -v 0.026280 -0.009372 0.067825 -vn 0.770263 0.318864 -0.552287 -v 0.026280 -0.008475 0.068722 -vn 0.707107 0.000000 0.707107 -v 0.026280 -0.022500 0.074600 -vn 1.000000 0.000000 0.000000 -v 0.026280 -0.022500 0.062325 -vn 0.770262 0.552289 0.318864 -v 0.026280 -0.009372 0.065375 -vn 0.770262 0.637727 -0.000000 -v 0.026280 -0.009700 0.066600 -vn 0.707107 0.000000 0.707107 -v 0.026280 0.000000 0.074600 -vn 0.770262 -0.637728 -0.000001 -v 0.026280 -0.004800 0.066600 -vn 0.770262 -0.552288 0.318865 -v 0.026280 -0.005128 0.065375 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.000000 0.062325 -vn 0.770261 -0.552289 -0.318864 -v 0.026280 -0.005128 0.067825 -vn 0.770261 -0.318865 0.552289 -v 0.026280 -0.006025 0.064478 -vn 0.770262 -0.000000 0.637727 -v 0.026280 -0.007250 0.064150 -vn 0.770261 0.318865 0.552289 -v 0.026280 -0.008475 0.064478 -vn 0.770261 -0.000000 -0.637728 -v 0.026280 -0.007250 0.069050 -vn 0.770262 -0.318864 -0.552288 -v 0.026280 -0.006025 0.068722 -vn 0.770262 0.552288 0.318865 -v 0.026280 0.005128 0.065375 -vn 0.770262 0.637728 -0.000000 -v 0.026280 0.004800 0.066600 -vn 0.770262 -0.637728 -0.000001 -v 0.026280 0.009700 0.066600 -vn 0.770262 -0.552288 0.318865 -v 0.026280 0.009372 0.065375 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.014975 0.062325 -vn 0.770261 0.552289 -0.318864 -v 0.026280 0.005128 0.067825 -vn 0.770262 0.318864 -0.552288 -v 0.026280 0.006025 0.068722 -vn 0.770261 -0.000000 -0.637728 -v 0.026280 0.007250 0.069050 -vn 0.707107 0.000000 0.707107 -v 0.026280 0.014975 0.074600 -vn 0.770262 -0.318864 -0.552288 -v 0.026280 0.008475 0.068722 -vn 0.770261 -0.552289 -0.318864 -v 0.026280 0.009372 0.067825 -vn 0.770261 -0.318865 0.552289 -v 0.026280 0.008475 0.064478 -vn 0.770263 -0.000000 0.637727 -v 0.026280 0.007250 0.064150 -vn 0.770261 0.318865 0.552289 -v 0.026280 0.006025 0.064478 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.000000 0.056750 -vn 0.770262 0.000000 -0.637728 -v 0.026280 -0.022500 0.053000 -vn 0.770262 0.318864 0.552289 -v 0.026280 0.021375 0.031426 -vn 0.770262 0.552288 0.318864 -v 0.026280 0.020551 0.032250 -vn 0.770262 -0.318864 -0.552289 -v 0.026280 0.023625 0.035324 -vn 0.770262 -0.552288 -0.318864 -v 0.026280 0.024449 0.034500 -vn 0.770262 -0.637728 0.000000 -v 0.026280 0.024750 0.033375 -vn 0.770262 -0.552288 0.318864 -v 0.026280 0.024449 0.032250 -vn 0.770262 0.637728 0.000000 -v 0.026280 0.020250 0.033375 -vn 0.770262 0.552289 -0.318864 -v 0.026280 0.020551 0.034500 -vn 0.770262 0.318865 -0.552288 -v 0.026280 0.021375 0.035324 -vn 0.770262 0.000000 -0.637728 -v 0.026280 0.022500 0.035625 -vn 0.770262 0.552289 -0.318864 -v 0.026280 0.020551 0.017125 -vn 0.770262 0.318865 -0.552288 -v 0.026280 0.021375 0.017949 -vn 0.770262 -0.552289 0.318864 -v 0.026280 0.024449 0.014875 -vn 0.770262 -0.318864 0.552288 -v 0.026280 0.023625 0.014051 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.029500 0.009875 -vn 0.770262 0.000000 0.637728 -v 0.026280 0.022500 0.013750 -vn 1.000000 0.000000 0.000000 -v 0.026280 0.014975 0.009875 -vn 0.770262 0.318864 0.552288 -v 0.026280 0.021375 0.014051 -vn 0.770262 0.552289 0.318863 -v 0.026280 0.020551 0.014875 -vn 0.770262 0.637728 -0.000000 -v 0.026280 0.020250 0.016000 -vn 0.770262 -0.000000 -0.637728 -v 0.026280 0.022500 0.018250 -vn 0.770262 -0.318864 -0.552288 -v 0.026280 0.023625 0.017949 -vn 0.770262 -0.552288 -0.318864 -v 0.026280 0.024449 0.017125 -vn 0.770262 -0.637728 -0.000000 -v 0.026280 0.024750 0.016000 -vn 0.707107 0.000000 -0.707107 -v 0.026280 0.014975 0.006000 -vn 0.707107 0.000000 -0.707107 -v 0.026280 0.000000 0.006000 -vn 0.707107 0.000000 -0.707107 -v 0.026280 -0.022500 0.006000 -vn 0.707107 0.000000 -0.707107 -v 0.026280 -0.029500 0.006000 -vn 0.724650 -0.050258 -0.687282 -v 0.025273 0.062735 0.246800 -vn 0.724650 -0.050258 0.687282 -v 0.025273 0.062735 0.248800 -vn 0.692866 -0.083504 -0.716215 -v 0.021252 0.037802 0.246800 -vn 0.692866 -0.083503 0.716215 -v 0.021252 0.037802 0.248800 -vn 0.697322 -0.027894 -0.716215 -v 0.019234 0.012628 0.246800 -vn 0.697322 -0.027894 0.716215 -v 0.019234 0.012628 0.248800 -vn 0.697322 0.027894 -0.716215 -v 0.019234 -0.012628 0.246800 -vn 0.697322 0.027894 0.716215 -v 0.019234 -0.012628 0.248800 -vn 0.698898 0.070434 -0.711745 -v 0.021252 -0.037802 0.246800 -vn 0.698898 0.070434 0.711745 -v 0.021252 -0.037802 0.248800 -vn 0.695588 0.098669 -0.711633 -v 0.021326 -0.038416 0.246800 -vn 0.695588 0.098669 0.711633 -v 0.021326 -0.038416 0.248800 -vn 0.724723 0.050619 -0.687178 -v 0.025273 -0.062735 0.246800 -vn 0.724723 0.050619 0.687178 -v 0.025273 -0.062735 0.248800 -vn 0.673484 0.277961 -0.684950 -v 0.031078 -0.086584 0.246800 -vn 0.673484 0.277961 0.684950 -v 0.031078 -0.086584 0.248800 -vn 0.671709 0.210522 -0.710273 -v 0.033261 -0.093908 0.246800 -vn 0.671708 0.210522 0.710274 -v 0.033261 -0.093908 0.248800 -vn 0.666428 0.228086 -0.709825 -v 0.036404 -0.103465 0.246800 -vn 0.666427 0.228086 0.709825 -v 0.036404 -0.103465 0.248800 -vn 0.664328 0.239457 -0.708046 -v 0.038128 -0.108310 0.246800 -vn 0.664328 0.239457 0.708046 -v 0.038128 -0.108310 0.248800 -vn 0.700885 0.188386 -0.687947 -v 0.038143 -0.108353 0.246800 -vn 0.700885 0.188386 0.687947 -v 0.038143 -0.108353 0.248800 -vn 0.727973 -0.095840 0.678874 -v 0.038750 -0.140000 0.248800 -vn 0.727973 -0.095840 -0.678874 -v 0.038750 -0.140000 0.246800 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.125125 0.248800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.125125 0.246800 -vn 0.722978 0.063435 0.687953 -v 0.038750 -0.111783 0.248800 -vn 0.722978 0.063435 -0.687953 -v 0.038750 -0.111783 0.246800 -vn -0.672729 -0.081889 -0.735343 -v 0.011750 -0.125000 0.246800 -vn -0.672729 -0.081889 0.735343 -v 0.011750 -0.125000 0.248800 -vn -0.569587 -0.299817 -0.765298 -v 0.010599 -0.120342 0.246800 -vn -0.569587 -0.299817 0.765298 -v 0.010599 -0.120342 0.248800 -vn -0.436638 -0.512366 -0.739479 -v 0.007411 -0.116757 0.246800 -vn -0.436638 -0.512366 0.739479 -v 0.007411 -0.116757 0.248800 -vn 0.727973 0.095840 -0.678874 -v 0.038750 0.140000 0.246800 -vn 0.727973 0.095840 0.678874 -v 0.038750 0.140000 0.248800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.125125 0.246800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.125125 0.248800 -vn 0.722978 -0.063435 -0.687953 -v 0.038750 0.111783 0.246800 -vn 0.722978 -0.063435 0.687953 -v 0.038750 0.111783 0.248800 -vn -0.584725 -0.281589 0.760792 -v -0.073349 -0.074983 0.248800 -vn -0.675741 -0.076134 0.733196 -v -0.073250 -0.075417 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.068275 0.248800 -vn -0.552288 -0.318865 0.770262 -v 0.031348 0.137500 0.248800 -vn -0.637728 -0.000001 0.770262 -v 0.031750 0.136000 0.248800 -vn -0.721981 0.058200 0.689461 -v -0.090250 0.041577 0.248800 -vn -0.707107 0.000000 0.707106 -v -0.090250 -0.000000 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.086375 -0.000000 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 0.058858 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 0.058858 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.103420 0.248800 -vn 0.637728 0.000000 0.770262 -v 0.000600 -0.100720 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.093851 0.248800 -vn 0.552289 -0.318863 0.770261 -v 0.001022 -0.099145 0.248800 -vn 0.318864 -0.552288 0.770263 -v 0.002175 -0.097992 0.248800 -vn 0.000000 -0.637729 0.770261 -v 0.003750 -0.097570 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 -0.093851 0.248800 -vn -0.637728 0.000000 0.770262 -v 0.006900 -0.100720 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 -0.103420 0.248800 -vn -0.552289 -0.318863 0.770262 -v 0.006478 -0.099145 0.248800 -vn -0.318863 -0.552288 0.770262 -v 0.005325 -0.097992 0.248800 -vn -0.552289 0.318864 0.770262 -v 0.006478 -0.102295 0.248800 -vn -0.318863 0.552288 0.770262 -v 0.005325 -0.103448 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 -0.108310 0.248800 -vn -0.000000 0.637729 0.770261 -v 0.003750 -0.103870 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.108310 0.248800 -vn 0.318864 0.552288 0.770263 -v 0.002175 -0.103448 0.248800 -vn 0.552289 0.318864 0.770261 -v 0.001022 -0.102295 0.248800 -vn 0.552289 0.318863 0.770261 -v 0.001022 0.099145 0.248800 -vn 0.637728 -0.000000 0.770262 -v 0.000600 0.100720 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.098020 0.248800 -vn 0.552289 -0.318864 0.770261 -v 0.001022 0.102295 0.248800 -vn 0.318864 -0.552288 0.770263 -v 0.002175 0.103448 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.108310 0.248800 -vn -0.637728 -0.000000 0.770262 -v 0.006900 0.100720 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 0.098020 0.248800 -vn -0.552289 -0.318864 0.770261 -v 0.006478 0.102295 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 0.108310 0.248800 -vn -0.318863 -0.552288 0.770262 -v 0.005325 0.103448 0.248800 -vn 0.000000 -0.637729 0.770261 -v 0.003750 0.103870 0.248800 -vn -0.552289 0.318863 0.770262 -v 0.006478 0.099145 0.248800 -vn -0.318863 0.552288 0.770262 -v 0.005325 0.097992 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 0.093851 0.248800 -vn 0.318864 0.552288 0.770263 -v 0.002175 0.097992 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.093851 0.248800 -vn 0.000000 0.637729 0.770261 -v 0.003750 0.097570 0.248800 -vn 0.637728 0.000000 0.770262 -v 0.026500 0.115000 0.248800 -vn 0.552289 -0.318864 0.770262 -v 0.026801 0.116125 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 0.125125 0.248800 -vn 0.318864 -0.552289 0.770262 -v 0.027625 0.116949 0.248800 -vn 0.000000 -0.637728 0.770262 -v 0.028750 0.117250 0.248800 -vn 0.552289 0.318864 0.770262 -v 0.026801 0.113875 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 0.108310 0.248800 -vn 0.318864 0.552289 0.770262 -v 0.027625 0.113051 0.248800 -vn 0.000000 0.637728 0.770262 -v 0.028750 0.112750 0.248800 -vn -0.318864 -0.552288 0.770262 -v 0.029875 0.116949 0.248800 -vn -0.552289 -0.318863 0.770262 -v 0.030699 0.116125 0.248800 -vn -0.637728 0.000000 0.770262 -v 0.031000 0.115000 0.248800 -vn 0.700885 -0.188386 0.687947 -v 0.038143 0.108353 0.248800 -vn -0.552290 0.318864 0.770261 -v 0.030699 0.113875 0.248800 -vn 0.664436 -0.236128 0.709061 -v 0.038128 0.108310 0.248800 -vn -0.318864 0.552288 0.770262 -v 0.029875 0.113051 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 0.098020 0.248800 -vn 0.668450 -0.222089 0.709825 -v 0.034593 0.098084 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 0.093851 0.248800 -vn 0.673628 -0.207804 0.709255 -v 0.033261 0.093908 0.248800 -vn 0.078494 -0.725548 0.683680 -v 0.029155 0.085132 0.248800 -vn 0.313172 -0.680950 0.661989 -v 0.029990 0.085315 0.248800 -vn 0.673484 -0.277961 0.684950 -v 0.031078 0.086584 0.248800 -vn 0.569050 -0.487805 0.661988 -v 0.030673 0.085831 0.248800 -vn 0.000000 -0.707107 0.707107 -v 0.021350 0.085132 0.248800 -vn -0.637729 0.000000 0.770261 -v 0.016950 0.089132 0.248800 -vn -0.552289 0.318862 0.770262 -v 0.016816 0.088632 0.248800 -vn 0.318864 -0.552288 0.770262 -v 0.003750 0.083793 0.248800 -vn 0.088122 -0.669353 0.737700 -v 0.008750 0.085132 0.248800 -vn 0.318865 0.552290 0.770261 -v 0.010950 0.088266 0.248800 -vn -0.318865 0.552288 0.770262 -v 0.016450 0.088266 0.248800 -vn -0.088123 0.669352 0.737701 -v 0.015950 0.088132 0.248800 -vn 0.088123 0.669352 0.737701 -v 0.011450 0.088132 0.248800 -vn 0.552287 0.318863 0.770263 -v 0.010584 0.088632 0.248800 -vn 0.637729 0.000000 0.770261 -v 0.010450 0.089132 0.248800 -vn 0.552287 -0.318863 0.770263 -v 0.010584 0.089632 0.248800 -vn 0.318865 -0.552290 0.770261 -v 0.010950 0.089999 0.248800 -vn -0.552289 -0.318862 0.770262 -v 0.016816 0.089632 0.248800 -vn 0.088123 -0.669352 0.737701 -v 0.011450 0.090132 0.248800 -vn -0.088123 -0.669352 0.737701 -v 0.015950 0.090132 0.248800 -vn -0.318865 -0.552288 0.770261 -v 0.016450 0.089999 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.084525 0.248800 -vn 0.552289 -0.318864 0.770262 -v 0.000090 0.080132 0.248800 -vn 0.637728 -0.000000 0.770262 -v -0.001250 0.075132 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.068275 0.248800 -vn 0.552289 0.318864 0.770262 -v 0.000090 0.070132 0.248800 -vn 0.318864 0.552289 0.770261 -v 0.003750 0.066472 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 0.058858 0.248800 -vn -0.552289 -0.318862 0.770262 -v 0.016816 0.061632 0.248800 -vn -0.637729 0.000000 0.770261 -v 0.016950 0.061132 0.248800 -vn -0.552289 0.318862 0.770262 -v 0.016816 0.060632 0.248800 -vn 0.318865 0.552290 0.770261 -v 0.010950 0.060266 0.248800 -vn 0.552287 0.318863 0.770263 -v 0.010584 0.060632 0.248800 -vn 0.088122 0.669353 0.737700 -v 0.008750 0.065132 0.248800 -vn 0.552287 -0.318863 0.770263 -v 0.010584 0.061632 0.248800 -vn 0.637729 0.000000 0.770261 -v 0.010450 0.061132 0.248800 -vn -0.318865 0.552288 0.770262 -v 0.016450 0.060266 0.248800 -vn -0.088123 0.669352 0.737701 -v 0.015950 0.060132 0.248800 -vn 0.088123 0.669352 0.737701 -v 0.011450 0.060132 0.248800 -vn 0.318862 -0.552290 0.770262 -v 0.010950 0.061999 0.248800 -vn 0.088121 -0.669353 0.737700 -v 0.011450 0.062132 0.248800 -vn 0.000000 0.707107 0.707107 -v 0.021350 0.065132 0.248800 -vn -0.088121 -0.669353 0.737700 -v 0.015950 0.062132 0.248800 -vn -0.318862 -0.552289 0.770262 -v 0.016450 0.061999 0.248800 -vn 0.080660 0.725882 0.683074 -v 0.023313 0.065132 0.248800 -vn 0.321481 0.678160 0.660870 -v 0.024170 0.064940 0.248800 -vn 0.580987 0.475082 0.660871 -v 0.024861 0.064399 0.248800 -vn 0.728492 0.180418 0.660870 -v 0.025254 0.063613 0.248800 -vn -0.552289 -0.318862 0.770262 -v 0.016816 -0.060632 0.248800 -vn -0.637729 0.000000 0.770261 -v 0.016950 -0.061132 0.248800 -vn 0.000000 -0.707107 0.707107 -v 0.021350 -0.065132 0.248800 -vn -0.552289 0.318862 0.770262 -v 0.016816 -0.061632 0.248800 -vn -0.318862 0.552289 0.770262 -v 0.016450 -0.061999 0.248800 -vn -0.088121 0.669353 0.737700 -v 0.015950 -0.062132 0.248800 -vn 0.088122 -0.669352 0.737700 -v 0.008750 -0.065132 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.008675 0.000000 0.248800 -vn 0.552287 -0.318863 0.770263 -v 0.010584 -0.060632 0.248800 -vn 0.318865 -0.552290 0.770261 -v 0.010950 -0.060266 0.248800 -vn 0.318864 -0.552289 0.770261 -v 0.003750 -0.066472 0.248800 -vn 0.637729 0.000000 0.770261 -v 0.010450 -0.061132 0.248800 -vn 0.088121 0.669353 0.737700 -v 0.011450 -0.062132 0.248800 -vn 0.318862 0.552290 0.770261 -v 0.010950 -0.061999 0.248800 -vn 0.552287 0.318863 0.770263 -v 0.010584 -0.061632 0.248800 -vn -0.318865 -0.552288 0.770261 -v 0.016450 -0.060266 0.248800 -vn -0.088123 -0.669352 0.737700 -v 0.015950 -0.060132 0.248800 -vn 0.088123 -0.669352 0.737701 -v 0.011450 -0.060132 0.248800 -vn 0.580988 -0.475081 0.660871 -v 0.024861 -0.064399 0.248800 -vn 0.728492 -0.180417 0.660870 -v 0.025254 -0.063613 0.248800 -vn 0.321481 -0.678160 0.660870 -v 0.024170 -0.064940 0.248800 -vn 0.080660 -0.725882 0.683073 -v 0.023313 -0.065132 0.248800 -vn 0.552289 0.318864 0.770262 -v 0.000090 -0.080132 0.248800 -vn 0.637728 0.000000 0.770262 -v -0.001250 -0.075132 0.248800 -vn 0.552289 -0.318864 0.770262 -v 0.000090 -0.070132 0.248800 -vn 0.090800 0.668991 0.737703 -v 0.008670 -0.085132 0.248800 -vn 0.320282 0.552181 0.769750 -v 0.003750 -0.083793 0.248800 -vn 0.088123 0.669352 0.737701 -v 0.011450 -0.090132 0.248800 -vn 0.318865 0.552290 0.770261 -v 0.010950 -0.089999 0.248800 -vn 0.000000 0.707107 0.707107 -v 0.021350 -0.085132 0.248800 -vn -0.318865 -0.552288 0.770261 -v 0.016450 -0.088266 0.248800 -vn -0.552289 -0.318862 0.770262 -v 0.016816 -0.088632 0.248800 -vn -0.552289 0.318862 0.770262 -v 0.016816 -0.089632 0.248800 -vn -0.318865 0.552288 0.770262 -v 0.016450 -0.089999 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 -0.093851 0.248800 -vn -0.088123 0.669352 0.737701 -v 0.015950 -0.090132 0.248800 -vn -0.637729 0.000000 0.770261 -v 0.016950 -0.089132 0.248800 -vn 0.552287 0.318863 0.770263 -v 0.010584 -0.089632 0.248800 -vn 0.637729 0.000000 0.770261 -v 0.010450 -0.089132 0.248800 -vn 0.552286 -0.318863 0.770264 -v 0.010584 -0.088632 0.248800 -vn 0.001410 0.706656 0.707556 -v 0.008750 -0.085132 0.248800 -vn 0.318865 -0.552290 0.770261 -v 0.010950 -0.088266 0.248800 -vn 0.088123 -0.669352 0.737701 -v 0.011450 -0.088132 0.248800 -vn -0.088123 -0.669352 0.737701 -v 0.015950 -0.088132 0.248800 -vn 0.569050 0.487805 0.661988 -v 0.030673 -0.085831 0.248800 -vn 0.078494 0.725548 0.683680 -v 0.029155 -0.085132 0.248800 -vn 0.313172 0.680950 0.661989 -v 0.029990 -0.085315 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 -0.103420 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 -0.108310 0.248800 -vn 0.552289 -0.318864 0.770262 -v 0.026801 -0.113875 0.248800 -vn 0.318864 -0.552289 0.770262 -v 0.027625 -0.113051 0.248800 -vn 0.000000 -0.637728 0.770262 -v 0.028750 -0.112750 0.248800 -vn -0.318865 -0.552288 0.770262 -v 0.029875 -0.113051 0.248800 -vn -0.552289 -0.318863 0.770262 -v 0.030699 -0.113875 0.248800 -vn -0.637728 0.000000 0.770262 -v 0.031000 -0.115000 0.248800 -vn 0.000000 0.637728 0.770262 -v 0.028750 -0.117250 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 -0.125125 0.248800 -vn -0.318864 0.552288 0.770262 -v 0.029875 -0.116949 0.248800 -vn -0.552289 0.318863 0.770262 -v 0.030699 -0.116125 0.248800 -vn 0.318864 0.552289 0.770262 -v 0.027625 -0.116949 0.248800 -vn 0.552289 0.318864 0.770262 -v 0.026801 -0.116125 0.248800 -vn 0.637728 0.000000 0.770262 -v 0.026500 -0.115000 0.248800 -vn 0.637728 0.000001 0.770262 -v 0.025750 -0.136000 0.248800 -vn 0.552288 -0.318864 0.770262 -v 0.026152 -0.134500 0.248800 -vn -0.552287 0.318866 0.770262 -v 0.031348 -0.137500 0.248800 -vn 0.655722 -0.378581 0.653227 -v 0.038080 -0.142500 0.248800 -vn -0.637728 0.000001 0.770262 -v 0.031750 -0.136000 0.248800 -vn -0.552287 -0.318865 0.770263 -v 0.031348 -0.134500 0.248800 -vn -0.318864 0.552290 0.770261 -v 0.030250 -0.138598 0.248800 -vn -0.000000 0.637727 0.770263 -v 0.028750 -0.139000 0.248800 -vn 0.000000 0.000000 1.000000 -v 0.021350 -0.142000 0.248800 -vn 0.318864 0.552289 0.770261 -v 0.027250 -0.138598 0.248800 -vn 0.552288 0.318865 0.770262 -v 0.026152 -0.137500 0.248800 -vn 0.318864 -0.552289 0.770261 -v 0.027250 -0.133402 0.248800 -vn -0.000000 -0.637727 0.770263 -v 0.028750 -0.133000 0.248800 -vn -0.318864 -0.552290 0.770261 -v 0.030250 -0.133402 0.248800 -vn -0.727973 -0.095840 0.678874 -v 0.011750 -0.140000 0.248800 -vn -0.655722 -0.378581 0.653227 -v 0.012420 -0.142500 0.248800 -vn -0.378581 -0.655722 0.653227 -v 0.014250 -0.144330 0.248800 -vn -0.095839 -0.727973 0.678875 -v 0.016750 -0.145000 0.248800 -vn 0.000000 -0.707107 0.707107 -v 0.021350 -0.145000 0.248800 -vn 0.095838 -0.727973 0.678875 -v 0.033750 -0.145000 0.248800 -vn 0.378581 -0.655722 0.653226 -v 0.036250 -0.144330 0.248800 -vn -0.707107 -0.000000 0.707107 -v 0.011750 -0.125125 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.103420 0.248800 -vn -0.012296 -0.680499 0.732645 -v -0.027153 -0.104228 0.248800 -vn -0.160362 -0.661449 0.732645 -v -0.014800 -0.105817 0.248800 -vn -0.300714 -0.610575 0.732646 -v -0.003091 -0.110062 0.248800 -vn 0.283943 -0.720103 0.633110 -v -0.071250 -0.124000 0.248800 -vn 0.407161 -0.545390 0.732645 -v -0.062147 -0.115500 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.108310 0.248800 -vn 0.278460 -0.621040 0.732645 -v -0.051410 -0.109188 0.248800 -vn 0.136363 -0.666810 0.732645 -v -0.039555 -0.105370 0.248800 -vn 0.318864 -0.552289 0.770262 -v -0.081375 -0.113051 0.248800 -vn 0.000000 -0.637728 0.770262 -v -0.080250 -0.112750 0.248800 -vn 0.000000 -0.707107 0.707107 -v -0.076625 -0.124000 0.248800 -vn -0.637728 0.000000 0.770262 -v -0.078000 -0.115000 0.248800 -vn -0.552289 0.318864 0.770262 -v -0.078301 -0.116125 0.248800 -vn 0.637728 0.000000 0.770262 -v -0.082500 -0.115000 0.248800 -vn 0.552289 -0.318864 0.770262 -v -0.082199 -0.113875 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.086375 -0.108310 0.248800 -vn -0.318864 -0.552289 0.770262 -v -0.079125 -0.113051 0.248800 -vn -0.552289 -0.318864 0.770262 -v -0.078301 -0.113875 0.248800 -vn -0.318864 0.552289 0.770262 -v -0.079125 -0.116949 0.248800 -vn 0.000000 0.637728 0.770262 -v -0.080250 -0.117250 0.248800 -vn -0.095839 -0.727973 0.678874 -v -0.085250 -0.124000 0.248800 -vn 0.318864 0.552288 0.770262 -v -0.081375 -0.116949 0.248800 -vn -0.378581 -0.655722 0.653227 -v -0.087750 -0.123330 0.248800 -vn 0.552289 0.318864 0.770262 -v -0.082199 -0.116125 0.248800 -vn -0.727973 -0.095840 0.678874 -v -0.090250 -0.119000 0.248800 -vn -0.655722 -0.378581 0.653227 -v -0.089580 -0.121500 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.086375 -0.093851 0.248800 -vn -0.469341 0.572463 0.672313 -v -0.088113 -0.086766 0.248800 -vn -0.668285 0.348441 0.657255 -v -0.089684 -0.088554 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.084525 0.248800 -vn -0.623292 0.226860 0.748359 -v -0.078371 -0.080601 0.248800 -vn -0.508111 0.426354 0.748361 -v -0.078718 -0.081203 0.248800 -vn -0.393681 0.562235 0.727260 -v -0.079250 -0.081649 0.248800 -vn -0.548586 -0.526558 0.649454 -v -0.089250 -0.044577 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.000000 0.248800 -vn -0.410993 -0.535615 0.737701 -v -0.079250 -0.050351 0.248800 -vn -0.552289 -0.318865 0.770261 -v -0.078518 -0.051083 0.248800 -vn -0.669352 -0.088123 0.737701 -v -0.078250 -0.052083 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.068275 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.078250 -0.068275 0.248800 -vn -0.683749 0.059822 0.727261 -v -0.078250 -0.079917 0.248800 -vn -0.721981 -0.058200 0.689461 -v -0.090250 -0.041577 0.248800 -vn -0.701887 -0.233963 0.672768 -v -0.089993 -0.043158 0.248800 -vn -0.669352 0.088123 0.737701 -v -0.078250 0.052083 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.058858 0.248800 -vn -0.701887 0.233963 0.672768 -v -0.089993 0.043158 0.248800 -vn -0.548585 0.526558 0.649455 -v -0.089250 0.044577 0.248800 -vn -0.410993 0.535615 0.737701 -v -0.079250 0.050351 0.248800 -vn -0.552289 0.318865 0.770261 -v -0.078518 0.051083 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.093851 0.248800 -vn -0.469341 -0.572464 0.672313 -v -0.088113 0.086766 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.084525 0.248800 -vn -0.410992 -0.535616 0.737700 -v -0.079250 0.081649 0.248800 -vn -0.552288 -0.318865 0.770261 -v -0.078518 0.080917 0.248800 -vn -0.669352 -0.088123 0.737701 -v -0.078250 0.079917 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.068275 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.078250 0.068275 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.078250 0.058858 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.086375 0.108310 0.248800 -vn -0.378581 0.655722 0.653227 -v -0.087750 0.123330 0.248800 -vn -0.655722 0.378581 0.653227 -v -0.089580 0.121500 0.248800 -vn -0.637728 0.000000 0.770262 -v -0.078000 0.115000 0.248800 -vn -0.552289 0.318864 0.770262 -v -0.078301 0.113875 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.108310 0.248800 -vn -0.318864 0.552289 0.770262 -v -0.079125 0.113051 0.248800 -vn 0.000000 0.637728 0.770262 -v -0.080250 0.112750 0.248800 -vn 0.318864 0.552289 0.770262 -v -0.081375 0.113051 0.248800 -vn -0.000000 0.707107 0.707107 -v -0.076625 0.124000 0.248800 -vn -0.318864 -0.552289 0.770262 -v -0.079125 0.116949 0.248800 -vn -0.552289 -0.318864 0.770262 -v -0.078301 0.116125 0.248800 -vn 0.552289 0.318864 0.770262 -v -0.082199 0.113875 0.248800 -vn 0.637728 0.000000 0.770262 -v -0.082500 0.115000 0.248800 -vn 0.552289 -0.318864 0.770262 -v -0.082199 0.116125 0.248800 -vn -0.095840 0.727973 0.678874 -v -0.085250 0.124000 0.248800 -vn 0.318864 -0.552289 0.770262 -v -0.081375 0.116949 0.248800 -vn 0.000000 -0.637728 0.770262 -v -0.080250 0.117250 0.248800 -vn 0.443970 0.564115 0.696178 -v -0.069821 0.122399 0.248800 -vn 0.299225 0.685377 0.663870 -v -0.071488 0.123582 0.248800 -vn 0.074871 0.724970 0.684699 -v -0.073488 0.124000 0.248800 -vn -0.246342 0.662809 0.707107 -v -0.007896 0.108310 0.248800 -vn -0.167666 0.660352 0.732000 -v -0.014205 0.105965 0.248800 -vn -0.318863 -0.552290 0.770261 -v -0.016125 0.102669 0.248800 -vn 0.318864 0.552288 0.770262 -v -0.018375 0.098771 0.248800 -vn 0.552289 0.318864 0.770262 -v -0.019199 0.099595 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 0.098020 0.248800 -vn -0.552287 -0.318865 0.770262 -v -0.015301 0.101845 0.248800 -vn -0.637728 0.000000 0.770262 -v -0.015000 0.100720 0.248800 -vn -0.552289 0.318864 0.770262 -v -0.015301 0.099595 0.248800 -vn -0.318864 0.552289 0.770262 -v -0.016125 0.098771 0.248800 -vn -0.000000 0.637728 0.770262 -v -0.017250 0.098470 0.248800 -vn -0.023339 0.680905 0.732000 -v -0.026234 0.104252 0.248800 -vn 0.122057 0.670283 0.732000 -v -0.038351 0.105137 0.248800 -vn 0.261864 0.628971 0.732000 -v -0.050003 0.108580 0.248800 -vn 0.389681 0.558861 0.732000 -v -0.060656 0.114423 0.248800 -vn 0.637728 0.000000 0.770262 -v -0.019500 0.100720 0.248800 -vn 0.552287 -0.318865 0.770262 -v -0.019199 0.101845 0.248800 -vn 0.318863 -0.552290 0.770261 -v -0.018375 0.102669 0.248800 -vn -0.000000 -0.637728 0.770262 -v -0.017250 0.102970 0.248800 -vn -0.569587 0.299817 0.765298 -v 0.010599 0.120342 0.248800 -vn -0.437562 0.512050 0.739151 -v 0.007411 0.116757 0.248800 -vn -0.304316 0.609564 0.731999 -v -0.002817 0.110198 0.248800 -vn -0.707107 -0.000000 0.707107 -v 0.011750 0.125125 0.248800 -vn -0.672729 0.081889 0.735343 -v 0.011750 0.125000 0.248800 -vn -0.095839 0.727973 0.678875 -v 0.016750 0.145000 0.248800 -vn -0.378581 0.655722 0.653226 -v 0.014250 0.144330 0.248800 -vn -0.727973 0.095840 0.678874 -v 0.011750 0.140000 0.248800 -vn -0.655722 0.378581 0.653227 -v 0.012420 0.142500 0.248800 -vn 0.318864 0.552289 0.770261 -v 0.027250 0.133402 0.248800 -vn 0.552288 0.318864 0.770262 -v 0.026152 0.134500 0.248800 -vn -0.552288 0.318864 0.770262 -v 0.031348 0.134500 0.248800 -vn -0.318864 0.552289 0.770261 -v 0.030250 0.133402 0.248800 -vn -0.000000 0.637727 0.770263 -v 0.028750 0.133000 0.248800 -vn 0.637728 -0.000001 0.770262 -v 0.025750 0.136000 0.248800 -vn 0.000000 0.707107 0.707107 -v 0.021350 0.145000 0.248800 -vn 0.552287 -0.318865 0.770262 -v 0.026152 0.137500 0.248800 -vn 0.318864 -0.552289 0.770261 -v 0.027250 0.138598 0.248800 -vn 0.095838 0.727973 0.678875 -v 0.033750 0.145000 0.248800 -vn -0.000000 -0.637727 0.770263 -v 0.028750 0.139000 0.248800 -vn -0.318864 -0.552289 0.770261 -v 0.030250 0.138598 0.248800 -vn 0.378581 0.655722 0.653226 -v 0.036250 0.144330 0.248800 -vn 0.655722 0.378581 0.653227 -v 0.038080 0.142500 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.086375 0.098020 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.086375 0.093851 0.248800 -vn -0.726915 -0.087765 0.681097 -v -0.090250 0.090865 0.248800 -vn -0.668285 -0.348441 0.657255 -v -0.089684 0.088554 0.248800 -vn -0.727973 0.095840 0.678874 -v -0.090250 0.119000 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.090250 0.108310 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.090250 0.098020 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.090250 0.093851 0.248800 -vn 0.552288 -0.318865 0.770261 -v -0.075116 0.080417 0.248800 -vn 0.318865 -0.552288 0.770262 -v -0.074750 0.080783 0.248800 -vn -0.000001 -0.637726 0.770263 -v -0.074250 0.080917 0.248800 -vn -0.318864 -0.552291 0.770260 -v -0.073750 0.080783 0.248800 -vn -0.669355 0.088118 0.737699 -v -0.073250 0.075417 0.248800 -vn -0.669355 -0.088118 0.737699 -v -0.073250 0.079917 0.248800 -vn -0.552286 -0.318862 0.770265 -v -0.073384 0.080417 0.248800 -vn -0.552286 0.318862 0.770265 -v -0.073384 0.074917 0.248800 -vn -0.318859 0.552292 0.770261 -v -0.073750 0.074551 0.248800 -vn -0.000001 0.637731 0.770259 -v -0.074250 0.074417 0.248800 -vn 0.318860 0.552289 0.770263 -v -0.074750 0.074551 0.248800 -vn 0.552288 0.318865 0.770262 -v -0.075116 0.074917 0.248800 -vn 0.669352 0.088123 0.737701 -v -0.075250 0.075417 0.248800 -vn 0.669352 -0.088123 0.737701 -v -0.075250 0.079917 0.248800 -vn 0.552288 -0.318866 0.770261 -v -0.075116 0.057083 0.248800 -vn 0.318865 -0.552288 0.770262 -v -0.074750 0.057449 0.248800 -vn -0.000001 -0.637726 0.770263 -v -0.074250 0.057583 0.248800 -vn -0.318864 -0.552291 0.770260 -v -0.073750 0.057449 0.248800 -vn -0.552286 -0.318863 0.770264 -v -0.073384 0.057083 0.248800 -vn -0.669354 -0.088119 0.737699 -v -0.073250 0.056583 0.248800 -vn -0.669355 0.088118 0.737699 -v -0.073250 0.052083 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.000000 0.248800 -vn -0.552286 0.318862 0.770265 -v -0.073384 0.051583 0.248800 -vn -0.318862 0.552292 0.770261 -v -0.073750 0.051217 0.248800 -vn -0.000001 0.637729 0.770261 -v -0.074250 0.051083 0.248800 -vn 0.318862 0.552289 0.770262 -v -0.074750 0.051217 0.248800 -vn 0.552288 0.318865 0.770262 -v -0.075116 0.051583 0.248800 -vn 0.669352 0.088123 0.737701 -v -0.075250 0.052083 0.248800 -vn 0.669352 -0.088123 0.737701 -v -0.075250 0.056583 0.248800 -vn 0.318862 -0.552289 0.770262 -v -0.074750 -0.051217 0.248800 -vn -0.000001 -0.637729 0.770261 -v -0.074250 -0.051083 0.248800 -vn -0.552286 -0.318862 0.770265 -v -0.073384 -0.051583 0.248800 -vn -0.669355 -0.088118 0.737699 -v -0.073250 -0.052083 0.248800 -vn 0.552288 0.318866 0.770261 -v -0.075116 -0.057083 0.248800 -vn 0.318865 0.552288 0.770261 -v -0.074750 -0.057449 0.248800 -vn -0.000001 0.637726 0.770263 -v -0.074250 -0.057583 0.248800 -vn -0.318862 -0.552292 0.770261 -v -0.073750 -0.051217 0.248800 -vn -0.669354 0.088119 0.737699 -v -0.073250 -0.056583 0.248800 -vn -0.552286 0.318863 0.770264 -v -0.073384 -0.057083 0.248800 -vn -0.318864 0.552291 0.770260 -v -0.073750 -0.057449 0.248800 -vn 0.669352 0.088123 0.737701 -v -0.075250 -0.056583 0.248800 -vn 0.669352 -0.088123 0.737701 -v -0.075250 -0.052083 0.248800 -vn 0.552288 -0.318865 0.770261 -v -0.075116 -0.051583 0.248800 -vn 0.318865 0.552288 0.770261 -v -0.074750 -0.080783 0.248800 -vn 0.552288 0.318865 0.770262 -v -0.075116 -0.080417 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.007200 -0.084525 0.248800 -vn -0.669355 0.088118 0.737699 -v -0.073250 -0.079917 0.248800 -vn -0.552286 0.318862 0.770265 -v -0.073384 -0.080417 0.248800 -vn -0.318864 0.552291 0.770260 -v -0.073750 -0.080783 0.248800 -vn -0.000001 0.637726 0.770263 -v -0.074250 -0.080917 0.248800 -vn 0.669352 0.088123 0.737701 -v -0.075250 -0.079917 0.248800 -vn 0.675739 -0.076139 0.733198 -v -0.075250 -0.075417 0.248800 -vn 0.584729 -0.281592 0.760788 -v -0.075151 -0.074983 0.248800 -vn 0.404645 -0.507408 0.760788 -v -0.074873 -0.074635 0.248800 -vn 0.144416 -0.632728 0.760789 -v -0.074473 -0.074442 0.248800 -vn -0.144416 -0.632728 0.760789 -v -0.074027 -0.074442 0.248800 -vn -0.404643 -0.507412 0.760787 -v -0.073627 -0.074635 0.248800 -vn -0.637728 0.000000 0.770262 -v -0.015000 -0.100720 0.248800 -vn -0.552287 0.318865 0.770262 -v -0.015301 -0.101845 0.248800 -vn 0.318863 0.552290 0.770261 -v -0.018375 -0.102669 0.248800 -vn -0.000000 0.637728 0.770262 -v -0.017250 -0.102970 0.248800 -vn -0.318863 0.552290 0.770261 -v -0.016125 -0.102669 0.248800 -vn -0.552288 -0.318864 0.770262 -v -0.015301 -0.099595 0.248800 -vn -0.318864 -0.552289 0.770262 -v -0.016125 -0.098771 0.248800 -vn -0.000000 -0.637728 0.770262 -v -0.017250 -0.098470 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.076625 -0.093851 0.248800 -vn 0.318864 -0.552289 0.770262 -v -0.018375 -0.098771 0.248800 -vn 0.552287 0.318865 0.770262 -v -0.019199 -0.101845 0.248800 -vn 0.637728 0.000000 0.770262 -v -0.019500 -0.100720 0.248800 -vn 0.552289 -0.318864 0.770262 -v -0.019199 -0.099595 0.248800 -vn 0.000000 0.000000 1.000000 -v -0.086375 -0.103420 0.248800 -vn -0.726915 0.087765 0.681097 -v -0.090250 -0.090865 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.090250 -0.093851 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.090250 -0.103420 0.248800 -vn -0.707107 0.000000 0.707107 -v -0.090250 -0.108310 0.248800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.058858 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.058858 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.068275 0.246800 -vn 0.552288 -0.318865 -0.770262 -v 0.026152 0.137500 0.246800 -vn 0.637728 -0.000001 -0.770262 -v 0.025750 0.136000 0.246800 -vn 0.000000 0.707107 -0.707107 -v 0.021350 0.145000 0.246800 -vn 0.078494 -0.725548 -0.683680 -v 0.029155 0.085132 0.246800 -vn 0.000000 -0.707107 -0.707107 -v 0.021350 0.085132 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 0.093851 0.246800 -vn 0.552289 0.318864 -0.770262 -v 0.000090 0.070132 0.246800 -vn 0.318864 0.552288 -0.770262 -v 0.003750 0.066472 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.068275 0.246800 -vn 0.318864 -0.552288 -0.770262 -v 0.003750 -0.066472 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.068275 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.000000 0.246800 -vn 0.320282 0.552181 -0.769750 -v 0.003750 -0.083793 0.246800 -vn 0.090800 0.668991 -0.737704 -v 0.008670 -0.085132 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 -0.093851 0.246800 -vn -0.160362 -0.661449 -0.732645 -v -0.014800 -0.105817 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.108310 0.246800 -vn -0.300714 -0.610575 -0.732646 -v -0.003091 -0.110062 0.246800 -vn -0.721981 -0.058200 -0.689461 -v -0.090250 -0.041577 0.246800 -vn -0.707107 0.000000 -0.707106 -v -0.090250 -0.000000 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 -0.000000 0.246800 -vn -0.304316 0.609564 -0.732000 -v -0.002817 0.110198 0.246800 -vn -0.437562 0.512049 -0.739151 -v 0.007411 0.116757 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 0.108310 0.246800 -vn -0.095839 0.727973 -0.678875 -v 0.016750 0.145000 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 0.125125 0.246800 -vn -0.707107 -0.000000 -0.707107 -v 0.011750 0.125125 0.246800 -vn -0.727973 0.095840 -0.678874 -v 0.011750 0.140000 0.246800 -vn -0.655722 0.378581 -0.653227 -v 0.012420 0.142500 0.246800 -vn -0.378581 0.655722 -0.653226 -v 0.014250 0.144330 0.246800 -vn -0.569587 0.299817 -0.765298 -v 0.010599 0.120342 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 0.108310 0.246800 -vn -0.672729 0.081889 -0.735343 -v 0.011750 0.125000 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.098020 0.246800 -vn -0.000000 0.637728 -0.770262 -v -0.017250 0.098470 0.246800 -vn -0.318864 0.552288 -0.770262 -v -0.016125 0.098771 0.246800 -vn 0.552289 0.318864 -0.770262 -v -0.019199 0.099595 0.246800 -vn 0.318864 0.552288 -0.770262 -v -0.018375 0.098771 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.098020 0.246800 -vn 0.637728 0.000000 -0.770262 -v -0.019500 0.100720 0.246800 -vn -0.023339 0.680905 -0.732000 -v -0.026234 0.104252 0.246800 -vn 0.552287 -0.318865 -0.770262 -v -0.019199 0.101845 0.246800 -vn -0.552287 -0.318865 -0.770262 -v -0.015301 0.101845 0.246800 -vn -0.318863 -0.552290 -0.770261 -v -0.016125 0.102669 0.246800 -vn -0.167666 0.660352 -0.732000 -v -0.014205 0.105965 0.246800 -vn -0.000000 -0.637728 -0.770262 -v -0.017250 0.102970 0.246800 -vn 0.318863 -0.552290 -0.770261 -v -0.018375 0.102669 0.246800 -vn -0.552289 0.318864 -0.770262 -v -0.015301 0.099595 0.246800 -vn -0.637728 0.000000 -0.770262 -v -0.015000 0.100720 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.108310 0.246800 -vn -0.246342 0.662809 -0.707107 -v -0.007896 0.108310 0.246800 -vn 0.443970 0.564115 -0.696178 -v -0.069821 0.122399 0.246800 -vn 0.389681 0.558861 -0.732000 -v -0.060656 0.114423 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.108310 0.246800 -vn 0.261864 0.628971 -0.732000 -v -0.050003 0.108580 0.246800 -vn 0.122057 0.670283 -0.732000 -v -0.038351 0.105137 0.246800 -vn -0.378581 0.655722 -0.653227 -v -0.087750 0.123330 0.246800 -vn 0.637728 0.000000 -0.770262 -v -0.082500 0.115000 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 0.108310 0.246800 -vn 0.552289 0.318864 -0.770262 -v -0.082199 0.113875 0.246800 -vn 0.318864 0.552289 -0.770262 -v -0.081375 0.113051 0.246800 -vn 0.000000 0.637728 -0.770262 -v -0.080250 0.112750 0.246800 -vn -0.318864 0.552289 -0.770262 -v -0.079125 0.113051 0.246800 -vn -0.552289 0.318864 -0.770262 -v -0.078301 0.113875 0.246800 -vn -0.637728 0.000000 -0.770262 -v -0.078000 0.115000 0.246800 -vn 0.299225 0.685377 -0.663870 -v -0.071488 0.123582 0.246800 -vn 0.074871 0.724970 -0.684699 -v -0.073488 0.124000 0.246800 -vn -0.000000 0.707107 -0.707107 -v -0.076625 0.124000 0.246800 -vn -0.552289 -0.318864 -0.770262 -v -0.078301 0.116125 0.246800 -vn -0.318864 -0.552289 -0.770262 -v -0.079125 0.116949 0.246800 -vn 0.000000 -0.637728 -0.770262 -v -0.080250 0.117250 0.246800 -vn -0.095840 0.727973 -0.678875 -v -0.085250 0.124000 0.246800 -vn 0.318864 -0.552289 -0.770262 -v -0.081375 0.116949 0.246800 -vn 0.552288 -0.318864 -0.770262 -v -0.082199 0.116125 0.246800 -vn -0.469341 -0.572464 -0.672313 -v -0.088113 0.086766 0.246800 -vn -0.668285 -0.348441 -0.657255 -v -0.089684 0.088554 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 0.093851 0.246800 -vn -0.726915 -0.087765 -0.681097 -v -0.090250 0.090865 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.078250 0.068275 0.246800 -vn -0.669352 -0.088123 -0.737701 -v -0.078250 0.079917 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.084525 0.246800 -vn -0.552288 -0.318865 -0.770261 -v -0.078518 0.080917 0.246800 -vn -0.410992 -0.535616 -0.737700 -v -0.079250 0.081649 0.246800 -vn -0.548586 0.526558 -0.649454 -v -0.089250 0.044577 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.000000 0.246800 -vn -0.410993 0.535615 -0.737701 -v -0.079250 0.050351 0.246800 -vn -0.552289 0.318865 -0.770261 -v -0.078518 0.051083 0.246800 -vn -0.669352 0.088123 -0.737701 -v -0.078250 0.052083 0.246800 -vn -0.721981 0.058200 -0.689461 -v -0.090250 0.041577 0.246800 -vn -0.701887 0.233963 -0.672768 -v -0.089993 0.043158 0.246800 -vn -0.669352 -0.088123 -0.737701 -v -0.078250 -0.052083 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.068275 0.246800 -vn -0.701887 -0.233963 -0.672768 -v -0.089993 -0.043158 0.246800 -vn -0.548585 -0.526558 -0.649455 -v -0.089250 -0.044577 0.246800 -vn -0.410993 -0.535615 -0.737701 -v -0.079250 -0.050351 0.246800 -vn -0.552289 -0.318865 -0.770261 -v -0.078518 -0.051083 0.246800 -vn -0.393681 0.562235 -0.727260 -v -0.079250 -0.081649 0.246800 -vn -0.508111 0.426354 -0.748361 -v -0.078718 -0.081203 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.084525 0.246800 -vn -0.623292 0.226860 -0.748359 -v -0.078371 -0.080601 0.246800 -vn -0.683749 0.059822 -0.727261 -v -0.078250 -0.079917 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.078250 -0.068275 0.246800 -vn -0.378581 -0.655722 -0.653227 -v -0.087750 -0.123330 0.246800 -vn -0.655722 -0.378581 -0.653227 -v -0.089580 -0.121500 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 -0.108310 0.246800 -vn -0.727973 -0.095840 -0.678874 -v -0.090250 -0.119000 0.246800 -vn 0.318864 -0.552289 -0.770262 -v -0.081375 -0.113051 0.246800 -vn 0.552289 -0.318864 -0.770262 -v -0.082199 -0.113875 0.246800 -vn 0.637728 0.000000 -0.770262 -v -0.082500 -0.115000 0.246800 -vn 0.552289 0.318864 -0.770262 -v -0.082199 -0.116125 0.246800 -vn -0.095839 -0.727973 -0.678874 -v -0.085250 -0.124000 0.246800 -vn 0.318864 0.552289 -0.770262 -v -0.081375 -0.116949 0.246800 -vn 0.000000 -0.707107 -0.707107 -v -0.076625 -0.124000 0.246800 -vn 0.000000 0.637728 -0.770262 -v -0.080250 -0.117250 0.246800 -vn -0.637728 0.000000 -0.770262 -v -0.078000 -0.115000 0.246800 -vn -0.552289 -0.318864 -0.770262 -v -0.078301 -0.113875 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.108310 0.246800 -vn -0.318864 -0.552289 -0.770262 -v -0.079125 -0.113051 0.246800 -vn 0.000000 -0.637728 -0.770262 -v -0.080250 -0.112750 0.246800 -vn -0.318864 0.552289 -0.770262 -v -0.079125 -0.116949 0.246800 -vn -0.552289 0.318864 -0.770262 -v -0.078301 -0.116125 0.246800 -vn 0.278460 -0.621040 -0.732645 -v -0.051410 -0.109188 0.246800 -vn 0.407161 -0.545390 -0.732645 -v -0.062147 -0.115500 0.246800 -vn 0.283943 -0.720103 -0.633110 -v -0.071250 -0.124000 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.103420 0.246800 -vn 0.136363 -0.666810 -0.732646 -v -0.039555 -0.105370 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.103420 0.246800 -vn -0.012296 -0.680500 -0.732645 -v -0.027153 -0.104228 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 -0.108310 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 -0.125125 0.246800 -vn -0.707107 -0.000000 -0.707107 -v 0.011750 -0.125125 0.246800 -vn -0.727973 -0.095840 -0.678874 -v 0.011750 -0.140000 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 -0.142000 0.246800 -vn -0.655722 -0.378581 -0.653227 -v 0.012420 -0.142500 0.246800 -vn -0.378581 -0.655722 -0.653226 -v 0.014250 -0.144330 0.246800 -vn -0.095839 -0.727973 -0.678875 -v 0.016750 -0.145000 0.246800 -vn 0.000000 -0.707107 -0.707107 -v 0.021350 -0.145000 0.246800 -vn 0.095838 -0.727973 -0.678875 -v 0.033750 -0.145000 0.246800 -vn 0.637728 0.000001 -0.770262 -v 0.025750 -0.136000 0.246800 -vn 0.552287 0.318865 -0.770262 -v 0.026152 -0.137500 0.246800 -vn 0.318864 0.552289 -0.770261 -v 0.027250 -0.138598 0.246800 -vn 0.552288 -0.318864 -0.770262 -v 0.026152 -0.134500 0.246800 -vn -0.000000 0.637727 -0.770263 -v 0.028750 -0.139000 0.246800 -vn 0.655722 -0.378581 -0.653227 -v 0.038080 -0.142500 0.246800 -vn 0.378581 -0.655722 -0.653226 -v 0.036250 -0.144330 0.246800 -vn -0.552287 -0.318865 -0.770263 -v 0.031348 -0.134500 0.246800 -vn -0.637728 0.000001 -0.770262 -v 0.031750 -0.136000 0.246800 -vn -0.552287 0.318866 -0.770262 -v 0.031348 -0.137500 0.246800 -vn -0.318864 0.552290 -0.770261 -v 0.030250 -0.138598 0.246800 -vn -0.318864 -0.552290 -0.770261 -v 0.030250 -0.133402 0.246800 -vn -0.000000 -0.637727 -0.770263 -v 0.028750 -0.133000 0.246800 -vn 0.318864 -0.552289 -0.770261 -v 0.027250 -0.133402 0.246800 -vn 0.318864 -0.552289 -0.770262 -v 0.027625 -0.113051 0.246800 -vn 0.552289 -0.318864 -0.770262 -v 0.026801 -0.113875 0.246800 -vn 0.637728 0.000000 -0.770262 -v 0.026500 -0.115000 0.246800 -vn 0.552289 0.318864 -0.770262 -v 0.026801 -0.116125 0.246800 -vn 0.318864 0.552289 -0.770262 -v 0.027625 -0.116949 0.246800 -vn 0.000000 0.637728 -0.770262 -v 0.028750 -0.117250 0.246800 -vn -0.318864 0.552288 -0.770262 -v 0.029875 -0.116949 0.246800 -vn -0.552289 0.318863 -0.770262 -v 0.030699 -0.116125 0.246800 -vn -0.637728 0.000000 -0.770262 -v 0.031000 -0.115000 0.246800 -vn -0.552289 -0.318863 -0.770262 -v 0.030699 -0.113875 0.246800 -vn -0.318864 -0.552288 -0.770262 -v 0.029875 -0.113051 0.246800 -vn 0.000000 -0.637728 -0.770262 -v 0.028750 -0.112750 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 -0.093851 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 -0.103420 0.246800 -vn 0.000000 0.707107 -0.707107 -v 0.021350 -0.085132 0.246800 -vn 0.078494 0.725548 -0.683680 -v 0.029155 -0.085132 0.246800 -vn 0.313172 0.680950 -0.661989 -v 0.029990 -0.085315 0.246800 -vn 0.569050 0.487805 -0.661988 -v 0.030673 -0.085831 0.246800 -vn 0.001410 0.706656 -0.707556 -v 0.008750 -0.085132 0.246800 -vn 0.318865 -0.552290 -0.770260 -v 0.010950 -0.088266 0.246800 -vn 0.552287 -0.318863 -0.770263 -v 0.010584 -0.088632 0.246800 -vn 0.637729 0.000000 -0.770261 -v 0.010450 -0.089132 0.246800 -vn 0.552287 0.318863 -0.770263 -v 0.010584 -0.089632 0.246800 -vn 0.318865 0.552290 -0.770261 -v 0.010950 -0.089999 0.246800 -vn 0.088123 0.669352 -0.737701 -v 0.011450 -0.090132 0.246800 -vn -0.088123 0.669352 -0.737701 -v 0.015950 -0.090132 0.246800 -vn -0.318865 0.552288 -0.770261 -v 0.016450 -0.089999 0.246800 -vn -0.552289 0.318862 -0.770262 -v 0.016816 -0.089632 0.246800 -vn -0.637729 0.000000 -0.770261 -v 0.016950 -0.089132 0.246800 -vn -0.552289 -0.318862 -0.770262 -v 0.016816 -0.088632 0.246800 -vn -0.318865 -0.552288 -0.770262 -v 0.016450 -0.088266 0.246800 -vn -0.088123 -0.669352 -0.737701 -v 0.015950 -0.088132 0.246800 -vn 0.088123 -0.669352 -0.737701 -v 0.011450 -0.088132 0.246800 -vn 0.552289 -0.318864 -0.770262 -v 0.000090 -0.070132 0.246800 -vn 0.637728 0.000000 -0.770262 -v -0.001250 -0.075132 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.084525 0.246800 -vn 0.552287 -0.318863 -0.770263 -v 0.010584 -0.060632 0.246800 -vn 0.637729 0.000000 -0.770261 -v 0.010450 -0.061132 0.246800 -vn 0.552287 0.318863 -0.770263 -v 0.010584 -0.061632 0.246800 -vn 0.088122 -0.669353 -0.737700 -v 0.008750 -0.065132 0.246800 -vn -0.318862 0.552289 -0.770262 -v 0.016450 -0.061999 0.246800 -vn -0.552289 0.318862 -0.770262 -v 0.016816 -0.061632 0.246800 -vn 0.000000 -0.707107 -0.707107 -v 0.021350 -0.065132 0.246800 -vn -0.637729 0.000000 -0.770261 -v 0.016950 -0.061132 0.246800 -vn 0.318862 0.552290 -0.770262 -v 0.010950 -0.061999 0.246800 -vn 0.088121 0.669353 -0.737700 -v 0.011450 -0.062132 0.246800 -vn -0.088121 0.669353 -0.737700 -v 0.015950 -0.062132 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 0.000000 0.246800 -vn -0.552289 -0.318862 -0.770262 -v 0.016816 -0.060632 0.246800 -vn -0.318865 -0.552289 -0.770261 -v 0.016450 -0.060266 0.246800 -vn -0.088123 -0.669352 -0.737701 -v 0.015950 -0.060132 0.246800 -vn 0.088123 -0.669352 -0.737701 -v 0.011450 -0.060132 0.246800 -vn 0.318865 -0.552290 -0.770261 -v 0.010950 -0.060266 0.246800 -vn 0.580988 -0.475081 -0.660871 -v 0.024861 -0.064399 0.246800 -vn 0.321481 -0.678160 -0.660870 -v 0.024170 -0.064940 0.246800 -vn 0.080660 -0.725882 -0.683073 -v 0.023313 -0.065132 0.246800 -vn 0.728492 -0.180417 -0.660870 -v 0.025254 -0.063613 0.246800 -vn 0.080660 0.725882 -0.683074 -v 0.023313 0.065132 0.246800 -vn 0.321481 0.678160 -0.660870 -v 0.024170 0.064940 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 0.058858 0.246800 -vn 0.580987 0.475082 -0.660871 -v 0.024861 0.064399 0.246800 -vn 0.728492 0.180418 -0.660870 -v 0.025254 0.063613 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 0.058858 0.246800 -vn 0.552287 0.318863 -0.770263 -v 0.010584 0.060632 0.246800 -vn 0.318865 0.552290 -0.770261 -v 0.010950 0.060266 0.246800 -vn -0.552289 0.318862 -0.770262 -v 0.016816 0.060632 0.246800 -vn -0.637729 0.000000 -0.770261 -v 0.016950 0.061132 0.246800 -vn 0.000000 0.707107 -0.707107 -v 0.021350 0.065132 0.246800 -vn -0.552289 -0.318862 -0.770262 -v 0.016816 0.061632 0.246800 -vn 0.088122 0.669353 -0.737700 -v 0.008750 0.065132 0.246800 -vn 0.318862 -0.552290 -0.770261 -v 0.010950 0.061999 0.246800 -vn 0.552287 -0.318863 -0.770263 -v 0.010584 0.061632 0.246800 -vn 0.637729 0.000000 -0.770261 -v 0.010450 0.061132 0.246800 -vn 0.088123 0.669352 -0.737701 -v 0.011450 0.060132 0.246800 -vn -0.088123 0.669352 -0.737701 -v 0.015950 0.060132 0.246800 -vn -0.318865 0.552288 -0.770261 -v 0.016450 0.060266 0.246800 -vn -0.318862 -0.552289 -0.770262 -v 0.016450 0.061999 0.246800 -vn -0.088121 -0.669353 -0.737700 -v 0.015950 0.062132 0.246800 -vn 0.088121 -0.669353 -0.737700 -v 0.011450 0.062132 0.246800 -vn 0.637728 -0.000000 -0.770262 -v -0.001250 0.075132 0.246800 -vn 0.088122 -0.669353 -0.737700 -v 0.008750 0.085132 0.246800 -vn 0.318864 -0.552288 -0.770262 -v 0.003750 0.083793 0.246800 -vn 0.552287 0.318863 -0.770263 -v 0.010584 0.088632 0.246800 -vn -0.318865 -0.552288 -0.770262 -v 0.016450 0.089999 0.246800 -vn -0.088123 -0.669352 -0.737701 -v 0.015950 0.090132 0.246800 -vn 0.088123 -0.669352 -0.737701 -v 0.011450 0.090132 0.246800 -vn 0.318865 -0.552290 -0.770261 -v 0.010950 0.089999 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 0.093851 0.246800 -vn 0.552287 -0.318863 -0.770263 -v 0.010584 0.089632 0.246800 -vn 0.637729 0.000000 -0.770261 -v 0.010450 0.089132 0.246800 -vn -0.318865 0.552288 -0.770261 -v 0.016450 0.088266 0.246800 -vn -0.552289 0.318862 -0.770262 -v 0.016816 0.088632 0.246800 -vn -0.637729 0.000000 -0.770261 -v 0.016950 0.089132 0.246800 -vn -0.552289 -0.318862 -0.770262 -v 0.016816 0.089632 0.246800 -vn 0.318865 0.552290 -0.770261 -v 0.010950 0.088266 0.246800 -vn 0.088123 0.669352 -0.737701 -v 0.011450 0.088132 0.246800 -vn -0.088123 0.669352 -0.737701 -v 0.015950 0.088132 0.246800 -vn 0.673484 -0.277961 -0.684950 -v 0.031078 0.086584 0.246800 -vn 0.569050 -0.487805 -0.661988 -v 0.030673 0.085831 0.246800 -vn 0.313172 -0.680950 -0.661989 -v 0.029990 0.085315 0.246800 -vn 0.673628 -0.207804 -0.709255 -v 0.033261 0.093908 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.021350 0.098020 0.246800 -vn 0.668450 -0.222089 -0.709825 -v 0.034593 0.098084 0.246800 -vn 0.664436 -0.236128 -0.709061 -v 0.038128 0.108310 0.246800 -vn -0.318864 -0.552288 -0.770262 -v 0.029875 0.116949 0.246800 -vn 0.000000 -0.637728 -0.770262 -v 0.028750 0.117250 0.246800 -vn 0.318864 -0.552289 -0.770262 -v 0.027625 0.116949 0.246800 -vn 0.552289 -0.318864 -0.770262 -v 0.026801 0.116125 0.246800 -vn 0.637728 0.000000 -0.770262 -v 0.026500 0.115000 0.246800 -vn 0.552289 0.318864 -0.770262 -v 0.026801 0.113875 0.246800 -vn -0.552289 -0.318863 -0.770262 -v 0.030699 0.116125 0.246800 -vn -0.637728 0.000000 -0.770262 -v 0.031000 0.115000 0.246800 -vn -0.552289 0.318863 -0.770262 -v 0.030699 0.113875 0.246800 -vn 0.700885 -0.188386 -0.687947 -v 0.038143 0.108353 0.246800 -vn -0.318863 0.552286 -0.770264 -v 0.029875 0.113051 0.246800 -vn 0.000000 0.637728 -0.770262 -v 0.028750 0.112750 0.246800 -vn 0.318864 0.552289 -0.770262 -v 0.027625 0.113051 0.246800 -vn 0.552288 0.318864 -0.770262 -v 0.026152 0.134500 0.246800 -vn 0.318864 0.552289 -0.770261 -v 0.027250 0.133402 0.246800 -vn -0.000000 0.637727 -0.770263 -v 0.028750 0.133000 0.246800 -vn -0.318864 0.552289 -0.770261 -v 0.030250 0.133402 0.246800 -vn -0.552288 0.318864 -0.770262 -v 0.031348 0.134500 0.246800 -vn -0.637728 -0.000001 -0.770262 -v 0.031750 0.136000 0.246800 -vn 0.655722 0.378581 -0.653227 -v 0.038080 0.142500 0.246800 -vn -0.552288 -0.318865 -0.770262 -v 0.031348 0.137500 0.246800 -vn 0.378581 0.655722 -0.653226 -v 0.036250 0.144330 0.246800 -vn -0.318864 -0.552289 -0.770261 -v 0.030250 0.138598 0.246800 -vn 0.095838 0.727973 -0.678875 -v 0.033750 0.145000 0.246800 -vn -0.000000 -0.637727 -0.770263 -v 0.028750 0.139000 0.246800 -vn 0.318864 -0.552289 -0.770261 -v 0.027250 0.138598 0.246800 -vn -0.318863 -0.552288 -0.770262 -v 0.005325 -0.097992 0.246800 -vn 0.000000 -0.637729 -0.770261 -v 0.003750 -0.097570 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 -0.093851 0.246800 -vn 0.552289 0.318864 -0.770262 -v 0.000090 -0.080132 0.246800 -vn 0.637728 0.000000 -0.770262 -v 0.000600 -0.100720 0.246800 -vn 0.552289 -0.318863 -0.770261 -v 0.001022 -0.099145 0.246800 -vn 0.318864 -0.552288 -0.770263 -v 0.002175 -0.097992 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 -0.103420 0.246800 -vn -0.637728 0.000000 -0.770262 -v 0.006900 -0.100720 0.246800 -vn -0.552289 -0.318863 -0.770262 -v 0.006478 -0.099145 0.246800 -vn 0.318864 0.552288 -0.770263 -v 0.002175 -0.103448 0.246800 -vn -0.000000 0.637729 -0.770261 -v 0.003750 -0.103870 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 -0.108310 0.246800 -vn -0.318863 0.552288 -0.770262 -v 0.005325 -0.103448 0.246800 -vn -0.552289 0.318864 -0.770262 -v 0.006478 -0.102295 0.246800 -vn 0.552289 0.318864 -0.770261 -v 0.001022 -0.102295 0.246800 -vn -0.552289 0.318863 -0.770262 -v 0.006478 0.099145 0.246800 -vn -0.637728 -0.000000 -0.770262 -v 0.006900 0.100720 0.246800 -vn 0.000000 0.000000 -1.000000 -v 0.008675 0.098020 0.246800 -vn -0.552289 -0.318864 -0.770261 -v 0.006478 0.102295 0.246800 -vn -0.318863 -0.552288 -0.770262 -v 0.005325 0.103448 0.246800 -vn 0.000000 -0.637729 -0.770261 -v 0.003750 0.103870 0.246800 -vn 0.637728 -0.000000 -0.770262 -v 0.000600 0.100720 0.246800 -vn 0.552289 -0.318864 -0.770261 -v 0.001022 0.102295 0.246800 -vn 0.318864 -0.552288 -0.770263 -v 0.002175 0.103448 0.246800 -vn 0.552289 0.318863 -0.770261 -v 0.001022 0.099145 0.246800 -vn 0.318864 0.552288 -0.770263 -v 0.002175 0.097992 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.093851 0.246800 -vn -0.318863 0.552288 -0.770262 -v 0.005325 0.097992 0.246800 -vn -0.000000 0.637729 -0.770261 -v 0.003750 0.097570 0.246800 -vn 0.552289 -0.318864 -0.770262 -v 0.000090 0.080132 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.007200 0.084525 0.246800 -vn 0.552287 0.318865 -0.770262 -v -0.019199 -0.101845 0.246800 -vn 0.318863 0.552290 -0.770261 -v -0.018375 -0.102669 0.246800 -vn -0.000000 0.637728 -0.770262 -v -0.017250 -0.102970 0.246800 -vn -0.318863 0.552290 -0.770261 -v -0.016125 -0.102669 0.246800 -vn -0.318864 -0.552289 -0.770262 -v -0.016125 -0.098771 0.246800 -vn -0.000000 -0.637728 -0.770262 -v -0.017250 -0.098470 0.246800 -vn 0.318864 -0.552289 -0.770262 -v -0.018375 -0.098771 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 -0.093851 0.246800 -vn 0.552288 -0.318864 -0.770262 -v -0.019199 -0.099595 0.246800 -vn 0.637728 0.000000 -0.770262 -v -0.019500 -0.100720 0.246800 -vn -0.552287 0.318865 -0.770262 -v -0.015301 -0.101845 0.246800 -vn -0.637728 0.000000 -0.770262 -v -0.015000 -0.100720 0.246800 -vn -0.552288 -0.318864 -0.770262 -v -0.015301 -0.099595 0.246800 -vn -0.469341 0.572463 -0.672313 -v -0.088113 -0.086766 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 -0.093851 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 -0.103420 0.246800 -vn -0.668285 0.348441 -0.657255 -v -0.089684 -0.088554 0.246800 -vn -0.726915 0.087765 -0.681097 -v -0.090250 -0.090865 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 -0.093851 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 -0.103420 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 -0.108310 0.246800 -vn -0.000001 0.637726 -0.770263 -v -0.074250 -0.080917 0.246800 -vn 0.318865 0.552288 -0.770262 -v -0.074750 -0.080783 0.246800 -vn 0.552288 0.318865 -0.770261 -v -0.075116 -0.080417 0.246800 -vn 0.144416 -0.632728 -0.760789 -v -0.074473 -0.074442 0.246800 -vn 0.404645 -0.507408 -0.760788 -v -0.074873 -0.074635 0.246800 -vn -0.318864 0.552291 -0.770260 -v -0.073750 -0.080783 0.246800 -vn 0.584729 -0.281592 -0.760788 -v -0.075151 -0.074983 0.246800 -vn 0.675739 -0.076139 -0.733198 -v -0.075250 -0.075417 0.246800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 -0.079917 0.246800 -vn -0.552286 0.318862 -0.770265 -v -0.073384 -0.080417 0.246800 -vn -0.669355 0.088118 -0.737699 -v -0.073250 -0.079917 0.246800 -vn -0.675742 -0.076134 -0.733196 -v -0.073250 -0.075417 0.246800 -vn -0.584725 -0.281589 -0.760792 -v -0.073349 -0.074983 0.246800 -vn -0.404643 -0.507412 -0.760787 -v -0.073627 -0.074635 0.246800 -vn -0.144416 -0.632728 -0.760789 -v -0.074027 -0.074442 0.246800 -vn 0.552288 0.318866 -0.770261 -v -0.075116 -0.057083 0.246800 -vn 0.318865 0.552288 -0.770262 -v -0.074750 -0.057449 0.246800 -vn 0.318862 -0.552289 -0.770262 -v -0.074750 -0.051217 0.246800 -vn 0.552288 -0.318865 -0.770262 -v -0.075116 -0.051583 0.246800 -vn 0.669352 -0.088123 -0.737701 -v -0.075250 -0.052083 0.246800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 -0.056583 0.246800 -vn -0.000001 0.637726 -0.770263 -v -0.074250 -0.057583 0.246800 -vn -0.318864 0.552291 -0.770260 -v -0.073750 -0.057449 0.246800 -vn -0.552286 0.318863 -0.770264 -v -0.073384 -0.057083 0.246800 -vn -0.318862 -0.552292 -0.770261 -v -0.073750 -0.051217 0.246800 -vn -0.000001 -0.637729 -0.770261 -v -0.074250 -0.051083 0.246800 -vn -0.669354 0.088119 -0.737699 -v -0.073250 -0.056583 0.246800 -vn -0.669355 -0.088118 -0.737699 -v -0.073250 -0.052083 0.246800 -vn -0.552286 -0.318862 -0.770265 -v -0.073384 -0.051583 0.246800 -vn 0.318862 0.552289 -0.770262 -v -0.074750 0.051217 0.246800 -vn -0.000001 0.637729 -0.770261 -v -0.074250 0.051083 0.246800 -vn -0.669354 -0.088119 -0.737699 -v -0.073250 0.056583 0.246800 -vn -0.552286 -0.318863 -0.770264 -v -0.073384 0.057083 0.246800 -vn -0.669355 0.088118 -0.737699 -v -0.073250 0.052083 0.246800 -vn -0.318862 0.552292 -0.770261 -v -0.073750 0.051217 0.246800 -vn -0.552286 0.318862 -0.770265 -v -0.073384 0.051583 0.246800 -vn -0.318864 -0.552291 -0.770260 -v -0.073750 0.057449 0.246800 -vn -0.000001 -0.637726 -0.770263 -v -0.074250 0.057583 0.246800 -vn 0.318865 -0.552288 -0.770261 -v -0.074750 0.057449 0.246800 -vn 0.552288 -0.318866 -0.770261 -v -0.075116 0.057083 0.246800 -vn 0.669352 -0.088123 -0.737701 -v -0.075250 0.056583 0.246800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 0.052083 0.246800 -vn 0.552288 0.318865 -0.770261 -v -0.075116 0.051583 0.246800 -vn -0.552286 -0.318862 -0.770265 -v -0.073384 0.080417 0.246800 -vn -0.318864 -0.552291 -0.770260 -v -0.073750 0.080783 0.246800 -vn -0.000001 -0.637726 -0.770263 -v -0.074250 0.080917 0.246800 -vn 0.318865 -0.552288 -0.770261 -v -0.074750 0.080783 0.246800 -vn 0.552288 -0.318865 -0.770262 -v -0.075116 0.080417 0.246800 -vn 0.669352 -0.088123 -0.737701 -v -0.075250 0.079917 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.078250 0.058858 0.246800 -vn 0.669352 0.088123 -0.737701 -v -0.075250 0.075417 0.246800 -vn 0.552288 0.318865 -0.770261 -v -0.075116 0.074917 0.246800 -vn 0.318860 0.552289 -0.770263 -v -0.074750 0.074551 0.246800 -vn -0.000001 0.637731 -0.770259 -v -0.074250 0.074417 0.246800 -vn -0.318859 0.552292 -0.770262 -v -0.073750 0.074551 0.246800 -vn -0.552286 0.318862 -0.770265 -v -0.073384 0.074917 0.246800 -vn -0.669354 0.088118 -0.737699 -v -0.073250 0.075417 0.246800 -vn -0.669355 -0.088118 -0.737699 -v -0.073250 0.079917 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.076625 0.093851 0.246800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 0.098020 0.246800 -vn -0.655722 0.378581 -0.653227 -v -0.089580 0.121500 0.246800 -vn -0.727973 0.095840 -0.678874 -v -0.090250 0.119000 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 0.108310 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 0.098020 0.246800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 0.093851 0.246800 -vn -0.637728 -0.000000 -0.770262 -v -0.078000 0.115000 0.092800 -vn -0.637728 0.000000 0.770262 -v -0.078000 0.115000 0.094800 -vn -0.552287 -0.318863 -0.770264 -v -0.078301 0.116125 0.092800 -vn -0.552287 -0.318863 0.770263 -v -0.078301 0.116125 0.094800 -vn -0.318864 -0.552289 -0.770262 -v -0.079125 0.116949 0.092800 -vn -0.318864 -0.552289 0.770262 -v -0.079125 0.116949 0.094800 -vn -0.000000 -0.637728 -0.770261 -v -0.080250 0.117250 0.092800 -vn -0.000000 -0.637727 0.770262 -v -0.080250 0.117250 0.094800 -vn 0.318864 -0.552289 -0.770261 -v -0.081375 0.116949 0.092800 -vn 0.318864 -0.552288 0.770262 -v -0.081375 0.116949 0.094800 -vn 0.552289 -0.318864 -0.770261 -v -0.082199 0.116125 0.092800 -vn 0.552288 -0.318864 0.770262 -v -0.082199 0.116125 0.094800 -vn 0.637729 -0.000000 -0.770261 -v -0.082500 0.115000 0.092800 -vn 0.637727 -0.000000 0.770262 -v -0.082500 0.115000 0.094800 -vn 0.552289 0.318864 -0.770261 -v -0.082199 0.113875 0.092800 -vn 0.552288 0.318864 0.770262 -v -0.082199 0.113875 0.094800 -vn 0.318864 0.552289 -0.770261 -v -0.081375 0.113051 0.092800 -vn 0.318864 0.552288 0.770263 -v -0.081375 0.113051 0.094800 -vn 0.000000 0.637729 -0.770261 -v -0.080250 0.112750 0.092800 -vn -0.000000 0.637726 0.770263 -v -0.080250 0.112750 0.094800 -vn -0.318864 0.552289 -0.770262 -v -0.079125 0.113051 0.092800 -vn -0.318864 0.552289 0.770262 -v -0.079125 0.113051 0.094800 -vn -0.552289 0.318864 -0.770262 -v -0.078301 0.113875 0.092800 -vn -0.552289 0.318864 0.770262 -v -0.078301 0.113875 0.094800 -vn -0.637728 -0.000001 -0.770262 -v -0.057000 0.136000 0.092800 -vn -0.637728 -0.000001 0.770262 -v -0.057000 0.136000 0.094800 -vn -0.552288 -0.318865 -0.770262 -v -0.057301 0.137125 0.092800 -vn -0.552288 -0.318865 0.770262 -v -0.057301 0.137125 0.094800 -vn -0.318862 -0.552289 -0.770263 -v -0.058125 0.137949 0.092800 -vn -0.318862 -0.552289 0.770263 -v -0.058125 0.137949 0.094800 -vn 0.000000 -0.637730 -0.770260 -v -0.059250 0.138250 0.092800 -vn -0.000000 -0.637730 0.770260 -v -0.059250 0.138250 0.094800 -vn 0.318862 -0.552289 -0.770263 -v -0.060375 0.137949 0.092800 -vn 0.318862 -0.552289 0.770263 -v -0.060375 0.137949 0.094800 -vn 0.552288 -0.318865 -0.770262 -v -0.061199 0.137125 0.092800 -vn 0.552288 -0.318865 0.770262 -v -0.061199 0.137125 0.094800 -vn 0.637728 -0.000001 -0.770262 -v -0.061500 0.136000 0.092800 -vn 0.637728 -0.000001 0.770262 -v -0.061500 0.136000 0.094800 -vn 0.552289 0.318863 -0.770262 -v -0.061199 0.134875 0.092800 -vn 0.552289 0.318863 0.770262 -v -0.061199 0.134875 0.094800 -vn 0.318862 0.552289 -0.770263 -v -0.060375 0.134051 0.092800 -vn 0.318862 0.552289 0.770263 -v -0.060375 0.134051 0.094800 -vn -0.000000 0.637730 -0.770260 -v -0.059250 0.133750 0.092800 -vn 0.000000 0.637730 0.770260 -v -0.059250 0.133750 0.094800 -vn -0.318862 0.552289 -0.770263 -v -0.058125 0.134051 0.092800 -vn -0.318862 0.552289 0.770263 -v -0.058125 0.134051 0.094800 -vn -0.552289 0.318863 -0.770262 -v -0.057301 0.134875 0.092800 -vn -0.552289 0.318863 0.770262 -v -0.057301 0.134875 0.094800 -vn -0.637728 -0.000001 -0.770262 -v 0.031750 0.136000 0.092800 -vn -0.637728 -0.000001 0.770262 -v 0.031750 0.136000 0.094800 -vn -0.552287 -0.318865 -0.770262 -v 0.031348 0.137500 0.092800 -vn -0.552287 -0.318865 0.770262 -v 0.031348 0.137500 0.094800 -vn -0.318864 -0.552289 -0.770261 -v 0.030250 0.138598 0.092800 -vn -0.318864 -0.552289 0.770261 -v 0.030250 0.138598 0.094800 -vn -0.000000 -0.637727 -0.770263 -v 0.028750 0.139000 0.092800 -vn -0.000000 -0.637727 0.770263 -v 0.028750 0.139000 0.094800 -vn 0.318864 -0.552289 -0.770261 -v 0.027250 0.138598 0.092800 -vn 0.318864 -0.552289 0.770261 -v 0.027250 0.138598 0.094800 -vn 0.552287 -0.318865 -0.770262 -v 0.026152 0.137500 0.092800 -vn 0.552287 -0.318865 0.770262 -v 0.026152 0.137500 0.094800 -vn 0.637728 -0.000001 -0.770262 -v 0.025750 0.136000 0.092800 -vn 0.637728 -0.000001 0.770262 -v 0.025750 0.136000 0.094800 -vn 0.552288 0.318864 -0.770262 -v 0.026152 0.134500 0.092800 -vn 0.552288 0.318864 0.770262 -v 0.026152 0.134500 0.094800 -vn 0.318864 0.552289 -0.770261 -v 0.027250 0.133402 0.092800 -vn 0.318864 0.552289 0.770261 -v 0.027250 0.133402 0.094800 -vn -0.000000 0.637727 -0.770263 -v 0.028750 0.133000 0.092800 -vn -0.000000 0.637727 0.770263 -v 0.028750 0.133000 0.094800 -vn -0.318864 0.552289 -0.770261 -v 0.030250 0.133402 0.092800 -vn -0.318864 0.552289 0.770261 -v 0.030250 0.133402 0.094800 -vn -0.552288 0.318864 -0.770262 -v 0.031348 0.134500 0.092800 -vn -0.552288 0.318864 0.770262 -v 0.031348 0.134500 0.094800 -vn -0.637728 -0.000001 -0.770262 -v 0.010000 0.136000 0.092800 -vn -0.637728 -0.000001 0.770262 -v 0.010000 0.136000 0.094800 -vn -0.552288 -0.318865 -0.770262 -v 0.009699 0.137125 0.092800 -vn -0.552288 -0.318865 0.770262 -v 0.009699 0.137125 0.094800 -vn -0.318862 -0.552289 -0.770263 -v 0.008875 0.137949 0.092800 -vn -0.318862 -0.552289 0.770263 -v 0.008875 0.137949 0.094800 -vn 0.000000 -0.637730 -0.770260 -v 0.007750 0.138250 0.092800 -vn 0.000000 -0.637730 0.770260 -v 0.007750 0.138250 0.094800 -vn 0.318862 -0.552289 -0.770263 -v 0.006625 0.137949 0.092800 -vn 0.318862 -0.552289 0.770263 -v 0.006625 0.137949 0.094800 -vn 0.552288 -0.318865 -0.770262 -v 0.005801 0.137125 0.092800 -vn 0.552288 -0.318865 0.770262 -v 0.005801 0.137125 0.094800 -vn 0.637728 -0.000001 -0.770262 -v 0.005500 0.136000 0.092800 -vn 0.637728 -0.000001 0.770262 -v 0.005500 0.136000 0.094800 -vn 0.552289 0.318863 -0.770262 -v 0.005801 0.134875 0.092800 -vn 0.552289 0.318863 0.770262 -v 0.005801 0.134875 0.094800 -vn 0.318862 0.552289 -0.770263 -v 0.006625 0.134051 0.092800 -vn 0.318862 0.552289 0.770263 -v 0.006625 0.134051 0.094800 -vn 0.000000 0.637730 -0.770260 -v 0.007750 0.133750 0.092800 -vn 0.000000 0.637730 0.770260 -v 0.007750 0.133750 0.094800 -vn -0.318862 0.552289 -0.770263 -v 0.008875 0.134051 0.092800 -vn -0.318862 0.552289 0.770263 -v 0.008875 0.134051 0.094800 -vn -0.552289 0.318863 -0.770262 -v 0.009699 0.134875 0.092800 -vn -0.552289 0.318863 0.770262 -v 0.009699 0.134875 0.094800 -vn -0.637728 -0.000000 -0.770262 -v 0.026250 0.057500 0.092800 -vn -0.637728 -0.000000 0.770262 -v 0.026250 0.057500 0.094800 -vn -0.552289 -0.318864 -0.770261 -v 0.025915 0.058750 0.092800 -vn -0.552289 -0.318864 0.770261 -v 0.025915 0.058750 0.094800 -vn -0.318863 -0.552288 -0.770262 -v 0.025000 0.059665 0.092800 -vn -0.318863 -0.552288 0.770262 -v 0.025000 0.059665 0.094800 -vn 0.000000 -0.637729 -0.770261 -v 0.023750 0.060000 0.092800 -vn 0.000000 -0.637729 0.770261 -v 0.023750 0.060000 0.094800 -vn 0.318864 -0.552288 -0.770262 -v 0.022500 0.059665 0.092800 -vn 0.318864 -0.552288 0.770262 -v 0.022500 0.059665 0.094800 -vn 0.552289 -0.318864 -0.770261 -v 0.021585 0.058750 0.092800 -vn 0.552289 -0.318864 0.770261 -v 0.021585 0.058750 0.094800 -vn 0.637728 -0.000000 -0.770262 -v 0.021250 0.057500 0.092800 -vn 0.637728 -0.000000 0.770262 -v 0.021250 0.057500 0.094800 -vn 0.552289 0.318864 -0.770262 -v 0.021585 0.056250 0.092800 -vn 0.552289 0.318864 0.770262 -v 0.021585 0.056250 0.094800 -vn 0.318864 0.552288 -0.770262 -v 0.022500 0.055335 0.092800 -vn 0.318864 0.552288 0.770262 -v 0.022500 0.055335 0.094800 -vn 0.000000 0.637728 -0.770262 -v 0.023750 0.055000 0.092800 -vn 0.000000 0.637728 0.770262 -v 0.023750 0.055000 0.094800 -vn -0.318864 0.552289 -0.770262 -v 0.025000 0.055335 0.092800 -vn -0.318864 0.552289 0.770262 -v 0.025000 0.055335 0.094800 -vn -0.552289 0.318864 -0.770262 -v 0.025915 0.056250 0.092800 -vn -0.552289 0.318864 0.770262 -v 0.025915 0.056250 0.094800 -vn -0.637728 -0.000000 -0.770262 -v 0.026250 0.107500 0.092800 -vn -0.637728 -0.000000 0.770262 -v 0.026250 0.107500 0.094800 -vn -0.552289 -0.318864 -0.770262 -v 0.025915 0.108750 0.092800 -vn -0.552289 -0.318864 0.770262 -v 0.025915 0.108750 0.094800 -vn -0.318863 -0.552288 -0.770262 -v 0.025000 0.109665 0.092800 -vn -0.318863 -0.552288 0.770262 -v 0.025000 0.109665 0.094800 -vn 0.000000 -0.637729 -0.770261 -v 0.023750 0.110000 0.092800 -vn 0.000000 -0.637729 0.770261 -v 0.023750 0.110000 0.094800 -vn 0.318864 -0.552288 -0.770262 -v 0.022500 0.109665 0.092800 -vn 0.318864 -0.552288 0.770262 -v 0.022500 0.109665 0.094800 -vn 0.552289 -0.318864 -0.770261 -v 0.021585 0.108750 0.092800 -vn 0.552289 -0.318864 0.770261 -v 0.021585 0.108750 0.094800 -vn 0.637727 0.000000 -0.770262 -v 0.021250 0.107500 0.092800 -vn 0.637727 0.000000 0.770262 -v 0.021250 0.107500 0.094800 -vn 0.552289 0.318864 -0.770261 -v 0.021585 0.106250 0.092800 -vn 0.552289 0.318864 0.770261 -v 0.021585 0.106250 0.094800 -vn 0.318866 0.552288 -0.770262 -v 0.022500 0.105335 0.092800 -vn 0.318866 0.552288 0.770262 -v 0.022500 0.105335 0.094800 -vn 0.000000 0.637727 -0.770263 -v 0.023750 0.105000 0.092800 -vn 0.000000 0.637727 0.770263 -v 0.023750 0.105000 0.094800 -vn -0.318865 0.552288 -0.770262 -v 0.025000 0.105335 0.092800 -vn -0.318865 0.552288 0.770262 -v 0.025000 0.105335 0.094800 -vn -0.552289 0.318863 -0.770262 -v 0.025915 0.106250 0.092800 -vn -0.552289 0.318863 0.770262 -v 0.025915 0.106250 0.094800 -vn -0.066397 0.680613 -0.729628 -v -0.016250 0.130223 0.092800 -vn -0.066397 0.680613 0.729628 -v -0.016250 0.130223 0.094800 -vn -0.249423 0.608539 -0.753305 -v -0.012457 0.130970 0.092800 -vn -0.249423 0.608539 0.753305 -v -0.012457 0.130970 0.094800 -vn -0.461578 0.468483 -0.753306 -v -0.009232 0.133099 0.092800 -vn -0.461578 0.468483 0.753306 -v -0.009232 0.133099 0.094800 -vn -0.604768 0.258430 -0.753306 -v -0.007054 0.136293 0.092800 -vn -0.604768 0.258430 0.753306 -v -0.007054 0.136293 0.094800 -vn -0.693485 0.170998 -0.699884 -v -0.006251 0.140074 0.092800 -vn -0.693485 0.170998 0.699884 -v -0.006251 0.140074 0.094800 -vn 0.000000 0.707107 0.707107 -v -0.025750 0.130223 0.094800 -vn 0.000000 0.707107 -0.707107 -v -0.025750 0.130223 0.092800 -vn 0.066397 0.680613 0.729628 -v -0.029250 0.130223 0.094800 -vn 0.066397 0.680613 -0.729628 -v -0.029250 0.130223 0.092800 -vn 0.714737 0.131428 -0.686934 -v -0.039249 0.140074 0.092800 -vn 0.714737 0.131428 0.686934 -v -0.039249 0.140074 0.094800 -vn 0.671952 0.126985 -0.729627 -v -0.039115 0.138588 0.092800 -vn 0.671952 0.126985 0.729627 -v -0.039115 0.138588 0.094800 -vn 0.604112 0.285272 -0.744089 -v -0.038446 0.136293 0.092800 -vn 0.604112 0.285272 0.744089 -v -0.038446 0.136293 0.094800 -vn 0.461578 0.468483 -0.753306 -v -0.036268 0.133099 0.092800 -vn 0.461578 0.468483 0.753306 -v -0.036268 0.133099 0.094800 -vn 0.249423 0.608538 -0.753306 -v -0.033043 0.130970 0.092800 -vn 0.249423 0.608538 0.753306 -v -0.033043 0.130970 0.094800 -vn -0.727973 0.095840 0.678874 -v -0.069250 0.140000 0.094800 -vn -0.727973 0.095840 -0.678874 -v -0.069250 0.140000 0.092800 -vn -0.707107 0.000000 0.707106 -v -0.069250 0.138625 0.094800 -vn -0.707107 0.000000 -0.707106 -v -0.069250 0.138625 0.092800 -vn -0.707107 0.000000 0.707107 -v -0.069250 0.133375 0.094800 -vn -0.707107 0.000000 -0.707107 -v -0.069250 0.133375 0.092800 -vn -0.669353 0.088121 0.737700 -v -0.069250 0.126000 0.094800 -vn -0.669353 0.088121 -0.737700 -v -0.069250 0.126000 0.092800 -vn -0.552287 0.318864 0.770263 -v -0.069518 0.125000 0.094800 -vn -0.552287 0.318864 -0.770263 -v -0.069518 0.125000 0.092800 -vn -0.318864 0.552290 0.770261 -v -0.070250 0.124268 0.094800 -vn -0.318864 0.552290 -0.770261 -v -0.070250 0.124268 0.092800 -vn -0.088124 0.669352 0.737701 -v -0.071250 0.124000 0.094800 -vn -0.088124 0.669352 -0.737701 -v -0.071250 0.124000 0.092800 -vn -0.095840 0.727973 0.678874 -v -0.085250 0.124000 0.094800 -vn -0.095839 0.727972 -0.678875 -v -0.085250 0.124000 0.092800 -vn -0.095839 -0.727973 0.678874 -v -0.085250 0.098056 0.094800 -vn -0.095839 -0.727973 -0.678874 -v -0.085250 0.098056 0.092800 -vn 0.000000 -0.707107 0.707107 -v -0.069750 0.098056 0.094800 -vn 0.000000 -0.707107 -0.707107 -v -0.069750 0.098056 0.092800 -vn 0.000000 -0.707107 0.707107 -v -0.025750 0.098056 0.094800 -vn 0.000000 -0.707107 -0.707107 -v -0.025750 0.098056 0.092800 -vn -0.054022 -0.686415 0.725200 -v 0.005750 0.098056 0.094800 -vn -0.054022 -0.686415 -0.725200 -v 0.005750 0.098056 0.092800 -vn -0.686416 -0.054022 -0.725200 -v 0.015750 0.088056 0.092800 -vn -0.686415 -0.054022 0.725200 -v 0.015750 0.088056 0.094800 -vn -0.635401 -0.206454 -0.744071 -v 0.015261 0.091146 0.092800 -vn -0.635401 -0.206454 0.744071 -v 0.015261 0.091146 0.094800 -vn -0.540504 -0.392699 -0.744071 -v 0.013840 0.093934 0.092800 -vn -0.540504 -0.392699 0.744071 -v 0.013840 0.093934 0.094800 -vn -0.392699 -0.540505 -0.744071 -v 0.011628 0.096146 0.092800 -vn -0.392699 -0.540505 0.744071 -v 0.011628 0.096146 0.094800 -vn -0.206454 -0.635401 -0.744071 -v 0.008840 0.097567 0.092800 -vn -0.206454 -0.635401 0.744071 -v 0.008840 0.097567 0.094800 -vn -0.727973 -0.095839 -0.678874 -v 0.015750 0.050500 0.092800 -vn -0.727973 -0.095839 0.678874 -v 0.015750 0.050500 0.094800 -vn -0.707107 -0.000000 -0.707107 -v 0.015750 0.051750 0.092800 -vn -0.707107 -0.000000 0.707107 -v 0.015750 0.051750 0.094800 -vn -0.707107 -0.000000 -0.707107 -v 0.015750 0.082500 0.092800 -vn -0.707107 -0.000000 0.707107 -v 0.015750 0.082500 0.094800 -vn 0.000000 0.000000 -1.000000 -v 0.029000 0.111375 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 0.111375 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 0.125125 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 0.051750 0.092800 -vn 0.000000 0.000000 -1.000000 -v -0.086375 0.111375 0.092800 -vn 0.000000 0.000000 -1.000000 -v -0.069750 0.111375 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 0.082500 0.092800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.138625 0.092800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.133375 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.029000 0.125125 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 0.138625 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 0.133375 0.092800 -vn 0.000000 0.707107 -0.707107 -v 0.029000 0.145000 0.092800 -vn 0.095838 0.727973 -0.678875 -v 0.033750 0.145000 0.092800 -vn 0.378581 0.655722 -0.653226 -v 0.036250 0.144330 0.092800 -vn 0.727973 0.095840 -0.678874 -v 0.038750 0.140000 0.092800 -vn 0.655722 0.378581 -0.653227 -v 0.038080 0.142500 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.029000 0.082500 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.029000 0.051750 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.015625 0.111375 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.015625 0.133375 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.015625 0.138625 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.015625 0.125125 0.092800 -vn 0.000000 0.000000 -1.000000 -v -0.025750 0.125125 0.092800 -vn 0.375134 0.657243 -0.653686 -v -0.041770 0.144342 0.092800 -vn 0.651601 0.384850 -0.653687 -v -0.039943 0.142543 0.092800 -vn 0.094907 0.727857 -0.679130 -v -0.044248 0.145000 0.092800 -vn -0.095839 0.727973 -0.678875 -v -0.064250 0.145000 0.092800 -vn -0.378581 0.655722 -0.653227 -v -0.066750 0.144330 0.092800 -vn -0.655722 0.378581 -0.653227 -v -0.068580 0.142500 0.092800 -vn -0.378581 0.655722 -0.653227 -v -0.087750 0.123330 0.092800 -vn -0.727973 0.095840 -0.678874 -v -0.090250 0.119000 0.092800 -vn -0.655722 0.378581 -0.653227 -v -0.089580 0.121500 0.092800 -vn -0.378581 -0.655722 -0.653227 -v -0.087750 0.098726 0.092800 -vn -0.655722 -0.378581 -0.653227 -v -0.089580 0.100556 0.092800 -vn -0.727973 -0.095839 -0.678874 -v -0.090250 0.103056 0.092800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 0.111375 0.092800 -vn 0.000000 0.000000 -1.000000 -v -0.025750 0.111375 0.092800 -vn 0.655722 -0.378582 -0.653226 -v 0.038482 0.049500 0.092800 -vn 0.378580 -0.655722 -0.653227 -v 0.037750 0.048768 0.092800 -vn 0.727973 -0.095838 -0.678875 -v 0.038750 0.050500 0.092800 -vn 0.095840 -0.727973 -0.678874 -v 0.036750 0.048500 0.092800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.051750 0.092800 -vn -0.378581 -0.655722 -0.653227 -v 0.016750 0.048768 0.092800 -vn -0.655722 -0.378581 -0.653227 -v 0.016018 0.049500 0.092800 -vn -0.095839 -0.727973 -0.678874 -v 0.017750 0.048500 0.092800 -vn 0.000000 -0.707107 -0.707107 -v 0.023500 0.048500 0.092800 -vn 0.000000 -0.707107 -0.707107 -v 0.029000 0.048500 0.092800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.082500 0.092800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.111375 0.092800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 0.125125 0.092800 -vn -0.651601 0.384850 -0.653687 -v -0.005557 0.142543 0.092800 -vn -0.375134 0.657243 -0.653686 -v -0.003730 0.144342 0.092800 -vn -0.094907 0.727857 -0.679130 -v -0.001252 0.145000 0.092800 -vn 0.000000 0.707107 -0.707107 -v 0.015625 0.145000 0.092800 -vn 0.000000 0.707107 -0.707107 -v 0.023500 0.145000 0.092800 -vn 0.000000 0.000000 1.000000 -v 0.015625 0.138625 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.029000 0.125125 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 0.138625 0.094800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.133375 0.094800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.138625 0.094800 -vn 0.655722 0.378581 0.653227 -v 0.038080 0.142500 0.094800 -vn 0.378581 0.655722 0.653226 -v 0.036250 0.144330 0.094800 -vn 0.095838 0.727973 0.678875 -v 0.033750 0.145000 0.094800 -vn 0.727973 0.095840 0.678874 -v 0.038750 0.140000 0.094800 -vn 0.000000 0.707107 0.707107 -v 0.029000 0.145000 0.094800 -vn 0.000000 0.707107 0.707107 -v 0.023500 0.145000 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 0.125125 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 0.133375 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.029000 0.082500 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 0.082500 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 0.051750 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.029000 0.051750 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.029000 0.111375 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.015625 0.111375 0.094800 -vn 0.000000 -0.707107 0.707107 -v 0.029000 0.048500 0.094800 -vn 0.095840 -0.727973 0.678874 -v 0.036750 0.048500 0.094800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.051750 0.094800 -vn 0.378580 -0.655722 0.653227 -v 0.037750 0.048768 0.094800 -vn 0.655722 -0.378582 0.653226 -v 0.038482 0.049500 0.094800 -vn 0.727973 -0.095838 0.678875 -v 0.038750 0.050500 0.094800 -vn -0.655722 -0.378581 0.653227 -v 0.016018 0.049500 0.094800 -vn -0.378581 -0.655722 0.653227 -v 0.016750 0.048768 0.094800 -vn -0.095839 -0.727973 0.678874 -v 0.017750 0.048500 0.094800 -vn -0.655722 -0.378581 0.653227 -v -0.089580 0.100556 0.094800 -vn -0.378581 -0.655722 0.653227 -v -0.087750 0.098726 0.094800 -vn -0.727973 -0.095839 0.678874 -v -0.090250 0.103056 0.094800 -vn -0.378581 0.655722 0.653227 -v -0.087750 0.123330 0.094800 -vn -0.655722 0.378581 0.653227 -v -0.089580 0.121500 0.094800 -vn -0.000000 -0.000000 1.000000 -v -0.086375 0.111375 0.094800 -vn -0.727973 0.095840 0.678874 -v -0.090250 0.119000 0.094800 -vn -0.707107 0.000000 0.707107 -v -0.090250 0.111375 0.094800 -vn -0.000000 -0.000000 1.000000 -v -0.069750 0.111375 0.094800 -vn 0.000000 0.000000 1.000000 -v -0.025750 0.111375 0.094800 -vn 0.000000 0.000000 1.000000 -v -0.025750 0.125125 0.094800 -vn -0.378581 0.655722 0.653227 -v -0.066750 0.144330 0.094800 -vn -0.655722 0.378581 0.653227 -v -0.068580 0.142500 0.094800 -vn -0.095839 0.727973 0.678875 -v -0.064250 0.145000 0.094800 -vn 0.094907 0.727857 0.679130 -v -0.044248 0.145000 0.094800 -vn 0.375134 0.657243 0.653686 -v -0.041770 0.144342 0.094800 -vn 0.651601 0.384850 0.653687 -v -0.039943 0.142543 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.015625 0.133375 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.015625 0.125125 0.094800 -vn -0.375134 0.657243 0.653686 -v -0.003730 0.144342 0.094800 -vn -0.651601 0.384850 0.653687 -v -0.005557 0.142543 0.094800 -vn -0.094907 0.727857 0.679130 -v -0.001252 0.145000 0.094800 -vn 0.000000 0.707107 0.707107 -v 0.015625 0.145000 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 0.111375 0.094800 -vn 0.000000 -0.707107 0.707107 -v 0.023500 0.048500 0.094800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.082500 0.094800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.111375 0.094800 -vn 0.707107 0.000000 0.707107 -v 0.038750 0.125125 0.094800 -vn 0.727973 -0.095840 0.678874 -v 0.038750 -0.140000 0.094800 -vn 0.727973 -0.095840 -0.678874 -v 0.038750 -0.140000 0.092800 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.138625 0.094800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.138625 0.092800 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.125125 0.094800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.125125 0.092800 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.111375 0.094800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.111375 0.092800 -vn 0.707107 0.000000 0.707107 -v 0.038750 -0.082500 0.094800 -vn 0.707107 0.000000 -0.707107 -v 0.038750 -0.082500 0.092800 -vn 0.727973 0.095838 0.678875 -v 0.038750 -0.050500 0.094800 -vn 0.727973 0.095838 -0.678875 -v 0.038750 -0.050500 0.092800 -vn 0.000000 0.000000 1.000000 -v 0.015625 -0.125125 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.015625 -0.111375 0.094800 -vn 0.000000 0.000000 1.000000 -v -0.025750 -0.111375 0.094800 -vn -0.094907 -0.727857 0.679130 -v -0.001252 -0.145000 0.094800 -vn 0.000000 -0.707107 0.707107 -v 0.015625 -0.145000 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.015625 -0.138625 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.029000 -0.082500 0.094800 -vn -0.552289 -0.318864 0.770261 -v 0.025915 -0.106250 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.029000 -0.111375 0.094800 -vn -0.637727 -0.000000 0.770262 -v 0.026250 -0.107500 0.094800 -vn -0.552289 0.318864 0.770261 -v 0.025915 -0.108750 0.094800 -vn 0.637728 0.000000 0.770262 -v 0.021250 -0.107500 0.094800 -vn 0.552289 -0.318863 0.770262 -v 0.021585 -0.106250 0.094800 -vn -0.686415 0.054022 0.725200 -v 0.015750 -0.087944 0.094800 -vn 0.318866 -0.552288 0.770262 -v 0.022500 -0.105335 0.094800 -vn 0.000000 -0.637727 0.770263 -v 0.023750 -0.105000 0.094800 -vn 0.000000 0.637729 0.770261 -v 0.023750 -0.110000 0.094800 -vn 0.318864 0.552288 0.770262 -v 0.022500 -0.109665 0.094800 -vn 0.552289 0.318864 0.770262 -v 0.021585 -0.108750 0.094800 -vn -0.707107 -0.000000 0.707107 -v 0.015750 -0.082500 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 -0.082500 0.094800 -vn -0.318865 -0.552288 0.770262 -v 0.025000 -0.105335 0.094800 -vn -0.552289 -0.318864 0.770262 -v 0.025915 -0.056250 0.094800 -vn -0.637728 0.000000 0.770262 -v 0.026250 -0.057500 0.094800 -vn 0.000000 0.707107 0.707107 -v 0.029000 -0.048500 0.094800 -vn 0.095840 0.727973 0.678874 -v 0.036750 -0.048500 0.094800 -vn -0.552289 0.318864 0.770261 -v 0.025915 -0.058750 0.094800 -vn -0.318863 0.552288 0.770262 -v 0.025000 -0.059665 0.094800 -vn 0.000000 0.637729 0.770261 -v 0.023750 -0.060000 0.094800 -vn -0.095839 0.727973 0.678874 -v 0.017750 -0.048500 0.094800 -vn 0.318864 -0.552288 0.770262 -v 0.022500 -0.055335 0.094800 -vn 0.000000 0.707107 0.707107 -v 0.023500 -0.048500 0.094800 -vn 0.000000 -0.637728 0.770262 -v 0.023750 -0.055000 0.094800 -vn -0.318864 -0.552289 0.770262 -v 0.025000 -0.055335 0.094800 -vn -0.727973 0.095839 0.678874 -v 0.015750 -0.050500 0.094800 -vn 0.552288 -0.318864 0.770262 -v 0.021585 -0.056250 0.094800 -vn -0.655722 0.378581 0.653227 -v 0.016018 -0.049500 0.094800 -vn -0.378581 0.655722 0.653227 -v 0.016750 -0.048768 0.094800 -vn 0.318864 0.552288 0.770262 -v 0.022500 -0.059665 0.094800 -vn 0.552289 0.318864 0.770261 -v 0.021585 -0.058750 0.094800 -vn 0.637728 0.000000 0.770262 -v 0.021250 -0.057500 0.094800 -vn 0.552288 -0.318864 0.770262 -v 0.026152 -0.134500 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 -0.125125 0.094800 -vn 0.637728 0.000001 0.770262 -v 0.025750 -0.136000 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 -0.138625 0.094800 -vn 0.552287 0.318865 0.770262 -v 0.026152 -0.137500 0.094800 -vn 0.318864 0.552289 0.770261 -v 0.027250 -0.138598 0.094800 -vn 0.378581 -0.655722 0.653226 -v 0.036250 -0.144330 0.094800 -vn 0.655722 -0.378581 0.653227 -v 0.038080 -0.142500 0.094800 -vn 0.000000 -0.707107 0.707107 -v 0.023500 -0.145000 0.094800 -vn 0.000000 -0.707107 0.707107 -v 0.029000 -0.145000 0.094800 -vn -0.000000 0.637727 0.770263 -v 0.028750 -0.139000 0.094800 -vn 0.095838 -0.727973 0.678875 -v 0.033750 -0.145000 0.094800 -vn -0.000000 -0.637727 0.770263 -v 0.028750 -0.133000 0.094800 -vn -0.318864 -0.552290 0.770261 -v 0.030250 -0.133402 0.094800 -vn -0.552287 -0.318865 0.770263 -v 0.031348 -0.134500 0.094800 -vn -0.637728 0.000001 0.770262 -v 0.031750 -0.136000 0.094800 -vn -0.318864 0.552290 0.770261 -v 0.030250 -0.138598 0.094800 -vn -0.552287 0.318866 0.770262 -v 0.031348 -0.137500 0.094800 -vn -0.378581 0.655722 0.653227 -v -0.087750 -0.098614 0.094800 -vn -0.655722 0.378581 0.653227 -v -0.089580 -0.100444 0.094800 -vn -0.095840 0.727973 0.678874 -v -0.085250 -0.097944 0.094800 -vn -0.727973 0.095840 0.678874 -v -0.090250 -0.102944 0.094800 -vn -0.000000 0.707107 0.707107 -v -0.069750 -0.097944 0.094800 -vn -0.000000 0.000000 1.000000 -v -0.069750 -0.111375 0.094800 -vn -0.000000 0.000000 1.000000 -v -0.086375 -0.111375 0.094800 -vn -0.707107 0.000000 0.707107 -v -0.090250 -0.111375 0.094800 -vn -0.540505 0.392699 0.744071 -v 0.013840 -0.093822 0.094800 -vn -0.392700 0.540504 0.744071 -v 0.011628 -0.096034 0.094800 -vn -0.635401 0.206454 0.744071 -v 0.015261 -0.091034 0.094800 -vn -0.206454 0.635401 0.744071 -v 0.008840 -0.097454 0.094800 -vn -0.054022 0.686415 0.725200 -v 0.005750 -0.097944 0.094800 -vn 0.000000 0.707107 0.707107 -v -0.025750 -0.097944 0.094800 -vn -0.693485 -0.170998 0.699884 -v -0.006251 -0.140074 0.094800 -vn -0.651601 -0.384850 0.653687 -v -0.005557 -0.142543 0.094800 -vn -0.375134 -0.657243 0.653686 -v -0.003730 -0.144342 0.094800 -vn 0.552289 -0.318863 0.770262 -v 0.005801 -0.134875 0.094800 -vn 0.318862 -0.552289 0.770263 -v 0.006625 -0.134051 0.094800 -vn 0.000000 0.000000 1.000000 -v -0.025750 -0.125125 0.094800 -vn -0.000000 -0.637730 0.770260 -v 0.007750 -0.133750 0.094800 -vn -0.318862 -0.552289 0.770263 -v 0.008875 -0.134051 0.094800 -vn -0.552289 -0.318863 0.770262 -v 0.009699 -0.134875 0.094800 -vn -0.637728 0.000001 0.770262 -v 0.010000 -0.136000 0.094800 -vn -0.552288 0.318865 0.770262 -v 0.009699 -0.137125 0.094800 -vn -0.318862 0.552289 0.770263 -v 0.008875 -0.137949 0.094800 -vn 0.000000 0.637730 0.770260 -v 0.007750 -0.138250 0.094800 -vn 0.318862 0.552289 0.770263 -v 0.006625 -0.137949 0.094800 -vn 0.552288 0.318865 0.770262 -v 0.005801 -0.137125 0.094800 -vn -0.604768 -0.258430 0.753306 -v -0.007054 -0.136293 0.094800 -vn 0.637728 0.000001 0.770262 -v 0.005500 -0.136000 0.094800 -vn -0.461578 -0.468483 0.753305 -v -0.009232 -0.133099 0.094800 -vn -0.249423 -0.608539 0.753305 -v -0.012457 -0.130970 0.094800 -vn -0.066397 -0.680613 0.729628 -v -0.016250 -0.130223 0.094800 -vn 0.671952 -0.126985 0.729627 -v -0.039115 -0.138588 0.094800 -vn -0.552288 0.318865 0.770262 -v -0.057301 -0.137125 0.094800 -vn -0.318862 0.552289 0.770263 -v -0.058125 -0.137949 0.094800 -vn -0.707107 0.000000 0.707106 -v -0.069250 -0.138625 0.094800 -vn 0.000000 0.637730 0.770260 -v -0.059250 -0.138250 0.094800 -vn 0.318862 0.552289 0.770263 -v -0.060375 -0.137949 0.094800 -vn -0.552287 -0.318864 0.770263 -v -0.069518 -0.125000 0.094800 -vn -0.000000 -0.637730 0.770260 -v -0.059250 -0.133750 0.094800 -vn -0.318862 -0.552289 0.770263 -v -0.058125 -0.134051 0.094800 -vn -0.552288 -0.318863 0.770262 -v -0.057301 -0.134875 0.094800 -vn 0.249423 -0.608539 0.753305 -v -0.033043 -0.130970 0.094800 -vn 0.066397 -0.680613 0.729628 -v -0.029250 -0.130223 0.094800 -vn 0.000000 -0.707107 0.707107 -v -0.025750 -0.130223 0.094800 -vn 0.552288 0.318865 0.770262 -v -0.061199 -0.137125 0.094800 -vn 0.637728 0.000001 0.770262 -v -0.061500 -0.136000 0.094800 -vn -0.669353 -0.088121 0.737700 -v -0.069250 -0.126000 0.094800 -vn 0.552289 -0.318863 0.770262 -v -0.061199 -0.134875 0.094800 -vn 0.318862 -0.552289 0.770263 -v -0.060375 -0.134051 0.094800 -vn -0.637728 0.000001 0.770262 -v -0.057000 -0.136000 0.094800 -vn 0.604112 -0.285272 0.744089 -v -0.038446 -0.136293 0.094800 -vn 0.461578 -0.468483 0.753306 -v -0.036268 -0.133099 0.094800 -vn 0.714737 -0.131428 0.686934 -v -0.039249 -0.140074 0.094800 -vn -0.727973 -0.095840 0.678874 -v -0.069250 -0.140000 0.094800 -vn 0.375134 -0.657243 0.653686 -v -0.041770 -0.144342 0.094800 -vn 0.651601 -0.384850 0.653687 -v -0.039943 -0.142543 0.094800 -vn 0.094907 -0.727857 0.679130 -v -0.044248 -0.145000 0.094800 -vn -0.095839 -0.727973 0.678875 -v -0.064250 -0.145000 0.094800 -vn -0.378581 -0.655722 0.653227 -v -0.066750 -0.144330 0.094800 -vn -0.655722 -0.378581 0.653227 -v -0.068580 -0.142500 0.094800 -vn -0.318864 -0.552290 0.770261 -v -0.070250 -0.124268 0.094800 -vn -0.552287 0.318863 0.770264 -v -0.078301 -0.116125 0.094800 -vn -0.637728 0.000000 0.770262 -v -0.078000 -0.115000 0.094800 -vn -0.088123 -0.669352 0.737701 -v -0.071250 -0.124000 0.094800 -vn -0.318864 0.552288 0.770262 -v -0.079125 -0.116949 0.094800 -vn -0.071344 -0.724383 0.685696 -v -0.085250 -0.124000 0.094800 -vn 0.552288 -0.318864 0.770262 -v -0.082199 -0.113875 0.094800 -vn 0.318864 -0.552288 0.770263 -v -0.081375 -0.113051 0.094800 -vn -0.000000 -0.637726 0.770263 -v -0.080250 -0.112750 0.094800 -vn -0.318864 -0.552289 0.770262 -v -0.079125 -0.113051 0.094800 -vn -0.552289 -0.318864 0.770262 -v -0.078301 -0.113875 0.094800 -vn 0.000000 0.637727 0.770262 -v -0.080250 -0.117250 0.094800 -vn 0.318864 0.552288 0.770262 -v -0.081375 -0.116949 0.094800 -vn -0.285559 -0.689402 0.665719 -v -0.087163 -0.123619 0.094800 -vn 0.552288 0.318864 0.770262 -v -0.082199 -0.116125 0.094800 -vn 0.637727 -0.000000 0.770263 -v -0.082500 -0.115000 0.094800 -vn -0.527646 -0.527644 0.665719 -v -0.088786 -0.122536 0.094800 -vn -0.689401 -0.285559 0.665719 -v -0.089869 -0.120913 0.094800 -vn -0.724383 -0.071346 0.685696 -v -0.090250 -0.119000 0.094800 -vn 0.655722 0.378582 0.653226 -v 0.038482 -0.049500 0.094800 -vn 0.378580 0.655722 0.653227 -v 0.037750 -0.048768 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.029000 -0.125125 0.094800 -vn 0.318864 -0.552289 0.770261 -v 0.027250 -0.133402 0.094800 -vn -0.318863 0.552288 0.770262 -v 0.025000 -0.109665 0.094800 -vn 0.000000 0.000000 1.000000 -v 0.023500 -0.111375 0.094800 -vn 0.637729 -0.000000 -0.770261 -v -0.082500 -0.115000 0.092800 -vn 0.552289 0.318864 -0.770261 -v -0.082199 -0.116125 0.092800 -vn -0.285559 -0.689402 -0.665719 -v -0.087163 -0.123619 0.092800 -vn -0.071344 -0.724382 -0.685697 -v -0.085250 -0.124000 0.092800 -vn 0.000000 -0.637729 -0.770261 -v -0.080250 -0.112750 0.092800 -vn 0.318864 -0.552289 -0.770261 -v -0.081375 -0.113051 0.092800 -vn 0.000000 -0.000000 -1.000000 -v -0.086375 -0.111375 0.092800 -vn 0.552289 -0.318864 -0.770261 -v -0.082199 -0.113875 0.092800 -vn 0.318864 0.552289 -0.770261 -v -0.081375 -0.116949 0.092800 -vn 0.000000 0.637728 -0.770262 -v -0.080250 -0.117250 0.092800 -vn -0.088123 -0.669352 -0.737701 -v -0.071250 -0.124000 0.092800 -vn -0.318864 -0.552290 -0.770261 -v -0.070250 -0.124268 0.092800 -vn -0.552287 0.318863 -0.770263 -v -0.078301 -0.116125 0.092800 -vn -0.637728 -0.000000 -0.770262 -v -0.078000 -0.115000 0.092800 -vn 0.000000 -0.000000 -1.000000 -v -0.069750 -0.111375 0.092800 -vn -0.552289 -0.318864 -0.770262 -v -0.078301 -0.113875 0.092800 -vn -0.318864 -0.552289 -0.770262 -v -0.079125 -0.113051 0.092800 -vn -0.552288 -0.318863 -0.770262 -v -0.057301 -0.134875 0.092800 -vn -0.318862 -0.552289 -0.770263 -v -0.058125 -0.134051 0.092800 -vn 0.000000 0.000000 -1.000000 -v -0.025750 -0.125125 0.092800 -vn 0.637728 0.000001 -0.770262 -v -0.061500 -0.136000 0.092800 -vn 0.552288 0.318865 -0.770262 -v -0.061199 -0.137125 0.092800 -vn -0.707107 0.000000 -0.707106 -v -0.069250 -0.138625 0.092800 -vn 0.318862 0.552289 -0.770263 -v -0.060375 -0.137949 0.092800 -vn -0.000000 0.637730 -0.770260 -v -0.059250 -0.138250 0.092800 -vn 0.552289 -0.318863 -0.770262 -v -0.061199 -0.134875 0.092800 -vn -0.669353 -0.088121 -0.737700 -v -0.069250 -0.126000 0.092800 -vn 0.318862 -0.552288 -0.770263 -v -0.060375 -0.134051 0.092800 -vn -0.552287 -0.318864 -0.770263 -v -0.069518 -0.125000 0.092800 -vn 0.000000 -0.637730 -0.770260 -v -0.059250 -0.133750 0.092800 -vn -0.318862 0.552289 -0.770263 -v -0.058125 -0.137949 0.092800 -vn 0.671952 -0.126985 -0.729627 -v -0.039115 -0.138588 0.092800 -vn -0.552288 0.318865 -0.770262 -v -0.057301 -0.137125 0.092800 -vn 0.604112 -0.285272 -0.744089 -v -0.038446 -0.136293 0.092800 -vn -0.637728 0.000001 -0.770262 -v -0.057000 -0.136000 0.092800 -vn 0.461578 -0.468483 -0.753305 -v -0.036268 -0.133099 0.092800 -vn 0.249423 -0.608539 -0.753305 -v -0.033043 -0.130970 0.092800 -vn 0.066397 -0.680613 -0.729628 -v -0.029250 -0.130223 0.092800 -vn 0.000000 -0.707107 -0.707107 -v -0.025750 -0.130223 0.092800 -vn 0.714737 -0.131428 -0.686934 -v -0.039249 -0.140074 0.092800 -vn -0.727973 -0.095840 -0.678874 -v -0.069250 -0.140000 0.092800 -vn -0.378581 -0.655722 -0.653227 -v -0.066750 -0.144330 0.092800 -vn -0.655722 -0.378581 -0.653227 -v -0.068580 -0.142500 0.092800 -vn -0.095839 -0.727973 -0.678875 -v -0.064250 -0.145000 0.092800 -vn 0.094907 -0.727857 -0.679130 -v -0.044248 -0.145000 0.092800 -vn 0.375134 -0.657243 -0.653686 -v -0.041770 -0.144342 0.092800 -vn 0.651601 -0.384850 -0.653687 -v -0.039943 -0.142543 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.015625 -0.125125 0.092800 -vn 0.000000 -0.637730 -0.770260 -v 0.007750 -0.133750 0.092800 -vn 0.318862 -0.552289 -0.770263 -v 0.006625 -0.134051 0.092800 -vn 0.552289 -0.318863 -0.770262 -v 0.005801 -0.134875 0.092800 -vn 0.552288 0.318865 -0.770262 -v 0.005801 -0.137125 0.092800 -vn 0.318862 0.552289 -0.770263 -v 0.006625 -0.137949 0.092800 -vn -0.693485 -0.170998 -0.699884 -v -0.006251 -0.140074 0.092800 -vn -0.000000 0.637730 -0.770260 -v 0.007750 -0.138250 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.015625 -0.138625 0.092800 -vn -0.318862 0.552289 -0.770263 -v 0.008875 -0.137949 0.092800 -vn -0.552288 0.318865 -0.770262 -v 0.009699 -0.137125 0.092800 -vn 0.637728 0.000001 -0.770262 -v 0.005500 -0.136000 0.092800 -vn -0.604768 -0.258430 -0.753306 -v -0.007054 -0.136293 0.092800 -vn -0.637728 0.000001 -0.770262 -v 0.010000 -0.136000 0.092800 -vn -0.552289 -0.318863 -0.770262 -v 0.009699 -0.134875 0.092800 -vn -0.318862 -0.552289 -0.770263 -v 0.008875 -0.134051 0.092800 -vn -0.461578 -0.468483 -0.753305 -v -0.009232 -0.133099 0.092800 -vn -0.249423 -0.608539 -0.753305 -v -0.012457 -0.130970 0.092800 -vn -0.066397 -0.680613 -0.729628 -v -0.016250 -0.130223 0.092800 -vn -0.318864 0.552290 -0.770261 -v 0.030250 -0.138598 0.092800 -vn -0.000000 0.637727 -0.770263 -v 0.028750 -0.139000 0.092800 -vn 0.655722 -0.378581 -0.653227 -v 0.038080 -0.142500 0.092800 -vn 0.378581 -0.655722 -0.653226 -v 0.036250 -0.144330 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.029000 -0.082500 0.092800 -vn 0.000000 0.707107 -0.707107 -v 0.029000 -0.048500 0.092800 -vn 0.095840 0.727973 -0.678874 -v 0.036750 -0.048500 0.092800 -vn 0.378580 0.655722 -0.653227 -v 0.037750 -0.048768 0.092800 -vn 0.655722 0.378582 -0.653226 -v 0.038482 -0.049500 0.092800 -vn -0.655722 0.378581 -0.653227 -v 0.016018 -0.049500 0.092800 -vn -0.378581 0.655722 -0.653227 -v 0.016750 -0.048768 0.092800 -vn -0.095839 0.727973 -0.678874 -v 0.017750 -0.048500 0.092800 -vn 0.318864 -0.552289 -0.770262 -v 0.022500 -0.055335 0.092800 -vn 0.552289 -0.318864 -0.770262 -v 0.021585 -0.056250 0.092800 -vn -0.727973 0.095839 -0.678874 -v 0.015750 -0.050500 0.092800 -vn 0.637728 0.000000 -0.770262 -v 0.021250 -0.057500 0.092800 -vn -0.707107 -0.000000 -0.707107 -v 0.015750 -0.082500 0.092800 -vn -0.686415 0.054022 -0.725200 -v 0.015750 -0.087944 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 -0.082500 0.092800 -vn 0.552289 -0.318863 -0.770262 -v 0.021585 -0.106250 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.015625 -0.111375 0.092800 -vn 0.637728 0.000000 -0.770262 -v 0.021250 -0.107500 0.092800 -vn -0.206454 0.635401 -0.744071 -v 0.008840 -0.097454 0.092800 -vn -0.392700 0.540504 -0.744071 -v 0.011628 -0.096034 0.092800 -vn -0.540505 0.392699 -0.744071 -v 0.013840 -0.093822 0.092800 -vn -0.635401 0.206454 -0.744071 -v 0.015261 -0.091034 0.092800 -vn 0.000000 0.000000 -1.000000 -v -0.025750 -0.111375 0.092800 -vn 0.000000 0.707107 -0.707107 -v -0.025750 -0.097944 0.092800 -vn -0.054022 0.686415 -0.725200 -v 0.005750 -0.097944 0.092800 -vn -0.318864 0.552289 -0.770262 -v -0.079125 -0.116949 0.092800 -vn -0.000000 0.707107 -0.707107 -v -0.069750 -0.097944 0.092800 -vn -0.095839 0.727973 -0.678875 -v -0.085250 -0.097944 0.092800 -vn -0.655722 0.378581 -0.653227 -v -0.089580 -0.100444 0.092800 -vn -0.378581 0.655722 -0.653227 -v -0.087750 -0.098614 0.092800 -vn -0.727973 0.095840 -0.678874 -v -0.090250 -0.102944 0.092800 -vn -0.707107 0.000000 -0.707107 -v -0.090250 -0.111375 0.092800 -vn -0.724383 -0.071346 -0.685696 -v -0.090250 -0.119000 0.092800 -vn -0.689401 -0.285559 -0.665719 -v -0.089869 -0.120913 0.092800 -vn -0.527646 -0.527644 -0.665719 -v -0.088786 -0.122536 0.092800 -vn 0.552289 0.318864 -0.770262 -v 0.021585 -0.108750 0.092800 -vn 0.318864 0.552288 -0.770262 -v 0.022500 -0.109665 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 -0.111375 0.092800 -vn 0.000000 0.637729 -0.770261 -v 0.023750 -0.110000 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.029000 -0.111375 0.092800 -vn -0.318863 0.552288 -0.770262 -v 0.025000 -0.109665 0.092800 -vn -0.552289 0.318864 -0.770261 -v 0.025915 -0.108750 0.092800 -vn -0.637727 -0.000000 -0.770262 -v 0.026250 -0.107500 0.092800 -vn -0.552289 -0.318864 -0.770261 -v 0.025915 -0.106250 0.092800 -vn -0.318865 -0.552288 -0.770262 -v 0.025000 -0.105335 0.092800 -vn 0.000000 -0.637727 -0.770263 -v 0.023750 -0.105000 0.092800 -vn 0.318866 -0.552288 -0.770262 -v 0.022500 -0.105335 0.092800 -vn 0.552289 0.318864 -0.770261 -v 0.021585 -0.058750 0.092800 -vn 0.318864 0.552288 -0.770262 -v 0.022500 -0.059665 0.092800 -vn 0.000000 0.637729 -0.770261 -v 0.023750 -0.060000 0.092800 -vn -0.318863 0.552288 -0.770262 -v 0.025000 -0.059665 0.092800 -vn 0.000000 -0.637728 -0.770262 -v 0.023750 -0.055000 0.092800 -vn 0.000000 0.707107 -0.707107 -v 0.023500 -0.048500 0.092800 -vn -0.318864 -0.552289 -0.770262 -v 0.025000 -0.055335 0.092800 -vn -0.552289 0.318864 -0.770261 -v 0.025915 -0.058750 0.092800 -vn -0.637728 0.000000 -0.770262 -v 0.026250 -0.057500 0.092800 -vn -0.552289 -0.318864 -0.770262 -v 0.025915 -0.056250 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.029000 -0.125125 0.092800 -vn -0.000000 -0.637727 -0.770263 -v 0.028750 -0.133000 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 -0.125125 0.092800 -vn 0.318864 -0.552289 -0.770261 -v 0.027250 -0.133402 0.092800 -vn 0.552288 -0.318864 -0.770262 -v 0.026152 -0.134500 0.092800 -vn 0.637728 0.000001 -0.770262 -v 0.025750 -0.136000 0.092800 -vn 0.000000 0.000000 -1.000000 -v 0.023500 -0.138625 0.092800 -vn 0.552287 0.318865 -0.770262 -v 0.026152 -0.137500 0.092800 -vn -0.552287 0.318866 -0.770262 -v 0.031348 -0.137500 0.092800 -vn -0.637728 0.000001 -0.770262 -v 0.031750 -0.136000 0.092800 -vn -0.552287 -0.318865 -0.770263 -v 0.031348 -0.134500 0.092800 -vn -0.318864 -0.552290 -0.770261 -v 0.030250 -0.133402 0.092800 -vn 0.095838 -0.727973 -0.678875 -v 0.033750 -0.145000 0.092800 -vn 0.000000 -0.707107 -0.707107 -v 0.029000 -0.145000 0.092800 -vn 0.318864 0.552289 -0.770261 -v 0.027250 -0.138598 0.092800 -vn 0.000000 -0.707107 -0.707107 -v 0.023500 -0.145000 0.092800 -vn -0.375134 -0.657243 -0.653686 -v -0.003730 -0.144342 0.092800 -vn -0.651601 -0.384850 -0.653687 -v -0.005557 -0.142543 0.092800 -vn -0.094907 -0.727857 -0.679130 -v -0.001252 -0.145000 0.092800 -vn 0.000000 -0.707107 -0.707107 -v 0.015625 -0.145000 0.092800 -# 8228 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 2//2 4//4 5//5 -f 6//6 7//7 8//8 -f 9//9 10//10 11//11 -f 12//12 13//13 14//14 -f 15//15 16//16 17//17 -f 18//18 19//19 20//20 -f 21//21 22//22 23//23 -f 24//24 25//25 26//26 -f 27//27 28//28 29//29 -f 30//30 31//31 32//32 -f 33//33 34//34 35//35 -f 36//36 37//37 38//38 -f 39//39 40//40 41//41 -f 42//42 43//43 44//44 -f 45//45 46//46 47//47 -f 48//48 49//49 50//50 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 55//55 56//56 8//8 -f 57//57 58//58 59//59 -f 60//60 61//61 62//62 -f 63//63 64//64 65//65 -f 66//66 67//67 68//68 -f 69//69 70//70 71//71 -f 72//72 73//73 74//74 -f 75//75 76//76 77//77 -f 78//78 79//79 80//80 -f 81//81 82//82 83//83 -f 84//84 81//81 85//85 -f 86//86 87//87 88//88 -f 88//88 87//87 89//89 -f 88//88 89//89 85//85 -f 85//85 89//89 90//90 -f 85//85 90//90 84//84 -f 91//91 92//92 93//93 -f 93//93 92//92 71//71 -f 93//93 71//71 94//94 -f 94//94 71//71 95//95 -f 96//96 97//97 98//98 -f 98//98 97//97 99//99 -f 98//98 99//99 100//100 -f 100//100 99//99 101//101 -f 100//100 101//101 71//71 -f 71//71 101//101 102//102 -f 71//71 102//102 95//95 -f 103//103 104//104 105//105 -f 105//105 106//106 103//103 -f 103//103 106//106 107//107 -f 103//103 107//107 96//96 -f 96//96 107//107 108//108 -f 96//96 108//108 97//97 -f 109//109 110//110 111//111 -f 112//112 113//113 114//114 -f 113//113 115//115 114//114 -f 114//114 115//115 116//116 -f 114//114 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 103//103 -f 103//103 122//122 123//123 -f 103//103 123//123 104//104 -f 124//124 125//125 126//126 -f 126//126 125//125 127//127 -f 126//126 127//127 128//128 -f 128//128 127//127 129//129 -f 129//129 130//130 128//128 -f 128//128 130//130 131//131 -f 128//128 131//131 132//132 -f 133//133 134//134 135//135 -f 135//135 134//134 132//132 -f 135//135 132//132 136//136 -f 136//136 132//132 131//131 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 140//140 141//141 139//139 -f 139//139 141//141 142//142 -f 139//139 142//142 134//134 -f 134//134 142//142 143//143 -f 82//82 144//144 83//83 -f 83//83 144//144 145//145 -f 83//83 145//145 139//139 -f 139//139 145//145 146//146 -f 139//139 146//146 137//137 -f 147//147 132//132 148//148 -f 148//148 132//132 134//134 -f 148//148 134//134 149//149 -f 149//149 134//134 143//143 -f 147//147 150//150 132//132 -f 132//132 150//150 151//151 -f 132//132 151//151 146//146 -f 146//146 151//151 152//152 -f 146//146 152//152 137//137 -f 153//153 154//154 155//155 -f 155//155 154//154 156//156 -f 157//157 158//158 159//159 -f 159//159 158//158 160//160 -f 159//159 160//160 161//161 -f 162//162 163//163 164//164 -f 164//164 163//163 165//165 -f 164//164 165//165 166//166 -f 167//167 168//168 169//169 -f 169//169 168//168 163//163 -f 169//169 163//163 170//170 -f 170//170 163//163 162//162 -f 167//167 171//171 168//168 -f 168//168 171//171 172//172 -f 168//168 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 175//175 -f 176//176 177//177 173//173 -f 173//173 177//177 178//178 -f 173//173 178//178 179//179 -f 179//179 178//178 180//180 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 183//183 -f 175//175 184//184 165//165 -f 165//165 184//184 185//185 -f 165//165 185//185 166//166 -f 165//165 186//186 175//175 -f 175//175 186//186 187//187 -f 175//175 187//187 173//173 -f 173//173 187//187 188//188 -f 173//173 188//188 176//176 -f 189//189 190//190 191//191 -f 191//191 190//190 192//192 -f 193//193 194//194 195//195 -f 195//195 194//194 191//191 -f 195//195 191//191 196//196 -f 196//196 191//191 192//192 -f 75//75 77//77 197//197 -f 198//198 199//199 200//200 -f 193//193 197//197 194//194 -f 194//194 197//197 77//77 -f 194//194 77//77 201//201 -f 201//201 77//77 200//200 -f 201//201 200//200 202//202 -f 202//202 200//200 199//199 -f 203//203 204//204 205//205 -f 205//205 204//204 206//206 -f 205//205 206//206 198//198 -f 156//156 207//207 155//155 -f 155//155 207//207 208//208 -f 155//155 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 214//214 215//215 216//216 -f 217//217 218//218 219//219 -f 215//215 220//220 216//216 -f 216//216 220//220 221//221 -f 216//216 221//221 159//159 -f 221//221 222//222 159//159 -f 159//159 222//222 223//223 -f 159//159 223//223 224//224 -f 72//72 219//219 73//73 -f 73//73 219//219 218//218 -f 73//73 218//218 225//225 -f 225//225 218//218 226//226 -f 225//225 226//226 227//227 -f 224//224 223//223 228//228 -f 228//228 223//223 229//229 -f 228//228 229//229 219//219 -f 219//219 229//229 230//230 -f 219//219 230//230 217//217 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 233//233 234//234 235//235 -f 236//236 237//237 238//238 -f 238//238 237//237 239//239 -f 238//238 239//239 240//240 -f 240//240 239//239 241//241 -f 241//241 239//239 242//242 -f 242//242 239//239 243//243 -f 242//242 243//243 244//244 -f 244//244 243//243 245//245 -f 244//244 245//245 246//246 -f 247//247 69//69 248//248 -f 248//248 69//69 71//71 -f 248//248 71//71 249//249 -f 249//249 71//71 92//92 -f 249//249 92//92 86//86 -f 86//86 92//92 91//91 -f 86//86 91//91 87//87 -f 250//250 251//251 252//252 -f 251//251 253//253 254//254 -f 254//254 253//253 255//255 -f 255//255 253//253 256//256 -f 255//255 256//256 247//247 -f 247//247 256//256 257//257 -f 247//247 257//257 69//69 -f 250//250 252//252 258//258 -f 254//254 259//259 251//251 -f 251//251 259//259 260//260 -f 251//251 260//260 252//252 -f 252//252 260//260 261//261 -f 252//252 261//261 262//262 -f 263//263 264//264 265//265 -f 266//266 264//264 267//267 -f 267//267 264//264 70//70 -f 267//267 70//70 268//268 -f 268//268 70//70 69//69 -f 269//269 270//270 271//271 -f 271//271 270//270 9//9 -f 265//265 272//272 263//263 -f 263//263 272//272 273//273 -f 263//263 273//273 9//9 -f 9//9 273//273 274//274 -f 9//9 274//274 275//275 -f 275//275 276//276 9//9 -f 9//9 276//276 277//277 -f 9//9 277//277 271//271 -f 271//271 277//277 278//278 -f 271//271 278//278 279//279 -f 279//279 278//278 280//280 -f 279//279 280//280 267//267 -f 267//267 280//280 281//281 -f 267//267 281//281 266//266 -f 282//282 283//283 252//252 -f 252//252 283//283 270//270 -f 252//252 270//270 258//258 -f 258//258 270//270 269//269 -f 284//284 285//285 286//286 -f 287//287 288//288 289//289 -f 284//284 290//290 285//285 -f 285//285 290//290 291//291 -f 285//285 291//291 292//292 -f 292//292 291//291 293//293 -f 292//292 293//293 294//294 -f 295//295 296//296 286//286 -f 286//286 296//296 297//297 -f 286//286 297//297 284//284 -f 68//68 67//67 298//298 -f 294//294 282//282 292//292 -f 292//292 282//282 252//252 -f 292//292 252//252 299//299 -f 299//299 252//252 300//300 -f 299//299 301//301 292//292 -f 292//292 301//301 302//302 -f 292//292 302//302 285//285 -f 285//285 302//302 303//303 -f 303//303 304//304 285//285 -f 285//285 304//304 305//305 -f 285//285 305//305 306//306 -f 305//305 307//307 306//306 -f 306//306 307//307 308//308 -f 306//306 308//308 68//68 -f 68//68 308//308 309//309 -f 68//68 309//309 66//66 -f 310//310 311//311 312//312 -f 312//312 311//311 313//313 -f 313//313 314//314 312//312 -f 312//312 314//314 315//315 -f 312//312 315//315 316//316 -f 316//316 315//315 317//317 -f 316//316 317//317 298//298 -f 298//298 317//317 318//318 -f 298//298 318//318 68//68 -f 318//318 319//319 68//68 -f 68//68 319//319 320//320 -f 68//68 320//320 306//306 -f 306//306 320//320 321//321 -f 321//321 322//322 306//306 -f 306//306 322//322 323//323 -f 306//306 323//323 310//310 -f 310//310 323//323 324//324 -f 310//310 324//324 311//311 -f 325//325 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 330//330 331//331 332//332 -f 333//333 334//334 335//335 -f 335//335 334//334 336//336 -f 330//330 332//332 337//337 -f 337//337 332//332 338//338 -f 337//337 338//338 339//339 -f 340//340 325//325 341//341 -f 342//342 343//343 338//338 -f 338//338 343//343 344//344 -f 338//338 344//344 339//339 -f 339//339 344//344 345//345 -f 339//339 345//345 346//346 -f 346//346 345//345 347//347 -f 346//346 347//347 348//348 -f 340//340 341//341 349//349 -f 349//349 341//341 350//350 -f 349//349 350//350 347//347 -f 347//347 350//350 351//351 -f 347//347 351//351 348//348 -f 352//352 353//353 354//354 -f 354//354 355//355 356//356 -f 356//356 355//355 357//357 -f 356//356 357//357 358//358 -f 352//352 354//354 359//359 -f 359//359 354//354 356//356 -f 359//359 356//356 360//360 -f 360//360 356//356 361//361 -f 360//360 361//361 362//362 -f 363//363 364//364 365//365 -f 366//366 367//367 361//361 -f 361//361 367//367 368//368 -f 361//361 368//368 362//362 -f 352//352 369//369 353//353 -f 353//353 369//369 370//370 -f 353//353 370//370 371//371 -f 371//371 370//370 372//372 -f 371//371 372//372 373//373 -f 373//373 372//372 363//363 -f 373//373 363//363 374//374 -f 374//374 363//363 365//365 -f 374//374 365//365 375//375 -f 357//357 376//376 358//358 -f 358//358 376//376 377//377 -f 358//358 377//377 378//378 -f 377//377 379//379 378//378 -f 378//378 379//379 380//380 -f 378//378 380//380 381//381 -f 382//382 383//383 384//384 -f 59//59 58//58 384//384 -f 384//384 58//58 385//385 -f 384//384 385//385 382//382 -f 386//386 387//387 388//388 -f 388//388 387//387 389//389 -f 388//388 389//389 390//390 -f 390//390 389//389 391//391 -f 390//390 391//391 392//392 -f 392//392 391//391 393//393 -f 394//394 395//395 396//396 -f 396//396 395//395 397//397 -f 398//398 399//399 393//393 -f 393//393 399//399 400//400 -f 393//393 400//400 392//392 -f 397//397 401//401 59//59 -f 59//59 401//401 402//402 -f 402//402 403//403 59//59 -f 59//59 403//403 404//404 -f 59//59 404//404 57//57 -f 57//57 404//404 398//398 -f 57//57 398//398 405//405 -f 405//405 398//398 393//393 -f 406//406 407//407 408//408 -f 408//408 407//407 409//409 -f 55//55 8//8 410//410 -f 410//410 8//8 7//7 -f 410//410 7//7 411//411 -f 412//412 413//413 7//7 -f 7//7 413//413 414//414 -f 7//7 414//414 415//415 -f 416//416 417//417 418//418 -f 418//418 417//417 419//419 -f 418//418 419//419 409//409 -f 409//409 419//419 420//420 -f 409//409 420//420 408//408 -f 408//408 420//420 421//421 -f 408//408 421//421 422//422 -f 411//411 7//7 423//423 -f 423//423 7//7 415//415 -f 423//423 415//415 416//416 -f 416//416 415//415 424//424 -f 416//416 424//424 417//417 -f 425//425 426//426 412//412 -f 412//412 426//426 427//427 -f 412//412 427//427 413//413 -f 428//428 429//429 430//430 -f 428//428 430//430 431//431 -f 262//262 432//432 252//252 -f 252//252 432//432 298//298 -f 252//252 298//298 300//300 -f 300//300 298//298 67//67 -f 433//433 434//434 435//435 -f 435//435 434//434 436//436 -f 435//435 436//436 437//437 -f 224//224 438//438 159//159 -f 159//159 438//438 236//236 -f 159//159 236//236 157//157 -f 157//157 236//236 238//238 -f 157//157 238//238 183//183 -f 183//183 238//238 439//439 -f 183//183 439//439 181//181 -f 181//181 439//439 440//440 -f 441//441 442//442 443//443 -f 443//443 442//442 444//444 -f 445//445 446//446 447//447 -f 447//447 446//446 448//448 -f 449//449 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 453//453 454//454 455//455 -f 456//456 457//457 458//458 -f 458//458 457//457 455//455 -f 458//458 455//455 459//459 -f 459//459 455//455 454//454 -f 460//460 461//461 462//462 -f 462//462 461//461 463//463 -f 463//463 461//461 464//464 -f 463//463 464//464 456//456 -f 456//456 464//464 465//465 -f 456//456 465//465 457//457 -f 466//466 467//467 381//381 -f 381//381 467//467 378//378 -f 378//378 467//467 468//468 -f 378//378 468//468 469//469 -f 470//470 471//471 213//213 -f 468//468 472//472 469//469 -f 469//469 472//472 473//473 -f 469//469 473//473 205//205 -f 205//205 473//473 474//474 -f 205//205 474//474 475//475 -f 212//212 203//203 213//213 -f 213//213 203//203 205//205 -f 213//213 205//205 470//470 -f 470//470 205//205 475//475 -f 476//476 477//477 478//478 -f 476//476 478//478 479//479 -f 480//480 481//481 482//482 -f 483//483 484//484 485//485 -f 486//486 487//487 488//488 -f 487//487 489//489 488//488 -f 488//488 489//489 490//490 -f 488//488 490//490 491//491 -f 491//491 490//490 492//492 -f 491//491 492//492 493//493 -f 482//482 494//494 480//480 -f 480//480 494//494 17//17 -f 480//480 17//17 495//495 -f 495//495 17//17 496//496 -f 497//497 498//498 499//499 -f 499//499 498//498 500//500 -f 499//499 500//500 501//501 -f 501//501 500//500 502//502 -f 501//501 502//502 503//503 -f 503//503 502//502 504//504 -f 505//505 506//506 507//507 -f 508//508 509//509 510//510 -f 510//510 509//509 511//511 -f 510//510 511//511 512//512 -f 499//499 513//513 497//497 -f 497//497 513//513 514//514 -f 497//497 514//514 508//508 -f 508//508 514//514 515//515 -f 508//508 515//515 509//509 -f 516//516 517//517 518//518 -f 518//518 517//517 519//519 -f 518//518 519//519 520//520 -f 521//521 522//522 518//518 -f 518//518 522//522 523//523 -f 518//518 523//523 516//516 -f 524//524 525//525 526//526 -f 524//524 526//526 1//1 -f 526//526 527//527 1//1 -f 1//1 527//527 528//528 -f 1//1 528//528 529//529 -f 529//529 528//528 530//530 -f 529//529 530//530 521//521 -f 521//521 530//530 531//531 -f 521//521 531//531 522//522 -f 532//532 533//533 534//534 -f 535//535 536//536 537//537 -f 535//535 537//537 538//538 -f 53//53 539//539 540//540 -f 540//540 539//539 541//541 -f 537//537 542//542 538//538 -f 538//538 542//542 543//543 -f 538//538 543//543 539//539 -f 539//539 543//543 544//544 -f 539//539 544//544 541//541 -f 536//536 535//535 545//545 -f 545//545 535//535 546//546 -f 545//545 546//546 547//547 -f 547//547 546//546 548//548 -f 547//547 548//548 549//549 -f 550//550 551//551 552//552 -f 552//552 551//551 553//553 -f 553//553 554//554 552//552 -f 552//552 554//554 555//555 -f 552//552 555//555 556//556 -f 556//556 555//555 557//557 -f 557//557 558//558 556//556 -f 556//556 558//558 559//559 -f 556//556 559//559 560//560 -f 561//561 562//562 563//563 -f 559//559 564//564 560//560 -f 560//560 564//564 565//565 -f 560//560 565//565 561//561 -f 561//561 565//565 566//566 -f 561//561 566//566 562//562 -f 567//567 568//568 569//569 -f 5//5 570//570 571//571 -f 572//572 573//573 574//574 -f 574//574 573//573 575//575 -f 574//574 575//575 569//569 -f 576//576 577//577 578//578 -f 578//578 577//577 579//579 -f 578//578 579//579 574//574 -f 574//574 579//579 580//580 -f 574//574 580//580 572//572 -f 576//576 581//581 577//577 -f 577//577 581//581 582//582 -f 577//577 582//582 583//583 -f 582//582 584//584 583//583 -f 583//583 584//584 585//585 -f 583//583 585//585 4//4 -f 4//4 585//585 586//586 -f 4//4 586//586 5//5 -f 5//5 586//586 587//587 -f 5//5 587//587 570//570 -f 588//588 589//589 590//590 -f 590//590 589//589 591//591 -f 590//590 591//591 189//189 -f 189//189 591//591 592//592 -f 189//189 592//592 190//190 -f 593//593 594//594 595//595 -f 596//596 124//124 597//597 -f 597//597 124//124 126//126 -f 597//597 126//126 111//111 -f 111//111 126//126 128//128 -f 111//111 128//128 109//109 -f 598//598 599//599 600//600 -f 599//599 601//601 600//600 -f 600//600 601//601 602//602 -f 600//600 602//602 603//603 -f 604//604 605//605 606//606 -f 606//606 605//605 607//607 -f 606//606 607//607 608//608 -f 609//609 610//610 611//611 -f 611//611 610//610 612//612 -f 612//612 610//610 613//613 -f 612//612 613//613 614//614 -f 603//603 602//602 613//613 -f 613//613 602//602 615//615 -f 613//613 615//615 614//614 -f 616//616 617//617 618//618 -f 616//616 618//618 619//619 -f 618//618 620//620 619//619 -f 619//619 620//620 621//621 -f 619//619 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 624//624 623//623 625//625 -f 624//624 625//625 626//626 -f 617//617 616//616 627//627 -f 627//627 616//616 628//628 -f 627//627 628//628 629//629 -f 49//49 630//630 631//631 -f 631//631 630//630 632//632 -f 633//633 634//634 635//635 -f 635//635 634//634 636//636 -f 635//635 636//636 637//637 -f 637//637 636//636 638//638 -f 637//637 638//638 639//639 -f 605//605 640//640 641//641 -f 638//638 642//642 639//639 -f 639//639 642//642 643//643 -f 639//639 643//643 600//600 -f 600//600 643//643 644//644 -f 600//600 644//644 645//645 -f 604//604 598//598 605//605 -f 605//605 598//598 600//600 -f 605//605 600//600 640//640 -f 640//640 600//600 645//645 -f 646//646 647//647 648//648 -f 43//43 649//649 650//650 -f 650//650 649//649 651//651 -f 650//650 651//651 652//652 -f 652//652 651//651 45//45 -f 653//653 654//654 655//655 -f 655//655 654//654 656//656 -f 655//655 656//656 657//657 -f 658//658 659//659 660//660 -f 660//660 659//659 661//661 -f 660//660 661//661 662//662 -f 659//659 663//663 664//664 -f 658//658 42//42 659//659 -f 659//659 42//42 44//44 -f 659//659 44//44 663//663 -f 663//663 44//44 665//665 -f 666//666 667//667 668//668 -f 41//41 40//40 668//668 -f 668//668 40//40 669//669 -f 668//668 669//669 666//666 -f 667//667 670//670 671//671 -f 671//671 670//670 672//672 -f 671//671 672//672 673//673 -f 673//673 672//672 674//674 -f 673//673 674//674 44//44 -f 44//44 674//674 675//675 -f 44//44 675//675 665//665 -f 676//676 677//677 661//661 -f 678//678 679//679 680//680 -f 680//680 679//679 661//661 -f 680//680 661//661 681//681 -f 681//681 661//661 677//677 -f 682//682 683//683 684//684 -f 38//38 37//37 685//685 -f 685//685 37//37 686//686 -f 685//685 686//686 687//687 -f 684//684 683//683 688//688 -f 688//688 683//683 689//689 -f 688//688 689//689 690//690 -f 691//691 692//692 693//693 -f 693//693 692//692 694//694 -f 694//694 695//695 693//693 -f 693//693 695//695 696//696 -f 693//693 696//696 697//697 -f 696//696 698//698 697//697 -f 697//697 698//698 699//699 -f 697//697 699//699 700//700 -f 163//163 701//701 691//691 -f 691//691 701//701 702//702 -f 691//691 702//702 692//692 -f 699//699 703//703 700//700 -f 700//700 703//703 704//704 -f 700//700 704//704 168//168 -f 168//168 704//704 705//705 -f 168//168 705//705 163//163 -f 163//163 705//705 706//706 -f 163//163 706//706 701//701 -f 707//707 38//38 708//708 -f 709//709 710//710 711//711 -f 711//711 710//710 685//685 -f 710//710 712//712 685//685 -f 685//685 712//712 713//713 -f 685//685 713//713 38//38 -f 38//38 713//713 714//714 -f 38//38 714//714 708//708 -f 715//715 716//716 717//717 -f 717//717 716//716 718//718 -f 717//717 718//718 711//711 -f 711//711 718//718 719//719 -f 711//711 719//719 709//709 -f 32//32 31//31 720//720 -f 720//720 31//31 721//721 -f 720//720 721//721 722//722 -f 721//721 723//723 722//722 -f 722//722 723//723 724//724 -f 722//722 724//724 29//29 -f 29//29 724//724 725//725 -f 29//29 725//725 726//726 -f 30//30 32//32 727//727 -f 727//727 32//32 728//728 -f 727//727 728//728 729//729 -f 726//726 730//730 731//731 -f 731//731 730//730 732//732 -f 731//731 732//732 733//733 -f 734//734 735//735 736//736 -f 736//736 735//735 737//737 -f 738//738 739//739 595//595 -f 737//737 740//740 741//741 -f 740//740 742//742 741//741 -f 741//741 742//742 743//743 -f 741//741 743//743 744//744 -f 744//744 743//743 745//745 -f 745//745 738//738 744//744 -f 744//744 738//738 595//595 -f 744//744 595//595 597//597 -f 597//597 595//595 594//594 -f 597//597 594//594 596//596 -f 739//739 746//746 595//595 -f 595//595 746//746 134//134 -f 595//595 134//134 593//593 -f 593//593 134//134 133//133 -f 734//734 139//139 747//747 -f 747//747 139//139 134//134 -f 747//747 134//134 748//748 -f 748//748 134//134 746//746 -f 749//749 750//750 654//654 -f 654//654 750//750 751//751 -f 654//654 751//751 656//656 -f 656//656 751//751 752//752 -f 656//656 752//752 753//753 -f 754//754 29//29 755//755 -f 755//755 29//29 28//28 -f 755//755 28//28 756//756 -f 756//756 28//28 757//757 -f 756//756 757//757 758//758 -f 758//758 757//757 751//751 -f 758//758 751//751 759//759 -f 759//759 751//751 750//750 -f 749//749 654//654 760//760 -f 760//760 654//654 722//722 -f 760//760 722//722 761//761 -f 754//754 762//762 29//29 -f 29//29 762//762 763//763 -f 29//29 763//763 722//722 -f 722//722 763//763 764//764 -f 722//722 764//764 761//761 -f 726//726 731//731 29//29 -f 29//29 731//731 765//765 -f 29//29 765//765 27//27 -f 766//766 767//767 768//768 -f 752//752 769//769 753//753 -f 753//753 769//769 770//770 -f 753//753 770//770 766//766 -f 766//766 770//770 771//771 -f 766//766 771//771 767//767 -f 668//668 772//772 41//41 -f 41//41 772//772 773//773 -f 41//41 773//773 690//690 -f 690//690 773//773 774//774 -f 690//690 774//774 688//688 -f 775//775 776//776 777//777 -f 775//775 777//777 778//778 -f 777//777 779//779 778//778 -f 778//778 779//779 780//780 -f 778//778 780//780 668//668 -f 668//668 780//780 781//781 -f 668//668 781//781 772//772 -f 776//776 775//775 782//782 -f 782//782 775//775 711//711 -f 782//782 711//711 783//783 -f 783//783 711//711 685//685 -f 783//783 685//685 684//684 -f 684//684 685//685 687//687 -f 684//684 687//687 682//682 -f 26//26 784//784 785//785 -f 785//785 786//786 26//26 -f 26//26 786//786 787//787 -f 26//26 787//787 24//24 -f 784//784 26//26 788//788 -f 788//788 26//26 789//789 -f 788//788 789//789 790//790 -f 790//790 789//789 791//791 -f 790//790 791//791 792//792 -f 792//792 791//791 793//793 -f 793//793 791//791 794//794 -f 793//793 794//794 795//795 -f 795//795 794//794 796//796 -f 795//795 796//796 797//797 -f 797//797 796//796 798//798 -f 797//797 798//798 799//799 -f 19//19 800//800 801//801 -f 533//533 532//532 802//802 -f 802//802 532//532 803//803 -f 802//802 803//803 804//804 -f 804//804 803//803 805//805 -f 804//804 805//805 806//806 -f 805//805 807//807 806//806 -f 806//806 807//807 808//808 -f 806//806 808//808 809//809 -f 809//809 808//808 16//16 -f 16//16 808//808 491//491 -f 16//16 491//491 17//17 -f 17//17 491//491 493//493 -f 17//17 493//493 496//496 -f 15//15 17//17 810//810 -f 810//810 17//17 494//494 -f 810//810 494//494 811//811 -f 811//811 494//494 812//812 -f 811//811 812//812 813//813 -f 500//500 814//814 815//815 -f 816//816 817//817 610//610 -f 613//613 818//818 819//819 -f 819//819 818//818 820//820 -f 819//819 820//820 821//821 -f 821//821 822//822 819//819 -f 819//819 822//822 823//823 -f 819//819 823//823 824//824 -f 824//824 823//823 825//825 -f 824//824 825//825 826//826 -f 817//817 827//827 610//610 -f 610//610 827//827 828//828 -f 610//610 828//828 613//613 -f 613//613 828//828 829//829 -f 613//613 829//829 818//818 -f 830//830 831//831 832//832 -f 832//832 831//831 833//833 -f 12//12 14//14 834//834 -f 834//834 14//14 835//835 -f 834//834 835//835 836//836 -f 836//836 835//835 837//837 -f 836//836 837//837 838//838 -f 838//838 837//837 839//839 -f 838//838 839//839 840//840 -f 841//841 50//50 840//840 -f 841//841 842//842 50//50 -f 50//50 842//842 843//843 -f 50//50 843//843 844//844 -f 844//844 845//845 50//50 -f 50//50 845//845 624//624 -f 50//50 624//624 48//48 -f 48//48 624//624 626//626 -f 845//845 846//846 624//624 -f 624//624 846//846 847//847 -f 624//624 847//847 839//839 -f 839//839 847//847 848//848 -f 839//839 848//848 849//849 -f 849//849 850//850 839//839 -f 839//839 850//850 851//851 -f 839//839 851//851 840//840 -f 840//840 851//851 852//852 -f 840//840 852//852 841//841 -f 853//853 854//854 855//855 -f 854//854 856//856 855//855 -f 855//855 856//856 857//857 -f 855//855 857//857 858//858 -f 857//857 859//859 858//858 -f 858//858 859//859 860//860 -f 858//858 860//860 619//619 -f 619//619 860//860 861//861 -f 619//619 861//861 862//862 -f 862//862 863//863 619//619 -f 619//619 863//863 864//864 -f 619//619 864//864 616//616 -f 616//616 864//864 865//865 -f 616//616 865//865 866//866 -f 867//867 868//868 869//869 -f 867//867 869//869 870//870 -f 870//870 869//869 832//832 -f 870//870 832//832 871//871 -f 872//872 873//873 874//874 -f 875//875 833//833 876//876 -f 876//876 833//833 872//872 -f 876//876 872//872 877//877 -f 877//877 872//872 874//874 -f 875//875 878//878 833//833 -f 833//833 878//878 879//879 -f 833//833 879//879 832//832 -f 832//832 879//879 880//880 -f 832//832 880//880 871//871 -f 881//881 882//882 11//11 -f 883//883 884//884 10//10 -f 10//10 884//884 885//885 -f 10//10 885//885 11//11 -f 11//11 885//885 886//886 -f 11//11 886//886 881//881 -f 887//887 888//888 834//834 -f 834//834 888//888 889//889 -f 834//834 889//889 12//12 -f 889//889 890//890 12//12 -f 12//12 890//890 891//891 -f 12//12 891//891 10//10 -f 10//10 891//891 892//892 -f 10//10 892//892 883//883 -f 49//49 631//631 50//50 -f 50//50 631//631 893//893 -f 50//50 893//893 840//840 -f 840//840 893//893 894//894 -f 840//840 894//894 838//838 -f 838//838 894//894 895//895 -f 838//838 895//895 836//836 -f 836//836 895//895 11//11 -f 836//836 11//11 834//834 -f 834//834 11//11 882//882 -f 834//834 882//882 887//887 -f 896//896 505//505 897//897 -f 897//897 505//505 507//507 -f 897//897 507//507 488//488 -f 488//488 507//507 483//483 -f 488//488 483//483 486//486 -f 486//486 483//483 485//485 -f 506//506 504//504 507//507 -f 507//507 504//504 502//502 -f 507//507 502//502 483//483 -f 483//483 502//502 482//482 -f 483//483 482//482 484//484 -f 484//484 482//482 481//481 -f 898//898 899//899 900//900 -f 899//899 901//901 900//900 -f 900//900 901//901 902//902 -f 900//900 902//902 25//25 -f 903//903 904//904 26//26 -f 26//26 904//904 905//905 -f 26//26 905//905 906//906 -f 906//906 905//905 907//907 -f 906//906 907//907 908//908 -f 908//908 898//898 906//906 -f 906//906 898//898 900//900 -f 906//906 900//900 447//447 -f 447//447 900//900 450//450 -f 447//447 450//450 445//445 -f 445//445 450//450 449//449 -f 902//902 909//909 25//25 -f 25//25 909//909 910//910 -f 25//25 910//910 26//26 -f 26//26 910//910 911//911 -f 26//26 911//911 903//903 -f 868//868 873//873 869//869 -f 869//869 873//873 872//872 -f 869//869 872//872 216//216 -f 216//216 872//872 225//225 -f 216//216 225//225 214//214 -f 214//214 225//225 227//227 -f 9//9 11//11 263//263 -f 263//263 11//11 895//895 -f 263//263 895//895 912//912 -f 912//912 895//895 894//894 -f 912//912 894//894 913//913 -f 913//913 894//894 893//893 -f 913//913 893//893 914//914 -f 914//914 893//893 631//631 -f 914//914 631//631 915//915 -f 915//915 631//631 632//632 -f 915//915 632//632 916//916 -f 500//500 815//815 502//502 -f 502//502 815//815 917//917 -f 502//502 917//917 482//482 -f 482//482 917//917 918//918 -f 482//482 918//918 494//494 -f 494//494 918//918 919//919 -f 494//494 919//919 812//812 -f 463//463 920//920 462//462 -f 462//462 920//920 921//921 -f 462//462 921//921 922//922 -f 922//922 921//921 923//923 -f 922//922 923//923 924//924 -f 924//924 923//923 925//925 -f 924//924 925//925 338//338 -f 338//338 925//925 65//65 -f 338//338 65//65 342//342 -f 342//342 65//65 64//64 -f 920//920 819//819 921//921 -f 921//921 819//819 824//824 -f 921//921 824//824 923//923 -f 923//923 824//824 926//926 -f 923//923 926//926 925//925 -f 925//925 926//926 927//927 -f 925//925 927//927 65//65 -f 65//65 927//927 329//329 -f 65//65 329//329 63//63 -f 63//63 329//329 328//328 -f 928//928 608//608 929//929 -f 929//929 608//608 607//607 -f 929//929 607//607 930//930 -f 930//930 607//607 931//931 -f 930//930 931//931 155//155 -f 155//155 931//931 932//932 -f 155//155 932//932 153//153 -f 153//153 932//932 933//933 -f 641//641 646//646 605//605 -f 605//605 646//646 648//648 -f 605//605 648//648 607//607 -f 607//607 648//648 934//934 -f 607//607 934//934 931//931 -f 931//931 934//934 935//935 -f 931//931 935//935 932//932 -f 932//932 935//935 936//936 -f 932//932 936//936 933//933 -f 933//933 936//936 937//937 -f 647//647 633//633 648//648 -f 648//648 633//633 635//635 -f 648//648 635//635 934//934 -f 934//934 635//635 938//938 -f 934//934 938//938 935//935 -f 935//935 938//938 939//939 -f 935//935 939//939 936//936 -f 936//936 939//939 80//80 -f 936//936 80//80 937//937 -f 937//937 80//80 79//79 -f 637//637 830//830 635//635 -f 635//635 830//830 832//832 -f 635//635 832//832 938//938 -f 938//938 832//832 869//869 -f 938//938 869//869 939//939 -f 939//939 869//869 216//216 -f 939//939 216//216 80//80 -f 80//80 216//216 159//159 -f 80//80 159//159 78//78 -f 78//78 159//159 161//161 -f 831//831 940//940 833//833 -f 833//833 940//940 941//941 -f 833//833 941//941 872//872 -f 872//872 941//941 942//942 -f 872//872 942//942 225//225 -f 225//225 942//942 943//943 -f 225//225 943//943 73//73 -f 73//73 943//943 232//232 -f 73//73 232//232 74//74 -f 74//74 232//232 231//231 -f 74//74 231//231 246//246 -f 246//246 231//231 944//944 -f 246//246 944//944 244//244 -f 945//945 946//946 947//947 -f 947//947 946//946 948//948 -f 947//947 948//948 949//949 -f 949//949 948//948 950//950 -f 949//949 950//950 951//951 -f 951//951 950//950 952//952 -f 951//951 952//952 286//286 -f 286//286 952//952 287//287 -f 286//286 287//287 295//295 -f 295//295 287//287 289//289 -f 946//946 13//13 948//948 -f 948//948 13//13 12//12 -f 948//948 12//12 950//950 -f 950//950 12//12 10//10 -f 950//950 10//10 952//952 -f 952//952 10//10 9//9 -f 952//952 9//9 287//287 -f 287//287 9//9 270//270 -f 287//287 270//270 288//288 -f 288//288 270//270 283//283 -f 264//264 263//263 70//70 -f 70//70 263//263 912//912 -f 70//70 912//912 71//71 -f 71//71 912//912 913//913 -f 71//71 913//913 100//100 -f 100//100 913//913 914//914 -f 100//100 914//914 98//98 -f 98//98 914//914 915//915 -f 98//98 915//915 96//96 -f 96//96 915//915 916//916 -f 96//96 916//916 103//103 -f 858//858 953//953 855//855 -f 855//855 953//953 954//954 -f 855//855 954//954 955//955 -f 955//955 954//954 956//956 -f 955//955 956//956 957//957 -f 957//957 956//956 958//958 -f 957//957 958//958 412//412 -f 412//412 958//958 408//408 -f 412//412 408//408 425//425 -f 425//425 408//408 422//422 -f 953//953 510//510 954//954 -f 954//954 510//510 512//512 -f 954//954 512//512 956//956 -f 956//956 512//512 959//959 -f 956//956 959//959 958//958 -f 958//958 959//959 960//960 -f 958//958 960//960 408//408 -f 408//408 960//960 431//431 -f 408//408 431//431 406//406 -f 406//406 431//431 430//430 -f 961//961 962//962 963//963 -f 964//964 965//965 966//966 -f 966//966 965//965 232//232 -f 966//966 232//232 967//967 -f 967//967 232//232 943//943 -f 967//967 943//943 968//968 -f 968//968 943//943 942//942 -f 968//968 942//942 969//969 -f 969//969 942//942 941//941 -f 969//969 941//941 970//970 -f 970//970 941//941 940//940 -f 962//962 961//961 971//971 -f 971//971 961//961 234//234 -f 971//971 234//234 972//972 -f 963//963 973//973 961//961 -f 961//961 973//973 974//974 -f 961//961 974//974 966//966 -f 966//966 974//974 975//975 -f 966//966 975//975 964//964 -f 965//965 976//976 232//232 -f 232//232 976//976 977//977 -f 232//232 977//977 234//234 -f 234//234 977//977 978//978 -f 234//234 978//978 972//972 -f 979//979 980//980 234//234 -f 234//234 980//980 981//981 -f 234//234 981//981 235//235 -f 980//980 982//982 981//981 -f 981//981 982//982 983//983 -f 981//981 983//983 984//984 -f 984//984 983//983 985//985 -f 984//984 985//985 986//986 -f 987//987 961//961 988//988 -f 988//988 961//961 984//984 -f 988//988 984//984 989//989 -f 989//989 984//984 986//986 -f 987//987 990//990 961//961 -f 961//961 990//990 991//991 -f 961//961 991//991 234//234 -f 234//234 991//991 992//992 -f 234//234 992//992 979//979 -f 866//866 853//853 616//616 -f 616//616 853//853 855//855 -f 616//616 855//855 628//628 -f 628//628 855//855 955//955 -f 628//628 955//955 993//993 -f 993//993 955//955 957//957 -f 993//993 957//957 994//994 -f 994//994 957//957 412//412 -f 994//994 412//412 995//995 -f 995//995 412//412 7//7 -f 995//995 7//7 996//996 -f 996//996 7//7 6//6 -f 996//996 6//6 997//997 -f 331//331 333//333 332//332 -f 332//332 333//333 335//335 -f 332//332 335//335 998//998 -f 998//998 335//335 999//999 -f 998//998 999//999 361//361 -f 361//361 999//999 365//365 -f 361//361 365//365 366//366 -f 366//366 365//365 364//364 -f 380//380 375//375 381//381 -f 381//381 375//375 365//365 -f 381//381 365//365 1000//1000 -f 1000//1000 365//365 999//999 -f 1000//1000 999//999 327//327 -f 327//327 999//999 335//335 -f 327//327 335//335 325//325 -f 325//325 335//335 336//336 -f 325//325 336//336 341//341 -f 826//826 816//816 824//824 -f 824//824 816//816 610//610 -f 824//824 610//610 926//926 -f 926//926 610//610 609//609 -f 926//926 609//609 927//927 -f 927//927 609//609 1001//1001 -f 927//927 1001//1001 329//329 -f 329//329 1001//1001 1002//1002 -f 329//329 1002//1002 327//327 -f 327//327 1002//1002 1003//1003 -f 327//327 1003//1003 1000//1000 -f 1000//1000 1003//1003 1004//1004 -f 1000//1000 1004//1004 381//381 -f 381//381 1004//1004 478//478 -f 381//381 478//478 466//466 -f 466//466 478//478 477//477 -f 611//611 928//928 609//609 -f 609//609 928//928 929//929 -f 609//609 929//929 1001//1001 -f 1001//1001 929//929 930//930 -f 1001//1001 930//930 1002//1002 -f 1002//1002 930//930 155//155 -f 1002//1002 155//155 1003//1003 -f 1003//1003 155//155 209//209 -f 1003//1003 209//209 1004//1004 -f 1004//1004 209//209 211//211 -f 1004//1004 211//211 478//478 -f 478//478 211//211 213//213 -f 478//478 213//213 479//479 -f 479//479 213//213 471//471 -f 440//440 441//441 181//181 -f 181//181 441//441 443//443 -f 181//181 443//443 179//179 -f 179//179 443//443 1005//1005 -f 1006//1006 984//984 1007//1007 -f 1007//1007 984//984 1008//1008 -f 1009//1009 1010//1010 1008//1008 -f 1010//1010 1011//1011 1008//1008 -f 1008//1008 1011//1011 1012//1012 -f 1008//1008 1012//1012 1007//1007 -f 1013//1013 981//981 1014//1014 -f 1014//1014 981//981 984//984 -f 1014//1014 984//984 1015//1015 -f 1015//1015 984//984 1006//1006 -f 1013//1013 1016//1016 981//981 -f 981//981 1016//1016 1017//1017 -f 981//981 1017//1017 1018//1018 -f 1018//1018 1017//1017 1019//1019 -f 1020//1020 945//945 1021//1021 -f 1021//1021 945//945 947//947 -f 1021//1021 947//947 1022//1022 -f 1022//1022 947//947 949//949 -f 1022//1022 949//949 1023//1023 -f 1023//1023 949//949 951//951 -f 1023//1023 951//951 1024//1024 -f 1024//1024 951//951 286//286 -f 1024//1024 286//286 1025//1025 -f 1025//1025 286//286 285//285 -f 1025//1025 285//285 1026//1026 -f 1026//1026 285//285 306//306 -f 1026//1026 306//306 1027//1027 -f 1027//1027 306//306 310//310 -f 1027//1027 310//310 720//720 -f 61//61 386//386 62//62 -f 62//62 386//386 388//388 -f 62//62 388//388 1028//1028 -f 382//382 60//60 383//383 -f 383//383 60//60 62//62 -f 383//383 62//62 1029//1029 -f 1029//1029 62//62 1028//1028 -f 1029//1029 1028//1028 428//428 -f 448//448 460//460 447//447 -f 447//447 460//460 462//462 -f 447//447 462//462 906//906 -f 906//906 462//462 922//922 -f 906//906 922//922 26//26 -f 26//26 922//922 924//924 -f 26//26 924//924 789//789 -f 789//789 924//924 338//338 -f 789//789 338//338 791//791 -f 791//791 338//338 332//332 -f 791//791 332//332 794//794 -f 794//794 332//332 998//998 -f 794//794 998//998 796//796 -f 796//796 998//998 361//361 -f 796//796 361//361 798//798 -f 798//798 361//361 356//356 -f 1030//1030 1031//1031 1032//1032 -f 1005//1005 1033//1033 179//179 -f 179//179 1033//1033 1034//1034 -f 179//179 1034//1034 1035//1035 -f 1035//1035 1036//1036 179//179 -f 179//179 1036//1036 1037//1037 -f 179//179 1037//1037 173//173 -f 173//173 1037//1037 1038//1038 -f 173//173 1038//1038 1039//1039 -f 1031//1031 1040//1040 1032//1032 -f 1032//1032 1040//1040 1041//1041 -f 1032//1032 1041//1041 1005//1005 -f 1005//1005 1041//1041 1042//1042 -f 1005//1005 1042//1042 1033//1033 -f 1019//1019 1009//1009 1018//1018 -f 1018//1018 1009//1009 1008//1008 -f 1018//1018 1008//1008 717//717 -f 717//717 1008//1008 35//35 -f 717//717 35//35 715//715 -f 715//715 35//35 34//34 -f 970//970 1043//1043 969//969 -f 969//969 1043//1043 1044//1044 -f 969//969 1044//1044 968//968 -f 968//968 1044//1044 1045//1045 -f 968//968 1045//1045 967//967 -f 967//967 1045//1045 1046//1046 -f 967//967 1046//1046 966//966 -f 966//966 1046//1046 1047//1047 -f 966//966 1047//1047 961//961 -f 961//961 1047//1047 1048//1048 -f 961//961 1048//1048 984//984 -f 984//984 1048//1048 1049//1049 -f 984//984 1049//1049 1008//1008 -f 1008//1008 1049//1049 1050//1050 -f 1008//1008 1050//1050 35//35 -f 35//35 1050//1050 707//707 -f 35//35 707//707 33//33 -f 33//33 707//707 708//708 -f 1051//1051 1052//1052 316//316 -f 316//316 1052//1052 1053//1053 -f 1054//1054 1051//1051 1055//1055 -f 1055//1055 1051//1051 316//316 -f 1055//1055 316//316 435//435 -f 435//435 316//316 298//298 -f 435//435 298//298 433//433 -f 433//433 298//298 432//432 -f 720//720 310//310 32//32 -f 32//32 310//310 312//312 -f 32//32 312//312 728//728 -f 728//728 312//312 316//316 -f 728//728 316//316 1056//1056 -f 1056//1056 316//316 1053//1053 -f 1056//1056 1053//1053 1057//1057 -f 1057//1057 1058//1058 1056//1056 -f 1056//1056 1058//1058 1059//1059 -f 1056//1056 1059//1059 1060//1060 -f 1060//1060 1059//1059 1061//1061 -f 1060//1060 1061//1061 1062//1062 -f 1062//1062 1063//1063 1060//1060 -f 1060//1060 1063//1063 1064//1064 -f 1060//1060 1064//1064 1055//1055 -f 1055//1055 1064//1064 1065//1065 -f 1055//1055 1065//1065 1054//1054 -f 437//437 249//249 435//435 -f 435//435 249//249 86//86 -f 435//435 86//86 1055//1055 -f 1055//1055 86//86 88//88 -f 1055//1055 88//88 1060//1060 -f 1060//1060 88//88 85//85 -f 110//110 112//112 111//111 -f 111//111 112//112 114//114 -f 111//111 114//114 1066//1066 -f 1066//1066 114//114 1067//1067 -f 1068//1068 997//997 1069//1069 -f 1069//1069 997//997 1070//1070 -f 1071//1071 1072//1072 117//117 -f 1072//1072 1073//1073 117//117 -f 117//117 1073//1073 1074//1074 -f 117//117 1074//1074 114//114 -f 114//114 1074//1074 1075//1075 -f 114//114 1075//1075 1067//1067 -f 1067//1067 1076//1076 1066//1066 -f 1066//1066 1076//1076 1077//1077 -f 1066//1066 1077//1077 1078//1078 -f 1068//1068 1071//1071 997//997 -f 997//997 1071//1071 117//117 -f 997//997 117//117 996//996 -f 996//996 117//117 119//119 -f 996//996 119//119 995//995 -f 995//995 119//119 121//121 -f 995//995 121//121 994//994 -f 994//994 121//121 103//103 -f 994//994 103//103 993//993 -f 993//993 103//103 916//916 -f 993//993 916//916 628//628 -f 628//628 916//916 632//632 -f 628//628 632//632 629//629 -f 629//629 632//632 630//630 -f 1078//1078 1070//1070 1066//1066 -f 1066//1066 1070//1070 997//997 -f 1066//1066 997//997 388//388 -f 388//388 997//997 6//6 -f 388//388 6//6 1028//1028 -f 1028//1028 6//6 8//8 -f 1028//1028 8//8 428//428 -f 428//428 8//8 56//56 -f 428//428 56//56 429//429 -f 511//511 896//896 512//512 -f 512//512 896//896 897//897 -f 512//512 897//897 959//959 -f 959//959 897//897 488//488 -f 959//959 488//488 960//960 -f 960//960 488//488 491//491 -f 960//960 491//491 431//431 -f 431//431 491//491 808//808 -f 431//431 808//808 428//428 -f 428//428 808//808 807//807 -f 428//428 807//807 1029//1029 -f 1029//1029 807//807 805//805 -f 1029//1029 805//805 383//383 -f 383//383 805//805 803//803 -f 383//383 803//803 384//384 -f 384//384 803//803 532//532 -f 198//198 200//200 205//205 -f 205//205 200//200 1079//1079 -f 205//205 1079//1079 469//469 -f 469//469 1079//1079 1080//1080 -f 469//469 1080//1080 378//378 -f 378//378 1080//1080 1081//1081 -f 378//378 1081//1081 358//358 -f 358//358 1081//1081 567//567 -f 358//358 567//567 356//356 -f 356//356 567//567 569//569 -f 356//356 569//569 798//798 -f 798//798 569//569 575//575 -f 798//798 575//575 799//799 -f 1043//1043 1082//1082 1044//1044 -f 1044//1044 1082//1082 1083//1083 -f 1044//1044 1083//1083 1045//1045 -f 1045//1045 1083//1083 1084//1084 -f 1045//1045 1084//1084 1046//1046 -f 1046//1046 1084//1084 1085//1085 -f 1046//1046 1085//1085 1047//1047 -f 1047//1047 1085//1085 1086//1086 -f 1047//1047 1086//1086 1048//1048 -f 1048//1048 1086//1086 1087//1087 -f 1048//1048 1087//1087 1049//1049 -f 1049//1049 1087//1087 1088//1088 -f 1049//1049 1088//1088 1050//1050 -f 1050//1050 1088//1088 1089//1089 -f 1050//1050 1089//1089 707//707 -f 707//707 1089//1089 1090//1090 -f 707//707 1090//1090 38//38 -f 38//38 1090//1090 679//679 -f 38//38 679//679 36//36 -f 36//36 679//679 678//678 -f 81//81 83//83 85//85 -f 85//85 83//83 1091//1091 -f 85//85 1091//1091 1060//1060 -f 1060//1060 1091//1091 1092//1092 -f 1060//1060 1092//1092 1056//1056 -f 1056//1056 1092//1092 731//731 -f 1056//1056 731//731 728//728 -f 728//728 731//731 733//733 -f 728//728 733//733 729//729 -f 1093//1093 59//59 1094//1094 -f 1094//1094 59//59 384//384 -f 1094//1094 384//384 54//54 -f 54//54 384//384 532//532 -f 54//54 532//532 53//53 -f 53//53 532//532 534//534 -f 53//53 534//534 539//539 -f 76//76 1095//1095 77//77 -f 77//77 1095//1095 1096//1096 -f 77//77 1096//1096 200//200 -f 200//200 1096//1096 1097//1097 -f 200//200 1097//1097 1079//1079 -f 1079//1079 1097//1097 1098//1098 -f 1079//1079 1098//1098 1080//1080 -f 1080//1080 1098//1098 1099//1099 -f 1080//1080 1099//1099 1081//1081 -f 1081//1081 1099//1099 1100//1100 -f 1081//1081 1100//1100 567//567 -f 567//567 1100//1100 5//5 -f 567//567 5//5 568//568 -f 568//568 5//5 571//571 -f 568//568 571//571 569//569 -f 1082//1082 1020//1020 1083//1083 -f 1083//1083 1020//1020 1021//1021 -f 1083//1083 1021//1021 1084//1084 -f 1084//1084 1021//1021 1022//1022 -f 1084//1084 1022//1022 1085//1085 -f 1085//1085 1022//1022 1023//1023 -f 1085//1085 1023//1023 1086//1086 -f 1086//1086 1023//1023 1024//1024 -f 1086//1086 1024//1024 1087//1087 -f 1087//1087 1024//1024 1025//1025 -f 1087//1087 1025//1025 1088//1088 -f 1088//1088 1025//1025 1026//1026 -f 1088//1088 1026//1026 1089//1089 -f 1089//1089 1026//1026 1027//1027 -f 1089//1089 1027//1027 1090//1090 -f 1090//1090 1027//1027 720//720 -f 1090//1090 720//720 679//679 -f 679//679 720//720 722//722 -f 679//679 722//722 661//661 -f 661//661 722//722 654//654 -f 661//661 654//654 662//662 -f 662//662 654//654 653//653 -f 734//734 736//736 139//139 -f 139//139 736//736 1101//1101 -f 139//139 1101//1101 83//83 -f 83//83 1101//1101 1102//1102 -f 83//83 1102//1102 1091//1091 -f 1091//1091 1102//1102 1103//1103 -f 1091//1091 1103//1103 1092//1092 -f 1092//1092 1103//1103 1104//1104 -f 1092//1092 1104//1104 731//731 -f 731//731 1104//1104 1105//1105 -f 731//731 1105//1105 765//765 -f 1106//1106 1093//1093 1107//1107 -f 1107//1107 1093//1093 1094//1094 -f 1107//1107 1094//1094 1108//1108 -f 1108//1108 1094//1094 54//54 -f 1108//1108 54//54 1109//1109 -f 1109//1109 54//54 52//52 -f 1109//1109 52//52 548//548 -f 548//548 52//52 51//51 -f 548//548 51//51 549//549 -f 2//2 5//5 3//3 -f 3//3 5//5 1100//1100 -f 3//3 1100//1100 1110//1110 -f 1110//1110 1100//1100 1099//1099 -f 1110//1110 1099//1099 1111//1111 -f 1111//1111 1099//1099 1098//1098 -f 1111//1111 1098//1098 1112//1112 -f 1112//1112 1098//1098 1097//1097 -f 1112//1112 1097//1097 1113//1113 -f 1113//1113 1097//1097 1096//1096 -f 1113//1113 1096//1096 1114//1114 -f 1114//1114 1096//1096 1095//1095 -f 1114//1114 1095//1095 1115//1115 -f 191//191 165//165 189//189 -f 189//189 165//165 163//163 -f 189//189 163//163 590//590 -f 590//590 163//163 691//691 -f 590//590 691//691 1116//1116 -f 1116//1116 691//691 693//693 -f 1039//1039 1030//1030 173//173 -f 173//173 1030//1030 1032//1032 -f 173//173 1032//1032 168//168 -f 168//168 1032//1032 1117//1117 -f 168//168 1117//1117 700//700 -f 700//700 1117//1117 1118//1118 -f 700//700 1118//1118 697//697 -f 697//697 1118//1118 1119//1119 -f 444//444 235//235 443//443 -f 443//443 235//235 981//981 -f 443//443 981//981 1005//1005 -f 1005//1005 981//981 1018//1018 -f 1005//1005 1018//1018 1032//1032 -f 1032//1032 1018//1018 717//717 -f 1032//1032 717//717 1117//1117 -f 1117//1117 717//717 711//711 -f 1117//1117 711//711 1118//1118 -f 1118//1118 711//711 775//775 -f 1118//1118 775//775 1119//1119 -f 1119//1119 775//775 778//778 -f 689//689 676//676 690//690 -f 690//690 676//676 661//661 -f 690//690 661//661 41//41 -f 41//41 661//661 659//659 -f 41//41 659//659 39//39 -f 39//39 659//659 664//664 -f 737//737 741//741 736//736 -f 736//736 741//741 1120//1120 -f 736//736 1120//1120 1101//1101 -f 1101//1101 1120//1120 1121//1121 -f 1101//1101 1121//1121 1102//1102 -f 1102//1102 1121//1121 1122//1122 -f 1102//1102 1122//1122 1103//1103 -f 1103//1103 1122//1122 766//766 -f 1103//1103 766//766 1104//1104 -f 1104//1104 766//766 768//768 -f 1104//1104 768//768 1105//1105 -f 390//390 394//394 388//388 -f 388//388 394//394 396//396 -f 388//388 396//396 1066//1066 -f 1066//1066 396//396 1123//1123 -f 1066//1066 1123//1123 111//111 -f 111//111 1123//1123 1124//1124 -f 111//111 1124//1124 597//597 -f 597//597 1124//1124 1125//1125 -f 597//597 1125//1125 744//744 -f 1126//1126 1106//1106 1127//1127 -f 1127//1127 1106//1106 1107//1107 -f 1127//1127 1107//1107 1128//1128 -f 1128//1128 1107//1107 1108//1108 -f 1128//1128 1108//1108 1129//1129 -f 1129//1129 1108//1108 1109//1109 -f 1129//1129 1109//1109 1130//1130 -f 1130//1130 1109//1109 548//548 -f 1130//1130 548//548 1131//1131 -f 1131//1131 548//548 546//546 -f 1131//1131 546//546 1132//1132 -f 1//1 3//3 524//524 -f 524//524 3//3 1110//1110 -f 524//524 1110//1110 1133//1133 -f 1133//1133 1110//1110 1111//1111 -f 1133//1133 1111//1111 1134//1134 -f 1134//1134 1111//1111 1112//1112 -f 1134//1134 1112//1112 1135//1135 -f 1135//1135 1112//1112 1113//1113 -f 1135//1135 1113//1113 1136//1136 -f 1136//1136 1113//1113 1114//1114 -f 1136//1136 1114//1114 1137//1137 -f 1137//1137 1114//1114 1115//1115 -f 1137//1137 1115//1115 1138//1138 -f 667//667 671//671 668//668 -f 668//668 671//671 1139//1139 -f 668//668 1139//1139 778//778 -f 778//778 1139//1139 1140//1140 -f 778//778 1140//1140 1119//1119 -f 1119//1119 1140//1140 1141//1141 -f 1119//1119 1141//1141 697//697 -f 697//697 1141//1141 1142//1142 -f 697//697 1142//1142 693//693 -f 693//693 1142//1142 1143//1143 -f 693//693 1143//1143 1116//1116 -f 1144//1144 1145//1145 656//656 -f 656//656 1145//1145 47//47 -f 656//656 47//47 657//657 -f 657//657 47//47 46//46 -f 1145//1145 1146//1146 47//47 -f 47//47 1146//1146 1147//1147 -f 47//47 1147//1147 1148//1148 -f 1148//1148 1147//1147 1149//1149 -f 1149//1149 1150//1150 1148//1148 -f 1148//1148 1150//1150 1151//1151 -f 1148//1148 1151//1151 1152//1152 -f 1153//1153 1154//1154 753//753 -f 753//753 1154//1154 1155//1155 -f 753//753 1155//1155 656//656 -f 656//656 1155//1155 1156//1156 -f 656//656 1156//1156 1144//1144 -f 1125//1125 1157//1157 744//744 -f 744//744 1157//1157 1158//1158 -f 744//744 1158//1158 741//741 -f 741//741 1158//1158 1159//1159 -f 741//741 1159//1159 1120//1120 -f 1120//1120 1159//1159 1160//1160 -f 1120//1120 1160//1160 1121//1121 -f 1121//1121 1160//1160 1161//1161 -f 1121//1121 1161//1161 1122//1122 -f 1122//1122 1161//1161 1162//1162 -f 1122//1122 1162//1162 766//766 -f 766//766 1162//1162 1148//1148 -f 766//766 1148//1148 753//753 -f 753//753 1148//1148 1152//1152 -f 753//753 1152//1152 1153//1153 -f 1163//1163 1126//1126 1164//1164 -f 1164//1164 1126//1126 1127//1127 -f 1164//1164 1127//1127 1165//1165 -f 1165//1165 1127//1127 1128//1128 -f 1165//1165 1128//1128 1166//1166 -f 1166//1166 1128//1128 1129//1129 -f 1166//1166 1129//1129 1167//1167 -f 1167//1167 1129//1129 1130//1130 -f 1167//1167 1130//1130 1168//1168 -f 1168//1168 1130//1130 1131//1131 -f 1168//1168 1131//1131 561//561 -f 561//561 1131//1131 1132//1132 -f 561//561 1132//1132 560//560 -f 19//19 801//801 20//20 -f 20//20 801//801 1169//1169 -f 20//20 1169//1169 1170//1170 -f 1170//1170 1169//1169 1171//1171 -f 1170//1170 1171//1171 1172//1172 -f 1172//1172 1171//1171 1173//1173 -f 1172//1172 1173//1173 1174//1174 -f 1174//1174 1173//1173 1175//1175 -f 1174//1174 1175//1175 22//22 -f 22//22 1175//1175 1176//1176 -f 22//22 1176//1176 23//23 -f 1138//1138 1177//1177 1137//1137 -f 1137//1137 1177//1177 1178//1178 -f 1137//1137 1178//1178 1136//1136 -f 1136//1136 1178//1178 1179//1179 -f 1136//1136 1179//1179 1135//1135 -f 1135//1135 1179//1179 1180//1180 -f 1135//1135 1180//1180 1134//1134 -f 1134//1134 1180//1180 520//520 -f 1134//1134 520//520 1133//1133 -f 1133//1133 520//520 519//519 -f 1133//1133 519//519 524//524 -f 524//524 519//519 1181//1181 -f 524//524 1181//1181 525//525 -f 1182//1182 1183//1183 1143//1143 -f 1184//1184 1185//1185 1186//1186 -f 1186//1186 1185//1185 1187//1187 -f 1188//1188 1189//1189 1138//1138 -f 1138//1138 1189//1189 1190//1190 -f 1183//1183 1188//1188 1143//1143 -f 1143//1143 1188//1188 1138//1138 -f 1143//1143 1138//1138 1116//1116 -f 1116//1116 1138//1138 1115//1115 -f 1116//1116 1115//1115 590//590 -f 590//590 1115//1115 1095//1095 -f 590//590 1095//1095 588//588 -f 588//588 1095//1095 76//76 -f 1190//1190 1191//1191 1138//1138 -f 1138//1138 1191//1191 1192//1192 -f 1138//1138 1192//1192 1177//1177 -f 1191//1191 1193//1193 1192//1192 -f 1192//1192 1193//1193 1194//1194 -f 1192//1192 1194//1194 1185//1185 -f 1185//1185 1194//1194 1195//1195 -f 1185//1185 1195//1195 1187//1187 -f 43//43 650//650 44//44 -f 44//44 650//650 1196//1196 -f 44//44 1196//1196 673//673 -f 673//673 1196//1196 1197//1197 -f 673//673 1197//1197 671//671 -f 671//671 1197//1197 1198//1198 -f 671//671 1198//1198 1139//1139 -f 1139//1139 1198//1198 1199//1199 -f 1139//1139 1199//1199 1140//1140 -f 1140//1140 1199//1199 1200//1200 -f 1140//1140 1200//1200 1141//1141 -f 1141//1141 1200//1200 1201//1201 -f 1141//1141 1201//1201 1142//1142 -f 1142//1142 1201//1201 1185//1185 -f 1142//1142 1185//1185 1143//1143 -f 1143//1143 1185//1185 1184//1184 -f 1143//1143 1184//1184 1182//1182 -f 1202//1202 1203//1203 1204//1204 -f 1204//1204 1203//1203 1205//1205 -f 1204//1204 1205//1205 1206//1206 -f 1206//1206 1205//1205 1207//1207 -f 1207//1207 1208//1208 1206//1206 -f 1206//1206 1208//1208 1209//1209 -f 1206//1206 1209//1209 1210//1210 -f 1211//1211 1212//1212 1163//1163 -f 1163//1163 1212//1212 1213//1213 -f 1157//1157 1214//1214 1215//1215 -f 397//397 59//59 396//396 -f 396//396 59//59 1093//1093 -f 396//396 1093//1093 1123//1123 -f 1123//1123 1093//1093 1106//1106 -f 1123//1123 1106//1106 1124//1124 -f 1124//1124 1106//1106 1126//1126 -f 1124//1124 1126//1126 1125//1125 -f 1125//1125 1126//1126 1163//1163 -f 1125//1125 1163//1163 1157//1157 -f 1157//1157 1163//1163 1213//1213 -f 1157//1157 1213//1213 1214//1214 -f 45//45 47//47 652//652 -f 652//652 47//47 1148//1148 -f 652//652 1148//1148 1216//1216 -f 1216//1216 1148//1148 1162//1162 -f 1216//1216 1162//1162 1217//1217 -f 1217//1217 1162//1162 1161//1161 -f 1217//1217 1161//1161 1218//1218 -f 1218//1218 1161//1161 1160//1160 -f 1218//1218 1160//1160 1219//1219 -f 1219//1219 1160//1160 1159//1159 -f 1219//1219 1159//1159 1220//1220 -f 1220//1220 1159//1159 1158//1158 -f 1220//1220 1158//1158 1221//1221 -f 1221//1221 1158//1158 1157//1157 -f 1221//1221 1157//1157 1204//1204 -f 1204//1204 1157//1157 1215//1215 -f 1204//1204 1215//1215 1202//1202 -f 563//563 551//551 561//561 -f 561//561 551//551 550//550 -f 561//561 550//550 1168//1168 -f 1168//1168 550//550 1222//1222 -f 1168//1168 1222//1222 1167//1167 -f 1167//1167 1222//1222 1223//1223 -f 1167//1167 1223//1223 1166//1166 -f 1166//1166 1223//1223 1224//1224 -f 1166//1166 1224//1224 1165//1165 -f 1165//1165 1224//1224 1225//1225 -f 1165//1165 1225//1225 1164//1164 -f 1164//1164 1225//1225 1206//1206 -f 1164//1164 1206//1206 1163//1163 -f 1163//1163 1206//1206 1210//1210 -f 1163//1163 1210//1210 1211//1211 -f 538//538 18//18 535//535 -f 535//535 18//18 20//20 -f 535//535 20//20 546//546 -f 546//546 20//20 1170//1170 -f 546//546 1170//1170 1132//1132 -f 1132//1132 1170//1170 1172//1172 -f 1132//1132 1172//1172 560//560 -f 560//560 1172//1172 1174//1174 -f 560//560 1174//1174 556//556 -f 556//556 1174//1174 22//22 -f 556//556 22//22 1226//1226 -f 1226//1226 22//22 21//21 -f 1226//1226 1227//1227 556//556 -f 556//556 1227//1227 1228//1228 -f 556//556 1228//1228 552//552 -f 552//552 1228//1228 1229//1229 -f 552//552 1229//1229 550//550 -f 550//550 1229//1229 1230//1230 -f 550//550 1230//1230 1222//1222 -f 1222//1222 1230//1230 1231//1231 -f 1222//1222 1231//1231 1223//1223 -f 1223//1223 1231//1231 1232//1232 -f 1223//1223 1232//1232 1224//1224 -f 1224//1224 1232//1232 1233//1233 -f 1224//1224 1233//1233 1225//1225 -f 1225//1225 1233//1233 1234//1234 -f 1225//1225 1234//1234 1206//1206 -f 1206//1206 1234//1234 1235//1235 -f 1206//1206 1235//1235 1204//1204 -f 1204//1204 1235//1235 1236//1236 -f 1204//1204 1236//1236 1221//1221 -f 1221//1221 1236//1236 1237//1237 -f 1221//1221 1237//1237 1220//1220 -f 1220//1220 1237//1237 1238//1238 -f 1220//1220 1238//1238 1219//1219 -f 1219//1219 1238//1238 1239//1239 -f 1219//1219 1239//1239 1218//1218 -f 1218//1218 1239//1239 1240//1240 -f 1218//1218 1240//1240 1217//1217 -f 1217//1217 1240//1240 1241//1241 -f 1217//1217 1241//1241 1216//1216 -f 1216//1216 1241//1241 1242//1242 -f 1216//1216 1242//1242 652//652 -f 652//652 1242//1242 1243//1243 -f 652//652 1243//1243 650//650 -f 650//650 1243//1243 1244//1244 -f 650//650 1244//1244 1196//1196 -f 1196//1196 1244//1244 1245//1245 -f 1196//1196 1245//1245 1197//1197 -f 1197//1197 1245//1245 1246//1246 -f 1197//1197 1246//1246 1198//1198 -f 1198//1198 1246//1246 1247//1247 -f 1198//1198 1247//1247 1199//1199 -f 1199//1199 1247//1247 1248//1248 -f 1199//1199 1248//1248 1200//1200 -f 1200//1200 1248//1248 1249//1249 -f 1200//1200 1249//1249 1201//1201 -f 1201//1201 1249//1249 1250//1250 -f 1201//1201 1250//1250 1185//1185 -f 1185//1185 1250//1250 1251//1251 -f 1185//1185 1251//1251 1192//1192 -f 1192//1192 1251//1251 1252//1252 -f 1192//1192 1252//1252 1177//1177 -f 1177//1177 1252//1252 1253//1253 -f 1177//1177 1253//1253 1178//1178 -f 1178//1178 1253//1253 1254//1254 -f 1178//1178 1254//1254 1179//1179 -f 1179//1179 1254//1254 1255//1255 -f 1179//1179 1255//1255 1180//1180 -f 1180//1180 1255//1255 1256//1256 -f 1180//1180 1256//1256 520//520 -f 520//520 1256//1256 1257//1257 -f 520//520 1257//1257 518//518 -f 518//518 1257//1257 1258//1258 -f 518//518 1258//1258 521//521 -f 521//521 1258//1258 1259//1259 -f 1260//1260 1261//1261 1262//1262 -f 1263//1263 1264//1264 1265//1265 -f 1266//1266 1267//1267 1268//1268 -f 1269//1269 1270//1270 1263//1263 -f 1271//1271 1272//1272 1273//1273 -f 1274//1274 1275//1275 1276//1276 -f 1277//1277 1278//1278 1279//1279 -f 1280//1280 1277//1277 1281//1281 -f 1282//1282 1283//1283 1284//1284 -f 1285//1285 1286//1286 1287//1287 -f 1288//1288 1289//1289 1290//1290 -f 1291//1291 1292//1292 1293//1293 -f 1294//1294 1295//1295 1296//1296 -f 1297//1297 1298//1298 1299//1299 -f 1300//1300 1301//1301 1302//1302 -f 1303//1303 1304//1304 1305//1305 -f 1306//1306 1307//1307 1308//1308 -f 1309//1309 1310//1310 1311//1311 -f 1312//1312 1302//1302 1313//1313 -f 1314//1314 1315//1315 1316//1316 -f 1317//1317 1318//1318 1319//1319 -f 1320//1320 1321//1321 1322//1322 -f 1323//1323 1324//1324 1325//1325 -f 1326//1326 1327//1327 1328//1328 -f 1329//1329 1328//1328 1330//1330 -f 1331//1331 1332//1332 1333//1333 -f 1334//1334 1335//1335 1336//1336 -f 1334//1334 1337//1337 1335//1335 -f 1335//1335 1337//1337 1338//1338 -f 1335//1335 1338//1338 1339//1339 -f 1339//1339 1338//1338 1340//1340 -f 1339//1339 1340//1340 1341//1341 -f 1341//1341 1340//1340 1342//1342 -f 1341//1341 1342//1342 1343//1343 -f 1343//1343 1342//1342 1344//1344 -f 1343//1343 1344//1344 1345//1345 -f 1345//1345 1344//1344 1346//1346 -f 1347//1347 1348//1348 1349//1349 -f 1350//1350 1351//1351 1347//1347 -f 1347//1347 1351//1351 1352//1352 -f 1347//1347 1352//1352 1348//1348 -f 1353//1353 1354//1354 1355//1355 -f 1355//1355 1354//1354 1334//1334 -f 1355//1355 1334//1334 1356//1356 -f 1356//1356 1334//1334 1336//1336 -f 1353//1353 1357//1357 1354//1354 -f 1354//1354 1357//1357 1358//1358 -f 1354//1354 1358//1358 1359//1359 -f 1360//1360 1361//1361 1358//1358 -f 1358//1358 1361//1361 1362//1362 -f 1358//1358 1362//1362 1359//1359 -f 1363//1363 1364//1364 1365//1365 -f 1366//1366 1367//1367 1368//1368 -f 1368//1368 1367//1367 1369//1369 -f 1368//1368 1369//1369 1370//1370 -f 1369//1369 1371//1371 1370//1370 -f 1370//1370 1371//1371 1372//1372 -f 1370//1370 1372//1372 1331//1331 -f 1373//1373 1374//1374 1375//1375 -f 1375//1375 1374//1374 1376//1376 -f 1375//1375 1376//1376 1377//1377 -f 1378//1378 1379//1379 1380//1380 -f 1380//1380 1379//1379 1381//1381 -f 1382//1382 1383//1383 1384//1384 -f 1384//1384 1385//1385 1382//1382 -f 1382//1382 1385//1385 1386//1386 -f 1382//1382 1386//1386 1373//1373 -f 1373//1373 1386//1386 1387//1387 -f 1373//1373 1387//1387 1374//1374 -f 1388//1388 1389//1389 1390//1390 -f 1390//1390 1389//1389 1391//1391 -f 1390//1390 1391//1391 1392//1392 -f 1378//1378 1393//1393 1394//1394 -f 1394//1394 1393//1393 1395//1395 -f 1394//1394 1395//1395 1396//1396 -f 1396//1396 1395//1395 1390//1390 -f 1396//1396 1390//1390 1397//1397 -f 1397//1397 1390//1390 1392//1392 -f 1390//1390 1398//1398 1388//1388 -f 1388//1388 1398//1398 1399//1399 -f 1388//1388 1399//1399 1400//1400 -f 1400//1400 1399//1399 1401//1401 -f 1400//1400 1401//1401 1402//1402 -f 1402//1402 1401//1401 1403//1403 -f 1404//1404 1405//1405 1403//1403 -f 1403//1403 1405//1405 1406//1406 -f 1406//1406 1407//1407 1403//1403 -f 1403//1403 1407//1407 1408//1408 -f 1403//1403 1408//1408 1402//1402 -f 1409//1409 1410//1410 1404//1404 -f 1404//1404 1410//1410 1411//1411 -f 1404//1404 1411//1411 1405//1405 -f 1299//1299 1412//1412 1413//1413 -f 1414//1414 1415//1415 1416//1416 -f 1416//1416 1415//1415 1299//1299 -f 1416//1416 1299//1299 1417//1417 -f 1417//1417 1299//1299 1413//1413 -f 1418//1418 1419//1419 1420//1420 -f 1414//1414 1421//1421 1415//1415 -f 1415//1415 1421//1421 1422//1422 -f 1415//1415 1422//1422 1409//1409 -f 1422//1422 1423//1423 1409//1409 -f 1409//1409 1423//1423 1424//1424 -f 1409//1409 1424//1424 1420//1420 -f 1420//1420 1424//1424 1425//1425 -f 1420//1420 1425//1425 1418//1418 -f 1298//1298 1426//1426 1299//1299 -f 1299//1299 1426//1426 1420//1420 -f 1299//1299 1420//1420 1412//1412 -f 1412//1412 1420//1420 1419//1419 -f 1426//1426 1427//1427 1420//1420 -f 1420//1420 1427//1427 1428//1428 -f 1420//1420 1428//1428 1332//1332 -f 1332//1332 1428//1428 1429//1429 -f 1429//1429 1430//1430 1332//1332 -f 1332//1332 1430//1430 1431//1431 -f 1332//1332 1431//1431 1333//1333 -f 1432//1432 1433//1433 1434//1434 -f 1434//1434 1433//1433 1435//1435 -f 1434//1434 1435//1435 1436//1436 -f 1437//1437 1438//1438 1439//1439 -f 1440//1440 1441//1441 1442//1442 -f 1432//1432 1443//1443 1444//1444 -f 1432//1432 1444//1444 1445//1445 -f 1445//1445 1444//1444 1446//1446 -f 1445//1445 1446//1446 1447//1447 -f 1447//1447 1448//1448 1445//1445 -f 1445//1445 1448//1448 1449//1449 -f 1445//1445 1449//1449 1450//1450 -f 1451//1451 1452//1452 1450//1450 -f 1453//1453 1454//1454 1455//1455 -f 1455//1455 1454//1454 1456//1456 -f 1450//1450 1452//1452 1457//1457 -f 1456//1456 1458//1458 1455//1455 -f 1455//1455 1458//1458 1459//1459 -f 1455//1455 1459//1459 1460//1460 -f 1460//1460 1459//1459 1461//1461 -f 1461//1461 1462//1462 1460//1460 -f 1460//1460 1462//1462 1463//1463 -f 1460//1460 1463//1463 1450//1450 -f 1450//1450 1463//1463 1464//1464 -f 1450//1450 1464//1464 1451//1451 -f 1465//1465 1466//1466 1467//1467 -f 1467//1467 1466//1466 1468//1468 -f 1465//1465 1467//1467 1469//1469 -f 1469//1469 1467//1467 1470//1470 -f 1469//1469 1470//1470 1471//1471 -f 1472//1472 1473//1473 1474//1474 -f 1474//1474 1473//1473 1475//1475 -f 1474//1474 1475//1475 1476//1476 -f 1476//1476 1475//1475 1477//1477 -f 1476//1476 1477//1477 1478//1478 -f 1478//1478 1477//1477 1479//1479 -f 1478//1478 1479//1479 1350//1350 -f 1350//1350 1479//1479 1480//1480 -f 1350//1350 1480//1480 1351//1351 -f 1481//1481 1482//1482 1474//1474 -f 1474//1474 1482//1482 1483//1483 -f 1474//1474 1483//1483 1472//1472 -f 1347//1347 1484//1484 1485//1485 -f 1486//1486 1487//1487 1488//1488 -f 1488//1488 1487//1487 1489//1489 -f 1488//1488 1489//1489 1490//1490 -f 1364//1364 1363//1363 1346//1346 -f 1346//1346 1363//1363 1491//1491 -f 1346//1346 1491//1491 1345//1345 -f 1345//1345 1491//1491 1492//1492 -f 1345//1345 1492//1492 1493//1493 -f 1493//1493 1492//1492 1494//1494 -f 1493//1493 1494//1494 1495//1495 -f 1489//1489 1496//1496 1490//1490 -f 1490//1490 1496//1496 1497//1497 -f 1490//1490 1497//1497 1498//1498 -f 1494//1494 1499//1499 1495//1495 -f 1495//1495 1499//1499 1500//1500 -f 1495//1495 1500//1500 1501//1501 -f 1501//1501 1500//1500 1502//1502 -f 1501//1501 1502//1502 1503//1503 -f 1503//1503 1502//1502 1484//1484 -f 1503//1503 1484//1484 1504//1504 -f 1504//1504 1484//1484 1347//1347 -f 1504//1504 1347//1347 1356//1356 -f 1356//1356 1347//1347 1349//1349 -f 1356//1356 1349//1349 1355//1355 -f 1505//1505 1506//1506 1507//1507 -f 1508//1508 1509//1509 1507//1507 -f 1510//1510 1511//1511 1512//1512 -f 1513//1513 1514//1514 1515//1515 -f 1507//1507 1506//1506 1513//1513 -f 1513//1513 1506//1506 1516//1516 -f 1513//1513 1516//1516 1514//1514 -f 1512//1512 1511//1511 1517//1517 -f 1517//1517 1511//1511 1518//1518 -f 1517//1517 1518//1518 1509//1509 -f 1518//1518 1519//1519 1509//1509 -f 1509//1509 1519//1519 1520//1520 -f 1509//1509 1520//1520 1507//1507 -f 1507//1507 1520//1520 1521//1521 -f 1507//1507 1521//1521 1505//1505 -f 1522//1522 1523//1523 1524//1524 -f 1525//1525 1526//1526 1527//1527 -f 1527//1527 1526//1526 1528//1528 -f 1527//1527 1528//1528 1529//1529 -f 1530//1530 1531//1531 1532//1532 -f 1532//1532 1531//1531 1533//1533 -f 1532//1532 1533//1533 1534//1534 -f 1534//1534 1533//1533 1535//1535 -f 1534//1534 1535//1535 1536//1536 -f 1536//1536 1535//1535 1537//1537 -f 1536//1536 1537//1537 1529//1529 -f 1529//1529 1537//1537 1538//1538 -f 1529//1529 1538//1538 1527//1527 -f 1539//1539 1540//1540 1330//1330 -f 1330//1330 1540//1540 1532//1532 -f 1532//1532 1540//1540 1541//1541 -f 1532//1532 1541//1541 1530//1530 -f 1542//1542 1543//1543 1544//1544 -f 1544//1544 1543//1543 1545//1545 -f 1544//1544 1545//1545 1539//1539 -f 1510//1510 1512//1512 1546//1546 -f 1546//1546 1512//1512 1547//1547 -f 1546//1546 1547//1547 1548//1548 -f 1548//1548 1547//1547 1526//1526 -f 1548//1548 1526//1526 1390//1390 -f 1390//1390 1526//1526 1525//1525 -f 1390//1390 1525//1525 1398//1398 -f 1398//1398 1525//1525 1542//1542 -f 1398//1398 1542//1542 1399//1399 -f 1549//1549 1550//1550 1532//1532 -f 1532//1532 1550//1550 1551//1551 -f 1532//1532 1551//1551 1552//1552 -f 1534//1534 1522//1522 1532//1532 -f 1532//1532 1522//1522 1524//1524 -f 1532//1532 1524//1524 1549//1549 -f 1549//1549 1524//1524 1553//1553 -f 1549//1549 1553//1553 1554//1554 -f 1551//1551 1555//1555 1552//1552 -f 1552//1552 1555//1555 1556//1556 -f 1552//1552 1556//1556 1557//1557 -f 1557//1557 1556//1556 1558//1558 -f 1557//1557 1558//1558 1559//1559 -f 1560//1560 1561//1561 1562//1562 -f 1562//1562 1561//1561 1563//1563 -f 1562//1562 1563//1563 1553//1553 -f 1553//1553 1563//1563 1564//1564 -f 1553//1553 1564//1564 1554//1554 -f 1329//1329 1330//1330 1565//1565 -f 1565//1565 1330//1330 1532//1532 -f 1565//1565 1532//1532 1566//1566 -f 1566//1566 1532//1532 1552//1552 -f 1566//1566 1552//1552 1567//1567 -f 1329//1329 1568//1568 1328//1328 -f 1328//1328 1568//1568 1569//1569 -f 1328//1328 1569//1569 1570//1570 -f 1570//1570 1569//1569 1571//1571 -f 1570//1570 1571//1571 1572//1572 -f 1573//1573 1574//1574 1557//1557 -f 1557//1557 1574//1574 1575//1575 -f 1557//1557 1575//1575 1552//1552 -f 1552//1552 1575//1575 1576//1576 -f 1552//1552 1576//1576 1567//1567 -f 1328//1328 1327//1327 1330//1330 -f 1330//1330 1327//1327 1577//1577 -f 1330//1330 1577//1577 1578//1578 -f 1578//1578 1577//1577 1579//1579 -f 1578//1578 1579//1579 1580//1580 -f 1579//1579 1581//1581 1580//1580 -f 1580//1580 1581//1581 1582//1582 -f 1580//1580 1582//1582 1583//1583 -f 1583//1583 1582//1582 1584//1584 -f 1583//1583 1584//1584 1585//1585 -f 1586//1586 1587//1587 1570//1570 -f 1570//1570 1587//1587 1588//1588 -f 1570//1570 1588//1588 1328//1328 -f 1328//1328 1588//1588 1589//1589 -f 1328//1328 1589//1589 1326//1326 -f 1590//1590 1591//1591 1592//1592 -f 1592//1592 1591//1591 1593//1593 -f 1594//1594 1595//1595 1596//1596 -f 1596//1596 1595//1595 1597//1597 -f 1596//1596 1597//1597 1325//1325 -f 1325//1325 1597//1597 1590//1590 -f 1590//1590 1592//1592 1325//1325 -f 1325//1325 1592//1592 1598//1598 -f 1325//1325 1598//1598 1323//1323 -f 1321//1321 1599//1599 1322//1322 -f 1322//1322 1599//1599 1600//1600 -f 1322//1322 1600//1600 1601//1601 -f 1602//1602 1603//1603 1604//1604 -f 1602//1602 1605//1605 1603//1603 -f 1603//1603 1605//1605 1606//1606 -f 1603//1603 1606//1606 1607//1607 -f 1607//1607 1606//1606 1608//1608 -f 1607//1607 1608//1608 1609//1609 -f 1609//1609 1608//1608 1610//1610 -f 1609//1609 1610//1610 1611//1611 -f 1611//1611 1610//1610 1612//1612 -f 1611//1611 1612//1612 1613//1613 -f 1613//1613 1612//1612 1614//1614 -f 1615//1615 1616//1616 1614//1614 -f 1614//1614 1616//1616 1617//1617 -f 1614//1614 1617//1617 1613//1613 -f 1618//1618 1318//1318 1619//1619 -f 1619//1619 1318//1318 1620//1620 -f 1618//1618 1621//1621 1318//1318 -f 1318//1318 1621//1621 1622//1622 -f 1318//1318 1622//1622 1319//1319 -f 1319//1319 1622//1622 1623//1623 -f 1624//1624 1625//1625 1626//1626 -f 1626//1626 1625//1625 1627//1627 -f 1626//1626 1627//1627 1628//1628 -f 1629//1629 1624//1624 1630//1630 -f 1630//1630 1624//1624 1626//1626 -f 1630//1630 1626//1626 1271//1271 -f 1271//1271 1626//1626 1628//1628 -f 1271//1271 1628//1628 1272//1272 -f 1631//1631 1632//1632 1633//1633 -f 1633//1633 1632//1632 1634//1634 -f 1633//1633 1634//1634 1635//1635 -f 1636//1636 1637//1637 1638//1638 -f 1638//1638 1637//1637 1639//1639 -f 1638//1638 1639//1639 1640//1640 -f 1640//1640 1639//1639 1634//1634 -f 1640//1640 1634//1634 1641//1641 -f 1641//1641 1634//1634 1632//1632 -f 1642//1642 1643//1643 1316//1316 -f 1316//1316 1643//1643 1644//1644 -f 1316//1316 1644//1644 1314//1314 -f 1645//1645 1646//1646 1647//1647 -f 1647//1647 1646//1646 1648//1648 -f 1647//1647 1648//1648 1649//1649 -f 1649//1649 1648//1648 1650//1650 -f 1651//1651 1649//1649 1652//1652 -f 1652//1652 1649//1649 1650//1650 -f 1652//1652 1650//1650 1653//1653 -f 1653//1653 1650//1650 1654//1654 -f 1653//1653 1654//1654 1313//1313 -f 1313//1313 1654//1654 1655//1655 -f 1313//1313 1655//1655 1312//1312 -f 1656//1656 1657//1657 1658//1658 -f 1659//1659 1660//1660 1657//1657 -f 1661//1661 1662//1662 1663//1663 -f 1663//1663 1662//1662 1664//1664 -f 1663//1663 1664//1664 1660//1660 -f 1665//1665 1661//1661 1666//1666 -f 1667//1667 1665//1665 1668//1668 -f 1668//1668 1665//1665 1666//1666 -f 1668//1668 1666//1666 1669//1669 -f 1669//1669 1666//1666 1670//1670 -f 1671//1671 1672//1672 1673//1673 -f 1673//1673 1672//1672 1674//1674 -f 1675//1675 1676//1676 1677//1677 -f 1677//1677 1676//1676 1678//1678 -f 1679//1679 1680//1680 1681//1681 -f 1681//1681 1680//1680 1682//1682 -f 1676//1676 1683//1683 1678//1678 -f 1678//1678 1683//1683 1684//1684 -f 1678//1678 1684//1684 1685//1685 -f 1685//1685 1684//1684 1682//1682 -f 1685//1685 1682//1682 1686//1686 -f 1686//1686 1682//1682 1680//1680 -f 1687//1687 1688//1688 1689//1689 -f 1689//1689 1688//1688 1690//1690 -f 1691//1691 1692//1692 1693//1693 -f 1692//1692 1694//1694 1693//1693 -f 1693//1693 1694//1694 1695//1695 -f 1693//1693 1695//1695 1696//1696 -f 1697//1697 1698//1698 1699//1699 -f 1260//1260 1700//1700 1701//1701 -f 1701//1701 1700//1700 1702//1702 -f 1701//1701 1702//1702 1703//1703 -f 1701//1701 1704//1704 1260//1260 -f 1260//1260 1704//1704 1705//1705 -f 1260//1260 1705//1705 1261//1261 -f 1261//1261 1705//1705 1706//1706 -f 1261//1261 1706//1706 1707//1707 -f 1702//1702 1708//1708 1703//1703 -f 1703//1703 1708//1708 1709//1709 -f 1703//1703 1709//1709 1710//1710 -f 1710//1710 1709//1709 1711//1711 -f 1710//1710 1711//1711 1712//1712 -f 1712//1712 1711//1711 1697//1697 -f 1712//1712 1697//1697 1713//1713 -f 1713//1713 1697//1697 1699//1699 -f 1713//1713 1699//1699 1714//1714 -f 1715//1715 1263//1263 1716//1716 -f 1716//1716 1263//1263 1270//1270 -f 1716//1716 1270//1270 1717//1717 -f 1718//1718 1719//1719 1270//1270 -f 1270//1270 1719//1719 1720//1720 -f 1270//1270 1720//1720 1717//1717 -f 1717//1717 1720//1720 1721//1721 -f 1717//1717 1721//1721 1722//1722 -f 1722//1722 1721//1721 1723//1723 -f 1722//1722 1723//1723 1724//1724 -f 1724//1724 1723//1723 1725//1725 -f 1725//1725 1723//1723 1726//1726 -f 1726//1726 1723//1723 1727//1727 -f 1726//1726 1727//1727 1728//1728 -f 1715//1715 1729//1729 1263//1263 -f 1263//1263 1729//1729 1730//1730 -f 1263//1263 1730//1730 1264//1264 -f 1727//1727 1731//1731 1728//1728 -f 1728//1728 1731//1731 1732//1732 -f 1728//1728 1732//1732 1733//1733 -f 1733//1733 1732//1732 1264//1264 -f 1733//1733 1264//1264 1734//1734 -f 1734//1734 1264//1264 1730//1730 -f 1735//1735 1736//1736 1737//1737 -f 1737//1737 1736//1736 1738//1738 -f 1739//1739 1740//1740 1741//1741 -f 1741//1741 1740//1740 1742//1742 -f 1741//1741 1742//1742 1743//1743 -f 1744//1744 1745//1745 1746//1746 -f 1747//1747 1748//1748 1749//1749 -f 1749//1749 1748//1748 1750//1750 -f 1749//1749 1750//1750 1751//1751 -f 1751//1751 1752//1752 1753//1753 -f 1754//1754 1755//1755 1756//1756 -f 1756//1756 1755//1755 1757//1757 -f 1756//1756 1757//1757 1758//1758 -f 1758//1758 1757//1757 1747//1747 -f 1758//1758 1747//1747 1759//1759 -f 1759//1759 1747//1747 1749//1749 -f 1759//1759 1749//1749 1739//1739 -f 1744//1744 1746//1746 1760//1760 -f 1752//1752 1761//1761 1753//1753 -f 1753//1753 1761//1761 1762//1762 -f 1753//1753 1762//1762 1746//1746 -f 1746//1746 1762//1762 1763//1763 -f 1746//1746 1763//1763 1760//1760 -f 1760//1760 1763//1763 1764//1764 -f 1760//1760 1764//1764 1754//1754 -f 1754//1754 1764//1764 1765//1765 -f 1754//1754 1765//1765 1755//1755 -f 1766//1766 1767//1767 1768//1768 -f 1769//1769 1770//1770 1771//1771 -f 1771//1771 1770//1770 1766//1766 -f 1772//1772 1773//1773 1774//1774 -f 1775//1775 1776//1776 1777//1777 -f 1777//1777 1776//1776 1778//1778 -f 1777//1777 1778//1778 1779//1779 -f 1779//1779 1778//1778 1774//1774 -f 1779//1779 1774//1774 1780//1780 -f 1780//1780 1774//1774 1773//1773 -f 1767//1767 1781//1781 1768//1768 -f 1768//1768 1781//1781 1782//1782 -f 1768//1768 1782//1782 1783//1783 -f 1784//1784 1783//1783 1775//1775 -f 1775//1775 1783//1783 1785//1785 -f 1775//1775 1785//1785 1776//1776 -f 1768//1768 1786//1786 1787//1787 -f 1787//1787 1786//1786 1788//1788 -f 1787//1787 1788//1788 1772//1772 -f 1784//1784 1789//1789 1783//1783 -f 1783//1783 1789//1789 1790//1790 -f 1783//1783 1790//1790 1768//1768 -f 1768//1768 1790//1790 1791//1791 -f 1768//1768 1791//1791 1786//1786 -f 1778//1778 1792//1792 1793//1793 -f 1793//1793 1792//1792 1794//1794 -f 1793//1793 1794//1794 1795//1795 -f 1795//1795 1794//1794 1769//1769 -f 1681//1681 1796//1796 1679//1679 -f 1679//1679 1796//1796 1797//1797 -f 1679//1679 1797//1797 1798//1798 -f 1735//1735 1799//1799 1736//1736 -f 1736//1736 1799//1799 1800//1800 -f 1736//1736 1800//1800 1801//1801 -f 1802//1802 1803//1803 1804//1804 -f 1805//1805 1806//1806 1807//1807 -f 1807//1807 1806//1806 1808//1808 -f 1801//1801 1809//1809 1810//1810 -f 1810//1810 1809//1809 1802//1802 -f 1811//1811 1437//1437 1812//1812 -f 1812//1812 1437//1437 1804//1804 -f 1812//1812 1804//1804 1813//1813 -f 1813//1813 1804//1804 1803//1803 -f 1814//1814 1815//1815 1816//1816 -f 1604//1604 1320//1320 1602//1602 -f 1602//1602 1320//1320 1322//1322 -f 1602//1602 1322//1322 1817//1817 -f 1817//1817 1322//1322 1818//1818 -f 1817//1817 1819//1819 1602//1602 -f 1602//1602 1819//1819 1820//1820 -f 1602//1602 1820//1820 1605//1605 -f 1605//1605 1820//1820 1821//1821 -f 1821//1821 1822//1822 1605//1605 -f 1605//1605 1822//1822 1823//1823 -f 1605//1605 1823//1823 1824//1824 -f 1824//1824 1823//1823 1825//1825 -f 1825//1825 1826//1826 1824//1824 -f 1824//1824 1826//1826 1827//1827 -f 1824//1824 1827//1827 1815//1815 -f 1815//1815 1827//1827 1828//1828 -f 1815//1815 1828//1828 1816//1816 -f 1591//1591 1829//1829 1593//1593 -f 1593//1593 1829//1829 1830//1830 -f 1593//1593 1830//1830 1831//1831 -f 1830//1830 1832//1832 1831//1831 -f 1831//1831 1832//1832 1833//1833 -f 1831//1831 1833//1833 1834//1834 -f 1834//1834 1833//1833 1835//1835 -f 1834//1834 1835//1835 1836//1836 -f 1836//1836 1835//1835 1837//1837 -f 1836//1836 1837//1837 1838//1838 -f 1838//1838 1837//1837 1839//1839 -f 1838//1838 1839//1839 1594//1594 -f 1594//1594 1839//1839 1840//1840 -f 1594//1594 1840//1840 1595//1595 -f 1841//1841 1842//1842 1843//1843 -f 1843//1843 1842//1842 1844//1844 -f 1843//1843 1844//1844 1845//1845 -f 1845//1845 1844//1844 1846//1846 -f 1303//1303 1305//1305 1847//1847 -f 1304//1304 1848//1848 1849//1849 -f 1849//1849 1848//1848 1850//1850 -f 1851//1851 1852//1852 1630//1630 -f 1630//1630 1852//1852 1853//1853 -f 1630//1630 1853//1853 1305//1305 -f 1305//1305 1853//1853 1854//1854 -f 1305//1305 1854//1854 1847//1847 -f 1855//1855 1856//1856 1857//1857 -f 1857//1857 1856//1856 1858//1858 -f 1857//1857 1858//1858 1851//1851 -f 1300//1300 1859//1859 1860//1860 -f 1860//1860 1859//1859 1861//1861 -f 1862//1862 1863//1863 1645//1645 -f 1645//1645 1863//1863 1864//1864 -f 1645//1645 1864//1864 1646//1646 -f 1448//1448 1865//1865 1449//1449 -f 1449//1449 1865//1865 1866//1866 -f 1449//1449 1866//1866 1867//1867 -f 1867//1867 1866//1866 1868//1868 -f 1869//1869 1870//1870 1871//1871 -f 1431//1431 1872//1872 1333//1333 -f 1333//1333 1872//1872 1873//1873 -f 1333//1333 1873//1873 1874//1874 -f 1874//1874 1873//1873 1875//1875 -f 1874//1874 1875//1875 1876//1876 -f 1876//1876 1297//1297 1877//1877 -f 1878//1878 1879//1879 1880//1880 -f 1878//1878 1880//1880 1881//1881 -f 1879//1879 1878//1878 1882//1882 -f 1882//1882 1878//1878 1883//1883 -f 1882//1882 1883//1883 1884//1884 -f 1884//1884 1883//1883 1885//1885 -f 1884//1884 1885//1885 1886//1886 -f 1886//1886 1885//1885 1887//1887 -f 1886//1886 1887//1887 1888//1888 -f 1889//1889 1890//1890 1891//1891 -f 1891//1891 1890//1890 1892//1892 -f 1891//1891 1892//1892 1893//1893 -f 1893//1893 1892//1892 1881//1881 -f 1893//1893 1881//1881 1894//1894 -f 1894//1894 1881//1881 1880//1880 -f 1889//1889 1895//1895 1890//1890 -f 1890//1890 1895//1895 1896//1896 -f 1890//1890 1896//1896 1897//1897 -f 1898//1898 1899//1899 1900//1900 -f 1898//1898 1900//1900 1901//1901 -f 1900//1900 1902//1902 1901//1901 -f 1901//1901 1902//1902 1903//1903 -f 1901//1901 1903//1903 1904//1904 -f 1899//1899 1898//1898 1905//1905 -f 1905//1905 1898//1898 1906//1906 -f 1905//1905 1906//1906 1295//1295 -f 1907//1907 1908//1908 1904//1904 -f 1904//1904 1908//1908 1909//1909 -f 1904//1904 1909//1909 1901//1901 -f 1907//1907 1910//1910 1908//1908 -f 1908//1908 1910//1910 1911//1911 -f 1908//1908 1911//1911 1912//1912 -f 1912//1912 1911//1911 1913//1913 -f 1912//1912 1913//1913 1914//1914 -f 1914//1914 1913//1913 1294//1294 -f 1915//1915 1890//1890 1916//1916 -f 1917//1917 1897//1897 1918//1918 -f 1918//1918 1897//1897 1919//1919 -f 1918//1918 1919//1919 1920//1920 -f 1917//1917 1921//1921 1897//1897 -f 1897//1897 1921//1921 1922//1922 -f 1897//1897 1922//1922 1890//1890 -f 1890//1890 1922//1922 1923//1923 -f 1890//1890 1923//1923 1916//1916 -f 1916//1916 1924//1924 1915//1915 -f 1915//1915 1924//1924 1925//1925 -f 1915//1915 1925//1925 1926//1926 -f 1926//1926 1925//1925 1927//1927 -f 1920//1920 1919//1919 1928//1928 -f 1928//1928 1919//1919 1929//1929 -f 1928//1928 1929//1929 1930//1930 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1935//1935 -f 1936//1936 1937//1937 1938//1938 -f 1939//1939 1940//1940 1941//1941 -f 1941//1941 1940//1940 1942//1942 -f 1941//1941 1942//1942 1943//1943 -f 1943//1943 1942//1942 1944//1944 -f 1943//1943 1944//1944 1937//1937 -f 1937//1937 1944//1944 1945//1945 -f 1937//1937 1945//1945 1938//1938 -f 1939//1939 1946//1946 1947//1947 -f 1947//1947 1946//1946 1948//1948 -f 1947//1947 1948//1948 1949//1949 -f 1949//1949 1948//1948 1950//1950 -f 1951//1951 1952//1952 1953//1953 -f 1953//1953 1952//1952 1954//1954 -f 1953//1953 1955//1955 1951//1951 -f 1951//1951 1955//1955 1956//1956 -f 1951//1951 1956//1956 1957//1957 -f 1957//1957 1956//1956 1958//1958 -f 1957//1957 1958//1958 1935//1935 -f 1935//1935 1958//1958 1959//1959 -f 1933//1933 1960//1960 1961//1961 -f 1961//1961 1960//1960 1962//1962 -f 1961//1961 1962//1962 1952//1952 -f 1952//1952 1962//1962 1963//1963 -f 1952//1952 1963//1963 1954//1954 -f 1959//1959 1964//1964 1935//1935 -f 1935//1935 1964//1964 1965//1965 -f 1935//1935 1965//1965 1933//1933 -f 1933//1933 1965//1965 1966//1966 -f 1933//1933 1966//1966 1960//1960 -f 1967//1967 1968//1968 1969//1969 -f 1969//1969 1970//1970 1967//1967 -f 1967//1967 1970//1970 1971//1971 -f 1967//1967 1971//1971 1972//1972 -f 1972//1972 1971//1971 1973//1973 -f 1972//1972 1973//1973 1974//1974 -f 1974//1974 1973//1973 1975//1975 -f 1974//1974 1975//1975 1976//1976 -f 1977//1977 1978//1978 1948//1948 -f 1948//1948 1978//1978 1979//1979 -f 1948//1948 1979//1979 1980//1980 -f 1980//1980 1979//1979 1981//1981 -f 1980//1980 1981//1981 1982//1982 -f 1982//1982 1981//1981 1983//1983 -f 1982//1982 1983//1983 1968//1968 -f 1968//1968 1983//1983 1984//1984 -f 1968//1968 1984//1984 1969//1969 -f 1985//1985 1986//1986 1987//1987 -f 1985//1985 1987//1987 1988//1988 -f 1987//1987 1989//1989 1988//1988 -f 1988//1988 1989//1989 1990//1990 -f 1988//1988 1990//1990 1991//1991 -f 1991//1991 1992//1992 1993//1993 -f 1993//1993 1992//1992 1994//1994 -f 1993//1993 1994//1994 1995//1995 -f 1994//1994 1996//1996 1995//1995 -f 1995//1995 1996//1996 1997//1997 -f 1995//1995 1997//1997 1460//1460 -f 1998//1998 1455//1455 1999//1999 -f 1999//1999 1455//1455 1460//1460 -f 1999//1999 1460//1460 2000//2000 -f 2000//2000 1460//1460 1997//1997 -f 2001//2001 2002//2002 2003//2003 -f 2003//2003 2002//2002 1967//1967 -f 2003//2003 1967//1967 2004//2004 -f 2001//2001 2005//2005 2002//2002 -f 2002//2002 2005//2005 2006//2006 -f 2002//2002 2006//2006 1266//1266 -f 2006//2006 2007//2007 1266//1266 -f 1266//1266 2007//2007 2008//2008 -f 1266//1266 2008//2008 1267//1267 -f 2008//2008 2009//2009 1267//1267 -f 1267//1267 2009//2009 2010//2010 -f 1267//1267 2010//2010 2011//2011 -f 2011//2011 2010//2010 2012//2012 -f 2004//2004 1967//1967 2013//2013 -f 2013//2013 1967//1967 1972//1972 -f 2013//2013 1972//1972 2014//2014 -f 2015//2015 2016//2016 2017//2017 -f 2017//2017 2016//2016 2018//2018 -f 2019//2019 2020//2020 2021//2021 -f 2021//2021 2020//2020 2022//2022 -f 2020//2020 2023//2023 2022//2022 -f 2022//2022 2023//2023 2024//2024 -f 2022//2022 2024//2024 2025//2025 -f 2026//2026 2027//2027 2028//2028 -f 2028//2028 2027//2027 2029//2029 -f 2028//2028 2029//2029 2015//2015 -f 2015//2015 2029//2029 2030//2030 -f 2015//2015 2030//2030 2016//2016 -f 2024//2024 2031//2031 2025//2025 -f 2025//2025 2031//2031 2032//2032 -f 2025//2025 2032//2032 2026//2026 -f 1877//1877 2033//2033 2034//2034 -f 2035//2035 2036//2036 2037//2037 -f 1877//1877 2034//2034 2035//2035 -f 2035//2035 2034//2034 2038//2038 -f 2035//2035 2038//2038 2036//2036 -f 2037//2037 2039//2039 2040//2040 -f 2040//2040 2039//2039 2041//2041 -f 2040//2040 2041//2041 2042//2042 -f 1297//1297 1299//1299 1877//1877 -f 1877//1877 1299//1299 2043//2043 -f 1877//1877 2043//2043 2033//2033 -f 2041//2041 2044//2044 2042//2042 -f 2042//2042 2044//2044 2045//2045 -f 2042//2042 2045//2045 1415//1415 -f 1415//1415 2045//2045 2046//2046 -f 1415//1415 2046//2046 1299//1299 -f 1299//1299 2046//2046 2047//2047 -f 1299//1299 2047//2047 2043//2043 -f 1292//1292 2048//2048 1941//1941 -f 1939//1939 1941//1941 1946//1946 -f 1946//1946 1941//1941 2048//2048 -f 1946//1946 2048//2048 2049//2049 -f 1291//1291 1293//1293 2050//2050 -f 2051//2051 2052//2052 2053//2053 -f 2053//2053 2052//2052 2054//2054 -f 2053//2053 2054//2054 2050//2050 -f 2055//2055 2056//2056 2015//2015 -f 2056//2056 2057//2057 2015//2015 -f 2015//2015 2057//2057 2058//2058 -f 2015//2015 2058//2058 2028//2028 -f 2028//2028 2058//2058 2059//2059 -f 2028//2028 2059//2059 2051//2051 -f 2051//2051 2059//2059 2060//2060 -f 2051//2051 2060//2060 2052//2052 -f 2056//2056 2061//2061 2057//2057 -f 2057//2057 2061//2061 2062//2062 -f 2057//2057 2062//2062 2063//2063 -f 2063//2063 2062//2062 2064//2064 -f 2063//2063 2064//2064 2049//2049 -f 2049//2049 2064//2064 2065//2065 -f 2049//2049 2065//2065 1946//1946 -f 1946//1946 2065//2065 2066//2066 -f 1946//1946 2066//2066 2067//2067 -f 2068//2068 2069//2069 2017//2017 -f 2017//2017 2069//2069 2070//2070 -f 2017//2017 2070//2070 2015//2015 -f 2015//2015 2070//2070 2071//2071 -f 2015//2015 2071//2071 2055//2055 -f 1951//1951 2072//2072 2073//2073 -f 2073//2073 2074//2074 2075//2075 -f 2075//2075 2074//2074 2076//2076 -f 2075//2075 2076//2076 2077//2077 -f 2072//2072 1951//1951 2078//2078 -f 2078//2078 1951//1951 1957//1957 -f 2078//2078 1957//1957 2079//2079 -f 2076//2076 2080//2080 2077//2077 -f 2077//2077 2080//2080 2081//2081 -f 2077//2077 2081//2081 2002//2002 -f 2002//2002 2081//2081 2082//2082 -f 2002//2002 2082//2082 1967//1967 -f 1967//1967 2082//2082 2083//2083 -f 1967//1967 2083//2083 1968//1968 -f 1635//1635 2084//2084 1633//1633 -f 1633//1633 2084//2084 2085//2085 -f 1633//1633 2085//2085 2086//2086 -f 1285//1285 1937//1937 2087//2087 -f 2087//2087 1937//1937 1936//1936 -f 2087//2087 1936//1936 2088//2088 -f 2088//2088 1936//1936 2089//2089 -f 2088//2088 2089//2089 2090//2090 -f 2090//2090 2089//2089 2091//2091 -f 2092//2092 2093//2093 2094//2094 -f 2094//2094 2093//2093 2095//2095 -f 1629//1629 1630//1630 2096//2096 -f 2096//2096 1630//1630 1305//1305 -f 2096//2096 1305//1305 2097//2097 -f 2098//2098 2099//2099 2086//2086 -f 2100//2100 2101//2101 1275//1275 -f 1275//1275 2101//2101 2102//2102 -f 1275//1275 2102//2102 1290//1290 -f 1290//1290 2102//2102 2103//2103 -f 1290//1290 2103//2103 2104//2104 -f 2104//2104 2105//2105 1290//1290 -f 1290//1290 2105//2105 2106//2106 -f 1290//1290 2106//2106 1288//1288 -f 1288//1288 2106//2106 2107//2107 -f 2105//2105 2108//2108 2106//2106 -f 2106//2106 2108//2108 2109//2109 -f 2106//2106 2109//2109 2110//2110 -f 2111//2111 2107//2107 2112//2112 -f 2112//2112 2107//2107 2106//2106 -f 2112//2112 2106//2106 1274//1274 -f 1274//1274 2106//2106 2110//2110 -f 2110//2110 2113//2113 1274//1274 -f 1274//1274 2113//2113 2114//2114 -f 1274//1274 2114//2114 1275//1275 -f 1275//1275 2114//2114 2115//2115 -f 1275//1275 2115//2115 2100//2100 -f 1938//1938 1931//1931 1936//1936 -f 1936//1936 1931//1931 1933//1933 -f 1936//1936 1933//1933 2089//2089 -f 2089//2089 1933//1933 1961//1961 -f 2089//2089 1961//1961 2091//2091 -f 2091//2091 1961//1961 1952//1952 -f 2116//2116 2117//2117 2118//2118 -f 2117//2117 2119//2119 2118//2118 -f 2118//2118 2119//2119 2120//2120 -f 2118//2118 2120//2120 2093//2093 -f 2093//2093 2120//2120 2121//2121 -f 2122//2122 2095//2095 2123//2123 -f 2123//2123 2095//2095 2093//2093 -f 2123//2123 2093//2093 2124//2124 -f 2124//2124 2093//2093 2121//2121 -f 2122//2122 2125//2125 2095//2095 -f 2095//2095 2125//2125 2126//2126 -f 2095//2095 2126//2126 2127//2127 -f 2127//2127 2126//2126 2128//2128 -f 2127//2127 2128//2128 2129//2129 -f 2130//2130 2111//2111 2131//2131 -f 2131//2131 2111//2111 2112//2112 -f 2131//2131 2112//2112 2132//2132 -f 2132//2132 2112//2112 1274//1274 -f 2132//2132 1274//1274 2133//2133 -f 2133//2133 1274//1274 1276//1276 -f 2133//2133 1276//1276 1867//1867 -f 1991//1991 1993//1993 1988//1988 -f 1988//1988 1993//1993 2134//2134 -f 1988//1988 2134//2134 2135//2135 -f 2135//2135 2134//2134 2136//2136 -f 2135//2135 2136//2136 2137//2137 -f 2137//2137 2136//2136 2138//2138 -f 2137//2137 2138//2138 2139//2139 -f 2073//2073 2075//2075 1951//1951 -f 1951//1951 2075//2075 2140//2140 -f 1951//1951 2140//2140 1952//1952 -f 1952//1952 2140//2140 2141//2141 -f 1952//1952 2141//2141 2091//2091 -f 2091//2091 2141//2141 2142//2142 -f 2091//2091 2142//2142 2090//2090 -f 2143//2143 2144//2144 2145//2145 -f 2146//2146 2147//2147 1293//1293 -f 1285//1285 1287//1287 1937//1937 -f 1937//1937 1287//1287 2143//2143 -f 1937//1937 2143//2143 1943//1943 -f 1943//1943 2143//2143 2145//2145 -f 1943//1943 2145//2145 2148//2148 -f 2147//2147 2149//2149 1293//1293 -f 1293//1293 2149//2149 2150//2150 -f 1293//1293 2150//2150 2143//2143 -f 2143//2143 2150//2150 2151//2151 -f 2143//2143 2151//2151 2144//2144 -f 1292//1292 1941//1941 1293//1293 -f 1293//1293 1941//1941 2152//2152 -f 1293//1293 2152//2152 2146//2146 -f 2148//2148 2153//2153 1943//1943 -f 1943//1943 2153//2153 2154//2154 -f 1943//1943 2154//2154 1941//1941 -f 1941//1941 2154//2154 2155//2155 -f 1941//1941 2155//2155 2152//2152 -f 2050//2050 1293//1293 2053//2053 -f 2053//2053 1293//1293 2143//2143 -f 2053//2053 2143//2143 2156//2156 -f 2156//2156 2143//2143 1287//1287 -f 2156//2156 1287//1287 2157//2157 -f 2157//2157 1287//1287 1286//1286 -f 2157//2157 1286//1286 2158//2158 -f 2037//2037 2040//2040 2035//2035 -f 2035//2035 2040//2040 2159//2159 -f 2035//2035 2159//2159 2127//2127 -f 2127//2127 2159//2159 2160//2160 -f 2127//2127 2160//2160 2095//2095 -f 2095//2095 2160//2160 2161//2161 -f 2095//2095 2161//2161 2094//2094 -f 1851//1851 1630//1630 1857//1857 -f 1857//1857 1630//1630 1271//1271 -f 1857//1857 1271//1271 2162//2162 -f 2162//2162 1271//1271 1273//1273 -f 2162//2162 1273//1273 2163//2163 -f 2164//2164 1860//1860 1862//1862 -f 1862//1862 1860//1860 1861//1861 -f 1862//1862 1861//1861 1863//1863 -f 2165//2165 2166//2166 2167//2167 -f 2167//2167 2166//2166 2168//2168 -f 2167//2167 2168//2168 2169//2169 -f 2169//2169 2168//2168 2170//2170 -f 2169//2169 2170//2170 2171//2171 -f 2171//2171 2170//2170 2172//2172 -f 2171//2171 2172//2172 2173//2173 -f 2173//2173 2172//2172 1871//1871 -f 2173//2173 1871//1871 1440//1440 -f 1440//1440 1871//1871 1870//1870 -f 1440//1440 1870//1870 1441//1441 -f 2166//2166 2130//2130 2168//2168 -f 2168//2168 2130//2130 2131//2131 -f 2168//2168 2131//2131 2170//2170 -f 2170//2170 2131//2131 2132//2132 -f 2170//2170 2132//2132 2172//2172 -f 2172//2172 2132//2132 2133//2133 -f 2172//2172 2133//2133 1871//1871 -f 1871//1871 2133//2133 1867//1867 -f 1871//1871 1867//1867 1869//1869 -f 1869//1869 1867//1867 1868//1868 -f 2174//2174 1985//1985 2175//2175 -f 2175//2175 1985//1985 1988//1988 -f 2175//2175 1988//1988 2176//2176 -f 2176//2176 1988//1988 2135//2135 -f 2176//2176 2135//2135 2177//2177 -f 2177//2177 2135//2135 2137//2137 -f 2177//2177 2137//2137 2178//2178 -f 2178//2178 2137//2137 2139//2139 -f 2178//2178 2139//2139 2179//2179 -f 1934//1934 1950//1950 1935//1935 -f 1935//1935 1950//1950 1948//1948 -f 1935//1935 1948//1948 1957//1957 -f 1957//1957 1948//1948 1980//1980 -f 1957//1957 1980//1980 2079//2079 -f 2079//2079 1980//1980 1982//1982 -f 1876//1876 1877//1877 1874//1874 -f 1874//1874 1877//1877 2035//2035 -f 1874//1874 2035//2035 2180//2180 -f 2180//2180 2035//2035 2127//2127 -f 2180//2180 2127//2127 2118//2118 -f 2118//2118 2127//2127 2129//2129 -f 2118//2118 2129//2129 2116//2116 -f 2181//2181 2182//2182 1843//1843 -f 1843//1843 2182//2182 2183//2183 -f 1843//1843 2183//2183 1841//1841 -f 1850//1850 1855//1855 1849//1849 -f 1849//1849 1855//1855 1857//1857 -f 1849//1849 1857//1857 2184//2184 -f 2184//2184 1857//1857 2162//2162 -f 2184//2184 2162//2162 2185//2185 -f 2185//2185 2162//2162 2163//2163 -f 2185//2185 2163//2163 2186//2186 -f 1300//1300 1860//1860 1301//1301 -f 1301//1301 1860//1860 2187//2187 -f 1301//1301 2187//2187 1302//1302 -f 2099//2099 2098//2098 2188//2188 -f 2188//2188 2098//2098 2189//2189 -f 2188//2188 2189//2189 2190//2190 -f 2190//2190 2189//2189 2191//2191 -f 2190//2190 2191//2191 2192//2192 -f 2192//2192 2191//2191 1434//1434 -f 2192//2192 1434//1434 1437//1437 -f 1437//1437 1434//1434 1436//1436 -f 1437//1437 1436//1436 1438//1438 -f 2085//2085 2165//2165 2086//2086 -f 2086//2086 2165//2165 2167//2167 -f 2086//2086 2167//2167 2098//2098 -f 2098//2098 2167//2167 2169//2169 -f 2098//2098 2169//2169 2189//2189 -f 2189//2189 2169//2169 2171//2171 -f 2189//2189 2171//2171 2191//2191 -f 2191//2191 2171//2171 2173//2173 -f 2191//2191 2173//2173 1434//1434 -f 1434//1434 2173//2173 1440//1440 -f 1434//1434 1440//1440 1432//1432 -f 1432//1432 1440//1440 1442//1442 -f 1432//1432 1442//1442 1443//1443 -f 1450//1450 1449//1449 1460//1460 -f 1460//1460 1449//1449 1867//1867 -f 1460//1460 1867//1867 1995//1995 -f 1995//1995 1867//1867 1276//1276 -f 1995//1995 1276//1276 1993//1993 -f 1993//1993 1276//1276 1275//1275 -f 1993//1993 1275//1275 2134//2134 -f 2134//2134 1275//1275 1290//1290 -f 2134//2134 1290//1290 2136//2136 -f 2136//2136 1290//1290 1289//1289 -f 2136//2136 1289//1289 2138//2138 -f 1266//1266 2174//2174 2002//2002 -f 2002//2002 2174//2174 2175//2175 -f 2002//2002 2175//2175 2077//2077 -f 2077//2077 2175//2175 2176//2176 -f 2077//2077 2176//2176 2075//2075 -f 2075//2075 2176//2176 2177//2177 -f 2075//2075 2177//2177 2140//2140 -f 2140//2140 2177//2177 2178//2178 -f 2140//2140 2178//2178 2141//2141 -f 2141//2141 2178//2178 2179//2179 -f 2141//2141 2179//2179 2142//2142 -f 2067//2067 2068//2068 1946//1946 -f 1946//1946 2068//2068 2017//2017 -f 1946//1946 2017//2017 1948//1948 -f 1948//1948 2017//2017 1974//1974 -f 1948//1948 1974//1974 1977//1977 -f 1977//1977 1974//1974 1976//1976 -f 2193//2193 2028//2028 2194//2194 -f 2194//2194 2028//2028 2051//2051 -f 2194//2194 2051//2051 2195//2195 -f 2195//2195 2051//2051 2053//2053 -f 2195//2195 2053//2053 2196//2196 -f 2196//2196 2053//2053 2156//2156 -f 2196//2196 2156//2156 2197//2197 -f 2197//2197 2156//2156 2157//2157 -f 2197//2197 2157//2157 2198//2198 -f 2198//2198 2157//2157 2158//2158 -f 2198//2198 2158//2158 1282//1282 -f 1409//1409 1404//1404 1415//1415 -f 1415//1415 1404//1404 2199//2199 -f 1415//1415 2199//2199 2042//2042 -f 2042//2042 2199//2199 2200//2200 -f 2042//2042 2200//2200 2040//2040 -f 2040//2040 2200//2200 2201//2201 -f 2040//2040 2201//2201 2159//2159 -f 2159//2159 2201//2201 2202//2202 -f 2159//2159 2202//2202 2160//2160 -f 2160//2160 2202//2202 2203//2203 -f 2160//2160 2203//2203 2161//2161 -f 1331//1331 1333//1333 1370//1370 -f 1370//1370 1333//1333 1874//1874 -f 1370//1370 1874//1874 2204//2204 -f 2204//2204 1874//1874 2180//2180 -f 2204//2204 2180//2180 2205//2205 -f 2205//2205 2180//2180 2118//2118 -f 2205//2205 2118//2118 2206//2206 -f 2206//2206 2118//2118 2093//2093 -f 2206//2206 2093//2093 2207//2207 -f 2207//2207 2093//2093 2092//2092 -f 2207//2207 2092//2092 1280//1280 -f 2208//2208 2181//2181 2209//2209 -f 2209//2209 2181//2181 1843//1843 -f 2209//2209 1843//1843 2210//2210 -f 2210//2210 1843//1843 1845//1845 -f 2210//2210 1845//1845 2211//2211 -f 2211//2211 1845//1845 1846//1846 -f 2211//2211 1846//1846 1740//1740 -f 2212//2212 1317//1317 2213//2213 -f 2213//2213 1317//1317 1319//1319 -f 2213//2213 1319//1319 2182//2182 -f 2182//2182 1319//1319 1623//1623 -f 2182//2182 1623//1623 2183//2183 -f 2097//2097 1305//1305 2214//2214 -f 2214//2214 1305//1305 1304//1304 -f 2214//2214 1304//1304 2208//2208 -f 2208//2208 1304//1304 1849//1849 -f 2208//2208 1849//1849 2181//2181 -f 2181//2181 1849//1849 2184//2184 -f 2181//2181 2184//2184 2182//2182 -f 2182//2182 2184//2184 2185//2185 -f 2182//2182 2185//2185 2213//2213 -f 2213//2213 2185//2185 2186//2186 -f 2213//2213 2186//2186 2212//2212 -f 2212//2212 2186//2186 2215//2215 -f 2212//2212 2215//2215 2216//2216 -f 1310//1310 1718//1718 1311//1311 -f 1311//1311 1718//1718 1270//1270 -f 1311//1311 1270//1270 2187//2187 -f 2187//2187 1270//1270 1269//1269 -f 2187//2187 1269//1269 1302//1302 -f 1302//1302 1269//1269 2217//2217 -f 1302//1302 2217//2217 1313//1313 -f 1737//1737 1309//1309 1735//1735 -f 1735//1735 1309//1309 1311//1311 -f 1735//1735 1311//1311 2218//2218 -f 2218//2218 1311//1311 2187//2187 -f 2218//2218 2187//2187 2219//2219 -f 2219//2219 2187//2187 1860//1860 -f 2219//2219 1860//1860 2220//2220 -f 2220//2220 1860//1860 2164//2164 -f 2220//2220 2164//2164 1637//1637 -f 1636//1636 1642//1642 1637//1637 -f 1637//1637 1642//1642 1316//1316 -f 1637//1637 1316//1316 2220//2220 -f 2220//2220 1316//1316 2221//2221 -f 2220//2220 2221//2221 2219//2219 -f 2219//2219 2221//2221 2222//2222 -f 2219//2219 2222//2222 2218//2218 -f 2218//2218 2222//2222 2223//2223 -f 2218//2218 2223//2223 1735//1735 -f 1735//1735 2223//2223 1807//1807 -f 1735//1735 1807//1807 1799//1799 -f 1799//1799 1807//1807 1808//1808 -f 1811//1811 1805//1805 1437//1437 -f 1437//1437 1805//1805 1807//1807 -f 1437//1437 1807//1807 2192//2192 -f 2192//2192 1807//1807 2223//2223 -f 2192//2192 2223//2223 2190//2190 -f 2190//2190 2223//2223 2222//2222 -f 2190//2190 2222//2222 2188//2188 -f 2188//2188 2222//2222 2221//2221 -f 2188//2188 2221//2221 2099//2099 -f 2099//2099 2221//2221 1316//1316 -f 2099//2099 1316//1316 2086//2086 -f 2086//2086 1316//1316 1315//1315 -f 2086//2086 1315//1315 1633//1633 -f 1633//1633 1315//1315 2224//2224 -f 1633//1633 2224//2224 1631//1631 -f 1457//1457 1452//1452 2225//2225 -f 2225//2225 1452//1452 2226//2226 -f 2225//2225 2226//2226 1468//1468 -f 1468//1468 2226//2226 1453//1453 -f 1468//1468 1453//1453 1467//1467 -f 1467//1467 1453//1453 1455//1455 -f 1467//1467 1455//1455 2227//2227 -f 2018//2018 2019//2019 2017//2017 -f 2017//2017 2019//2019 2021//2021 -f 2017//2017 2021//2021 1974//1974 -f 1974//1974 2021//2021 2228//2228 -f 1974//1974 2228//2228 1972//1972 -f 1972//1972 2228//2228 2011//2011 -f 1972//1972 2011//2011 2014//2014 -f 2014//2014 2011//2011 2012//2012 -f 1282//1282 1284//1284 2198//2198 -f 2198//2198 1284//1284 2229//2229 -f 2198//2198 2229//2229 2197//2197 -f 2197//2197 2229//2229 2230//2230 -f 2197//2197 2230//2230 2196//2196 -f 2196//2196 2230//2230 2231//2231 -f 2196//2196 2231//2231 2195//2195 -f 2195//2195 2231//2231 2232//2232 -f 2195//2195 2232//2232 2194//2194 -f 2194//2194 2232//2232 2233//2233 -f 2194//2194 2233//2233 2193//2193 -f 1280//1280 1281//1281 2207//2207 -f 2207//2207 1281//1281 2234//2234 -f 2207//2207 2234//2234 2206//2206 -f 2206//2206 2234//2234 2235//2235 -f 2206//2206 2235//2235 2205//2205 -f 2205//2205 2235//2235 2236//2236 -f 2205//2205 2236//2236 2204//2204 -f 2204//2204 2236//2236 2237//2237 -f 2204//2204 2237//2237 1370//1370 -f 1370//1370 2237//2237 2238//2238 -f 1370//1370 2238//2238 1368//1368 -f 1751//1751 1753//1753 1749//1749 -f 1749//1749 1753//1753 2239//2239 -f 1749//1749 2239//2239 2240//2240 -f 2240//2240 2239//2239 2241//2241 -f 2240//2240 2241//2241 2242//2242 -f 2242//2242 2241//2241 2243//2243 -f 2242//2242 2243//2243 2244//2244 -f 2244//2244 2243//2243 2245//2245 -f 2244//2244 2245//2245 2246//2246 -f 2246//2246 2245//2245 1279//1279 -f 2246//2246 1279//1279 2247//2247 -f 2247//2247 1279//1279 1278//1278 -f 2247//2247 1278//1278 2248//2248 -f 1739//1739 1749//1749 1740//1740 -f 1740//1740 1749//1749 2240//2240 -f 1740//1740 2240//2240 2211//2211 -f 2211//2211 2240//2240 2242//2242 -f 2211//2211 2242//2242 2210//2210 -f 2210//2210 2242//2242 2244//2244 -f 2210//2210 2244//2244 2209//2209 -f 2209//2209 2244//2244 2246//2246 -f 2209//2209 2246//2246 2208//2208 -f 2208//2208 2246//2246 2247//2247 -f 2208//2208 2247//2247 2214//2214 -f 2214//2214 2247//2247 2248//2248 -f 2214//2214 2248//2248 2097//2097 -f 2249//2249 2250//2250 2227//2227 -f 2227//2227 2250//2250 2251//2251 -f 2227//2227 2251//2251 1467//1467 -f 1467//1467 2251//2251 2252//2252 -f 1467//1467 2252//2252 2253//2253 -f 2254//2254 1470//1470 2255//2255 -f 2255//2255 1470//1470 1467//1467 -f 2255//2255 1467//1467 2256//2256 -f 2256//2256 1467//1467 2253//2253 -f 2254//2254 2257//2257 1470//1470 -f 1470//1470 2257//2257 2258//2258 -f 1470//1470 2258//2258 2259//2259 -f 2259//2259 2258//2258 2260//2260 -f 2259//2259 2260//2260 2261//2261 -f 2261//2261 2249//2249 2259//2259 -f 2259//2259 2249//2249 2227//2227 -f 2259//2259 2227//2227 2262//2262 -f 1268//1268 1267//1267 2263//2263 -f 2263//2263 1267//1267 2011//2011 -f 2263//2263 2011//2011 2264//2264 -f 2264//2264 2011//2011 2228//2228 -f 2264//2264 2228//2228 2265//2265 -f 2265//2265 2228//2228 2021//2021 -f 2265//2265 2021//2021 1583//1583 -f 1583//1583 2021//2021 2022//2022 -f 1583//1583 2022//2022 1580//1580 -f 1580//1580 2022//2022 2025//2025 -f 1580//1580 2025//2025 1578//1578 -f 2233//2233 2266//2266 2267//2267 -f 2268//2268 2269//2269 1578//1578 -f 2270//2270 2271//2271 2193//2193 -f 2272//2272 2273//2273 2274//2274 -f 2233//2233 2267//2267 2193//2193 -f 2193//2193 2267//2267 2275//2275 -f 2193//2193 2275//2275 2270//2270 -f 2026//2026 2028//2028 2025//2025 -f 2025//2025 2028//2028 2193//2193 -f 2025//2025 2193//2193 1578//1578 -f 1578//1578 2193//2193 2271//2271 -f 1578//1578 2271//2271 2268//2268 -f 2273//2273 2276//2276 2274//2274 -f 2274//2274 2276//2276 2277//2277 -f 2274//2274 2277//2277 2233//2233 -f 2233//2233 2277//2277 2278//2278 -f 2233//2233 2278//2278 2266//2266 -f 2279//2279 1377//1377 2280//2280 -f 2280//2280 1377//1377 2281//2281 -f 2282//2282 2283//2283 2284//2284 -f 1376//1376 1366//1366 1377//1377 -f 1377//1377 1366//1366 1368//1368 -f 1377//1377 1368//1368 2281//2281 -f 2281//2281 1368//1368 2285//2285 -f 2286//2286 2238//2238 2287//2287 -f 2287//2287 2238//2238 2284//2284 -f 2287//2287 2284//2284 2288//2288 -f 2288//2288 2284//2284 2283//2283 -f 2286//2286 2289//2289 2238//2238 -f 2238//2238 2289//2289 2290//2290 -f 2238//2238 2290//2290 1368//1368 -f 1368//1368 2290//2290 2291//2291 -f 1368//1368 2291//2291 2285//2285 -f 1687//1687 1265//1265 2292//2292 -f 2292//2292 1265//1265 1264//1264 -f 2292//2292 1264//1264 1736//1736 -f 1736//1736 1264//1264 1732//1732 -f 1736//1736 1732//1732 1738//1738 -f 2293//2293 2294//2294 2295//2295 -f 2296//2296 2297//2297 2262//2262 -f 2262//2262 2297//2297 2298//2298 -f 2299//2299 2300//2300 1268//1268 -f 1268//1268 2300//2300 2301//2301 -f 2301//2301 2296//2296 1268//1268 -f 1268//1268 2296//2296 2262//2262 -f 1268//1268 2262//2262 1266//1266 -f 1266//1266 2262//2262 2227//2227 -f 1266//1266 2227//2227 2174//2174 -f 2174//2174 2227//2227 1455//1455 -f 2174//2174 1455//1455 1985//1985 -f 1985//1985 1455//1455 1998//1998 -f 1985//1985 1998//1998 1986//1986 -f 2302//2302 2303//2303 2304//2304 -f 2304//2304 2303//2303 2305//2305 -f 2304//2304 2305//2305 2295//2295 -f 2295//2295 2305//2305 2306//2306 -f 2295//2295 2306//2306 2293//2293 -f 2298//2298 2302//2302 2262//2262 -f 2262//2262 2302//2302 2304//2304 -f 2262//2262 2304//2304 2259//2259 -f 2259//2259 2304//2304 1360//1360 -f 2259//2259 1360//1360 1470//1470 -f 1470//1470 1360//1360 1358//1358 -f 1470//1470 1358//1358 1471//1471 -f 1471//1471 1358//1358 1357//1357 -f 1585//1585 1586//1586 1583//1583 -f 1583//1583 1586//1586 1570//1570 -f 1583//1583 1570//1570 2265//2265 -f 2265//2265 1570//1570 2307//2307 -f 2265//2265 2307//2307 2264//2264 -f 2264//2264 2307//2307 2308//2308 -f 2264//2264 2308//2308 2263//2263 -f 2263//2263 2308//2308 2309//2309 -f 2263//2263 2309//2309 1268//1268 -f 1268//1268 2309//2309 2295//2295 -f 1268//1268 2295//2295 2299//2299 -f 2299//2299 2295//2295 2294//2294 -f 1539//1539 1330//1330 1544//1544 -f 1544//1544 1330//1330 1578//1578 -f 1544//1544 1578//1578 2274//2274 -f 2274//2274 1578//1578 2269//2269 -f 2274//2274 2269//2269 2272//2272 -f 1542//1542 1544//1544 1399//1399 -f 1399//1399 1544//1544 2274//2274 -f 1399//1399 2274//2274 1401//1401 -f 1401//1401 2274//2274 2233//2233 -f 1401//1401 2233//2233 1403//1403 -f 1403//1403 2233//2233 2232//2232 -f 1403//1403 2232//2232 1404//1404 -f 1404//1404 2232//2232 2231//2231 -f 1404//1404 2231//2231 2199//2199 -f 2199//2199 2231//2231 2230//2230 -f 2199//2199 2230//2230 2200//2200 -f 2200//2200 2230//2230 2229//2229 -f 2200//2200 2229//2229 2201//2201 -f 2201//2201 2229//2229 1284//1284 -f 2201//2201 1284//1284 2202//2202 -f 2202//2202 1284//1284 1283//1283 -f 2202//2202 1283//1283 2203//2203 -f 1657//1657 1656//1656 1659//1659 -f 1659//1659 1656//1656 1693//1693 -f 1659//1659 1693//1693 1260//1260 -f 1260//1260 1693//1693 1696//1696 -f 1260//1260 1696//1696 1700//1700 -f 1698//1698 1691//1691 1699//1699 -f 1699//1699 1691//1691 1693//1693 -f 1699//1699 1693//1693 2310//2310 -f 2310//2310 1693//1693 1656//1656 -f 2310//2310 1656//1656 2311//2311 -f 2311//2311 1656//1656 1658//1658 -f 2311//2311 1658//1658 2312//2312 -f 1689//1689 1714//1714 1687//1687 -f 1687//1687 1714//1714 1699//1699 -f 1687//1687 1699//1699 1265//1265 -f 1265//1265 1699//1699 2310//2310 -f 1265//1265 2310//2310 1263//1263 -f 1263//1263 2310//2310 2311//2311 -f 1263//1263 2311//2311 1269//1269 -f 1269//1269 2311//2311 2312//2312 -f 1269//1269 2312//2312 2217//2217 -f 1802//1802 1804//1804 1810//1810 -f 1810//1810 1804//1804 2313//2313 -f 1810//1810 2313//2313 2314//2314 -f 2314//2314 2313//2313 2315//2315 -f 2314//2314 2315//2315 2316//2316 -f 2317//2317 2318//2318 2319//2319 -f 2304//2304 2320//2320 2321//2321 -f 2295//2295 2322//2322 2323//2323 -f 2321//2321 1363//1363 2304//2304 -f 2304//2304 1363//1363 1365//1365 -f 2304//2304 1365//1365 1360//1360 -f 1360//1360 1365//1365 2324//2324 -f 1360//1360 2324//2324 1361//1361 -f 2321//2321 2325//2325 1363//1363 -f 1363//1363 2325//2325 2326//2326 -f 1363//1363 2326//2326 2319//2319 -f 2319//2319 2326//2326 2327//2327 -f 2319//2319 2327//2327 2317//2317 -f 2323//2323 2328//2328 2295//2295 -f 2295//2295 2328//2328 2329//2329 -f 2295//2295 2329//2329 2304//2304 -f 2304//2304 2329//2329 2330//2330 -f 2304//2304 2330//2330 2320//2320 -f 1572//1572 1573//1573 1570//1570 -f 1570//1570 1573//1573 1557//1557 -f 1570//1570 1557//1557 2307//2307 -f 2307//2307 1557//1557 2331//2331 -f 2307//2307 2331//2331 2308//2308 -f 2308//2308 2331//2331 2332//2332 -f 2308//2308 2332//2332 2309//2309 -f 2309//2309 2332//2332 2333//2333 -f 2309//2309 2333//2333 2295//2295 -f 2295//2295 2333//2333 2319//2319 -f 2295//2295 2319//2319 2322//2322 -f 2322//2322 2319//2319 2318//2318 -f 1766//1766 1768//1768 1771//1771 -f 1771//1771 1768//1768 2334//2334 -f 1771//1771 2334//2334 2335//2335 -f 2335//2335 2334//2334 1746//1746 -f 2335//2335 1746//1746 1308//1308 -f 1308//1308 1746//1746 1745//1745 -f 1308//1308 1745//1745 1306//1306 -f 1769//1769 1771//1771 1795//1795 -f 1795//1795 1771//1771 2335//2335 -f 1795//1795 2335//2335 2336//2336 -f 2336//2336 2335//2335 1308//1308 -f 2336//2336 1308//1308 1742//1742 -f 1742//1742 1308//1308 1307//1307 -f 1742//1742 1307//1307 1743//1743 -f 1439//1439 2337//2337 1437//1437 -f 1437//1437 2337//2337 2338//2338 -f 1437//1437 2338//2338 1804//1804 -f 1804//1804 2338//2338 2339//2339 -f 1804//1804 2339//2339 2313//2313 -f 2313//2313 2339//2339 1481//1481 -f 2313//2313 1481//1481 2315//2315 -f 2315//2315 1481//1481 1474//1474 -f 2315//2315 1474//1474 2316//2316 -f 2316//2316 1474//1474 2340//2340 -f 2319//2319 2341//2341 2342//2342 -f 2343//2343 1491//1491 2344//2344 -f 2344//2344 2345//2345 2343//2343 -f 2343//2343 2345//2345 2346//2346 -f 2343//2343 2346//2346 2347//2347 -f 2342//2342 2348//2348 2319//2319 -f 2319//2319 2348//2348 2349//2349 -f 2319//2319 2349//2349 1363//1363 -f 1363//1363 2349//2349 2350//2350 -f 2350//2350 2351//2351 1363//1363 -f 1363//1363 2351//2351 2352//2352 -f 1363//1363 2352//2352 1491//1491 -f 1491//1491 2352//2352 2353//2353 -f 1491//1491 2353//2353 2344//2344 -f 1559//1559 1560//1560 1557//1557 -f 1557//1557 1560//1560 1562//1562 -f 1557//1557 1562//1562 2331//2331 -f 2331//2331 1562//1562 2354//2354 -f 2331//2331 2354//2354 2332//2332 -f 2332//2332 2354//2354 2355//2355 -f 2332//2332 2355//2355 2333//2333 -f 2333//2333 2355//2355 2356//2356 -f 2333//2333 2356//2356 2319//2319 -f 2319//2319 2356//2356 2343//2343 -f 2319//2319 2343//2343 2341//2341 -f 2341//2341 2343//2343 2347//2347 -f 2357//2357 1262//1262 2358//2358 -f 2358//2358 1262//1262 1261//1261 -f 2358//2358 1261//1261 1688//1688 -f 1688//1688 1261//1261 1707//1707 -f 1688//1688 1707//1707 1690//1690 -f 1485//1485 1486//1486 1347//1347 -f 1347//1347 1486//1486 1488//1488 -f 1347//1347 1488//1488 1350//1350 -f 1350//1350 1488//1488 2359//2359 -f 1350//1350 2359//2359 1478//1478 -f 1478//1478 2359//2359 2360//2360 -f 1478//1478 2360//2360 1476//1476 -f 1476//1476 2360//2360 2361//2361 -f 1476//1476 2361//2361 1474//1474 -f 1474//1474 2361//2361 2362//2362 -f 1474//1474 2362//2362 2340//2340 -f 2340//2340 2362//2362 2363//2363 -f 1523//1523 1508//1508 1524//1524 -f 1524//1524 1508//1508 1507//1507 -f 1524//1524 1507//1507 1553//1553 -f 1553//1553 1507//1507 2364//2364 -f 1553//1553 2364//2364 1562//1562 -f 1562//1562 2364//2364 2365//2365 -f 1562//1562 2365//2365 2354//2354 -f 2354//2354 2365//2365 2366//2366 -f 2354//2354 2366//2366 2355//2355 -f 2355//2355 2366//2366 2367//2367 -f 2355//2355 2367//2367 2356//2356 -f 2356//2356 2367//2367 2368//2368 -f 2356//2356 2368//2368 2343//2343 -f 2343//2343 2368//2368 2369//2369 -f 2343//2343 2369//2369 1491//1491 -f 1491//1491 2369//2369 2370//2370 -f 1491//1491 2370//2370 1492//1492 -f 1492//1492 2370//2370 1490//1490 -f 1492//1492 1490//1490 1494//1494 -f 1494//1494 1490//1490 1498//1498 -f 1393//1393 2371//2371 1395//1395 -f 1395//1395 2371//2371 2372//2372 -f 1395//1395 2372//2372 1390//1390 -f 1390//1390 2372//2372 2373//2373 -f 1390//1390 2373//2373 1548//1548 -f 1548//1548 2373//2373 1513//1513 -f 1548//1548 1513//1513 1546//1546 -f 1546//1546 1513//1513 1515//1515 -f 2374//2374 2375//2375 2376//2376 -f 2377//2377 2378//2378 1666//1666 -f 1666//1666 2378//2378 2379//2379 -f 1666//1666 2379//2379 1670//1670 -f 2379//2379 2380//2380 1670//1670 -f 1670//1670 2380//2380 2381//2381 -f 1670//1670 2381//2381 2376//2376 -f 2376//2376 2381//2381 2382//2382 -f 2376//2376 2382//2382 2374//2374 -f 2383//2383 2384//2384 2385//2385 -f 2385//2385 2384//2384 2386//2386 -f 2385//2385 2386//2386 2387//2387 -f 1660//1660 1659//1659 1663//1663 -f 1663//1663 1659//1659 1260//1260 -f 1663//1663 1260//1260 2388//2388 -f 2388//2388 1260//1260 1262//1262 -f 2388//2388 1262//1262 2389//2389 -f 2389//2389 1262//1262 2357//2357 -f 2389//2389 2357//2357 2390//2390 -f 2371//2371 2391//2391 2372//2372 -f 2372//2372 2391//2391 2392//2392 -f 2372//2372 2392//2392 2373//2373 -f 2373//2373 2392//2392 2393//2393 -f 2373//2373 2393//2393 1513//1513 -f 1513//1513 2393//2393 2394//2394 -f 1513//1513 2394//2394 1507//1507 -f 1507//1507 2394//2394 2395//2395 -f 1507//1507 2395//2395 2364//2364 -f 2364//2364 2395//2395 2396//2396 -f 2364//2364 2396//2396 2365//2365 -f 2365//2365 2396//2396 2397//2397 -f 2365//2365 2397//2397 2366//2366 -f 2366//2366 2397//2397 2398//2398 -f 2366//2366 2398//2398 2367//2367 -f 2367//2367 2398//2398 2399//2399 -f 2367//2367 2399//2399 2368//2368 -f 2368//2368 2399//2399 2400//2400 -f 2368//2368 2400//2400 2369//2369 -f 2369//2369 2400//2400 2401//2401 -f 2369//2369 2401//2401 2370//2370 -f 2370//2370 2401//2401 2402//2402 -f 2370//2370 2402//2402 1490//1490 -f 1490//1490 2402//2402 2403//2403 -f 1490//1490 2403//2403 1488//1488 -f 1488//1488 2403//2403 2404//2404 -f 1488//1488 2404//2404 2359//2359 -f 2359//2359 2404//2404 2405//2405 -f 2359//2359 2405//2405 2360//2360 -f 2360//2360 2405//2405 2406//2406 -f 2360//2360 2406//2406 2361//2361 -f 2361//2361 2406//2406 1887//1887 -f 2361//2361 1887//1887 2362//2362 -f 2362//2362 1887//1887 1885//1885 -f 2362//2362 1885//1885 2363//2363 -f 2363//2363 1885//1885 1883//1883 -f 1295//1295 1906//1906 1296//1296 -f 1296//1296 1906//1906 2407//2407 -f 1296//1296 2407//2407 2408//2408 -f 2408//2408 2407//2407 1380//1380 -f 2408//2408 1380//1380 1382//1382 -f 1382//1382 1380//1380 1381//1381 -f 1382//1382 1381//1381 1383//1383 -f 1294//1294 1296//1296 1914//1914 -f 1914//1914 1296//1296 2408//2408 -f 1914//1914 2408//2408 2409//2409 -f 2409//2409 2408//2408 1382//1382 -f 2409//2409 1382//1382 2410//2410 -f 2410//2410 1382//1382 1373//1373 -f 2410//2410 1373//1373 2411//2411 -f 2411//2411 1373//1373 1375//1375 -f 2411//2411 1375//1375 2412//2412 -f 2412//2412 1375//1375 1377//1377 -f 2412//2412 1377//1377 2284//2284 -f 2284//2284 1377//1377 2279//2279 -f 2284//2284 2279//2279 2282//2282 -f 1620//1620 1318//1318 2413//2413 -f 2413//2413 1318//1318 1615//1615 -f 2413//2413 1615//1615 1846//1846 -f 1846//1846 1615//1615 1614//1614 -f 1846//1846 1614//1614 1740//1740 -f 1740//1740 1614//1614 1612//1612 -f 1740//1740 1612//1612 1742//1742 -f 1742//1742 1612//1612 1610//1610 -f 1742//1742 1610//1610 2336//2336 -f 2336//2336 1610//1610 1608//1608 -f 2336//2336 1608//1608 1795//1795 -f 1795//1795 1608//1608 1606//1606 -f 1795//1795 1606//1606 1793//1793 -f 1793//1793 1606//1606 1605//1605 -f 1793//1793 1605//1605 2414//2414 -f 2414//2414 1605//1605 1824//1824 -f 2414//2414 1824//1824 2415//2415 -f 1601//1601 2416//2416 1322//1322 -f 1322//1322 2416//2416 1814//1814 -f 1322//1322 1814//1814 1818//1818 -f 1818//1818 1814//1814 1816//1816 -f 2376//2376 1672//1672 1677//1677 -f 1677//1677 1672//1672 1671//1671 -f 1677//1677 1671//1671 1675//1675 -f 2375//2375 2383//2383 2376//2376 -f 2376//2376 2383//2383 2385//2385 -f 2376//2376 2385//2385 1672//1672 -f 1672//1672 2385//2385 2417//2417 -f 1672//1672 2417//2417 1674//1674 -f 1674//1674 2417//2417 2418//2418 -f 2403//2403 2419//2419 2420//2420 -f 2420//2420 2421//2421 2403//2403 -f 2403//2403 2421//2421 2422//2422 -f 2403//2403 2422//2422 2404//2404 -f 2404//2404 2422//2422 2423//2423 -f 2404//2404 2423//2423 2424//2424 -f 2425//2425 2426//2426 2427//2427 -f 2428//2428 2429//2429 2430//2430 -f 2430//2430 2429//2429 2431//2431 -f 2430//2430 2431//2431 2427//2427 -f 2427//2427 2431//2431 2432//2432 -f 2427//2427 2432//2432 2425//2425 -f 2424//2424 2428//2428 2404//2404 -f 2404//2404 2428//2428 2430//2430 -f 2404//2404 2430//2430 2405//2405 -f 2405//2405 2430//2430 1929//1929 -f 2405//2405 1929//1929 2406//2406 -f 2406//2406 1929//1929 1919//1919 -f 2406//2406 1919//1919 1887//1887 -f 1887//1887 1919//1919 1897//1897 -f 1887//1887 1897//1897 1888//1888 -f 1888//1888 1897//1897 1896//1896 -f 2394//2394 2433//2433 2434//2434 -f 2434//2434 2435//2435 2394//2394 -f 2394//2394 2435//2435 2436//2436 -f 2394//2394 2436//2436 2395//2395 -f 2395//2395 2436//2436 2437//2437 -f 2395//2395 2437//2437 2438//2438 -f 2438//2438 2439//2439 2395//2395 -f 2395//2395 2439//2439 2440//2440 -f 2395//2395 2440//2440 2396//2396 -f 2396//2396 2440//2440 2441//2441 -f 2396//2396 2441//2441 2397//2397 -f 2397//2397 2441//2441 2442//2442 -f 2397//2397 2442//2442 2398//2398 -f 2398//2398 2442//2442 2443//2443 -f 2398//2398 2443//2443 2399//2399 -f 2399//2399 2443//2443 2444//2444 -f 2399//2399 2444//2444 2400//2400 -f 2400//2400 2444//2444 2445//2445 -f 2400//2400 2445//2445 2401//2401 -f 2401//2401 2445//2445 2446//2446 -f 2401//2401 2446//2446 2402//2402 -f 2402//2402 2446//2446 2447//2447 -f 2402//2402 2447//2447 2403//2403 -f 2403//2403 2447//2447 2427//2427 -f 2403//2403 2427//2427 2419//2419 -f 2419//2419 2427//2427 2426//2426 -f 2448//2448 2449//2449 2450//2450 -f 2439//2439 2451//2451 2440//2440 -f 2440//2440 2451//2451 2452//2452 -f 2440//2440 2452//2452 2448//2448 -f 2448//2448 2452//2452 2453//2453 -f 2448//2448 2453//2453 2449//2449 -f 2391//2391 2454//2454 2392//2392 -f 2392//2392 2454//2454 2455//2455 -f 2392//2392 2455//2455 2393//2393 -f 2393//2393 2455//2455 2456//2456 -f 2393//2393 2456//2456 2394//2394 -f 2394//2394 2456//2456 2448//2448 -f 2394//2394 2448//2448 2433//2433 -f 2433//2433 2448//2448 2450//2450 -f 2416//2416 1598//1598 1814//1814 -f 1814//1814 1598//1598 1592//1592 -f 1814//1814 1592//1592 1815//1815 -f 1815//1815 1592//1592 1593//1593 -f 1815//1815 1593//1593 1824//1824 -f 1824//1824 1593//1593 1831//1831 -f 1824//1824 1831//1831 2415//2415 -f 2415//2415 1831//1831 1834//1834 -f 1797//1797 2418//2418 1798//1798 -f 1798//1798 2418//2418 2417//2417 -f 1798//1798 2417//2417 2457//2457 -f 2458//2458 2457//2457 2459//2459 -f 2459//2459 2457//2457 2417//2417 -f 2459//2459 2417//2417 2460//2460 -f 2460//2460 2417//2417 2385//2385 -f 2460//2460 2385//2385 1666//1666 -f 1666//1666 2385//2385 2387//2387 -f 1666//1666 2387//2387 2377//2377 -f 2461//2461 2462//2462 1878//1878 -f 1801//1801 1810//1810 1736//1736 -f 1736//1736 1810//1810 2314//2314 -f 1736//1736 2314//2314 2292//2292 -f 2292//2292 2314//2314 2316//2316 -f 2292//2292 2316//2316 1687//1687 -f 1687//1687 2316//2316 2340//2340 -f 1687//1687 2340//2340 1688//1688 -f 1688//1688 2340//2340 2363//2363 -f 1688//1688 2363//2363 2358//2358 -f 2358//2358 2363//2363 1883//1883 -f 2358//2358 1883//1883 2357//2357 -f 2357//2357 1883//1883 1878//1878 -f 2357//2357 1878//1878 2390//2390 -f 2390//2390 1878//1878 2462//2462 -f 2390//2390 2462//2462 2463//2463 -f 2463//2463 2464//2464 2390//2390 -f 2390//2390 2464//2464 2465//2465 -f 2390//2390 2465//2465 2466//2466 -f 2467//2467 2468//2468 2458//2458 -f 2458//2458 2468//2468 2469//2469 -f 2458//2458 2469//2469 1881//1881 -f 2469//2469 2470//2470 1881//1881 -f 1881//1881 2470//2470 2471//2471 -f 1881//1881 2471//2471 1878//1878 -f 1878//1878 2471//2471 2472//2472 -f 1878//1878 2472//2472 2461//2461 -f 1661//1661 1663//1663 1666//1666 -f 1666//1666 1663//1663 2388//2388 -f 1666//1666 2388//2388 2460//2460 -f 2460//2460 2388//2388 2389//2389 -f 2460//2460 2389//2389 2459//2459 -f 2459//2459 2389//2389 2390//2390 -f 2459//2459 2390//2390 2458//2458 -f 2458//2458 2390//2390 2466//2466 -f 2458//2458 2466//2466 2467//2467 -f 2473//2473 2474//2474 2475//2475 -f 2476//2476 2477//2477 2454//2454 -f 2454//2454 2477//2477 2478//2478 -f 2479//2479 1901//1901 2480//2480 -f 2480//2480 1901//1901 2475//2475 -f 2480//2480 2475//2475 2481//2481 -f 2481//2481 2475//2475 2474//2474 -f 2479//2479 2482//2482 1901//1901 -f 1901//1901 2482//2482 2483//2483 -f 1901//1901 2483//2483 1898//1898 -f 1898//1898 2483//2483 2484//2484 -f 1898//1898 2484//2484 2485//2485 -f 1378//1378 1380//1380 1393//1393 -f 1393//1393 1380//1380 2407//2407 -f 1393//1393 2407//2407 2371//2371 -f 2371//2371 2407//2407 1906//1906 -f 2371//2371 1906//1906 2391//2391 -f 2391//2391 1906//1906 1898//1898 -f 2391//2391 1898//1898 2454//2454 -f 2454//2454 1898//1898 2485//2485 -f 2454//2454 2485//2485 2476//2476 -f 2478//2478 2473//2473 2454//2454 -f 2454//2454 2473//2473 2475//2475 -f 2454//2454 2475//2475 2455//2455 -f 2455//2455 2475//2475 2486//2486 -f 2455//2455 2486//2486 2456//2456 -f 2456//2456 2486//2486 2487//2487 -f 2456//2456 2487//2487 2448//2448 -f 2448//2448 2487//2487 2488//2488 -f 2448//2448 2488//2488 2440//2440 -f 2440//2440 2488//2488 2489//2489 -f 2440//2440 2489//2489 2441//2441 -f 2441//2441 2489//2489 2490//2490 -f 2441//2441 2490//2490 2442//2442 -f 2442//2442 2490//2490 2491//2491 -f 2442//2442 2491//2491 2443//2443 -f 2443//2443 2491//2491 2492//2492 -f 2443//2443 2492//2492 2444//2444 -f 2444//2444 2492//2492 2493//2493 -f 2444//2444 2493//2493 2445//2445 -f 2445//2445 2493//2493 2494//2494 -f 2445//2445 2494//2494 2446//2446 -f 2446//2446 2494//2494 2495//2495 -f 2446//2446 2495//2495 2447//2447 -f 2447//2447 2495//2495 2496//2496 -f 2447//2447 2496//2496 2427//2427 -f 2427//2427 2496//2496 2497//2497 -f 2427//2427 2497//2497 2430//2430 -f 2430//2430 2497//2497 2498//2498 -f 2430//2430 2498//2498 1929//1929 -f 1929//1929 2498//2498 1926//1926 -f 1929//1929 1926//1926 1930//1930 -f 1930//1930 1926//1926 1927//1927 -f 1912//1912 2499//2499 2500//2500 -f 1277//1277 1279//1279 1281//1281 -f 1281//1281 1279//1279 2245//2245 -f 1281//1281 2245//2245 2234//2234 -f 2234//2234 2245//2245 2243//2243 -f 2234//2234 2243//2243 2235//2235 -f 2235//2235 2243//2243 2241//2241 -f 2235//2235 2241//2241 2236//2236 -f 2236//2236 2241//2241 2239//2239 -f 2236//2236 2239//2239 2237//2237 -f 2237//2237 2239//2239 1753//1753 -f 2237//2237 1753//1753 2238//2238 -f 2238//2238 1753//1753 1746//1746 -f 2238//2238 1746//1746 2284//2284 -f 2284//2284 1746//1746 2334//2334 -f 2284//2284 2334//2334 2412//2412 -f 2412//2412 2334//2334 1768//1768 -f 2412//2412 1768//1768 2411//2411 -f 2411//2411 1768//1768 1787//1787 -f 2411//2411 1787//1787 2410//2410 -f 2410//2410 1787//1787 2501//2501 -f 2410//2410 2501//2501 2409//2409 -f 2409//2409 2501//2501 2502//2502 -f 2409//2409 2502//2502 1914//1914 -f 1914//1914 2502//2502 2503//2503 -f 1914//1914 2503//2503 1912//1912 -f 1912//1912 2503//2503 2504//2504 -f 1912//1912 2504//2504 2499//2499 -f 2505//2505 1908//1908 2506//2506 -f 2506//2506 1908//1908 1912//1912 -f 2506//2506 1912//1912 2507//2507 -f 2507//2507 1912//1912 2500//2500 -f 2505//2505 2508//2508 1908//1908 -f 1908//1908 2508//2508 2509//2509 -f 1908//1908 2509//2509 2510//2510 -f 2510//2510 2509//2509 2511//2511 -f 2511//2511 2512//2512 2510//2510 -f 2510//2510 2512//2512 2513//2513 -f 2510//2510 2513//2513 2503//2503 -f 2503//2503 2513//2513 2514//2514 -f 2503//2503 2514//2514 2504//2504 -f 1772//1772 1774//1774 1787//1787 -f 1787//1787 1774//1774 2515//2515 -f 1787//1787 2515//2515 2501//2501 -f 2501//2501 2515//2515 2516//2516 -f 2501//2501 2516//2516 2502//2502 -f 2502//2502 2516//2516 2517//2517 -f 2502//2502 2517//2517 2503//2503 -f 2503//2503 2517//2517 2518//2518 -f 2503//2503 2518//2518 2510//2510 -f 1778//1778 1793//1793 1774//1774 -f 1774//1774 1793//1793 2414//2414 -f 1774//1774 2414//2414 2515//2515 -f 2515//2515 2414//2414 2415//2415 -f 2515//2515 2415//2415 2516//2516 -f 2516//2516 2415//2415 1834//1834 -f 2516//2516 1834//1834 2517//2517 -f 2517//2517 1834//1834 1836//1836 -f 2517//2517 1836//1836 2518//2518 -f 2084//2084 1258//1258 2085//2085 -f 2085//2085 1258//1258 1257//1257 -f 2085//2085 1257//1257 2165//2165 -f 2165//2165 1257//1257 1256//1256 -f 2165//2165 1256//1256 2166//2166 -f 2166//2166 1256//1256 1255//1255 -f 2166//2166 1255//1255 2130//2130 -f 2130//2130 1255//1255 1254//1254 -f 2130//2130 1254//1254 2111//2111 -f 2111//2111 1254//1254 1253//1253 -f 2111//2111 1253//1253 2107//2107 -f 2107//2107 1253//1253 1252//1252 -f 2107//2107 1252//1252 1288//1288 -f 1288//1288 1252//1252 1251//1251 -f 1288//1288 1251//1251 1289//1289 -f 1289//1289 1251//1251 1250//1250 -f 1289//1289 1250//1250 2138//2138 -f 2138//2138 1250//1250 1249//1249 -f 2138//2138 1249//1249 2139//2139 -f 2139//2139 1249//1249 1248//1248 -f 2139//2139 1248//1248 2179//2179 -f 2179//2179 1248//1248 1247//1247 -f 2179//2179 1247//1247 2142//2142 -f 2142//2142 1247//1247 1246//1246 -f 2142//2142 1246//1246 2090//2090 -f 2090//2090 1246//1246 1245//1245 -f 2090//2090 1245//1245 2088//2088 -f 2088//2088 1245//1245 1244//1244 -f 2088//2088 1244//1244 2087//2087 -f 2087//2087 1244//1244 1243//1243 -f 2087//2087 1243//1243 1285//1285 -f 1285//1285 1243//1243 1242//1242 -f 1285//1285 1242//1242 1286//1286 -f 1286//1286 1242//1242 1241//1241 -f 1286//1286 1241//1241 2158//2158 -f 2158//2158 1241//1241 1240//1240 -f 2158//2158 1240//1240 1282//1282 -f 1282//1282 1240//1240 1239//1239 -f 1282//1282 1239//1239 1283//1283 -f 1283//1283 1239//1239 1238//1238 -f 1283//1283 1238//1238 2203//2203 -f 2203//2203 1238//1238 1237//1237 -f 2203//2203 1237//1237 2161//2161 -f 2161//2161 1237//1237 1236//1236 -f 2161//2161 1236//1236 2094//2094 -f 2094//2094 1236//1236 1235//1235 -f 2094//2094 1235//1235 2092//2092 -f 2092//2092 1235//1235 1234//1234 -f 2092//2092 1234//1234 1280//1280 -f 1280//1280 1234//1234 1233//1233 -f 1280//1280 1233//1233 1277//1277 -f 1277//1277 1233//1233 1232//1232 -f 1277//1277 1232//1232 1278//1278 -f 1278//1278 1232//1232 1231//1231 -f 1278//1278 1231//1231 2248//2248 -f 2248//2248 1231//1231 1230//1230 -f 2248//2248 1230//1230 2097//2097 -f 2097//2097 1230//1230 1229//1229 -f 2097//2097 1229//1229 2096//2096 -f 2096//2096 1229//1229 1228//1228 -f 2096//2096 1228//1228 1629//1629 -f 1629//1629 1228//1228 1227//1227 -f 1629//1629 1227//1227 1624//1624 -f 1624//1624 1227//1227 1226//1226 -f 206//206 1439//1439 198//198 -f 198//198 1439//1439 1438//1438 -f 198//198 1438//1438 199//199 -f 199//199 1438//1438 1436//1436 -f 199//199 1436//1436 202//202 -f 202//202 1436//1436 1435//1435 -f 202//202 1435//1435 201//201 -f 201//201 1435//1435 1433//1433 -f 1439//1439 206//206 2337//2337 -f 2337//2337 206//206 204//204 -f 2337//2337 204//204 2338//2338 -f 2338//2338 204//204 203//203 -f 2338//2338 203//203 2339//2339 -f 2339//2339 203//203 212//212 -f 2339//2339 212//212 1481//1481 -f 1481//1481 212//212 210//210 -f 1481//1481 210//210 1482//1482 -f 1482//1482 210//210 208//208 -f 153//153 1475//1475 154//154 -f 154//154 1475//1475 1473//1473 -f 154//154 1473//1473 156//156 -f 156//156 1473//1473 1472//1472 -f 156//156 1472//1472 207//207 -f 207//207 1472//1472 1483//1483 -f 207//207 1483//1483 208//208 -f 208//208 1483//1483 1482//1482 -f 1475//1475 153//153 1477//1477 -f 1477//1477 153//153 933//933 -f 1477//1477 933//933 1479//1479 -f 1479//1479 933//933 937//937 -f 1479//1479 937//937 1480//1480 -f 1480//1480 937//937 79//79 -f 1480//1480 79//79 1351//1351 -f 1351//1351 79//79 78//78 -f 157//157 1355//1355 158//158 -f 158//158 1355//1355 1349//1349 -f 158//158 1349//1349 160//160 -f 160//160 1349//1349 1348//1348 -f 160//160 1348//1348 161//161 -f 161//161 1348//1348 1352//1352 -f 161//161 1352//1352 78//78 -f 78//78 1352//1352 1351//1351 -f 1355//1355 157//157 1353//1353 -f 1353//1353 157//157 183//183 -f 1353//1353 183//183 1357//1357 -f 1357//1357 183//183 182//182 -f 1357//1357 182//182 1471//1471 -f 1471//1471 182//182 180//180 -f 1471//1471 180//180 1469//1469 -f 1469//1469 180//180 178//178 -f 1469//1469 178//178 1465//1465 -f 1465//1465 178//178 177//177 -f 186//186 1457//1457 187//187 -f 187//187 1457//1457 2225//2225 -f 187//187 2225//2225 188//188 -f 188//188 2225//2225 1468//1468 -f 188//188 1468//1468 176//176 -f 176//176 1468//1468 1466//1466 -f 176//176 1466//1466 177//177 -f 177//177 1466//1466 1465//1465 -f 1457//1457 186//186 1450//1450 -f 1450//1450 186//186 165//165 -f 1450//1450 165//165 1445//1445 -f 1445//1445 165//165 191//191 -f 1445//1445 191//191 1432//1432 -f 1432//1432 191//191 194//194 -f 1432//1432 194//194 1433//1433 -f 1433//1433 194//194 201//201 -f 109//109 1331//1331 110//110 -f 110//110 1331//1331 1372//1372 -f 110//110 1372//1372 112//112 -f 112//112 1372//1372 1371//1371 -f 112//112 1371//1371 113//113 -f 113//113 1371//1371 1369//1369 -f 113//113 1369//1369 115//115 -f 115//115 1369//1369 1367//1367 -f 1331//1331 109//109 1332//1332 -f 1332//1332 109//109 128//128 -f 1332//1332 128//128 1420//1420 -f 1420//1420 128//128 132//132 -f 1420//1420 132//132 1409//1409 -f 1409//1409 132//132 146//146 -f 1409//1409 146//146 1410//1410 -f 1410//1410 146//146 145//145 -f 84//84 1407//1407 81//81 -f 81//81 1407//1407 1406//1406 -f 81//81 1406//1406 82//82 -f 82//82 1406//1406 1405//1405 -f 82//82 1405//1405 144//144 -f 144//144 1405//1405 1411//1411 -f 144//144 1411//1411 145//145 -f 145//145 1411//1411 1410//1410 -f 1407//1407 84//84 1408//1408 -f 1408//1408 84//84 90//90 -f 1408//1408 90//90 1402//1402 -f 1402//1402 90//90 89//89 -f 1402//1402 89//89 1400//1400 -f 1400//1400 89//89 87//87 -f 1400//1400 87//87 1388//1388 -f 1388//1388 87//87 91//91 -f 1388//1388 91//91 1389//1389 -f 1389//1389 91//91 93//93 -f 101//101 1396//1396 102//102 -f 102//102 1396//1396 1397//1397 -f 102//102 1397//1397 95//95 -f 95//95 1397//1397 1392//1392 -f 95//95 1392//1392 94//94 -f 94//94 1392//1392 1391//1391 -f 94//94 1391//1391 93//93 -f 93//93 1391//1391 1389//1389 -f 1396//1396 101//101 1394//1394 -f 1394//1394 101//101 99//99 -f 1394//1394 99//99 1378//1378 -f 1378//1378 99//99 97//97 -f 1378//1378 97//97 1379//1379 -f 1379//1379 97//97 108//108 -f 1379//1379 108//108 1381//1381 -f 1381//1381 108//108 107//107 -f 123//123 1386//1386 104//104 -f 104//104 1386//1386 1385//1385 -f 104//104 1385//1385 105//105 -f 105//105 1385//1385 1384//1384 -f 105//105 1384//1384 106//106 -f 106//106 1384//1384 1383//1383 -f 106//106 1383//1383 107//107 -f 107//107 1383//1383 1381//1381 -f 1386//1386 123//123 1387//1387 -f 1387//1387 123//123 122//122 -f 1387//1387 122//122 1374//1374 -f 1374//1374 122//122 120//120 -f 1374//1374 120//120 1376//1376 -f 1376//1376 120//120 118//118 -f 1376//1376 118//118 1366//1366 -f 1366//1366 118//118 116//116 -f 1366//1366 116//116 1367//1367 -f 1367//1367 116//116 115//115 -f 1356//1356 236//236 1504//1504 -f 1504//1504 236//236 438//438 -f 1504//1504 438//438 1503//1503 -f 1503//1503 438//438 224//224 -f 1503//1503 224//224 1501//1501 -f 1501//1501 224//224 228//228 -f 1501//1501 228//228 1495//1495 -f 1495//1495 228//228 219//219 -f 1495//1495 219//219 1493//1493 -f 1493//1493 219//219 72//72 -f 1493//1493 72//72 1345//1345 -f 1345//1345 72//72 74//74 -f 1345//1345 74//74 1343//1343 -f 1343//1343 74//74 246//246 -f 1343//1343 246//246 1341//1341 -f 1341//1341 246//246 245//245 -f 1341//1341 245//245 1339//1339 -f 1339//1339 245//245 243//243 -f 1339//1339 243//243 1335//1335 -f 1335//1335 243//243 239//239 -f 1335//1335 239//239 1336//1336 -f 1336//1336 239//239 237//237 -f 1336//1336 237//237 1356//1356 -f 1356//1356 237//237 236//236 -f 1523//1523 258//258 1508//1508 -f 1508//1508 258//258 269//269 -f 1508//1508 269//269 1509//1509 -f 1509//1509 269//269 271//271 -f 1509//1509 271//271 1517//1517 -f 1517//1517 271//271 279//279 -f 1517//1517 279//279 1512//1512 -f 1512//1512 279//279 267//267 -f 1512//1512 267//267 1547//1547 -f 1547//1547 267//267 268//268 -f 1547//1547 268//268 1526//1526 -f 1526//1526 268//268 69//69 -f 1526//1526 69//69 1528//1528 -f 1528//1528 69//69 257//257 -f 1528//1528 257//257 1529//1529 -f 1529//1529 257//257 256//256 -f 1529//1529 256//256 1536//1536 -f 1536//1536 256//256 253//253 -f 1536//1536 253//253 1534//1534 -f 1534//1534 253//253 251//251 -f 1534//1534 251//251 1522//1522 -f 1522//1522 251//251 250//250 -f 1522//1522 250//250 1523//1523 -f 1523//1523 250//250 258//258 -f 1560//1560 284//284 1561//1561 -f 1561//1561 284//284 297//297 -f 1561//1561 297//297 1563//1563 -f 1563//1563 297//297 296//296 -f 1563//1563 296//296 1564//1564 -f 1564//1564 296//296 295//295 -f 1564//1564 295//295 1554//1554 -f 1554//1554 295//295 289//289 -f 1554//1554 289//289 1549//1549 -f 1549//1549 289//289 288//288 -f 1549//1549 288//288 1550//1550 -f 1550//1550 288//288 283//283 -f 1550//1550 283//283 1551//1551 -f 1551//1551 283//283 282//282 -f 1551//1551 282//282 1555//1555 -f 1555//1555 282//282 294//294 -f 1555//1555 294//294 1556//1556 -f 1556//1556 294//294 293//293 -f 1556//1556 293//293 1558//1558 -f 1558//1558 293//293 291//291 -f 1558//1558 291//291 1559//1559 -f 1559//1559 291//291 290//290 -f 1559//1559 290//290 1560//1560 -f 1560//1560 290//290 284//284 -f 2352//2352 978//978 2353//2353 -f 2353//2353 978//978 977//977 -f 2353//2353 977//977 2344//2344 -f 2344//2344 977//977 976//976 -f 2344//2344 976//976 2345//2345 -f 2345//2345 976//976 965//965 -f 2345//2345 965//965 2346//2346 -f 2346//2346 965//965 964//964 -f 2346//2346 964//964 2347//2347 -f 2347//2347 964//964 975//975 -f 2347//2347 975//975 2341//2341 -f 2341//2341 975//975 974//974 -f 2341//2341 974//974 2342//2342 -f 2342//2342 974//974 973//973 -f 2342//2342 973//973 2348//2348 -f 2348//2348 973//973 963//963 -f 2348//2348 963//963 2349//2349 -f 2349//2349 963//963 962//962 -f 2349//2349 962//962 2350//2350 -f 2350//2350 962//962 971//971 -f 2350//2350 971//971 2351//2351 -f 2351//2351 971//971 972//972 -f 2351//2351 972//972 2352//2352 -f 2352//2352 972//972 978//978 -f 2255//2255 1037//1037 2254//2254 -f 2254//2254 1037//1037 1036//1036 -f 2254//2254 1036//1036 2257//2257 -f 2257//2257 1036//1036 1035//1035 -f 2257//2257 1035//1035 2258//2258 -f 2258//2258 1035//1035 1034//1034 -f 2258//2258 1034//1034 2260//2260 -f 2260//2260 1034//1034 1033//1033 -f 2260//2260 1033//1033 2261//2261 -f 2261//2261 1033//1033 1042//1042 -f 2261//2261 1042//1042 2249//2249 -f 2249//2249 1042//1042 1041//1041 -f 2249//2249 1041//1041 2250//2250 -f 2250//2250 1041//1041 1040//1040 -f 2250//2250 1040//1040 2251//2251 -f 2251//2251 1040//1040 1031//1031 -f 2251//2251 1031//1031 2252//2252 -f 2252//2252 1031//1031 1030//1030 -f 2252//2252 1030//1030 2253//2253 -f 2253//2253 1030//1030 1039//1039 -f 2253//2253 1039//1039 2256//2256 -f 2256//2256 1039//1039 1038//1038 -f 2256//2256 1038//1038 2255//2255 -f 2255//2255 1038//1038 1037//1037 -f 2321//2321 980//980 2325//2325 -f 2325//2325 980//980 979//979 -f 2325//2325 979//979 2326//2326 -f 2326//2326 979//979 992//992 -f 2326//2326 992//992 2327//2327 -f 2327//2327 992//992 991//991 -f 2327//2327 991//991 2317//2317 -f 2317//2317 991//991 990//990 -f 2317//2317 990//990 2318//2318 -f 2318//2318 990//990 987//987 -f 2318//2318 987//987 2322//2322 -f 2322//2322 987//987 988//988 -f 2322//2322 988//988 2323//2323 -f 2323//2323 988//988 989//989 -f 2323//2323 989//989 2328//2328 -f 2328//2328 989//989 986//986 -f 2328//2328 986//986 2329//2329 -f 2329//2329 986//986 985//985 -f 2329//2329 985//985 2330//2330 -f 2330//2330 985//985 983//983 -f 2330//2330 983//983 2320//2320 -f 2320//2320 983//983 982//982 -f 2320//2320 982//982 2321//2321 -f 2321//2321 982//982 980//980 -f 1573//1573 305//305 1574//1574 -f 1574//1574 305//305 304//304 -f 1574//1574 304//304 1575//1575 -f 1575//1575 304//304 303//303 -f 1575//1575 303//303 1576//1576 -f 1576//1576 303//303 302//302 -f 1576//1576 302//302 1567//1567 -f 1567//1567 302//302 301//301 -f 1567//1567 301//301 1566//1566 -f 1566//1566 301//301 299//299 -f 1566//1566 299//299 1565//1565 -f 1565//1565 299//299 300//300 -f 1565//1565 300//300 1329//1329 -f 1329//1329 300//300 67//67 -f 1329//1329 67//67 1568//1568 -f 1568//1568 67//67 66//66 -f 1568//1568 66//66 1569//1569 -f 1569//1569 66//66 309//309 -f 1569//1569 309//309 1571//1571 -f 1571//1571 309//309 308//308 -f 1571//1571 308//308 1572//1572 -f 1572//1572 308//308 307//307 -f 1572//1572 307//307 1573//1573 -f 1573//1573 307//307 305//305 -f 1586//1586 323//323 1587//1587 -f 1587//1587 323//323 322//322 -f 1587//1587 322//322 1588//1588 -f 1588//1588 322//322 321//321 -f 1588//1588 321//321 1589//1589 -f 1589//1589 321//321 320//320 -f 1589//1589 320//320 1326//1326 -f 1326//1326 320//320 319//319 -f 1326//1326 319//319 1327//1327 -f 1327//1327 319//319 318//318 -f 1327//1327 318//318 1577//1577 -f 1577//1577 318//318 317//317 -f 1577//1577 317//317 1579//1579 -f 1579//1579 317//317 315//315 -f 1579//1579 315//315 1581//1581 -f 1581//1581 315//315 314//314 -f 1581//1581 314//314 1582//1582 -f 1582//1582 314//314 313//313 -f 1582//1582 313//313 1584//1584 -f 1584//1584 313//313 311//311 -f 1584//1584 311//311 1585//1585 -f 1585//1585 311//311 324//324 -f 1585//1585 324//324 1586//1586 -f 1586//1586 324//324 323//323 -f 2271//2271 1057//1057 2268//2268 -f 2268//2268 1057//1057 1053//1053 -f 2268//2268 1053//1053 2269//2269 -f 2269//2269 1053//1053 1052//1052 -f 2269//2269 1052//1052 2272//2272 -f 2272//2272 1052//1052 1051//1051 -f 2272//2272 1051//1051 2273//2273 -f 2273//2273 1051//1051 1054//1054 -f 2273//2273 1054//1054 2276//2276 -f 2276//2276 1054//1054 1065//1065 -f 2276//2276 1065//1065 2277//2277 -f 2277//2277 1065//1065 1064//1064 -f 2277//2277 1064//1064 2278//2278 -f 2278//2278 1064//1064 1063//1063 -f 2278//2278 1063//1063 2266//2266 -f 2266//2266 1063//1063 1062//1062 -f 2266//2266 1062//1062 2267//2267 -f 2267//2267 1062//1062 1061//1061 -f 2267//2267 1061//1061 2275//2275 -f 2275//2275 1061//1061 1059//1059 -f 2275//2275 1059//1059 2270//2270 -f 2270//2270 1059//1059 1058//1058 -f 2270//2270 1058//1058 2271//2271 -f 2271//2271 1058//1058 1057//1057 -f 2302//2302 1017//1017 2303//2303 -f 2303//2303 1017//1017 1016//1016 -f 2303//2303 1016//1016 2305//2305 -f 2305//2305 1016//1016 1013//1013 -f 2305//2305 1013//1013 2306//2306 -f 2306//2306 1013//1013 1014//1014 -f 2306//2306 1014//1014 2293//2293 -f 2293//2293 1014//1014 1015//1015 -f 2293//2293 1015//1015 2294//2294 -f 2294//2294 1015//1015 1006//1006 -f 2294//2294 1006//1006 2299//2299 -f 2299//2299 1006//1006 1007//1007 -f 2299//2299 1007//1007 2300//2300 -f 2300//2300 1007//1007 1012//1012 -f 2300//2300 1012//1012 2301//2301 -f 2301//2301 1012//1012 1011//1011 -f 2301//2301 1011//1011 2296//2296 -f 2296//2296 1011//1011 1010//1010 -f 2296//2296 1010//1010 2297//2297 -f 2297//2297 1010//1010 1009//1009 -f 2297//2297 1009//1009 2298//2298 -f 2298//2298 1009//1009 1019//1019 -f 2298//2298 1019//1019 2302//2302 -f 2302//2302 1019//1019 1017//1017 -f 1616//1616 534//534 1617//1617 -f 1617//1617 534//534 533//533 -f 1617//1617 533//533 1613//1613 -f 1613//1613 533//533 802//802 -f 1613//1613 802//802 1611//1611 -f 1611//1611 802//802 804//804 -f 1611//1611 804//804 1609//1609 -f 1609//1609 804//804 806//806 -f 1609//1609 806//806 1607//1607 -f 1607//1607 806//806 809//809 -f 799//799 2217//2217 797//797 -f 797//797 2217//2217 2312//2312 -f 797//797 2312//2312 795//795 -f 795//795 2312//2312 1658//1658 -f 795//795 1658//1658 793//793 -f 793//793 1658//1658 1657//1657 -f 793//793 1657//1657 792//792 -f 792//792 1657//1657 1660//1660 -f 792//792 1660//1660 790//790 -f 790//790 1660//1660 1664//1664 -f 534//534 1616//1616 539//539 -f 539//539 1616//1616 1615//1615 -f 539//539 1615//1615 538//538 -f 538//538 1615//1615 1318//1318 -f 538//538 1318//1318 18//18 -f 18//18 1318//1318 1317//1317 -f 810//810 1320//1320 15//15 -f 15//15 1320//1320 1604//1604 -f 15//15 1604//1604 16//16 -f 16//16 1604//1604 1603//1603 -f 16//16 1603//1603 809//809 -f 809//809 1603//1603 1607//1607 -f 572//572 1652//1652 573//573 -f 573//573 1652//1652 1653//1653 -f 573//573 1653//1653 575//575 -f 575//575 1653//1653 1313//1313 -f 575//575 1313//1313 799//799 -f 799//799 1313//1313 2217//2217 -f 790//790 1664//1664 788//788 -f 788//788 1664//1664 1662//1662 -f 788//788 1662//1662 784//784 -f 784//784 1662//1662 1661//1661 -f 784//784 1661//1661 785//785 -f 785//785 1661//1661 1665//1665 -f 1786//1786 413//413 1788//1788 -f 1788//1788 413//413 427//427 -f 1788//1788 427//427 1772//1772 -f 1772//1772 427//427 426//426 -f 1772//1772 426//426 1773//1773 -f 1773//1773 426//426 425//425 -f 1773//1773 425//425 1780//1780 -f 1780//1780 425//425 422//422 -f 1780//1780 422//422 1779//1779 -f 1779//1779 422//422 421//421 -f 1779//1779 421//421 1777//1777 -f 1777//1777 421//421 420//420 -f 1777//1777 420//420 1775//1775 -f 1775//1775 420//420 419//419 -f 1775//1775 419//419 1784//1784 -f 1784//1784 419//419 417//417 -f 1784//1784 417//417 1789//1789 -f 1789//1789 417//417 424//424 -f 1789//1789 424//424 1790//1790 -f 1790//1790 424//424 415//415 -f 1790//1790 415//415 1791//1791 -f 1791//1791 415//415 414//414 -f 1791//1791 414//414 1786//1786 -f 1786//1786 414//414 413//413 -f 1701//1701 345//345 1704//1704 -f 1704//1704 345//345 344//344 -f 1704//1704 344//344 1705//1705 -f 1705//1705 344//344 343//343 -f 1705//1705 343//343 1706//1706 -f 1706//1706 343//343 342//342 -f 1706//1706 342//342 1707//1707 -f 1707//1707 342//342 64//64 -f 1707//1707 64//64 1690//1690 -f 1690//1690 64//64 63//63 -f 1690//1690 63//63 1689//1689 -f 1689//1689 63//63 328//328 -f 1689//1689 328//328 1714//1714 -f 1714//1714 328//328 326//326 -f 1714//1714 326//326 1713//1713 -f 1713//1713 326//326 325//325 -f 1713//1713 325//325 1712//1712 -f 1712//1712 325//325 340//340 -f 1712//1712 340//340 1710//1710 -f 1710//1710 340//340 349//349 -f 1710//1710 349//349 1703//1703 -f 1703//1703 349//349 347//347 -f 1703//1703 347//347 1701//1701 -f 1701//1701 347//347 345//345 -f 1696//1696 337//337 1700//1700 -f 1700//1700 337//337 339//339 -f 1700//1700 339//339 1702//1702 -f 1702//1702 339//339 346//346 -f 1702//1702 346//346 1708//1708 -f 1708//1708 346//346 348//348 -f 1708//1708 348//348 1709//1709 -f 1709//1709 348//348 351//351 -f 1709//1709 351//351 1711//1711 -f 1711//1711 351//351 350//350 -f 1711//1711 350//350 1697//1697 -f 1697//1697 350//350 341//341 -f 1697//1697 341//341 1698//1698 -f 1698//1698 341//341 336//336 -f 1698//1698 336//336 1691//1691 -f 1691//1691 336//336 334//334 -f 1691//1691 334//334 1692//1692 -f 1692//1692 334//334 333//333 -f 1692//1692 333//333 1694//1694 -f 1694//1694 333//333 331//331 -f 1694//1694 331//331 1695//1695 -f 1695//1695 331//331 330//330 -f 1695//1695 330//330 1696//1696 -f 1696//1696 330//330 337//337 -f 1716//1716 360//360 1715//1715 -f 1715//1715 360//360 362//362 -f 1715//1715 362//362 1729//1729 -f 1729//1729 362//362 368//368 -f 1729//1729 368//368 1730//1730 -f 1730//1730 368//368 367//367 -f 1730//1730 367//367 1734//1734 -f 1734//1734 367//367 366//366 -f 1734//1734 366//366 1733//1733 -f 1733//1733 366//366 364//364 -f 1733//1733 364//364 1728//1728 -f 1728//1728 364//364 363//363 -f 1728//1728 363//363 1726//1726 -f 1726//1726 363//363 372//372 -f 1726//1726 372//372 1725//1725 -f 1725//1725 372//372 370//370 -f 1725//1725 370//370 1724//1724 -f 1724//1724 370//370 369//369 -f 1724//1724 369//369 1722//1722 -f 1722//1722 369//369 352//352 -f 1722//1722 352//352 1717//1717 -f 1717//1717 352//352 359//359 -f 1717//1717 359//359 1716//1716 -f 1716//1716 359//359 360//360 -f 1721//1721 354//354 1723//1723 -f 1723//1723 354//354 353//353 -f 1723//1723 353//353 1727//1727 -f 1727//1727 353//353 371//371 -f 1727//1727 371//371 1731//1731 -f 1731//1731 371//371 373//373 -f 1731//1731 373//373 1732//1732 -f 1732//1732 373//373 374//374 -f 1732//1732 374//374 1738//1738 -f 1738//1738 374//374 375//375 -f 1738//1738 375//375 1737//1737 -f 1737//1737 375//375 380//380 -f 1737//1737 380//380 1309//1309 -f 1309//1309 380//380 379//379 -f 1309//1309 379//379 1310//1310 -f 1310//1310 379//379 377//377 -f 1310//1310 377//377 1718//1718 -f 1718//1718 377//377 376//376 -f 1718//1718 376//376 1719//1719 -f 1719//1719 376//376 357//357 -f 1719//1719 357//357 1720//1720 -f 1720//1720 357//357 355//355 -f 1720//1720 355//355 1721//1721 -f 1721//1721 355//355 354//354 -f 1762//1762 394//394 1763//1763 -f 1763//1763 394//394 390//390 -f 1763//1763 390//390 1764//1764 -f 1764//1764 390//390 392//392 -f 1764//1764 392//392 1765//1765 -f 1765//1765 392//392 400//400 -f 1765//1765 400//400 1755//1755 -f 1755//1755 400//400 399//399 -f 1755//1755 399//399 1757//1757 -f 1757//1757 399//399 398//398 -f 1757//1757 398//398 1747//1747 -f 1747//1747 398//398 404//404 -f 1747//1747 404//404 1748//1748 -f 1748//1748 404//404 403//403 -f 1748//1748 403//403 1750//1750 -f 1750//1750 403//403 402//402 -f 1750//1750 402//402 1751//1751 -f 1751//1751 402//402 401//401 -f 1751//1751 401//401 1752//1752 -f 1752//1752 401//401 397//397 -f 1752//1752 397//397 1761//1761 -f 1761//1761 397//397 395//395 -f 1761//1761 395//395 1762//1762 -f 1762//1762 395//395 394//394 -f 1760//1760 391//391 1744//1744 -f 1744//1744 391//391 389//389 -f 1744//1744 389//389 1745//1745 -f 1745//1745 389//389 387//387 -f 1745//1745 387//387 1306//1306 -f 1306//1306 387//387 386//386 -f 1306//1306 386//386 1307//1307 -f 1307//1307 386//386 61//61 -f 1307//1307 61//61 1743//1743 -f 1743//1743 61//61 60//60 -f 1743//1743 60//60 1741//1741 -f 1741//1741 60//60 382//382 -f 1741//1741 382//382 1739//1739 -f 1739//1739 382//382 385//385 -f 1739//1739 385//385 1759//1759 -f 1759//1759 385//385 58//58 -f 1759//1759 58//58 1758//1758 -f 1758//1758 58//58 57//57 -f 1758//1758 57//57 1756//1756 -f 1756//1756 57//57 405//405 -f 1756//1756 405//405 1754//1754 -f 1754//1754 405//405 393//393 -f 1754//1754 393//393 1760//1760 -f 1760//1760 393//393 391//391 -f 1782//1782 423//423 1783//1783 -f 1783//1783 423//423 416//416 -f 1783//1783 416//416 1785//1785 -f 1785//1785 416//416 418//418 -f 1785//1785 418//418 1776//1776 -f 1776//1776 418//418 409//409 -f 1776//1776 409//409 1778//1778 -f 1778//1778 409//409 407//407 -f 1778//1778 407//407 1792//1792 -f 1792//1792 407//407 406//406 -f 1792//1792 406//406 1794//1794 -f 1794//1794 406//406 430//430 -f 1794//1794 430//430 1769//1769 -f 1769//1769 430//430 429//429 -f 1769//1769 429//429 1770//1770 -f 1770//1770 429//429 56//56 -f 1770//1770 56//56 1766//1766 -f 1766//1766 56//56 55//55 -f 1766//1766 55//55 1767//1767 -f 1767//1767 55//55 410//410 -f 1767//1767 410//410 1781//1781 -f 1781//1781 410//410 411//411 -f 1781//1781 411//411 1782//1782 -f 1782//1782 411//411 423//423 -f 1531//1531 1530//1530 261//261 -f 261//261 1530//1530 262//262 -f 1542//1542 1525//1525 249//249 -f 249//249 1525//1525 248//248 -f 1531//1531 261//261 1533//1533 -f 1533//1533 261//261 260//260 -f 1533//1533 260//260 1535//1535 -f 1535//1535 260//260 259//259 -f 1535//1535 259//259 1537//1537 -f 1537//1537 259//259 254//254 -f 1537//1537 254//254 1538//1538 -f 1538//1538 254//254 255//255 -f 1538//1538 255//255 1527//1527 -f 1527//1527 255//255 247//247 -f 1527//1527 247//247 1525//1525 -f 1525//1525 247//247 248//248 -f 1542//1542 249//249 1543//1543 -f 1543//1543 249//249 437//437 -f 1543//1543 437//437 1545//1545 -f 1545//1545 437//437 436//436 -f 1545//1545 436//436 1539//1539 -f 1539//1539 436//436 434//434 -f 1539//1539 434//434 1540//1540 -f 1540//1540 434//434 433//433 -f 1540//1540 433//433 1541//1541 -f 1541//1541 433//433 432//432 -f 1541//1541 432//432 1530//1530 -f 1530//1530 432//432 262//262 -f 2428//2428 870//870 2429//2429 -f 2429//2429 870//870 871//871 -f 2429//2429 871//871 2431//2431 -f 2431//2431 871//871 880//880 -f 2431//2431 880//880 2432//2432 -f 2432//2432 880//880 879//879 -f 2432//2432 879//879 2425//2425 -f 2425//2425 879//879 878//878 -f 2425//2425 878//878 2426//2426 -f 2426//2426 878//878 875//875 -f 2426//2426 875//875 2419//2419 -f 2419//2419 875//875 876//876 -f 2419//2419 876//876 2420//2420 -f 2420//2420 876//876 877//877 -f 2420//2420 877//877 2421//2421 -f 2421//2421 877//877 874//874 -f 2421//2421 874//874 2422//2422 -f 2422//2422 874//874 873//873 -f 2422//2422 873//873 2423//2423 -f 2423//2423 873//873 868//868 -f 2423//2423 868//868 2424//2424 -f 2424//2424 868//868 867//867 -f 2424//2424 867//867 2428//2428 -f 2428//2428 867//867 870//870 -f 1364//1364 1346//1346 233//233 -f 233//233 1346//1346 231//231 -f 1334//1334 1354//1354 238//238 -f 238//238 1354//1354 439//439 -f 1364//1364 233//233 1365//1365 -f 1365//1365 233//233 235//235 -f 1365//1365 235//235 2324//2324 -f 2324//2324 235//235 444//444 -f 2324//2324 444//444 1361//1361 -f 1361//1361 444//444 442//442 -f 1361//1361 442//442 1362//1362 -f 1362//1362 442//442 441//441 -f 1362//1362 441//441 1359//1359 -f 1359//1359 441//441 440//440 -f 1359//1359 440//440 1354//1354 -f 1354//1354 440//440 439//439 -f 1334//1334 238//238 1337//1337 -f 1337//1337 238//238 240//240 -f 1337//1337 240//240 1338//1338 -f 1338//1338 240//240 241//241 -f 1338//1338 241//241 1340//1340 -f 1340//1340 241//241 242//242 -f 1340//1340 242//242 1342//1342 -f 1342//1342 242//242 244//244 -f 1342//1342 244//244 1344//1344 -f 1344//1344 244//244 944//944 -f 1344//1344 944//944 1346//1346 -f 1346//1346 944//944 231//231 -f 2439//2439 892//892 2451//2451 -f 2451//2451 892//892 891//891 -f 2451//2451 891//891 2452//2452 -f 2452//2452 891//891 890//890 -f 2452//2452 890//890 2453//2453 -f 2453//2453 890//890 889//889 -f 2453//2453 889//889 2449//2449 -f 2449//2449 889//889 888//888 -f 2449//2449 888//888 2450//2450 -f 2450//2450 888//888 887//887 -f 2450//2450 887//887 2433//2433 -f 2433//2433 887//887 882//882 -f 2433//2433 882//882 2434//2434 -f 2434//2434 882//882 881//881 -f 2434//2434 881//881 2435//2435 -f 2435//2435 881//881 886//886 -f 2435//2435 886//886 2436//2436 -f 2436//2436 886//886 885//885 -f 2436//2436 885//885 2437//2437 -f 2437//2437 885//885 884//884 -f 2437//2437 884//884 2438//2438 -f 2438//2438 884//884 883//883 -f 2438//2438 883//883 2439//2439 -f 2439//2439 883//883 892//892 -f 1521//1521 276//276 1505//1505 -f 1505//1505 276//276 275//275 -f 1505//1505 275//275 1506//1506 -f 1506//1506 275//275 274//274 -f 1506//1506 274//274 1516//1516 -f 1516//1516 274//274 273//273 -f 1516//1516 273//273 1514//1514 -f 1514//1514 273//273 272//272 -f 1514//1514 272//272 1515//1515 -f 1515//1515 272//272 265//265 -f 1515//1515 265//265 1546//1546 -f 1546//1546 265//265 264//264 -f 1546//1546 264//264 1510//1510 -f 1510//1510 264//264 266//266 -f 1510//1510 266//266 1511//1511 -f 1511//1511 266//266 281//281 -f 1511//1511 281//281 1518//1518 -f 1518//1518 281//281 280//280 -f 1518//1518 280//280 1519//1519 -f 1519//1519 280//280 278//278 -f 1519//1519 278//278 1520//1520 -f 1520//1520 278//278 277//277 -f 1520//1520 277//277 1521//1521 -f 1521//1521 277//277 276//276 -f 1486//1486 221//221 1487//1487 -f 1487//1487 221//221 220//220 -f 1487//1487 220//220 1489//1489 -f 1489//1489 220//220 215//215 -f 1489//1489 215//215 1496//1496 -f 1496//1496 215//215 214//214 -f 1496//1496 214//214 1497//1497 -f 1497//1497 214//214 227//227 -f 1497//1497 227//227 1498//1498 -f 1498//1498 227//227 226//226 -f 1498//1498 226//226 1494//1494 -f 1494//1494 226//226 218//218 -f 1494//1494 218//218 1499//1499 -f 1499//1499 218//218 217//217 -f 1499//1499 217//217 1500//1500 -f 1500//1500 217//217 230//230 -f 1500//1500 230//230 1502//1502 -f 1502//1502 230//230 229//229 -f 1502//1502 229//229 1484//1484 -f 1484//1484 229//229 223//223 -f 1484//1484 223//223 1485//1485 -f 1485//1485 223//223 222//222 -f 1485//1485 222//222 1486//1486 -f 1486//1486 222//222 221//221 -f 2466//2466 823//823 2467//2467 -f 2467//2467 823//823 822//822 -f 2467//2467 822//822 2468//2468 -f 2468//2468 822//822 821//821 -f 2468//2468 821//821 2469//2469 -f 2469//2469 821//821 820//820 -f 2469//2469 820//820 2470//2470 -f 2470//2470 820//820 818//818 -f 2470//2470 818//818 2471//2471 -f 2471//2471 818//818 829//829 -f 2471//2471 829//829 2472//2472 -f 2472//2472 829//829 828//828 -f 2472//2472 828//828 2461//2461 -f 2461//2461 828//828 827//827 -f 2461//2461 827//827 2462//2462 -f 2462//2462 827//827 817//817 -f 2462//2462 817//817 2463//2463 -f 2463//2463 817//817 816//816 -f 2463//2463 816//816 2464//2464 -f 2464//2464 816//816 826//826 -f 2464//2464 826//826 2465//2465 -f 2465//2465 826//826 825//825 -f 2465//2465 825//825 2466//2466 -f 2466//2466 825//825 823//823 -f 1683//1683 451//451 1684//1684 -f 1684//1684 451//451 453//453 -f 1684//1684 453//453 1682//1682 -f 1682//1682 453//453 455//455 -f 1682//1682 455//455 1681//1681 -f 1681//1681 455//455 457//457 -f 1681//1681 457//457 1796//1796 -f 1796//1796 457//457 465//465 -f 1796//1796 465//465 1797//1797 -f 1797//1797 465//465 464//464 -f 1797//1797 464//464 2418//2418 -f 2418//2418 464//464 461//461 -f 2418//2418 461//461 1674//1674 -f 1674//1674 461//461 460//460 -f 1674//1674 460//460 1673//1673 -f 1673//1673 460//460 448//448 -f 1673//1673 448//448 1671//1671 -f 1671//1671 448//448 446//446 -f 1671//1671 446//446 1675//1675 -f 1675//1675 446//446 445//445 -f 1675//1675 445//445 1676//1676 -f 1676//1676 445//445 449//449 -f 1676//1676 449//449 1683//1683 -f 1683//1683 449//449 451//451 -f 2382//2382 902//902 2374//2374 -f 2374//2374 902//902 901//901 -f 2374//2374 901//901 2375//2375 -f 2375//2375 901//901 899//899 -f 2375//2375 899//899 2383//2383 -f 2383//2383 899//899 898//898 -f 2383//2383 898//898 2384//2384 -f 2384//2384 898//898 908//908 -f 2384//2384 908//908 2386//2386 -f 2386//2386 908//908 907//907 -f 2386//2386 907//907 2387//2387 -f 2387//2387 907//907 905//905 -f 2387//2387 905//905 2377//2377 -f 2377//2377 905//905 904//904 -f 2377//2377 904//904 2378//2378 -f 2378//2378 904//904 903//903 -f 2378//2378 903//903 2379//2379 -f 2379//2379 903//903 911//911 -f 2379//2379 911//911 2380//2380 -f 2380//2380 911//911 910//910 -f 2380//2380 910//910 2381//2381 -f 2381//2381 910//910 909//909 -f 2381//2381 909//909 2382//2382 -f 2382//2382 909//909 902//902 -f 1800//1800 467//467 1801//1801 -f 1801//1801 467//467 466//466 -f 1801//1801 466//466 1809//1809 -f 1809//1809 466//466 477//477 -f 1809//1809 477//477 1802//1802 -f 1802//1802 477//477 476//476 -f 1802//1802 476//476 1803//1803 -f 1803//1803 476//476 479//479 -f 1803//1803 479//479 1813//1813 -f 1813//1813 479//479 471//471 -f 1813//1813 471//471 1812//1812 -f 1812//1812 471//471 470//470 -f 1812//1812 470//470 1811//1811 -f 1811//1811 470//470 475//475 -f 1811//1811 475//475 1805//1805 -f 1805//1805 475//475 474//474 -f 1805//1805 474//474 1806//1806 -f 1806//1806 474//474 473//473 -f 1806//1806 473//473 1808//1808 -f 1808//1808 473//473 472//472 -f 1808//1808 472//472 1799//1799 -f 1799//1799 472//472 468//468 -f 1799//1799 468//468 1800//1800 -f 1800//1800 468//468 467//467 -f 2281//2281 1074//1074 2280//2280 -f 2280//2280 1074//1074 1073//1073 -f 2280//2280 1073//1073 2279//2279 -f 2279//2279 1073//1073 1072//1072 -f 2279//2279 1072//1072 2282//2282 -f 2282//2282 1072//1072 1071//1071 -f 2282//2282 1071//1071 2283//2283 -f 2283//2283 1071//1071 1068//1068 -f 2283//2283 1068//1068 2288//2288 -f 2288//2288 1068//1068 1069//1069 -f 2288//2288 1069//1069 2287//2287 -f 2287//2287 1069//1069 1070//1070 -f 2287//2287 1070//1070 2286//2286 -f 2286//2286 1070//1070 1078//1078 -f 2286//2286 1078//1078 2289//2289 -f 2289//2289 1078//1078 1077//1077 -f 2289//2289 1077//1077 2290//2290 -f 2290//2290 1077//1077 1076//1076 -f 2290//2290 1076//1076 2291//2291 -f 2291//2291 1076//1076 1067//1067 -f 2291//2291 1067//1067 2285//2285 -f 2285//2285 1067//1067 1075//1075 -f 2285//2285 1075//1075 2281//2281 -f 2281//2281 1075//1075 1074//1074 -f 1823//1823 490//490 1825//1825 -f 1825//1825 490//490 489//489 -f 1825//1825 489//489 1826//1826 -f 1826//1826 489//489 487//487 -f 1826//1826 487//487 1827//1827 -f 1827//1827 487//487 486//486 -f 1827//1827 486//486 1828//1828 -f 1828//1828 486//486 485//485 -f 1828//1828 485//485 1816//1816 -f 1816//1816 485//485 484//484 -f 1816//1816 484//484 1818//1818 -f 1818//1818 484//484 481//481 -f 1818//1818 481//481 1817//1817 -f 1817//1817 481//481 480//480 -f 1817//1817 480//480 1819//1819 -f 1819//1819 480//480 495//495 -f 1819//1819 495//495 1820//1820 -f 1820//1820 495//495 496//496 -f 1820//1820 496//496 1821//1821 -f 1821//1821 496//496 493//493 -f 1821//1821 493//493 1822//1822 -f 1822//1822 493//493 492//492 -f 1822//1822 492//492 1823//1823 -f 1823//1823 492//492 490//490 -f 1835//1835 511//511 1837//1837 -f 1837//1837 511//511 509//509 -f 1837//1837 509//509 1839//1839 -f 1839//1839 509//509 515//515 -f 1839//1839 515//515 1840//1840 -f 1840//1840 515//515 514//514 -f 1840//1840 514//514 1595//1595 -f 1595//1595 514//514 513//513 -f 1595//1595 513//513 1597//1597 -f 1597//1597 513//513 499//499 -f 1597//1597 499//499 1590//1590 -f 1590//1590 499//499 501//501 -f 1590//1590 501//501 1591//1591 -f 1591//1591 501//501 503//503 -f 1591//1591 503//503 1829//1829 -f 1829//1829 503//503 504//504 -f 1829//1829 504//504 1830//1830 -f 1830//1830 504//504 506//506 -f 1830//1830 506//506 1832//1832 -f 1832//1832 506//506 505//505 -f 1832//1832 505//505 1833//1833 -f 1833//1833 505//505 896//896 -f 1833//1833 896//896 1835//1835 -f 1835//1835 896//896 511//511 -f 2506//2506 864//864 2505//2505 -f 2505//2505 864//864 863//863 -f 2505//2505 863//863 2508//2508 -f 2508//2508 863//863 862//862 -f 2508//2508 862//862 2509//2509 -f 2509//2509 862//862 861//861 -f 2509//2509 861//861 2511//2511 -f 2511//2511 861//861 860//860 -f 2511//2511 860//860 2512//2512 -f 2512//2512 860//860 859//859 -f 2512//2512 859//859 2513//2513 -f 2513//2513 859//859 857//857 -f 2513//2513 857//857 2514//2514 -f 2514//2514 857//857 856//856 -f 2514//2514 856//856 2504//2504 -f 2504//2504 856//856 854//854 -f 2504//2504 854//854 2499//2499 -f 2499//2499 854//854 853//853 -f 2499//2499 853//853 2500//2500 -f 2500//2500 853//853 866//866 -f 2500//2500 866//866 2507//2507 -f 2507//2507 866//866 865//865 -f 2507//2507 865//865 2506//2506 -f 2506//2506 865//865 864//864 -f 519//519 1315//1315 1181//1181 -f 1181//1181 1315//1315 1314//1314 -f 1181//1181 1314//1314 525//525 -f 525//525 1314//1314 1644//1644 -f 525//525 1644//1644 526//526 -f 526//526 1644//1644 1643//1643 -f 526//526 1643//1643 527//527 -f 527//527 1643//1643 1642//1642 -f 527//527 1642//1642 528//528 -f 528//528 1642//1642 1636//1636 -f 528//528 1636//1636 530//530 -f 530//530 1636//1636 1638//1638 -f 530//530 1638//1638 531//531 -f 531//531 1638//1638 1640//1640 -f 531//531 1640//1640 522//522 -f 522//522 1640//1640 1641//1641 -f 522//522 1641//1641 523//523 -f 523//523 1641//1641 1632//1632 -f 523//523 1632//1632 516//516 -f 516//516 1632//1632 1631//1631 -f 516//516 1631//1631 517//517 -f 517//517 1631//1631 2224//2224 -f 517//517 2224//2224 519//519 -f 519//519 2224//2224 1315//1315 -f 1210//1210 2120//2120 1211//1211 -f 1211//1211 2120//2120 2119//2119 -f 1211//1211 2119//2119 1212//1212 -f 1212//1212 2119//2119 2117//2117 -f 1212//1212 2117//2117 1213//1213 -f 1213//1213 2117//2117 2116//2116 -f 1213//1213 2116//2116 1214//1214 -f 1214//1214 2116//2116 2129//2129 -f 1214//1214 2129//2129 1215//1215 -f 1215//1215 2129//2129 2128//2128 -f 1215//1215 2128//2128 1202//1202 -f 1202//1202 2128//2128 2126//2126 -f 1202//1202 2126//2126 1203//1203 -f 1203//1203 2126//2126 2125//2125 -f 1203//1203 2125//2125 1205//1205 -f 1205//1205 2125//2125 2122//2122 -f 1205//1205 2122//2122 1207//1207 -f 1207//1207 2122//2122 2123//2123 -f 1207//1207 2123//2123 1208//1208 -f 1208//1208 2123//2123 2124//2124 -f 1208//1208 2124//2124 1209//1209 -f 1209//1209 2124//2124 2121//2121 -f 1209//1209 2121//2121 1210//1210 -f 1210//1210 2121//2121 2120//2120 -f 537//537 1622//1622 542//542 -f 542//542 1622//1622 1621//1621 -f 542//542 1621//1621 543//543 -f 543//543 1621//1621 1618//1618 -f 543//543 1618//1618 544//544 -f 544//544 1618//1618 1619//1619 -f 544//544 1619//1619 541//541 -f 541//541 1619//1619 1620//1620 -f 541//541 1620//1620 540//540 -f 540//540 1620//1620 2413//2413 -f 540//540 2413//2413 53//53 -f 53//53 2413//2413 1846//1846 -f 53//53 1846//1846 51//51 -f 51//51 1846//1846 1844//1844 -f 51//51 1844//1844 549//549 -f 549//549 1844//1844 1842//1842 -f 549//549 1842//1842 547//547 -f 547//547 1842//1842 1841//1841 -f 547//547 1841//1841 545//545 -f 545//545 1841//1841 2183//2183 -f 545//545 2183//2183 536//536 -f 536//536 2183//2183 1623//1623 -f 536//536 1623//1623 537//537 -f 537//537 1623//1623 1622//1622 -f 559//559 1851//1851 564//564 -f 564//564 1851//1851 1858//1858 -f 564//564 1858//1858 565//565 -f 565//565 1858//1858 1856//1856 -f 565//565 1856//1856 566//566 -f 566//566 1856//1856 1855//1855 -f 566//566 1855//1855 562//562 -f 562//562 1855//1855 1850//1850 -f 562//562 1850//1850 563//563 -f 563//563 1850//1850 1848//1848 -f 563//563 1848//1848 551//551 -f 551//551 1848//1848 1304//1304 -f 551//551 1304//1304 553//553 -f 553//553 1304//1304 1303//1303 -f 553//553 1303//1303 554//554 -f 554//554 1303//1303 1847//1847 -f 554//554 1847//1847 555//555 -f 555//555 1847//1847 1854//1854 -f 555//555 1854//1854 557//557 -f 557//557 1854//1854 1853//1853 -f 557//557 1853//1853 558//558 -f 558//558 1853//1853 1852//1852 -f 558//558 1852//1852 559//559 -f 559//559 1852//1852 1851//1851 -f 569//569 1302//1302 574//574 -f 574//574 1302//1302 1312//1312 -f 574//574 1312//1312 578//578 -f 578//578 1312//1312 1655//1655 -f 578//578 1655//1655 576//576 -f 576//576 1655//1655 1654//1654 -f 576//576 1654//1654 581//581 -f 581//581 1654//1654 1650//1650 -f 581//581 1650//1650 582//582 -f 582//582 1650//1650 1648//1648 -f 582//582 1648//1648 584//584 -f 584//584 1648//1648 1646//1646 -f 584//584 1646//1646 585//585 -f 585//585 1646//1646 1864//1864 -f 585//585 1864//1864 586//586 -f 586//586 1864//1864 1863//1863 -f 586//586 1863//1863 587//587 -f 587//587 1863//1863 1861//1861 -f 587//587 1861//1861 570//570 -f 570//570 1861//1861 1859//1859 -f 570//570 1859//1859 571//571 -f 571//571 1859//1859 1300//1300 -f 571//571 1300//1300 569//569 -f 569//569 1300//1300 1302//1302 -f 1184//1184 2102//2102 1182//1182 -f 1182//1182 2102//2102 2101//2101 -f 1182//1182 2101//2101 1183//1183 -f 1183//1183 2101//2101 2100//2100 -f 1183//1183 2100//2100 1188//1188 -f 1188//1188 2100//2100 2115//2115 -f 1188//1188 2115//2115 1189//1189 -f 1189//1189 2115//2115 2114//2114 -f 1189//1189 2114//2114 1190//1190 -f 1190//1190 2114//2114 2113//2113 -f 1190//1190 2113//2113 1191//1191 -f 1191//1191 2113//2113 2110//2110 -f 1191//1191 2110//2110 1193//1193 -f 1193//1193 2110//2110 2109//2109 -f 1193//1193 2109//2109 1194//1194 -f 1194//1194 2109//2109 2108//2108 -f 1194//1194 2108//2108 1195//1195 -f 1195//1195 2108//2108 2105//2105 -f 1195//1195 2105//2105 1187//1187 -f 1187//1187 2105//2105 2104//2104 -f 1187//1187 2104//2104 1186//1186 -f 1186//1186 2104//2104 2103//2103 -f 1186//1186 2103//2103 1184//1184 -f 1184//1184 2103//2103 2102//2102 -f 190//190 1865//1865 192//192 -f 192//192 1865//1865 1448//1448 -f 192//192 1448//1448 196//196 -f 196//196 1448//1448 1447//1447 -f 196//196 1447//1447 195//195 -f 195//195 1447//1447 1446//1446 -f 195//195 1446//1446 193//193 -f 193//193 1446//1446 1444//1444 -f 193//193 1444//1444 197//197 -f 197//197 1444//1444 1443//1443 -f 197//197 1443//1443 75//75 -f 75//75 1443//1443 1442//1442 -f 75//75 1442//1442 76//76 -f 76//76 1442//1442 1441//1441 -f 76//76 1441//1441 588//588 -f 588//588 1441//1441 1870//1870 -f 588//588 1870//1870 589//589 -f 589//589 1870//1870 1869//1869 -f 589//589 1869//1869 591//591 -f 591//591 1869//1869 1868//1868 -f 591//591 1868//1868 592//592 -f 592//592 1868//1868 1866//1866 -f 592//592 1866//1866 190//190 -f 190//190 1866//1866 1865//1865 -f 127//127 1872//1872 129//129 -f 129//129 1872//1872 1431//1431 -f 129//129 1431//1431 130//130 -f 130//130 1431//1431 1430//1430 -f 130//130 1430//1430 131//131 -f 131//131 1430//1430 1429//1429 -f 131//131 1429//1429 136//136 -f 136//136 1429//1429 1428//1428 -f 136//136 1428//1428 135//135 -f 135//135 1428//1428 1427//1427 -f 135//135 1427//1427 133//133 -f 133//133 1427//1427 1426//1426 -f 133//133 1426//1426 593//593 -f 593//593 1426//1426 1298//1298 -f 593//593 1298//1298 594//594 -f 594//594 1298//1298 1297//1297 -f 594//594 1297//1297 596//596 -f 596//596 1297//1297 1876//1876 -f 596//596 1876//1876 124//124 -f 124//124 1876//1876 1875//1875 -f 124//124 1875//1875 125//125 -f 125//125 1875//1875 1873//1873 -f 125//125 1873//1873 127//127 -f 127//127 1873//1873 1872//1872 -f 598//598 1896//1896 599//599 -f 599//599 1896//1896 1895//1895 -f 599//599 1895//1895 601//601 -f 601//601 1895//1895 1889//1889 -f 601//601 1889//1889 602//602 -f 602//602 1889//1889 1891//1891 -f 602//602 1891//1891 615//615 -f 615//615 1891//1891 1893//1893 -f 615//615 1893//1893 614//614 -f 614//614 1893//1893 1894//1894 -f 614//614 1894//1894 612//612 -f 612//612 1894//1894 1880//1880 -f 612//612 1880//1880 611//611 -f 611//611 1880//1880 1879//1879 -f 611//611 1879//1879 928//928 -f 928//928 1879//1879 1882//1882 -f 928//928 1882//1882 608//608 -f 608//608 1882//1882 1884//1884 -f 608//608 1884//1884 606//606 -f 606//606 1884//1884 1886//1886 -f 606//606 1886//1886 604//604 -f 604//604 1886//1886 1888//1888 -f 604//604 1888//1888 598//598 -f 598//598 1888//1888 1896//1896 -f 618//618 1911//1911 620//620 -f 620//620 1911//1911 1910//1910 -f 620//620 1910//1910 621//621 -f 621//621 1910//1910 1907//1907 -f 621//621 1907//1907 623//623 -f 623//623 1907//1907 1904//1904 -f 623//623 1904//1904 625//625 -f 625//625 1904//1904 1903//1903 -f 625//625 1903//1903 626//626 -f 626//626 1903//1903 1902//1902 -f 626//626 1902//1902 48//48 -f 48//48 1902//1902 1900//1900 -f 48//48 1900//1900 49//49 -f 49//49 1900//1900 1899//1899 -f 49//49 1899//1899 630//630 -f 630//630 1899//1899 1905//1905 -f 630//630 1905//1905 629//629 -f 629//629 1905//1905 1295//1295 -f 629//629 1295//1295 627//627 -f 627//627 1295//1295 1294//1294 -f 627//627 1294//1294 617//617 -f 617//617 1294//1294 1913//1913 -f 617//617 1913//1913 618//618 -f 618//618 1913//1913 1911//1911 -f 845//845 2483//2483 846//846 -f 846//846 2483//2483 2482//2482 -f 846//846 2482//2482 847//847 -f 847//847 2482//2482 2479//2479 -f 847//847 2479//2479 848//848 -f 848//848 2479//2479 2480//2480 -f 848//848 2480//2480 849//849 -f 849//849 2480//2480 2481//2481 -f 849//849 2481//2481 850//850 -f 850//850 2481//2481 2474//2474 -f 850//850 2474//2474 851//851 -f 851//851 2474//2474 2473//2473 -f 851//851 2473//2473 852//852 -f 852//852 2473//2473 2478//2478 -f 852//852 2478//2478 841//841 -f 841//841 2478//2478 2477//2477 -f 841//841 2477//2477 842//842 -f 842//842 2477//2477 2476//2476 -f 842//842 2476//2476 843//843 -f 843//843 2476//2476 2485//2485 -f 843//843 2485//2485 844//844 -f 844//844 2485//2485 2484//2484 -f 844//844 2484//2484 845//845 -f 845//845 2484//2484 2483//2483 -f 636//636 1930//1930 638//638 -f 638//638 1930//1930 1927//1927 -f 638//638 1927//1927 642//642 -f 642//642 1927//1927 1925//1925 -f 642//642 1925//1925 643//643 -f 643//643 1925//1925 1924//1924 -f 643//643 1924//1924 644//644 -f 644//644 1924//1924 1916//1916 -f 644//644 1916//1916 645//645 -f 645//645 1916//1916 1923//1923 -f 645//645 1923//1923 640//640 -f 640//640 1923//1923 1922//1922 -f 640//640 1922//1922 641//641 -f 641//641 1922//1922 1921//1921 -f 641//641 1921//1921 646//646 -f 646//646 1921//1921 1917//1917 -f 646//646 1917//1917 647//647 -f 647//647 1917//1917 1918//1918 -f 647//647 1918//1918 633//633 -f 633//633 1918//1918 1920//1920 -f 633//633 1920//1920 634//634 -f 634//634 1920//1920 1928//1928 -f 634//634 1928//1928 636//636 -f 636//636 1928//1928 1930//1930 -f 657//657 1942//1942 655//655 -f 655//655 1942//1942 1940//1940 -f 655//655 1940//1940 653//653 -f 653//653 1940//1940 1939//1939 -f 653//653 1939//1939 662//662 -f 662//662 1939//1939 1947//1947 -f 662//662 1947//1947 660//660 -f 660//660 1947//1947 1949//1949 -f 660//660 1949//1949 658//658 -f 658//658 1949//1949 1950//1950 -f 658//658 1950//1950 42//42 -f 42//42 1950//1950 1934//1934 -f 42//42 1934//1934 43//43 -f 43//43 1934//1934 1932//1932 -f 43//43 1932//1932 649//649 -f 649//649 1932//1932 1931//1931 -f 649//649 1931//1931 651//651 -f 651//651 1931//1931 1938//1938 -f 651//651 1938//1938 45//45 -f 45//45 1938//1938 1945//1945 -f 45//45 1945//1945 46//46 -f 46//46 1945//1945 1944//1944 -f 46//46 1944//1944 657//657 -f 657//657 1944//1944 1942//1942 -f 663//663 1965//1965 664//664 -f 664//664 1965//1965 1964//1964 -f 664//664 1964//1964 39//39 -f 39//39 1964//1964 1959//1959 -f 39//39 1959//1959 40//40 -f 40//40 1959//1959 1958//1958 -f 40//40 1958//1958 669//669 -f 669//669 1958//1958 1956//1956 -f 669//669 1956//1956 666//666 -f 666//666 1956//1956 1955//1955 -f 666//666 1955//1955 667//667 -f 667//667 1955//1955 1953//1953 -f 667//667 1953//1953 670//670 -f 670//670 1953//1953 1954//1954 -f 670//670 1954//1954 672//672 -f 672//672 1954//1954 1963//1963 -f 672//672 1963//1963 674//674 -f 674//674 1963//1963 1962//1962 -f 674//674 1962//1962 675//675 -f 675//675 1962//1962 1960//1960 -f 675//675 1960//1960 665//665 -f 665//665 1960//1960 1966//1966 -f 665//665 1966//1966 663//663 -f 663//663 1966//1966 1965//1965 -f 1152//1152 2150//2150 1153//1153 -f 1153//1153 2150//2150 2149//2149 -f 1153//1153 2149//2149 1154//1154 -f 1154//1154 2149//2149 2147//2147 -f 1154//1154 2147//2147 1155//1155 -f 1155//1155 2147//2147 2146//2146 -f 1155//1155 2146//2146 1156//1156 -f 1156//1156 2146//2146 2152//2152 -f 1156//1156 2152//2152 1144//1144 -f 1144//1144 2152//2152 2155//2155 -f 1144//1144 2155//2155 1145//1145 -f 1145//1145 2155//2155 2154//2154 -f 1145//1145 2154//2154 1146//1146 -f 1146//1146 2154//2154 2153//2153 -f 1146//1146 2153//2153 1147//1147 -f 1147//1147 2153//2153 2148//2148 -f 1147//1147 2148//2148 1149//1149 -f 1149//1149 2148//2148 2145//2145 -f 1149//1149 2145//2145 1150//1150 -f 1150//1150 2145//2145 2144//2144 -f 1150//1150 2144//2144 1151//1151 -f 1151//1151 2144//2144 2151//2151 -f 1151//1151 2151//2151 1152//1152 -f 1152//1152 2151//2151 2150//2150 -f 680//680 1977//1977 678//678 -f 678//678 1977//1977 1976//1976 -f 678//678 1976//1976 36//36 -f 36//36 1976//1976 1975//1975 -f 36//36 1975//1975 37//37 -f 37//37 1975//1975 1973//1973 -f 37//37 1973//1973 686//686 -f 686//686 1973//1973 1971//1971 -f 686//686 1971//1971 687//687 -f 687//687 1971//1971 1970//1970 -f 687//687 1970//1970 682//682 -f 682//682 1970//1970 1969//1969 -f 682//682 1969//1969 683//683 -f 683//683 1969//1969 1984//1984 -f 683//683 1984//1984 689//689 -f 689//689 1984//1984 1983//1983 -f 689//689 1983//1983 676//676 -f 676//676 1983//1983 1981//1981 -f 676//676 1981//1981 677//677 -f 677//677 1981//1981 1979//1979 -f 677//677 1979//1979 681//681 -f 681//681 1979//1979 1978//1978 -f 681//681 1978//1978 680//680 -f 680//680 1978//1978 1977//1977 -f 755//755 2061//2061 754//754 -f 754//754 2061//2061 2056//2056 -f 754//754 2056//2056 762//762 -f 762//762 2056//2056 2055//2055 -f 762//762 2055//2055 763//763 -f 763//763 2055//2055 2071//2071 -f 763//763 2071//2071 764//764 -f 764//764 2071//2071 2070//2070 -f 764//764 2070//2070 761//761 -f 761//761 2070//2070 2069//2069 -f 761//761 2069//2069 760//760 -f 760//760 2069//2069 2068//2068 -f 760//760 2068//2068 749//749 -f 749//749 2068//2068 2067//2067 -f 749//749 2067//2067 750//750 -f 750//750 2067//2067 2066//2066 -f 750//750 2066//2066 759//759 -f 759//759 2066//2066 2065//2065 -f 759//759 2065//2065 758//758 -f 758//758 2065//2065 2064//2064 -f 758//758 2064//2064 756//756 -f 756//756 2064//2064 2062//2062 -f 756//756 2062//2062 755//755 -f 755//755 2062//2062 2061//2061 -f 1422//1422 138//138 1423//1423 -f 1423//1423 138//138 137//137 -f 1423//1423 137//137 1424//1424 -f 1424//1424 137//137 152//152 -f 1424//1424 152//152 1425//1425 -f 1425//1425 152//152 151//151 -f 1425//1425 151//151 1418//1418 -f 1418//1418 151//151 150//150 -f 1418//1418 150//150 1419//1419 -f 1419//1419 150//150 147//147 -f 1419//1419 147//147 1412//1412 -f 1412//1412 147//147 148//148 -f 1412//1412 148//148 1413//1413 -f 1413//1413 148//148 149//149 -f 1413//1413 149//149 1417//1417 -f 1417//1417 149//149 143//143 -f 1417//1417 143//143 1416//1416 -f 1416//1416 143//143 142//142 -f 1416//1416 142//142 1414//1414 -f 1414//1414 142//142 141//141 -f 1414//1414 141//141 1421//1421 -f 1421//1421 141//141 140//140 -f 1421//1421 140//140 1422//1422 -f 1422//1422 140//140 138//138 -f 1996//1996 692//692 1997//1997 -f 1997//1997 692//692 702//702 -f 1997//1997 702//702 2000//2000 -f 2000//2000 702//702 701//701 -f 2000//2000 701//701 1999//1999 -f 1999//1999 701//701 706//706 -f 1999//1999 706//706 1998//1998 -f 1998//1998 706//706 705//705 -f 1998//1998 705//705 1986//1986 -f 1986//1986 705//705 704//704 -f 1986//1986 704//704 1987//1987 -f 1987//1987 704//704 703//703 -f 1987//1987 703//703 1989//1989 -f 1989//1989 703//703 699//699 -f 1989//1989 699//699 1990//1990 -f 1990//1990 699//699 698//698 -f 1990//1990 698//698 1991//1991 -f 1991//1991 698//698 696//696 -f 1991//1991 696//696 1992//1992 -f 1992//1992 696//696 695//695 -f 1992//1992 695//695 1994//1994 -f 1994//1994 695//695 694//694 -f 1994//1994 694//694 1996//1996 -f 1996//1996 694//694 692//692 -f 2006//2006 719//719 2007//2007 -f 2007//2007 719//719 718//718 -f 2007//2007 718//718 2008//2008 -f 2008//2008 718//718 716//716 -f 2008//2008 716//716 2009//2009 -f 2009//2009 716//716 715//715 -f 2009//2009 715//715 2010//2010 -f 2010//2010 715//715 34//34 -f 2010//2010 34//34 2012//2012 -f 2012//2012 34//34 33//33 -f 2012//2012 33//33 2014//2014 -f 2014//2014 33//33 708//708 -f 2014//2014 708//708 2013//2013 -f 2013//2013 708//708 714//714 -f 2013//2013 714//714 2004//2004 -f 2004//2004 714//714 713//713 -f 2004//2004 713//713 2003//2003 -f 2003//2003 713//713 712//712 -f 2003//2003 712//712 2001//2001 -f 2001//2001 712//712 710//710 -f 2001//2001 710//710 2005//2005 -f 2005//2005 710//710 709//709 -f 2005//2005 709//709 2006//2006 -f 2006//2006 709//709 719//719 -f 1463//1463 164//164 1464//1464 -f 1464//1464 164//164 166//166 -f 1464//1464 166//166 1451//1451 -f 1451//1451 166//166 185//185 -f 1451//1451 185//185 1452//1452 -f 1452//1452 185//185 184//184 -f 1452//1452 184//184 2226//2226 -f 2226//2226 184//184 175//175 -f 2226//2226 175//175 1453//1453 -f 1453//1453 175//175 174//174 -f 1453//1453 174//174 1454//1454 -f 1454//1454 174//174 172//172 -f 1454//1454 172//172 1456//1456 -f 1456//1456 172//172 171//171 -f 1456//1456 171//171 1458//1458 -f 1458//1458 171//171 167//167 -f 1458//1458 167//167 1459//1459 -f 1459//1459 167//167 169//169 -f 1459//1459 169//169 1461//1461 -f 1461//1461 169//169 170//170 -f 1461//1461 170//170 1462//1462 -f 1462//1462 170//170 162//162 -f 1462//1462 162//162 1463//1463 -f 1463//1463 162//162 164//164 -f 2019//2019 723//723 2020//2020 -f 2020//2020 723//723 721//721 -f 2020//2020 721//721 2023//2023 -f 2023//2023 721//721 31//31 -f 2023//2023 31//31 2024//2024 -f 2024//2024 31//31 30//30 -f 2024//2024 30//30 2031//2031 -f 2031//2031 30//30 727//727 -f 2031//2031 727//727 2032//2032 -f 2032//2032 727//727 729//729 -f 2032//2032 729//729 2026//2026 -f 2026//2026 729//729 733//733 -f 2026//2026 733//733 2027//2027 -f 2027//2027 733//733 732//732 -f 2027//2027 732//732 2029//2029 -f 2029//2029 732//732 730//730 -f 2029//2029 730//730 2030//2030 -f 2030//2030 730//730 726//726 -f 2030//2030 726//726 2016//2016 -f 2016//2016 726//726 725//725 -f 2016//2016 725//725 2018//2018 -f 2018//2018 725//725 724//724 -f 2018//2018 724//724 2019//2019 -f 2019//2019 724//724 723//723 -f 2044//2044 737//737 2045//2045 -f 2045//2045 737//737 735//735 -f 2045//2045 735//735 2046//2046 -f 2046//2046 735//735 734//734 -f 2046//2046 734//734 2047//2047 -f 2047//2047 734//734 747//747 -f 2047//2047 747//747 2043//2043 -f 2043//2043 747//747 748//748 -f 2043//2043 748//748 2033//2033 -f 2033//2033 748//748 746//746 -f 2033//2033 746//746 2034//2034 -f 2034//2034 746//746 739//739 -f 2034//2034 739//739 2038//2038 -f 2038//2038 739//739 738//738 -f 2038//2038 738//738 2036//2036 -f 2036//2036 738//738 745//745 -f 2036//2036 745//745 2037//2037 -f 2037//2037 745//745 743//743 -f 2037//2037 743//743 2039//2039 -f 2039//2039 743//743 742//742 -f 2039//2039 742//742 2041//2041 -f 2041//2041 742//742 740//740 -f 2041//2041 740//740 2044//2044 -f 2044//2044 740//740 737//737 -f 2049//2049 751//751 2063//2063 -f 2063//2063 751//751 757//757 -f 2063//2063 757//757 2057//2057 -f 2057//2057 757//757 28//28 -f 2057//2057 28//28 2058//2058 -f 2058//2058 28//28 27//27 -f 2058//2058 27//27 2059//2059 -f 2059//2059 27//27 765//765 -f 2059//2059 765//765 2060//2060 -f 2060//2060 765//765 1105//1105 -f 2060//2060 1105//1105 2052//2052 -f 2052//2052 1105//1105 768//768 -f 2052//2052 768//768 2054//2054 -f 2054//2054 768//768 767//767 -f 2054//2054 767//767 2050//2050 -f 2050//2050 767//767 771//771 -f 2050//2050 771//771 1291//1291 -f 1291//1291 771//771 770//770 -f 1291//1291 770//770 1292//1292 -f 1292//1292 770//770 769//769 -f 1292//1292 769//769 2048//2048 -f 2048//2048 769//769 752//752 -f 2048//2048 752//752 2049//2049 -f 2049//2049 752//752 751//751 -f 2080//2080 777//777 2081//2081 -f 2081//2081 777//777 776//776 -f 2081//2081 776//776 2082//2082 -f 2082//2082 776//776 782//782 -f 2082//2082 782//782 2083//2083 -f 2083//2083 782//782 783//783 -f 2083//2083 783//783 1968//1968 -f 1968//1968 783//783 684//684 -f 1968//1968 684//684 1982//1982 -f 1982//1982 684//684 688//688 -f 1982//1982 688//688 2079//2079 -f 2079//2079 688//688 774//774 -f 2079//2079 774//774 2078//2078 -f 2078//2078 774//774 773//773 -f 2078//2078 773//773 2072//2072 -f 2072//2072 773//773 772//772 -f 2072//2072 772//772 2073//2073 -f 2073//2073 772//772 781//781 -f 2073//2073 781//781 2074//2074 -f 2074//2074 781//781 780//780 -f 2074//2074 780//780 2076//2076 -f 2076//2076 780//780 779//779 -f 2076//2076 779//779 2080//2080 -f 2080//2080 779//779 777//777 -f 458//458 1680//1680 456//456 -f 456//456 1680//1680 1679//1679 -f 456//456 1679//1679 463//463 -f 463//463 1679//1679 1798//1798 -f 463//463 1798//1798 920//920 -f 920//920 1798//1798 2457//2457 -f 920//920 2457//2457 819//819 -f 819//819 2457//2457 2458//2458 -f 819//819 2458//2458 613//613 -f 613//613 2458//2458 1881//1881 -f 613//613 1881//1881 603//603 -f 603//603 1881//1881 1892//1892 -f 603//603 1892//1892 600//600 -f 600//600 1892//1892 1890//1890 -f 600//600 1890//1890 639//639 -f 639//639 1890//1890 1915//1915 -f 639//639 1915//1915 637//637 -f 637//637 1915//1915 1926//1926 -f 637//637 1926//1926 830//830 -f 830//830 1926//1926 2498//2498 -f 830//830 2498//2498 831//831 -f 831//831 2498//2498 2497//2497 -f 831//831 2497//2497 940//940 -f 940//940 2497//2497 2496//2496 -f 940//940 2496//2496 970//970 -f 970//970 2496//2496 2495//2495 -f 970//970 2495//2495 1043//1043 -f 1043//1043 2495//2495 2494//2494 -f 1043//1043 2494//2494 1082//1082 -f 1082//1082 2494//2494 2493//2493 -f 1082//1082 2493//2493 1020//1020 -f 1020//1020 2493//2493 2492//2492 -f 1020//1020 2492//2492 945//945 -f 945//945 2492//2492 2491//2491 -f 945//945 2491//2491 946//946 -f 946//946 2491//2491 2490//2490 -f 946//946 2490//2490 13//13 -f 13//13 2490//2490 2489//2489 -f 13//13 2489//2489 14//14 -f 14//14 2489//2489 2488//2488 -f 14//14 2488//2488 835//835 -f 835//835 2488//2488 2487//2487 -f 835//835 2487//2487 837//837 -f 837//837 2487//2487 2486//2486 -f 837//837 2486//2486 839//839 -f 839//839 2486//2486 2475//2475 -f 839//839 2475//2475 624//624 -f 624//624 2475//2475 1901//1901 -f 624//624 1901//1901 622//622 -f 622//622 1901//1901 1909//1909 -f 622//622 1909//1909 619//619 -f 619//619 1909//1909 1908//1908 -f 619//619 1908//1908 858//858 -f 858//858 1908//1908 2510//2510 -f 858//858 2510//2510 953//953 -f 953//953 2510//2510 2518//2518 -f 953//953 2518//2518 510//510 -f 510//510 2518//2518 1836//1836 -f 510//510 1836//1836 508//508 -f 508//508 1836//1836 1838//1838 -f 508//508 1838//1838 497//497 -f 497//497 1838//1838 1594//1594 -f 497//497 1594//1594 498//498 -f 498//498 1594//1594 1596//1596 -f 1678//1678 452//452 1677//1677 -f 1677//1677 452//452 450//450 -f 1677//1677 450//450 2376//2376 -f 2376//2376 450//450 900//900 -f 2376//2376 900//900 1670//1670 -f 1670//1670 900//900 25//25 -f 1670//1670 25//25 1669//1669 -f 1669//1669 25//25 24//24 -f 1600//1600 812//812 1601//1601 -f 1601//1601 812//812 919//919 -f 1601//1601 919//919 2416//2416 -f 2416//2416 919//919 918//918 -f 2416//2416 918//918 1598//1598 -f 1598//1598 918//918 917//917 -f 1598//1598 917//917 1323//1323 -f 1323//1323 917//917 815//815 -f 1647//1647 577//577 1645//1645 -f 1645//1645 577//577 583//583 -f 1645//1645 583//583 1862//1862 -f 1862//1862 583//583 4//4 -f 1862//1862 4//4 2164//2164 -f 2164//2164 4//4 2//2 -f 2164//2164 2//2 1637//1637 -f 1637//1637 2//2 1//1 -f 1637//1637 1//1 1639//1639 -f 1639//1639 1//1 529//529 -f 1628//1628 1176//1176 1272//1272 -f 1272//1272 1176//1176 1175//1175 -f 1272//1272 1175//1175 1273//1273 -f 1273//1273 1175//1175 1173//1173 -f 1273//1273 1173//1173 2163//2163 -f 2163//2163 1173//1173 1171//1171 -f 2163//2163 1171//1171 2186//2186 -f 2186//2186 1171//1171 1169//1169 -f 2186//2186 1169//1169 2215//2215 -f 2215//2215 1169//1169 801//801 -f 452//452 1678//1678 1685//1685 -f 452//452 1685//1685 454//454 -f 454//454 1685//1685 1686//1686 -f 454//454 1686//1686 459//459 -f 459//459 1686//1686 1680//1680 -f 459//459 1680//1680 458//458 -f 1669//1669 24//24 787//787 -f 1669//1669 787//787 1668//1668 -f 1668//1668 787//787 786//786 -f 1668//1668 786//786 1667//1667 -f 1667//1667 786//786 785//785 -f 1667//1667 785//785 1665//1665 -f 577//577 1647//1647 1649//1649 -f 577//577 1649//1649 579//579 -f 579//579 1649//1649 1651//1651 -f 579//579 1651//1651 580//580 -f 580//580 1651//1651 1652//1652 -f 580//580 1652//1652 572//572 -f 1639//1639 529//529 521//521 -f 1639//1639 521//521 1634//1634 -f 1634//1634 521//521 1259//1259 -f 1634//1634 1259//1259 1635//1635 -f 1635//1635 1259//1259 1258//1258 -f 1635//1635 1258//1258 2084//2084 -f 1176//1176 1628//1628 1627//1627 -f 1176//1176 1627//1627 23//23 -f 23//23 1627//1627 1625//1625 -f 23//23 1625//1625 21//21 -f 21//21 1625//1625 1624//1624 -f 21//21 1624//1624 1226//1226 -f 2215//2215 801//801 800//800 -f 2215//2215 800//800 2216//2216 -f 2216//2216 800//800 19//19 -f 2216//2216 19//19 2212//2212 -f 2212//2212 19//19 18//18 -f 2212//2212 18//18 1317//1317 -f 812//812 1600//1600 1599//1599 -f 812//812 1599//1599 813//813 -f 813//813 1599//1599 1321//1321 -f 813//813 1321//1321 811//811 -f 811//811 1321//1321 1320//1320 -f 811//811 1320//1320 810//810 -f 1323//1323 815//815 814//814 -f 1323//1323 814//814 1324//1324 -f 1324//1324 814//814 500//500 -f 1324//1324 500//500 1325//1325 -f 1325//1325 500//500 498//498 -f 1325//1325 498//498 1596//1596 -f 2519//2519 2520//2520 2521//2521 -f 2521//2521 2520//2520 2522//2522 -f 2521//2521 2522//2522 2523//2523 -f 2523//2523 2522//2522 2524//2524 -f 2525//2525 2526//2526 2527//2527 -f 2527//2527 2526//2526 2528//2528 -f 2527//2527 2528//2528 2529//2529 -f 2529//2529 2528//2528 2530//2530 -f 2529//2529 2530//2530 2531//2531 -f 2531//2531 2530//2530 2532//2532 -f 2533//2533 2534//2534 2535//2535 -f 2535//2535 2534//2534 2536//2536 -f 2535//2535 2536//2536 2537//2537 -f 2537//2537 2536//2536 2538//2538 -f 2537//2537 2538//2538 2539//2539 -f 2539//2539 2538//2538 2540//2540 -f 2539//2539 2540//2540 2541//2541 -f 2541//2541 2540//2540 2542//2542 -f 2541//2541 2542//2542 2543//2543 -f 2543//2543 2542//2542 2544//2544 -f 2543//2543 2544//2544 2532//2532 -f 2532//2532 2544//2544 2531//2531 -f 2534//2534 2533//2533 2545//2545 -f 2534//2534 2545//2545 2546//2546 -f 2546//2546 2545//2545 2547//2547 -f 2546//2546 2547//2547 2548//2548 -f 2548//2548 2547//2547 2549//2549 -f 2548//2548 2549//2549 2550//2550 -f 2550//2550 2549//2549 2551//2551 -f 2550//2550 2551//2551 2552//2552 -f 2553//2553 2554//2554 2555//2555 -f 2555//2555 2554//2554 2556//2556 -f 2555//2555 2556//2556 2557//2557 -f 2557//2557 2556//2556 2558//2558 -f 2557//2557 2558//2558 2559//2559 -f 2559//2559 2558//2558 2560//2560 -f 2559//2559 2560//2560 2561//2561 -f 2561//2561 2560//2560 2562//2562 -f 2561//2561 2562//2562 2563//2563 -f 2563//2563 2562//2562 2564//2564 -f 2563//2563 2564//2564 2565//2565 -f 2565//2565 2564//2564 2566//2566 -f 2565//2565 2566//2566 2567//2567 -f 2567//2567 2566//2566 2568//2568 -f 2567//2567 2568//2568 2569//2569 -f 2569//2569 2568//2568 2570//2570 -f 2569//2569 2570//2570 2551//2551 -f 2551//2551 2570//2570 2552//2552 -f 2554//2554 2553//2553 2571//2571 -f 2554//2554 2571//2571 2572//2572 -f 2572//2572 2571//2571 2573//2573 -f 2572//2572 2573//2573 2574//2574 -f 2574//2574 2573//2573 2575//2575 -f 2574//2574 2575//2575 2576//2576 -f 2576//2576 2575//2575 2577//2577 -f 2576//2576 2577//2577 2578//2578 -f 2523//2523 2524//2524 2579//2579 -f 2579//2579 2524//2524 2580//2580 -f 2579//2579 2580//2580 2581//2581 -f 2581//2581 2580//2580 2582//2582 -f 2581//2581 2582//2582 2583//2583 -f 2583//2583 2582//2582 2584//2584 -f 2583//2583 2584//2584 2585//2585 -f 2585//2585 2584//2584 2586//2586 -f 2585//2585 2586//2586 2587//2587 -f 2587//2587 2586//2586 2588//2588 -f 2587//2587 2588//2588 2577//2577 -f 2577//2577 2588//2588 2578//2578 -f 2572//2572 2574//2574 2576//2576 -f 2589//2589 2590//2590 2591//2591 -f 2592//2592 2593//2593 2594//2594 -f 2594//2594 2593//2593 2595//2595 -f 2594//2594 2595//2595 2596//2596 -f 2596//2596 2595//2595 2597//2597 -f 2598//2598 2599//2599 2600//2600 -f 2599//2599 2601//2601 2600//2600 -f 2600//2600 2601//2601 2602//2602 -f 2600//2600 2602//2602 2591//2591 -f 2591//2591 2602//2602 2603//2603 -f 2591//2591 2603//2603 2589//2589 -f 2604//2604 2605//2605 2606//2606 -f 2536//2536 2607//2607 2608//2608 -f 2608//2608 2607//2607 2609//2609 -f 2605//2605 2610//2610 2546//2546 -f 2546//2546 2610//2610 2534//2534 -f 2610//2610 2611//2611 2534//2534 -f 2534//2534 2611//2611 2612//2612 -f 2534//2534 2612//2612 2536//2536 -f 2536//2536 2612//2612 2613//2613 -f 2536//2536 2613//2613 2607//2607 -f 2609//2609 2614//2614 2608//2608 -f 2608//2608 2614//2614 2615//2615 -f 2608//2608 2615//2615 2616//2616 -f 2604//2604 2606//2606 2617//2617 -f 2617//2617 2606//2606 2618//2618 -f 2617//2617 2618//2618 2619//2619 -f 2554//2554 2572//2572 2594//2594 -f 2594//2594 2572//2572 2576//2576 -f 2594//2594 2576//2576 2592//2592 -f 2592//2592 2576//2576 2578//2578 -f 2592//2592 2578//2578 2620//2620 -f 2605//2605 2546//2546 2606//2606 -f 2606//2606 2546//2546 2548//2548 -f 2606//2606 2548//2548 2550//2550 -f 2621//2621 2622//2622 2623//2623 -f 2624//2624 2625//2625 2626//2626 -f 2625//2625 2624//2624 2627//2627 -f 2627//2627 2624//2624 2628//2628 -f 2627//2627 2628//2628 2629//2629 -f 2630//2630 2631//2631 2527//2527 -f 2527//2527 2631//2631 2525//2525 -f 2631//2631 2632//2632 2525//2525 -f 2525//2525 2632//2632 2633//2633 -f 2525//2525 2633//2633 2634//2634 -f 2634//2634 2633//2633 2635//2635 -f 2634//2634 2635//2635 2621//2621 -f 2621//2621 2635//2635 2636//2636 -f 2621//2621 2636//2636 2622//2622 -f 2637//2637 2638//2638 2639//2639 -f 2639//2639 2638//2638 2525//2525 -f 2639//2639 2525//2525 2640//2640 -f 2640//2640 2525//2525 2634//2634 -f 2641//2641 2642//2642 2643//2643 -f 2643//2643 2642//2642 2621//2621 -f 2643//2643 2621//2621 2628//2628 -f 2628//2628 2621//2621 2623//2623 -f 2628//2628 2623//2623 2629//2629 -f 2644//2644 2645//2645 2646//2646 -f 2647//2647 2648//2648 2649//2649 -f 2650//2650 2651//2651 2652//2652 -f 2648//2648 2647//2647 2653//2653 -f 2653//2653 2647//2647 2654//2654 -f 2653//2653 2654//2654 2655//2655 -f 2655//2655 2654//2654 2646//2646 -f 2655//2655 2646//2646 2656//2656 -f 2649//2649 2651//2651 2647//2647 -f 2647//2647 2651//2651 2650//2650 -f 2647//2647 2650//2650 2657//2657 -f 2657//2657 2650//2650 2658//2658 -f 2652//2652 2659//2659 2650//2650 -f 2650//2650 2659//2659 2660//2660 -f 2650//2650 2660//2660 2645//2645 -f 2660//2660 2661//2661 2645//2645 -f 2645//2645 2661//2661 2662//2662 -f 2645//2645 2662//2662 2646//2646 -f 2646//2646 2662//2662 2663//2663 -f 2646//2646 2663//2663 2656//2656 -f 2658//2658 2650//2650 2664//2664 -f 2664//2664 2650//2650 2665//2665 -f 2664//2664 2665//2665 2666//2666 -f 2520//2520 2667//2667 2668//2668 -f 2669//2669 2670//2670 2666//2666 -f 2671//2671 2672//2672 2673//2673 -f 2673//2673 2672//2672 2520//2520 -f 2673//2673 2520//2520 2674//2674 -f 2674//2674 2520//2520 2668//2668 -f 2674//2674 2668//2668 2675//2675 -f 2676//2676 2677//2677 2673//2673 -f 2673//2673 2677//2677 2678//2678 -f 2673//2673 2678//2678 2671//2671 -f 2669//2669 2666//2666 2679//2679 -f 2670//2670 2680//2680 2666//2666 -f 2666//2666 2680//2680 2681//2681 -f 2666//2666 2681//2681 2664//2664 -f 2664//2664 2681//2681 2682//2682 -f 2664//2664 2682//2682 2683//2683 -f 2683//2683 2682//2682 2684//2684 -f 2683//2683 2684//2684 2676//2676 -f 2676//2676 2684//2684 2685//2685 -f 2676//2676 2685//2685 2677//2677 -f 2686//2686 2522//2522 2520//2520 -f 2616//2616 2687//2687 2688//2688 -f 2688//2688 2687//2687 2689//2689 -f 2689//2689 2687//2687 2690//2690 -f 2689//2689 2690//2690 2691//2691 -f 2691//2691 2690//2690 2692//2692 -f 2691//2691 2692//2692 2693//2693 -f 2693//2693 2692//2692 2694//2694 -f 2693//2693 2694//2694 2695//2695 -f 2695//2695 2694//2694 2696//2696 -f 2695//2695 2696//2696 2697//2697 -f 2698//2698 2699//2699 2700//2700 -f 2701//2701 2702//2702 2703//2703 -f 2702//2702 2704//2704 2703//2703 -f 2703//2703 2704//2704 2705//2705 -f 2703//2703 2705//2705 2540//2540 -f 2706//2706 2542//2542 2707//2707 -f 2707//2707 2542//2542 2540//2540 -f 2707//2707 2540//2540 2708//2708 -f 2708//2708 2540//2540 2705//2705 -f 2706//2706 2709//2709 2542//2542 -f 2542//2542 2709//2709 2710//2710 -f 2542//2542 2710//2710 2698//2698 -f 2698//2698 2710//2710 2711//2711 -f 2698//2698 2711//2711 2699//2699 -f 2712//2712 2713//2713 2538//2538 -f 2703//2703 2714//2714 2715//2715 -f 2716//2716 2717//2717 2718//2718 -f 2538//2538 2713//2713 2540//2540 -f 2713//2713 2719//2719 2540//2540 -f 2540//2540 2719//2719 2720//2720 -f 2540//2540 2720//2720 2703//2703 -f 2703//2703 2720//2720 2721//2721 -f 2703//2703 2721//2721 2714//2714 -f 2718//2718 2722//2722 2716//2716 -f 2716//2716 2722//2722 2723//2723 -f 2716//2716 2723//2723 2538//2538 -f 2538//2538 2723//2723 2724//2724 -f 2538//2538 2724//2724 2712//2712 -f 2531//2531 2544//2544 2529//2529 -f 2529//2529 2544//2544 2725//2725 -f 2529//2529 2725//2725 2527//2527 -f 2527//2527 2725//2725 2624//2624 -f 2527//2527 2624//2624 2630//2630 -f 2630//2630 2624//2624 2626//2626 -f 2538//2538 2536//2536 2716//2716 -f 2716//2716 2536//2536 2608//2608 -f 2716//2716 2608//2608 2696//2696 -f 2696//2696 2608//2608 2616//2616 -f 2696//2696 2616//2616 2697//2697 -f 2697//2697 2616//2616 2688//2688 -f 2544//2544 2542//2542 2725//2725 -f 2725//2725 2542//2542 2698//2698 -f 2725//2725 2698//2698 2624//2624 -f 2624//2624 2698//2698 2726//2726 -f 2624//2624 2726//2726 2628//2628 -f 2628//2628 2726//2726 2727//2727 -f 2628//2628 2727//2727 2643//2643 -f 2643//2643 2727//2727 2644//2644 -f 2643//2643 2644//2644 2641//2641 -f 2641//2641 2644//2644 2646//2646 -f 2728//2728 2692//2692 2729//2729 -f 2729//2729 2692//2692 2730//2730 -f 2730//2730 2692//2692 2690//2690 -f 2730//2730 2690//2690 2731//2731 -f 2731//2731 2690//2690 2732//2732 -f 2731//2731 2732//2732 2733//2733 -f 2700//2700 2701//2701 2698//2698 -f 2698//2698 2701//2701 2703//2703 -f 2698//2698 2703//2703 2726//2726 -f 2726//2726 2703//2703 2734//2734 -f 2726//2726 2734//2734 2727//2727 -f 2727//2727 2734//2734 2735//2735 -f 2727//2727 2735//2735 2644//2644 -f 2644//2644 2735//2735 2736//2736 -f 2644//2644 2736//2736 2645//2645 -f 2645//2645 2736//2736 2737//2737 -f 2645//2645 2737//2737 2650//2650 -f 2650//2650 2737//2737 2738//2738 -f 2650//2650 2738//2738 2665//2665 -f 2665//2665 2738//2738 2739//2739 -f 2615//2615 2619//2619 2616//2616 -f 2616//2616 2619//2619 2618//2618 -f 2616//2616 2618//2618 2687//2687 -f 2687//2687 2618//2618 2740//2740 -f 2687//2687 2740//2740 2690//2690 -f 2690//2690 2740//2740 2741//2741 -f 2690//2690 2741//2741 2732//2732 -f 2732//2732 2741//2741 2742//2742 -f 2732//2732 2742//2742 2743//2743 -f 2743//2743 2742//2742 2744//2744 -f 2743//2743 2744//2744 2600//2600 -f 2600//2600 2744//2744 2596//2596 -f 2600//2600 2596//2596 2598//2598 -f 2598//2598 2596//2596 2597//2597 -f 2745//2745 2746//2746 2747//2747 -f 2748//2748 2749//2749 2750//2750 -f 2747//2747 2746//2746 2739//2739 -f 2665//2665 2751//2751 2752//2752 -f 2750//2750 2753//2753 2748//2748 -f 2748//2748 2753//2753 2754//2754 -f 2748//2748 2754//2754 2747//2747 -f 2747//2747 2754//2754 2755//2755 -f 2747//2747 2755//2755 2745//2745 -f 2746//2746 2756//2756 2739//2739 -f 2739//2739 2756//2756 2757//2757 -f 2739//2739 2757//2757 2665//2665 -f 2665//2665 2757//2757 2758//2758 -f 2665//2665 2758//2758 2751//2751 -f 2672//2672 2679//2679 2520//2520 -f 2520//2520 2679//2679 2666//2666 -f 2520//2520 2666//2666 2686//2686 -f 2686//2686 2666//2666 2665//2665 -f 2686//2686 2665//2665 2748//2748 -f 2748//2748 2665//2665 2752//2752 -f 2748//2748 2752//2752 2749//2749 -f 2759//2759 2760//2760 2761//2761 -f 2761//2761 2760//2760 2739//2739 -f 2761//2761 2739//2739 2762//2762 -f 2762//2762 2739//2739 2738//2738 -f 2762//2762 2738//2738 2728//2728 -f 2728//2728 2738//2738 2737//2737 -f 2728//2728 2737//2737 2692//2692 -f 2692//2692 2737//2737 2736//2736 -f 2692//2692 2736//2736 2694//2694 -f 2694//2694 2736//2736 2735//2735 -f 2694//2694 2735//2735 2696//2696 -f 2696//2696 2735//2735 2734//2734 -f 2696//2696 2734//2734 2716//2716 -f 2716//2716 2734//2734 2703//2703 -f 2716//2716 2703//2703 2717//2717 -f 2717//2717 2703//2703 2715//2715 -f 2760//2760 2763//2763 2739//2739 -f 2739//2739 2763//2763 2764//2764 -f 2739//2739 2764//2764 2747//2747 -f 2747//2747 2764//2764 2765//2765 -f 2747//2747 2765//2765 2766//2766 -f 2766//2766 2767//2767 2747//2747 -f 2747//2747 2767//2767 2768//2768 -f 2747//2747 2768//2768 2769//2769 -f 2769//2769 2768//2768 2770//2770 -f 2770//2770 2771//2771 2769//2769 -f 2769//2769 2771//2771 2772//2772 -f 2769//2769 2772//2772 2761//2761 -f 2761//2761 2772//2772 2773//2773 -f 2761//2761 2773//2773 2759//2759 -f 2729//2729 2733//2733 2728//2728 -f 2728//2728 2733//2733 2732//2732 -f 2728//2728 2732//2732 2762//2762 -f 2762//2762 2732//2732 2743//2743 -f 2762//2762 2743//2743 2761//2761 -f 2761//2761 2743//2743 2600//2600 -f 2761//2761 2600//2600 2769//2769 -f 2769//2769 2600//2600 2591//2591 -f 2550//2550 2552//2552 2606//2606 -f 2606//2606 2552//2552 2570//2570 -f 2606//2606 2570//2570 2618//2618 -f 2618//2618 2570//2570 2568//2568 -f 2618//2618 2568//2568 2740//2740 -f 2740//2740 2568//2568 2566//2566 -f 2740//2740 2566//2566 2741//2741 -f 2741//2741 2566//2566 2564//2564 -f 2741//2741 2564//2564 2742//2742 -f 2742//2742 2564//2564 2562//2562 -f 2742//2742 2562//2562 2744//2744 -f 2744//2744 2562//2562 2560//2560 -f 2744//2744 2560//2560 2596//2596 -f 2596//2596 2560//2560 2558//2558 -f 2596//2596 2558//2558 2594//2594 -f 2594//2594 2558//2558 2556//2556 -f 2594//2594 2556//2556 2554//2554 -f 2620//2620 2578//2578 2590//2590 -f 2590//2590 2578//2578 2588//2588 -f 2590//2590 2588//2588 2591//2591 -f 2591//2591 2588//2588 2586//2586 -f 2591//2591 2586//2586 2769//2769 -f 2769//2769 2586//2586 2584//2584 -f 2769//2769 2584//2584 2747//2747 -f 2747//2747 2584//2584 2582//2582 -f 2747//2747 2582//2582 2748//2748 -f 2748//2748 2582//2582 2580//2580 -f 2748//2748 2580//2580 2686//2686 -f 2686//2686 2580//2580 2524//2524 -f 2686//2686 2524//2524 2522//2522 -f 2774//2774 2775//2775 2776//2776 -f 2585//2585 2587//2587 2777//2777 -f 2519//2519 2521//2521 2778//2778 -f 2779//2779 2780//2780 2781//2781 -f 2528//2528 2526//2526 2782//2782 -f 2783//2783 2784//2784 2785//2785 -f 2785//2785 2784//2784 2786//2786 -f 2785//2785 2786//2786 2787//2787 -f 2787//2787 2786//2786 2788//2788 -f 2787//2787 2788//2788 2789//2789 -f 2790//2790 2791//2791 2526//2526 -f 2526//2526 2791//2791 2792//2792 -f 2789//2789 2782//2782 2787//2787 -f 2787//2787 2782//2782 2526//2526 -f 2787//2787 2526//2526 2793//2793 -f 2793//2793 2526//2526 2792//2792 -f 2794//2794 2795//2795 2796//2796 -f 2796//2796 2795//2795 2797//2797 -f 2796//2796 2797//2797 2798//2798 -f 2799//2799 2800//2800 2801//2801 -f 2802//2802 2803//2803 2804//2804 -f 2805//2805 2806//2806 2535//2535 -f 2535//2535 2806//2806 2807//2807 -f 2535//2535 2807//2807 2533//2533 -f 2807//2807 2808//2808 2533//2533 -f 2533//2533 2808//2808 2809//2809 -f 2533//2533 2809//2809 2545//2545 -f 2545//2545 2809//2809 2799//2799 -f 2799//2799 2801//2801 2545//2545 -f 2545//2545 2801//2801 2549//2549 -f 2545//2545 2549//2549 2547//2547 -f 2575//2575 2573//2573 2810//2810 -f 2810//2810 2573//2573 2571//2571 -f 2810//2810 2571//2571 2553//2553 -f 2811//2811 2812//2812 2577//2577 -f 2577//2577 2812//2812 2587//2587 -f 2587//2587 2812//2812 2813//2813 -f 2587//2587 2813//2813 2777//2777 -f 2814//2814 2815//2815 2816//2816 -f 2817//2817 2818//2818 2819//2819 -f 2819//2819 2818//2818 2814//2814 -f 2819//2819 2814//2814 2820//2820 -f 2820//2820 2814//2814 2816//2816 -f 2817//2817 2821//2821 2822//2822 -f 2822//2822 2821//2821 2823//2823 -f 2822//2822 2823//2823 2824//2824 -f 2825//2825 2826//2826 2519//2519 -f 2827//2827 2828//2828 2519//2519 -f 2519//2519 2828//2828 2829//2829 -f 2519//2519 2829//2829 2825//2825 -f 2825//2825 2829//2829 2830//2830 -f 2825//2825 2830//2830 2815//2815 -f 2815//2815 2830//2830 2831//2831 -f 2815//2815 2831//2831 2816//2816 -f 2826//2826 2832//2832 2519//2519 -f 2519//2519 2832//2832 2833//2833 -f 2519//2519 2833//2833 2834//2834 -f 2817//2817 2822//2822 2818//2818 -f 2818//2818 2822//2822 2835//2835 -f 2818//2818 2835//2835 2836//2836 -f 2837//2837 2836//2836 2838//2838 -f 2838//2838 2836//2836 2839//2839 -f 2840//2840 2841//2841 2836//2836 -f 2836//2836 2841//2841 2842//2842 -f 2836//2836 2842//2842 2818//2818 -f 2837//2837 2843//2843 2836//2836 -f 2836//2836 2843//2843 2844//2844 -f 2836//2836 2844//2844 2840//2840 -f 2844//2844 2845//2845 2840//2840 -f 2840//2840 2845//2845 2846//2846 -f 2840//2840 2846//2846 2847//2847 -f 2847//2847 2846//2846 2848//2848 -f 2847//2847 2848//2848 2849//2849 -f 2849//2849 2848//2848 2850//2850 -f 2849//2849 2850//2850 2851//2851 -f 2852//2852 2853//2853 2839//2839 -f 2839//2839 2853//2853 2854//2854 -f 2839//2839 2854//2854 2838//2838 -f 2855//2855 2856//2856 2857//2857 -f 2857//2857 2856//2856 2779//2779 -f 2857//2857 2779//2779 2785//2785 -f 2785//2785 2779//2779 2781//2781 -f 2785//2785 2781//2781 2783//2783 -f 2577//2577 2575//2575 2811//2811 -f 2811//2811 2575//2575 2810//2810 -f 2811//2811 2810//2810 2858//2858 -f 2858//2858 2810//2810 2859//2859 -f 2813//2813 2860//2860 2777//2777 -f 2777//2777 2860//2860 2861//2861 -f 2777//2777 2861//2861 2862//2862 -f 2861//2861 2863//2863 2862//2862 -f 2862//2862 2863//2863 2864//2864 -f 2862//2862 2864//2864 2865//2865 -f 2859//2859 2810//2810 2866//2866 -f 2866//2866 2810//2810 2867//2867 -f 2866//2866 2867//2867 2868//2868 -f 2869//2869 2870//2870 2871//2871 -f 2800//2800 2872//2872 2801//2801 -f 2801//2801 2872//2872 2869//2869 -f 2801//2801 2869//2869 2873//2873 -f 2874//2874 2871//2871 2875//2875 -f 2875//2875 2871//2871 2876//2876 -f 2875//2875 2876//2876 2877//2877 -f 2877//2877 2876//2876 2878//2878 -f 2877//2877 2878//2878 2879//2879 -f 2879//2879 2878//2878 2880//2880 -f 2879//2879 2880//2880 2881//2881 -f 2881//2881 2880//2880 2882//2882 -f 2881//2881 2882//2882 2883//2883 -f 2883//2883 2882//2882 2884//2884 -f 2883//2883 2884//2884 2874//2874 -f 2874//2874 2884//2884 2871//2871 -f 2585//2585 2885//2885 2583//2583 -f 2583//2583 2885//2885 2886//2886 -f 2583//2583 2886//2886 2581//2581 -f 2581//2581 2886//2886 2887//2887 -f 2581//2581 2887//2887 2579//2579 -f 2579//2579 2887//2887 2778//2778 -f 2579//2579 2778//2778 2523//2523 -f 2523//2523 2778//2778 2521//2521 -f 2886//2886 2888//2888 2889//2889 -f 2890//2890 2891//2891 2887//2887 -f 2887//2887 2891//2891 2835//2835 -f 2887//2887 2835//2835 2778//2778 -f 2778//2778 2835//2835 2822//2822 -f 2778//2778 2822//2822 2519//2519 -f 2519//2519 2822//2822 2824//2824 -f 2519//2519 2824//2824 2827//2827 -f 2891//2891 2892//2892 2835//2835 -f 2835//2835 2892//2892 2893//2893 -f 2835//2835 2893//2893 2894//2894 -f 2889//2889 2895//2895 2886//2886 -f 2886//2886 2895//2895 2896//2896 -f 2886//2886 2896//2896 2887//2887 -f 2887//2887 2896//2896 2897//2897 -f 2887//2887 2897//2897 2890//2890 -f 2888//2888 2886//2886 2898//2898 -f 2898//2898 2886//2886 2899//2899 -f 2898//2898 2899//2899 2900//2900 -f 2901//2901 2886//2886 2902//2902 -f 2902//2902 2886//2886 2885//2885 -f 2902//2902 2885//2885 2903//2903 -f 2903//2903 2885//2885 2904//2904 -f 2901//2901 2905//2905 2886//2886 -f 2886//2886 2905//2905 2906//2906 -f 2886//2886 2906//2906 2899//2899 -f 2899//2899 2906//2906 2907//2907 -f 2899//2899 2907//2907 2908//2908 -f 2908//2908 2909//2909 2910//2910 -f 2909//2909 2911//2911 2910//2910 -f 2910//2910 2911//2911 2912//2912 -f 2910//2910 2912//2912 2885//2885 -f 2885//2885 2912//2912 2913//2913 -f 2885//2885 2913//2913 2904//2904 -f 2585//2585 2777//2777 2885//2885 -f 2885//2885 2777//2777 2862//2862 -f 2885//2885 2862//2862 2910//2910 -f 2910//2910 2862//2862 2914//2914 -f 2910//2910 2914//2914 2915//2915 -f 2915//2915 2914//2914 2916//2916 -f 2915//2915 2916//2916 2917//2917 -f 2918//2918 2882//2882 2919//2919 -f 2919//2919 2882//2882 2880//2880 -f 2919//2919 2880//2880 2920//2920 -f 2920//2920 2880//2880 2917//2917 -f 2920//2920 2917//2917 2921//2921 -f 2921//2921 2917//2917 2916//2916 -f 2921//2921 2916//2916 2918//2918 -f 2918//2918 2916//2916 2882//2882 -f 2922//2922 2779//2779 2923//2923 -f 2923//2923 2779//2779 2856//2856 -f 2923//2923 2856//2856 2924//2924 -f 2924//2924 2856//2856 2855//2855 -f 2924//2924 2855//2855 2839//2839 -f 2839//2839 2855//2855 2849//2849 -f 2839//2839 2849//2849 2852//2852 -f 2852//2852 2849//2849 2851//2851 -f 2925//2925 2922//2922 2926//2926 -f 2926//2926 2922//2922 2923//2923 -f 2926//2926 2923//2923 2927//2927 -f 2927//2927 2923//2923 2924//2924 -f 2927//2927 2924//2924 2928//2928 -f 2928//2928 2924//2924 2839//2839 -f 2928//2928 2839//2839 2929//2929 -f 2929//2929 2839//2839 2836//2836 -f 2929//2929 2836//2836 2930//2930 -f 2930//2930 2836//2836 2835//2835 -f 2930//2930 2835//2835 2899//2899 -f 2899//2899 2835//2835 2894//2894 -f 2899//2899 2894//2894 2900//2900 -f 2869//2869 2871//2871 2873//2873 -f 2873//2873 2871//2871 2884//2884 -f 2873//2873 2884//2884 2931//2931 -f 2931//2931 2884//2884 2882//2882 -f 2931//2931 2882//2882 2932//2932 -f 2932//2932 2882//2882 2916//2916 -f 2932//2932 2916//2916 2933//2933 -f 2933//2933 2916//2916 2914//2914 -f 2933//2933 2914//2914 2934//2934 -f 2934//2934 2914//2914 2862//2862 -f 2934//2934 2862//2862 2867//2867 -f 2867//2867 2862//2862 2865//2865 -f 2867//2867 2865//2865 2868//2868 -f 2935//2935 2530//2530 2528//2528 -f 2870//2870 2803//2803 2871//2871 -f 2871//2871 2803//2803 2802//2802 -f 2871//2871 2802//2802 2876//2876 -f 2876//2876 2802//2802 2776//2776 -f 2553//2553 2555//2555 2810//2810 -f 2810//2810 2555//2555 2557//2557 -f 2810//2810 2557//2557 2867//2867 -f 2867//2867 2557//2557 2559//2559 -f 2867//2867 2559//2559 2934//2934 -f 2934//2934 2559//2559 2561//2561 -f 2934//2934 2561//2561 2933//2933 -f 2933//2933 2561//2561 2563//2563 -f 2933//2933 2563//2563 2932//2932 -f 2932//2932 2563//2563 2565//2565 -f 2932//2932 2565//2565 2931//2931 -f 2931//2931 2565//2565 2567//2567 -f 2931//2931 2567//2567 2873//2873 -f 2873//2873 2567//2567 2569//2569 -f 2873//2873 2569//2569 2801//2801 -f 2801//2801 2569//2569 2551//2551 -f 2801//2801 2551//2551 2549//2549 -f 2532//2532 2530//2530 2543//2543 -f 2543//2543 2530//2530 2935//2935 -f 2543//2543 2935//2935 2541//2541 -f 2936//2936 2937//2937 2925//2925 -f 2925//2925 2937//2937 2938//2938 -f 2925//2925 2938//2938 2939//2939 -f 2940//2940 2941//2941 2942//2942 -f 2942//2942 2941//2941 2943//2943 -f 2942//2942 2943//2943 2944//2944 -f 2782//2782 2794//2794 2528//2528 -f 2528//2528 2794//2794 2796//2796 -f 2528//2528 2796//2796 2935//2935 -f 2935//2935 2796//2796 2942//2942 -f 2935//2935 2942//2942 2541//2541 -f 2541//2541 2942//2942 2944//2944 -f 2541//2541 2944//2944 2945//2945 -f 2945//2945 2946//2946 2541//2541 -f 2541//2541 2946//2946 2947//2947 -f 2541//2541 2947//2947 2539//2539 -f 2539//2539 2947//2947 2948//2948 -f 2939//2939 2940//2940 2925//2925 -f 2925//2925 2940//2940 2942//2942 -f 2925//2925 2942//2942 2922//2922 -f 2922//2922 2942//2942 2796//2796 -f 2922//2922 2796//2796 2779//2779 -f 2779//2779 2796//2796 2798//2798 -f 2779//2779 2798//2798 2780//2780 -f 2949//2949 2950//2950 2925//2925 -f 2775//2775 2951//2951 2776//2776 -f 2776//2776 2951//2951 2952//2952 -f 2776//2776 2952//2952 2953//2953 -f 2908//2908 2910//2910 2899//2899 -f 2899//2899 2910//2910 2915//2915 -f 2899//2899 2915//2915 2930//2930 -f 2930//2930 2915//2915 2917//2917 -f 2930//2930 2917//2917 2929//2929 -f 2929//2929 2917//2917 2880//2880 -f 2929//2929 2880//2880 2928//2928 -f 2928//2928 2880//2880 2878//2878 -f 2928//2928 2878//2878 2927//2927 -f 2927//2927 2878//2878 2876//2876 -f 2927//2927 2876//2876 2926//2926 -f 2926//2926 2876//2876 2776//2776 -f 2926//2926 2776//2776 2925//2925 -f 2925//2925 2776//2776 2953//2953 -f 2925//2925 2953//2953 2949//2949 -f 2950//2950 2954//2954 2925//2925 -f 2925//2925 2954//2954 2539//2539 -f 2925//2925 2539//2539 2936//2936 -f 2936//2936 2539//2539 2948//2948 -f 2954//2954 2955//2955 2539//2539 -f 2539//2539 2955//2955 2956//2956 -f 2539//2539 2956//2956 2537//2537 -f 2537//2537 2956//2956 2957//2957 -f 2537//2537 2957//2957 2958//2958 -f 2804//2804 2805//2805 2802//2802 -f 2802//2802 2805//2805 2535//2535 -f 2802//2802 2535//2535 2776//2776 -f 2776//2776 2535//2535 2537//2537 -f 2776//2776 2537//2537 2774//2774 -f 2774//2774 2537//2537 2958//2958 -f 2861//2861 2603//2603 2863//2863 -f 2863//2863 2603//2603 2602//2602 -f 2863//2863 2602//2602 2864//2864 -f 2864//2864 2602//2602 2601//2601 -f 2864//2864 2601//2601 2865//2865 -f 2865//2865 2601//2601 2599//2599 -f 2865//2865 2599//2599 2868//2868 -f 2868//2868 2599//2599 2598//2598 -f 2868//2868 2598//2598 2866//2866 -f 2866//2866 2598//2598 2597//2597 -f 2866//2866 2597//2597 2859//2859 -f 2859//2859 2597//2597 2595//2595 -f 2859//2859 2595//2595 2858//2858 -f 2858//2858 2595//2595 2593//2593 -f 2858//2858 2593//2593 2811//2811 -f 2811//2811 2593//2593 2592//2592 -f 2811//2811 2592//2592 2812//2812 -f 2812//2812 2592//2592 2620//2620 -f 2812//2812 2620//2620 2813//2813 -f 2813//2813 2620//2620 2590//2590 -f 2813//2813 2590//2590 2860//2860 -f 2860//2860 2590//2590 2589//2589 -f 2860//2860 2589//2589 2861//2861 -f 2861//2861 2589//2589 2603//2603 -f 2805//2805 2609//2609 2806//2806 -f 2806//2806 2609//2609 2607//2607 -f 2806//2806 2607//2607 2807//2807 -f 2807//2807 2607//2607 2613//2613 -f 2807//2807 2613//2613 2808//2808 -f 2808//2808 2613//2613 2612//2612 -f 2808//2808 2612//2612 2809//2809 -f 2809//2809 2612//2612 2611//2611 -f 2809//2809 2611//2611 2799//2799 -f 2799//2799 2611//2611 2610//2610 -f 2799//2799 2610//2610 2800//2800 -f 2800//2800 2610//2610 2605//2605 -f 2800//2800 2605//2605 2872//2872 -f 2872//2872 2605//2605 2604//2604 -f 2872//2872 2604//2604 2869//2869 -f 2869//2869 2604//2604 2617//2617 -f 2869//2869 2617//2617 2870//2870 -f 2870//2870 2617//2617 2619//2619 -f 2870//2870 2619//2619 2803//2803 -f 2803//2803 2619//2619 2615//2615 -f 2803//2803 2615//2615 2804//2804 -f 2804//2804 2615//2615 2614//2614 -f 2804//2804 2614//2614 2805//2805 -f 2805//2805 2614//2614 2609//2609 -f 2954//2954 2721//2721 2955//2955 -f 2955//2955 2721//2721 2720//2720 -f 2955//2955 2720//2720 2956//2956 -f 2956//2956 2720//2720 2719//2719 -f 2956//2956 2719//2719 2957//2957 -f 2957//2957 2719//2719 2713//2713 -f 2957//2957 2713//2713 2958//2958 -f 2958//2958 2713//2713 2712//2712 -f 2958//2958 2712//2712 2774//2774 -f 2774//2774 2712//2712 2724//2724 -f 2774//2774 2724//2724 2775//2775 -f 2775//2775 2724//2724 2723//2723 -f 2775//2775 2723//2723 2951//2951 -f 2951//2951 2723//2723 2722//2722 -f 2951//2951 2722//2722 2952//2952 -f 2952//2952 2722//2722 2718//2718 -f 2952//2952 2718//2718 2953//2953 -f 2953//2953 2718//2718 2717//2717 -f 2953//2953 2717//2717 2949//2949 -f 2949//2949 2717//2717 2715//2715 -f 2949//2949 2715//2715 2950//2950 -f 2950//2950 2715//2715 2714//2714 -f 2950//2950 2714//2714 2954//2954 -f 2954//2954 2714//2714 2721//2721 -f 2944//2944 2711//2711 2945//2945 -f 2945//2945 2711//2711 2710//2710 -f 2945//2945 2710//2710 2946//2946 -f 2946//2946 2710//2710 2709//2709 -f 2946//2946 2709//2709 2947//2947 -f 2947//2947 2709//2709 2706//2706 -f 2947//2947 2706//2706 2948//2948 -f 2948//2948 2706//2706 2707//2707 -f 2948//2948 2707//2707 2936//2936 -f 2936//2936 2707//2707 2708//2708 -f 2936//2936 2708//2708 2937//2937 -f 2937//2937 2708//2708 2705//2705 -f 2937//2937 2705//2705 2938//2938 -f 2938//2938 2705//2705 2704//2704 -f 2938//2938 2704//2704 2939//2939 -f 2939//2939 2704//2704 2702//2702 -f 2939//2939 2702//2702 2940//2940 -f 2940//2940 2702//2702 2701//2701 -f 2940//2940 2701//2701 2941//2941 -f 2941//2941 2701//2701 2700//2700 -f 2941//2941 2700//2700 2943//2943 -f 2943//2943 2700//2700 2699//2699 -f 2943//2943 2699//2699 2944//2944 -f 2944//2944 2699//2699 2711//2711 -f 2891//2891 2749//2749 2892//2892 -f 2892//2892 2749//2749 2752//2752 -f 2892//2892 2752//2752 2893//2893 -f 2893//2893 2752//2752 2751//2751 -f 2893//2893 2751//2751 2894//2894 -f 2894//2894 2751//2751 2758//2758 -f 2894//2894 2758//2758 2900//2900 -f 2900//2900 2758//2758 2757//2757 -f 2900//2900 2757//2757 2898//2898 -f 2898//2898 2757//2757 2756//2756 -f 2898//2898 2756//2756 2888//2888 -f 2888//2888 2756//2756 2746//2746 -f 2888//2888 2746//2746 2889//2889 -f 2889//2889 2746//2746 2745//2745 -f 2889//2889 2745//2745 2895//2895 -f 2895//2895 2745//2745 2755//2755 -f 2895//2895 2755//2755 2896//2896 -f 2896//2896 2755//2755 2754//2754 -f 2896//2896 2754//2754 2897//2897 -f 2897//2897 2754//2754 2753//2753 -f 2897//2897 2753//2753 2890//2890 -f 2890//2890 2753//2753 2750//2750 -f 2890//2890 2750//2750 2891//2891 -f 2891//2891 2750//2750 2749//2749 -f 2906//2906 2765//2765 2907//2907 -f 2907//2907 2765//2765 2764//2764 -f 2907//2907 2764//2764 2908//2908 -f 2908//2908 2764//2764 2763//2763 -f 2908//2908 2763//2763 2909//2909 -f 2909//2909 2763//2763 2760//2760 -f 2909//2909 2760//2760 2911//2911 -f 2911//2911 2760//2760 2759//2759 -f 2911//2911 2759//2759 2912//2912 -f 2912//2912 2759//2759 2773//2773 -f 2912//2912 2773//2773 2913//2913 -f 2913//2913 2773//2773 2772//2772 -f 2913//2913 2772//2772 2904//2904 -f 2904//2904 2772//2772 2771//2771 -f 2904//2904 2771//2771 2903//2903 -f 2903//2903 2771//2771 2770//2770 -f 2903//2903 2770//2770 2902//2902 -f 2902//2902 2770//2770 2768//2768 -f 2902//2902 2768//2768 2901//2901 -f 2901//2901 2768//2768 2767//2767 -f 2901//2901 2767//2767 2905//2905 -f 2905//2905 2767//2767 2766//2766 -f 2905//2905 2766//2766 2906//2906 -f 2906//2906 2766//2766 2765//2765 -f 2793//2793 2640//2640 2787//2787 -f 2787//2787 2640//2640 2634//2634 -f 2787//2787 2634//2634 2785//2785 -f 2785//2785 2634//2634 2621//2621 -f 2785//2785 2621//2621 2857//2857 -f 2857//2857 2621//2621 2642//2642 -f 2857//2857 2642//2642 2855//2855 -f 2855//2855 2642//2642 2641//2641 -f 2855//2855 2641//2641 2849//2849 -f 2849//2849 2641//2641 2646//2646 -f 2849//2849 2646//2646 2847//2847 -f 2847//2847 2646//2646 2654//2654 -f 2847//2847 2654//2654 2840//2840 -f 2840//2840 2654//2654 2647//2647 -f 2840//2840 2647//2647 2841//2841 -f 2841//2841 2647//2647 2657//2657 -f 2841//2841 2657//2657 2842//2842 -f 2842//2842 2657//2657 2658//2658 -f 2842//2842 2658//2658 2818//2818 -f 2818//2818 2658//2658 2664//2664 -f 2818//2818 2664//2664 2814//2814 -f 2814//2814 2664//2664 2683//2683 -f 2814//2814 2683//2683 2815//2815 -f 2815//2815 2683//2683 2676//2676 -f 2815//2815 2676//2676 2825//2825 -f 2825//2825 2676//2676 2673//2673 -f 2825//2825 2673//2673 2826//2826 -f 2826//2826 2673//2673 2674//2674 -f 2826//2826 2674//2674 2675//2675 -f 2826//2826 2675//2675 2832//2832 -f 2832//2832 2675//2675 2668//2668 -f 2832//2832 2668//2668 2833//2833 -f 2833//2833 2668//2668 2667//2667 -f 2833//2833 2667//2667 2834//2834 -f 2834//2834 2667//2667 2520//2520 -f 2834//2834 2520//2520 2519//2519 -f 2526//2526 2525//2525 2638//2638 -f 2526//2526 2638//2638 2790//2790 -f 2790//2790 2638//2638 2637//2637 -f 2790//2790 2637//2637 2791//2791 -f 2791//2791 2637//2637 2639//2639 -f 2791//2791 2639//2639 2792//2792 -f 2792//2792 2639//2639 2640//2640 -f 2792//2792 2640//2640 2793//2793 -f 2829//2829 2671//2671 2830//2830 -f 2830//2830 2671//2671 2678//2678 -f 2830//2830 2678//2678 2831//2831 -f 2831//2831 2678//2678 2677//2677 -f 2831//2831 2677//2677 2816//2816 -f 2816//2816 2677//2677 2685//2685 -f 2816//2816 2685//2685 2820//2820 -f 2820//2820 2685//2685 2684//2684 -f 2820//2820 2684//2684 2819//2819 -f 2819//2819 2684//2684 2682//2682 -f 2819//2819 2682//2682 2817//2817 -f 2817//2817 2682//2682 2681//2681 -f 2817//2817 2681//2681 2821//2821 -f 2821//2821 2681//2681 2680//2680 -f 2821//2821 2680//2680 2823//2823 -f 2823//2823 2680//2680 2670//2670 -f 2823//2823 2670//2670 2824//2824 -f 2824//2824 2670//2670 2669//2669 -f 2824//2824 2669//2669 2827//2827 -f 2827//2827 2669//2669 2679//2679 -f 2827//2827 2679//2679 2828//2828 -f 2828//2828 2679//2679 2672//2672 -f 2828//2828 2672//2672 2829//2829 -f 2829//2829 2672//2672 2671//2671 -f 2789//2789 2633//2633 2782//2782 -f 2782//2782 2633//2633 2632//2632 -f 2782//2782 2632//2632 2794//2794 -f 2794//2794 2632//2632 2631//2631 -f 2794//2794 2631//2631 2795//2795 -f 2795//2795 2631//2631 2630//2630 -f 2795//2795 2630//2630 2797//2797 -f 2797//2797 2630//2630 2626//2626 -f 2797//2797 2626//2626 2798//2798 -f 2798//2798 2626//2626 2625//2625 -f 2798//2798 2625//2625 2780//2780 -f 2780//2780 2625//2625 2627//2627 -f 2780//2780 2627//2627 2781//2781 -f 2781//2781 2627//2627 2629//2629 -f 2781//2781 2629//2629 2783//2783 -f 2783//2783 2629//2629 2623//2623 -f 2783//2783 2623//2623 2784//2784 -f 2784//2784 2623//2623 2622//2622 -f 2784//2784 2622//2622 2786//2786 -f 2786//2786 2622//2622 2636//2636 -f 2786//2786 2636//2636 2788//2788 -f 2788//2788 2636//2636 2635//2635 -f 2788//2788 2635//2635 2789//2789 -f 2789//2789 2635//2635 2633//2633 -f 2848//2848 2653//2653 2850//2850 -f 2850//2850 2653//2653 2655//2655 -f 2850//2850 2655//2655 2851//2851 -f 2851//2851 2655//2655 2656//2656 -f 2851//2851 2656//2656 2852//2852 -f 2852//2852 2656//2656 2663//2663 -f 2852//2852 2663//2663 2853//2853 -f 2853//2853 2663//2663 2662//2662 -f 2853//2853 2662//2662 2854//2854 -f 2854//2854 2662//2662 2661//2661 -f 2854//2854 2661//2661 2838//2838 -f 2838//2838 2661//2661 2660//2660 -f 2838//2838 2660//2660 2837//2837 -f 2837//2837 2660//2660 2659//2659 -f 2837//2837 2659//2659 2843//2843 -f 2843//2843 2659//2659 2652//2652 -f 2843//2843 2652//2652 2844//2844 -f 2844//2844 2652//2652 2651//2651 -f 2844//2844 2651//2651 2845//2845 -f 2845//2845 2651//2651 2649//2649 -f 2845//2845 2649//2649 2846//2846 -f 2846//2846 2649//2649 2648//2648 -f 2846//2846 2648//2648 2848//2848 -f 2848//2848 2648//2648 2653//2653 -f 2729//2729 2919//2919 2733//2733 -f 2733//2733 2919//2919 2920//2920 -f 2733//2733 2920//2920 2731//2731 -f 2731//2731 2920//2920 2921//2921 -f 2731//2731 2921//2921 2730//2730 -f 2730//2730 2921//2921 2918//2918 -f 2730//2730 2918//2918 2729//2729 -f 2729//2729 2918//2918 2919//2919 -f 2695//2695 2875//2875 2693//2693 -f 2693//2693 2875//2875 2877//2877 -f 2693//2693 2877//2877 2691//2691 -f 2691//2691 2877//2877 2879//2879 -f 2691//2691 2879//2879 2689//2689 -f 2689//2689 2879//2879 2881//2881 -f 2689//2689 2881//2881 2688//2688 -f 2688//2688 2881//2881 2883//2883 -f 2688//2688 2883//2883 2697//2697 -f 2697//2697 2883//2883 2874//2874 -f 2697//2697 2874//2874 2695//2695 -f 2695//2695 2874//2874 2875//2875 -f 2959//2959 2960//2960 2961//2961 -f 2961//2961 2960//2960 2962//2962 -f 2961//2961 2962//2962 2963//2963 -f 2963//2963 2962//2962 2964//2964 -f 2963//2963 2964//2964 2965//2965 -f 2965//2965 2964//2964 2966//2966 -f 2967//2967 2968//2968 2969//2969 -f 2969//2969 2968//2968 2970//2970 -f 2969//2969 2970//2970 2971//2971 -f 2971//2971 2970//2970 2972//2972 -f 2973//2973 2974//2974 2975//2975 -f 2975//2975 2974//2974 2976//2976 -f 2975//2975 2976//2976 2977//2977 -f 2977//2977 2976//2976 2978//2978 -f 2977//2977 2978//2978 2979//2979 -f 2979//2979 2978//2978 2980//2980 -f 2979//2979 2980//2980 2981//2981 -f 2981//2981 2980//2980 2982//2982 -f 2981//2981 2982//2982 2983//2983 -f 2983//2983 2982//2982 2984//2984 -f 2983//2983 2984//2984 2972//2972 -f 2972//2972 2984//2984 2971//2971 -f 2974//2974 2973//2973 2985//2985 -f 2974//2974 2985//2985 2986//2986 -f 2986//2986 2985//2985 2987//2987 -f 2986//2986 2987//2987 2988//2988 -f 2988//2988 2987//2987 2989//2989 -f 2988//2988 2989//2989 2990//2990 -f 2990//2990 2989//2989 2991//2991 -f 2990//2990 2991//2991 2992//2992 -f 2993//2993 2994//2994 2995//2995 -f 2995//2995 2994//2994 2996//2996 -f 2995//2995 2996//2996 2997//2997 -f 2997//2997 2996//2996 2998//2998 -f 2997//2997 2998//2998 2999//2999 -f 2999//2999 2998//2998 3000//3000 -f 2999//2999 3000//3000 3001//3001 -f 3001//3001 3000//3000 3002//3002 -f 3001//3001 3002//3002 3003//3003 -f 3003//3003 3002//3002 3004//3004 -f 3003//3003 3004//3004 3005//3005 -f 3005//3005 3004//3004 3006//3006 -f 3005//3005 3006//3006 3007//3007 -f 3007//3007 3006//3006 3008//3008 -f 3007//3007 3008//3008 3009//3009 -f 3009//3009 3008//3008 3010//3010 -f 3009//3009 3010//3010 2991//2991 -f 2991//2991 3010//3010 2992//2992 -f 2994//2994 2993//2993 3011//3011 -f 2994//2994 3011//3011 3012//3012 -f 3012//3012 3011//3011 3013//3013 -f 3012//3012 3013//3013 3014//3014 -f 3014//3014 3013//3013 3015//3015 -f 3014//3014 3015//3015 3016//3016 -f 3016//3016 3015//3015 3017//3017 -f 3016//3016 3017//3017 3018//3018 -f 2965//2965 2966//2966 3019//3019 -f 3019//3019 2966//2966 3020//3020 -f 3019//3019 3020//3020 3021//3021 -f 3021//3021 3020//3020 3022//3022 -f 3021//3021 3022//3022 3023//3023 -f 3023//3023 3022//3022 3024//3024 -f 3023//3023 3024//3024 3025//3025 -f 3025//3025 3024//3024 3026//3026 -f 3025//3025 3026//3026 3027//3027 -f 3027//3027 3026//3026 3028//3028 -f 3027//3027 3028//3028 3017//3017 -f 3017//3017 3028//3028 3018//3018 -f 2964//2964 2962//2962 3029//3029 -f 3030//3030 3031//3031 3032//3032 -f 3033//3033 3034//3034 3035//3035 -f 3014//3014 3016//3016 3018//3018 -f 2996//2996 3036//3036 2998//2998 -f 2998//2998 3036//3036 3037//3037 -f 3037//3037 3038//3038 2998//2998 -f 2998//2998 3038//3038 3039//3039 -f 2998//2998 3039//3039 3040//3040 -f 3040//3040 3039//3039 3041//3041 -f 3040//3040 3041//3041 3042//3042 -f 3042//3042 3043//3043 3044//3044 -f 3012//3012 3045//3045 2994//2994 -f 2994//2994 3045//3045 3046//3046 -f 2994//2994 3046//3046 2996//2996 -f 2996//2996 3046//3046 3047//3047 -f 2996//2996 3047//3047 3036//3036 -f 3012//3012 3014//3014 3045//3045 -f 3045//3045 3014//3014 3018//3018 -f 3045//3045 3018//3018 3048//3048 -f 3048//3048 3018//3018 3044//3044 -f 3048//3048 3044//3044 3049//3049 -f 3049//3049 3044//3044 3043//3043 -f 3050//3050 3051//3051 3052//3052 -f 3052//3052 3051//3051 2976//2976 -f 3052//3052 2976//2976 3053//3053 -f 3010//3010 3054//3054 2992//2992 -f 2992//2992 3054//3054 3055//3055 -f 2992//2992 3055//3055 2990//2990 -f 2990//2990 3055//3055 3056//3056 -f 2990//2990 3056//3056 2988//2988 -f 3053//3053 2976//2976 3057//3057 -f 3057//3057 2976//2976 2974//2974 -f 3057//3057 2974//2974 3056//3056 -f 3056//3056 2974//2974 2986//2986 -f 3056//3056 2986//2986 2988//2988 -f 3058//3058 3059//3059 3008//3008 -f 3008//3008 3059//3059 3060//3060 -f 3008//3008 3060//3060 3010//3010 -f 3010//3010 3060//3060 3061//3061 -f 3010//3010 3061//3061 3054//3054 -f 3033//3033 3062//3062 3063//3063 -f 3034//3034 3064//3064 3065//3065 -f 3065//3065 3064//3064 3066//3066 -f 3065//3065 3066//3066 3067//3067 -f 3068//3068 3069//3069 2967//2967 -f 2967//2967 3069//3069 3070//3070 -f 2967//2967 3070//3070 3071//3071 -f 3072//3072 3073//3073 3074//3074 -f 3074//3074 3073//3073 2967//2967 -f 3074//3074 2967//2967 3075//3075 -f 3075//3075 2967//2967 3071//3071 -f 3075//3075 3071//3071 3062//3062 -f 3062//3062 3071//3071 3076//3076 -f 3062//3062 3076//3076 3063//3063 -f 3063//3063 3077//3077 3033//3033 -f 3033//3033 3077//3077 3078//3078 -f 3033//3033 3078//3078 3034//3034 -f 3034//3034 3078//3078 3079//3079 -f 3034//3034 3079//3079 3064//3064 -f 3080//3080 3081//3081 3082//3082 -f 3083//3083 3084//3084 3085//3085 -f 3085//3085 3084//3084 3086//3086 -f 3085//3085 3086//3086 3080//3080 -f 3080//3080 3086//3086 3087//3087 -f 3080//3080 3087//3087 3081//3081 -f 3031//3031 3088//3088 3089//3089 -f 3090//3090 3091//3091 3092//3092 -f 3085//3085 3093//3093 3094//3094 -f 3088//3088 3031//3031 3095//3095 -f 3095//3095 3031//3031 3030//3030 -f 3095//3095 3030//3030 3096//3096 -f 3096//3096 3030//3030 3097//3097 -f 3096//3096 3097//3097 3098//3098 -f 3098//3098 3097//3097 3099//3099 -f 3098//3098 3099//3099 3094//3094 -f 3100//3100 3101//3101 3034//3034 -f 3034//3034 3101//3101 3102//3102 -f 3034//3034 3102//3102 3035//3035 -f 3035//3035 3102//3102 3103//3103 -f 3035//3035 3103//3103 3104//3104 -f 3104//3104 3103//3103 3105//3105 -f 3104//3104 3105//3105 3106//3106 -f 3106//3106 3105//3105 3107//3107 -f 3106//3106 3107//3107 3108//3108 -f 3108//3108 3107//3107 3083//3083 -f 3108//3108 3083//3083 3109//3109 -f 3109//3109 3083//3083 3085//3085 -f 3109//3109 3085//3085 3110//3110 -f 3110//3110 3085//3085 3094//3094 -f 3110//3110 3094//3094 3111//3111 -f 3111//3111 3094//3094 3099//3099 -f 3091//3091 3112//3112 3092//3092 -f 3092//3092 3112//3112 3113//3113 -f 3092//3092 3113//3113 3085//3085 -f 3085//3085 3113//3113 3114//3114 -f 3085//3085 3114//3114 3093//3093 -f 3115//3115 3116//3116 3117//3117 -f 3117//3117 3116//3116 3118//3118 -f 3117//3117 3118//3118 3119//3119 -f 3120//3120 3121//3121 3122//3122 -f 3122//3122 3123//3123 3120//3120 -f 3120//3120 3123//3123 3124//3124 -f 3120//3120 3124//3124 3031//3031 -f 3031//3031 3124//3124 3125//3125 -f 3031//3031 3125//3125 3032//3032 -f 3126//3126 3127//3127 3116//3116 -f 3116//3116 3127//3127 3128//3128 -f 3116//3116 3128//3128 3118//3118 -f 3125//3125 3129//3129 3032//3032 -f 3032//3032 3129//3129 3130//3130 -f 3032//3032 3130//3130 3126//3126 -f 3126//3126 3130//3130 3131//3131 -f 3126//3126 3131//3131 3127//3127 -f 3119//3119 3121//3121 3117//3117 -f 3117//3117 3121//3121 3120//3120 -f 3117//3117 3120//3120 3132//3132 -f 3132//3132 3120//3120 3029//3029 -f 3132//3132 3029//3029 2960//2960 -f 2960//2960 3029//3029 2962//2962 -f 3133//3133 3134//3134 3135//3135 -f 3000//3000 3136//3136 3002//3002 -f 3002//3002 3136//3136 3137//3137 -f 3002//3002 3137//3137 3004//3004 -f 3004//3004 3137//3137 3138//3138 -f 3004//3004 3138//3138 3139//3139 -f 3134//3134 3140//3140 3135//3135 -f 3135//3135 3140//3140 3141//3141 -f 3135//3135 3141//3141 3142//3142 -f 3142//3142 3141//3141 3143//3143 -f 3142//3142 3143//3143 3144//3144 -f 3143//3143 3145//3145 3144//3144 -f 3144//3144 3145//3145 3146//3146 -f 3144//3144 3146//3146 3147//3147 -f 3147//3147 3146//3146 3148//3148 -f 3147//3147 3148//3148 3040//3040 -f 3040//3040 3148//3148 3149//3149 -f 3040//3040 3149//3149 2998//2998 -f 2998//2998 3149//3149 3150//3150 -f 2998//2998 3150//3150 3000//3000 -f 3000//3000 3150//3150 3151//3151 -f 3000//3000 3151//3151 3136//3136 -f 2971//2971 2984//2984 2969//2969 -f 2969//2969 2984//2984 3152//3152 -f 2969//2969 3152//3152 2967//2967 -f 2967//2967 3152//3152 3065//3065 -f 2967//2967 3065//3065 3068//3068 -f 3068//3068 3065//3065 3067//3067 -f 3153//3153 3154//3154 3155//3155 -f 3156//3156 3157//3157 3158//3158 -f 3157//3157 3159//3159 3158//3158 -f 3158//3158 3159//3159 3160//3160 -f 3158//3158 3160//3160 2980//2980 -f 3161//3161 2982//2982 3162//3162 -f 3162//3162 2982//2982 2980//2980 -f 3162//3162 2980//2980 3163//3163 -f 3163//3163 2980//2980 3160//3160 -f 3161//3161 3164//3164 2982//2982 -f 2982//2982 3164//3164 3165//3165 -f 2982//2982 3165//3165 3153//3153 -f 3153//3153 3165//3165 3166//3166 -f 3153//3153 3166//3166 3154//3154 -f 3167//3167 3168//3168 3158//3158 -f 3158//3158 3168//3168 3169//3169 -f 3170//3170 3171//3171 3172//3172 -f 3167//3167 3158//3158 3173//3173 -f 3173//3173 3158//3158 2980//2980 -f 3173//3173 2980//2980 3174//3174 -f 3174//3174 2980//2980 3175//3175 -f 3175//3175 2980//2980 2978//2978 -f 3175//3175 2978//2978 3176//3176 -f 3172//3172 3177//3177 3170//3170 -f 3170//3170 3177//3177 3178//3178 -f 3170//3170 3178//3178 2978//2978 -f 2978//2978 3178//3178 3179//3179 -f 2978//2978 3179//3179 3176//3176 -f 2984//2984 2982//2982 3152//3152 -f 3152//3152 2982//2982 3153//3153 -f 3152//3152 3153//3153 3065//3065 -f 3065//3065 3153//3153 3180//3180 -f 3065//3065 3180//3180 3034//3034 -f 3034//3034 3180//3180 3080//3080 -f 3034//3034 3080//3080 3100//3100 -f 3100//3100 3080//3080 3082//3082 -f 2978//2978 2976//2976 3170//3170 -f 3170//3170 2976//2976 3051//3051 -f 3170//3170 3051//3051 3181//3181 -f 3181//3181 3051//3051 3182//3182 -f 3181//3181 3182//3182 3183//3183 -f 3183//3183 3182//3182 3184//3184 -f 3183//3183 3184//3184 3135//3135 -f 3135//3135 3184//3184 3185//3185 -f 3135//3135 3185//3185 3133//3133 -f 3133//3133 3185//3185 3186//3186 -f 3050//3050 3187//3187 3051//3051 -f 3051//3051 3187//3187 3058//3058 -f 3051//3051 3058//3058 3182//3182 -f 3182//3182 3058//3058 3008//3008 -f 3182//3182 3008//3008 3184//3184 -f 3184//3184 3008//3008 3006//3006 -f 3184//3184 3006//3006 3185//3185 -f 3185//3185 3006//3006 3004//3004 -f 3185//3185 3004//3004 3186//3186 -f 3186//3186 3004//3004 3139//3139 -f 3089//3089 3090//3090 3031//3031 -f 3031//3031 3090//3090 3092//3092 -f 3031//3031 3092//3092 3120//3120 -f 3120//3120 3092//3092 3188//3188 -f 3120//3120 3188//3188 3029//3029 -f 3029//3029 3188//3188 3189//3189 -f 3155//3155 3156//3156 3153//3153 -f 3153//3153 3156//3156 3158//3158 -f 3153//3153 3158//3158 3180//3180 -f 3180//3180 3158//3158 3190//3190 -f 3180//3180 3190//3190 3080//3080 -f 3080//3080 3190//3190 3191//3191 -f 3080//3080 3191//3191 3085//3085 -f 3085//3085 3191//3191 3192//3192 -f 3085//3085 3192//3192 3092//3092 -f 3092//3092 3192//3192 3193//3193 -f 3092//3092 3193//3193 3188//3188 -f 3188//3188 3193//3193 3194//3194 -f 3188//3188 3194//3194 3189//3189 -f 3189//3189 3194//3194 3195//3195 -f 3196//3196 3197//3197 3198//3198 -f 3199//3199 3200//3200 3201//3201 -f 3198//3198 3197//3197 3195//3195 -f 3189//3189 3202//3202 3203//3203 -f 3201//3201 3204//3204 3199//3199 -f 3199//3199 3204//3204 3205//3205 -f 3199//3199 3205//3205 3198//3198 -f 3198//3198 3205//3205 3206//3206 -f 3198//3198 3206//3206 3196//3196 -f 3197//3197 3207//3207 3195//3195 -f 3195//3195 3207//3207 3208//3208 -f 3195//3195 3208//3208 3189//3189 -f 3189//3189 3208//3208 3209//3209 -f 3189//3189 3209//3209 3202//3202 -f 2964//2964 3029//3029 3210//3210 -f 3210//3210 3029//3029 3189//3189 -f 3210//3210 3189//3189 3199//3199 -f 3199//3199 3189//3189 3203//3203 -f 3199//3199 3203//3203 3200//3200 -f 3147//3147 3211//3211 3212//3212 -f 3212//3212 3213//3213 3147//3147 -f 3147//3147 3213//3213 3195//3195 -f 3147//3147 3195//3195 3144//3144 -f 3144//3144 3195//3195 3194//3194 -f 3144//3144 3194//3194 3142//3142 -f 3142//3142 3194//3194 3193//3193 -f 3142//3142 3193//3193 3135//3135 -f 3135//3135 3193//3193 3192//3192 -f 3135//3135 3192//3192 3183//3183 -f 3183//3183 3192//3192 3191//3191 -f 3183//3183 3191//3191 3181//3181 -f 3181//3181 3191//3191 3190//3190 -f 3181//3181 3190//3190 3170//3170 -f 3170//3170 3190//3190 3158//3158 -f 3170//3170 3158//3158 3171//3171 -f 3171//3171 3158//3158 3169//3169 -f 3213//3213 3214//3214 3195//3195 -f 3195//3195 3214//3214 3215//3215 -f 3195//3195 3215//3215 3198//3198 -f 3198//3198 3215//3215 3216//3216 -f 3198//3198 3216//3216 3217//3217 -f 3217//3217 3218//3218 3198//3198 -f 3198//3198 3218//3218 3219//3219 -f 3198//3198 3219//3219 3220//3220 -f 3219//3219 3221//3221 3220//3220 -f 3220//3220 3221//3221 3222//3222 -f 3220//3220 3222//3222 3223//3223 -f 3042//3042 3044//3044 3040//3040 -f 3040//3040 3044//3044 3220//3220 -f 3040//3040 3220//3220 3147//3147 -f 3147//3147 3220//3220 3223//3223 -f 3147//3147 3223//3223 3211//3211 -f 3018//3018 3028//3028 3044//3044 -f 3044//3044 3028//3028 3026//3026 -f 3044//3044 3026//3026 3220//3220 -f 3220//3220 3026//3026 3024//3024 -f 3220//3220 3024//3024 3198//3198 -f 3198//3198 3024//3024 3022//3022 -f 3198//3198 3022//3022 3199//3199 -f 3199//3199 3022//3022 3020//3020 -f 3199//3199 3020//3020 3210//3210 -f 3210//3210 3020//3020 2966//2966 -f 3210//3210 2966//2966 2964//2964 -f 3224//3224 3225//3225 3226//3226 -f 3227//3227 3228//3228 3229//3229 -f 3230//3230 3231//3231 3225//3225 -f 3232//3232 3233//3233 3234//3234 -f 3235//3235 3236//3236 3224//3224 -f 3224//3224 3236//3236 3237//3237 -f 3224//3224 3237//3237 3238//3238 -f 3239//3239 3240//3240 3241//3241 -f 3241//3241 3240//3240 3242//3242 -f 3241//3241 3242//3242 3243//3243 -f 3236//3236 3244//3244 3237//3237 -f 3237//3237 3244//3244 3245//3245 -f 3237//3237 3245//3245 3246//3246 -f 3247//3247 3248//3248 3249//3249 -f 3249//3249 3248//3248 3246//3246 -f 3249//3249 3246//3246 3250//3250 -f 3250//3250 3246//3246 3245//3245 -f 2968//2968 3251//3251 3252//3252 -f 3247//3247 3253//3253 3248//3248 -f 3248//3248 3253//3253 2968//2968 -f 3248//3248 2968//2968 3254//3254 -f 3254//3254 2968//2968 3252//3252 -f 3255//3255 2970//2970 2968//2968 -f 3256//3256 3257//3257 3258//3258 -f 3256//3256 3258//3258 2975//2975 -f 3258//3258 3259//3259 2975//2975 -f 2975//2975 3259//3259 3260//3260 -f 2975//2975 3260//3260 2973//2973 -f 2973//2973 3260//3260 3261//3261 -f 2973//2973 3261//3261 3262//3262 -f 3263//3263 3009//3009 3264//3264 -f 3264//3264 3009//3009 2991//2991 -f 3264//3264 2991//2991 3262//3262 -f 2985//2985 2973//2973 2987//2987 -f 2987//2987 2973//2973 3262//3262 -f 2987//2987 3262//3262 2989//2989 -f 2989//2989 3262//3262 2991//2991 -f 3013//3013 3011//3011 3265//3265 -f 3265//3265 3011//3011 2993//2993 -f 3265//3265 2993//2993 3266//3266 -f 3266//3266 2993//2993 2995//2995 -f 3266//3266 2995//2995 3267//3267 -f 3268//3268 3269//3269 3270//3270 -f 3271//3271 3272//3272 3273//3273 -f 3273//3273 3268//3268 3271//3271 -f 3271//3271 3268//3268 3270//3270 -f 3271//3271 3270//3270 3274//3274 -f 3274//3274 3270//3270 3275//3275 -f 3274//3274 3275//3275 2959//2959 -f 3276//3276 3277//3277 3270//3270 -f 3232//3232 3278//3278 3233//3233 -f 3233//3233 3278//3278 3279//3279 -f 3233//3233 3279//3279 3271//3271 -f 3271//3271 3279//3279 3280//3280 -f 3271//3271 3280//3280 3272//3272 -f 3281//3281 3276//3276 3282//3282 -f 3282//3282 3276//3276 3270//3270 -f 3282//3282 3270//3270 3283//3283 -f 3283//3283 3270//3270 3269//3269 -f 3282//3282 3284//3284 3281//3281 -f 3281//3281 3284//3284 3285//3285 -f 3281//3281 3285//3285 3232//3232 -f 3232//3232 3285//3285 3286//3286 -f 3232//3232 3286//3286 3278//3278 -f 3287//3287 3288//3288 3289//3289 -f 3289//3289 3288//3288 3290//3290 -f 3289//3289 3290//3290 3291//3291 -f 3287//3287 3289//3289 3292//3292 -f 3292//3292 3289//3289 3293//3293 -f 3292//3292 3293//3293 3294//3294 -f 3291//3291 3295//3295 3233//3233 -f 3233//3233 3295//3295 3296//3296 -f 3233//3233 3296//3296 3234//3234 -f 3234//3234 3296//3296 3297//3297 -f 3234//3234 3297//3297 3298//3298 -f 3298//3298 3297//3297 3299//3299 -f 3298//3298 3299//3299 3300//3300 -f 3300//3300 3299//3299 3301//3301 -f 3300//3300 3301//3301 3302//3302 -f 3302//3302 3301//3301 3303//3303 -f 3302//3302 3303//3303 3304//3304 -f 3225//3225 3231//3231 3293//3293 -f 3293//3293 3231//3231 3305//3305 -f 3293//3293 3305//3305 3306//3306 -f 3307//3307 3308//3308 3224//3224 -f 3224//3224 3308//3308 3309//3309 -f 3224//3224 3309//3309 3225//3225 -f 3225//3225 3309//3309 3310//3310 -f 3225//3225 3310//3310 3230//3230 -f 3303//3303 3294//3294 3304//3304 -f 3304//3304 3294//3294 3293//3293 -f 3304//3304 3293//3293 3311//3311 -f 3311//3311 3293//3293 3306//3306 -f 3311//3311 3306//3306 3312//3312 -f 3307//3307 3224//3224 3313//3313 -f 3313//3313 3224//3224 3238//3238 -f 3313//3313 3238//3238 3314//3314 -f 3314//3314 3238//3238 3315//3315 -f 3314//3314 3315//3315 3316//3316 -f 3316//3316 3315//3315 3317//3317 -f 3316//3316 3317//3317 3312//3312 -f 3312//3312 3317//3317 3318//3318 -f 3312//3312 3318//3318 3311//3311 -f 3319//3319 3320//3320 3321//3321 -f 3322//3322 3323//3323 3324//3324 -f 3320//3320 3325//3325 3321//3321 -f 3321//3321 3325//3325 3326//3326 -f 3321//3321 3326//3326 2997//2997 -f 3326//3326 3327//3327 2997//2997 -f 2997//2997 3327//3327 3328//3328 -f 2997//2997 3328//3328 2995//2995 -f 2995//2995 3328//3328 3329//3329 -f 2995//2995 3329//3329 3267//3267 -f 3330//3330 3007//3007 3331//3331 -f 3331//3331 3007//3007 3009//3009 -f 3331//3331 3009//3009 3332//3332 -f 3332//3332 3009//3009 3263//3263 -f 3257//3257 3256//3256 3333//3333 -f 3333//3333 3256//3256 3334//3334 -f 3333//3333 3334//3334 3330//3330 -f 3335//3335 3227//3227 3336//3336 -f 3337//3337 3338//3338 3339//3339 -f 3339//3339 3338//3338 3340//3340 -f 3339//3339 3340//3340 3336//3336 -f 3336//3336 3340//3340 3341//3341 -f 3336//3336 3341//3341 3335//3335 -f 3342//3342 3343//3343 3003//3003 -f 3003//3003 3343//3343 3344//3344 -f 3003//3003 3344//3344 3001//3001 -f 3001//3001 3344//3344 3345//3345 -f 3001//3001 3345//3345 2999//2999 -f 3345//3345 3346//3346 2999//2999 -f 2999//2999 3346//3346 3347//3347 -f 2999//2999 3347//3347 2997//2997 -f 2997//2997 3347//3347 3348//3348 -f 2997//2997 3348//3348 3321//3321 -f 3321//3321 3348//3348 3349//3349 -f 3321//3321 3349//3349 3350//3350 -f 3350//3350 3349//3349 3351//3351 -f 3350//3350 3351//3351 3337//3337 -f 3337//3337 3351//3351 3352//3352 -f 3337//3337 3352//3352 3338//3338 -f 3353//3353 3021//3021 3354//3354 -f 3354//3354 3021//3021 3023//3023 -f 3354//3354 3023//3023 3355//3355 -f 3355//3355 3023//3023 3025//3025 -f 3355//3355 3025//3025 3322//3322 -f 3322//3322 3025//3025 3027//3027 -f 3322//3322 3027//3027 3323//3323 -f 3323//3323 3027//3027 3017//3017 -f 3323//3323 3017//3017 3265//3265 -f 3265//3265 3017//3017 3015//3015 -f 3265//3265 3015//3015 3013//3013 -f 2959//2959 2961//2961 3274//3274 -f 3274//3274 2961//2961 2963//2963 -f 3274//3274 2963//2963 3356//3356 -f 3356//3356 2963//2963 2965//2965 -f 3356//3356 2965//2965 3019//3019 -f 3357//3357 3358//3358 3353//3353 -f 3359//3359 3360//3360 3354//3354 -f 3354//3354 3360//3360 3361//3361 -f 3353//3353 3358//3358 3362//3362 -f 3358//3358 3363//3363 3362//3362 -f 3362//3362 3363//3363 3364//3364 -f 3362//3362 3364//3364 3365//3365 -f 3361//3361 3366//3366 3354//3354 -f 3354//3354 3366//3366 3367//3367 -f 3354//3354 3367//3367 3353//3353 -f 3353//3353 3367//3367 3368//3368 -f 3353//3353 3368//3368 3357//3357 -f 3369//3369 3370//3370 3355//3355 -f 3355//3355 3370//3370 3371//3371 -f 3371//3371 3372//3372 3355//3355 -f 3355//3355 3372//3372 3373//3373 -f 3355//3355 3373//3373 3354//3354 -f 3354//3354 3373//3373 3374//3374 -f 3354//3354 3374//3374 3375//3375 -f 3375//3375 3376//3376 3354//3354 -f 3354//3354 3376//3376 3377//3377 -f 3354//3354 3377//3377 3359//3359 -f 3359//3359 3377//3377 3378//3378 -f 3379//3379 3380//3380 3350//3350 -f 3376//3376 3381//3381 3377//3377 -f 3377//3377 3381//3381 3382//3382 -f 3377//3377 3382//3382 3379//3379 -f 3324//3324 3319//3319 3322//3322 -f 3322//3322 3319//3319 3321//3321 -f 3322//3322 3321//3321 3355//3355 -f 3355//3355 3321//3321 3350//3350 -f 3355//3355 3350//3350 3369//3369 -f 3369//3369 3350//3350 3380//3380 -f 3291//3291 3233//3233 3289//3289 -f 3289//3289 3233//3233 3271//3271 -f 3289//3289 3271//3271 3383//3383 -f 3383//3383 3271//3271 3274//3274 -f 3383//3383 3274//3274 3362//3362 -f 3362//3362 3274//3274 3356//3356 -f 3362//3362 3356//3356 3353//3353 -f 3353//3353 3356//3356 3019//3019 -f 3353//3353 3019//3019 3021//3021 -f 3384//3384 3226//3226 3385//3385 -f 3385//3385 3226//3226 3225//3225 -f 3385//3385 3225//3225 3386//3386 -f 3386//3386 3225//3225 3293//3293 -f 3386//3386 3293//3293 3387//3387 -f 3387//3387 3293//3293 3289//3289 -f 3387//3387 3289//3289 3388//3388 -f 3388//3388 3289//3289 3383//3383 -f 3388//3388 3383//3383 3389//3389 -f 3389//3389 3383//3383 3362//3362 -f 3389//3389 3362//3362 3377//3377 -f 3377//3377 3362//3362 3365//3365 -f 3377//3377 3365//3365 3378//3378 -f 3330//3330 3334//3334 3007//3007 -f 3007//3007 3334//3334 3390//3390 -f 3007//3007 3390//3390 3005//3005 -f 3005//3005 3390//3390 3229//3229 -f 3005//3005 3229//3229 3003//3003 -f 3003//3003 3229//3229 3228//3228 -f 3003//3003 3228//3228 3342//3342 -f 3253//3253 3239//3239 2968//2968 -f 2968//2968 3239//3239 3241//3241 -f 2968//2968 3241//3241 3255//3255 -f 3255//3255 3241//3241 3391//3391 -f 3391//3391 2981//2981 3255//3255 -f 3255//3255 2981//2981 2983//2983 -f 3255//3255 2983//2983 2970//2970 -f 2970//2970 2983//2983 2972//2972 -f 3392//3392 3393//3393 2981//2981 -f 3391//3391 3394//3394 3395//3395 -f 2981//2981 3393//3393 2979//2979 -f 3384//3384 3396//3396 3397//3397 -f 3395//3395 3398//3398 3391//3391 -f 3391//3391 3398//3398 3399//3399 -f 3391//3391 3399//3399 2981//2981 -f 2981//2981 3399//3399 3400//3400 -f 2981//2981 3400//3400 3392//3392 -f 3397//3397 3394//3394 3384//3384 -f 3384//3384 3394//3394 3391//3391 -f 3384//3384 3391//3391 3226//3226 -f 3226//3226 3391//3391 3241//3241 -f 3226//3226 3241//3241 3224//3224 -f 3224//3224 3241//3241 3243//3243 -f 3224//3224 3243//3243 3235//3235 -f 3393//3393 3401//3401 2979//2979 -f 2979//2979 3401//3401 3402//3402 -f 2979//2979 3402//3402 3384//3384 -f 3384//3384 3402//3402 3403//3403 -f 3384//3384 3403//3403 3396//3396 -f 3404//3404 3405//3405 3406//3406 -f 3406//3406 3405//3405 2977//2977 -f 3404//3404 3407//3407 3405//3405 -f 3405//3405 3407//3407 3408//3408 -f 3405//3405 3408//3408 3409//3409 -f 3379//3379 3350//3350 3377//3377 -f 3377//3377 3350//3350 3337//3337 -f 3377//3377 3337//3337 3389//3389 -f 3389//3389 3337//3337 3339//3339 -f 3389//3389 3339//3339 3388//3388 -f 3388//3388 3339//3339 3336//3336 -f 3388//3388 3336//3336 3387//3387 -f 3387//3387 3336//3336 3410//3410 -f 3387//3387 3410//3410 3386//3386 -f 3386//3386 3410//3410 3411//3411 -f 3386//3386 3411//3411 3385//3385 -f 3385//3385 3411//3411 3405//3405 -f 3385//3385 3405//3405 3384//3384 -f 3384//3384 3405//3405 3409//3409 -f 3384//3384 3409//3409 3412//3412 -f 3413//3413 2979//2979 3414//3414 -f 3414//3414 2979//2979 3384//3384 -f 3414//3414 3384//3384 3415//3415 -f 3415//3415 3384//3384 3412//3412 -f 3413//3413 3416//3416 2979//2979 -f 2979//2979 3416//3416 3417//3417 -f 2979//2979 3417//3417 2977//2977 -f 2977//2977 3417//3417 3418//3418 -f 2977//2977 3418//3418 3406//3406 -f 3227//3227 3229//3229 3336//3336 -f 3336//3336 3229//3229 3390//3390 -f 3336//3336 3390//3390 3410//3410 -f 3410//3410 3390//3390 3334//3334 -f 3410//3410 3334//3334 3411//3411 -f 3411//3411 3334//3334 3256//3256 -f 3411//3411 3256//3256 3405//3405 -f 3405//3405 3256//3256 2975//2975 -f 3405//3405 2975//2975 2977//2977 -f 3319//3319 3043//3043 3320//3320 -f 3320//3320 3043//3043 3042//3042 -f 3320//3320 3042//3042 3325//3325 -f 3325//3325 3042//3042 3041//3041 -f 3325//3325 3041//3041 3326//3326 -f 3326//3326 3041//3041 3039//3039 -f 3326//3326 3039//3039 3327//3327 -f 3327//3327 3039//3039 3038//3038 -f 3327//3327 3038//3038 3328//3328 -f 3328//3328 3038//3038 3037//3037 -f 3328//3328 3037//3037 3329//3329 -f 3329//3329 3037//3037 3036//3036 -f 3329//3329 3036//3036 3267//3267 -f 3267//3267 3036//3036 3047//3047 -f 3267//3267 3047//3047 3266//3266 -f 3266//3266 3047//3047 3046//3046 -f 3266//3266 3046//3046 3265//3265 -f 3265//3265 3046//3046 3045//3045 -f 3265//3265 3045//3045 3323//3323 -f 3323//3323 3045//3045 3048//3048 -f 3323//3323 3048//3048 3324//3324 -f 3324//3324 3048//3048 3049//3049 -f 3324//3324 3049//3049 3319//3319 -f 3319//3319 3049//3049 3043//3043 -f 3258//3258 3050//3050 3259//3259 -f 3259//3259 3050//3050 3052//3052 -f 3259//3259 3052//3052 3260//3260 -f 3260//3260 3052//3052 3053//3053 -f 3260//3260 3053//3053 3261//3261 -f 3261//3261 3053//3053 3057//3057 -f 3261//3261 3057//3057 3262//3262 -f 3262//3262 3057//3057 3056//3056 -f 3262//3262 3056//3056 3264//3264 -f 3264//3264 3056//3056 3055//3055 -f 3264//3264 3055//3055 3263//3263 -f 3263//3263 3055//3055 3054//3054 -f 3263//3263 3054//3054 3332//3332 -f 3332//3332 3054//3054 3061//3061 -f 3332//3332 3061//3061 3331//3331 -f 3331//3331 3061//3061 3060//3060 -f 3331//3331 3060//3060 3330//3330 -f 3330//3330 3060//3060 3059//3059 -f 3330//3330 3059//3059 3333//3333 -f 3333//3333 3059//3059 3058//3058 -f 3333//3333 3058//3058 3257//3257 -f 3257//3257 3058//3058 3187//3187 -f 3257//3257 3187//3187 3258//3258 -f 3258//3258 3187//3187 3050//3050 -f 3414//3414 3167//3167 3413//3413 -f 3413//3413 3167//3167 3173//3173 -f 3413//3413 3173//3173 3416//3416 -f 3416//3416 3173//3173 3174//3174 -f 3416//3416 3174//3174 3417//3417 -f 3417//3417 3174//3174 3175//3175 -f 3417//3417 3175//3175 3418//3418 -f 3418//3418 3175//3175 3176//3176 -f 3418//3418 3176//3176 3406//3406 -f 3406//3406 3176//3176 3179//3179 -f 3406//3406 3179//3179 3404//3404 -f 3404//3404 3179//3179 3178//3178 -f 3404//3404 3178//3178 3407//3407 -f 3407//3407 3178//3178 3177//3177 -f 3407//3407 3177//3177 3408//3408 -f 3408//3408 3177//3177 3172//3172 -f 3408//3408 3172//3172 3409//3409 -f 3409//3409 3172//3172 3171//3171 -f 3409//3409 3171//3171 3412//3412 -f 3412//3412 3171//3171 3169//3169 -f 3412//3412 3169//3169 3415//3415 -f 3415//3415 3169//3169 3168//3168 -f 3415//3415 3168//3168 3414//3414 -f 3414//3414 3168//3168 3167//3167 -f 3399//3399 3166//3166 3400//3400 -f 3400//3400 3166//3166 3165//3165 -f 3400//3400 3165//3165 3392//3392 -f 3392//3392 3165//3165 3164//3164 -f 3392//3392 3164//3164 3393//3393 -f 3393//3393 3164//3164 3161//3161 -f 3393//3393 3161//3161 3401//3401 -f 3401//3401 3161//3161 3162//3162 -f 3401//3401 3162//3162 3402//3402 -f 3402//3402 3162//3162 3163//3163 -f 3402//3402 3163//3163 3403//3403 -f 3403//3403 3163//3163 3160//3160 -f 3403//3403 3160//3160 3396//3396 -f 3396//3396 3160//3160 3159//3159 -f 3396//3396 3159//3159 3397//3397 -f 3397//3397 3159//3159 3157//3157 -f 3397//3397 3157//3157 3394//3394 -f 3394//3394 3157//3157 3156//3156 -f 3394//3394 3156//3156 3395//3395 -f 3395//3395 3156//3156 3155//3155 -f 3395//3395 3155//3155 3398//3398 -f 3398//3398 3155//3155 3154//3154 -f 3398//3398 3154//3154 3399//3399 -f 3399//3399 3154//3154 3166//3166 -f 3358//3358 3200//3200 3363//3363 -f 3363//3363 3200//3200 3203//3203 -f 3363//3363 3203//3203 3364//3364 -f 3364//3364 3203//3203 3202//3202 -f 3364//3364 3202//3202 3365//3365 -f 3365//3365 3202//3202 3209//3209 -f 3365//3365 3209//3209 3378//3378 -f 3378//3378 3209//3209 3208//3208 -f 3378//3378 3208//3208 3359//3359 -f 3359//3359 3208//3208 3207//3207 -f 3359//3359 3207//3207 3360//3360 -f 3360//3360 3207//3207 3197//3197 -f 3360//3360 3197//3197 3361//3361 -f 3361//3361 3197//3197 3196//3196 -f 3361//3361 3196//3196 3366//3366 -f 3366//3366 3196//3196 3206//3206 -f 3366//3366 3206//3206 3367//3367 -f 3367//3367 3206//3206 3205//3205 -f 3367//3367 3205//3205 3368//3368 -f 3368//3368 3205//3205 3204//3204 -f 3368//3368 3204//3204 3357//3357 -f 3357//3357 3204//3204 3201//3201 -f 3357//3357 3201//3201 3358//3358 -f 3358//3358 3201//3201 3200//3200 -f 3376//3376 3216//3216 3381//3381 -f 3381//3381 3216//3216 3215//3215 -f 3381//3381 3215//3215 3382//3382 -f 3382//3382 3215//3215 3214//3214 -f 3382//3382 3214//3214 3379//3379 -f 3379//3379 3214//3214 3213//3213 -f 3379//3379 3213//3213 3380//3380 -f 3380//3380 3213//3213 3212//3212 -f 3380//3380 3212//3212 3369//3369 -f 3369//3369 3212//3212 3211//3211 -f 3369//3369 3211//3211 3370//3370 -f 3370//3370 3211//3211 3223//3223 -f 3370//3370 3223//3223 3371//3371 -f 3371//3371 3223//3223 3222//3222 -f 3371//3371 3222//3222 3372//3372 -f 3372//3372 3222//3222 3221//3221 -f 3372//3372 3221//3221 3373//3373 -f 3373//3373 3221//3221 3219//3219 -f 3373//3373 3219//3219 3374//3374 -f 3374//3374 3219//3219 3218//3218 -f 3374//3374 3218//3218 3375//3375 -f 3375//3375 3218//3218 3217//3217 -f 3375//3375 3217//3217 3376//3376 -f 3376//3376 3217//3217 3216//3216 -f 3248//3248 3075//3075 3246//3246 -f 3246//3246 3075//3075 3062//3062 -f 3246//3246 3062//3062 3237//3237 -f 3237//3237 3062//3062 3033//3033 -f 3237//3237 3033//3033 3238//3238 -f 3238//3238 3033//3033 3035//3035 -f 3238//3238 3035//3035 3315//3315 -f 3315//3315 3035//3035 3104//3104 -f 3315//3315 3104//3104 3317//3317 -f 3317//3317 3104//3104 3106//3106 -f 3317//3317 3106//3106 3318//3318 -f 3318//3318 3106//3106 3108//3108 -f 3318//3318 3108//3108 3311//3311 -f 3311//3311 3108//3108 3109//3109 -f 3311//3311 3109//3109 3304//3304 -f 3304//3304 3109//3109 3110//3110 -f 3304//3304 3110//3110 3302//3302 -f 3302//3302 3110//3110 3111//3111 -f 3302//3302 3111//3111 3300//3300 -f 3300//3300 3111//3111 3099//3099 -f 3300//3300 3099//3099 3298//3298 -f 3298//3298 3099//3099 3097//3097 -f 3298//3298 3097//3097 3234//3234 -f 3234//3234 3097//3097 3030//3030 -f 3234//3234 3030//3030 3232//3232 -f 3232//3232 3030//3030 3032//3032 -f 3232//3232 3032//3032 3281//3281 -f 3281//3281 3032//3032 3126//3126 -f 3281//3281 3126//3126 3276//3276 -f 3276//3276 3126//3126 3116//3116 -f 3276//3276 3116//3116 3115//3115 -f 3276//3276 3115//3115 3277//3277 -f 3277//3277 3115//3115 3117//3117 -f 3277//3277 3117//3117 3270//3270 -f 3270//3270 3117//3117 3132//3132 -f 3270//3270 3132//3132 3275//3275 -f 3275//3275 3132//3132 2960//2960 -f 3275//3275 2960//2960 2959//2959 -f 2968//2968 2967//2967 3073//3073 -f 2968//2968 3073//3073 3251//3251 -f 3251//3251 3073//3073 3072//3072 -f 3251//3251 3072//3072 3252//3252 -f 3252//3252 3072//3072 3074//3074 -f 3252//3252 3074//3074 3254//3254 -f 3254//3254 3074//3074 3075//3075 -f 3254//3254 3075//3075 3248//3248 -f 3297//3297 3095//3095 3299//3299 -f 3299//3299 3095//3095 3096//3096 -f 3299//3299 3096//3096 3301//3301 -f 3301//3301 3096//3096 3098//3098 -f 3301//3301 3098//3098 3303//3303 -f 3303//3303 3098//3098 3094//3094 -f 3303//3303 3094//3094 3294//3294 -f 3294//3294 3094//3094 3093//3093 -f 3294//3294 3093//3093 3292//3292 -f 3292//3292 3093//3093 3114//3114 -f 3292//3292 3114//3114 3287//3287 -f 3287//3287 3114//3114 3113//3113 -f 3287//3287 3113//3113 3288//3288 -f 3288//3288 3113//3113 3112//3112 -f 3288//3288 3112//3112 3290//3290 -f 3290//3290 3112//3112 3091//3091 -f 3290//3290 3091//3091 3291//3291 -f 3291//3291 3091//3091 3090//3090 -f 3291//3291 3090//3090 3295//3295 -f 3295//3295 3090//3090 3089//3089 -f 3295//3295 3089//3089 3296//3296 -f 3296//3296 3089//3089 3088//3088 -f 3296//3296 3088//3088 3297//3297 -f 3297//3297 3088//3088 3095//3095 -f 3313//3313 3103//3103 3307//3307 -f 3307//3307 3103//3103 3102//3102 -f 3307//3307 3102//3102 3308//3308 -f 3308//3308 3102//3102 3101//3101 -f 3308//3308 3101//3101 3309//3309 -f 3309//3309 3101//3101 3100//3100 -f 3309//3309 3100//3100 3310//3310 -f 3310//3310 3100//3100 3082//3082 -f 3310//3310 3082//3082 3230//3230 -f 3230//3230 3082//3082 3081//3081 -f 3230//3230 3081//3081 3231//3231 -f 3231//3231 3081//3081 3087//3087 -f 3231//3231 3087//3087 3305//3305 -f 3305//3305 3087//3087 3086//3086 -f 3305//3305 3086//3086 3306//3306 -f 3306//3306 3086//3086 3084//3084 -f 3306//3306 3084//3084 3312//3312 -f 3312//3312 3084//3084 3083//3083 -f 3312//3312 3083//3083 3316//3316 -f 3316//3316 3083//3083 3107//3107 -f 3316//3316 3107//3107 3314//3314 -f 3314//3314 3107//3107 3105//3105 -f 3314//3314 3105//3105 3313//3313 -f 3313//3313 3105//3105 3103//3103 -f 3124//3124 3280//3280 3125//3125 -f 3125//3125 3280//3280 3279//3279 -f 3125//3125 3279//3279 3129//3129 -f 3129//3129 3279//3279 3278//3278 -f 3129//3129 3278//3278 3130//3130 -f 3130//3130 3278//3278 3286//3286 -f 3130//3130 3286//3286 3131//3131 -f 3131//3131 3286//3286 3285//3285 -f 3131//3131 3285//3285 3127//3127 -f 3127//3127 3285//3285 3284//3284 -f 3127//3127 3284//3284 3128//3128 -f 3128//3128 3284//3284 3282//3282 -f 3128//3128 3282//3282 3118//3118 -f 3118//3118 3282//3282 3283//3283 -f 3118//3118 3283//3283 3119//3119 -f 3119//3119 3283//3283 3269//3269 -f 3119//3119 3269//3269 3121//3121 -f 3121//3121 3269//3269 3268//3268 -f 3121//3121 3268//3268 3122//3122 -f 3122//3122 3268//3268 3273//3273 -f 3122//3122 3273//3273 3123//3123 -f 3123//3123 3273//3273 3272//3272 -f 3123//3123 3272//3272 3124//3124 -f 3124//3124 3272//3272 3280//3280 -f 3064//3064 3235//3235 3066//3066 -f 3066//3066 3235//3235 3243//3243 -f 3066//3066 3243//3243 3067//3067 -f 3067//3067 3243//3243 3242//3242 -f 3067//3067 3242//3242 3068//3068 -f 3068//3068 3242//3242 3240//3240 -f 3068//3068 3240//3240 3069//3069 -f 3069//3069 3240//3240 3239//3239 -f 3069//3069 3239//3239 3070//3070 -f 3070//3070 3239//3239 3253//3253 -f 3070//3070 3253//3253 3071//3071 -f 3071//3071 3253//3253 3247//3247 -f 3071//3071 3247//3247 3076//3076 -f 3076//3076 3247//3247 3249//3249 -f 3076//3076 3249//3249 3063//3063 -f 3063//3063 3249//3249 3250//3250 -f 3063//3063 3250//3250 3077//3077 -f 3077//3077 3250//3250 3245//3245 -f 3077//3077 3245//3245 3078//3078 -f 3078//3078 3245//3245 3244//3244 -f 3078//3078 3244//3244 3079//3079 -f 3079//3079 3244//3244 3236//3236 -f 3079//3079 3236//3236 3064//3064 -f 3064//3064 3236//3236 3235//3235 -f 3137//3137 3345//3345 3138//3138 -f 3138//3138 3345//3345 3344//3344 -f 3138//3138 3344//3344 3139//3139 -f 3139//3139 3344//3344 3343//3343 -f 3139//3139 3343//3343 3186//3186 -f 3186//3186 3343//3343 3342//3342 -f 3186//3186 3342//3342 3133//3133 -f 3133//3133 3342//3342 3228//3228 -f 3133//3133 3228//3228 3134//3134 -f 3134//3134 3228//3228 3227//3227 -f 3134//3134 3227//3227 3140//3140 -f 3140//3140 3227//3227 3335//3335 -f 3140//3140 3335//3335 3141//3141 -f 3141//3141 3335//3335 3341//3341 -f 3141//3141 3341//3341 3143//3143 -f 3143//3143 3341//3341 3340//3340 -f 3143//3143 3340//3340 3145//3145 -f 3145//3145 3340//3340 3338//3338 -f 3145//3145 3338//3338 3146//3146 -f 3146//3146 3338//3338 3352//3352 -f 3146//3146 3352//3352 3148//3148 -f 3148//3148 3352//3352 3351//3351 -f 3148//3148 3351//3351 3149//3149 -f 3149//3149 3351//3351 3349//3349 -f 3149//3149 3349//3349 3150//3150 -f 3150//3150 3349//3349 3348//3348 -f 3150//3150 3348//3348 3151//3151 -f 3151//3151 3348//3348 3347//3347 -f 3151//3151 3347//3347 3136//3136 -f 3136//3136 3347//3347 3346//3346 -f 3136//3136 3346//3346 3137//3137 -f 3137//3137 3346//3346 3345//3345 -f 3419//3419 3420//3420 3421//3421 -f 3421//3421 3420//3420 3422//3422 -f 3421//3421 3422//3422 3423//3423 -f 3423//3423 3422//3422 3424//3424 -f 3423//3423 3424//3424 3425//3425 -f 3425//3425 3424//3424 3426//3426 -f 3427//3427 3428//3428 3429//3429 -f 3429//3429 3428//3428 3430//3430 -f 3429//3429 3430//3430 3431//3431 -f 3431//3431 3430//3430 3432//3432 -f 3433//3433 3434//3434 3435//3435 -f 3434//3434 3436//3436 3437//3437 -f 3438//3438 3439//3439 3440//3440 -f 3436//3436 3441//3441 3442//3442 -f 3443//3443 3444//3444 3445//3445 -f 3446//3446 3447//3447 3448//3448 -f 3448//3448 3447//3447 3449//3449 -f 3450//3450 3451//3451 3452//3452 -f 3453//3453 3454//3454 3455//3455 -f 3456//3456 3457//3457 3458//3458 -f 3459//3459 3460//3460 3461//3461 -f 3462//3462 3463//3463 3464//3464 -f 3465//3465 3466//3466 3467//3467 -f 3468//3468 3469//3469 3470//3470 -f 3471//3471 3472//3472 3473//3473 -f 3474//3474 3475//3475 3476//3476 -f 3477//3477 3478//3478 3479//3479 -f 3480//3480 3481//3481 3482//3482 -f 3482//3482 3481//3481 3483//3483 -f 3484//3484 3430//3430 3485//3485 -f 3485//3485 3430//3430 3428//3428 -f 3485//3485 3428//3428 3486//3486 -f 3477//3477 3487//3487 3478//3478 -f 3478//3478 3487//3487 3488//3488 -f 3478//3478 3488//3488 3489//3489 -f 3489//3489 3488//3488 3490//3490 -f 3489//3489 3490//3490 3491//3491 -f 3491//3491 3490//3490 3486//3486 -f 3491//3491 3486//3486 3492//3492 -f 3492//3492 3486//3486 3428//3428 -f 3493//3493 3494//3494 3479//3479 -f 3479//3479 3494//3494 3495//3495 -f 3479//3479 3495//3495 3477//3477 -f 3475//3475 3474//3474 3496//3496 -f 3497//3497 3498//3498 3419//3419 -f 3499//3499 3500//3500 3501//3501 -f 3423//3423 3502//3502 3421//3421 -f 3421//3421 3502//3502 3503//3503 -f 3501//3501 3497//3497 3499//3499 -f 3499//3499 3497//3497 3419//3419 -f 3499//3499 3419//3419 3504//3504 -f 3504//3504 3419//3419 3421//3421 -f 3504//3504 3421//3421 3505//3505 -f 3505//3505 3421//3421 3503//3503 -f 3506//3506 3507//3507 3508//3508 -f 3508//3508 3507//3507 3509//3509 -f 3508//3508 3509//3509 3423//3423 -f 3423//3423 3509//3509 3510//3510 -f 3423//3423 3510//3510 3502//3502 -f 3511//3511 3512//3512 3513//3513 -f 3513//3513 3512//3512 3514//3514 -f 3515//3515 3516//3516 3517//3517 -f 3517//3517 3516//3516 3518//3518 -f 3514//3514 3512//3512 3519//3519 -f 3519//3519 3512//3512 3520//3520 -f 3519//3519 3520//3520 3518//3518 -f 3518//3518 3520//3520 3521//3521 -f 3518//3518 3521//3521 3517//3517 -f 3517//3517 3522//3522 3515//3515 -f 3515//3515 3522//3522 3523//3523 -f 3515//3515 3523//3523 3524//3524 -f 3524//3524 3523//3523 3525//3525 -f 3525//3525 3523//3523 3526//3526 -f 3526//3526 3523//3523 3527//3527 -f 3526//3526 3527//3527 3528//3528 -f 3529//3529 3512//3512 3530//3530 -f 3530//3530 3512//3512 3531//3531 -f 3531//3531 3512//3512 3511//3511 -f 3531//3531 3511//3511 3532//3532 -f 3511//3511 3533//3533 3532//3532 -f 3532//3532 3533//3533 3528//3528 -f 3532//3532 3528//3528 3534//3534 -f 3535//3535 3536//3536 3537//3537 -f 3538//3538 3539//3539 3540//3540 -f 3540//3540 3539//3539 3535//3535 -f 3541//3541 3542//3542 3473//3473 -f 3473//3473 3472//3472 3541//3541 -f 3541//3541 3472//3472 3543//3543 -f 3541//3541 3543//3543 3536//3536 -f 3536//3536 3543//3543 3544//3544 -f 3536//3536 3544//3544 3537//3537 -f 3537//3537 3544//3544 3545//3545 -f 3537//3537 3545//3545 3546//3546 -f 3546//3546 3545//3545 3547//3547 -f 3546//3546 3547//3547 3548//3548 -f 3549//3549 3550//3550 3465//3465 -f 3465//3465 3550//3550 3551//3551 -f 3551//3551 3550//3550 3552//3552 -f 3551//3551 3552//3552 3553//3553 -f 3553//3553 3552//3552 3554//3554 -f 3553//3553 3554//3554 3473//3473 -f 3473//3473 3554//3554 3555//3555 -f 3473//3473 3555//3555 3471//3471 -f 3556//3556 3557//3557 3558//3558 -f 3558//3558 3557//3557 3559//3559 -f 3558//3558 3559//3559 3560//3560 -f 3561//3561 3562//3562 3441//3441 -f 3563//3563 3564//3564 3560//3560 -f 3565//3565 3563//3563 3566//3566 -f 3566//3566 3563//3563 3560//3560 -f 3566//3566 3560//3560 3567//3567 -f 3567//3567 3560//3560 3559//3559 -f 3568//3568 3569//3569 3570//3570 -f 3570//3570 3569//3569 3571//3571 -f 3570//3570 3571//3571 3572//3572 -f 3572//3572 3573//3573 3570//3570 -f 3570//3570 3573//3573 3574//3574 -f 3570//3570 3574//3574 3563//3563 -f 3563//3563 3574//3574 3575//3575 -f 3563//3563 3575//3575 3564//3564 -f 3576//3576 3577//3577 3578//3578 -f 3578//3578 3577//3577 3579//3579 -f 3580//3580 3568//3568 3581//3581 -f 3581//3581 3568//3568 3570//3570 -f 3581//3581 3570//3570 3582//3582 -f 3582//3582 3570//3570 3583//3583 -f 3576//3576 3584//3584 3577//3577 -f 3577//3577 3584//3584 3585//3585 -f 3577//3577 3585//3585 3586//3586 -f 3583//3583 3570//3570 3587//3587 -f 3587//3587 3570//3570 3577//3577 -f 3587//3587 3577//3577 3588//3588 -f 3589//3589 3590//3590 3591//3591 -f 3591//3591 3590//3590 3592//3592 -f 3591//3591 3592//3592 3586//3586 -f 3586//3586 3592//3592 3593//3593 -f 3586//3586 3593//3593 3577//3577 -f 3577//3577 3593//3593 3594//3594 -f 3577//3577 3594//3594 3588//3588 -f 3595//3595 3596//3596 3597//3597 -f 3598//3598 3599//3599 3600//3600 -f 3600//3600 3599//3599 3601//3601 -f 3600//3600 3601//3601 3579//3579 -f 3579//3579 3601//3601 3602//3602 -f 3579//3579 3602//3602 3578//3578 -f 3603//3603 3600//3600 3604//3604 -f 3603//3603 3605//3605 3600//3600 -f 3600//3600 3605//3605 3606//3606 -f 3600//3600 3606//3606 3607//3607 -f 3589//3589 3608//3608 3590//3590 -f 3590//3590 3608//3608 3598//3598 -f 3590//3590 3598//3598 3597//3597 -f 3597//3597 3598//3598 3600//3600 -f 3597//3597 3600//3600 3595//3595 -f 3595//3595 3600//3600 3607//3607 -f 3595//3595 3607//3607 3609//3609 -f 3609//3609 3610//3610 3595//3595 -f 3595//3595 3610//3610 3611//3611 -f 3595//3595 3611//3611 3612//3612 -f 3612//3612 3611//3611 3613//3613 -f 3612//3612 3613//3613 3614//3614 -f 3614//3614 3615//3615 3604//3604 -f 3615//3615 3616//3616 3604//3604 -f 3604//3604 3616//3616 3617//3617 -f 3604//3604 3617//3617 3603//3603 -f 3614//3614 3604//3604 3612//3612 -f 3612//3612 3604//3604 3618//3618 -f 3612//3612 3618//3618 3619//3619 -f 3620//3620 3621//3621 3622//3622 -f 3623//3623 3624//3624 3625//3625 -f 3625//3625 3624//3624 3619//3619 -f 3625//3625 3619//3619 3626//3626 -f 3626//3626 3619//3619 3618//3618 -f 3626//3626 3618//3618 3627//3627 -f 3627//3627 3618//3618 3628//3628 -f 3627//3627 3628//3628 3629//3629 -f 3629//3629 3628//3628 3622//3622 -f 3629//3629 3622//3622 3630//3630 -f 3630//3630 3622//3622 3621//3621 -f 3622//3622 3631//3631 3620//3620 -f 3620//3620 3631//3631 3632//3632 -f 3620//3620 3632//3632 3633//3633 -f 3634//3634 3635//3635 3636//3636 -f 3636//3636 3635//3635 3637//3637 -f 3636//3636 3637//3637 3638//3638 -f 3639//3639 3640//3640 3641//3641 -f 3641//3641 3642//3642 3639//3639 -f 3639//3639 3642//3642 3643//3643 -f 3639//3639 3643//3643 3636//3636 -f 3636//3636 3643//3643 3644//3644 -f 3645//3645 3646//3646 3647//3647 -f 3644//3644 3648//3648 3636//3636 -f 3636//3636 3648//3648 3649//3649 -f 3636//3636 3649//3649 3634//3634 -f 3634//3634 3649//3649 3650//3650 -f 3634//3634 3650//3650 3651//3651 -f 3651//3651 3650//3650 3652//3652 -f 3651//3651 3652//3652 3645//3645 -f 3645//3645 3652//3652 3653//3653 -f 3645//3645 3653//3653 3646//3646 -f 3470//3470 3469//3469 3654//3654 -f 3647//3647 3640//3640 3645//3645 -f 3645//3645 3640//3640 3639//3639 -f 3645//3645 3639//3639 3655//3655 -f 3655//3655 3639//3639 3654//3654 -f 3655//3655 3654//3654 3656//3656 -f 3656//3656 3654//3654 3469//3469 -f 3657//3657 3658//3658 3659//3659 -f 3470//3470 3660//3660 3661//3661 -f 3661//3661 3662//3662 3470//3470 -f 3470//3470 3662//3662 3663//3663 -f 3470//3470 3663//3663 3468//3468 -f 3664//3664 3665//3665 3666//3666 -f 3666//3666 3665//3665 3659//3659 -f 3666//3666 3659//3659 3667//3667 -f 3667//3667 3659//3659 3658//3658 -f 3659//3659 3668//3668 3657//3657 -f 3657//3657 3668//3668 3669//3669 -f 3657//3657 3669//3669 3470//3470 -f 3470//3470 3669//3669 3670//3670 -f 3470//3470 3670//3670 3660//3660 -f 3661//3661 3671//3671 3662//3662 -f 3662//3662 3671//3671 3672//3672 -f 3662//3662 3672//3672 3673//3673 -f 3673//3673 3672//3672 3674//3674 -f 3673//3673 3674//3674 3675//3675 -f 3675//3675 3674//3674 3676//3676 -f 3675//3675 3676//3676 3664//3664 -f 3664//3664 3676//3676 3677//3677 -f 3664//3664 3677//3677 3665//3665 -f 3678//3678 3679//3679 3654//3654 -f 3654//3654 3679//3679 3470//3470 -f 3470//3470 3679//3679 3680//3680 -f 3470//3470 3680//3680 3657//3657 -f 3678//3678 3654//3654 3681//3681 -f 3681//3681 3654//3654 3682//3682 -f 3681//3681 3682//3682 3683//3683 -f 3548//3548 3549//3549 3546//3546 -f 3546//3546 3549//3549 3465//3465 -f 3546//3546 3465//3465 3684//3684 -f 3684//3684 3465//3465 3467//3467 -f 3684//3684 3467//3467 3683//3683 -f 3466//3466 3465//3465 3685//3685 -f 3685//3685 3465//3465 3551//3551 -f 3685//3685 3551//3551 3686//3686 -f 3493//3493 3687//3687 3551//3551 -f 3551//3551 3687//3687 3688//3688 -f 3551//3551 3688//3688 3686//3686 -f 3689//3689 3690//3690 3479//3479 -f 3479//3479 3690//3690 3691//3691 -f 3479//3479 3691//3691 3493//3493 -f 3493//3493 3691//3691 3692//3692 -f 3493//3493 3692//3692 3687//3687 -f 3432//3432 3693//3693 3694//3694 -f 3694//3694 3693//3693 3695//3695 -f 3696//3696 3697//3697 3482//3482 -f 3482//3482 3697//3697 3430//3430 -f 3482//3482 3430//3430 3480//3480 -f 3480//3480 3430//3430 3484//3484 -f 3698//3698 3699//3699 3700//3700 -f 3697//3697 3701//3701 3430//3430 -f 3430//3430 3701//3701 3702//3702 -f 3430//3430 3702//3702 3432//3432 -f 3432//3432 3702//3702 3703//3703 -f 3432//3432 3703//3703 3693//3693 -f 3700//3700 3704//3704 3698//3698 -f 3698//3698 3704//3704 3705//3705 -f 3698//3698 3705//3705 3482//3482 -f 3482//3482 3705//3705 3706//3706 -f 3482//3482 3706//3706 3696//3696 -f 3463//3463 3462//3462 3707//3707 -f 3462//3462 3708//3708 3707//3707 -f 3707//3707 3708//3708 3694//3694 -f 3707//3707 3694//3694 3698//3698 -f 3698//3698 3694//3694 3695//3695 -f 3698//3698 3695//3695 3699//3699 -f 3709//3709 3538//3538 3710//3710 -f 3710//3710 3538//3538 3577//3577 -f 3710//3710 3577//3577 3711//3711 -f 3711//3711 3577//3577 3570//3570 -f 3711//3711 3570//3570 3461//3461 -f 3461//3461 3570//3570 3563//3563 -f 3461//3461 3563//3563 3459//3459 -f 3459//3459 3563//3563 3712//3712 -f 3459//3459 3712//3712 3713//3713 -f 3517//3517 3714//3714 3522//3522 -f 3522//3522 3714//3714 3715//3715 -f 3522//3522 3715//3715 3712//3712 -f 3712//3712 3715//3715 3716//3716 -f 3712//3712 3716//3716 3713//3713 -f 3717//3717 3718//3718 3719//3719 -f 3719//3719 3718//3718 3720//3720 -f 3719//3719 3720//3720 3721//3721 -f 3722//3722 3723//3723 3720//3720 -f 3720//3720 3723//3723 3721//3721 -f 3721//3721 3723//3723 3724//3724 -f 3721//3721 3724//3724 3725//3725 -f 3725//3725 3724//3724 3726//3726 -f 3725//3725 3726//3726 3425//3425 -f 3425//3425 3726//3726 3727//3727 -f 3425//3425 3727//3727 3423//3423 -f 3727//3727 3728//3728 3423//3423 -f 3423//3423 3728//3728 3729//3729 -f 3423//3423 3729//3729 3508//3508 -f 3508//3508 3729//3729 3730//3730 -f 3508//3508 3730//3730 3731//3731 -f 3731//3731 3732//3732 3508//3508 -f 3508//3508 3732//3732 3733//3733 -f 3508//3508 3733//3733 3720//3720 -f 3720//3720 3733//3733 3734//3734 -f 3720//3720 3734//3734 3722//3722 -f 3735//3735 3456//3456 3496//3496 -f 3496//3496 3456//3456 3458//3458 -f 3496//3496 3458//3458 3475//3475 -f 3475//3475 3458//3458 3500//3500 -f 3475//3475 3500//3500 3476//3476 -f 3476//3476 3500//3500 3499//3499 -f 3530//3530 3736//3736 3529//3529 -f 3529//3529 3736//3736 3737//3737 -f 3529//3529 3737//3737 3496//3496 -f 3496//3496 3737//3737 3738//3738 -f 3496//3496 3738//3738 3735//3735 -f 3528//3528 3527//3527 3534//3534 -f 3534//3534 3527//3527 3739//3739 -f 3534//3534 3739//3739 3740//3740 -f 3740//3740 3739//3739 3741//3741 -f 3740//3740 3741//3741 3742//3742 -f 3743//3743 3744//3744 3745//3745 -f 3744//3744 3746//3746 3745//3745 -f 3745//3745 3746//3746 3747//3747 -f 3745//3745 3747//3747 3741//3741 -f 3741//3741 3747//3747 3748//3748 -f 3741//3741 3748//3748 3742//3742 -f 3749//3749 3750//3750 3751//3751 -f 3749//3749 3751//3751 3743//3743 -f 3751//3751 3752//3752 3743//3743 -f 3743//3743 3752//3752 3753//3753 -f 3743//3743 3753//3753 3454//3454 -f 3454//3454 3753//3753 3754//3754 -f 3454//3454 3754//3754 3755//3755 -f 3755//3755 3756//3756 3454//3454 -f 3454//3454 3756//3756 3757//3757 -f 3454//3454 3757//3757 3455//3455 -f 3455//3455 3757//3757 3758//3758 -f 3758//3758 3759//3759 3455//3455 -f 3455//3455 3759//3759 3760//3760 -f 3455//3455 3760//3760 3749//3749 -f 3749//3749 3760//3760 3761//3761 -f 3749//3749 3761//3761 3750//3750 -f 3455//3455 3762//3762 3763//3763 -f 3764//3764 3765//3765 3766//3766 -f 3766//3766 3765//3765 3453//3453 -f 3766//3766 3453//3453 3767//3767 -f 3767//3767 3453//3453 3455//3455 -f 3767//3767 3455//3455 3768//3768 -f 3768//3768 3455//3455 3763//3763 -f 3768//3768 3763//3763 3769//3769 -f 3762//3762 3455//3455 3770//3770 -f 3770//3770 3455//3455 3749//3749 -f 3770//3770 3749//3749 3771//3771 -f 3743//3743 3745//3745 3749//3749 -f 3749//3749 3745//3745 3772//3772 -f 3749//3749 3772//3772 3771//3771 -f 3773//3773 3774//3774 3775//3775 -f 3776//3776 3777//3777 3778//3778 -f 3777//3777 3774//3774 3778//3778 -f 3778//3778 3774//3774 3773//3773 -f 3778//3778 3773//3773 3745//3745 -f 3745//3745 3773//3773 3779//3779 -f 3745//3745 3779//3779 3772//3772 -f 3775//3775 3780//3780 3773//3773 -f 3773//3773 3780//3780 3781//3781 -f 3773//3773 3781//3781 3782//3782 -f 3782//3782 3781//3781 3783//3783 -f 3782//3782 3783//3783 3452//3452 -f 3452//3452 3783//3783 3784//3784 -f 3452//3452 3784//3784 3785//3785 -f 3785//3785 3786//3786 3787//3787 -f 3787//3787 3786//3786 3788//3788 -f 3787//3787 3788//3788 3778//3778 -f 3778//3778 3788//3788 3789//3789 -f 3778//3778 3789//3789 3776//3776 -f 3785//3785 3787//3787 3452//3452 -f 3452//3452 3787//3787 3790//3790 -f 3452//3452 3790//3790 3450//3450 -f 3791//3791 3792//3792 3793//3793 -f 3793//3793 3792//3792 3794//3794 -f 3794//3794 3792//3792 3795//3795 -f 3795//3795 3792//3792 3796//3796 -f 3795//3795 3796//3796 3797//3797 -f 3447//3447 3798//3798 3449//3449 -f 3449//3449 3798//3798 3799//3799 -f 3449//3449 3799//3799 3796//3796 -f 3796//3796 3799//3799 3800//3800 -f 3796//3796 3800//3800 3797//3797 -f 3801//3801 3802//3802 3803//3803 -f 3803//3803 3802//3802 3446//3446 -f 3446//3446 3448//3448 3803//3803 -f 3803//3803 3448//3448 3440//3440 -f 3803//3803 3440//3440 3804//3804 -f 3805//3805 3806//3806 3442//3442 -f 3806//3806 3807//3807 3442//3442 -f 3442//3442 3807//3807 3808//3808 -f 3442//3442 3808//3808 3440//3440 -f 3808//3808 3809//3809 3440//3440 -f 3440//3440 3809//3809 3810//3810 -f 3440//3440 3810//3810 3804//3804 -f 3804//3804 3810//3810 3811//3811 -f 3804//3804 3811//3811 3812//3812 -f 3812//3812 3813//3813 3804//3804 -f 3804//3804 3813//3813 3814//3814 -f 3804//3804 3814//3814 3815//3815 -f 3815//3815 3814//3814 3816//3816 -f 3815//3815 3816//3816 3817//3817 -f 3818//3818 3819//3819 3815//3815 -f 3815//3815 3819//3819 3820//3820 -f 3815//3815 3820//3820 3556//3556 -f 3556//3556 3820//3820 3821//3821 -f 3556//3556 3821//3821 3557//3557 -f 3562//3562 3822//3822 3441//3441 -f 3441//3441 3822//3822 3818//3818 -f 3441//3441 3818//3818 3442//3442 -f 3442//3442 3818//3818 3815//3815 -f 3442//3442 3815//3815 3805//3805 -f 3805//3805 3815//3815 3817//3817 -f 3823//3823 3682//3682 3824//3824 -f 3824//3824 3682//3682 3654//3654 -f 3824//3824 3654//3654 3825//3825 -f 3825//3825 3654//3654 3639//3639 -f 3825//3825 3639//3639 3826//3826 -f 3826//3826 3639//3639 3636//3636 -f 3826//3826 3636//3636 3827//3827 -f 3827//3827 3636//3636 3638//3638 -f 3827//3827 3638//3638 3828//3828 -f 3483//3483 3494//3494 3482//3482 -f 3482//3482 3494//3494 3493//3493 -f 3482//3482 3493//3493 3698//3698 -f 3698//3698 3493//3493 3551//3551 -f 3698//3698 3551//3551 3707//3707 -f 3707//3707 3551//3551 3553//3553 -f 3707//3707 3553//3553 3463//3463 -f 3463//3463 3553//3553 3473//3473 -f 3463//3463 3473//3473 3464//3464 -f 3464//3464 3473//3473 3542//3542 -f 3829//3829 3830//3830 3823//3823 -f 3823//3823 3830//3830 3831//3831 -f 3823//3823 3831//3831 3832//3832 -f 3683//3683 3682//3682 3684//3684 -f 3684//3684 3682//3682 3823//3823 -f 3684//3684 3823//3823 3546//3546 -f 3546//3546 3823//3823 3832//3832 -f 3546//3546 3832//3832 3833//3833 -f 3833//3833 3834//3834 3546//3546 -f 3546//3546 3834//3834 3835//3835 -f 3546//3546 3835//3835 3537//3537 -f 3537//3537 3835//3835 3836//3836 -f 3836//3836 3837//3837 3537//3537 -f 3537//3537 3837//3837 3838//3838 -f 3537//3537 3838//3838 3839//3839 -f 3838//3838 3840//3840 3839//3839 -f 3839//3839 3840//3840 3841//3841 -f 3839//3839 3841//3841 3829//3829 -f 3829//3829 3823//3823 3839//3839 -f 3839//3839 3823//3823 3824//3824 -f 3839//3839 3824//3824 3842//3842 -f 3842//3842 3824//3824 3825//3825 -f 3842//3842 3825//3825 3445//3445 -f 3445//3445 3825//3825 3826//3826 -f 3445//3445 3826//3826 3622//3622 -f 3622//3622 3826//3826 3827//3827 -f 3622//3622 3827//3827 3631//3631 -f 3631//3631 3827//3827 3828//3828 -f 3631//3631 3828//3828 3632//3632 -f 3843//3843 3844//3844 3622//3622 -f 3845//3845 3846//3846 3847//3847 -f 3847//3847 3846//3846 3848//3848 -f 3849//3849 3850//3850 3628//3628 -f 3628//3628 3850//3850 3851//3851 -f 3628//3628 3851//3851 3852//3852 -f 3622//3622 3844//3844 3445//3445 -f 3445//3445 3844//3844 3853//3853 -f 3445//3445 3853//3853 3443//3443 -f 3535//3535 3537//3537 3540//3540 -f 3540//3540 3537//3537 3839//3839 -f 3540//3540 3839//3839 3854//3854 -f 3854//3854 3839//3839 3842//3842 -f 3854//3854 3842//3842 3855//3855 -f 3855//3855 3842//3842 3445//3445 -f 3855//3855 3445//3445 3847//3847 -f 3847//3847 3445//3445 3444//3444 -f 3847//3847 3444//3444 3845//3845 -f 3852//3852 3856//3856 3628//3628 -f 3628//3628 3856//3856 3857//3857 -f 3628//3628 3857//3857 3622//3622 -f 3622//3622 3857//3857 3858//3858 -f 3622//3622 3858//3858 3843//3843 -f 3604//3604 3859//3859 3860//3860 -f 3861//3861 3862//3862 3628//3628 -f 3628//3628 3862//3862 3847//3847 -f 3628//3628 3847//3847 3849//3849 -f 3849//3849 3847//3847 3848//3848 -f 3618//3618 3863//3863 3864//3864 -f 3862//3862 3865//3865 3847//3847 -f 3847//3847 3865//3865 3866//3866 -f 3847//3847 3866//3866 3867//3867 -f 3860//3860 3868//3868 3604//3604 -f 3604//3604 3868//3868 3869//3869 -f 3604//3604 3869//3869 3618//3618 -f 3618//3618 3869//3869 3870//3870 -f 3618//3618 3870//3870 3863//3863 -f 3538//3538 3540//3540 3577//3577 -f 3577//3577 3540//3540 3854//3854 -f 3577//3577 3854//3854 3579//3579 -f 3579//3579 3854//3854 3855//3855 -f 3579//3579 3855//3855 3600//3600 -f 3600//3600 3855//3855 3847//3847 -f 3600//3600 3847//3847 3604//3604 -f 3604//3604 3847//3847 3867//3867 -f 3604//3604 3867//3867 3859//3859 -f 3864//3864 3871//3871 3618//3618 -f 3618//3618 3871//3871 3872//3872 -f 3618//3618 3872//3872 3628//3628 -f 3628//3628 3872//3872 3873//3873 -f 3628//3628 3873//3873 3861//3861 -f 3874//3874 3875//3875 3876//3876 -f 3436//3436 3442//3442 3437//3437 -f 3437//3437 3442//3442 3440//3440 -f 3437//3437 3440//3440 3876//3876 -f 3876//3876 3440//3440 3439//3439 -f 3876//3876 3439//3439 3874//3874 -f 3877//3877 3878//3878 3449//3449 -f 3879//3879 3880//3880 3448//3448 -f 3448//3448 3880//3880 3881//3881 -f 3448//3448 3881//3881 3440//3440 -f 3440//3440 3881//3881 3882//3882 -f 3440//3440 3882//3882 3438//3438 -f 3877//3877 3449//3449 3883//3883 -f 3878//3878 3884//3884 3449//3449 -f 3449//3449 3884//3884 3885//3885 -f 3449//3449 3885//3885 3448//3448 -f 3448//3448 3885//3885 3886//3886 -f 3448//3448 3886//3886 3879//3879 -f 3796//3796 3887//3887 3888//3888 -f 3889//3889 3890//3890 3891//3891 -f 3891//3891 3890//3890 3892//3892 -f 3891//3891 3892//3892 3796//3796 -f 3796//3796 3892//3892 3893//3893 -f 3796//3796 3893//3893 3887//3887 -f 3888//3888 3894//3894 3796//3796 -f 3796//3796 3894//3894 3895//3895 -f 3796//3796 3895//3895 3449//3449 -f 3449//3449 3895//3895 3896//3896 -f 3449//3449 3896//3896 3897//3897 -f 3897//3897 3898//3898 3449//3449 -f 3449//3449 3898//3898 3876//3876 -f 3449//3449 3876//3876 3883//3883 -f 3883//3883 3876//3876 3875//3875 -f 3898//3898 3899//3899 3876//3876 -f 3876//3876 3899//3899 3900//3900 -f 3876//3876 3900//3900 3901//3901 -f 3434//3434 3437//3437 3435//3435 -f 3435//3435 3437//3437 3876//3876 -f 3435//3435 3876//3876 3891//3891 -f 3891//3891 3876//3876 3901//3901 -f 3891//3891 3901//3901 3889//3889 -f 3433//3433 3435//3435 3902//3902 -f 3902//3902 3435//3435 3891//3891 -f 3902//3902 3891//3891 3903//3903 -f 3903//3903 3891//3891 3796//3796 -f 3903//3903 3796//3796 3904//3904 -f 3904//3904 3796//3796 3792//3792 -f 3904//3904 3792//3792 3905//3905 -f 3905//3905 3792//3792 3791//3791 -f 3905//3905 3791//3791 3906//3906 -f 3907//3907 3908//3908 3523//3523 -f 3909//3909 3910//3910 3433//3433 -f 3911//3911 3527//3527 3912//3912 -f 3912//3912 3527//3527 3523//3523 -f 3912//3912 3523//3523 3913//3913 -f 3913//3913 3523//3523 3908//3908 -f 3914//3914 3915//3915 3739//3739 -f 3911//3911 3916//3916 3527//3527 -f 3527//3527 3916//3916 3917//3917 -f 3527//3527 3917//3917 3739//3739 -f 3739//3739 3917//3917 3918//3918 -f 3739//3739 3918//3918 3914//3914 -f 3909//3909 3433//3433 3915//3915 -f 3910//3910 3907//3907 3433//3433 -f 3433//3433 3907//3907 3523//3523 -f 3433//3433 3523//3523 3434//3434 -f 3434//3434 3523//3523 3522//3522 -f 3434//3434 3522//3522 3436//3436 -f 3436//3436 3522//3522 3712//3712 -f 3436//3436 3712//3712 3441//3441 -f 3441//3441 3712//3712 3563//3563 -f 3441//3441 3563//3563 3561//3561 -f 3561//3561 3563//3563 3565//3565 -f 3915//3915 3433//3433 3739//3739 -f 3739//3739 3433//3433 3902//3902 -f 3739//3739 3902//3902 3741//3741 -f 3741//3741 3902//3902 3903//3903 -f 3741//3741 3903//3903 3745//3745 -f 3745//3745 3903//3903 3904//3904 -f 3745//3745 3904//3904 3778//3778 -f 3778//3778 3904//3904 3905//3905 -f 3778//3778 3905//3905 3787//3787 -f 3787//3787 3905//3905 3906//3906 -f 3787//3787 3906//3906 3790//3790 -f 3717//3717 3521//3521 3718//3718 -f 3718//3718 3521//3521 3520//3520 -f 3718//3718 3520//3520 3720//3720 -f 3720//3720 3520//3520 3512//3512 -f 3720//3720 3512//3512 3508//3508 -f 3508//3508 3512//3512 3529//3529 -f 3508//3508 3529//3529 3506//3506 -f 3506//3506 3529//3529 3496//3496 -f 3506//3506 3496//3496 3919//3919 -f 3919//3919 3496//3496 3474//3474 -f 3920//3920 3921//3921 3922//3922 -f 3923//3923 3924//3924 3925//3925 -f 3926//3926 3927//3927 3928//3928 -f 3929//3929 3930//3930 3931//3931 -f 3932//3932 3933//3933 3934//3934 -f 3935//3935 3936//3936 3937//3937 -f 3938//3938 3939//3939 3940//3940 -f 3941//3941 3942//3942 3938//3938 -f 3943//3943 3944//3944 3945//3945 -f 3946//3946 3947//3947 3948//3948 -f 3948//3948 3947//3947 3949//3949 -f 3950//3950 3951//3951 3952//3952 -f 3953//3953 3954//3954 3955//3955 -f 3955//3955 3954//3954 3429//3429 -f 3954//3954 3956//3956 3429//3429 -f 3429//3429 3956//3956 3957//3957 -f 3429//3429 3957//3957 3427//3427 -f 3427//3427 3957//3957 3958//3958 -f 3427//3427 3958//3958 3959//3959 -f 3959//3959 3958//3958 3960//3960 -f 3959//3959 3960//3960 3961//3961 -f 3961//3961 3960//3960 3950//3950 -f 3961//3961 3950//3950 3962//3962 -f 3962//3962 3950//3950 3952//3952 -f 3951//3951 3963//3963 3952//3952 -f 3952//3952 3963//3963 3964//3964 -f 3952//3952 3964//3964 3965//3965 -f 3965//3965 3964//3964 3966//3966 -f 3965//3965 3966//3966 3967//3967 -f 3967//3967 3966//3966 3968//3968 -f 3969//3969 3970//3970 3422//3422 -f 3422//3422 3970//3970 3424//3424 -f 3970//3970 3971//3971 3424//3424 -f 3424//3424 3971//3971 3972//3972 -f 3424//3424 3972//3972 3945//3945 -f 3945//3945 3972//3972 3973//3973 -f 3945//3945 3973//3973 3943//3943 -f 3974//3974 3975//3975 3976//3976 -f 3976//3976 3975//3975 3977//3977 -f 3976//3976 3977//3977 3946//3946 -f 3969//3969 3422//3422 3978//3978 -f 3978//3978 3422//3422 3420//3420 -f 3978//3978 3420//3420 3976//3976 -f 3976//3976 3420//3420 3979//3979 -f 3976//3976 3979//3979 3974//3974 -f 3980//3980 3981//3981 3982//3982 -f 3982//3982 3981//3981 3983//3983 -f 3983//3983 3981//3981 3984//3984 -f 3983//3983 3984//3984 3985//3985 -f 3980//3980 3982//3982 3986//3986 -f 3986//3986 3982//3982 3987//3987 -f 3986//3986 3987//3987 3988//3988 -f 3989//3989 3990//3990 3991//3991 -f 3991//3991 3990//3990 3992//3992 -f 3992//3992 3990//3990 3993//3993 -f 3992//3992 3993//3993 3994//3994 -f 3995//3995 3996//3996 3997//3997 -f 3998//3998 3999//3999 4000//4000 -f 4000//4000 3999//3999 4001//4001 -f 4000//4000 4001//4001 4002//4002 -f 4003//4003 4004//4004 4005//4005 -f 4006//4006 4007//4007 4004//4004 -f 4004//4004 4007//4007 4008//4008 -f 4004//4004 4008//4008 4005//4005 -f 4009//4009 4010//4010 4011//4011 -f 4011//4011 4010//4010 4012//4012 -f 4011//4011 4012//4012 4008//4008 -f 4008//4008 4012//4012 4013//4013 -f 4008//4008 4013//4013 4005//4005 -f 4001//4001 4014//4014 4002//4002 -f 4002//4002 4014//4014 4015//4015 -f 4002//4002 4015//4015 4016//4016 -f 4016//4016 4015//4015 4017//4017 -f 4016//4016 4017//4017 4018//4018 -f 4019//4019 4020//4020 4021//4021 -f 4022//4022 4023//4023 4024//4024 -f 4023//4023 4025//4025 4024//4024 -f 4024//4024 4025//4025 4026//4026 -f 4024//4024 4026//4026 4027//4027 -f 4028//4028 4029//4029 4030//4030 -f 4030//4030 4029//4029 4031//4031 -f 4030//4030 4031//4031 4027//4027 -f 4027//4027 4031//4031 4032//4032 -f 4027//4027 4032//4032 4024//4024 -f 4024//4024 4032//4032 4033//4033 -f 4024//4024 4033//4033 4034//4034 -f 4035//4035 4036//4036 4037//4037 -f 4037//4037 4036//4036 4038//4038 -f 4037//4037 4038//4038 4039//4039 -f 4028//4028 4040//4040 4029//4029 -f 4029//4029 4040//4040 4041//4041 -f 4029//4029 4041//4041 4042//4042 -f 4042//4042 4041//4041 4043//4043 -f 4042//4042 4043//4043 4044//4044 -f 3938//3938 3942//3942 3939//3939 -f 3939//3939 3942//3942 4045//4045 -f 3939//3939 4045//4045 4046//4046 -f 4047//4047 4048//4048 4042//4042 -f 4042//4042 4048//4048 4049//4049 -f 4042//4042 4049//4049 3938//3938 -f 3938//3938 4049//4049 4050//4050 -f 3938//3938 4050//4050 3941//3941 -f 4051//4051 4052//4052 4044//4044 -f 4044//4044 4052//4052 4053//4053 -f 4044//4044 4053//4053 4042//4042 -f 4042//4042 4053//4053 4054//4054 -f 4042//4042 4054//4054 4047//4047 -f 4055//4055 4056//4056 4057//4057 -f 4057//4057 4056//4056 4058//4058 -f 4057//4057 4058//4058 4059//4059 -f 4060//4060 4061//4061 3922//3922 -f 3922//3922 4061//4061 4059//4059 -f 3922//3922 4059//4059 3940//3940 -f 3940//3940 4059//4059 4058//4058 -f 3940//3940 4058//4058 3938//3938 -f 4062//4062 4063//4063 4064//4064 -f 4064//4064 4063//4063 4060//4060 -f 4065//4065 4066//4066 4067//4067 -f 4068//4068 4069//4069 4070//4070 -f 4068//4068 4070//4070 4071//4071 -f 4072//4072 4073//4073 3937//3937 -f 4071//4071 4074//4074 4068//4068 -f 4068//4068 4074//4074 4075//4075 -f 4068//4068 4075//4075 4076//4076 -f 4076//4076 4075//4075 4077//4077 -f 4076//4076 4077//4077 3936//3936 -f 3936//3936 4077//4077 4078//4078 -f 3936//3936 4078//4078 4079//4079 -f 4073//4073 4080//4080 4071//4071 -f 4071//4071 4080//4080 4081//4081 -f 4071//4071 4081//4081 4074//4074 -f 4079//4079 4082//4082 3936//3936 -f 3936//3936 4082//4082 4083//4083 -f 3936//3936 4083//4083 3937//3937 -f 3937//3937 4083//4083 4084//4084 -f 3937//3937 4084//4084 4072//4072 -f 4085//4085 4086//4086 4087//4087 -f 4087//4087 4086//4086 4088//4088 -f 4087//4087 4088//4088 3935//3935 -f 4089//4089 4090//4090 4091//4091 -f 4091//4091 4090//4090 4092//4092 -f 4091//4091 4092//4092 4085//4085 -f 4085//4085 4092//4092 4093//4093 -f 4085//4085 4093//4093 4086//4086 -f 4094//4094 4095//4095 4096//4096 -f 4097//4097 4098//4098 4091//4091 -f 4091//4091 4098//4098 4099//4099 -f 4091//4091 4099//4099 4089//4089 -f 4100//4100 4091//4091 4101//4101 -f 4101//4101 4091//4091 4102//4102 -f 4103//4103 4104//4104 4085//4085 -f 4085//4085 4104//4104 4105//4105 -f 4105//4105 4106//4106 4085//4085 -f 4085//4085 4106//4106 4107//4107 -f 4085//4085 4107//4107 4091//4091 -f 4091//4091 4107//4107 4108//4108 -f 4091//4091 4108//4108 4102//4102 -f 4096//4096 4097//4097 4094//4094 -f 4094//4094 4097//4097 4091//4091 -f 4094//4094 4091//4091 4109//4109 -f 4109//4109 4091//4091 4100//4100 -f 4109//4109 4100//4100 4110//4110 -f 4110//4110 4111//4111 4109//4109 -f 4109//4109 4111//4111 4112//4112 -f 4109//4109 4112//4112 4103//4103 -f 4103//4103 4112//4112 4113//4113 -f 4103//4103 4113//4113 4104//4104 -f 4114//4114 4115//4115 4087//4087 -f 3924//3924 4116//4116 4117//4117 -f 4087//4087 4115//4115 4085//4085 -f 4085//4085 4115//4115 4118//4118 -f 4085//4085 4118//4118 4103//4103 -f 4116//4116 3924//3924 4119//4119 -f 4119//4119 3924//3924 3923//3923 -f 4119//4119 3923//3923 4120//4120 -f 3949//3949 4121//4121 4122//4122 -f 4122//4122 4121//4121 4123//4123 -f 4122//4122 4123//4123 3982//3982 -f 3982//3982 4123//4123 4124//4124 -f 3982//3982 4124//4124 3987//3987 -f 4125//4125 4126//4126 3949//3949 -f 3949//3949 4126//4126 4127//4127 -f 3949//3949 4127//4127 4121//4121 -f 3946//3946 3977//3977 3947//3947 -f 3947//3947 3977//3977 4128//4128 -f 3947//3947 4128//4128 3949//3949 -f 3949//3949 4128//4128 4129//4129 -f 3949//3949 4129//4129 4125//4125 -f 4130//4130 4131//4131 4132//4132 -f 4132//4132 4133//4133 4130//4130 -f 4130//4130 4133//4133 4134//4134 -f 4130//4130 4134//4134 3945//3945 -f 3945//3945 4134//4134 4135//4135 -f 3426//3426 3424//3424 4136//4136 -f 4135//4135 4137//4137 3945//3945 -f 3945//3945 4137//4137 4138//4138 -f 3945//3945 4138//4138 3424//3424 -f 3424//3424 4138//4138 4139//4139 -f 3424//3424 4139//4139 4136//4136 -f 4136//4136 4140//4140 3426//3426 -f 3426//3426 4140//4140 4141//4141 -f 3426//3426 4141//4141 4142//4142 -f 4142//4142 4141//4141 4143//4143 -f 4142//4142 4143//4143 4144//4144 -f 4145//4145 4146//4146 4147//4147 -f 4147//4147 4146//4146 4144//4144 -f 4147//4147 4144//4144 4130//4130 -f 4130//4130 4144//4144 4143//4143 -f 4130//4130 4143//4143 4131//4131 -f 3985//3985 4148//4148 3983//3983 -f 3983//3983 4148//4148 4149//4149 -f 3983//3983 4149//4149 4145//4145 -f 4150//4150 4151//4151 4152//4152 -f 3985//3985 3995//3995 4148//4148 -f 4148//4148 3995//3995 3997//3997 -f 4148//4148 3997//3997 4153//4153 -f 4153//4153 3997//3997 4154//4154 -f 4155//4155 4156//4156 4157//4157 -f 4155//4155 4157//4157 4024//4024 -f 4034//4034 4035//4035 4024//4024 -f 4024//4024 4035//4035 4037//4037 -f 4024//4024 4037//4037 4155//4155 -f 4155//4155 4037//4037 4158//4158 -f 4006//4006 4159//4159 4007//4007 -f 4007//4007 4159//4159 3932//3932 -f 4007//4007 3932//3932 4160//4160 -f 4160//4160 3932//3932 3934//3934 -f 4161//4161 4162//4162 4163//4163 -f 4164//4164 4165//4165 4166//4166 -f 4166//4166 4165//4165 4167//4167 -f 4166//4166 4167//4167 4161//4161 -f 4161//4161 4167//4167 4168//4168 -f 4161//4161 4168//4168 4162//4162 -f 4169//4169 4170//4170 3955//3955 -f 3955//3955 4170//4170 4171//4171 -f 3955//3955 4171//4171 4164//4164 -f 4164//4164 4171//4171 4172//4172 -f 4172//4172 4173//4173 4164//4164 -f 4164//4164 4173//4173 4174//4174 -f 4164//4164 4174//4174 4165//4165 -f 4165//4165 4174//4174 4175//4175 -f 4165//4165 4175//4175 3431//3431 -f 4175//4175 4176//4176 3431//3431 -f 3431//3431 4176//4176 4177//4177 -f 3431//3431 4177//4177 3429//3429 -f 4177//4177 4178//4178 3429//3429 -f 3429//3429 4178//4178 4179//4179 -f 3429//3429 4179//4179 3955//3955 -f 3955//3955 4179//4179 4180//4180 -f 3955//3955 4180//4180 4169//4169 -f 4016//4016 4181//4181 4182//4182 -f 4016//4016 4182//4182 3967//3967 -f 4183//4183 4184//4184 4185//4185 -f 4185//4185 4184//4184 3965//3965 -f 4185//4185 3965//3965 4186//4186 -f 4186//4186 3965//3965 3967//3967 -f 4186//4186 3967//3967 4187//4187 -f 4187//4187 3967//3967 4182//4182 -f 4188//4188 4189//4189 4190//4190 -f 4189//4189 4191//4191 4190//4190 -f 4190//4190 4191//4191 4192//4192 -f 4190//4190 4192//4192 4193//4193 -f 4192//4192 4194//4194 4193//4193 -f 4193//4193 4194//4194 4195//4195 -f 4193//4193 4195//4195 4196//4196 -f 4196//4196 4195//4195 4197//4197 -f 4196//4196 4197//4197 4018//4018 -f 4018//4018 4197//4197 4198//4198 -f 4018//4018 4198//4198 4016//4016 -f 4016//4016 4198//4198 4199//4199 -f 4016//4016 4199//4199 4181//4181 -f 4200//4200 4201//4201 4202//4202 -f 4203//4203 4204//4204 4205//4205 -f 4206//4206 4200//4200 4207//4207 -f 4207//4207 4200//4200 4202//4202 -f 4207//4207 4202//4202 4208//4208 -f 4208//4208 4202//4202 4188//4188 -f 4207//4207 4209//4209 4206//4206 -f 4206//4206 4209//4209 4210//4210 -f 4206//4206 4210//4210 4211//4211 -f 4210//4210 4212//4212 4211//4211 -f 4211//4211 4212//4212 4213//4213 -f 4211//4211 4213//4213 4214//4214 -f 4214//4214 4213//4213 4215//4215 -f 4214//4214 4215//4215 4216//4216 -f 4204//4204 4217//4217 4205//4205 -f 4205//4205 4217//4217 4218//4218 -f 4205//4205 4218//4218 4188//4188 -f 4188//4188 4218//4218 4219//4219 -f 4188//4188 4219//4219 4208//4208 -f 4205//4205 4220//4220 4221//4221 -f 4215//4215 4203//4203 4216//4216 -f 4216//4216 4203//4203 4205//4205 -f 4216//4216 4205//4205 4222//4222 -f 4222//4222 4205//4205 4221//4221 -f 4188//4188 4190//4190 4205//4205 -f 4205//4205 4190//4190 4223//4223 -f 4205//4205 4223//4223 4220//4220 -f 4224//4224 4225//4225 4226//4226 -f 4227//4227 4228//4228 4229//4229 -f 4229//4229 4228//4228 4230//4230 -f 4229//4229 4230//4230 4226//4226 -f 4226//4226 4230//4230 4231//4231 -f 4226//4226 4231//4231 4224//4224 -f 4232//4232 4233//4233 4234//4234 -f 4225//4225 4232//4232 4226//4226 -f 4226//4226 4232//4232 4234//4234 -f 4226//4226 4234//4234 4190//4190 -f 4190//4190 4234//4234 4235//4235 -f 4190//4190 4235//4235 4223//4223 -f 4233//4233 4236//4236 4234//4234 -f 4234//4234 4236//4236 4237//4237 -f 4234//4234 4237//4237 4238//4238 -f 4238//4238 4237//4237 4239//4239 -f 4238//4238 4239//4239 4240//4240 -f 4240//4240 4239//4239 4241//4241 -f 4240//4240 4241//4241 4227//4227 -f 4229//4229 4242//4242 4243//4243 -f 4227//4227 4229//4229 4240//4240 -f 4240//4240 4229//4229 4243//4243 -f 4240//4240 4243//4243 4244//4244 -f 4245//4245 4246//4246 3931//3931 -f 3931//3931 4246//4246 4247//4247 -f 3931//3931 4247//4247 3929//3929 -f 4248//4248 4249//4249 4250//4250 -f 4250//4250 4249//4249 4251//4251 -f 4250//4250 4251//4251 4252//4252 -f 4252//4252 4251//4251 4253//4253 -f 4252//4252 4253//4253 4245//4245 -f 4245//4245 4253//4253 4254//4254 -f 4245//4245 4254//4254 4246//4246 -f 4255//4255 4256//4256 4257//4257 -f 4257//4257 4256//4256 4248//4248 -f 4248//4248 4250//4250 4257//4257 -f 4257//4257 4250//4250 3928//3928 -f 4257//4257 3928//3928 4258//4258 -f 4258//4258 3928//3928 3927//3927 -f 4258//4258 3927//3927 4259//4259 -f 4260//4260 4261//4261 4262//4262 -f 4262//4262 4261//4261 4263//4263 -f 4263//4263 4264//4264 4262//4262 -f 4262//4262 4264//4264 4265//4265 -f 4262//4262 4265//4265 3928//3928 -f 3928//3928 4265//4265 4266//4266 -f 3928//3928 4266//4266 3926//3926 -f 4259//4259 4267//4267 4258//4258 -f 4258//4258 4267//4267 4268//4268 -f 4258//4258 4268//4268 4269//4269 -f 4269//4269 4268//4268 4270//4270 -f 4269//4269 4270//4270 4260//4260 -f 4260//4260 4262//4262 4269//4269 -f 4269//4269 4262//4262 4271//4271 -f 4269//4269 4271//4271 4272//4272 -f 4273//4273 4274//4274 4262//4262 -f 4262//4262 4274//4274 4275//4275 -f 4262//4262 4275//4275 4271//4271 -f 4271//4271 4275//4275 4276//4276 -f 4271//4271 4276//4276 4277//4277 -f 4278//4278 4279//4279 4273//4273 -f 4273//4273 4279//4279 4280//4280 -f 4273//4273 4280//4280 4274//4274 -f 4276//4276 4281//4281 4277//4277 -f 4277//4277 4281//4281 4282//4282 -f 4277//4277 4282//4282 4283//4283 -f 4283//4283 4282//4282 4284//4284 -f 4283//4283 4284//4284 4285//4285 -f 4286//4286 4037//4037 4287//4287 -f 4287//4287 4037//4037 4039//4039 -f 4287//4287 4039//4039 4288//4288 -f 4286//4286 4289//4289 4037//4037 -f 4037//4037 4289//4289 4290//4290 -f 4037//4037 4290//4290 4291//4291 -f 3934//3934 4158//4158 4160//4160 -f 4160//4160 4158//4158 4037//4037 -f 4160//4160 4037//4037 4292//4292 -f 4292//4292 4037//4037 4291//4291 -f 4292//4292 4293//4293 4160//4160 -f 4160//4160 4293//4293 4294//4294 -f 4160//4160 4294//4294 4285//4285 -f 4284//4284 4295//4295 4285//4285 -f 4285//4285 4295//4295 4296//4296 -f 4285//4285 4296//4296 4160//4160 -f 4160//4160 4296//4296 4297//4297 -f 4160//4160 4297//4297 4278//4278 -f 4145//4145 4147//4147 3983//3983 -f 3983//3983 4147//4147 4130//4130 -f 3983//3983 4130//4130 3982//3982 -f 3982//3982 4130//4130 3945//3945 -f 3982//3982 3945//3945 4122//4122 -f 4122//4122 3945//3945 3944//3944 -f 4122//4122 3944//3944 3949//3949 -f 3949//3949 3944//3944 4298//4298 -f 3949//3949 4298//4298 3948//3948 -f 4299//4299 4300//4300 3923//3923 -f 4299//4299 3923//3923 4301//4301 -f 4302//4302 4303//4303 3992//3992 -f 4304//4304 4305//4305 4306//4306 -f 4306//4306 4305//4305 4307//4307 -f 4306//4306 4307//4307 4301//4301 -f 4300//4300 4302//4302 3923//3923 -f 3923//3923 4302//4302 3992//3992 -f 3923//3923 3992//3992 4120//4120 -f 4120//4120 3992//3992 3994//3994 -f 4120//4120 3994//3994 3988//3988 -f 3988//3988 3994//3994 4308//4308 -f 3988//3988 4308//4308 3986//3986 -f 4303//4303 4309//4309 3992//3992 -f 3992//3992 4309//4309 4310//4310 -f 3992//3992 4310//4310 3991//3991 -f 3991//3991 4310//4310 4311//4311 -f 3991//3991 4311//4311 4312//4312 -f 4313//4313 3925//3925 4314//4314 -f 4314//4314 3925//3925 3924//3924 -f 4314//4314 3924//3924 4087//4087 -f 4087//4087 3924//3924 4117//4117 -f 4087//4087 4117//4117 4114//4114 -f 4073//4073 4071//4071 3937//3937 -f 3937//3937 4071//4071 4315//4315 -f 3937//3937 4315//4315 4316//4316 -f 4316//4316 4315//4315 4317//4317 -f 4316//4316 4317//4317 4064//4064 -f 4070//4070 4318//4318 4071//4071 -f 4071//4071 4318//4318 4319//4319 -f 4071//4071 4319//4319 4315//4315 -f 4315//4315 4319//4319 4065//4065 -f 4315//4315 4065//4065 4317//4317 -f 4317//4317 4065//4065 4067//4067 -f 4317//4317 4067//4067 4064//4064 -f 4064//4064 4067//4067 4320//4320 -f 4064//4064 4320//4320 4062//4062 -f 4321//4321 4322//4322 4323//4323 -f 4060//4060 3922//3922 4064//4064 -f 4064//4064 3922//3922 3921//3921 -f 4064//4064 3921//3921 4324//4324 -f 4324//4324 4325//4325 4064//4064 -f 4064//4064 4325//4325 4326//4326 -f 4064//4064 4326//4326 4327//4327 -f 4328//4328 4329//4329 4313//4313 -f 4313//4313 4329//4329 4330//4330 -f 3935//3935 3937//3937 4087//4087 -f 4087//4087 3937//3937 4316//4316 -f 4087//4087 4316//4316 4314//4314 -f 4314//4314 4316//4316 4064//4064 -f 4314//4314 4064//4064 4313//4313 -f 4313//4313 4064//4064 4327//4327 -f 4313//4313 4327//4327 4328//4328 -f 4301//4301 3923//3923 4306//4306 -f 4306//4306 3923//3923 3925//3925 -f 4306//4306 3925//3925 4331//4331 -f 4331//4331 3925//3925 4313//4313 -f 4331//4331 4313//4313 4323//4323 -f 4323//4323 4313//4313 4330//4330 -f 4323//4323 4330//4330 4321//4321 -f 4332//4332 4333//4333 3922//3922 -f 3922//3922 4333//4333 4334//4334 -f 3922//3922 4334//4334 3920//3920 -f 4021//4021 4022//4022 4019//4019 -f 4019//4019 4022//4022 4024//4024 -f 4019//4019 4024//4024 4150//4150 -f 4150//4150 4024//4024 4157//4157 -f 4150//4150 4157//4157 4151//4151 -f 4043//4043 4020//4020 4044//4044 -f 4044//4044 4020//4020 4019//4019 -f 4044//4044 4019//4019 4335//4335 -f 4335//4335 4019//4019 4150//4150 -f 4335//4335 4150//4150 3997//3997 -f 3997//3997 4150//4150 4152//4152 -f 3997//3997 4152//4152 4154//4154 -f 4046//4046 4051//4051 3939//3939 -f 3939//3939 4051//4051 4044//4044 -f 3939//3939 4044//4044 4336//4336 -f 4336//4336 4044//4044 4335//4335 -f 4336//4336 4335//4335 4337//4337 -f 4337//4337 4335//4335 3997//3997 -f 4337//4337 3997//3997 3991//3991 -f 3991//3991 3997//3997 3996//3996 -f 3991//3991 3996//3996 3989//3989 -f 3940//3940 4338//4338 3922//3922 -f 3922//3922 4338//4338 4339//4339 -f 3922//3922 4339//4339 4340//4340 -f 4341//4341 4342//4342 3940//3940 -f 3940//3940 4342//4342 4343//4343 -f 3940//3940 4343//4343 4338//4338 -f 4344//4344 4345//4345 3939//3939 -f 3939//3939 4345//4345 4346//4346 -f 3939//3939 4346//4346 3940//3940 -f 3940//3940 4346//4346 4347//4347 -f 3940//3940 4347//4347 4341//4341 -f 4340//4340 4348//4348 3922//3922 -f 3922//3922 4348//4348 4323//4323 -f 3922//3922 4323//4323 4332//4332 -f 4332//4332 4323//4323 4322//4322 -f 4348//4348 4349//4349 4323//4323 -f 4323//4323 4349//4349 4350//4350 -f 4323//4323 4350//4350 4351//4351 -f 4312//4312 4304//4304 3991//3991 -f 3991//3991 4304//4304 4306//4306 -f 3991//3991 4306//4306 4337//4337 -f 4337//4337 4306//4306 4331//4331 -f 4337//4337 4331//4331 4336//4336 -f 4336//4336 4331//4331 4323//4323 -f 4336//4336 4323//4323 3939//3939 -f 3939//3939 4323//4323 4351//4351 -f 3939//3939 4351//4351 4344//4344 -f 4352//4352 4353//4353 4252//4252 -f 4252//4252 4353//4353 4354//4354 -f 4252//4252 4354//4354 4355//4355 -f 4356//4356 4357//4357 4250//4250 -f 4358//4358 4359//4359 4352//4352 -f 4352//4352 4359//4359 4360//4360 -f 4352//4352 4360//4360 4353//4353 -f 4355//4355 4361//4361 4252//4252 -f 4252//4252 4361//4361 4362//4362 -f 4252//4252 4362//4362 4250//4250 -f 4250//4250 4362//4362 4363//4363 -f 4250//4250 4363//4363 4356//4356 -f 4357//4357 4364//4364 4250//4250 -f 4250//4250 4364//4364 4365//4365 -f 4250//4250 4365//4365 3928//3928 -f 3928//3928 4365//4365 4366//4366 -f 3928//3928 4366//4366 4367//4367 -f 4367//4367 4358//4358 3928//3928 -f 3928//3928 4358//4358 4352//4352 -f 3928//3928 4352//4352 4262//4262 -f 4262//4262 4352//4352 4368//4368 -f 4262//4262 4368//4368 4273//4273 -f 4273//4273 4368//4368 4369//4369 -f 4370//4370 4371//4371 4372//4372 -f 4372//4372 4371//4371 4373//4373 -f 4372//4372 4373//4373 4245//4245 -f 4245//4245 4373//4373 4374//4374 -f 4245//4245 4374//4374 4375//4375 -f 4375//4375 4376//4376 4245//4245 -f 4245//4245 4376//4376 4377//4377 -f 4245//4245 4377//4377 4252//4252 -f 4252//4252 4377//4377 4378//4378 -f 4252//4252 4378//4378 4379//4379 -f 4380//4380 4381//4381 4352//4352 -f 4352//4352 4381//4381 4382//4382 -f 4379//4379 4383//4383 4252//4252 -f 4252//4252 4383//4383 4384//4384 -f 4252//4252 4384//4384 4352//4352 -f 4352//4352 4384//4384 4385//4385 -f 4352//4352 4385//4385 4380//4380 -f 4386//4386 4369//4369 4387//4387 -f 4387//4387 4369//4369 4368//4368 -f 4387//4387 4368//4368 4372//4372 -f 4372//4372 4368//4368 4352//4352 -f 4372//4372 4352//4352 4370//4370 -f 4370//4370 4352//4352 4382//4382 -f 4388//4388 4389//4389 4386//4386 -f 4386//4386 4389//4389 4390//4390 -f 4386//4386 4390//4390 4391//4391 -f 4278//4278 4273//4273 4160//4160 -f 4160//4160 4273//4273 4369//4369 -f 4160//4160 4369//4369 4007//4007 -f 4007//4007 4369//4369 4386//4386 -f 4007//4007 4386//4386 4008//4008 -f 4008//4008 4386//4386 4391//4391 -f 4008//4008 4391//4391 4392//4392 -f 4392//4392 4393//4393 4008//4008 -f 4008//4008 4393//4393 4394//4394 -f 4008//4008 4394//4394 4011//4011 -f 4011//4011 4394//4394 4395//4395 -f 4395//4395 4396//4396 4011//4011 -f 4011//4011 4396//4396 4397//4397 -f 4011//4011 4397//4397 4398//4398 -f 4398//4398 4397//4397 4399//4399 -f 4398//4398 4399//4399 4400//4400 -f 3930//3930 4401//4401 3931//3931 -f 3931//3931 4401//4401 4402//4402 -f 3931//3931 4402//4402 4245//4245 -f 4245//4245 4402//4402 4403//4403 -f 4245//4245 4403//4403 4372//4372 -f 4372//4372 4403//4403 4404//4404 -f 4372//4372 4404//4404 4387//4387 -f 4387//4387 4404//4404 4405//4405 -f 4387//4387 4405//4405 4386//4386 -f 4386//4386 4405//4405 4398//4398 -f 4386//4386 4398//4398 4388//4388 -f 4388//4388 4398//4398 4400//4400 -f 4401//4401 4242//4242 4402//4402 -f 4402//4402 4242//4242 4229//4229 -f 4402//4402 4229//4229 4403//4403 -f 4403//4403 4229//4229 4226//4226 -f 4403//4403 4226//4226 4404//4404 -f 4404//4404 4226//4226 4190//4190 -f 4404//4404 4190//4190 4405//4405 -f 4405//4405 4190//4190 4193//4193 -f 4405//4405 4193//4193 4398//4398 -f 4398//4398 4193//4193 4196//4196 -f 4398//4398 4196//4196 4011//4011 -f 4011//4011 4196//4196 4018//4018 -f 4011//4011 4018//4018 4009//4009 -f 4009//4009 4018//4018 4017//4017 -f 4005//4005 4406//4406 4003//4003 -f 4003//4003 4406//4406 3998//3998 -f 4003//4003 3998//3998 4163//4163 -f 4163//4163 3998//3998 4000//4000 -f 4163//4163 4000//4000 4161//4161 -f 4161//4161 4000//4000 4002//4002 -f 4161//4161 4002//4002 4166//4166 -f 4166//4166 4002//4002 4016//4016 -f 4166//4166 4016//4016 4164//4164 -f 4164//4164 4016//4016 3967//3967 -f 4164//4164 3967//3967 3955//3955 -f 3955//3955 3967//3967 3968//3968 -f 3955//3955 3968//3968 3953//3953 -f 3782//3782 4076//4076 3773//3773 -f 3773//3773 4076//4076 3936//3936 -f 3773//3773 3936//3936 3779//3779 -f 3779//3779 3936//3936 3935//3935 -f 4090//4090 3763//3763 4092//4092 -f 4092//4092 3763//3763 3762//3762 -f 4092//4092 3762//3762 4093//4093 -f 4093//4093 3762//3762 3770//3770 -f 4222//4222 4221//4221 3663//3663 -f 3663//3663 4221//4221 3468//3468 -f 4238//4238 3651//3651 4234//4234 -f 4234//4234 3651//3651 3645//3645 -f 4234//4234 3645//3645 4235//4235 -f 4235//4235 3645//3645 3655//3655 -f 3779//3779 3935//3935 3772//3772 -f 3772//3772 3935//3935 4088//4088 -f 3772//3772 4088//4088 3771//3771 -f 3771//3771 4088//4088 4086//4086 -f 3771//3771 4086//4086 3770//3770 -f 3770//3770 4086//4086 4093//4093 -f 3468//3468 4221//4221 3469//3469 -f 3469//3469 4221//4221 4220//4220 -f 3469//3469 4220//4220 3656//3656 -f 3656//3656 4220//4220 4223//4223 -f 3656//3656 4223//4223 3655//3655 -f 3655//3655 4223//4223 4235//4235 -f 4232//4232 3640//3640 4233//4233 -f 4233//4233 3640//3640 3647//3647 -f 4233//4233 3647//3647 4236//4236 -f 4236//4236 3647//3647 3646//3646 -f 4236//4236 3646//3646 4237//4237 -f 4237//4237 3646//3646 3653//3653 -f 4237//4237 3653//3653 4239//4239 -f 4239//4239 3653//3653 3652//3652 -f 4239//4239 3652//3652 4241//4241 -f 4241//4241 3652//3652 3650//3650 -f 4241//4241 3650//3650 4227//4227 -f 4227//4227 3650//3650 3649//3649 -f 4227//4227 3649//3649 4228//4228 -f 4228//4228 3649//3649 3648//3648 -f 4228//4228 3648//3648 4230//4230 -f 4230//4230 3648//3648 3644//3644 -f 4230//4230 3644//3644 4231//4231 -f 4231//4231 3644//3644 3643//3643 -f 4231//4231 3643//3643 4224//4224 -f 4224//4224 3643//3643 3642//3642 -f 4224//4224 3642//3642 4225//4225 -f 4225//4225 3642//3642 3641//3641 -f 4225//4225 3641//3641 4232//4232 -f 4232//4232 3641//3641 3640//3640 -f 4083//4083 3774//3774 4084//4084 -f 4084//4084 3774//3774 3777//3777 -f 4084//4084 3777//3777 4072//4072 -f 4072//4072 3777//3777 3776//3776 -f 4072//4072 3776//3776 4073//4073 -f 4073//4073 3776//3776 3789//3789 -f 4073//4073 3789//3789 4080//4080 -f 4080//4080 3789//3789 3788//3788 -f 4080//4080 3788//3788 4081//4081 -f 4081//4081 3788//3788 3786//3786 -f 4081//4081 3786//3786 4074//4074 -f 4074//4074 3786//3786 3785//3785 -f 4074//4074 3785//3785 4075//4075 -f 4075//4075 3785//3785 3784//3784 -f 4075//4075 3784//3784 4077//4077 -f 4077//4077 3784//3784 3783//3783 -f 4077//4077 3783//3783 4078//4078 -f 4078//4078 3783//3783 3781//3781 -f 4078//4078 3781//3781 4079//4079 -f 4079//4079 3781//3781 3780//3780 -f 4079//4079 3780//3780 4082//4082 -f 4082//4082 3780//3780 3775//3775 -f 4082//4082 3775//3775 4083//4083 -f 4083//4083 3775//3775 3774//3774 -f 4112//4112 3754//3754 4113//4113 -f 4113//4113 3754//3754 3753//3753 -f 4113//4113 3753//3753 4104//4104 -f 4104//4104 3753//3753 3752//3752 -f 4104//4104 3752//3752 4105//4105 -f 4105//4105 3752//3752 3751//3751 -f 4105//4105 3751//3751 4106//4106 -f 4106//4106 3751//3751 3750//3750 -f 4106//4106 3750//3750 4107//4107 -f 4107//4107 3750//3750 3761//3761 -f 4107//4107 3761//3761 4108//4108 -f 4108//4108 3761//3761 3760//3760 -f 4108//4108 3760//3760 4102//4102 -f 4102//4102 3760//3760 3759//3759 -f 4102//4102 3759//3759 4101//4101 -f 4101//4101 3759//3759 3758//3758 -f 4101//4101 3758//3758 4100//4100 -f 4100//4100 3758//3758 3757//3757 -f 4100//4100 3757//3757 4110//4110 -f 4110//4110 3757//3757 3756//3756 -f 4110//4110 3756//3756 4111//4111 -f 4111//4111 3756//3756 3755//3755 -f 4111//4111 3755//3755 4112//4112 -f 4112//4112 3755//3755 3754//3754 -f 4207//4207 3659//3659 4209//4209 -f 4209//4209 3659//3659 3665//3665 -f 4209//4209 3665//3665 4210//4210 -f 4210//4210 3665//3665 3677//3677 -f 4210//4210 3677//3677 4212//4212 -f 4212//4212 3677//3677 3676//3676 -f 4212//4212 3676//3676 4213//4213 -f 4213//4213 3676//3676 3674//3674 -f 4213//4213 3674//3674 4215//4215 -f 4215//4215 3674//3674 3672//3672 -f 4215//4215 3672//3672 4203//4203 -f 4203//4203 3672//3672 3671//3671 -f 4203//4203 3671//3671 4204//4204 -f 4204//4204 3671//3671 3661//3661 -f 4204//4204 3661//3661 4217//4217 -f 4217//4217 3661//3661 3660//3660 -f 4217//4217 3660//3660 4218//4218 -f 4218//4218 3660//3660 3670//3670 -f 4218//4218 3670//3670 4219//4219 -f 4219//4219 3670//3670 3669//3669 -f 4219//4219 3669//3669 4208//4208 -f 4208//4208 3669//3669 3668//3668 -f 4208//4208 3668//3668 4207//4207 -f 4207//4207 3668//3668 3659//3659 -f 3958//3958 3485//3485 3960//3960 -f 3960//3960 3485//3485 3486//3486 -f 3960//3960 3486//3486 3950//3950 -f 3950//3950 3486//3486 3490//3490 -f 3950//3950 3490//3490 3951//3951 -f 3951//3951 3490//3490 3488//3488 -f 3951//3951 3488//3488 3963//3963 -f 3963//3963 3488//3488 3487//3487 -f 3963//3963 3487//3487 3964//3964 -f 3964//3964 3487//3487 3477//3477 -f 3964//3964 3477//3477 3966//3966 -f 3966//3966 3477//3477 3495//3495 -f 3966//3966 3495//3495 3968//3968 -f 3968//3968 3495//3495 3494//3494 -f 3968//3968 3494//3494 3953//3953 -f 3953//3953 3494//3494 3483//3483 -f 3953//3953 3483//3483 3954//3954 -f 3954//3954 3483//3483 3481//3481 -f 3954//3954 3481//3481 3956//3956 -f 3956//3956 3481//3481 3480//3480 -f 3956//3956 3480//3480 3957//3957 -f 3957//3957 3480//3480 3484//3484 -f 3957//3957 3484//3484 3958//3958 -f 3958//3958 3484//3484 3485//3485 -f 4140//4140 3727//3727 4141//4141 -f 4141//4141 3727//3727 3726//3726 -f 4141//4141 3726//3726 4143//4143 -f 4143//4143 3726//3726 3724//3724 -f 4143//4143 3724//3724 4131//4131 -f 4131//4131 3724//3724 3723//3723 -f 4131//4131 3723//3723 4132//4132 -f 4132//4132 3723//3723 3722//3722 -f 4132//4132 3722//3722 4133//4133 -f 4133//4133 3722//3722 3734//3734 -f 4133//4133 3734//3734 4134//4134 -f 4134//4134 3734//3734 3733//3733 -f 4134//4134 3733//3733 4135//4135 -f 4135//4135 3733//3733 3732//3732 -f 4135//4135 3732//3732 4137//4137 -f 4137//4137 3732//3732 3731//3731 -f 4137//4137 3731//3731 4138//4138 -f 4138//4138 3731//3731 3730//3730 -f 4138//4138 3730//3730 4139//4139 -f 4139//4139 3730//3730 3729//3729 -f 4139//4139 3729//3729 4136//4136 -f 4136//4136 3729//3729 3728//3728 -f 4136//4136 3728//3728 4140//4140 -f 4140//4140 3728//3728 3727//3727 -f 4177//4177 3703//3703 4178//4178 -f 4178//4178 3703//3703 3702//3702 -f 4178//4178 3702//3702 4179//4179 -f 4179//4179 3702//3702 3701//3701 -f 4179//4179 3701//3701 4180//4180 -f 4180//4180 3701//3701 3697//3697 -f 4180//4180 3697//3697 4169//4169 -f 4169//4169 3697//3697 3696//3696 -f 4169//4169 3696//3696 4170//4170 -f 4170//4170 3696//3696 3706//3706 -f 4170//4170 3706//3706 4171//4171 -f 4171//4171 3706//3706 3705//3705 -f 4171//4171 3705//3705 4172//4172 -f 4172//4172 3705//3705 3704//3704 -f 4172//4172 3704//3704 4173//4173 -f 4173//4173 3704//3704 3700//3700 -f 4173//4173 3700//3700 4174//4174 -f 4174//4174 3700//3700 3699//3699 -f 4174//4174 3699//3699 4175//4175 -f 4175//4175 3699//3699 3695//3695 -f 4175//4175 3695//3695 4176//4176 -f 4176//4176 3695//3695 3693//3693 -f 4176//4176 3693//3693 4177//4177 -f 4177//4177 3693//3693 3703//3703 -f 3970//3970 3503//3503 3971//3971 -f 3971//3971 3503//3503 3502//3502 -f 3971//3971 3502//3502 3972//3972 -f 3972//3972 3502//3502 3510//3510 -f 3972//3972 3510//3510 3973//3973 -f 3973//3973 3510//3510 3509//3509 -f 3973//3973 3509//3509 3943//3943 -f 3943//3943 3509//3509 3507//3507 -f 3943//3943 3507//3507 3944//3944 -f 3944//3944 3507//3507 3506//3506 -f 3944//3944 3506//3506 4298//4298 -f 4298//4298 3506//3506 3919//3919 -f 4298//4298 3919//3919 3948//3948 -f 3948//3948 3919//3919 3474//3474 -f 3948//3948 3474//3474 3946//3946 -f 3946//3946 3474//3474 3476//3476 -f 3946//3946 3476//3476 3976//3976 -f 3976//3976 3476//3476 3499//3499 -f 3976//3976 3499//3499 3978//3978 -f 3978//3978 3499//3499 3504//3504 -f 3978//3978 3504//3504 3969//3969 -f 3969//3969 3504//3504 3505//3505 -f 3969//3969 3505//3505 3970//3970 -f 3970//3970 3505//3505 3503//3503 -f 4123//4123 3736//3736 4124//4124 -f 4124//4124 3736//3736 3530//3530 -f 4124//4124 3530//3530 3987//3987 -f 3987//3987 3530//3530 3531//3531 -f 3987//3987 3531//3531 3988//3988 -f 3988//3988 3531//3531 3532//3532 -f 4126//4126 3735//3735 4127//4127 -f 4127//4127 3735//3735 3738//3738 -f 4127//4127 3738//3738 4121//4121 -f 4121//4121 3738//3738 3737//3737 -f 4121//4121 3737//3737 4123//4123 -f 4123//4123 3737//3737 3736//3736 -f 3453//3453 4094//4094 3454//3454 -f 3454//3454 4094//4094 4109//4109 -f 3454//3454 4109//4109 3743//3743 -f 3743//3743 4109//4109 4103//4103 -f 3743//3743 4103//4103 3744//3744 -f 3744//3744 4103//4103 4118//4118 -f 4117//4117 3748//3748 4114//4114 -f 4114//4114 3748//3748 3747//3747 -f 4114//4114 3747//3747 4115//4115 -f 4115//4115 3747//3747 3746//3746 -f 4115//4115 3746//3746 4118//4118 -f 4118//4118 3746//3746 3744//3744 -f 3748//3748 4117//4117 3742//3742 -f 3742//3742 4117//4117 4116//4116 -f 3742//3742 4116//4116 3740//3740 -f 3740//3740 4116//4116 4119//4119 -f 3740//3740 4119//4119 3534//3534 -f 3534//3534 4119//4119 4120//4120 -f 3534//3534 4120//4120 3532//3532 -f 3532//3532 4120//4120 3988//3988 -f 3691//3691 4185//4185 3692//3692 -f 3692//3692 4185//4185 4186//4186 -f 3692//3692 4186//4186 3687//3687 -f 3687//3687 4186//4186 4187//4187 -f 4199//4199 3685//3685 4181//4181 -f 4181//4181 3685//3685 3686//3686 -f 4181//4181 3686//3686 4182//4182 -f 4182//4182 3686//3686 3688//3688 -f 4182//4182 3688//3688 4187//4187 -f 4187//4187 3688//3688 3687//3687 -f 3685//3685 4199//4199 3466//3466 -f 3466//3466 4199//4199 4198//4198 -f 3466//3466 4198//4198 3467//3467 -f 3467//3467 4198//4198 4197//4197 -f 3467//3467 4197//4197 3683//3683 -f 3683//3683 4197//4197 4195//4195 -f 3683//3683 4195//4195 3681//3681 -f 3681//3681 4195//4195 4194//4194 -f 4189//4189 3680//3680 4191//4191 -f 4191//4191 3680//3680 3679//3679 -f 4191//4191 3679//3679 4192//4192 -f 4192//4192 3679//3679 3678//3678 -f 4192//4192 3678//3678 4194//4194 -f 4194//4194 3678//3678 3681//3681 -f 4202//4202 3658//3658 4188//4188 -f 4188//4188 3658//3658 3657//3657 -f 4188//4188 3657//3657 4189//4189 -f 4189//4189 3657//3657 3680//3680 -f 4153//4153 3714//3714 4148//4148 -f 4148//4148 3714//3714 3517//3517 -f 4148//4148 3517//3517 4149//4149 -f 4149//4149 3517//3517 3521//3521 -f 4149//4149 3521//3521 4145//4145 -f 4145//4145 3521//3521 3717//3717 -f 4145//4145 3717//3717 4146//4146 -f 4146//4146 3717//3717 3719//3719 -f 4146//4146 3719//3719 4144//4144 -f 4144//4144 3719//3719 3721//3721 -f 3460//3460 4156//4156 3461//3461 -f 3461//3461 4156//4156 4155//4155 -f 3461//3461 4155//4155 3711//3711 -f 3711//3711 4155//4155 4158//4158 -f 3711//3711 4158//4158 3710//3710 -f 3710//3710 4158//4158 3934//3934 -f 3710//3710 3934//3934 3709//3709 -f 3709//3709 3934//3934 3933//3933 -f 4167//4167 3708//3708 4168//4168 -f 4168//4168 3708//3708 3462//3462 -f 4168//4168 3462//3462 4162//4162 -f 4162//4162 3462//3462 3464//3464 -f 4162//4162 3464//3464 4163//4163 -f 4163//4163 3464//3464 3542//3542 -f 4163//4163 3542//3542 4003//4003 -f 4003//4003 3542//3542 3541//3541 -f 4144//4144 3721//3721 3725//3725 -f 4144//4144 3725//3725 4142//4142 -f 4142//4142 3725//3725 3425//3425 -f 4142//4142 3425//3425 3426//3426 -f 3431//3431 3432//3432 3694//3694 -f 3431//3431 3694//3694 4165//4165 -f 4165//4165 3694//3694 3708//3708 -f 4165//4165 3708//3708 4167//4167 -f 3981//3981 3514//3514 3984//3984 -f 3984//3984 3514//3514 3519//3519 -f 3984//3984 3519//3519 3985//3985 -f 3985//3985 3519//3519 3518//3518 -f 3985//3985 3518//3518 3995//3995 -f 3995//3995 3518//3518 3516//3516 -f 3995//3995 3516//3516 3996//3996 -f 3996//3996 3516//3516 3515//3515 -f 3996//3996 3515//3515 3989//3989 -f 3989//3989 3515//3515 3524//3524 -f 3989//3989 3524//3524 3990//3990 -f 3990//3990 3524//3524 3525//3525 -f 3990//3990 3525//3525 3993//3993 -f 3993//3993 3525//3525 3526//3526 -f 3993//3993 3526//3526 3994//3994 -f 3994//3994 3526//3526 3528//3528 -f 3994//3994 3528//3528 4308//4308 -f 4308//4308 3528//3528 3533//3533 -f 4308//4308 3533//3533 3986//3986 -f 3986//3986 3533//3533 3511//3511 -f 3986//3986 3511//3511 3980//3980 -f 3980//3980 3511//3511 3513//3513 -f 3980//3980 3513//3513 3981//3981 -f 3981//3981 3513//3513 3514//3514 -f 4310//4310 3912//3912 4311//4311 -f 4311//4311 3912//3912 3913//3913 -f 4311//4311 3913//3913 4312//4312 -f 4312//4312 3913//3913 3908//3908 -f 4312//4312 3908//3908 4304//4304 -f 4304//4304 3908//3908 3907//3907 -f 4304//4304 3907//3907 4305//4305 -f 4305//4305 3907//3907 3910//3910 -f 4305//4305 3910//3910 4307//4307 -f 4307//4307 3910//3910 3909//3909 -f 4307//4307 3909//3909 4301//4301 -f 4301//4301 3909//3909 3915//3915 -f 4301//4301 3915//3915 4299//4299 -f 4299//4299 3915//3915 3914//3914 -f 4299//4299 3914//3914 4300//4300 -f 4300//4300 3914//3914 3918//3918 -f 4300//4300 3918//3918 4302//4302 -f 4302//4302 3918//3918 3917//3917 -f 4302//4302 3917//3917 4303//4303 -f 4303//4303 3917//3917 3916//3916 -f 4303//4303 3916//3916 4309//4309 -f 4309//4309 3916//3916 3911//3911 -f 4309//4309 3911//3911 4310//4310 -f 4310//4310 3911//3911 3912//3912 -f 4394//4394 3835//3835 4395//4395 -f 4395//4395 3835//3835 3834//3834 -f 4395//4395 3834//3834 4396//4396 -f 4396//4396 3834//3834 3833//3833 -f 4396//4396 3833//3833 4397//4397 -f 4397//4397 3833//3833 3832//3832 -f 4397//4397 3832//3832 4399//4399 -f 4399//4399 3832//3832 3831//3831 -f 4399//4399 3831//3831 4400//4400 -f 4400//4400 3831//3831 3830//3830 -f 4400//4400 3830//3830 4388//4388 -f 4388//4388 3830//3830 3829//3829 -f 4388//4388 3829//3829 4389//4389 -f 4389//4389 3829//3829 3841//3841 -f 4389//4389 3841//3841 4390//4390 -f 4390//4390 3841//3841 3840//3840 -f 4390//4390 3840//3840 4391//4391 -f 4391//4391 3840//3840 3838//3838 -f 4391//4391 3838//3838 4392//4392 -f 4392//4392 3838//3838 3837//3837 -f 4392//4392 3837//3837 4393//4393 -f 4393//4393 3837//3837 3836//3836 -f 4393//4393 3836//3836 4394//4394 -f 4394//4394 3836//3836 3835//3835 -f 4001//4001 3555//3555 4014//4014 -f 4014//4014 3555//3555 3554//3554 -f 4014//4014 3554//3554 4015//4015 -f 4015//4015 3554//3554 3552//3552 -f 4015//4015 3552//3552 4017//4017 -f 4017//4017 3552//3552 3550//3550 -f 4017//4017 3550//3550 4009//4009 -f 4009//4009 3550//3550 3549//3549 -f 4009//4009 3549//3549 4010//4010 -f 4010//4010 3549//3549 3548//3548 -f 4010//4010 3548//3548 4012//4012 -f 4012//4012 3548//3548 3547//3547 -f 4012//4012 3547//3547 4013//4013 -f 4013//4013 3547//3547 3545//3545 -f 4013//4013 3545//3545 4005//4005 -f 4005//4005 3545//3545 3544//3544 -f 4005//4005 3544//3544 4406//4406 -f 4406//4406 3544//3544 3543//3543 -f 4406//4406 3543//3543 3998//3998 -f 3998//3998 3543//3543 3472//3472 -f 3998//3998 3472//3472 3999//3999 -f 3999//3999 3472//3472 3471//3471 -f 3999//3999 3471//3471 4001//4001 -f 4001//4001 3471//3471 3555//3555 -f 4286//4286 3580//3580 4289//4289 -f 4289//4289 3580//3580 3581//3581 -f 4289//4289 3581//3581 4290//4290 -f 4290//4290 3581//3581 3582//3582 -f 4290//4290 3582//3582 4291//4291 -f 4291//4291 3582//3582 3583//3583 -f 4291//4291 3583//3583 4292//4292 -f 4292//4292 3583//3583 3587//3587 -f 4288//4288 3569//3569 4287//4287 -f 4287//4287 3569//3569 3568//3568 -f 4287//4287 3568//3568 4286//4286 -f 4286//4286 3568//3568 3580//3580 -f 4031//4031 3558//3558 4032//4032 -f 4032//4032 3558//3558 3560//3560 -f 4032//4032 3560//3560 4033//4033 -f 4033//4033 3560//3560 3564//3564 -f 4033//4033 3564//3564 4034//4034 -f 4034//4034 3564//3564 3575//3575 -f 4034//4034 3575//3575 4035//4035 -f 4035//4035 3575//3575 3574//3574 -f 4058//4058 3803//3803 3938//3938 -f 3938//3938 3803//3803 3804//3804 -f 3938//3938 3804//3804 4042//4042 -f 4042//4042 3804//3804 3815//3815 -f 4042//4042 3815//3815 4029//4029 -f 4029//4029 3815//3815 3556//3556 -f 4029//4029 3556//3556 4031//4031 -f 4031//4031 3556//3556 3558//3558 -f 4272//4272 3596//3596 4269//4269 -f 4269//4269 3596//3596 3595//3595 -f 4269//4269 3595//3595 4258//4258 -f 4258//4258 3595//3595 3612//3612 -f 4258//4258 3612//3612 4257//4257 -f 4257//4257 3612//3612 3619//3619 -f 4261//4261 3607//3607 4263//4263 -f 4263//4263 3607//3607 3606//3606 -f 4263//4263 3606//3606 4264//4264 -f 4264//4264 3606//3606 3605//3605 -f 4264//4264 3605//3605 4265//4265 -f 4265//4265 3605//3605 3603//3603 -f 4265//4265 3603//3603 4266//4266 -f 4266//4266 3603//3603 3617//3617 -f 4266//4266 3617//3617 3926//3926 -f 3926//3926 3617//3617 3616//3616 -f 3926//3926 3616//3616 3927//3927 -f 3927//3927 3616//3616 3615//3615 -f 3927//3927 3615//3615 4259//4259 -f 4259//4259 3615//3615 3614//3614 -f 4259//4259 3614//3614 4267//4267 -f 4267//4267 3614//3614 3613//3613 -f 4267//4267 3613//3613 4268//4268 -f 4268//4268 3613//3613 3611//3611 -f 4268//4268 3611//3611 4270//4270 -f 4270//4270 3611//3611 3610//3610 -f 4270//4270 3610//3610 4260//4260 -f 4260//4260 3610//3610 3609//3609 -f 4260//4260 3609//3609 4261//4261 -f 4261//4261 3609//3609 3607//3607 -f 4054//4054 3805//3805 4047//4047 -f 4047//4047 3805//3805 3817//3817 -f 4047//4047 3817//3817 4048//4048 -f 4048//4048 3817//3817 3816//3816 -f 4048//4048 3816//3816 4049//4049 -f 4049//4049 3816//3816 3814//3814 -f 4049//4049 3814//3814 4050//4050 -f 4050//4050 3814//3814 3813//3813 -f 4050//4050 3813//3813 3941//3941 -f 3941//3941 3813//3813 3812//3812 -f 3941//3941 3812//3812 3942//3942 -f 3942//3942 3812//3812 3811//3811 -f 3942//3942 3811//3811 4045//4045 -f 4045//4045 3811//3811 3810//3810 -f 4045//4045 3810//3810 4046//4046 -f 4046//4046 3810//3810 3809//3809 -f 4046//4046 3809//3809 4051//4051 -f 4051//4051 3809//3809 3808//3808 -f 4051//4051 3808//3808 4052//4052 -f 4052//4052 3808//3808 3807//3807 -f 4052//4052 3807//3807 4053//4053 -f 4053//4053 3807//3807 3806//3806 -f 4053//4053 3806//3806 4054//4054 -f 4054//4054 3806//3806 3805//3805 -f 4320//4320 3795//3795 4062//4062 -f 4062//4062 3795//3795 3797//3797 -f 4062//4062 3797//3797 4063//4063 -f 4063//4063 3797//3797 3800//3800 -f 4063//4063 3800//3800 4060//4060 -f 4060//4060 3800//3800 3799//3799 -f 3794//3794 3795//3795 4067//4067 -f 4067//4067 3795//3795 4320//4320 -f 3446//3446 4057//4057 3447//3447 -f 3447//3447 4057//4057 4059//4059 -f 3447//3447 4059//4059 3798//3798 -f 3798//3798 4059//4059 4061//4061 -f 3798//3798 4061//4061 3799//3799 -f 3799//3799 4061//4061 4060//4060 -f 4247//4247 4246//4246 3620//3620 -f 3620//3620 4246//4246 3621//3621 -f 4253//4253 3629//3629 4254//4254 -f 4254//4254 3629//3629 3630//3630 -f 4254//4254 3630//3630 4246//4246 -f 4246//4246 3630//3630 3621//3621 -f 4248//4248 3625//3625 4249//4249 -f 4249//4249 3625//3625 3626//3626 -f 4249//4249 3626//3626 4251//4251 -f 4251//4251 3626//3626 3627//3627 -f 4251//4251 3627//3627 4253//4253 -f 4253//4253 3627//3627 3629//3629 -f 4324//4324 3894//3894 4325//4325 -f 4325//4325 3894//3894 3888//3888 -f 4325//4325 3888//3888 4326//4326 -f 4326//4326 3888//3888 3887//3887 -f 4326//4326 3887//3887 4327//4327 -f 4327//4327 3887//3887 3893//3893 -f 4327//4327 3893//3893 4328//4328 -f 4328//4328 3893//3893 3892//3892 -f 4328//4328 3892//3892 4329//4329 -f 4329//4329 3892//3892 3890//3890 -f 4329//4329 3890//3890 4330//4330 -f 4330//4330 3890//3890 3889//3889 -f 4324//4324 3921//3921 3894//3894 -f 3894//3894 3921//3921 3895//3895 -f 4321//4321 3901//3901 4322//4322 -f 4322//4322 3901//3901 3900//3900 -f 4322//4322 3900//3900 4332//4332 -f 4332//4332 3900//3900 3899//3899 -f 4332//4332 3899//3899 4333//4333 -f 4333//4333 3899//3899 3898//3898 -f 4333//4333 3898//3898 4334//4334 -f 4334//4334 3898//3898 3897//3897 -f 4334//4334 3897//3897 3920//3920 -f 3920//3920 3897//3897 3896//3896 -f 3920//3920 3896//3896 3921//3921 -f 3921//3921 3896//3896 3895//3895 -f 4321//4321 4330//4330 3901//3901 -f 3901//3901 4330//4330 3889//3889 -f 4344//4344 3439//3439 4345//4345 -f 4345//4345 3439//3439 3438//3438 -f 4345//4345 3438//3438 4346//4346 -f 4346//4346 3438//3438 3882//3882 -f 4346//4346 3882//3882 4347//4347 -f 4347//4347 3882//3882 3881//3881 -f 4347//4347 3881//3881 4341//4341 -f 4341//4341 3881//3881 3880//3880 -f 4341//4341 3880//3880 4342//4342 -f 4342//4342 3880//3880 3879//3879 -f 4342//4342 3879//3879 4343//4343 -f 4343//4343 3879//3879 3886//3886 -f 4344//4344 4351//4351 3439//3439 -f 3439//3439 4351//4351 3874//3874 -f 4338//4338 3885//3885 4339//4339 -f 4339//4339 3885//3885 3884//3884 -f 4339//4339 3884//3884 4340//4340 -f 4340//4340 3884//3884 3878//3878 -f 4340//4340 3878//3878 4348//4348 -f 4348//4348 3878//3878 3877//3877 -f 4348//4348 3877//3877 4349//4349 -f 4349//4349 3877//3877 3883//3883 -f 4349//4349 3883//3883 4350//4350 -f 4350//4350 3883//3883 3875//3875 -f 4350//4350 3875//3875 4351//4351 -f 4351//4351 3875//3875 3874//3874 -f 4338//4338 4343//4343 3885//3885 -f 3885//3885 4343//4343 3886//3886 -f 4370//4370 3444//3444 4371//4371 -f 4371//4371 3444//3444 3443//3443 -f 4371//4371 3443//3443 4373//4373 -f 4373//4373 3443//3443 3853//3853 -f 4373//4373 3853//3853 4374//4374 -f 4374//4374 3853//3853 3844//3844 -f 4374//4374 3844//3844 4375//4375 -f 4375//4375 3844//3844 3843//3843 -f 4375//4375 3843//3843 4376//4376 -f 4376//4376 3843//3843 3858//3858 -f 4376//4376 3858//3858 4377//4377 -f 4377//4377 3858//3858 3857//3857 -f 4370//4370 4382//4382 3444//3444 -f 3444//3444 4382//4382 3845//3845 -f 4378//4378 3856//3856 4379//4379 -f 4379//4379 3856//3856 3852//3852 -f 4379//4379 3852//3852 4383//4383 -f 4383//4383 3852//3852 3851//3851 -f 4383//4383 3851//3851 4384//4384 -f 4384//4384 3851//3851 3850//3850 -f 4384//4384 3850//3850 4385//4385 -f 4385//4385 3850//3850 3849//3849 -f 4385//4385 3849//3849 4380//4380 -f 4380//4380 3849//3849 3848//3848 -f 4380//4380 3848//3848 4381//4381 -f 4381//4381 3848//3848 3846//3846 -f 4381//4381 3846//3846 4382//4382 -f 4382//4382 3846//3846 3845//3845 -f 4378//4378 4377//4377 3856//3856 -f 3856//3856 4377//4377 3857//3857 -f 4363//4363 3871//3871 4356//4356 -f 4356//4356 3871//3871 3864//3864 -f 4356//4356 3864//3864 4357//4357 -f 4357//4357 3864//3864 3863//3863 -f 4357//4357 3863//3863 4364//4364 -f 4364//4364 3863//3863 3870//3870 -f 4364//4364 3870//3870 4365//4365 -f 4365//4365 3870//3870 3869//3869 -f 4365//4365 3869//3869 4366//4366 -f 4366//4366 3869//3869 3868//3868 -f 4366//4366 3868//3868 4367//4367 -f 4367//4367 3868//3868 3860//3860 -f 4367//4367 3860//3860 4358//4358 -f 4358//4358 3860//3860 3859//3859 -f 4363//4363 4362//4362 3871//3871 -f 3871//3871 4362//4362 3872//3872 -f 4359//4359 3867//3867 4360//4360 -f 4360//4360 3867//3867 3866//3866 -f 4360//4360 3866//3866 4353//4353 -f 4353//4353 3866//3866 3865//3865 -f 4353//4353 3865//3865 4354//4354 -f 4354//4354 3865//3865 3862//3862 -f 4354//4354 3862//3862 4355//4355 -f 4355//4355 3862//3862 3861//3861 -f 4355//4355 3861//3861 4361//4361 -f 4361//4361 3861//3861 3873//3873 -f 4361//4361 3873//3873 4362//4362 -f 4362//4362 3873//3873 3872//3872 -f 4359//4359 4358//4358 3867//3867 -f 3867//3867 4358//4358 3859//3859 -f 3625//3625 4248//4248 4256//4256 -f 3625//3625 4256//4256 3623//3623 -f 3623//3623 4256//4256 4255//4255 -f 3623//3623 4255//4255 3624//3624 -f 3624//3624 4255//4255 4257//4257 -f 3624//3624 4257//4257 3619//3619 -f 4057//4057 3446//3446 3802//3802 -f 4057//4057 3802//3802 4055//4055 -f 4055//4055 3802//3802 3801//3801 -f 4055//4055 3801//3801 4056//4056 -f 4056//4056 3801//3801 3803//3803 -f 4056//4056 3803//3803 4058//4058 -f 4003//4003 3541//3541 4004//4004 -f 4004//4004 3541//3541 3536//3536 -f 4004//4004 3536//3536 4006//4006 -f 4006//4006 3536//3536 3535//3535 -f 4006//4006 3535//3535 4159//4159 -f 4159//4159 3535//3535 3539//3539 -f 4159//4159 3539//3539 3932//3932 -f 3932//3932 3539//3539 3538//3538 -f 3932//3932 3538//3538 3933//3933 -f 3933//3933 3538//3538 3709//3709 -f 4156//4156 3460//3460 4157//4157 -f 4157//4157 3460//3460 3459//3459 -f 4157//4157 3459//3459 4151//4151 -f 4151//4151 3459//3459 3713//3713 -f 4151//4151 3713//3713 4152//4152 -f 4152//4152 3713//3713 3716//3716 -f 4152//4152 3716//3716 4154//4154 -f 4154//4154 3716//3716 3715//3715 -f 4154//4154 3715//3715 4153//4153 -f 4153//4153 3715//3715 3714//3714 -f 4206//4206 4211//4211 3664//3664 -f 3664//3664 4211//4211 3675//3675 -f 3489//3489 3962//3962 3478//3478 -f 3478//3478 3962//3962 3952//3952 -f 3478//3478 3952//3952 3479//3479 -f 3479//3479 3952//3952 3965//3965 -f 3766//3766 3767//3767 4097//4097 -f 4097//4097 3767//3767 4098//4098 -f 3975//3975 3501//3501 3977//3977 -f 3977//3977 3501//3501 3500//3500 -f 3977//3977 3500//3500 4128//4128 -f 4128//4128 3500//3500 3458//3458 -f 3637//3637 4243//4243 3638//3638 -f 3638//3638 4243//4243 4242//4242 -f 3638//3638 4242//4242 3828//3828 -f 3828//3828 4242//4242 4401//4401 -f 3828//3828 4401//4401 3632//3632 -f 3632//3632 4401//4401 3930//3930 -f 3632//3632 3930//3930 3633//3633 -f 3633//3633 3930//3930 3929//3929 -f 4070//4070 3450//3450 4318//4318 -f 4318//4318 3450//3450 3790//3790 -f 4318//4318 3790//3790 4319//4319 -f 4319//4319 3790//3790 3906//3906 -f 4319//4319 3906//3906 4065//4065 -f 4065//4065 3906//3906 3791//3791 -f 4065//4065 3791//3791 4066//4066 -f 4066//4066 3791//3791 3793//3793 -f 3962//3962 3489//3489 3491//3491 -f 3962//3962 3491//3491 3961//3961 -f 3961//3961 3491//3491 3492//3492 -f 3961//3961 3492//3492 3959//3959 -f 3959//3959 3492//3492 3428//3428 -f 3959//3959 3428//3428 3427//3427 -f 3479//3479 3965//3965 4184//4184 -f 3479//3479 4184//4184 3689//3689 -f 3689//3689 4184//4184 4183//4183 -f 3689//3689 4183//4183 3690//3690 -f 3690//3690 4183//4183 4185//4185 -f 3690//3690 4185//4185 3691//3691 -f 3501//3501 3975//3975 3974//3974 -f 3501//3501 3974//3974 3497//3497 -f 3497//3497 3974//3974 3979//3979 -f 3497//3497 3979//3979 3498//3498 -f 3498//3498 3979//3979 3420//3420 -f 3498//3498 3420//3420 3419//3419 -f 4128//4128 3458//3458 3457//3457 -f 4128//4128 3457//3457 4129//4129 -f 4129//4129 3457//3457 3456//3456 -f 4129//4129 3456//3456 4125//4125 -f 4125//4125 3456//3456 3735//3735 -f 4125//4125 3735//3735 4126//4126 -f 3766//3766 4097//4097 4096//4096 -f 3766//3766 4096//4096 3764//3764 -f 3764//3764 4096//4096 4095//4095 -f 3764//3764 4095//4095 3765//3765 -f 3765//3765 4095//4095 4094//4094 -f 3765//3765 4094//4094 3453//3453 -f 4098//4098 3767//3767 3768//3768 -f 4098//4098 3768//3768 4099//4099 -f 4099//4099 3768//3768 3769//3769 -f 4099//4099 3769//3769 4089//4089 -f 4089//4089 3769//3769 3763//3763 -f 4089//4089 3763//3763 4090//4090 -f 3450//3450 4070//4070 4069//4069 -f 3450//3450 4069//4069 3451//3451 -f 3451//3451 4069//4069 4068//4068 -f 3451//3451 4068//4068 3452//3452 -f 3452//3452 4068//4068 4076//4076 -f 3452//3452 4076//4076 3782//3782 -f 4066//4066 3793//3793 4067//4067 -f 4067//4067 3793//3793 3794//3794 -f 3633//3633 3929//3929 3620//3620 -f 3620//3620 3929//3929 4247//4247 -f 4243//4243 3637//3637 3635//3635 -f 4243//4243 3635//3635 4244//4244 -f 4244//4244 3635//3635 3634//3634 -f 4244//4244 3634//3634 4240//4240 -f 4240//4240 3634//3634 3651//3651 -f 4240//4240 3651//3651 4238//4238 -f 4206//4206 3664//3664 3666//3666 -f 4206//4206 3666//3666 4200//4200 -f 4200//4200 3666//3666 3667//3667 -f 4200//4200 3667//3667 4201//4201 -f 4201//4201 3667//3667 3658//3658 -f 4201//4201 3658//3658 4202//4202 -f 3675//3675 4211//4211 4214//4214 -f 3675//3675 4214//4214 3673//3673 -f 3673//3673 4214//4214 4216//4216 -f 3673//3673 4216//4216 3662//3662 -f 3662//3662 4216//4216 4222//4222 -f 3662//3662 4222//4222 3663//3663 -f 3596//3596 4272//4272 3597//3597 -f 3597//3597 4272//4272 4271//4271 -f 4292//4292 3587//3587 4293//4293 -f 4293//4293 3587//3587 3588//3588 -f 4293//4293 3588//3588 4294//4294 -f 4294//4294 3588//3588 3594//3594 -f 4294//4294 3594//3594 4285//4285 -f 4285//4285 3594//3594 3593//3593 -f 4285//4285 3593//3593 4283//4283 -f 4283//4283 3593//3593 3592//3592 -f 3597//3597 4271//4271 3590//3590 -f 3590//3590 4271//4271 4277//4277 -f 3590//3590 4277//4277 3592//3592 -f 3592//3592 4277//4277 4283//4283 -f 4035//4035 3574//3574 4036//4036 -f 4036//4036 3574//3574 3573//3573 -f 4036//4036 3573//3573 4038//4038 -f 4038//4038 3573//3573 3572//3572 -f 4038//4038 3572//3572 4039//4039 -f 4039//4039 3572//3572 3571//3571 -f 4039//4039 3571//3571 4288//4288 -f 4288//4288 3571//3571 3569//3569 -f 4026//4026 3566//3566 4027//4027 -f 4027//4027 3566//3566 3567//3567 -f 4027//4027 3567//3567 4030//4030 -f 4030//4030 3567//3567 3559//3559 -f 4030//4030 3559//3559 4028//4028 -f 4028//4028 3559//3559 3557//3557 -f 4028//4028 3557//3557 4040//4040 -f 4040//4040 3557//3557 3821//3821 -f 4040//4040 3821//3821 4041//4041 -f 4041//4041 3821//3821 3820//3820 -f 4041//4041 3820//3820 4043//4043 -f 4043//4043 3820//3820 3819//3819 -f 4043//4043 3819//3819 4020//4020 -f 4020//4020 3819//3819 3818//3818 -f 4020//4020 3818//3818 4021//4021 -f 4021//4021 3818//3818 3822//3822 -f 4021//4021 3822//3822 4022//4022 -f 4022//4022 3822//3822 3562//3562 -f 4022//4022 3562//3562 4023//4023 -f 4023//4023 3562//3562 3561//3561 -f 4023//4023 3561//3561 4025//4025 -f 4025//4025 3561//3561 3565//3565 -f 4025//4025 3565//3565 4026//4026 -f 4026//4026 3565//3565 3566//3566 -f 4296//4296 3585//3585 4297//4297 -f 4297//4297 3585//3585 3584//3584 -f 4297//4297 3584//3584 4278//4278 -f 4278//4278 3584//3584 3576//3576 -f 4278//4278 3576//3576 4279//4279 -f 4279//4279 3576//3576 3578//3578 -f 4279//4279 3578//3578 4280//4280 -f 4280//4280 3578//3578 3602//3602 -f 4280//4280 3602//3602 4274//4274 -f 4274//4274 3602//3602 3601//3601 -f 4274//4274 3601//3601 4275//4275 -f 4275//4275 3601//3601 3599//3599 -f 4275//4275 3599//3599 4276//4276 -f 4276//4276 3599//3599 3598//3598 -f 4276//4276 3598//3598 4281//4281 -f 4281//4281 3598//3598 3608//3608 -f 4281//4281 3608//3608 4282//4282 -f 4282//4282 3608//3608 3589//3589 -f 4282//4282 3589//3589 4284//4284 -f 4284//4284 3589//3589 3591//3591 -f 4284//4284 3591//3591 4295//4295 -f 4295//4295 3591//3591 3586//3586 -f 4295//4295 3586//3586 4296//4296 -f 4296//4296 3586//3586 3585//3585 -f 4407//4407 4408//4408 4409//4409 -f 4409//4409 4408//4408 4410//4410 -f 4409//4409 4410//4410 4411//4411 -f 4411//4411 4410//4410 4412//4412 -f 4411//4411 4412//4412 4413//4413 -f 4413//4413 4412//4412 4414//4414 -f 4413//4413 4414//4414 4415//4415 -f 4415//4415 4414//4414 4416//4416 -f 4415//4415 4416//4416 4417//4417 -f 4417//4417 4416//4416 4418//4418 -f 4417//4417 4418//4418 4419//4419 -f 4419//4419 4418//4418 4420//4420 -f 4421//4421 4422//4422 4423//4423 -f 4423//4423 4422//4422 4424//4424 -f 4423//4423 4424//4424 4425//4425 -f 4425//4425 4424//4424 4426//4426 -f 4425//4425 4426//4426 4427//4427 -f 4427//4427 4426//4426 4428//4428 -f 4427//4427 4428//4428 4429//4429 -f 4429//4429 4428//4428 4430//4430 -f 4431//4431 4432//4432 4433//4433 -f 4433//4433 4432//4432 4434//4434 -f 4433//4433 4434//4434 4435//4435 -f 4435//4435 4434//4434 4436//4436 -f 4435//4435 4436//4436 4437//4437 -f 4437//4437 4436//4436 4438//4438 -f 4437//4437 4438//4438 4439//4439 -f 4439//4439 4438//4438 4440//4440 -f 4441//4441 4442//4442 4443//4443 -f 4443//4443 4442//4442 4444//4444 -f 4443//4443 4444//4444 4445//4445 -f 4445//4445 4444//4444 4446//4446 -f 4447//4447 4448//4448 4449//4449 -f 4449//4449 4448//4448 4450//4450 -f 4449//4449 4450//4450 4451//4451 -f 4451//4451 4450//4450 4452//4452 -f 4451//4451 4452//4452 4453//4453 -f 4453//4453 4452//4452 4454//4454 -f 4453//4453 4454//4454 4455//4455 -f 4455//4455 4454//4454 4456//4456 -f 4455//4455 4456//4456 4457//4457 -f 4457//4457 4456//4456 4458//4458 -f 4457//4457 4458//4458 4459//4459 -f 4459//4459 4458//4458 4460//4460 -f 4461//4461 4462//4462 4463//4463 -f 4463//4463 4462//4462 4464//4464 -f 4465//4465 4466//4466 4467//4467 -f 4467//4467 4466//4466 4468//4468 -f 4467//4467 4468//4468 4469//4469 -f 4469//4469 4468//4468 4470//4470 -f 4469//4469 4470//4470 4471//4471 -f 4471//4471 4470//4470 4472//4472 -f 4471//4471 4472//4472 4473//4473 -f 4473//4473 4472//4472 4474//4474 -f 4473//4473 4474//4474 4475//4475 -f 4475//4475 4474//4474 4476//4476 -f 4475//4475 4476//4476 4462//4462 -f 4462//4462 4476//4476 4464//4464 -f 4477//4477 4466//4466 4478//4478 -f 4478//4478 4466//4466 4465//4465 -f 4479//4479 4480//4480 4481//4481 -f 4481//4481 4480//4480 4482//4482 -f 4481//4481 4482//4482 4483//4483 -f 4483//4483 4482//4482 4484//4484 -f 4483//4483 4484//4484 4485//4485 -f 4485//4485 4484//4484 4486//4486 -f 4485//4485 4486//4486 4487//4487 -f 4487//4487 4486//4486 4488//4488 -f 4487//4487 4488//4488 4489//4489 -f 4489//4489 4488//4488 4490//4490 -f 4489//4489 4490//4490 4491//4491 -f 4491//4491 4490//4490 4492//4492 -f 4491//4491 4492//4492 4493//4493 -f 4493//4493 4492//4492 4494//4494 -f 4495//4495 4496//4496 4497//4497 -f 4497//4497 4496//4496 4498//4498 -f 4497//4497 4498//4498 4499//4499 -f 4499//4499 4498//4498 4500//4500 -f 4501//4501 4502//4502 4503//4503 -f 4504//4504 4505//4505 4506//4506 -f 4507//4507 4508//4508 4427//4427 -f 4509//4509 4510//4510 4511//4511 -f 4512//4512 4513//4513 4514//4514 -f 4464//4464 4476//4476 4515//4515 -f 4466//4466 4477//4477 4516//4516 -f 4516//4516 4477//4477 4517//4517 -f 4518//4518 4519//4519 4520//4520 -f 4521//4521 4522//4522 4523//4523 -f 4524//4524 4525//4525 4526//4526 -f 4527//4527 4528//4528 4529//4529 -f 4530//4530 4531//4531 4532//4532 -f 4532//4532 4531//4531 4533//4533 -f 4532//4532 4533//4533 4534//4534 -f 4534//4534 4533//4533 4535//4535 -f 4534//4534 4535//4535 4536//4536 -f 4537//4537 4538//4538 4539//4539 -f 4539//4539 4538//4538 4540//4540 -f 4539//4539 4540//4540 4529//4529 -f 4529//4529 4540//4540 4541//4541 -f 4529//4529 4541//4541 4527//4527 -f 4542//4542 4543//4543 4544//4544 -f 4545//4545 4546//4546 4547//4547 -f 4547//4547 4546//4546 4548//4548 -f 4543//4543 4549//4549 4544//4544 -f 4544//4544 4549//4549 4550//4550 -f 4544//4544 4550//4550 4532//4532 -f 4545//4545 4547//4547 4551//4551 -f 4551//4551 4547//4547 4529//4529 -f 4551//4551 4529//4529 4552//4552 -f 4552//4552 4529//4529 4528//4528 -f 4552//4552 4528//4528 4553//4553 -f 4550//4550 4554//4554 4532//4532 -f 4532//4532 4554//4554 4555//4555 -f 4532//4532 4555//4555 4530//4530 -f 4530//4530 4555//4555 4553//4553 -f 4530//4530 4553//4553 4556//4556 -f 4556//4556 4553//4553 4528//4528 -f 4557//4557 4558//4558 4559//4559 -f 4559//4559 4558//4558 4560//4560 -f 4559//4559 4560//4560 4561//4561 -f 4562//4562 4563//4563 4564//4564 -f 4564//4564 4563//4563 4565//4565 -f 4564//4564 4565//4565 4566//4566 -f 4566//4566 4565//4565 4567//4567 -f 4567//4567 4568//4568 4566//4566 -f 4566//4566 4568//4568 4569//4569 -f 4566//4566 4569//4569 4570//4570 -f 4570//4570 4569//4569 4571//4571 -f 4570//4570 4571//4571 4572//4572 -f 4572//4572 4571//4571 4573//4573 -f 4572//4572 4573//4573 4557//4557 -f 4557//4557 4573//4573 4574//4574 -f 4557//4557 4574//4574 4558//4558 -f 4575//4575 4576//4576 4577//4577 -f 4578//4578 4579//4579 4580//4580 -f 4580//4580 4579//4579 4581//4581 -f 4580//4580 4581//4581 4575//4575 -f 4575//4575 4581//4581 4582//4582 -f 4575//4575 4582//4582 4576//4576 -f 4577//4577 4583//4583 4584//4584 -f 4584//4584 4583//4583 4585//4585 -f 4584//4584 4585//4585 4586//4586 -f 4586//4586 4585//4585 4587//4587 -f 4588//4588 4437//4437 4589//4589 -f 4589//4589 4437//4437 4439//4439 -f 4589//4589 4439//4439 4587//4587 -f 4587//4587 4439//4439 4590//4590 -f 4587//4587 4590//4590 4586//4586 -f 4423//4423 4591//4591 4592//4592 -f 4423//4423 4592//4592 4421//4421 -f 4421//4421 4592//4592 4593//4593 -f 4421//4421 4593//4593 4594//4594 -f 4594//4594 4593//4593 4595//4595 -f 4595//4595 4593//4593 4596//4596 -f 4595//4595 4596//4596 4513//4513 -f 4596//4596 4597//4597 4513//4513 -f 4513//4513 4597//4597 4598//4598 -f 4513//4513 4598//4598 4514//4514 -f 4514//4514 4598//4598 4599//4599 -f 4599//4599 4600//4600 4514//4514 -f 4514//4514 4600//4600 4601//4601 -f 4514//4514 4601//4601 4602//4602 -f 4602//4602 4601//4601 4603//4603 -f 4603//4603 4604//4604 4602//4602 -f 4602//4602 4604//4604 4605//4605 -f 4602//4602 4605//4605 4606//4606 -f 4607//4607 4608//4608 4559//4559 -f 4559//4559 4608//4608 4609//4609 -f 4559//4559 4609//4609 4557//4557 -f 4557//4557 4609//4609 4610//4610 -f 4557//4557 4610//4610 4611//4611 -f 4612//4612 4613//4613 4614//4614 -f 4614//4614 4613//4613 4615//4615 -f 4614//4614 4615//4615 4616//4616 -f 4616//4616 4615//4615 4617//4617 -f 4616//4616 4617//4617 4618//4618 -f 4618//4618 4619//4619 4616//4616 -f 4616//4616 4619//4619 4620//4620 -f 4616//4616 4620//4620 4621//4621 -f 4607//4607 4559//4559 4620//4620 -f 4620//4620 4559//4559 4622//4622 -f 4620//4620 4622//4622 4621//4621 -f 4524//4524 4526//4526 4623//4623 -f 4624//4624 4625//4625 4616//4616 -f 4616//4616 4625//4625 4626//4626 -f 4616//4616 4626//4626 4614//4614 -f 4614//4614 4626//4626 4627//4627 -f 4614//4614 4627//4627 4628//4628 -f 4629//4629 4630//4630 4631//4631 -f 4631//4631 4630//4630 4632//4632 -f 4631//4631 4632//4632 4526//4526 -f 4526//4526 4632//4632 4633//4633 -f 4526//4526 4633//4633 4623//4623 -f 4526//4526 4522//4522 4634//4634 -f 4521//4521 4523//4523 4635//4635 -f 4634//4634 4636//4636 4526//4526 -f 4526//4526 4636//4636 4637//4637 -f 4526//4526 4637//4637 4631//4631 -f 4631//4631 4637//4637 4638//4638 -f 4631//4631 4638//4638 4639//4639 -f 4640//4640 4641//4641 4642//4642 -f 4642//4642 4641//4641 4643//4643 -f 4642//4642 4643//4643 4523//4523 -f 4523//4523 4643//4643 4644//4644 -f 4523//4523 4644//4644 4635//4635 -f 4518//4518 4520//4520 4645//4645 -f 4646//4646 4647//4647 4648//4648 -f 4647//4647 4646//4646 4649//4649 -f 4649//4649 4646//4646 4650//4650 -f 4649//4649 4650//4650 4651//4651 -f 4652//4652 4653//4653 4654//4654 -f 4654//4654 4653//4653 4655//4655 -f 4654//4654 4655//4655 4520//4520 -f 4520//4520 4655//4655 4656//4656 -f 4520//4520 4656//4656 4645//4645 -f 4520//4520 4657//4657 4658//4658 -f 4658//4658 4659//4659 4520//4520 -f 4520//4520 4659//4659 4660//4660 -f 4520//4520 4660//4660 4654//4654 -f 4654//4654 4660//4660 4661//4661 -f 4654//4654 4661//4661 4662//4662 -f 4663//4663 4664//4664 4665//4665 -f 4666//4666 4667//4667 4668//4668 -f 4668//4668 4667//4667 4669//4669 -f 4668//4668 4669//4669 4663//4663 -f 4663//4663 4669//4669 4670//4670 -f 4663//4663 4670//4670 4664//4664 -f 4671//4671 4657//4657 4672//4672 -f 4672//4672 4657//4657 4520//4520 -f 4672//4672 4520//4520 4504//4504 -f 4504//4504 4520//4520 4519//4519 -f 4504//4504 4519//4519 4650//4650 -f 4650//4650 4519//4519 4673//4673 -f 4650//4650 4673//4673 4651//4651 -f 4663//4663 4674//4674 4675//4675 -f 4675//4675 4676//4676 4663//4663 -f 4663//4663 4676//4676 4677//4677 -f 4663//4663 4677//4677 4668//4668 -f 4668//4668 4677//4677 4678//4678 -f 4668//4668 4678//4678 4679//4679 -f 4680//4680 4681//4681 4529//4529 -f 4529//4529 4681//4681 4682//4682 -f 4529//4529 4682//4682 4539//4539 -f 4539//4539 4682//4682 4683//4683 -f 4539//4539 4683//4683 4684//4684 -f 4671//4671 4685//4685 4539//4539 -f 4665//4665 4657//4657 4663//4663 -f 4663//4663 4657//4657 4671//4671 -f 4663//4663 4671//4671 4674//4674 -f 4674//4674 4671//4671 4539//4539 -f 4674//4674 4539//4539 4686//4686 -f 4686//4686 4539//4539 4684//4684 -f 4687//4687 4688//4688 4689//4689 -f 4690//4690 4691//4691 4692//4692 -f 4692//4692 4691//4691 4693//4693 -f 4694//4694 4695//4695 4696//4696 -f 4691//4691 4697//4697 4693//4693 -f 4693//4693 4697//4697 4698//4698 -f 4693//4693 4698//4698 4696//4696 -f 4696//4696 4698//4698 4699//4699 -f 4696//4696 4699//4699 4694//4694 -f 4687//4687 4689//4689 4695//4695 -f 4700//4700 4701//4701 4418//4418 -f 4418//4418 4701//4701 4702//4702 -f 4418//4418 4702//4702 4420//4420 -f 4420//4420 4702//4702 4690//4690 -f 4420//4420 4690//4690 4703//4703 -f 4703//4703 4690//4690 4692//4692 -f 4704//4704 4705//4705 4706//4706 -f 4706//4706 4705//4705 4707//4707 -f 4706//4706 4707//4707 4708//4708 -f 4708//4708 4707//4707 4709//4709 -f 4708//4708 4709//4709 4710//4710 -f 4710//4710 4709//4709 4711//4711 -f 4710//4710 4711//4711 4712//4712 -f 4713//4713 4714//4714 4715//4715 -f 4715//4715 4714//4714 4716//4716 -f 4715//4715 4716//4716 4717//4717 -f 4577//4577 4584//4584 4575//4575 -f 4575//4575 4584//4584 4713//4713 -f 4575//4575 4713//4713 4718//4718 -f 4718//4718 4713//4713 4715//4715 -f 4718//4718 4715//4715 4719//4719 -f 4720//4720 4721//4721 4433//4433 -f 4722//4722 4723//4723 4720//4720 -f 4499//4499 4724//4724 4725//4725 -f 4725//4725 4724//4724 4726//4726 -f 4725//4725 4726//4726 4727//4727 -f 4727//4727 4726//4726 4431//4431 -f 4727//4727 4431//4431 4728//4728 -f 4728//4728 4431//4431 4433//4433 -f 4728//4728 4433//4433 4729//4729 -f 4729//4729 4433//4433 4721//4721 -f 4499//4499 4725//4725 4497//4497 -f 4497//4497 4725//4725 4730//4730 -f 4497//4497 4730//4730 4731//4731 -f 4731//4731 4732//4732 4497//4497 -f 4497//4497 4732//4732 4733//4733 -f 4497//4497 4733//4733 4722//4722 -f 4722//4722 4733//4733 4734//4734 -f 4722//4722 4734//4734 4723//4723 -f 4735//4735 4736//4736 4737//4737 -f 4737//4737 4736//4736 4495//4495 -f 4737//4737 4495//4495 4738//4738 -f 4738//4738 4495//4495 4497//4497 -f 4738//4738 4497//4497 4739//4739 -f 4739//4739 4497//4497 4722//4722 -f 4739//4739 4722//4722 4740//4740 -f 4740//4740 4722//4722 4741//4741 -f 4741//4741 4722//4722 4742//4742 -f 4742//4742 4722//4722 4743//4743 -f 4742//4742 4743//4743 4744//4744 -f 4744//4744 4743//4743 4745//4745 -f 4744//4744 4745//4745 4746//4746 -f 4746//4746 4745//4745 4747//4747 -f 4746//4746 4747//4747 4748//4748 -f 4748//4748 4747//4747 4749//4749 -f 4748//4748 4749//4749 4750//4750 -f 4750//4750 4749//4749 4751//4751 -f 4750//4750 4751//4751 4752//4752 -f 4753//4753 4754//4754 4468//4468 -f 4468//4468 4754//4754 4470//4470 -f 4470//4470 4754//4754 4755//4755 -f 4470//4470 4755//4755 4472//4472 -f 4515//4515 4476//4476 4756//4756 -f 4756//4756 4476//4476 4474//4474 -f 4756//4756 4474//4474 4757//4757 -f 4505//4505 4758//4758 4506//4506 -f 4506//4506 4758//4758 4759//4759 -f 4506//4506 4759//4759 4760//4760 -f 4760//4760 4759//4759 4761//4761 -f 4760//4760 4761//4761 4762//4762 -f 4763//4763 4764//4764 4765//4765 -f 4765//4765 4764//4764 4766//4766 -f 4767//4767 4768//4768 4505//4505 -f 4505//4505 4768//4768 4769//4769 -f 4505//4505 4769//4769 4758//4758 -f 4445//4445 4770//4770 4771//4771 -f 4772//4772 4773//4773 4443//4443 -f 4774//4774 4765//4765 4775//4775 -f 4775//4775 4765//4765 4776//4776 -f 4774//4774 4772//4772 4765//4765 -f 4765//4765 4772//4772 4443//4443 -f 4765//4765 4443//4443 4763//4763 -f 4763//4763 4443//4443 4445//4445 -f 4763//4763 4445//4445 4777//4777 -f 4777//4777 4445//4445 4771//4771 -f 4776//4776 4765//4765 4778//4778 -f 4778//4778 4765//4765 4427//4427 -f 4778//4778 4427//4427 4779//4779 -f 4429//4429 4780//4780 4427//4427 -f 4427//4427 4780//4780 4781//4781 -f 4427//4427 4781//4781 4779//4779 -f 4773//4773 4782//4782 4443//4443 -f 4443//4443 4782//4782 4783//4783 -f 4443//4443 4783//4783 4441//4441 -f 4441//4441 4783//4783 4784//4784 -f 4441//4441 4784//4784 4785//4785 -f 4785//4785 4784//4784 4780//4780 -f 4785//4785 4780//4780 4786//4786 -f 4786//4786 4780//4780 4429//4429 -f 4511//4511 4510//4510 4787//4787 -f 4788//4788 4789//4789 4790//4790 -f 4790//4790 4789//4789 4791//4791 -f 4791//4791 4792//4792 4790//4790 -f 4790//4790 4792//4792 4793//4793 -f 4790//4790 4793//4793 4794//4794 -f 4794//4794 4793//4793 4795//4795 -f 4795//4795 4793//4793 4796//4796 -f 4795//4795 4796//4796 4797//4797 -f 4797//4797 4796//4796 4798//4798 -f 4797//4797 4798//4798 4799//4799 -f 4800//4800 4801//4801 4802//4802 -f 4800//4800 4802//4802 4803//4803 -f 4791//4791 4804//4804 4805//4805 -f 4805//4805 4804//4804 4806//4806 -f 4805//4805 4806//4806 4807//4807 -f 4807//4807 4806//4806 4808//4808 -f 4807//4807 4808//4808 4408//4408 -f 4408//4408 4808//4808 4809//4809 -f 4408//4408 4809//4809 4410//4410 -f 4801//4801 4810//4810 4802//4802 -f 4802//4802 4810//4810 4811//4811 -f 4802//4802 4811//4811 4789//4789 -f 4811//4811 4812//4812 4789//4789 -f 4789//4789 4812//4812 4813//4813 -f 4789//4789 4813//4813 4791//4791 -f 4791//4791 4813//4813 4814//4814 -f 4791//4791 4814//4814 4804//4804 -f 4815//4815 4816//4816 4817//4817 -f 4815//4815 4817//4817 4818//4818 -f 4816//4816 4819//4819 4817//4817 -f 4817//4817 4819//4819 4820//4820 -f 4817//4817 4820//4820 4821//4821 -f 4820//4820 4822//4822 4821//4821 -f 4821//4821 4822//4822 4823//4823 -f 4821//4821 4823//4823 4824//4824 -f 4824//4824 4823//4823 4825//4825 -f 4824//4824 4825//4825 4826//4826 -f 4826//4826 4825//4825 4509//4509 -f 4509//4509 4825//4825 4799//4799 -f 4509//4509 4799//4799 4510//4510 -f 4510//4510 4799//4799 4798//4798 -f 4510//4510 4798//4798 4787//4787 -f 4827//4827 4828//4828 4829//4829 -f 4830//4830 4831//4831 4832//4832 -f 4832//4832 4831//4831 4696//4696 -f 4711//4711 4833//4833 4712//4712 -f 4712//4712 4833//4833 4693//4693 -f 4712//4712 4693//4693 4834//4834 -f 4834//4834 4693//4693 4696//4696 -f 4834//4834 4696//4696 4835//4835 -f 4835//4835 4696//4696 4831//4831 -f 4828//4828 4836//4836 4829//4829 -f 4829//4829 4836//4836 4837//4837 -f 4829//4829 4837//4837 4832//4832 -f 4832//4832 4837//4837 4838//4838 -f 4832//4832 4838//4838 4830//4830 -f 4839//4839 4840//4840 4514//4514 -f 4514//4514 4840//4840 4841//4841 -f 4514//4514 4841//4841 4512//4512 -f 4512//4512 4841//4841 4842//4842 -f 4512//4512 4842//4842 4843//4843 -f 4843//4843 4842//4842 4844//4844 -f 4843//4843 4844//4844 4798//4798 -f 4798//4798 4844//4844 4845//4845 -f 4798//4798 4845//4845 4787//4787 -f 4824//4824 4846//4846 4821//4821 -f 4821//4821 4846//4846 4847//4847 -f 4821//4821 4847//4847 4646//4646 -f 4646//4646 4847//4847 4848//4848 -f 4646//4646 4848//4848 4849//4849 -f 4850//4850 4851//4851 4852//4852 -f 4853//4853 4854//4854 4829//4829 -f 4829//4829 4854//4854 4705//4705 -f 4829//4829 4705//4705 4827//4827 -f 4827//4827 4705//4705 4704//4704 -f 4854//4854 4855//4855 4705//4705 -f 4705//4705 4855//4855 4856//4856 -f 4705//4705 4856//4856 4707//4707 -f 4707//4707 4856//4856 4857//4857 -f 4707//4707 4857//4857 4716//4716 -f 4716//4716 4857//4857 4858//4858 -f 4716//4716 4858//4858 4717//4717 -f 4851//4851 4859//4859 4852//4852 -f 4852//4852 4859//4859 4860//4860 -f 4852//4852 4860//4860 4829//4829 -f 4829//4829 4860//4860 4861//4861 -f 4829//4829 4861//4861 4853//4853 -f 4606//4606 4862//4862 4863//4863 -f 4427//4427 4508//4508 4425//4425 -f 4425//4425 4508//4508 4864//4864 -f 4425//4425 4864//4864 4865//4865 -f 4591//4591 4423//4423 4605//4605 -f 4605//4605 4423//4423 4425//4425 -f 4605//4605 4425//4425 4606//4606 -f 4606//4606 4425//4425 4865//4865 -f 4606//4606 4865//4865 4862//4862 -f 4863//4863 4866//4866 4606//4606 -f 4606//4606 4866//4866 4867//4867 -f 4606//4606 4867//4867 4765//4765 -f 4765//4765 4867//4867 4868//4868 -f 4868//4868 4869//4869 4765//4765 -f 4765//4765 4869//4869 4870//4870 -f 4765//4765 4870//4870 4427//4427 -f 4427//4427 4870//4870 4871//4871 -f 4427//4427 4871//4871 4507//4507 -f 4504//4504 4506//4506 4672//4672 -f 4672//4672 4506//4506 4760//4760 -f 4672//4672 4760//4760 4671//4671 -f 4671//4671 4760//4760 4762//4762 -f 4671//4671 4762//4762 4685//4685 -f 4761//4761 4872//4872 4762//4762 -f 4762//4762 4872//4872 4873//4873 -f 4762//4762 4873//4873 4685//4685 -f 4685//4685 4873//4873 4874//4874 -f 4685//4685 4874//4874 4539//4539 -f 4539//4539 4874//4874 4534//4534 -f 4539//4539 4534//4534 4537//4537 -f 4537//4537 4534//4534 4536//4536 -f 4766//4766 4767//4767 4765//4765 -f 4765//4765 4767//4767 4505//4505 -f 4765//4765 4505//4505 4606//4606 -f 4606//4606 4505//4505 4504//4504 -f 4606//4606 4504//4504 4602//4602 -f 4602//4602 4504//4504 4650//4650 -f 4602//4602 4650//4650 4514//4514 -f 4514//4514 4650//4650 4646//4646 -f 4514//4514 4646//4646 4839//4839 -f 4839//4839 4646//4646 4849//4849 -f 4875//4875 4876//4876 4872//4872 -f 4872//4872 4876//4876 4447//4447 -f 4872//4872 4447//4447 4873//4873 -f 4873//4873 4447//4447 4449//4449 -f 4873//4873 4449//4449 4874//4874 -f 4874//4874 4449//4449 4451//4451 -f 4874//4874 4451//4451 4534//4534 -f 4534//4534 4451//4451 4453//4453 -f 4534//4534 4453//4453 4532//4532 -f 4532//4532 4453//4453 4455//4455 -f 4532//4532 4455//4455 4544//4544 -f 4544//4544 4455//4455 4457//4457 -f 4544//4544 4457//4457 4877//4877 -f 4877//4877 4457//4457 4459//4459 -f 4877//4877 4459//4459 4878//4878 -f 4878//4878 4459//4459 4879//4879 -f 4548//4548 4542//4542 4547//4547 -f 4547//4547 4542//4542 4544//4544 -f 4547//4547 4544//4544 4880//4880 -f 4880//4880 4544//4544 4877//4877 -f 4817//4817 4881//4881 4882//4882 -f 4882//4882 4881//4881 4883//4883 -f 4883//4883 4884//4884 4882//4882 -f 4882//4882 4884//4884 4885//4885 -f 4882//4882 4885//4885 4886//4886 -f 4887//4887 4888//4888 4817//4817 -f 4817//4817 4888//4888 4889//4889 -f 4817//4817 4889//4889 4881//4881 -f 4890//4890 4891//4891 4892//4892 -f 4885//4885 4893//4893 4886//4886 -f 4886//4886 4893//4893 4894//4894 -f 4886//4886 4894//4894 4890//4890 -f 4890//4890 4894//4894 4895//4895 -f 4890//4890 4895//4895 4891//4891 -f 4648//4648 4652//4652 4646//4646 -f 4646//4646 4652//4652 4654//4654 -f 4646//4646 4654//4654 4821//4821 -f 4821//4821 4654//4654 4896//4896 -f 4821//4821 4896//4896 4817//4817 -f 4817//4817 4896//4896 4890//4890 -f 4817//4817 4890//4890 4887//4887 -f 4887//4887 4890//4890 4892//4892 -f 4897//4897 4898//4898 4899//4899 -f 4900//4900 4901//4901 4902//4902 -f 4903//4903 4904//4904 4890//4890 -f 4904//4904 4905//4905 4890//4890 -f 4890//4890 4905//4905 4906//4906 -f 4890//4890 4906//4906 4886//4886 -f 4886//4886 4906//4906 4907//4907 -f 4886//4886 4907//4907 4900//4900 -f 4901//4901 4908//4908 4902//4902 -f 4902//4902 4908//4908 4909//4909 -f 4902//4902 4909//4909 4899//4899 -f 4899//4899 4909//4909 4910//4910 -f 4899//4899 4910//4910 4897//4897 -f 4898//4898 4903//4903 4899//4899 -f 4899//4899 4903//4903 4890//4890 -f 4899//4899 4890//4890 4911//4911 -f 4911//4911 4890//4890 4896//4896 -f 4911//4911 4896//4896 4668//4668 -f 4668//4668 4896//4896 4654//4654 -f 4668//4668 4654//4654 4666//4666 -f 4666//4666 4654//4654 4662//4662 -f 4912//4912 4515//4515 4913//4913 -f 4913//4913 4515//4515 4902//4902 -f 4913//4913 4902//4902 4914//4914 -f 4899//4899 4915//4915 4916//4916 -f 4912//4912 4917//4917 4515//4515 -f 4515//4515 4917//4917 4880//4880 -f 4515//4515 4880//4880 4464//4464 -f 4464//4464 4880//4880 4877//4877 -f 4464//4464 4877//4877 4463//4463 -f 4463//4463 4877//4877 4878//4878 -f 4917//4917 4918//4918 4880//4880 -f 4880//4880 4918//4918 4919//4919 -f 4880//4880 4919//4919 4920//4920 -f 4916//4916 4921//4921 4899//4899 -f 4899//4899 4921//4921 4922//4922 -f 4899//4899 4922//4922 4902//4902 -f 4902//4902 4922//4922 4923//4923 -f 4902//4902 4923//4923 4914//4914 -f 4679//4679 4680//4680 4668//4668 -f 4668//4668 4680//4680 4529//4529 -f 4668//4668 4529//4529 4911//4911 -f 4911//4911 4529//4529 4547//4547 -f 4911//4911 4547//4547 4899//4899 -f 4899//4899 4547//4547 4880//4880 -f 4899//4899 4880//4880 4915//4915 -f 4915//4915 4880//4880 4920//4920 -f 4788//4788 4818//4818 4789//4789 -f 4789//4789 4818//4818 4817//4817 -f 4789//4789 4817//4817 4802//4802 -f 4802//4802 4817//4817 4882//4882 -f 4802//4802 4882//4882 4924//4924 -f 4924//4924 4882//4882 4925//4925 -f 4925//4925 4926//4926 4927//4927 -f 4928//4928 4929//4929 4930//4930 -f 4930//4930 4929//4929 4931//4931 -f 4932//4932 4933//4933 4886//4886 -f 4886//4886 4933//4933 4934//4934 -f 4886//4886 4934//4934 4882//4882 -f 4882//4882 4934//4934 4935//4935 -f 4935//4935 4936//4936 4882//4882 -f 4882//4882 4936//4936 4937//4937 -f 4882//4882 4937//4937 4925//4925 -f 4925//4925 4937//4937 4938//4938 -f 4925//4925 4938//4938 4926//4926 -f 4939//4939 4940//4940 4941//4941 -f 4902//4902 4942//4942 4943//4943 -f 4900//4900 4902//4902 4886//4886 -f 4886//4886 4902//4902 4943//4943 -f 4886//4886 4943//4943 4944//4944 -f 4944//4944 4945//4945 4886//4886 -f 4886//4886 4945//4945 4930//4930 -f 4886//4886 4930//4930 4932//4932 -f 4932//4932 4930//4930 4931//4931 -f 4945//4945 4946//4946 4930//4930 -f 4930//4930 4946//4946 4947//4947 -f 4930//4930 4947//4947 4948//4948 -f 4940//4940 4949//4949 4941//4941 -f 4941//4941 4949//4949 4950//4950 -f 4941//4941 4950//4950 4902//4902 -f 4902//4902 4950//4950 4951//4951 -f 4902//4902 4951//4951 4942//4942 -f 4952//4952 4953//4953 4756//4756 -f 4941//4941 4954//4954 4955//4955 -f 4953//4953 4956//4956 4756//4756 -f 4756//4756 4956//4956 4957//4957 -f 4756//4756 4957//4957 4515//4515 -f 4958//4958 4902//4902 4959//4959 -f 4959//4959 4902//4902 4515//4515 -f 4959//4959 4515//4515 4960//4960 -f 4960//4960 4515//4515 4957//4957 -f 4958//4958 4961//4961 4902//4902 -f 4902//4902 4961//4961 4962//4962 -f 4902//4902 4962//4962 4941//4941 -f 4941//4941 4962//4962 4963//4963 -f 4941//4941 4963//4963 4954//4954 -f 4964//4964 4502//4502 4965//4965 -f 4965//4965 4502//4502 4924//4924 -f 4965//4965 4924//4924 4966//4966 -f 4964//4964 4967//4967 4502//4502 -f 4502//4502 4967//4967 4968//4968 -f 4502//4502 4968//4968 4503//4503 -f 4968//4968 4969//4969 4503//4503 -f 4503//4503 4969//4969 4970//4970 -f 4503//4503 4970//4970 4925//4925 -f 4925//4925 4970//4970 4971//4971 -f 4925//4925 4971//4971 4972//4972 -f 4972//4972 4973//4973 4925//4925 -f 4925//4925 4973//4973 4974//4974 -f 4925//4925 4974//4974 4924//4924 -f 4924//4924 4974//4974 4975//4975 -f 4924//4924 4975//4975 4966//4966 -f 4976//4976 4977//4977 4978//4978 -f 4979//4979 4503//4503 4980//4980 -f 4980//4980 4503//4503 4981//4981 -f 4977//4977 4982//4982 4978//4978 -f 4978//4978 4982//4982 4983//4983 -f 4978//4978 4983//4983 4984//4984 -f 4985//4985 4986//4986 4987//4987 -f 4927//4927 4928//4928 4925//4925 -f 4925//4925 4928//4928 4930//4930 -f 4925//4925 4930//4930 4503//4503 -f 4503//4503 4930//4930 4985//4985 -f 4503//4503 4985//4985 4981//4981 -f 4981//4981 4985//4985 4987//4987 -f 4983//4983 4988//4988 4984//4984 -f 4984//4984 4988//4988 4989//4989 -f 4984//4984 4989//4989 4985//4985 -f 4985//4985 4989//4989 4990//4990 -f 4985//4985 4990//4990 4986//4986 -f 4991//4991 4992//4992 4993//4993 -f 4994//4994 4995//4995 4985//4985 -f 4995//4995 4996//4996 4985//4985 -f 4985//4985 4996//4996 4997//4997 -f 4985//4985 4997//4997 4984//4984 -f 4984//4984 4997//4997 4998//4998 -f 4984//4984 4998//4998 4999//4999 -f 4992//4992 4994//4994 4993//4993 -f 4993//4993 4994//4994 4985//4985 -f 4993//4993 4985//4985 4941//4941 -f 4941//4941 4985//4985 4930//4930 -f 4941//4941 4930//4930 4939//4939 -f 4939//4939 4930//4930 4948//4948 -f 5000//5000 5001//5001 5002//5002 -f 5002//5002 5001//5001 5003//5003 -f 5002//5002 5003//5003 4993//4993 -f 4993//4993 5003//5003 5004//5004 -f 4993//4993 5004//5004 4991//4991 -f 5005//5005 5006//5006 4755//4755 -f 5002//5002 5007//5007 5005//5005 -f 5006//5006 5008//5008 4755//4755 -f 4755//4755 5008//5008 4757//4757 -f 4755//4755 4757//4757 4472//4472 -f 4472//4472 4757//4757 4474//4474 -f 4993//4993 5009//5009 5010//5010 -f 5008//5008 5011//5011 4757//4757 -f 4757//4757 5011//5011 5012//5012 -f 4757//4757 5012//5012 5013//5013 -f 5010//5010 5014//5014 4993//4993 -f 4993//4993 5014//5014 5015//5015 -f 4993//4993 5015//5015 5002//5002 -f 5002//5002 5015//5015 5016//5016 -f 5002//5002 5016//5016 5007//5007 -f 4955//4955 4952//4952 4941//4941 -f 4941//4941 4952//4952 4756//4756 -f 4941//4941 4756//4756 4993//4993 -f 4993//4993 4756//4756 4757//4757 -f 4993//4993 4757//4757 5009//5009 -f 5009//5009 4757//4757 5013//5013 -f 4809//4809 4803//4803 4410//4410 -f 4410//4410 4803//4803 4802//4802 -f 4410//4410 4802//4802 4412//4412 -f 4412//4412 4802//4802 4924//4924 -f 4412//4412 4924//4924 4414//4414 -f 4414//4414 4924//4924 4502//4502 -f 4414//4414 4502//4502 4416//4416 -f 4416//4416 4502//4502 4501//4501 -f 4416//4416 4501//4501 4418//4418 -f 4418//4418 4501//4501 4689//4689 -f 4418//4418 4689//4689 4700//4700 -f 4700//4700 4689//4689 4688//4688 -f 5017//5017 5018//5018 4501//4501 -f 5019//5019 4689//4689 5020//5020 -f 5020//5020 4689//4689 4501//4501 -f 5020//5020 4501//4501 5021//5021 -f 5021//5021 4501//4501 5018//5018 -f 5022//5022 5023//5023 4978//4978 -f 5019//5019 5024//5024 4689//4689 -f 4689//4689 5024//5024 5025//5025 -f 4689//4689 5025//5025 5026//5026 -f 4979//4979 4976//4976 4503//4503 -f 4503//4503 4976//4976 4978//4978 -f 4503//4503 4978//4978 4501//4501 -f 4501//4501 4978//4978 5023//5023 -f 4501//4501 5023//5023 5017//5017 -f 5025//5025 5027//5027 5026//5026 -f 5026//5026 5027//5027 5028//5028 -f 5026//5026 5028//5028 4978//4978 -f 4978//4978 5028//5028 5029//5029 -f 4978//4978 5029//5029 5022//5022 -f 5030//5030 5031//5031 5032//5032 -f 5026//5026 5033//5033 5030//5030 -f 5031//5031 5034//5034 5032//5032 -f 5032//5032 5034//5034 5035//5035 -f 5032//5032 5035//5035 4984//4984 -f 5035//5035 5036//5036 4984//4984 -f 4984//4984 5036//5036 5037//5037 -f 4984//4984 5037//5037 4978//4978 -f 4978//4978 5037//5037 5038//5038 -f 4978//4978 5038//5038 5039//5039 -f 5039//5039 5040//5040 4978//4978 -f 4978//4978 5040//5040 5041//5041 -f 4978//4978 5041//5041 5026//5026 -f 5026//5026 5041//5041 5042//5042 -f 5026//5026 5042//5042 5033//5033 -f 5043//5043 5044//5044 5045//5045 -f 5043//5043 5045//5045 5046//5046 -f 5044//5044 5047//5047 5045//5045 -f 5045//5045 5047//5047 5048//5048 -f 5045//5045 5048//5048 5002//5002 -f 5002//5002 5048//5048 5049//5049 -f 5002//5002 5049//5049 5050//5050 -f 5050//5050 5051//5051 5002//5002 -f 5002//5002 5051//5051 4984//4984 -f 5002//5002 4984//4984 5000//5000 -f 5000//5000 4984//4984 4999//4999 -f 5051//5051 5052//5052 4984//4984 -f 4984//4984 5052//5052 5053//5053 -f 4984//4984 5053//5053 5032//5032 -f 5032//5032 5053//5053 5054//5054 -f 5032//5032 5054//5054 5055//5055 -f 5056//5056 5057//5057 4754//4754 -f 5058//5058 5059//5059 5045//5045 -f 5045//5045 5059//5059 5056//5056 -f 5005//5005 4755//4755 5002//5002 -f 5002//5002 4755//4755 5060//5060 -f 5002//5002 5060//5060 5061//5061 -f 5061//5061 5062//5062 5002//5002 -f 5002//5002 5062//5062 5063//5063 -f 5002//5002 5063//5063 5045//5045 -f 5045//5045 5063//5063 5064//5064 -f 5045//5045 5064//5064 5058//5058 -f 5057//5057 5065//5065 4754//4754 -f 4754//4754 5065//5065 5066//5066 -f 4754//4754 5066//5066 4755//4755 -f 4755//4755 5066//5066 5067//5067 -f 4755//4755 5067//5067 5060//5060 -f 5068//5068 4832//4832 5069//5069 -f 5069//5069 4832//4832 5070//5070 -f 5071//5071 5072//5072 5073//5073 -f 5074//5074 5075//5075 5026//5026 -f 5026//5026 5075//5075 5076//5076 -f 5030//5030 5032//5032 5026//5026 -f 5026//5026 5032//5032 5077//5077 -f 5026//5026 5077//5077 5074//5074 -f 4695//4695 4689//4689 4696//4696 -f 4696//4696 4689//4689 5026//5026 -f 4696//4696 5026//5026 4832//4832 -f 4832//4832 5026//5026 5076//5076 -f 4832//4832 5076//5076 5070//5070 -f 5072//5072 5078//5078 5073//5073 -f 5073//5073 5078//5078 5079//5079 -f 5073//5073 5079//5079 5032//5032 -f 5032//5032 5079//5079 5080//5080 -f 5032//5032 5080//5080 5077//5077 -f 5081//5081 5082//5082 5073//5073 -f 5083//5083 5084//5084 5085//5085 -f 5084//5084 5086//5086 5085//5085 -f 5085//5085 5086//5086 5087//5087 -f 5085//5085 5087//5087 5045//5045 -f 5045//5045 5087//5087 5088//5088 -f 5045//5045 5088//5088 5089//5089 -f 5089//5089 5090//5090 5045//5045 -f 5045//5045 5090//5090 5032//5032 -f 5045//5045 5032//5032 5046//5046 -f 5046//5046 5032//5032 5055//5055 -f 5090//5090 5091//5091 5032//5032 -f 5032//5032 5091//5091 5092//5092 -f 5032//5032 5092//5092 5073//5073 -f 5073//5073 5092//5092 5093//5093 -f 5073//5073 5093//5093 5081//5081 -f 5094//5094 5095//5095 5085//5085 -f 5096//5096 5097//5097 4753//4753 -f 5056//5056 4754//4754 5045//5045 -f 5045//5045 4754//4754 5098//5098 -f 5045//5045 5098//5098 5099//5099 -f 5099//5099 5100//5100 5045//5045 -f 5045//5045 5100//5100 5101//5101 -f 5045//5045 5101//5101 5085//5085 -f 5085//5085 5101//5101 5102//5102 -f 5085//5085 5102//5102 5094//5094 -f 5097//5097 5103//5103 4753//4753 -f 4753//4753 5103//5103 5104//5104 -f 4753//4753 5104//5104 4754//4754 -f 4754//4754 5104//5104 5105//5105 -f 4754//4754 5105//5105 5098//5098 -f 5106//5106 5107//5107 5108//5108 -f 5108//5108 5107//5107 5109//5109 -f 5108//5108 5109//5109 4516//4516 -f 4516//4516 5109//5109 4753//4753 -f 4516//4516 4753//4753 4466//4466 -f 4466//4466 4753//4753 4468//4468 -f 5110//5110 4572//4572 5111//5111 -f 5111//5111 4572//4572 5109//5109 -f 5111//5111 5109//5109 5112//5112 -f 5112//5112 5109//5109 5107//5107 -f 5110//5110 5113//5113 4572//4572 -f 4572//4572 5113//5113 5114//5114 -f 4572//4572 5114//5114 4570//4570 -f 4570//4570 5114//5114 5115//5115 -f 4570//4570 5115//5115 5116//5116 -f 5116//5116 5117//5117 4570//4570 -f 4570//4570 5117//5117 5118//5118 -f 4570//4570 5118//5118 5108//5108 -f 5108//5108 5118//5118 5119//5119 -f 5108//5108 5119//5119 5106//5106 -f 5068//5068 5071//5071 4832//4832 -f 4832//4832 5071//5071 5073//5073 -f 4832//4832 5073//5073 4829//4829 -f 4829//4829 5073//5073 5120//5120 -f 4829//4829 5120//5120 4852//4852 -f 4852//4852 5120//5120 5121//5121 -f 4852//4852 5121//5121 4642//4642 -f 4642//4642 5121//5121 4631//4631 -f 4642//4642 4631//4631 4640//4640 -f 4640//4640 4631//4631 4639//4639 -f 5082//5082 5083//5083 5073//5073 -f 5073//5073 5083//5083 5085//5085 -f 5073//5073 5085//5085 5120//5120 -f 5120//5120 5085//5085 5122//5122 -f 5120//5120 5122//5122 5121//5121 -f 5121//5121 5122//5122 5123//5123 -f 5121//5121 5123//5123 4631//4631 -f 4631//4631 5123//5123 4614//4614 -f 4631//4631 4614//4614 4629//4629 -f 4629//4629 4614//4614 4628//4628 -f 5095//5095 5096//5096 5085//5085 -f 5085//5085 5096//5096 4753//4753 -f 5085//5085 4753//4753 5122//5122 -f 5122//5122 4753//4753 5109//5109 -f 5122//5122 5109//5109 5123//5123 -f 5123//5123 5109//5109 4572//4572 -f 5123//5123 4572//4572 4614//4614 -f 4614//4614 4572//4572 4557//4557 -f 4614//4614 4557//4557 4612//4612 -f 4612//4612 4557//4557 4611//4611 -f 4719//4719 4850//4850 4718//4718 -f 4718//4718 4850//4850 4852//4852 -f 4718//4718 4852//4852 4575//4575 -f 4575//4575 4852//4852 4642//4642 -f 4575//4575 4642//4642 4580//4580 -f 4580//4580 4642//4642 4523//4523 -f 4624//4624 4616//4616 4525//4525 -f 4525//4525 4616//4616 4621//4621 -f 4525//4525 4621//4621 4526//4526 -f 4526//4526 4621//4621 5124//5124 -f 4526//4526 5124//5124 4522//4522 -f 4522//4522 5124//5124 5125//5125 -f 4522//4522 5125//5125 4523//4523 -f 4523//4523 5125//5125 5126//5126 -f 4523//4523 5126//5126 4580//4580 -f 4580//4580 5126//5126 5127//5127 -f 4580//4580 5127//5127 4578//4578 -f 4561//4561 4562//4562 4559//4559 -f 4559//4559 4562//4562 4564//4564 -f 4559//4559 4564//4564 4622//4622 -f 4622//4622 4564//4564 5128//5128 -f 5129//5129 5130//5130 4433//4433 -f 4720//4720 4433//4433 4722//4722 -f 4722//4722 4433//4433 5130//5130 -f 4722//4722 5130//5130 5131//5131 -f 5131//5131 5132//5132 4722//4722 -f 4722//4722 5132//5132 5133//5133 -f 4722//4722 5133//5133 5134//5134 -f 4588//4588 5127//5127 4437//4437 -f 4437//4437 5127//5127 5126//5126 -f 4437//4437 5126//5126 4435//4435 -f 4435//4435 5126//5126 5135//5135 -f 5135//5135 5136//5136 4435//4435 -f 4435//4435 5136//5136 5137//5137 -f 4435//4435 5137//5137 4433//4433 -f 4433//4433 5137//5137 5138//5138 -f 4433//4433 5138//5138 5129//5129 -f 5134//5134 5139//5139 5126//5126 -f 5126//5126 5139//5139 5140//5140 -f 5126//5126 5140//5140 5135//5135 -f 5134//5134 5126//5126 4722//4722 -f 4722//4722 5126//5126 5125//5125 -f 4722//4722 5125//5125 4743//4743 -f 4743//4743 5125//5125 5124//5124 -f 4743//4743 5124//5124 4745//4745 -f 4745//4745 5124//5124 4621//4621 -f 4745//4745 4621//4621 4747//4747 -f 4747//4747 4621//4621 4622//4622 -f 4747//4747 4622//4622 4749//4749 -f 4749//4749 4622//4622 5128//5128 -f 4749//4749 5128//5128 4751//4751 -f 4517//4517 5141//5141 4516//4516 -f 4516//4516 5141//5141 4479//4479 -f 4516//4516 4479//4479 5108//5108 -f 5108//5108 4479//4479 4481//4481 -f 5108//5108 4481//4481 4570//4570 -f 4570//4570 4481//4481 4483//4483 -f 4570//4570 4483//4483 4566//4566 -f 4566//4566 4483//4483 4485//4485 -f 4566//4566 4485//4485 4564//4564 -f 4564//4564 4485//4485 4487//4487 -f 4564//4564 4487//4487 5128//5128 -f 5128//5128 4487//4487 4489//4489 -f 5128//5128 4489//4489 4751//4751 -f 4751//4751 4489//4489 4491//4491 -f 4751//4751 4491//4491 4752//4752 -f 4752//4752 4491//4491 4493//4493 -f 4752//4752 4493//4493 5142//5142 -f 5142//5142 4493//4493 5143//5143 -f 5144//5144 5145//5145 5146//5146 -f 5147//5147 5148//5148 5149//5149 -f 5150//5150 5151//5151 5152//5152 -f 5153//5153 5154//5154 5155//5155 -f 5156//5156 5157//5157 5158//5158 -f 5159//5159 5160//5160 5161//5161 -f 5162//5162 5163//5163 5164//5164 -f 5165//5165 5166//5166 5167//5167 -f 5168//5168 5169//5169 5170//5170 -f 5171//5171 5172//5172 5173//5173 -f 5173//5173 5172//5172 5174//5174 -f 5174//5174 5175//5175 5173//5173 -f 5173//5173 5175//5175 5176//5176 -f 5173//5173 5176//5176 5168//5168 -f 5176//5176 5177//5177 5168//5168 -f 5168//5168 5177//5177 5178//5178 -f 5168//5168 5178//5178 5169//5169 -f 5178//5178 5179//5179 5169//5169 -f 5169//5169 5179//5179 5180//5180 -f 5169//5169 5180//5180 5181//5181 -f 5181//5181 5180//5180 5182//5182 -f 5181//5181 5182//5182 5183//5183 -f 5183//5183 5182//5182 5184//5184 -f 5183//5183 5184//5184 4422//4422 -f 4422//4422 5184//5184 5185//5185 -f 4422//4422 5185//5185 4424//4424 -f 4424//4424 5185//5185 5186//5186 -f 5187//5187 5188//5188 4444//4444 -f 4444//4444 5188//5188 5189//5189 -f 4444//4444 5189//5189 5190//5190 -f 5190//5190 5189//5189 5191//5191 -f 5191//5191 5192//5192 5190//5190 -f 5190//5190 5192//5192 5193//5193 -f 5190//5190 5193//5193 4428//4428 -f 4428//4428 5193//5193 5194//5194 -f 5195//5195 4430//4430 5196//5196 -f 5196//5196 4430//4430 4428//4428 -f 5196//5196 4428//4428 5197//5197 -f 5197//5197 4428//4428 5194//5194 -f 5198//5198 4430//4430 5199//5199 -f 5199//5199 4430//4430 5195//5195 -f 5199//5199 5195//5195 4442//4442 -f 4442//4442 5195//5195 5200//5200 -f 4442//4442 5200//5200 4444//4444 -f 4444//4444 5200//5200 5201//5201 -f 4444//4444 5201//5201 5187//5187 -f 5202//5202 5190//5190 5203//5203 -f 5203//5203 5190//5190 5204//5204 -f 5203//5203 5204//5204 5205//5205 -f 5206//5206 5207//5207 5208//5208 -f 5208//5208 5207//5207 4446//4446 -f 5208//5208 4446//4446 5209//5209 -f 5209//5209 4446//4446 4444//4444 -f 5209//5209 4444//4444 5210//5210 -f 5210//5210 4444//4444 5190//5190 -f 5210//5210 5190//5190 5211//5211 -f 5211//5211 5190//5190 5202//5202 -f 5205//5205 5204//5204 5212//5212 -f 5212//5212 5204//5204 5213//5213 -f 5212//5212 5213//5213 5214//5214 -f 5214//5214 5213//5213 5215//5215 -f 5214//5214 5215//5215 5216//5216 -f 5215//5215 5217//5217 5216//5216 -f 5216//5216 5217//5217 5218//5218 -f 5216//5216 5218//5218 5219//5219 -f 5220//5220 5221//5221 4448//4448 -f 4448//4448 5221//5221 5219//5219 -f 4448//4448 5219//5219 4450//4450 -f 4450//4450 5219//5219 5218//5218 -f 4461//4461 5222//5222 5223//5223 -f 5223//5223 5222//5222 5224//5224 -f 4461//4461 5223//5223 4462//4462 -f 4462//4462 5223//5223 5225//5225 -f 4462//4462 5225//5225 4475//4475 -f 5226//5226 5227//5227 4480//4480 -f 4480//4480 5227//5227 5228//5228 -f 4480//4480 5228//5228 4482//4482 -f 5229//5229 5230//5230 5231//5231 -f 5232//5232 5233//5233 5234//5234 -f 5233//5233 5235//5235 5234//5234 -f 5234//5234 5235//5235 5236//5236 -f 5234//5234 5236//5236 5237//5237 -f 5236//5236 5238//5238 5237//5237 -f 5237//5237 5238//5238 5239//5239 -f 5237//5237 5239//5239 5240//5240 -f 5240//5240 5239//5239 5241//5241 -f 5240//5240 5241//5241 5242//5242 -f 5242//5242 5241//5241 5243//5243 -f 5242//5242 5243//5243 5244//5244 -f 5244//5244 5243//5243 5245//5245 -f 5244//5244 5245//5245 5229//5229 -f 4496//4496 5246//5246 5247//5247 -f 5234//5234 5248//5248 5249//5249 -f 5250//5250 5251//5251 4434//4434 -f 5252//5252 5253//5253 4498//4498 -f 5249//5249 5252//5252 5234//5234 -f 5234//5234 5252//5252 4498//4498 -f 5234//5234 4498//4498 5232//5232 -f 5232//5232 4498//4498 4496//4496 -f 5232//5232 4496//4496 5254//5254 -f 5254//5254 4496//4496 5247//5247 -f 5255//5255 4500//4500 5256//5256 -f 5256//5256 4500//4500 4498//4498 -f 5256//5256 4498//4498 5257//5257 -f 5257//5257 4498//4498 5253//5253 -f 4434//4434 5251//5251 5234//5234 -f 5234//5234 5251//5251 5258//5258 -f 5234//5234 5258//5258 5248//5248 -f 5259//5259 4500//4500 5260//5260 -f 5260//5260 4500//4500 5255//5255 -f 5260//5260 5255//5255 4432//4432 -f 4432//4432 5255//5255 5261//5261 -f 4432//4432 5261//5261 4434//4434 -f 4434//4434 5261//5261 5262//5262 -f 4434//4434 5262//5262 5250//5250 -f 5263//5263 5264//5264 5153//5153 -f 5265//5265 5266//5266 5267//5267 -f 5268//5268 5269//5269 5270//5270 -f 5270//5270 5269//5269 5271//5271 -f 5270//5270 5271//5271 5272//5272 -f 4438//4438 5273//5273 5274//5274 -f 4438//4438 5274//5274 4440//4440 -f 4440//4440 5274//5274 5275//5275 -f 4440//4440 5275//5275 5276//5276 -f 5265//5265 5267//5267 5275//5275 -f 5275//5275 5267//5267 5277//5277 -f 5275//5275 5277//5277 5276//5276 -f 5278//5278 5279//5279 5267//5267 -f 5280//5280 5281//5281 5282//5282 -f 5282//5282 5281//5281 5283//5283 -f 5282//5282 5283//5283 5284//5284 -f 5284//5284 5283//5283 5285//5285 -f 5284//5284 5285//5285 5286//5286 -f 5286//5286 5285//5285 5287//5287 -f 5288//5288 5289//5289 5290//5290 -f 5290//5290 5289//5289 5291//5291 -f 5292//5292 5293//5293 5294//5294 -f 5294//5294 5293//5293 5291//5291 -f 5292//5292 5294//5294 5295//5295 -f 5295//5295 5294//5294 5296//5296 -f 5295//5295 5296//5296 5297//5297 -f 5298//5298 5299//5299 5296//5296 -f 5296//5296 5299//5299 5300//5300 -f 5296//5296 5300//5300 5297//5297 -f 5293//5293 5301//5301 5291//5291 -f 5291//5291 5301//5301 5302//5302 -f 5291//5291 5302//5302 5303//5303 -f 5303//5303 5302//5302 5304//5304 -f 5303//5303 5304//5304 5305//5305 -f 5305//5305 5304//5304 5306//5306 -f 5305//5305 5306//5306 4419//4419 -f 4419//4419 5306//5306 5307//5307 -f 4419//4419 5307//5307 4417//4417 -f 4417//4417 5307//5307 5298//5298 -f 5308//5308 5309//5309 4409//4409 -f 5310//5310 5311//5311 5312//5312 -f 5312//5312 5311//5311 5313//5313 -f 5314//5314 5315//5315 5167//5167 -f 5167//5167 5315//5315 5316//5316 -f 5167//5167 5316//5316 5165//5165 -f 4409//4409 5309//5309 4407//4407 -f 4407//4407 5309//5309 5317//5317 -f 4407//4407 5317//5317 5318//5318 -f 5318//5318 5317//5317 5319//5319 -f 5319//5319 5317//5317 5320//5320 -f 5319//5319 5320//5320 5314//5314 -f 5314//5314 5320//5320 5321//5321 -f 5314//5314 5321//5321 5315//5315 -f 5322//5322 5323//5323 5324//5324 -f 5325//5325 5326//5326 5327//5327 -f 5327//5327 5326//5326 5328//5328 -f 5327//5327 5328//5328 5329//5329 -f 5329//5329 5328//5328 5330//5330 -f 5324//5324 5331//5331 5322//5322 -f 5322//5322 5331//5331 5332//5332 -f 5322//5322 5332//5332 5333//5333 -f 5325//5325 5334//5334 5326//5326 -f 5326//5326 5334//5334 5335//5335 -f 5326//5326 5335//5335 5323//5323 -f 5323//5323 5335//5335 5336//5336 -f 5323//5323 5336//5336 5324//5324 -f 5337//5337 5338//5338 5328//5328 -f 5339//5339 5340//5340 5341//5341 -f 5341//5341 5340//5340 5342//5342 -f 5341//5341 5342//5342 5343//5343 -f 5343//5343 5342//5342 5344//5344 -f 5343//5343 5344//5344 5345//5345 -f 5328//5328 5338//5338 5330//5330 -f 5330//5330 5338//5338 5346//5346 -f 5330//5330 5346//5346 5347//5347 -f 5347//5347 5346//5346 5348//5348 -f 5347//5347 5348//5348 5333//5333 -f 5333//5333 5348//5348 5349//5349 -f 5333//5333 5349//5349 5322//5322 -f 5322//5322 5349//5349 5350//5350 -f 5322//5322 5350//5350 5341//5341 -f 5341//5341 5350//5350 5351//5351 -f 5341//5341 5351//5351 5339//5339 -f 5352//5352 5353//5353 5354//5354 -f 5354//5354 5353//5353 5355//5355 -f 5356//5356 5357//5357 5358//5358 -f 5356//5356 5358//5358 5164//5164 -f 5164//5164 5358//5358 5359//5359 -f 5164//5164 5359//5359 5162//5162 -f 5352//5352 5354//5354 5360//5360 -f 5360//5360 5354//5354 5361//5361 -f 5360//5360 5361//5361 5362//5362 -f 5362//5362 5361//5361 5363//5363 -f 5363//5363 5361//5361 5364//5364 -f 5363//5363 5364//5364 5365//5365 -f 5161//5161 5366//5366 5367//5367 -f 5368//5368 5369//5369 5356//5356 -f 5370//5370 5371//5371 5372//5372 -f 5372//5372 5371//5371 5164//5164 -f 5372//5372 5164//5164 5373//5373 -f 5373//5373 5164//5164 5163//5163 -f 5367//5367 5374//5374 5161//5161 -f 5161//5161 5374//5374 5375//5375 -f 5161//5161 5375//5375 5372//5372 -f 5372//5372 5375//5375 5376//5376 -f 5372//5372 5376//5376 5370//5370 -f 5371//5371 5377//5377 5164//5164 -f 5164//5164 5377//5377 5378//5378 -f 5164//5164 5378//5378 5356//5356 -f 5356//5356 5378//5378 5379//5379 -f 5356//5356 5379//5379 5368//5368 -f 5369//5369 5366//5366 5356//5356 -f 5356//5356 5366//5366 5380//5380 -f 5356//5356 5380//5380 5381//5381 -f 5382//5382 5160//5160 5383//5383 -f 5159//5159 5161//5161 5384//5384 -f 5383//5383 5385//5385 5382//5382 -f 5382//5382 5385//5385 5386//5386 -f 5382//5382 5386//5386 5387//5387 -f 5387//5387 5386//5386 5388//5388 -f 5387//5387 5388//5388 5389//5389 -f 5390//5390 5391//5391 5372//5372 -f 5372//5372 5391//5391 5392//5392 -f 5372//5372 5392//5392 5161//5161 -f 5161//5161 5392//5392 5393//5393 -f 5161//5161 5393//5393 5384//5384 -f 5154//5154 5394//5394 5395//5395 -f 5395//5395 5396//5396 5154//5154 -f 5154//5154 5396//5396 5397//5397 -f 5154//5154 5397//5397 5155//5155 -f 5155//5155 5397//5397 5398//5398 -f 5155//5155 5398//5398 5399//5399 -f 5400//5400 5401//5401 5387//5387 -f 5387//5387 5401//5401 5402//5402 -f 5387//5387 5402//5402 5382//5382 -f 5382//5382 5402//5402 5403//5403 -f 5382//5382 5403//5403 5404//5404 -f 5366//5366 5161//5161 5380//5380 -f 5380//5380 5161//5161 5160//5160 -f 5380//5380 5160//5160 5405//5405 -f 5405//5405 5160//5160 5382//5382 -f 5405//5405 5382//5382 5406//5406 -f 5407//5407 5157//5157 5408//5408 -f 5156//5156 5158//5158 5409//5409 -f 5410//5410 5411//5411 5412//5412 -f 5412//5412 5411//5411 5407//5407 -f 5412//5412 5407//5407 5413//5413 -f 5413//5413 5407//5407 5408//5408 -f 5410//5410 5414//5414 5411//5411 -f 5411//5411 5414//5414 5415//5415 -f 5411//5411 5415//5415 5416//5416 -f 5415//5415 5417//5417 5416//5416 -f 5416//5416 5417//5417 5418//5418 -f 5416//5416 5418//5418 5158//5158 -f 5158//5158 5418//5418 5419//5419 -f 5158//5158 5419//5419 5409//5409 -f 5420//5420 5407//5407 5421//5421 -f 5421//5421 5407//5407 5422//5422 -f 5423//5423 5424//5424 5425//5425 -f 5426//5426 5427//5427 5428//5428 -f 5428//5428 5427//5427 5423//5423 -f 5424//5424 5429//5429 5425//5425 -f 5425//5425 5429//5429 5430//5430 -f 5425//5425 5430//5430 5411//5411 -f 5430//5430 5431//5431 5411//5411 -f 5411//5411 5431//5431 5432//5432 -f 5411//5411 5432//5432 5407//5407 -f 5407//5407 5432//5432 5433//5433 -f 5407//5407 5433//5433 5422//5422 -f 5420//5420 5434//5434 5407//5407 -f 5407//5407 5434//5434 5435//5435 -f 5407//5407 5435//5435 5157//5157 -f 5157//5157 5435//5435 5436//5436 -f 5157//5157 5436//5436 5158//5158 -f 5326//5326 5437//5437 5438//5438 -f 5439//5439 5440//5440 5428//5428 -f 5428//5428 5440//5440 5441//5441 -f 5428//5428 5441//5441 5437//5437 -f 5423//5423 5425//5425 5428//5428 -f 5428//5428 5425//5425 5442//5442 -f 5428//5428 5442//5442 5439//5439 -f 5438//5438 5443//5443 5326//5326 -f 5326//5326 5443//5443 5444//5444 -f 5326//5326 5444//5444 5328//5328 -f 5328//5328 5444//5444 5445//5445 -f 5445//5445 5446//5446 5328//5328 -f 5328//5328 5446//5446 5447//5447 -f 5328//5328 5447//5447 5425//5425 -f 5425//5425 5447//5447 5448//5448 -f 5425//5425 5448//5448 5442//5442 -f 5449//5449 5450//5450 5167//5167 -f 5167//5167 5450//5450 5451//5451 -f 5167//5167 5451//5451 5314//5314 -f 5314//5314 5451//5451 5452//5452 -f 5314//5314 5452//5452 5453//5453 -f 5454//5454 5455//5455 5456//5456 -f 5456//5456 5455//5455 5457//5457 -f 5456//5456 5457//5457 5458//5458 -f 5453//5453 5452//5452 5459//5459 -f 5459//5459 5452//5452 5460//5460 -f 5459//5459 5460//5460 5461//5461 -f 5461//5461 5460//5460 5462//5462 -f 5461//5461 5462//5462 5463//5463 -f 5463//5463 5462//5462 5464//5464 -f 5463//5463 5464//5464 5465//5465 -f 5465//5465 5464//5464 5466//5466 -f 5465//5465 5466//5466 5467//5467 -f 5467//5467 5466//5466 5468//5468 -f 5468//5468 5466//5466 5469//5469 -f 5468//5468 5469//5469 5470//5470 -f 5470//5470 5469//5469 5471//5471 -f 5470//5470 5471//5471 5472//5472 -f 5291//5291 5289//5289 5294//5294 -f 5294//5294 5289//5289 5473//5473 -f 5294//5294 5473//5473 5474//5474 -f 5475//5475 5476//5476 5477//5477 -f 5478//5478 5479//5479 5281//5281 -f 5281//5281 5479//5479 5480//5480 -f 5281//5281 5480//5480 5283//5283 -f 5283//5283 5480//5480 5481//5481 -f 5283//5283 5481//5481 5482//5482 -f 5482//5482 5481//5481 5483//5483 -f 5482//5482 5483//5483 5288//5288 -f 5288//5288 5483//5483 5484//5484 -f 5288//5288 5484//5484 5289//5289 -f 5474//5474 5485//5485 5486//5486 -f 5486//5486 5485//5485 5487//5487 -f 5486//5486 5487//5487 5488//5488 -f 5489//5489 5490//5490 5416//5416 -f 5489//5489 5416//5416 5491//5491 -f 5467//5467 5492//5492 5465//5465 -f 5465//5465 5492//5492 5493//5493 -f 5465//5465 5493//5493 5463//5463 -f 5463//5463 5493//5493 5494//5494 -f 5463//5463 5494//5494 5495//5495 -f 5495//5495 5494//5494 5496//5496 -f 5495//5495 5496//5496 5170//5170 -f 5170//5170 5496//5496 5497//5497 -f 5170//5170 5497//5497 5168//5168 -f 5168//5168 5497//5497 5498//5498 -f 5168//5168 5498//5498 5491//5491 -f 5499//5499 5500//5500 5472//5472 -f 5472//5472 5500//5500 5501//5501 -f 5472//5472 5501//5501 5470//5470 -f 5280//5280 5502//5502 5281//5281 -f 5281//5281 5502//5502 5477//5477 -f 5281//5281 5477//5477 5478//5478 -f 5478//5478 5477//5477 5476//5476 -f 5503//5503 5504//5504 5505//5505 -f 5285//5285 5506//5506 5287//5287 -f 5287//5287 5506//5506 5279//5279 -f 5287//5287 5279//5279 5507//5507 -f 5507//5507 5279//5279 5278//5278 -f 5507//5507 5278//5278 5508//5508 -f 5508//5508 5278//5278 5509//5509 -f 5502//5502 5510//5510 5477//5477 -f 5477//5477 5510//5510 5511//5511 -f 5477//5477 5511//5511 5512//5512 -f 5234//5234 5513//5513 5514//5514 -f 5515//5515 5516//5516 5517//5517 -f 5517//5517 5516//5516 5518//5518 -f 5519//5519 4434//4434 5520//5520 -f 5520//5520 4434//4434 5234//5234 -f 5520//5520 5234//5234 5521//5521 -f 5521//5521 5234//5234 5514//5514 -f 5273//5273 4438//4438 5522//5522 -f 5522//5522 4438//4438 4436//4436 -f 5522//5522 4436//4436 5517//5517 -f 5517//5517 4436//4436 5523//5523 -f 5517//5517 5523//5523 5515//5515 -f 5519//5519 5524//5524 4434//4434 -f 4434//4434 5524//5524 5525//5525 -f 4434//4434 5525//5525 4436//4436 -f 4436//4436 5525//5525 5526//5526 -f 4436//4436 5526//5526 5523//5523 -f 5244//5244 5381//5381 5242//5242 -f 5242//5242 5381//5381 5380//5380 -f 5242//5242 5380//5380 5240//5240 -f 5240//5240 5380//5380 5405//5405 -f 5240//5240 5405//5405 5237//5237 -f 5237//5237 5405//5405 5406//5406 -f 5237//5237 5406//5406 5234//5234 -f 5234//5234 5406//5406 5517//5517 -f 5234//5234 5517//5517 5513//5513 -f 5513//5513 5517//5517 5518//5518 -f 5404//5404 5527//5527 5382//5382 -f 5382//5382 5527//5527 5394//5394 -f 5382//5382 5394//5394 5406//5406 -f 5406//5406 5394//5394 5154//5154 -f 5406//5406 5154//5154 5517//5517 -f 5517//5517 5154//5154 5153//5153 -f 5517//5517 5153//5153 5522//5522 -f 5522//5522 5153//5153 5264//5264 -f 5231//5231 4494//4494 5229//5229 -f 5229//5229 4494//4494 5528//5528 -f 5229//5229 5528//5528 5244//5244 -f 5244//5244 5528//5528 5529//5529 -f 5244//5244 5529//5529 5381//5381 -f 5381//5381 5529//5529 5354//5354 -f 5381//5381 5354//5354 5356//5356 -f 5356//5356 5354//5354 5355//5355 -f 5356//5356 5355//5355 5357//5357 -f 5266//5266 5268//5268 5267//5267 -f 5267//5267 5268//5268 5270//5270 -f 5267//5267 5270//5270 5278//5278 -f 5278//5278 5270//5270 5505//5505 -f 5278//5278 5505//5505 5509//5509 -f 5509//5509 5505//5505 5504//5504 -f 5399//5399 5400//5400 5155//5155 -f 5155//5155 5400//5400 5387//5387 -f 5155//5155 5387//5387 5530//5530 -f 5530//5530 5387//5387 5531//5531 -f 5530//5530 5531//5531 5532//5532 -f 5532//5532 5531//5531 5533//5533 -f 5534//5534 5535//5535 5533//5533 -f 5536//5536 5537//5537 5538//5538 -f 5538//5538 5537//5537 5539//5539 -f 5538//5538 5539//5539 5364//5364 -f 5364//5364 5539//5539 5540//5540 -f 5364//5364 5540//5540 5541//5541 -f 5541//5541 5542//5542 5364//5364 -f 5364//5364 5542//5542 5373//5373 -f 5364//5364 5373//5373 5365//5365 -f 5365//5365 5373//5373 5163//5163 -f 5533//5533 5535//5535 5538//5538 -f 5538//5538 5535//5535 5543//5543 -f 5538//5538 5543//5543 5536//5536 -f 5542//5542 5544//5544 5373//5373 -f 5373//5373 5544//5544 5545//5545 -f 5373//5373 5545//5545 5546//5546 -f 5389//5389 5390//5390 5387//5387 -f 5387//5387 5390//5390 5372//5372 -f 5387//5387 5372//5372 5531//5531 -f 5531//5531 5372//5372 5373//5373 -f 5531//5531 5373//5373 5533//5533 -f 5533//5533 5373//5373 5546//5546 -f 5533//5533 5546//5546 5534//5534 -f 5547//5547 5548//5548 5549//5549 -f 5549//5549 5548//5548 5477//5477 -f 5549//5549 5477//5477 5505//5505 -f 5505//5505 5477//5477 5512//5512 -f 5505//5505 5512//5512 5503//5503 -f 4494//4494 4492//4492 5528//5528 -f 5528//5528 4492//4492 4490//4490 -f 5528//5528 4490//4490 5529//5529 -f 5529//5529 4490//4490 4488//4488 -f 5529//5529 4488//4488 5354//5354 -f 5354//5354 4488//4488 4486//4486 -f 5354//5354 4486//4486 5361//5361 -f 5361//5361 4486//4486 4484//4484 -f 5361//5361 4484//4484 5364//5364 -f 5364//5364 4484//4484 4482//4482 -f 5364//5364 4482//4482 5538//5538 -f 5538//5538 4482//4482 5228//5228 -f 5538//5538 5228//5228 5533//5533 -f 5533//5533 5228//5228 5550//5550 -f 5533//5533 5550//5550 5532//5532 -f 5551//5551 5552//5552 5486//5486 -f 5553//5553 5554//5554 5548//5548 -f 5548//5548 5554//5554 5555//5555 -f 5548//5548 5555//5555 5556//5556 -f 5557//5557 5558//5558 5559//5559 -f 5559//5559 5558//5558 5560//5560 -f 5559//5559 5560//5560 5561//5561 -f 5556//5556 5551//5551 5548//5548 -f 5548//5548 5551//5551 5486//5486 -f 5548//5548 5486//5486 5477//5477 -f 5477//5477 5486//5486 5488//5488 -f 5477//5477 5488//5488 5475//5475 -f 5552//5552 5562//5562 5486//5486 -f 5486//5486 5562//5562 5563//5563 -f 5486//5486 5563//5563 5560//5560 -f 5560//5560 5563//5563 5564//5564 -f 5560//5560 5564//5564 5561//5561 -f 5565//5565 5566//5566 5547//5547 -f 5547//5547 5566//5566 5567//5567 -f 5547//5547 5567//5567 5548//5548 -f 5548//5548 5567//5567 5568//5568 -f 5548//5548 5568//5568 5569//5569 -f 5569//5569 5570//5570 5548//5548 -f 5548//5548 5570//5570 5558//5558 -f 5548//5548 5558//5558 5553//5553 -f 5553//5553 5558//5558 5557//5557 -f 5570//5570 5571//5571 5558//5558 -f 5558//5558 5571//5571 5572//5572 -f 5558//5558 5572//5572 5573//5573 -f 5573//5573 5572//5572 5574//5574 -f 5574//5574 5575//5575 5573//5573 -f 5573//5573 5575//5575 5576//5576 -f 5573//5573 5576//5576 5547//5547 -f 5547//5547 5576//5576 5577//5577 -f 5547//5547 5577//5577 5565//5565 -f 5578//5578 5579//5579 5550//5550 -f 5550//5550 5579//5579 5580//5580 -f 5550//5550 5580//5580 5581//5581 -f 5582//5582 5583//5583 5547//5547 -f 5584//5584 5585//5585 5586//5586 -f 5586//5586 5585//5585 5573//5573 -f 5586//5586 5573//5573 5587//5587 -f 5584//5584 5578//5578 5585//5585 -f 5585//5585 5578//5578 5550//5550 -f 5585//5585 5550//5550 4465//4465 -f 4465//4465 5550//5550 5228//5228 -f 4465//4465 5228//5228 4478//4478 -f 4478//4478 5228//5228 5227//5227 -f 5581//5581 5582//5582 5550//5550 -f 5550//5550 5582//5582 5547//5547 -f 5550//5550 5547//5547 5532//5532 -f 5532//5532 5547//5547 5549//5549 -f 5532//5532 5549//5549 5530//5530 -f 5530//5530 5549//5549 5505//5505 -f 5530//5530 5505//5505 5155//5155 -f 5155//5155 5505//5505 5270//5270 -f 5155//5155 5270//5270 5153//5153 -f 5153//5153 5270//5270 5272//5272 -f 5153//5153 5272//5272 5263//5263 -f 5583//5583 5588//5588 5547//5547 -f 5547//5547 5588//5588 5589//5589 -f 5547//5547 5589//5589 5573//5573 -f 5573//5573 5589//5589 5590//5590 -f 5573//5573 5590//5590 5587//5587 -f 5591//5591 5592//5592 5296//5296 -f 5593//5593 5594//5594 5595//5595 -f 5474//5474 5486//5486 5294//5294 -f 5294//5294 5486//5486 5560//5560 -f 5294//5294 5560//5560 5296//5296 -f 5296//5296 5560//5560 5596//5596 -f 5296//5296 5596//5596 5591//5591 -f 5597//5597 5598//5598 5593//5593 -f 5594//5594 5599//5599 5595//5595 -f 5595//5595 5599//5599 5600//5600 -f 5595//5595 5600//5600 5560//5560 -f 5560//5560 5600//5600 5601//5601 -f 5560//5560 5601//5601 5596//5596 -f 5592//5592 5602//5602 5296//5296 -f 5296//5296 5602//5602 5603//5603 -f 5296//5296 5603//5603 5597//5597 -f 5597//5597 5603//5603 5604//5604 -f 5597//5597 5604//5604 5598//5598 -f 5605//5605 5606//5606 5558//5558 -f 5558//5558 5606//5606 5560//5560 -f 5560//5560 5606//5606 5607//5607 -f 5560//5560 5607//5607 5608//5608 -f 5609//5609 5595//5595 5610//5610 -f 5610//5610 5595//5595 5560//5560 -f 5610//5610 5560//5560 5611//5611 -f 5611//5611 5560//5560 5608//5608 -f 5609//5609 5612//5612 5595//5595 -f 5595//5595 5612//5612 5613//5613 -f 5595//5595 5613//5613 5614//5614 -f 5613//5613 5615//5615 5614//5614 -f 5614//5614 5615//5615 5616//5616 -f 5614//5614 5616//5616 5558//5558 -f 5558//5558 5616//5616 5617//5617 -f 5558//5558 5617//5617 5605//5605 -f 5618//5618 5558//5558 5619//5619 -f 5619//5619 5558//5558 5573//5573 -f 5619//5619 5573//5573 5620//5620 -f 5620//5620 5573//5573 5621//5621 -f 5618//5618 5622//5622 5558//5558 -f 5558//5558 5622//5622 5623//5623 -f 5558//5558 5623//5623 5614//5614 -f 5614//5614 5623//5623 5624//5624 -f 5625//5625 5626//5626 5627//5627 -f 5626//5626 5628//5628 5627//5627 -f 5627//5627 5628//5628 5629//5629 -f 5627//5627 5629//5629 5573//5573 -f 5573//5573 5629//5629 5630//5630 -f 5573//5573 5630//5630 5621//5621 -f 5631//5631 5585//5585 5632//5632 -f 5632//5632 5585//5585 5633//5633 -f 5632//5632 5633//5633 5634//5634 -f 5634//5634 5633//5633 5635//5635 -f 5631//5631 5636//5636 5585//5585 -f 5585//5585 5636//5636 5637//5637 -f 5585//5585 5637//5637 5573//5573 -f 5573//5573 5637//5637 5638//5638 -f 5573//5573 5638//5638 5639//5639 -f 5639//5639 5640//5640 5573//5573 -f 5573//5573 5640//5640 5641//5641 -f 5573//5573 5641//5641 5627//5627 -f 5627//5627 5641//5641 5642//5642 -f 5627//5627 5642//5642 5643//5643 -f 5298//5298 5296//5296 4417//4417 -f 4417//4417 5296//5296 5597//5597 -f 4417//4417 5597//5597 4415//4415 -f 4415//4415 5597//5597 5644//5644 -f 4415//4415 5644//5644 4413//4413 -f 5614//5614 5645//5645 5646//5646 -f 5646//5646 5647//5647 5614//5614 -f 5614//5614 5647//5647 5648//5648 -f 5614//5614 5648//5648 5595//5595 -f 5595//5595 5648//5648 5649//5649 -f 5650//5650 5651//5651 5652//5652 -f 5653//5653 5654//5654 5645//5645 -f 5645//5645 5654//5654 5655//5655 -f 5645//5645 5655//5655 5646//5646 -f 5649//5649 5656//5656 5595//5595 -f 5595//5595 5656//5656 5657//5657 -f 5595//5595 5657//5657 5650//5650 -f 5650//5650 5657//5657 5658//5658 -f 5650//5650 5658//5658 5651//5651 -f 5659//5659 5660//5660 5645//5645 -f 5661//5661 5662//5662 5150//5150 -f 5663//5663 5664//5664 5627//5627 -f 5627//5627 5664//5664 5614//5614 -f 5627//5627 5614//5614 5625//5625 -f 5625//5625 5614//5614 5624//5624 -f 5662//5662 5665//5665 5150//5150 -f 5150//5150 5665//5665 5666//5666 -f 5150//5150 5666//5666 5627//5627 -f 5627//5627 5666//5666 5667//5667 -f 5627//5627 5667//5667 5663//5663 -f 5664//5664 5668//5668 5614//5614 -f 5614//5614 5668//5668 5669//5669 -f 5614//5614 5669//5669 5645//5645 -f 5645//5645 5669//5669 5670//5670 -f 5645//5645 5670//5670 5659//5659 -f 5643//5643 5635//5635 5627//5627 -f 5627//5627 5635//5635 5633//5633 -f 5627//5627 5633//5633 5671//5671 -f 5671//5671 5633//5633 5672//5672 -f 5671//5671 5673//5673 5627//5627 -f 5627//5627 5673//5673 5674//5674 -f 5627//5627 5674//5674 5150//5150 -f 5150//5150 5674//5674 5675//5675 -f 5150//5150 5675//5675 5676//5676 -f 5677//5677 5151//5151 5678//5678 -f 5678//5678 5151//5151 5150//5150 -f 5678//5678 5150//5150 5679//5679 -f 5679//5679 5150//5150 5676//5676 -f 5677//5677 5680//5680 5151//5151 -f 5151//5151 5680//5680 5681//5681 -f 5151//5151 5681//5681 5633//5633 -f 5633//5633 5681//5681 5682//5682 -f 5633//5633 5682//5682 5672//5672 -f 5683//5683 5684//5684 5147//5147 -f 5685//5685 5686//5686 5650//5650 -f 5650//5650 5686//5686 5687//5687 -f 5688//5688 5689//5689 5644//5644 -f 5644//5644 5689//5689 5690//5690 -f 5593//5593 5595//5595 5597//5597 -f 5597//5597 5595//5595 5650//5650 -f 5597//5597 5650//5650 5644//5644 -f 5644//5644 5650//5650 5687//5687 -f 5644//5644 5687//5687 5688//5688 -f 4411//4411 4413//4413 5147//5147 -f 5147//5147 4413//4413 5644//5644 -f 5147//5147 5644//5644 5683//5683 -f 5683//5683 5644//5644 5690//5690 -f 5684//5684 5691//5691 5147//5147 -f 5147//5147 5691//5691 5692//5692 -f 5147//5147 5692//5692 5148//5148 -f 5148//5148 5692//5692 5693//5693 -f 5148//5148 5693//5693 5694//5694 -f 5694//5694 5685//5685 5148//5148 -f 5148//5148 5685//5685 5650//5650 -f 5148//5148 5650//5650 5695//5695 -f 4411//4411 5312//5312 4409//4409 -f 4409//4409 5312//5312 5313//5313 -f 4409//4409 5313//5313 5308//5308 -f 5149//5149 5696//5696 5697//5697 -f 5698//5698 5699//5699 5695//5695 -f 5695//5695 5699//5699 5700//5700 -f 5695//5695 5700//5700 5148//5148 -f 5148//5148 5700//5700 5701//5701 -f 5149//5149 5697//5697 5702//5702 -f 5697//5697 5703//5703 5702//5702 -f 5702//5702 5703//5703 5704//5704 -f 5702//5702 5704//5704 5695//5695 -f 5695//5695 5704//5704 5705//5705 -f 5695//5695 5705//5705 5698//5698 -f 5701//5701 5706//5706 5148//5148 -f 5148//5148 5706//5706 5707//5707 -f 5148//5148 5707//5707 5149//5149 -f 5149//5149 5707//5707 5708//5708 -f 5149//5149 5708//5708 5696//5696 -f 5709//5709 5710//5710 5711//5711 -f 5702//5702 5712//5712 5713//5713 -f 5713//5713 5712//5712 5714//5714 -f 5714//5714 5715//5715 5713//5713 -f 5713//5713 5715//5715 5716//5716 -f 5713//5713 5716//5716 5711//5711 -f 5711//5711 5716//5716 5717//5717 -f 5711//5711 5717//5717 5709//5709 -f 5718//5718 5719//5719 5695//5695 -f 5710//5710 5718//5718 5711//5711 -f 5711//5711 5718//5718 5695//5695 -f 5711//5711 5695//5695 5645//5645 -f 5645//5645 5695//5695 5650//5650 -f 5645//5645 5650//5650 5653//5653 -f 5653//5653 5650//5650 5652//5652 -f 5719//5719 5720//5720 5695//5695 -f 5695//5695 5720//5720 5721//5721 -f 5695//5695 5721//5721 5702//5702 -f 5702//5702 5721//5721 5722//5722 -f 5702//5702 5722//5722 5712//5712 -f 5723//5723 5724//5724 5713//5713 -f 5711//5711 5725//5725 5726//5726 -f 5713//5713 5724//5724 5727//5727 -f 5152//5152 5728//5728 5729//5729 -f 5726//5726 5730//5730 5711//5711 -f 5711//5711 5730//5730 5731//5731 -f 5711//5711 5731//5731 5713//5713 -f 5713//5713 5731//5731 5732//5732 -f 5713//5713 5732//5732 5723//5723 -f 5660//5660 5661//5661 5645//5645 -f 5645//5645 5661//5661 5150//5150 -f 5645//5645 5150//5150 5711//5711 -f 5711//5711 5150//5150 5152//5152 -f 5711//5711 5152//5152 5725//5725 -f 5725//5725 5152//5152 5729//5729 -f 5724//5724 5733//5733 5727//5727 -f 5727//5727 5733//5733 5734//5734 -f 5727//5727 5734//5734 5152//5152 -f 5152//5152 5734//5734 5735//5735 -f 5152//5152 5735//5735 5728//5728 -f 5458//5458 5449//5449 5456//5456 -f 5456//5456 5449//5449 5167//5167 -f 5456//5456 5167//5167 5312//5312 -f 5312//5312 5167//5167 5166//5166 -f 5312//5312 5166//5166 5310//5310 -f 5736//5736 5737//5737 5149//5149 -f 5145//5145 5738//5738 5702//5702 -f 5702//5702 5738//5738 5739//5739 -f 5702//5702 5739//5739 5149//5149 -f 5149//5149 5739//5739 5740//5740 -f 5149//5149 5740//5740 5736//5736 -f 5741//5741 5742//5742 5456//5456 -f 5742//5742 5743//5743 5456//5456 -f 5456//5456 5743//5743 5744//5744 -f 5456//5456 5744//5744 5146//5146 -f 5146//5146 5744//5744 5745//5745 -f 5146//5146 5745//5745 5144//5144 -f 4411//4411 5147//5147 5312//5312 -f 5312//5312 5147//5147 5149//5149 -f 5312//5312 5149//5149 5456//5456 -f 5456//5456 5149//5149 5737//5737 -f 5456//5456 5737//5737 5741//5741 -f 5746//5746 5747//5747 5748//5748 -f 5748//5748 5747//5747 5146//5146 -f 5746//5746 5749//5749 5747//5747 -f 5747//5747 5749//5749 5750//5750 -f 5747//5747 5750//5750 5713//5713 -f 5713//5713 5750//5750 5751//5751 -f 5145//5145 5702//5702 5146//5146 -f 5146//5146 5702//5702 5752//5752 -f 5146//5146 5752//5752 5753//5753 -f 5753//5753 5754//5754 5146//5146 -f 5146//5146 5754//5754 5755//5755 -f 5146//5146 5755//5755 5748//5748 -f 5751//5751 5756//5756 5713//5713 -f 5713//5713 5756//5756 5757//5757 -f 5713//5713 5757//5757 5702//5702 -f 5702//5702 5757//5757 5758//5758 -f 5702//5702 5758//5758 5752//5752 -f 5759//5759 5760//5760 5225//5225 -f 5225//5225 5760//5760 5727//5727 -f 5225//5225 5727//5727 4475//4475 -f 4475//4475 5727//5727 5152//5152 -f 4475//4475 5152//5152 4473//4473 -f 4473//4473 5152//5152 5151//5151 -f 4473//4473 5151//5151 4471//4471 -f 4471//4471 5151//5151 5633//5633 -f 4471//4471 5633//5633 4469//4469 -f 4469//4469 5633//5633 5585//5585 -f 4469//4469 5585//5585 4467//4467 -f 4467//4467 5585//5585 4465//4465 -f 5761//5761 5762//5762 5747//5747 -f 5747//5747 5762//5762 5763//5763 -f 5747//5747 5763//5763 5225//5225 -f 5225//5225 5763//5763 5764//5764 -f 5225//5225 5764//5764 5759//5759 -f 5765//5765 5713//5713 5766//5766 -f 5766//5766 5713//5713 5727//5727 -f 5766//5766 5727//5727 5767//5767 -f 5767//5767 5727//5727 5760//5760 -f 5765//5765 5768//5768 5713//5713 -f 5713//5713 5768//5768 5769//5769 -f 5713//5713 5769//5769 5747//5747 -f 5747//5747 5769//5769 5770//5770 -f 5747//5747 5770//5770 5761//5761 -f 5224//5224 4460//4460 5223//5223 -f 5223//5223 4460//4460 5341//5341 -f 5223//5223 5341//5341 5225//5225 -f 5225//5225 5341//5341 5343//5343 -f 5225//5225 5343//5343 5747//5747 -f 5747//5747 5343//5343 5771//5771 -f 5747//5747 5771//5771 5146//5146 -f 5146//5146 5771//5771 5772//5772 -f 5146//5146 5772//5772 5456//5456 -f 5456//5456 5772//5772 5472//5472 -f 5456//5456 5472//5472 5454//5454 -f 5454//5454 5472//5472 5471//5471 -f 5345//5345 5337//5337 5343//5343 -f 5343//5343 5337//5337 5328//5328 -f 5343//5343 5328//5328 5771//5771 -f 5771//5771 5328//5328 5425//5425 -f 5771//5771 5425//5425 5772//5772 -f 5772//5772 5425//5425 5411//5411 -f 5772//5772 5411//5411 5472//5472 -f 5472//5472 5411//5411 5416//5416 -f 5472//5472 5416//5416 5499//5499 -f 5499//5499 5416//5416 5490//5490 -f 4460//4460 4458//4458 5341//5341 -f 5341//5341 4458//4458 4456//4456 -f 5341//5341 4456//4456 5322//5322 -f 5322//5322 4456//4456 4454//4454 -f 5322//5322 4454//4454 5323//5323 -f 5491//5491 5416//5416 5168//5168 -f 5168//5168 5416//5416 5158//5158 -f 5168//5168 5158//5158 5173//5173 -f 5173//5173 5158//5158 5436//5436 -f 5173//5173 5436//5436 5171//5171 -f 4454//4454 4452//4452 5323//5323 -f 5323//5323 4452//4452 5773//5773 -f 5323//5323 5773//5773 5326//5326 -f 5326//5326 5773//5773 5774//5774 -f 5326//5326 5774//5774 5437//5437 -f 5437//5437 5774//5774 5434//5434 -f 5437//5437 5434//5434 5428//5428 -f 5428//5428 5434//5434 5420//5420 -f 5428//5428 5420//5420 5426//5426 -f 5775//5775 5776//5776 5171//5171 -f 5171//5171 5776//5776 5777//5777 -f 5171//5171 5777//5777 5778//5778 -f 5190//5190 5779//5779 5780//5780 -f 5186//5186 5172//5172 4424//4424 -f 4424//4424 5172//5172 5171//5171 -f 4424//4424 5171//5171 4426//4426 -f 4426//4426 5171//5171 5778//5778 -f 5778//5778 5781//5781 4426//4426 -f 4426//4426 5781//5781 5782//5782 -f 4426//4426 5782//5782 4428//4428 -f 4428//4428 5782//5782 5783//5783 -f 5783//5783 5784//5784 4428//4428 -f 4428//4428 5784//5784 5785//5785 -f 4428//4428 5785//5785 5190//5190 -f 5190//5190 5785//5785 5786//5786 -f 5190//5190 5786//5786 5779//5779 -f 4452//4452 4450//4450 5773//5773 -f 5773//5773 4450//4450 5218//5218 -f 5773//5773 5218//5218 5774//5774 -f 5774//5774 5218//5218 5217//5217 -f 5774//5774 5217//5217 5434//5434 -f 5434//5434 5217//5217 5215//5215 -f 5434//5434 5215//5215 5435//5435 -f 5435//5435 5215//5215 5213//5213 -f 5435//5435 5213//5213 5436//5436 -f 5436//5436 5213//5213 5204//5204 -f 5436//5436 5204//5204 5171//5171 -f 5171//5171 5204//5204 5190//5190 -f 5171//5171 5190//5190 5775//5775 -f 5775//5775 5190//5190 5780//5780 -f 5118//5118 5539//5539 5119//5119 -f 5119//5119 5539//5539 5537//5537 -f 5119//5119 5537//5537 5106//5106 -f 5106//5106 5537//5537 5536//5536 -f 5106//5106 5536//5536 5107//5107 -f 5107//5107 5536//5536 5543//5543 -f 5107//5107 5543//5543 5112//5112 -f 5112//5112 5543//5543 5535//5535 -f 5112//5112 5535//5535 5111//5111 -f 5111//5111 5535//5535 5534//5534 -f 5111//5111 5534//5534 5110//5110 -f 5110//5110 5534//5534 5546//5546 -f 5110//5110 5546//5546 5113//5113 -f 5113//5113 5546//5546 5545//5545 -f 5113//5113 5545//5545 5114//5114 -f 5114//5114 5545//5545 5544//5544 -f 5114//5114 5544//5544 5115//5115 -f 5115//5115 5544//5544 5542//5542 -f 5115//5115 5542//5542 5116//5116 -f 5116//5116 5542//5542 5541//5541 -f 5116//5116 5541//5541 5117//5117 -f 5117//5117 5541//5541 5540//5540 -f 5117//5117 5540//5540 5118//5118 -f 5118//5118 5540//5540 5539//5539 -f 4550//4550 5351//5351 4554//4554 -f 4554//4554 5351//5351 5350//5350 -f 4554//4554 5350//5350 4555//4555 -f 4555//4555 5350//5350 5349//5349 -f 4555//4555 5349//5349 4553//4553 -f 4553//4553 5349//5349 5348//5348 -f 4553//4553 5348//5348 4552//4552 -f 4552//4552 5348//5348 5346//5346 -f 4552//4552 5346//5346 4551//4551 -f 4551//4551 5346//5346 5338//5338 -f 4551//4551 5338//5338 4545//4545 -f 4545//4545 5338//5338 5337//5337 -f 4545//4545 5337//5337 4546//4546 -f 4546//4546 5337//5337 5345//5345 -f 4546//4546 5345//5345 4548//4548 -f 4548//4548 5345//5345 5344//5344 -f 4548//4548 5344//5344 4542//4542 -f 4542//4542 5344//5344 5342//5342 -f 4542//4542 5342//5342 4543//4543 -f 4543//4543 5342//5342 5340//5340 -f 4543//4543 5340//5340 4549//4549 -f 4549//4549 5340//5340 5339//5339 -f 4549//4549 5339//5339 4550//4550 -f 4550//4550 5339//5339 5351//5351 -f 4533//4533 5331//5331 4535//4535 -f 4535//4535 5331//5331 5324//5324 -f 4535//4535 5324//5324 4536//4536 -f 4536//4536 5324//5324 5336//5336 -f 4536//4536 5336//5336 4537//4537 -f 4537//4537 5336//5336 5335//5335 -f 4537//4537 5335//5335 4538//4538 -f 4538//4538 5335//5335 5334//5334 -f 4538//4538 5334//5334 4540//4540 -f 4540//4540 5334//5334 5325//5325 -f 4540//4540 5325//5325 4541//4541 -f 4541//4541 5325//5325 5327//5327 -f 4541//4541 5327//5327 4527//4527 -f 4527//4527 5327//5327 5329//5329 -f 4527//4527 5329//5329 4528//4528 -f 4528//4528 5329//5329 5330//5330 -f 4528//4528 5330//5330 4556//4556 -f 4556//4556 5330//5330 5347//5347 -f 4556//4556 5347//5347 4530//4530 -f 4530//4530 5347//5347 5333//5333 -f 4530//4530 5333//5333 4531//4531 -f 4531//4531 5333//5333 5332//5332 -f 4531//4531 5332//5332 4533//4533 -f 4533//4533 5332//5332 5331//5331 -f 4567//4567 5360//5360 4568//4568 -f 4568//4568 5360//5360 5362//5362 -f 4568//4568 5362//5362 4569//4569 -f 4569//4569 5362//5362 5363//5363 -f 4569//4569 5363//5363 4571//4571 -f 4571//4571 5363//5363 5365//5365 -f 4571//4571 5365//5365 4573//4573 -f 4573//4573 5365//5365 5163//5163 -f 4573//4573 5163//5163 4574//4574 -f 4574//4574 5163//5163 5162//5162 -f 4574//4574 5162//5162 4558//4558 -f 4558//4558 5162//5162 5359//5359 -f 4558//4558 5359//5359 4560//4560 -f 4560//4560 5359//5359 5358//5358 -f 4560//4560 5358//5358 4561//4561 -f 4561//4561 5358//5358 5357//5357 -f 4561//4561 5357//5357 4562//4562 -f 4562//4562 5357//5357 5355//5355 -f 4562//4562 5355//5355 4563//4563 -f 4563//4563 5355//5355 5353//5353 -f 4563//4563 5353//5353 4565//4565 -f 4565//4565 5353//5353 5352//5352 -f 4565//4565 5352//5352 4567//4567 -f 4567//4567 5352//5352 5360//5360 -f 4581//4581 5272//5272 4582//4582 -f 4582//4582 5272//5272 5271//5271 -f 4582//4582 5271//5271 4576//4576 -f 4576//4576 5271//5271 5269//5269 -f 4576//4576 5269//5269 4577//4577 -f 4577//4577 5269//5269 5268//5268 -f 4577//4577 5268//5268 4583//4583 -f 4583//4583 5268//5268 5266//5266 -f 4583//4583 5266//5266 4585//4585 -f 4585//4585 5266//5266 5265//5265 -f 4585//4585 5265//5265 4587//4587 -f 4587//4587 5265//5265 5275//5275 -f 4587//4587 5275//5275 4589//4589 -f 4589//4589 5275//5275 5274//5274 -f 4589//4589 5274//5274 4588//4588 -f 4588//4588 5274//5274 5273//5273 -f 4588//4588 5273//5273 5127//5127 -f 5127//5127 5273//5273 5522//5522 -f 5127//5127 5522//5522 4578//4578 -f 4578//4578 5522//5522 5264//5264 -f 4578//4578 5264//5264 4579//4579 -f 4579//4579 5264//5264 5263//5263 -f 4579//4579 5263//5263 4581//4581 -f 4581//4581 5263//5263 5272//5272 -f 4601//4601 5176//5176 4603//4603 -f 4603//4603 5176//5176 5175//5175 -f 4603//4603 5175//5175 4604//4604 -f 4604//4604 5175//5175 5174//5174 -f 4604//4604 5174//5174 4605//4605 -f 4605//4605 5174//5174 5172//5172 -f 4605//4605 5172//5172 4591//4591 -f 4591//4591 5172//5172 5186//5186 -f 4591//4591 5186//5186 4592//4592 -f 4592//4592 5186//5186 5185//5185 -f 4592//4592 5185//5185 4593//4593 -f 4593//4593 5185//5185 5184//5184 -f 4593//4593 5184//5184 4596//4596 -f 4596//4596 5184//5184 5182//5182 -f 4596//4596 5182//5182 4597//4597 -f 4597//4597 5182//5182 5180//5180 -f 4597//4597 5180//5180 4598//4598 -f 4598//4598 5180//5180 5179//5179 -f 4598//4598 5179//5179 4599//4599 -f 4599//4599 5179//5179 5178//5178 -f 4599//4599 5178//5178 4600//4600 -f 4600//4600 5178//5178 5177//5177 -f 4600//4600 5177//5177 4601//4601 -f 4601//4601 5177//5177 5176//5176 -f 5029//5029 5600//5600 5022//5022 -f 5022//5022 5600//5600 5599//5599 -f 5022//5022 5599//5599 5023//5023 -f 5023//5023 5599//5599 5594//5594 -f 5023//5023 5594//5594 5017//5017 -f 5017//5017 5594//5594 5593//5593 -f 5017//5017 5593//5593 5018//5018 -f 5018//5018 5593//5593 5598//5598 -f 5018//5018 5598//5598 5021//5021 -f 5021//5021 5598//5598 5604//5604 -f 5021//5021 5604//5604 5020//5020 -f 5020//5020 5604//5604 5603//5603 -f 5020//5020 5603//5603 5019//5019 -f 5019//5019 5603//5603 5602//5602 -f 5019//5019 5602//5602 5024//5024 -f 5024//5024 5602//5602 5592//5592 -f 5024//5024 5592//5592 5025//5025 -f 5025//5025 5592//5592 5591//5591 -f 5025//5025 5591//5591 5027//5027 -f 5027//5027 5591//5591 5596//5596 -f 5027//5027 5596//5596 5028//5028 -f 5028//5028 5596//5596 5601//5601 -f 5028//5028 5601//5601 5029//5029 -f 5029//5029 5601//5601 5600//5600 -f 4971//4971 5685//5685 4972//4972 -f 4972//4972 5685//5685 5694//5694 -f 4972//4972 5694//5694 4973//4973 -f 4973//4973 5694//5694 5693//5693 -f 4973//4973 5693//5693 4974//4974 -f 4974//4974 5693//5693 5692//5692 -f 4974//4974 5692//5692 4975//4975 -f 4975//4975 5692//5692 5691//5691 -f 4975//4975 5691//5691 4966//4966 -f 4966//4966 5691//5691 5684//5684 -f 4966//4966 5684//5684 4965//4965 -f 4965//4965 5684//5684 5683//5683 -f 4965//4965 5683//5683 4964//4964 -f 4964//4964 5683//5683 5690//5690 -f 4964//4964 5690//5690 4967//4967 -f 4967//4967 5690//5690 5689//5689 -f 4967//4967 5689//5689 4968//4968 -f 4968//4968 5689//5689 5688//5688 -f 4968//4968 5688//5688 4969//4969 -f 4969//4969 5688//5688 5687//5687 -f 4969//4969 5687//5687 4970//4970 -f 4970//4970 5687//5687 5686//5686 -f 4970//4970 5686//5686 4971//4971 -f 4971//4971 5686//5686 5685//5685 -f 5079//5079 5554//5554 5080//5080 -f 5080//5080 5554//5554 5553//5553 -f 5080//5080 5553//5553 5077//5077 -f 5077//5077 5553//5553 5557//5557 -f 5077//5077 5557//5557 5074//5074 -f 5074//5074 5557//5557 5559//5559 -f 5074//5074 5559//5559 5075//5075 -f 5075//5075 5559//5559 5561//5561 -f 5075//5075 5561//5561 5076//5076 -f 5076//5076 5561//5561 5564//5564 -f 5076//5076 5564//5564 5070//5070 -f 5070//5070 5564//5564 5563//5563 -f 5070//5070 5563//5563 5069//5069 -f 5069//5069 5563//5563 5562//5562 -f 5069//5069 5562//5562 5068//5068 -f 5068//5068 5562//5562 5552//5552 -f 5068//5068 5552//5552 5071//5071 -f 5071//5071 5552//5552 5551//5551 -f 5071//5071 5551//5551 5072//5072 -f 5072//5072 5551//5551 5556//5556 -f 5072//5072 5556//5556 5078//5078 -f 5078//5078 5556//5556 5555//5555 -f 5078//5078 5555//5555 5079//5079 -f 5079//5079 5555//5555 5554//5554 -f 4695//4695 5295//5295 4687//4687 -f 4687//4687 5295//5295 5297//5297 -f 4687//4687 5297//5297 4688//4688 -f 4688//4688 5297//5297 5300//5300 -f 4688//4688 5300//5300 4700//4700 -f 4700//4700 5300//5300 5299//5299 -f 4700//4700 5299//5299 4701//4701 -f 4701//4701 5299//5299 5298//5298 -f 4701//4701 5298//5298 4702//4702 -f 4702//4702 5298//5298 5307//5307 -f 4702//4702 5307//5307 4690//4690 -f 4690//4690 5307//5307 5306//5306 -f 4690//4690 5306//5306 4691//4691 -f 4691//4691 5306//5306 5304//5304 -f 4691//4691 5304//5304 4697//4697 -f 4697//4697 5304//5304 5302//5302 -f 4697//4697 5302//5302 4698//4698 -f 4698//4698 5302//5302 5301//5301 -f 4698//4698 5301//5301 4699//4699 -f 4699//4699 5301//5301 5293//5293 -f 4699//4699 5293//5293 4694//4694 -f 4694//4694 5293//5293 5292//5292 -f 4694//4694 5292//5292 4695//4695 -f 4695//4695 5292//5292 5295//5295 -f 5104//5104 5579//5579 5105//5105 -f 5105//5105 5579//5579 5578//5578 -f 5105//5105 5578//5578 5098//5098 -f 5098//5098 5578//5578 5584//5584 -f 5098//5098 5584//5584 5099//5099 -f 5099//5099 5584//5584 5586//5586 -f 5099//5099 5586//5586 5100//5100 -f 5100//5100 5586//5586 5587//5587 -f 5100//5100 5587//5587 5101//5101 -f 5101//5101 5587//5587 5590//5590 -f 5101//5101 5590//5590 5102//5102 -f 5102//5102 5590//5590 5589//5589 -f 5102//5102 5589//5589 5094//5094 -f 5094//5094 5589//5589 5588//5588 -f 5094//5094 5588//5588 5095//5095 -f 5095//5095 5588//5588 5583//5583 -f 5095//5095 5583//5583 5096//5096 -f 5096//5096 5583//5583 5582//5582 -f 5096//5096 5582//5582 5097//5097 -f 5097//5097 5582//5582 5581//5581 -f 5097//5097 5581//5581 5103//5103 -f 5103//5103 5581//5581 5580//5580 -f 5103//5103 5580//5580 5104//5104 -f 5104//5104 5580//5580 5579//5579 -f 4609//4609 5379//5379 4610//4610 -f 4610//4610 5379//5379 5378//5378 -f 4610//4610 5378//5378 4611//4611 -f 4611//4611 5378//5378 5377//5377 -f 4611//4611 5377//5377 4612//4612 -f 4612//4612 5377//5377 5371//5371 -f 4612//4612 5371//5371 4613//4613 -f 4613//4613 5371//5371 5370//5370 -f 4613//4613 5370//5370 4615//4615 -f 4615//4615 5370//5370 5376//5376 -f 4615//4615 5376//5376 4617//4617 -f 4617//4617 5376//5376 5375//5375 -f 4617//4617 5375//5375 4618//4618 -f 4618//4618 5375//5375 5374//5374 -f 4618//4618 5374//5374 4619//4619 -f 4619//4619 5374//5374 5367//5367 -f 4619//4619 5367//5367 4620//4620 -f 4620//4620 5367//5367 5366//5366 -f 4620//4620 5366//5366 4607//4607 -f 4607//4607 5366//5366 5369//5369 -f 4607//4607 5369//5369 4608//4608 -f 4608//4608 5369//5369 5368//5368 -f 4608//4608 5368//5368 4609//4609 -f 4609//4609 5368//5368 5379//5379 -f 4626//4626 5393//5393 4627//4627 -f 4627//4627 5393//5393 5392//5392 -f 4627//4627 5392//5392 4628//4628 -f 4628//4628 5392//5392 5391//5391 -f 4628//4628 5391//5391 4629//4629 -f 4629//4629 5391//5391 5390//5390 -f 4629//4629 5390//5390 4630//4630 -f 4630//4630 5390//5390 5389//5389 -f 4630//4630 5389//5389 4632//4632 -f 4632//4632 5389//5389 5388//5388 -f 4632//4632 5388//5388 4633//4633 -f 4633//4633 5388//5388 5386//5386 -f 4633//4633 5386//5386 4623//4623 -f 4623//4623 5386//5386 5385//5385 -f 4623//4623 5385//5385 4524//4524 -f 4524//4524 5385//5385 5383//5383 -f 4524//4524 5383//5383 4525//4525 -f 4525//4525 5383//5383 5160//5160 -f 4525//4525 5160//5160 4624//4624 -f 4624//4624 5160//5160 5159//5159 -f 4624//4624 5159//5159 4625//4625 -f 4625//4625 5159//5159 5384//5384 -f 4625//4625 5384//5384 4626//4626 -f 4626//4626 5384//5384 5393//5393 -f 4637//4637 5403//5403 4638//4638 -f 4638//4638 5403//5403 5402//5402 -f 4638//4638 5402//5402 4639//4639 -f 4639//4639 5402//5402 5401//5401 -f 4639//4639 5401//5401 4640//4640 -f 4640//4640 5401//5401 5400//5400 -f 4640//4640 5400//5400 4641//4641 -f 4641//4641 5400//5400 5399//5399 -f 4641//4641 5399//5399 4643//4643 -f 4643//4643 5399//5399 5398//5398 -f 4643//4643 5398//5398 4644//4644 -f 4644//4644 5398//5398 5397//5397 -f 4644//4644 5397//5397 4635//4635 -f 4635//4635 5397//5397 5396//5396 -f 4635//4635 5396//5396 4521//4521 -f 4521//4521 5396//5396 5395//5395 -f 4521//4521 5395//5395 4522//4522 -f 4522//4522 5395//5395 5394//5394 -f 4522//4522 5394//5394 4634//4634 -f 4634//4634 5394//5394 5527//5527 -f 4634//4634 5527//5527 4636//4636 -f 4636//4636 5527//5527 5404//5404 -f 4636//4636 5404//5404 4637//4637 -f 4637//4637 5404//5404 5403//5403 -f 4656//4656 5412//5412 4645//4645 -f 4645//4645 5412//5412 5413//5413 -f 4645//4645 5413//5413 4518//4518 -f 4518//4518 5413//5413 5408//5408 -f 4518//4518 5408//5408 4519//4519 -f 4519//4519 5408//5408 5157//5157 -f 4519//4519 5157//5157 4673//4673 -f 4673//4673 5157//5157 5156//5156 -f 4673//4673 5156//5156 4651//4651 -f 4651//4651 5156//5156 5409//5409 -f 4651//4651 5409//5409 4649//4649 -f 4649//4649 5409//5409 5419//5419 -f 4649//4649 5419//5419 4647//4647 -f 4647//4647 5419//5419 5418//5418 -f 4647//4647 5418//5418 4648//4648 -f 4648//4648 5418//5418 5417//5417 -f 4648//4648 5417//5417 4652//4652 -f 4652//4652 5417//5417 5415//5415 -f 4652//4652 5415//5415 4653//4653 -f 4653//4653 5415//5415 5414//5414 -f 4653//4653 5414//5414 4655//4655 -f 4655//4655 5414//5414 5410//5410 -f 4655//4655 5410//5410 4656//4656 -f 4656//4656 5410//5410 5412//5412 -f 4670//4670 5423//5423 4664//4664 -f 4664//4664 5423//5423 5427//5427 -f 4664//4664 5427//5427 4665//4665 -f 4665//4665 5427//5427 5426//5426 -f 4665//4665 5426//5426 4657//4657 -f 4657//4657 5426//5426 5420//5420 -f 4657//4657 5420//5420 4658//4658 -f 4658//4658 5420//5420 5421//5421 -f 4658//4658 5421//5421 4659//4659 -f 4659//4659 5421//5421 5422//5422 -f 4659//4659 5422//5422 4660//4660 -f 4660//4660 5422//5422 5433//5433 -f 4660//4660 5433//5433 4661//4661 -f 4661//4661 5433//5433 5432//5432 -f 4661//4661 5432//5432 4662//4662 -f 4662//4662 5432//5432 5431//5431 -f 4662//4662 5431//5431 4666//4666 -f 4666//4666 5431//5431 5430//5430 -f 4666//4666 5430//5430 4667//4667 -f 4667//4667 5430//5430 5429//5429 -f 4667//4667 5429//5429 4669//4669 -f 4669//4669 5429//5429 5424//5424 -f 4669//4669 5424//5424 4670//4670 -f 4670//4670 5424//5424 5423//5423 -f 4683//4683 5444//5444 4684//4684 -f 4684//4684 5444//5444 5443//5443 -f 4684//4684 5443//5443 4686//4686 -f 4686//4686 5443//5443 5438//5438 -f 4686//4686 5438//5438 4674//4674 -f 4674//4674 5438//5438 5437//5437 -f 4674//4674 5437//5437 4675//4675 -f 4675//4675 5437//5437 5441//5441 -f 4675//4675 5441//5441 4676//4676 -f 4676//4676 5441//5441 5440//5440 -f 4676//4676 5440//5440 4677//4677 -f 4677//4677 5440//5440 5439//5439 -f 4677//4677 5439//5439 4678//4678 -f 4678//4678 5439//5439 5442//5442 -f 4678//4678 5442//5442 4679//4679 -f 4679//4679 5442//5442 5448//5448 -f 4679//4679 5448//5448 4680//4680 -f 4680//4680 5448//5448 5447//5447 -f 4680//4680 5447//5447 4681//4681 -f 4681//4681 5447//5447 5446//5446 -f 4681//4681 5446//5446 4682//4682 -f 4682//4682 5446//5446 5445//5445 -f 4682//4682 5445//5445 4683//4683 -f 4683//4683 5445//5445 5444//5444 -f 4918//4918 5760//5760 4919//4919 -f 4919//4919 5760//5760 5759//5759 -f 4919//4919 5759//5759 4920//4920 -f 4920//4920 5759//5759 5764//5764 -f 4920//4920 5764//5764 4915//4915 -f 4915//4915 5764//5764 5763//5763 -f 4915//4915 5763//5763 4916//4916 -f 4916//4916 5763//5763 5762//5762 -f 4916//4916 5762//5762 4921//4921 -f 4921//4921 5762//5762 5761//5761 -f 4921//4921 5761//5761 4922//4922 -f 4922//4922 5761//5761 5770//5770 -f 4922//4922 5770//5770 4923//4923 -f 4923//4923 5770//5770 5769//5769 -f 4923//4923 5769//5769 4914//4914 -f 4914//4914 5769//5769 5768//5768 -f 4914//4914 5768//5768 4913//4913 -f 4913//4913 5768//5768 5765//5765 -f 4913//4913 5765//5765 4912//4912 -f 4912//4912 5765//5765 5766//5766 -f 4912//4912 5766//5766 4917//4917 -f 4917//4917 5766//5766 5767//5767 -f 4917//4917 5767//5767 4918//4918 -f 4918//4918 5767//5767 5760//5760 -f 4811//4811 5166//5166 4812//4812 -f 4812//4812 5166//5166 5165//5165 -f 4812//4812 5165//5165 4813//4813 -f 4813//4813 5165//5165 5316//5316 -f 4813//4813 5316//5316 4814//4814 -f 4814//4814 5316//5316 5315//5315 -f 4814//4814 5315//5315 4804//4804 -f 4804//4804 5315//5315 5321//5321 -f 4804//4804 5321//5321 4806//4806 -f 4806//4806 5321//5321 5320//5320 -f 4806//4806 5320//5320 4808//4808 -f 4808//4808 5320//5320 5317//5317 -f 4808//4808 5317//5317 4809//4809 -f 4809//4809 5317//5317 5309//5309 -f 4809//4809 5309//5309 4803//4803 -f 4803//4803 5309//5309 5308//5308 -f 4803//4803 5308//5308 4800//4800 -f 4800//4800 5308//5308 5313//5313 -f 4800//4800 5313//5313 4801//4801 -f 4801//4801 5313//5313 5311//5311 -f 4801//4801 5311//5311 4810//4810 -f 4810//4810 5311//5311 5310//5310 -f 4810//4810 5310//5310 4811//4811 -f 4811//4811 5310//5310 5166//5166 -f 4895//4895 5145//5145 4891//4891 -f 4891//4891 5145//5145 5144//5144 -f 4891//4891 5144//5144 4892//4892 -f 4892//4892 5144//5144 5745//5745 -f 4892//4892 5745//5745 4887//4887 -f 4887//4887 5745//5745 5744//5744 -f 4887//4887 5744//5744 4888//4888 -f 4888//4888 5744//5744 5743//5743 -f 4888//4888 5743//5743 4889//4889 -f 4889//4889 5743//5743 5742//5742 -f 4889//4889 5742//5742 4881//4881 -f 4881//4881 5742//5742 5741//5741 -f 4881//4881 5741//5741 4883//4883 -f 4883//4883 5741//5741 5737//5737 -f 4883//4883 5737//5737 4884//4884 -f 4884//4884 5737//5737 5736//5736 -f 4884//4884 5736//5736 4885//4885 -f 4885//4885 5736//5736 5740//5740 -f 4885//4885 5740//5740 4893//4893 -f 4893//4893 5740//5740 5739//5739 -f 4893//4893 5739//5739 4894//4894 -f 4894//4894 5739//5739 5738//5738 -f 4894//4894 5738//5738 4895//4895 -f 4895//4895 5738//5738 5145//5145 -f 4910//4910 5750//5750 4897//4897 -f 4897//4897 5750//5750 5749//5749 -f 4897//4897 5749//5749 4898//4898 -f 4898//4898 5749//5749 5746//5746 -f 4898//4898 5746//5746 4903//4903 -f 4903//4903 5746//5746 5748//5748 -f 4903//4903 5748//5748 4904//4904 -f 4904//4904 5748//5748 5755//5755 -f 4904//4904 5755//5755 4905//4905 -f 4905//4905 5755//5755 5754//5754 -f 4905//4905 5754//5754 4906//4906 -f 4906//4906 5754//5754 5753//5753 -f 4906//4906 5753//5753 4907//4907 -f 4907//4907 5753//5753 5752//5752 -f 4907//4907 5752//5752 4900//4900 -f 4900//4900 5752//5752 5758//5758 -f 4900//4900 5758//5758 4901//4901 -f 4901//4901 5758//5758 5757//5757 -f 4901//4901 5757//5757 4908//4908 -f 4908//4908 5757//5757 5756//5756 -f 4908//4908 5756//5756 4909//4909 -f 4909//4909 5756//5756 5751//5751 -f 4909//4909 5751//5751 4910//4910 -f 4910//4910 5751//5751 5750//5750 -f 5087//5087 5577//5577 5088//5088 -f 5088//5088 5577//5577 5576//5576 -f 5088//5088 5576//5576 5089//5089 -f 5089//5089 5576//5576 5575//5575 -f 5089//5089 5575//5575 5090//5090 -f 5090//5090 5575//5575 5574//5574 -f 5090//5090 5574//5574 5091//5091 -f 5091//5091 5574//5574 5572//5572 -f 5091//5091 5572//5572 5092//5092 -f 5092//5092 5572//5572 5571//5571 -f 5092//5092 5571//5571 5093//5093 -f 5093//5093 5571//5571 5570//5570 -f 5093//5093 5570//5570 5081//5081 -f 5081//5081 5570//5570 5569//5569 -f 5081//5081 5569//5569 5082//5082 -f 5082//5082 5569//5569 5568//5568 -f 5082//5082 5568//5568 5083//5083 -f 5083//5083 5568//5568 5567//5567 -f 5083//5083 5567//5567 5084//5084 -f 5084//5084 5567//5567 5566//5566 -f 5084//5084 5566//5566 5086//5086 -f 5086//5086 5566//5566 5565//5565 -f 5086//5086 5565//5565 5087//5087 -f 5087//5087 5565//5565 5577//5577 -f 4763//4763 5209//5209 4764//4764 -f 4764//4764 5209//5209 5210//5210 -f 4764//4764 5210//5210 4766//4766 -f 4766//4766 5210//5210 5211//5211 -f 4766//4766 5211//5211 4767//4767 -f 4767//4767 5211//5211 5202//5202 -f 4767//4767 5202//5202 4768//4768 -f 4768//4768 5202//5202 5203//5203 -f 5208//5208 5209//5209 4777//4777 -f 4777//4777 5209//5209 4763//4763 -f 5219//5219 4872//4872 5216//5216 -f 5216//5216 4872//4872 4761//4761 -f 5216//5216 4761//4761 5214//5214 -f 5214//5214 4761//4761 4759//4759 -f 5214//5214 4759//4759 5212//5212 -f 5212//5212 4759//4759 4758//4758 -f 5212//5212 4758//4758 5205//5205 -f 5205//5205 4758//4758 4769//4769 -f 5205//5205 4769//4769 5203//5203 -f 5203//5203 4769//4769 4768//4768 -f 4737//4737 4738//4738 5254//5254 -f 5254//5254 4738//4738 5232//5232 -f 4742//4742 5238//5238 4741//4741 -f 4741//4741 5238//5238 5236//5236 -f 4741//4741 5236//5236 4740//4740 -f 4740//4740 5236//5236 5235//5235 -f 4740//4740 5235//5235 4739//4739 -f 4739//4739 5235//5235 5233//5233 -f 4739//4739 5233//5233 4738//4738 -f 4738//4738 5233//5233 5232//5232 -f 4752//4752 5229//5229 4750//4750 -f 4750//4750 5229//5229 5245//5245 -f 4750//4750 5245//5245 4748//4748 -f 4748//4748 5245//5245 5243//5243 -f 4748//4748 5243//5243 4746//4746 -f 4746//4746 5243//5243 5241//5241 -f 4746//4746 5241//5241 4744//4744 -f 4744//4744 5241//5241 5239//5239 -f 4744//4744 5239//5239 4742//4742 -f 4742//4742 5239//5239 5238//5238 -f 4990//4990 5646//5646 4986//4986 -f 4986//4986 5646//5646 5655//5655 -f 4986//4986 5655//5655 4987//4987 -f 4987//4987 5655//5655 5654//5654 -f 4987//4987 5654//5654 4981//4981 -f 4981//4981 5654//5654 5653//5653 -f 4981//4981 5653//5653 4980//4980 -f 4980//4980 5653//5653 5652//5652 -f 4980//4980 5652//5652 4979//4979 -f 4979//4979 5652//5652 5651//5651 -f 4979//4979 5651//5651 4976//4976 -f 4976//4976 5651//5651 5658//5658 -f 4976//4976 5658//5658 4977//4977 -f 4977//4977 5658//5658 5657//5657 -f 4977//4977 5657//5657 4982//4982 -f 4982//4982 5657//5657 5656//5656 -f 4982//4982 5656//5656 4983//4983 -f 4983//4983 5656//5656 5649//5649 -f 4983//4983 5649//5649 4988//4988 -f 4988//4988 5649//5649 5648//5648 -f 4988//4988 5648//5648 4989//4989 -f 4989//4989 5648//5648 5647//5647 -f 4989//4989 5647//5647 4990//4990 -f 4990//4990 5647//5647 5646//5646 -f 5004//5004 5666//5666 4991//4991 -f 4991//4991 5666//5666 5665//5665 -f 4991//4991 5665//5665 4992//4992 -f 4992//4992 5665//5665 5662//5662 -f 4992//4992 5662//5662 4994//4994 -f 4994//4994 5662//5662 5661//5661 -f 4994//4994 5661//5661 4995//4995 -f 4995//4995 5661//5661 5660//5660 -f 4995//4995 5660//5660 4996//4996 -f 4996//4996 5660//5660 5659//5659 -f 4996//4996 5659//5659 4997//4997 -f 4997//4997 5659//5659 5670//5670 -f 4997//4997 5670//5670 4998//4998 -f 4998//4998 5670//5670 5669//5669 -f 4998//4998 5669//5669 4999//4999 -f 4999//4999 5669//5669 5668//5668 -f 4999//4999 5668//5668 5000//5000 -f 5000//5000 5668//5668 5664//5664 -f 5000//5000 5664//5664 5001//5001 -f 5001//5001 5664//5664 5663//5663 -f 5001//5001 5663//5663 5003//5003 -f 5003//5003 5663//5663 5667//5667 -f 5003//5003 5667//5667 5004//5004 -f 5004//5004 5667//5667 5666//5666 -f 5011//5011 5681//5681 5012//5012 -f 5012//5012 5681//5681 5680//5680 -f 5012//5012 5680//5680 5013//5013 -f 5013//5013 5680//5680 5677//5677 -f 5013//5013 5677//5677 5009//5009 -f 5009//5009 5677//5677 5678//5678 -f 5009//5009 5678//5678 5010//5010 -f 5010//5010 5678//5678 5679//5679 -f 5010//5010 5679//5679 5014//5014 -f 5014//5014 5679//5679 5676//5676 -f 5014//5014 5676//5676 5015//5015 -f 5015//5015 5676//5676 5675//5675 -f 5015//5015 5675//5675 5016//5016 -f 5016//5016 5675//5675 5674//5674 -f 5016//5016 5674//5674 5007//5007 -f 5007//5007 5674//5674 5673//5673 -f 5007//5007 5673//5673 5005//5005 -f 5005//5005 5673//5673 5671//5671 -f 5005//5005 5671//5671 5006//5006 -f 5006//5006 5671//5671 5672//5672 -f 5006//5006 5672//5672 5008//5008 -f 5008//5008 5672//5672 5682//5682 -f 5008//5008 5682//5682 5011//5011 -f 5011//5011 5682//5682 5681//5681 -f 5066//5066 5631//5631 5067//5067 -f 5067//5067 5631//5631 5632//5632 -f 5067//5067 5632//5632 5060//5060 -f 5060//5060 5632//5632 5634//5634 -f 5060//5060 5634//5634 5061//5061 -f 5061//5061 5634//5634 5635//5635 -f 5061//5061 5635//5635 5062//5062 -f 5062//5062 5635//5635 5643//5643 -f 5062//5062 5643//5643 5063//5063 -f 5063//5063 5643//5643 5642//5642 -f 5063//5063 5642//5642 5064//5064 -f 5064//5064 5642//5642 5641//5641 -f 5064//5064 5641//5641 5058//5058 -f 5058//5058 5641//5641 5640//5640 -f 5058//5058 5640//5640 5059//5059 -f 5059//5059 5640//5640 5639//5639 -f 5059//5059 5639//5639 5056//5056 -f 5056//5056 5639//5639 5638//5638 -f 5056//5056 5638//5638 5057//5057 -f 5057//5057 5638//5638 5637//5637 -f 5057//5057 5637//5637 5065//5065 -f 5065//5065 5637//5637 5636//5636 -f 5065//5065 5636//5636 5066//5066 -f 5066//5066 5636//5636 5631//5631 -f 4957//4957 5735//5735 4960//4960 -f 4960//4960 5735//5735 5734//5734 -f 4960//4960 5734//5734 4959//4959 -f 4959//4959 5734//5734 5733//5733 -f 4959//4959 5733//5733 4958//4958 -f 4958//4958 5733//5733 5724//5724 -f 4958//4958 5724//5724 4961//4961 -f 4961//4961 5724//5724 5723//5723 -f 4961//4961 5723//5723 4962//4962 -f 4962//4962 5723//5723 5732//5732 -f 4962//4962 5732//5732 4963//4963 -f 4963//4963 5732//5732 5731//5731 -f 4963//4963 5731//5731 4954//4954 -f 4954//4954 5731//5731 5730//5730 -f 4954//4954 5730//5730 4955//4955 -f 4955//4955 5730//5730 5726//5726 -f 4955//4955 5726//5726 4952//4952 -f 4952//4952 5726//5726 5725//5725 -f 4952//4952 5725//5725 4953//4953 -f 4953//4953 5725//5725 5729//5729 -f 4953//4953 5729//5729 4956//4956 -f 4956//4956 5729//5729 5728//5728 -f 4956//4956 5728//5728 4957//4957 -f 4957//4957 5728//5728 5735//5735 -f 4950//4950 5717//5717 4951//4951 -f 4951//4951 5717//5717 5716//5716 -f 4951//4951 5716//5716 4942//4942 -f 4942//4942 5716//5716 5715//5715 -f 4942//4942 5715//5715 4943//4943 -f 4943//4943 5715//5715 5714//5714 -f 4943//4943 5714//5714 4944//4944 -f 4944//4944 5714//5714 5712//5712 -f 4944//4944 5712//5712 4945//4945 -f 4945//4945 5712//5712 5722//5722 -f 4945//4945 5722//5722 4946//4946 -f 4946//4946 5722//5722 5721//5721 -f 4946//4946 5721//5721 4947//4947 -f 4947//4947 5721//5721 5720//5720 -f 4947//4947 5720//5720 4948//4948 -f 4948//4948 5720//5720 5719//5719 -f 4948//4948 5719//5719 4939//4939 -f 4939//4939 5719//5719 5718//5718 -f 4939//4939 5718//5718 4940//4940 -f 4940//4940 5718//5718 5710//5710 -f 4940//4940 5710//5710 4949//4949 -f 4949//4949 5710//5710 5709//5709 -f 4949//4949 5709//5709 4950//4950 -f 4950//4950 5709//5709 5717//5717 -f 5048//5048 5630//5630 5049//5049 -f 5049//5049 5630//5630 5629//5629 -f 5049//5049 5629//5629 5050//5050 -f 5050//5050 5629//5629 5628//5628 -f 5050//5050 5628//5628 5051//5051 -f 5051//5051 5628//5628 5626//5626 -f 5051//5051 5626//5626 5052//5052 -f 5052//5052 5626//5626 5625//5625 -f 5052//5052 5625//5625 5053//5053 -f 5053//5053 5625//5625 5624//5624 -f 5053//5053 5624//5624 5054//5054 -f 5054//5054 5624//5624 5623//5623 -f 5054//5054 5623//5623 5055//5055 -f 5055//5055 5623//5623 5622//5622 -f 5055//5055 5622//5622 5046//5046 -f 5046//5046 5622//5622 5618//5618 -f 5046//5046 5618//5618 5043//5043 -f 5043//5043 5618//5618 5619//5619 -f 5043//5043 5619//5619 5044//5044 -f 5044//5044 5619//5619 5620//5620 -f 5044//5044 5620//5620 5047//5047 -f 5047//5047 5620//5620 5621//5621 -f 5047//5047 5621//5621 5048//5048 -f 5048//5048 5621//5621 5630//5630 -f 5035//5035 5617//5617 5036//5036 -f 5036//5036 5617//5617 5616//5616 -f 5036//5036 5616//5616 5037//5037 -f 5037//5037 5616//5616 5615//5615 -f 5037//5037 5615//5615 5038//5038 -f 5038//5038 5615//5615 5613//5613 -f 5038//5038 5613//5613 5039//5039 -f 5039//5039 5613//5613 5612//5612 -f 5039//5039 5612//5612 5040//5040 -f 5040//5040 5612//5612 5609//5609 -f 5040//5040 5609//5609 5041//5041 -f 5041//5041 5609//5609 5610//5610 -f 5041//5041 5610//5610 5042//5042 -f 5042//5042 5610//5610 5611//5611 -f 5042//5042 5611//5611 5033//5033 -f 5033//5033 5611//5611 5608//5608 -f 5033//5033 5608//5608 5030//5030 -f 5030//5030 5608//5608 5607//5607 -f 5030//5030 5607//5607 5031//5031 -f 5031//5031 5607//5607 5606//5606 -f 5031//5031 5606//5606 5034//5034 -f 5034//5034 5606//5606 5605//5605 -f 5034//5034 5605//5605 5035//5035 -f 5035//5035 5605//5605 5617//5617 -f 4932//4932 5705//5705 4933//4933 -f 4933//4933 5705//5705 5704//5704 -f 4933//4933 5704//5704 4934//4934 -f 4934//4934 5704//5704 5703//5703 -f 4934//4934 5703//5703 4935//4935 -f 4935//4935 5703//5703 5697//5697 -f 4935//4935 5697//5697 4936//4936 -f 4936//4936 5697//5697 5696//5696 -f 4936//4936 5696//5696 4937//4937 -f 4937//4937 5696//5696 5708//5708 -f 4937//4937 5708//5708 4938//4938 -f 4938//4938 5708//5708 5707//5707 -f 4938//4938 5707//5707 4926//4926 -f 4926//4926 5707//5707 5706//5706 -f 4926//4926 5706//5706 4927//4927 -f 4927//4927 5706//5706 5701//5701 -f 4927//4927 5701//5701 4928//4928 -f 4928//4928 5701//5701 5700//5700 -f 4928//4928 5700//5700 4929//4929 -f 4929//4929 5700//5700 5699//5699 -f 4929//4929 5699//5699 4931//4931 -f 4931//4931 5699//5699 5698//5698 -f 4931//4931 5698//5698 4932//4932 -f 4932//4932 5698//5698 5705//5705 -f 4867//4867 5775//5775 4868//4868 -f 4868//4868 5775//5775 5780//5780 -f 4868//4868 5780//5780 4869//4869 -f 4869//4869 5780//5780 5779//5779 -f 4869//4869 5779//5779 4870//4870 -f 4870//4870 5779//5779 5786//5786 -f 4870//4870 5786//5786 4871//4871 -f 4871//4871 5786//5786 5785//5785 -f 4871//4871 5785//5785 4507//4507 -f 4507//4507 5785//5785 5784//5784 -f 4507//4507 5784//5784 4508//4508 -f 4508//4508 5784//5784 5783//5783 -f 4508//4508 5783//5783 4864//4864 -f 4864//4864 5783//5783 5782//5782 -f 4864//4864 5782//5782 4865//4865 -f 4865//4865 5782//5782 5781//5781 -f 4865//4865 5781//5781 4862//4862 -f 4862//4862 5781//5781 5778//5778 -f 4862//4862 5778//5778 4863//4863 -f 4863//4863 5778//5778 5777//5777 -f 4863//4863 5777//5777 4866//4866 -f 4866//4866 5777//5777 5776//5776 -f 4866//4866 5776//5776 4867//4867 -f 4867//4867 5776//5776 5775//5775 -f 5169//5169 5181//5181 4513//4513 -f 4513//4513 5181//5181 4595//4595 -f 4796//4796 5461//5461 4798//4798 -f 4798//4798 5461//5461 5463//5463 -f 4798//4798 5463//5463 4843//4843 -f 4843//4843 5463//5463 5495//5495 -f 4791//4791 4805//4805 5314//5314 -f 5314//5314 4805//4805 5319//5319 -f 5134//5134 5513//5513 5139//5139 -f 5139//5139 5513//5513 5518//5518 -f 5139//5139 5518//5518 5140//5140 -f 5140//5140 5518//5518 5516//5516 -f 5140//5140 5516//5516 5135//5135 -f 5135//5135 5516//5516 5515//5515 -f 5135//5135 5515//5515 5136//5136 -f 5136//5136 5515//5515 5523//5523 -f 5136//5136 5523//5523 5137//5137 -f 5137//5137 5523//5523 5526//5526 -f 5137//5137 5526//5526 5138//5138 -f 5138//5138 5526//5526 5525//5525 -f 5138//5138 5525//5525 5129//5129 -f 5129//5129 5525//5525 5524//5524 -f 5129//5129 5524//5524 5130//5130 -f 5130//5130 5524//5524 5519//5519 -f 5130//5130 5519//5519 5131//5131 -f 5131//5131 5519//5519 5520//5520 -f 5131//5131 5520//5520 5132//5132 -f 5132//5132 5520//5520 5521//5521 -f 5132//5132 5521//5521 5133//5133 -f 5133//5133 5521//5521 5514//5514 -f 5133//5133 5514//5514 5134//5134 -f 5134//5134 5514//5514 5513//5513 -f 4733//4733 5252//5252 4734//4734 -f 4734//4734 5252//5252 5249//5249 -f 4734//4734 5249//5249 4723//4723 -f 4723//4723 5249//5249 5248//5248 -f 4723//4723 5248//5248 4720//4720 -f 4720//4720 5248//5248 5258//5258 -f 4720//4720 5258//5258 4721//4721 -f 4721//4721 5258//5258 5251//5251 -f 4721//4721 5251//5251 4729//4729 -f 4729//4729 5251//5251 5250//5250 -f 4729//4729 5250//5250 4728//4728 -f 4728//4728 5250//5250 5262//5262 -f 4728//4728 5262//5262 4727//4727 -f 4727//4727 5262//5262 5261//5261 -f 4727//4727 5261//5261 4725//4725 -f 4725//4725 5261//5261 5255//5255 -f 4725//4725 5255//5255 4730//4730 -f 4730//4730 5255//5255 5256//5256 -f 4730//4730 5256//5256 4731//4731 -f 4731//4731 5256//5256 5257//5257 -f 4731//4731 5257//5257 4732//4732 -f 4732//4732 5257//5257 5253//5253 -f 4732//4732 5253//5253 4733//4733 -f 4733//4733 5253//5253 5252//5252 -f 4692//4692 4693//4693 5303//5303 -f 5303//5303 4693//4693 5291//5291 -f 4716//4716 5285//5285 4707//4707 -f 4707//4707 5285//5285 5283//5283 -f 4707//4707 5283//5283 4709//4709 -f 4709//4709 5283//5283 5482//5482 -f 5279//5279 4713//4713 5267//5267 -f 5267//5267 4713//4713 4584//4584 -f 5267//5267 4584//4584 5277//5277 -f 5277//5277 4584//4584 4586//4586 -f 4772//4772 5189//5189 4773//4773 -f 4773//4773 5189//5189 5188//5188 -f 4773//4773 5188//5188 4782//4782 -f 4782//4782 5188//5188 5187//5187 -f 4782//4782 5187//5187 4783//4783 -f 4783//4783 5187//5187 5201//5201 -f 4783//4783 5201//5201 4784//4784 -f 4784//4784 5201//5201 5200//5200 -f 4784//4784 5200//5200 4780//4780 -f 4780//4780 5200//5200 5195//5195 -f 4780//4780 5195//5195 4781//4781 -f 4781//4781 5195//5195 5196//5196 -f 4781//4781 5196//5196 4779//4779 -f 4779//4779 5196//5196 5197//5197 -f 4779//4779 5197//5197 4778//4778 -f 4778//4778 5197//5197 5194//5194 -f 4778//4778 5194//5194 4776//4776 -f 4776//4776 5194//5194 5193//5193 -f 4776//4776 5193//5193 4775//4775 -f 4775//4775 5193//5193 5192//5192 -f 4775//4775 5192//5192 4774//4774 -f 4774//4774 5192//5192 5191//5191 -f 4774//4774 5191//5191 4772//4772 -f 4772//4772 5191//5191 5189//5189 -f 5461//5461 4796//4796 5459//5459 -f 5459//5459 4796//4796 4793//4793 -f 5459//5459 4793//4793 5453//5453 -f 5453//5453 4793//4793 4792//4792 -f 5453//5453 4792//4792 5314//5314 -f 5314//5314 4792//4792 4791//4791 -f 5169//5169 4513//4513 5170//5170 -f 5170//5170 4513//4513 4512//4512 -f 5170//5170 4512//4512 5495//5495 -f 5495//5495 4512//4512 4843//4843 -f 4408//4408 4407//4407 5318//5318 -f 4408//4408 5318//5318 4807//4807 -f 4807//4807 5318//5318 5319//5319 -f 4807//4807 5319//5319 4805//4805 -f 4595//4595 5181//5181 5183//5183 -f 4595//4595 5183//5183 4594//4594 -f 4594//4594 5183//5183 4422//4422 -f 4594//4594 4422//4422 4421//4421 -f 4429//4429 4430//4430 5198//5198 -f 4429//4429 5198//5198 4786//4786 -f 4786//4786 5198//5198 5199//5199 -f 4786//4786 5199//5199 4785//4785 -f 4785//4785 5199//5199 4442//4442 -f 4785//4785 4442//4442 4441//4441 -f 5208//5208 4777//4777 4771//4771 -f 5208//5208 4771//4771 5206//5206 -f 5206//5206 4771//4771 4770//4770 -f 5206//5206 4770//4770 5207//5207 -f 5207//5207 4770//4770 4445//4445 -f 5207//5207 4445//4445 4446//4446 -f 4872//4872 5219//5219 5221//5221 -f 4872//4872 5221//5221 4875//4875 -f 4875//4875 5221//5221 5220//5220 -f 4875//4875 5220//5220 4876//4876 -f 4876//4876 5220//5220 4448//4448 -f 4876//4876 4448//4448 4447//4447 -f 4459//4459 4460//4460 5224//5224 -f 4459//4459 5224//5224 4879//4879 -f 4879//4879 5224//5224 5222//5222 -f 4879//4879 5222//5222 4878//4878 -f 4878//4878 5222//5222 4461//4461 -f 4878//4878 4461//4461 4463//4463 -f 4477//4477 4478//4478 5227//5227 -f 4477//4477 5227//5227 4517//4517 -f 4517//4517 5227//5227 5226//5226 -f 4517//4517 5226//5226 5141//5141 -f 5141//5141 5226//5226 4480//4480 -f 5141//5141 4480//4480 4479//4479 -f 5229//5229 4752//4752 5142//5142 -f 5229//5229 5142//5142 5230//5230 -f 5230//5230 5142//5142 5143//5143 -f 5230//5230 5143//5143 5231//5231 -f 5231//5231 5143//5143 4493//4493 -f 5231//5231 4493//4493 4494//4494 -f 4737//4737 5254//5254 5247//5247 -f 4737//4737 5247//5247 4735//4735 -f 4735//4735 5247//5247 5246//5246 -f 4735//4735 5246//5246 4736//4736 -f 4736//4736 5246//5246 4496//4496 -f 4736//4736 4496//4496 4495//4495 -f 4499//4499 4500//4500 5259//5259 -f 4499//4499 5259//5259 4724//4724 -f 4724//4724 5259//5259 5260//5260 -f 4724//4724 5260//5260 4726//4726 -f 4726//4726 5260//5260 4432//4432 -f 4726//4726 4432//4432 4431//4431 -f 4439//4439 4440//4440 5276//5276 -f 4439//4439 5276//5276 4590//4590 -f 4590//4590 5276//5276 5277//5277 -f 4590//4590 5277//5277 4586//4586 -f 5285//5285 4716//4716 5506//5506 -f 5506//5506 4716//4716 4714//4714 -f 5506//5506 4714//4714 5279//5279 -f 5279//5279 4714//4714 4713//4713 -f 4692//4692 5303//5303 5305//5305 -f 4692//4692 5305//5305 4703//4703 -f 4703//4703 5305//5305 4419//4419 -f 4703//4703 4419//4419 4420//4420 -f 5291//5291 4693//4693 5290//5290 -f 5290//5290 4693//4693 4833//4833 -f 5290//5290 4833//4833 5288//5288 -f 5288//5288 4833//4833 4711//4711 -f 5288//5288 4711//4711 5482//5482 -f 5482//5482 4711//4711 4709//4709 -f 4794//4794 5460//5460 4790//4790 -f 4790//4790 5460//5460 5452//5452 -f 4790//4790 5452//5452 4788//4788 -f 4788//4788 5452//5452 5451//5451 -f 4788//4788 5451//5451 4818//4818 -f 4818//4818 5451//5451 5450//5450 -f 4818//4818 5450//5450 4815//4815 -f 4815//4815 5450//5450 5449//5449 -f 4815//4815 5449//5449 4816//4816 -f 4816//4816 5449//5449 5458//5458 -f 4816//4816 5458//5458 4819//4819 -f 4819//4819 5458//5458 5457//5457 -f 4795//4795 5462//5462 4794//4794 -f 4794//4794 5462//5462 5460//5460 -f 4820//4820 5455//5455 4822//4822 -f 4822//4822 5455//5455 5454//5454 -f 4822//4822 5454//5454 4823//4823 -f 4823//4823 5454//5454 5471//5471 -f 4823//4823 5471//5471 4825//4825 -f 4825//4825 5471//5471 5469//5469 -f 4825//4825 5469//5469 4799//4799 -f 4799//4799 5469//5469 5466//5466 -f 4799//4799 5466//5466 4797//4797 -f 4797//4797 5466//5466 5464//5464 -f 4797//4797 5464//5464 4795//4795 -f 4795//4795 5464//5464 5462//5462 -f 4819//4819 5457//5457 4820//4820 -f 4820//4820 5457//5457 5455//5455 -f 4708//4708 5483//5483 4706//4706 -f 4706//4706 5483//5483 5481//5481 -f 4706//4706 5481//5481 4704//4704 -f 4704//4704 5481//5481 5480//5480 -f 4704//4704 5480//5480 4827//4827 -f 4827//4827 5480//5480 5479//5479 -f 4827//4827 5479//5479 4828//4828 -f 4828//4828 5479//5479 5478//5478 -f 4828//4828 5478//5478 4836//4836 -f 4836//4836 5478//5478 5476//5476 -f 4836//4836 5476//5476 4837//4837 -f 4837//4837 5476//5476 5475//5475 -f 4710//4710 5484//5484 4708//4708 -f 4708//4708 5484//5484 5483//5483 -f 4838//4838 5488//5488 4830//4830 -f 4830//4830 5488//5488 5487//5487 -f 4830//4830 5487//5487 4831//4831 -f 4831//4831 5487//5487 5485//5485 -f 4831//4831 5485//5485 4835//4835 -f 4835//4835 5485//5485 5474//5474 -f 4835//4835 5474//5474 4834//4834 -f 4834//4834 5474//5474 5473//5473 -f 4834//4834 5473//5473 4712//4712 -f 4712//4712 5473//5473 5289//5289 -f 4712//4712 5289//5289 4710//4710 -f 4710//4710 5289//5289 5484//5484 -f 4837//4837 5475//5475 4838//4838 -f 4838//4838 5475//5475 5488//5488 -f 4848//4848 5499//5499 4849//4849 -f 4849//4849 5499//5499 5490//5490 -f 4849//4849 5490//5490 4839//4839 -f 4839//4839 5490//5490 5489//5489 -f 4839//4839 5489//5489 4840//4840 -f 4840//4840 5489//5489 5491//5491 -f 4840//4840 5491//5491 4841//4841 -f 4841//4841 5491//5491 5498//5498 -f 4841//4841 5498//5498 4842//4842 -f 4842//4842 5498//5498 5497//5497 -f 4842//4842 5497//5497 4844//4844 -f 4844//4844 5497//5497 5496//5496 -f 4847//4847 5500//5500 4848//4848 -f 4848//4848 5500//5500 5499//5499 -f 4845//4845 5494//5494 4787//4787 -f 4787//4787 5494//5494 5493//5493 -f 4787//4787 5493//5493 4511//4511 -f 4511//4511 5493//5493 5492//5492 -f 4511//4511 5492//5492 4509//4509 -f 4509//4509 5492//5492 5467//5467 -f 4509//4509 5467//5467 4826//4826 -f 4826//4826 5467//5467 5468//5468 -f 4826//4826 5468//5468 4824//4824 -f 4824//4824 5468//5468 5470//5470 -f 4824//4824 5470//5470 4846//4846 -f 4846//4846 5470//5470 5501//5501 -f 4846//4846 5501//5501 4847//4847 -f 4847//4847 5501//5501 5500//5500 -f 4844//4844 5496//5496 4845//4845 -f 4845//4845 5496//5496 5494//5494 -f 4717//4717 5286//5286 4715//4715 -f 4715//4715 5286//5286 5287//5287 -f 4715//4715 5287//5287 4719//4719 -f 4719//4719 5287//5287 5507//5507 -f 4719//4719 5507//5507 4850//4850 -f 4850//4850 5507//5507 5508//5508 -f 4850//4850 5508//5508 4851//4851 -f 4851//4851 5508//5508 5509//5509 -f 4851//4851 5509//5509 4859//4859 -f 4859//4859 5509//5509 5504//5504 -f 4859//4859 5504//5504 4860//4860 -f 4860//4860 5504//5504 5503//5503 -f 4858//4858 5284//5284 4717//4717 -f 4717//4717 5284//5284 5286//5286 -f 4861//4861 5512//5512 4853//4853 -f 4853//4853 5512//5512 5511//5511 -f 4853//4853 5511//5511 4854//4854 -f 4854//4854 5511//5511 5510//5510 -f 4854//4854 5510//5510 4855//4855 -f 4855//4855 5510//5510 5502//5502 -f 4855//4855 5502//5502 4856//4856 -f 4856//4856 5502//5502 5280//5280 -f 4856//4856 5280//5280 4857//4857 -f 4857//4857 5280//5280 5282//5282 -f 4857//4857 5282//5282 4858//4858 -f 4858//4858 5282//5282 5284//5284 -f 4860//4860 5503//5503 4861//4861 -f 4861//4861 5503//5503 5512//5512 -f 5787//5787 5788//5788 5789//5789 -f 5789//5789 5788//5788 5790//5790 -f 5789//5789 5790//5790 5791//5791 -f 5791//5791 5790//5790 5792//5792 -f 5791//5791 5792//5792 5793//5793 -f 5793//5793 5792//5792 5794//5794 -f 5793//5793 5794//5794 5795//5795 -f 5795//5795 5794//5794 5796//5796 -f 5797//5797 5798//5798 5799//5799 -f 5799//5799 5798//5798 5800//5800 -f 5799//5799 5800//5800 5801//5801 -f 5801//5801 5800//5800 5802//5802 -f 5803//5803 5804//5804 5805//5805 -f 5805//5805 5804//5804 5806//5806 -f 5805//5805 5806//5806 5807//5807 -f 5807//5807 5806//5806 5808//5808 -f 5809//5809 5810//5810 5811//5811 -f 5811//5811 5810//5810 5812//5812 -f 5811//5811 5812//5812 5813//5813 -f 5813//5813 5812//5812 5814//5814 -f 5813//5813 5814//5814 5815//5815 -f 5815//5815 5814//5814 5816//5816 -f 5815//5815 5816//5816 5817//5817 -f 5817//5817 5816//5816 5818//5818 -f 5817//5817 5818//5818 5819//5819 -f 5819//5819 5818//5818 5820//5820 -f 5821//5821 5822//5822 5823//5823 -f 5823//5823 5822//5822 5824//5824 -f 5823//5823 5824//5824 5825//5825 -f 5825//5825 5824//5824 5826//5826 -f 5827//5827 5828//5828 5829//5829 -f 5829//5829 5828//5828 5830//5830 -f 5829//5829 5830//5830 5831//5831 -f 5831//5831 5830//5830 5832//5832 -f 5833//5833 5834//5834 5835//5835 -f 5835//5835 5834//5834 5836//5836 -f 5837//5837 5838//5838 5839//5839 -f 5839//5839 5838//5838 5840//5840 -f 5841//5841 5842//5842 5843//5843 -f 5843//5843 5842//5842 5844//5844 -f 5843//5843 5844//5844 5845//5845 -f 5845//5845 5844//5844 5846//5846 -f 5847//5847 5848//5848 5849//5849 -f 5849//5849 5848//5848 5850//5850 -f 5849//5849 5850//5850 5851//5851 -f 5851//5851 5850//5850 5852//5852 -f 5853//5853 5854//5854 5855//5855 -f 5855//5855 5854//5854 5856//5856 -f 5855//5855 5856//5856 5857//5857 -f 5857//5857 5856//5856 5858//5858 -f 5857//5857 5858//5858 5859//5859 -f 5859//5859 5858//5858 5860//5860 -f 5859//5859 5860//5860 5861//5861 -f 5861//5861 5860//5860 5862//5862 -f 5861//5861 5862//5862 5863//5863 -f 5863//5863 5862//5862 5864//5864 -f 5865//5865 5866//5866 5867//5867 -f 5867//5867 5866//5866 5868//5868 -f 5867//5867 5868//5868 5869//5869 -f 5869//5869 5868//5868 5870//5870 -f 5869//5869 5870//5870 5871//5871 -f 5871//5871 5870//5870 5872//5872 -f 5871//5871 5872//5872 5873//5873 -f 5873//5873 5872//5872 5874//5874 -f 5875//5875 5876//5876 5877//5877 -f 5877//5877 5878//5878 5855//5855 -f 5879//5879 5880//5880 5881//5881 -f 5882//5882 5883//5883 5884//5884 -f 5797//5797 5799//5799 5885//5885 -f 5855//5855 5878//5878 5853//5853 -f 5788//5788 5886//5886 5887//5887 -f 5834//5834 5888//5888 5889//5889 -f 5890//5890 5891//5891 5892//5892 -f 5893//5893 5894//5894 5895//5895 -f 5895//5895 5894//5894 5863//5863 -f 5863//5863 5894//5894 5896//5896 -f 5863//5863 5896//5896 5861//5861 -f 5897//5897 5898//5898 5899//5899 -f 5899//5899 5898//5898 5900//5900 -f 5899//5899 5900//5900 5901//5901 -f 5901//5901 5900//5900 5902//5902 -f 5902//5902 5903//5903 5901//5901 -f 5901//5901 5903//5903 5904//5904 -f 5901//5901 5904//5904 5905//5905 -f 5905//5905 5904//5904 5906//5906 -f 5905//5905 5906//5906 5893//5893 -f 5907//5907 5908//5908 5909//5909 -f 5910//5910 5817//5817 5911//5911 -f 5911//5911 5817//5817 5819//5819 -f 5911//5911 5819//5819 5912//5912 -f 5819//5819 5913//5913 5912//5912 -f 5912//5912 5913//5913 5914//5914 -f 5912//5912 5914//5914 5915//5915 -f 5915//5915 5914//5914 5821//5821 -f 5915//5915 5821//5821 5916//5916 -f 5916//5916 5821//5821 5823//5823 -f 5916//5916 5823//5823 5917//5917 -f 5918//5918 5919//5919 5830//5830 -f 5830//5830 5919//5919 5832//5832 -f 5917//5917 5823//5823 5920//5920 -f 5920//5920 5823//5823 5825//5825 -f 5920//5920 5825//5825 5921//5921 -f 5919//5919 5922//5922 5832//5832 -f 5832//5832 5922//5922 5920//5920 -f 5832//5832 5920//5920 5923//5923 -f 5923//5923 5920//5920 5921//5921 -f 5808//5808 5806//5806 5924//5924 -f 5924//5924 5806//5806 5804//5804 -f 5924//5924 5804//5804 5881//5881 -f 5888//5888 5834//5834 5925//5925 -f 5925//5925 5834//5834 5833//5833 -f 5925//5925 5833//5833 5926//5926 -f 5908//5908 5918//5918 5909//5909 -f 5909//5909 5918//5918 5830//5830 -f 5909//5909 5830//5830 5927//5927 -f 5927//5927 5830//5830 5828//5828 -f 5928//5928 5929//5929 5930//5930 -f 5930//5930 5929//5929 5931//5931 -f 5932//5932 5933//5933 5930//5930 -f 5930//5930 5933//5933 5934//5934 -f 5930//5930 5934//5934 5928//5928 -f 5931//5931 5935//5935 5936//5936 -f 5936//5936 5935//5935 5937//5937 -f 5938//5938 5939//5939 5811//5811 -f 5811//5811 5939//5939 5940//5940 -f 5811//5811 5940//5940 5809//5809 -f 5809//5809 5940//5940 5941//5941 -f 5809//5809 5941//5941 5932//5932 -f 5932//5932 5941//5941 5942//5942 -f 5932//5932 5942//5942 5933//5933 -f 5943//5943 5944//5944 5945//5945 -f 5946//5946 5943//5943 5947//5947 -f 5947//5947 5943//5943 5945//5945 -f 5947//5947 5945//5945 5865//5865 -f 5865//5865 5945//5945 5948//5948 -f 5949//5949 5950//5950 5947//5947 -f 5947//5947 5950//5950 5951//5951 -f 5947//5947 5951//5951 5946//5946 -f 5952//5952 5953//5953 5954//5954 -f 5954//5954 5953//5953 5945//5945 -f 5954//5954 5945//5945 5955//5955 -f 5955//5955 5945//5945 5944//5944 -f 5956//5956 5957//5957 5958//5958 -f 5958//5958 5957//5957 5959//5959 -f 5958//5958 5959//5959 5949//5949 -f 5949//5949 5959//5959 5960//5960 -f 5949//5949 5960//5960 5950//5950 -f 5952//5952 5956//5956 5953//5953 -f 5953//5953 5956//5956 5958//5958 -f 5953//5953 5958//5958 5961//5961 -f 5961//5961 5958//5958 5962//5962 -f 5962//5962 5958//5958 5963//5963 -f 5963//5963 5958//5958 5964//5964 -f 5963//5963 5964//5964 5965//5965 -f 5966//5966 5967//5967 5968//5968 -f 5968//5968 5967//5967 5969//5969 -f 5968//5968 5969//5969 5965//5965 -f 5970//5970 5971//5971 5972//5972 -f 5971//5971 5973//5973 5972//5972 -f 5972//5972 5973//5973 5974//5974 -f 5972//5972 5974//5974 5975//5975 -f 5975//5975 5974//5974 5976//5976 -f 5975//5975 5976//5976 5977//5977 -f 5966//5966 5978//5978 5979//5979 -f 5979//5979 5980//5980 5966//5966 -f 5966//5966 5980//5980 5981//5981 -f 5966//5966 5981//5981 5967//5967 -f 5979//5979 5982//5982 5980//5980 -f 5980//5980 5982//5982 5983//5983 -f 5980//5980 5983//5983 5887//5887 -f 5887//5887 5983//5983 5984//5984 -f 5887//5887 5984//5984 5985//5985 -f 5788//5788 5887//5887 5790//5790 -f 5893//5893 5895//5895 5905//5905 -f 5905//5905 5895//5895 5986//5986 -f 5905//5905 5986//5986 5796//5796 -f 5851//5851 5987//5987 5988//5988 -f 5989//5989 5990//5990 5878//5878 -f 5990//5990 5991//5991 5878//5878 -f 5878//5878 5991//5991 5992//5992 -f 5878//5878 5992//5992 5993//5993 -f 5988//5988 5853//5853 5851//5851 -f 5851//5851 5853//5853 5878//5878 -f 5851//5851 5878//5878 5849//5849 -f 5849//5849 5878//5878 5993//5993 -f 5849//5849 5993//5993 5994//5994 -f 5995//5995 5843//5843 5996//5996 -f 5996//5996 5843//5843 5845//5845 -f 5996//5996 5845//5845 5997//5997 -f 5997//5997 5845//5845 5998//5998 -f 5997//5997 5998//5998 5999//5999 -f 5994//5994 6000//6000 5849//5849 -f 5849//5849 6000//6000 6001//6001 -f 5849//5849 6001//6001 5847//5847 -f 5847//5847 6001//6001 5999//5999 -f 5847//5847 5999//5999 6002//6002 -f 6002//6002 5999//5999 5998//5998 -f 5995//5995 5989//5989 5843//5843 -f 5843//5843 5989//5989 5878//5878 -f 5843//5843 5878//5878 5841//5841 -f 5841//5841 5878//5878 5877//5877 -f 5841//5841 5877//5877 6003//6003 -f 6003//6003 5877//5877 5876//5876 -f 5799//5799 5801//5801 5885//5885 -f 5885//5885 5801//5801 5875//5875 -f 5885//5885 5875//5875 5975//5975 -f 5801//5801 6004//6004 5875//5875 -f 5875//5875 6004//6004 5838//5838 -f 5875//5875 5838//5838 5876//5876 -f 5876//5876 5838//5838 5837//5837 -f 5876//5876 5837//5837 6003//6003 -f 6005//6005 6006//6006 6007//6007 -f 6007//6007 6006//6006 6008//6008 -f 6007//6007 6008//6008 6009//6009 -f 6005//6005 6010//6010 6006//6006 -f 6006//6006 6010//6010 6011//6011 -f 6006//6006 6011//6011 6012//6012 -f 6013//6013 6014//6014 6015//6015 -f 6015//6015 6014//6014 6016//6016 -f 6015//6015 6016//6016 5881//5881 -f 5881//5881 6016//6016 6017//6017 -f 5881//5881 6017//6017 5879//5879 -f 6018//6018 6019//6019 6020//6020 -f 6020//6020 6019//6019 5880//5880 -f 5804//5804 6021//6021 5881//5881 -f 5881//5881 6021//6021 6022//6022 -f 5881//5881 6022//6022 6015//6015 -f 6015//6015 6022//6022 6023//6023 -f 6015//6015 6023//6023 6013//6013 -f 6013//6013 6023//6023 6024//6024 -f 6013//6013 6024//6024 6025//6025 -f 6025//6025 6024//6024 6026//6026 -f 6025//6025 6026//6026 6027//6027 -f 6027//6027 6026//6026 6012//6012 -f 6027//6027 6012//6012 6028//6028 -f 6028//6028 6012//6012 6011//6011 -f 6028//6028 6011//6011 6029//6029 -f 6029//6029 6011//6011 6018//6018 -f 6030//6030 6031//6031 6032//6032 -f 6032//6032 6031//6031 6010//6010 -f 6032//6032 6010//6010 6033//6033 -f 6033//6033 6010//6010 6005//6005 -f 6031//6031 6034//6034 6010//6010 -f 6010//6010 6034//6034 6035//6035 -f 6010//6010 6035//6035 6036//6036 -f 6036//6036 6035//6035 6037//6037 -f 6036//6036 6037//6037 6038//6038 -f 6038//6038 6039//6039 6036//6036 -f 6036//6036 6039//6039 6040//6040 -f 6036//6036 6040//6040 6041//6041 -f 6041//6041 6040//6040 6042//6042 -f 6041//6041 6042//6042 6043//6043 -f 6043//6043 6042//6042 6044//6044 -f 6043//6043 6044//6044 6045//6045 -f 6045//6045 6044//6044 6046//6046 -f 6045//6045 6046//6046 6032//6032 -f 6032//6032 6046//6046 6047//6047 -f 6032//6032 6047//6047 6030//6030 -f 6048//6048 5883//5883 6049//6049 -f 6049//6049 5883//5883 5882//5882 -f 6049//6049 5882//5882 6050//6050 -f 6008//6008 6051//6051 6009//6009 -f 6009//6009 6051//6051 5884//5884 -f 6009//6009 5884//5884 6052//6052 -f 6052//6052 5884//5884 5883//5883 -f 6052//6052 5883//5883 6053//6053 -f 6053//6053 5883//5883 6048//6048 -f 6054//6054 6055//6055 6036//6036 -f 6018//6018 6011//6011 6019//6019 -f 6019//6019 6011//6011 6056//6056 -f 6019//6019 6056//6056 6057//6057 -f 6057//6057 6058//6058 6019//6019 -f 6019//6019 6058//6058 6059//6059 -f 6019//6019 6059//6059 6054//6054 -f 6055//6055 6060//6060 6036//6036 -f 6036//6036 6060//6060 6061//6061 -f 6036//6036 6061//6061 6010//6010 -f 6010//6010 6061//6061 6062//6062 -f 6062//6062 6063//6063 6010//6010 -f 6010//6010 6063//6063 6064//6064 -f 6010//6010 6064//6064 6011//6011 -f 6011//6011 6064//6064 6065//6065 -f 6011//6011 6065//6065 6056//6056 -f 5910//5910 5907//5907 5817//5817 -f 5817//5817 5907//5907 5909//5909 -f 5817//5817 5909//5909 5815//5815 -f 5815//5815 5909//5909 5927//5927 -f 5815//5815 5927//5927 5813//5813 -f 5813//5813 5927//5927 6066//6066 -f 5813//5813 6066//6066 5811//5811 -f 5811//5811 6066//6066 5936//5936 -f 5811//5811 5936//5936 5938//5938 -f 5938//5938 5936//5936 5937//5937 -f 5828//5828 5889//5889 5927//5927 -f 5927//5927 5889//5889 5888//5888 -f 5927//5927 5888//5888 6066//6066 -f 6066//6066 5888//5888 5925//5925 -f 6066//6066 5925//5925 5936//5936 -f 5936//5936 5925//5925 6067//6067 -f 6054//6054 6036//6036 6019//6019 -f 6019//6019 6036//6036 5964//5964 -f 6019//6019 5964//5964 5880//5880 -f 5880//5880 5964//5964 5958//5958 -f 5880//5880 5958//5958 5881//5881 -f 5881//5881 5958//5958 5949//5949 -f 5881//5881 5949//5949 5924//5924 -f 5965//5965 5964//5964 5968//5968 -f 5968//5968 5964//5964 6036//6036 -f 5968//5968 6036//6036 5966//5966 -f 5966//5966 6036//6036 6041//6041 -f 5966//5966 6041//6041 6049//6049 -f 6049//6049 6041//6041 6068//6068 -f 6049//6049 6068//6068 6048//6048 -f 6050//6050 5797//5797 6049//6049 -f 6049//6049 5797//5797 5885//5885 -f 6049//6049 5885//5885 5966//5966 -f 5966//5966 5885//5885 5975//5975 -f 5966//5966 5975//5975 5978//5978 -f 5978//5978 5975//5975 5977//5977 -f 5891//5891 5897//5897 5892//5892 -f 5892//5892 5897//5897 5899//5899 -f 5892//5892 5899//5899 6069//6069 -f 5896//5896 5890//5890 5861//5861 -f 5861//5861 5890//5890 5892//5892 -f 5861//5861 5892//5892 5859//5859 -f 5859//5859 5892//5892 6069//6069 -f 5859//5859 6069//6069 5857//5857 -f 6070//6070 6071//6071 5947//5947 -f 6072//6072 6073//6073 6074//6074 -f 5947//5947 6071//6071 5949//5949 -f 5949//5949 6071//6071 6075//6075 -f 5949//5949 6075//6075 6076//6076 -f 6077//6077 6078//6078 6067//6067 -f 6067//6067 6078//6078 6079//6079 -f 6074//6074 6080//6080 6072//6072 -f 6072//6072 6080//6080 6081//6081 -f 6072//6072 6081//6081 5947//5947 -f 5947//5947 6081//6081 6082//6082 -f 5947//5947 6082//6082 6070//6070 -f 5926//5926 5808//5808 5925//5925 -f 5925//5925 5808//5808 5924//5924 -f 5925//5925 5924//5924 6067//6067 -f 6067//6067 5924//5924 5949//5949 -f 6067//6067 5949//5949 6077//6077 -f 6077//6077 5949//5949 6076//6076 -f 5931//5931 5936//5936 5930//5930 -f 5930//5930 5936//5936 6067//6067 -f 5930//5930 6067//6067 6072//6072 -f 6072//6072 6067//6067 6079//6079 -f 6072//6072 6079//6079 6073//6073 -f 6083//6083 6084//6084 5899//5899 -f 5972//5972 6085//6085 6086//6086 -f 6085//6085 5972//5972 6087//6087 -f 6087//6087 5972//5972 5975//5975 -f 6087//6087 5975//5975 6088//6088 -f 5855//5855 5857//5857 5877//5877 -f 5877//5877 5857//5857 6069//6069 -f 5877//5877 6069//6069 5875//5875 -f 5875//5875 6069//6069 5899//5899 -f 5875//5875 5899//5899 5975//5975 -f 5975//5975 5899//5899 6084//6084 -f 5975//5975 6084//6084 6088//6088 -f 6086//6086 6089//6089 5972//5972 -f 5972//5972 6089//6089 6090//6090 -f 5972//5972 6090//6090 5901//5901 -f 5901//5901 6090//6090 6091//6091 -f 6091//6091 6092//6092 5901//5901 -f 5901//5901 6092//6092 6093//6093 -f 5901//5901 6093//6093 5899//5899 -f 5899//5899 6093//6093 6094//6094 -f 5899//5899 6094//6094 6083//6083 -f 5865//5865 5867//5867 5947//5947 -f 5947//5947 5867//5867 5869//5869 -f 5947//5947 5869//5869 6072//6072 -f 6072//6072 5869//5869 5871//5871 -f 6072//6072 5871//5871 5930//5930 -f 5930//5930 5871//5871 5873//5873 -f 5930//5930 5873//5873 5932//5932 -f 5932//5932 5873//5873 6095//6095 -f 5796//5796 5794//5794 5905//5905 -f 5905//5905 5794//5794 5792//5792 -f 5905//5905 5792//5792 5901//5901 -f 5901//5901 5792//5792 5790//5790 -f 5901//5901 5790//5790 5972//5972 -f 5972//5972 5790//5790 5887//5887 -f 5972//5972 5887//5887 5970//5970 -f 5970//5970 5887//5887 5985//5985 -f 6096//6096 6097//6097 6098//6098 -f 6099//6099 6100//6100 6101//6101 -f 6102//6102 6103//6103 6104//6104 -f 6104//6104 6103//6103 6105//6105 -f 6105//6105 6106//6106 5818//5818 -f 5818//5818 6106//6106 6107//6107 -f 5818//5818 6107//6107 5820//5820 -f 5820//5820 6107//6107 6108//6108 -f 5820//5820 6108//6108 6109//6109 -f 6109//6109 6108//6108 6110//6110 -f 6109//6109 6110//6110 6111//6111 -f 6111//6111 6110//6110 6112//6112 -f 6111//6111 6112//6112 5822//5822 -f 5822//5822 6112//6112 5824//5824 -f 6113//6113 6114//6114 5831//5831 -f 5831//5831 6114//6114 5829//5829 -f 6115//6115 6116//6116 5826//5826 -f 5831//5831 6115//6115 6113//6113 -f 6113//6113 6115//6115 5826//5826 -f 6113//6113 5826//5826 6117//6117 -f 6117//6117 5826//5826 5824//5824 -f 6117//6117 5824//5824 6118//6118 -f 6118//6118 5824//5824 6112//6112 -f 6119//6119 6120//6120 6121//6121 -f 6121//6121 6120//6120 5864//5864 -f 6121//6121 5864//5864 6122//6122 -f 6122//6122 5864//5864 5862//5862 -f 6123//6123 6124//6124 6125//6125 -f 6125//6125 6124//6124 6126//6126 -f 6127//6127 6128//6128 6123//6123 -f 6119//6119 6129//6129 6130//6130 -f 6130//6130 6129//6129 6131//6131 -f 6130//6130 6131//6131 6127//6127 -f 6127//6127 6131//6131 6132//6132 -f 6127//6127 6132//6132 6128//6128 -f 5798//5798 6133//6133 6134//6134 -f 5840//5840 6135//6135 5839//5839 -f 5839//5839 6135//6135 6136//6136 -f 5839//5839 6136//6136 6137//6137 -f 5840//5840 6138//6138 6135//6135 -f 6135//6135 6138//6138 5802//5802 -f 6135//6135 5802//5802 6134//6134 -f 6134//6134 5802//5802 5800//5800 -f 6134//6134 5800//5800 5798//5798 -f 6139//6139 6140//6140 6141//6141 -f 6141//6141 6140//6140 6142//6142 -f 6142//6142 6143//6143 6141//6141 -f 6141//6141 6143//6143 5844//5844 -f 6141//6141 5844//5844 6144//6144 -f 6144//6144 5844//5844 5842//5842 -f 6144//6144 5842//5842 6137//6137 -f 6143//6143 6145//6145 5844//5844 -f 5844//5844 6145//6145 6146//6146 -f 5844//5844 6146//6146 5846//5846 -f 6146//6146 6147//6147 5846//5846 -f 5846//5846 6147//6147 6148//6148 -f 5846//5846 6148//6148 6149//6149 -f 6149//6149 6148//6148 6150//6150 -f 6149//6149 6150//6150 6151//6151 -f 6152//6152 6153//6153 5850//5850 -f 5850//5850 6153//6153 6154//6154 -f 6152//6152 5850//5850 6150//6150 -f 6150//6150 5850//5850 5848//5848 -f 6150//6150 5848//5848 6151//6151 -f 5856//5856 5854//5854 5850//5850 -f 6155//6155 6156//6156 5854//5854 -f 5854//5854 6156//6156 5852//5852 -f 5854//5854 5852//5852 5850//5850 -f 6130//6130 5793//5793 5795//5795 -f 6119//6119 6130//6130 6120//6120 -f 6120//6120 6130//6130 5795//5795 -f 6120//6120 5795//5795 6157//6157 -f 6097//6097 6158//6158 6098//6098 -f 6098//6098 6158//6158 6159//6159 -f 6098//6098 6159//6159 6160//6160 -f 6160//6160 6159//6159 6161//6161 -f 6161//6161 6162//6162 6160//6160 -f 6160//6160 6162//6162 6163//6163 -f 6160//6160 6163//6163 6164//6164 -f 6164//6164 6163//6163 6165//6165 -f 6166//6166 6167//6167 6168//6168 -f 6168//6168 6167//6167 6169//6169 -f 6168//6168 6169//6169 6170//6170 -f 6170//6170 6169//6169 6171//6171 -f 6170//6170 6171//6171 6096//6096 -f 6165//6165 6166//6166 6164//6164 -f 6164//6164 6166//6166 6168//6168 -f 6164//6164 6168//6168 6172//6172 -f 6172//6172 6168//6168 6173//6173 -f 6174//6174 6175//6175 6176//6176 -f 6176//6176 6175//6175 6173//6173 -f 6177//6177 6178//6178 6179//6179 -f 6179//6179 6178//6178 6180//6180 -f 6179//6179 6180//6180 6181//6181 -f 6177//6177 6182//6182 6183//6183 -f 6183//6183 6182//6182 6184//6184 -f 6184//6184 6185//6185 6183//6183 -f 6183//6183 6185//6185 6186//6186 -f 6183//6183 6186//6186 6187//6187 -f 6187//6187 6186//6186 6188//6188 -f 6188//6188 6189//6189 6187//6187 -f 6187//6187 6189//6189 6190//6190 -f 6187//6187 6190//6190 6191//6191 -f 6191//6191 6190//6190 6192//6192 -f 6192//6192 6193//6193 6191//6191 -f 6191//6191 6193//6193 6194//6194 -f 6191//6191 6194//6194 6179//6179 -f 6179//6179 6194//6194 6195//6195 -f 6179//6179 6195//6195 6177//6177 -f 6177//6177 6195//6195 6196//6196 -f 6177//6177 6196//6196 6182//6182 -f 6197//6197 6198//6198 6199//6199 -f 6199//6199 6198//6198 5874//5874 -f 6199//6199 5874//5874 5872//5872 -f 6200//6200 6201//6201 6199//6199 -f 6199//6199 6201//6201 6202//6202 -f 6203//6203 6204//6204 6200//6200 -f 6200//6200 6204//6204 6205//6205 -f 6200//6200 6205//6205 6201//6201 -f 6202//6202 6206//6206 6199//6199 -f 6199//6199 6206//6206 6207//6207 -f 6199//6199 6207//6207 6197//6197 -f 6207//6207 6208//6208 6197//6197 -f 6197//6197 6208//6208 6209//6209 -f 6197//6197 6209//6209 5810//5810 -f 5810//5810 6209//6209 6210//6210 -f 5810//5810 6210//6210 5812//5812 -f 5812//5812 6210//6210 6211//6211 -f 5812//5812 6211//6211 6212//6212 -f 6114//6114 6102//6102 5829//5829 -f 5829//5829 6102//6102 6104//6104 -f 5829//5829 6104//6104 5827//5827 -f 5827//5827 6104//6104 6213//6213 -f 5827//5827 6213//6213 6214//6214 -f 5807//5807 6215//6215 6216//6216 -f 5807//5807 6217//6217 6215//6215 -f 6215//6215 6217//6217 5835//5835 -f 6215//6215 5835//5835 6218//6218 -f 6218//6218 5835//5835 5836//5836 -f 6218//6218 5836//5836 6214//6214 -f 6219//6219 6220//6220 6221//6221 -f 6221//6221 6220//6220 5803//5803 -f 6221//6221 5803//5803 6216//6216 -f 6216//6216 5803//5803 5805//5805 -f 6216//6216 5805//5805 5807//5807 -f 6222//6222 6223//6223 6224//6224 -f 6224//6224 6223//6223 6225//6225 -f 6223//6223 6226//6226 6225//6225 -f 6225//6225 6226//6226 6227//6227 -f 6225//6225 6227//6227 6228//6228 -f 5798//5798 6229//6229 6133//6133 -f 6133//6133 6229//6229 6230//6230 -f 6133//6133 6230//6230 6231//6231 -f 6231//6231 6230//6230 6232//6232 -f 6231//6231 6232//6232 6233//6233 -f 6233//6233 6232//6232 6234//6234 -f 6233//6233 6234//6234 6235//6235 -f 6235//6235 6234//6234 6236//6236 -f 6235//6235 6236//6236 6237//6237 -f 6237//6237 6236//6236 6228//6228 -f 6221//6221 6238//6238 6239//6239 -f 6239//6239 6240//6240 6221//6221 -f 6221//6221 6240//6240 6241//6241 -f 6221//6221 6241//6241 6219//6219 -f 6219//6219 6241//6241 6242//6242 -f 6224//6224 6243//6243 6222//6222 -f 6222//6222 6243//6243 6242//6242 -f 6222//6222 6242//6242 6244//6244 -f 6244//6244 6242//6242 6241//6241 -f 6244//6244 6241//6241 6245//6245 -f 6245//6245 6241//6241 6240//6240 -f 6246//6246 6179//6179 6247//6247 -f 6247//6247 6179//6179 6181//6181 -f 6247//6247 6181//6181 6174//6174 -f 6248//6248 6246//6246 6249//6249 -f 6249//6249 6246//6246 6227//6227 -f 6249//6249 6227//6227 6250//6250 -f 6250//6250 6227//6227 6226//6226 -f 6251//6251 6252//6252 6253//6253 -f 6253//6253 6252//6252 6254//6254 -f 6255//6255 6256//6256 6257//6257 -f 6257//6257 6256//6256 6258//6258 -f 6257//6257 6258//6258 6259//6259 -f 6259//6259 6258//6258 6260//6260 -f 6259//6259 6260//6260 6251//6251 -f 6251//6251 6260//6260 6261//6261 -f 6251//6251 6261//6261 6252//6252 -f 6262//6262 6263//6263 6264//6264 -f 6264//6264 6263//6263 6265//6265 -f 6264//6264 6265//6265 6266//6266 -f 6266//6266 6265//6265 6267//6267 -f 6257//6257 6268//6268 6255//6255 -f 6255//6255 6268//6268 6266//6266 -f 6255//6255 6266//6266 6269//6269 -f 6269//6269 6266//6266 6267//6267 -f 6173//6173 6168//6168 6176//6176 -f 6176//6176 6168//6168 6253//6253 -f 6176//6176 6253//6253 6264//6264 -f 6264//6264 6253//6253 6254//6254 -f 6264//6264 6254//6254 6262//6262 -f 6233//6233 6270//6270 6231//6231 -f 6231//6231 6270//6270 6271//6271 -f 6231//6231 6271//6271 6133//6133 -f 6133//6133 6271//6271 6272//6272 -f 6133//6133 6272//6272 6273//6273 -f 6274//6274 5870//5870 6187//6187 -f 6187//6187 5870//5870 5868//5868 -f 6187//6187 5868//5868 6183//6183 -f 6183//6183 5868//5868 5866//5866 -f 6183//6183 5866//5866 6275//6275 -f 5793//5793 6130//6130 5791//5791 -f 5791//5791 6130//6130 6127//6127 -f 5791//5791 6127//6127 5789//5789 -f 5789//5789 6127//6127 6098//6098 -f 5789//5789 6098//6098 5787//5787 -f 5787//5787 6098//6098 6160//6160 -f 5787//5787 6160//6160 6276//6276 -f 6277//6277 6278//6278 6279//6279 -f 6279//6279 6278//6278 6274//6274 -f 6279//6279 6274//6274 6280//6280 -f 6281//6281 6282//6282 6187//6187 -f 6187//6187 6282//6282 6283//6283 -f 6187//6187 6283//6283 6274//6274 -f 6274//6274 6283//6283 6284//6284 -f 6274//6274 6284//6284 6280//6280 -f 6277//6277 6285//6285 6278//6278 -f 6278//6278 6285//6285 6286//6286 -f 6278//6278 6286//6286 6191//6191 -f 6286//6286 6287//6287 6191//6191 -f 6191//6191 6287//6287 6288//6288 -f 6191//6191 6288//6288 6187//6187 -f 6187//6187 6288//6288 6289//6289 -f 6187//6187 6289//6289 6281//6281 -f 6127//6127 6290//6290 6291//6291 -f 6123//6123 6125//6125 6127//6127 -f 6127//6127 6125//6125 6292//6292 -f 6127//6127 6292//6292 6290//6290 -f 6098//6098 6293//6293 6294//6294 -f 6096//6096 6098//6098 6170//6170 -f 6170//6170 6098//6098 6294//6294 -f 6170//6170 6294//6294 6295//6295 -f 6295//6295 6296//6296 6170//6170 -f 6170//6170 6296//6296 6297//6297 -f 6170//6170 6297//6297 6125//6125 -f 6125//6125 6297//6297 6298//6298 -f 6125//6125 6298//6298 6292//6292 -f 6291//6291 6299//6299 6127//6127 -f 6127//6127 6299//6299 6300//6300 -f 6127//6127 6300//6300 6098//6098 -f 6098//6098 6300//6300 6301//6301 -f 6098//6098 6301//6301 6293//6293 -f 6248//6248 6302//6302 6246//6246 -f 6246//6246 6302//6302 6238//6238 -f 6246//6246 6238//6238 6179//6179 -f 6179//6179 6238//6238 6221//6221 -f 6179//6179 6221//6221 6191//6191 -f 6191//6191 6221//6221 6216//6216 -f 6191//6191 6216//6216 6278//6278 -f 6278//6278 6216//6216 6215//6215 -f 6125//6125 6135//6135 6170//6170 -f 6170//6170 6135//6135 6134//6134 -f 6170//6170 6134//6134 6168//6168 -f 6168//6168 6134//6134 6133//6133 -f 6168//6168 6133//6133 6253//6253 -f 6253//6253 6133//6133 6273//6273 -f 6214//6214 6213//6213 6218//6218 -f 6218//6218 6213//6213 6303//6303 -f 6218//6218 6303//6303 6215//6215 -f 6215//6215 6303//6303 6200//6200 -f 6215//6215 6200//6200 6278//6278 -f 6278//6278 6200//6200 6199//6199 -f 6278//6278 6199//6199 6274//6274 -f 6274//6274 6199//6199 5872//5872 -f 6274//6274 5872//5872 5870//5870 -f 6304//6304 6305//6305 6264//6264 -f 6264//6264 6305//6305 6306//6306 -f 6307//6307 6308//6308 6246//6246 -f 6246//6246 6308//6308 6309//6309 -f 6246//6246 6309//6309 6227//6227 -f 6227//6227 6309//6309 6310//6310 -f 6227//6227 6310//6310 6311//6311 -f 6174//6174 6176//6176 6247//6247 -f 6247//6247 6176//6176 6264//6264 -f 6247//6247 6264//6264 6246//6246 -f 6246//6246 6264//6264 6306//6306 -f 6246//6246 6306//6306 6307//6307 -f 6311//6311 6312//6312 6227//6227 -f 6227//6227 6312//6312 6266//6266 -f 6227//6227 6266//6266 6228//6228 -f 6228//6228 6266//6266 6268//6268 -f 6228//6228 6268//6268 6237//6237 -f 6312//6312 6313//6313 6266//6266 -f 6266//6266 6313//6313 6314//6314 -f 6266//6266 6314//6314 6264//6264 -f 6264//6264 6314//6314 6315//6315 -f 6264//6264 6315//6315 6304//6304 -f 6137//6137 6136//6136 6144//6144 -f 6144//6144 6136//6136 6135//6135 -f 6144//6144 6135//6135 6316//6316 -f 6316//6316 6135//6135 6125//6125 -f 6316//6316 6125//6125 6101//6101 -f 6101//6101 6125//6125 6126//6126 -f 6101//6101 6126//6126 6099//6099 -f 6105//6105 5818//5818 6104//6104 -f 6104//6104 5818//5818 5816//5816 -f 6104//6104 5816//5816 6213//6213 -f 6213//6213 5816//5816 5814//5814 -f 6213//6213 5814//5814 6303//6303 -f 6303//6303 5814//5814 5812//5812 -f 6303//6303 5812//5812 6200//6200 -f 6200//6200 5812//5812 6212//6212 -f 6200//6200 6212//6212 6203//6203 -f 6154//6154 6139//6139 5850//5850 -f 5850//5850 6139//6139 6141//6141 -f 5850//5850 6141//6141 5856//5856 -f 5856//5856 6141//6141 6144//6144 -f 5856//5856 6144//6144 5858//5858 -f 5858//5858 6144//6144 6316//6316 -f 5858//5858 6316//6316 5860//5860 -f 5860//5860 6316//6316 6101//6101 -f 5860//5860 6101//6101 5862//5862 -f 5862//5862 6101//6101 6100//6100 -f 5862//5862 6100//6100 6122//6122 -f 5845//5845 5846//5846 6149//6149 -f 5845//5845 6149//6149 5998//5998 -f 5998//5998 6149//6149 6151//6151 -f 5998//5998 6151//6151 6002//6002 -f 6002//6002 6151//6151 5848//5848 -f 6002//6002 5848//5848 5847//5847 -f 5851//5851 5852//5852 6156//6156 -f 5851//5851 6156//6156 5987//5987 -f 5987//5987 6156//6156 6155//6155 -f 5987//5987 6155//6155 5988//5988 -f 5988//5988 6155//6155 5854//5854 -f 5988//5988 5854//5854 5853//5853 -f 5863//5863 5864//5864 6120//6120 -f 5863//5863 6120//6120 5895//5895 -f 5895//5895 6120//6120 6157//6157 -f 5895//5895 6157//6157 5986//5986 -f 5986//5986 6157//6157 5795//5795 -f 5986//5986 5795//5795 5796//5796 -f 5873//5873 5874//5874 6198//6198 -f 5873//5873 6198//6198 6095//6095 -f 6095//6095 6198//6198 6197//6197 -f 6095//6095 6197//6197 5932//5932 -f 5932//5932 6197//6197 5810//5810 -f 5932//5932 5810//5810 5809//5809 -f 5819//5819 5820//5820 6109//6109 -f 5819//5819 6109//6109 5913//5913 -f 5913//5913 6109//6109 6111//6111 -f 5913//5913 6111//6111 5914//5914 -f 5914//5914 6111//6111 5822//5822 -f 5914//5914 5822//5822 5821//5821 -f 5825//5825 5826//5826 6116//6116 -f 5825//5825 6116//6116 5921//5921 -f 5921//5921 6116//6116 6115//6115 -f 5921//5921 6115//6115 5923//5923 -f 5923//5923 6115//6115 5831//5831 -f 5923//5923 5831//5831 5832//5832 -f 5842//5842 5841//5841 6137//6137 -f 6137//6137 5841//5841 6003//6003 -f 6137//6137 6003//6003 5839//5839 -f 5839//5839 6003//6003 5837//5837 -f 5840//5840 5838//5838 6138//6138 -f 6138//6138 5838//5838 6004//6004 -f 6138//6138 6004//6004 5802//5802 -f 5802//5802 6004//6004 5801//5801 -f 5807//5807 5808//5808 6217//6217 -f 6217//6217 5808//5808 5926//5926 -f 6217//6217 5926//5926 5835//5835 -f 5835//5835 5926//5926 5833//5833 -f 5836//5836 5834//5834 6214//6214 -f 6214//6214 5834//5834 5889//5889 -f 6214//6214 5889//5889 5827//5827 -f 5827//5827 5889//5889 5828//5828 -f 5896//5896 6121//6121 5890//5890 -f 5890//5890 6121//6121 6122//6122 -f 5890//5890 6122//6122 5891//5891 -f 5891//5891 6122//6122 6100//6100 -f 5891//5891 6100//6100 5897//5897 -f 5897//5897 6100//6100 6099//6099 -f 5897//5897 6099//6099 5898//5898 -f 5898//5898 6099//6099 6126//6126 -f 5898//5898 6126//6126 5900//5900 -f 5900//5900 6126//6126 6124//6124 -f 5900//5900 6124//6124 5902//5902 -f 5902//5902 6124//6124 6123//6123 -f 5902//5902 6123//6123 5903//5903 -f 5903//5903 6123//6123 6128//6128 -f 5903//5903 6128//6128 5904//5904 -f 5904//5904 6128//6128 6132//6132 -f 5904//5904 6132//6132 5906//5906 -f 5906//5906 6132//6132 6131//6131 -f 5906//5906 6131//6131 5893//5893 -f 5893//5893 6131//6131 6129//6129 -f 5893//5893 6129//6129 5894//5894 -f 5894//5894 6129//6129 6119//6119 -f 5894//5894 6119//6119 5896//5896 -f 5896//5896 6119//6119 6121//6121 -f 5974//5974 6097//6097 5976//5976 -f 5976//5976 6097//6097 6096//6096 -f 5976//5976 6096//6096 5977//5977 -f 5977//5977 6096//6096 6171//6171 -f 5977//5977 6171//6171 5978//5978 -f 5978//5978 6171//6171 6169//6169 -f 5978//5978 6169//6169 5979//5979 -f 5979//5979 6169//6169 6167//6167 -f 5979//5979 6167//6167 5982//5982 -f 5982//5982 6167//6167 6166//6166 -f 5982//5982 6166//6166 5983//5983 -f 5983//5983 6166//6166 6165//6165 -f 5983//5983 6165//6165 5984//5984 -f 5984//5984 6165//6165 6163//6163 -f 5984//5984 6163//6163 5985//5985 -f 5985//5985 6163//6163 6162//6162 -f 5985//5985 6162//6162 5970//5970 -f 5970//5970 6162//6162 6161//6161 -f 5970//5970 6161//6161 5971//5971 -f 5971//5971 6161//6161 6159//6159 -f 5971//5971 6159//6159 5973//5973 -f 5973//5973 6159//6159 6158//6158 -f 5973//5973 6158//6158 5974//5974 -f 5974//5974 6158//6158 6097//6097 -f 5952//5952 6182//6182 5956//5956 -f 5956//5956 6182//6182 6196//6196 -f 5956//5956 6196//6196 5957//5957 -f 5957//5957 6196//6196 6195//6195 -f 5957//5957 6195//6195 5959//5959 -f 5959//5959 6195//6195 6194//6194 -f 5959//5959 6194//6194 5960//5960 -f 5960//5960 6194//6194 6193//6193 -f 5960//5960 6193//6193 5950//5950 -f 5950//5950 6193//6193 6192//6192 -f 5950//5950 6192//6192 5951//5951 -f 5951//5951 6192//6192 6190//6190 -f 5951//5951 6190//6190 5946//5946 -f 5946//5946 6190//6190 6189//6189 -f 5946//5946 6189//6189 5943//5943 -f 5943//5943 6189//6189 6188//6188 -f 5943//5943 6188//6188 5944//5944 -f 5944//5944 6188//6188 6186//6186 -f 5944//5944 6186//6186 5955//5955 -f 5955//5955 6186//6186 6185//6185 -f 5955//5955 6185//6185 5954//5954 -f 5954//5954 6185//6185 6184//6184 -f 5954//5954 6184//6184 5952//5952 -f 5952//5952 6184//6184 6182//6182 -f 5931//5931 6201//6201 5935//5935 -f 5935//5935 6201//6201 6205//6205 -f 5935//5935 6205//6205 5937//5937 -f 5937//5937 6205//6205 6204//6204 -f 5937//5937 6204//6204 5938//5938 -f 5938//5938 6204//6204 6203//6203 -f 5938//5938 6203//6203 5939//5939 -f 5939//5939 6203//6203 6212//6212 -f 5939//5939 6212//6212 5940//5940 -f 5940//5940 6212//6212 6211//6211 -f 5940//5940 6211//6211 5941//5941 -f 5941//5941 6211//6211 6210//6210 -f 5941//5941 6210//6210 5942//5942 -f 5942//5942 6210//6210 6209//6209 -f 5942//5942 6209//6209 5933//5933 -f 5933//5933 6209//6209 6208//6208 -f 5933//5933 6208//6208 5934//5934 -f 5934//5934 6208//6208 6207//6207 -f 5934//5934 6207//6207 5928//5928 -f 5928//5928 6207//6207 6206//6206 -f 5928//5928 6206//6206 5929//5929 -f 5929//5929 6206//6206 6202//6202 -f 5929//5929 6202//6202 5931//5931 -f 5931//5931 6202//6202 6201//6201 -f 5922//5922 6114//6114 5920//5920 -f 5920//5920 6114//6114 6113//6113 -f 5920//5920 6113//6113 5917//5917 -f 5917//5917 6113//6113 6117//6117 -f 5917//5917 6117//6117 5916//5916 -f 5916//5916 6117//6117 6118//6118 -f 5916//5916 6118//6118 5915//5915 -f 5915//5915 6118//6118 6112//6112 -f 5915//5915 6112//6112 5912//5912 -f 5912//5912 6112//6112 6110//6110 -f 5912//5912 6110//6110 5911//5911 -f 5911//5911 6110//6110 6108//6108 -f 5911//5911 6108//6108 5910//5910 -f 5910//5910 6108//6108 6107//6107 -f 5910//5910 6107//6107 5907//5907 -f 5907//5907 6107//6107 6106//6106 -f 5907//5907 6106//6106 5908//5908 -f 5908//5908 6106//6106 6105//6105 -f 5908//5908 6105//6105 5918//5918 -f 5918//5918 6105//6105 6103//6103 -f 5918//5918 6103//6103 5919//5919 -f 5919//5919 6103//6103 6102//6102 -f 5919//5919 6102//6102 5922//5922 -f 5922//5922 6102//6102 6114//6114 -f 5993//5993 6139//6139 5994//5994 -f 5994//5994 6139//6139 6154//6154 -f 5994//5994 6154//6154 6000//6000 -f 6000//6000 6154//6154 6153//6153 -f 6000//6000 6153//6153 6001//6001 -f 6001//6001 6153//6153 6152//6152 -f 6001//6001 6152//6152 5999//5999 -f 5999//5999 6152//6152 6150//6150 -f 5999//5999 6150//6150 5997//5997 -f 5997//5997 6150//6150 6148//6148 -f 5997//5997 6148//6148 5996//5996 -f 5996//5996 6148//6148 6147//6147 -f 5996//5996 6147//6147 5995//5995 -f 5995//5995 6147//6147 6146//6146 -f 5995//5995 6146//6146 5989//5989 -f 5989//5989 6146//6146 6145//6145 -f 5989//5989 6145//6145 5990//5990 -f 5990//5990 6145//6145 6143//6143 -f 5990//5990 6143//6143 5991//5991 -f 5991//5991 6143//6143 6142//6142 -f 5991//5991 6142//6142 5992//5992 -f 5992//5992 6142//6142 6140//6140 -f 5992//5992 6140//6140 5993//5993 -f 5993//5993 6140//6140 6139//6139 -f 6279//6279 6073//6073 6277//6277 -f 6277//6277 6073//6073 6079//6079 -f 6277//6277 6079//6079 6285//6285 -f 6285//6285 6079//6079 6078//6078 -f 6285//6285 6078//6078 6286//6286 -f 6286//6286 6078//6078 6077//6077 -f 6286//6286 6077//6077 6287//6287 -f 6287//6287 6077//6077 6076//6076 -f 6287//6287 6076//6076 6288//6288 -f 6288//6288 6076//6076 6075//6075 -f 6288//6288 6075//6075 6289//6289 -f 6289//6289 6075//6075 6071//6071 -f 6289//6289 6071//6071 6281//6281 -f 6281//6281 6071//6071 6070//6070 -f 6281//6281 6070//6070 6282//6282 -f 6282//6282 6070//6070 6082//6082 -f 6282//6282 6082//6082 6283//6283 -f 6283//6283 6082//6082 6081//6081 -f 6283//6283 6081//6081 6284//6284 -f 6284//6284 6081//6081 6080//6080 -f 6284//6284 6080//6080 6280//6280 -f 6280//6280 6080//6080 6074//6074 -f 6280//6280 6074//6074 6279//6279 -f 6279//6279 6074//6074 6073//6073 -f 6294//6294 6085//6085 6295//6295 -f 6295//6295 6085//6085 6087//6087 -f 6295//6295 6087//6087 6296//6296 -f 6296//6296 6087//6087 6088//6088 -f 6296//6296 6088//6088 6297//6297 -f 6297//6297 6088//6088 6084//6084 -f 6297//6297 6084//6084 6298//6298 -f 6298//6298 6084//6084 6083//6083 -f 6298//6298 6083//6083 6292//6292 -f 6292//6292 6083//6083 6094//6094 -f 6292//6292 6094//6094 6290//6290 -f 6290//6290 6094//6094 6093//6093 -f 6290//6290 6093//6093 6291//6291 -f 6291//6291 6093//6093 6092//6092 -f 6291//6291 6092//6092 6299//6299 -f 6299//6299 6092//6092 6091//6091 -f 6299//6299 6091//6091 6300//6300 -f 6300//6300 6091//6091 6090//6090 -f 6300//6300 6090//6090 6301//6301 -f 6301//6301 6090//6090 6089//6089 -f 6301//6301 6089//6089 6293//6293 -f 6293//6293 6089//6089 6086//6086 -f 6293//6293 6086//6086 6294//6294 -f 6294//6294 6086//6086 6085//6085 -f 6236//6236 6008//6008 6228//6228 -f 6228//6228 6008//6008 6006//6006 -f 6228//6228 6006//6006 6225//6225 -f 6225//6225 6006//6006 6012//6012 -f 6225//6225 6012//6012 6224//6224 -f 6224//6224 6012//6012 6026//6026 -f 5882//5882 5884//5884 6230//6230 -f 6230//6230 5884//5884 6232//6232 -f 6023//6023 6022//6022 6242//6242 -f 6242//6242 6022//6022 6219//6219 -f 6309//6309 6057//6057 6310//6310 -f 6310//6310 6057//6057 6056//6056 -f 6310//6310 6056//6056 6311//6311 -f 6311//6311 6056//6056 6065//6065 -f 6311//6311 6065//6065 6312//6312 -f 6312//6312 6065//6065 6064//6064 -f 6312//6312 6064//6064 6313//6313 -f 6313//6313 6064//6064 6063//6063 -f 6313//6313 6063//6063 6314//6314 -f 6314//6314 6063//6063 6062//6062 -f 6314//6314 6062//6062 6315//6315 -f 6315//6315 6062//6062 6061//6061 -f 6315//6315 6061//6061 6304//6304 -f 6304//6304 6061//6061 6060//6060 -f 6304//6304 6060//6060 6305//6305 -f 6305//6305 6060//6060 6055//6055 -f 6305//6305 6055//6055 6306//6306 -f 6306//6306 6055//6055 6054//6054 -f 6306//6306 6054//6054 6307//6307 -f 6307//6307 6054//6054 6059//6059 -f 6307//6307 6059//6059 6308//6308 -f 6308//6308 6059//6059 6058//6058 -f 6308//6308 6058//6058 6309//6309 -f 6309//6309 6058//6058 6057//6057 -f 6265//6265 6037//6037 6267//6267 -f 6267//6267 6037//6037 6035//6035 -f 6267//6267 6035//6035 6269//6269 -f 6269//6269 6035//6035 6034//6034 -f 6269//6269 6034//6034 6255//6255 -f 6255//6255 6034//6034 6031//6031 -f 6255//6255 6031//6031 6256//6256 -f 6256//6256 6031//6031 6030//6030 -f 6256//6256 6030//6030 6258//6258 -f 6258//6258 6030//6030 6047//6047 -f 6258//6258 6047//6047 6260//6260 -f 6260//6260 6047//6047 6046//6046 -f 6260//6260 6046//6046 6261//6261 -f 6261//6261 6046//6046 6044//6044 -f 6261//6261 6044//6044 6252//6252 -f 6252//6252 6044//6044 6042//6042 -f 6252//6252 6042//6042 6254//6254 -f 6254//6254 6042//6042 6040//6040 -f 6254//6254 6040//6040 6262//6262 -f 6262//6262 6040//6040 6039//6039 -f 6262//6262 6039//6039 6263//6263 -f 6263//6263 6039//6039 6038//6038 -f 6263//6263 6038//6038 6265//6265 -f 6265//6265 6038//6038 6037//6037 -f 6160//6160 6164//6164 5887//5887 -f 5887//5887 6164//6164 5980//5980 -f 5967//5967 6173//6173 5969//5969 -f 5969//5969 6173//6173 6175//6175 -f 5969//5969 6175//6175 5965//5965 -f 5965//5965 6175//6175 6174//6174 -f 5965//5965 6174//6174 5963//5963 -f 5963//5963 6174//6174 6181//6181 -f 5945//5945 5953//5953 6183//6183 -f 6183//6183 5953//5953 6177//6177 -f 5882//5882 6230//6230 6050//6050 -f 6050//6050 6230//6230 6229//6229 -f 6050//6050 6229//6229 5797//5797 -f 5797//5797 6229//6229 5798//5798 -f 6008//6008 6236//6236 6234//6234 -f 6008//6008 6234//6234 6051//6051 -f 6051//6051 6234//6234 6232//6232 -f 6051//6051 6232//6232 5884//5884 -f 6224//6224 6026//6026 6024//6024 -f 6224//6224 6024//6024 6243//6243 -f 6243//6243 6024//6024 6023//6023 -f 6243//6243 6023//6023 6242//6242 -f 6219//6219 6022//6022 6220//6220 -f 6220//6220 6022//6022 6021//6021 -f 6220//6220 6021//6021 5803//5803 -f 5803//5803 6021//6021 5804//5804 -f 5945//5945 6183//6183 6275//6275 -f 5945//5945 6275//6275 5948//5948 -f 5948//5948 6275//6275 5866//5866 -f 5948//5948 5866//5866 5865//5865 -f 5788//5788 5787//5787 6276//6276 -f 5788//5788 6276//6276 5886//5886 -f 5886//5886 6276//6276 6160//6160 -f 5886//5886 6160//6160 5887//5887 -f 5980//5980 6164//6164 5981//5981 -f 5981//5981 6164//6164 6172//6172 -f 5981//5981 6172//6172 5967//5967 -f 5967//5967 6172//6172 6173//6173 -f 5963//5963 6181//6181 5962//5962 -f 5962//5962 6181//6181 6180//6180 -f 5962//5962 6180//6180 5961//5961 -f 5961//5961 6180//6180 6178//6178 -f 5961//5961 6178//6178 5953//5953 -f 5953//5953 6178//6178 6177//6177 -f 6245//6245 6016//6016 6244//6244 -f 6244//6244 6016//6016 6014//6014 -f 6244//6244 6014//6014 6222//6222 -f 6222//6222 6014//6014 6013//6013 -f 6222//6222 6013//6013 6223//6223 -f 6223//6223 6013//6013 6025//6025 -f 6223//6223 6025//6025 6226//6226 -f 6226//6226 6025//6025 6027//6027 -f 6226//6226 6027//6027 6250//6250 -f 6250//6250 6027//6027 6028//6028 -f 6250//6250 6028//6028 6249//6249 -f 6249//6249 6028//6028 6029//6029 -f 6249//6249 6029//6029 6248//6248 -f 6248//6248 6029//6029 6018//6018 -f 6248//6248 6018//6018 6302//6302 -f 6302//6302 6018//6018 6020//6020 -f 6302//6302 6020//6020 6238//6238 -f 6238//6238 6020//6020 5880//5880 -f 6238//6238 5880//5880 6239//6239 -f 6239//6239 5880//5880 5879//5879 -f 6239//6239 5879//5879 6240//6240 -f 6240//6240 5879//5879 6017//6017 -f 6240//6240 6017//6017 6245//6245 -f 6245//6245 6017//6017 6016//6016 -f 6257//6257 6032//6032 6268//6268 -f 6268//6268 6032//6032 6033//6033 -f 6268//6268 6033//6033 6237//6237 -f 6237//6237 6033//6033 6005//6005 -f 6237//6237 6005//6005 6235//6235 -f 6235//6235 6005//6005 6007//6007 -f 6235//6235 6007//6007 6233//6233 -f 6233//6233 6007//6007 6009//6009 -f 6233//6233 6009//6009 6270//6270 -f 6270//6270 6009//6009 6052//6052 -f 6270//6270 6052//6052 6271//6271 -f 6271//6271 6052//6052 6053//6053 -f 6271//6271 6053//6053 6272//6272 -f 6272//6272 6053//6053 6048//6048 -f 6272//6272 6048//6048 6273//6273 -f 6273//6273 6048//6048 6068//6068 -f 6273//6273 6068//6068 6253//6253 -f 6253//6253 6068//6068 6041//6041 -f 6253//6253 6041//6041 6251//6251 -f 6251//6251 6041//6041 6043//6043 -f 6251//6251 6043//6043 6259//6259 -f 6259//6259 6043//6043 6045//6045 -f 6259//6259 6045//6045 6257//6257 -f 6257//6257 6045//6045 6032//6032 -f 6317//6317 6318//6318 6319//6319 -f 6320//6320 6321//6321 6322//6322 -f 6323//6323 6324//6324 6325//6325 -f 6326//6326 6327//6327 6328//6328 -f 6329//6329 6330//6330 6331//6331 -f 6331//6331 6330//6330 6332//6332 -f 6331//6331 6332//6332 6333//6333 -f 6333//6333 6332//6332 6334//6334 -f 6335//6335 6336//6336 6337//6337 -f 6337//6337 6336//6336 6338//6338 -f 6337//6337 6338//6338 6339//6339 -f 6339//6339 6338//6338 6333//6333 -f 6339//6339 6333//6333 6340//6340 -f 6340//6340 6333//6333 6334//6334 -f 6341//6341 6342//6342 6343//6343 -f 6341//6341 6343//6343 6344//6344 -f 6345//6345 6346//6346 6335//6335 -f 6335//6335 6346//6346 6347//6347 -f 6335//6335 6347//6347 6336//6336 -f 6348//6348 6349//6349 6350//6350 -f 6350//6350 6349//6349 6351//6351 -f 6350//6350 6351//6351 6352//6352 -f 6353//6353 6354//6354 6355//6355 -f 6355//6355 6354//6354 6348//6348 -f 6351//6351 6356//6356 6352//6352 -f 6352//6352 6356//6356 6357//6357 -f 6352//6352 6357//6357 6358//6358 -f 6357//6357 6359//6359 6358//6358 -f 6358//6358 6359//6359 6360//6360 -f 6358//6358 6360//6360 6361//6361 -f 6361//6361 6360//6360 6362//6362 -f 6361//6361 6362//6362 6363//6363 -f 6363//6363 6362//6362 6364//6364 -f 6363//6363 6364//6364 6365//6365 -f 6366//6366 6367//6367 6368//6368 -f 6369//6369 6370//6370 6367//6367 -f 6367//6367 6370//6370 6371//6371 -f 6367//6367 6371//6371 6368//6368 -f 6368//6368 6372//6372 6366//6366 -f 6366//6366 6372//6372 6373//6373 -f 6366//6366 6373//6373 6374//6374 -f 6374//6374 6373//6373 6375//6375 -f 6374//6374 6375//6375 6363//6363 -f 6363//6363 6375//6375 6376//6376 -f 6361//6361 6377//6377 6369//6369 -f 6369//6369 6377//6377 6378//6378 -f 6369//6369 6378//6378 6370//6370 -f 6376//6376 6379//6379 6363//6363 -f 6363//6363 6379//6379 6380//6380 -f 6363//6363 6380//6380 6361//6361 -f 6361//6361 6380//6380 6381//6381 -f 6361//6361 6381//6381 6377//6377 -f 6343//6343 6382//6382 6318//6318 -f 6318//6318 6382//6382 6383//6383 -f 6318//6318 6383//6383 6319//6319 -f 6384//6384 6385//6385 6322//6322 -f 6383//6383 6386//6386 6319//6319 -f 6319//6319 6386//6386 6387//6387 -f 6319//6319 6387//6387 6388//6388 -f 6389//6389 6390//6390 6391//6391 -f 6391//6391 6390//6390 6392//6392 -f 6391//6391 6392//6392 6343//6343 -f 6343//6343 6392//6392 6393//6393 -f 6343//6343 6393//6393 6382//6382 -f 6387//6387 6394//6394 6388//6388 -f 6388//6388 6394//6394 6395//6395 -f 6388//6388 6395//6395 6384//6384 -f 6396//6396 6366//6366 6397//6397 -f 6398//6398 6363//6363 6355//6355 -f 6355//6355 6363//6363 6365//6365 -f 6355//6355 6365//6365 6353//6353 -f 6398//6398 6399//6399 6363//6363 -f 6363//6363 6399//6399 6400//6400 -f 6363//6363 6400//6400 6374//6374 -f 6374//6374 6400//6400 6401//6401 -f 6374//6374 6401//6401 6366//6366 -f 6366//6366 6401//6401 6402//6402 -f 6366//6366 6402//6402 6397//6397 -f 6397//6397 6403//6403 6396//6396 -f 6396//6396 6403//6403 6404//6404 -f 6396//6396 6404//6404 6317//6317 -f 6317//6317 6404//6404 6405//6405 -f 6317//6317 6405//6405 6406//6406 -f 6406//6406 6405//6405 6407//6407 -f 6406//6406 6407//6407 6408//6408 -f 6408//6408 6407//6407 6409//6409 -f 6408//6408 6409//6409 6355//6355 -f 6355//6355 6409//6409 6410//6410 -f 6355//6355 6410//6410 6398//6398 -f 6411//6411 6412//6412 6413//6413 -f 6413//6413 6414//6414 6411//6411 -f 6411//6411 6414//6414 6415//6415 -f 6411//6411 6415//6415 6367//6367 -f 6367//6367 6415//6415 6416//6416 -f 6367//6367 6416//6416 6369//6369 -f 6417//6417 6418//6418 6412//6412 -f 6412//6412 6418//6418 6419//6419 -f 6412//6412 6419//6419 6413//6413 -f 6416//6416 6420//6420 6369//6369 -f 6369//6369 6420//6420 6421//6421 -f 6369//6369 6421//6421 6361//6361 -f 6361//6361 6421//6421 6422//6422 -f 6423//6423 6424//6424 6417//6417 -f 6417//6417 6424//6424 6425//6425 -f 6417//6417 6425//6425 6418//6418 -f 6426//6426 6427//6427 6428//6428 -f 6428//6428 6427//6427 6429//6429 -f 6428//6428 6429//6429 6430//6430 -f 6430//6430 6429//6429 6431//6431 -f 6430//6430 6431//6431 6432//6432 -f 6432//6432 6431//6431 6433//6433 -f 6434//6434 6435//6435 6436//6436 -f 6436//6436 6435//6435 6437//6437 -f 6436//6436 6437//6437 6438//6438 -f 6438//6438 6437//6437 6439//6439 -f 6438//6438 6439//6439 6440//6440 -f 6441//6441 6442//6442 6443//6443 -f 6441//6441 6443//6443 6444//6444 -f 6445//6445 6446//6446 6391//6391 -f 6443//6443 6447//6447 6444//6444 -f 6444//6444 6447//6447 6448//6448 -f 6444//6444 6448//6448 6445//6445 -f 6446//6446 6449//6449 6391//6391 -f 6391//6391 6449//6449 6322//6322 -f 6391//6391 6322//6322 6389//6389 -f 6389//6389 6322//6322 6385//6385 -f 6449//6449 6450//6450 6322//6322 -f 6322//6322 6450//6450 6451//6451 -f 6322//6322 6451//6451 6452//6452 -f 6452//6452 6451//6451 6453//6453 -f 6452//6452 6453//6453 6454//6454 -f 6442//6442 6441//6441 6455//6455 -f 6455//6455 6441//6441 6456//6456 -f 6455//6455 6456//6456 6454//6454 -f 6417//6417 6457//6457 6458//6458 -f 6458//6458 6457//6457 6459//6459 -f 6458//6458 6459//6459 6460//6460 -f 6461//6461 6462//6462 6463//6463 -f 6463//6463 6462//6462 6464//6464 -f 6463//6463 6464//6464 6465//6465 -f 6454//6454 6456//6456 6452//6452 -f 6452//6452 6456//6456 6461//6461 -f 6452//6452 6461//6461 6466//6466 -f 6467//6467 6468//6468 6469//6469 -f 6469//6469 6468//6468 6427//6427 -f 6469//6469 6427//6427 6470//6470 -f 6445//6445 6391//6391 6444//6444 -f 6444//6444 6391//6391 6343//6343 -f 6444//6444 6343//6343 6345//6345 -f 6345//6345 6343//6343 6342//6342 -f 6345//6345 6342//6342 6346//6346 -f 6329//6329 6326//6326 6330//6330 -f 6330//6330 6326//6326 6328//6328 -f 6330//6330 6328//6328 6471//6471 -f 6471//6471 6328//6328 6472//6472 -f 6384//6384 6322//6322 6388//6388 -f 6388//6388 6322//6322 6321//6321 -f 6388//6388 6321//6321 6473//6473 -f 6473//6473 6474//6474 6388//6388 -f 6388//6388 6474//6474 6475//6475 -f 6388//6388 6475//6475 6476//6476 -f 6475//6475 6477//6477 6476//6476 -f 6476//6476 6477//6477 6478//6478 -f 6476//6476 6478//6478 6452//6452 -f 6452//6452 6478//6478 6479//6479 -f 6452//6452 6479//6479 6480//6480 -f 6480//6480 6481//6481 6452//6452 -f 6452//6452 6481//6481 6482//6482 -f 6452//6452 6482//6482 6322//6322 -f 6322//6322 6482//6482 6483//6483 -f 6322//6322 6483//6483 6320//6320 -f 6484//6484 6485//6485 6452//6452 -f 6452//6452 6485//6485 6486//6486 -f 6452//6452 6486//6486 6476//6476 -f 6484//6484 6452//6452 6487//6487 -f 6487//6487 6452//6452 6466//6466 -f 6487//6487 6466//6466 6488//6488 -f 6489//6489 6490//6490 6491//6491 -f 6491//6491 6490//6490 6492//6492 -f 6491//6491 6492//6492 6466//6466 -f 6466//6466 6492//6492 6493//6493 -f 6466//6466 6493//6493 6488//6488 -f 6486//6486 6494//6494 6476//6476 -f 6476//6476 6494//6494 6495//6495 -f 6476//6476 6495//6495 6491//6491 -f 6491//6491 6495//6495 6496//6496 -f 6491//6491 6496//6496 6489//6489 -f 6497//6497 6498//6498 6499//6499 -f 6499//6499 6498//6498 6471//6471 -f 6500//6500 6472//6472 6501//6501 -f 6501//6501 6472//6472 6502//6502 -f 6501//6501 6502//6502 6503//6503 -f 6503//6503 6502//6502 6504//6504 -f 6497//6497 6505//6505 6498//6498 -f 6498//6498 6505//6505 6506//6506 -f 6498//6498 6506//6506 6502//6502 -f 6502//6502 6506//6506 6507//6507 -f 6502//6502 6507//6507 6504//6504 -f 6500//6500 6508//6508 6472//6472 -f 6472//6472 6508//6508 6509//6509 -f 6472//6472 6509//6509 6471//6471 -f 6471//6471 6509//6509 6510//6510 -f 6471//6471 6510//6510 6499//6499 -f 6317//6317 6319//6319 6396//6396 -f 6396//6396 6319//6319 6388//6388 -f 6396//6396 6388//6388 6366//6366 -f 6366//6366 6388//6388 6476//6476 -f 6366//6366 6476//6476 6367//6367 -f 6367//6367 6476//6476 6491//6491 -f 6367//6367 6491//6491 6411//6411 -f 6511//6511 6512//6512 6513//6513 -f 6513//6513 6512//6512 6498//6498 -f 6513//6513 6498//6498 6514//6514 -f 6515//6515 6516//6516 6517//6517 -f 6515//6515 6517//6517 6518//6518 -f 6516//6516 6519//6519 6517//6517 -f 6517//6517 6519//6519 6520//6520 -f 6517//6517 6520//6520 6502//6502 -f 6502//6502 6520//6520 6521//6521 -f 6521//6521 6522//6522 6502//6502 -f 6502//6502 6522//6522 6523//6523 -f 6502//6502 6523//6523 6498//6498 -f 6498//6498 6523//6523 6524//6524 -f 6498//6498 6524//6524 6514//6514 -f 6511//6511 6518//6518 6512//6512 -f 6512//6512 6518//6518 6517//6517 -f 6512//6512 6517//6517 6431//6431 -f 6431//6431 6517//6517 6325//6325 -f 6431//6431 6325//6325 6433//6433 -f 6433//6433 6325//6325 6324//6324 -f 6327//6327 6344//6344 6328//6328 -f 6328//6328 6344//6344 6343//6343 -f 6328//6328 6343//6343 6472//6472 -f 6472//6472 6343//6343 6318//6318 -f 6472//6472 6318//6318 6502//6502 -f 6502//6502 6318//6318 6317//6317 -f 6502//6502 6317//6317 6517//6517 -f 6517//6517 6317//6317 6406//6406 -f 6517//6517 6406//6406 6325//6325 -f 6325//6325 6406//6406 6408//6408 -f 6325//6325 6408//6408 6323//6323 -f 6461//6461 6463//6463 6466//6466 -f 6466//6466 6463//6463 6525//6525 -f 6466//6466 6525//6525 6491//6491 -f 6491//6491 6525//6525 6526//6526 -f 6491//6491 6526//6526 6411//6411 -f 6411//6411 6526//6526 6527//6527 -f 6411//6411 6527//6527 6412//6412 -f 6412//6412 6527//6527 6528//6528 -f 6412//6412 6528//6528 6417//6417 -f 6417//6417 6528//6528 6529//6529 -f 6417//6417 6529//6529 6457//6457 -f 6348//6348 6350//6350 6355//6355 -f 6355//6355 6350//6350 6438//6438 -f 6355//6355 6438//6438 6408//6408 -f 6408//6408 6438//6438 6440//6440 -f 6408//6408 6440//6440 6323//6323 -f 6422//6422 6423//6423 6361//6361 -f 6361//6361 6423//6423 6417//6417 -f 6361//6361 6417//6417 6358//6358 -f 6358//6358 6417//6417 6458//6458 -f 6358//6358 6458//6458 6530//6530 -f 6530//6530 6458//6458 6460//6460 -f 6530//6530 6460//6460 6531//6531 -f 6530//6530 6532//6532 6358//6358 -f 6358//6358 6532//6532 6533//6533 -f 6358//6358 6533//6533 6352//6352 -f 6352//6352 6533//6533 6534//6534 -f 6352//6352 6534//6534 6350//6350 -f 6350//6350 6534//6534 6535//6535 -f 6350//6350 6535//6535 6438//6438 -f 6438//6438 6535//6535 6470//6470 -f 6438//6438 6470//6470 6436//6436 -f 6436//6436 6470//6470 6427//6427 -f 6436//6436 6427//6427 6434//6434 -f 6434//6434 6427//6427 6426//6426 -f 6536//6536 6537//6537 6538//6538 -f 6539//6539 6540//6540 6541//6541 -f 6542//6542 6543//6543 6544//6544 -f 6545//6545 6546//6546 6547//6547 -f 6548//6548 6549//6549 6550//6550 -f 6551//6551 6552//6552 6553//6553 -f 6554//6554 6555//6555 6556//6556 -f 6556//6556 6555//6555 6557//6557 -f 6558//6558 6559//6559 6560//6560 -f 6561//6561 6562//6562 6563//6563 -f 6563//6563 6562//6562 6564//6564 -f 6563//6563 6558//6558 6561//6561 -f 6561//6561 6558//6558 6560//6560 -f 6561//6561 6560//6560 6565//6565 -f 6565//6565 6560//6560 6566//6566 -f 6565//6565 6566//6566 6567//6567 -f 6567//6567 6566//6566 6568//6568 -f 6567//6567 6568//6568 6569//6569 -f 6569//6569 6568//6568 6557//6557 -f 6570//6570 6571//6571 6554//6554 -f 6562//6562 6572//6572 6564//6564 -f 6564//6564 6572//6572 6573//6573 -f 6564//6564 6573//6573 6574//6574 -f 6574//6574 6573//6573 6575//6575 -f 6576//6576 6577//6577 6578//6578 -f 6578//6578 6577//6577 6579//6579 -f 6578//6578 6579//6579 6580//6580 -f 6581//6581 6582//6582 6583//6583 -f 6583//6583 6582//6582 6584//6584 -f 6583//6583 6584//6584 6585//6585 -f 6579//6579 6586//6586 6580//6580 -f 6580//6580 6586//6586 6587//6587 -f 6580//6580 6587//6587 6588//6588 -f 6589//6589 6590//6590 6538//6538 -f 6538//6538 6590//6590 6591//6591 -f 6538//6538 6591//6591 6581//6581 -f 6581//6581 6591//6591 6592//6592 -f 6581//6581 6592//6592 6582//6582 -f 6593//6593 6594//6594 6595//6595 -f 6595//6595 6594//6594 6596//6596 -f 6597//6597 6598//6598 6599//6599 -f 6596//6596 6600//6600 6595//6595 -f 6595//6595 6600//6600 6601//6601 -f 6595//6595 6601//6601 6547//6547 -f 6547//6547 6601//6601 6602//6602 -f 6547//6547 6602//6602 6597//6597 -f 6603//6603 6604//6604 6541//6541 -f 6541//6541 6604//6604 6605//6605 -f 6541//6541 6605//6605 6593//6593 -f 6593//6593 6605//6605 6606//6606 -f 6593//6593 6606//6606 6594//6594 -f 6551//6551 6553//6553 6607//6607 -f 6608//6608 6609//6609 6610//6610 -f 6610//6610 6611//6611 6608//6608 -f 6608//6608 6611//6611 6612//6612 -f 6608//6608 6612//6612 6613//6613 -f 6613//6613 6612//6612 6614//6614 -f 6613//6613 6614//6614 6615//6615 -f 6615//6615 6614//6614 6616//6616 -f 6615//6615 6616//6616 6607//6607 -f 6617//6617 6618//6618 6619//6619 -f 6619//6619 6620//6620 6617//6617 -f 6617//6617 6620//6620 6621//6621 -f 6617//6617 6621//6621 6609//6609 -f 6609//6609 6621//6621 6622//6622 -f 6609//6609 6622//6622 6610//6610 -f 6623//6623 6624//6624 6625//6625 -f 6625//6625 6626//6626 6623//6623 -f 6623//6623 6626//6626 6599//6599 -f 6623//6623 6599//6599 6627//6627 -f 6627//6627 6599//6599 6598//6598 -f 6628//6628 6629//6629 6630//6630 -f 6630//6630 6629//6629 6631//6631 -f 6626//6626 6632//6632 6599//6599 -f 6599//6599 6632//6632 6633//6633 -f 6599//6599 6633//6633 6634//6634 -f 6634//6634 6633//6633 6635//6635 -f 6634//6634 6635//6635 6629//6629 -f 6629//6629 6635//6635 6636//6636 -f 6629//6629 6636//6636 6631//6631 -f 6631//6631 6637//6637 6630//6630 -f 6630//6630 6637//6637 6638//6638 -f 6630//6630 6638//6638 6639//6639 -f 6639//6639 6638//6638 6640//6640 -f 6639//6639 6640//6640 6641//6641 -f 6642//6642 6643//6643 6644//6644 -f 6644//6644 6643//6643 6645//6645 -f 6646//6646 6639//6639 6623//6623 -f 6623//6623 6639//6639 6641//6641 -f 6623//6623 6641//6641 6624//6624 -f 6645//6645 6647//6647 6644//6644 -f 6644//6644 6647//6647 6648//6648 -f 6644//6644 6648//6648 6623//6623 -f 6623//6623 6648//6648 6649//6649 -f 6623//6623 6649//6649 6646//6646 -f 6650//6650 6630//6630 6651//6651 -f 6651//6651 6630//6630 6639//6639 -f 6651//6651 6639//6639 6652//6652 -f 6652//6652 6639//6639 6646//6646 -f 6650//6650 6653//6653 6654//6654 -f 6654//6654 6653//6653 6655//6655 -f 6654//6654 6655//6655 6642//6642 -f 6642//6642 6655//6655 6656//6656 -f 6642//6642 6656//6656 6643//6643 -f 6657//6657 6658//6658 6659//6659 -f 6657//6657 6659//6659 6570//6570 -f 6570//6570 6659//6659 6660//6660 -f 6570//6570 6660//6660 6583//6583 -f 6548//6548 6550//6550 6661//6661 -f 6660//6660 6662//6662 6583//6583 -f 6583//6583 6662//6662 6663//6663 -f 6583//6583 6663//6663 6581//6581 -f 6581//6581 6663//6663 6664//6664 -f 6665//6665 6666//6666 6667//6667 -f 6667//6667 6666//6666 6581//6581 -f 6667//6667 6581//6581 6668//6668 -f 6668//6668 6581//6581 6664//6664 -f 6546//6546 6669//6669 6618//6618 -f 6618//6618 6669//6669 6670//6670 -f 6597//6597 6599//6599 6547//6547 -f 6547//6547 6599//6599 6671//6671 -f 6547//6547 6671//6671 6545//6545 -f 6672//6672 6673//6673 6629//6629 -f 6629//6629 6673//6673 6674//6674 -f 6629//6629 6674//6674 6634//6634 -f 6634//6634 6674//6674 6675//6675 -f 6634//6634 6675//6675 6599//6599 -f 6599//6599 6675//6675 6676//6676 -f 6599//6599 6676//6676 6671//6671 -f 6677//6677 6678//6678 6679//6679 -f 6680//6680 6681//6681 6678//6678 -f 6678//6678 6681//6681 6682//6682 -f 6678//6678 6682//6682 6679//6679 -f 6539//6539 6683//6683 6540//6540 -f 6540//6540 6683//6683 6684//6684 -f 6540//6540 6684//6684 6685//6685 -f 6686//6686 6617//6617 6687//6687 -f 6687//6687 6617//6617 6609//6609 -f 6687//6687 6609//6609 6688//6688 -f 6688//6688 6609//6609 6608//6608 -f 6688//6688 6608//6608 6689//6689 -f 6689//6689 6608//6608 6690//6690 -f 6595//6595 6691//6691 6593//6593 -f 6593//6593 6691//6691 6692//6692 -f 6593//6593 6692//6692 6541//6541 -f 6541//6541 6692//6692 6693//6693 -f 6541//6541 6693//6693 6539//6539 -f 6546//6546 6618//6618 6547//6547 -f 6547//6547 6618//6618 6617//6617 -f 6547//6547 6617//6617 6595//6595 -f 6595//6595 6617//6617 6686//6686 -f 6595//6595 6686//6686 6691//6691 -f 6685//6685 6694//6694 6540//6540 -f 6540//6540 6694//6694 6644//6644 -f 6540//6540 6644//6644 6541//6541 -f 6541//6541 6644//6644 6623//6623 -f 6541//6541 6623//6623 6603//6603 -f 6603//6603 6623//6623 6627//6627 -f 6695//6695 6696//6696 6697//6697 -f 6698//6698 6699//6699 6700//6700 -f 6697//6697 6696//6696 6701//6701 -f 6702//6702 6703//6703 6704//6704 -f 6702//6702 6704//6704 6705//6705 -f 6703//6703 6706//6706 6704//6704 -f 6704//6704 6706//6706 6707//6707 -f 6704//6704 6707//6707 6698//6698 -f 6698//6698 6707//6707 6708//6708 -f 6698//6698 6708//6708 6699//6699 -f 6607//6607 6553//6553 6615//6615 -f 6615//6615 6553//6553 6698//6698 -f 6615//6615 6698//6698 6697//6697 -f 6697//6697 6698//6698 6700//6700 -f 6697//6697 6700//6700 6695//6695 -f 6696//6696 6709//6709 6701//6701 -f 6701//6701 6709//6709 6710//6710 -f 6701//6701 6710//6710 6705//6705 -f 6704//6704 6711//6711 6712//6712 -f 6713//6713 6714//6714 6715//6715 -f 6705//6705 6704//6704 6701//6701 -f 6701//6701 6704//6704 6712//6712 -f 6701//6701 6712//6712 6716//6716 -f 6716//6716 6717//6717 6701//6701 -f 6701//6701 6717//6717 6718//6718 -f 6701//6701 6718//6718 6719//6719 -f 6719//6719 6718//6718 6720//6720 -f 6719//6719 6720//6720 6721//6721 -f 6714//6714 6722//6722 6715//6715 -f 6715//6715 6722//6722 6723//6723 -f 6715//6715 6723//6723 6704//6704 -f 6704//6704 6723//6723 6724//6724 -f 6704//6704 6724//6724 6711//6711 -f 6725//6725 6550//6550 6657//6657 -f 6657//6657 6550//6550 6549//6549 -f 6657//6657 6549//6549 6658//6658 -f 6669//6669 6726//6726 6670//6670 -f 6670//6670 6726//6726 6542//6542 -f 6670//6670 6542//6542 6725//6725 -f 6725//6725 6542//6542 6544//6544 -f 6725//6725 6544//6544 6550//6550 -f 6550//6550 6544//6544 6666//6666 -f 6550//6550 6666//6666 6661//6661 -f 6661//6661 6666//6666 6665//6665 -f 6557//6557 6568//6568 6556//6556 -f 6556//6556 6568//6568 6719//6719 -f 6556//6556 6719//6719 6715//6715 -f 6715//6715 6719//6719 6721//6721 -f 6715//6715 6721//6721 6713//6713 -f 6554//6554 6556//6556 6570//6570 -f 6570//6570 6556//6556 6715//6715 -f 6570//6570 6715//6715 6657//6657 -f 6657//6657 6715//6715 6704//6704 -f 6657//6657 6704//6704 6725//6725 -f 6725//6725 6704//6704 6698//6698 -f 6725//6725 6698//6698 6670//6670 -f 6670//6670 6698//6698 6553//6553 -f 6670//6670 6553//6553 6618//6618 -f 6618//6618 6553//6553 6552//6552 -f 6618//6618 6552//6552 6619//6619 -f 6727//6727 6728//6728 6628//6628 -f 6727//6727 6628//6628 6537//6537 -f 6729//6729 6730//6730 6581//6581 -f 6581//6581 6730//6730 6731//6731 -f 6581//6581 6731//6731 6538//6538 -f 6538//6538 6731//6731 6732//6732 -f 6538//6538 6732//6732 6536//6536 -f 6728//6728 6733//6733 6628//6628 -f 6628//6628 6733//6733 6666//6666 -f 6628//6628 6666//6666 6629//6629 -f 6629//6629 6666//6666 6544//6544 -f 6629//6629 6544//6544 6672//6672 -f 6672//6672 6544//6544 6543//6543 -f 6733//6733 6734//6734 6666//6666 -f 6666//6666 6734//6734 6735//6735 -f 6666//6666 6735//6735 6581//6581 -f 6581//6581 6735//6735 6736//6736 -f 6581//6581 6736//6736 6729//6729 -f 6737//6737 6738//6738 6628//6628 -f 6739//6739 6740//6740 6741//6741 -f 6741//6741 6740//6740 6742//6742 -f 6741//6741 6742//6742 6743//6743 -f 6742//6742 6744//6744 6743//6743 -f 6743//6743 6744//6744 6745//6745 -f 6743//6743 6745//6745 6746//6746 -f 6537//6537 6628//6628 6538//6538 -f 6538//6538 6628//6628 6738//6738 -f 6538//6538 6738//6738 6747//6747 -f 6747//6747 6748//6748 6538//6538 -f 6538//6538 6748//6748 6749//6749 -f 6538//6538 6749//6749 6741//6741 -f 6741//6741 6749//6749 6750//6750 -f 6741//6741 6750//6750 6739//6739 -f 6650//6650 6654//6654 6630//6630 -f 6630//6630 6654//6654 6743//6743 -f 6630//6630 6743//6743 6628//6628 -f 6628//6628 6743//6743 6746//6746 -f 6628//6628 6746//6746 6737//6737 -f 6587//6587 6589//6589 6588//6588 -f 6588//6588 6589//6589 6538//6538 -f 6588//6588 6538//6538 6679//6679 -f 6679//6679 6538//6538 6741//6741 -f 6679//6679 6741//6741 6677//6677 -f 6677//6677 6741//6741 6743//6743 -f 6677//6677 6743//6743 6751//6751 -f 6751//6751 6743//6743 6654//6654 -f 6751//6751 6654//6654 6752//6752 -f 6752//6752 6654//6654 6642//6642 -f 6752//6752 6642//6642 6753//6753 -f 6753//6753 6642//6642 6644//6644 -f 6753//6753 6644//6644 6754//6754 -f 6754//6754 6644//6644 6694//6694 -f 6585//6585 6576//6576 6583//6583 -f 6583//6583 6576//6576 6578//6578 -f 6583//6583 6578//6578 6570//6570 -f 6570//6570 6578//6578 6574//6574 -f 6570//6570 6574//6574 6571//6571 -f 6571//6571 6574//6574 6575//6575 -f 6461//6461 6679//6679 6682//6682 -f 6461//6461 6682//6682 6462//6462 -f 6462//6462 6682//6682 6681//6681 -f 6462//6462 6681//6681 6464//6464 -f 6464//6464 6681//6681 6680//6680 -f 6464//6464 6680//6680 6465//6465 -f 6465//6465 6680//6680 6678//6678 -f 6465//6465 6678//6678 6463//6463 -f 6694//6694 6457//6457 6754//6754 -f 6754//6754 6457//6457 6529//6529 -f 6754//6754 6529//6529 6753//6753 -f 6753//6753 6529//6529 6528//6528 -f 6753//6753 6528//6528 6752//6752 -f 6752//6752 6528//6528 6527//6527 -f 6752//6752 6527//6527 6751//6751 -f 6751//6751 6527//6527 6526//6526 -f 6751//6751 6526//6526 6677//6677 -f 6677//6677 6526//6526 6525//6525 -f 6677//6677 6525//6525 6678//6678 -f 6678//6678 6525//6525 6463//6463 -f 6457//6457 6694//6694 6685//6685 -f 6457//6457 6685//6685 6459//6459 -f 6459//6459 6685//6685 6684//6684 -f 6459//6459 6684//6684 6460//6460 -f 6460//6460 6684//6684 6683//6683 -f 6460//6460 6683//6683 6531//6531 -f 6531//6531 6683//6683 6539//6539 -f 6531//6531 6539//6539 6530//6530 -f 6688//6688 6469//6469 6687//6687 -f 6687//6687 6469//6469 6470//6470 -f 6687//6687 6470//6470 6686//6686 -f 6686//6686 6470//6470 6535//6535 -f 6686//6686 6535//6535 6691//6691 -f 6691//6691 6535//6535 6534//6534 -f 6691//6691 6534//6534 6692//6692 -f 6692//6692 6534//6534 6533//6533 -f 6692//6692 6533//6533 6693//6693 -f 6693//6693 6533//6533 6532//6532 -f 6693//6693 6532//6532 6539//6539 -f 6539//6539 6532//6532 6530//6530 -f 6337//6337 6563//6563 6335//6335 -f 6335//6335 6563//6563 6564//6564 -f 6335//6335 6564//6564 6345//6345 -f 6345//6345 6564//6564 6574//6574 -f 6345//6345 6574//6574 6444//6444 -f 6444//6444 6574//6574 6578//6578 -f 6444//6444 6578//6578 6441//6441 -f 6441//6441 6578//6578 6580//6580 -f 6441//6441 6580//6580 6456//6456 -f 6456//6456 6580//6580 6588//6588 -f 6456//6456 6588//6588 6461//6461 -f 6461//6461 6588//6588 6679//6679 -f 6401//6401 6675//6675 6402//6402 -f 6402//6402 6675//6675 6674//6674 -f 6402//6402 6674//6674 6397//6397 -f 6397//6397 6674//6674 6673//6673 -f 6397//6397 6673//6673 6403//6403 -f 6403//6403 6673//6673 6672//6672 -f 6403//6403 6672//6672 6404//6404 -f 6404//6404 6672//6672 6543//6543 -f 6404//6404 6543//6543 6405//6405 -f 6405//6405 6543//6543 6542//6542 -f 6405//6405 6542//6542 6407//6407 -f 6407//6407 6542//6542 6726//6726 -f 6407//6407 6726//6726 6409//6409 -f 6409//6409 6726//6726 6669//6669 -f 6409//6409 6669//6669 6410//6410 -f 6410//6410 6669//6669 6546//6546 -f 6410//6410 6546//6546 6398//6398 -f 6398//6398 6546//6546 6545//6545 -f 6398//6398 6545//6545 6399//6399 -f 6399//6399 6545//6545 6671//6671 -f 6399//6399 6671//6671 6400//6400 -f 6400//6400 6671//6671 6676//6676 -f 6400//6400 6676//6676 6401//6401 -f 6401//6401 6676//6676 6675//6675 -f 6384//6384 6667//6667 6385//6385 -f 6385//6385 6667//6667 6668//6668 -f 6385//6385 6668//6668 6389//6389 -f 6389//6389 6668//6668 6664//6664 -f 6389//6389 6664//6664 6390//6390 -f 6390//6390 6664//6664 6663//6663 -f 6390//6390 6663//6663 6392//6392 -f 6392//6392 6663//6663 6662//6662 -f 6392//6392 6662//6662 6393//6393 -f 6393//6393 6662//6662 6660//6660 -f 6393//6393 6660//6660 6382//6382 -f 6382//6382 6660//6660 6659//6659 -f 6382//6382 6659//6659 6383//6383 -f 6383//6383 6659//6659 6658//6658 -f 6383//6383 6658//6658 6386//6386 -f 6386//6386 6658//6658 6549//6549 -f 6386//6386 6549//6549 6387//6387 -f 6387//6387 6549//6549 6548//6548 -f 6387//6387 6548//6548 6394//6394 -f 6394//6394 6548//6548 6661//6661 -f 6394//6394 6661//6661 6395//6395 -f 6395//6395 6661//6661 6665//6665 -f 6395//6395 6665//6665 6384//6384 -f 6384//6384 6665//6665 6667//6667 -f 6479//6479 6537//6537 6480//6480 -f 6480//6480 6537//6537 6536//6536 -f 6480//6480 6536//6536 6481//6481 -f 6481//6481 6536//6536 6732//6732 -f 6481//6481 6732//6732 6482//6482 -f 6482//6482 6732//6732 6731//6731 -f 6482//6482 6731//6731 6483//6483 -f 6483//6483 6731//6731 6730//6730 -f 6483//6483 6730//6730 6320//6320 -f 6320//6320 6730//6730 6729//6729 -f 6320//6320 6729//6729 6321//6321 -f 6321//6321 6729//6729 6736//6736 -f 6321//6321 6736//6736 6473//6473 -f 6473//6473 6736//6736 6735//6735 -f 6473//6473 6735//6735 6474//6474 -f 6474//6474 6735//6735 6734//6734 -f 6474//6474 6734//6734 6475//6475 -f 6475//6475 6734//6734 6733//6733 -f 6475//6475 6733//6733 6477//6477 -f 6477//6477 6733//6733 6728//6728 -f 6477//6477 6728//6728 6478//6478 -f 6478//6478 6728//6728 6727//6727 -f 6478//6478 6727//6727 6479//6479 -f 6479//6479 6727//6727 6537//6537 -f 6492//6492 6742//6742 6493//6493 -f 6493//6493 6742//6742 6740//6740 -f 6493//6493 6740//6740 6488//6488 -f 6488//6488 6740//6740 6739//6739 -f 6488//6488 6739//6739 6487//6487 -f 6487//6487 6739//6739 6750//6750 -f 6487//6487 6750//6750 6484//6484 -f 6484//6484 6750//6750 6749//6749 -f 6484//6484 6749//6749 6485//6485 -f 6485//6485 6749//6749 6748//6748 -f 6485//6485 6748//6748 6486//6486 -f 6486//6486 6748//6748 6747//6747 -f 6486//6486 6747//6747 6494//6494 -f 6494//6494 6747//6747 6738//6738 -f 6494//6494 6738//6738 6495//6495 -f 6495//6495 6738//6738 6737//6737 -f 6495//6495 6737//6737 6496//6496 -f 6496//6496 6737//6737 6746//6746 -f 6496//6496 6746//6746 6489//6489 -f 6489//6489 6746//6746 6745//6745 -f 6489//6489 6745//6745 6490//6490 -f 6490//6490 6745//6745 6744//6744 -f 6490//6490 6744//6744 6492//6492 -f 6492//6492 6744//6744 6742//6742 -f 6419//6419 6643//6643 6413//6413 -f 6413//6413 6643//6643 6656//6656 -f 6413//6413 6656//6656 6414//6414 -f 6414//6414 6656//6656 6655//6655 -f 6414//6414 6655//6655 6415//6415 -f 6415//6415 6655//6655 6653//6653 -f 6415//6415 6653//6653 6416//6416 -f 6416//6416 6653//6653 6650//6650 -f 6416//6416 6650//6650 6420//6420 -f 6420//6420 6650//6650 6651//6651 -f 6420//6420 6651//6651 6421//6421 -f 6421//6421 6651//6651 6652//6652 -f 6421//6421 6652//6652 6422//6422 -f 6422//6422 6652//6652 6646//6646 -f 6422//6422 6646//6646 6423//6423 -f 6423//6423 6646//6646 6649//6649 -f 6423//6423 6649//6649 6424//6424 -f 6424//6424 6649//6649 6648//6648 -f 6424//6424 6648//6648 6425//6425 -f 6425//6425 6648//6648 6647//6647 -f 6425//6425 6647//6647 6418//6418 -f 6418//6418 6647//6647 6645//6645 -f 6418//6418 6645//6645 6419//6419 -f 6419//6419 6645//6645 6643//6643 -f 6378//6378 6641//6641 6370//6370 -f 6370//6370 6641//6641 6640//6640 -f 6370//6370 6640//6640 6371//6371 -f 6371//6371 6640//6640 6638//6638 -f 6371//6371 6638//6638 6368//6368 -f 6368//6368 6638//6638 6637//6637 -f 6368//6368 6637//6637 6372//6372 -f 6372//6372 6637//6637 6631//6631 -f 6372//6372 6631//6631 6373//6373 -f 6373//6373 6631//6631 6636//6636 -f 6373//6373 6636//6636 6375//6375 -f 6375//6375 6636//6636 6635//6635 -f 6375//6375 6635//6635 6376//6376 -f 6376//6376 6635//6635 6633//6633 -f 6376//6376 6633//6633 6379//6379 -f 6379//6379 6633//6633 6632//6632 -f 6379//6379 6632//6632 6380//6380 -f 6380//6380 6632//6632 6626//6626 -f 6380//6380 6626//6626 6381//6381 -f 6381//6381 6626//6626 6625//6625 -f 6381//6381 6625//6625 6377//6377 -f 6377//6377 6625//6625 6624//6624 -f 6377//6377 6624//6624 6378//6378 -f 6378//6378 6624//6624 6641//6641 -f 6440//6440 6620//6620 6323//6323 -f 6323//6323 6620//6620 6619//6619 -f 6323//6323 6619//6619 6324//6324 -f 6324//6324 6619//6619 6552//6552 -f 6324//6324 6552//6552 6433//6433 -f 6433//6433 6552//6552 6551//6551 -f 6433//6433 6551//6551 6432//6432 -f 6432//6432 6551//6551 6607//6607 -f 6432//6432 6607//6607 6430//6430 -f 6430//6430 6607//6607 6616//6616 -f 6430//6430 6616//6616 6428//6428 -f 6428//6428 6616//6616 6614//6614 -f 6428//6428 6614//6614 6426//6426 -f 6426//6426 6614//6614 6612//6612 -f 6426//6426 6612//6612 6434//6434 -f 6434//6434 6612//6612 6611//6611 -f 6434//6434 6611//6611 6435//6435 -f 6435//6435 6611//6611 6610//6610 -f 6435//6435 6610//6610 6437//6437 -f 6437//6437 6610//6610 6622//6622 -f 6437//6437 6622//6622 6439//6439 -f 6439//6439 6622//6622 6621//6621 -f 6439//6439 6621//6621 6440//6440 -f 6440//6440 6621//6621 6620//6620 -f 6360//6360 6604//6604 6362//6362 -f 6362//6362 6604//6604 6603//6603 -f 6362//6362 6603//6603 6364//6364 -f 6364//6364 6603//6603 6627//6627 -f 6364//6364 6627//6627 6365//6365 -f 6365//6365 6627//6627 6598//6598 -f 6365//6365 6598//6598 6353//6353 -f 6353//6353 6598//6598 6597//6597 -f 6353//6353 6597//6597 6354//6354 -f 6354//6354 6597//6597 6602//6602 -f 6354//6354 6602//6602 6348//6348 -f 6348//6348 6602//6602 6601//6601 -f 6348//6348 6601//6601 6349//6349 -f 6349//6349 6601//6601 6600//6600 -f 6349//6349 6600//6600 6351//6351 -f 6351//6351 6600//6600 6596//6596 -f 6351//6351 6596//6596 6356//6356 -f 6356//6356 6596//6596 6594//6594 -f 6356//6356 6594//6594 6357//6357 -f 6357//6357 6594//6594 6606//6606 -f 6357//6357 6606//6606 6359//6359 -f 6359//6359 6606//6606 6605//6605 -f 6359//6359 6605//6605 6360//6360 -f 6360//6360 6605//6605 6604//6604 -f 6454//6454 6590//6590 6455//6455 -f 6455//6455 6590//6590 6589//6589 -f 6455//6455 6589//6589 6442//6442 -f 6442//6442 6589//6589 6587//6587 -f 6442//6442 6587//6587 6443//6443 -f 6443//6443 6587//6587 6586//6586 -f 6443//6443 6586//6586 6447//6447 -f 6447//6447 6586//6586 6579//6579 -f 6447//6447 6579//6579 6448//6448 -f 6448//6448 6579//6579 6577//6577 -f 6448//6448 6577//6577 6445//6445 -f 6445//6445 6577//6577 6576//6576 -f 6445//6445 6576//6576 6446//6446 -f 6446//6446 6576//6576 6585//6585 -f 6446//6446 6585//6585 6449//6449 -f 6449//6449 6585//6585 6584//6584 -f 6449//6449 6584//6584 6450//6450 -f 6450//6450 6584//6584 6582//6582 -f 6450//6450 6582//6582 6451//6451 -f 6451//6451 6582//6582 6592//6592 -f 6451//6451 6592//6592 6453//6453 -f 6453//6453 6592//6592 6591//6591 -f 6453//6453 6591//6591 6454//6454 -f 6454//6454 6591//6591 6590//6590 -f 6342//6342 6571//6571 6346//6346 -f 6346//6346 6571//6571 6575//6575 -f 6346//6346 6575//6575 6347//6347 -f 6347//6347 6575//6575 6573//6573 -f 6347//6347 6573//6573 6336//6336 -f 6336//6336 6573//6573 6572//6572 -f 6336//6336 6572//6572 6338//6338 -f 6338//6338 6572//6572 6562//6562 -f 6338//6338 6562//6562 6333//6333 -f 6333//6333 6562//6562 6561//6561 -f 6333//6333 6561//6561 6331//6331 -f 6331//6331 6561//6561 6565//6565 -f 6331//6331 6565//6565 6329//6329 -f 6329//6329 6565//6565 6567//6567 -f 6329//6329 6567//6567 6326//6326 -f 6326//6326 6567//6567 6569//6569 -f 6326//6326 6569//6569 6327//6327 -f 6327//6327 6569//6569 6557//6557 -f 6327//6327 6557//6557 6344//6344 -f 6344//6344 6557//6557 6555//6555 -f 6344//6344 6555//6555 6341//6341 -f 6341//6341 6555//6555 6554//6554 -f 6341//6341 6554//6554 6342//6342 -f 6342//6342 6554//6554 6571//6571 -f 6429//6429 6613//6613 6431//6431 -f 6431//6431 6613//6613 6615//6615 -f 6431//6431 6615//6615 6512//6512 -f 6512//6512 6615//6615 6697//6697 -f 6512//6512 6697//6697 6498//6498 -f 6498//6498 6697//6697 6701//6701 -f 6498//6498 6701//6701 6471//6471 -f 6471//6471 6701//6701 6719//6719 -f 6471//6471 6719//6719 6330//6330 -f 6330//6330 6719//6719 6568//6568 -f 6330//6330 6568//6568 6332//6332 -f 6332//6332 6568//6568 6566//6566 -f 6709//6709 6513//6513 6710//6710 -f 6710//6710 6513//6513 6514//6514 -f 6710//6710 6514//6514 6705//6705 -f 6705//6705 6514//6514 6524//6524 -f 6705//6705 6524//6524 6702//6702 -f 6702//6702 6524//6524 6523//6523 -f 6702//6702 6523//6523 6703//6703 -f 6703//6703 6523//6523 6522//6522 -f 6703//6703 6522//6522 6706//6706 -f 6706//6706 6522//6522 6521//6521 -f 6706//6706 6521//6521 6707//6707 -f 6707//6707 6521//6521 6520//6520 -f 6707//6707 6520//6520 6708//6708 -f 6708//6708 6520//6520 6519//6519 -f 6708//6708 6519//6519 6699//6699 -f 6699//6699 6519//6519 6516//6516 -f 6699//6699 6516//6516 6700//6700 -f 6700//6700 6516//6516 6515//6515 -f 6700//6700 6515//6515 6695//6695 -f 6695//6695 6515//6515 6518//6518 -f 6695//6695 6518//6518 6696//6696 -f 6696//6696 6518//6518 6511//6511 -f 6696//6696 6511//6511 6709//6709 -f 6709//6709 6511//6511 6513//6513 -f 6718//6718 6497//6497 6720//6720 -f 6720//6720 6497//6497 6499//6499 -f 6720//6720 6499//6499 6721//6721 -f 6721//6721 6499//6499 6510//6510 -f 6721//6721 6510//6510 6713//6713 -f 6713//6713 6510//6510 6509//6509 -f 6713//6713 6509//6509 6714//6714 -f 6714//6714 6509//6509 6508//6508 -f 6714//6714 6508//6508 6722//6722 -f 6722//6722 6508//6508 6500//6500 -f 6722//6722 6500//6500 6723//6723 -f 6723//6723 6500//6500 6501//6501 -f 6723//6723 6501//6501 6724//6724 -f 6724//6724 6501//6501 6503//6503 -f 6724//6724 6503//6503 6711//6711 -f 6711//6711 6503//6503 6504//6504 -f 6711//6711 6504//6504 6712//6712 -f 6712//6712 6504//6504 6507//6507 -f 6712//6712 6507//6507 6716//6716 -f 6716//6716 6507//6507 6506//6506 -f 6716//6716 6506//6506 6717//6717 -f 6717//6717 6506//6506 6505//6505 -f 6717//6717 6505//6505 6718//6718 -f 6718//6718 6505//6505 6497//6497 -f 6613//6613 6429//6429 6427//6427 -f 6613//6613 6427//6427 6608//6608 -f 6608//6608 6427//6427 6468//6468 -f 6608//6608 6468//6468 6690//6690 -f 6690//6690 6468//6468 6467//6467 -f 6690//6690 6467//6467 6689//6689 -f 6689//6689 6467//6467 6469//6469 -f 6689//6689 6469//6469 6688//6688 -f 6563//6563 6337//6337 6339//6339 -f 6563//6563 6339//6339 6558//6558 -f 6558//6558 6339//6339 6340//6340 -f 6558//6558 6340//6340 6559//6559 -f 6559//6559 6340//6340 6334//6334 -f 6559//6559 6334//6334 6560//6560 -f 6560//6560 6334//6334 6332//6332 -f 6560//6560 6332//6332 6566//6566 -f 6755//6755 6756//6756 6757//6757 -f 6757//6757 6756//6756 6758//6758 -f 6757//6757 6758//6758 6759//6759 -f 6759//6759 6758//6758 6760//6760 -f 6759//6759 6760//6760 6761//6761 -f 6761//6761 6760//6760 6762//6762 -f 6761//6761 6762//6762 6763//6763 -f 6763//6763 6762//6762 6764//6764 -f 6763//6763 6764//6764 6765//6765 -f 6765//6765 6764//6764 6766//6766 -f 6765//6765 6766//6766 6767//6767 -f 6767//6767 6766//6766 6768//6768 -f 6769//6769 6770//6770 6771//6771 -f 6771//6771 6770//6770 6772//6772 -f 6771//6771 6772//6772 6773//6773 -f 6773//6773 6772//6772 6774//6774 -f 6773//6773 6774//6774 6775//6775 -f 6775//6775 6774//6774 6776//6776 -f 6775//6775 6776//6776 6777//6777 -f 6777//6777 6776//6776 6778//6778 -f 6779//6779 6780//6780 6781//6781 -f 6781//6781 6780//6780 6782//6782 -f 6781//6781 6782//6782 6783//6783 -f 6783//6783 6782//6782 6784//6784 -f 6785//6785 6786//6786 6787//6787 -f 6787//6787 6786//6786 6788//6788 -f 6787//6787 6788//6788 6789//6789 -f 6789//6789 6788//6788 6790//6790 -f 6791//6791 6792//6792 6793//6793 -f 6793//6793 6792//6792 6794//6794 -f 6793//6793 6794//6794 6795//6795 -f 6795//6795 6794//6794 6796//6796 -f 6797//6797 6798//6798 6799//6799 -f 6800//6800 6801//6801 6792//6792 -f 6802//6802 6803//6803 6804//6804 -f 6758//6758 6805//6805 6806//6806 -f 6807//6807 6808//6808 6809//6809 -f 6809//6809 6808//6808 6810//6810 -f 6811//6811 6812//6812 6813//6813 -f 6814//6814 6815//6815 6816//6816 -f 6816//6816 6815//6815 6813//6813 -f 6816//6816 6813//6813 6817//6817 -f 6817//6817 6813//6813 6812//6812 -f 6814//6814 6818//6818 6815//6815 -f 6815//6815 6818//6818 6819//6819 -f 6815//6815 6819//6819 6820//6820 -f 6820//6820 6819//6819 6821//6821 -f 6820//6820 6821//6821 6822//6822 -f 6822//6822 6821//6821 6823//6823 -f 6822//6822 6823//6823 6807//6807 -f 6807//6807 6823//6823 6824//6824 -f 6807//6807 6824//6824 6808//6808 -f 6825//6825 6826//6826 6827//6827 -f 6828//6828 6829//6829 6830//6830 -f 6831//6831 6832//6832 6833//6833 -f 6833//6833 6832//6832 6834//6834 -f 6833//6833 6834//6834 6835//6835 -f 6830//6830 6829//6829 6834//6834 -f 6834//6834 6829//6829 6836//6836 -f 6834//6834 6836//6836 6835//6835 -f 6831//6831 6837//6837 6832//6832 -f 6832//6832 6837//6837 6838//6838 -f 6832//6832 6838//6838 6839//6839 -f 6825//6825 6827//6827 6840//6840 -f 6840//6840 6827//6827 6841//6841 -f 6840//6840 6841//6841 6842//6842 -f 6843//6843 6844//6844 6845//6845 -f 6844//6844 6846//6846 6845//6845 -f 6845//6845 6846//6846 6847//6847 -f 6845//6845 6847//6847 6794//6794 -f 6848//6848 6849//6849 6850//6850 -f 6850//6850 6849//6849 6851//6851 -f 6847//6847 6852//6852 6794//6794 -f 6794//6794 6852//6852 6853//6853 -f 6794//6794 6853//6853 6796//6796 -f 6796//6796 6853//6853 6854//6854 -f 6796//6796 6854//6854 6855//6855 -f 6855//6855 6854//6854 6856//6856 -f 6855//6855 6856//6856 6857//6857 -f 6857//6857 6856//6856 6858//6858 -f 6857//6857 6858//6858 6851//6851 -f 6851//6851 6849//6849 6857//6857 -f 6857//6857 6849//6849 6859//6859 -f 6857//6857 6859//6859 6860//6860 -f 6860//6860 6859//6859 6861//6861 -f 6860//6860 6861//6861 6862//6862 -f 6861//6861 6863//6863 6864//6864 -f 6862//6862 6861//6861 6865//6865 -f 6865//6865 6861//6861 6864//6864 -f 6865//6865 6864//6864 6866//6866 -f 6867//6867 6868//6868 6869//6869 -f 6870//6870 6871//6871 6872//6872 -f 6869//6869 6873//6873 6867//6867 -f 6867//6867 6873//6873 6874//6874 -f 6867//6867 6874//6874 6871//6871 -f 6871//6871 6874//6874 6875//6875 -f 6871//6871 6875//6875 6872//6872 -f 6872//6872 6876//6876 6870//6870 -f 6870//6870 6876//6876 6877//6877 -f 6870//6870 6877//6877 6839//6839 -f 6839//6839 6877//6877 6878//6878 -f 6839//6839 6878//6878 6879//6879 -f 6863//6863 6861//6861 6867//6867 -f 6867//6867 6861//6861 6880//6880 -f 6867//6867 6880//6880 6868//6868 -f 6881//6881 6882//6882 6861//6861 -f 6861//6861 6882//6882 6883//6883 -f 6861//6861 6883//6883 6880//6880 -f 6838//6838 6842//6842 6839//6839 -f 6839//6839 6842//6842 6841//6841 -f 6839//6839 6841//6841 6870//6870 -f 6870//6870 6841//6841 6884//6884 -f 6870//6870 6884//6884 6885//6885 -f 6885//6885 6884//6884 6886//6886 -f 6886//6886 6884//6884 6887//6887 -f 6886//6886 6887//6887 6888//6888 -f 6888//6888 6887//6887 6889//6889 -f 6889//6889 6887//6887 6890//6890 -f 6889//6889 6890//6890 6806//6806 -f 6891//6891 6892//6892 6805//6805 -f 6805//6805 6892//6892 6893//6893 -f 6806//6806 6894//6894 6895//6895 -f 6896//6896 6889//6889 6897//6897 -f 6806//6806 6895//6895 6889//6889 -f 6889//6889 6895//6895 6898//6898 -f 6889//6889 6898//6898 6897//6897 -f 6893//6893 6899//6899 6805//6805 -f 6805//6805 6899//6899 6900//6900 -f 6805//6805 6900//6900 6806//6806 -f 6806//6806 6900//6900 6901//6901 -f 6806//6806 6901//6901 6894//6894 -f 6897//6897 6902//6902 6896//6896 -f 6896//6896 6902//6902 6903//6903 -f 6896//6896 6903//6903 6904//6904 -f 6904//6904 6903//6903 6905//6905 -f 6904//6904 6905//6905 6906//6906 -f 6906//6906 6891//6891 6904//6904 -f 6904//6904 6891//6891 6805//6805 -f 6904//6904 6805//6805 6907//6907 -f 6907//6907 6805//6805 6908//6908 -f 6909//6909 6908//6908 6910//6910 -f 6910//6910 6908//6908 6805//6805 -f 6910//6910 6805//6805 6756//6756 -f 6756//6756 6805//6805 6758//6758 -f 6911//6911 6912//6912 6913//6913 -f 6913//6913 6912//6912 6914//6914 -f 6914//6914 6915//6915 6913//6913 -f 6913//6913 6915//6915 6916//6916 -f 6913//6913 6916//6916 6917//6917 -f 6918//6918 6919//6919 6920//6920 -f 6921//6921 6922//6922 6919//6919 -f 6916//6916 6923//6923 6917//6917 -f 6917//6917 6923//6923 6924//6924 -f 6917//6917 6924//6924 6921//6921 -f 6921//6921 6924//6924 6925//6925 -f 6921//6921 6925//6925 6922//6922 -f 6762//6762 6760//6760 6918//6918 -f 6926//6926 6766//6766 6927//6927 -f 6927//6927 6766//6766 6764//6764 -f 6764//6764 6762//6762 6927//6927 -f 6927//6927 6762//6762 6918//6918 -f 6927//6927 6918//6918 6928//6928 -f 6928//6928 6918//6918 6920//6920 -f 6929//6929 6930//6930 6768//6768 -f 6931//6931 6929//6929 6932//6932 -f 6932//6932 6929//6929 6768//6768 -f 6932//6932 6768//6768 6913//6913 -f 6913//6913 6768//6768 6766//6766 -f 6913//6913 6766//6766 6911//6911 -f 6911//6911 6766//6766 6926//6926 -f 6933//6933 6934//6934 6799//6799 -f 6799//6799 6934//6934 6935//6935 -f 6799//6799 6935//6935 6921//6921 -f 6936//6936 6937//6937 6813//6813 -f 6813//6813 6937//6937 6809//6809 -f 6813//6813 6809//6809 6811//6811 -f 6811//6811 6809//6809 6810//6810 -f 6938//6938 6939//6939 6813//6813 -f 6940//6940 6941//6941 6942//6942 -f 6943//6943 6944//6944 6945//6945 -f 6938//6938 6813//6813 6946//6946 -f 6943//6943 6945//6945 6947//6947 -f 6939//6939 6948//6948 6813//6813 -f 6813//6813 6948//6948 6949//6949 -f 6813//6813 6949//6949 6936//6936 -f 6936//6936 6949//6949 6950//6950 -f 6936//6936 6950//6950 6951//6951 -f 6950//6950 6952//6952 6951//6951 -f 6951//6951 6952//6952 6953//6953 -f 6951//6951 6953//6953 6940//6940 -f 6940//6940 6953//6953 6954//6954 -f 6940//6940 6954//6954 6941//6941 -f 6945//6945 6770//6770 6955//6955 -f 6942//6942 6947//6947 6940//6940 -f 6940//6940 6947//6947 6945//6945 -f 6940//6940 6945//6945 6956//6956 -f 6956//6956 6945//6945 6955//6955 -f 6956//6956 6955//6955 6957//6957 -f 6770//6770 6945//6945 6772//6772 -f 6772//6772 6945//6945 6958//6958 -f 6772//6772 6958//6958 6774//6774 -f 6774//6774 6958//6958 6959//6959 -f 6774//6774 6959//6959 6776//6776 -f 6960//6960 6961//6961 6959//6959 -f 6959//6959 6961//6961 6962//6962 -f 6959//6959 6962//6962 6776//6776 -f 6776//6776 6962//6962 6963//6963 -f 6776//6776 6963//6963 6778//6778 -f 6778//6778 6963//6963 6964//6964 -f 6778//6778 6964//6964 6783//6783 -f 6783//6783 6964//6964 6965//6965 -f 6783//6783 6965//6965 6781//6781 -f 6966//6966 6967//6967 6968//6968 -f 6968//6968 6967//6967 6781//6781 -f 6968//6968 6781//6781 6969//6969 -f 6969//6969 6781//6781 6965//6965 -f 6966//6966 6970//6970 6967//6967 -f 6967//6967 6970//6970 6971//6971 -f 6967//6967 6971//6971 6959//6959 -f 6959//6959 6971//6971 6972//6972 -f 6959//6959 6972//6972 6960//6960 -f 6973//6973 6974//6974 6967//6967 -f 6975//6975 6976//6976 6977//6977 -f 6977//6977 6976//6976 6779//6779 -f 6977//6977 6779//6779 6978//6978 -f 6978//6978 6779//6779 6781//6781 -f 6975//6975 6979//6979 6976//6976 -f 6976//6976 6979//6979 6980//6980 -f 6976//6976 6980//6980 6981//6981 -f 6981//6981 6980//6980 6982//6982 -f 6981//6981 6982//6982 6983//6983 -f 6974//6974 6984//6984 6967//6967 -f 6967//6967 6984//6984 6985//6985 -f 6967//6967 6985//6985 6781//6781 -f 6781//6781 6985//6985 6986//6986 -f 6781//6781 6986//6986 6978//6978 -f 6987//6987 6988//6988 6981//6981 -f 6981//6981 6988//6988 6989//6989 -f 6989//6989 6990//6990 6981//6981 -f 6981//6981 6990//6990 6991//6991 -f 6981//6981 6991//6991 6976//6976 -f 6976//6976 6991//6991 6992//6992 -f 6976//6976 6992//6992 6993//6993 -f 6994//6994 6987//6987 6967//6967 -f 6967//6967 6987//6987 6981//6981 -f 6967//6967 6981//6981 6973//6973 -f 6973//6973 6981//6981 6983//6983 -f 6790//6790 6788//6788 6959//6959 -f 6959//6959 6788//6788 6967//6967 -f 6967//6967 6788//6788 6786//6786 -f 6967//6967 6786//6786 6994//6994 -f 6995//6995 6996//6996 6807//6807 -f 6807//6807 6996//6996 6997//6997 -f 6807//6807 6997//6997 6822//6822 -f 6822//6822 6997//6997 6998//6998 -f 6822//6822 6998//6998 6820//6820 -f 6999//6999 7000//7000 7001//7001 -f 7001//7001 7000//7000 7002//7002 -f 7001//7001 7002//7002 6995//6995 -f 6995//6995 7002//7002 7003//7003 -f 6995//6995 7003//7003 6996//6996 -f 7004//7004 7005//7005 7001//7001 -f 6999//6999 7001//7001 7006//7006 -f 7006//7006 7001//7001 7007//7007 -f 7006//7006 7007//7007 7008//7008 -f 7009//7009 7010//7010 7011//7011 -f 7005//7005 7012//7012 7001//7001 -f 7001//7001 7012//7012 7013//7013 -f 7001//7001 7013//7013 7007//7007 -f 7008//7008 7014//7014 7006//7006 -f 7006//7006 7014//7014 7015//7015 -f 7006//7006 7015//7015 7016//7016 -f 7016//7016 7015//7015 7017//7017 -f 7016//7016 7017//7017 7018//7018 -f 7018//7018 7017//7017 7019//7019 -f 7018//7018 7019//7019 7009//7009 -f 7009//7009 7011//7011 7018//7018 -f 7018//7018 7011//7011 7020//7020 -f 7018//7018 7020//7020 7021//7021 -f 7022//7022 7023//7023 7024//7024 -f 7023//7023 7022//7022 7025//7025 -f 7026//7026 7027//7027 7025//7025 -f 7025//7025 7027//7027 7028//7028 -f 7025//7025 7028//7028 7023//7023 -f 6804//6804 7029//7029 7030//7030 -f 7030//7030 7029//7029 7031//7031 -f 7031//7031 7032//7032 7030//7030 -f 7030//7030 7032//7032 7033//7033 -f 7030//7030 7033//7033 7034//7034 -f 7034//7034 7033//7033 7035//7035 -f 7034//7034 7035//7035 7025//7025 -f 7025//7025 7035//7035 7036//7036 -f 7025//7025 7036//7036 7026//7026 -f 6804//6804 6803//6803 7029//7029 -f 7029//7029 6803//6803 7037//7037 -f 7029//7029 7037//7037 7038//7038 -f 7039//7039 7030//7030 7040//7040 -f 7041//7041 6802//6802 7042//7042 -f 7042//7042 6802//6802 6804//6804 -f 7042//7042 6804//6804 7043//7043 -f 7043//7043 6804//6804 7030//7030 -f 7043//7043 7030//7030 7044//7044 -f 7044//7044 7030//7030 7039//7039 -f 7045//7045 7046//7046 7047//7047 -f 7047//7047 7046//7046 7048//7048 -f 7048//7048 7049//7049 7047//7047 -f 7047//7047 7049//7049 7050//7050 -f 7047//7047 7050//7050 7051//7051 -f 7051//7051 7050//7050 7052//7052 -f 7051//7051 7052//7052 7040//7040 -f 7040//7040 7052//7052 7053//7053 -f 7040//7040 7053//7053 7039//7039 -f 7054//7054 7055//7055 7056//7056 -f 7057//7057 7058//7058 7059//7059 -f 7059//7059 7058//7058 7060//7060 -f 7061//7061 7062//7062 7054//7054 -f 7063//7063 7064//7064 7065//7065 -f 7062//7062 7066//7066 7054//7054 -f 7054//7054 7066//7066 7067//7067 -f 7054//7054 7067//7067 7055//7055 -f 7055//7055 7067//7067 7068//7068 -f 7055//7055 7068//7068 7069//7069 -f 7069//7069 7068//7068 7070//7070 -f 7069//7069 7070//7070 7063//7063 -f 7063//7063 7070//7070 7071//7071 -f 7063//7063 7071//7071 7064//7064 -f 7059//7059 7072//7072 7073//7073 -f 7065//7065 7057//7057 7063//7063 -f 7063//7063 7057//7057 7059//7059 -f 7063//7063 7059//7059 7074//7074 -f 7074//7074 7059//7059 7073//7073 -f 7075//7075 7076//7076 7077//7077 -f 7078//7078 7079//7079 7080//7080 -f 7081//7081 6827//6827 6830//6830 -f 6830//6830 6827//6827 6826//6826 -f 6830//6830 6826//6826 6828//6828 -f 7081//7081 7082//7082 6827//6827 -f 6827//6827 7082//7082 7083//7083 -f 6827//6827 7083//7083 7084//7084 -f 7078//7078 7080//7080 7085//7085 -f 7086//7086 7087//7087 7080//7080 -f 7080//7080 7087//7087 7088//7088 -f 7080//7080 7088//7088 7059//7059 -f 7059//7059 7088//7088 7089//7089 -f 7059//7059 7089//7089 7072//7072 -f 7079//7079 7090//7090 7080//7080 -f 7080//7080 7090//7090 7091//7091 -f 7080//7080 7091//7091 7086//7086 -f 7086//7086 7091//7091 7092//7092 -f 7086//7086 7092//7092 7076//7076 -f 7076//7076 7092//7092 7093//7093 -f 7076//7076 7093//7093 7077//7077 -f 7094//7094 7095//7095 6834//6834 -f 6834//6834 7095//7095 7096//7096 -f 6834//6834 7096//7096 6830//6830 -f 6830//6830 7096//7096 7075//7075 -f 6830//6830 7075//7075 7081//7081 -f 7081//7081 7075//7075 7077//7077 -f 7097//7097 7098//7098 6845//6845 -f 6845//6845 7098//7098 6849//6849 -f 6845//6845 6849//6849 6843//6843 -f 6843//6843 6849//6849 6848//6848 -f 6845//6845 7099//7099 7100//7100 -f 7097//7097 6845//6845 7101//7101 -f 7101//7101 6845//6845 7100//7100 -f 7101//7101 7100//7100 7102//7102 -f 6792//6792 6801//6801 6794//6794 -f 7103//7103 7104//7104 6845//6845 -f 6801//6801 7105//7105 6794//6794 -f 6794//6794 7105//7105 7106//7106 -f 6794//6794 7106//7106 6845//6845 -f 6845//6845 7106//7106 7107//7107 -f 6845//6845 7107//7107 7103//7103 -f 7104//7104 7108//7108 6845//6845 -f 6845//6845 7108//7108 7109//7109 -f 6845//6845 7109//7109 7099//7099 -f 7108//7108 7110//7110 7109//7109 -f 7109//7109 7110//7110 7111//7111 -f 7109//7109 7111//7111 7112//7112 -f 7111//7111 7113//7113 7112//7112 -f 7112//7112 7113//7113 7114//7114 -f 7112//7112 7114//7114 7115//7115 -f 7115//7115 7114//7114 6800//6800 -f 7115//7115 6800//6800 7116//7116 -f 7116//7116 6800//6800 6792//6792 -f 7098//7098 7094//7094 6849//6849 -f 6849//6849 7094//7094 6834//6834 -f 6849//6849 6834//6834 6859//6859 -f 6859//6859 6834//6834 6832//6832 -f 6859//6859 6832//6832 6861//6861 -f 6861//6861 6832//6832 6839//6839 -f 6861//6861 6839//6839 6881//6881 -f 6881//6881 6839//6839 6879//6879 -f 7060//7060 7061//7061 7059//7059 -f 7059//7059 7061//7061 7054//7054 -f 7059//7059 7054//7054 7080//7080 -f 7080//7080 7054//7054 7117//7117 -f 7080//7080 7117//7117 7045//7045 -f 7045//7045 7117//7117 7118//7118 -f 7045//7045 7118//7118 7046//7046 -f 7046//7046 7118//7118 7119//7119 -f 7046//7046 7119//7119 7120//7120 -f 7056//7056 7121//7121 7054//7054 -f 7054//7054 7121//7121 7122//7122 -f 7054//7054 7122//7122 7117//7117 -f 7117//7117 7122//7122 7123//7123 -f 7117//7117 7123//7123 7118//7118 -f 7118//7118 7123//7123 7124//7124 -f 7118//7118 7124//7124 7119//7119 -f 7047//7047 7125//7125 7126//7126 -f 7127//7127 7128//7128 6884//6884 -f 7129//7129 6887//6887 7130//7130 -f 7130//7130 6887//6887 6884//6884 -f 7130//7130 6884//6884 7131//7131 -f 7131//7131 6884//6884 7128//7128 -f 7132//7132 7133//7133 7051//7051 -f 7051//7051 7133//7133 7134//7134 -f 7051//7051 7134//7134 7135//7135 -f 7126//7126 7127//7127 7047//7047 -f 7047//7047 7127//7127 6884//6884 -f 7047//7047 6884//6884 7045//7045 -f 7045//7045 6884//6884 6841//6841 -f 7045//7045 6841//6841 7080//7080 -f 7080//7080 6841//6841 6827//6827 -f 7080//7080 6827//6827 7085//7085 -f 7085//7085 6827//6827 7084//7084 -f 7135//7135 7136//7136 7051//7051 -f 7051//7051 7136//7136 7137//7137 -f 7051//7051 7137//7137 7047//7047 -f 7047//7047 7137//7137 7138//7138 -f 7047//7047 7138//7138 7125//7125 -f 7040//7040 7139//7139 7140//7140 -f 7141//7141 7142//7142 6890//6890 -f 7142//7142 7143//7143 6890//6890 -f 6890//6890 7143//7143 7144//7144 -f 6890//6890 7144//7144 7145//7145 -f 7140//7140 7141//7141 7040//7040 -f 7040//7040 7141//7141 6890//6890 -f 7040//7040 6890//6890 7051//7051 -f 7051//7051 6890//6890 6887//6887 -f 7051//7051 6887//6887 7132//7132 -f 7132//7132 6887//6887 7129//7129 -f 7145//7145 7146//7146 6890//6890 -f 6890//6890 7146//7146 6918//6918 -f 6890//6890 6918//6918 6806//6806 -f 6806//6806 6918//6918 6760//6760 -f 6806//6806 6760//6760 6758//6758 -f 7145//7145 7147//7147 7146//7146 -f 7146//7146 7147//7147 7148//7148 -f 7146//7146 7148//7148 7030//7030 -f 7030//7030 7148//7148 7149//7149 -f 7030//7030 7149//7149 7150//7150 -f 7150//7150 7151//7151 7030//7030 -f 7030//7030 7151//7151 7152//7152 -f 7030//7030 7152//7152 7040//7040 -f 7040//7040 7152//7152 7153//7153 -f 7040//7040 7153//7153 7139//7139 -f 7154//7154 7155//7155 7030//7030 -f 6919//6919 6918//6918 6921//6921 -f 6921//6921 6918//6918 7146//7146 -f 6921//6921 7146//7146 6799//6799 -f 6799//6799 7146//7146 7156//7156 -f 6799//6799 7156//7156 7157//7157 -f 7158//7158 7034//7034 7159//7159 -f 7159//7159 7034//7034 7160//7160 -f 7030//7030 7155//7155 7146//7146 -f 7146//7146 7155//7155 7161//7161 -f 7146//7146 7161//7161 7156//7156 -f 7157//7157 7162//7162 6799//6799 -f 6799//6799 7162//7162 7163//7163 -f 6799//6799 7163//7163 7034//7034 -f 7034//7034 7163//7163 7164//7164 -f 7034//7034 7164//7164 7160//7160 -f 7158//7158 7165//7165 7034//7034 -f 7034//7034 7165//7165 7166//7166 -f 7034//7034 7166//7166 7030//7030 -f 7030//7030 7166//7166 7167//7167 -f 7030//7030 7167//7167 7154//7154 -f 7168//7168 7169//7169 7025//7025 -f 6933//6933 6799//6799 7170//7170 -f 7170//7170 6799//6799 6798//6798 -f 7170//7170 6798//6798 7171//7171 -f 7171//7171 7172//7172 7170//7170 -f 7170//7170 7172//7172 7173//7173 -f 7170//7170 7173//7173 7025//7025 -f 7025//7025 7173//7173 7174//7174 -f 7025//7025 7174//7174 7168//7168 -f 7169//7169 7175//7175 7025//7025 -f 7025//7025 7175//7175 7176//7176 -f 7025//7025 7176//7176 7034//7034 -f 7034//7034 7176//7176 7177//7177 -f 7034//7034 7177//7177 7178//7178 -f 7178//7178 7179//7179 7034//7034 -f 7034//7034 7179//7179 7180//7180 -f 7034//7034 7180//7180 6799//6799 -f 6799//6799 7180//7180 7181//7181 -f 6799//6799 7181//7181 6797//6797 -f 6807//6807 7182//7182 7183//7183 -f 7184//7184 6995//6995 7185//7185 -f 7185//7185 6995//6995 6807//6807 -f 7185//7185 6807//6807 7186//7186 -f 7186//7186 6807//6807 7183//7183 -f 7182//7182 6807//6807 7187//7187 -f 7187//7187 6807//6807 6809//6809 -f 7187//7187 6809//6809 7188//7188 -f 7188//7188 6809//6809 7189//7189 -f 7189//7189 6809//6809 7190//7190 -f 7189//7189 7190//7190 7191//7191 -f 7184//7184 7192//7192 6995//6995 -f 6995//6995 7192//7192 7193//7193 -f 6995//6995 7193//7193 7190//7190 -f 7190//7190 7193//7193 7194//7194 -f 7190//7190 7194//7194 7191//7191 -f 6944//6944 6946//6946 6945//6945 -f 6945//6945 6946//6946 6813//6813 -f 6945//6945 6813//6813 6958//6958 -f 6958//6958 6813//6813 6815//6815 -f 6958//6958 6815//6815 6959//6959 -f 6959//6959 6815//6815 6820//6820 -f 6959//6959 6820//6820 6790//6790 -f 6790//6790 6820//6820 6998//6998 -f 7010//7010 7004//7004 7011//7011 -f 7011//7011 7004//7004 7001//7001 -f 7011//7011 7001//7001 7195//7195 -f 7195//7195 7001//7001 6995//6995 -f 7195//7195 6995//6995 7022//7022 -f 7022//7022 6995//6995 7190//7190 -f 7022//7022 7190//7190 7025//7025 -f 7025//7025 7190//7190 6809//6809 -f 7025//7025 6809//6809 7170//7170 -f 7170//7170 6809//6809 6937//6937 -f 7170//7170 6937//6937 6933//6933 -f 7024//7024 7196//7196 7022//7022 -f 7022//7022 7196//7196 7197//7197 -f 7022//7022 7197//7197 7195//7195 -f 7195//7195 7197//7197 7198//7198 -f 7195//7195 7198//7198 7011//7011 -f 7011//7011 7198//7198 7199//7199 -f 7011//7011 7199//7199 7020//7020 -f 7200//7200 7201//7201 7202//7202 -f 7203//7203 7204//7204 7205//7205 -f 7206//7206 7207//7207 7208//7208 -f 7209//7209 7210//7210 7211//7211 -f 7212//7212 7213//7213 7214//7214 -f 7215//7215 7216//7216 7217//7217 -f 7218//7218 7219//7219 7220//7220 -f 7221//7221 7222//7222 7223//7223 -f 7224//7224 7225//7225 7226//7226 -f 7227//7227 7205//7205 7228//7228 -f 7228//7228 7229//7229 7230//7230 -f 7230//7230 7231//7231 7228//7228 -f 7228//7228 7231//7231 7232//7232 -f 7228//7228 7232//7232 7227//7227 -f 7225//7225 7233//7233 7234//7234 -f 7234//7234 7233//7233 7228//7228 -f 7228//7228 7233//7233 7235//7235 -f 7228//7228 7235//7235 7229//7229 -f 7236//7236 7237//7237 7238//7238 -f 7239//7239 7240//7240 7241//7241 -f 7241//7241 7240//7240 7237//7237 -f 7239//7239 7241//7241 7242//7242 -f 7242//7242 7241//7241 7243//7243 -f 7242//7242 7243//7243 7244//7244 -f 7245//7245 7246//7246 7247//7247 -f 7247//7247 7246//7246 7248//7248 -f 7247//7247 7248//7248 7243//7243 -f 7243//7243 7248//7248 7249//7249 -f 7243//7243 7249//7249 7244//7244 -f 7238//7238 7250//7250 7236//7236 -f 7236//7236 7250//7250 7251//7251 -f 7236//7236 7251//7251 7252//7252 -f 7252//7252 7251//7251 7245//7245 -f 7252//7252 7245//7245 7253//7253 -f 7253//7253 7245//7245 7247//7247 -f 7254//7254 7255//7255 7256//7256 -f 7256//7256 7255//7255 7257//7257 -f 7256//7256 7257//7257 7241//7241 -f 7241//7241 7257//7257 7258//7258 -f 7241//7241 7258//7258 7243//7243 -f 7259//7259 7260//7260 7261//7261 -f 7261//7261 7260//7260 7262//7262 -f 7261//7261 7262//7262 7263//7263 -f 7264//7264 7265//7265 7256//7256 -f 7256//7256 7265//7265 7266//7266 -f 7256//7256 7266//7266 7267//7267 -f 7268//7268 7254//7254 7269//7269 -f 7269//7269 7254//7254 7256//7256 -f 7269//7269 7256//7256 7270//7270 -f 7270//7270 7256//7256 7267//7267 -f 7270//7270 7267//7267 7271//7271 -f 7271//7271 7272//7272 7270//7270 -f 7270//7270 7272//7272 7273//7273 -f 7270//7270 7273//7273 7274//7274 -f 7274//7274 7273//7273 7275//7275 -f 7274//7274 7275//7275 7259//7259 -f 7259//7259 7275//7275 7276//7276 -f 7259//7259 7276//7276 7260//7260 -f 7277//7277 7278//7278 7279//7279 -f 7279//7279 7278//7278 7280//7280 -f 7281//7281 7282//7282 7283//7283 -f 7283//7283 7282//7282 7284//7284 -f 7283//7283 7284//7284 7285//7285 -f 7223//7223 7286//7286 7287//7287 -f 7287//7287 7286//7286 7288//7288 -f 7288//7288 7289//7289 7287//7287 -f 7287//7287 7289//7289 7290//7290 -f 7287//7287 7290//7290 7201//7201 -f 7223//7223 7222//7222 7286//7286 -f 7286//7286 7222//7222 7291//7291 -f 7286//7286 7291//7291 7292//7292 -f 7293//7293 7287//7287 7294//7294 -f 7295//7295 7221//7221 7296//7296 -f 7296//7296 7221//7221 7223//7223 -f 7296//7296 7223//7223 7297//7297 -f 7297//7297 7223//7223 7287//7287 -f 7297//7297 7287//7287 7298//7298 -f 7298//7298 7287//7287 7293//7293 -f 7299//7299 7300//7300 7301//7301 -f 7300//7300 7302//7302 7301//7301 -f 7301//7301 7302//7302 7303//7303 -f 7301//7301 7303//7303 7294//7294 -f 7294//7294 7303//7303 7304//7304 -f 7294//7294 7304//7304 7293//7293 -f 7305//7305 7306//7306 7307//7307 -f 7307//7307 7306//7306 7308//7308 -f 7309//7309 7310//7310 7307//7307 -f 7307//7307 7310//7310 7311//7311 -f 7307//7307 7311//7311 7305//7305 -f 7305//7305 7311//7311 7312//7312 -f 7305//7305 7312//7312 7313//7313 -f 7313//7313 7312//7312 7314//7314 -f 7313//7313 7314//7314 7315//7315 -f 7315//7315 7314//7314 7316//7316 -f 7317//7317 7318//7318 7319//7319 -f 7319//7319 7318//7318 7320//7320 -f 7319//7319 7320//7320 7321//7321 -f 7316//7316 7322//7322 7315//7315 -f 7315//7315 7322//7322 7323//7323 -f 7315//7315 7323//7323 7317//7317 -f 7319//7319 7324//7324 7325//7325 -f 7317//7317 7319//7319 7315//7315 -f 7315//7315 7319//7319 7325//7325 -f 7315//7315 7325//7325 7326//7326 -f 7219//7219 7218//7218 7327//7327 -f 7324//7324 7319//7319 7328//7328 -f 7328//7328 7319//7319 7329//7329 -f 7328//7328 7329//7329 7330//7330 -f 6787//6787 7331//7331 6785//6785 -f 6785//6785 7331//7331 7332//7332 -f 6785//6785 7332//7332 7333//7333 -f 7333//7333 7332//7332 7334//7334 -f 7335//7335 7336//7336 7334//7334 -f 7337//7337 7336//7336 7338//7338 -f 7338//7338 7336//7336 7335//7335 -f 7338//7338 7335//7335 7339//7339 -f 7339//7339 7335//7335 7340//7340 -f 7341//7341 7342//7342 7335//7335 -f 7335//7335 7342//7342 7343//7343 -f 7334//7334 7332//7332 7335//7335 -f 7335//7335 7332//7332 7344//7344 -f 7335//7335 7344//7344 7341//7341 -f 7343//7343 7345//7345 7335//7335 -f 7335//7335 7345//7345 7346//7346 -f 7335//7335 7346//7346 7340//7340 -f 7340//7340 7346//7346 7347//7347 -f 7348//7348 6782//6782 7349//7349 -f 7349//7349 6782//6782 6780//6780 -f 7349//7349 6780//6780 7350//7350 -f 7350//7350 6780//6780 7346//7346 -f 7350//7350 7346//7346 7351//7351 -f 7351//7351 7346//7346 7345//7345 -f 7352//7352 7353//7353 7332//7332 -f 7332//7332 7353//7353 7354//7354 -f 7332//7332 7354//7354 7344//7344 -f 7355//7355 7356//7356 7331//7331 -f 7331//7331 7356//7356 7357//7357 -f 7331//7331 7357//7357 7332//7332 -f 7332//7332 7357//7357 7358//7358 -f 7332//7332 7358//7358 7359//7359 -f 7359//7359 7360//7360 7332//7332 -f 7332//7332 7360//7360 6782//6782 -f 7332//7332 6782//6782 7352//7352 -f 7352//7352 6782//6782 7348//7348 -f 7360//7360 7361//7361 6782//6782 -f 6782//6782 7361//7361 7362//7362 -f 6782//6782 7362//7362 6784//6784 -f 6784//6784 7362//7362 7363//7363 -f 6784//6784 7363//7363 6777//6777 -f 6777//6777 7363//7363 7364//7364 -f 6777//6777 7364//7364 6775//6775 -f 6775//6775 7364//7364 7365//7365 -f 6775//6775 7365//7365 7366//7366 -f 6769//6769 6771//6771 7367//7367 -f 7367//7367 6771//6771 6773//6773 -f 7367//7367 6773//6773 7368//7368 -f 7368//7368 6773//6773 6775//6775 -f 7368//7368 6775//6775 7331//7331 -f 7331//7331 6775//6775 7366//7366 -f 7331//7331 7366//7366 7355//7355 -f 7367//7367 7369//7369 7370//7370 -f 7370//7370 7371//7371 7367//7367 -f 7367//7367 7371//7371 7372//7372 -f 7367//7367 7372//7372 6769//6769 -f 7216//7216 7373//7373 7374//7374 -f 7374//7374 7375//7375 7216//7216 -f 7216//7216 7375//7375 7376//7376 -f 7216//7216 7376//7376 7217//7217 -f 7376//7376 7377//7377 7217//7217 -f 7217//7217 7377//7377 7378//7378 -f 7217//7217 7378//7378 7379//7379 -f 7379//7379 7380//7380 7367//7367 -f 7380//7380 7381//7381 7367//7367 -f 7367//7367 7381//7381 7382//7382 -f 7367//7367 7382//7382 7369//7369 -f 7369//7369 7382//7382 7383//7383 -f 7369//7369 7383//7383 7384//7384 -f 7384//7384 7385//7385 7369//7369 -f 7369//7369 7385//7385 7386//7386 -f 7369//7369 7386//7386 7373//7373 -f 7373//7373 7386//7386 7387//7387 -f 7373//7373 7387//7387 7374//7374 -f 7212//7212 7388//7388 7213//7213 -f 7213//7213 7388//7388 7389//7389 -f 7213//7213 7389//7389 7390//7390 -f 7391//7391 7392//7392 7212//7212 -f 7212//7212 7392//7392 7393//7393 -f 7212//7212 7393//7393 7394//7394 -f 7395//7395 7396//7396 7397//7397 -f 7397//7397 7396//7396 7398//7398 -f 7393//7393 7399//7399 7394//7394 -f 7394//7394 7399//7399 7400//7400 -f 7394//7394 7400//7400 7397//7397 -f 7397//7397 7400//7400 7401//7401 -f 7397//7397 7401//7401 7395//7395 -f 6757//6757 6759//6759 7402//7402 -f 7402//7402 6759//6759 6761//6761 -f 7398//7398 7403//7403 6765//6765 -f 6765//6765 7403//7403 7404//7404 -f 6765//6765 7404//7404 6763//6763 -f 6763//6763 7404//7404 7405//7405 -f 6763//6763 7405//7405 6761//6761 -f 6761//6761 7405//7405 7406//7406 -f 6761//6761 7406//7406 7402//7402 -f 7402//7402 7406//7406 7407//7407 -f 7402//7402 7407//7407 7391//7391 -f 7408//7408 7409//7409 7410//7410 -f 7398//7398 6765//6765 7397//7397 -f 7397//7397 6765//6765 6767//6767 -f 7397//7397 6767//6767 7410//7410 -f 7410//7410 6767//6767 7411//7411 -f 7410//7410 7411//7411 7408//7408 -f 7412//7412 7413//7413 7414//7414 -f 7414//7414 7413//7413 7415//7415 -f 7414//7414 7415//7415 7416//7416 -f 7417//7417 7418//7418 7419//7419 -f 7414//7414 7420//7420 7421//7421 -f 7412//7412 7414//7414 7422//7422 -f 7422//7422 7414//7414 7421//7421 -f 7422//7422 7421//7421 7423//7423 -f 7424//7424 7425//7425 7210//7210 -f 7210//7210 7425//7425 7426//7426 -f 7210//7210 7426//7426 7427//7427 -f 7419//7419 7428//7428 7417//7417 -f 7417//7417 7428//7428 7429//7429 -f 7417//7417 7429//7429 7414//7414 -f 7414//7414 7429//7429 7430//7430 -f 7414//7414 7430//7430 7420//7420 -f 7423//7423 7431//7431 7422//7422 -f 7422//7422 7431//7431 7432//7432 -f 7422//7422 7432//7432 7424//7424 -f 7424//7424 7432//7432 7433//7433 -f 7424//7424 7433//7433 7425//7425 -f 7209//7209 7211//7211 7434//7434 -f 7435//7435 7436//7436 7437//7437 -f 7208//7208 7438//7438 7439//7439 -f 7440//7440 7441//7441 7442//7442 -f 7442//7442 7441//7441 7443//7443 -f 7442//7442 7443//7443 7436//7436 -f 7436//7436 7443//7443 7444//7444 -f 7436//7436 7444//7444 7437//7437 -f 7445//7445 7446//7446 7207//7207 -f 7207//7207 7446//7446 7447//7447 -f 7207//7207 7447//7447 7208//7208 -f 7208//7208 7447//7447 7448//7448 -f 7208//7208 7448//7448 7438//7438 -f 7437//7437 7449//7449 7435//7435 -f 7435//7435 7449//7449 7450//7450 -f 7435//7435 7450//7450 7207//7207 -f 7207//7207 7450//7450 7451//7451 -f 7207//7207 7451//7451 7445//7445 -f 7452//7452 7453//7453 7208//7208 -f 7208//7208 7453//7453 7454//7454 -f 7208//7208 7454//7454 7206//7206 -f 7452//7452 7208//7208 7455//7455 -f 7455//7455 7208//7208 7456//7456 -f 7455//7455 7456//7456 7457//7457 -f 7457//7457 7456//7456 7234//7234 -f 7457//7457 7234//7234 7458//7458 -f 7459//7459 7460//7460 7228//7228 -f 7460//7460 7461//7461 7228//7228 -f 7228//7228 7461//7461 7462//7462 -f 7228//7228 7462//7462 7234//7234 -f 7234//7234 7462//7462 7463//7463 -f 7234//7234 7463//7463 7464//7464 -f 7465//7465 6793//6793 7466//7466 -f 7466//7466 6793//6793 6795//6795 -f 7466//7466 6795//6795 7467//7467 -f 7467//7467 6795//6795 7468//7468 -f 7467//7467 7468//7468 7469//7469 -f 7469//7469 7468//7468 7458//7458 -f 7469//7469 7458//7458 7470//7470 -f 7470//7470 7458//7458 7234//7234 -f 7470//7470 7234//7234 7471//7471 -f 7471//7471 7234//7234 7464//7464 -f 7205//7205 7204//7204 7228//7228 -f 7228//7228 7204//7204 7472//7472 -f 7228//7228 7472//7472 7473//7473 -f 7473//7473 7474//7474 7228//7228 -f 7228//7228 7474//7474 6793//6793 -f 7228//7228 6793//6793 7459//7459 -f 7459//7459 6793//6793 7465//7465 -f 7474//7474 7475//7475 6793//6793 -f 6793//6793 7475//7475 7476//7476 -f 6793//6793 7476//7476 6791//6791 -f 6791//6791 7476//7476 7477//7477 -f 6791//6791 7477//7477 7478//7478 -f 7478//7478 7477//7477 7479//7479 -f 7478//7478 7479//7479 7480//7480 -f 7480//7480 7479//7479 7481//7481 -f 7480//7480 7481//7481 7482//7482 -f 7482//7482 7481//7481 7483//7483 -f 7482//7482 7483//7483 7205//7205 -f 7205//7205 7483//7483 7484//7484 -f 7205//7205 7484//7484 7203//7203 -f 7485//7485 7486//7486 7217//7217 -f 7217//7217 7486//7486 7487//7487 -f 7217//7217 7487//7487 7215//7215 -f 7215//7215 7487//7487 7390//7390 -f 7215//7215 7390//7390 7488//7488 -f 7488//7488 7390//7390 7389//7389 -f 7489//7489 7327//7327 7490//7490 -f 7490//7490 7327//7327 7487//7487 -f 7490//7490 7487//7487 7491//7491 -f 7491//7491 7487//7487 7486//7486 -f 7492//7492 7493//7493 7217//7217 -f 7217//7217 7493//7493 7494//7494 -f 7217//7217 7494//7494 7485//7485 -f 7495//7495 7496//7496 7497//7497 -f 7497//7497 7496//7496 7498//7498 -f 7497//7497 7498//7498 7492//7492 -f 7492//7492 7498//7498 7499//7499 -f 7492//7492 7499//7499 7493//7493 -f 7489//7489 7500//7500 7327//7327 -f 7327//7327 7500//7500 7495//7495 -f 7327//7327 7495//7495 7219//7219 -f 7219//7219 7495//7495 7497//7497 -f 7219//7219 7497//7497 7220//7220 -f 7220//7220 7497//7497 6789//6789 -f 7501//7501 7502//7502 7503//7503 -f 7503//7503 7502//7502 7226//7226 -f 7226//7226 7502//7502 7504//7504 -f 7226//7226 7504//7504 7505//7505 -f 7505//7505 7506//7506 7226//7226 -f 7226//7226 7506//7506 7252//7252 -f 7226//7226 7252//7252 7224//7224 -f 7224//7224 7252//7252 7253//7253 -f 7507//7507 7236//7236 7508//7508 -f 7508//7508 7236//7236 7252//7252 -f 7508//7508 7252//7252 7509//7509 -f 7509//7509 7252//7252 7506//7506 -f 7507//7507 7510//7510 7236//7236 -f 7236//7236 7510//7510 7511//7511 -f 7236//7236 7511//7511 7512//7512 -f 7501//7501 7503//7503 7513//7513 -f 7513//7513 7503//7503 7442//7442 -f 7513//7513 7442//7442 7514//7514 -f 7434//7434 7211//7211 7515//7515 -f 7515//7515 7211//7211 7516//7516 -f 7515//7515 7516//7516 7436//7436 -f 7436//7436 7516//7516 7512//7512 -f 7436//7436 7512//7512 7442//7442 -f 7442//7442 7512//7512 7511//7511 -f 7442//7442 7511//7511 7514//7514 -f 7379//7379 7367//7367 7217//7217 -f 7217//7217 7367//7367 7368//7368 -f 7217//7217 7368//7368 7492//7492 -f 7492//7492 7368//7368 7331//7331 -f 7492//7492 7331//7331 7497//7497 -f 7497//7497 7331//7331 6787//6787 -f 7497//7497 6787//6787 6789//6789 -f 7517//7517 7518//7518 7329//7329 -f 7519//7519 7520//7520 7327//7327 -f 7487//7487 7521//7521 7522//7522 -f 7522//7522 7523//7523 7524//7524 -f 7524//7524 7523//7523 7525//7525 -f 7524//7524 7525//7525 7329//7329 -f 7329//7329 7525//7525 7526//7526 -f 7329//7329 7526//7526 7517//7517 -f 7218//7218 7330//7330 7327//7327 -f 7327//7327 7330//7330 7329//7329 -f 7327//7327 7329//7329 7519//7519 -f 7519//7519 7329//7329 7518//7518 -f 7520//7520 7527//7527 7327//7327 -f 7327//7327 7527//7527 7528//7528 -f 7327//7327 7528//7528 7487//7487 -f 7487//7487 7528//7528 7529//7529 -f 7487//7487 7529//7529 7521//7521 -f 7299//7299 7301//7301 7530//7530 -f 7530//7530 7301//7301 7524//7524 -f 7530//7530 7524//7524 7531//7531 -f 7531//7531 7524//7524 7329//7329 -f 7531//7531 7329//7329 7532//7532 -f 7532//7532 7329//7329 7319//7319 -f 7532//7532 7319//7319 7307//7307 -f 7307//7307 7319//7319 7321//7321 -f 7307//7307 7321//7321 7309//7309 -f 7533//7533 7530//7530 7534//7534 -f 7534//7534 7530//7530 7531//7531 -f 7534//7534 7531//7531 7535//7535 -f 7535//7535 7531//7531 7532//7532 -f 7535//7535 7532//7532 7536//7536 -f 7536//7536 7532//7532 7307//7307 -f 7536//7536 7307//7307 7537//7537 -f 7537//7537 7307//7307 7308//7308 -f 7538//7538 7301//7301 7539//7539 -f 7539//7539 7301//7301 7540//7540 -f 7541//7541 7542//7542 7294//7294 -f 7522//7522 7524//7524 7487//7487 -f 7487//7487 7524//7524 7301//7301 -f 7487//7487 7301//7301 7390//7390 -f 7390//7390 7301//7301 7538//7538 -f 7390//7390 7538//7538 7543//7543 -f 7542//7542 7544//7544 7294//7294 -f 7294//7294 7544//7544 7545//7545 -f 7294//7294 7545//7545 7301//7301 -f 7301//7301 7545//7545 7546//7546 -f 7301//7301 7546//7546 7540//7540 -f 7543//7543 7547//7547 7390//7390 -f 7390//7390 7547//7547 7548//7548 -f 7390//7390 7548//7548 7213//7213 -f 7213//7213 7548//7548 7549//7549 -f 7549//7549 7550//7550 7213//7213 -f 7213//7213 7550//7550 7551//7551 -f 7213//7213 7551//7551 7294//7294 -f 7294//7294 7551//7551 7552//7552 -f 7294//7294 7552//7552 7541//7541 -f 7294//7294 7553//7553 7554//7554 -f 7555//7555 7556//7556 7287//7287 -f 7287//7287 7556//7556 7557//7557 -f 7287//7287 7557//7557 7294//7294 -f 7294//7294 7557//7557 7558//7558 -f 7294//7294 7558//7558 7553//7553 -f 7554//7554 7559//7559 7294//7294 -f 7294//7294 7559//7559 7560//7560 -f 7294//7294 7560//7560 7213//7213 -f 7213//7213 7560//7560 7561//7561 -f 7214//7214 7562//7562 7287//7287 -f 7287//7287 7562//7562 7563//7563 -f 7287//7287 7563//7563 7555//7555 -f 7561//7561 7564//7564 7213//7213 -f 7213//7213 7564//7564 7565//7565 -f 7213//7213 7565//7565 7214//7214 -f 7214//7214 7565//7565 7566//7566 -f 7214//7214 7566//7566 7562//7562 -f 7416//7416 6755//6755 7414//7414 -f 7414//7414 6755//6755 6757//6757 -f 7414//7414 6757//6757 7417//7417 -f 7417//7417 6757//6757 7402//7402 -f 7417//7417 7402//7402 7200//7200 -f 7567//7567 7568//7568 7287//7287 -f 7569//7569 7570//7570 7200//7200 -f 7569//7569 7200//7200 7571//7571 -f 7287//7287 7568//7568 7214//7214 -f 7214//7214 7568//7568 7572//7572 -f 7214//7214 7572//7572 7573//7573 -f 7570//7570 7574//7574 7200//7200 -f 7200//7200 7574//7574 7575//7575 -f 7200//7200 7575//7575 7201//7201 -f 7201//7201 7575//7575 7576//7576 -f 7201//7201 7576//7576 7577//7577 -f 7391//7391 7212//7212 7402//7402 -f 7402//7402 7212//7212 7214//7214 -f 7402//7402 7214//7214 7200//7200 -f 7200//7200 7214//7214 7573//7573 -f 7200//7200 7573//7573 7571//7571 -f 7577//7577 7578//7578 7201//7201 -f 7201//7201 7578//7578 7579//7579 -f 7201//7201 7579//7579 7287//7287 -f 7287//7287 7579//7579 7580//7580 -f 7287//7287 7580//7580 7567//7567 -f 7581//7581 7582//7582 7516//7516 -f 7583//7583 7584//7584 7283//7283 -f 7283//7283 7584//7584 7585//7585 -f 7283//7283 7585//7585 7586//7586 -f 7290//7290 7587//7587 7201//7201 -f 7201//7201 7587//7587 7281//7281 -f 7201//7201 7281//7281 7202//7202 -f 7202//7202 7281//7281 7283//7283 -f 7202//7202 7283//7283 7588//7588 -f 7588//7588 7283//7283 7586//7586 -f 7588//7588 7589//7589 7202//7202 -f 7202//7202 7589//7589 7590//7590 -f 7202//7202 7590//7590 7591//7591 -f 7591//7591 7592//7592 7202//7202 -f 7202//7202 7592//7592 7211//7211 -f 7202//7202 7211//7211 7200//7200 -f 7200//7200 7211//7211 7210//7210 -f 7200//7200 7210//7210 7417//7417 -f 7417//7417 7210//7210 7427//7427 -f 7417//7417 7427//7427 7418//7418 -f 7592//7592 7593//7593 7211//7211 -f 7211//7211 7593//7593 7594//7594 -f 7211//7211 7594//7594 7516//7516 -f 7516//7516 7594//7594 7595//7595 -f 7516//7516 7595//7595 7581//7581 -f 7237//7237 7236//7236 7241//7241 -f 7241//7241 7236//7236 7512//7512 -f 7241//7241 7512//7512 7596//7596 -f 7596//7596 7512//7512 7516//7516 -f 7596//7596 7516//7516 7283//7283 -f 7283//7283 7516//7516 7582//7582 -f 7283//7283 7582//7582 7583//7583 -f 7225//7225 7234//7234 7226//7226 -f 7226//7226 7234//7234 7456//7456 -f 7226//7226 7456//7456 7503//7503 -f 7503//7503 7456//7456 7208//7208 -f 7503//7503 7208//7208 7442//7442 -f 7442//7442 7208//7208 7439//7439 -f 7442//7442 7439//7439 7440//7440 -f 7285//7285 7277//7277 7283//7283 -f 7283//7283 7277//7277 7279//7279 -f 7283//7283 7279//7279 7596//7596 -f 7596//7596 7279//7279 7597//7597 -f 7596//7596 7597//7597 7241//7241 -f 7241//7241 7597//7597 7261//7261 -f 7241//7241 7261//7261 7256//7256 -f 7256//7256 7261//7261 7263//7263 -f 7256//7256 7263//7263 7264//7264 -f 7598//7598 7259//7259 7599//7599 -f 7599//7599 7259//7259 7261//7261 -f 7599//7599 7261//7261 7600//7600 -f 7600//7600 7261//7261 7597//7597 -f 7600//7600 7597//7597 7601//7601 -f 7601//7601 7597//7597 7279//7279 -f 7601//7601 7279//7279 7602//7602 -f 7602//7602 7279//7279 7280//7280 -f 7016//7016 7313//7313 7006//7006 -f 7006//7006 7313//7313 7315//7315 -f 7006//7006 7315//7315 6999//6999 -f 6999//6999 7315//7315 7326//7326 -f 7074//7074 7269//7269 7063//7063 -f 7063//7063 7269//7269 7270//7270 -f 7063//7063 7270//7270 7069//7069 -f 7069//7069 7270//7270 7274//7274 -f 7267//7267 7057//7057 7271//7271 -f 7271//7271 7057//7057 7065//7065 -f 7271//7271 7065//7065 7272//7272 -f 7272//7272 7065//7065 7064//7064 -f 7272//7272 7064//7064 7273//7273 -f 7273//7273 7064//7064 7071//7071 -f 7273//7273 7071//7071 7275//7275 -f 7275//7275 7071//7071 7070//7070 -f 7275//7275 7070//7070 7276//7276 -f 7276//7276 7070//7070 7068//7068 -f 7276//7276 7068//7068 7260//7260 -f 7260//7260 7068//7068 7067//7067 -f 7260//7260 7067//7067 7262//7262 -f 7262//7262 7067//7067 7066//7066 -f 7262//7262 7066//7066 7263//7263 -f 7263//7263 7066//7066 7062//7062 -f 7263//7263 7062//7062 7264//7264 -f 7264//7264 7062//7062 7061//7061 -f 7264//7264 7061//7061 7265//7265 -f 7265//7265 7061//7061 7060//7060 -f 7265//7265 7060//7060 7266//7266 -f 7266//7266 7060//7060 7058//7058 -f 7266//7266 7058//7058 7267//7267 -f 7267//7267 7058//7058 7057//7057 -f 7317//7317 7007//7007 7318//7318 -f 7318//7318 7007//7007 7013//7013 -f 7318//7318 7013//7013 7320//7320 -f 7320//7320 7013//7013 7012//7012 -f 7320//7320 7012//7012 7321//7321 -f 7321//7321 7012//7012 7005//7005 -f 7321//7321 7005//7005 7309//7309 -f 7309//7309 7005//7005 7004//7004 -f 7309//7309 7004//7004 7310//7310 -f 7310//7310 7004//7004 7010//7010 -f 7310//7310 7010//7010 7311//7311 -f 7311//7311 7010//7010 7009//7009 -f 7311//7311 7009//7009 7312//7312 -f 7312//7312 7009//7009 7019//7019 -f 7312//7312 7019//7019 7314//7314 -f 7314//7314 7019//7019 7017//7017 -f 7314//7314 7017//7017 7316//7316 -f 7316//7316 7017//7017 7015//7015 -f 7316//7316 7015//7015 7322//7322 -f 7322//7322 7015//7015 7014//7014 -f 7322//7322 7014//7014 7323//7323 -f 7323//7323 7014//7014 7008//7008 -f 7323//7323 7008//7008 7317//7317 -f 7317//7317 7008//7008 7007//7007 -f 7477//7477 6801//6801 7479//7479 -f 7479//7479 6801//6801 6800//6800 -f 7479//7479 6800//6800 7481//7481 -f 7481//7481 6800//6800 7114//7114 -f 7481//7481 7114//7114 7483//7483 -f 7483//7483 7114//7114 7113//7113 -f 7483//7483 7113//7113 7484//7484 -f 7484//7484 7113//7113 7111//7111 -f 7484//7484 7111//7111 7203//7203 -f 7203//7203 7111//7111 7110//7110 -f 7203//7203 7110//7110 7204//7204 -f 7204//7204 7110//7110 7108//7108 -f 7204//7204 7108//7108 7472//7472 -f 7472//7472 7108//7108 7104//7104 -f 7472//7472 7104//7104 7473//7473 -f 7473//7473 7104//7104 7103//7103 -f 7473//7473 7103//7103 7474//7474 -f 7474//7474 7103//7103 7107//7107 -f 7474//7474 7107//7107 7475//7475 -f 7475//7475 7107//7107 7106//7106 -f 7475//7475 7106//7106 7476//7476 -f 7476//7476 7106//7106 7105//7105 -f 7476//7476 7105//7105 7477//7477 -f 7477//7477 7105//7105 6801//6801 -f 7363//7363 6965//6965 7364//7364 -f 7364//7364 6965//6965 6964//6964 -f 7364//7364 6964//6964 7365//7365 -f 7365//7365 6964//6964 6963//6963 -f 7365//7365 6963//6963 7366//7366 -f 7366//7366 6963//6963 6962//6962 -f 7366//7366 6962//6962 7355//7355 -f 7355//7355 6962//6962 6961//6961 -f 7355//7355 6961//6961 7356//7356 -f 7356//7356 6961//6961 6960//6960 -f 7356//7356 6960//6960 7357//7357 -f 7357//7357 6960//6960 6972//6972 -f 7357//7357 6972//6972 7358//7358 -f 7358//7358 6972//6972 6971//6971 -f 7358//7358 6971//6971 7359//7359 -f 7359//7359 6971//6971 6970//6970 -f 7359//7359 6970//6970 7360//7360 -f 7360//7360 6970//6970 6966//6966 -f 7360//7360 6966//6966 7361//7361 -f 7361//7361 6966//6966 6968//6968 -f 7361//7361 6968//6968 7362//7362 -f 7362//7362 6968//6968 6969//6969 -f 7362//7362 6969//6969 7363//7363 -f 7363//7363 6969//6969 6965//6965 -f 7466//7466 6854//6854 7465//7465 -f 7465//7465 6854//6854 6853//6853 -f 7465//7465 6853//6853 7459//7459 -f 7459//7459 6853//6853 6852//6852 -f 7459//7459 6852//6852 7460//7460 -f 7460//7460 6852//6852 6847//6847 -f 7460//7460 6847//6847 7461//7461 -f 7461//7461 6847//6847 6846//6846 -f 7461//7461 6846//6846 7462//7462 -f 7462//7462 6846//6846 6844//6844 -f 7462//7462 6844//6844 7463//7463 -f 7463//7463 6844//6844 6843//6843 -f 7463//7463 6843//6843 7464//7464 -f 7464//7464 6843//6843 6848//6848 -f 7464//7464 6848//6848 7471//7471 -f 7471//7471 6848//6848 6850//6850 -f 7471//7471 6850//6850 7470//7470 -f 7470//7470 6850//6850 6851//6851 -f 7470//7470 6851//6851 7469//7469 -f 7469//7469 6851//6851 6858//6858 -f 7469//7469 6858//6858 7467//7467 -f 7467//7467 6858//6858 6856//6856 -f 7467//7467 6856//6856 7466//7466 -f 7466//7466 6856//6856 6854//6854 -f 7349//7349 6977//6977 7348//7348 -f 7348//7348 6977//6977 6978//6978 -f 7348//7348 6978//6978 7352//7352 -f 7352//7352 6978//6978 6986//6986 -f 7352//7352 6986//6986 7353//7353 -f 7353//7353 6986//6986 6985//6985 -f 7353//7353 6985//6985 7354//7354 -f 7354//7354 6985//6985 6984//6984 -f 7354//7354 6984//6984 7344//7344 -f 7344//7344 6984//6984 6974//6974 -f 7344//7344 6974//6974 7341//7341 -f 7341//7341 6974//6974 6973//6973 -f 7341//7341 6973//6973 7342//7342 -f 7342//7342 6973//6973 6983//6983 -f 7342//7342 6983//6983 7343//7343 -f 7343//7343 6983//6983 6982//6982 -f 7343//7343 6982//6982 7345//7345 -f 7345//7345 6982//6982 6980//6980 -f 7345//7345 6980//6980 7351//7351 -f 7351//7351 6980//6980 6979//6979 -f 7351//7351 6979//6979 7350//7350 -f 7350//7350 6979//6979 6975//6975 -f 7350//7350 6975//6975 7349//7349 -f 7349//7349 6975//6975 6977//6977 -f 7334//7334 6987//6987 7333//7333 -f 7333//7333 6987//6987 6994//6994 -f 7333//7333 6994//6994 6785//6785 -f 6785//6785 6994//6994 6786//6786 -f 7101//7101 7230//7230 7097//7097 -f 7097//7097 7230//7230 7229//7229 -f 7097//7097 7229//7229 7098//7098 -f 7098//7098 7229//7229 7235//7235 -f 7225//7225 7095//7095 7233//7233 -f 7233//7233 7095//7095 7094//7094 -f 7233//7233 7094//7094 7235//7235 -f 7235//7235 7094//7094 7098//7098 -f 7254//7254 7072//7072 7255//7255 -f 7255//7255 7072//7072 7089//7089 -f 7255//7255 7089//7089 7257//7257 -f 7257//7257 7089//7089 7088//7088 -f 7257//7257 7088//7088 7258//7258 -f 7258//7258 7088//7088 7087//7087 -f 7258//7258 7087//7087 7243//7243 -f 7243//7243 7087//7087 7086//7086 -f 7243//7243 7086//7086 7247//7247 -f 7247//7247 7086//7086 7076//7076 -f 7247//7247 7076//7076 7253//7253 -f 7253//7253 7076//7076 7075//7075 -f 7253//7253 7075//7075 7224//7224 -f 7224//7224 7075//7075 7096//7096 -f 7224//7224 7096//7096 7225//7225 -f 7225//7225 7096//7096 7095//7095 -f 6789//6789 6790//6790 7220//7220 -f 7220//7220 6790//6790 6998//6998 -f 7220//7220 6998//6998 7218//7218 -f 7218//7218 6998//6998 6997//6997 -f 7218//7218 6997//6997 7330//7330 -f 7330//7330 6997//6997 6996//6996 -f 7330//7330 6996//6996 7328//7328 -f 7328//7328 6996//6996 7003//7003 -f 7328//7328 7003//7003 7324//7324 -f 7324//7324 7003//7003 7002//7002 -f 7324//7324 7002//7002 7325//7325 -f 7325//7325 7002//7002 7000//7000 -f 7325//7325 7000//7000 7326//7326 -f 7326//7326 7000//7000 6999//6999 -f 7528//7528 7182//7182 7529//7529 -f 7529//7529 7182//7182 7187//7187 -f 7529//7529 7187//7187 7521//7521 -f 7521//7521 7187//7187 7188//7188 -f 7521//7521 7188//7188 7522//7522 -f 7522//7522 7188//7188 7189//7189 -f 7522//7522 7189//7189 7523//7523 -f 7523//7523 7189//7189 7191//7191 -f 7523//7523 7191//7191 7525//7525 -f 7525//7525 7191//7191 7194//7194 -f 7525//7525 7194//7194 7526//7526 -f 7526//7526 7194//7194 7193//7193 -f 7526//7526 7193//7193 7517//7517 -f 7517//7517 7193//7193 7192//7192 -f 7517//7517 7192//7192 7518//7518 -f 7518//7518 7192//7192 7184//7184 -f 7518//7518 7184//7184 7519//7519 -f 7519//7519 7184//7184 7185//7185 -f 7519//7519 7185//7185 7520//7520 -f 7520//7520 7185//7185 7186//7186 -f 7520//7520 7186//7186 7527//7527 -f 7527//7527 7186//7186 7183//7183 -f 7527//7527 7183//7183 7528//7528 -f 7528//7528 7183//7183 7182//7182 -f 7493//7493 6814//6814 7494//7494 -f 7494//7494 6814//6814 6816//6816 -f 7494//7494 6816//6816 7485//7485 -f 7485//7485 6816//6816 6817//6817 -f 7485//7485 6817//6817 7486//7486 -f 7486//7486 6817//6817 6812//6812 -f 7486//7486 6812//6812 7491//7491 -f 7491//7491 6812//6812 6811//6811 -f 7491//7491 6811//6811 7490//7490 -f 7490//7490 6811//6811 6810//6810 -f 7490//7490 6810//6810 7489//7489 -f 7489//7489 6810//6810 6808//6808 -f 7489//7489 6808//6808 7500//7500 -f 7500//7500 6808//6808 6824//6824 -f 7500//7500 6824//6824 7495//7495 -f 7495//7495 6824//6824 6823//6823 -f 7495//7495 6823//6823 7496//7496 -f 7496//7496 6823//6823 6821//6821 -f 7496//7496 6821//6821 7498//7498 -f 7498//7498 6821//6821 6819//6819 -f 7498//7498 6819//6819 7499//7499 -f 7499//7499 6819//6819 6818//6818 -f 7499//7499 6818//6818 7493//7493 -f 7493//7493 6818//6818 6814//6814 -f 7251//7251 7082//7082 7245//7245 -f 7245//7245 7082//7082 7081//7081 -f 7245//7245 7081//7081 7246//7246 -f 7246//7246 7081//7081 7077//7077 -f 7246//7246 7077//7077 7248//7248 -f 7248//7248 7077//7077 7093//7093 -f 7248//7248 7093//7093 7249//7249 -f 7249//7249 7093//7093 7092//7092 -f 7249//7249 7092//7092 7244//7244 -f 7244//7244 7092//7092 7091//7091 -f 7244//7244 7091//7091 7242//7242 -f 7242//7242 7091//7091 7090//7090 -f 7242//7242 7090//7090 7239//7239 -f 7239//7239 7090//7090 7079//7079 -f 7239//7239 7079//7079 7240//7240 -f 7240//7240 7079//7079 7078//7078 -f 7240//7240 7078//7078 7237//7237 -f 7237//7237 7078//7078 7085//7085 -f 7237//7237 7085//7085 7238//7238 -f 7238//7238 7085//7085 7084//7084 -f 7238//7238 7084//7084 7250//7250 -f 7250//7250 7084//7084 7083//7083 -f 7250//7250 7083//7083 7251//7251 -f 7251//7251 7083//7083 7082//7082 -f 7502//7502 6831//6831 7504//7504 -f 7504//7504 6831//6831 6833//6833 -f 7504//7504 6833//6833 7505//7505 -f 7505//7505 6833//6833 6835//6835 -f 7505//7505 6835//6835 7506//7506 -f 7506//7506 6835//6835 6836//6836 -f 7506//7506 6836//6836 7509//7509 -f 7509//7509 6836//6836 6829//6829 -f 7509//7509 6829//6829 7508//7508 -f 7508//7508 6829//6829 6828//6828 -f 7508//7508 6828//6828 7507//7507 -f 7507//7507 6828//6828 6826//6826 -f 7507//7507 6826//6826 7510//7510 -f 7510//7510 6826//6826 6825//6825 -f 7510//7510 6825//6825 7511//7511 -f 7511//7511 6825//6825 6840//6840 -f 7511//7511 6840//6840 7514//7514 -f 7514//7514 6840//6840 6842//6842 -f 7514//7514 6842//6842 7513//7513 -f 7513//7513 6842//6842 6838//6838 -f 7513//7513 6838//6838 7501//7501 -f 7501//7501 6838//6838 6837//6837 -f 7501//7501 6837//6837 7502//7502 -f 7502//7502 6837//6837 6831//6831 -f 7468//7468 6855//6855 7458//7458 -f 7458//7458 6855//6855 6857//6857 -f 7458//7458 6857//6857 7457//7457 -f 7457//7457 6857//6857 6860//6860 -f 7457//7457 6860//6860 7455//7455 -f 7455//7455 6860//6860 6862//6862 -f 7455//7455 6862//6862 7452//7452 -f 7452//7452 6862//6862 6865//6865 -f 6778//6778 6783//6783 6777//6777 -f 6777//6777 6783//6783 6784//6784 -f 6796//6796 6855//6855 6795//6795 -f 6795//6795 6855//6855 7468//7468 -f 7031//7031 7297//7297 7032//7032 -f 7032//7032 7297//7297 7298//7298 -f 7032//7032 7298//7298 7033//7033 -f 7033//7033 7298//7298 7293//7293 -f 7029//7029 7296//7296 7031//7031 -f 7031//7031 7296//7296 7297//7297 -f 7028//7028 7299//7299 7023//7023 -f 7023//7023 7299//7299 7530//7530 -f 7036//7036 7303//7303 7026//7026 -f 7026//7026 7303//7303 7302//7302 -f 7026//7026 7302//7302 7027//7027 -f 7027//7027 7302//7302 7300//7300 -f 7027//7027 7300//7300 7028//7028 -f 7028//7028 7300//7300 7299//7299 -f 7033//7033 7293//7293 7035//7035 -f 7035//7035 7293//7293 7304//7304 -f 7035//7035 7304//7304 7036//7036 -f 7036//7036 7304//7304 7303//7303 -f 7176//7176 7545//7545 7177//7177 -f 7177//7177 7545//7545 7544//7544 -f 7177//7177 7544//7544 7178//7178 -f 7178//7178 7544//7544 7542//7542 -f 7178//7178 7542//7542 7179//7179 -f 7179//7179 7542//7542 7541//7541 -f 7179//7179 7541//7541 7180//7180 -f 7180//7180 7541//7541 7552//7552 -f 7180//7180 7552//7552 7181//7181 -f 7181//7181 7552//7552 7551//7551 -f 7181//7181 7551//7551 6797//6797 -f 6797//6797 7551//7551 7550//7550 -f 6797//6797 7550//7550 6798//6798 -f 6798//6798 7550//7550 7549//7549 -f 7175//7175 7546//7546 7176//7176 -f 7176//7176 7546//7546 7545//7545 -f 7171//7171 7548//7548 7172//7172 -f 7172//7172 7548//7548 7547//7547 -f 7172//7172 7547//7547 7173//7173 -f 7173//7173 7547//7547 7543//7543 -f 7173//7173 7543//7543 7174//7174 -f 7174//7174 7543//7543 7538//7538 -f 7174//7174 7538//7538 7168//7168 -f 7168//7168 7538//7538 7539//7539 -f 7168//7168 7539//7539 7169//7169 -f 7169//7169 7539//7539 7540//7540 -f 7169//7169 7540//7540 7175//7175 -f 7175//7175 7540//7540 7546//7546 -f 6798//6798 7549//7549 7171//7171 -f 7171//7171 7549//7549 7548//7548 -f 7166//7166 7557//7557 7167//7167 -f 7167//7167 7557//7557 7556//7556 -f 7167//7167 7556//7556 7154//7154 -f 7154//7154 7556//7556 7555//7555 -f 7154//7154 7555//7555 7155//7155 -f 7155//7155 7555//7555 7563//7563 -f 7155//7155 7563//7563 7161//7161 -f 7161//7161 7563//7563 7562//7562 -f 7161//7161 7562//7562 7156//7156 -f 7156//7156 7562//7562 7566//7566 -f 7156//7156 7566//7566 7157//7157 -f 7157//7157 7566//7566 7565//7565 -f 7165//7165 7558//7558 7166//7166 -f 7166//7166 7558//7558 7557//7557 -f 7162//7162 7564//7564 7163//7163 -f 7163//7163 7564//7564 7561//7561 -f 7163//7163 7561//7561 7164//7164 -f 7164//7164 7561//7561 7560//7560 -f 7164//7164 7560//7560 7160//7160 -f 7160//7160 7560//7560 7559//7559 -f 7160//7160 7559//7559 7159//7159 -f 7159//7159 7559//7559 7554//7554 -f 7159//7159 7554//7554 7158//7158 -f 7158//7158 7554//7554 7553//7553 -f 7158//7158 7553//7553 7165//7165 -f 7165//7165 7553//7553 7558//7558 -f 7157//7157 7565//7565 7162//7162 -f 7162//7162 7565//7565 7564//7564 -f 7153//7153 7578//7578 7139//7139 -f 7139//7139 7578//7578 7577//7577 -f 7139//7139 7577//7577 7140//7140 -f 7140//7140 7577//7577 7576//7576 -f 7140//7140 7576//7576 7141//7141 -f 7141//7141 7576//7576 7575//7575 -f 7141//7141 7575//7575 7142//7142 -f 7142//7142 7575//7575 7574//7574 -f 7142//7142 7574//7574 7143//7143 -f 7143//7143 7574//7574 7570//7570 -f 7143//7143 7570//7570 7144//7144 -f 7144//7144 7570//7570 7569//7569 -f 7152//7152 7579//7579 7153//7153 -f 7153//7153 7579//7579 7578//7578 -f 7145//7145 7571//7571 7147//7147 -f 7147//7147 7571//7571 7573//7573 -f 7147//7147 7573//7573 7148//7148 -f 7148//7148 7573//7573 7572//7572 -f 7148//7148 7572//7572 7149//7149 -f 7149//7149 7572//7572 7568//7568 -f 7149//7149 7568//7568 7150//7150 -f 7150//7150 7568//7568 7567//7567 -f 7150//7150 7567//7567 7151//7151 -f 7151//7151 7567//7567 7580//7580 -f 7151//7151 7580//7580 7152//7152 -f 7152//7152 7580//7580 7579//7579 -f 7144//7144 7569//7569 7145//7145 -f 7145//7145 7569//7569 7571//7571 -f 7138//7138 7586//7586 7125//7125 -f 7125//7125 7586//7586 7585//7585 -f 7125//7125 7585//7585 7126//7126 -f 7126//7126 7585//7585 7584//7584 -f 7126//7126 7584//7584 7127//7127 -f 7127//7127 7584//7584 7583//7583 -f 7127//7127 7583//7583 7128//7128 -f 7128//7128 7583//7583 7582//7582 -f 7128//7128 7582//7582 7131//7131 -f 7131//7131 7582//7582 7581//7581 -f 7131//7131 7581//7581 7130//7130 -f 7130//7130 7581//7581 7595//7595 -f 7137//7137 7588//7588 7138//7138 -f 7138//7138 7588//7588 7586//7586 -f 7129//7129 7594//7594 7132//7132 -f 7132//7132 7594//7594 7593//7593 -f 7132//7132 7593//7593 7133//7133 -f 7133//7133 7593//7593 7592//7592 -f 7133//7133 7592//7592 7134//7134 -f 7134//7134 7592//7592 7591//7591 -f 7134//7134 7591//7591 7135//7135 -f 7135//7135 7591//7591 7590//7590 -f 7135//7135 7590//7590 7136//7136 -f 7136//7136 7590//7590 7589//7589 -f 7136//7136 7589//7589 7137//7137 -f 7137//7137 7589//7589 7588//7588 -f 7130//7130 7595//7595 7129//7129 -f 7129//7129 7595//7595 7594//7594 -f 7048//7048 7285//7285 7049//7049 -f 7049//7049 7285//7285 7284//7284 -f 7049//7049 7284//7284 7050//7050 -f 7050//7050 7284//7284 7282//7282 -f 7046//7046 7277//7277 7048//7048 -f 7048//7048 7277//7277 7285//7285 -f 7043//7043 7288//7288 7042//7042 -f 7042//7042 7288//7288 7286//7286 -f 7039//7039 7290//7290 7044//7044 -f 7044//7044 7290//7290 7289//7289 -f 7044//7044 7289//7289 7043//7043 -f 7043//7043 7289//7289 7288//7288 -f 7050//7050 7282//7282 7052//7052 -f 7052//7052 7282//7282 7281//7281 -f 7052//7052 7281//7281 7053//7053 -f 7053//7053 7281//7281 7587//7587 -f 7053//7053 7587//7587 7039//7039 -f 7039//7039 7587//7587 7290//7290 -f 6956//6956 7370//7370 6940//6940 -f 6940//6940 7370//7370 7369//7369 -f 6940//6940 7369//7369 6951//6951 -f 6951//6951 7369//7369 7373//7373 -f 7410//7410 6932//6932 7397//7397 -f 7397//7397 6932//6932 6913//6913 -f 7397//7397 6913//6913 7394//7394 -f 7394//7394 6913//6913 6917//6917 -f 6951//6951 7373//7373 6936//6936 -f 6936//6936 7373//7373 7216//7216 -f 6936//6936 7216//7216 6937//6937 -f 6937//6937 7216//7216 7215//7215 -f 6937//6937 7215//7215 6933//6933 -f 6933//6933 7215//7215 7488//7488 -f 6933//6933 7488//7488 6934//6934 -f 6934//6934 7488//7488 7389//7389 -f 6934//6934 7389//7389 6935//6935 -f 6935//6935 7389//7389 7388//7388 -f 6935//6935 7388//7388 6921//6921 -f 6921//6921 7388//7388 7212//7212 -f 6921//6921 7212//7212 6917//6917 -f 6917//6917 7212//7212 7394//7394 -f 6907//6907 7412//7412 6904//6904 -f 6904//6904 7412//7412 7422//7422 -f 6904//6904 7422//7422 6896//6896 -f 6896//6896 7422//7422 7424//7424 -f 7206//7206 6863//6863 7207//7207 -f 7207//7207 6863//6863 6867//6867 -f 7207//7207 6867//6867 7435//7435 -f 7435//7435 6867//6867 6871//6871 -f 6896//6896 7424//7424 6889//6889 -f 6889//6889 7424//7424 7210//7210 -f 6889//6889 7210//7210 6888//6888 -f 6888//6888 7210//7210 7209//7209 -f 6888//6888 7209//7209 6886//6886 -f 6886//6886 7209//7209 7434//7434 -f 6886//6886 7434//7434 6885//6885 -f 6885//6885 7434//7434 7515//7515 -f 6885//6885 7515//7515 6870//6870 -f 6870//6870 7515//7515 7436//7436 -f 6870//6870 7436//7436 6871//6871 -f 6871//6871 7436//7436 7435//7435 -f 7370//7370 6956//6956 6957//6957 -f 7370//7370 6957//6957 7371//7371 -f 7371//7371 6957//6957 6955//6955 -f 7371//7371 6955//6955 7372//7372 -f 7372//7372 6955//6955 6770//6770 -f 7372//7372 6770//6770 6769//6769 -f 6767//6767 6768//6768 6930//6930 -f 6767//6767 6930//6930 7411//7411 -f 7411//7411 6930//6930 6929//6929 -f 7411//7411 6929//6929 7408//7408 -f 7408//7408 6929//6929 6931//6931 -f 7408//7408 6931//6931 7409//7409 -f 7409//7409 6931//6931 6932//6932 -f 7409//7409 6932//6932 7410//7410 -f 7452//7452 6865//6865 6866//6866 -f 7452//7452 6866//6866 7453//7453 -f 7453//7453 6866//6866 6864//6864 -f 7453//7453 6864//6864 7454//7454 -f 7454//7454 6864//6864 6863//6863 -f 7454//7454 6863//6863 7206//7206 -f 7412//7412 6907//6907 6908//6908 -f 7412//7412 6908//6908 7413//7413 -f 7413//7413 6908//6908 6909//6909 -f 7413//7413 6909//6909 7415//7415 -f 7415//7415 6909//6909 6910//6910 -f 7415//7415 6910//6910 7416//7416 -f 7416//7416 6910//6910 6756//6756 -f 7416//7416 6756//6756 6755//6755 -f 6905//6905 7432//7432 6906//6906 -f 6906//6906 7432//7432 7431//7431 -f 6906//6906 7431//7431 6891//6891 -f 6891//6891 7431//7431 7423//7423 -f 6891//6891 7423//7423 6892//6892 -f 6892//6892 7423//7423 7421//7421 -f 6892//6892 7421//7421 6893//6893 -f 6893//6893 7421//7421 7420//7420 -f 6893//6893 7420//7420 6899//6899 -f 6899//6899 7420//7420 7430//7430 -f 6899//6899 7430//7430 6900//6900 -f 6900//6900 7430//7430 7429//7429 -f 6903//6903 7433//7433 6905//6905 -f 6905//6905 7433//7433 7432//7432 -f 6901//6901 7428//7428 6894//6894 -f 6894//6894 7428//7428 7419//7419 -f 6894//6894 7419//7419 6895//6895 -f 6895//6895 7419//7419 7418//7418 -f 6895//6895 7418//7418 6898//6898 -f 6898//6898 7418//7418 7427//7427 -f 6898//6898 7427//7427 6897//6897 -f 6897//6897 7427//7427 7426//7426 -f 6897//6897 7426//7426 6902//6902 -f 6902//6902 7426//7426 7425//7425 -f 6902//6902 7425//7425 6903//6903 -f 6903//6903 7425//7425 7433//7433 -f 6900//6900 7429//7429 6901//6901 -f 6901//6901 7429//7429 7428//7428 -f 6882//6882 7439//7439 6883//6883 -f 6883//6883 7439//7439 7438//7438 -f 6883//6883 7438//7438 6880//6880 -f 6880//6880 7438//7438 7448//7448 -f 6880//6880 7448//7448 6868//6868 -f 6868//6868 7448//7448 7447//7447 -f 6868//6868 7447//7447 6869//6869 -f 6869//6869 7447//7447 7446//7446 -f 6869//6869 7446//7446 6873//6873 -f 6873//6873 7446//7446 7445//7445 -f 6873//6873 7445//7445 6874//6874 -f 6874//6874 7445//7445 7451//7451 -f 6881//6881 7440//7440 6882//6882 -f 6882//6882 7440//7440 7439//7439 -f 6875//6875 7450//7450 6872//6872 -f 6872//6872 7450//7450 7449//7449 -f 6872//6872 7449//7449 6876//6876 -f 6876//6876 7449//7449 7437//7437 -f 6876//6876 7437//7437 6877//6877 -f 6877//6877 7437//7437 7444//7444 -f 6877//6877 7444//7444 6878//6878 -f 6878//6878 7444//7444 7443//7443 -f 6878//6878 7443//7443 6879//6879 -f 6879//6879 7443//7443 7441//7441 -f 6879//6879 7441//7441 6881//6881 -f 6881//6881 7441//7441 7440//7440 -f 6874//6874 7451//7451 6875//6875 -f 6875//6875 7451//7451 7450//7450 -f 6927//6927 7405//7405 6926//6926 -f 6926//6926 7405//7405 7404//7404 -f 6926//6926 7404//7404 6911//6911 -f 6911//6911 7404//7404 7403//7403 -f 6911//6911 7403//7403 6912//6912 -f 6912//6912 7403//7403 7398//7398 -f 6912//6912 7398//7398 6914//6914 -f 6914//6914 7398//7398 7396//7396 -f 6914//6914 7396//7396 6915//6915 -f 6915//6915 7396//7396 7395//7395 -f 6915//6915 7395//7395 6916//6916 -f 6916//6916 7395//7395 7401//7401 -f 6928//6928 7406//7406 6927//6927 -f 6927//6927 7406//7406 7405//7405 -f 6923//6923 7400//7400 6924//6924 -f 6924//6924 7400//7400 7399//7399 -f 6924//6924 7399//7399 6925//6925 -f 6925//6925 7399//7399 7393//7393 -f 6925//6925 7393//7393 6922//6922 -f 6922//6922 7393//7393 7392//7392 -f 6922//6922 7392//7392 6919//6919 -f 6919//6919 7392//7392 7391//7391 -f 6919//6919 7391//7391 6920//6920 -f 6920//6920 7391//7391 7407//7407 -f 6920//6920 7407//7407 6928//6928 -f 6928//6928 7407//7407 7406//7406 -f 6916//6916 7401//7401 6923//6923 -f 6923//6923 7401//7401 7400//7400 -f 6954//6954 7386//7386 6941//6941 -f 6941//6941 7386//7386 7385//7385 -f 6941//6941 7385//7385 6942//6942 -f 6942//6942 7385//7385 7384//7384 -f 6942//6942 7384//7384 6947//6947 -f 6947//6947 7384//7384 7383//7383 -f 6947//6947 7383//7383 6943//6943 -f 6943//6943 7383//7383 7382//7382 -f 6943//6943 7382//7382 6944//6944 -f 6944//6944 7382//7382 7381//7381 -f 6944//6944 7381//7381 6946//6946 -f 6946//6946 7381//7381 7380//7380 -f 6953//6953 7387//7387 6954//6954 -f 6954//6954 7387//7387 7386//7386 -f 6938//6938 7379//7379 6939//6939 -f 6939//6939 7379//7379 7378//7378 -f 6939//6939 7378//7378 6948//6948 -f 6948//6948 7378//7378 7377//7377 -f 6948//6948 7377//7377 6949//6949 -f 6949//6949 7377//7377 7376//7376 -f 6949//6949 7376//7376 6950//6950 -f 6950//6950 7376//7376 7375//7375 -f 6950//6950 7375//7375 6952//6952 -f 6952//6952 7375//7375 7374//7374 -f 6952//6952 7374//7374 6953//6953 -f 6953//6953 7374//7374 7387//7387 -f 6946//6946 7380//7380 6938//6938 -f 6938//6938 7380//7380 7379//7379 -f 7112//7112 7482//7482 7109//7109 -f 7109//7109 7482//7482 7205//7205 -f 7109//7109 7205//7205 7099//7099 -f 7099//7099 7205//7205 7227//7227 -f 6990//6990 7338//7338 6991//6991 -f 6991//6991 7338//7338 7339//7339 -f 6991//6991 7339//7339 6992//6992 -f 6992//6992 7339//7339 7340//7340 -f 6802//6802 7291//7291 6803//6803 -f 6803//6803 7291//7291 7222//7222 -f 6803//6803 7222//7222 7037//7037 -f 7037//7037 7222//7222 7221//7221 -f 7121//7121 7599//7599 7122//7122 -f 7122//7122 7599//7599 7600//7600 -f 7122//7122 7600//7600 7123//7123 -f 7123//7123 7600//7600 7601//7601 -f 7123//7123 7601//7601 7124//7124 -f 7124//7124 7601//7601 7602//7602 -f 7124//7124 7602//7602 7119//7119 -f 7119//7119 7602//7602 7280//7280 -f 7196//7196 7534//7534 7197//7197 -f 7197//7197 7534//7534 7535//7535 -f 7197//7197 7535//7535 7198//7198 -f 7198//7198 7535//7535 7536//7536 -f 7198//7198 7536//7536 7199//7199 -f 7199//7199 7536//7536 7537//7537 -f 7199//7199 7537//7537 7020//7020 -f 7020//7020 7537//7537 7308//7308 -f 7482//7482 7112//7112 7115//7115 -f 7482//7482 7115//7115 7480//7480 -f 7480//7480 7115//7115 7116//7116 -f 7480//7480 7116//7116 7478//7478 -f 7478//7478 7116//7116 6792//6792 -f 7478//7478 6792//6792 6791//6791 -f 7099//7099 7227//7227 7232//7232 -f 7099//7099 7232//7232 7100//7100 -f 7100//7100 7232//7232 7231//7231 -f 7100//7100 7231//7231 7102//7102 -f 7102//7102 7231//7231 7230//7230 -f 7102//7102 7230//7230 7101//7101 -f 7269//7269 7074//7074 7073//7073 -f 7269//7269 7073//7073 7268//7268 -f 7268//7268 7073//7073 7072//7072 -f 7268//7268 7072//7072 7254//7254 -f 7599//7599 7121//7121 7056//7056 -f 7599//7599 7056//7056 7598//7598 -f 7598//7598 7056//7056 7055//7055 -f 7598//7598 7055//7055 7259//7259 -f 7259//7259 7055//7055 7069//7069 -f 7259//7259 7069//7069 7274//7274 -f 7119//7119 7280//7280 7278//7278 -f 7119//7119 7278//7278 7120//7120 -f 7120//7120 7278//7278 7277//7277 -f 7120//7120 7277//7277 7046//7046 -f 7291//7291 6802//6802 7041//7041 -f 7291//7291 7041//7041 7292//7292 -f 7292//7292 7041//7041 7042//7042 -f 7292//7292 7042//7042 7286//7286 -f 7037//7037 7221//7221 7295//7295 -f 7037//7037 7295//7295 7038//7038 -f 7038//7038 7295//7295 7296//7296 -f 7038//7038 7296//7296 7029//7029 -f 7534//7534 7196//7196 7024//7024 -f 7534//7534 7024//7024 7533//7533 -f 7533//7533 7024//7024 7023//7023 -f 7533//7533 7023//7023 7530//7530 -f 7020//7020 7308//7308 7306//7306 -f 7020//7020 7306//7306 7021//7021 -f 7021//7021 7306//7306 7305//7305 -f 7021//7021 7305//7305 7018//7018 -f 7018//7018 7305//7305 7313//7313 -f 7018//7018 7313//7313 7016//7016 -f 7338//7338 6990//6990 6989//6989 -f 7338//7338 6989//6989 7337//7337 -f 7337//7337 6989//6989 6988//6988 -f 7337//7337 6988//6988 7336//7336 -f 7336//7336 6988//6988 6987//6987 -f 7336//7336 6987//6987 7334//7334 -f 6992//6992 7340//7340 7347//7347 -f 6992//6992 7347//7347 6993//6993 -f 6993//6993 7347//7347 7346//7346 -f 6993//6993 7346//7346 6976//6976 -f 6976//6976 7346//7346 6780//6780 -f 6976//6976 6780//6780 6779//6779 -f 7603//7603 7604//7604 7605//7605 -f 7605//7605 7604//7604 7606//7606 -f 7605//7605 7606//7606 7607//7607 -f 7607//7607 7606//7606 7608//7608 -f 7607//7607 7608//7608 7609//7609 -f 7609//7609 7608//7608 7610//7610 -f 7609//7609 7610//7610 7611//7611 -f 7611//7611 7610//7610 7612//7612 -f 7611//7611 7612//7612 7613//7613 -f 7613//7613 7612//7612 7614//7614 -f 7613//7613 7614//7614 7615//7615 -f 7615//7615 7614//7614 7616//7616 -f 7615//7615 7616//7616 7617//7617 -f 7617//7617 7616//7616 7618//7618 -f 7617//7617 7618//7618 7619//7619 -f 7619//7619 7618//7618 7620//7620 -f 7619//7619 7620//7620 7621//7621 -f 7621//7621 7620//7620 7622//7622 -f 7621//7621 7622//7622 7623//7623 -f 7623//7623 7622//7622 7624//7624 -f 7623//7623 7624//7624 7625//7625 -f 7625//7625 7624//7624 7626//7626 -f 7625//7625 7626//7626 7603//7603 -f 7603//7603 7626//7626 7604//7604 -f 7627//7627 7628//7628 7629//7629 -f 7629//7629 7628//7628 7630//7630 -f 7629//7629 7630//7630 7631//7631 -f 7631//7631 7630//7630 7632//7632 -f 7631//7631 7632//7632 7633//7633 -f 7633//7633 7632//7632 7634//7634 -f 7633//7633 7634//7634 7635//7635 -f 7635//7635 7634//7634 7636//7636 -f 7635//7635 7636//7636 7637//7637 -f 7637//7637 7636//7636 7638//7638 -f 7637//7637 7638//7638 7639//7639 -f 7639//7639 7638//7638 7640//7640 -f 7639//7639 7640//7640 7641//7641 -f 7641//7641 7640//7640 7642//7642 -f 7641//7641 7642//7642 7643//7643 -f 7643//7643 7642//7642 7644//7644 -f 7643//7643 7644//7644 7645//7645 -f 7645//7645 7644//7644 7646//7646 -f 7645//7645 7646//7646 7647//7647 -f 7647//7647 7646//7646 7648//7648 -f 7647//7647 7648//7648 7649//7649 -f 7649//7649 7648//7648 7650//7650 -f 7649//7649 7650//7650 7627//7627 -f 7627//7627 7650//7650 7628//7628 -f 7651//7651 7652//7652 7653//7653 -f 7653//7653 7652//7652 7654//7654 -f 7653//7653 7654//7654 7655//7655 -f 7655//7655 7654//7654 7656//7656 -f 7655//7655 7656//7656 7657//7657 -f 7657//7657 7656//7656 7658//7658 -f 7657//7657 7658//7658 7659//7659 -f 7659//7659 7658//7658 7660//7660 -f 7659//7659 7660//7660 7661//7661 -f 7661//7661 7660//7660 7662//7662 -f 7661//7661 7662//7662 7663//7663 -f 7663//7663 7662//7662 7664//7664 -f 7663//7663 7664//7664 7665//7665 -f 7665//7665 7664//7664 7666//7666 -f 7665//7665 7666//7666 7667//7667 -f 7667//7667 7666//7666 7668//7668 -f 7667//7667 7668//7668 7669//7669 -f 7669//7669 7668//7668 7670//7670 -f 7669//7669 7670//7670 7671//7671 -f 7671//7671 7670//7670 7672//7672 -f 7671//7671 7672//7672 7673//7673 -f 7673//7673 7672//7672 7674//7674 -f 7673//7673 7674//7674 7651//7651 -f 7651//7651 7674//7674 7652//7652 -f 7675//7675 7676//7676 7677//7677 -f 7677//7677 7676//7676 7678//7678 -f 7677//7677 7678//7678 7679//7679 -f 7679//7679 7678//7678 7680//7680 -f 7679//7679 7680//7680 7681//7681 -f 7681//7681 7680//7680 7682//7682 -f 7681//7681 7682//7682 7683//7683 -f 7683//7683 7682//7682 7684//7684 -f 7683//7683 7684//7684 7685//7685 -f 7685//7685 7684//7684 7686//7686 -f 7685//7685 7686//7686 7687//7687 -f 7687//7687 7686//7686 7688//7688 -f 7687//7687 7688//7688 7689//7689 -f 7689//7689 7688//7688 7690//7690 -f 7689//7689 7690//7690 7691//7691 -f 7691//7691 7690//7690 7692//7692 -f 7691//7691 7692//7692 7693//7693 -f 7693//7693 7692//7692 7694//7694 -f 7693//7693 7694//7694 7695//7695 -f 7695//7695 7694//7694 7696//7696 -f 7695//7695 7696//7696 7697//7697 -f 7697//7697 7696//7696 7698//7698 -f 7697//7697 7698//7698 7675//7675 -f 7675//7675 7698//7698 7676//7676 -f 7699//7699 7700//7700 7701//7701 -f 7701//7701 7700//7700 7702//7702 -f 7701//7701 7702//7702 7703//7703 -f 7703//7703 7702//7702 7704//7704 -f 7703//7703 7704//7704 7705//7705 -f 7705//7705 7704//7704 7706//7706 -f 7705//7705 7706//7706 7707//7707 -f 7707//7707 7706//7706 7708//7708 -f 7707//7707 7708//7708 7709//7709 -f 7709//7709 7708//7708 7710//7710 -f 7709//7709 7710//7710 7711//7711 -f 7711//7711 7710//7710 7712//7712 -f 7711//7711 7712//7712 7713//7713 -f 7713//7713 7712//7712 7714//7714 -f 7713//7713 7714//7714 7715//7715 -f 7715//7715 7714//7714 7716//7716 -f 7715//7715 7716//7716 7717//7717 -f 7717//7717 7716//7716 7718//7718 -f 7717//7717 7718//7718 7719//7719 -f 7719//7719 7718//7718 7720//7720 -f 7719//7719 7720//7720 7721//7721 -f 7721//7721 7720//7720 7722//7722 -f 7721//7721 7722//7722 7699//7699 -f 7699//7699 7722//7722 7700//7700 -f 7723//7723 7724//7724 7725//7725 -f 7725//7725 7724//7724 7726//7726 -f 7725//7725 7726//7726 7727//7727 -f 7727//7727 7726//7726 7728//7728 -f 7727//7727 7728//7728 7729//7729 -f 7729//7729 7728//7728 7730//7730 -f 7729//7729 7730//7730 7731//7731 -f 7731//7731 7730//7730 7732//7732 -f 7731//7731 7732//7732 7733//7733 -f 7733//7733 7732//7732 7734//7734 -f 7733//7733 7734//7734 7735//7735 -f 7735//7735 7734//7734 7736//7736 -f 7735//7735 7736//7736 7737//7737 -f 7737//7737 7736//7736 7738//7738 -f 7737//7737 7738//7738 7739//7739 -f 7739//7739 7738//7738 7740//7740 -f 7739//7739 7740//7740 7741//7741 -f 7741//7741 7740//7740 7742//7742 -f 7741//7741 7742//7742 7743//7743 -f 7743//7743 7742//7742 7744//7744 -f 7743//7743 7744//7744 7745//7745 -f 7745//7745 7744//7744 7746//7746 -f 7745//7745 7746//7746 7723//7723 -f 7723//7723 7746//7746 7724//7724 -f 7747//7747 7748//7748 7749//7749 -f 7749//7749 7748//7748 7750//7750 -f 7749//7749 7750//7750 7751//7751 -f 7751//7751 7750//7750 7752//7752 -f 7751//7751 7752//7752 7753//7753 -f 7753//7753 7752//7752 7754//7754 -f 7753//7753 7754//7754 7755//7755 -f 7755//7755 7754//7754 7756//7756 -f 7748//7748 7747//7747 7757//7757 -f 7757//7757 7747//7747 7758//7758 -f 7757//7757 7758//7758 7759//7759 -f 7759//7759 7758//7758 7760//7760 -f 7761//7761 7762//7762 7763//7763 -f 7763//7763 7762//7762 7764//7764 -f 7763//7763 7764//7764 7765//7765 -f 7765//7765 7764//7764 7766//7766 -f 7765//7765 7766//7766 7767//7767 -f 7767//7767 7766//7766 7768//7768 -f 7767//7767 7768//7768 7769//7769 -f 7769//7769 7768//7768 7770//7770 -f 7769//7769 7770//7770 7760//7760 -f 7760//7760 7770//7770 7759//7759 -f 7771//7771 7772//7772 7773//7773 -f 7773//7773 7772//7772 7774//7774 -f 7773//7773 7774//7774 7775//7775 -f 7775//7775 7774//7774 7776//7776 -f 7775//7775 7776//7776 7777//7777 -f 7777//7777 7776//7776 7778//7778 -f 7777//7777 7778//7778 7779//7779 -f 7779//7779 7778//7778 7780//7780 -f 7779//7779 7780//7780 7781//7781 -f 7781//7781 7780//7780 7782//7782 -f 7781//7781 7782//7782 7783//7783 -f 7783//7783 7782//7782 7784//7784 -f 7785//7785 7783//7783 7786//7786 -f 7786//7786 7783//7783 7784//7784 -f 7787//7787 7788//7788 7789//7789 -f 7789//7789 7788//7788 7790//7790 -f 7789//7789 7790//7790 7791//7791 -f 7791//7791 7790//7790 7792//7792 -f 7791//7791 7792//7792 7793//7793 -f 7793//7793 7792//7792 7794//7794 -f 7795//7795 7796//7796 7797//7797 -f 7797//7797 7796//7796 7798//7798 -f 7797//7797 7798//7798 7799//7799 -f 7799//7799 7798//7798 7800//7800 -f 7799//7799 7800//7800 7801//7801 -f 7801//7801 7800//7800 7802//7802 -f 7801//7801 7802//7802 7803//7803 -f 7803//7803 7802//7802 7804//7804 -f 7803//7803 7804//7804 7794//7794 -f 7794//7794 7804//7804 7793//7793 -f 7805//7805 7806//7806 7807//7807 -f 7807//7807 7806//7806 7808//7808 -f 7807//7807 7808//7808 7809//7809 -f 7809//7809 7808//7808 7810//7810 -f 7809//7809 7810//7810 7795//7795 -f 7795//7795 7810//7810 7796//7796 -f 7811//7811 7812//7812 7813//7813 -f 7805//7805 7807//7807 7814//7814 -f 7788//7788 7815//7815 7816//7816 -f 7703//7703 7705//7705 7817//7817 -f 7818//7818 7819//7819 7651//7651 -f 7667//7667 7669//7669 7820//7820 -f 7820//7820 7669//7669 7671//7671 -f 7659//7659 7661//7661 7821//7821 -f 7821//7821 7661//7661 7663//7663 -f 7821//7821 7663//7663 7822//7822 -f 7823//7823 7824//7824 7655//7655 -f 7655//7655 7824//7824 7825//7825 -f 7651//7651 7653//7653 7818//7818 -f 7818//7818 7653//7653 7655//7655 -f 7818//7818 7655//7655 7826//7826 -f 7826//7826 7655//7655 7825//7825 -f 7826//7826 7825//7825 7827//7827 -f 7701//7701 7828//7828 7699//7699 -f 7699//7699 7828//7828 7829//7829 -f 7699//7699 7829//7829 7721//7721 -f 7711//7711 7807//7807 7709//7709 -f 7709//7709 7807//7807 7809//7809 -f 7709//7709 7809//7809 7707//7707 -f 7711//7711 7713//7713 7807//7807 -f 7807//7807 7713//7713 7715//7715 -f 7807//7807 7715//7715 7814//7814 -f 7814//7814 7715//7715 7717//7717 -f 7814//7814 7717//7717 7829//7829 -f 7829//7829 7717//7717 7719//7719 -f 7829//7829 7719//7719 7721//7721 -f 7741//7741 7743//7743 7828//7828 -f 7828//7828 7743//7743 7745//7745 -f 7828//7828 7745//7745 7811//7811 -f 7811//7811 7745//7745 7723//7723 -f 7729//7729 7812//7812 7727//7727 -f 7727//7727 7812//7812 7811//7811 -f 7727//7727 7811//7811 7725//7725 -f 7725//7725 7811//7811 7723//7723 -f 7735//7735 7737//7737 7795//7795 -f 7729//7729 7731//7731 7830//7830 -f 7830//7830 7731//7731 7733//7733 -f 7830//7830 7733//7733 7735//7735 -f 7795//7795 7817//7817 7809//7809 -f 7809//7809 7817//7817 7705//7705 -f 7809//7809 7705//7705 7707//7707 -f 7701//7701 7703//7703 7828//7828 -f 7828//7828 7703//7703 7817//7817 -f 7828//7828 7817//7817 7741//7741 -f 7741//7741 7817//7817 7795//7795 -f 7741//7741 7795//7795 7739//7739 -f 7739//7739 7795//7795 7737//7737 -f 7693//7693 7695//7695 7831//7831 -f 7755//7755 7832//7832 7681//7681 -f 7681//7681 7832//7832 7679//7679 -f 7681//7681 7683//7683 7755//7755 -f 7755//7755 7683//7683 7685//7685 -f 7755//7755 7685//7685 7753//7753 -f 7753//7753 7685//7685 7687//7687 -f 7753//7753 7687//7687 7751//7751 -f 7751//7751 7687//7687 7689//7689 -f 7751//7751 7689//7689 7691//7691 -f 7695//7695 7697//7697 7831//7831 -f 7831//7831 7697//7697 7675//7675 -f 7831//7831 7675//7675 7832//7832 -f 7832//7832 7675//7675 7677//7677 -f 7832//7832 7677//7677 7679//7679 -f 7691//7691 7693//7693 7751//7751 -f 7751//7751 7693//7693 7831//7831 -f 7751//7751 7831//7831 7749//7749 -f 7749//7749 7831//7831 7833//7833 -f 7749//7749 7833//7833 7747//7747 -f 7747//7747 7833//7833 7834//7834 -f 7769//7769 7760//7760 7834//7834 -f 7834//7834 7760//7760 7758//7758 -f 7834//7834 7758//7758 7747//7747 -f 7776//7776 7641//7641 7643//7643 -f 7633//7633 7635//7635 7774//7774 -f 7774//7774 7635//7635 7637//7637 -f 7774//7774 7637//7637 7776//7776 -f 7776//7776 7637//7637 7639//7639 -f 7776//7776 7639//7639 7641//7641 -f 7645//7645 7647//7647 7767//7767 -f 7767//7767 7647//7647 7649//7649 -f 7767//7767 7649//7649 7765//7765 -f 7765//7765 7649//7649 7627//7627 -f 7765//7765 7627//7627 7763//7763 -f 7763//7763 7627//7627 7629//7629 -f 7763//7763 7629//7629 7631//7631 -f 7643//7643 7645//7645 7776//7776 -f 7776//7776 7645//7645 7767//7767 -f 7776//7776 7767//7767 7778//7778 -f 7778//7778 7767//7767 7769//7769 -f 7778//7778 7769//7769 7780//7780 -f 7780//7780 7769//7769 7834//7834 -f 7631//7631 7633//7633 7763//7763 -f 7763//7763 7633//7633 7774//7774 -f 7763//7763 7774//7774 7761//7761 -f 7761//7761 7774//7774 7772//7772 -f 7835//7835 7836//7836 7837//7837 -f 7837//7837 7836//7836 7761//7761 -f 7837//7837 7761//7761 7838//7838 -f 7838//7838 7761//7761 7772//7772 -f 7838//7838 7772//7772 7839//7839 -f 7839//7839 7772//7772 7840//7840 -f 7613//7613 7615//7615 7815//7815 -f 7815//7815 7615//7615 7617//7617 -f 7617//7617 7619//7619 7815//7815 -f 7815//7815 7619//7619 7621//7621 -f 7815//7815 7621//7621 7816//7816 -f 7816//7816 7621//7621 7623//7623 -f 7816//7816 7623//7623 7625//7625 -f 7603//7603 7605//7605 7780//7780 -f 7613//7613 7841//7841 7611//7611 -f 7611//7611 7841//7841 7786//7786 -f 7611//7611 7786//7786 7609//7609 -f 7609//7609 7786//7786 7607//7607 -f 7607//7607 7786//7786 7784//7784 -f 7607//7607 7784//7784 7605//7605 -f 7605//7605 7784//7784 7782//7782 -f 7605//7605 7782//7782 7780//7780 -f 7613//7613 7815//7815 7841//7841 -f 7841//7841 7815//7815 7842//7842 -f 7841//7841 7842//7842 7843//7843 -f 7844//7844 7845//7845 7788//7788 -f 7788//7788 7845//7845 7846//7846 -f 7788//7788 7846//7846 7815//7815 -f 7815//7815 7846//7846 7847//7847 -f 7815//7815 7847//7847 7842//7842 -f 7735//7735 7795//7795 7830//7830 -f 7830//7830 7795//7795 7797//7797 -f 7830//7830 7797//7797 7799//7799 -f 7830//7830 7794//7794 7848//7848 -f 7848//7848 7794//7794 7792//7792 -f 7848//7848 7792//7792 7816//7816 -f 7816//7816 7792//7792 7790//7790 -f 7816//7816 7790//7790 7788//7788 -f 7799//7799 7801//7801 7830//7830 -f 7830//7830 7801//7801 7803//7803 -f 7830//7830 7803//7803 7794//7794 -f 7849//7849 7850//7850 7851//7851 -f 7851//7851 7850//7850 7852//7852 -f 7851//7851 7852//7852 7853//7853 -f 7854//7854 7855//7855 7856//7856 -f 7856//7856 7855//7855 7805//7805 -f 7856//7856 7805//7805 7857//7857 -f 7857//7857 7805//7805 7814//7814 -f 7857//7857 7814//7814 7858//7858 -f 7858//7858 7814//7814 7829//7829 -f 7811//7811 7859//7859 7828//7828 -f 7828//7828 7859//7859 7853//7853 -f 7828//7828 7853//7853 7829//7829 -f 7829//7829 7853//7853 7852//7852 -f 7829//7829 7852//7852 7858//7858 -f 7860//7860 7820//7820 7861//7861 -f 7861//7861 7820//7820 7671//7671 -f 7861//7861 7671//7671 7819//7819 -f 7819//7819 7671//7671 7673//7673 -f 7819//7819 7673//7673 7651//7651 -f 7663//7663 7665//7665 7822//7822 -f 7822//7822 7665//7665 7667//7667 -f 7822//7822 7667//7667 7813//7813 -f 7813//7813 7667//7667 7820//7820 -f 7813//7813 7820//7820 7811//7811 -f 7811//7811 7820//7820 7860//7860 -f 7811//7811 7860//7860 7859//7859 -f 7625//7625 7603//7603 7816//7816 -f 7816//7816 7603//7603 7780//7780 -f 7816//7816 7780//7780 7848//7848 -f 7848//7848 7780//7780 7834//7834 -f 7848//7848 7834//7834 7830//7830 -f 7830//7830 7834//7834 7833//7833 -f 7729//7729 7830//7830 7812//7812 -f 7812//7812 7830//7830 7833//7833 -f 7812//7812 7833//7833 7813//7813 -f 7813//7813 7833//7833 7831//7831 -f 7813//7813 7831//7831 7822//7822 -f 7822//7822 7831//7831 7832//7832 -f 7822//7822 7832//7832 7821//7821 -f 7862//7862 7863//7863 7755//7755 -f 7755//7755 7863//7863 7864//7864 -f 7755//7755 7864//7864 7832//7832 -f 7832//7832 7864//7864 7865//7865 -f 7832//7832 7865//7865 7821//7821 -f 7821//7821 7865//7865 7866//7866 -f 7821//7821 7866//7866 7659//7659 -f 7659//7659 7866//7866 7823//7823 -f 7659//7659 7823//7823 7657//7657 -f 7657//7657 7823//7823 7655//7655 -f 7678//7678 7676//7676 7867//7867 -f 7672//7672 7670//7670 7868//7868 -f 7662//7662 7660//7660 7869//7869 -f 7870//7870 7871//7871 7652//7652 -f 7872//7872 7873//7873 7874//7874 -f 7872//7872 7658//7658 7875//7875 -f 7875//7875 7658//7658 7656//7656 -f 7875//7875 7656//7656 7871//7871 -f 7871//7871 7656//7656 7654//7654 -f 7871//7871 7654//7654 7652//7652 -f 7872//7872 7874//7874 7658//7658 -f 7658//7658 7874//7874 7876//7876 -f 7658//7658 7876//7876 7660//7660 -f 7660//7660 7876//7876 7877//7877 -f 7660//7660 7877//7877 7869//7869 -f 7878//7878 7668//7668 7879//7879 -f 7879//7879 7668//7668 7666//7666 -f 7879//7879 7666//7666 7869//7869 -f 7869//7869 7666//7666 7664//7664 -f 7869//7869 7664//7664 7662//7662 -f 7704//7704 7880//7880 7706//7706 -f 7706//7706 7880//7880 7881//7881 -f 7706//7706 7881//7881 7708//7708 -f 7718//7718 7882//7882 7720//7720 -f 7720//7720 7882//7882 7883//7883 -f 7704//7704 7702//7702 7880//7880 -f 7880//7880 7702//7702 7700//7700 -f 7880//7880 7700//7700 7883//7883 -f 7883//7883 7700//7700 7722//7722 -f 7883//7883 7722//7722 7720//7720 -f 7710//7710 7810//7810 7712//7712 -f 7712//7712 7810//7810 7808//7808 -f 7712//7712 7808//7808 7714//7714 -f 7714//7714 7808//7808 7716//7716 -f 7730//7730 7728//7728 7884//7884 -f 7728//7728 7726//7726 7884//7884 -f 7884//7884 7726//7726 7724//7724 -f 7884//7884 7724//7724 7880//7880 -f 7736//7736 7734//7734 7885//7885 -f 7710//7710 7708//7708 7810//7810 -f 7810//7810 7708//7708 7881//7881 -f 7810//7810 7881//7881 7796//7796 -f 7740//7740 7796//7796 7742//7742 -f 7742//7742 7796//7796 7881//7881 -f 7742//7742 7881//7881 7744//7744 -f 7744//7744 7881//7881 7880//7880 -f 7744//7744 7880//7880 7746//7746 -f 7746//7746 7880//7880 7724//7724 -f 7736//7736 7885//7885 7738//7738 -f 7886//7886 7887//7887 7888//7888 -f 7889//7889 7890//7890 7887//7887 -f 7887//7887 7890//7890 7891//7891 -f 7887//7887 7891//7891 7888//7888 -f 7806//7806 7892//7892 7893//7893 -f 7893//7893 7894//7894 7806//7806 -f 7806//7806 7894//7894 7882//7882 -f 7806//7806 7882//7882 7808//7808 -f 7808//7808 7882//7882 7718//7718 -f 7808//7808 7718//7718 7716//7716 -f 7791//7791 7793//7793 7885//7885 -f 7793//7793 7804//7804 7885//7885 -f 7885//7885 7804//7804 7802//7802 -f 7885//7885 7802//7802 7800//7800 -f 7740//7740 7738//7738 7796//7796 -f 7796//7796 7738//7738 7885//7885 -f 7796//7796 7885//7885 7798//7798 -f 7798//7798 7885//7885 7800//7800 -f 7895//7895 7896//7896 7897//7897 -f 7897//7897 7896//7896 7787//7787 -f 7898//7898 7899//7899 7900//7900 -f 7900//7900 7899//7899 7901//7901 -f 7900//7900 7901//7901 7902//7902 -f 7606//7606 7604//7604 7903//7903 -f 7903//7903 7604//7604 7626//7626 -f 7626//7626 7624//7624 7903//7903 -f 7903//7903 7624//7624 7622//7622 -f 7903//7903 7622//7622 7900//7900 -f 7900//7900 7622//7622 7620//7620 -f 7620//7620 7618//7618 7900//7900 -f 7900//7900 7618//7618 7616//7616 -f 7900//7900 7616//7616 7898//7898 -f 7898//7898 7616//7616 7614//7614 -f 7898//7898 7614//7614 7785//7785 -f 7614//7614 7612//7612 7785//7785 -f 7785//7785 7612//7612 7610//7610 -f 7785//7785 7610//7610 7783//7783 -f 7783//7783 7610//7610 7608//7608 -f 7783//7783 7608//7608 7781//7781 -f 7781//7781 7608//7608 7606//7606 -f 7781//7781 7606//7606 7779//7779 -f 7606//7606 7903//7903 7779//7779 -f 7779//7779 7903//7903 7904//7904 -f 7779//7779 7904//7904 7905//7905 -f 7770//7770 7779//7779 7759//7759 -f 7759//7759 7779//7779 7905//7905 -f 7759//7759 7905//7905 7757//7757 -f 7757//7757 7905//7905 7748//7748 -f 7634//7634 7632//7632 7764//7764 -f 7764//7764 7632//7632 7630//7630 -f 7764//7764 7630//7630 7766//7766 -f 7766//7766 7630//7630 7628//7628 -f 7766//7766 7628//7628 7768//7768 -f 7768//7768 7628//7628 7650//7650 -f 7768//7768 7650//7650 7648//7648 -f 7648//7648 7646//7646 7768//7768 -f 7768//7768 7646//7646 7775//7775 -f 7768//7768 7775//7775 7770//7770 -f 7770//7770 7775//7775 7777//7777 -f 7770//7770 7777//7777 7779//7779 -f 7646//7646 7644//7644 7775//7775 -f 7775//7775 7644//7644 7642//7642 -f 7775//7775 7642//7642 7773//7773 -f 7773//7773 7642//7642 7640//7640 -f 7640//7640 7638//7638 7773//7773 -f 7773//7773 7638//7638 7636//7636 -f 7773//7773 7636//7636 7634//7634 -f 7634//7634 7764//7764 7773//7773 -f 7773//7773 7764//7764 7762//7762 -f 7773//7773 7762//7762 7771//7771 -f 7906//7906 7907//7907 7908//7908 -f 7908//7908 7907//7907 7771//7771 -f 7908//7908 7771//7771 7909//7909 -f 7909//7909 7771//7771 7762//7762 -f 7909//7909 7762//7762 7910//7910 -f 7910//7910 7762//7762 7911//7911 -f 7867//7867 7676//7676 7912//7912 -f 7912//7912 7676//7676 7698//7698 -f 7912//7912 7698//7698 7696//7696 -f 7696//7696 7694//7694 7912//7912 -f 7912//7912 7694//7694 7752//7752 -f 7912//7912 7752//7752 7913//7913 -f 7913//7913 7752//7752 7750//7750 -f 7694//7694 7692//7692 7752//7752 -f 7752//7752 7692//7692 7690//7690 -f 7752//7752 7690//7690 7754//7754 -f 7754//7754 7690//7690 7688//7688 -f 7754//7754 7688//7688 7756//7756 -f 7756//7756 7688//7688 7686//7686 -f 7686//7686 7684//7684 7756//7756 -f 7756//7756 7684//7684 7682//7682 -f 7756//7756 7682//7682 7867//7867 -f 7867//7867 7682//7682 7680//7680 -f 7867//7867 7680//7680 7678//7678 -f 7914//7914 7915//7915 7916//7916 -f 7916//7916 7915//7915 7756//7756 -f 7916//7916 7756//7756 7917//7917 -f 7917//7917 7756//7756 7867//7867 -f 7670//7670 7668//7668 7868//7868 -f 7868//7868 7668//7668 7878//7878 -f 7868//7868 7878//7878 7884//7884 -f 7884//7884 7878//7878 7918//7918 -f 7884//7884 7918//7918 7730//7730 -f 7730//7730 7918//7918 7732//7732 -f 7877//7877 7917//7917 7869//7869 -f 7869//7869 7917//7917 7867//7867 -f 7869//7869 7867//7867 7879//7879 -f 7879//7879 7867//7867 7912//7912 -f 7879//7879 7912//7912 7878//7878 -f 7878//7878 7912//7912 7913//7913 -f 7878//7878 7913//7913 7918//7918 -f 7918//7918 7913//7913 7885//7885 -f 7918//7918 7885//7885 7732//7732 -f 7732//7732 7885//7885 7734//7734 -f 7750//7750 7748//7748 7913//7913 -f 7913//7913 7748//7748 7905//7905 -f 7913//7913 7905//7905 7885//7885 -f 7885//7885 7905//7905 7904//7904 -f 7885//7885 7904//7904 7791//7791 -f 7791//7791 7904//7904 7903//7903 -f 7791//7791 7903//7903 7789//7789 -f 7789//7789 7903//7903 7900//7900 -f 7789//7789 7900//7900 7787//7787 -f 7787//7787 7900//7900 7902//7902 -f 7787//7787 7902//7902 7897//7897 -f 7894//7894 7919//7919 7882//7882 -f 7882//7882 7919//7919 7886//7886 -f 7882//7882 7886//7886 7883//7883 -f 7883//7883 7886//7886 7888//7888 -f 7883//7883 7888//7888 7880//7880 -f 7880//7880 7888//7888 7920//7920 -f 7880//7880 7920//7920 7884//7884 -f 7884//7884 7920//7920 7921//7921 -f 7884//7884 7921//7921 7868//7868 -f 7868//7868 7921//7921 7922//7922 -f 7868//7868 7922//7922 7672//7672 -f 7672//7672 7922//7922 7870//7870 -f 7672//7672 7870//7870 7674//7674 -f 7674//7674 7870//7870 7652//7652 -f 7826//7826 7875//7875 7818//7818 -f 7818//7818 7875//7875 7871//7871 -f 7818//7818 7871//7871 7819//7819 -f 7819//7819 7871//7871 7870//7870 -f 7819//7819 7870//7870 7861//7861 -f 7861//7861 7870//7870 7922//7922 -f 7861//7861 7922//7922 7860//7860 -f 7860//7860 7922//7922 7921//7921 -f 7860//7860 7921//7921 7859//7859 -f 7859//7859 7921//7921 7920//7920 -f 7859//7859 7920//7920 7853//7853 -f 7853//7853 7920//7920 7888//7888 -f 7853//7853 7888//7888 7851//7851 -f 7851//7851 7888//7888 7891//7891 -f 7852//7852 7887//7887 7858//7858 -f 7858//7858 7887//7887 7886//7886 -f 7858//7858 7886//7886 7857//7857 -f 7857//7857 7886//7886 7919//7919 -f 7857//7857 7919//7919 7856//7856 -f 7856//7856 7919//7919 7894//7894 -f 7851//7851 7891//7891 7890//7890 -f 7851//7851 7890//7890 7849//7849 -f 7849//7849 7890//7890 7889//7889 -f 7849//7849 7889//7889 7850//7850 -f 7850//7850 7889//7889 7887//7887 -f 7850//7850 7887//7887 7852//7852 -f 7856//7856 7894//7894 7893//7893 -f 7856//7856 7893//7893 7854//7854 -f 7854//7854 7893//7893 7892//7892 -f 7854//7854 7892//7892 7855//7855 -f 7855//7855 7892//7892 7806//7806 -f 7855//7855 7806//7806 7805//7805 -f 7846//7846 7897//7897 7847//7847 -f 7847//7847 7897//7897 7902//7902 -f 7847//7847 7902//7902 7842//7842 -f 7842//7842 7902//7902 7901//7901 -f 7874//7874 7824//7824 7876//7876 -f 7876//7876 7824//7824 7823//7823 -f 7876//7876 7823//7823 7877//7877 -f 7877//7877 7823//7823 7866//7866 -f 7877//7877 7866//7866 7917//7917 -f 7917//7917 7866//7866 7865//7865 -f 7917//7917 7865//7865 7916//7916 -f 7916//7916 7865//7865 7864//7864 -f 7837//7837 7838//7838 7909//7909 -f 7909//7909 7838//7838 7908//7908 -f 7824//7824 7874//7874 7873//7873 -f 7824//7824 7873//7873 7825//7825 -f 7825//7825 7873//7873 7872//7872 -f 7825//7825 7872//7872 7827//7827 -f 7827//7827 7872//7872 7875//7875 -f 7827//7827 7875//7875 7826//7826 -f 7755//7755 7756//7756 7915//7915 -f 7755//7755 7915//7915 7862//7862 -f 7862//7862 7915//7915 7914//7914 -f 7862//7862 7914//7914 7863//7863 -f 7863//7863 7914//7914 7916//7916 -f 7863//7863 7916//7916 7864//7864 -f 7837//7837 7909//7909 7910//7910 -f 7837//7837 7910//7910 7835//7835 -f 7835//7835 7910//7910 7911//7911 -f 7835//7835 7911//7911 7836//7836 -f 7836//7836 7911//7911 7762//7762 -f 7836//7836 7762//7762 7761//7761 -f 7908//7908 7838//7838 7839//7839 -f 7908//7908 7839//7839 7906//7906 -f 7906//7906 7839//7839 7840//7840 -f 7906//7906 7840//7840 7907//7907 -f 7907//7907 7840//7840 7772//7772 -f 7907//7907 7772//7772 7771//7771 -f 7897//7897 7846//7846 7845//7845 -f 7897//7897 7845//7845 7895//7895 -f 7895//7895 7845//7845 7844//7844 -f 7895//7895 7844//7844 7896//7896 -f 7896//7896 7844//7844 7788//7788 -f 7896//7896 7788//7788 7787//7787 -f 7842//7842 7901//7901 7899//7899 -f 7842//7842 7899//7899 7843//7843 -f 7843//7843 7899//7899 7898//7898 -f 7843//7843 7898//7898 7841//7841 -f 7841//7841 7898//7898 7785//7785 -f 7841//7841 7785//7785 7786//7786 -f 7923//7923 7924//7924 7925//7925 -f 7925//7925 7924//7924 7926//7926 -f 7925//7925 7926//7926 7927//7927 -f 7927//7927 7926//7926 7928//7928 -f 7927//7927 7928//7928 7929//7929 -f 7929//7929 7928//7928 7930//7930 -f 7929//7929 7930//7930 7931//7931 -f 7931//7931 7930//7930 7932//7932 -f 7931//7931 7932//7932 7933//7933 -f 7933//7933 7932//7932 7934//7934 -f 7935//7935 7936//7936 7937//7937 -f 7938//7938 7939//7939 7940//7940 -f 7941//7941 7942//7942 7943//7943 -f 7943//7943 7942//7942 7944//7944 -f 7943//7943 7944//7944 7945//7945 -f 7946//7946 7947//7947 7948//7948 -f 7948//7948 7947//7947 7949//7949 -f 7948//7948 7949//7949 7950//7950 -f 7951//7951 7952//7952 7936//7936 -f 7936//7936 7952//7952 7953//7953 -f 7936//7936 7953//7953 7946//7946 -f 7954//7954 7948//7948 7955//7955 -f 7955//7955 7948//7948 7950//7950 -f 7955//7955 7950//7950 7941//7941 -f 7941//7941 7950//7950 7956//7956 -f 7941//7941 7956//7956 7942//7942 -f 7957//7957 7958//7958 7959//7959 -f 7959//7959 7958//7958 7941//7941 -f 7959//7959 7941//7941 7960//7960 -f 7958//7958 7961//7961 7941//7941 -f 7941//7941 7961//7961 7962//7962 -f 7941//7941 7962//7962 7955//7955 -f 7955//7955 7962//7962 7963//7963 -f 7955//7955 7963//7963 7954//7954 -f 7964//7964 7965//7965 7966//7966 -f 7966//7966 7965//7965 7967//7967 -f 7966//7966 7967//7967 7959//7959 -f 7959//7959 7967//7967 7968//7968 -f 7959//7959 7968//7968 7957//7957 -f 7969//7969 7970//7970 7971//7971 -f 7971//7971 7970//7970 7965//7965 -f 7971//7971 7965//7965 7972//7972 -f 7972//7972 7965//7965 7964//7964 -f 7963//7963 7973//7973 7954//7954 -f 7954//7954 7973//7973 7974//7974 -f 7954//7954 7974//7974 7969//7969 -f 7969//7969 7974//7974 7975//7975 -f 7969//7969 7975//7975 7970//7970 -f 7976//7976 7977//7977 7978//7978 -f 7978//7978 7977//7977 7979//7979 -f 7978//7978 7979//7979 7980//7980 -f 7980//7980 7979//7979 7981//7981 -f 7982//7982 7983//7983 7923//7923 -f 7979//7979 7984//7984 7981//7981 -f 7981//7981 7984//7984 7985//7985 -f 7981//7981 7985//7985 7986//7986 -f 7986//7986 7985//7985 7987//7987 -f 7988//7988 7989//7989 7927//7927 -f 7927//7927 7989//7989 7990//7990 -f 7927//7927 7990//7990 7925//7925 -f 7925//7925 7990//7990 7991//7991 -f 7987//7987 7982//7982 7986//7986 -f 7986//7986 7982//7982 7923//7923 -f 7986//7986 7923//7923 7992//7992 -f 7992//7992 7923//7923 7925//7925 -f 7992//7992 7925//7925 7993//7993 -f 7993//7993 7925//7925 7991//7991 -f 7994//7994 7995//7995 7996//7996 -f 7996//7996 7995//7995 7997//7997 -f 7937//7937 7998//7998 7999//7999 -f 7999//7999 7998//7998 7996//7996 -f 7999//7999 7996//7996 8000//8000 -f 8000//8000 7996//7996 7997//7997 -f 8000//8000 7997//7997 8001//8001 -f 8002//8002 8003//8003 7936//7936 -f 7946//7946 7948//7948 7936//7936 -f 7936//7936 7948//7948 8004//8004 -f 7936//7936 8004//8004 8002//8002 -f 8003//8003 8005//8005 7936//7936 -f 7936//7936 8005//8005 8006//8006 -f 7936//7936 8006//8006 7937//7937 -f 7937//7937 8006//8006 8007//8007 -f 7937//7937 8007//8007 7998//7998 -f 8008//8008 8009//8009 8010//8010 -f 8011//8011 8012//8012 8013//8013 -f 8014//8014 8015//8015 7935//7935 -f 7935//7935 8015//8015 8016//8016 -f 7935//7935 8016//8016 7940//7940 -f 8016//8016 8017//8017 7940//7940 -f 7940//7940 8017//8017 8018//8018 -f 7940//7940 8018//8018 8019//8019 -f 8010//8010 7938//7938 8008//8008 -f 8008//8008 7938//7938 7940//7940 -f 8008//8008 7940//7940 8020//8020 -f 8020//8020 7940//7940 8019//8019 -f 8020//8020 8021//8021 8008//8008 -f 8008//8008 8021//8021 8022//8022 -f 8008//8008 8022//8022 8023//8023 -f 8023//8023 8022//8022 8024//8024 -f 8023//8023 8024//8024 8025//8025 -f 8025//8025 8024//8024 8011//8011 -f 8025//8025 8011//8011 8026//8026 -f 8026//8026 8011//8011 8013//8013 -f 8026//8026 8013//8013 8027//8027 -f 8028//8028 8029//8029 8030//8030 -f 8031//8031 8032//8032 8033//8033 -f 8013//8013 8034//8034 8035//8035 -f 8035//8035 8036//8036 8013//8013 -f 8013//8013 8036//8036 8037//8037 -f 8013//8013 8037//8037 8038//8038 -f 8038//8038 8039//8039 8013//8013 -f 8013//8013 8039//8039 8040//8040 -f 8013//8013 8040//8040 8027//8027 -f 8033//8033 8041//8041 8031//8031 -f 8031//8031 8041//8041 8042//8042 -f 8031//8031 8042//8042 8043//8043 -f 8043//8043 8042//8042 8044//8044 -f 8043//8043 8044//8044 8034//8034 -f 8034//8034 8044//8044 8045//8045 -f 8034//8034 8045//8045 8035//8035 -f 8029//8029 8028//8028 8046//8046 -f 8046//8046 8028//8028 8047//8047 -f 8046//8046 8047//8047 8037//8037 -f 8037//8037 8047//8047 8048//8048 -f 8037//8037 8048//8048 8038//8038 -f 8030//8030 8032//8032 8028//8028 -f 8028//8028 8032//8032 8031//8031 -f 8028//8028 8031//8031 8049//8049 -f 8049//8049 8031//8031 8050//8050 -f 8051//8051 8052//8052 8053//8053 -f 8053//8053 8052//8052 8049//8049 -f 8053//8053 8049//8049 8054//8054 -f 8054//8054 8049//8049 8050//8050 -f 8054//8054 8050//8050 8055//8055 -f 8055//8055 8050//8050 8056//8056 -f 8057//8057 8034//8034 8058//8058 -f 8058//8058 8034//8034 8059//8059 -f 8057//8057 8058//8058 8060//8060 -f 8060//8060 8058//8058 8061//8061 -f 8060//8060 8061//8061 8062//8062 -f 8063//8063 8064//8064 8000//8000 -f 8000//8000 8064//8064 8065//8065 -f 8000//8000 8065//8065 7999//7999 -f 7999//7999 8065//8065 8066//8066 -f 7999//7999 8066//8066 8067//8067 -f 8061//8061 8068//8068 8062//8062 -f 8062//8062 8068//8068 8069//8069 -f 8062//8062 8069//8069 8070//8070 -f 8070//8070 8069//8069 8071//8071 -f 8070//8070 8071//8071 8000//8000 -f 8000//8000 8071//8071 8072//8072 -f 8000//8000 8072//8072 8063//8063 -f 8073//8073 8070//8070 8074//8074 -f 8074//8074 8070//8070 8000//8000 -f 8074//8074 8000//8000 8075//8075 -f 8075//8075 8000//8000 8001//8001 -f 8076//8076 8077//8077 7933//7933 -f 7933//7933 8077//8077 7960//7960 -f 7933//7933 7960//7960 7931//7931 -f 7931//7931 7960//7960 7941//7941 -f 7931//7931 7941//7941 7929//7929 -f 7929//7929 7941//7941 7943//7943 -f 7929//7929 7943//7943 7927//7927 -f 7927//7927 7943//7943 8078//8078 -f 7927//7927 8078//8078 7988//7988 -f 7988//7988 8078//8078 8079//8079 -f 7945//7945 8080//8080 7943//7943 -f 7943//7943 8080//8080 8081//8081 -f 7943//7943 8081//8081 8078//8078 -f 8078//8078 8081//8081 7977//7977 -f 8078//8078 7977//7977 8079//8079 -f 8079//8079 7977//7977 7976//7976 -f 8067//8067 8059//8059 7999//7999 -f 7999//7999 8059//8059 8034//8034 -f 7999//7999 8034//8034 7937//7937 -f 7937//7937 8034//8034 8013//8013 -f 7937//7937 8013//8013 7935//7935 -f 7935//7935 8013//8013 8012//8012 -f 7935//7935 8012//8012 8014//8014 -f 8080//8080 7951//7951 8081//8081 -f 8081//8081 7951//7951 7936//7936 -f 8081//8081 7936//7936 7977//7977 -f 7977//7977 7936//7936 7935//7935 -f 7977//7977 7935//7935 7979//7979 -f 7979//7979 7935//7935 7940//7940 -f 7979//7979 7940//7940 7984//7984 -f 7984//7984 7940//7940 7939//7939 -f 8082//8082 8083//8083 8084//8084 -f 8084//8084 8083//8083 8085//8085 -f 8086//8086 8087//8087 8088//8088 -f 8088//8088 8087//8087 8089//8089 -f 8088//8088 8089//8089 8082//8082 -f 8083//8083 8090//8090 8085//8085 -f 8085//8085 8090//8090 8091//8091 -f 8085//8085 8091//8091 8092//8092 -f 8092//8092 8091//8091 8093//8093 -f 8094//8094 8095//8095 8096//8096 -f 8096//8096 8095//8095 8097//8097 -f 8096//8096 8097//8097 8098//8098 -f 8099//8099 8100//8100 8101//8101 -f 8102//8102 8103//8103 8104//8104 -f 8104//8104 8103//8103 8105//8105 -f 8104//8104 8105//8105 8106//8106 -f 8102//8102 8104//8104 8107//8107 -f 8107//8107 8104//8104 8108//8108 -f 8107//8107 8108//8108 8109//8109 -f 8109//8109 8108//8108 8110//8110 -f 8109//8109 8110//8110 8111//8111 -f 8106//8106 8112//8112 8113//8113 -f 8113//8113 8112//8112 8114//8114 -f 8113//8113 8114//8114 8115//8115 -f 8115//8115 8114//8114 8116//8116 -f 8115//8115 8116//8116 8117//8117 -f 8117//8117 8116//8116 8099//8099 -f 8117//8117 8099//8099 8118//8118 -f 8118//8118 8099//8099 8101//8101 -f 8118//8118 8101//8101 8119//8119 -f 8119//8119 8101//8101 8120//8120 -f 8106//8106 8113//8113 8104//8104 -f 8104//8104 8113//8113 8121//8121 -f 8104//8104 8121//8121 8122//8122 -f 8123//8123 8124//8124 8125//8125 -f 8125//8125 8124//8124 8122//8122 -f 8125//8125 8122//8122 8126//8126 -f 8126//8126 8122//8122 8121//8121 -f 8126//8126 8121//8121 8127//8127 -f 8127//8127 8121//8121 8128//8128 -f 8129//8129 8130//8130 8101//8101 -f 8101//8101 8130//8130 8131//8131 -f 8101//8101 8131//8131 8132//8132 -f 8133//8133 8134//8134 8135//8135 -f 8135//8135 8134//8134 8136//8136 -f 8135//8135 8136//8136 8137//8137 -f 8137//8137 8136//8136 8138//8138 -f 8137//8137 8138//8138 8139//8139 -f 8133//8133 8135//8135 8140//8140 -f 8140//8140 8135//8135 8141//8141 -f 8140//8140 8141//8141 8132//8132 -f 8142//8142 8143//8143 8129//8129 -f 8129//8129 8143//8143 8144//8144 -f 8129//8129 8144//8144 8130//8130 -f 8141//8141 8145//8145 8132//8132 -f 8132//8132 8145//8145 8146//8146 -f 8132//8132 8146//8146 8101//8101 -f 8101//8101 8146//8146 8147//8147 -f 8101//8101 8147//8147 8120//8120 -f 8148//8148 7926//7926 7924//7924 -f 8148//8148 7924//7924 8149//8149 -f 8149//8149 7924//7924 8150//8150 -f 8149//8149 8150//8150 8151//8151 -f 8152//8152 8153//8153 8154//8154 -f 8155//8155 8156//8156 8154//8154 -f 8154//8154 8156//8156 7934//7934 -f 8154//8154 7934//7934 8152//8152 -f 8157//8157 8158//8158 8159//8159 -f 8160//8160 8161//8161 8162//8162 -f 8162//8162 8161//8161 8163//8163 -f 8162//8162 8163//8163 8164//8164 -f 8165//8165 8164//8164 8166//8166 -f 8165//8165 8167//8167 8168//8168 -f 8168//8168 8167//8167 8169//8169 -f 8170//8170 8171//8171 8168//8168 -f 8171//8171 8172//8172 8168//8168 -f 8168//8168 8172//8172 8173//8173 -f 8168//8168 8173//8173 8165//8165 -f 8174//8174 8175//8175 8168//8168 -f 8168//8168 8175//8175 8176//8176 -f 8168//8168 8176//8176 8170//8170 -f 8091//8091 8177//8177 8093//8093 -f 8093//8093 8177//8177 8094//8094 -f 8093//8093 8094//8094 8110//8110 -f 8110//8110 8094//8094 8096//8096 -f 8110//8110 8096//8096 8174//8174 -f 8174//8174 8096//8096 8178//8178 -f 8174//8174 8178//8178 8175//8175 -f 8098//8098 8086//8086 8096//8096 -f 8096//8096 8086//8086 8088//8088 -f 8096//8096 8088//8088 8178//8178 -f 8178//8178 8088//8088 8179//8179 -f 8180//8180 8181//8181 8182//8182 -f 8182//8182 8181//8181 8179//8179 -f 8182//8182 8179//8179 8183//8183 -f 8183//8183 8179//8179 8088//8088 -f 8183//8183 8088//8088 8184//8184 -f 8184//8184 8088//8088 8185//8185 -f 8082//8082 8084//8084 8088//8088 -f 8088//8088 8084//8084 8186//8186 -f 8088//8088 8186//8186 8185//8185 -f 8169//8169 8187//8187 8168//8168 -f 8168//8168 8187//8187 8188//8188 -f 8168//8168 8188//8188 8189//8189 -f 8189//8189 8188//8188 8190//8190 -f 8189//8189 8190//8190 8191//8191 -f 8191//8191 8190//8190 8192//8192 -f 8192//8192 8193//8193 8191//8191 -f 8191//8191 8193//8193 8194//8194 -f 8191//8191 8194//8194 8152//8152 -f 8194//8194 8195//8195 8152//8152 -f 8152//8152 8195//8195 8196//8196 -f 8152//8152 8196//8196 8166//8166 -f 8166//8166 8196//8196 8197//8197 -f 8166//8166 8197//8197 8165//8165 -f 8165//8165 8197//8197 8198//8198 -f 8165//8165 8198//8198 8167//8167 -f 8163//8163 8199//8199 8164//8164 -f 8164//8164 8199//8199 8200//8200 -f 8164//8164 8200//8200 8166//8166 -f 8166//8166 8200//8200 8201//8201 -f 8166//8166 8201//8201 8152//8152 -f 8152//8152 8201//8201 8202//8202 -f 8162//8162 8157//8157 8160//8160 -f 8160//8160 8157//8157 8159//8159 -f 8160//8160 8159//8159 8203//8203 -f 8203//8203 8159//8159 8204//8204 -f 8203//8203 8204//8204 8205//8205 -f 8205//8205 8204//8204 8153//8153 -f 8202//8202 8206//8206 8152//8152 -f 8152//8152 8206//8206 8207//8207 -f 8152//8152 8207//8207 8153//8153 -f 8153//8153 8207//8207 8208//8208 -f 8153//8153 8208//8208 8205//8205 -f 8209//8209 8210//8210 8211//8211 -f 8211//8211 8210//8210 8212//8212 -f 8213//8213 8214//8214 8215//8215 -f 8215//8215 8214//8214 8216//8216 -f 8148//8148 8217//8217 7926//7926 -f 7926//7926 8217//8217 8218//8218 -f 7926//7926 8218//8218 7928//7928 -f 7928//7928 8218//8218 8219//8219 -f 7928//7928 8219//8219 8220//8220 -f 8151//8151 8221//8221 8149//8149 -f 8149//8149 8221//8221 8222//8222 -f 8149//8149 8222//8222 8223//8223 -f 8223//8223 8222//8222 8224//8224 -f 8225//8225 8226//8226 8227//8227 -f 8227//8227 8226//8226 8135//8135 -f 8227//8227 8135//8135 8228//8228 -f 8228//8228 8135//8135 8137//8137 -f 8228//8228 8137//8137 8224//8224 -f 8224//8224 8137//8137 8215//8215 -f 8224//8224 8215//8215 8223//8223 -f 8223//8223 8215//8215 8216//8216 -f 8139//8139 8142//8142 8137//8137 -f 8137//8137 8142//8142 8129//8129 -f 8137//8137 8129//8129 8215//8215 -f 8215//8215 8129//8129 8211//8211 -f 8215//8215 8211//8211 8213//8213 -f 8213//8213 8211//8211 8212//8212 -f 8191//8191 8209//8209 8189//8189 -f 8189//8189 8209//8209 8211//8211 -f 8189//8189 8211//8211 8168//8168 -f 8168//8168 8211//8211 8129//8129 -f 8168//8168 8129//8129 8174//8174 -f 8174//8174 8129//8129 8101//8101 -f 8174//8174 8101//8101 8110//8110 -f 8110//8110 8101//8101 8100//8100 -f 8110//8110 8100//8100 8111//8111 -f 7934//7934 7932//7932 8152//8152 -f 8152//8152 7932//7932 7930//7930 -f 8152//8152 7930//7930 8191//8191 -f 8191//8191 7930//7930 7928//7928 -f 8191//8191 7928//7928 8209//8209 -f 8209//8209 7928//7928 8220//8220 -f 8209//8209 8220//8220 8210//8210 -f 7969//7969 8162//8162 7954//7954 -f 7954//7954 8162//8162 8164//8164 -f 7954//7954 8164//8164 7948//7948 -f 7948//7948 8164//8164 8165//8165 -f 8085//8085 8092//8092 8062//8062 -f 8062//8062 8092//8092 8060//8060 -f 8122//8122 8050//8050 8104//8104 -f 8104//8104 8050//8050 8031//8031 -f 8104//8104 8031//8031 8108//8108 -f 8108//8108 8031//8031 8043//8043 -f 8060//8060 8092//8092 8057//8057 -f 8057//8057 8092//8092 8093//8093 -f 8057//8057 8093//8093 8034//8034 -f 8034//8034 8093//8093 8110//8110 -f 8034//8034 8110//8110 8043//8043 -f 8043//8043 8110//8110 8108//8108 -f 8095//8095 8059//8059 8097//8097 -f 8097//8097 8059//8059 8067//8067 -f 8097//8097 8067//8067 8098//8098 -f 8098//8098 8067//8067 8066//8066 -f 8098//8098 8066//8066 8086//8086 -f 8086//8086 8066//8066 8065//8065 -f 8086//8086 8065//8065 8087//8087 -f 8087//8087 8065//8065 8064//8064 -f 8087//8087 8064//8064 8089//8089 -f 8089//8089 8064//8064 8063//8063 -f 8089//8089 8063//8063 8082//8082 -f 8082//8082 8063//8063 8072//8072 -f 8082//8082 8072//8072 8083//8083 -f 8083//8083 8072//8072 8071//8071 -f 8083//8083 8071//8071 8090//8090 -f 8090//8090 8071//8071 8069//8069 -f 8090//8090 8069//8069 8091//8091 -f 8091//8091 8069//8069 8068//8068 -f 8091//8091 8068//8068 8177//8177 -f 8177//8177 8068//8068 8061//8061 -f 8177//8177 8061//8061 8094//8094 -f 8094//8094 8061//8061 8058//8058 -f 8094//8094 8058//8058 8095//8095 -f 8095//8095 8058//8058 8059//8059 -f 8116//8116 8046//8046 8099//8099 -f 8099//8099 8046//8046 8037//8037 -f 8099//8099 8037//8037 8100//8100 -f 8100//8100 8037//8037 8036//8036 -f 8100//8100 8036//8036 8111//8111 -f 8111//8111 8036//8036 8035//8035 -f 8111//8111 8035//8035 8109//8109 -f 8109//8109 8035//8035 8045//8045 -f 8109//8109 8045//8045 8107//8107 -f 8107//8107 8045//8045 8044//8044 -f 8107//8107 8044//8044 8102//8102 -f 8102//8102 8044//8044 8042//8042 -f 8102//8102 8042//8042 8103//8103 -f 8103//8103 8042//8042 8041//8041 -f 8103//8103 8041//8041 8105//8105 -f 8105//8105 8041//8041 8033//8033 -f 8105//8105 8033//8033 8106//8106 -f 8106//8106 8033//8033 8032//8032 -f 8106//8106 8032//8032 8112//8112 -f 8112//8112 8032//8032 8030//8030 -f 8112//8112 8030//8030 8114//8114 -f 8114//8114 8030//8030 8029//8029 -f 8114//8114 8029//8029 8116//8116 -f 8116//8116 8029//8029 8046//8046 -f 8218//8218 7991//7991 8219//8219 -f 8219//8219 7991//7991 7990//7990 -f 8219//8219 7990//7990 8220//8220 -f 8220//8220 7990//7990 7989//7989 -f 8220//8220 7989//7989 8210//8210 -f 8210//8210 7989//7989 7988//7988 -f 8210//8210 7988//7988 8212//8212 -f 8212//8212 7988//7988 8079//8079 -f 8212//8212 8079//8079 8213//8213 -f 8213//8213 8079//8079 7976//7976 -f 8213//8213 7976//7976 8214//8214 -f 8214//8214 7976//7976 7978//7978 -f 8214//8214 7978//7978 8216//8216 -f 8216//8216 7978//7978 7980//7980 -f 8216//8216 7980//7980 8223//8223 -f 8223//8223 7980//7980 7981//7981 -f 8223//8223 7981//7981 8149//8149 -f 8149//8149 7981//7981 7986//7986 -f 8149//8149 7986//7986 8148//8148 -f 8148//8148 7986//7986 7992//7992 -f 8148//8148 7992//7992 8217//8217 -f 8217//8217 7992//7992 7993//7993 -f 8217//8217 7993//7993 8218//8218 -f 8218//8218 7993//7993 7991//7991 -f 8142//8142 8017//8017 8143//8143 -f 8143//8143 8017//8017 8016//8016 -f 8143//8143 8016//8016 8144//8144 -f 8144//8144 8016//8016 8015//8015 -f 8144//8144 8015//8015 8130//8130 -f 8130//8130 8015//8015 8014//8014 -f 8130//8130 8014//8014 8131//8131 -f 8131//8131 8014//8014 8012//8012 -f 8131//8131 8012//8012 8132//8132 -f 8132//8132 8012//8012 8011//8011 -f 8132//8132 8011//8011 8140//8140 -f 8140//8140 8011//8011 8024//8024 -f 8140//8140 8024//8024 8133//8133 -f 8133//8133 8024//8024 8022//8022 -f 8133//8133 8022//8022 8134//8134 -f 8134//8134 8022//8022 8021//8021 -f 8134//8134 8021//8021 8136//8136 -f 8136//8136 8021//8021 8020//8020 -f 8136//8136 8020//8020 8138//8138 -f 8138//8138 8020//8020 8019//8019 -f 8138//8138 8019//8019 8139//8139 -f 8139//8139 8019//8019 8018//8018 -f 8139//8139 8018//8018 8142//8142 -f 8142//8142 8018//8018 8017//8017 -f 8135//8135 8008//8008 8141//8141 -f 8141//8141 8008//8008 8023//8023 -f 8141//8141 8023//8023 8145//8145 -f 8145//8145 8023//8023 8025//8025 -f 8145//8145 8025//8025 8146//8146 -f 8146//8146 8025//8025 8026//8026 -f 8146//8146 8026//8026 8147//8147 -f 8147//8147 8026//8026 8027//8027 -f 8119//8119 8039//8039 8118//8118 -f 8118//8118 8039//8039 8038//8038 -f 8118//8118 8038//8038 8117//8117 -f 8117//8117 8038//8038 8048//8048 -f 8117//8117 8048//8048 8115//8115 -f 8115//8115 8048//8048 8047//8047 -f 8115//8115 8047//8047 8113//8113 -f 8113//8113 8047//8047 8028//8028 -f 8113//8113 8028//8028 8121//8121 -f 8121//8121 8028//8028 8049//8049 -f 8039//8039 8119//8119 8040//8040 -f 8040//8040 8119//8119 8120//8120 -f 8040//8040 8120//8120 8027//8027 -f 8027//8027 8120//8120 8147//8147 -f 8207//8207 7958//7958 8208//8208 -f 8208//8208 7958//7958 7957//7957 -f 8208//8208 7957//7957 8205//8205 -f 8205//8205 7957//7957 7968//7968 -f 8205//8205 7968//7968 8203//8203 -f 8203//8203 7968//7968 7967//7967 -f 8203//8203 7967//7967 8160//8160 -f 8160//8160 7967//7967 7965//7965 -f 8160//8160 7965//7965 8161//8161 -f 8161//8161 7965//7965 7970//7970 -f 8161//8161 7970//7970 8163//8163 -f 8163//8163 7970//7970 7975//7975 -f 8163//8163 7975//7975 8199//8199 -f 8199//8199 7975//7975 7974//7974 -f 8199//8199 7974//7974 8200//8200 -f 8200//8200 7974//7974 7973//7973 -f 8200//8200 7973//7973 8201//8201 -f 8201//8201 7973//7973 7963//7963 -f 8201//8201 7963//7963 8202//8202 -f 8202//8202 7963//7963 7962//7962 -f 8202//8202 7962//7962 8206//8206 -f 8206//8206 7962//7962 7961//7961 -f 8206//8206 7961//7961 8207//8207 -f 8207//8207 7961//7961 7958//7958 -f 8194//8194 7944//7944 8195//8195 -f 8195//8195 7944//7944 7942//7942 -f 8195//8195 7942//7942 8196//8196 -f 8196//8196 7942//7942 7956//7956 -f 8196//8196 7956//7956 8197//8197 -f 8197//8197 7956//7956 7950//7950 -f 8197//8197 7950//7950 8198//8198 -f 8198//8198 7950//7950 7949//7949 -f 8198//8198 7949//7949 8167//8167 -f 8167//8167 7949//7949 7947//7947 -f 8167//8167 7947//7947 8169//8169 -f 8169//8169 7947//7947 7946//7946 -f 8169//8169 7946//7946 8187//8187 -f 8187//8187 7946//7946 7953//7953 -f 8187//8187 7953//7953 8188//8188 -f 8188//8188 7953//7953 7952//7952 -f 8188//8188 7952//7952 8190//8190 -f 8190//8190 7952//7952 7951//7951 -f 8190//8190 7951//7951 8192//8192 -f 8192//8192 7951//7951 8080//8080 -f 8192//8192 8080//8080 8193//8193 -f 8193//8193 8080//8080 7945//7945 -f 8193//8193 7945//7945 8194//8194 -f 8194//8194 7945//7945 7944//7944 -f 8179//8179 7996//7996 8178//8178 -f 8178//8178 7996//7996 7998//7998 -f 8178//8178 7998//7998 8175//8175 -f 8175//8175 7998//7998 8007//8007 -f 8175//8175 8007//8007 8176//8176 -f 8176//8176 8007//8007 8006//8006 -f 8176//8176 8006//8006 8170//8170 -f 8170//8170 8006//8006 8005//8005 -f 8170//8170 8005//8005 8171//8171 -f 8171//8171 8005//8005 8003//8003 -f 8171//8171 8003//8003 8172//8172 -f 8172//8172 8003//8003 8002//8002 -f 8172//8172 8002//8002 8173//8173 -f 8173//8173 8002//8002 8004//8004 -f 8173//8173 8004//8004 8165//8165 -f 8165//8165 8004//8004 7948//7948 -f 8159//8159 7964//7964 8204//8204 -f 8204//8204 7964//7964 7966//7966 -f 8204//8204 7966//7966 8153//8153 -f 8153//8153 7966//7966 7959//7959 -f 8153//8153 7959//7959 8154//8154 -f 8154//8154 7959//7959 7960//7960 -f 8162//8162 7969//7969 7971//7971 -f 8162//8162 7971//7971 8157//8157 -f 8157//8157 7971//7971 7972//7972 -f 8157//8157 7972//7972 8158//8158 -f 8158//8158 7972//7972 7964//7964 -f 8158//8158 7964//7964 8159//8159 -f 8154//8154 7960//7960 8077//8077 -f 8154//8154 8077//8077 8155//8155 -f 8155//8155 8077//8077 8076//8076 -f 8155//8155 8076//8076 8156//8156 -f 8156//8156 8076//8076 7933//7933 -f 8156//8156 7933//7933 7934//7934 -f 8184//8184 8075//8075 8183//8183 -f 8183//8183 8075//8075 8001//8001 -f 8183//8183 8001//8001 8182//8182 -f 8182//8182 8001//8001 7997//7997 -f 8125//8125 8126//8126 8054//8054 -f 8054//8054 8126//8126 8053//8053 -f 7938//7938 8227//8227 7939//7939 -f 7939//7939 8227//8227 8228//8228 -f 7939//7939 8228//8228 7984//7984 -f 7984//7984 8228//8228 8224//8224 -f 7984//7984 8224//8224 7985//7985 -f 7985//7985 8224//8224 8222//8222 -f 7985//7985 8222//8222 7987//7987 -f 7987//7987 8222//8222 8221//8221 -f 8075//8075 8184//8184 8185//8185 -f 8075//8075 8185//8185 8074//8074 -f 8074//8074 8185//8185 8186//8186 -f 8074//8074 8186//8186 8073//8073 -f 8073//8073 8186//8186 8084//8084 -f 8073//8073 8084//8084 8070//8070 -f 8070//8070 8084//8084 8085//8085 -f 8070//8070 8085//8085 8062//8062 -f 8182//8182 7997//7997 7995//7995 -f 8182//8182 7995//7995 8180//8180 -f 8180//8180 7995//7995 7994//7994 -f 8180//8180 7994//7994 8181//8181 -f 8181//8181 7994//7994 7996//7996 -f 8181//8181 7996//7996 8179//8179 -f 8125//8125 8054//8054 8055//8055 -f 8125//8125 8055//8055 8123//8123 -f 8123//8123 8055//8055 8056//8056 -f 8123//8123 8056//8056 8124//8124 -f 8124//8124 8056//8056 8050//8050 -f 8124//8124 8050//8050 8122//8122 -f 8121//8121 8049//8049 8052//8052 -f 8121//8121 8052//8052 8128//8128 -f 8128//8128 8052//8052 8051//8051 -f 8128//8128 8051//8051 8127//8127 -f 8127//8127 8051//8051 8053//8053 -f 8127//8127 8053//8053 8126//8126 -f 8227//8227 7938//7938 8010//8010 -f 8227//8227 8010//8010 8225//8225 -f 8225//8225 8010//8010 8009//8009 -f 8225//8225 8009//8009 8226//8226 -f 8226//8226 8009//8009 8008//8008 -f 8226//8226 8008//8008 8135//8135 -f 7987//7987 8221//8221 8151//8151 -f 7987//7987 8151//8151 7982//7982 -f 7982//7982 8151//8151 8150//8150 -f 7982//7982 8150//8150 7983//7983 -f 7983//7983 8150//8150 7924//7924 -f 7983//7983 7924//7924 7923//7923 -# 17192 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_vakuum_pumpe.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_vakuum_pumpe.obj deleted file mode 100644 index e66da0cf7..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/robot_vakuum_pumpe.obj +++ /dev/null @@ -1,4192 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object vakuum_pumpe.obj -# -# Vertices: 1046 -# Faces: 2084 -# -#### -vn 3.496198 1.331170 -2.773874 -v 0.005550 0.069386 0.088295 -vn 3.516681 0.000000 -3.075471 -v 0.005550 0.067000 0.087750 -vn 2.899933 -0.000000 3.118687 -v 0.005550 0.067000 0.075250 -vn 2.899930 0.746351 3.028063 -v 0.005550 0.062692 0.075773 -vn 3.496195 -1.331169 -2.773874 -v 0.005550 0.064614 0.088295 -vn 2.899932 1.449327 2.761459 -v 0.005550 0.058635 0.077312 -vn 4.712389 -1.570796 1.570796 -v 0.005550 0.054000 0.095250 -vn 2.899932 3.095948 -0.375915 -v 0.005550 0.049131 0.095420 -vn 2.899932 3.095948 0.375916 -v 0.005550 0.049131 0.091080 -vn 2.899931 -2.566629 -1.771616 -v 0.005550 0.081814 0.103475 -vn 4.712390 -1.570796 1.570796 -v 0.005550 0.079000 0.095250 -vn 2.899934 -2.916023 -1.105902 -v 0.005550 0.083830 0.099633 -vn 4.712389 1.570796 1.570796 -v 0.005550 0.080000 0.095250 -vn 2.899931 -3.095948 -0.375917 -v 0.005550 0.084869 0.095420 -vn 4.712389 1.570796 -1.570796 -v 0.005550 0.080000 0.091250 -vn 2.899931 -3.095948 0.375917 -v 0.005550 0.084869 0.091080 -vn 2.899931 -2.068070 -2.334372 -v 0.005550 0.078936 0.106723 -vn 2.899933 -1.449326 -2.761461 -v 0.005550 0.075365 0.109188 -vn 2.899931 -0.746351 -3.028063 -v 0.005550 0.071308 0.110727 -vn 4.712389 1.570796 1.570796 -v 0.005550 0.055000 0.095250 -vn 2.899929 0.746351 -3.028063 -v 0.005550 0.062692 0.110727 -vn 2.899933 1.449326 -2.761461 -v 0.005550 0.058635 0.109188 -vn 4.712389 -1.570796 -1.570796 -v 0.005550 0.054000 0.091250 -vn 2.899932 2.916023 1.105902 -v 0.005550 0.050170 0.086867 -vn 4.712389 1.570796 -1.570796 -v 0.005550 0.055000 0.091250 -vn 2.899932 2.566629 1.771616 -v 0.005550 0.052186 0.083025 -vn 2.899932 2.068073 2.334370 -v 0.005550 0.055064 0.079777 -vn 2.899930 2.068071 -2.334371 -v 0.005550 0.055064 0.106723 -vn 2.899933 2.566629 -1.771616 -v 0.005550 0.052186 0.103475 -vn 2.899931 2.916023 -1.105901 -v 0.005550 0.050170 0.099633 -vn 2.899931 -0.746351 3.028063 -v 0.005550 0.071308 0.075773 -vn 2.899932 -1.449328 2.761459 -v 0.005550 0.075365 0.077312 -vn 4.712389 -1.570796 -1.570796 -v 0.005550 0.079000 0.091250 -vn 2.899932 -2.068072 2.334370 -v 0.005550 0.078936 0.079777 -vn 2.899932 -2.566629 1.771616 -v 0.005550 0.081814 0.083025 -vn 2.899933 -2.916023 1.105902 -v 0.005550 0.083830 0.086867 -vn 3.513806 -2.411378 -1.908248 -v 0.005550 0.062700 0.089821 -vn 3.505719 -2.995618 -0.696701 -v 0.005550 0.061638 0.092026 -vn 3.524813 2.415869 -1.899402 -v 0.005550 0.071300 0.089821 -vn 3.515516 -2.991666 0.705368 -v 0.005550 0.061638 0.094474 -vn 3.524808 -2.415865 1.899406 -v 0.005550 0.062700 0.096679 -vn 3.496186 -1.331172 2.773875 -v 0.005550 0.064614 0.098205 -vn 3.516683 0.000000 3.075470 -v 0.005550 0.067000 0.098750 -vn 3.496189 1.331172 2.773874 -v 0.005550 0.069386 0.098205 -vn 2.899933 -0.000000 -3.118687 -v 0.005550 0.067000 0.111250 -vn 3.513813 2.411376 1.908247 -v 0.005550 0.071300 0.096679 -vn 3.505719 2.995619 0.696700 -v 0.005550 0.072362 0.094474 -vn 3.515517 2.991667 -0.705368 -v 0.005550 0.072362 0.092026 -vn 1.110721 -0.785398 -5.823110 -v -0.041691 0.085000 0.112750 -vn 1.110719 3.926991 -2.681516 -v -0.041691 0.086000 0.112750 -vn 1.570800 1.570796 -1.570796 -v -0.039450 0.086000 0.112750 -vn 1.570797 -1.570796 -1.570797 -v -0.039450 0.048000 0.112750 -vn 1.110720 -3.926991 -2.681517 -v -0.041691 0.048000 0.112750 -vn 1.110721 0.785398 -5.823110 -v -0.041691 0.049000 0.112750 -vn 1.570797 1.570796 -1.570796 -v -0.050450 0.049000 0.112750 -vn 1.570797 -1.570796 -1.570796 -v -0.050450 0.085000 0.112750 -vn -1.570796 -1.570796 1.570796 -v -0.077450 0.048000 0.131750 -vn -4.712389 -1.570796 1.570796 -v -0.077450 0.055000 0.131750 -vn -2.984512 -3.122253 -0.245727 -v -0.077450 0.048000 0.083750 -vn -2.984515 3.122254 -0.245723 -v -0.077450 0.086000 0.083750 -vn -1.570796 1.570796 1.570796 -v -0.077450 0.086000 0.131750 -vn -4.712389 1.570796 1.570796 -v -0.077450 0.079000 0.131750 -vn -1.570796 1.570796 1.570796 -v -0.077450 0.079000 0.135750 -vn -1.570796 -1.570796 1.570796 -v -0.077450 0.055000 0.135750 -vn -2.827435 2.510309 -1.823850 -v -0.077450 0.084090 0.077872 -vn -2.827435 1.823850 -2.510309 -v -0.077450 0.081878 0.075660 -vn -2.827429 0.958853 -2.951046 -v -0.077450 0.079090 0.074239 -vn -2.984515 -0.245724 -3.122254 -v -0.077450 0.058000 0.073750 -vn -2.827430 -0.958853 -2.951047 -v -0.077450 0.054910 0.074239 -vn -2.984515 0.245723 -3.122254 -v -0.077450 0.076000 0.073750 -vn -2.827429 2.951046 -0.958853 -v -0.077450 0.085511 0.080660 -vn -2.827435 -1.823850 -2.510310 -v -0.077450 0.052122 0.075660 -vn -2.827434 -2.510311 -1.823848 -v -0.077450 0.049910 0.077872 -vn -2.827434 -2.951047 -0.958854 -v -0.077450 0.048489 0.080660 -vn 1.570796 1.570796 1.570796 -v -0.039450 0.086000 0.131750 -vn 4.712389 1.570796 1.570796 -v -0.039450 0.079000 0.131750 -vn 3.665192 -3.034545 -0.000004 -v -0.039450 0.055250 0.132500 -vn 1.570795 -1.570796 1.570796 -v -0.039450 0.055000 0.135750 -vn 4.712389 -1.570796 1.570796 -v -0.039450 0.055000 0.131750 -vn 3.665184 -1.517274 -2.627995 -v -0.039450 0.056750 0.129902 -vn 3.665193 -2.627988 -1.517279 -v -0.039450 0.055652 0.131000 -vn 1.570796 -1.570796 1.570796 -v -0.039450 0.048000 0.131750 -vn 3.665185 -1.517273 -2.627996 -v -0.039450 0.074250 0.129902 -vn 3.665196 -2.627990 -1.517275 -v -0.039450 0.073152 0.131000 -vn 3.665183 1.517272 -2.627997 -v -0.039450 0.059750 0.129902 -vn 3.665198 0.000002 -3.034543 -v -0.039450 0.075750 0.129500 -vn 3.665198 0.000000 -3.034542 -v -0.039450 0.058250 0.129500 -vn 3.665200 -2.627991 1.517271 -v -0.039450 0.073152 0.134000 -vn 3.665197 2.627988 1.517277 -v -0.039450 0.060848 0.134000 -vn 3.665188 -3.034547 -0.000004 -v -0.039450 0.072750 0.132500 -vn 3.665193 3.034544 -0.000004 -v -0.039450 0.061250 0.132500 -vn 3.665195 2.627987 -1.517281 -v -0.039450 0.060848 0.131000 -vn 3.665195 -2.627990 1.517275 -v -0.039450 0.055652 0.134000 -vn 3.665184 -1.517274 2.627995 -v -0.039450 0.056750 0.135098 -vn 3.665197 -0.000000 3.034542 -v -0.039450 0.058250 0.135500 -vn 3.665181 1.517271 2.627999 -v -0.039450 0.077250 0.135098 -vn 1.570797 1.570796 1.570796 -v -0.039450 0.079000 0.135750 -vn 3.665198 0.000002 3.034542 -v -0.039450 0.075750 0.135500 -vn 3.665188 -1.517273 2.627996 -v -0.039450 0.074250 0.135098 -vn 3.665183 1.517272 2.627997 -v -0.039450 0.059750 0.135098 -vn 3.665201 2.627987 1.517276 -v -0.039450 0.078348 0.134000 -vn 3.665188 3.034546 -0.000004 -v -0.039450 0.078750 0.132500 -vn 3.665199 2.627986 -1.517279 -v -0.039450 0.078348 0.131000 -vn 3.665181 1.517271 -2.627999 -v -0.039450 0.077250 0.129902 -vn 2.681516 -3.926991 -1.110721 -v -0.050450 0.048000 0.103991 -vn 5.823109 0.785398 -1.110721 -v -0.050450 0.049000 0.103991 -vn 3.383256 0.000000 -3.118686 -v -0.050450 0.067000 0.074750 -vn 2.984514 -0.245724 -3.122254 -v -0.050450 0.058000 0.073750 -vn 2.984514 0.245723 -3.122254 -v -0.050450 0.076000 0.073750 -vn 3.383253 1.449327 2.761461 -v -0.050450 0.075597 0.109631 -vn 3.383253 2.068071 2.334372 -v -0.050450 0.079268 0.107097 -vn 5.823108 -0.785398 -1.110720 -v -0.050450 0.085000 0.103991 -vn 2.827433 -2.510311 -1.823848 -v -0.050450 0.049910 0.077872 -vn 3.383255 -2.068073 -2.334369 -v -0.050450 0.054732 0.079403 -vn 3.383252 -2.566629 -1.771616 -v -0.050450 0.051775 0.082741 -vn 3.383254 -2.916023 -1.105903 -v -0.050450 0.049702 0.086690 -vn 2.984511 -3.122253 -0.245727 -v -0.050450 0.048000 0.083750 -vn 2.827434 -2.951047 -0.958854 -v -0.050450 0.048489 0.080660 -vn 2.984513 3.122254 -0.245723 -v -0.050450 0.086000 0.083750 -vn 3.383254 2.916023 -1.105900 -v -0.050450 0.084298 0.086690 -vn 2.827429 2.951046 -0.958853 -v -0.050450 0.085511 0.080660 -vn 3.383253 2.566630 -1.771616 -v -0.050450 0.082225 0.082741 -vn 2.827435 2.510309 -1.823850 -v -0.050450 0.084090 0.077872 -vn 3.383255 2.068072 -2.334371 -v -0.050450 0.079268 0.079403 -vn 2.827435 1.823850 -2.510309 -v -0.050450 0.081878 0.075660 -vn 2.827429 0.958853 -2.951046 -v -0.050450 0.079090 0.074239 -vn 3.383254 1.449324 -2.761461 -v -0.050450 0.075597 0.076869 -vn 3.383251 0.746351 -3.028064 -v -0.050450 0.071427 0.075288 -vn 3.383253 -1.449327 2.761459 -v -0.050450 0.058403 0.109631 -vn 3.383255 -0.746351 3.028063 -v -0.050450 0.062573 0.111212 -vn 3.383253 0.000000 3.118687 -v -0.050450 0.067000 0.111750 -vn 3.383255 0.746351 3.028063 -v -0.050450 0.071427 0.111212 -vn 3.383252 -0.746351 -3.028064 -v -0.050450 0.062573 0.075288 -vn 3.383255 -1.449325 -2.761461 -v -0.050450 0.058403 0.076869 -vn 2.827430 -0.958853 -2.951046 -v -0.050450 0.054910 0.074239 -vn 2.827435 -1.823850 -2.510310 -v -0.050450 0.052122 0.075660 -vn 3.383255 2.566629 1.771616 -v -0.050450 0.082225 0.103759 -vn 3.383254 2.916024 1.105899 -v -0.050450 0.084298 0.099810 -vn 2.681516 3.926991 -1.110721 -v -0.050450 0.086000 0.103991 -vn 3.383253 3.095948 0.375915 -v -0.050450 0.085365 0.095480 -vn 3.383253 3.095949 -0.375915 -v -0.050450 0.085365 0.091020 -vn 3.383254 -3.095948 -0.375916 -v -0.050450 0.048635 0.091020 -vn 3.383254 -3.095949 0.375916 -v -0.050450 0.048635 0.095480 -vn 3.383254 -2.916024 1.105902 -v -0.050450 0.049702 0.099810 -vn 3.383254 -2.566629 1.771616 -v -0.050450 0.051775 0.103759 -vn 3.383254 -2.068072 2.334371 -v -0.050450 0.054732 0.107097 -vn 2.617984 2.627985 1.517279 -v -0.059450 0.056085 0.131250 -vn 2.618011 1.517276 2.627997 -v -0.059450 0.057000 0.130335 -vn 6.283185 0.000000 0.000000 -v -0.059450 0.058250 0.132500 -vn 2.617977 0.000001 3.034538 -v -0.059450 0.058250 0.130000 -vn 2.618008 -1.517279 2.627997 -v -0.059450 0.059500 0.130335 -vn 2.618011 1.517277 -2.627999 -v -0.059450 0.057000 0.134665 -vn 2.617980 2.627985 -1.517272 -v -0.059450 0.056085 0.133750 -vn 2.618001 3.034548 0.000005 -v -0.059450 0.055750 0.132500 -vn 2.617985 -2.627987 -1.517276 -v -0.059450 0.060415 0.133750 -vn 2.618008 -1.517277 -2.627995 -v -0.059450 0.059500 0.134665 -vn 2.617977 0.000001 -3.034538 -v -0.059450 0.058250 0.135000 -vn 2.617989 -2.627985 1.517279 -v -0.059450 0.060415 0.131250 -vn 2.617995 -3.034546 0.000005 -v -0.059450 0.060750 0.132500 -vn 2.617984 2.627985 1.517278 -v -0.059450 0.073585 0.131250 -vn 2.618011 1.517277 2.627998 -v -0.059450 0.074500 0.130335 -vn 6.283185 0.000000 0.000000 -v -0.059450 0.075750 0.132500 -vn 2.617976 -0.000000 3.034537 -v -0.059450 0.075750 0.130000 -vn 2.618011 -1.517277 2.627998 -v -0.059450 0.077000 0.130335 -vn 2.618011 1.517277 -2.627998 -v -0.059450 0.074500 0.134665 -vn 2.617980 2.627986 -1.517273 -v -0.059450 0.073585 0.133750 -vn 2.618001 3.034547 0.000005 -v -0.059450 0.073250 0.132500 -vn 2.617980 -2.627985 -1.517274 -v -0.059450 0.077915 0.133750 -vn 2.618011 -1.517277 -2.627998 -v -0.059450 0.077000 0.134665 -vn 2.617976 0.000000 -3.034537 -v -0.059450 0.075750 0.135000 -vn 2.617984 -2.627985 1.517278 -v -0.059450 0.077915 0.131250 -vn 2.618001 -3.034548 0.000004 -v -0.059450 0.078250 0.132500 -vn 3.630355 0.000000 3.491266 -v -0.011387 0.058250 0.130000 -vn 3.630324 -1.745638 3.023528 -v -0.011387 0.059500 0.130335 -vn 3.630344 -3.023519 1.745644 -v -0.011387 0.060415 0.131250 -vn 3.630337 -3.491266 0.000006 -v -0.011387 0.060750 0.132500 -vn 3.630347 -3.023520 -1.745638 -v -0.011387 0.060415 0.133750 -vn 3.630325 -1.745640 -3.023528 -v -0.011387 0.059500 0.134665 -vn 3.630355 0.000002 -3.491267 -v -0.011387 0.058250 0.135000 -vn 3.630322 1.745634 -3.023529 -v -0.011387 0.057000 0.134665 -vn 3.630351 3.023523 -1.745637 -v -0.011387 0.056085 0.133750 -vn 3.630332 3.491268 0.000004 -v -0.011387 0.055750 0.132500 -vn 3.630349 3.023519 1.745643 -v -0.011387 0.056085 0.131250 -vn 3.630322 1.745638 3.023529 -v -0.011387 0.057000 0.130335 -vn 3.629358 0.006218 3.500497 -v -0.011297 0.075750 0.130000 -vn 3.629521 -1.747732 3.032704 -v -0.011297 0.077000 0.130335 -vn 3.629265 -3.030081 1.755161 -v -0.011297 0.077915 0.131250 -vn 3.628703 -3.504611 0.005952 -v -0.011297 0.078250 0.132500 -vn 3.627779 -3.042106 -1.750567 -v -0.011297 0.077915 0.133750 -vn 3.626172 -1.760736 -3.046630 -v -0.011297 0.077000 0.134665 -vn 3.624199 -0.000000 -3.530877 -v -0.011297 0.075750 0.135000 -vn 3.626172 1.760733 -3.046629 -v -0.011297 0.074500 0.134665 -vn 3.627779 3.042104 -1.750568 -v -0.011297 0.073585 0.133750 -vn 3.628704 3.504609 0.005953 -v -0.011297 0.073250 0.132500 -vn 3.626705 3.031346 1.780462 -v -0.011297 0.073585 0.131250 -vn 3.626219 1.741428 3.056191 -v -0.011297 0.074500 0.130335 -vn 2.986996 -2.379162 -1.373617 -v -0.011324 0.055652 0.131000 -vn 2.987005 -1.373612 -2.379168 -v -0.011324 0.056750 0.129902 -vn 2.986993 -0.000001 -2.747221 -v -0.011324 0.058250 0.129500 -vn 2.987007 1.373613 -2.379168 -v -0.011324 0.059750 0.129902 -vn 2.986992 2.379161 -1.373621 -v -0.011324 0.060848 0.131000 -vn 2.986996 2.747226 -0.000004 -v -0.011324 0.061250 0.132500 -vn 2.986993 2.379164 1.373616 -v -0.011324 0.060848 0.134000 -vn 2.987008 1.373610 2.379169 -v -0.011324 0.059750 0.135098 -vn 2.986993 0.000001 2.747221 -v -0.011324 0.058250 0.135500 -vn 2.987005 -1.373615 2.379167 -v -0.011324 0.056750 0.135098 -vn 2.986992 -2.379162 1.373615 -v -0.011324 0.055652 0.134000 -vn 2.986997 -2.747226 -0.000004 -v -0.011324 0.055250 0.132500 -vn 3.268149 -1.313128 -2.405179 -v -0.011228 0.074250 0.129902 -vn 3.262833 -0.701986 -2.709314 -v -0.011228 0.075032 0.129587 -vn 3.270142 -2.623600 -0.832493 -v -0.011228 0.072945 0.131436 -vn 3.275884 -2.308447 -1.470523 -v -0.011228 0.073152 0.131000 -vn 3.267729 -1.911583 -2.027005 -v -0.011228 0.073761 0.130254 -vn 3.275361 -2.694570 0.531338 -v -0.011228 0.072772 0.132862 -vn 3.282292 -2.718547 -0.182698 -v -0.011228 0.072750 0.132500 -vn 3.280316 -2.100079 1.758267 -v -0.011228 0.073281 0.134204 -vn 3.289665 -2.467010 1.154492 -v -0.011228 0.073152 0.134000 -vn 3.284986 -0.989911 2.544916 -v -0.011228 0.074356 0.135156 -vn 3.296730 -1.600379 2.202763 -v -0.011228 0.074250 0.135098 -vn 3.284957 0.989950 2.544902 -v -0.011228 0.077144 0.135156 -vn 3.063870 -0.000001 2.721007 -v -0.011228 0.075750 0.135500 -vn 3.286903 2.102943 1.754434 -v -0.011228 0.078219 0.134204 -vn 3.303535 1.596323 2.205280 -v -0.011228 0.077250 0.135098 -vn 3.288527 2.695908 0.521881 -v -0.011228 0.078728 0.132862 -vn 3.303527 2.462297 1.162892 -v -0.011228 0.078348 0.134000 -vn 3.289787 2.618555 -0.845923 -v -0.011228 0.078555 0.131436 -vn 3.303559 2.718422 -0.168185 -v -0.011228 0.078750 0.132500 -vn 3.290612 1.888330 -2.007214 -v -0.011228 0.077739 0.130254 -vn 3.303566 2.300956 -1.457994 -v -0.011228 0.078348 0.131000 -vn 3.303592 0.000000 -2.724290 -v -0.011228 0.075750 0.129500 -vn 3.291045 0.686646 -2.671057 -v -0.011228 0.076468 0.129587 -vn 3.303608 1.313216 -2.386802 -v -0.011228 0.077250 0.129902 -vn 3.665197 0.000004 3.034544 -v 0.009050 0.067000 0.094750 -vn 2.829944 0.725371 -2.989812 -v 0.009050 0.065923 0.097619 -vn 3.665190 -1.517275 2.627993 -v 0.009050 0.066250 0.094549 -vn 2.858998 2.028539 -2.324954 -v 0.009050 0.064016 0.096618 -vn 3.665190 -2.627993 1.517275 -v 0.009050 0.065701 0.094000 -vn 2.834511 2.890770 -1.075968 -v 0.009050 0.062792 0.094846 -vn 3.665197 -3.034544 -0.000004 -v 0.009050 0.065500 0.093250 -vn 2.871423 3.066308 0.358823 -v 0.009050 0.062533 0.092708 -vn 3.665181 -2.628000 -1.517271 -v 0.009050 0.065701 0.092500 -vn 2.776910 2.494032 1.797492 -v 0.009050 0.063297 0.090694 -vn 3.665206 -1.517269 -2.627989 -v 0.009050 0.066250 0.091951 -vn 2.860151 1.464515 2.711590 -v 0.009050 0.064909 0.089265 -vn 3.665178 0.000004 -3.034551 -v 0.009050 0.067000 0.091750 -vn 2.731810 -0.078850 3.066906 -v 0.009050 0.067000 0.088750 -vn 3.665197 1.517265 -2.627995 -v 0.009050 0.067750 0.091951 -vn 2.857201 -1.398969 2.743850 -v 0.009050 0.069091 0.089265 -vn 3.665197 2.627996 -1.517265 -v 0.009050 0.068299 0.092500 -vn 2.738475 -2.566809 1.679157 -v 0.009050 0.070703 0.090694 -vn 3.665178 3.034551 -0.000004 -v 0.009050 0.068500 0.093250 -vn 2.839972 -3.051536 0.376089 -v 0.009050 0.071467 0.092708 -vn 3.665206 2.627989 1.517269 -v 0.009050 0.068299 0.094000 -vn 2.722105 -2.845102 -1.127353 -v 0.009050 0.071208 0.094846 -vn 3.665181 1.517271 2.627999 -v 0.009050 0.067750 0.094549 -vn 2.836572 -2.045468 -2.296996 -v 0.009050 0.069984 0.096618 -vn 2.742061 -0.671857 -2.989281 -v 0.009050 0.068077 0.097619 -vn -2.246807 -0.000000 2.950417 -v -0.019450 0.058250 0.136522 -vn -2.246808 1.475210 2.555136 -v -0.019450 0.060261 0.135983 -vn -2.246811 2.555139 1.475205 -v -0.019450 0.061733 0.134511 -vn -2.246813 2.950419 -0.000003 -v -0.019450 0.062272 0.132500 -vn -2.246810 2.555137 -1.475208 -v -0.019450 0.061733 0.130489 -vn -2.246807 1.475211 -2.555135 -v -0.019450 0.060261 0.129017 -vn -2.246807 -0.000001 -2.950417 -v -0.019450 0.058250 0.128478 -vn -2.246809 -1.475210 -2.555136 -v -0.019450 0.056239 0.129017 -vn -2.246814 -2.555138 -1.475210 -v -0.019450 0.054767 0.130489 -vn -2.246809 -2.950417 -0.000003 -v -0.019450 0.054228 0.132500 -vn -2.246811 -2.555138 1.475208 -v -0.019450 0.054767 0.134511 -vn -2.246808 -1.475211 2.555135 -v -0.019450 0.056239 0.135983 -vn -2.249106 -2.435982 1.681518 -v -0.019450 0.072343 0.134851 -vn -2.249453 -2.938450 0.356880 -v -0.019450 0.071641 0.132999 -vn -2.248683 -1.375519 2.620899 -v -0.019450 0.073826 0.136165 -vn -2.249691 -2.767762 -1.049552 -v -0.019450 0.071880 0.131032 -vn -2.249842 -1.963018 -2.215583 -v -0.019450 0.073005 0.129402 -vn -2.276937 0.710647 -2.882021 -v -0.019450 0.076741 0.128481 -vn -2.262815 -0.718703 -2.875728 -v -0.019450 0.074759 0.128481 -vn -2.275332 1.968694 -2.220933 -v -0.019450 0.078495 0.129402 -vn -2.272107 2.774618 -1.050799 -v -0.019450 0.079620 0.131032 -vn -2.267274 2.943654 0.359345 -v -0.019450 0.079859 0.132999 -vn -2.260838 2.437608 1.685515 -v -0.019450 0.079157 0.134851 -vn -2.248132 0.000001 2.959835 -v -0.019450 0.075750 0.136639 -vn -2.252841 1.373556 2.623383 -v -0.019450 0.077674 0.136165 -vn 3.160392 -1.017531 1.962744 -v 0.010050 0.069091 0.089265 -vn 3.427035 -1.415938 1.730258 -v 0.010050 0.069645 0.089609 -vn 3.221696 -1.726359 1.475608 -v 0.010050 0.070641 0.090605 -vn 3.264820 -1.977318 1.068224 -v 0.010050 0.070703 0.090694 -vn 3.717490 -1.995240 0.868622 -v 0.010050 0.071280 0.091859 -vn 3.161722 -2.194697 0.300562 -v 0.010050 0.071467 0.092708 -vn 3.475234 -2.220731 -0.209574 -v 0.010050 0.071500 0.093250 -vn 3.319092 -2.207743 -0.474161 -v 0.010050 0.071280 0.094641 -vn 3.269229 -1.989547 -0.988999 -v 0.010050 0.071208 0.094846 -vn 3.783674 -1.851091 -1.108434 -v 0.010050 0.070641 0.095895 -vn 3.164225 -1.517164 -1.625591 -v 0.010050 0.069984 0.096618 -vn 3.398828 -1.151300 -1.926389 -v 0.010050 0.069645 0.096891 -vn 3.349213 -0.891710 -2.068756 -v 0.010050 0.068391 0.097530 -vn 3.271946 -0.332467 -2.166038 -v 0.010050 0.068077 0.097619 -vn 3.849910 -0.171859 -2.130473 -v 0.010050 0.067000 0.097750 -vn 3.167700 0.453691 -2.188748 -v 0.010050 0.065923 0.097619 -vn 3.330980 0.877466 -2.077435 -v 0.010050 0.065609 0.097530 -vn 3.377918 1.167589 -1.920003 -v 0.010050 0.064355 0.096891 -vn 3.171714 2.060894 -0.900712 -v 0.010050 0.062792 0.094846 -vn 3.463861 1.823779 -1.260002 -v 0.010050 0.063359 0.095895 -vn 3.148546 1.460609 -1.611452 -v 0.010050 0.064016 0.096618 -vn 3.271966 2.203109 -0.521215 -v 0.010050 0.062720 0.094641 -vn 3.404157 2.235940 -0.157046 -v 0.010050 0.062500 0.093250 -vn 3.136527 2.124143 0.248223 -v 0.010050 0.062533 0.092708 -vn 3.454642 2.076879 0.769724 -v 0.010050 0.062720 0.091859 -vn 3.175879 1.939939 1.166379 -v 0.010050 0.063297 0.090694 -vn 3.288595 1.671785 1.525416 -v 0.010050 0.063359 0.090605 -vn 3.559840 1.471350 1.653937 -v 0.010050 0.064355 0.089609 -vn 3.122623 1.012582 1.837831 -v 0.010050 0.064909 0.089265 -vn 3.440155 0.562331 2.141078 -v 0.010050 0.065609 0.088970 -vn 3.403967 -0.094246 2.193518 -v 0.010050 0.067000 0.088750 -vn 3.651876 -0.458746 2.144393 -v 0.010050 0.068391 0.088970 -vn -3.665198 -0.000000 -3.034542 -v -0.019450 0.058250 0.129500 -vn -3.665184 -1.517274 -2.627995 -v -0.019450 0.056750 0.129902 -vn -3.665193 -2.627989 -1.517279 -v -0.019450 0.055652 0.131000 -vn -3.665192 -3.034544 -0.000004 -v -0.019450 0.055250 0.132500 -vn -3.665196 -2.627990 1.517275 -v -0.019450 0.055652 0.134000 -vn -3.665184 -1.517274 2.627995 -v -0.019450 0.056750 0.135098 -vn -3.665198 0.000000 3.034542 -v -0.019450 0.058250 0.135500 -vn -3.665183 1.517272 2.627997 -v -0.019450 0.059750 0.135098 -vn -3.665197 2.627988 1.517277 -v -0.019450 0.060848 0.134000 -vn -3.665192 3.034545 -0.000004 -v -0.019450 0.061250 0.132500 -vn -3.665195 2.627986 -1.517281 -v -0.019450 0.060848 0.131000 -vn -3.665183 1.517272 -2.627997 -v -0.019450 0.059750 0.129902 -vn -3.665198 0.000002 -3.034542 -v -0.019450 0.075750 0.129500 -vn -3.665185 -1.517273 -2.627996 -v -0.019450 0.074250 0.129902 -vn -3.665195 -2.627990 -1.517275 -v -0.019450 0.073152 0.131000 -vn -3.665188 -3.034546 -0.000004 -v -0.019450 0.072750 0.132500 -vn -3.665198 -2.627991 1.517272 -v -0.019450 0.073152 0.134000 -vn -3.665185 -1.517273 2.627996 -v -0.019450 0.074250 0.135098 -vn -3.665198 0.000002 3.034543 -v -0.019450 0.075750 0.135500 -vn -3.665181 1.517271 2.627999 -v -0.019450 0.077250 0.135098 -vn -3.665201 2.627987 1.517275 -v -0.019450 0.078348 0.134000 -vn -3.665188 3.034547 -0.000004 -v -0.019450 0.078750 0.132500 -vn -3.665199 2.627985 -1.517279 -v -0.019450 0.078348 0.131000 -vn -3.665181 1.517271 -2.627999 -v -0.019450 0.077250 0.129902 -vn 0.973281 5.955418 -1.121591 -v 0.009050 0.072362 0.092026 -vn 0.805418 6.064971 0.051951 -v 0.009050 0.072500 0.093250 -vn 2.918317 5.124943 0.053188 -v 0.009550 0.072366 0.093250 -vn 0.890590 4.522768 4.077529 -v 0.009050 0.071300 0.096679 -vn 0.825892 3.606370 4.865142 -v 0.009050 0.070233 0.097700 -vn 2.897756 2.991059 4.164499 -v 0.009550 0.070154 0.097591 -vn 2.876337 0.000002 5.128852 -v 0.009550 0.067000 0.098616 -vn 2.946588 1.519245 4.887519 -v 0.009550 0.068658 0.098353 -vn 0.770851 1.618731 5.863239 -v 0.009050 0.068700 0.098481 -vn 2.946578 -1.519228 -4.887505 -v 0.009550 0.065342 0.088147 -vn 2.897766 -2.991067 -4.164513 -v 0.009550 0.063846 0.088909 -vn 0.825913 -3.606384 -4.865122 -v 0.009050 0.063767 0.088800 -vn 2.952104 -4.845938 -1.640526 -v 0.009550 0.061897 0.091592 -vn 0.765021 -5.677371 -2.215253 -v 0.009050 0.061769 0.091550 -vn 2.946831 -4.175572 -2.959143 -v 0.009550 0.062659 0.090096 -vn 0.775825 -5.175769 -3.240857 -v 0.009050 0.062550 0.090017 -vn 0.890561 -4.522741 -4.077595 -v 0.009050 0.062700 0.089821 -vn 0.759043 -5.181906 3.228092 -v 0.009050 0.062550 0.096483 -vn 0.746413 -5.670400 2.228031 -v 0.009050 0.061769 0.094950 -vn 2.960901 -4.839345 1.662801 -v 0.009550 0.061897 0.094908 -vn 0.973300 -5.955417 1.121581 -v 0.009050 0.061638 0.094474 -vn 2.918294 -5.124942 -0.053193 -v 0.009550 0.061634 0.093250 -vn 0.805402 -6.064978 -0.051960 -v 0.009050 0.061500 0.093250 -vn 1.086422 -5.921323 -1.038431 -v 0.009050 0.061638 0.092026 -vn 0.890583 -4.522738 4.077587 -v 0.009050 0.062700 0.096679 -vn 2.946856 -4.175573 2.959137 -v 0.009550 0.062659 0.096404 -vn 2.958765 -3.046768 4.115578 -v 0.009550 0.063846 0.097591 -vn 0.783043 0.000001 6.025215 -v 0.009050 0.067000 0.098750 -vn 0.770861 -1.618741 5.863229 -v 0.009050 0.065300 0.098481 -vn 2.953090 -1.499246 4.895128 -v 0.009550 0.065342 0.098353 -vn 1.018967 -2.692674 5.409677 -v 0.009050 0.064614 0.098205 -vn 0.767967 -3.684484 4.839310 -v 0.009050 0.063767 0.097700 -vn 1.250789 2.748374 5.260641 -v 0.009050 0.069386 0.098205 -vn 2.952084 4.845935 1.640524 -v 0.009550 0.072103 0.094908 -vn 0.765005 5.677371 2.215283 -v 0.009050 0.072231 0.094950 -vn 2.946851 4.175593 2.959139 -v 0.009550 0.071341 0.096404 -vn 0.775852 5.175810 3.240801 -v 0.009050 0.071450 0.096483 -vn 1.086404 5.921323 1.038447 -v 0.009050 0.072362 0.094474 -vn 0.746362 5.670413 -2.228057 -v 0.009050 0.072231 0.091550 -vn 2.960867 4.839331 -1.662807 -v 0.009550 0.072103 0.091592 -vn 0.759022 5.181962 -3.228045 -v 0.009050 0.071450 0.090017 -vn 2.946833 4.175588 -2.959146 -v 0.009550 0.071341 0.090096 -vn 0.890568 4.522771 -4.077537 -v 0.009050 0.071300 0.089821 -vn 2.958734 3.046796 -4.115587 -v 0.009550 0.070154 0.088909 -vn 0.767946 3.684508 -4.839312 -v 0.009050 0.070233 0.088800 -vn 1.018960 2.692669 -5.409667 -v 0.009050 0.069386 0.088295 -vn 1.250790 -2.748368 -5.260636 -v 0.009050 0.064614 0.088295 -vn 0.770827 -1.618715 -5.863255 -v 0.009050 0.065300 0.088019 -vn 2.876340 -0.000004 -5.128855 -v 0.009550 0.067000 0.087884 -vn 0.783039 -0.000003 -6.025217 -v 0.009050 0.067000 0.087750 -vn 2.953066 1.499227 -4.895120 -v 0.009550 0.068658 0.088147 -vn 0.770814 1.618710 -5.863264 -v 0.009050 0.068700 0.088019 -vn 5.100274 -2.509946 -1.831363 -v 0.009916 0.062955 0.090311 -vn 5.102010 -2.949346 -0.955149 -v 0.009916 0.062245 0.091705 -vn 5.098810 -3.112935 0.011318 -v 0.009916 0.062000 0.093250 -vn 5.098886 -2.963879 0.951186 -v 0.009916 0.062245 0.094795 -vn 5.101394 -2.506819 1.828570 -v 0.009916 0.062955 0.096189 -vn 5.098724 -1.821172 2.524961 -v 0.009916 0.064061 0.097295 -vn 5.098228 -0.976621 2.958514 -v 0.009916 0.065455 0.098005 -vn 5.100777 0.008587 3.105502 -v 0.009916 0.067000 0.098250 -vn 5.098894 0.970664 2.957120 -v 0.009916 0.068545 0.098005 -vn 5.098102 1.818462 2.530701 -v 0.009916 0.069939 0.097295 -vn 5.100165 2.520973 1.817905 -v 0.009916 0.071045 0.096189 -vn 5.099526 2.959757 0.954363 -v 0.009916 0.071755 0.094795 -vn 5.098260 3.115729 0.016836 -v 0.009916 0.072000 0.093250 -vn 5.099617 2.954069 -0.973794 -v 0.009916 0.071755 0.091705 -vn 5.100700 2.509840 -1.828066 -v 0.009916 0.071045 0.090311 -vn 5.099067 -1.838172 -2.511084 -v 0.009916 0.064061 0.089205 -vn 5.102629 -0.957146 -2.945789 -v 0.009916 0.065455 0.088495 -vn 5.102626 0.000001 -3.097389 -v 0.009916 0.067000 0.088250 -vn 5.099079 0.947498 -2.964888 -v 0.009916 0.068545 0.088495 -vn 5.098596 1.843816 -2.510018 -v 0.009916 0.069939 0.089205 -vn 3.383251 -0.000000 3.118687 -v 0.007550 0.067000 0.075250 -vn 3.383255 -0.746351 3.028064 -v 0.007550 0.071308 0.075773 -vn 3.383254 -1.449327 2.761459 -v 0.007550 0.075365 0.077312 -vn 3.383253 -2.068072 2.334371 -v 0.007550 0.078936 0.079777 -vn 3.383255 -2.566629 1.771616 -v 0.007550 0.081814 0.083025 -vn 3.383253 -2.916023 1.105902 -v 0.007550 0.083830 0.086867 -vn 3.383254 -3.095948 0.375917 -v 0.007550 0.084869 0.091080 -vn 3.383254 -3.095948 -0.375917 -v 0.007550 0.084869 0.095420 -vn 3.383252 -2.916023 -1.105902 -v 0.007550 0.083830 0.099633 -vn 3.383254 -2.566629 -1.771616 -v 0.007550 0.081814 0.103475 -vn 3.383253 -2.068070 -2.334372 -v 0.007550 0.078936 0.106723 -vn 3.383252 -1.449326 -2.761461 -v 0.007550 0.075365 0.109188 -vn 3.383256 -0.746351 -3.028063 -v 0.007550 0.071308 0.110727 -vn 3.383252 -0.000000 -3.118687 -v 0.007550 0.067000 0.111250 -vn 3.383254 0.746351 -3.028064 -v 0.007550 0.062692 0.110727 -vn 3.383252 1.449326 -2.761461 -v 0.007550 0.058635 0.109188 -vn 3.383255 2.068071 -2.334371 -v 0.007550 0.055064 0.106723 -vn 3.383253 2.566629 -1.771616 -v 0.007550 0.052186 0.103475 -vn 3.383256 2.916023 -1.105901 -v 0.007550 0.050170 0.099633 -vn 3.383253 3.095948 -0.375916 -v 0.007550 0.049131 0.095420 -vn 3.383254 3.095948 0.375916 -v 0.007550 0.049131 0.091080 -vn 3.383254 2.916023 1.105902 -v 0.007550 0.050170 0.086867 -vn 3.383254 2.566629 1.771616 -v 0.007550 0.052186 0.083025 -vn 3.383254 2.068073 2.334370 -v 0.007550 0.055064 0.079777 -vn 3.383254 1.449328 2.761460 -v 0.007550 0.058635 0.077312 -vn 3.383256 0.746351 3.028063 -v 0.007550 0.062692 0.075773 -vn 2.899929 2.566629 1.771616 -v 0.007550 0.082225 0.103759 -vn 2.899932 2.068071 2.334372 -v 0.007550 0.079268 0.107097 -vn 2.899933 1.449327 2.761460 -v 0.007550 0.075597 0.109631 -vn 2.899930 0.746351 3.028063 -v 0.007550 0.071427 0.111212 -vn 2.899933 0.000000 3.118687 -v 0.007550 0.067000 0.111750 -vn 2.899930 -0.746351 3.028063 -v 0.007550 0.062573 0.111212 -vn 2.899931 -1.449327 2.761460 -v 0.007550 0.058403 0.109631 -vn 2.899932 -2.068072 2.334371 -v 0.007550 0.054732 0.107097 -vn 2.899932 -2.566629 1.771616 -v 0.007550 0.051775 0.103759 -vn 2.899932 -2.916023 1.105902 -v 0.007550 0.049702 0.099810 -vn 2.899931 -3.095948 0.375916 -v 0.007550 0.048635 0.095480 -vn 2.899932 -3.095949 -0.375916 -v 0.007550 0.048635 0.091020 -vn 2.899932 -2.916022 -1.105902 -v 0.007550 0.049702 0.086690 -vn 2.899933 -2.566629 -1.771615 -v 0.007550 0.051775 0.082741 -vn 2.899931 -2.068073 -2.334370 -v 0.007550 0.054732 0.079403 -vn 2.899932 -1.449325 -2.761460 -v 0.007550 0.058403 0.076869 -vn 2.899933 -0.746351 -3.028063 -v 0.007550 0.062573 0.075288 -vn 2.899930 0.000000 -3.118686 -v 0.007550 0.067000 0.074750 -vn 2.899935 0.746351 -3.028064 -v 0.007550 0.071427 0.075288 -vn 2.899932 1.449325 -2.761461 -v 0.007550 0.075597 0.076869 -vn 2.899931 2.068072 -2.334371 -v 0.007550 0.079268 0.079403 -vn 2.899932 2.566629 -1.771615 -v 0.007550 0.082225 0.082741 -vn 2.899931 2.916024 -1.105901 -v 0.007550 0.084298 0.086690 -vn 2.899932 3.095948 -0.375915 -v 0.007550 0.085365 0.091020 -vn 2.899932 3.095949 0.375915 -v 0.007550 0.085365 0.095480 -vn 2.899932 2.916024 1.105900 -v 0.007550 0.084298 0.099810 -vn -1.570796 -4.712389 1.570796 -v -0.070450 0.048000 0.131750 -vn 1.570796 -4.712389 1.570796 -v -0.046450 0.048000 0.131750 -vn -1.570796 -1.570796 1.570796 -v -0.070450 0.048000 0.135750 -vn 1.570796 -1.570796 1.570796 -v -0.046450 0.048000 0.135750 -vn 3.088069 0.406551 3.403391 -v -0.046450 0.082500 0.135750 -vn 1.570796 1.570796 1.570796 -v -0.046450 0.086000 0.135750 -vn -1.517272 -2.627994 3.665190 -v -0.072200 0.054531 0.135750 -vn -1.570796 1.570796 1.570796 -v -0.070450 0.086000 0.135750 -vn -3.088069 0.406551 3.403391 -v -0.070450 0.082500 0.135750 -vn -2.627994 1.517272 3.665192 -v -0.070919 0.080750 0.135750 -vn -0.406551 3.088069 3.403391 -v -0.073950 0.079000 0.135750 -vn -3.088069 -0.406551 3.403391 -v -0.070450 0.051500 0.135750 -vn 2.627994 1.517272 3.665190 -v -0.045981 0.080750 0.135750 -vn 2.627994 -1.517272 3.665193 -v -0.045981 0.053250 0.135750 -vn 1.517272 -2.627994 3.665190 -v -0.044700 0.054531 0.135750 -vn -1.517272 2.627994 3.665192 -v -0.072200 0.079469 0.135750 -vn -0.406551 -3.088069 3.403391 -v -0.073950 0.055000 0.135750 -vn -2.627994 -1.517272 3.665192 -v -0.070919 0.053250 0.135750 -vn 3.088069 -0.406551 3.403391 -v -0.046450 0.051500 0.135750 -vn 0.406551 -3.088069 3.403391 -v -0.042950 0.055000 0.135750 -vn 0.406551 3.088069 3.403391 -v -0.042950 0.079000 0.135750 -vn 1.517272 2.627994 3.665192 -v -0.044700 0.079469 0.135750 -vn 1.570796 4.712389 1.570796 -v -0.046450 0.086000 0.131750 -vn -1.570796 4.712389 1.570796 -v -0.070450 0.086000 0.131750 -vn -0.406551 -3.088069 2.879794 -v -0.073950 0.055000 0.131750 -vn -3.088069 -0.406551 2.879794 -v -0.070450 0.051500 0.131750 -vn -1.517272 -2.627994 2.617993 -v -0.072200 0.054531 0.131750 -vn -2.627994 -1.517272 2.617993 -v -0.070919 0.053250 0.131750 -vn 3.088069 -0.406551 2.879794 -v -0.046450 0.051500 0.131750 -vn 2.627994 -1.517272 2.617993 -v -0.045981 0.053250 0.131750 -vn 1.517272 -2.627994 2.617993 -v -0.044700 0.054531 0.131750 -vn 0.406551 -3.088069 2.879794 -v -0.042950 0.055000 0.131750 -vn 0.406551 3.088069 2.879794 -v -0.042950 0.079000 0.131750 -vn 3.088069 0.406551 2.879794 -v -0.046450 0.082500 0.131750 -vn 2.627994 1.517272 2.617993 -v -0.045981 0.080750 0.131750 -vn 1.517272 2.627994 2.617993 -v -0.044700 0.079469 0.131750 -vn -3.088069 0.406551 2.879794 -v -0.070450 0.082500 0.131750 -vn -2.627994 1.517272 2.617993 -v -0.070919 0.080750 0.131750 -vn -1.517272 2.627994 2.617993 -v -0.072200 0.079469 0.131750 -vn -0.406551 3.088069 2.879794 -v -0.073950 0.079000 0.131750 -vn 1.570796 1.570796 -1.570796 -v 0.013550 0.055000 0.091250 -vn 1.570796 -1.570796 -1.570796 -v 0.013550 0.054000 0.091250 -vn 1.570796 1.570796 1.570796 -v 0.013550 0.055000 0.095250 -vn 1.570796 -1.570796 1.570796 -v 0.013550 0.054000 0.095250 -vn 1.570796 -1.570796 1.570796 -v 0.013550 0.079000 0.095250 -vn 1.570796 1.570796 1.570796 -v 0.013550 0.080000 0.095250 -vn 1.570796 -1.570796 -1.570796 -v 0.013550 0.079000 0.091250 -vn 1.570796 1.570796 -1.570796 -v 0.013550 0.080000 0.091250 -vn 2.618005 1.517271 2.628000 -v 0.013050 0.067750 0.094549 -vn 2.617979 2.627989 1.517268 -v 0.013050 0.068299 0.094000 -vn 2.618007 3.034551 -0.000004 -v 0.013050 0.068500 0.093250 -vn 2.617989 2.627995 -1.517265 -v 0.013050 0.068299 0.092500 -vn 2.617989 1.517265 -2.627996 -v 0.013050 0.067750 0.091951 -vn 2.618007 0.000004 -3.034551 -v 0.013050 0.067000 0.091750 -vn 2.617979 -1.517269 -2.627989 -v 0.013050 0.066250 0.091951 -vn 2.618005 -2.627999 -1.517271 -v 0.013050 0.065701 0.092500 -vn 2.617989 -3.034544 -0.000004 -v 0.013050 0.065500 0.093250 -vn 2.617996 -2.627993 1.517275 -v 0.013050 0.065701 0.094000 -vn 2.617996 -1.517275 2.627993 -v 0.013050 0.066250 0.094549 -vn 2.617989 0.000004 3.034544 -v 0.013050 0.067000 0.094750 -vn 6.283185 0.000000 0.000000 -v 0.013050 0.067000 0.093250 -vn 3.496196 1.331169 -2.773874 -v 0.005550 -0.064614 0.088295 -vn 3.516681 -0.000000 -3.075471 -v 0.005550 -0.067000 0.087750 -vn 2.899933 -0.000000 3.118687 -v 0.005550 -0.067000 0.075250 -vn 2.899931 0.746351 3.028063 -v 0.005550 -0.071308 0.075773 -vn 3.496198 -1.331170 -2.773874 -v 0.005550 -0.069386 0.088295 -vn 2.899932 1.449327 2.761459 -v 0.005550 -0.075365 0.077312 -vn 4.712389 -1.570796 1.570796 -v 0.005550 -0.080000 0.095250 -vn 2.899931 3.095948 -0.375917 -v 0.005550 -0.084869 0.095420 -vn 2.899931 3.095948 0.375917 -v 0.005550 -0.084869 0.091080 -vn 2.899931 -2.566629 -1.771616 -v 0.005550 -0.052186 0.103475 -vn 4.712390 -1.570796 1.570796 -v 0.005550 -0.055000 0.095250 -vn 2.899933 -2.916023 -1.105900 -v 0.005550 -0.050170 0.099633 -vn 4.712389 1.570796 1.570796 -v 0.005550 -0.054000 0.095250 -vn 2.899932 -3.095948 -0.375916 -v 0.005550 -0.049131 0.095420 -vn 4.712389 1.570796 -1.570796 -v 0.005550 -0.054000 0.091250 -vn 2.899932 -3.095948 0.375916 -v 0.005550 -0.049131 0.091080 -vn 2.899931 -2.068070 -2.334372 -v 0.005550 -0.055064 0.106723 -vn 2.899932 -1.449325 -2.761461 -v 0.005550 -0.058635 0.109188 -vn 2.899931 -0.746350 -3.028063 -v 0.005550 -0.062692 0.110727 -vn 4.712389 1.570796 1.570796 -v 0.005550 -0.079000 0.095250 -vn 2.899932 0.746351 -3.028063 -v 0.005550 -0.071308 0.110727 -vn 2.899933 1.449326 -2.761461 -v 0.005550 -0.075365 0.109188 -vn 4.712389 -1.570796 -1.570796 -v 0.005550 -0.080000 0.091250 -vn 2.899934 2.916023 1.105902 -v 0.005550 -0.083830 0.086867 -vn 4.712389 1.570796 -1.570796 -v 0.005550 -0.079000 0.091250 -vn 2.899931 2.566629 1.771616 -v 0.005550 -0.081814 0.083025 -vn 2.899932 2.068072 2.334371 -v 0.005550 -0.078936 0.079777 -vn 2.899931 2.068070 -2.334372 -v 0.005550 -0.078936 0.106723 -vn 2.899932 2.566629 -1.771616 -v 0.005550 -0.081814 0.103475 -vn 2.899932 2.916023 -1.105902 -v 0.005550 -0.083830 0.099633 -vn 2.899931 -0.746350 3.028064 -v 0.005550 -0.062692 0.075773 -vn 2.899931 -1.449327 2.761459 -v 0.005550 -0.058635 0.077312 -vn 4.712390 -1.570796 -1.570796 -v 0.005550 -0.055000 0.091250 -vn 2.899932 -2.068072 2.334370 -v 0.005550 -0.055064 0.079777 -vn 2.899932 -2.566629 1.771616 -v 0.005550 -0.052186 0.083025 -vn 2.899932 -2.916023 1.105901 -v 0.005550 -0.050170 0.086867 -vn 3.513811 -2.411379 -1.908246 -v 0.005550 -0.071300 0.089821 -vn 3.505719 -2.995619 -0.696700 -v 0.005550 -0.072362 0.092026 -vn 3.524807 2.415867 -1.899404 -v 0.005550 -0.062700 0.089821 -vn 3.515517 -2.991667 0.705368 -v 0.005550 -0.072362 0.094474 -vn 3.524814 -2.415866 1.899404 -v 0.005550 -0.071300 0.096679 -vn 3.496189 -1.331172 2.773874 -v 0.005550 -0.069386 0.098205 -vn 3.516683 -0.000000 3.075470 -v 0.005550 -0.067000 0.098750 -vn 3.496186 1.331172 2.773875 -v 0.005550 -0.064614 0.098205 -vn 2.899932 0.000000 -3.118687 -v 0.005550 -0.067000 0.111250 -vn 3.513808 2.411376 1.908249 -v 0.005550 -0.062700 0.096679 -vn 3.505719 2.995618 0.696701 -v 0.005550 -0.061638 0.094474 -vn 3.515516 2.991666 -0.705368 -v 0.005550 -0.061638 0.092026 -vn 1.110721 -0.785398 -5.823110 -v -0.041691 -0.049000 0.112750 -vn 1.110720 3.926991 -2.681517 -v -0.041691 -0.048000 0.112750 -vn 1.570798 1.570796 -1.570796 -v -0.039450 -0.048000 0.112750 -vn 1.570798 -1.570796 -1.570796 -v -0.039450 -0.086000 0.112750 -vn 1.110720 -3.926991 -2.681517 -v -0.041691 -0.086000 0.112750 -vn 1.110721 0.785398 -5.823110 -v -0.041691 -0.085000 0.112750 -vn 1.570797 1.570796 -1.570796 -v -0.050450 -0.085000 0.112750 -vn 1.570797 -1.570796 -1.570796 -v -0.050450 -0.049000 0.112750 -vn -1.570796 -1.570796 1.570796 -v -0.077450 -0.086000 0.131750 -vn -4.712389 -1.570796 1.570796 -v -0.077450 -0.079000 0.131750 -vn -2.984512 -3.122253 -0.245727 -v -0.077450 -0.086000 0.083750 -vn -2.984514 3.122253 -0.245725 -v -0.077450 -0.048000 0.083750 -vn -1.570796 1.570796 1.570796 -v -0.077450 -0.048000 0.131750 -vn -4.712389 1.570796 1.570796 -v -0.077450 -0.055000 0.131750 -vn -1.570796 1.570796 1.570796 -v -0.077450 -0.055000 0.135750 -vn -1.570796 -1.570796 1.570796 -v -0.077450 -0.079000 0.135750 -vn -2.827434 2.510310 -1.823849 -v -0.077450 -0.049910 0.077872 -vn -2.827435 1.823850 -2.510310 -v -0.077450 -0.052122 0.075660 -vn -2.827430 0.958853 -2.951046 -v -0.077450 -0.054910 0.074239 -vn -2.984515 -0.245723 -3.122254 -v -0.077450 -0.076000 0.073750 -vn -2.827429 -0.958853 -2.951046 -v -0.077450 -0.079090 0.074239 -vn -2.984515 0.245724 -3.122254 -v -0.077450 -0.058000 0.073750 -vn -2.827431 2.951046 -0.958853 -v -0.077450 -0.048489 0.080660 -vn -2.827437 -1.823849 -2.510311 -v -0.077450 -0.081878 0.075660 -vn -2.827432 -2.510309 -1.823849 -v -0.077450 -0.084090 0.077872 -vn -2.827434 -2.951047 -0.958854 -v -0.077450 -0.085511 0.080660 -vn 1.570796 1.570796 1.570796 -v -0.039450 -0.048000 0.131750 -vn 4.712389 1.570796 1.570796 -v -0.039450 -0.055000 0.131750 -vn 3.665188 -3.034547 -0.000004 -v -0.039450 -0.078750 0.132500 -vn 1.570794 -1.570796 1.570796 -v -0.039450 -0.079000 0.135750 -vn 4.712389 -1.570796 1.570796 -v -0.039450 -0.079000 0.131750 -vn 3.665181 -1.517271 -2.627999 -v -0.039450 -0.077250 0.129902 -vn 3.665199 -2.627985 -1.517279 -v -0.039450 -0.078348 0.131000 -vn 1.570796 -1.570796 1.570796 -v -0.039450 -0.086000 0.131750 -vn 3.665185 -1.517273 -2.627996 -v -0.039450 -0.059750 0.129902 -vn 3.665194 -2.627988 -1.517279 -v -0.039450 -0.060848 0.131000 -vn 3.665186 1.517273 -2.627996 -v -0.039450 -0.074250 0.129902 -vn 3.665198 0.000001 -3.034544 -v -0.039450 -0.058250 0.129500 -vn 3.665198 -0.000002 -3.034542 -v -0.039450 -0.075750 0.129500 -vn 3.665198 -2.627990 1.517275 -v -0.039450 -0.060848 0.134000 -vn 3.665198 2.627991 1.517272 -v -0.039450 -0.073152 0.134000 -vn 3.665193 -3.034545 -0.000004 -v -0.039450 -0.061250 0.132500 -vn 3.665188 3.034546 -0.000004 -v -0.039450 -0.072750 0.132500 -vn 3.665195 2.627990 -1.517275 -v -0.039450 -0.073152 0.131000 -vn 3.665201 -2.627987 1.517275 -v -0.039450 -0.078348 0.134000 -vn 3.665181 -1.517271 2.627999 -v -0.039450 -0.077250 0.135098 -vn 3.665197 -0.000002 3.034543 -v -0.039450 -0.075750 0.135500 -vn 3.665184 1.517274 2.627995 -v -0.039450 -0.056750 0.135098 -vn 1.570798 1.570796 1.570796 -v -0.039450 -0.055000 0.135750 -vn 3.665197 0.000001 3.034542 -v -0.039450 -0.058250 0.135500 -vn 3.665188 -1.517273 2.627996 -v -0.039450 -0.059750 0.135098 -vn 3.665185 1.517273 2.627996 -v -0.039450 -0.074250 0.135098 -vn 3.665195 2.627990 1.517275 -v -0.039450 -0.055652 0.134000 -vn 3.665192 3.034544 -0.000004 -v -0.039450 -0.055250 0.132500 -vn 3.665193 2.627989 -1.517279 -v -0.039450 -0.055652 0.131000 -vn 3.665184 1.517274 -2.627995 -v -0.039450 -0.056750 0.129902 -vn 2.681516 -3.926991 -1.110721 -v -0.050450 -0.086000 0.103991 -vn 5.823110 0.785398 -1.110721 -v -0.050450 -0.085000 0.103991 -vn 3.383256 -0.000000 -3.118686 -v -0.050450 -0.067000 0.074750 -vn 2.984514 -0.245723 -3.122254 -v -0.050450 -0.076000 0.073750 -vn 2.984514 0.245724 -3.122254 -v -0.050450 -0.058000 0.073750 -vn 3.383253 1.449327 2.761460 -v -0.050450 -0.058403 0.109631 -vn 3.383253 2.068072 2.334372 -v -0.050450 -0.054732 0.107097 -vn 5.823109 -0.785398 -1.110721 -v -0.050450 -0.049000 0.103991 -vn 2.827432 -2.510309 -1.823850 -v -0.050450 -0.084090 0.077872 -vn 3.383255 -2.068072 -2.334371 -v -0.050450 -0.079268 0.079403 -vn 3.383253 -2.566629 -1.771615 -v -0.050450 -0.082225 0.082741 -vn 3.383253 -2.916023 -1.105903 -v -0.050450 -0.084298 0.086690 -vn 2.984511 -3.122253 -0.245727 -v -0.050450 -0.086000 0.083750 -vn 2.827434 -2.951047 -0.958854 -v -0.050450 -0.085511 0.080660 -vn 2.984512 3.122254 -0.245725 -v -0.050450 -0.048000 0.083750 -vn 3.383255 2.916023 -1.105901 -v -0.050450 -0.049702 0.086690 -vn 2.827431 2.951046 -0.958853 -v -0.050450 -0.048489 0.080660 -vn 3.383253 2.566629 -1.771617 -v -0.050450 -0.051775 0.082741 -vn 2.827435 2.510310 -1.823849 -v -0.050450 -0.049910 0.077872 -vn 3.383254 2.068073 -2.334371 -v -0.050450 -0.054732 0.079403 -vn 2.827435 1.823850 -2.510310 -v -0.050450 -0.052122 0.075660 -vn 2.827430 0.958853 -2.951047 -v -0.050450 -0.054910 0.074239 -vn 3.383255 1.449325 -2.761460 -v -0.050450 -0.058403 0.076869 -vn 3.383252 0.746351 -3.028063 -v -0.050450 -0.062573 0.075288 -vn 3.383253 -1.449327 2.761460 -v -0.050450 -0.075597 0.109631 -vn 3.383255 -0.746351 3.028063 -v -0.050450 -0.071427 0.111212 -vn 3.383253 -0.000000 3.118687 -v -0.050450 -0.067000 0.111750 -vn 3.383255 0.746351 3.028063 -v -0.050450 -0.062573 0.111212 -vn 3.383251 -0.746351 -3.028064 -v -0.050450 -0.071427 0.075288 -vn 3.383254 -1.449325 -2.761461 -v -0.050450 -0.075597 0.076869 -vn 2.827429 -0.958853 -2.951046 -v -0.050450 -0.079090 0.074239 -vn 2.827437 -1.823848 -2.510311 -v -0.050450 -0.081878 0.075660 -vn 3.383255 2.566629 1.771617 -v -0.050450 -0.051775 0.103759 -vn 3.383255 2.916024 1.105900 -v -0.050450 -0.049702 0.099810 -vn 2.681516 3.926991 -1.110721 -v -0.050450 -0.048000 0.103991 -vn 3.383253 3.095948 0.375915 -v -0.050450 -0.048635 0.095480 -vn 3.383253 3.095949 -0.375915 -v -0.050450 -0.048635 0.091020 -vn 3.383255 -3.095948 -0.375918 -v -0.050450 -0.085365 0.091020 -vn 3.383255 -3.095948 0.375918 -v -0.050450 -0.085365 0.095480 -vn 3.383252 -2.916024 1.105902 -v -0.050450 -0.084298 0.099810 -vn 3.383255 -2.566629 1.771616 -v -0.050450 -0.082225 0.103759 -vn 3.383253 -2.068071 2.334372 -v -0.050450 -0.079268 0.107097 -vn 2.617984 2.627985 1.517279 -v -0.059450 -0.077915 0.131250 -vn 2.618011 1.517276 2.627997 -v -0.059450 -0.077000 0.130335 -vn 6.283185 0.000000 0.000000 -v -0.059450 -0.075750 0.132500 -vn 2.617976 -0.000000 3.034538 -v -0.059450 -0.075750 0.130000 -vn 2.618011 -1.517277 2.627999 -v -0.059450 -0.074500 0.130335 -vn 2.618011 1.517277 -2.627999 -v -0.059450 -0.077000 0.134665 -vn 2.617980 2.627985 -1.517272 -v -0.059450 -0.077915 0.133750 -vn 2.618001 3.034548 0.000005 -v -0.059450 -0.078250 0.132500 -vn 2.617980 -2.627986 -1.517274 -v -0.059450 -0.073585 0.133750 -vn 2.618011 -1.517276 -2.627997 -v -0.059450 -0.074500 0.134665 -vn 2.617976 0.000000 -3.034538 -v -0.059450 -0.075750 0.135000 -vn 2.617984 -2.627984 1.517277 -v -0.059450 -0.073585 0.131250 -vn 2.618001 -3.034548 0.000005 -v -0.059450 -0.073250 0.132500 -vn 2.617989 2.627985 1.517280 -v -0.059450 -0.060415 0.131250 -vn 2.618008 1.517278 2.627996 -v -0.059450 -0.059500 0.130335 -vn 6.283185 0.000000 0.000000 -v -0.059450 -0.058250 0.132500 -vn 2.617977 -0.000001 3.034538 -v -0.059450 -0.058250 0.130000 -vn 2.618009 -1.517279 2.627995 -v -0.059450 -0.057000 0.130335 -vn 2.618008 1.517278 -2.627996 -v -0.059450 -0.059500 0.134665 -vn 2.617985 2.627987 -1.517276 -v -0.059450 -0.060415 0.133750 -vn 2.617995 3.034545 0.000005 -v -0.059450 -0.060750 0.132500 -vn 2.617985 -2.627986 -1.517276 -v -0.059450 -0.056085 0.133750 -vn 2.618009 -1.517279 -2.627996 -v -0.059450 -0.057000 0.134665 -vn 2.617977 -0.000001 -3.034537 -v -0.059450 -0.058250 0.135000 -vn 2.617988 -2.627986 1.517280 -v -0.059450 -0.056085 0.131250 -vn 2.617995 -3.034545 0.000004 -v -0.059450 -0.055750 0.132500 -vn 3.630355 -0.000001 3.491267 -v -0.011387 -0.075750 0.130000 -vn 3.630322 -1.745633 3.023528 -v -0.011387 -0.074500 0.130335 -vn 3.630349 -3.023519 1.745641 -v -0.011387 -0.073585 0.131250 -vn 3.630332 -3.491268 0.000006 -v -0.011387 -0.073250 0.132500 -vn 3.630352 -3.023519 -1.745636 -v -0.011387 -0.073585 0.133750 -vn 3.630322 -1.745637 -3.023528 -v -0.011387 -0.074500 0.134665 -vn 3.630356 0.000001 -3.491267 -v -0.011387 -0.075750 0.135000 -vn 3.630322 1.745636 -3.023530 -v -0.011387 -0.077000 0.134665 -vn 3.630352 3.023520 -1.745637 -v -0.011387 -0.077915 0.133750 -vn 3.630332 3.491268 0.000005 -v -0.011387 -0.078250 0.132500 -vn 3.630349 3.023517 1.745641 -v -0.011387 -0.077915 0.131250 -vn 3.630322 1.745639 3.023530 -v -0.011387 -0.077000 0.130335 -vn 3.629357 0.006217 3.500497 -v -0.011297 -0.058250 0.130000 -vn 3.629524 -1.747734 3.032701 -v -0.011297 -0.057000 0.130335 -vn 3.629260 -3.030081 1.755162 -v -0.011297 -0.056085 0.131250 -vn 3.628709 -3.504608 0.005952 -v -0.011297 -0.055750 0.132500 -vn 3.627775 -3.042106 -1.750568 -v -0.011297 -0.056085 0.133750 -vn 3.626173 -1.760737 -3.046627 -v -0.011297 -0.057000 0.134665 -vn 3.624199 -0.000002 -3.530877 -v -0.011297 -0.058250 0.135000 -vn 3.626174 1.760736 -3.046628 -v -0.011297 -0.059500 0.134665 -vn 3.627774 3.042106 -1.750569 -v -0.011297 -0.060415 0.133750 -vn 3.628709 3.504609 0.005951 -v -0.011297 -0.060750 0.132500 -vn 3.626700 3.031346 1.780464 -v -0.011297 -0.060415 0.131250 -vn 3.626222 1.741431 3.056190 -v -0.011297 -0.059500 0.130335 -vn 2.986992 -2.379162 -1.373618 -v -0.011324 -0.078348 0.131000 -vn 2.987010 -1.373609 -2.379170 -v -0.011324 -0.077250 0.129902 -vn 2.986992 -0.000003 -2.747221 -v -0.011324 -0.075750 0.129500 -vn 2.987005 1.373615 -2.379169 -v -0.011324 -0.074250 0.129902 -vn 2.986993 2.379163 -1.373617 -v -0.011324 -0.073152 0.131000 -vn 2.987002 2.747227 -0.000003 -v -0.011324 -0.072750 0.132500 -vn 2.986991 2.379166 1.373612 -v -0.011324 -0.073152 0.134000 -vn 2.987004 1.373612 2.379170 -v -0.011324 -0.074250 0.135098 -vn 2.986992 -0.000000 2.747221 -v -0.011324 -0.075750 0.135500 -vn 2.987009 -1.373612 2.379169 -v -0.011324 -0.077250 0.135098 -vn 2.986986 -2.379162 1.373616 -v -0.011324 -0.078348 0.134000 -vn 2.987000 -2.747227 -0.000003 -v -0.011324 -0.078750 0.132500 -vn 3.268148 -1.313134 -2.405175 -v -0.011228 -0.059750 0.129902 -vn 3.262831 -0.701987 -2.709315 -v -0.011228 -0.058968 0.129587 -vn 3.270133 -2.623600 -0.832502 -v -0.011228 -0.061055 0.131436 -vn 3.275887 -2.308439 -1.470535 -v -0.011228 -0.060848 0.131000 -vn 3.267736 -1.911582 -2.027001 -v -0.011228 -0.060239 0.130254 -vn 3.275383 -2.694561 0.531362 -v -0.011228 -0.061228 0.132862 -vn 3.282271 -2.718551 -0.182671 -v -0.011228 -0.061250 0.132500 -vn 3.280315 -2.100079 1.758267 -v -0.011228 -0.060719 0.134204 -vn 3.289661 -2.467012 1.154489 -v -0.011228 -0.060848 0.134000 -vn 3.284970 -0.989929 2.544909 -v -0.011228 -0.059644 0.135156 -vn 3.296744 -1.600394 2.202749 -v -0.011228 -0.059750 0.135098 -vn 3.284972 0.989931 2.544909 -v -0.011228 -0.056856 0.135156 -vn 3.063870 0.000000 2.721007 -v -0.011228 -0.058250 0.135500 -vn 3.286893 2.102958 1.754419 -v -0.011228 -0.055781 0.134204 -vn 3.303520 1.596311 2.205293 -v -0.011228 -0.056750 0.135098 -vn 3.288526 2.695908 0.521885 -v -0.011228 -0.055272 0.132862 -vn 3.303543 2.462302 1.162880 -v -0.011228 -0.055652 0.134000 -vn 3.289782 2.618553 -0.845933 -v -0.011228 -0.055445 0.131436 -vn 3.303560 2.718421 -0.168185 -v -0.011228 -0.055250 0.132500 -vn 3.290606 1.888338 -2.007210 -v -0.011228 -0.056261 0.130254 -vn 3.303579 2.300954 -1.457995 -v -0.011228 -0.055652 0.131000 -vn 3.303593 0.000001 -2.724290 -v -0.011228 -0.058250 0.129500 -vn 3.291047 0.686643 -2.671058 -v -0.011228 -0.057532 0.129587 -vn 3.303607 1.313215 -2.386804 -v -0.011228 -0.056750 0.129902 -vn 3.665197 -0.000004 3.034544 -v 0.009050 -0.067000 0.094750 -vn 2.829942 0.725374 -2.989811 -v 0.009050 -0.068077 0.097619 -vn 3.665181 -1.517271 2.628000 -v 0.009050 -0.067750 0.094549 -vn 2.859004 2.028536 -2.324958 -v 0.009050 -0.069984 0.096618 -vn 3.665206 -2.627989 1.517269 -v 0.009050 -0.068299 0.094000 -vn 2.834510 2.890769 -1.075969 -v 0.009050 -0.071208 0.094846 -vn 3.665178 -3.034551 -0.000004 -v 0.009050 -0.068500 0.093250 -vn 2.871422 3.066307 0.358826 -v 0.009050 -0.071467 0.092708 -vn 3.665196 -2.627995 -1.517265 -v 0.009050 -0.068299 0.092500 -vn 2.776922 2.494033 1.797495 -v 0.009050 -0.070703 0.090694 -vn 3.665197 -1.517265 -2.627996 -v 0.009050 -0.067750 0.091951 -vn 2.860155 1.464516 2.711591 -v 0.009050 -0.069091 0.089265 -vn 3.665178 -0.000004 -3.034551 -v 0.009050 -0.067000 0.091750 -vn 2.731811 -0.078848 3.066907 -v 0.009050 -0.067000 0.088750 -vn 3.665206 1.517269 -2.627989 -v 0.009050 -0.066250 0.091951 -vn 2.857199 -1.398967 2.743850 -v 0.009050 -0.064909 0.089265 -vn 3.665181 2.627999 -1.517271 -v 0.009050 -0.065701 0.092500 -vn 2.738466 -2.566809 1.679154 -v 0.009050 -0.063297 0.090694 -vn 3.665197 3.034544 -0.000004 -v 0.009050 -0.065500 0.093250 -vn 2.839978 -3.051537 0.376089 -v 0.009050 -0.062533 0.092708 -vn 3.665190 2.627993 1.517275 -v 0.009050 -0.065701 0.094000 -vn 2.722108 -2.845104 -1.127349 -v 0.009050 -0.062792 0.094846 -vn 3.665190 1.517275 2.627993 -v 0.009050 -0.066250 0.094549 -vn 2.836566 -2.045469 -2.296992 -v 0.009050 -0.064016 0.096618 -vn 2.742063 -0.671855 -2.989282 -v 0.009050 -0.065923 0.097619 -vn -2.246807 0.000000 2.950417 -v -0.019450 -0.075750 0.136522 -vn -2.246810 1.475209 2.555137 -v -0.019450 -0.073739 0.135983 -vn -2.246810 2.555137 1.475208 -v -0.019450 -0.072267 0.134511 -vn -2.246808 2.950417 -0.000002 -v -0.019450 -0.071728 0.132500 -vn -2.246812 2.555136 -1.475212 -v -0.019450 -0.072267 0.130489 -vn -2.246810 1.475210 -2.555137 -v -0.019450 -0.073739 0.129017 -vn -2.246807 -0.000001 -2.950417 -v -0.019450 -0.075750 0.128478 -vn -2.246809 -1.475209 -2.555138 -v -0.019450 -0.077761 0.129017 -vn -2.246809 -2.555138 -1.475207 -v -0.019450 -0.079233 0.130489 -vn -2.246816 -2.950421 -0.000003 -v -0.019450 -0.079772 0.132500 -vn -2.246806 -2.555137 1.475204 -v -0.019450 -0.079233 0.134511 -vn -2.246809 -1.475210 2.555136 -v -0.019450 -0.077761 0.135983 -vn -2.249108 -2.435984 1.681517 -v -0.019450 -0.061657 0.134851 -vn -2.249455 -2.938452 0.356883 -v -0.019450 -0.062359 0.132999 -vn -2.248682 -1.375521 2.620898 -v -0.019450 -0.060174 0.136165 -vn -2.249691 -2.767765 -1.049549 -v -0.019450 -0.062120 0.131032 -vn -2.249840 -1.963019 -2.215579 -v -0.019450 -0.060995 0.129402 -vn -2.276937 0.710647 -2.882020 -v -0.019450 -0.057259 0.128481 -vn -2.262815 -0.718703 -2.875728 -v -0.019450 -0.059241 0.128481 -vn -2.275333 1.968694 -2.220935 -v -0.019450 -0.055505 0.129402 -vn -2.272104 2.774614 -1.050801 -v -0.019450 -0.054380 0.131032 -vn -2.267271 2.943652 0.359347 -v -0.019450 -0.054141 0.132999 -vn -2.260840 2.437611 1.685517 -v -0.019450 -0.054843 0.134851 -vn -2.248132 0.000000 2.959836 -v -0.019450 -0.058250 0.136639 -vn -2.252840 1.373554 2.623378 -v -0.019450 -0.056326 0.136165 -vn 3.160393 -1.017523 1.962741 -v 0.010050 -0.064909 0.089265 -vn 3.427033 -1.415932 1.730251 -v 0.010050 -0.064355 0.089609 -vn 3.221632 -1.726341 1.475661 -v 0.010050 -0.063359 0.090605 -vn 3.264872 -1.977259 1.068265 -v 0.010050 -0.063297 0.090694 -vn 3.717478 -1.995253 0.868614 -v 0.010050 -0.062720 0.091859 -vn 3.161711 -2.194708 0.300581 -v 0.010050 -0.062533 0.092708 -vn 3.475272 -2.220720 -0.209572 -v 0.010050 -0.062500 0.093250 -vn 3.319093 -2.207750 -0.474164 -v 0.010050 -0.062720 0.094641 -vn 3.269228 -1.989555 -0.988999 -v 0.010050 -0.062792 0.094846 -vn 3.783655 -1.851098 -1.108436 -v 0.010050 -0.063359 0.095895 -vn 3.164228 -1.517162 -1.625578 -v 0.010050 -0.064016 0.096618 -vn 3.398830 -1.151293 -1.926385 -v 0.010050 -0.064355 0.096891 -vn 3.349211 -0.891707 -2.068758 -v 0.010050 -0.065609 0.097530 -vn 3.271946 -0.332467 -2.166038 -v 0.010050 -0.065923 0.097619 -vn 3.849910 -0.171859 -2.130473 -v 0.010050 -0.067000 0.097750 -vn 3.167700 0.453691 -2.188748 -v 0.010050 -0.068077 0.097619 -vn 3.330984 0.877469 -2.077433 -v 0.010050 -0.068391 0.097530 -vn 3.377917 1.167596 -1.920007 -v 0.010050 -0.069645 0.096891 -vn 3.171713 2.060889 -0.900711 -v 0.010050 -0.071208 0.094846 -vn 3.463872 1.823772 -1.260008 -v 0.010050 -0.070641 0.095895 -vn 3.148546 1.460619 -1.611467 -v 0.010050 -0.069984 0.096618 -vn 3.271965 2.203104 -0.521214 -v 0.010050 -0.071280 0.094641 -vn 3.404153 2.235928 -0.157047 -v 0.010050 -0.071500 0.093250 -vn 3.136522 2.124127 0.248220 -v 0.010050 -0.071467 0.092708 -vn 3.454649 2.076868 0.769727 -v 0.010050 -0.071280 0.091859 -vn 3.175823 1.939991 1.166342 -v 0.010050 -0.070703 0.090694 -vn 3.288656 1.671806 1.525358 -v 0.010050 -0.070641 0.090605 -vn 3.559834 1.471351 1.653948 -v 0.010050 -0.069645 0.089609 -vn 3.122624 1.012590 1.837843 -v 0.010050 -0.069091 0.089265 -vn 3.440161 0.562336 2.141076 -v 0.010050 -0.068391 0.088970 -vn 3.403966 -0.094245 2.193518 -v 0.010050 -0.067000 0.088750 -vn 3.651871 -0.458744 2.144396 -v 0.010050 -0.065609 0.088970 -vn -3.665198 -0.000002 -3.034543 -v -0.019450 -0.075750 0.129500 -vn -3.665181 -1.517271 -2.627999 -v -0.019450 -0.077250 0.129902 -vn -3.665199 -2.627986 -1.517279 -v -0.019450 -0.078348 0.131000 -vn -3.665187 -3.034546 -0.000004 -v -0.019450 -0.078750 0.132500 -vn -3.665201 -2.627987 1.517276 -v -0.019450 -0.078348 0.134000 -vn -3.665181 -1.517271 2.627999 -v -0.019450 -0.077250 0.135098 -vn -3.665198 -0.000002 3.034542 -v -0.019450 -0.075750 0.135500 -vn -3.665185 1.517273 2.627996 -v -0.019450 -0.074250 0.135098 -vn -3.665198 2.627991 1.517271 -v -0.019450 -0.073152 0.134000 -vn -3.665188 3.034547 -0.000004 -v -0.019450 -0.072750 0.132500 -vn -3.665195 2.627990 -1.517275 -v -0.019450 -0.073152 0.131000 -vn -3.665185 1.517273 -2.627996 -v -0.019450 -0.074250 0.129902 -vn -3.665198 0.000001 -3.034542 -v -0.019450 -0.058250 0.129500 -vn -3.665185 -1.517273 -2.627996 -v -0.019450 -0.059750 0.129902 -vn -3.665193 -2.627989 -1.517279 -v -0.019450 -0.060848 0.131000 -vn -3.665192 -3.034544 -0.000004 -v -0.019450 -0.061250 0.132500 -vn -3.665196 -2.627990 1.517275 -v -0.019450 -0.060848 0.134000 -vn -3.665185 -1.517273 2.627996 -v -0.019450 -0.059750 0.135098 -vn -3.665197 0.000001 3.034544 -v -0.019450 -0.058250 0.135500 -vn -3.665184 1.517274 2.627995 -v -0.019450 -0.056750 0.135098 -vn -3.665196 2.627990 1.517275 -v -0.019450 -0.055652 0.134000 -vn -3.665193 3.034545 -0.000004 -v -0.019450 -0.055250 0.132500 -vn -3.665193 2.627988 -1.517279 -v -0.019450 -0.055652 0.131000 -vn -3.665184 1.517274 -2.627995 -v -0.019450 -0.056750 0.129902 -vn 0.973294 5.955419 -1.121582 -v 0.009050 -0.061638 0.092026 -vn 0.805402 6.064977 0.051957 -v 0.009050 -0.061500 0.093250 -vn 2.918293 5.124943 0.053191 -v 0.009550 -0.061634 0.093250 -vn 0.890583 4.522738 4.077587 -v 0.009050 -0.062700 0.096679 -vn 0.825910 3.606369 4.865129 -v 0.009050 -0.063767 0.097700 -vn 2.897777 2.991055 4.164500 -v 0.009550 -0.063846 0.097591 -vn 2.876337 0.000001 5.128851 -v 0.009550 -0.067000 0.098616 -vn 2.946597 1.519244 4.887517 -v 0.009550 -0.065342 0.098353 -vn 0.770861 1.618742 5.863230 -v 0.009050 -0.065300 0.098481 -vn 2.946569 -1.519229 -4.887506 -v 0.009550 -0.068658 0.088147 -vn 2.897744 -2.991069 -4.164517 -v 0.009550 -0.070154 0.088909 -vn 0.825895 -3.606385 -4.865134 -v 0.009050 -0.070233 0.088800 -vn 2.952078 -4.845934 -1.640521 -v 0.009550 -0.072103 0.091592 -vn 0.764987 -5.677380 -2.215279 -v 0.009050 -0.072231 0.091550 -vn 2.946806 -4.175583 -2.959135 -v 0.009550 -0.071341 0.090096 -vn 0.775796 -5.175826 -3.240810 -v 0.009050 -0.071450 0.090017 -vn 0.890544 -4.522773 -4.077547 -v 0.009050 -0.071300 0.089821 -vn 0.759012 -5.181965 3.228045 -v 0.009050 -0.071450 0.096483 -vn 0.746377 -5.670407 2.228057 -v 0.009050 -0.072231 0.094950 -vn 2.960875 -4.839340 1.662798 -v 0.009550 -0.072103 0.094908 -vn 0.973287 -5.955416 1.121590 -v 0.009050 -0.072362 0.094474 -vn 2.918318 -5.124943 -0.053189 -v 0.009550 -0.072366 0.093250 -vn 0.805418 -6.064972 -0.051955 -v 0.009050 -0.072500 0.093250 -vn 1.086398 -5.921326 -1.038449 -v 0.009050 -0.072362 0.092026 -vn 0.890566 -4.522770 4.077539 -v 0.009050 -0.071300 0.096679 -vn 2.946832 -4.175584 2.959128 -v 0.009550 -0.071341 0.096404 -vn 2.958745 -3.046773 4.115580 -v 0.009550 -0.070154 0.097591 -vn 0.783043 -0.000002 6.025215 -v 0.009050 -0.067000 0.098750 -vn 0.770851 -1.618731 5.863238 -v 0.009050 -0.068700 0.098481 -vn 2.953083 -1.499247 4.895129 -v 0.009550 -0.068658 0.098353 -vn 1.018960 -2.692673 5.409676 -v 0.009050 -0.069386 0.098205 -vn 0.767945 -3.684490 4.839321 -v 0.009050 -0.070233 0.097700 -vn 1.250783 2.748372 5.260651 -v 0.009050 -0.064614 0.098205 -vn 2.952114 4.845942 1.640521 -v 0.009550 -0.061897 0.094908 -vn 0.765036 5.677365 2.215253 -v 0.009050 -0.061769 0.094950 -vn 2.946856 4.175574 2.959134 -v 0.009550 -0.062659 0.096404 -vn 0.775847 5.175762 3.240855 -v 0.009050 -0.062550 0.096483 -vn 1.086428 5.921320 1.038429 -v 0.009050 -0.061638 0.094474 -vn 0.746398 5.670405 -2.228030 -v 0.009050 -0.061769 0.091550 -vn 2.960891 4.839339 -1.662807 -v 0.009550 -0.061897 0.091592 -vn 0.759021 5.181913 -3.228094 -v 0.009050 -0.062550 0.090017 -vn 2.946832 4.175569 -2.959144 -v 0.009550 -0.062659 0.090096 -vn 0.890561 4.522741 -4.077595 -v 0.009050 -0.062700 0.089821 -vn 2.958754 3.046790 -4.115586 -v 0.009550 -0.063846 0.088909 -vn 0.767969 3.684502 -4.839301 -v 0.009050 -0.063767 0.088800 -vn 1.018967 2.692670 -5.409668 -v 0.009050 -0.064614 0.088295 -vn 1.250796 -2.748370 -5.260626 -v 0.009050 -0.069386 0.088295 -vn 0.770818 -1.618704 -5.863264 -v 0.009050 -0.068700 0.088019 -vn 2.876339 -0.000004 -5.128855 -v 0.009550 -0.067000 0.087884 -vn 0.783040 -0.000006 -6.025217 -v 0.009050 -0.067000 0.087750 -vn 2.953074 1.499226 -4.895118 -v 0.009550 -0.065342 0.088147 -vn 0.770824 1.618720 -5.863255 -v 0.009050 -0.065300 0.088019 -vn 5.100276 -2.509943 -1.831357 -v 0.009916 -0.071045 0.090311 -vn 5.102020 -2.949342 -0.955141 -v 0.009916 -0.071755 0.091705 -vn 5.098811 -3.112944 0.011315 -v 0.009916 -0.072000 0.093250 -vn 5.098896 -2.963876 0.951182 -v 0.009916 -0.071755 0.094795 -vn 5.101393 -2.506821 1.828568 -v 0.009916 -0.071045 0.096189 -vn 5.098726 -1.821169 2.524957 -v 0.009916 -0.069939 0.097295 -vn 5.098229 -0.976622 2.958513 -v 0.009916 -0.068545 0.098005 -vn 5.100777 0.008587 3.105502 -v 0.009916 -0.067000 0.098250 -vn 5.098894 0.970664 2.957120 -v 0.009916 -0.065455 0.098005 -vn 5.098103 1.818461 2.530707 -v 0.009916 -0.064061 0.097295 -vn 5.100184 2.520963 1.817894 -v 0.009916 -0.062955 0.096189 -vn 5.099516 2.959760 0.954373 -v 0.009916 -0.062245 0.094795 -vn 5.098257 3.115727 0.016832 -v 0.009916 -0.062000 0.093250 -vn 5.099610 2.954072 -0.973794 -v 0.009916 -0.062245 0.091705 -vn 5.100719 2.509823 -1.828066 -v 0.009916 -0.062955 0.090311 -vn 5.099069 -1.838169 -2.511078 -v 0.009916 -0.069939 0.089205 -vn 5.102629 -0.957146 -2.945789 -v 0.009916 -0.068545 0.088495 -vn 5.102626 0.000001 -3.097389 -v 0.009916 -0.067000 0.088250 -vn 5.099079 0.947497 -2.964889 -v 0.009916 -0.065455 0.088495 -vn 5.098594 1.843819 -2.510023 -v 0.009916 -0.064061 0.089205 -vn 3.383252 0.000000 3.118687 -v 0.007550 -0.067000 0.075250 -vn 3.383255 -0.746350 3.028063 -v 0.007550 -0.062692 0.075773 -vn 3.383254 -1.449327 2.761460 -v 0.007550 -0.058635 0.077312 -vn 3.383253 -2.068072 2.334371 -v 0.007550 -0.055064 0.079777 -vn 3.383254 -2.566629 1.771616 -v 0.007550 -0.052186 0.083025 -vn 3.383252 -2.916023 1.105901 -v 0.007550 -0.050170 0.086867 -vn 3.383254 -3.095948 0.375916 -v 0.007550 -0.049131 0.091080 -vn 3.383253 -3.095948 -0.375915 -v 0.007550 -0.049131 0.095420 -vn 3.383253 -2.916023 -1.105900 -v 0.007550 -0.050170 0.099633 -vn 3.383254 -2.566629 -1.771616 -v 0.007550 -0.052186 0.103475 -vn 3.383254 -2.068070 -2.334372 -v 0.007550 -0.055064 0.106723 -vn 3.383254 -1.449325 -2.761461 -v 0.007550 -0.058635 0.109188 -vn 3.383253 -0.746350 -3.028064 -v 0.007550 -0.062692 0.110727 -vn 3.383252 -0.000000 -3.118687 -v 0.007550 -0.067000 0.111250 -vn 3.383255 0.746351 -3.028064 -v 0.007550 -0.071308 0.110727 -vn 3.383252 1.449326 -2.761461 -v 0.007550 -0.075365 0.109188 -vn 3.383254 2.068070 -2.334372 -v 0.007550 -0.078936 0.106723 -vn 3.383255 2.566629 -1.771616 -v 0.007550 -0.081814 0.103475 -vn 3.383253 2.916023 -1.105902 -v 0.007550 -0.083830 0.099633 -vn 3.383254 3.095948 -0.375917 -v 0.007550 -0.084869 0.095420 -vn 3.383255 3.095948 0.375917 -v 0.007550 -0.084869 0.091080 -vn 3.383252 2.916023 1.105902 -v 0.007550 -0.083830 0.086867 -vn 3.383255 2.566629 1.771616 -v 0.007550 -0.081814 0.083025 -vn 3.383252 2.068072 2.334371 -v 0.007550 -0.078936 0.079777 -vn 3.383254 1.449328 2.761460 -v 0.007550 -0.075365 0.077312 -vn 3.383255 0.746351 3.028063 -v 0.007550 -0.071308 0.075773 -vn 2.899930 2.566629 1.771617 -v 0.007550 -0.051775 0.103759 -vn 2.899933 2.068071 2.334372 -v 0.007550 -0.054732 0.107097 -vn 2.899932 1.449327 2.761459 -v 0.007550 -0.058403 0.109631 -vn 2.899930 0.746351 3.028063 -v 0.007550 -0.062573 0.111212 -vn 2.899933 -0.000000 3.118687 -v 0.007550 -0.067000 0.111750 -vn 2.899930 -0.746351 3.028063 -v 0.007550 -0.071427 0.111212 -vn 2.899932 -1.449327 2.761461 -v 0.007550 -0.075597 0.109631 -vn 2.899932 -2.068071 2.334372 -v 0.007550 -0.079268 0.107097 -vn 2.899930 -2.566629 1.771616 -v 0.007550 -0.082225 0.103759 -vn 2.899934 -2.916024 1.105902 -v 0.007550 -0.084298 0.099810 -vn 2.899931 -3.095948 0.375918 -v 0.007550 -0.085365 0.095480 -vn 2.899930 -3.095948 -0.375918 -v 0.007550 -0.085365 0.091020 -vn 2.899933 -2.916023 -1.105903 -v 0.007550 -0.084298 0.086690 -vn 2.899931 -2.566630 -1.771616 -v 0.007550 -0.082225 0.082741 -vn 2.899931 -2.068072 -2.334371 -v 0.007550 -0.079268 0.079403 -vn 2.899932 -1.449324 -2.761461 -v 0.007550 -0.075597 0.076869 -vn 2.899933 -0.746351 -3.028064 -v 0.007550 -0.071427 0.075288 -vn 2.899930 -0.000000 -3.118686 -v 0.007550 -0.067000 0.074750 -vn 2.899934 0.746351 -3.028064 -v 0.007550 -0.062573 0.075288 -vn 2.899931 1.449325 -2.761461 -v 0.007550 -0.058403 0.076869 -vn 2.899932 2.068073 -2.334371 -v 0.007550 -0.054732 0.079403 -vn 2.899933 2.566629 -1.771616 -v 0.007550 -0.051775 0.082741 -vn 2.899930 2.916023 -1.105901 -v 0.007550 -0.049702 0.086690 -vn 2.899932 3.095948 -0.375915 -v 0.007550 -0.048635 0.091020 -vn 2.899933 3.095949 0.375915 -v 0.007550 -0.048635 0.095480 -vn 2.899932 2.916024 1.105901 -v 0.007550 -0.049702 0.099810 -vn -1.570796 -4.712389 1.570796 -v -0.070450 -0.086000 0.131750 -vn 1.570796 -4.712389 1.570796 -v -0.046450 -0.086000 0.131750 -vn -1.570796 -1.570796 1.570796 -v -0.070450 -0.086000 0.135750 -vn 1.570796 -1.570796 1.570796 -v -0.046450 -0.086000 0.135750 -vn 3.088069 0.406551 3.403391 -v -0.046450 -0.051500 0.135750 -vn 1.570796 1.570796 1.570796 -v -0.046450 -0.048000 0.135750 -vn -1.517278 -2.627992 3.665185 -v -0.072200 -0.079469 0.135750 -vn -1.570796 1.570796 1.570796 -v -0.070450 -0.048000 0.135750 -vn -3.088069 0.406551 3.403391 -v -0.070450 -0.051500 0.135750 -vn -2.627994 1.517272 3.665192 -v -0.070919 -0.053250 0.135750 -vn -0.406551 3.088069 3.403391 -v -0.073950 -0.055000 0.135750 -vn -3.088069 -0.406551 3.403391 -v -0.070450 -0.082500 0.135750 -vn 2.627994 1.517272 3.665193 -v -0.045981 -0.053250 0.135750 -vn 2.627994 -1.517272 3.665193 -v -0.045981 -0.080750 0.135750 -vn 1.517278 -2.627992 3.665189 -v -0.044700 -0.079469 0.135750 -vn -1.517272 2.627994 3.665192 -v -0.072200 -0.054531 0.135750 -vn -0.406557 -3.088068 3.403395 -v -0.073950 -0.079000 0.135750 -vn -2.627994 -1.517272 3.665192 -v -0.070919 -0.080750 0.135750 -vn 3.088069 -0.406551 3.403391 -v -0.046450 -0.082500 0.135750 -vn 0.406557 -3.088068 3.403395 -v -0.042950 -0.079000 0.135750 -vn 0.406551 3.088069 3.403391 -v -0.042950 -0.055000 0.135750 -vn 1.517272 2.627994 3.665192 -v -0.044700 -0.054531 0.135750 -vn 1.570796 4.712389 1.570796 -v -0.046450 -0.048000 0.131750 -vn -1.570796 4.712389 1.570796 -v -0.070450 -0.048000 0.131750 -vn -0.406557 -3.088068 2.879790 -v -0.073950 -0.079000 0.131750 -vn -3.088069 -0.406551 2.879794 -v -0.070450 -0.082500 0.131750 -vn -1.517278 -2.627992 2.617997 -v -0.072200 -0.079469 0.131750 -vn -2.627994 -1.517272 2.617993 -v -0.070919 -0.080750 0.131750 -vn 3.088069 -0.406551 2.879794 -v -0.046450 -0.082500 0.131750 -vn 2.627994 -1.517272 2.617993 -v -0.045981 -0.080750 0.131750 -vn 1.517278 -2.627992 2.617997 -v -0.044700 -0.079469 0.131750 -vn 0.406557 -3.088068 2.879790 -v -0.042950 -0.079000 0.131750 -vn 0.406551 3.088069 2.879794 -v -0.042950 -0.055000 0.131750 -vn 3.088069 0.406551 2.879794 -v -0.046450 -0.051500 0.131750 -vn 2.627994 1.517272 2.617993 -v -0.045981 -0.053250 0.131750 -vn 1.517272 2.627994 2.617993 -v -0.044700 -0.054531 0.131750 -vn -3.088069 0.406551 2.879794 -v -0.070450 -0.051500 0.131750 -vn -2.627994 1.517272 2.617993 -v -0.070919 -0.053250 0.131750 -vn -1.517272 2.627994 2.617993 -v -0.072200 -0.054531 0.131750 -vn -0.406551 3.088069 2.879794 -v -0.073950 -0.055000 0.131750 -vn 1.570796 1.570796 -1.570796 -v 0.013550 -0.079000 0.091250 -vn 1.570796 -1.570796 -1.570796 -v 0.013550 -0.080000 0.091250 -vn 1.570796 1.570796 1.570796 -v 0.013550 -0.079000 0.095250 -vn 1.570796 -1.570796 1.570796 -v 0.013550 -0.080000 0.095250 -vn 1.570796 -1.570796 1.570796 -v 0.013550 -0.055000 0.095250 -vn 1.570796 1.570796 1.570796 -v 0.013550 -0.054000 0.095250 -vn 1.570796 -1.570796 -1.570796 -v 0.013550 -0.055000 0.091250 -vn 1.570796 1.570796 -1.570796 -v 0.013550 -0.054000 0.091250 -vn 2.617996 1.517275 2.627993 -v 0.013050 -0.066250 0.094549 -vn 2.617996 2.627993 1.517275 -v 0.013050 -0.065701 0.094000 -vn 2.617989 3.034544 -0.000004 -v 0.013050 -0.065500 0.093250 -vn 2.618005 2.628000 -1.517271 -v 0.013050 -0.065701 0.092500 -vn 2.617979 1.517268 -2.627989 -v 0.013050 -0.066250 0.091951 -vn 2.618007 -0.000004 -3.034551 -v 0.013050 -0.067000 0.091750 -vn 2.617989 -1.517265 -2.627995 -v 0.013050 -0.067750 0.091951 -vn 2.617989 -2.627996 -1.517265 -v 0.013050 -0.068299 0.092500 -vn 2.618007 -3.034551 -0.000004 -v 0.013050 -0.068500 0.093250 -vn 2.617979 -2.627989 1.517269 -v 0.013050 -0.068299 0.094000 -vn 2.618005 -1.517271 2.627999 -v 0.013050 -0.067750 0.094549 -vn 2.617989 -0.000004 3.034544 -v 0.013050 -0.067000 0.094750 -vn 6.283185 0.000000 0.000000 -v 0.013050 -0.067000 0.093250 -# 1046 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 4//4 2//2 5//5 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 10//10 11//11 12//12 -f 12//12 11//11 13//13 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 14//14 15//15 16//16 -f 10//10 17//17 11//11 -f 11//11 17//17 18//18 -f 11//11 18//18 19//19 -f 20//20 21//21 22//22 -f 7//7 9//9 23//23 -f 23//23 9//9 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 5//5 -f 5//5 26//26 27//27 -f 5//5 27//27 6//6 -f 22//22 28//28 20//20 -f 20//20 28//28 29//29 -f 20//20 29//29 7//7 -f 7//7 29//29 30//30 -f 7//7 30//30 8//8 -f 31//31 32//32 33//33 -f 32//32 34//34 33//33 -f 33//33 34//34 35//35 -f 33//33 35//35 15//15 -f 15//15 35//35 36//36 -f 15//15 36//36 16//16 -f 5//5 37//37 25//25 -f 25//25 37//37 38//38 -f 25//25 38//38 20//20 -f 31//31 33//33 3//3 -f 3//3 33//33 39//39 -f 3//3 39//39 1//1 -f 38//38 40//40 20//20 -f 20//20 40//40 41//41 -f 20//20 41//41 21//21 -f 21//21 41//41 42//42 -f 21//21 42//42 43//43 -f 43//43 44//44 21//21 -f 21//21 44//44 11//11 -f 21//21 11//11 45//45 -f 45//45 11//11 19//19 -f 44//44 46//46 11//11 -f 11//11 46//46 47//47 -f 11//11 47//47 33//33 -f 33//33 47//47 48//48 -f 33//33 48//48 39//39 -f 49//49 50//50 51//51 -f 52//52 53//53 54//54 -f 55//55 56//56 54//54 -f 54//54 56//56 49//49 -f 54//54 49//49 52//52 -f 52//52 49//49 51//51 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 61//61 60//60 62//62 -f 62//62 60//60 58//58 -f 62//62 58//58 63//63 -f 63//63 58//58 64//64 -f 65//65 66//66 67//67 -f 59//59 68//68 69//69 -f 68//68 59//59 70//70 -f 70//70 59//59 60//60 -f 70//70 60//60 67//67 -f 67//67 60//60 71//71 -f 67//67 71//71 65//65 -f 69//69 72//72 59//59 -f 59//59 72//72 73//73 -f 59//59 73//73 74//74 -f 51//51 75//75 76//76 -f 77//77 78//78 79//79 -f 52//52 80//80 81//81 -f 77//77 79//79 81//81 -f 81//81 79//79 82//82 -f 81//81 82//82 52//52 -f 83//83 84//84 85//85 -f 86//86 83//83 51//51 -f 51//51 83//83 85//85 -f 51//51 85//85 52//52 -f 52//52 85//85 87//87 -f 52//52 87//87 80//80 -f 88//88 89//89 90//90 -f 90//90 89//89 91//91 -f 90//90 91//91 84//84 -f 84//84 91//91 92//92 -f 84//84 92//92 85//85 -f 77//77 93//93 78//78 -f 78//78 93//93 94//94 -f 78//78 94//94 95//95 -f 96//96 97//97 98//98 -f 98//98 97//97 78//78 -f 98//98 78//78 99//99 -f 99//99 78//78 95//95 -f 99//99 95//95 88//88 -f 88//88 95//95 100//100 -f 88//88 100//100 89//89 -f 96//96 101//101 97//97 -f 97//97 101//101 102//102 -f 97//97 102//102 76//76 -f 76//76 102//102 103//103 -f 76//76 103//103 51//51 -f 51//51 103//103 104//104 -f 51//51 104//104 86//86 -f 105//105 106//106 53//53 -f 53//53 106//106 54//54 -f 107//107 108//108 109//109 -f 110//110 111//111 56//56 -f 56//56 111//111 112//112 -f 113//113 114//114 115//115 -f 116//116 117//117 115//115 -f 115//115 117//117 118//118 -f 115//115 118//118 113//113 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 126//126 124//124 127//127 -f 126//126 127//127 109//109 -f 109//109 127//127 128//128 -f 109//109 128//128 107//107 -f 129//129 130//130 55//55 -f 55//55 130//130 131//131 -f 55//55 131//131 56//56 -f 56//56 131//131 132//132 -f 56//56 132//132 110//110 -f 107//107 133//133 108//108 -f 108//108 133//133 134//134 -f 108//108 134//134 135//135 -f 135//135 134//134 114//114 -f 135//135 114//114 136//136 -f 136//136 114//114 113//113 -f 111//111 137//137 112//112 -f 112//112 137//137 138//138 -f 112//112 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 119//119 -f 119//119 140//140 141//141 -f 119//119 141//141 120//120 -f 116//116 142//142 117//117 -f 117//117 142//142 143//143 -f 117//117 143//143 105//105 -f 105//105 143//143 144//144 -f 105//105 144//144 106//106 -f 106//106 144//144 145//145 -f 106//106 145//145 55//55 -f 55//55 145//145 146//146 -f 55//55 146//146 129//129 -f 147//147 148//148 149//149 -f 149//149 148//148 150//150 -f 149//149 150//150 151//151 -f 152//152 153//153 149//149 -f 149//149 153//153 154//154 -f 149//149 154//154 147//147 -f 155//155 156//156 149//149 -f 149//149 156//156 157//157 -f 149//149 157//157 152//152 -f 151//151 158//158 149//149 -f 149//149 158//158 159//159 -f 149//149 159//159 155//155 -f 160//160 161//161 162//162 -f 162//162 161//161 163//163 -f 162//162 163//163 164//164 -f 165//165 166//166 162//162 -f 162//162 166//166 167//167 -f 162//162 167//167 160//160 -f 168//168 169//169 162//162 -f 162//162 169//169 170//170 -f 162//162 170//170 165//165 -f 164//164 171//171 162//162 -f 162//162 171//171 172//172 -f 162//162 172//172 168//168 -f 150//150 173//173 151//151 -f 151//151 173//173 174//174 -f 151//151 174//174 158//158 -f 158//158 174//174 175//175 -f 158//158 175//175 159//159 -f 159//159 175//175 176//176 -f 159//159 176//176 155//155 -f 155//155 176//176 177//177 -f 155//155 177//177 156//156 -f 156//156 177//177 178//178 -f 156//156 178//178 157//157 -f 157//157 178//178 179//179 -f 157//157 179//179 152//152 -f 152//152 179//179 180//180 -f 152//152 180//180 153//153 -f 153//153 180//180 181//181 -f 153//153 181//181 154//154 -f 154//154 181//181 182//182 -f 154//154 182//182 147//147 -f 147//147 182//182 183//183 -f 147//147 183//183 148//148 -f 148//148 183//183 184//184 -f 148//148 184//184 150//150 -f 150//150 184//184 173//173 -f 163//163 185//185 164//164 -f 164//164 185//185 186//186 -f 164//164 186//186 171//171 -f 171//171 186//186 187//187 -f 171//171 187//187 172//172 -f 172//172 187//187 188//188 -f 172//172 188//188 168//168 -f 168//168 188//188 189//189 -f 168//168 189//189 169//169 -f 169//169 189//189 190//190 -f 169//169 190//190 170//170 -f 170//170 190//190 191//191 -f 170//170 191//191 165//165 -f 165//165 191//191 192//192 -f 165//165 192//192 166//166 -f 166//166 192//192 193//193 -f 166//166 193//193 167//167 -f 167//167 193//193 194//194 -f 167//167 194//194 160//160 -f 160//160 194//194 195//195 -f 160//160 195//195 161//161 -f 161//161 195//195 196//196 -f 161//161 196//196 163//163 -f 163//163 196//196 185//185 -f 183//183 197//197 184//184 -f 184//184 197//197 198//198 -f 184//184 198//198 173//173 -f 173//173 198//198 199//199 -f 173//173 199//199 174//174 -f 174//174 199//199 200//200 -f 174//174 200//200 175//175 -f 175//175 200//200 201//201 -f 175//175 201//201 176//176 -f 176//176 201//201 202//202 -f 176//176 202//202 177//177 -f 177//177 202//202 203//203 -f 177//177 203//203 178//178 -f 178//178 203//203 204//204 -f 178//178 204//204 179//179 -f 179//179 204//204 205//205 -f 179//179 205//205 180//180 -f 180//180 205//205 206//206 -f 180//180 206//206 181//181 -f 181//181 206//206 207//207 -f 181//181 207//207 182//182 -f 182//182 207//207 208//208 -f 182//182 208//208 183//183 -f 183//183 208//208 197//197 -f 196//196 209//209 185//185 -f 185//185 209//209 210//210 -f 194//194 211//211 195//195 -f 195//195 211//211 212//212 -f 195//195 212//212 196//196 -f 196//196 212//212 213//213 -f 196//196 213//213 209//209 -f 193//193 214//214 194//194 -f 194//194 214//214 215//215 -f 194//194 215//215 211//211 -f 192//192 216//216 193//193 -f 193//193 216//216 217//217 -f 193//193 217//217 214//214 -f 191//191 218//218 192//192 -f 192//192 218//218 219//219 -f 192//192 219//219 216//216 -f 190//190 220//220 191//191 -f 191//191 220//220 221//221 -f 191//191 221//221 218//218 -f 189//189 222//222 190//190 -f 190//190 222//222 223//223 -f 190//190 223//223 220//220 -f 188//188 224//224 189//189 -f 189//189 224//224 225//225 -f 189//189 225//225 222//222 -f 187//187 226//226 188//188 -f 188//188 226//226 227//227 -f 188//188 227//227 224//224 -f 186//186 228//228 187//187 -f 187//187 228//228 229//229 -f 187//187 229//229 226//226 -f 210//210 230//230 185//185 -f 185//185 230//230 231//231 -f 185//185 231//231 186//186 -f 186//186 231//231 232//232 -f 186//186 232//232 228//228 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 237//237 -f 237//237 236//236 238//238 -f 237//237 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 241//241 -f 241//241 240//240 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 249//249 -f 249//249 248//248 250//250 -f 249//249 250//250 251//251 -f 251//251 250//250 252//252 -f 251//251 252//252 253//253 -f 253//253 252//252 254//254 -f 253//253 254//254 255//255 -f 255//255 254//254 256//256 -f 255//255 256//256 233//233 -f 233//233 256//256 257//257 -f 233//233 257//257 234//234 -f 258//258 204//204 259//259 -f 259//259 204//204 203//203 -f 259//259 203//203 260//260 -f 260//260 203//203 202//202 -f 260//260 202//202 261//261 -f 261//261 202//202 201//201 -f 261//261 201//201 262//262 -f 262//262 201//201 200//200 -f 262//262 200//200 263//263 -f 263//263 200//200 199//199 -f 263//263 199//199 264//264 -f 264//264 199//199 198//198 -f 264//264 198//198 265//265 -f 265//265 198//198 197//197 -f 265//265 197//197 266//266 -f 266//266 197//197 208//208 -f 266//266 208//208 267//267 -f 267//267 208//208 207//207 -f 267//267 207//207 268//268 -f 268//268 207//207 206//206 -f 268//268 206//206 269//269 -f 269//269 206//206 205//205 -f 269//269 205//205 258//258 -f 258//258 205//205 204//204 -f 270//270 271//271 214//214 -f 219//219 272//272 216//216 -f 216//216 272//272 270//270 -f 216//216 270//270 217//217 -f 217//217 270//270 214//214 -f 273//273 274//274 213//213 -f 213//213 212//212 273//273 -f 273//273 212//212 211//211 -f 273//273 211//211 271//271 -f 271//271 211//211 215//215 -f 271//271 215//215 214//214 -f 275//275 230//230 276//276 -f 276//276 230//230 210//210 -f 276//276 210//210 274//274 -f 274//274 210//210 209//209 -f 274//274 209//209 213//213 -f 277//277 232//232 275//275 -f 275//275 232//232 231//231 -f 275//275 231//231 230//230 -f 278//278 229//229 277//277 -f 277//277 229//229 228//228 -f 277//277 228//228 232//232 -f 279//279 227//227 278//278 -f 278//278 227//227 226//226 -f 278//278 226//226 229//229 -f 280//280 225//225 279//279 -f 279//279 225//225 224//224 -f 279//279 224//224 227//227 -f 219//219 218//218 272//272 -f 272//272 218//218 221//221 -f 272//272 221//221 281//281 -f 281//281 221//221 220//220 -f 281//281 220//220 282//282 -f 282//282 220//220 223//223 -f 282//282 223//223 280//280 -f 280//280 223//223 222//222 -f 280//280 222//222 225//225 -f 248//248 283//283 284//284 -f 248//248 284//284 250//250 -f 284//284 285//285 250//250 -f 250//250 285//285 286//286 -f 250//250 286//286 252//252 -f 252//252 286//286 287//287 -f 252//252 287//287 288//288 -f 288//288 289//289 252//252 -f 252//252 289//289 290//290 -f 252//252 290//290 254//254 -f 254//254 290//290 291//291 -f 254//254 291//291 256//256 -f 256//256 291//291 292//292 -f 256//256 292//292 293//293 -f 293//293 294//294 256//256 -f 256//256 294//294 295//295 -f 256//256 295//295 257//257 -f 257//257 295//295 296//296 -f 257//257 296//296 234//234 -f 234//234 296//296 297//297 -f 234//234 297//297 298//298 -f 298//298 299//299 234//234 -f 234//234 299//299 300//300 -f 234//234 300//300 236//236 -f 301//301 238//238 302//302 -f 302//302 238//238 236//236 -f 302//302 236//236 303//303 -f 303//303 236//236 300//300 -f 301//301 304//304 238//238 -f 238//238 304//304 305//305 -f 238//238 305//305 240//240 -f 305//305 306//306 240//240 -f 240//240 306//306 307//307 -f 240//240 307//307 242//242 -f 307//307 308//308 242//242 -f 242//242 308//308 309//309 -f 242//242 309//309 244//244 -f 244//244 309//309 310//310 -f 310//310 311//311 244//244 -f 244//244 311//311 312//312 -f 244//244 312//312 246//246 -f 246//246 312//312 313//313 -f 246//246 313//313 248//248 -f 248//248 313//313 314//314 -f 248//248 314//314 283//283 -f 315//315 264//264 316//316 -f 316//316 264//264 265//265 -f 316//316 265//265 317//317 -f 317//317 265//265 266//266 -f 317//317 266//266 318//318 -f 318//318 266//266 267//267 -f 318//318 267//267 319//319 -f 319//319 267//267 268//268 -f 319//319 268//268 320//320 -f 320//320 268//268 269//269 -f 320//320 269//269 321//321 -f 321//321 269//269 258//258 -f 321//321 258//258 322//322 -f 322//322 258//258 259//259 -f 322//322 259//259 323//323 -f 323//323 259//259 260//260 -f 323//323 260//260 324//324 -f 324//324 260//260 261//261 -f 324//324 261//261 325//325 -f 325//325 261//261 262//262 -f 325//325 262//262 326//326 -f 326//326 262//262 263//263 -f 326//326 263//263 315//315 -f 315//315 263//263 264//264 -f 327//327 276//276 328//328 -f 328//328 276//276 274//274 -f 328//328 274//274 329//329 -f 329//329 274//274 273//273 -f 329//329 273//273 330//330 -f 330//330 273//273 271//271 -f 330//330 271//271 331//331 -f 331//331 271//271 270//270 -f 331//331 270//270 332//332 -f 332//332 270//270 272//272 -f 332//332 272//272 333//333 -f 333//333 272//272 281//281 -f 333//333 281//281 334//334 -f 334//334 281//281 282//282 -f 334//334 282//282 335//335 -f 335//335 282//282 280//280 -f 335//335 280//280 336//336 -f 336//336 280//280 279//279 -f 336//336 279//279 337//337 -f 337//337 279//279 278//278 -f 337//337 278//278 338//338 -f 338//338 278//278 277//277 -f 338//338 277//277 327//327 -f 327//327 277//277 275//275 -f 327//327 275//275 276//276 -f 339//339 340//340 341//341 -f 342//342 343//343 344//344 -f 345//345 346//346 347//347 -f 348//348 349//349 350//350 -f 351//351 352//352 353//353 -f 353//353 352//352 354//354 -f 353//353 354//354 355//355 -f 356//356 357//357 358//358 -f 358//358 357//357 359//359 -f 358//358 359//359 360//360 -f 360//360 359//359 361//361 -f 360//360 361//361 351//351 -f 351//351 361//361 362//362 -f 351//351 362//362 352//352 -f 363//363 364//364 365//365 -f 366//366 367//367 368//368 -f 368//368 367//367 369//369 -f 368//368 369//369 365//365 -f 365//365 369//369 370//370 -f 365//365 370//370 363//363 -f 344//344 343//343 346//346 -f 346//346 343//343 371//371 -f 346//346 371//371 347//347 -f 372//372 373//373 374//374 -f 374//374 373//373 375//375 -f 341//341 340//340 372//372 -f 372//372 340//340 376//376 -f 372//372 376//376 373//373 -f 377//377 378//378 379//379 -f 379//379 378//378 380//380 -f 379//379 380//380 381//381 -f 381//381 380//380 382//382 -f 381//381 382//382 383//383 -f 383//383 382//382 384//384 -f 350//350 385//385 348//348 -f 348//348 385//385 386//386 -f 348//348 386//386 387//387 -f 387//387 386//386 388//388 -f 387//387 388//388 389//389 -f 389//389 388//388 390//390 -f 353//353 391//391 351//351 -f 351//351 391//391 392//392 -f 351//351 392//392 360//360 -f 360//360 392//392 393//393 -f 360//360 393//393 358//358 -f 394//394 395//395 364//364 -f 364//364 395//395 365//365 -f 365//365 395//395 396//396 -f 365//365 396//396 368//368 -f 397//397 398//398 345//345 -f 345//345 398//398 346//346 -f 346//346 398//398 399//399 -f 346//346 399//399 344//344 -f 400//400 401//401 374//374 -f 374//374 401//401 372//372 -f 372//372 401//401 402//402 -f 372//372 402//402 341//341 -f 403//403 404//404 378//378 -f 378//378 404//404 380//380 -f 380//380 404//404 405//405 -f 380//380 405//405 382//382 -f 406//406 349//349 407//407 -f 407//407 349//349 348//348 -f 407//407 348//348 408//408 -f 408//408 348//348 387//387 -f 408//408 387//387 409//409 -f 409//409 387//387 389//389 -f 409//409 389//389 410//410 -f 310//310 391//391 406//406 -f 406//406 391//391 353//353 -f 406//406 353//353 349//349 -f 349//349 353//353 355//355 -f 349//349 355//355 350//350 -f 310//310 309//309 391//391 -f 391//391 309//309 308//308 -f 391//391 308//308 392//392 -f 392//392 308//308 307//307 -f 392//392 307//307 393//393 -f 393//393 307//307 306//306 -f 306//306 305//305 393//393 -f 393//393 305//305 394//394 -f 393//393 394//394 358//358 -f 358//358 394//394 364//364 -f 358//358 364//364 356//356 -f 356//356 364//364 363//363 -f 305//305 304//304 394//394 -f 394//394 304//304 301//301 -f 394//394 301//301 395//395 -f 395//395 301//301 302//302 -f 395//395 302//302 396//396 -f 396//396 302//302 303//303 -f 303//303 300//300 396//396 -f 396//396 300//300 397//397 -f 396//396 397//397 368//368 -f 368//368 397//397 345//345 -f 368//368 345//345 366//366 -f 366//366 345//345 347//347 -f 300//300 299//299 397//397 -f 397//397 299//299 298//298 -f 397//397 298//298 398//398 -f 398//398 298//298 297//297 -f 398//398 297//297 399//399 -f 399//399 297//297 296//296 -f 296//296 295//295 399//399 -f 399//399 295//295 400//400 -f 399//399 400//400 344//344 -f 344//344 400//400 374//374 -f 344//344 374//374 342//342 -f 342//342 374//374 375//375 -f 295//295 294//294 400//400 -f 400//400 294//294 293//293 -f 400//400 293//293 401//401 -f 401//401 293//293 292//292 -f 401//401 292//292 402//402 -f 402//402 292//292 291//291 -f 291//291 290//290 402//402 -f 402//402 290//290 403//403 -f 402//402 403//403 341//341 -f 341//341 403//403 378//378 -f 341//341 378//378 339//339 -f 339//339 378//378 377//377 -f 290//290 289//289 403//403 -f 403//403 289//289 288//288 -f 403//403 288//288 404//404 -f 404//404 288//288 287//287 -f 404//404 287//287 405//405 -f 405//405 287//287 286//286 -f 286//286 285//285 405//405 -f 405//405 285//285 410//410 -f 405//405 410//410 382//382 -f 382//382 410//410 389//389 -f 382//382 389//389 384//384 -f 384//384 389//389 390//390 -f 285//285 284//284 410//410 -f 410//410 284//284 283//283 -f 410//410 283//283 409//409 -f 409//409 283//283 314//314 -f 409//409 314//314 408//408 -f 408//408 314//314 313//313 -f 408//408 313//313 407//407 -f 407//407 313//313 312//312 -f 407//407 312//312 406//406 -f 406//406 312//312 311//311 -f 406//406 311//311 310//310 -f 95//95 322//322 100//100 -f 100//100 322//322 323//323 -f 100//100 323//323 89//89 -f 89//89 323//323 324//324 -f 89//89 324//324 91//91 -f 91//91 324//324 325//325 -f 91//91 325//325 92//92 -f 92//92 325//325 326//326 -f 92//92 326//326 85//85 -f 85//85 326//326 315//315 -f 85//85 315//315 87//87 -f 87//87 315//315 316//316 -f 87//87 316//316 80//80 -f 80//80 316//316 317//317 -f 80//80 317//317 81//81 -f 81//81 317//317 318//318 -f 81//81 318//318 77//77 -f 77//77 318//318 319//319 -f 77//77 319//319 93//93 -f 93//93 319//319 320//320 -f 93//93 320//320 94//94 -f 94//94 320//320 321//321 -f 94//94 321//321 95//95 -f 95//95 321//321 322//322 -f 98//98 334//334 96//96 -f 96//96 334//334 335//335 -f 96//96 335//335 101//101 -f 101//101 335//335 336//336 -f 101//101 336//336 102//102 -f 102//102 336//336 337//337 -f 102//102 337//337 103//103 -f 103//103 337//337 338//338 -f 103//103 338//338 104//104 -f 104//104 338//338 327//327 -f 104//104 327//327 86//86 -f 86//86 327//327 328//328 -f 86//86 328//328 83//83 -f 83//83 328//328 329//329 -f 83//83 329//329 84//84 -f 84//84 329//329 330//330 -f 84//84 330//330 90//90 -f 90//90 330//330 331//331 -f 90//90 331//331 88//88 -f 88//88 331//331 332//332 -f 88//88 332//332 99//99 -f 99//99 332//332 333//333 -f 99//99 333//333 98//98 -f 98//98 333//333 334//334 -f 43//43 42//42 367//367 -f 41//41 370//370 42//42 -f 42//42 370//370 369//369 -f 42//42 369//369 367//367 -f 359//359 357//357 40//40 -f 40//40 357//357 356//356 -f 40//40 356//356 41//41 -f 41//41 356//356 363//363 -f 41//41 363//363 370//370 -f 359//359 40//40 361//361 -f 361//361 40//40 38//38 -f 361//361 38//38 362//362 -f 362//362 38//38 352//352 -f 352//352 38//38 37//37 -f 352//352 37//37 354//354 -f 5//5 350//350 37//37 -f 37//37 350//350 355//355 -f 37//37 355//355 354//354 -f 2//2 386//386 5//5 -f 5//5 386//386 385//385 -f 5//5 385//385 350//350 -f 1//1 390//390 2//2 -f 2//2 390//390 388//388 -f 2//2 388//388 386//386 -f 39//39 383//383 1//1 -f 1//1 383//383 384//384 -f 1//1 384//384 390//390 -f 339//339 377//377 48//48 -f 48//48 377//377 379//379 -f 48//48 379//379 39//39 -f 39//39 379//379 381//381 -f 39//39 381//381 383//383 -f 339//339 48//48 340//340 -f 340//340 48//48 47//47 -f 340//340 47//47 376//376 -f 376//376 47//47 373//373 -f 373//373 47//47 46//46 -f 373//373 46//46 375//375 -f 44//44 343//343 46//46 -f 46//46 343//343 342//342 -f 46//46 342//342 375//375 -f 367//367 366//366 43//43 -f 43//43 366//366 347//347 -f 43//43 347//347 44//44 -f 44//44 347//347 371//371 -f 44//44 371//371 343//343 -f 3//3 411//411 31//31 -f 31//31 411//411 412//412 -f 31//31 412//412 32//32 -f 32//32 412//412 413//413 -f 32//32 413//413 34//34 -f 34//34 413//413 414//414 -f 34//34 414//414 35//35 -f 35//35 414//414 415//415 -f 35//35 415//415 36//36 -f 36//36 415//415 416//416 -f 36//36 416//416 16//16 -f 16//16 416//416 417//417 -f 16//16 417//417 14//14 -f 14//14 417//417 418//418 -f 14//14 418//418 12//12 -f 12//12 418//418 419//419 -f 12//12 419//419 10//10 -f 10//10 419//419 420//420 -f 10//10 420//420 17//17 -f 17//17 420//420 421//421 -f 17//17 421//421 18//18 -f 18//18 421//421 422//422 -f 18//18 422//422 19//19 -f 19//19 422//422 423//423 -f 19//19 423//423 45//45 -f 45//45 423//423 424//424 -f 45//45 424//424 21//21 -f 21//21 424//424 425//425 -f 21//21 425//425 22//22 -f 22//22 425//425 426//426 -f 22//22 426//426 28//28 -f 28//28 426//426 427//427 -f 28//28 427//427 29//29 -f 29//29 427//427 428//428 -f 29//29 428//428 30//30 -f 30//30 428//428 429//429 -f 30//30 429//429 8//8 -f 8//8 429//429 430//430 -f 8//8 430//430 9//9 -f 9//9 430//430 431//431 -f 9//9 431//431 24//24 -f 24//24 431//431 432//432 -f 24//24 432//432 26//26 -f 26//26 432//432 433//433 -f 26//26 433//433 27//27 -f 27//27 433//433 434//434 -f 27//27 434//434 6//6 -f 6//6 434//434 435//435 -f 6//6 435//435 4//4 -f 4//4 435//435 436//436 -f 4//4 436//436 3//3 -f 3//3 436//436 411//411 -f 420//420 437//437 421//421 -f 421//421 437//437 438//438 -f 421//421 438//438 422//422 -f 422//422 438//438 439//439 -f 422//422 439//439 423//423 -f 423//423 439//439 440//440 -f 423//423 440//440 424//424 -f 424//424 440//440 441//441 -f 424//424 441//441 425//425 -f 425//425 441//441 442//442 -f 425//425 442//442 426//426 -f 426//426 442//442 443//443 -f 426//426 443//443 427//427 -f 427//427 443//443 444//444 -f 427//427 444//444 428//428 -f 428//428 444//444 445//445 -f 428//428 445//445 429//429 -f 429//429 445//445 446//446 -f 429//429 446//446 430//430 -f 430//430 446//446 447//447 -f 430//430 447//447 431//431 -f 431//431 447//447 448//448 -f 431//431 448//448 432//432 -f 432//432 448//448 449//449 -f 432//432 449//449 433//433 -f 433//433 449//449 450//450 -f 433//433 450//450 434//434 -f 434//434 450//450 451//451 -f 434//434 451//451 435//435 -f 435//435 451//451 452//452 -f 435//435 452//452 436//436 -f 436//436 452//452 453//453 -f 436//436 453//453 411//411 -f 411//411 453//453 454//454 -f 411//411 454//454 412//412 -f 412//412 454//454 455//455 -f 412//412 455//455 413//413 -f 413//413 455//455 456//456 -f 413//413 456//456 414//414 -f 414//414 456//456 457//457 -f 414//414 457//457 415//415 -f 415//415 457//457 458//458 -f 415//415 458//458 416//416 -f 416//416 458//458 459//459 -f 416//416 459//459 417//417 -f 417//417 459//459 460//460 -f 417//417 460//460 418//418 -f 418//418 460//460 461//461 -f 418//418 461//461 419//419 -f 419//419 461//461 462//462 -f 419//419 462//462 420//420 -f 420//420 462//462 437//437 -f 131//131 440//440 132//132 -f 132//132 440//440 439//439 -f 132//132 439//439 110//110 -f 110//110 439//439 438//438 -f 110//110 438//438 111//111 -f 111//111 438//438 437//437 -f 111//111 437//437 137//137 -f 137//137 437//437 462//462 -f 137//137 462//462 138//138 -f 138//138 462//462 461//461 -f 138//138 461//461 140//140 -f 140//140 461//461 460//460 -f 140//140 460//460 141//141 -f 141//141 460//460 459//459 -f 141//141 459//459 120//120 -f 120//120 459//459 458//458 -f 120//120 458//458 122//122 -f 122//122 458//458 457//457 -f 122//122 457//457 124//124 -f 124//124 457//457 456//456 -f 124//124 456//456 127//127 -f 127//127 456//456 455//455 -f 127//127 455//455 128//128 -f 128//128 455//455 454//454 -f 128//128 454//454 107//107 -f 107//107 454//454 453//453 -f 107//107 453//453 133//133 -f 133//133 453//453 452//452 -f 133//133 452//452 134//134 -f 134//134 452//452 451//451 -f 134//134 451//451 114//114 -f 114//114 451//451 450//450 -f 114//114 450//450 115//115 -f 115//115 450//450 449//449 -f 115//115 449//449 116//116 -f 116//116 449//449 448//448 -f 116//116 448//448 142//142 -f 142//142 448//448 447//447 -f 142//142 447//447 143//143 -f 143//143 447//447 446//446 -f 143//143 446//446 144//144 -f 144//144 446//446 445//445 -f 144//144 445//445 145//145 -f 145//145 445//445 444//444 -f 145//145 444//444 146//146 -f 146//146 444//444 443//443 -f 146//146 443//443 129//129 -f 129//129 443//443 442//442 -f 129//129 442//442 130//130 -f 130//130 442//442 441//441 -f 130//130 441//441 131//131 -f 131//131 441//441 440//440 -f 54//54 106//106 55//55 -f 57//57 59//59 463//463 -f 463//463 59//59 464//464 -f 463//463 464//464 465//465 -f 465//465 464//464 466//466 -f 52//52 82//82 53//53 -f 53//53 82//82 464//464 -f 53//53 464//464 105//105 -f 105//105 464//464 59//59 -f 105//105 59//59 117//117 -f 467//467 468//468 469//469 -f 470//470 471//471 468//468 -f 468//468 471//471 472//472 -f 468//468 472//472 469//469 -f 473//473 63//63 64//64 -f 474//474 465//465 466//466 -f 467//467 469//469 475//475 -f 475//475 469//469 476//476 -f 475//475 476//476 477//477 -f 472//472 478//478 469//469 -f 469//469 478//478 473//473 -f 469//469 473//473 479//479 -f 479//479 473//473 64//64 -f 469//469 480//480 476//476 -f 476//476 480//480 474//474 -f 476//476 474//474 481//481 -f 481//481 474//474 466//466 -f 78//78 97//97 482//482 -f 482//482 97//97 483//483 -f 482//482 483//483 477//477 -f 477//477 483//483 484//484 -f 477//477 484//484 475//475 -f 109//109 108//108 70//70 -f 70//70 108//108 68//68 -f 49//49 56//56 112//112 -f 139//139 50//50 112//112 -f 112//112 50//50 49//49 -f 139//139 119//119 60//60 -f 468//468 485//485 470//470 -f 470//470 485//485 486//486 -f 485//485 75//75 51//51 -f 51//51 50//50 485//485 -f 485//485 50//50 139//139 -f 485//485 139//139 486//486 -f 486//486 139//139 60//60 -f 486//486 60//60 61//61 -f 479//479 64//64 487//487 -f 487//487 64//64 58//58 -f 488//488 463//463 474//474 -f 474//474 463//463 465//465 -f 487//487 58//58 57//57 -f 489//489 487//487 490//490 -f 490//490 487//487 57//57 -f 490//490 57//57 488//488 -f 488//488 57//57 463//463 -f 491//491 464//464 82//82 -f 492//492 491//491 493//493 -f 493//493 491//491 82//82 -f 493//493 82//82 494//494 -f 494//494 82//82 79//79 -f 494//494 79//79 482//482 -f 482//482 79//79 78//78 -f 481//481 466//466 491//491 -f 491//491 466//466 464//464 -f 495//495 76//76 75//75 -f 75//75 485//485 496//496 -f 496//496 497//497 75//75 -f 75//75 497//497 498//498 -f 75//75 498//498 495//495 -f 483//483 97//97 495//495 -f 495//495 97//97 76//76 -f 496//496 485//485 467//467 -f 467//467 485//485 468//468 -f 499//499 486//486 61//61 -f 500//500 499//499 501//501 -f 501//501 499//499 61//61 -f 501//501 61//61 502//502 -f 502//502 61//61 62//62 -f 502//502 62//62 473//473 -f 473//473 62//62 63//63 -f 471//471 470//470 499//499 -f 499//499 470//470 486//486 -f 503//503 504//504 25//25 -f 25//25 504//504 23//23 -f 505//505 503//503 20//20 -f 20//20 503//503 25//25 -f 506//506 505//505 7//7 -f 7//7 505//505 20//20 -f 504//504 506//506 23//23 -f 23//23 506//506 7//7 -f 505//505 506//506 503//503 -f 503//503 506//506 504//504 -f 507//507 508//508 11//11 -f 11//11 508//508 13//13 -f 509//509 507//507 33//33 -f 33//33 507//507 11//11 -f 510//510 509//509 15//15 -f 15//15 509//509 33//33 -f 508//508 510//510 13//13 -f 13//13 510//510 15//15 -f 509//509 510//510 507//507 -f 507//507 510//510 508//508 -f 233//233 511//511 255//255 -f 255//255 511//511 512//512 -f 255//255 512//512 253//253 -f 253//253 512//512 513//513 -f 253//253 513//513 251//251 -f 251//251 513//513 514//514 -f 251//251 514//514 249//249 -f 249//249 514//514 515//515 -f 249//249 515//515 247//247 -f 247//247 515//515 516//516 -f 247//247 516//516 245//245 -f 245//245 516//516 517//517 -f 245//245 517//517 243//243 -f 243//243 517//517 518//518 -f 243//243 518//518 241//241 -f 241//241 518//518 519//519 -f 241//241 519//519 239//239 -f 239//239 519//519 520//520 -f 239//239 520//520 237//237 -f 237//237 520//520 521//521 -f 237//237 521//521 235//235 -f 235//235 521//521 522//522 -f 235//235 522//522 233//233 -f 233//233 522//522 511//511 -f 518//518 517//517 523//523 -f 523//523 517//517 516//516 -f 523//523 516//516 515//515 -f 521//521 520//520 523//523 -f 523//523 520//520 519//519 -f 523//523 519//519 518//518 -f 512//512 511//511 523//523 -f 523//523 511//511 522//522 -f 523//523 522//522 521//521 -f 515//515 514//514 523//523 -f 523//523 514//514 513//513 -f 523//523 513//513 512//512 -f 502//502 473//473 501//501 -f 501//501 473//473 478//478 -f 501//501 478//478 500//500 -f 500//500 478//478 472//472 -f 500//500 472//472 499//499 -f 499//499 472//472 471//471 -f 483//483 495//495 484//484 -f 484//484 495//495 498//498 -f 484//484 498//498 475//475 -f 475//475 498//498 497//497 -f 475//475 497//497 467//467 -f 467//467 497//497 496//496 -f 494//494 482//482 493//493 -f 493//493 482//482 477//477 -f 493//493 477//477 492//492 -f 492//492 477//477 476//476 -f 492//492 476//476 491//491 -f 491//491 476//476 481//481 -f 479//479 487//487 469//469 -f 469//469 487//487 489//489 -f 469//469 489//489 480//480 -f 480//480 489//489 490//490 -f 480//480 490//490 474//474 -f 474//474 490//490 488//488 -f 60//60 119//119 121//121 -f 60//60 121//121 71//71 -f 71//71 121//121 123//123 -f 71//71 123//123 65//65 -f 65//65 123//123 125//125 -f 65//65 125//125 66//66 -f 66//66 125//125 126//126 -f 66//66 126//126 67//67 -f 67//67 126//126 109//109 -f 67//67 109//109 70//70 -f 117//117 59//59 74//74 -f 117//117 74//74 118//118 -f 118//118 74//74 73//73 -f 118//118 73//73 113//113 -f 113//113 73//73 72//72 -f 113//113 72//72 136//136 -f 136//136 72//72 69//69 -f 136//136 69//69 135//135 -f 135//135 69//69 68//68 -f 135//135 68//68 108//108 -f 524//524 525//525 526//526 -f 526//526 525//525 527//527 -f 527//527 525//525 528//528 -f 527//527 528//528 529//529 -f 530//530 531//531 532//532 -f 533//533 534//534 535//535 -f 535//535 534//534 536//536 -f 535//535 536//536 537//537 -f 537//537 536//536 538//538 -f 537//537 538//538 539//539 -f 533//533 540//540 534//534 -f 534//534 540//540 541//541 -f 534//534 541//541 542//542 -f 543//543 544//544 545//545 -f 530//530 532//532 546//546 -f 546//546 532//532 547//547 -f 546//546 547//547 548//548 -f 548//548 547//547 549//549 -f 548//548 549//549 528//528 -f 528//528 549//549 550//550 -f 528//528 550//550 529//529 -f 545//545 551//551 543//543 -f 543//543 551//551 552//552 -f 543//543 552//552 530//530 -f 530//530 552//552 553//553 -f 530//530 553//553 531//531 -f 554//554 555//555 556//556 -f 555//555 557//557 556//556 -f 556//556 557//557 558//558 -f 556//556 558//558 538//538 -f 538//538 558//558 559//559 -f 538//538 559//559 539//539 -f 528//528 560//560 548//548 -f 548//548 560//560 561//561 -f 548//548 561//561 543//543 -f 554//554 556//556 526//526 -f 526//526 556//556 562//562 -f 526//526 562//562 524//524 -f 561//561 563//563 543//543 -f 543//543 563//563 564//564 -f 543//543 564//564 544//544 -f 544//544 564//564 565//565 -f 544//544 565//565 566//566 -f 566//566 567//567 544//544 -f 544//544 567//567 534//534 -f 544//544 534//534 568//568 -f 568//568 534//534 542//542 -f 567//567 569//569 534//534 -f 534//534 569//569 570//570 -f 534//534 570//570 556//556 -f 556//556 570//570 571//571 -f 556//556 571//571 562//562 -f 572//572 573//573 574//574 -f 575//575 576//576 577//577 -f 578//578 579//579 577//577 -f 577//577 579//579 572//572 -f 577//577 572//572 575//575 -f 575//575 572//572 574//574 -f 580//580 581//581 582//582 -f 582//582 581//581 583//583 -f 584//584 583//583 585//585 -f 585//585 583//583 581//581 -f 585//585 581//581 586//586 -f 586//586 581//581 587//587 -f 588//588 589//589 590//590 -f 582//582 591//591 592//592 -f 591//591 582//582 593//593 -f 593//593 582//582 583//583 -f 593//593 583//583 590//590 -f 590//590 583//583 594//594 -f 590//590 594//594 588//588 -f 592//592 595//595 582//582 -f 582//582 595//595 596//596 -f 582//582 596//596 597//597 -f 574//574 598//598 599//599 -f 600//600 601//601 602//602 -f 575//575 603//603 604//604 -f 600//600 602//602 604//604 -f 604//604 602//602 605//605 -f 604//604 605//605 575//575 -f 606//606 607//607 608//608 -f 609//609 606//606 574//574 -f 574//574 606//606 608//608 -f 574//574 608//608 575//575 -f 575//575 608//608 610//610 -f 575//575 610//610 603//603 -f 611//611 612//612 613//613 -f 613//613 612//612 614//614 -f 613//613 614//614 607//607 -f 607//607 614//614 615//615 -f 607//607 615//615 608//608 -f 600//600 616//616 601//601 -f 601//601 616//616 617//617 -f 601//601 617//617 618//618 -f 619//619 620//620 621//621 -f 621//621 620//620 601//601 -f 621//621 601//601 622//622 -f 622//622 601//601 618//618 -f 622//622 618//618 611//611 -f 611//611 618//618 623//623 -f 611//611 623//623 612//612 -f 619//619 624//624 620//620 -f 620//620 624//624 625//625 -f 620//620 625//625 599//599 -f 599//599 625//625 626//626 -f 599//599 626//626 574//574 -f 574//574 626//626 627//627 -f 574//574 627//627 609//609 -f 628//628 629//629 576//576 -f 576//576 629//629 577//577 -f 630//630 631//631 632//632 -f 633//633 634//634 579//579 -f 579//579 634//634 635//635 -f 636//636 637//637 638//638 -f 639//639 640//640 638//638 -f 638//638 640//640 641//641 -f 638//638 641//641 636//636 -f 642//642 643//643 644//644 -f 644//644 643//643 645//645 -f 644//644 645//645 646//646 -f 646//646 645//645 647//647 -f 646//646 647//647 648//648 -f 648//648 647//647 649//649 -f 649//649 647//647 650//650 -f 649//649 650//650 632//632 -f 632//632 650//650 651//651 -f 632//632 651//651 630//630 -f 652//652 653//653 578//578 -f 578//578 653//653 654//654 -f 578//578 654//654 579//579 -f 579//579 654//654 655//655 -f 579//579 655//655 633//633 -f 630//630 656//656 631//631 -f 631//631 656//656 657//657 -f 631//631 657//657 658//658 -f 658//658 657//657 637//637 -f 658//658 637//637 659//659 -f 659//659 637//637 636//636 -f 634//634 660//660 635//635 -f 635//635 660//660 661//661 -f 635//635 661//661 662//662 -f 662//662 661//661 663//663 -f 662//662 663//663 642//642 -f 642//642 663//663 664//664 -f 642//642 664//664 643//643 -f 639//639 665//665 640//640 -f 640//640 665//665 666//666 -f 640//640 666//666 628//628 -f 628//628 666//666 667//667 -f 628//628 667//667 629//629 -f 629//629 667//667 668//668 -f 629//629 668//668 578//578 -f 578//578 668//668 669//669 -f 578//578 669//669 652//652 -f 670//670 671//671 672//672 -f 672//672 671//671 673//673 -f 672//672 673//673 674//674 -f 675//675 676//676 672//672 -f 672//672 676//676 677//677 -f 672//672 677//677 670//670 -f 678//678 679//679 672//672 -f 672//672 679//679 680//680 -f 672//672 680//680 675//675 -f 674//674 681//681 672//672 -f 672//672 681//681 682//682 -f 672//672 682//682 678//678 -f 683//683 684//684 685//685 -f 685//685 684//684 686//686 -f 685//685 686//686 687//687 -f 688//688 689//689 685//685 -f 685//685 689//689 690//690 -f 685//685 690//690 683//683 -f 691//691 692//692 685//685 -f 685//685 692//692 693//693 -f 685//685 693//693 688//688 -f 687//687 694//694 685//685 -f 685//685 694//694 695//695 -f 685//685 695//695 691//691 -f 673//673 696//696 674//674 -f 674//674 696//696 697//697 -f 674//674 697//697 681//681 -f 681//681 697//697 698//698 -f 681//681 698//698 682//682 -f 682//682 698//698 699//699 -f 682//682 699//699 678//678 -f 678//678 699//699 700//700 -f 678//678 700//700 679//679 -f 679//679 700//700 701//701 -f 679//679 701//701 680//680 -f 680//680 701//701 702//702 -f 680//680 702//702 675//675 -f 675//675 702//702 703//703 -f 675//675 703//703 676//676 -f 676//676 703//703 704//704 -f 676//676 704//704 677//677 -f 677//677 704//704 705//705 -f 677//677 705//705 670//670 -f 670//670 705//705 706//706 -f 670//670 706//706 671//671 -f 671//671 706//706 707//707 -f 671//671 707//707 673//673 -f 673//673 707//707 696//696 -f 686//686 708//708 687//687 -f 687//687 708//708 709//709 -f 687//687 709//709 694//694 -f 694//694 709//709 710//710 -f 694//694 710//710 695//695 -f 695//695 710//710 711//711 -f 695//695 711//711 691//691 -f 691//691 711//711 712//712 -f 691//691 712//712 692//692 -f 692//692 712//712 713//713 -f 692//692 713//713 693//693 -f 693//693 713//713 714//714 -f 693//693 714//714 688//688 -f 688//688 714//714 715//715 -f 688//688 715//715 689//689 -f 689//689 715//715 716//716 -f 689//689 716//716 690//690 -f 690//690 716//716 717//717 -f 690//690 717//717 683//683 -f 683//683 717//717 718//718 -f 683//683 718//718 684//684 -f 684//684 718//718 719//719 -f 684//684 719//719 686//686 -f 686//686 719//719 708//708 -f 706//706 720//720 707//707 -f 707//707 720//720 721//721 -f 707//707 721//721 696//696 -f 696//696 721//721 722//722 -f 696//696 722//722 697//697 -f 697//697 722//722 723//723 -f 697//697 723//723 698//698 -f 698//698 723//723 724//724 -f 698//698 724//724 699//699 -f 699//699 724//724 725//725 -f 699//699 725//725 700//700 -f 700//700 725//725 726//726 -f 700//700 726//726 701//701 -f 701//701 726//726 727//727 -f 701//701 727//727 702//702 -f 702//702 727//727 728//728 -f 702//702 728//728 703//703 -f 703//703 728//728 729//729 -f 703//703 729//729 704//704 -f 704//704 729//729 730//730 -f 704//704 730//730 705//705 -f 705//705 730//730 731//731 -f 705//705 731//731 706//706 -f 706//706 731//731 720//720 -f 719//719 732//732 708//708 -f 708//708 732//732 733//733 -f 717//717 734//734 718//718 -f 718//718 734//734 735//735 -f 718//718 735//735 719//719 -f 719//719 735//735 736//736 -f 719//719 736//736 732//732 -f 716//716 737//737 717//717 -f 717//717 737//737 738//738 -f 717//717 738//738 734//734 -f 715//715 739//739 716//716 -f 716//716 739//739 740//740 -f 716//716 740//740 737//737 -f 714//714 741//741 715//715 -f 715//715 741//741 742//742 -f 715//715 742//742 739//739 -f 713//713 743//743 714//714 -f 714//714 743//743 744//744 -f 714//714 744//744 741//741 -f 712//712 745//745 713//713 -f 713//713 745//745 746//746 -f 713//713 746//746 743//743 -f 711//711 747//747 712//712 -f 712//712 747//747 748//748 -f 712//712 748//748 745//745 -f 710//710 749//749 711//711 -f 711//711 749//749 750//750 -f 711//711 750//750 747//747 -f 709//709 751//751 710//710 -f 710//710 751//751 752//752 -f 710//710 752//752 749//749 -f 733//733 753//753 708//708 -f 708//708 753//753 754//754 -f 708//708 754//754 709//709 -f 709//709 754//754 755//755 -f 709//709 755//755 751//751 -f 756//756 757//757 758//758 -f 758//758 757//757 759//759 -f 758//758 759//759 760//760 -f 760//760 759//759 761//761 -f 760//760 761//761 762//762 -f 762//762 761//761 763//763 -f 762//762 763//763 764//764 -f 764//764 763//763 765//765 -f 764//764 765//765 766//766 -f 766//766 765//765 767//767 -f 766//766 767//767 768//768 -f 768//768 767//767 769//769 -f 768//768 769//769 770//770 -f 770//770 769//769 771//771 -f 770//770 771//771 772//772 -f 772//772 771//771 773//773 -f 772//772 773//773 774//774 -f 774//774 773//773 775//775 -f 774//774 775//775 776//776 -f 776//776 775//775 777//777 -f 776//776 777//777 778//778 -f 778//778 777//777 779//779 -f 778//778 779//779 756//756 -f 756//756 779//779 780//780 -f 756//756 780//780 757//757 -f 781//781 727//727 782//782 -f 782//782 727//727 726//726 -f 782//782 726//726 783//783 -f 783//783 726//726 725//725 -f 783//783 725//725 784//784 -f 784//784 725//725 724//724 -f 784//784 724//724 785//785 -f 785//785 724//724 723//723 -f 785//785 723//723 786//786 -f 786//786 723//723 722//722 -f 786//786 722//722 787//787 -f 787//787 722//722 721//721 -f 787//787 721//721 788//788 -f 788//788 721//721 720//720 -f 788//788 720//720 789//789 -f 789//789 720//720 731//731 -f 789//789 731//731 790//790 -f 790//790 731//731 730//730 -f 790//790 730//730 791//791 -f 791//791 730//730 729//729 -f 791//791 729//729 792//792 -f 792//792 729//729 728//728 -f 792//792 728//728 781//781 -f 781//781 728//728 727//727 -f 793//793 794//794 737//737 -f 742//742 795//795 739//739 -f 739//739 795//795 793//793 -f 739//739 793//793 740//740 -f 740//740 793//793 737//737 -f 796//796 797//797 736//736 -f 736//736 735//735 796//796 -f 796//796 735//735 734//734 -f 796//796 734//734 794//794 -f 794//794 734//734 738//738 -f 794//794 738//738 737//737 -f 798//798 753//753 799//799 -f 799//799 753//753 733//733 -f 799//799 733//733 797//797 -f 797//797 733//733 732//732 -f 797//797 732//732 736//736 -f 800//800 755//755 798//798 -f 798//798 755//755 754//754 -f 798//798 754//754 753//753 -f 801//801 752//752 800//800 -f 800//800 752//752 751//751 -f 800//800 751//751 755//755 -f 802//802 750//750 801//801 -f 801//801 750//750 749//749 -f 801//801 749//749 752//752 -f 803//803 748//748 802//802 -f 802//802 748//748 747//747 -f 802//802 747//747 750//750 -f 742//742 741//741 795//795 -f 795//795 741//741 744//744 -f 795//795 744//744 804//804 -f 804//804 744//744 743//743 -f 804//804 743//743 805//805 -f 805//805 743//743 746//746 -f 805//805 746//746 803//803 -f 803//803 746//746 745//745 -f 803//803 745//745 748//748 -f 771//771 806//806 807//807 -f 771//771 807//807 773//773 -f 807//807 808//808 773//773 -f 773//773 808//808 809//809 -f 773//773 809//809 775//775 -f 775//775 809//809 810//810 -f 775//775 810//810 811//811 -f 811//811 812//812 775//775 -f 775//775 812//812 813//813 -f 775//775 813//813 777//777 -f 777//777 813//813 814//814 -f 777//777 814//814 779//779 -f 779//779 814//814 815//815 -f 779//779 815//815 816//816 -f 816//816 817//817 779//779 -f 779//779 817//817 818//818 -f 779//779 818//818 780//780 -f 780//780 818//818 819//819 -f 780//780 819//819 757//757 -f 757//757 819//819 820//820 -f 757//757 820//820 821//821 -f 821//821 822//822 757//757 -f 757//757 822//822 823//823 -f 757//757 823//823 759//759 -f 824//824 761//761 825//825 -f 825//825 761//761 759//759 -f 825//825 759//759 826//826 -f 826//826 759//759 823//823 -f 824//824 827//827 761//761 -f 761//761 827//827 828//828 -f 761//761 828//828 763//763 -f 828//828 829//829 763//763 -f 763//763 829//829 830//830 -f 763//763 830//830 765//765 -f 830//830 831//831 765//765 -f 765//765 831//831 832//832 -f 765//765 832//832 767//767 -f 767//767 832//832 833//833 -f 833//833 834//834 767//767 -f 767//767 834//834 835//835 -f 767//767 835//835 769//769 -f 769//769 835//835 836//836 -f 769//769 836//836 771//771 -f 771//771 836//836 837//837 -f 771//771 837//837 806//806 -f 838//838 787//787 839//839 -f 839//839 787//787 788//788 -f 839//839 788//788 840//840 -f 840//840 788//788 789//789 -f 840//840 789//789 841//841 -f 841//841 789//789 790//790 -f 841//841 790//790 842//842 -f 842//842 790//790 791//791 -f 842//842 791//791 843//843 -f 843//843 791//791 792//792 -f 843//843 792//792 844//844 -f 844//844 792//792 781//781 -f 844//844 781//781 845//845 -f 845//845 781//781 782//782 -f 845//845 782//782 846//846 -f 846//846 782//782 783//783 -f 846//846 783//783 847//847 -f 847//847 783//783 784//784 -f 847//847 784//784 848//848 -f 848//848 784//784 785//785 -f 848//848 785//785 849//849 -f 849//849 785//785 786//786 -f 849//849 786//786 838//838 -f 838//838 786//786 787//787 -f 850//850 799//799 851//851 -f 851//851 799//799 797//797 -f 851//851 797//797 852//852 -f 852//852 797//797 796//796 -f 852//852 796//796 853//853 -f 853//853 796//796 794//794 -f 853//853 794//794 854//854 -f 854//854 794//794 793//793 -f 854//854 793//793 855//855 -f 855//855 793//793 795//795 -f 855//855 795//795 856//856 -f 856//856 795//795 804//804 -f 856//856 804//804 857//857 -f 857//857 804//804 805//805 -f 857//857 805//805 858//858 -f 858//858 805//805 803//803 -f 858//858 803//803 859//859 -f 859//859 803//803 802//802 -f 859//859 802//802 860//860 -f 860//860 802//802 801//801 -f 860//860 801//801 861//861 -f 861//861 801//801 800//800 -f 861//861 800//800 850//850 -f 850//850 800//800 798//798 -f 850//850 798//798 799//799 -f 862//862 863//863 864//864 -f 865//865 866//866 867//867 -f 868//868 869//869 870//870 -f 871//871 872//872 873//873 -f 874//874 875//875 876//876 -f 876//876 875//875 877//877 -f 876//876 877//877 878//878 -f 879//879 880//880 881//881 -f 881//881 880//880 882//882 -f 881//881 882//882 883//883 -f 883//883 882//882 884//884 -f 883//883 884//884 874//874 -f 874//874 884//884 885//885 -f 874//874 885//885 875//875 -f 886//886 887//887 888//888 -f 889//889 890//890 891//891 -f 891//891 890//890 892//892 -f 891//891 892//892 888//888 -f 888//888 892//892 893//893 -f 888//888 893//893 886//886 -f 867//867 866//866 869//869 -f 869//869 866//866 894//894 -f 869//869 894//894 870//870 -f 895//895 896//896 897//897 -f 897//897 896//896 898//898 -f 864//864 863//863 895//895 -f 895//895 863//863 899//899 -f 895//895 899//899 896//896 -f 900//900 901//901 902//902 -f 902//902 901//901 903//903 -f 902//902 903//903 904//904 -f 904//904 903//903 905//905 -f 904//904 905//905 906//906 -f 906//906 905//905 907//907 -f 873//873 908//908 871//871 -f 871//871 908//908 909//909 -f 871//871 909//909 910//910 -f 910//910 909//909 911//911 -f 910//910 911//911 912//912 -f 912//912 911//911 913//913 -f 876//876 914//914 874//874 -f 874//874 914//914 915//915 -f 874//874 915//915 883//883 -f 883//883 915//915 916//916 -f 883//883 916//916 881//881 -f 917//917 918//918 887//887 -f 887//887 918//918 888//888 -f 888//888 918//918 919//919 -f 888//888 919//919 891//891 -f 920//920 921//921 868//868 -f 868//868 921//921 869//869 -f 869//869 921//921 922//922 -f 869//869 922//922 867//867 -f 923//923 924//924 897//897 -f 897//897 924//924 895//895 -f 895//895 924//924 925//925 -f 895//895 925//925 864//864 -f 926//926 927//927 901//901 -f 901//901 927//927 903//903 -f 903//903 927//927 928//928 -f 903//903 928//928 905//905 -f 929//929 872//872 930//930 -f 930//930 872//872 871//871 -f 930//930 871//871 931//931 -f 931//931 871//871 910//910 -f 931//931 910//910 932//932 -f 932//932 910//910 912//912 -f 932//932 912//912 933//933 -f 833//833 914//914 929//929 -f 929//929 914//914 876//876 -f 929//929 876//876 872//872 -f 872//872 876//876 878//878 -f 872//872 878//878 873//873 -f 833//833 832//832 914//914 -f 914//914 832//832 831//831 -f 914//914 831//831 915//915 -f 915//915 831//831 830//830 -f 915//915 830//830 916//916 -f 916//916 830//830 829//829 -f 829//829 828//828 916//916 -f 916//916 828//828 917//917 -f 916//916 917//917 881//881 -f 881//881 917//917 887//887 -f 881//881 887//887 879//879 -f 879//879 887//887 886//886 -f 828//828 827//827 917//917 -f 917//917 827//827 824//824 -f 917//917 824//824 918//918 -f 918//918 824//824 825//825 -f 918//918 825//825 919//919 -f 919//919 825//825 826//826 -f 826//826 823//823 919//919 -f 919//919 823//823 920//920 -f 919//919 920//920 891//891 -f 891//891 920//920 868//868 -f 891//891 868//868 889//889 -f 889//889 868//868 870//870 -f 823//823 822//822 920//920 -f 920//920 822//822 821//821 -f 920//920 821//821 921//921 -f 921//921 821//821 820//820 -f 921//921 820//820 922//922 -f 922//922 820//820 819//819 -f 819//819 818//818 922//922 -f 922//922 818//818 923//923 -f 922//922 923//923 867//867 -f 867//867 923//923 897//897 -f 867//867 897//897 865//865 -f 865//865 897//897 898//898 -f 818//818 817//817 923//923 -f 923//923 817//817 816//816 -f 923//923 816//816 924//924 -f 924//924 816//816 815//815 -f 924//924 815//815 925//925 -f 925//925 815//815 814//814 -f 814//814 813//813 925//925 -f 925//925 813//813 926//926 -f 925//925 926//926 864//864 -f 864//864 926//926 901//901 -f 864//864 901//901 862//862 -f 862//862 901//901 900//900 -f 813//813 812//812 926//926 -f 926//926 812//812 811//811 -f 926//926 811//811 927//927 -f 927//927 811//811 810//810 -f 927//927 810//810 928//928 -f 928//928 810//810 809//809 -f 809//809 808//808 928//928 -f 928//928 808//808 933//933 -f 928//928 933//933 905//905 -f 905//905 933//933 912//912 -f 905//905 912//912 907//907 -f 907//907 912//912 913//913 -f 808//808 807//807 933//933 -f 933//933 807//807 806//806 -f 933//933 806//806 932//932 -f 932//932 806//806 837//837 -f 932//932 837//837 931//931 -f 931//931 837//837 836//836 -f 931//931 836//836 930//930 -f 930//930 836//836 835//835 -f 930//930 835//835 929//929 -f 929//929 835//835 834//834 -f 929//929 834//834 833//833 -f 618//618 845//845 623//623 -f 623//623 845//845 846//846 -f 623//623 846//846 612//612 -f 612//612 846//846 847//847 -f 612//612 847//847 614//614 -f 614//614 847//847 848//848 -f 614//614 848//848 615//615 -f 615//615 848//848 849//849 -f 615//615 849//849 608//608 -f 608//608 849//849 838//838 -f 608//608 838//838 610//610 -f 610//610 838//838 839//839 -f 610//610 839//839 603//603 -f 603//603 839//839 840//840 -f 603//603 840//840 604//604 -f 604//604 840//840 841//841 -f 604//604 841//841 600//600 -f 600//600 841//841 842//842 -f 600//600 842//842 616//616 -f 616//616 842//842 843//843 -f 616//616 843//843 617//617 -f 617//617 843//843 844//844 -f 617//617 844//844 618//618 -f 618//618 844//844 845//845 -f 621//621 857//857 619//619 -f 619//619 857//857 858//858 -f 619//619 858//858 624//624 -f 624//624 858//858 859//859 -f 624//624 859//859 625//625 -f 625//625 859//859 860//860 -f 625//625 860//860 626//626 -f 626//626 860//860 861//861 -f 626//626 861//861 627//627 -f 627//627 861//861 850//850 -f 627//627 850//850 609//609 -f 609//609 850//850 851//851 -f 609//609 851//851 606//606 -f 606//606 851//851 852//852 -f 606//606 852//852 607//607 -f 607//607 852//852 853//853 -f 607//607 853//853 613//613 -f 613//613 853//853 854//854 -f 613//613 854//854 611//611 -f 611//611 854//854 855//855 -f 611//611 855//855 622//622 -f 622//622 855//855 856//856 -f 622//622 856//856 621//621 -f 621//621 856//856 857//857 -f 566//566 565//565 890//890 -f 564//564 893//893 565//565 -f 565//565 893//893 892//892 -f 565//565 892//892 890//890 -f 882//882 880//880 563//563 -f 563//563 880//880 879//879 -f 563//563 879//879 564//564 -f 564//564 879//879 886//886 -f 564//564 886//886 893//893 -f 882//882 563//563 884//884 -f 884//884 563//563 561//561 -f 884//884 561//561 885//885 -f 885//885 561//561 875//875 -f 875//875 561//561 560//560 -f 875//875 560//560 877//877 -f 528//528 873//873 560//560 -f 560//560 873//873 878//878 -f 560//560 878//878 877//877 -f 525//525 909//909 528//528 -f 528//528 909//909 908//908 -f 528//528 908//908 873//873 -f 524//524 913//913 525//525 -f 525//525 913//913 911//911 -f 525//525 911//911 909//909 -f 562//562 906//906 524//524 -f 524//524 906//906 907//907 -f 524//524 907//907 913//913 -f 862//862 900//900 571//571 -f 571//571 900//900 902//902 -f 571//571 902//902 562//562 -f 562//562 902//902 904//904 -f 562//562 904//904 906//906 -f 862//862 571//571 863//863 -f 863//863 571//571 570//570 -f 863//863 570//570 899//899 -f 899//899 570//570 896//896 -f 896//896 570//570 569//569 -f 896//896 569//569 898//898 -f 567//567 866//866 569//569 -f 569//569 866//866 865//865 -f 569//569 865//865 898//898 -f 890//890 889//889 566//566 -f 566//566 889//889 870//870 -f 566//566 870//870 567//567 -f 567//567 870//870 894//894 -f 567//567 894//894 866//866 -f 526//526 934//934 554//554 -f 554//554 934//934 935//935 -f 554//554 935//935 555//555 -f 555//555 935//935 936//936 -f 555//555 936//936 557//557 -f 557//557 936//936 937//937 -f 557//557 937//937 558//558 -f 558//558 937//937 938//938 -f 558//558 938//938 559//559 -f 559//559 938//938 939//939 -f 559//559 939//939 539//539 -f 539//539 939//939 940//940 -f 539//539 940//940 537//537 -f 537//537 940//940 941//941 -f 537//537 941//941 535//535 -f 535//535 941//941 942//942 -f 535//535 942//942 533//533 -f 533//533 942//942 943//943 -f 533//533 943//943 540//540 -f 540//540 943//943 944//944 -f 540//540 944//944 541//541 -f 541//541 944//944 945//945 -f 541//541 945//945 542//542 -f 542//542 945//945 946//946 -f 542//542 946//946 568//568 -f 568//568 946//946 947//947 -f 568//568 947//947 544//544 -f 544//544 947//947 948//948 -f 544//544 948//948 545//545 -f 545//545 948//948 949//949 -f 545//545 949//949 551//551 -f 551//551 949//949 950//950 -f 551//551 950//950 552//552 -f 552//552 950//950 951//951 -f 552//552 951//951 553//553 -f 553//553 951//951 952//952 -f 553//553 952//952 531//531 -f 531//531 952//952 953//953 -f 531//531 953//953 532//532 -f 532//532 953//953 954//954 -f 532//532 954//954 547//547 -f 547//547 954//954 955//955 -f 547//547 955//955 549//549 -f 549//549 955//955 956//956 -f 549//549 956//956 550//550 -f 550//550 956//956 957//957 -f 550//550 957//957 529//529 -f 529//529 957//957 958//958 -f 529//529 958//958 527//527 -f 527//527 958//958 959//959 -f 527//527 959//959 526//526 -f 526//526 959//959 934//934 -f 943//943 960//960 944//944 -f 944//944 960//960 961//961 -f 944//944 961//961 945//945 -f 945//945 961//961 962//962 -f 945//945 962//962 946//946 -f 946//946 962//962 963//963 -f 946//946 963//963 947//947 -f 947//947 963//963 964//964 -f 947//947 964//964 948//948 -f 948//948 964//964 965//965 -f 948//948 965//965 949//949 -f 949//949 965//965 966//966 -f 949//949 966//966 950//950 -f 950//950 966//966 967//967 -f 950//950 967//967 951//951 -f 951//951 967//967 968//968 -f 951//951 968//968 952//952 -f 952//952 968//968 969//969 -f 952//952 969//969 953//953 -f 953//953 969//969 970//970 -f 953//953 970//970 954//954 -f 954//954 970//970 971//971 -f 954//954 971//971 955//955 -f 955//955 971//971 972//972 -f 955//955 972//972 956//956 -f 956//956 972//972 973//973 -f 956//956 973//973 957//957 -f 957//957 973//973 974//974 -f 957//957 974//974 958//958 -f 958//958 974//974 975//975 -f 958//958 975//975 959//959 -f 959//959 975//975 976//976 -f 959//959 976//976 934//934 -f 934//934 976//976 977//977 -f 934//934 977//977 935//935 -f 935//935 977//977 978//978 -f 935//935 978//978 936//936 -f 936//936 978//978 979//979 -f 936//936 979//979 937//937 -f 937//937 979//979 980//980 -f 937//937 980//980 938//938 -f 938//938 980//980 981//981 -f 938//938 981//981 939//939 -f 939//939 981//981 982//982 -f 939//939 982//982 940//940 -f 940//940 982//982 983//983 -f 940//940 983//983 941//941 -f 941//941 983//983 984//984 -f 941//941 984//984 942//942 -f 942//942 984//984 985//985 -f 942//942 985//985 943//943 -f 943//943 985//985 960//960 -f 654//654 963//963 655//655 -f 655//655 963//963 962//962 -f 655//655 962//962 633//633 -f 633//633 962//962 961//961 -f 633//633 961//961 634//634 -f 634//634 961//961 960//960 -f 634//634 960//960 660//660 -f 660//660 960//960 985//985 -f 660//660 985//985 661//661 -f 661//661 985//985 984//984 -f 661//661 984//984 663//663 -f 663//663 984//984 983//983 -f 663//663 983//983 664//664 -f 664//664 983//983 982//982 -f 664//664 982//982 643//643 -f 643//643 982//982 981//981 -f 643//643 981//981 645//645 -f 645//645 981//981 980//980 -f 645//645 980//980 647//647 -f 647//647 980//980 979//979 -f 647//647 979//979 650//650 -f 650//650 979//979 978//978 -f 650//650 978//978 651//651 -f 651//651 978//978 977//977 -f 651//651 977//977 630//630 -f 630//630 977//977 976//976 -f 630//630 976//976 656//656 -f 656//656 976//976 975//975 -f 656//656 975//975 657//657 -f 657//657 975//975 974//974 -f 657//657 974//974 637//637 -f 637//637 974//974 973//973 -f 637//637 973//973 638//638 -f 638//638 973//973 972//972 -f 638//638 972//972 639//639 -f 639//639 972//972 971//971 -f 639//639 971//971 665//665 -f 665//665 971//971 970//970 -f 665//665 970//970 666//666 -f 666//666 970//970 969//969 -f 666//666 969//969 667//667 -f 667//667 969//969 968//968 -f 667//667 968//968 668//668 -f 668//668 968//968 967//967 -f 668//668 967//967 669//669 -f 669//669 967//967 966//966 -f 669//669 966//966 652//652 -f 652//652 966//966 965//965 -f 652//652 965//965 653//653 -f 653//653 965//965 964//964 -f 653//653 964//964 654//654 -f 654//654 964//964 963//963 -f 577//577 629//629 578//578 -f 580//580 582//582 986//986 -f 986//986 582//582 987//987 -f 986//986 987//987 988//988 -f 988//988 987//987 989//989 -f 575//575 605//605 576//576 -f 576//576 605//605 987//987 -f 576//576 987//987 628//628 -f 628//628 987//987 582//582 -f 628//628 582//582 640//640 -f 990//990 991//991 992//992 -f 993//993 994//994 991//991 -f 991//991 994//994 995//995 -f 991//991 995//995 992//992 -f 996//996 586//586 587//587 -f 997//997 988//988 989//989 -f 990//990 992//992 998//998 -f 998//998 992//992 999//999 -f 998//998 999//999 1000//1000 -f 995//995 1001//1001 992//992 -f 992//992 1001//1001 996//996 -f 992//992 996//996 1002//1002 -f 1002//1002 996//996 587//587 -f 992//992 1003//1003 999//999 -f 999//999 1003//1003 997//997 -f 999//999 997//997 1004//1004 -f 1004//1004 997//997 989//989 -f 601//601 620//620 1005//1005 -f 1005//1005 620//620 1006//1006 -f 1005//1005 1006//1006 1000//1000 -f 1000//1000 1006//1006 1007//1007 -f 1000//1000 1007//1007 998//998 -f 632//632 631//631 593//593 -f 593//593 631//631 591//591 -f 572//572 579//579 635//635 -f 662//662 573//573 635//635 -f 635//635 573//573 572//572 -f 662//662 642//642 583//583 -f 991//991 1008//1008 993//993 -f 993//993 1008//1008 1009//1009 -f 1008//1008 598//598 574//574 -f 574//574 573//573 1008//1008 -f 1008//1008 573//573 662//662 -f 1008//1008 662//662 1009//1009 -f 1009//1009 662//662 583//583 -f 1009//1009 583//583 584//584 -f 1002//1002 587//587 1010//1010 -f 1010//1010 587//587 581//581 -f 1011//1011 986//986 997//997 -f 997//997 986//986 988//988 -f 1010//1010 581//581 580//580 -f 1012//1012 1010//1010 1013//1013 -f 1013//1013 1010//1010 580//580 -f 1013//1013 580//580 1011//1011 -f 1011//1011 580//580 986//986 -f 1014//1014 987//987 605//605 -f 1015//1015 1014//1014 1016//1016 -f 1016//1016 1014//1014 605//605 -f 1016//1016 605//605 1017//1017 -f 1017//1017 605//605 602//602 -f 1017//1017 602//602 1005//1005 -f 1005//1005 602//602 601//601 -f 1004//1004 989//989 1014//1014 -f 1014//1014 989//989 987//987 -f 1018//1018 599//599 598//598 -f 598//598 1008//1008 1019//1019 -f 1019//1019 1020//1020 598//598 -f 598//598 1020//1020 1021//1021 -f 598//598 1021//1021 1018//1018 -f 1006//1006 620//620 1018//1018 -f 1018//1018 620//620 599//599 -f 1019//1019 1008//1008 990//990 -f 990//990 1008//1008 991//991 -f 1022//1022 1009//1009 584//584 -f 1023//1023 1022//1022 1024//1024 -f 1024//1024 1022//1022 584//584 -f 1024//1024 584//584 1025//1025 -f 1025//1025 584//584 585//585 -f 1025//1025 585//585 996//996 -f 996//996 585//585 586//586 -f 994//994 993//993 1022//1022 -f 1022//1022 993//993 1009//1009 -f 1026//1026 1027//1027 548//548 -f 548//548 1027//1027 546//546 -f 1028//1028 1026//1026 543//543 -f 543//543 1026//1026 548//548 -f 1029//1029 1028//1028 530//530 -f 530//530 1028//1028 543//543 -f 1027//1027 1029//1029 546//546 -f 546//546 1029//1029 530//530 -f 1028//1028 1029//1029 1026//1026 -f 1026//1026 1029//1029 1027//1027 -f 1030//1030 1031//1031 534//534 -f 534//534 1031//1031 536//536 -f 1032//1032 1030//1030 556//556 -f 556//556 1030//1030 534//534 -f 1033//1033 1032//1032 538//538 -f 538//538 1032//1032 556//556 -f 1031//1031 1033//1033 536//536 -f 536//536 1033//1033 538//538 -f 1032//1032 1033//1033 1030//1030 -f 1030//1030 1033//1033 1031//1031 -f 756//756 1034//1034 778//778 -f 778//778 1034//1034 1035//1035 -f 778//778 1035//1035 776//776 -f 776//776 1035//1035 1036//1036 -f 776//776 1036//1036 774//774 -f 774//774 1036//1036 1037//1037 -f 774//774 1037//1037 772//772 -f 772//772 1037//1037 1038//1038 -f 772//772 1038//1038 770//770 -f 770//770 1038//1038 1039//1039 -f 770//770 1039//1039 768//768 -f 768//768 1039//1039 1040//1040 -f 768//768 1040//1040 766//766 -f 766//766 1040//1040 1041//1041 -f 766//766 1041//1041 764//764 -f 764//764 1041//1041 1042//1042 -f 764//764 1042//1042 762//762 -f 762//762 1042//1042 1043//1043 -f 762//762 1043//1043 760//760 -f 760//760 1043//1043 1044//1044 -f 760//760 1044//1044 758//758 -f 758//758 1044//1044 1045//1045 -f 758//758 1045//1045 756//756 -f 756//756 1045//1045 1034//1034 -f 1041//1041 1040//1040 1046//1046 -f 1046//1046 1040//1040 1039//1039 -f 1046//1046 1039//1039 1038//1038 -f 1044//1044 1043//1043 1046//1046 -f 1046//1046 1043//1043 1042//1042 -f 1046//1046 1042//1042 1041//1041 -f 1035//1035 1034//1034 1046//1046 -f 1046//1046 1034//1034 1045//1045 -f 1046//1046 1045//1045 1044//1044 -f 1038//1038 1037//1037 1046//1046 -f 1046//1046 1037//1037 1036//1036 -f 1046//1046 1036//1036 1035//1035 -f 1025//1025 996//996 1024//1024 -f 1024//1024 996//996 1001//1001 -f 1024//1024 1001//1001 1023//1023 -f 1023//1023 1001//1001 995//995 -f 1023//1023 995//995 1022//1022 -f 1022//1022 995//995 994//994 -f 1006//1006 1018//1018 1007//1007 -f 1007//1007 1018//1018 1021//1021 -f 1007//1007 1021//1021 998//998 -f 998//998 1021//1021 1020//1020 -f 998//998 1020//1020 990//990 -f 990//990 1020//1020 1019//1019 -f 1017//1017 1005//1005 1016//1016 -f 1016//1016 1005//1005 1000//1000 -f 1016//1016 1000//1000 1015//1015 -f 1015//1015 1000//1000 999//999 -f 1015//1015 999//999 1014//1014 -f 1014//1014 999//999 1004//1004 -f 1002//1002 1010//1010 992//992 -f 992//992 1010//1010 1012//1012 -f 992//992 1012//1012 1003//1003 -f 1003//1003 1012//1012 1013//1013 -f 1003//1003 1013//1013 997//997 -f 997//997 1013//1013 1011//1011 -f 583//583 642//642 644//644 -f 583//583 644//644 594//594 -f 594//594 644//644 646//646 -f 594//594 646//646 588//588 -f 588//588 646//646 648//648 -f 588//588 648//648 589//589 -f 589//589 648//648 649//649 -f 589//589 649//649 590//590 -f 590//590 649//649 632//632 -f 590//590 632//632 593//593 -f 640//640 582//582 597//597 -f 640//640 597//597 641//641 -f 641//641 597//597 596//596 -f 641//641 596//596 636//636 -f 636//636 596//596 595//595 -f 636//636 595//595 659//659 -f 659//659 595//595 592//592 -f 659//659 592//592 658//658 -f 658//658 592//592 591//591 -f 658//658 591//591 631//631 -# 2084 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sablja_base.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sablja_base.obj deleted file mode 100644 index 6f5a11b7a..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sablja_base.obj +++ /dev/null @@ -1,2924 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sablja_base.obj -# -# Vertices: 710 -# Faces: 1488 -# -#### -vn 4.712389 1.570796 1.570796 -v 0.097000 -0.018800 0.035723 -vn 3.403392 -0.406550 3.088069 -v 0.097000 -0.013600 0.035723 -vn 0.000000 3.141593 3.141593 -v 0.095500 -0.018800 0.035723 -vn -3.403391 -0.406551 3.088070 -v 0.095300 -0.013600 0.035723 -vn -1.570796 4.712389 1.570796 -v 0.095300 -0.018800 0.035723 -vn 3.403389 0.406548 3.088070 -v 0.097000 0.008600 0.035723 -vn 4.712389 -1.570791 1.570796 -v 0.097000 0.013800 0.035723 -vn -3.403389 0.406548 3.088070 -v 0.095300 0.008600 0.035723 -vn -1.570796 -4.712394 1.570796 -v 0.095300 0.013800 0.035723 -vn -3.128154 -3.272492 0.205032 -v 0.093500 0.013800 0.033923 -vn -3.128154 3.272493 0.205031 -v 0.093500 0.017500 0.033923 -vn -3.008584 -3.403392 0.806150 -v 0.093108 0.013800 0.030946 -vn -3.008584 3.403392 0.806150 -v 0.093108 0.017500 0.030946 -vn -2.697423 -3.403390 1.557358 -v 0.091959 0.013800 0.028173 -vn -2.697423 3.403390 1.557358 -v 0.091959 0.017500 0.028173 -vn -2.202438 -3.403393 2.202435 -v 0.090132 0.013800 0.025791 -vn -2.202438 3.403393 2.202435 -v 0.090132 0.017500 0.025791 -vn -1.557358 -3.403392 2.697423 -v 0.087750 0.013800 0.023963 -vn -1.557358 3.403392 2.697423 -v 0.087750 0.017500 0.023963 -vn -0.950476 -3.310008 2.982680 -v 0.084976 0.013800 0.022815 -vn -0.827284 3.374207 3.005500 -v 0.084976 0.017500 0.022815 -vn -0.640641 -0.240650 6.230138 -v 0.084135 0.013800 0.022623 -vn 0.014557 3.368759 3.117658 -v 0.082000 0.017500 0.022423 -vn -0.146478 0.093386 6.276341 -v 0.084135 0.013500 0.022623 -vn -0.000001 2.954821 3.127904 -v 0.082000 0.013500 0.022423 -vn 0.146477 0.093386 6.276340 -v 0.079865 0.013500 0.022623 -vn 0.707737 -0.382054 6.208646 -v 0.079865 0.013800 0.022623 -vn 0.888066 -3.377357 2.994882 -v 0.079024 0.013800 0.022815 -vn 0.806148 3.403393 3.008584 -v 0.079024 0.017500 0.022815 -vn 1.557359 -3.403391 2.697422 -v 0.076250 0.013800 0.023963 -vn 1.557359 3.403391 2.697422 -v 0.076250 0.017500 0.023963 -vn 2.202436 -3.403385 2.202438 -v 0.073868 0.013800 0.025791 -vn 2.202436 3.403384 2.202438 -v 0.073868 0.017500 0.025791 -vn 2.697422 -3.403396 1.557360 -v 0.072041 0.013800 0.028173 -vn 2.697422 3.403394 1.557360 -v 0.072041 0.017500 0.028173 -vn 3.008584 -3.403394 0.806146 -v 0.070892 0.013800 0.030946 -vn 3.008584 3.403394 0.806146 -v 0.070892 0.017500 0.030946 -vn 3.128155 -3.272488 0.205028 -v 0.070500 0.013800 0.033923 -vn 3.128155 3.272491 0.205028 -v 0.070500 0.017500 0.033923 -vn -1.570797 -1.570795 1.570796 -v 0.095300 0.013800 0.022623 -vn -3.665188 2.627991 1.517269 -v 0.095300 0.008340 0.035873 -vn -1.570804 1.570796 1.570799 -v 0.095300 -0.018800 0.022623 -vn -3.665184 -1.517262 2.628003 -v 0.095300 -0.013450 0.035763 -vn -3.665190 1.517264 2.627999 -v 0.095300 0.008450 0.035763 -vn -3.141593 3.141593 0.000000 -v 0.095300 -0.018800 0.027123 -vn -3.403386 -3.088071 0.406543 -v 0.095300 -0.013300 0.036023 -vn -1.570796 -1.570796 1.570796 -v 0.095300 -0.013300 0.045723 -vn -1.570796 1.570796 1.570796 -v 0.095300 0.008300 0.045723 -vn -3.665205 -2.627986 1.517273 -v 0.095300 -0.013340 0.035873 -vn -3.403387 3.088071 0.406543 -v 0.095300 0.008300 0.036023 -vn -1.570796 1.570796 1.570796 -v 0.067000 -0.018800 0.060123 -vn -1.570796 -1.570796 1.570795 -v 0.067000 -0.022700 0.060123 -vn 0.000000 3.141592 3.141592 -v 0.067125 -0.018800 0.060123 -vn 0.000000 -3.141592 3.141593 -v 0.067125 -0.022700 0.060123 -vn 1.570796 1.570795 1.570796 -v 0.072000 -0.018800 0.060123 -vn 1.570796 -1.570795 1.570796 -v 0.072000 -0.022700 0.060123 -vn 1.570796 1.570796 1.570796 -v 0.070500 0.017500 0.060123 -vn -1.570796 1.570796 1.570796 -v 0.067000 0.017500 0.060123 -vn 1.570797 -1.570791 1.570796 -v 0.070500 0.013800 0.060123 -vn -1.570797 -1.570792 1.570796 -v 0.067000 0.013800 0.060123 -vn -6.218603 0.289185 0.670605 -v 0.070000 -0.018925 0.019623 -vn -2.878572 1.117543 3.511913 -v 0.069661 -0.020735 0.019623 -vn -1.551930 -1.415652 4.955112 -v 0.070000 -0.022700 0.019623 -vn -2.278992 2.083576 3.511907 -v 0.068690 -0.022299 0.019623 -vn 2.178755 -2.178759 2.748893 -v 0.095536 -0.038536 0.019623 -vn 2.846683 -1.179138 2.748895 -v 0.096619 -0.036914 0.019623 -vn 3.111410 -0.306450 2.945242 -v 0.097000 -0.035000 0.019623 -vn 0.000000 -3.034546 3.665191 -v 0.067000 -0.032455 0.019623 -vn -1.641505 2.662841 3.326750 -v 0.067219 -0.023406 0.019623 -vn -1.641501 2.662843 2.956438 -v 0.066781 -0.023623 0.019623 -vn -1.517273 2.627994 3.665191 -v 0.088125 -0.036654 0.019623 -vn 0.306447 -3.111410 2.945242 -v 0.092000 -0.040000 0.019623 -vn -2.627993 1.517274 3.665190 -v 0.088949 -0.035830 0.019623 -vn 1.179133 -2.846684 2.748895 -v 0.093913 -0.039620 0.019623 -vn -3.034545 0.000001 3.665193 -v 0.089250 -0.034705 0.019623 -vn -2.627994 -1.517273 3.665192 -v 0.068949 -0.033580 0.019623 -vn 0.000000 -3.141592 3.141593 -v 0.082000 -0.022700 0.019623 -vn -1.517273 -2.627994 3.665191 -v 0.068125 -0.032757 0.019623 -vn -2.627993 1.517274 3.665190 -v 0.068949 -0.035830 0.019623 -vn -0.306447 -3.111411 2.945243 -v 0.069000 -0.040000 0.019623 -vn -1.517273 2.627994 3.665191 -v 0.068125 -0.036654 0.019623 -vn -1.179134 -2.846684 2.748895 -v 0.067087 -0.039620 0.019623 -vn 0.000000 3.034546 3.665191 -v 0.067000 -0.036955 0.019623 -vn -2.178755 -2.178759 2.748893 -v 0.065464 -0.038536 0.019623 -vn 1.517273 2.627994 3.665191 -v 0.065875 -0.036654 0.019623 -vn -2.846684 -1.179132 2.748891 -v 0.064381 -0.036914 0.019623 -vn 2.627993 1.517274 3.665191 -v 0.065051 -0.035830 0.019623 -vn -3.111411 -0.306444 2.945245 -v 0.064000 -0.035000 0.019623 -vn 3.034545 0.000001 3.665192 -v 0.064750 -0.034705 0.019623 -vn -3.114744 0.289185 2.956434 -v 0.064000 -0.028104 0.019623 -vn -2.627994 -1.517273 3.665191 -v 0.088949 -0.033580 0.019623 -vn 4.712382 -1.570796 1.570796 -v 0.097000 -0.022700 0.019623 -vn -1.517273 -2.627994 3.665191 -v 0.088125 -0.032757 0.019623 -vn 0.000000 -3.141593 3.141593 -v 0.095500 -0.022700 0.019623 -vn 0.000000 -3.034546 3.665192 -v 0.087000 -0.032455 0.019623 -vn 0.000000 3.034546 3.665192 -v 0.087000 -0.036955 0.019623 -vn 1.517273 2.627994 3.665191 -v 0.085875 -0.036654 0.019623 -vn 2.627993 1.517274 3.665190 -v 0.085051 -0.035830 0.019623 -vn -3.034545 0.000001 3.665192 -v 0.069250 -0.034705 0.019623 -vn 3.034545 0.000001 3.665193 -v 0.084750 -0.034705 0.019623 -vn 2.627994 -1.517273 3.665191 -v 0.085051 -0.033580 0.019623 -vn 1.517273 -2.627994 3.665191 -v 0.085875 -0.032757 0.019623 -vn 2.627994 -1.517273 3.665192 -v 0.065051 -0.033580 0.019623 -vn 1.517273 -2.627994 3.665191 -v 0.065875 -0.032757 0.019623 -vn -2.878575 1.117539 2.771275 -v 0.064339 -0.026294 0.019623 -vn -2.278991 2.083575 2.771273 -v 0.065310 -0.024730 0.019623 -vn 0.000000 3.141593 3.141597 -v 0.096875 0.017500 0.019623 -vn -2.627994 1.517273 3.665191 -v 0.068949 0.033580 0.019623 -vn 0.000000 3.141593 3.141595 -v 0.082000 0.017500 0.019623 -vn -1.517273 2.627994 3.665191 -v 0.068125 0.032756 0.019623 -vn -1.517273 2.627994 3.665191 -v 0.088125 0.032756 0.019623 -vn -2.627994 1.517273 3.665200 -v 0.088949 0.033580 0.019623 -vn 4.712389 1.570792 1.570796 -v 0.097000 0.017500 0.019623 -vn -3.034545 -0.000001 3.665193 -v 0.089250 0.034705 0.019623 -vn 3.111410 0.306450 2.945241 -v 0.097000 0.035000 0.019623 -vn 0.000000 3.034546 3.665192 -v 0.087000 0.032455 0.019623 -vn 1.517273 2.627994 3.665191 -v 0.085875 0.032756 0.019623 -vn 2.627994 1.517273 3.665192 -v 0.085051 0.033580 0.019623 -vn -3.034545 -0.000001 3.665193 -v 0.069250 0.034705 0.019623 -vn 3.034545 -0.000001 3.665192 -v 0.084750 0.034705 0.019623 -vn -2.627993 -1.517274 3.665190 -v 0.068949 0.035830 0.019623 -vn 2.846683 1.179138 2.748895 -v 0.096619 0.036913 0.019623 -vn 2.178755 2.178759 2.748893 -v 0.095536 0.038535 0.019623 -vn -2.627993 -1.517274 3.665190 -v 0.088949 0.035830 0.019623 -vn 1.179134 2.846684 2.748895 -v 0.093913 0.039619 0.019623 -vn -1.517273 -2.627994 3.665192 -v 0.088125 0.036653 0.019623 -vn 0.306447 3.111411 2.945243 -v 0.092000 0.040000 0.019623 -vn 0.000000 -3.034546 3.665192 -v 0.087000 0.036955 0.019623 -vn -0.306447 3.111410 2.945243 -v 0.069000 0.040000 0.019623 -vn 1.517273 -2.627994 3.665191 -v 0.085875 0.036653 0.019623 -vn -3.114743 -0.289185 2.956436 -v 0.064000 0.028103 0.019623 -vn 2.627994 1.517273 3.665191 -v 0.065051 0.033580 0.019623 -vn -3.111411 0.306444 2.945245 -v 0.064000 0.035000 0.019623 -vn 3.034545 -0.000001 3.665193 -v 0.064750 0.034705 0.019623 -vn -2.846684 1.179132 2.748891 -v 0.064381 0.036913 0.019623 -vn 2.627993 -1.517274 3.665191 -v 0.065051 0.035830 0.019623 -vn -2.178755 2.178759 2.748893 -v 0.065464 0.038535 0.019623 -vn 1.517273 -2.627994 3.665191 -v 0.065875 0.036653 0.019623 -vn -1.179133 2.846684 2.748895 -v 0.067087 0.039619 0.019623 -vn 0.000000 -3.034546 3.665192 -v 0.067000 0.036955 0.019623 -vn -1.517273 -2.627994 3.665191 -v 0.068125 0.036653 0.019623 -vn 2.627993 -1.517274 3.665191 -v 0.085051 0.035830 0.019623 -vn -4.693522 1.415651 1.813521 -v 0.070000 0.017500 0.019623 -vn -3.114743 -0.289185 3.326750 -v 0.070000 0.018925 0.019623 -vn -2.878572 -1.117543 3.511912 -v 0.069661 0.020735 0.019623 -vn -2.878575 -1.117539 2.771275 -v 0.064339 0.026294 0.019623 -vn 0.000000 3.034546 3.665191 -v 0.067000 0.032455 0.019623 -vn 1.517273 2.627994 3.665191 -v 0.065875 0.032756 0.019623 -vn -2.278992 -2.083576 3.511907 -v 0.068690 0.022299 0.019623 -vn -1.641505 -2.662840 3.326749 -v 0.067219 0.023406 0.019623 -vn -1.641501 -2.662843 2.956438 -v 0.066781 0.023623 0.019623 -vn -2.278991 -2.083575 2.771273 -v 0.065310 0.024729 0.019623 -vn -3.111411 0.306444 -2.945245 -v 0.064000 0.035000 0.015623 -vn -3.114744 -0.289185 -2.956435 -v 0.064000 0.028103 0.015623 -vn -2.627993 -1.517274 -3.665190 -v 0.068949 0.035830 0.015623 -vn -1.517273 -2.627994 -3.665191 -v 0.068125 0.036653 0.015623 -vn -0.306447 3.111411 -2.945243 -v 0.069000 0.040000 0.015623 -vn -2.627994 -1.517273 -3.665191 -v 0.068949 -0.033580 0.015623 -vn -1.517273 -2.627994 -3.665189 -v 0.068125 -0.032757 0.015623 -vn 1.517273 2.627994 -3.665192 -v 0.085875 0.032756 0.015623 -vn -0.000000 -3.034546 -3.665192 -v 0.067000 -0.032455 0.015623 -vn 3.034545 -0.000001 -3.665236 -v 0.084750 0.034705 0.015623 -vn 2.627994 1.517273 -3.665191 -v 0.085051 0.033580 0.015623 -vn -1.179134 2.846684 -2.748895 -v 0.067087 0.039619 0.015623 -vn -0.000000 -3.034546 -3.665191 -v 0.067000 0.036955 0.015623 -vn -2.178755 2.178759 -2.748893 -v 0.065464 0.038535 0.015623 -vn 1.517273 -2.627994 -3.665191 -v 0.065875 0.036653 0.015623 -vn -2.846684 1.179132 -2.748891 -v 0.064381 0.036913 0.015623 -vn 2.627993 -1.517274 -3.665191 -v 0.065051 0.035830 0.015623 -vn 3.034545 -0.000001 -3.665192 -v 0.064750 0.034705 0.015623 -vn -2.627994 -1.517273 -3.665192 -v 0.088949 -0.033580 0.015623 -vn 0.000000 3.034546 -3.665191 -v 0.087000 0.032455 0.015623 -vn -3.034545 0.000001 -3.665190 -v 0.089250 -0.034705 0.015623 -vn -1.517273 2.627994 -3.665191 -v 0.088125 0.032756 0.015623 -vn 3.111409 -0.306450 -2.945241 -v 0.097000 -0.035000 0.015623 -vn 3.111410 0.306450 -2.945241 -v 0.097000 0.035000 0.015623 -vn -2.627994 1.517273 -3.665191 -v 0.088949 0.033580 0.015623 -vn -3.034545 -0.000001 -3.665193 -v 0.089250 0.034705 0.015623 -vn 1.517273 2.627994 -3.665191 -v 0.085875 -0.036654 0.015623 -vn 0.000000 3.034546 -3.665192 -v 0.087000 -0.036955 0.015623 -vn 0.306447 -3.111411 -2.945240 -v 0.092000 -0.040000 0.015623 -vn -1.517273 2.627994 -3.665192 -v 0.088125 -0.036654 0.015623 -vn 1.179134 -2.846684 -2.748895 -v 0.093913 -0.039620 0.015623 -vn -2.627993 1.517274 -3.665190 -v 0.088949 -0.035830 0.015623 -vn 2.178755 -2.178759 -2.748893 -v 0.095536 -0.038536 0.015623 -vn 2.846683 -1.179138 -2.748895 -v 0.096619 -0.036914 0.015623 -vn 0.306447 3.111410 -2.945243 -v 0.092000 0.040000 0.015623 -vn 1.179134 2.846684 -2.748895 -v 0.093913 0.039619 0.015623 -vn -2.627993 -1.517274 -3.665190 -v 0.088949 0.035830 0.015623 -vn 2.178755 2.178759 -2.748893 -v 0.095536 0.038535 0.015623 -vn 2.846683 1.179138 -2.748895 -v 0.096619 0.036913 0.015623 -vn -3.114743 0.289185 -2.956435 -v 0.064000 -0.028104 0.015623 -vn 2.627994 -1.517273 -3.665191 -v 0.065051 -0.033580 0.015623 -vn -3.111411 -0.306444 -2.945245 -v 0.064000 -0.035000 0.015623 -vn 3.034545 0.000001 -3.665193 -v 0.064750 -0.034705 0.015623 -vn -2.846684 -1.179132 -2.748891 -v 0.064381 -0.036914 0.015623 -vn 2.627993 1.517274 -3.665191 -v 0.065051 -0.035830 0.015623 -vn -2.178755 -2.178759 -2.748893 -v 0.065464 -0.038536 0.015623 -vn 1.517273 2.627994 -3.665191 -v 0.065875 -0.036654 0.015623 -vn -1.179134 -2.846684 -2.748895 -v 0.067087 -0.039620 0.015623 -vn 0.000000 3.034546 -3.665192 -v 0.067000 -0.036955 0.015623 -vn -0.306447 -3.111410 -2.945243 -v 0.069000 -0.040000 0.015623 -vn -1.517273 2.627994 -3.665191 -v 0.068125 -0.036654 0.015623 -vn -2.627993 1.517274 -3.665189 -v 0.068949 -0.035830 0.015623 -vn 0.000000 3.034546 -3.665191 -v 0.067000 0.032455 0.015623 -vn -1.641505 -2.662841 -3.326750 -v 0.067219 0.023406 0.015623 -vn -1.641501 -2.662843 -2.956438 -v 0.066781 0.023623 0.015623 -vn -1.517273 -2.627994 -3.665191 -v 0.088125 -0.032757 0.015623 -vn -0.000000 -3.034546 -3.665188 -v 0.087000 -0.032455 0.015623 -vn 1.517273 -2.627994 -3.665191 -v 0.085875 -0.032757 0.015623 -vn 2.627994 -1.517273 -3.665192 -v 0.085051 -0.033580 0.015623 -vn -3.034545 0.000001 -3.665193 -v 0.069250 -0.034705 0.015623 -vn 3.034545 0.000001 -3.665192 -v 0.084750 -0.034705 0.015623 -vn 2.627993 1.517274 -3.665191 -v 0.085051 -0.035830 0.015623 -vn -1.641501 2.662843 -2.956438 -v 0.066781 -0.023623 0.015623 -vn -1.641505 2.662840 -3.326750 -v 0.067219 -0.023406 0.015623 -vn -2.278992 2.083576 -3.511907 -v 0.068690 -0.022299 0.015623 -vn -2.878572 1.117543 -3.511912 -v 0.069661 -0.020735 0.015623 -vn -3.114743 0.289185 -3.326750 -v 0.070000 -0.018925 0.015623 -vn -3.114744 -0.289185 -3.326748 -v 0.070000 0.018925 0.015623 -vn -1.517273 -2.627994 -3.665191 -v 0.088125 0.036653 0.015623 -vn -0.000000 -3.034546 -3.665192 -v 0.087000 0.036955 0.015623 -vn 1.517273 -2.627994 -3.665191 -v 0.085875 0.036653 0.015623 -vn 2.627993 -1.517274 -3.665190 -v 0.085051 0.035830 0.015623 -vn -3.034545 -0.000001 -3.665192 -v 0.069250 0.034705 0.015623 -vn -2.627994 1.517273 -3.665191 -v 0.068949 0.033580 0.015623 -vn -1.517273 2.627994 -3.665195 -v 0.068125 0.032756 0.015623 -vn -2.878572 -1.117543 -3.511915 -v 0.069661 0.020735 0.015623 -vn -2.278992 -2.083576 -3.511907 -v 0.068690 0.022299 0.015623 -vn 2.627994 1.517273 -3.665191 -v 0.065051 0.033580 0.015623 -vn 1.517273 2.627994 -3.665192 -v 0.065875 0.032756 0.015623 -vn -2.878575 -1.117539 -2.771276 -v 0.064339 0.026294 0.015623 -vn -2.278991 -2.083575 -2.771273 -v 0.065310 0.024729 0.015623 -vn -2.278991 2.083575 -2.771273 -v 0.065310 -0.024730 0.015623 -vn -2.878575 1.117539 -2.771275 -v 0.064339 -0.026294 0.015623 -vn 1.517273 -2.627994 -3.665191 -v 0.065875 -0.032757 0.015623 -vn 3.665190 1.517264 2.627999 -v 0.097000 0.008450 0.035763 -vn 3.665189 2.627991 1.517268 -v 0.097000 0.008340 0.035873 -vn 1.570797 -1.570800 1.570796 -v 0.097000 0.013800 0.060123 -vn 3.141593 3.141597 0.000000 -v 0.097000 0.017500 0.044873 -vn 3.141593 3.141590 0.000000 -v 0.097000 0.017500 0.052873 -vn 3.141593 3.141593 0.000000 -v 0.097000 0.017500 0.059123 -vn 1.570796 1.570796 1.570796 -v 0.097000 0.017500 0.060123 -vn 3.141593 3.141597 0.000000 -v 0.097000 0.017500 0.036873 -vn 3.403386 3.088071 0.406543 -v 0.097000 0.008300 0.036023 -vn 1.570796 1.570796 1.570796 -v 0.097000 0.008300 0.045723 -vn 1.570796 -1.570796 1.570796 -v 0.097000 -0.013300 0.045723 -vn 1.570796 1.570797 1.570796 -v 0.097000 -0.018800 0.060123 -vn 1.570796 -1.570797 1.570796 -v 0.097000 -0.022700 0.060123 -vn 3.141593 3.141599 0.000000 -v 0.097000 -0.018800 0.052873 -vn 3.141593 -3.141599 0.000000 -v 0.097000 -0.022700 0.052873 -vn 3.141593 3.141599 0.000000 -v 0.097000 -0.018800 0.044873 -vn 3.141593 -3.141599 0.000000 -v 0.097000 -0.022700 0.044873 -vn 3.141593 3.141596 0.000000 -v 0.097000 -0.018800 0.036873 -vn 3.141593 -3.141595 0.000000 -v 0.097000 -0.022700 0.036873 -vn 3.141593 -3.141592 0.000000 -v 0.097000 -0.022700 0.025623 -vn 3.665184 -1.517262 2.628003 -v 0.097000 -0.013450 0.035763 -vn 3.665205 -2.627986 1.517273 -v 0.097000 -0.013340 0.035873 -vn 3.403387 -3.088071 0.406543 -v 0.097000 -0.013300 0.036023 -vn -4.586720 -1.928912 0.584267 -v 0.070157 0.013800 0.022623 -vn 0.000000 3.141593 3.141592 -v 0.082000 -0.018800 0.022623 -vn -4.567143 2.010690 0.536664 -v 0.070157 -0.018800 0.022623 -vn -3.141593 3.141593 0.000000 -v 0.067000 0.017500 0.059123 -vn -3.141593 3.141597 0.000000 -v 0.067000 0.017500 0.052873 -vn -3.141593 3.141597 0.000000 -v 0.067000 0.017500 0.044873 -vn -3.107458 -2.932734 -0.325688 -v 0.067000 0.013800 0.028839 -vn -3.141593 3.141597 0.000000 -v 0.067000 0.017500 0.036873 -vn -3.107458 2.932739 -0.325688 -v 0.067000 0.017500 0.028839 -vn -1.570796 1.570796 1.570796 -v 0.093500 0.017500 0.060123 -vn -1.570797 -1.570784 1.570796 -v 0.093500 0.013800 0.060123 -vn 0.000000 3.141593 3.141593 -v 0.096875 0.017500 0.060123 -vn 0.000000 -3.141593 3.141593 -v 0.095500 -0.022700 0.060123 -vn 0.000000 3.141593 3.141593 -v 0.095500 -0.018800 0.060123 -vn -1.570796 -1.570795 1.570796 -v 0.092000 -0.022700 0.060123 -vn -1.570796 1.570795 1.570796 -v 0.092000 -0.018800 0.060123 -vn -3.138673 3.080607 -0.095735 -v 0.067000 -0.018800 0.028839 -vn -3.138672 -3.080607 -0.095735 -v 0.067000 -0.022700 0.028839 -vn -3.141593 3.141593 0.000000 -v 0.067000 -0.018800 0.036873 -vn -3.141593 -3.141593 0.000000 -v 0.067000 -0.022700 0.036873 -vn -3.141593 3.141591 0.000000 -v 0.067000 -0.018800 0.044873 -vn -3.141593 -3.141591 0.000000 -v 0.067000 -0.022700 0.044873 -vn -3.141593 3.141591 0.000000 -v 0.067000 -0.018800 0.052873 -vn -3.141593 -3.141591 0.000000 -v 0.067000 -0.022700 0.052873 -vn 2.971477 3.295769 -0.990652 -v 0.076082 -0.018800 0.036610 -vn 2.971478 -3.295769 -0.990652 -v 0.076082 -0.022700 0.036610 -vn 3.083799 3.504696 -0.195030 -v 0.075513 -0.018800 0.034333 -vn 3.083799 -3.504696 -0.195030 -v 0.075513 -0.022700 0.034333 -vn 2.952007 3.504691 0.912972 -v 0.075790 -0.018800 0.032002 -vn 2.952007 -3.504690 0.912972 -v 0.075790 -0.022700 0.032002 -vn 2.435271 3.504696 1.901922 -v 0.076877 -0.018800 0.029922 -vn 2.435271 -3.504695 1.901922 -v 0.076877 -0.022700 0.029922 -vn 1.600971 3.504698 2.642867 -v 0.078632 -0.018800 0.028363 -vn 1.600971 -3.504695 2.642867 -v 0.078632 -0.022700 0.028363 -vn 0.557906 3.504691 3.039177 -v 0.080826 -0.018800 0.027530 -vn 0.557906 -3.504693 3.039177 -v 0.080826 -0.022700 0.027530 -vn -0.557908 3.504694 3.039176 -v 0.083174 -0.018800 0.027530 -vn -0.557908 -3.504694 3.039176 -v 0.083174 -0.022700 0.027530 -vn -1.600972 3.504695 2.642866 -v 0.085368 -0.018800 0.028363 -vn -1.600972 -3.504694 2.642866 -v 0.085368 -0.022700 0.028363 -vn -2.435269 3.504693 1.901926 -v 0.087123 -0.018800 0.029922 -vn -2.435269 -3.504693 1.901926 -v 0.087123 -0.022700 0.029922 -vn -2.952005 3.504696 0.912971 -v 0.088210 -0.018800 0.032002 -vn -2.952005 -3.504696 0.912971 -v 0.088210 -0.022700 0.032002 -vn -3.083800 3.504693 -0.195035 -v 0.088487 -0.018800 0.034333 -vn -3.083800 -3.504693 -0.195035 -v 0.088487 -0.022700 0.034333 -vn -3.049986 3.136308 -0.753073 -v 0.087918 -0.018800 0.036610 -vn -3.049986 -3.136308 -0.753073 -v 0.087918 -0.022700 0.036610 -vn -2.579226 2.954761 1.769554 -v 0.088630 -0.018800 0.041879 -vn -2.579226 -2.954760 1.769554 -v 0.088630 -0.022700 0.041879 -vn -2.777516 3.836333 1.005599 -v 0.092000 -0.018800 0.045923 -vn -2.777516 -3.836330 1.005599 -v 0.092000 -0.022700 0.045923 -vn -3.141593 3.141594 0.000000 -v 0.092000 -0.018800 0.052873 -vn -3.141593 -3.141594 0.000000 -v 0.092000 -0.022700 0.052873 -vn 2.777515 3.836332 1.005600 -v 0.072000 -0.018800 0.045923 -vn 2.777515 -3.836333 1.005600 -v 0.072000 -0.022700 0.045923 -vn 2.413438 3.141593 2.011199 -v 0.072875 -0.018800 0.044873 -vn 2.413438 -3.141592 2.011199 -v 0.072875 -0.022700 0.044873 -vn 2.579226 2.954761 1.769553 -v 0.075370 -0.018800 0.041879 -vn 2.579226 -2.954761 1.769553 -v 0.075370 -0.022700 0.041879 -vn 3.141593 3.141594 0.000000 -v 0.072000 -0.018800 0.052873 -vn 3.141593 -3.141594 0.000000 -v 0.072000 -0.022700 0.052873 -vn -3.082653 -2.767929 -0.162279 -v 0.087478 -0.022700 0.038415 -vn -3.082653 2.767929 -0.162279 -v 0.087478 -0.018800 0.038415 -vn -2.929172 -2.767925 0.974182 -v 0.087726 -0.022700 0.040256 -vn -2.929171 2.767924 0.974182 -v 0.087726 -0.018800 0.040256 -vn 3.092274 -2.795294 -0.120386 -v 0.076522 -0.022700 0.038415 -vn 2.929172 2.767925 0.974182 -v 0.076274 -0.018800 0.040256 -vn 2.929171 -2.767925 0.974182 -v 0.076274 -0.022700 0.040256 -vn 2.983088 -2.954765 -0.940700 -v 0.076188 -0.022700 0.036862 -vn 2.983088 2.954768 -0.940700 -v 0.076188 -0.018800 0.036862 -vn 3.092274 2.795294 -0.120386 -v 0.076522 -0.018800 0.038415 -vn -3.034548 3.665186 -0.000002 -v 0.069750 -0.018800 0.056873 -vn -3.034548 -3.665186 -0.000002 -v 0.069750 -0.022700 0.056873 -vn -2.627990 3.665197 -1.517274 -v 0.069583 -0.018800 0.057498 -vn -2.627990 -3.665197 -1.517274 -v 0.069583 -0.022700 0.057498 -vn -1.517274 3.665184 -2.627997 -v 0.069125 -0.018800 0.057955 -vn -1.517273 -3.665184 -2.627996 -v 0.069125 -0.022700 0.057955 -vn 0.000000 3.665198 -3.034543 -v 0.068500 -0.018800 0.058123 -vn -0.000000 -3.665198 -3.034543 -v 0.068500 -0.022700 0.058123 -vn 1.517273 3.665184 -2.627996 -v 0.067875 -0.018800 0.057955 -vn 1.517274 -3.665184 -2.627997 -v 0.067875 -0.022700 0.057955 -vn 2.627990 3.665197 -1.517274 -v 0.067417 -0.018800 0.057498 -vn 2.627990 -3.665197 -1.517274 -v 0.067417 -0.022700 0.057498 -vn 3.034548 3.665186 -0.000002 -v 0.067250 -0.018800 0.056873 -vn 3.034548 -3.665186 -0.000002 -v 0.067250 -0.022700 0.056873 -vn 2.627990 3.665199 1.517272 -v 0.067417 -0.018800 0.056248 -vn 2.627990 -3.665199 1.517272 -v 0.067417 -0.022700 0.056248 -vn 1.517274 3.665184 2.627997 -v 0.067875 -0.018800 0.055790 -vn 1.517273 -3.665184 2.627996 -v 0.067875 -0.022700 0.055790 -vn -0.000000 3.665199 3.034543 -v 0.068500 -0.018800 0.055623 -vn 0.000000 -3.665198 3.034543 -v 0.068500 -0.022700 0.055623 -vn -1.517273 3.665184 2.627996 -v 0.069125 -0.018800 0.055790 -vn -1.517274 -3.665184 2.627997 -v 0.069125 -0.022700 0.055790 -vn -2.627990 3.665199 1.517272 -v 0.069583 -0.018800 0.056248 -vn -2.627990 -3.665199 1.517272 -v 0.069583 -0.022700 0.056248 -vn -3.034547 3.665187 -0.000000 -v 0.069750 -0.018800 0.048873 -vn -3.034547 -3.665187 0.000000 -v 0.069750 -0.022700 0.048873 -vn -2.627994 3.665194 -1.517270 -v 0.069583 -0.018800 0.049498 -vn -2.627994 -3.665194 -1.517270 -v 0.069583 -0.022700 0.049498 -vn -1.517270 3.665194 -2.627994 -v 0.069125 -0.018800 0.049955 -vn -1.517270 -3.665194 -2.627994 -v 0.069125 -0.022700 0.049955 -vn 0.000000 3.665187 -3.034547 -v 0.068500 -0.018800 0.050123 -vn -0.000000 -3.665187 -3.034547 -v 0.068500 -0.022700 0.050123 -vn 1.517270 3.665194 -2.627994 -v 0.067875 -0.018800 0.049955 -vn 1.517270 -3.665194 -2.627994 -v 0.067875 -0.022700 0.049955 -vn 2.627994 3.665193 -1.517270 -v 0.067417 -0.018800 0.049498 -vn 2.627994 -3.665193 -1.517270 -v 0.067417 -0.022700 0.049498 -vn 3.034547 3.665188 0.000000 -v 0.067250 -0.018800 0.048873 -vn 3.034547 -3.665188 -0.000000 -v 0.067250 -0.022700 0.048873 -vn 2.627994 3.665193 1.517270 -v 0.067417 -0.018800 0.048248 -vn 2.627994 -3.665193 1.517270 -v 0.067417 -0.022700 0.048248 -vn 1.517270 3.665194 2.627994 -v 0.067875 -0.018800 0.047790 -vn 1.517270 -3.665194 2.627994 -v 0.067875 -0.022700 0.047790 -vn -0.000000 3.665187 3.034547 -v 0.068500 -0.018800 0.047623 -vn 0.000000 -3.665187 3.034547 -v 0.068500 -0.022700 0.047623 -vn -1.517270 3.665194 2.627994 -v 0.069125 -0.018800 0.047790 -vn -1.517270 -3.665194 2.627994 -v 0.069125 -0.022700 0.047790 -vn -2.627994 3.665194 1.517270 -v 0.069583 -0.018800 0.048248 -vn -2.627994 -3.665194 1.517270 -v 0.069583 -0.022700 0.048248 -vn -3.034548 3.665185 -0.000002 -v 0.069750 -0.018800 0.040873 -vn -3.034548 -3.665185 -0.000002 -v 0.069750 -0.022700 0.040873 -vn -2.627990 3.665198 -1.517274 -v 0.069583 -0.018800 0.041498 -vn -2.627990 -3.665198 -1.517274 -v 0.069583 -0.022700 0.041498 -vn -1.517274 3.665184 -2.627997 -v 0.069125 -0.018800 0.041955 -vn -1.517273 -3.665184 -2.627996 -v 0.069125 -0.022700 0.041955 -vn 0.000000 3.665198 -3.034543 -v 0.068500 -0.018800 0.042123 -vn -0.000000 -3.665199 -3.034543 -v 0.068500 -0.022700 0.042123 -vn 1.517273 3.665184 -2.627996 -v 0.067875 -0.018800 0.041955 -vn 1.517274 -3.665184 -2.627997 -v 0.067875 -0.022700 0.041955 -vn 2.627990 3.665197 -1.517274 -v 0.067417 -0.018800 0.041498 -vn 2.627990 -3.665197 -1.517274 -v 0.067417 -0.022700 0.041498 -vn 3.034548 3.665185 -0.000002 -v 0.067250 -0.018800 0.040873 -vn 3.034548 -3.665185 -0.000002 -v 0.067250 -0.022700 0.040873 -vn 2.627990 3.665199 1.517272 -v 0.067417 -0.018800 0.040248 -vn 2.627990 -3.665199 1.517272 -v 0.067417 -0.022700 0.040248 -vn 1.517274 3.665184 2.627997 -v 0.067875 -0.018800 0.039790 -vn 1.517273 -3.665184 2.627996 -v 0.067875 -0.022700 0.039790 -vn -0.000000 3.665199 3.034543 -v 0.068500 -0.018800 0.039623 -vn 0.000000 -3.665198 3.034543 -v 0.068500 -0.022700 0.039623 -vn -1.517273 3.665184 2.627996 -v 0.069125 -0.018800 0.039790 -vn -1.517274 -3.665184 2.627997 -v 0.069125 -0.022700 0.039790 -vn -2.627990 3.665199 1.517272 -v 0.069583 -0.018800 0.040248 -vn -2.627990 -3.665199 1.517272 -v 0.069583 -0.022700 0.040248 -vn -3.034547 3.665187 -0.000000 -v 0.069750 -0.018800 0.032873 -vn -3.034547 -3.665187 0.000000 -v 0.069750 -0.022700 0.032873 -vn -2.627994 3.665194 -1.517270 -v 0.069583 -0.018800 0.033498 -vn -2.627994 -3.665193 -1.517270 -v 0.069583 -0.022700 0.033498 -vn -1.517270 3.665194 -2.627994 -v 0.069125 -0.018800 0.033955 -vn -1.517270 -3.665194 -2.627994 -v 0.069125 -0.022700 0.033955 -vn 0.000000 3.665187 -3.034547 -v 0.068500 -0.018800 0.034123 -vn -0.000000 -3.665187 -3.034547 -v 0.068500 -0.022700 0.034123 -vn 1.517270 3.665194 -2.627994 -v 0.067875 -0.018800 0.033955 -vn 1.517270 -3.665194 -2.627994 -v 0.067875 -0.022700 0.033955 -vn 2.627994 3.665193 -1.517270 -v 0.067417 -0.018800 0.033498 -vn 2.627994 -3.665193 -1.517270 -v 0.067417 -0.022700 0.033498 -vn 3.034547 3.665188 0.000000 -v 0.067250 -0.018800 0.032873 -vn 3.034547 -3.665188 -0.000000 -v 0.067250 -0.022700 0.032873 -vn 2.627994 3.665194 1.517270 -v 0.067417 -0.018800 0.032248 -vn 2.627994 -3.665194 1.517270 -v 0.067417 -0.022700 0.032248 -vn 1.517270 3.665193 2.627994 -v 0.067875 -0.018800 0.031790 -vn 1.517270 -3.665194 2.627994 -v 0.067875 -0.022700 0.031790 -vn -0.000000 3.665187 3.034547 -v 0.068500 -0.018800 0.031623 -vn 0.000000 -3.665188 3.034547 -v 0.068500 -0.022700 0.031623 -vn -1.517270 3.665202 2.627994 -v 0.069125 -0.018800 0.031790 -vn -1.517270 -3.665194 2.627994 -v 0.069125 -0.022700 0.031790 -vn -2.627994 3.665193 1.517270 -v 0.069583 -0.018800 0.032248 -vn -2.627994 -3.665193 1.517270 -v 0.069583 -0.022700 0.032248 -vn -3.034548 3.665185 -0.000002 -v 0.096750 -0.018800 0.040873 -vn -3.034548 -3.665185 -0.000002 -v 0.096750 -0.022700 0.040873 -vn -2.627990 3.665198 -1.517274 -v 0.096583 -0.018800 0.041498 -vn -2.627990 -3.665198 -1.517274 -v 0.096583 -0.022700 0.041498 -vn -1.517274 3.665184 -2.627997 -v 0.096125 -0.018800 0.041955 -vn -1.517273 -3.665184 -2.627996 -v 0.096125 -0.022700 0.041955 -vn 0.000000 3.665198 -3.034543 -v 0.095500 -0.018800 0.042123 -vn -0.000000 -3.665198 -3.034543 -v 0.095500 -0.022700 0.042123 -vn 1.517273 3.665184 -2.627996 -v 0.094875 -0.018800 0.041955 -vn 1.517274 -3.665184 -2.627997 -v 0.094875 -0.022700 0.041955 -vn 2.627990 3.665198 -1.517274 -v 0.094417 -0.018800 0.041498 -vn 2.627990 -3.665197 -1.517274 -v 0.094417 -0.022700 0.041498 -vn 3.034548 3.665186 -0.000002 -v 0.094250 -0.018800 0.040873 -vn 3.034548 -3.665185 -0.000002 -v 0.094250 -0.022700 0.040873 -vn 2.627990 3.665199 1.517272 -v 0.094417 -0.018800 0.040248 -vn 2.627990 -3.665199 1.517272 -v 0.094417 -0.022700 0.040248 -vn 1.517274 3.665184 2.627997 -v 0.094875 -0.018800 0.039790 -vn 1.517273 -3.665184 2.627996 -v 0.094875 -0.022700 0.039790 -vn -0.000000 3.665198 3.034543 -v 0.095500 -0.018800 0.039623 -vn 0.000000 -3.665198 3.034543 -v 0.095500 -0.022700 0.039623 -vn -1.517273 3.665184 2.627996 -v 0.096125 -0.018800 0.039790 -vn -1.517274 -3.665184 2.627997 -v 0.096125 -0.022700 0.039790 -vn -2.627990 3.665199 1.517272 -v 0.096583 -0.018800 0.040248 -vn -2.627990 -3.665199 1.517272 -v 0.096583 -0.022700 0.040248 -vn -3.034547 3.665187 -0.000000 -v 0.096750 -0.018800 0.048873 -vn -3.034547 -3.665187 0.000000 -v 0.096750 -0.022700 0.048873 -vn -2.627994 3.665194 -1.517270 -v 0.096583 -0.018800 0.049498 -vn -2.627994 -3.665194 -1.517270 -v 0.096583 -0.022700 0.049498 -vn -1.517270 3.665193 -2.627994 -v 0.096125 -0.018800 0.049955 -vn -1.517270 -3.665194 -2.627994 -v 0.096125 -0.022700 0.049955 -vn 0.000000 3.665187 -3.034547 -v 0.095500 -0.018800 0.050123 -vn -0.000000 -3.665187 -3.034547 -v 0.095500 -0.022700 0.050123 -vn 1.517270 3.665194 -2.627994 -v 0.094875 -0.018800 0.049955 -vn 1.517270 -3.665194 -2.627994 -v 0.094875 -0.022700 0.049955 -vn 2.627994 3.665194 -1.517270 -v 0.094417 -0.018800 0.049498 -vn 2.627994 -3.665194 -1.517270 -v 0.094417 -0.022700 0.049498 -vn 3.034547 3.665187 0.000000 -v 0.094250 -0.018800 0.048873 -vn 3.034547 -3.665187 -0.000000 -v 0.094250 -0.022700 0.048873 -vn 2.627994 3.665194 1.517270 -v 0.094417 -0.018800 0.048248 -vn 2.627994 -3.665194 1.517270 -v 0.094417 -0.022700 0.048248 -vn 1.517270 3.665194 2.627994 -v 0.094875 -0.018800 0.047790 -vn 1.517270 -3.665194 2.627994 -v 0.094875 -0.022700 0.047790 -vn -0.000000 3.665187 3.034547 -v 0.095500 -0.018800 0.047623 -vn 0.000000 -3.665187 3.034547 -v 0.095500 -0.022700 0.047623 -vn -1.517270 3.665194 2.627994 -v 0.096125 -0.018800 0.047790 -vn -1.517270 -3.665193 2.627994 -v 0.096125 -0.022700 0.047790 -vn -2.627994 3.665194 1.517270 -v 0.096583 -0.018800 0.048248 -vn -2.627994 -3.665194 1.517270 -v 0.096583 -0.022700 0.048248 -vn -3.034548 3.665185 -0.000002 -v 0.096750 -0.018800 0.056873 -vn -3.034548 -3.665185 -0.000002 -v 0.096750 -0.022700 0.056873 -vn -2.627990 3.665198 -1.517274 -v 0.096583 -0.018800 0.057498 -vn -2.627990 -3.665198 -1.517274 -v 0.096583 -0.022700 0.057498 -vn -1.517274 3.665184 -2.627997 -v 0.096125 -0.018800 0.057955 -vn -1.517273 -3.665184 -2.627996 -v 0.096125 -0.022700 0.057955 -vn 0.000000 3.665198 -3.034543 -v 0.095500 -0.018800 0.058123 -vn -0.000000 -3.665198 -3.034543 -v 0.095500 -0.022700 0.058123 -vn 1.517273 3.665184 -2.627996 -v 0.094875 -0.018800 0.057955 -vn 1.517274 -3.665184 -2.627997 -v 0.094875 -0.022700 0.057955 -vn 2.627990 3.665197 -1.517274 -v 0.094417 -0.018800 0.057498 -vn 2.627990 -3.665197 -1.517274 -v 0.094417 -0.022700 0.057498 -vn 3.034548 3.665186 -0.000002 -v 0.094250 -0.018800 0.056873 -vn 3.034548 -3.665186 -0.000002 -v 0.094250 -0.022700 0.056873 -vn 2.627990 3.665199 1.517272 -v 0.094417 -0.018800 0.056248 -vn 2.627990 -3.665199 1.517272 -v 0.094417 -0.022700 0.056248 -vn 1.517274 3.665184 2.627997 -v 0.094875 -0.018800 0.055790 -vn 1.517273 -3.665184 2.627996 -v 0.094875 -0.022700 0.055790 -vn -0.000000 3.665198 3.034543 -v 0.095500 -0.018800 0.055623 -vn 0.000000 -3.665198 3.034543 -v 0.095500 -0.022700 0.055623 -vn -1.517273 3.665184 2.627996 -v 0.096125 -0.018800 0.055790 -vn -1.517274 -3.665184 2.627997 -v 0.096125 -0.022700 0.055790 -vn -2.627990 3.665199 1.517272 -v 0.096583 -0.018800 0.056248 -vn -2.627990 -3.665199 1.517272 -v 0.096583 -0.022700 0.056248 -vn -3.034548 3.665186 -0.000002 -v 0.069750 0.017500 0.056873 -vn -3.034548 -3.665186 -0.000002 -v 0.069750 0.013800 0.056873 -vn -2.627990 3.665197 -1.517274 -v 0.069583 0.017500 0.057498 -vn -2.627990 -3.665198 -1.517274 -v 0.069583 0.013800 0.057498 -vn -1.517274 3.665184 -2.627997 -v 0.069125 0.017500 0.057955 -vn -1.517273 -3.665184 -2.627996 -v 0.069125 0.013800 0.057955 -vn 0.000000 3.665199 -3.034543 -v 0.068500 0.017500 0.058123 -vn -0.000000 -3.665198 -3.034543 -v 0.068500 0.013800 0.058123 -vn 1.517273 3.665184 -2.627996 -v 0.067875 0.017500 0.057955 -vn 1.517274 -3.665184 -2.627997 -v 0.067875 0.013800 0.057955 -vn 2.627990 3.665198 -1.517274 -v 0.067417 0.017500 0.057498 -vn 2.627990 -3.665198 -1.517274 -v 0.067417 0.013800 0.057498 -vn 3.034548 3.665186 -0.000002 -v 0.067250 0.017500 0.056873 -vn 3.034548 -3.665185 -0.000002 -v 0.067250 0.013800 0.056873 -vn 2.627990 3.665199 1.517272 -v 0.067417 0.017500 0.056248 -vn 2.627991 -3.665199 1.517272 -v 0.067417 0.013800 0.056248 -vn 1.517274 3.665184 2.627997 -v 0.067875 0.017500 0.055790 -vn 1.517273 -3.665184 2.627996 -v 0.067875 0.013800 0.055790 -vn -0.000000 3.665198 3.034543 -v 0.068500 0.017500 0.055623 -vn 0.000000 -3.665199 3.034543 -v 0.068500 0.013800 0.055623 -vn -1.517273 3.665184 2.627996 -v 0.069125 0.017500 0.055790 -vn -1.517274 -3.665184 2.627997 -v 0.069125 0.013800 0.055790 -vn -2.627991 3.665199 1.517272 -v 0.069583 0.017500 0.056248 -vn -2.627990 -3.665200 1.517272 -v 0.069583 0.013800 0.056248 -vn -3.034547 3.665188 0.000000 -v 0.069750 0.017500 0.048873 -vn -3.034547 -3.665188 -0.000000 -v 0.069750 0.013800 0.048873 -vn -2.627995 3.665194 -1.517270 -v 0.069583 0.017500 0.049498 -vn -2.627995 -3.665193 -1.517270 -v 0.069583 0.013800 0.049498 -vn -1.517270 3.665194 -2.627995 -v 0.069125 0.017500 0.049955 -vn -1.517270 -3.665192 -2.627995 -v 0.069125 0.013800 0.049955 -vn -0.000000 3.665187 -3.034547 -v 0.068500 0.017500 0.050123 -vn 0.000000 -3.665189 -3.034547 -v 0.068500 0.013800 0.050123 -vn 1.517270 3.665194 -2.627995 -v 0.067875 0.017500 0.049955 -vn 1.517270 -3.665195 -2.627995 -v 0.067875 0.013800 0.049955 -vn 2.627995 3.665194 -1.517270 -v 0.067417 0.017500 0.049498 -vn 2.627995 -3.665192 -1.517270 -v 0.067417 0.013800 0.049498 -vn 3.034547 3.665187 -0.000000 -v 0.067250 0.017500 0.048873 -vn 3.034547 -3.665186 0.000000 -v 0.067250 0.013800 0.048873 -vn 2.627995 3.665194 1.517270 -v 0.067417 0.017500 0.048248 -vn 2.627995 -3.665193 1.517270 -v 0.067417 0.013800 0.048248 -vn 1.517270 3.665194 2.627995 -v 0.067875 0.017500 0.047790 -vn 1.517270 -3.665194 2.627995 -v 0.067875 0.013800 0.047790 -vn 0.000000 3.665187 3.034547 -v 0.068500 0.017500 0.047623 -vn -0.000000 -3.665189 3.034547 -v 0.068500 0.013800 0.047623 -vn -1.517270 3.665194 2.627995 -v 0.069125 0.017500 0.047790 -vn -1.517270 -3.665194 2.627995 -v 0.069125 0.013800 0.047790 -vn -2.627995 3.665194 1.517270 -v 0.069583 0.017500 0.048248 -vn -2.627995 -3.665195 1.517270 -v 0.069583 0.013800 0.048248 -vn -3.034548 3.665186 -0.000002 -v 0.069750 0.017500 0.040873 -vn -3.034548 -3.665186 -0.000002 -v 0.069750 0.013800 0.040873 -vn -2.627990 3.665197 -1.517274 -v 0.069583 0.017500 0.041498 -vn -2.627990 -3.665198 -1.517274 -v 0.069583 0.013800 0.041498 -vn -1.517274 3.665184 -2.627997 -v 0.069125 0.017500 0.041955 -vn -1.517273 -3.665184 -2.627996 -v 0.069125 0.013800 0.041955 -vn 0.000000 3.665198 -3.034543 -v 0.068500 0.017500 0.042123 -vn -0.000000 -3.665199 -3.034543 -v 0.068500 0.013800 0.042123 -vn 1.517273 3.665184 -2.627996 -v 0.067875 0.017500 0.041955 -vn 1.517274 -3.665184 -2.627997 -v 0.067875 0.013800 0.041955 -vn 2.627990 3.665197 -1.517274 -v 0.067417 0.017500 0.041498 -vn 2.627990 -3.665197 -1.517274 -v 0.067417 0.013800 0.041498 -vn 3.034548 3.665186 -0.000002 -v 0.067250 0.017500 0.040873 -vn 3.034548 -3.665187 -0.000002 -v 0.067250 0.013800 0.040873 -vn 2.627990 3.665199 1.517272 -v 0.067417 0.017500 0.040248 -vn 2.627991 -3.665198 1.517272 -v 0.067417 0.013800 0.040248 -vn 1.517274 3.665184 2.627997 -v 0.067875 0.017500 0.039790 -vn 1.517273 -3.665185 2.627996 -v 0.067875 0.013800 0.039790 -vn -0.000000 3.665198 3.034543 -v 0.068500 0.017500 0.039623 -vn 0.000000 -3.665198 3.034543 -v 0.068500 0.013800 0.039623 -vn -1.517273 3.665184 2.627996 -v 0.069125 0.017500 0.039790 -vn -1.517274 -3.665183 2.627997 -v 0.069125 0.013800 0.039790 -vn -2.627991 3.665199 1.517272 -v 0.069583 0.017500 0.040248 -vn -2.627990 -3.665200 1.517272 -v 0.069583 0.013800 0.040248 -vn -3.034547 3.665187 0.000000 -v 0.069750 0.017500 0.032873 -vn -3.034547 -3.665189 -0.000000 -v 0.069750 0.013800 0.032873 -vn -2.627995 3.665194 -1.517270 -v 0.069583 0.017500 0.033498 -vn -2.627995 -3.665194 -1.517270 -v 0.069583 0.013800 0.033498 -vn -1.517270 3.665194 -2.627995 -v 0.069125 0.017500 0.033955 -vn -1.517270 -3.665194 -2.627995 -v 0.069125 0.013800 0.033955 -vn -0.000000 3.665187 -3.034547 -v 0.068500 0.017500 0.034123 -vn 0.000000 -3.665188 -3.034547 -v 0.068500 0.013800 0.034123 -vn 1.517270 3.665194 -2.627995 -v 0.067875 0.017500 0.033955 -vn 1.517270 -3.665194 -2.627995 -v 0.067875 0.013800 0.033955 -vn 2.627995 3.665194 -1.517270 -v 0.067417 0.017500 0.033498 -vn 2.627995 -3.665194 -1.517270 -v 0.067417 0.013800 0.033498 -vn 3.034547 3.665187 -0.000000 -v 0.067250 0.017500 0.032873 -vn 3.034547 -3.665186 0.000000 -v 0.067250 0.013800 0.032873 -vn 2.627995 3.665194 1.517270 -v 0.067417 0.017500 0.032248 -vn 2.627995 -3.665194 1.517270 -v 0.067417 0.013800 0.032248 -vn 1.517270 3.665193 2.627995 -v 0.067875 0.017500 0.031790 -vn 1.517270 -3.665194 2.627995 -v 0.067875 0.013800 0.031790 -vn 0.000000 3.665187 3.034547 -v 0.068500 0.017500 0.031623 -vn -0.000000 -3.665187 3.034547 -v 0.068500 0.013800 0.031623 -vn -1.517270 3.665188 2.627995 -v 0.069125 0.017500 0.031790 -vn -1.517270 -3.665188 2.627995 -v 0.069125 0.013800 0.031790 -vn -2.627995 3.665194 1.517270 -v 0.069583 0.017500 0.032248 -vn -2.627995 -3.665193 1.517270 -v 0.069583 0.013800 0.032248 -vn -3.034548 3.665185 -0.000002 -v 0.096750 0.017500 0.040873 -vn -3.034548 -3.665183 -0.000002 -v 0.096750 0.013800 0.040873 -vn -2.627990 3.665197 -1.517274 -v 0.096583 0.017500 0.041498 -vn -2.627990 -3.665198 -1.517274 -v 0.096583 0.013800 0.041498 -vn -1.517274 3.665184 -2.627997 -v 0.096125 0.017500 0.041955 -vn -1.517273 -3.665184 -2.627996 -v 0.096125 0.013800 0.041955 -vn 0.000000 3.665198 -3.034543 -v 0.095500 0.017500 0.042123 -vn -0.000000 -3.665199 -3.034543 -v 0.095500 0.013800 0.042123 -vn 1.517273 3.665184 -2.627996 -v 0.094875 0.017500 0.041955 -vn 1.517274 -3.665184 -2.627997 -v 0.094875 0.013800 0.041955 -vn 2.627990 3.665197 -1.517274 -v 0.094417 0.017500 0.041498 -vn 2.627990 -3.665198 -1.517274 -v 0.094417 0.013800 0.041498 -vn 3.034548 3.665186 -0.000002 -v 0.094250 0.017500 0.040873 -vn 3.034548 -3.665188 -0.000002 -v 0.094250 0.013800 0.040873 -vn 2.627990 3.665199 1.517272 -v 0.094417 0.017500 0.040248 -vn 2.627991 -3.665200 1.517272 -v 0.094417 0.013800 0.040248 -vn 1.517274 3.665184 2.627997 -v 0.094875 0.017500 0.039790 -vn 1.517273 -3.665184 2.627996 -v 0.094875 0.013800 0.039790 -vn -0.000000 3.665198 3.034543 -v 0.095500 0.017500 0.039623 -vn 0.000000 -3.665198 3.034543 -v 0.095500 0.013800 0.039623 -vn -1.517273 3.665184 2.627996 -v 0.096125 0.017500 0.039790 -vn -1.517274 -3.665184 2.627997 -v 0.096125 0.013800 0.039790 -vn -2.627991 3.665199 1.517272 -v 0.096583 0.017500 0.040248 -vn -2.627990 -3.665199 1.517272 -v 0.096583 0.013800 0.040248 -vn -3.034547 3.665188 0.000000 -v 0.096750 0.017500 0.048873 -vn -3.034547 -3.665189 -0.000000 -v 0.096750 0.013800 0.048873 -vn -2.627995 3.665193 -1.517270 -v 0.096583 0.017500 0.049498 -vn -2.627995 -3.665199 -1.517270 -v 0.096583 0.013800 0.049498 -vn -1.517270 3.665194 -2.627995 -v 0.096125 0.017500 0.049955 -vn -1.517270 -3.665194 -2.627995 -v 0.096125 0.013800 0.049955 -vn -0.000000 3.665188 -3.034547 -v 0.095500 0.017500 0.050123 -vn 0.000000 -3.665189 -3.034547 -v 0.095500 0.013800 0.050123 -vn 1.517270 3.665194 -2.627995 -v 0.094875 0.017500 0.049955 -vn 1.517270 -3.665193 -2.627995 -v 0.094875 0.013800 0.049955 -vn 2.627995 3.665194 -1.517270 -v 0.094417 0.017500 0.049498 -vn 2.627995 -3.665194 -1.517270 -v 0.094417 0.013800 0.049498 -vn 3.034547 3.665188 -0.000000 -v 0.094250 0.017500 0.048873 -vn 3.034547 -3.665188 0.000000 -v 0.094250 0.013800 0.048873 -vn 2.627995 3.665194 1.517270 -v 0.094417 0.017500 0.048248 -vn 2.627995 -3.665194 1.517270 -v 0.094417 0.013800 0.048248 -vn 1.517270 3.665194 2.627995 -v 0.094875 0.017500 0.047790 -vn 1.517270 -3.665194 2.627995 -v 0.094875 0.013800 0.047790 -vn 0.000000 3.665187 3.034547 -v 0.095500 0.017500 0.047623 -vn -0.000000 -3.665188 3.034547 -v 0.095500 0.013800 0.047623 -vn -1.517270 3.665194 2.627995 -v 0.096125 0.017500 0.047790 -vn -1.517270 -3.665194 2.627995 -v 0.096125 0.013800 0.047790 -vn -2.627995 3.665193 1.517270 -v 0.096583 0.017500 0.048248 -vn -2.627995 -3.665193 1.517270 -v 0.096583 0.013800 0.048248 -vn -3.034548 3.665187 -0.000002 -v 0.096750 0.017500 0.056873 -vn -3.034548 -3.665186 -0.000002 -v 0.096750 0.013800 0.056873 -vn -2.627990 3.665197 -1.517274 -v 0.096583 0.017500 0.057498 -vn -2.627990 -3.665198 -1.517274 -v 0.096583 0.013800 0.057498 -vn -1.517274 3.665184 -2.627997 -v 0.096125 0.017500 0.057955 -vn -1.517273 -3.665184 -2.627996 -v 0.096125 0.013800 0.057955 -vn 0.000000 3.665198 -3.034543 -v 0.095500 0.017500 0.058123 -vn -0.000000 -3.665198 -3.034543 -v 0.095500 0.013800 0.058123 -vn 1.517273 3.665184 -2.627996 -v 0.094875 0.017500 0.057955 -vn 1.517274 -3.665184 -2.627997 -v 0.094875 0.013800 0.057955 -vn 2.627990 3.665197 -1.517274 -v 0.094417 0.017500 0.057498 -vn 2.627990 -3.665198 -1.517274 -v 0.094417 0.013800 0.057498 -vn 3.034548 3.665186 -0.000002 -v 0.094250 0.017500 0.056873 -vn 3.034548 -3.665186 -0.000002 -v 0.094250 0.013800 0.056873 -vn 2.627990 3.665199 1.517272 -v 0.094417 0.017500 0.056248 -vn 2.627991 -3.665199 1.517272 -v 0.094417 0.013800 0.056248 -vn 1.517274 3.665184 2.627997 -v 0.094875 0.017500 0.055790 -vn 1.517273 -3.665184 2.627996 -v 0.094875 0.013800 0.055790 -vn -0.000000 3.665198 3.034543 -v 0.095500 0.017500 0.055623 -vn 0.000000 -3.665199 3.034543 -v 0.095500 0.013800 0.055623 -vn -1.517273 3.665184 2.627996 -v 0.096125 0.017500 0.055790 -vn -1.517274 -3.665184 2.627997 -v 0.096125 0.013800 0.055790 -vn -2.627991 3.665199 1.517272 -v 0.096583 0.017500 0.056248 -vn -2.627990 -3.665200 1.517272 -v 0.096583 0.013800 0.056248 -vn -3.077873 -3.526581 -0.129572 -v 0.070308 -0.022700 0.021593 -vn -2.534867 -3.130852 -1.855740 -v 0.068646 -0.022700 0.025131 -vn -2.534867 3.130853 -1.855739 -v 0.068646 -0.018800 0.025131 -vn -2.787820 -3.537815 -1.309712 -v 0.069832 -0.022700 0.023529 -vn -2.756340 3.492618 -1.418339 -v 0.069832 -0.018800 0.023529 -vn -2.534867 -3.130852 -1.855739 -v 0.068646 0.013800 0.025131 -vn -2.534867 3.130853 -1.855739 -v 0.068646 0.017500 0.025131 -vn -2.741192 -3.434848 -1.464510 -v 0.069832 0.013800 0.023529 -vn -2.781147 3.502598 -1.335006 -v 0.069832 0.017500 0.023529 -vn -3.083103 3.503138 -0.106902 -v 0.070308 0.017500 0.021593 -vn -3.081828 -2.932731 -0.514484 -v 0.067037 -0.022700 0.028231 -vn -3.081828 2.932730 -0.514484 -v 0.067037 -0.018800 0.028231 -vn -2.786368 -2.784872 -1.339813 -v 0.067430 -0.022700 0.026811 -vn -2.786368 2.784872 -1.339813 -v 0.067430 -0.018800 0.026811 -vn -2.809077 2.723879 -1.246752 -v 0.067430 0.017500 0.026811 -vn -2.809078 -2.723880 -1.246753 -v 0.067430 0.013800 0.026811 -vn 0.000000 6.283185 0.000000 -v 0.095500 -0.018800 0.052873 -vn 0.000000 6.283185 0.000000 -v 0.095500 -0.018800 0.044873 -vn 0.000000 6.283185 0.000000 -v 0.095500 -0.018800 0.036873 -vn 0.000000 6.283185 0.000000 -v 0.082000 -0.018800 0.027123 -vn 0.000000 6.283166 0.000000 -v 0.067125 -0.018800 0.036873 -vn 0.000000 6.283182 0.000000 -v 0.067125 -0.018800 0.044873 -vn 0.000000 6.283178 0.000000 -v 0.067125 -0.018800 0.052873 -vn 3.141593 3.141593 0.000000 -v 0.070500 0.017500 0.059123 -vn 3.141593 3.141592 0.000000 -v 0.070500 0.017500 0.036873 -vn 3.141593 3.141593 0.000000 -v 0.070500 0.017500 0.044873 -vn 3.141593 3.141593 0.000000 -v 0.070500 0.017500 0.052873 -vn -3.141593 3.141594 0.000000 -v 0.093500 0.017500 0.036873 -vn -3.141593 3.141594 0.000000 -v 0.093500 0.017500 0.059123 -vn -3.141593 3.141595 0.000000 -v 0.093500 0.017500 0.052873 -vn -3.141593 3.141595 0.000000 -v 0.093500 0.017500 0.044873 -vn 0.000000 -6.283165 0.000000 -v 0.067125 -0.022700 0.036873 -vn 0.000000 -6.283185 0.000000 -v 0.095500 -0.022700 0.036873 -vn 0.000000 -6.283185 0.000000 -v 0.095500 -0.022700 0.044873 -vn 0.000000 -6.283185 0.000000 -v 0.095500 -0.022700 0.052873 -vn 0.000000 -6.283178 0.000000 -v 0.067125 -0.022700 0.052873 -vn 0.000000 -6.283182 0.000000 -v 0.067125 -0.022700 0.044873 -vn 0.000000 -6.283185 0.000000 -v 0.082000 -0.022700 0.025623 -vn 0.000000 -6.283185 0.000000 -v 0.095500 -0.022700 0.025623 -vn 0.000000 6.283178 0.000000 -v 0.096875 0.017500 0.036873 -vn 0.000000 6.283182 0.000000 -v 0.096875 0.017500 0.059123 -vn 0.000000 6.283183 0.000000 -v 0.096875 0.017500 0.052873 -vn 0.000000 6.283189 0.000000 -v 0.096875 0.017500 0.044873 -# 710 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 6//6 7//7 8//8 -f 8//8 7//7 9//9 -f 10//10 11//11 12//12 -f 12//12 11//11 13//13 -f 12//12 13//13 14//14 -f 14//14 13//13 15//15 -f 14//14 15//15 16//16 -f 16//16 15//15 17//17 -f 16//16 17//17 18//18 -f 18//18 17//17 19//19 -f 18//18 19//19 20//20 -f 20//20 19//19 21//21 -f 20//20 21//21 22//22 -f 22//22 21//21 23//23 -f 22//22 23//23 24//24 -f 24//24 23//23 25//25 -f 26//26 25//25 27//27 -f 27//27 25//25 23//23 -f 27//27 23//23 28//28 -f 28//28 23//23 29//29 -f 28//28 29//29 30//30 -f 30//30 29//29 31//31 -f 30//30 31//31 32//32 -f 32//32 31//31 33//33 -f 32//32 33//33 34//34 -f 34//34 33//33 35//35 -f 34//34 35//35 36//36 -f 36//36 35//35 37//37 -f 36//36 37//37 38//38 -f 38//38 37//37 39//39 -f 8//8 9//9 40//40 -f 41//41 42//42 43//43 -f 42//42 41//41 40//40 -f 40//40 41//41 44//44 -f 40//40 44//44 8//8 -f 43//43 42//42 4//4 -f 4//4 42//42 45//45 -f 4//4 45//45 5//5 -f 46//46 47//47 48//48 -f 43//43 49//49 41//41 -f 41//41 49//49 46//46 -f 41//41 46//46 50//50 -f 50//50 46//46 48//48 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 65//65 66//66 67//67 -f 68//68 69//69 70//70 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 76//76 77//77 78//78 -f 78//78 77//77 63//63 -f 78//78 63//63 68//68 -f 68//68 63//63 64//64 -f 68//68 64//64 69//69 -f 72//72 79//79 80//80 -f 80//80 79//79 81//81 -f 80//80 81//81 82//82 -f 82//82 81//81 83//83 -f 82//82 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 86//86 87//87 88//88 -f 88//88 87//87 89//89 -f 88//88 89//89 90//90 -f 74//74 65//65 75//75 -f 75//75 65//65 67//67 -f 75//75 67//67 91//91 -f 91//91 67//67 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 77//77 -f 71//71 96//96 72//72 -f 72//72 96//96 97//97 -f 72//72 97//97 79//79 -f 79//79 97//97 98//98 -f 79//79 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 76//76 -f 76//76 100//100 101//101 -f 76//76 101//101 77//77 -f 77//77 101//101 102//102 -f 77//77 102//102 95//95 -f 89//89 103//103 90//90 -f 90//90 103//103 104//104 -f 90//90 104//104 105//105 -f 105//105 104//104 68//68 -f 105//105 68//68 106//106 -f 106//106 68//68 70//70 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 111//111 107//107 112//112 -f 112//112 107//107 113//113 -f 112//112 113//113 114//114 -f 114//114 113//113 115//115 -f 111//111 116//116 107//107 -f 107//107 116//116 117//117 -f 107//107 117//117 108//108 -f 108//108 117//117 118//118 -f 108//108 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 115//115 122//122 114//114 -f 114//114 122//122 123//123 -f 114//114 123//123 124//124 -f 124//124 123//123 125//125 -f 124//124 125//125 126//126 -f 126//126 125//125 127//127 -f 126//126 127//127 128//128 -f 128//128 127//127 129//129 -f 128//128 129//129 130//130 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 135//135 136//136 137//137 -f 137//137 136//136 138//138 -f 137//137 138//138 139//139 -f 139//139 138//138 140//140 -f 139//139 140//140 129//129 -f 129//129 140//140 141//141 -f 129//129 141//141 130//130 -f 130//130 141//141 121//121 -f 130//130 121//121 142//142 -f 142//142 121//121 120//120 -f 143//143 109//109 144//144 -f 144//144 109//109 145//145 -f 146//146 147//147 131//131 -f 131//131 147//147 148//148 -f 131//131 148//148 132//132 -f 145//145 109//109 149//149 -f 149//149 109//109 110//110 -f 149//149 110//110 150//150 -f 150//150 110//110 147//147 -f 150//150 147//147 151//151 -f 151//151 147//147 146//146 -f 151//151 146//146 152//152 -f 153//153 154//154 133//133 -f 133//133 154//154 131//131 -f 155//155 156//156 157//157 -f 158//158 159//159 160//160 -f 161//161 162//162 159//159 -f 159//159 162//162 163//163 -f 159//159 163//163 160//160 -f 157//157 156//156 164//164 -f 164//164 156//156 165//165 -f 164//164 165//165 166//166 -f 166//166 165//165 167//167 -f 166//166 167//167 168//168 -f 168//168 167//167 169//169 -f 168//168 169//169 153//153 -f 153//153 169//169 170//170 -f 153//153 170//170 154//154 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 173//173 174//174 175//175 -f 175//175 174//174 176//176 -f 176//176 174//174 177//177 -f 176//176 177//177 178//178 -f 179//179 180//180 181//181 -f 181//181 180//180 182//182 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 185//185 -f 185//185 184//184 173//173 -f 185//185 173//173 186//186 -f 186//186 173//173 175//175 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 189//189 190//190 178//178 -f 178//178 190//190 191//191 -f 178//178 191//191 176//176 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 194//194 195//195 196//196 -f 196//196 195//195 197//197 -f 196//196 197//197 198//198 -f 198//198 197//197 199//199 -f 198//198 199//199 200//200 -f 200//200 199//199 201//201 -f 200//200 201//201 202//202 -f 202//202 201//201 203//203 -f 202//202 203//203 181//181 -f 181//181 203//203 204//204 -f 181//181 204//204 179//179 -f 205//205 206//206 207//207 -f 171//171 208//208 172//172 -f 172//172 208//208 209//209 -f 172//172 209//209 160//160 -f 160//160 209//209 210//210 -f 160//160 210//210 158//158 -f 158//158 210//210 211//211 -f 158//158 211//211 212//212 -f 212//212 211//211 213//213 -f 212//212 213//213 204//204 -f 204//204 213//213 214//214 -f 204//204 214//214 179//179 -f 215//215 216//216 161//161 -f 216//216 217//217 161//161 -f 161//161 217//217 218//218 -f 161//161 218//218 162//162 -f 162//162 218//218 219//219 -f 162//162 219//219 220//220 -f 189//189 221//221 187//187 -f 187//187 221//221 222//222 -f 187//187 222//222 157//157 -f 157//157 222//222 223//223 -f 157//157 223//223 155//155 -f 155//155 223//223 224//224 -f 155//155 224//224 225//225 -f 225//225 224//224 162//162 -f 225//225 162//162 226//226 -f 226//226 162//162 220//220 -f 226//226 220//220 227//227 -f 227//227 220//220 228//228 -f 227//227 228//228 205//205 -f 205//205 228//228 229//229 -f 205//205 229//229 206//206 -f 170//170 230//230 154//154 -f 154//154 230//230 231//231 -f 154//154 231//231 232//232 -f 232//232 231//231 205//205 -f 232//232 205//205 233//233 -f 233//233 205//205 207//207 -f 234//234 215//215 235//235 -f 235//235 215//215 161//161 -f 235//235 161//161 192//192 -f 192//192 161//161 236//236 -f 192//192 236//236 193//193 -f 187//187 157//157 127//127 -f 127//127 157//157 129//129 -f 88//88 90//90 194//194 -f 194//194 90//90 192//192 -f 202//202 181//181 80//80 -f 80//80 181//181 72//72 -f 176//176 115//115 113//113 -f 237//237 238//238 92//92 -f 176//176 113//113 175//175 -f 175//175 113//113 92//92 -f 175//175 92//92 67//67 -f 239//239 7//7 240//240 -f 240//240 241//241 239//239 -f 239//239 241//241 242//242 -f 239//239 242//242 243//243 -f 237//237 92//92 6//6 -f 6//6 92//92 113//113 -f 6//6 113//113 7//7 -f 7//7 113//113 244//244 -f 7//7 244//244 240//240 -f 245//245 246//246 247//247 -f 248//248 249//249 250//250 -f 250//250 249//249 251//251 -f 250//250 251//251 252//252 -f 252//252 251//251 253//253 -f 252//252 253//253 254//254 -f 254//254 253//253 255//255 -f 254//254 255//255 1//1 -f 1//1 255//255 256//256 -f 1//1 256//256 2//2 -f 2//2 256//256 92//92 -f 2//2 92//92 257//257 -f 257//257 92//92 238//238 -f 257//257 238//238 258//258 -f 258//258 238//238 245//245 -f 258//258 245//245 259//259 -f 259//259 245//245 247//247 -f 161//161 68//68 236//236 -f 236//236 68//68 104//104 -f 236//236 104//104 193//193 -f 193//193 104//104 103//103 -f 193//193 103//103 195//195 -f 195//195 103//103 89//89 -f 195//195 89//89 197//197 -f 197//197 89//89 87//87 -f 197//197 87//87 199//199 -f 199//199 87//87 85//85 -f 199//199 85//85 201//201 -f 201//201 85//85 83//83 -f 201//201 83//83 203//203 -f 203//203 83//83 81//81 -f 203//203 81//81 204//204 -f 204//204 81//81 79//79 -f 204//204 79//79 212//212 -f 212//212 79//79 99//99 -f 212//212 99//99 158//158 -f 158//158 99//99 76//76 -f 158//158 76//76 159//159 -f 159//159 76//76 78//78 -f 159//159 78//78 161//161 -f 161//161 78//78 68//68 -f 209//209 95//95 210//210 -f 210//210 95//95 102//102 -f 210//210 102//102 211//211 -f 211//211 102//102 101//101 -f 211//211 101//101 213//213 -f 213//213 101//101 100//100 -f 213//213 100//100 214//214 -f 214//214 100//100 98//98 -f 214//214 98//98 179//179 -f 179//179 98//98 97//97 -f 179//179 97//97 180//180 -f 180//180 97//97 96//96 -f 180//180 96//96 182//182 -f 182//182 96//96 71//71 -f 182//182 71//71 184//184 -f 184//184 71//71 73//73 -f 184//184 73//73 173//173 -f 173//173 73//73 75//75 -f 173//173 75//75 171//171 -f 171//171 75//75 91//91 -f 171//171 91//91 208//208 -f 208//208 91//91 93//93 -f 208//208 93//93 209//209 -f 209//209 93//93 95//95 -f 222//222 128//128 223//223 -f 223//223 128//128 130//130 -f 223//223 130//130 224//224 -f 224//224 130//130 142//142 -f 224//224 142//142 162//162 -f 162//162 142//142 120//120 -f 162//162 120//120 163//163 -f 163//163 120//120 118//118 -f 163//163 118//118 160//160 -f 160//160 118//118 117//117 -f 160//160 117//117 172//172 -f 172//172 117//117 116//116 -f 172//172 116//116 174//174 -f 174//174 116//116 111//111 -f 174//174 111//111 177//177 -f 177//177 111//111 112//112 -f 177//177 112//112 178//178 -f 178//178 112//112 114//114 -f 178//178 114//114 189//189 -f 189//189 114//114 124//124 -f 189//189 124//124 221//221 -f 221//221 124//124 126//126 -f 221//221 126//126 222//222 -f 222//222 126//126 128//128 -f 165//165 140//140 167//167 -f 167//167 140//140 138//138 -f 167//167 138//138 169//169 -f 169//169 138//138 136//136 -f 169//169 136//136 170//170 -f 170//170 136//136 134//134 -f 170//170 134//134 230//230 -f 230//230 134//134 132//132 -f 230//230 132//132 231//231 -f 231//231 132//132 148//148 -f 231//231 148//148 205//205 -f 205//205 148//148 147//147 -f 205//205 147//147 227//227 -f 227//227 147//147 110//110 -f 227//227 110//110 226//226 -f 226//226 110//110 108//108 -f 226//226 108//108 225//225 -f 225//225 108//108 119//119 -f 225//225 119//119 155//155 -f 155//155 119//119 121//121 -f 155//155 121//121 156//156 -f 156//156 121//121 141//141 -f 156//156 141//141 165//165 -f 165//165 141//141 140//140 -f 207//207 206//206 151//151 -f 151//151 206//206 150//150 -f 144//144 220//220 143//143 -f 143//143 220//220 219//219 -f 143//143 219//219 61//61 -f 216//216 215//215 69//69 -f 69//69 215//215 70//70 -f 88//88 194//194 196//196 -f 88//88 196//196 86//86 -f 86//86 196//196 198//198 -f 86//86 198//198 84//84 -f 84//84 198//198 200//200 -f 84//84 200//200 82//82 -f 82//82 200//200 202//202 -f 82//82 202//202 80//80 -f 72//72 181//181 183//183 -f 72//72 183//183 74//74 -f 74//74 183//183 185//185 -f 74//74 185//185 65//65 -f 65//65 185//185 186//186 -f 65//65 186//186 66//66 -f 66//66 186//186 175//175 -f 66//66 175//175 67//67 -f 115//115 176//176 191//191 -f 115//115 191//191 122//122 -f 122//122 191//191 190//190 -f 122//122 190//190 123//123 -f 123//123 190//190 188//188 -f 123//123 188//188 125//125 -f 125//125 188//188 187//187 -f 125//125 187//187 127//127 -f 129//129 157//157 164//164 -f 129//129 164//164 139//139 -f 139//139 164//164 166//166 -f 139//139 166//166 137//137 -f 137//137 166//166 168//168 -f 137//137 168//168 135//135 -f 135//135 168//168 153//153 -f 135//135 153//153 133//133 -f 131//131 154//154 232//232 -f 131//131 232//232 146//146 -f 146//146 232//232 233//233 -f 146//146 233//233 152//152 -f 152//152 233//233 207//207 -f 152//152 207//207 151//151 -f 220//220 144//144 228//228 -f 228//228 144//144 145//145 -f 228//228 145//145 229//229 -f 229//229 145//145 149//149 -f 229//229 149//149 206//206 -f 206//206 149//149 150//150 -f 61//61 219//219 62//62 -f 62//62 219//219 218//218 -f 62//62 218//218 64//64 -f 64//64 218//218 217//217 -f 64//64 217//217 69//69 -f 69//69 217//217 216//216 -f 192//192 90//90 105//105 -f 192//192 105//105 235//235 -f 235//235 105//105 106//106 -f 235//235 106//106 234//234 -f 234//234 106//106 70//70 -f 234//234 70//70 215//215 -f 26//26 27//27 260//260 -f 40//40 22//22 42//42 -f 42//42 22//22 24//24 -f 42//42 24//24 261//261 -f 261//261 24//24 26//26 -f 261//261 26//26 262//262 -f 262//262 26//26 260//260 -f 60//60 58//58 263//263 -f 263//263 264//264 60//60 -f 60//60 264//264 265//265 -f 60//60 265//265 266//266 -f 266//266 265//265 267//267 -f 266//266 267//267 268//268 -f 269//269 270//270 271//271 -f 271//271 270//270 239//239 -f 271//271 239//239 243//243 -f 249//249 248//248 272//272 -f 272//272 248//248 273//273 -f 272//272 273//273 274//274 -f 274//274 273//273 275//275 -f 276//276 277//277 278//278 -f 278//278 277//277 279//279 -f 278//278 279//279 280//280 -f 280//280 279//279 281//281 -f 280//280 281//281 282//282 -f 282//282 281//281 283//283 -f 282//282 283//283 51//51 -f 51//51 283//283 52//52 -f 25//25 26//26 24//24 -f 284//284 285//285 286//286 -f 286//286 285//285 287//287 -f 286//286 287//287 288//288 -f 288//288 287//287 289//289 -f 288//288 289//289 290//290 -f 290//290 289//289 291//291 -f 290//290 291//291 292//292 -f 292//292 291//291 293//293 -f 292//292 293//293 294//294 -f 294//294 293//293 295//295 -f 294//294 295//295 296//296 -f 296//296 295//295 297//297 -f 296//296 297//297 298//298 -f 298//298 297//297 299//299 -f 298//298 299//299 300//300 -f 300//300 299//299 301//301 -f 300//300 301//301 302//302 -f 302//302 301//301 303//303 -f 302//302 303//303 304//304 -f 304//304 303//303 305//305 -f 304//304 305//305 306//306 -f 306//306 305//305 307//307 -f 308//308 309//309 310//310 -f 310//310 309//309 311//311 -f 310//310 311//311 312//312 -f 312//312 311//311 313//313 -f 312//312 313//313 275//275 -f 275//275 313//313 274//274 -f 314//314 315//315 316//316 -f 316//316 315//315 317//317 -f 316//316 317//317 318//318 -f 318//318 317//317 319//319 -f 55//55 56//56 320//320 -f 320//320 56//56 321//321 -f 320//320 321//321 314//314 -f 314//314 321//321 315//315 -f 306//306 307//307 322//322 -f 306//306 322//322 323//323 -f 323//323 322//322 324//324 -f 323//323 324//324 325//325 -f 325//325 324//324 309//309 -f 325//325 309//309 308//308 -f 326//326 327//327 328//328 -f 328//328 327//327 318//318 -f 328//328 318//318 319//319 -f 285//285 284//284 329//329 -f 329//329 284//284 330//330 -f 329//329 330//330 326//326 -f 326//326 330//330 331//331 -f 326//326 331//331 327//327 -f 332//332 333//333 334//334 -f 334//334 333//333 335//335 -f 334//334 335//335 336//336 -f 336//336 335//335 337//337 -f 336//336 337//337 338//338 -f 338//338 337//337 339//339 -f 338//338 339//339 340//340 -f 340//340 339//339 341//341 -f 340//340 341//341 342//342 -f 342//342 341//341 343//343 -f 342//342 343//343 344//344 -f 344//344 343//343 345//345 -f 344//344 345//345 346//346 -f 346//346 345//345 347//347 -f 346//346 347//347 348//348 -f 348//348 347//347 349//349 -f 348//348 349//349 350//350 -f 350//350 349//349 351//351 -f 350//350 351//351 352//352 -f 352//352 351//351 353//353 -f 352//352 353//353 354//354 -f 354//354 353//353 355//355 -f 354//354 355//355 332//332 -f 332//332 355//355 333//333 -f 356//356 357//357 358//358 -f 358//358 357//357 359//359 -f 358//358 359//359 360//360 -f 360//360 359//359 361//361 -f 360//360 361//361 362//362 -f 362//362 361//361 363//363 -f 362//362 363//363 364//364 -f 364//364 363//363 365//365 -f 364//364 365//365 366//366 -f 366//366 365//365 367//367 -f 366//366 367//367 368//368 -f 368//368 367//367 369//369 -f 368//368 369//369 370//370 -f 370//370 369//369 371//371 -f 370//370 371//371 372//372 -f 372//372 371//371 373//373 -f 372//372 373//373 374//374 -f 374//374 373//373 375//375 -f 374//374 375//375 376//376 -f 376//376 375//375 377//377 -f 376//376 377//377 378//378 -f 378//378 377//377 379//379 -f 378//378 379//379 356//356 -f 356//356 379//379 357//357 -f 380//380 381//381 382//382 -f 382//382 381//381 383//383 -f 382//382 383//383 384//384 -f 384//384 383//383 385//385 -f 384//384 385//385 386//386 -f 386//386 385//385 387//387 -f 386//386 387//387 388//388 -f 388//388 387//387 389//389 -f 388//388 389//389 390//390 -f 390//390 389//389 391//391 -f 390//390 391//391 392//392 -f 392//392 391//391 393//393 -f 392//392 393//393 394//394 -f 394//394 393//393 395//395 -f 394//394 395//395 396//396 -f 396//396 395//395 397//397 -f 396//396 397//397 398//398 -f 398//398 397//397 399//399 -f 398//398 399//399 400//400 -f 400//400 399//399 401//401 -f 400//400 401//401 402//402 -f 402//402 401//401 403//403 -f 402//402 403//403 380//380 -f 380//380 403//403 381//381 -f 404//404 405//405 406//406 -f 406//406 405//405 407//407 -f 406//406 407//407 408//408 -f 408//408 407//407 409//409 -f 408//408 409//409 410//410 -f 410//410 409//409 411//411 -f 410//410 411//411 412//412 -f 412//412 411//411 413//413 -f 412//412 413//413 414//414 -f 414//414 413//413 415//415 -f 414//414 415//415 416//416 -f 416//416 415//415 417//417 -f 416//416 417//417 418//418 -f 418//418 417//417 419//419 -f 418//418 419//419 420//420 -f 420//420 419//419 421//421 -f 420//420 421//421 422//422 -f 422//422 421//421 423//423 -f 422//422 423//423 424//424 -f 424//424 423//423 425//425 -f 424//424 425//425 426//426 -f 426//426 425//425 427//427 -f 426//426 427//427 404//404 -f 404//404 427//427 405//405 -f 428//428 429//429 430//430 -f 430//430 429//429 431//431 -f 430//430 431//431 432//432 -f 432//432 431//431 433//433 -f 432//432 433//433 434//434 -f 434//434 433//433 435//435 -f 434//434 435//435 436//436 -f 436//436 435//435 437//437 -f 436//436 437//437 438//438 -f 438//438 437//437 439//439 -f 438//438 439//439 440//440 -f 440//440 439//439 441//441 -f 440//440 441//441 442//442 -f 442//442 441//441 443//443 -f 442//442 443//443 444//444 -f 444//444 443//443 445//445 -f 444//444 445//445 446//446 -f 446//446 445//445 447//447 -f 446//446 447//447 448//448 -f 448//448 447//447 449//449 -f 448//448 449//449 450//450 -f 450//450 449//449 451//451 -f 450//450 451//451 428//428 -f 428//428 451//451 429//429 -f 452//452 453//453 454//454 -f 454//454 453//453 455//455 -f 454//454 455//455 456//456 -f 456//456 455//455 457//457 -f 456//456 457//457 458//458 -f 458//458 457//457 459//459 -f 458//458 459//459 460//460 -f 460//460 459//459 461//461 -f 460//460 461//461 462//462 -f 462//462 461//461 463//463 -f 462//462 463//463 464//464 -f 464//464 463//463 465//465 -f 464//464 465//465 466//466 -f 466//466 465//465 467//467 -f 466//466 467//467 468//468 -f 468//468 467//467 469//469 -f 468//468 469//469 470//470 -f 470//470 469//469 471//471 -f 470//470 471//471 472//472 -f 472//472 471//471 473//473 -f 472//472 473//473 474//474 -f 474//474 473//473 475//475 -f 474//474 475//475 452//452 -f 452//452 475//475 453//453 -f 476//476 477//477 478//478 -f 478//478 477//477 479//479 -f 478//478 479//479 480//480 -f 480//480 479//479 481//481 -f 480//480 481//481 482//482 -f 482//482 481//481 483//483 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 486//486 -f 486//486 485//485 487//487 -f 486//486 487//487 488//488 -f 488//488 487//487 489//489 -f 488//488 489//489 490//490 -f 490//490 489//489 491//491 -f 490//490 491//491 492//492 -f 492//492 491//491 493//493 -f 492//492 493//493 494//494 -f 494//494 493//493 495//495 -f 494//494 495//495 496//496 -f 496//496 495//495 497//497 -f 496//496 497//497 498//498 -f 498//498 497//497 499//499 -f 498//498 499//499 476//476 -f 476//476 499//499 477//477 -f 500//500 501//501 502//502 -f 502//502 501//501 503//503 -f 502//502 503//503 504//504 -f 504//504 503//503 505//505 -f 504//504 505//505 506//506 -f 506//506 505//505 507//507 -f 506//506 507//507 508//508 -f 508//508 507//507 509//509 -f 508//508 509//509 510//510 -f 510//510 509//509 511//511 -f 510//510 511//511 512//512 -f 512//512 511//511 513//513 -f 512//512 513//513 514//514 -f 514//514 513//513 515//515 -f 514//514 515//515 516//516 -f 516//516 515//515 517//517 -f 516//516 517//517 518//518 -f 518//518 517//517 519//519 -f 518//518 519//519 520//520 -f 520//520 519//519 521//521 -f 520//520 521//521 522//522 -f 522//522 521//521 523//523 -f 522//522 523//523 500//500 -f 500//500 523//523 501//501 -f 524//524 525//525 526//526 -f 526//526 525//525 527//527 -f 526//526 527//527 528//528 -f 528//528 527//527 529//529 -f 528//528 529//529 530//530 -f 530//530 529//529 531//531 -f 530//530 531//531 532//532 -f 532//532 531//531 533//533 -f 532//532 533//533 534//534 -f 534//534 533//533 535//535 -f 534//534 535//535 536//536 -f 536//536 535//535 537//537 -f 536//536 537//537 538//538 -f 538//538 537//537 539//539 -f 538//538 539//539 540//540 -f 540//540 539//539 541//541 -f 540//540 541//541 542//542 -f 542//542 541//541 543//543 -f 542//542 543//543 544//544 -f 544//544 543//543 545//545 -f 544//544 545//545 546//546 -f 546//546 545//545 547//547 -f 546//546 547//547 524//524 -f 524//524 547//547 525//525 -f 548//548 549//549 550//550 -f 550//550 549//549 551//551 -f 550//550 551//551 552//552 -f 552//552 551//551 553//553 -f 552//552 553//553 554//554 -f 554//554 553//553 555//555 -f 554//554 555//555 556//556 -f 556//556 555//555 557//557 -f 556//556 557//557 558//558 -f 558//558 557//557 559//559 -f 558//558 559//559 560//560 -f 560//560 559//559 561//561 -f 560//560 561//561 562//562 -f 562//562 561//561 563//563 -f 562//562 563//563 564//564 -f 564//564 563//563 565//565 -f 564//564 565//565 566//566 -f 566//566 565//565 567//567 -f 566//566 567//567 568//568 -f 568//568 567//567 569//569 -f 568//568 569//569 570//570 -f 570//570 569//569 571//571 -f 570//570 571//571 548//548 -f 548//548 571//571 549//549 -f 572//572 573//573 574//574 -f 574//574 573//573 575//575 -f 574//574 575//575 576//576 -f 576//576 575//575 577//577 -f 576//576 577//577 578//578 -f 578//578 577//577 579//579 -f 578//578 579//579 580//580 -f 580//580 579//579 581//581 -f 580//580 581//581 582//582 -f 582//582 581//581 583//583 -f 582//582 583//583 584//584 -f 584//584 583//583 585//585 -f 584//584 585//585 586//586 -f 586//586 585//585 587//587 -f 586//586 587//587 588//588 -f 588//588 587//587 589//589 -f 588//588 589//589 590//590 -f 590//590 589//589 591//591 -f 590//590 591//591 592//592 -f 592//592 591//591 593//593 -f 592//592 593//593 594//594 -f 594//594 593//593 595//595 -f 594//594 595//595 572//572 -f 572//572 595//595 573//573 -f 596//596 597//597 598//598 -f 598//598 597//597 599//599 -f 598//598 599//599 600//600 -f 600//600 599//599 601//601 -f 600//600 601//601 602//602 -f 602//602 601//601 603//603 -f 602//602 603//603 604//604 -f 604//604 603//603 605//605 -f 604//604 605//605 606//606 -f 606//606 605//605 607//607 -f 606//606 607//607 608//608 -f 608//608 607//607 609//609 -f 608//608 609//609 610//610 -f 610//610 609//609 611//611 -f 610//610 611//611 612//612 -f 612//612 611//611 613//613 -f 612//612 613//613 614//614 -f 614//614 613//613 615//615 -f 614//614 615//615 616//616 -f 616//616 615//615 617//617 -f 616//616 617//617 618//618 -f 618//618 617//617 619//619 -f 618//618 619//619 596//596 -f 596//596 619//619 597//597 -f 620//620 621//621 622//622 -f 622//622 621//621 623//623 -f 622//622 623//623 624//624 -f 624//624 623//623 625//625 -f 624//624 625//625 626//626 -f 626//626 625//625 627//627 -f 626//626 627//627 628//628 -f 628//628 627//627 629//629 -f 628//628 629//629 630//630 -f 630//630 629//629 631//631 -f 630//630 631//631 632//632 -f 632//632 631//631 633//633 -f 632//632 633//633 634//634 -f 634//634 633//633 635//635 -f 634//634 635//635 636//636 -f 636//636 635//635 637//637 -f 636//636 637//637 638//638 -f 638//638 637//637 639//639 -f 638//638 639//639 640//640 -f 640//640 639//639 641//641 -f 640//640 641//641 642//642 -f 642//642 641//641 643//643 -f 642//642 643//643 620//620 -f 620//620 643//643 621//621 -f 644//644 645//645 646//646 -f 646//646 645//645 647//647 -f 646//646 647//647 648//648 -f 648//648 647//647 649//649 -f 648//648 649//649 650//650 -f 650//650 649//649 651//651 -f 650//650 651//651 652//652 -f 652//652 651//651 653//653 -f 652//652 653//653 654//654 -f 654//654 653//653 655//655 -f 654//654 655//655 656//656 -f 656//656 655//655 657//657 -f 656//656 657//657 658//658 -f 658//658 657//657 659//659 -f 658//658 659//659 660//660 -f 660//660 659//659 661//661 -f 660//660 661//661 662//662 -f 662//662 661//661 663//663 -f 662//662 663//663 664//664 -f 664//664 663//663 665//665 -f 664//664 665//665 666//666 -f 666//666 665//665 667//667 -f 666//666 667//667 644//644 -f 644//644 667//667 645//645 -f 61//61 63//63 668//668 -f 669//669 670//670 671//671 -f 671//671 670//670 672//672 -f 671//671 672//672 668//668 -f 668//668 672//672 262//262 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 260//260 -f 260//260 676//676 677//677 -f 260//260 677//677 262//262 -f 262//262 677//677 668//668 -f 668//668 677//677 143//143 -f 668//668 143//143 61//61 -f 277//277 276//276 678//678 -f 678//678 276//276 679//679 -f 678//678 679//679 680//680 -f 679//679 681//681 680//680 -f 680//680 681//681 670//670 -f 680//680 670//670 669//669 -f 266//266 268//268 682//682 -f 266//266 682//682 683//683 -f 683//683 682//682 674//674 -f 683//683 674//674 673//673 -f 472//472 474//474 252//252 -f 252//252 474//474 452//452 -f 252//252 452//452 250//250 -f 452//452 454//454 250//250 -f 250//250 454//454 456//456 -f 250//250 456//456 684//684 -f 684//684 456//456 458//458 -f 684//684 458//458 312//312 -f 472//472 252//252 470//470 -f 470//470 252//252 685//685 -f 470//470 685//685 468//468 -f 468//468 685//685 310//310 -f 468//468 310//310 466//466 -f 458//458 460//460 312//312 -f 312//312 460//460 462//462 -f 312//312 462//462 310//310 -f 310//310 462//462 464//464 -f 310//310 464//464 466//466 -f 275//275 486//486 488//488 -f 275//275 488//488 312//312 -f 5//5 306//306 686//686 -f 296//296 298//298 45//45 -f 298//298 300//300 45//45 -f 45//45 300//300 302//302 -f 45//45 302//302 5//5 -f 5//5 302//302 304//304 -f 5//5 304//304 306//306 -f 679//679 418//418 420//420 -f 294//294 296//296 687//687 -f 408//408 410//410 688//688 -f 679//679 420//420 681//681 -f 681//681 420//420 422//422 -f 681//681 422//422 424//424 -f 410//410 412//412 688//688 -f 688//688 412//412 414//414 -f 688//688 414//414 416//416 -f 330//330 284//284 406//406 -f 406//406 284//284 286//286 -f 406//406 286//286 404//404 -f 404//404 286//286 288//288 -f 404//404 288//288 426//426 -f 394//394 396//396 688//688 -f 394//394 688//688 392//392 -f 392//392 688//688 689//689 -f 392//392 689//689 390//390 -f 396//396 398//398 688//688 -f 688//688 398//398 330//330 -f 688//688 330//330 408//408 -f 408//408 330//330 406//406 -f 384//384 386//386 689//689 -f 689//689 386//386 388//388 -f 689//689 388//388 390//390 -f 398//398 400//400 330//330 -f 330//330 400//400 402//402 -f 330//330 402//402 331//331 -f 331//331 402//402 380//380 -f 331//331 380//380 327//327 -f 382//382 316//316 380//380 -f 380//380 316//316 318//318 -f 380//380 318//318 327//327 -f 366//366 368//368 690//690 -f 372//372 374//374 689//689 -f 690//690 368//368 689//689 -f 689//689 368//368 370//370 -f 689//689 370//370 372//372 -f 382//382 384//384 316//316 -f 316//316 384//384 689//689 -f 316//316 689//689 314//314 -f 314//314 689//689 374//374 -f 314//314 374//374 376//376 -f 360//360 362//362 690//690 -f 690//690 362//362 364//364 -f 690//690 364//364 366//366 -f 376//376 378//378 314//314 -f 314//314 378//378 356//356 -f 314//314 356//356 320//320 -f 320//320 356//356 358//358 -f 334//334 336//336 55//55 -f 55//55 336//336 53//53 -f 53//53 336//336 338//338 -f 53//53 338//338 340//340 -f 340//340 342//342 53//53 -f 53//53 342//342 344//344 -f 53//53 344//344 690//690 -f 690//690 344//344 346//346 -f 690//690 346//346 348//348 -f 348//348 350//350 690//690 -f 690//690 350//350 320//320 -f 690//690 320//320 360//360 -f 360//360 320//320 358//358 -f 350//350 352//352 320//320 -f 320//320 352//352 354//354 -f 320//320 354//354 55//55 -f 55//55 354//354 332//332 -f 55//55 332//332 334//334 -f 276//276 688//688 679//679 -f 679//679 688//688 416//416 -f 679//679 416//416 418//418 -f 261//261 262//262 687//687 -f 687//687 262//262 672//672 -f 288//288 290//290 426//426 -f 426//426 290//290 292//292 -f 426//426 292//292 424//424 -f 424//424 292//292 294//294 -f 424//424 294//294 681//681 -f 681//681 294//294 687//687 -f 681//681 687//687 670//670 -f 670//670 687//687 672//672 -f 296//296 45//45 687//687 -f 687//687 45//45 42//42 -f 687//687 42//42 261//261 -f 254//254 1//1 686//686 -f 686//686 1//1 3//3 -f 686//686 3//3 5//5 -f 248//248 480//480 273//273 -f 273//273 480//480 482//482 -f 273//273 482//482 275//275 -f 275//275 482//482 484//484 -f 275//275 484//484 486//486 -f 488//488 490//490 312//312 -f 312//312 490//490 492//492 -f 312//312 492//492 684//684 -f 684//684 492//492 494//494 -f 684//684 494//494 250//250 -f 250//250 494//494 496//496 -f 496//496 498//498 250//250 -f 250//250 498//498 476//476 -f 250//250 476//476 248//248 -f 248//248 476//476 478//478 -f 248//248 478//478 480//480 -f 252//252 432//432 685//685 -f 685//685 432//432 434//434 -f 685//685 434//434 310//310 -f 310//310 434//434 436//436 -f 310//310 436//436 308//308 -f 308//308 436//436 438//438 -f 308//308 438//438 325//325 -f 325//325 438//438 440//440 -f 325//325 440//440 323//323 -f 323//323 440//440 442//442 -f 323//323 442//442 306//306 -f 306//306 442//442 444//444 -f 306//306 444//444 686//686 -f 686//686 444//444 446//446 -f 686//686 446//446 254//254 -f 254//254 446//446 448//448 -f 448//448 450//450 254//254 -f 254//254 450//450 428//428 -f 254//254 428//428 252//252 -f 252//252 428//428 430//430 -f 252//252 430//430 432//432 -f 276//276 278//278 688//688 -f 688//688 278//278 280//280 -f 688//688 280//280 689//689 -f 689//689 280//280 282//282 -f 689//689 282//282 690//690 -f 690//690 282//282 51//51 -f 690//690 51//51 53//53 -f 597//597 619//619 7//7 -f 7//7 619//619 617//617 -f 7//7 617//617 9//9 -f 9//9 617//617 615//615 -f 9//9 615//615 613//613 -f 599//599 643//643 601//601 -f 601//601 643//643 641//641 -f 601//601 641//641 603//603 -f 603//603 641//641 639//639 -f 603//603 639//639 605//605 -f 605//605 639//639 637//637 -f 605//605 637//637 635//635 -f 627//627 645//645 667//667 -f 649//649 647//647 239//239 -f 239//239 647//647 645//645 -f 613//613 611//611 9//9 -f 9//9 611//611 609//609 -f 9//9 609//609 40//40 -f 10//10 12//12 40//40 -f 40//40 12//12 14//14 -f 40//40 14//14 16//16 -f 16//16 18//18 40//40 -f 40//40 18//18 20//20 -f 40//40 20//20 22//22 -f 661//661 629//629 663//663 -f 663//663 629//629 627//627 -f 663//663 627//627 665//665 -f 665//665 627//627 667//667 -f 270//270 653//653 239//239 -f 239//239 653//653 651//651 -f 239//239 651//651 649//649 -f 599//599 597//597 643//643 -f 643//643 597//597 7//7 -f 643//643 7//7 621//621 -f 621//621 7//7 239//239 -f 621//621 239//239 623//623 -f 623//623 239//239 645//645 -f 623//623 645//645 625//625 -f 625//625 645//645 627//627 -f 633//633 609//609 635//635 -f 635//635 609//609 607//607 -f 635//635 607//607 605//605 -f 661//661 659//659 629//629 -f 629//629 659//659 657//657 -f 629//629 657//657 270//270 -f 270//270 657//657 655//655 -f 270//270 655//655 653//653 -f 40//40 609//609 10//10 -f 10//10 609//609 633//633 -f 10//10 633//633 270//270 -f 270//270 633//633 631//631 -f 270//270 631//631 629//629 -f 559//559 543//543 561//561 -f 561//561 543//543 541//541 -f 561//561 541//541 539//539 -f 573//573 36//36 38//38 -f 547//547 38//38 525//525 -f 525//525 38//38 59//59 -f 525//525 59//59 527//527 -f 517//517 533//533 519//519 -f 519//519 533//533 531//531 -f 519//519 531//531 521//521 -f 559//559 557//557 543//543 -f 543//543 557//557 555//555 -f 543//543 555//555 545//545 -f 545//545 555//555 553//553 -f 545//545 553//553 547//547 -f 553//553 551//551 547//547 -f 547//547 551//551 549//549 -f 547//547 549//549 38//38 -f 38//38 549//549 571//571 -f 36//36 573//573 34//34 -f 34//34 573//573 595//595 -f 34//34 595//595 593//593 -f 583//583 581//581 569//569 -f 569//569 581//581 579//579 -f 569//569 579//579 571//571 -f 571//571 579//579 577//577 -f 571//571 577//577 38//38 -f 38//38 577//577 575//575 -f 38//38 575//575 573//573 -f 513//513 511//511 60//60 -f 27//27 28//28 260//260 -f 260//260 28//28 30//30 -f 260//260 30//30 675//675 -f 675//675 30//30 32//32 -f 675//675 32//32 673//673 -f 511//511 509//509 60//60 -f 60//60 509//509 507//507 -f 60//60 507//507 59//59 -f 507//507 505//505 59//59 -f 59//59 505//505 503//503 -f 59//59 503//503 501//501 -f 266//266 683//683 591//591 -f 591//591 683//683 673//673 -f 591//591 673//673 593//593 -f 593//593 673//673 32//32 -f 593//593 32//32 34//34 -f 527//527 59//59 529//529 -f 529//529 59//59 501//501 -f 529//529 501//501 531//531 -f 531//531 501//501 523//523 -f 531//531 523//523 521//521 -f 591//591 589//589 266//266 -f 266//266 589//589 587//587 -f 266//266 587//587 585//585 -f 266//266 537//537 60//60 -f 60//60 537//537 535//535 -f 60//60 535//535 513//513 -f 513//513 535//535 533//533 -f 513//513 533//533 515//515 -f 515//515 533//533 517//517 -f 539//539 537//537 561//561 -f 561//561 537//537 266//266 -f 561//561 266//266 563//563 -f 563//563 266//266 585//585 -f 563//563 585//585 565//565 -f 565//565 585//585 583//583 -f 565//565 583//583 567//567 -f 567//567 583//583 569//569 -f 691//691 57//57 59//59 -f 39//39 692//692 38//38 -f 38//38 692//692 693//693 -f 38//38 693//693 59//59 -f 59//59 693//693 694//694 -f 59//59 694//694 691//691 -f 695//695 11//11 10//10 -f 269//269 696//696 270//270 -f 270//270 696//696 697//697 -f 270//270 697//697 10//10 -f 10//10 697//697 698//698 -f 10//10 698//698 695//695 -f 259//259 247//247 46//46 -f 46//46 247//247 47//47 -f 50//50 48//48 245//245 -f 245//245 48//48 246//246 -f 246//246 48//48 247//247 -f 247//247 48//48 47//47 -f 6//6 8//8 237//237 -f 237//237 8//8 44//44 -f 237//237 44//44 238//238 -f 238//238 44//44 41//41 -f 238//238 41//41 245//245 -f 245//245 41//41 50//50 -f 4//4 2//2 43//43 -f 43//43 2//2 257//257 -f 43//43 257//257 49//49 -f 49//49 257//257 258//258 -f 49//49 258//258 46//46 -f 46//46 258//258 259//259 -f 277//277 678//678 699//699 -f 668//668 63//63 77//77 -f 449//449 447//447 700//700 -f 433//433 431//431 253//253 -f 253//253 431//431 429//429 -f 253//253 429//429 255//255 -f 255//255 429//429 451//451 -f 441//441 322//322 443//443 -f 443//443 322//322 307//307 -f 443//443 307//307 445//445 -f 433//433 253//253 435//435 -f 435//435 253//253 701//701 -f 435//435 701//701 437//437 -f 437//437 701//701 311//311 -f 437//437 311//311 439//439 -f 439//439 311//311 309//309 -f 439//439 309//309 441//441 -f 441//441 309//309 324//324 -f 441//441 324//324 322//322 -f 479//479 477//477 249//249 -f 249//249 477//477 251//251 -f 477//477 499//499 251//251 -f 251//251 499//499 497//497 -f 251//251 497//497 702//702 -f 702//702 497//497 495//495 -f 702//702 495//495 313//313 -f 495//495 493//493 313//313 -f 313//313 493//493 491//491 -f 313//313 491//491 274//274 -f 274//274 491//491 489//489 -f 489//489 487//487 274//274 -f 274//274 487//487 485//485 -f 274//274 485//485 272//272 -f 272//272 485//485 483//483 -f 272//272 483//483 249//249 -f 249//249 483//483 481//481 -f 249//249 481//481 479//479 -f 337//337 335//335 56//56 -f 56//56 335//335 333//333 -f 56//56 333//333 321//321 -f 333//333 355//355 321//321 -f 321//321 355//355 353//353 -f 321//321 353//353 703//703 -f 703//703 353//353 351//351 -f 703//703 351//351 349//349 -f 337//337 56//56 339//339 -f 339//339 56//56 54//54 -f 339//339 54//54 341//341 -f 349//349 347//347 703//703 -f 703//703 347//347 345//345 -f 703//703 345//345 54//54 -f 54//54 345//345 343//343 -f 54//54 343//343 341//341 -f 365//365 363//363 703//703 -f 377//377 375//375 704//704 -f 704//704 375//375 373//373 -f 357//357 315//315 359//359 -f 359//359 315//315 321//321 -f 703//703 363//363 321//321 -f 321//321 363//363 361//361 -f 321//321 361//361 359//359 -f 373//373 371//371 704//704 -f 704//704 371//371 369//369 -f 704//704 369//369 703//703 -f 703//703 369//369 367//367 -f 703//703 367//367 365//365 -f 387//387 385//385 317//317 -f 317//317 385//385 383//383 -f 317//317 383//383 319//319 -f 319//319 383//383 381//381 -f 319//319 381//381 328//328 -f 389//389 387//387 704//704 -f 704//704 387//387 317//317 -f 704//704 317//317 377//377 -f 377//377 317//317 315//315 -f 377//377 315//315 379//379 -f 379//379 315//315 357//357 -f 328//328 381//381 326//326 -f 326//326 381//381 403//403 -f 326//326 403//403 329//329 -f 329//329 403//403 401//401 -f 329//329 401//401 699//699 -f 699//699 401//401 399//399 -f 699//699 399//399 397//397 -f 397//397 395//395 699//699 -f 699//699 395//395 393//393 -f 699//699 393//393 704//704 -f 704//704 393//393 391//391 -f 704//704 391//391 389//389 -f 287//287 285//285 407//407 -f 407//407 285//285 329//329 -f 407//407 329//329 409//409 -f 705//705 295//295 293//293 -f 409//409 329//329 411//411 -f 411//411 329//329 699//699 -f 411//411 699//699 413//413 -f 287//287 407//407 289//289 -f 289//289 407//407 405//405 -f 289//289 405//405 291//291 -f 291//291 405//405 427//427 -f 291//291 427//427 293//293 -f 423//423 421//421 678//678 -f 427//427 425//425 669//669 -f 669//669 425//425 423//423 -f 669//669 423//423 680//680 -f 680//680 423//423 678//678 -f 421//421 419//419 678//678 -f 678//678 419//419 417//417 -f 678//678 417//417 699//699 -f 699//699 417//417 415//415 -f 699//699 415//415 413//413 -f 303//303 301//301 706//706 -f 706//706 301//301 299//299 -f 706//706 299//299 705//705 -f 705//705 299//299 297//297 -f 705//705 297//297 295//295 -f 303//303 706//706 305//305 -f 305//305 706//706 700//700 -f 305//305 700//700 307//307 -f 307//307 700//700 447//447 -f 307//307 447//447 445//445 -f 311//311 467//467 465//465 -f 311//311 465//465 313//313 -f 668//668 77//77 671//671 -f 293//293 427//427 705//705 -f 705//705 427//427 669//669 -f 705//705 669//669 671//671 -f 465//465 463//463 313//313 -f 313//313 463//463 461//461 -f 313//313 461//461 702//702 -f 702//702 461//461 459//459 -f 702//702 459//459 251//251 -f 251//251 459//459 457//457 -f 253//253 473//473 701//701 -f 701//701 473//473 471//471 -f 701//701 471//471 311//311 -f 311//311 471//471 469//469 -f 311//311 469//469 467//467 -f 457//457 455//455 251//251 -f 251//251 455//455 453//453 -f 251//251 453//453 253//253 -f 253//253 453//453 475//475 -f 253//253 475//475 473//473 -f 54//54 52//52 703//703 -f 703//703 52//52 283//283 -f 703//703 283//283 704//704 -f 704//704 283//283 281//281 -f 704//704 281//281 699//699 -f 699//699 281//281 279//279 -f 699//699 279//279 277//277 -f 451//451 449//449 255//255 -f 255//255 449//449 700//700 -f 255//255 700//700 256//256 -f 256//256 700//700 706//706 -f 671//671 77//77 705//705 -f 705//705 77//77 94//94 -f 705//705 94//94 706//706 -f 706//706 94//94 92//92 -f 706//706 92//92 256//256 -f 113//113 107//107 707//707 -f 516//516 518//518 264//264 -f 540//540 542//542 265//265 -f 564//564 566//566 267//267 -f 578//578 580//580 267//267 -f 592//592 594//594 35//35 -f 576//576 692//692 574//574 -f 574//574 692//692 39//39 -f 574//574 39//39 572//572 -f 143//143 677//677 23//23 -f 23//23 677//677 29//29 -f 578//578 267//267 576//576 -f 33//33 676//676 674//674 -f 572//572 39//39 594//594 -f 594//594 39//39 37//37 -f 594//594 37//37 35//35 -f 676//676 33//33 677//677 -f 677//677 33//33 31//31 -f 677//677 31//31 29//29 -f 35//35 33//33 592//592 -f 592//592 33//33 674//674 -f 592//592 674//674 590//590 -f 590//590 674//674 682//682 -f 590//590 682//682 588//588 -f 588//588 682//682 268//268 -f 580//580 582//582 267//267 -f 267//267 582//582 584//584 -f 267//267 584//584 268//268 -f 268//268 584//584 586//586 -f 268//268 586//586 588//588 -f 554//554 556//556 265//265 -f 576//576 267//267 692//692 -f 692//692 267//267 566//566 -f 692//692 566//566 568//568 -f 568//568 570//570 692//692 -f 692//692 570//570 548//548 -f 692//692 548//548 693//693 -f 693//693 548//548 550//550 -f 693//693 550//550 552//552 -f 554//554 265//265 552//552 -f 556//556 558//558 265//265 -f 265//265 558//558 560//560 -f 265//265 560//560 267//267 -f 267//267 560//560 562//562 -f 267//267 562//562 564//564 -f 552//552 265//265 693//693 -f 693//693 265//265 542//542 -f 693//693 542//542 544//544 -f 544//544 546//546 693//693 -f 693//693 546//546 524//524 -f 693//693 524//524 694//694 -f 694//694 524//524 526//526 -f 694//694 526//526 528//528 -f 528//528 530//530 264//264 -f 264//264 530//530 532//532 -f 532//532 534//534 264//264 -f 264//264 534//534 536//536 -f 264//264 536//536 265//265 -f 265//265 536//536 538//538 -f 265//265 538//538 540//540 -f 506//506 508//508 263//263 -f 528//528 264//264 694//694 -f 694//694 264//264 518//518 -f 694//694 518//518 520//520 -f 506//506 263//263 504//504 -f 520//520 522//522 694//694 -f 694//694 522//522 500//500 -f 694//694 500//500 691//691 -f 691//691 500//500 502//502 -f 691//691 502//502 504//504 -f 508//508 510//510 263//263 -f 263//263 510//510 512//512 -f 263//263 512//512 264//264 -f 264//264 512//512 514//514 -f 264//264 514//514 516//516 -f 504//504 263//263 691//691 -f 691//691 263//263 58//58 -f 691//691 58//58 57//57 -f 696//696 269//269 708//708 -f 708//708 269//269 271//271 -f 697//697 660//660 709//709 -f 709//709 660//660 662//662 -f 709//709 662//662 664//664 -f 664//664 666//666 709//709 -f 709//709 666//666 644//644 -f 709//709 644//644 708//708 -f 708//708 644//644 646//646 -f 652//652 696//696 650//650 -f 650//650 696//696 708//708 -f 650//650 708//708 648//648 -f 648//648 708//708 646//646 -f 652//652 654//654 696//696 -f 696//696 654//654 656//656 -f 696//696 656//656 697//697 -f 697//697 656//656 658//658 -f 697//697 658//658 660//660 -f 640//640 642//642 710//710 -f 710//710 642//642 620//620 -f 710//710 620//620 709//709 -f 709//709 620//620 622//622 -f 622//622 624//624 709//709 -f 709//709 624//624 626//626 -f 709//709 626//626 697//697 -f 697//697 626//626 628//628 -f 628//628 630//630 697//697 -f 697//697 630//630 632//632 -f 697//697 632//632 698//698 -f 632//632 634//634 698//698 -f 698//698 634//634 636//636 -f 698//698 636//636 710//710 -f 710//710 636//636 638//638 -f 710//710 638//638 640//640 -f 616//616 618//618 707//707 -f 707//707 618//618 596//596 -f 707//707 596//596 710//710 -f 710//710 596//596 598//598 -f 695//695 612//612 707//707 -f 707//707 612//612 614//614 -f 707//707 614//614 616//616 -f 604//604 698//698 602//602 -f 602//602 698//698 710//710 -f 602//602 710//710 600//600 -f 600//600 710//710 598//598 -f 604//604 606//606 698//698 -f 698//698 606//606 608//608 -f 698//698 608//608 695//695 -f 695//695 608//608 610//610 -f 695//695 610//610 612//612 -f 143//143 23//23 109//109 -f 109//109 23//23 21//21 -f 109//109 21//21 107//107 -f 107//107 21//21 19//19 -f 107//107 19//19 17//17 -f 17//17 15//15 107//107 -f 107//107 15//15 13//13 -f 107//107 13//13 707//707 -f 707//707 13//13 11//11 -f 707//707 11//11 695//695 -f 113//113 707//707 244//244 -f 244//244 707//707 710//710 -f 244//244 710//710 240//240 -f 240//240 710//710 709//709 -f 240//240 709//709 241//241 -f 241//241 709//709 708//708 -f 241//241 708//708 242//242 -f 242//242 708//708 271//271 -f 242//242 271//271 243//243 -# 1488 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sablja_sisaljka.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sablja_sisaljka.obj deleted file mode 100644 index 68c07ce25..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sablja_sisaljka.obj +++ /dev/null @@ -1,11600 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sablja_sisaljka.obj -# -# Vertices: 2896 -# Faces: 5792 -# -#### -vn -0.000002 6.228199 0.454461 -v 0.066656 0.007106 0.141472 -vn 0.580567 5.894611 1.772174 -v 0.067436 0.007025 0.141760 -vn 0.610471 6.198203 0.453170 -v 0.067440 0.007067 0.141472 -vn 1.155550 5.809320 1.772161 -v 0.068208 0.006910 0.141760 -vn 1.215066 6.108529 0.454443 -v 0.068217 0.006952 0.141472 -vn 1.719399 5.668083 1.772161 -v 0.068966 0.006721 0.141760 -vn 1.807946 5.960013 0.453159 -v 0.068978 0.006761 0.141472 -vn 2.266687 5.472263 1.772177 -v 0.069701 0.006458 0.141760 -vn 2.383425 5.754104 0.454473 -v 0.069717 0.006497 0.141472 -vn 2.792140 5.223737 1.772192 -v 0.070407 0.006124 0.141760 -vn 2.935955 5.492773 0.453178 -v 0.070427 0.006161 0.141472 -vn 3.290718 4.924892 1.772158 -v 0.071077 0.005722 0.141760 -vn 3.460213 5.178560 0.454425 -v 0.071101 0.005757 0.141472 -vn 3.757594 4.578649 1.772177 -v 0.071704 0.005257 0.141760 -vn 3.951110 4.814469 0.453178 -v 0.071731 0.005290 0.141472 -vn 4.188272 4.188283 1.772197 -v 0.072283 0.004733 0.141760 -vn 4.403999 4.404003 0.454456 -v 0.072313 0.004763 0.141472 -vn 4.578634 3.757586 1.772184 -v 0.072807 0.004154 0.141760 -vn 4.814470 3.951120 0.453143 -v 0.072840 0.004181 0.141472 -vn 4.924903 3.290712 1.772148 -v 0.073273 0.003527 0.141760 -vn 5.178567 3.460202 0.454423 -v 0.073308 0.003550 0.141472 -vn 5.223752 2.792140 1.772135 -v 0.073674 0.002857 0.141760 -vn 5.492776 2.935961 0.453156 -v 0.073711 0.002877 0.141472 -vn 5.472241 2.266694 1.772218 -v 0.074008 0.002151 0.141760 -vn 5.754098 2.383431 0.454474 -v 0.074047 0.002167 0.141472 -vn 5.668093 1.719385 1.772138 -v 0.074271 0.001416 0.141760 -vn 5.960022 1.807946 0.453134 -v 0.074312 0.001428 0.141472 -vn 5.809294 1.155543 1.772215 -v 0.074461 0.000658 0.141760 -vn 6.108522 1.215070 0.454457 -v 0.074502 0.000666 0.141472 -vn 5.894604 0.580565 1.772199 -v 0.074575 -0.000114 0.141760 -vn 6.198204 0.610455 0.453178 -v 0.074617 -0.000110 0.141472 -vn 5.923145 -0.000012 1.772136 -v 0.074614 -0.000894 0.141760 -vn 6.228203 -0.000004 0.454445 -v 0.074656 -0.000894 0.141472 -vn 5.894600 -0.580555 1.772206 -v 0.074575 -0.001674 0.141760 -vn 6.198204 -0.610449 0.453179 -v 0.074617 -0.001678 0.141472 -vn 5.809299 -1.155525 1.772217 -v 0.074461 -0.002447 0.141760 -vn 6.108524 -1.215067 0.454451 -v 0.074502 -0.002455 0.141472 -vn 5.668085 -1.719415 1.772132 -v 0.074271 -0.003204 0.141760 -vn 5.960017 -1.807960 0.453137 -v 0.074312 -0.003217 0.141472 -vn 5.472253 -2.266666 1.772213 -v 0.074008 -0.003940 0.141760 -vn 5.754104 -2.383417 0.454476 -v 0.074047 -0.003956 0.141472 -vn 5.223744 -2.792156 1.772141 -v 0.073674 -0.004646 0.141760 -vn 5.492775 -2.935965 0.453148 -v 0.073711 -0.004666 0.141472 -vn 4.924898 -3.290712 1.772156 -v 0.073273 -0.005315 0.141760 -vn 5.178564 -3.460206 0.454421 -v 0.073308 -0.005339 0.141472 -vn 4.578635 -3.757583 1.772182 -v 0.072807 -0.005943 0.141760 -vn 4.814468 -3.951122 0.453147 -v 0.072840 -0.005969 0.141472 -vn 4.188276 -4.188282 1.772189 -v 0.072283 -0.006521 0.141760 -vn 4.404000 -4.404000 0.454460 -v 0.072313 -0.006551 0.141472 -vn 3.757593 -4.578648 1.772183 -v 0.071704 -0.007046 0.141760 -vn 3.951118 -4.814464 0.453173 -v 0.071731 -0.007078 0.141472 -vn 3.290713 -4.924895 1.772159 -v 0.071077 -0.007511 0.141760 -vn 3.460202 -5.178568 0.454425 -v 0.071101 -0.007546 0.141472 -vn 2.792146 -5.223734 1.772184 -v 0.070407 -0.007912 0.141760 -vn 2.935961 -5.492767 0.453185 -v 0.070427 -0.007950 0.141472 -vn 2.266688 -5.472263 1.772181 -v 0.069701 -0.008246 0.141760 -vn 2.383430 -5.754102 0.454474 -v 0.069717 -0.008285 0.141472 -vn 1.719396 -5.668082 1.772167 -v 0.068966 -0.008509 0.141760 -vn 1.807943 -5.960015 0.453156 -v 0.068978 -0.008550 0.141472 -vn 1.155548 -5.809320 1.772164 -v 0.068208 -0.008699 0.141760 -vn 1.215063 -6.108528 0.454449 -v 0.068217 -0.008741 0.141472 -vn 0.580571 -5.894611 1.772172 -v 0.067436 -0.008814 0.141760 -vn 0.610474 -6.198203 0.453171 -v 0.067440 -0.008856 0.141472 -vn -0.000002 -5.923135 1.772172 -v 0.066656 -0.008852 0.141760 -vn -0.000001 -6.228199 0.454461 -v 0.066656 -0.008894 0.141472 -vn -0.580570 -5.894611 1.772174 -v 0.065876 -0.008814 0.141760 -vn -0.610474 -6.198203 0.453170 -v 0.065872 -0.008856 0.141472 -vn -1.155550 -5.809320 1.772165 -v 0.065104 -0.008699 0.141760 -vn -1.215065 -6.108528 0.454448 -v 0.065095 -0.008741 0.141472 -vn -1.719398 -5.668083 1.772161 -v 0.064346 -0.008509 0.141760 -vn -1.807947 -5.960013 0.453160 -v 0.064334 -0.008550 0.141472 -vn -2.266685 -5.472267 1.772175 -v 0.063611 -0.008246 0.141760 -vn -2.383424 -5.754103 0.454477 -v 0.063595 -0.008285 0.141472 -vn -2.792150 -5.223745 1.772165 -v 0.062905 -0.007912 0.141760 -vn -2.935955 -5.492773 0.453182 -v 0.062885 -0.007950 0.141472 -vn -3.290716 -4.924911 1.772168 -v 0.062235 -0.007511 0.141760 -vn -3.460205 -5.178556 0.454460 -v 0.062211 -0.007546 0.141472 -vn -3.757594 -4.578649 1.772156 -v 0.061608 -0.007046 0.141760 -vn -3.951127 -4.814462 0.453153 -v 0.061581 -0.007078 0.141472 -vn -4.188290 -4.188288 1.772147 -v 0.061029 -0.006521 0.141760 -vn -4.404006 -4.404006 0.454432 -v 0.060999 -0.006551 0.141472 -vn -4.578646 -3.757588 1.772156 -v 0.060505 -0.005943 0.141760 -vn -4.814461 -3.951130 0.453150 -v 0.060472 -0.005969 0.141472 -vn -4.924906 -3.290719 1.772187 -v 0.060039 -0.005315 0.141760 -vn -5.178548 -3.460208 0.454483 -v 0.060004 -0.005339 0.141472 -vn -5.223730 -2.792147 1.772195 -v 0.059638 -0.004646 0.141760 -vn -5.492777 -2.935944 0.453182 -v 0.059601 -0.004666 0.141472 -vn -5.472262 -2.266686 1.772163 -v 0.059304 -0.003940 0.141760 -vn -5.754111 -2.383426 0.454447 -v 0.059265 -0.003956 0.141472 -vn -5.668087 -1.719399 1.772164 -v 0.059041 -0.003204 0.141760 -vn -5.960010 -1.807952 0.453162 -v 0.059000 -0.003217 0.141472 -vn -5.809316 -1.155536 1.772153 -v 0.058851 -0.002447 0.141760 -vn -6.108536 -1.215053 0.454423 -v 0.058810 -0.002455 0.141472 -vn -5.894619 -0.580567 1.772166 -v 0.058737 -0.001674 0.141760 -vn -6.198201 -0.610478 0.453182 -v 0.058695 -0.001678 0.141472 -vn -5.923143 0.000001 1.772168 -v 0.058698 -0.000894 0.141760 -vn -6.228195 -0.000002 0.454479 -v 0.058656 -0.000894 0.141472 -vn -5.894615 0.580563 1.772179 -v 0.058737 -0.000114 0.141760 -vn -6.198203 0.610472 0.453175 -v 0.058695 -0.000110 0.141472 -vn -5.809315 1.155539 1.772155 -v 0.058851 0.000658 0.141760 -vn -6.108533 1.215066 0.454422 -v 0.058810 0.000666 0.141472 -vn -5.668087 1.719399 1.772158 -v 0.059041 0.001416 0.141760 -vn -5.960011 1.807945 0.453165 -v 0.059000 0.001428 0.141472 -vn -5.472259 2.266690 1.772162 -v 0.059304 0.002151 0.141760 -vn -5.754107 2.383431 0.454449 -v 0.059265 0.002167 0.141472 -vn -5.223733 2.792142 1.772188 -v 0.059638 0.002857 0.141760 -vn -5.492778 2.935941 0.453186 -v 0.059601 0.002877 0.141472 -vn -4.924908 3.290714 1.772193 -v 0.060039 0.003527 0.141760 -vn -5.178555 3.460200 0.454479 -v 0.060004 0.003550 0.141472 -vn -4.578644 3.757589 1.772163 -v 0.060505 0.004154 0.141760 -vn -4.814457 3.951136 0.453144 -v 0.060472 0.004181 0.141472 -vn -4.188288 4.188291 1.772144 -v 0.061029 0.004733 0.141760 -vn -4.404004 4.404007 0.454432 -v 0.060999 0.004763 0.141472 -vn -3.757594 4.578650 1.772151 -v 0.061608 0.005257 0.141760 -vn -3.951126 4.814462 0.453157 -v 0.061581 0.005290 0.141472 -vn -3.290719 4.924912 1.772161 -v 0.062235 0.005722 0.141760 -vn -3.460204 5.178555 0.454463 -v 0.062211 0.005757 0.141472 -vn -2.792147 5.223750 1.772159 -v 0.062905 0.006124 0.141760 -vn -2.935954 5.492773 0.453184 -v 0.062885 0.006161 0.141472 -vn -2.266688 5.472262 1.772180 -v 0.063611 0.006458 0.141760 -vn -2.383429 5.754103 0.454470 -v 0.063595 0.006497 0.141472 -vn -1.719398 5.668082 1.772167 -v 0.064346 0.006721 0.141760 -vn -1.807943 5.960015 0.453155 -v 0.064334 0.006761 0.141472 -vn -1.155547 5.809321 1.772159 -v 0.065104 0.006910 0.141760 -vn -1.215063 6.108529 0.454444 -v 0.065095 0.006952 0.141472 -vn -0.580571 5.894611 1.772171 -v 0.065876 0.007025 0.141760 -vn -0.610475 6.198202 0.453171 -v 0.065872 0.007067 0.141472 -vn -0.000001 5.923134 1.772171 -v 0.066656 0.007063 0.141760 -vn 0.506788 5.145514 3.399020 -v 0.067424 0.006902 0.142023 -vn 1.008697 5.071056 3.399027 -v 0.068184 0.006789 0.142023 -vn 1.500889 4.947769 3.399030 -v 0.068930 0.006603 0.142023 -vn 1.978634 4.776830 3.399019 -v 0.069654 0.006344 0.142023 -vn 2.437316 4.559896 3.399021 -v 0.070349 0.006015 0.142023 -vn 2.872519 4.299042 3.399035 -v 0.071008 0.005620 0.142023 -vn 3.280082 3.996788 3.399009 -v 0.071626 0.005162 0.142023 -vn 3.656030 3.656037 3.399028 -v 0.072196 0.004645 0.142023 -vn 3.996786 3.280077 3.399037 -v 0.072712 0.004076 0.142023 -vn 4.299010 2.872525 3.399059 -v 0.073170 0.003458 0.142023 -vn 4.559896 2.437300 3.399011 -v 0.073565 0.002799 0.142023 -vn 4.776837 1.978632 3.399040 -v 0.073894 0.002104 0.142023 -vn 4.947760 1.500886 3.399027 -v 0.074153 0.001380 0.142023 -vn 5.071066 1.008691 3.399049 -v 0.074340 0.000634 0.142023 -vn 5.145525 0.506801 3.399026 -v 0.074453 -0.000126 0.142023 -vn 5.170422 -0.000004 3.398988 -v 0.074490 -0.000894 0.142023 -vn 5.145530 -0.506804 3.399013 -v 0.074453 -0.001662 0.142023 -vn 5.071061 -1.008682 3.399057 -v 0.074340 -0.002423 0.142023 -vn 4.947758 -1.500887 3.399031 -v 0.074153 -0.003168 0.142023 -vn 4.776838 -1.978630 3.399041 -v 0.073894 -0.003892 0.142023 -vn 4.559886 -2.437307 3.399018 -v 0.073565 -0.004587 0.142023 -vn 4.299022 -2.872519 3.399046 -v 0.073170 -0.005247 0.142023 -vn 3.996785 -3.280084 3.399032 -v 0.072712 -0.005864 0.142023 -vn 3.656032 -3.656030 3.399035 -v 0.072196 -0.006434 0.142023 -vn 3.280074 -3.996795 3.399009 -v 0.071626 -0.006950 0.142023 -vn 2.872525 -4.299037 3.399035 -v 0.071008 -0.007408 0.142023 -vn 2.437314 -4.559890 3.399030 -v 0.070349 -0.007804 0.142023 -vn 1.978633 -4.776831 3.399016 -v 0.069654 -0.008132 0.142023 -vn 1.500890 -4.947770 3.399027 -v 0.068930 -0.008391 0.142023 -vn 1.008698 -5.071058 3.399026 -v 0.068184 -0.008578 0.142023 -vn 0.506788 -5.145513 3.399021 -v 0.067424 -0.008691 0.142023 -vn -0.000001 -5.170409 3.399020 -v 0.066656 -0.008729 0.142023 -vn -0.506789 -5.145514 3.399019 -v 0.065888 -0.008691 0.142023 -vn -1.008699 -5.071065 3.399018 -v 0.065128 -0.008578 0.142023 -vn -1.500886 -4.947772 3.399028 -v 0.064382 -0.008391 0.142023 -vn -1.978634 -4.776847 3.399003 -v 0.063658 -0.008132 0.142023 -vn -2.437325 -4.559901 3.398994 -v 0.062963 -0.007804 0.142023 -vn -2.872531 -4.299041 3.399011 -v 0.062304 -0.007408 0.142023 -vn -3.280070 -3.996783 3.399019 -v 0.061686 -0.006950 0.142023 -vn -3.656030 -3.656029 3.399022 -v 0.061116 -0.006434 0.142023 -vn -3.996789 -3.280073 3.399023 -v 0.060600 -0.005864 0.142023 -vn -4.299045 -2.872523 3.399013 -v 0.060142 -0.005247 0.142023 -vn -4.559894 -2.437316 3.399024 -v 0.059747 -0.004587 0.142023 -vn -4.776829 -1.978637 3.399026 -v 0.059418 -0.003892 0.142023 -vn -4.947778 -1.500889 3.399011 -v 0.059159 -0.003168 0.142023 -vn -5.071057 -1.008696 3.399039 -v 0.058972 -0.002423 0.142023 -vn -5.145521 -0.506792 3.399009 -v 0.058859 -0.001662 0.142023 -vn -5.170423 0.000002 3.398989 -v 0.058822 -0.000894 0.142023 -vn -5.145523 0.506796 3.399003 -v 0.058859 -0.000126 0.142023 -vn -5.071059 1.008685 3.399040 -v 0.058972 0.000634 0.142023 -vn -4.947773 1.500895 3.399014 -v 0.059159 0.001380 0.142023 -vn -4.776831 1.978635 3.399024 -v 0.059418 0.002104 0.142023 -vn -4.559895 2.437315 3.399024 -v 0.059747 0.002799 0.142023 -vn -4.299045 2.872526 3.399011 -v 0.060142 0.003458 0.142023 -vn -3.996789 3.280072 3.399022 -v 0.060600 0.004076 0.142023 -vn -3.656030 3.656027 3.399025 -v 0.061116 0.004645 0.142023 -vn -3.280070 3.996783 3.399020 -v 0.061686 0.005162 0.142023 -vn -2.872532 4.299039 3.399013 -v 0.062304 0.005620 0.142023 -vn -2.437321 4.559906 3.398991 -v 0.062963 0.006015 0.142023 -vn -1.978629 4.776849 3.399003 -v 0.063658 0.006344 0.142023 -vn -1.500893 4.947770 3.399027 -v 0.064382 0.006603 0.142023 -vn -1.008697 5.071064 3.399020 -v 0.065128 0.006789 0.142023 -vn -0.506788 5.145513 3.399021 -v 0.065888 0.006902 0.142023 -vn -0.000001 5.170411 3.399018 -v 0.066656 0.006940 0.142023 -vn 0.422185 4.328801 4.492426 -v 0.067405 0.006709 0.142240 -vn 0.853109 4.269720 4.488501 -v 0.068147 0.006599 0.142240 -vn 1.262195 4.163472 4.491320 -v 0.068874 0.006417 0.142240 -vn 1.665507 4.019220 4.491284 -v 0.069580 0.006164 0.142240 -vn 2.053256 3.821328 4.501312 -v 0.070258 0.005844 0.142240 -vn 2.406013 3.617514 4.495996 -v 0.070901 0.005458 0.142240 -vn 2.757549 3.364078 4.492045 -v 0.071503 0.005012 0.142240 -vn 3.081282 3.076254 4.488553 -v 0.072058 0.004508 0.142240 -vn 3.362356 2.762018 4.490722 -v 0.072562 0.003953 0.142240 -vn 3.619324 2.416251 4.490398 -v 0.073009 0.003350 0.142240 -vn 3.832397 2.040552 4.498322 -v 0.073394 0.002707 0.142240 -vn 4.013437 1.671303 4.493680 -v 0.073715 0.002029 0.142240 -vn 4.162492 1.263581 4.491894 -v 0.073967 0.001323 0.142240 -vn 4.270577 0.846313 4.488874 -v 0.074149 0.000596 0.142240 -vn 4.330301 0.429536 4.490575 -v 0.074259 -0.000145 0.142240 -vn 4.352704 -0.002632 4.489634 -v 0.074296 -0.000894 0.142240 -vn 4.323568 -0.430567 4.495789 -v 0.074259 -0.001643 0.142240 -vn 4.267773 -0.841721 4.491738 -v 0.074149 -0.002385 0.142240 -vn 4.162498 -1.263564 4.491893 -v 0.073967 -0.003112 0.142240 -vn 4.020592 -1.667926 4.489512 -v 0.073715 -0.003818 0.142240 -vn 3.839184 -2.047888 4.490870 -v 0.073394 -0.004496 0.142240 -vn 3.617915 -2.421335 4.489077 -v 0.073009 -0.005139 0.142240 -vn 3.358947 -2.760028 4.493805 -v 0.072562 -0.005741 0.142240 -vn 3.081386 -3.073191 4.490201 -v 0.072058 -0.006297 0.142240 -vn 2.757549 -3.364078 4.492045 -v 0.071503 -0.006800 0.142240 -vn 2.416549 -3.618992 4.490463 -v 0.070901 -0.007247 0.142240 -vn 2.054407 -3.834874 4.491473 -v 0.070258 -0.007632 0.142240 -vn 1.662806 -4.023867 4.488678 -v 0.069580 -0.007953 0.142240 -vn 1.261754 -4.162258 4.492340 -v 0.068874 -0.008206 0.142240 -vn 0.849198 -4.265648 4.492295 -v 0.068147 -0.008388 0.142240 -vn 0.412729 -4.313869 4.504838 -v 0.067405 -0.008498 0.142240 -vn 0.010157 -4.341088 4.498726 -v 0.066656 -0.008535 0.142240 -vn -0.422182 -4.328801 4.492427 -v 0.065907 -0.008498 0.142240 -vn -0.853117 -4.269727 4.488491 -v 0.065165 -0.008388 0.142240 -vn -1.262190 -4.163474 4.491321 -v 0.064438 -0.008206 0.142240 -vn -1.665511 -4.019230 4.491269 -v 0.063732 -0.007953 0.142240 -vn -2.053262 -3.821321 4.501314 -v 0.063054 -0.007632 0.142240 -vn -2.406012 -3.617502 4.496010 -v 0.062411 -0.007247 0.142240 -vn -2.757541 -3.364068 4.492059 -v 0.061809 -0.006800 0.142240 -vn -3.081272 -3.076247 4.488568 -v 0.061254 -0.006297 0.142240 -vn -3.362341 -2.762018 4.490738 -v 0.060750 -0.005741 0.142240 -vn -3.619341 -2.416251 4.490381 -v 0.060303 -0.005139 0.142240 -vn -3.832417 -2.040552 4.498302 -v 0.059918 -0.004496 0.142240 -vn -4.013419 -1.671318 4.493696 -v 0.059597 -0.003818 0.142240 -vn -4.162508 -1.263574 4.491875 -v 0.059345 -0.003112 0.142240 -vn -4.270562 -0.846309 4.488894 -v 0.059163 -0.002385 0.142240 -vn -4.330278 -0.429533 4.490600 -v 0.059053 -0.001643 0.142240 -vn -4.352700 0.002635 4.489637 -v 0.059016 -0.000894 0.142240 -vn -4.323548 0.430562 4.495811 -v 0.059053 -0.000145 0.142240 -vn -4.267754 0.841705 4.491763 -v 0.059163 0.000596 0.142240 -vn -4.162509 1.263575 4.491874 -v 0.059345 0.001323 0.142240 -vn -4.020580 1.667924 4.489529 -v 0.059597 0.002029 0.142240 -vn -3.839196 2.047893 4.490855 -v 0.059918 0.002707 0.142240 -vn -3.617929 2.421342 4.489058 -v 0.060303 0.003350 0.142240 -vn -3.358939 2.760022 4.493817 -v 0.060750 0.003953 0.142240 -vn -3.081375 3.073184 4.490216 -v 0.061254 0.004508 0.142240 -vn -2.757540 3.364069 4.492060 -v 0.061809 0.005012 0.142240 -vn -2.416552 3.618977 4.490477 -v 0.062411 0.005458 0.142240 -vn -2.054411 3.834867 4.491476 -v 0.063054 0.005844 0.142240 -vn -1.662800 4.023880 4.488665 -v 0.063732 0.006164 0.142240 -vn -1.261757 4.162260 4.492340 -v 0.064438 0.006417 0.142240 -vn -0.849200 4.265652 4.492290 -v 0.065165 0.006599 0.142240 -vn -0.412730 4.313870 4.504837 -v 0.065907 0.006709 0.142240 -vn -0.010159 4.341091 4.498723 -v 0.066656 0.006746 0.142240 -vn -4.317725 1.113775 4.393114 -v 0.060161 0.000588 0.143055 -vn -4.198743 1.502160 4.392278 -v 0.060454 0.001540 0.143055 -vn -3.927927 1.808938 4.544599 -v 0.060501 0.001655 0.143055 -vn -3.897313 2.161503 4.397545 -v 0.060886 0.002437 0.143055 -vn -3.457482 2.346061 4.690496 -v 0.061116 0.002807 0.143055 -vn -3.475673 2.807830 4.386311 -v 0.061447 0.003260 0.143055 -vn -4.198744 -1.502159 4.392279 -v 0.060454 -0.003328 0.143055 -vn -4.317724 -1.113777 4.393114 -v 0.060161 -0.002377 0.143055 -vn -4.191560 -0.676391 4.625078 -v 0.060121 -0.002194 0.143055 -vn -4.437766 -0.395546 4.399190 -v 0.060012 -0.001392 0.143055 -vn -4.174847 0.004193 4.693739 -v 0.059993 -0.000894 0.143055 -vn -4.453508 0.380785 4.384860 -v 0.060012 -0.000396 0.143055 -vn -4.237299 0.704724 4.576123 -v 0.060121 0.000405 0.143055 -vn -2.632056 -3.600339 4.391251 -v 0.062903 -0.006399 0.143055 -vn -2.947686 -3.345585 4.393809 -v 0.062124 -0.005778 0.143055 -vn -3.043241 -2.849260 4.698296 -v 0.061945 -0.005605 0.143055 -vn -3.451662 -2.815258 4.400783 -v 0.061447 -0.005048 0.143055 -vn -3.464482 -2.340674 4.688051 -v 0.061116 -0.004596 0.143055 -vn -3.904823 -2.178731 4.383273 -v 0.060886 -0.004226 0.143055 -vn -3.956321 -1.810712 4.517649 -v 0.060501 -0.003444 0.143055 -vn 2.947672 -3.345532 4.393869 -v 0.071188 -0.005778 0.143055 -vn 2.632057 -3.600336 4.391252 -v 0.070409 -0.006399 0.143055 -vn 2.299843 -3.752264 4.460244 -v 0.070357 -0.006434 0.143055 -vn 2.015502 -3.976123 4.395911 -v 0.069547 -0.006897 0.143055 -vn 1.552656 -3.893368 4.678101 -v 0.069206 -0.007050 0.143055 -vn 1.307565 -4.270986 4.387610 -v 0.068620 -0.007261 0.143055 -vn 0.895206 -4.127030 4.648776 -v 0.067956 -0.007429 0.143055 -vn 0.565251 -4.439555 4.379804 -v 0.067649 -0.007482 0.143055 -vn 0.009532 -4.454733 4.402143 -v 0.066656 -0.007557 0.143055 -vn -0.560758 -4.423530 4.394310 -v 0.065663 -0.007482 0.143055 -vn -0.901667 -4.117114 4.656097 -v 0.065356 -0.007429 0.143055 -vn -1.307129 -4.269641 4.388858 -v 0.064692 -0.007261 0.143055 -vn -1.562516 -3.895401 4.673212 -v 0.064106 -0.007050 0.143055 -vn -2.016421 -3.993163 4.381589 -v 0.063765 -0.006897 0.143055 -vn -2.306218 -3.763224 4.447816 -v 0.062954 -0.006434 0.143055 -vn 4.317724 -1.113784 4.393114 -v 0.073151 -0.002377 0.143055 -vn 4.198827 -1.502128 4.392192 -v 0.072858 -0.003328 0.143055 -vn 3.927953 -1.808904 4.544590 -v 0.072811 -0.003444 0.143055 -vn 3.897305 -2.161517 4.397546 -v 0.072426 -0.004226 0.143055 -vn 3.457516 -2.346094 4.690454 -v 0.072196 -0.004596 0.143055 -vn 3.475712 -2.807865 4.386248 -v 0.071865 -0.005048 0.143055 -vn 3.081550 -2.927175 4.621693 -v 0.071367 -0.005605 0.143055 -vn 4.198828 1.502132 4.392191 -v 0.072858 0.001540 0.143055 -vn 4.317726 1.113782 4.393112 -v 0.073151 0.000588 0.143055 -vn 4.191572 0.676404 4.625064 -v 0.073191 0.000405 0.143055 -vn 4.437700 0.395530 4.399272 -v 0.073300 -0.000396 0.143055 -vn 4.174841 -0.004196 4.693742 -v 0.073319 -0.000894 0.143055 -vn 4.453442 -0.380769 4.384943 -v 0.073300 -0.001392 0.143055 -vn 4.237296 -0.704728 4.576125 -v 0.073191 -0.002194 0.143055 -vn 2.632056 3.600339 4.391251 -v 0.070409 0.004611 0.143055 -vn 2.947675 3.345530 4.393868 -v 0.071188 0.003990 0.143055 -vn 3.043247 2.849245 4.698301 -v 0.071367 0.003817 0.143055 -vn 3.451700 2.815294 4.400722 -v 0.071865 0.003260 0.143055 -vn 3.464519 2.340707 4.688005 -v 0.072196 0.002807 0.143055 -vn 3.904815 2.178746 4.383274 -v 0.072426 0.002437 0.143055 -vn 3.956347 1.810679 4.517639 -v 0.072811 0.001655 0.143055 -vn -3.081543 2.927179 4.621696 -v 0.061945 0.003817 0.143055 -vn -2.947688 3.345584 4.393809 -v 0.062124 0.003990 0.143055 -vn -2.632056 3.600338 4.391250 -v 0.062903 0.004611 0.143055 -vn -2.299844 3.752262 4.460245 -v 0.062954 0.004645 0.143055 -vn -2.015500 3.976120 4.395915 -v 0.063765 0.005108 0.143055 -vn -1.552654 3.893367 4.678102 -v 0.064106 0.005261 0.143055 -vn -1.307566 4.270985 4.387611 -v 0.064692 0.005472 0.143055 -vn -0.895216 4.127047 4.648758 -v 0.065356 0.005640 0.143055 -vn -0.565262 4.439556 4.379802 -v 0.065663 0.005694 0.143055 -vn -0.009533 4.454733 4.402143 -v 0.066656 0.005768 0.143055 -vn 0.560750 4.423532 4.394309 -v 0.067649 0.005694 0.143055 -vn 0.901654 4.117101 4.656113 -v 0.067956 0.005640 0.143055 -vn 1.307130 4.269642 4.388856 -v 0.068620 0.005472 0.143055 -vn 1.562517 3.895405 4.673209 -v 0.069206 0.005261 0.143055 -vn 2.016421 3.993165 4.381587 -v 0.069547 0.005108 0.143055 -vn 2.306218 3.763224 4.447815 -v 0.070357 0.004645 0.143055 -vn 1.612681 5.246087 2.858757 -v 0.068605 0.005424 0.143118 -vn 0.763194 5.435065 2.857812 -v 0.067641 0.005644 0.143118 -vn 0.921646 6.114689 0.391236 -v 0.067638 0.005623 0.143196 -vn 5.124424 1.953902 2.862645 -v 0.072811 0.001521 0.143118 -vn 4.771145 2.712602 2.858432 -v 0.072382 0.002412 0.143118 -vn 5.355289 3.091871 0.391249 -v 0.072364 0.002401 0.143196 -vn 4.780396 -2.704715 2.852318 -v 0.072382 -0.004200 0.143118 -vn 5.123366 -1.957458 2.861996 -v 0.072811 -0.003310 0.143118 -vn 5.756278 -2.259161 0.391213 -v 0.072791 -0.003302 0.143196 -vn 0.763195 -5.435064 2.857812 -v 0.067641 -0.007433 0.143118 -vn 1.612682 -5.246088 2.858760 -v 0.068605 -0.007213 0.143118 -vn 1.822703 -5.909030 0.391314 -v 0.068599 -0.007192 0.143196 -vn -3.691896 -4.058568 2.859875 -v 0.062159 -0.005741 0.143118 -vn -3.122703 -4.512881 2.857128 -v 0.062931 -0.006358 0.143118 -vn -3.483446 -5.109263 0.391253 -v 0.062943 -0.006340 0.143196 -vn -5.470996 0.436271 2.858544 -v 0.060062 -0.000400 0.143118 -vn -5.475833 -0.453757 2.849395 -v 0.060062 -0.001388 0.143118 -vn -6.166484 -0.462114 0.391187 -v 0.060083 -0.001387 0.143196 -vn -3.120391 4.515082 2.856251 -v 0.062931 0.004569 0.143118 -vn -3.689301 4.060849 2.860235 -v 0.062159 0.003953 0.143118 -vn -4.206036 4.533017 0.391218 -v 0.062173 0.003937 0.143196 -vn 2.422852 4.924604 2.858231 -v 0.069525 0.005063 0.143118 -vn 3.122705 4.512879 2.857131 -v 0.070381 0.004569 0.143118 -vn 3.691877 4.058530 2.859927 -v 0.071153 0.003953 0.143118 -vn 4.281121 -3.434303 2.858664 -v 0.071826 -0.005017 0.143118 -vn 3.689280 -4.060815 2.860286 -v 0.071153 -0.005741 0.143118 -vn 3.120397 -4.515080 2.856252 -v 0.070381 -0.006358 0.143118 -vn -4.771145 -2.712593 2.858440 -v 0.060930 -0.004200 0.143118 -vn -5.335167 -1.273182 2.861795 -v 0.060210 -0.002366 0.143118 -vn -5.334183 1.276715 2.862270 -v 0.060210 0.000577 0.143118 -vn -4.780397 2.704712 2.852314 -v 0.060930 0.002412 0.143118 -vn -1.612685 5.246088 2.858758 -v 0.064707 0.005424 0.143118 -vn -0.763211 5.435051 2.857849 -v 0.065670 0.005644 0.143118 -vn -4.281082 3.434268 2.858733 -v 0.061486 0.003228 0.143118 -vn -5.123343 1.957478 2.861945 -v 0.060501 0.001521 0.143118 -vn -5.124400 -1.953923 2.862595 -v 0.060501 -0.003310 0.143118 -vn -2.422852 -4.924605 2.858230 -v 0.063787 -0.006852 0.143118 -vn -1.612682 -5.246088 2.858758 -v 0.064707 -0.007213 0.143118 -vn 5.334144 -1.276709 2.862395 -v 0.073102 -0.002366 0.143118 -vn 5.470891 -0.436260 2.858759 -v 0.073250 -0.001388 0.143118 -vn 5.335127 1.273172 2.861925 -v 0.073102 0.000577 0.143118 -vn -2.683007 5.571356 0.391231 -v 0.063796 0.005044 0.143196 -vn -1.822701 5.909029 0.391312 -v 0.064713 0.005404 0.143196 -vn -4.535582 3.617003 -2.154922 -v 0.061494 0.003222 0.143276 -vn -4.834652 3.855507 0.391208 -v 0.061503 0.003215 0.143196 -vn -6.028696 1.376010 0.391208 -v 0.060230 0.000572 0.143196 -vn -5.756313 2.259181 0.391218 -v 0.060521 0.001514 0.143196 -vn -5.655771 -1.290897 -2.154968 -v 0.060219 -0.002363 0.143276 -vn -6.028698 -1.376010 0.391208 -v 0.060230 -0.002361 0.143196 -vn -4.834650 -3.855508 0.391211 -v 0.061503 -0.005004 0.143196 -vn -5.355285 -3.091875 0.391246 -v 0.060948 -0.004190 0.143196 -vn -2.517063 -5.226726 -2.154952 -v 0.063791 -0.006843 0.143276 -vn -2.683002 -5.571357 0.391229 -v 0.063796 -0.006833 0.143196 -vn -0.000002 -6.183753 0.391268 -v 0.066656 -0.007485 0.143196 -vn -0.921635 -6.114683 0.391276 -v 0.065674 -0.007412 0.143196 -vn -0.763213 -5.435051 2.857850 -v 0.065670 -0.007433 0.143118 -vn 2.517037 -5.226703 -2.154921 -v 0.069521 -0.006843 0.143276 -vn 2.683019 -5.571363 0.391352 -v 0.069516 -0.006833 0.143196 -vn 2.428918 -4.923934 2.855160 -v 0.069525 -0.006852 0.143118 -vn 4.834646 -3.855515 0.391208 -v 0.071809 -0.005004 0.143196 -vn 4.206034 -4.533019 0.391218 -v 0.071139 -0.005726 0.143196 -vn 5.655714 -1.290888 -2.155065 -v 0.073093 -0.002363 0.143276 -vn 6.028666 -1.376011 0.391339 -v 0.073082 -0.002361 0.143196 -vn 6.028668 1.375999 0.391339 -v 0.073082 0.000572 0.143196 -vn 6.166441 0.462118 0.391185 -v 0.073229 -0.000402 0.143196 -vn 5.475726 0.453739 2.849613 -v 0.073250 -0.000400 0.143118 -vn 4.535615 3.617037 -2.154848 -v 0.071818 0.003222 0.143276 -vn 4.834645 3.855515 0.391210 -v 0.071809 0.003215 0.143196 -vn 4.273451 3.457088 2.846493 -v 0.071826 0.003228 0.143118 -vn 2.683022 5.571360 0.391350 -v 0.069516 0.005044 0.143196 -vn 3.483449 5.109263 0.391257 -v 0.070369 0.004551 0.143196 -vn -0.000002 5.801225 -2.154896 -v 0.066656 0.005708 0.143276 -vn -0.000001 6.183753 0.391268 -v 0.066656 0.005697 0.143196 -vn -0.000001 5.511057 2.825483 -v 0.066656 0.005718 0.143118 -vn -1.769882 5.524942 -2.152341 -v 0.064710 0.005415 0.143276 -vn -2.527124 5.247597 -2.109374 -v 0.063791 0.005054 0.143276 -vn -3.219388 4.826368 -2.151807 -v 0.062937 0.004561 0.143276 -vn -5.423068 2.061000 -2.152369 -v 0.060510 0.001518 0.143276 -vn -5.678360 1.296044 -2.109393 -v 0.060219 0.000575 0.143276 -vn -5.780636 0.492156 -2.151870 -v 0.060072 -0.000401 0.143276 -vn -4.992604 -2.954938 -2.152347 -v 0.060938 -0.004195 0.143276 -vn -4.553694 -3.631451 -2.109345 -v 0.061494 -0.005011 0.143276 -vn -3.988976 -4.212646 -2.151814 -v 0.062165 -0.005734 0.143276 -vn -0.802574 -5.745725 -2.152381 -v 0.065672 -0.007423 0.143276 -vn -0.000001 -5.824394 -2.109320 -v 0.066656 -0.007497 0.143276 -vn 0.806498 -5.745240 -2.151850 -v 0.067640 -0.007423 0.143276 -vn 3.991775 -4.209854 -2.152415 -v 0.071147 -0.005734 0.143276 -vn 4.553736 -3.631483 -2.109258 -v 0.071818 -0.005011 0.143276 -vn 4.994702 -2.951606 -2.151734 -v 0.072374 -0.004195 0.143276 -vn 5.780260 0.496111 -2.152449 -v 0.073240 -0.000401 0.143276 -vn 5.678300 1.296036 -2.109500 -v 0.073093 0.000575 0.143276 -vn 5.421701 2.064716 -2.151953 -v 0.072802 0.001518 0.143276 -vn 3.216064 4.828505 -2.152343 -v 0.070375 0.004561 0.143276 -vn 2.527081 5.247582 -2.109349 -v 0.069521 0.005054 0.143276 -vn 1.766145 5.526205 -2.151809 -v 0.068602 0.005415 0.143276 -vn -0.899111 5.731084 -2.154535 -v 0.065672 0.005634 0.143276 -vn -0.814978 4.911919 -3.795938 -v 0.065666 0.005676 0.143345 -vn -0.372253 4.691120 -4.161592 -v 0.066060 0.005723 0.143345 -vn -0.921636 6.114682 0.391277 -v 0.065674 0.005623 0.143196 -vn -0.000001 4.980629 -3.794206 -v 0.066656 0.005750 0.143345 -vn -1.139113 4.669196 -4.039384 -v 0.064888 0.005511 0.143345 -vn -3.434038 3.217080 -4.161940 -v 0.061853 0.003697 0.143345 -vn -3.314301 3.709358 -3.803472 -v 0.062137 0.003976 0.143345 -vn -3.909626 4.293761 -2.143005 -v 0.062165 0.003945 0.143276 -vn -3.483446 5.109267 0.391259 -v 0.062943 0.004551 0.143196 -vn -2.428918 4.923934 2.855160 -v 0.063787 0.005063 0.143118 -vn -2.935028 3.743430 -4.100505 -v 0.062751 0.004481 0.143345 -vn -2.683399 4.192570 -3.797287 -v 0.062913 0.004595 0.143345 -vn -2.156455 4.477078 -3.811843 -v 0.063773 0.005092 0.143345 -vn -1.604221 4.711521 -3.797987 -v 0.064698 0.005455 0.143345 -vn -3.894038 3.103891 -3.795224 -v 0.061461 0.003248 0.143345 -vn -5.041351 2.870332 -2.154503 -v 0.060938 0.002407 0.143276 -vn -4.347269 2.426034 -3.796693 -v 0.060902 0.002428 0.143345 -vn -3.899883 2.633786 -4.161504 -v 0.061111 0.002766 0.143345 -vn -5.355283 3.091878 0.391248 -v 0.060948 0.002401 0.143196 -vn -4.360290 2.019275 -4.040451 -v 0.060546 0.001717 0.143345 -vn -4.655802 -0.678372 -4.162589 -v 0.060072 -0.001786 0.143345 -vn -4.964607 -0.280215 -3.805520 -v 0.060030 -0.001391 0.143345 -vn -5.794577 -0.379553 -2.143061 -v 0.060072 -0.001388 0.143276 -vn -6.166483 0.462114 0.391193 -v 0.060083 -0.000402 0.143196 -vn -4.755077 0.041037 -4.102262 -v 0.060018 -0.000596 0.143345 -vn -4.951526 0.517068 -3.796544 -v 0.060030 -0.000398 0.143345 -vn -4.846084 1.104931 -3.810590 -v 0.060178 0.000584 0.143345 -vn -4.683792 1.683206 -3.798080 -v 0.060471 0.001533 0.143345 -vn -4.854279 -1.109771 -3.795469 -v 0.060178 -0.002373 0.143345 -vn -5.387320 -2.151841 -2.154529 -v 0.060510 -0.003306 0.143276 -vn -4.618689 -1.884896 -3.785327 -v 0.060471 -0.003322 0.143345 -vn -4.494843 -1.416478 -4.153831 -v 0.060337 -0.002948 0.143345 -vn -5.756313 -2.259182 0.391221 -v 0.060521 -0.003302 0.143196 -vn -4.301862 -2.152323 -4.034784 -v 0.060805 -0.004043 0.143345 -vn -2.372462 -4.062974 -4.162626 -v 0.063248 -0.006598 0.143345 -vn -2.874683 -4.056075 -3.806668 -v 0.062913 -0.006384 0.143345 -vn -3.316131 -4.767054 -2.142994 -v 0.062937 -0.006349 0.143276 -vn -4.206037 -4.533021 0.391221 -v 0.062173 -0.005726 0.143196 -vn -4.273412 -3.457051 2.846565 -v 0.061486 -0.005017 0.143118 -vn -2.997037 -3.690399 -4.103548 -v 0.062284 -0.005898 0.143345 -vn -3.493320 -3.548589 -3.795290 -v 0.062137 -0.005765 0.143345 -vn -3.891845 -3.100845 -3.804036 -v 0.061461 -0.005037 0.143345 -vn -4.240697 -2.617490 -3.790860 -v 0.060902 -0.004217 0.143345 -vn -2.159612 -4.485852 -3.796466 -v 0.063773 -0.006881 0.143345 -vn -1.676556 -5.553640 -2.154495 -v 0.064710 -0.007203 0.143276 -vn -1.402433 -4.783963 -3.788929 -v 0.064698 -0.007244 0.143345 -vn -1.695265 -4.393670 -4.157625 -v 0.064321 -0.007115 0.143345 -vn -1.822705 -5.909028 0.391315 -v 0.064713 -0.007192 0.143196 -vn -1.000626 -4.703628 -4.036331 -v 0.065470 -0.007432 0.143345 -vn 1.698066 -4.388346 -4.162076 -v 0.068991 -0.007115 0.143345 -vn 1.379362 -4.775885 -3.807110 -v 0.068614 -0.007244 0.143345 -vn 1.659448 -5.564861 -2.142999 -v 0.068602 -0.007203 0.143276 -vn 0.921649 -6.114688 0.391236 -v 0.067638 -0.007412 0.143196 -vn -0.000000 -5.511056 2.825483 -v 0.066656 -0.007507 0.143118 -vn 1.015852 -4.643557 -4.104318 -v 0.067842 -0.007432 0.143345 -vn 0.596862 -4.942878 -3.796129 -v 0.067646 -0.007464 0.143345 -vn -0.002712 -4.975964 -3.804238 -v 0.066656 -0.007539 0.143345 -vn -0.595820 -4.946293 -3.792450 -v 0.065666 -0.007464 0.143345 -vn 2.161720 -4.486322 -3.794982 -v 0.069539 -0.006881 0.143345 -vn 3.296690 -4.773430 -2.154494 -v 0.070375 -0.006349 0.143276 -vn 2.866339 -4.076010 -3.791558 -v 0.070399 -0.006384 0.143345 -vn 2.374926 -4.065913 -4.158412 -v 0.070064 -0.006598 0.143345 -vn 3.483452 -5.109263 0.391259 -v 0.070369 -0.006340 0.143196 -vn 3.052258 -3.714890 -4.037351 -v 0.071028 -0.005898 0.143345 -vn 4.495625 -1.405019 -4.156898 -v 0.072975 -0.002948 0.143345 -vn 4.594214 -1.899274 -3.806866 -v 0.072841 -0.003322 0.143345 -vn 5.385415 -2.172181 -2.143157 -v 0.072802 -0.003306 0.143276 -vn 5.355286 -3.091873 0.391245 -v 0.072364 -0.004190 0.143196 -vn 4.263676 -2.101054 -4.104449 -v 0.072507 -0.004043 0.143345 -vn 4.236390 -2.613501 -3.797315 -v 0.072410 -0.004217 0.143345 -vn 3.886629 -3.101921 -3.807978 -v 0.071851 -0.005037 0.143345 -vn 3.493287 -3.548818 -3.795156 -v 0.071175 -0.005765 0.143345 -vn 4.858809 -1.113209 -3.789658 -v 0.073134 -0.002373 0.143345 -vn 5.787474 -0.398724 -2.154600 -v 0.073240 -0.001388 0.143276 -vn 4.972507 -0.298578 -3.793211 -v 0.073282 -0.001391 0.143345 -vn 4.657961 -0.679642 -4.160012 -v 0.073240 -0.001786 0.143345 -vn 6.166438 -0.462111 0.391187 -v 0.073229 -0.001387 0.143196 -vn 4.807141 0.069774 -4.037724 -v 0.073294 -0.000596 0.143345 -vn 3.901119 2.635845 -4.159077 -v 0.072201 0.002766 0.143345 -vn 4.350072 2.407460 -3.806265 -v 0.072410 0.002428 0.143345 -vn 5.056149 2.856163 -2.142917 -v 0.072374 0.002407 0.143276 -vn 5.756275 2.259167 0.391219 -v 0.072791 0.001514 0.143196 -vn 4.301161 2.024153 -4.104008 -v 0.072766 0.001717 0.143345 -vn 4.683778 1.683242 -3.798086 -v 0.072841 0.001533 0.143345 -vn 4.846025 1.104913 -3.810682 -v 0.073134 0.000584 0.143345 -vn 4.951385 0.517287 -3.796639 -v 0.073282 -0.000398 0.143345 -vn 3.896452 3.105075 -3.792245 -v 0.071851 0.003248 0.143345 -vn 3.920138 4.276198 -2.154573 -v 0.071147 0.003945 0.143276 -vn 3.332381 3.701617 -3.794183 -v 0.071175 0.003976 0.143345 -vn 3.435574 3.216568 -4.161086 -v 0.071458 0.003697 0.143345 -vn 4.206035 4.533020 0.391221 -v 0.071139 0.003937 0.143196 -vn 2.942609 3.802114 -4.037542 -v 0.070561 0.004481 0.143345 -vn 0.373073 4.691791 -4.160774 -v 0.067252 0.005723 0.143345 -vn 0.831141 4.902590 -3.805483 -v 0.067646 0.005676 0.143345 -vn 0.919391 5.733777 -2.143037 -v 0.067640 0.005634 0.143276 -vn 1.822705 5.909029 0.391315 -v 0.068599 0.005404 0.143196 -vn 1.098447 4.625956 -4.102999 -v 0.068424 0.005511 0.143345 -vn 1.604223 4.711522 -3.797988 -v 0.068614 0.005455 0.143345 -vn 2.156438 4.477023 -3.811925 -v 0.069539 0.005092 0.143345 -vn 2.683397 4.192571 -3.797288 -v 0.070399 0.004595 0.143345 -vn -1.942743 -4.551037 -3.806776 -v 0.063207 -0.009606 0.146265 -vn -2.287468 -4.386615 -3.805014 -v 0.062142 -0.009105 0.146265 -vn -2.660736 -4.242478 -3.707465 -v 0.061850 -0.008938 0.146265 -vn -2.895067 -4.017139 -3.791876 -v 0.061149 -0.008475 0.146265 -vn -3.218872 -3.803145 -3.751909 -v 0.060491 -0.007950 0.146265 -vn -4.877192 0.818187 -3.806958 -v 0.057452 0.000861 0.146265 -vn -3.465225 -3.527217 -3.807717 -v 0.060242 -0.007725 0.146265 -vn -3.723987 -3.254179 -3.809760 -v 0.059436 -0.006867 0.146265 -vn -3.970602 -2.988739 -3.770894 -v 0.059330 -0.006736 0.146265 -vn -4.142206 -2.697458 -3.803476 -v 0.058745 -0.005915 0.146265 -vn -4.381205 -2.382862 -3.740412 -v 0.058405 -0.005334 0.146265 -vn -4.503717 -2.026357 -3.810814 -v 0.058178 -0.004884 0.146265 -vn -4.698340 -1.528499 -3.795200 -v 0.057745 -0.003790 0.146265 -vn -4.841048 -1.011952 -3.803534 -v 0.057452 -0.002650 0.146265 -vn -5.007959 -0.601652 -3.640267 -v 0.057371 -0.002152 0.146265 -vn -4.945764 -0.296386 -3.785916 -v 0.057305 -0.001483 0.146265 -vn -4.964345 0.100925 -3.780647 -v 0.057296 -0.000474 0.146265 -vn -4.926942 0.442368 -3.808417 -v 0.057305 -0.000306 0.146265 -vn -4.855750 1.220275 -3.708590 -v 0.057521 0.001191 0.146265 -vn -4.715453 1.509907 -3.792261 -v 0.057745 0.002001 0.146265 -vn -4.612186 1.887550 -3.750854 -v 0.058040 0.002788 0.146265 -vn -4.428519 2.204323 -3.805448 -v 0.058178 0.003095 0.146265 -vn -4.246763 2.539747 -3.806860 -v 0.058745 0.004126 0.146265 -vn -4.075552 2.851456 -3.766432 -v 0.058836 0.004267 0.146265 -vn -3.846547 3.112663 -3.798237 -v 0.059436 0.005078 0.146265 -vn -3.626201 3.430222 -3.735996 -v 0.059884 0.005581 0.146265 -vn -3.319066 3.663774 -3.805651 -v 0.060242 0.005936 0.146265 -vn -2.905342 3.996089 -3.795296 -v 0.061149 0.006686 0.146265 -vn -2.458241 4.290631 -3.804317 -v 0.062142 0.007316 0.146265 -vn -2.119175 4.576731 -3.640697 -v 0.062591 0.007548 0.146265 -vn -1.812009 4.611908 -3.785465 -v 0.063207 0.007817 0.146265 -vn -1.437428 4.754509 -3.778886 -v 0.064163 0.008138 0.146265 -vn -1.102273 4.823033 -3.807780 -v 0.064326 0.008181 0.146265 -vn -0.728492 4.892542 -3.805766 -v 0.065482 0.008402 0.146265 -vn -0.339955 4.995178 -3.708592 -v 0.065816 0.008438 0.146265 -vn -0.020105 4.950699 -3.792807 -v 0.066656 0.008475 0.146265 -vn 0.369550 4.967750 -3.752943 -v 0.067496 0.008438 0.146265 -vn 0.727530 4.891734 -3.806737 -v 0.067830 0.008402 0.146265 -vn 1.102301 4.823025 -3.807778 -v 0.068986 0.008181 0.146265 -vn 1.452219 4.757833 -3.765914 -v 0.069149 0.008138 0.146265 -vn 1.771990 4.619887 -3.798388 -v 0.070105 0.007817 0.146265 -vn 2.141685 4.509011 -3.735757 -v 0.070721 0.007548 0.146265 -vn 2.458242 4.290624 -3.804327 -v 0.071170 0.007316 0.146265 -vn 2.905253 3.996660 -3.794885 -v 0.072163 0.006686 0.146265 -vn 3.319642 3.664090 -3.805013 -v 0.073070 0.005936 0.146265 -vn 3.697816 3.428398 -3.641714 -v 0.073428 0.005581 0.146265 -vn 3.825105 3.147060 -3.787271 -v 0.073876 0.005078 0.146265 -vn 4.075211 2.834489 -3.782013 -v 0.074476 0.004267 0.146265 -vn 4.244554 2.540086 -3.808658 -v 0.074567 0.004126 0.146265 -vn 4.428521 2.204310 -3.805447 -v 0.075134 0.003095 0.146265 -vn 4.646285 1.868286 -3.707436 -v 0.075272 0.002788 0.146265 -vn 4.703017 1.548145 -3.792284 -v 0.075567 0.002001 0.146265 -vn 4.839471 1.184681 -3.752022 -v 0.075791 0.001191 0.146265 -vn 4.877192 0.818187 -3.806958 -v 0.075860 0.000861 0.146265 -vn 4.927161 0.442600 -3.808172 -v 0.076007 -0.000306 0.146265 -vn 4.971531 0.086856 -3.768255 -v 0.076016 -0.000474 0.146265 -vn 4.939744 -0.255393 -3.800136 -v 0.076007 -0.001483 0.146265 -vn 4.947998 -0.645116 -3.737750 -v 0.075941 -0.002152 0.146265 -vn 4.837316 -1.011145 -3.807448 -v 0.075860 -0.002650 0.146265 -vn 4.700066 -1.524791 -3.794708 -v 0.075567 -0.003790 0.146265 -vn 4.511309 -2.027265 -3.803336 -v 0.075134 -0.004884 0.146265 -vn 4.405609 -2.456762 -3.639914 -v 0.074907 -0.005334 0.146265 -vn 4.175209 -2.667522 -3.785973 -v 0.074567 -0.005915 0.146265 -vn 3.957205 -2.999626 -3.780393 -v 0.073982 -0.006736 0.146265 -vn 3.723992 -3.254173 -3.809762 -v 0.073876 -0.006867 0.146265 -vn 3.465086 -3.527193 -3.807837 -v 0.073070 -0.007725 0.146265 -vn 3.208247 -3.841160 -3.710673 -v 0.072821 -0.007950 0.146265 -vn 2.926538 -3.990305 -3.795166 -v 0.072163 -0.008475 0.146265 -vn 2.618254 -4.235544 -3.755015 -v 0.071462 -0.008938 0.146265 -vn 2.288424 -4.382425 -3.808395 -v 0.071170 -0.009105 0.146265 -vn 1.942746 -4.551036 -3.806776 -v 0.070105 -0.009606 0.146265 -vn 1.622119 -4.702915 -3.765615 -v 0.069948 -0.009667 0.146265 -vn 1.281778 -4.779847 -3.797690 -v 0.068986 -0.009970 0.146265 -vn 0.918172 -4.907083 -3.735294 -v 0.068329 -0.010114 0.146265 -vn 0.531065 -4.915364 -3.805302 -v 0.067830 -0.010190 0.146265 -vn -0.001987 -4.936831 -3.799112 -v 0.066656 -0.010264 0.146265 -vn -0.529180 -4.913063 -3.807849 -v 0.065482 -0.010190 0.146265 -vn -0.978335 -4.944459 -3.644087 -v 0.064983 -0.010114 0.146265 -vn -1.241765 -4.792290 -3.790118 -v 0.064326 -0.009970 0.146265 -vn -1.629963 -4.690467 -3.780390 -v 0.063364 -0.009667 0.146265 -vn 2.638686 4.268669 3.702567 -v 0.071465 0.007155 0.147622 -vn 2.949640 4.021846 3.743321 -v 0.072168 0.006692 0.147622 -vn 3.379465 4.622734 2.173350 -v 0.072282 0.006850 0.147307 -vn 3.988415 3.023247 3.728216 -v 0.073987 0.004952 0.147622 -vn 4.208097 2.688605 3.733968 -v 0.074573 0.004130 0.147622 -vn 4.836246 3.058670 2.179132 -v 0.074738 0.004235 0.147307 -vn 4.107318 -2.856847 3.729892 -v 0.074482 -0.006060 0.147622 -vn 3.855309 -3.171840 3.735285 -v 0.073881 -0.006871 0.147622 -vn 4.403463 -3.654375 2.179110 -v 0.074031 -0.006996 0.147307 -vn -1.448754 -4.791968 3.726690 -v 0.064161 -0.009933 0.147622 -vn -1.826249 -4.648276 3.733470 -v 0.063204 -0.009613 0.147622 -vn -2.114765 -5.317188 2.179138 -v 0.063132 -0.009794 0.147307 -vn -5.003469 -0.101747 3.728470 -v 0.057289 -0.001315 0.147622 -vn -4.984761 0.298669 3.733916 -v 0.057298 -0.000306 0.147622 -vn -5.710452 0.368162 2.179119 -v 0.057103 -0.000293 0.147307 -vn 5.178277 -2.457935 2.164069 -v 0.075317 -0.004970 0.147307 -vn 5.534651 -2.604396 -0.031644 -v 0.075377 -0.004998 0.146942 -vn 5.817432 -1.890196 -0.031663 -v 0.075823 -0.003873 0.146942 -vn -0.737464 -5.684377 2.164043 -v 0.065456 -0.010391 0.147307 -vn -0.766639 -6.068574 -0.031675 -v 0.065448 -0.010457 0.146942 -vn -0.000001 -6.116810 -0.031674 -v 0.066656 -0.010533 0.146942 -vn -5.634059 -1.055199 2.164036 -v 0.057254 -0.002688 0.147307 -vn -6.008464 -1.146175 -0.031672 -v 0.057188 -0.002700 0.146942 -vn -5.817423 -1.890195 -0.031692 -v 0.057489 -0.003873 0.146942 -vn -2.744571 5.032232 2.164035 -v 0.062045 0.007494 0.147307 -vn -2.946793 5.360201 -0.031679 -v 0.062012 0.007552 0.146942 -vn -3.595368 4.948602 -0.031678 -v 0.060990 0.006904 0.146942 -vn 5.173776 -2.412472 -2.224990 -v 0.075313 -0.004968 0.146578 -vn 5.416658 -1.759975 -2.244256 -v 0.075756 -0.003851 0.146578 -vn -0.695615 -5.666051 -2.224990 -v 0.065457 -0.010387 0.146578 -vn -0.000000 -5.695421 -2.244241 -v 0.066656 -0.010462 0.146578 -vn -5.603689 -1.089340 -2.224983 -v 0.057257 -0.002687 0.146578 -vn -5.416665 -1.759982 -2.244263 -v 0.057556 -0.003851 0.146578 -vn -2.767658 4.992805 -2.224985 -v 0.062047 0.007490 0.146578 -vn -3.347681 4.607692 -2.244251 -v 0.061032 0.006846 0.146578 -vn 3.893185 4.175052 -2.224979 -v 0.073206 0.006081 0.146578 -vn -0.734481 5.661999 -2.223525 -v 0.065457 0.008598 0.146578 -vn -1.401687 5.533793 -2.225008 -v 0.064276 0.008373 0.146578 -vn -3.889013 4.181213 -2.223000 -v 0.060106 0.006081 0.146578 -vn -4.412347 3.620035 -2.227412 -v 0.059284 0.005205 0.146578 -vn -4.824776 3.047179 -2.227758 -v 0.058577 0.004233 0.146578 -vn -5.156476 2.456087 -2.220893 -v 0.057998 0.003180 0.146578 -vn -5.429652 1.746605 -2.232738 -v 0.057556 0.002062 0.146578 -vn -5.611847 1.051119 -2.223522 -v 0.057257 0.000899 0.146578 -vn -5.696092 0.376951 -2.224998 -v 0.057107 -0.000294 0.146578 -vn -5.178348 -2.406609 -2.223004 -v 0.057998 -0.004968 0.146578 -vn -4.806358 -3.077738 -2.227402 -v 0.058577 -0.006021 0.146578 -vn -4.388976 -3.646998 -2.227766 -v 0.059284 -0.006993 0.146578 -vn -3.929311 -4.145120 -2.220891 -v 0.060106 -0.007869 0.146578 -vn -3.338970 -4.624181 -2.232722 -v 0.061032 -0.008635 0.146578 -vn -2.733829 -5.012372 -2.223522 -v 0.062047 -0.009279 0.146578 -vn -2.118696 -5.300823 -2.225011 -v 0.063134 -0.009791 0.146578 -vn 0.688623 -5.668581 -2.223008 -v 0.067855 -0.010387 0.146578 -vn 1.441859 -5.522182 -2.227423 -v 0.069035 -0.010162 0.146578 -vn 2.112235 -5.301147 -2.227780 -v 0.070178 -0.009791 0.146578 -vn 2.728015 -5.017911 -2.220917 -v 0.071265 -0.009279 0.146578 -vn 3.366062 -4.604500 -2.232708 -v 0.072280 -0.008635 0.146578 -vn 3.922254 -4.148926 -2.223511 -v 0.073206 -0.007869 0.146578 -vn 4.386672 -3.653044 -2.224999 -v 0.074028 -0.006993 0.146578 -vn 5.603935 -1.096773 -2.223004 -v 0.076055 -0.002687 0.146578 -vn 5.697466 -0.335163 -2.227406 -v 0.076205 -0.001495 0.146578 -vn 5.694406 0.370709 -2.227763 -v 0.076205 -0.000294 0.146578 -vn 5.615325 1.043886 -2.220892 -v 0.076055 0.000899 0.146578 -vn 5.419301 1.778441 -2.232730 -v 0.075756 0.002062 0.146578 -vn 5.157912 2.448182 -2.223523 -v 0.075313 0.003180 0.146578 -vn 4.829799 3.043118 -2.225026 -v 0.074735 0.004233 0.146578 -vn 1.407108 5.530256 -2.227779 -v 0.069035 0.008373 0.146578 -vn 2.079369 5.315046 -2.227425 -v 0.070178 0.008002 0.146578 -vn 0.742437 5.663070 -2.220899 -v 0.067855 0.008598 0.146578 -vn -0.016744 5.703639 -2.232717 -v 0.066656 0.008674 0.146578 -vn -1.521190 5.924634 -0.031678 -v 0.064259 0.008442 0.146942 -vn -0.766639 6.068573 -0.031677 -v 0.065448 0.008668 0.146942 -vn -4.187248 4.458965 -0.031667 -v 0.060058 0.006132 0.146942 -vn -4.713084 3.899000 -0.031673 -v 0.059229 0.005250 0.146942 -vn -5.164598 3.277552 -0.031687 -v 0.058518 0.004270 0.146942 -vn -5.534657 2.604418 -0.031699 -v 0.057935 0.003210 0.146942 -vn -5.817423 1.890198 -0.031694 -v 0.057489 0.002084 0.146942 -vn -6.008466 1.146172 -0.031668 -v 0.057188 0.000912 0.146942 -vn -6.104742 0.384079 -0.031666 -v 0.057036 -0.000289 0.146942 -vn -5.534657 -2.604417 -0.031694 -v 0.057935 -0.004998 0.146942 -vn -5.164598 -3.277551 -0.031688 -v 0.058518 -0.006059 0.146942 -vn -4.713084 -3.899001 -0.031672 -v 0.059229 -0.007038 0.146942 -vn -4.187245 -4.458967 -0.031667 -v 0.060058 -0.007921 0.146942 -vn -3.595371 -4.948600 -0.031682 -v 0.060990 -0.008692 0.146942 -vn -2.946794 -5.360200 -0.031680 -v 0.062012 -0.009341 0.146942 -vn -2.251749 -5.687260 -0.031683 -v 0.063108 -0.009856 0.146942 -vn 0.766638 -6.068573 -0.031676 -v 0.067864 -0.010457 0.146942 -vn 1.521191 -5.924634 -0.031678 -v 0.069053 -0.010230 0.146942 -vn 2.251746 -5.687262 -0.031683 -v 0.070204 -0.009856 0.146942 -vn 2.946796 -5.360191 -0.031678 -v 0.071299 -0.009341 0.146942 -vn 3.595376 -4.948609 -0.031679 -v 0.072321 -0.008692 0.146942 -vn 4.187249 -4.458961 -0.031669 -v 0.073254 -0.007921 0.146942 -vn 4.713083 -3.899006 -0.031675 -v 0.074083 -0.007038 0.146942 -vn 6.008462 -1.146180 -0.031668 -v 0.076124 -0.002700 0.146942 -vn 6.104742 -0.384079 -0.031666 -v 0.076276 -0.001500 0.146942 -vn 6.104742 0.384079 -0.031668 -v 0.076276 -0.000289 0.146942 -vn 6.008463 1.146180 -0.031669 -v 0.076124 0.000912 0.146942 -vn 5.817433 1.890194 -0.031666 -v 0.075823 0.002084 0.146942 -vn 5.534648 2.604403 -0.031647 -v 0.075377 0.003210 0.146942 -vn 5.164582 3.277550 -0.031683 -v 0.074794 0.004270 0.146942 -vn -0.000001 6.116810 -0.031674 -v 0.066656 0.008744 0.146942 -vn 0.766638 6.068573 -0.031675 -v 0.067864 0.008668 0.146942 -vn 1.521190 5.924634 -0.031678 -v 0.069053 0.008442 0.146942 -vn 2.251746 5.687263 -0.031682 -v 0.070204 0.008068 0.146942 -vn -1.414486 5.544727 2.179132 -v 0.064276 0.008377 0.147307 -vn -0.698286 5.688476 2.165532 -v 0.065456 0.008602 0.147307 -vn -3.352165 4.642559 2.173375 -v 0.061030 0.006850 0.147307 -vn -3.944913 4.161427 2.161374 -v 0.060104 0.006083 0.147307 -vn -4.406330 3.661488 2.168333 -v 0.059281 0.005207 0.147307 -vn -4.825333 3.089992 2.167984 -v 0.058574 0.004235 0.147307 -vn -5.198856 2.416036 2.163507 -v 0.057995 0.003181 0.147307 -vn -5.438234 1.766982 2.185078 -v 0.057553 0.002064 0.147307 -vn -5.625851 1.093725 2.165526 -v 0.057254 0.000899 0.147307 -vn -5.451204 -1.753463 2.173389 -v 0.057553 -0.003852 0.147307 -vn -5.176800 -2.465881 2.161361 -v 0.057995 -0.004970 0.147307 -vn -4.843908 -3.059197 2.168335 -v 0.058574 -0.006023 0.147307 -vn -4.429871 -3.634317 2.167982 -v 0.059281 -0.006996 0.147307 -vn -3.904319 -4.197810 2.163517 -v 0.060104 -0.007872 0.147307 -vn -3.361018 -4.626042 2.185061 -v 0.061030 -0.008638 0.147307 -vn -2.778680 -5.012517 2.165522 -v 0.062045 -0.009282 0.147307 -vn -0.016870 -5.726264 2.173371 -v 0.066656 -0.010466 0.147307 -vn 0.745471 -5.685426 2.161386 -v 0.067856 -0.010391 0.147307 -vn 1.412626 -5.552173 2.168352 -v 0.069036 -0.010166 0.147307 -vn 2.087527 -5.336120 2.167996 -v 0.070180 -0.009794 0.147307 -vn 2.785859 -5.010414 2.163537 -v 0.071267 -0.009282 0.147307 -vn 3.361020 -4.626052 2.185033 -v 0.072282 -0.008638 0.147307 -vn 3.908527 -4.191625 2.165530 -v 0.073208 -0.007872 0.147307 -vn 5.440789 -1.785558 2.173375 -v 0.075759 -0.003852 0.147307 -vn 5.637518 -1.047909 2.161394 -v 0.076058 -0.002688 0.147307 -vn 5.716949 -0.372232 2.168353 -v 0.076209 -0.001495 0.147307 -vn 5.720024 0.336409 2.168002 -v 0.076209 -0.000293 0.147307 -vn 5.626061 1.101202 2.163540 -v 0.076058 0.000899 0.147307 -vn 5.438244 1.766990 2.185064 -v 0.075759 0.002064 0.147307 -vn 5.194279 2.421940 2.165560 -v 0.075317 0.003181 0.147307 -vn 3.347681 4.607696 -2.244233 -v 0.072280 0.006846 0.146578 -vn 4.187247 4.458963 -0.031666 -v 0.073254 0.006132 0.146942 -vn 3.595375 4.948608 -0.031681 -v 0.072321 0.006904 0.146942 -vn 3.937817 4.165278 2.164039 -v 0.073208 0.006083 0.147307 -vn -0.000000 5.718107 2.185057 -v 0.066656 0.008678 0.147307 -vn 0.691245 5.691001 2.163527 -v 0.067856 0.008602 0.147307 -vn 1.447648 5.544025 2.168002 -v 0.069036 0.008377 0.147307 -vn 2.120650 5.322124 2.168349 -v 0.070180 0.008005 0.147307 -vn -0.985629 4.981809 3.590348 -v 0.064982 0.008332 0.147622 -vn -1.251588 4.830077 3.738230 -v 0.064324 0.008188 0.147622 -vn -1.642820 4.727419 3.728226 -v 0.063361 0.007885 0.147622 -vn -1.958141 4.587185 3.754962 -v 0.063204 0.007824 0.147622 -vn -2.127146 5.321769 2.165543 -v 0.063132 0.008005 0.147307 -vn -2.251747 5.687261 -0.031682 -v 0.063108 0.008068 0.146942 -vn -2.106363 5.296147 -2.238413 -v 0.063134 0.008002 0.146578 -vn -2.305638 4.421408 3.753210 -v 0.062139 0.007323 0.147622 -vn -4.001788 3.012201 3.718647 -v 0.059325 0.004952 0.147622 -vn -3.753585 3.280011 3.758005 -v 0.059431 0.005083 0.147622 -vn -3.492729 3.555212 3.755971 -v 0.060237 0.005941 0.147622 -vn -3.244044 3.832854 3.699367 -v 0.060487 0.006167 0.147622 -vn -2.917968 4.048839 3.739962 -v 0.061144 0.006692 0.147622 -vn -2.681177 4.275232 3.654383 -v 0.061847 0.007155 0.147622 -vn -4.174986 2.718812 3.751787 -v 0.058739 0.004130 0.147622 -vn -4.415297 2.401368 3.687812 -v 0.058399 0.003549 0.147622 -vn -4.539410 2.042478 3.759222 -v 0.058172 0.003098 0.147622 -vn -4.735420 1.540571 3.743468 -v 0.057738 0.002003 0.147622 -vn -4.879434 1.019950 3.751735 -v 0.057445 0.000863 0.147622 -vn -5.045742 0.606313 3.586435 -v 0.057364 0.000364 0.147622 -vn -4.966079 -0.445876 3.756632 -v 0.057298 -0.001483 0.147622 -vn -5.718633 -0.378518 2.165529 -v 0.057103 -0.001495 0.147307 -vn -6.104742 -0.384079 -0.031668 -v 0.057036 -0.001500 0.146942 -vn -5.687835 -0.366673 -2.238394 -v 0.057107 -0.001495 0.146578 -vn -4.915895 -0.824695 3.755194 -v 0.057445 -0.002651 0.147622 -vn -4.107571 -2.873763 3.714100 -v 0.058830 -0.006060 0.147622 -vn -4.280471 -2.559914 3.755071 -v 0.058739 -0.005919 0.147622 -vn -4.463656 -2.221794 3.753663 -v 0.058172 -0.004887 0.147622 -vn -4.648211 -1.902316 3.698300 -v 0.058034 -0.004580 0.147622 -vn -4.752678 -1.521851 3.740374 -v 0.057738 -0.003792 0.147622 -vn -4.893216 -1.229616 3.655526 -v 0.057514 -0.002981 0.147622 -vn -3.876963 -3.137331 3.746378 -v 0.059431 -0.006871 0.147622 -vn -3.654394 -3.456908 3.683265 -v 0.059878 -0.007374 0.147622 -vn -3.345399 -3.692811 3.753908 -v 0.060237 -0.007730 0.147622 -vn -2.928289 -4.027629 3.743551 -v 0.061144 -0.008480 0.147622 -vn -2.477706 -4.324653 3.752552 -v 0.062139 -0.009111 0.147622 -vn -2.135275 -4.611223 3.586886 -v 0.062588 -0.009343 0.147622 -vn -1.111083 -4.861320 3.755984 -v 0.064324 -0.009977 0.147622 -vn -1.407166 -5.555706 2.165543 -v 0.064276 -0.010166 0.147307 -vn -1.521190 -5.924634 -0.031678 -v 0.064259 -0.010230 0.146942 -vn -1.408914 -5.522760 -2.238410 -v 0.064276 -0.010162 0.146578 -vn -0.734258 -4.931361 3.753986 -v 0.065481 -0.010197 0.147622 -vn 1.463549 -4.795187 3.713551 -v 0.069151 -0.009933 0.147622 -vn 1.111055 -4.861322 3.755996 -v 0.068988 -0.009977 0.147622 -vn 0.733280 -4.930550 3.754980 -v 0.067831 -0.010197 0.147622 -vn 0.372464 -5.006569 3.700435 -v 0.067497 -0.010233 0.147622 -vn -0.020224 -4.989803 3.740911 -v 0.066656 -0.010271 0.147622 -vn -0.342661 -5.033687 3.655543 -v 0.065815 -0.010233 0.147622 -vn 1.786050 -4.656428 3.746553 -v 0.070108 -0.009613 0.147622 -vn 2.158346 -4.544069 3.683028 -v 0.070724 -0.009343 0.147622 -vn 2.477705 -4.324648 3.752563 -v 0.071173 -0.009111 0.147622 -vn 2.928204 -4.028205 3.743116 -v 0.072168 -0.008480 0.147622 -vn 3.345961 -3.693135 3.753272 -v 0.073075 -0.007730 0.147622 -vn 3.725637 -3.454376 3.587916 -v 0.073434 -0.007374 0.147622 -vn 4.278221 -2.560337 3.756871 -v 0.074573 -0.005919 0.147622 -vn 4.848949 -3.055103 2.165545 -v 0.074738 -0.006023 0.147307 -vn 5.164579 -3.277557 -0.031687 -v 0.074794 -0.006059 0.146942 -vn 4.817067 -3.046587 -2.238430 -v 0.074735 -0.006021 0.146578 -vn 4.463654 -2.221807 3.753666 -v 0.075140 -0.004887 0.147622 -vn 5.010548 -0.087580 3.715957 -v 0.076023 -0.001315 0.147622 -vn 4.966283 -0.446109 3.756401 -v 0.076014 -0.001483 0.147622 -vn 4.915882 -0.824691 3.755217 -v 0.075867 -0.002651 0.147622 -vn 4.877289 -1.193912 3.699499 -v 0.075798 -0.002981 0.147622 -vn 4.740191 -1.560320 3.740353 -v 0.075574 -0.003792 0.147622 -vn 4.682070 -1.882811 3.654327 -v 0.075278 -0.004580 0.147622 -vn 4.978832 0.257440 3.748348 -v 0.076014 -0.000306 0.147622 -vn 4.986470 0.650155 3.685083 -v 0.075948 0.000364 0.147622 -vn 4.875676 1.019127 3.755768 -v 0.075867 0.000863 0.147622 -vn 4.737184 1.536816 3.742921 -v 0.075574 0.002003 0.147622 -vn 4.547064 2.043339 3.751559 -v 0.075140 0.003098 0.147622 -vn 4.438946 2.475173 3.586047 -v 0.074913 0.003549 0.147622 -vn 3.753619 3.279982 3.757989 -v 0.073881 0.005083 0.147622 -vn 4.403993 3.667560 2.165520 -v 0.074031 0.005207 0.147307 -vn 4.713082 3.899007 -0.031670 -v 0.074083 0.005250 0.146942 -vn 4.386033 3.639871 -2.238405 -v 0.074028 0.005205 0.146578 -vn 3.492575 3.555192 3.756114 -v 0.073075 0.005941 0.147622 -vn 3.233047 3.870729 3.657687 -v 0.072825 0.006167 0.147622 -vn 2.306636 4.417175 3.756677 -v 0.071173 0.007323 0.147622 -vn 2.738705 5.037780 2.161399 -v 0.071267 0.007494 0.147307 -vn 2.946794 5.360191 -0.031682 -v 0.071299 0.007552 0.146942 -vn 2.774802 4.990734 -2.223024 -v 0.071265 0.007490 0.146578 -vn 1.958143 4.587184 3.754962 -v 0.070108 0.007824 0.147622 -vn -0.533364 4.952022 3.756179 -v 0.065481 0.008409 0.147622 -vn -0.002018 4.975818 3.747458 -v 0.066656 0.008483 0.147622 -vn 0.535275 4.954331 3.753566 -v 0.067831 0.008409 0.147622 -vn 0.925307 4.945243 3.682546 -v 0.068330 0.008332 0.147622 -vn 1.291883 4.817677 3.745839 -v 0.068988 0.008188 0.147622 -vn 1.634896 4.739802 3.713248 -v 0.069951 0.007885 0.147622 -vn -1.741864 4.514829 4.001508 -v 0.064308 0.005362 0.150570 -vn -2.197620 4.564786 3.665063 -v 0.063757 0.005126 0.150570 -vn -2.438102 4.174951 4.006626 -v 0.063229 0.004842 0.150570 -vn -2.925508 4.127689 3.675846 -v 0.062892 0.004627 0.150570 -vn -3.075800 3.784861 3.949695 -v 0.062260 0.004138 0.150570 -vn -3.554748 3.610938 3.663970 -v 0.062111 0.004004 0.150570 -vn -4.932282 -1.124591 3.680869 -v 0.060141 -0.002381 0.150570 -vn -5.038643 -0.526232 3.665120 -v 0.059993 -0.001394 0.150570 -vn -3.960980 3.155948 3.674177 -v 0.061432 0.003272 0.150570 -vn -4.315159 2.663552 3.659373 -v 0.060869 0.002447 0.150570 -vn -4.405193 2.205708 3.882943 -v 0.060772 0.002272 0.150570 -vn -4.699731 1.918067 3.653733 -v 0.060436 0.001547 0.150570 -vn -4.618552 1.455595 3.997705 -v 0.060301 0.001171 0.150570 -vn -4.939656 1.129266 3.664099 -v 0.060141 0.000593 0.150570 -vn -4.784291 0.696871 4.006567 -v 0.060034 0.000003 0.150570 -vn -5.052344 0.285115 3.674577 -v 0.059993 -0.000395 0.150570 -vn -4.878080 -0.043719 3.948325 -v 0.059981 -0.001194 0.150570 -vn -4.766234 -1.712712 3.666754 -v 0.060436 -0.003336 0.150570 -vn -4.466455 -2.066759 3.888746 -v 0.060512 -0.003521 0.150570 -vn -4.423778 -2.468691 3.665303 -v 0.060869 -0.004235 0.150570 -vn -4.007592 -2.706215 4.005482 -v 0.061079 -0.004575 0.150570 -vn -3.962522 -3.158488 3.663836 -v 0.061432 -0.005061 0.150570 -vn -3.528589 -3.305972 4.005951 -v 0.061826 -0.005512 0.150570 -vn -3.372781 -3.774847 3.672609 -v 0.062111 -0.005793 0.150570 -vn -3.009584 -3.841207 3.946632 -v 0.062728 -0.006300 0.150570 -vn -2.730523 -4.266351 3.665972 -v 0.062892 -0.006415 0.150570 -vn -2.194835 -4.556763 3.682097 -v 0.063757 -0.006915 0.150570 -vn -1.632509 -4.794388 3.666662 -v 0.064686 -0.007280 0.150570 -vn -1.168148 -4.781865 3.887588 -v 0.064878 -0.007336 0.150570 -vn -0.829347 -4.998329 3.664535 -v 0.065660 -0.007502 0.150570 -vn -0.382787 -4.820498 4.005559 -v 0.066057 -0.007549 0.150570 -vn 0.000000 -5.068234 3.662759 -v 0.066656 -0.007576 0.150570 -vn 0.383612 -4.821175 4.004715 -v 0.067255 -0.007549 0.150570 -vn 0.845873 -4.989190 3.674592 -v 0.067652 -0.007502 0.150570 -vn 1.128415 -4.745278 3.949081 -v 0.068434 -0.007336 0.150570 -vn 1.632484 -4.794395 3.666665 -v 0.068626 -0.007280 0.150570 -vn 2.194825 -4.556715 3.682174 -v 0.069555 -0.006915 0.150570 -vn 2.730562 -4.266322 3.665979 -v 0.070420 -0.006415 0.150570 -vn 3.012625 -3.895066 3.885678 -v 0.070584 -0.006300 0.150570 -vn 3.390983 -3.766774 3.662681 -v 0.071201 -0.005793 0.150570 -vn 3.530148 -3.305475 4.005047 -v 0.071486 -0.005512 0.150570 -vn 3.964904 -3.159620 3.660883 -v 0.071880 -0.005061 0.150570 -vn 4.008842 -2.708306 4.002964 -v 0.072233 -0.004575 0.150570 -vn 4.426887 -2.449942 3.675483 -v 0.072443 -0.004235 0.150570 -vn 4.413068 -2.074973 3.950279 -v 0.072800 -0.003521 0.150570 -vn 4.766298 -1.712687 3.666665 -v 0.072876 -0.003336 0.150570 -vn 4.932282 -1.124592 3.680868 -v 0.073171 -0.002381 0.150570 -vn 5.038442 -0.526451 3.665320 -v 0.073319 -0.001394 0.150570 -vn 4.923413 -0.073002 3.885932 -v 0.073331 -0.001194 0.150570 -vn 5.059908 0.303815 3.661807 -v 0.073319 -0.000395 0.150570 -vn 4.786465 0.698157 4.003913 -v 0.073278 0.000003 0.150570 -vn 4.944236 1.132722 3.658073 -v 0.073171 0.000593 0.150570 -vn 4.619372 1.444041 4.000826 -v 0.073011 0.001171 0.150570 -vn 4.675398 1.932940 3.675931 -v 0.072876 0.001547 0.150570 -vn 4.373319 2.156805 3.950594 -v 0.072540 0.002272 0.150570 -vn 4.310863 2.659462 3.666052 -v 0.072443 0.002447 0.150570 -vn 3.955708 3.157028 3.678271 -v 0.071880 0.003272 0.150570 -vn 3.554806 3.611194 3.663686 -v 0.071201 0.004004 0.150570 -vn 3.127305 3.803784 3.885536 -v 0.071052 0.004138 0.150570 -vn 2.916737 4.147614 3.660116 -v 0.070420 0.004627 0.150570 -vn 2.440569 4.177883 4.002327 -v 0.070083 0.004842 0.150570 -vn 2.199745 4.565254 3.663541 -v 0.069555 0.005126 0.150570 -vn 1.744711 4.509496 4.006045 -v 0.069004 0.005362 0.150570 -vn 1.403681 4.860287 3.676266 -v 0.068626 0.005491 0.150570 -vn 1.040579 4.764066 3.950445 -v 0.067849 0.005680 0.150570 -vn 0.607305 5.029821 3.664749 -v 0.067652 0.005713 0.150570 -vn -0.002738 5.064397 3.674343 -v 0.066656 0.005788 0.150570 -vn -0.606248 5.033230 3.660999 -v 0.065660 0.005713 0.150570 -vn -1.023342 4.817738 3.884466 -v 0.065463 0.005680 0.150570 -vn -1.427018 4.868016 3.657404 -v 0.064686 0.005491 0.150570 -vn 1.690142 5.664622 1.720436 -v 0.068612 0.005448 0.150651 -vn 0.823873 5.848717 1.729035 -v 0.067645 0.005669 0.150651 -vn 0.901241 5.979411 -1.191792 -v 0.067645 0.005665 0.150744 -vn 5.482596 2.210431 1.720427 -v 0.072834 0.001530 0.150651 -vn 5.086408 3.002510 1.728957 -v 0.072404 0.002424 0.150651 -vn 5.236812 3.023478 -1.191817 -v 0.072401 0.002422 0.150744 -vn 5.146546 -2.908276 1.720369 -v 0.072404 -0.004213 0.150651 -vn 5.518775 -2.104641 1.729027 -v 0.072834 -0.003319 0.150651 -vn 5.628974 -2.209200 -1.191704 -v 0.072831 -0.003318 0.150744 -vn 0.935037 -5.836985 1.720439 -v 0.067645 -0.007457 0.150651 -vn 1.795382 -5.626967 1.729019 -v 0.068612 -0.007237 0.150651 -vn 1.782378 -5.778312 -1.191795 -v 0.068611 -0.007233 0.150744 -vn -3.980533 -4.370326 1.720396 -v 0.062142 -0.005760 0.150651 -vn -3.279917 -4.912031 1.729080 -v 0.062917 -0.006378 0.150651 -vn -3.406358 -4.996217 -1.191834 -v 0.062919 -0.006375 0.150744 -vn -5.898705 0.387270 1.720448 -v 0.060037 -0.000398 0.150651 -vn -5.885412 -0.498251 1.729032 -v 0.060037 -0.001390 0.150651 -vn -6.030019 -0.451890 -1.191831 -v 0.060041 -0.001390 0.150744 -vn -3.374984 4.853230 1.720479 -v 0.062917 0.004590 0.150651 -vn -4.059017 4.290730 1.728986 -v 0.062142 0.003971 0.150651 -vn -4.112979 4.432729 -1.191884 -v 0.062144 0.003968 0.150744 -vn 2.562491 5.321084 1.732835 -v 0.069536 0.005086 0.150651 -vn 3.355569 4.860026 1.732475 -v 0.070395 0.004590 0.150651 -vn 5.757884 1.314196 1.732859 -v 0.073127 0.000583 0.150651 -vn 5.891923 0.406695 1.732319 -v 0.073275 -0.000398 0.150651 -vn 4.617459 -3.682301 1.732974 -v 0.071845 -0.005033 0.150651 -vn 3.991501 -4.352925 1.732411 -v 0.071170 -0.005760 0.150651 -vn -0.000000 -5.905976 1.732842 -v 0.066656 -0.007531 0.150651 -vn -0.914599 -5.834684 1.732435 -v 0.065667 -0.007457 0.150651 -vn -4.617465 -3.682306 1.732881 -v 0.061467 -0.005033 0.150651 -vn -5.131999 -2.922823 1.732371 -v 0.060908 -0.004213 0.150651 -vn -5.757883 1.314196 1.732862 -v 0.060185 0.000583 0.150651 -vn -5.484865 2.189987 1.732392 -v 0.060478 0.001530 0.150651 -vn -2.562523 5.321107 1.732862 -v 0.063776 0.005086 0.150651 -vn -1.707559 5.653682 1.732423 -v 0.064700 0.005448 0.150651 -vn -0.819374 5.849254 1.729739 -v 0.065667 0.005669 0.150651 -vn -5.084014 3.006367 1.729673 -v 0.060908 0.002424 0.150651 -vn -5.520258 -2.100392 1.729700 -v 0.060478 -0.003319 0.150651 -vn -1.799670 -5.625494 1.729732 -v 0.064700 -0.007237 0.150651 -vn 3.276113 -4.914467 1.729769 -v 0.070395 -0.006378 0.150651 -vn 5.884937 -0.502775 1.729629 -v 0.073275 -0.001390 0.150651 -vn 4.062274 4.287547 1.729725 -v 0.071170 0.003971 0.150651 -vn -2.623659 5.448098 -1.191813 -v 0.063778 0.005082 0.150744 -vn -1.782378 5.778313 -1.191795 -v 0.064701 0.005444 0.150744 -vn -3.763150 3.001011 -3.827673 -v 0.061440 0.003265 0.150828 -vn -4.727695 3.770215 -1.191798 -v 0.061470 0.003242 0.150744 -vn -4.634462 3.695868 1.685355 -v 0.061467 0.003244 0.150651 -vn -5.895347 1.345575 -1.191820 -v 0.060189 0.000582 0.150744 -vn -5.628973 2.209203 -1.191818 -v 0.060481 0.001529 0.150744 -vn -4.692597 -1.071057 -3.827645 -v 0.060152 -0.002379 0.150828 -vn -5.895348 -1.345575 -1.191813 -v 0.060189 -0.002370 0.150744 -vn -5.779084 -1.319039 1.685329 -v 0.060185 -0.002371 0.150651 -vn -4.727699 -3.770213 -1.191796 -v 0.061470 -0.005030 0.150744 -vn -5.236810 -3.023477 -1.191819 -v 0.060911 -0.004211 0.150744 -vn -2.088396 -4.336588 -3.827703 -v 0.063761 -0.006905 0.150828 -vn -2.623659 -5.448101 -1.191811 -v 0.063778 -0.006871 0.150744 -vn -2.571960 -5.340697 1.685331 -v 0.063776 -0.006874 0.150651 -vn -0.000001 -6.046950 -1.191815 -v 0.066656 -0.007528 0.150744 -vn -0.901243 -5.979411 -1.191793 -v 0.065667 -0.007454 0.150744 -vn 2.088401 -4.336586 -3.827702 -v 0.069551 -0.006905 0.150828 -vn 2.623672 -5.448091 -1.191921 -v 0.069534 -0.006871 0.150744 -vn 2.571929 -5.340676 1.685310 -v 0.069536 -0.006874 0.150651 -vn 4.727660 -3.770205 -1.191780 -v 0.071842 -0.005030 0.150744 -vn 4.112956 -4.432713 -1.191874 -v 0.071168 -0.005757 0.150744 -vn 4.692543 -1.071040 -3.827689 -v 0.073160 -0.002379 0.150828 -vn 5.895346 -1.345576 -1.191813 -v 0.073123 -0.002370 0.150744 -vn 5.779085 -1.319041 1.685328 -v 0.073127 -0.002371 0.150651 -vn 5.895344 1.345580 -1.191817 -v 0.073123 0.000582 0.150744 -vn 6.030061 0.451898 -1.191851 -v 0.073271 -0.000399 0.150744 -vn 3.763154 3.001019 -3.827711 -v 0.071872 0.003265 0.150828 -vn 4.727663 3.770199 -1.191784 -v 0.071842 0.003242 0.150744 -vn 4.634467 3.695856 1.685447 -v 0.071845 0.003244 0.150651 -vn 2.623664 5.448098 -1.191917 -v 0.069534 0.005082 0.150744 -vn 3.406361 4.996216 -1.191832 -v 0.070393 0.004586 0.150744 -vn -0.000001 4.813263 -3.827666 -v 0.066656 0.005777 0.150828 -vn -0.000003 6.046950 -1.191816 -v 0.066656 0.005739 0.150744 -vn -0.000002 5.927723 1.685312 -v 0.066656 0.005743 0.150651 -vn -1.462325 4.586990 -3.825874 -v 0.064690 0.005481 0.150828 -vn -2.100482 4.361677 -3.802476 -v 0.063761 0.005117 0.150828 -vn -2.677329 4.001596 -3.825573 -v 0.062898 0.004618 0.150828 -vn -4.498045 1.716649 -3.825822 -v 0.060446 0.001543 0.150828 -vn -4.719749 1.077255 -3.802417 -v 0.060152 0.000590 0.150828 -vn -4.797911 0.401750 -3.825547 -v 0.060003 -0.000396 0.150828 -vn -4.146596 -2.446389 -3.825878 -v 0.060878 -0.004230 0.150828 -vn -3.784919 -3.018378 -3.802451 -v 0.061440 -0.005054 0.150828 -vn -3.305568 -3.500687 -3.825488 -v 0.062118 -0.005785 0.150828 -vn -0.672702 -4.767224 -3.825888 -v 0.065662 -0.007491 0.150828 -vn -0.000002 -4.841111 -3.802442 -v 0.066656 -0.007566 0.150828 -vn 0.675963 -4.767002 -3.825528 -v 0.067650 -0.007491 0.150828 -vn 3.307753 -3.498248 -3.825918 -v 0.071194 -0.005785 0.150828 -vn 3.784932 -3.018375 -3.802487 -v 0.071872 -0.005054 0.150828 -vn 4.148487 -2.443733 -3.825484 -v 0.072434 -0.004230 0.150828 -vn 4.797397 0.404965 -3.825856 -v 0.073309 -0.000396 0.150828 -vn 4.719687 1.077243 -3.802472 -v 0.073160 0.000590 0.150828 -vn 4.497002 1.719761 -3.825542 -v 0.072866 0.001543 0.150828 -vn 2.674488 4.003212 -3.825934 -v 0.070414 0.004618 0.150828 -vn 2.100481 4.361679 -3.802476 -v 0.069551 0.005117 0.150828 -vn 1.459311 4.588238 -3.825481 -v 0.068622 0.005481 0.150828 -vn -0.742615 4.755735 -3.827411 -v 0.065662 0.005703 0.150828 -vn -0.542514 3.269382 -5.298594 -v 0.065651 0.005774 0.150886 -vn -0.243481 3.075156 -5.460947 -v 0.066052 0.005822 0.150886 -vn -0.901241 5.979412 -1.191791 -v 0.065667 0.005665 0.150744 -vn -0.000001 3.315157 -5.298089 -v 0.066656 0.005849 0.150886 -vn -0.749833 3.076370 -5.406194 -v 0.064862 0.005606 0.150886 -vn -2.252588 2.108679 -5.460562 -v 0.061782 0.003766 0.150886 -vn -2.204155 2.465941 -5.303646 -v 0.062069 0.004049 0.150886 -vn -3.249140 3.560846 -3.820986 -v 0.062118 0.003996 0.150828 -vn -3.406356 4.996217 -1.191828 -v 0.062919 0.004586 0.150744 -vn -1.927853 2.458368 -5.434708 -v 0.062692 0.004561 0.150886 -vn -1.786557 2.788705 -5.299578 -v 0.062857 0.004677 0.150886 -vn -1.430655 2.970794 -5.313004 -v 0.063730 0.005181 0.150886 -vn -1.066418 3.135512 -5.299574 -v 0.064668 0.005550 0.150886 -vn -2.591881 2.066952 -5.298103 -v 0.061384 0.003310 0.150886 -vn -4.181210 2.384564 -3.827394 -v 0.060878 0.002441 0.150828 -vn -2.894372 1.614284 -5.298581 -v 0.060816 0.002477 0.150886 -vn -2.556063 1.726975 -5.460943 -v 0.061028 0.002821 0.150886 -vn -5.236812 3.023477 -1.191812 -v 0.060911 0.002422 0.150744 -vn -2.872723 1.331832 -5.406194 -v 0.060455 0.001756 0.150886 -vn -3.053108 -0.446408 -5.460555 -v 0.059973 -0.001800 0.150886 -vn -3.302226 -0.185795 -5.303639 -v 0.059931 -0.001398 0.150886 -vn -4.809763 -0.320133 -3.821043 -v 0.060003 -0.001393 0.150828 -vn -6.030020 0.451889 -1.191835 -v 0.060041 -0.000399 0.150744 -vn -3.124055 0.025520 -5.434689 -v 0.059919 -0.000592 0.150886 -vn -3.294260 0.341972 -5.299526 -v 0.059931 -0.000390 0.150886 -vn -3.214655 0.733726 -5.313007 -v 0.060082 0.000606 0.150886 -vn -3.116378 1.121202 -5.299546 -v 0.060379 0.001569 0.150886 -vn -3.232046 -0.737696 -5.298083 -v 0.060082 -0.002395 0.150886 -vn -4.471289 -1.782254 -3.827338 -v 0.060446 -0.003332 0.150828 -vn -3.066700 -1.256420 -5.298588 -v 0.060379 -0.003358 0.150886 -vn -2.943872 -0.921663 -5.460948 -v 0.060243 -0.002978 0.150886 -vn -5.628973 -2.209203 -1.191820 -v 0.060481 -0.003318 0.150744 -vn -2.832400 -1.415595 -5.406185 -v 0.060718 -0.004090 0.150886 -vn -1.554562 -2.665330 -5.460567 -v 0.063197 -0.006683 0.150886 -vn -1.913604 -2.697572 -5.303691 -v 0.062857 -0.006466 0.150886 -vn -2.748514 -3.959983 -3.821071 -v 0.062898 -0.006407 0.150828 -vn -4.112976 -4.432734 -1.191884 -v 0.062144 -0.005757 0.150744 -vn -1.967772 -2.426571 -5.434691 -v 0.062219 -0.005973 0.150886 -vn -2.321294 -2.362337 -5.299530 -v 0.062069 -0.005838 0.150886 -vn -2.577934 -2.055837 -5.313027 -v 0.061384 -0.005099 0.150886 -vn -2.819634 -1.737422 -5.299540 -v 0.060816 -0.004266 0.150886 -vn -1.438397 -2.986865 -5.298079 -v 0.063730 -0.006970 0.150886 -vn -1.394358 -4.606976 -3.827390 -v 0.064690 -0.007269 0.150828 -vn -0.929741 -3.180977 -5.298612 -v 0.064668 -0.007338 0.150886 -vn -1.114889 -2.876255 -5.460950 -v 0.064286 -0.007208 0.150886 -vn -1.782379 -5.778312 -1.191793 -v 0.064701 -0.007233 0.150744 -vn -0.659214 -3.097071 -5.406184 -v 0.065452 -0.007529 0.150886 -vn 1.114582 -2.877215 -5.460564 -v 0.069025 -0.007208 0.150886 -vn 0.915939 -3.178068 -5.303658 -v 0.068644 -0.007338 0.150886 -vn 1.382374 -4.617957 -3.820977 -v 0.068622 -0.007269 0.150828 -vn 0.901240 -5.979411 -1.191791 -v 0.067645 -0.007454 0.150744 -vn 0.670286 -3.051387 -5.434703 -v 0.067860 -0.007529 0.150886 -vn 0.399649 -3.287726 -5.299554 -v 0.067661 -0.007563 0.150886 -vn -0.000001 -3.297320 -5.313012 -v 0.066656 -0.007638 0.150886 -vn -0.399649 -3.287725 -5.299554 -v 0.065651 -0.007563 0.150886 -vn 1.438397 -2.986865 -5.298079 -v 0.069582 -0.006970 0.150886 -vn 2.732483 -3.962528 -3.827457 -v 0.070414 -0.006407 0.150828 -vn 1.907303 -2.710197 -5.298619 -v 0.070455 -0.006466 0.150886 -vn 1.553625 -2.664971 -5.460951 -v 0.070115 -0.006683 0.150886 -vn 3.406355 -4.996220 -1.191834 -v 0.070393 -0.006375 0.150744 -vn 2.010380 -2.446394 -5.406178 -v 0.071093 -0.005973 0.150886 -vn 2.944385 -0.922473 -5.460595 -v 0.073069 -0.002978 0.150886 -vn 3.055694 -1.265317 -5.303750 -v 0.072933 -0.003358 0.150886 -vn 4.472276 -1.798404 -3.821044 -v 0.072866 -0.003332 0.150828 -vn 5.236814 -3.023472 -1.191813 -v 0.072401 -0.004211 0.150744 -vn 2.803587 -1.378484 -5.434695 -v 0.072594 -0.004090 0.150886 -vn 2.819665 -1.737475 -5.299499 -v 0.072496 -0.004266 0.150886 -vn 2.577972 -2.055863 -5.312990 -v 0.071928 -0.005099 0.150886 -vn 2.321297 -2.362336 -5.299530 -v 0.071243 -0.005838 0.150886 -vn 3.231988 -0.737674 -5.298131 -v 0.073230 -0.002395 0.150886 -vn 4.801750 -0.334265 -3.827378 -v 0.073309 -0.001393 0.150828 -vn 3.308104 -0.198599 -5.298616 -v 0.073381 -0.001398 0.150886 -vn 3.052235 -0.446918 -5.460943 -v 0.073338 -0.001800 0.150886 -vn 6.030061 -0.451897 -1.191849 -v 0.073271 -0.001390 0.150744 -vn 3.166122 0.046464 -5.406173 -v 0.073393 -0.000592 0.150886 -vn 2.557067 1.726891 -5.460555 -v 0.072284 0.002821 0.150886 -vn 2.894622 1.600182 -5.303614 -v 0.072496 0.002477 0.150886 -vn 4.194606 2.375323 -3.820963 -v 0.072434 0.002441 0.150828 -vn 5.628978 2.209190 -1.191705 -v 0.072831 0.001529 0.150744 -vn 2.825689 1.332483 -5.434724 -v 0.072857 0.001756 0.150886 -vn 3.116249 1.121210 -5.299642 -v 0.072933 0.001569 0.150886 -vn 3.214602 0.733708 -5.313051 -v 0.073230 0.000606 0.150886 -vn 3.294199 0.341935 -5.299577 -v 0.073381 -0.000390 0.150886 -vn 2.591912 2.066990 -5.298066 -v 0.071928 0.003310 0.150886 -vn 3.255180 3.545747 -3.827437 -v 0.071194 0.003996 0.150828 -vn 2.217878 2.462600 -5.298572 -v 0.071243 0.004049 0.150886 -vn 2.252476 2.107706 -5.460925 -v 0.071530 0.003766 0.150886 -vn 4.112952 4.432716 -1.191871 -v 0.071168 0.003968 0.150744 -vn 1.937703 2.504335 -5.406184 -v 0.070620 0.004561 0.150886 -vn 0.244167 3.075883 -5.460564 -v 0.067260 0.005822 0.150886 -vn 0.553673 3.260739 -5.303668 -v 0.067661 0.005774 0.150886 -vn 0.758165 4.760397 -3.821023 -v 0.067650 0.005703 0.150828 -vn 1.782383 5.778311 -1.191796 -v 0.068611 0.005444 0.150744 -vn 0.720047 3.040039 -5.434698 -v 0.068450 0.005606 0.150886 -vn 1.066423 3.135553 -5.299543 -v 0.068644 0.005550 0.150886 -vn 1.430655 2.970793 -5.313003 -v 0.069582 0.005181 0.150886 -vn 1.786554 2.788705 -5.299579 -v 0.070455 0.004677 0.150886 -vn -0.253574 -3.303163 -5.277693 -v 0.066066 -0.010078 0.152060 -vn -0.494136 -3.372667 -5.201325 -v 0.065013 -0.009949 0.152060 -vn -0.725973 -3.232134 -5.281367 -v 0.064897 -0.009928 0.152060 -vn -0.974175 -3.167223 -5.278507 -v 0.063756 -0.009628 0.152060 -vn -1.322439 -3.327487 -5.036762 -v 0.063422 -0.009510 0.152060 -vn -1.437026 -2.984022 -5.278124 -v 0.062663 -0.009186 0.152060 -vn -1.777123 -3.107499 -5.037168 -v 0.061936 -0.008795 0.152060 -vn -1.867789 -2.735951 -5.278945 -v 0.061635 -0.008607 0.152060 -vn -2.074322 -2.582811 -5.281373 -v 0.060690 -0.007902 0.152060 -vn -2.346786 -2.492662 -5.187962 -v 0.060601 -0.007825 0.152060 -vn -2.422348 -2.264438 -5.275031 -v 0.059843 -0.007081 0.152060 -vn -2.848036 -2.271230 -4.971032 -v 0.059461 -0.006632 0.152060 -vn -2.740618 -1.861230 -5.277695 -v 0.059108 -0.006159 0.152060 -vn -2.944906 -1.716480 -5.201367 -v 0.058552 -0.005255 0.152060 -vn -2.979593 -1.447620 -5.281385 -v 0.058497 -0.005151 0.152060 -vn -3.083565 -1.213082 -5.278554 -v 0.058019 -0.004073 0.152060 -vn -3.426055 -1.040729 -5.036765 -v 0.057904 -0.003738 0.152060 -vn -3.228971 -0.736989 -5.278127 -v 0.057684 -0.002942 0.152060 -vn -3.537530 -0.548075 -5.037200 -v 0.057536 -0.002130 0.152060 -vn -3.303550 -0.245536 -5.278989 -v 0.057496 -0.001778 0.152060 -vn -3.312664 0.011478 -5.281347 -v 0.057458 -0.000599 0.152060 -vn -3.411973 0.280675 -5.188028 -v 0.057462 -0.000481 0.152060 -vn -3.280752 0.482024 -5.275004 -v 0.057571 0.000574 0.152060 -vn -3.551423 0.810582 -4.971056 -v 0.057684 0.001153 0.152060 -vn -3.163910 0.982233 -5.277701 -v 0.057833 0.001724 0.152060 -vn -3.178122 1.232250 -5.201343 -v 0.058194 0.002723 0.152060 -vn -2.989494 1.426999 -5.281413 -v 0.058241 0.002831 0.152060 -vn -2.871028 1.654503 -5.278525 -v 0.058786 0.003876 0.152060 -vn -2.949802 2.029720 -5.036747 -v 0.058976 0.004176 0.152060 -vn -2.589445 2.065013 -5.278114 -v 0.059461 0.004844 0.152060 -vn -2.634140 2.424058 -5.037162 -v 0.060004 0.005465 0.152060 -vn -2.251718 2.429758 -5.278958 -v 0.060254 0.005717 0.152060 -vn -2.056465 2.597060 -5.281365 -v 0.061152 0.006481 0.152060 -vn -1.907937 2.842604 -5.187985 -v 0.061247 0.006551 0.152060 -vn -1.668645 2.865514 -5.275020 -v 0.062140 0.007124 0.152060 -vn -1.580532 3.282005 -4.971059 -v 0.062663 0.007397 0.152060 -vn -1.204735 3.086077 -5.277683 -v 0.063202 0.007636 0.152060 -vn -1.018136 3.253092 -5.201301 -v 0.064208 0.007977 0.152060 -vn -0.748273 3.227046 -5.281370 -v 0.064322 0.008008 0.152060 -vn -0.496511 3.276254 -5.278502 -v 0.065479 0.008233 0.152060 -vn -0.252268 3.571764 -5.036744 -v 0.065831 0.008271 0.152060 -vn -0.000001 3.312032 -5.278108 -v 0.066656 0.008309 0.152060 -vn 0.252844 3.570844 -5.037148 -v 0.067481 0.008271 0.152060 -vn 0.495736 3.275417 -5.278941 -v 0.067833 0.008233 0.152060 -vn 0.748300 3.227040 -5.281368 -v 0.068990 0.008008 0.152060 -vn 1.032861 3.263986 -5.188014 -v 0.069104 0.007977 0.152060 -vn 1.199941 3.091179 -5.275057 -v 0.070110 0.007636 0.152060 -vn 1.580538 3.282019 -4.971041 -v 0.070649 0.007397 0.152060 -vn 1.661673 2.866060 -5.277658 -v 0.071172 0.007124 0.152060 -vn 1.908579 2.824266 -5.201308 -v 0.072065 0.006551 0.152060 -vn 2.056461 2.597011 -5.281401 -v 0.072160 0.006481 0.152060 -vn 2.251861 2.430855 -5.278556 -v 0.073058 0.005717 0.152060 -vn 2.635178 2.424147 -5.036813 -v 0.073308 0.005465 0.152060 -vn 2.589441 2.065017 -5.278113 -v 0.073851 0.004844 0.152060 -vn 2.949480 2.028714 -5.037109 -v 0.074336 0.004176 0.152060 -vn 2.869934 1.654616 -5.278920 -v 0.074526 0.003876 0.152060 -vn 2.989566 1.426983 -5.281361 -v 0.075071 0.002831 0.152060 -vn 3.195876 1.227530 -5.188011 -v 0.075118 0.002723 0.152060 -vn 3.164963 0.989158 -5.275037 -v 0.075478 0.001724 0.152060 -vn 3.551348 0.810578 -4.971137 -v 0.075628 0.001153 0.152060 -vn 3.276674 0.487803 -5.277773 -v 0.075741 0.000574 0.152060 -vn 3.398154 0.268734 -5.201240 -v 0.075850 -0.000481 0.152060 -vn 3.312723 0.011435 -5.281303 -v 0.075854 -0.000599 0.152060 -vn 3.304599 -0.244970 -5.278499 -v 0.075816 -0.001778 0.152060 -vn 3.538367 -0.548858 -5.036717 -v 0.075776 -0.002130 0.152060 -vn 3.228908 -0.736983 -5.278182 -v 0.075628 -0.002942 0.152060 -vn 3.425028 -1.041082 -5.037172 -v 0.075408 -0.003738 0.152060 -vn 3.082923 -1.212147 -5.278991 -v 0.075293 -0.004073 0.152060 -vn 2.979647 -1.447644 -5.281338 -v 0.074815 -0.005151 0.152060 -vn 2.952335 -1.733287 -5.187995 -v 0.074760 -0.005255 0.152060 -vn 2.746730 -1.857758 -5.274986 -v 0.074204 -0.006159 0.152060 -vn 2.848058 -2.271246 -4.971001 -v 0.073851 -0.006632 0.152060 -vn 2.424373 -2.257709 -5.277738 -v 0.073469 -0.007081 0.152060 -vn 2.328795 -2.489186 -5.201289 -v 0.072711 -0.007825 0.152060 -vn 2.074372 -2.582823 -5.281336 -v 0.072622 -0.007902 0.152060 -vn 1.868863 -2.736407 -5.278475 -v 0.071676 -0.008607 0.152060 -vn 1.776999 -3.108575 -5.036770 -v 0.071376 -0.008795 0.152060 -vn 1.437029 -2.984021 -5.278123 -v 0.070649 -0.009186 0.152060 -vn 1.321519 -3.326906 -5.037169 -v 0.069890 -0.009510 0.152060 -vn 0.974509 -3.166130 -5.278944 -v 0.069556 -0.009628 0.152060 -vn 0.725974 -3.232134 -5.281368 -v 0.068415 -0.009928 0.152060 -vn 0.485617 -3.388903 -5.188002 -v 0.068299 -0.009949 0.152060 -vn 0.260096 -3.305728 -5.275029 -v 0.067246 -0.010078 0.152060 -vn -0.000000 -3.642781 -4.971024 -v 0.066656 -0.010097 0.152060 -vn -0.646316 4.737607 -3.758069 -v 0.065470 0.008302 0.152115 -vn -0.000002 4.778792 -3.760334 -v 0.066656 0.008378 0.152115 -vn -1.182948 4.635285 -3.756018 -v 0.064304 0.008075 0.152115 -vn -1.773548 4.437411 -3.760310 -v 0.063176 0.007701 0.152115 -vn -2.366770 4.147753 -3.762608 -v 0.062106 0.007185 0.152115 -vn -2.884356 3.815827 -3.756347 -v 0.061110 0.006537 0.152115 -vn -4.106959 2.448525 -3.758097 -v 0.058726 0.003913 0.152115 -vn -3.736196 2.979515 -3.760359 -v 0.059406 0.004887 0.152115 -vn -3.301022 3.459144 -3.758091 -v 0.060205 0.005767 0.152115 -vn -4.361554 1.965175 -3.755987 -v 0.058177 0.002859 0.152115 -vn -4.575092 1.380059 -3.760295 -v 0.057767 0.001744 0.152115 -vn -4.718515 0.735671 -3.762607 -v 0.057502 0.000586 0.152115 -vn -4.781720 0.124062 -3.756307 -v 0.057388 -0.000597 0.152115 -vn -4.474976 -1.684316 -3.758059 -v 0.057954 -0.004097 0.152115 -vn -4.658949 -1.063370 -3.760366 -v 0.057616 -0.002958 0.152115 -vn -4.762608 -0.424105 -3.758070 -v 0.057426 -0.001785 0.152115 -vn -4.255816 -2.184751 -3.755995 -v 0.058435 -0.005183 0.152115 -vn -3.931498 -2.716488 -3.760322 -v 0.059051 -0.006199 0.152115 -vn -3.517101 -3.230392 -3.762593 -v 0.059792 -0.007128 0.152115 -vn -3.078316 -3.661139 -3.756366 -v 0.060645 -0.007955 0.152115 -vn -1.473266 -4.548870 -3.758040 -v 0.063734 -0.009695 0.152115 -vn -2.073428 -4.305524 -3.760349 -v 0.062633 -0.009249 0.152115 -vn -2.637878 -3.988015 -3.758056 -v 0.061597 -0.008666 0.152115 -vn -0.945368 -4.689531 -3.755965 -v 0.064883 -0.009996 0.152115 -vn -0.327416 -4.767475 -3.760323 -v 0.066062 -0.010148 0.152115 -vn 0.332748 -4.763892 -3.762614 -v 0.067250 -0.010148 0.152115 -vn 0.943096 -4.689432 -3.756307 -v 0.068429 -0.009996 0.152115 -vn 2.637872 -3.988028 -3.758090 -v 0.071715 -0.008666 0.152115 -vn 2.073431 -4.305523 -3.760350 -v 0.070679 -0.009249 0.152115 -vn 1.473268 -4.548872 -3.758039 -v 0.069578 -0.009695 0.152115 -vn 3.077024 -3.663020 -3.755934 -v 0.072667 -0.007955 0.152115 -vn 3.523230 -3.228442 -3.760250 -v 0.073520 -0.007128 0.152115 -vn 3.932028 -2.710101 -3.762659 -v 0.074261 -0.006199 0.152115 -vn 4.254368 -2.186489 -3.756297 -v 0.074877 -0.005183 0.152115 -vn 4.762719 -0.424102 -3.757912 -v 0.075886 -0.001785 0.152115 -vn 4.658895 -1.063370 -3.760406 -v 0.075696 -0.002958 0.152115 -vn 4.475016 -1.684330 -3.757957 -v 0.075358 -0.004097 0.152115 -vn 4.782402 0.121847 -3.755909 -v 0.075924 -0.000597 0.152115 -vn 4.720792 0.741671 -3.760186 -v 0.075810 0.000586 0.152115 -vn 4.570415 1.384457 -3.762588 -v 0.075545 0.001744 0.152115 -vn 4.362008 1.962943 -3.756287 -v 0.075135 0.002859 0.152115 -vn 3.300996 3.459109 -3.758120 -v 0.073107 0.005767 0.152115 -vn 3.736224 2.979537 -3.760273 -v 0.073906 0.004887 0.152115 -vn 4.107005 2.448555 -3.758055 -v 0.074585 0.003913 0.152115 -vn 2.886436 3.814903 -3.756029 -v 0.072202 0.006537 0.152115 -vn 2.363517 4.153301 -3.760347 -v 0.071206 0.007185 0.152115 -vn 1.767171 4.436458 -3.762634 -v 0.070136 0.007701 0.152115 -vn 1.184963 4.634198 -3.756363 -v 0.069008 0.008075 0.152115 -vn 0.646315 4.737608 -3.758070 -v 0.067842 0.008302 0.152115 -vn 0.755421 5.858927 -1.350042 -v 0.067847 0.008341 0.152195 -vn 1.498447 5.714211 -1.350047 -v 0.069018 0.008113 0.152195 -vn 2.216861 5.475691 -1.350026 -v 0.070150 0.007737 0.152195 -vn 2.898870 5.147222 -1.350098 -v 0.071225 0.007219 0.152195 -vn 3.533292 4.734283 -1.349998 -v 0.072225 0.006568 0.152195 -vn 4.109690 4.243587 -1.349922 -v 0.073134 0.005795 0.152195 -vn 4.618642 3.683243 -1.350012 -v 0.073936 0.004911 0.152195 -vn 5.051696 3.062369 -1.350134 -v 0.074619 0.003933 0.152195 -vn 5.401842 2.391238 -1.349999 -v 0.075171 0.002875 0.152195 -vn 5.663279 1.680822 -1.349998 -v 0.075583 0.001755 0.152195 -vn 5.831802 0.942844 -1.349921 -v 0.075848 0.000592 0.152195 -vn 5.904406 0.189339 -1.350000 -v 0.075963 -0.000596 0.152195 -vn 5.880205 -0.567247 -1.349914 -v 0.075925 -0.001788 0.152195 -vn 5.759307 -1.314520 -1.349929 -v 0.075734 -0.002966 0.152195 -vn 5.544010 -2.040250 -1.350005 -v 0.075395 -0.004110 0.152195 -vn 5.237538 -2.732423 -1.350167 -v 0.074912 -0.005201 0.152195 -vn 4.845070 -3.379717 -1.350175 -v 0.074293 -0.006222 0.152195 -vn 4.373173 -3.971604 -1.349991 -v 0.073549 -0.007155 0.152195 -vn 3.829374 -4.498206 -1.350057 -v 0.072692 -0.007985 0.152195 -vn 3.222700 -4.950924 -1.350049 -v 0.071736 -0.008698 0.152195 -vn 2.563142 -5.322407 -1.349975 -v 0.070696 -0.009284 0.152195 -vn 1.861479 -5.606499 -1.350053 -v 0.069590 -0.009732 0.152195 -vn 1.129253 -5.798510 -1.350030 -v 0.068436 -0.010034 0.152195 -vn 0.378481 -5.895289 -1.350050 -v 0.067253 -0.010187 0.152195 -vn -0.378482 -5.895287 -1.350050 -v 0.066059 -0.010187 0.152195 -vn -1.129251 -5.798509 -1.350032 -v 0.064876 -0.010034 0.152195 -vn -1.861479 -5.606498 -1.350053 -v 0.063722 -0.009732 0.152195 -vn -2.563134 -5.322415 -1.350083 -v 0.062616 -0.009284 0.152195 -vn -3.222712 -4.950951 -1.349997 -v 0.061576 -0.008698 0.152195 -vn -3.829353 -4.498173 -1.350043 -v 0.060620 -0.007985 0.152195 -vn -4.373147 -3.971576 -1.350060 -v 0.059763 -0.007155 0.152195 -vn -4.845107 -3.379735 -1.349988 -v 0.059019 -0.006222 0.152195 -vn -5.237528 -2.732416 -1.349941 -v 0.058400 -0.005201 0.152195 -vn -5.543958 -2.040228 -1.349973 -v 0.057917 -0.004110 0.152195 -vn -5.759314 -1.314523 -1.350055 -v 0.057578 -0.002966 0.152195 -vn -5.880150 -0.567251 -1.350016 -v 0.057387 -0.001788 0.152195 -vn -5.904405 0.189343 -1.350005 -v 0.057349 -0.000596 0.152195 -vn -5.831700 0.942827 -1.350119 -v 0.057464 0.000592 0.152195 -vn -5.663275 1.680825 -1.349997 -v 0.057729 0.001755 0.152195 -vn -5.401846 2.391239 -1.349999 -v 0.058141 0.002875 0.152195 -vn -5.051690 3.062365 -1.350024 -v 0.058693 0.003933 0.152195 -vn -4.618607 3.683210 -1.349987 -v 0.059376 0.004911 0.152195 -vn -4.109692 4.243591 -1.350011 -v 0.060178 0.005795 0.152195 -vn -3.533290 4.734289 -1.350076 -v 0.061087 0.006568 0.152195 -vn -2.898875 5.147249 -1.350048 -v 0.062087 0.007219 0.152195 -vn -2.216862 5.475692 -1.350025 -v 0.063162 0.007737 0.152195 -vn -1.498446 5.714213 -1.350047 -v 0.064294 0.008113 0.152195 -vn -0.755422 5.858927 -1.350044 -v 0.065465 0.008341 0.152195 -vn -0.000001 5.907433 -1.350047 -v 0.066656 0.008417 0.152195 -vn 0.756099 5.864217 1.326335 -v 0.067847 0.008341 0.152284 -vn 1.499794 5.719362 1.326389 -v 0.069018 0.008113 0.152284 -vn 2.218860 5.480628 1.326370 -v 0.070150 0.007737 0.152284 -vn 2.901507 5.151903 1.326307 -v 0.071225 0.007219 0.152284 -vn 3.536475 4.738560 1.326410 -v 0.072225 0.006568 0.152284 -vn 4.113438 4.247476 1.326369 -v 0.073134 0.005795 0.152284 -vn 4.622745 3.686515 1.326388 -v 0.073936 0.004911 0.152284 -vn 5.056238 3.065115 1.326276 -v 0.074619 0.003933 0.152284 -vn 5.406658 2.393370 1.326416 -v 0.075171 0.002875 0.152284 -vn 5.668427 1.682351 1.326250 -v 0.075583 0.001755 0.152284 -vn 5.836972 0.943677 1.326255 -v 0.075848 0.000592 0.152284 -vn 5.909801 0.189515 1.326196 -v 0.075963 -0.000596 0.152284 -vn 5.885491 -0.567764 1.326223 -v 0.075925 -0.001788 0.152284 -vn 5.764587 -1.315726 1.326320 -v 0.075734 -0.002966 0.152284 -vn 5.548933 -2.042056 1.326238 -v 0.075395 -0.004110 0.152284 -vn 5.242214 -2.734847 1.326252 -v 0.074912 -0.005201 0.152284 -vn 4.849472 -3.382781 1.326295 -v 0.074293 -0.006222 0.152284 -vn 4.377105 -3.975182 1.326232 -v 0.073549 -0.007155 0.152284 -vn 3.832830 -4.502254 1.326254 -v 0.072692 -0.007985 0.152284 -vn 3.225610 -4.955403 1.326385 -v 0.071736 -0.008698 0.152284 -vn 2.565447 -5.327219 1.326396 -v 0.070696 -0.009284 0.152284 -vn 1.863161 -5.611508 1.326342 -v 0.069590 -0.009732 0.152284 -vn 1.130278 -5.803722 1.326313 -v 0.068436 -0.010034 0.152284 -vn 0.378841 -5.900610 1.326334 -v 0.067253 -0.010187 0.152284 -vn -0.378841 -5.900609 1.326334 -v 0.066059 -0.010187 0.152284 -vn -1.130278 -5.803721 1.326313 -v 0.064876 -0.010034 0.152284 -vn -1.863162 -5.611541 1.326278 -v 0.063722 -0.009732 0.152284 -vn -2.565440 -5.327165 1.326369 -v 0.062616 -0.009284 0.152284 -vn -3.225612 -4.955406 1.326385 -v 0.061576 -0.008698 0.152284 -vn -3.832828 -4.502263 1.326338 -v 0.060620 -0.007985 0.152284 -vn -4.377083 -3.975146 1.326306 -v 0.059763 -0.007155 0.152284 -vn -4.849514 -3.382809 1.326323 -v 0.059019 -0.006222 0.152284 -vn -5.242259 -2.734888 1.326393 -v 0.058400 -0.005201 0.152284 -vn -5.548938 -2.042061 1.326356 -v 0.057917 -0.004110 0.152284 -vn -5.764478 -1.315708 1.326391 -v 0.057578 -0.002966 0.152284 -vn -5.885436 -0.567760 1.326324 -v 0.057387 -0.001788 0.152284 -vn -5.909748 0.189513 1.326299 -v 0.057349 -0.000596 0.152284 -vn -5.836972 0.943678 1.326259 -v 0.057464 0.000592 0.152284 -vn -5.668375 1.682343 1.326344 -v 0.057729 0.001755 0.152284 -vn -5.406700 2.393390 1.326331 -v 0.058141 0.002875 0.152284 -vn -5.056242 3.065123 1.326383 -v 0.058693 0.003933 0.152284 -vn -4.622782 3.686544 1.326405 -v 0.059376 0.004911 0.152284 -vn -4.113412 4.247441 1.326348 -v 0.060178 0.005795 0.152284 -vn -3.536476 4.738554 1.326338 -v 0.061087 0.006568 0.152284 -vn -2.901493 5.151884 1.326356 -v 0.062087 0.007219 0.152284 -vn -2.218860 5.480626 1.326372 -v 0.063162 0.007737 0.152284 -vn -1.499797 5.719361 1.326389 -v 0.064294 0.008113 0.152284 -vn -0.756099 5.864218 1.326334 -v 0.065465 0.008341 0.152284 -vn -0.000001 5.912749 1.326341 -v 0.066656 0.008417 0.152284 -vn 0.610562 4.735300 3.754868 -v 0.067842 0.008303 0.152365 -vn 1.211071 4.618369 3.754882 -v 0.069008 0.008076 0.152365 -vn 1.791707 4.425569 3.754880 -v 0.070136 0.007701 0.152365 -vn 2.342947 4.160130 3.754829 -v 0.071207 0.007186 0.152365 -vn 2.855708 3.826390 3.754848 -v 0.072202 0.006537 0.152365 -vn 3.321554 3.429762 3.754783 -v 0.073107 0.005767 0.152365 -vn 3.732874 2.976874 3.754908 -v 0.073906 0.004887 0.152365 -vn 4.082851 2.475053 3.754913 -v 0.074586 0.003913 0.152365 -vn 4.365900 1.932663 3.754900 -v 0.075136 0.002859 0.152365 -vn 4.577240 1.358490 3.754730 -v 0.075546 0.001744 0.152365 -vn 4.713280 0.762012 3.754873 -v 0.075810 0.000586 0.152365 -vn 4.772088 0.153034 3.754726 -v 0.075924 -0.000597 0.152365 -vn 4.752529 -0.458474 3.754726 -v 0.075886 -0.001785 0.152365 -vn 4.654765 -1.062418 3.754793 -v 0.075697 -0.002958 0.152365 -vn 4.480672 -1.648925 3.754905 -v 0.075359 -0.004097 0.152365 -vn 4.233025 -2.208359 3.754959 -v 0.074878 -0.005184 0.152365 -vn 3.915905 -2.731567 3.754888 -v 0.074262 -0.006200 0.152365 -vn 3.534445 -3.209881 3.754839 -v 0.073521 -0.007129 0.152365 -vn 3.094982 -3.635541 3.754830 -v 0.072667 -0.007955 0.152365 -vn 2.604666 -4.001481 3.754864 -v 0.071715 -0.008666 0.152365 -vn 2.071581 -4.301681 3.754865 -v 0.070679 -0.009249 0.152365 -vn 1.504486 -4.531290 3.754886 -v 0.069578 -0.009695 0.152365 -vn 0.912693 -4.686455 3.754868 -v 0.068429 -0.009997 0.152365 -vn 0.305894 -4.764695 3.754866 -v 0.067250 -0.010149 0.152365 -vn -0.305894 -4.764696 3.754867 -v 0.066062 -0.010149 0.152365 -vn -0.912691 -4.686455 3.754866 -v 0.064883 -0.009997 0.152365 -vn -1.504498 -4.531279 3.754846 -v 0.063734 -0.009695 0.152365 -vn -2.071575 -4.301698 3.754917 -v 0.062632 -0.009249 0.152365 -vn -2.604669 -4.001478 3.754867 -v 0.061597 -0.008666 0.152365 -vn -3.094981 -3.635540 3.754833 -v 0.060645 -0.007955 0.152365 -vn -3.534449 -3.209894 3.754883 -v 0.059791 -0.007129 0.152365 -vn -3.915944 -2.731583 3.754796 -v 0.059050 -0.006200 0.152365 -vn -4.233109 -2.208407 3.754819 -v 0.058434 -0.005184 0.152365 -vn -4.480723 -1.648947 3.754859 -v 0.057953 -0.004097 0.152365 -vn -4.654793 -1.062429 3.754916 -v 0.057615 -0.002958 0.152365 -vn -4.752420 -0.458463 3.754882 -v 0.057426 -0.001785 0.152365 -vn -4.772039 0.153030 3.754837 -v 0.057388 -0.000597 0.152365 -vn -4.713279 0.762007 3.754871 -v 0.057502 0.000586 0.152365 -vn -4.577142 1.358471 3.754879 -v 0.057766 0.001744 0.152365 -vn -4.365889 1.932653 3.754842 -v 0.058176 0.002859 0.152365 -vn -4.082896 2.475080 3.754874 -v 0.058726 0.003913 0.152365 -vn -3.732871 2.976860 3.754863 -v 0.059406 0.004887 0.152365 -vn -3.321556 3.429775 3.754829 -v 0.060205 0.005767 0.152365 -vn -2.855686 3.826363 3.754874 -v 0.061110 0.006537 0.152365 -vn -2.342929 4.160115 3.754885 -v 0.062105 0.007186 0.152365 -vn -1.791710 4.425569 3.754878 -v 0.063176 0.007701 0.152365 -vn -1.211072 4.618370 3.754883 -v 0.064304 0.008076 0.152365 -vn -0.610558 4.735315 3.754858 -v 0.065470 0.008303 0.152365 -vn -0.000001 4.774516 3.754872 -v 0.066656 0.008379 0.152365 -vn 0.344432 2.671419 5.471253 -v 0.067833 0.008234 0.152420 -vn 0.683241 2.605476 5.471219 -v 0.068991 0.008008 0.152420 -vn 1.010798 2.496694 5.471243 -v 0.070110 0.007637 0.152420 -vn 1.321760 2.346918 5.471245 -v 0.071172 0.007125 0.152420 -vn 1.611067 2.158667 5.471203 -v 0.072161 0.006482 0.152420 -vn 1.873825 1.934888 5.471278 -v 0.073059 0.005717 0.152420 -vn 2.105947 1.679426 5.471195 -v 0.073852 0.004844 0.152420 -vn 2.303364 1.396320 5.471264 -v 0.074526 0.003877 0.152420 -vn 2.463074 1.090329 5.471182 -v 0.075072 0.002831 0.152420 -vn 2.582239 0.766391 5.471217 -v 0.075479 0.001724 0.152420 -vn 2.659001 0.429886 5.471273 -v 0.075742 0.000575 0.152420 -vn 2.692114 0.086339 5.471279 -v 0.075855 -0.000599 0.152420 -vn 2.681137 -0.258652 5.471208 -v 0.075817 -0.001778 0.152420 -vn 2.625939 -0.599357 5.471324 -v 0.075629 -0.002942 0.152420 -vn 2.527761 -0.930242 5.471295 -v 0.075293 -0.004073 0.152420 -vn 2.388088 -1.245862 5.471267 -v 0.074816 -0.005151 0.152420 -vn 2.209162 -1.541018 5.471249 -v 0.074205 -0.006160 0.152420 -vn 1.993930 -1.810836 5.471299 -v 0.073469 -0.007082 0.152420 -vn 1.746028 -2.050982 5.471246 -v 0.072622 -0.007902 0.152420 -vn 1.469429 -2.257440 5.471221 -v 0.071677 -0.008608 0.152420 -vn 1.168687 -2.426806 5.471249 -v 0.070649 -0.009187 0.152420 -vn 0.848774 -2.556350 5.471215 -v 0.069556 -0.009629 0.152420 -vn 0.514890 -2.643864 5.471252 -v 0.068415 -0.009928 0.152420 -vn 0.172583 -2.688004 5.471248 -v 0.067246 -0.010079 0.152420 -vn -0.172581 -2.688008 5.471246 -v 0.066066 -0.010079 0.152420 -vn -0.514887 -2.643863 5.471251 -v 0.064897 -0.009928 0.152420 -vn -0.848754 -2.556314 5.471249 -v 0.063756 -0.009629 0.152420 -vn -1.168710 -2.426831 5.471207 -v 0.062663 -0.009187 0.152420 -vn -1.469438 -2.257450 5.471218 -v 0.061635 -0.008608 0.152420 -vn -1.746029 -2.050985 5.471246 -v 0.060690 -0.007902 0.152420 -vn -1.993951 -1.810856 5.471264 -v 0.059843 -0.007082 0.152420 -vn -2.209161 -1.541016 5.471252 -v 0.059107 -0.006160 0.152420 -vn -2.388119 -1.245875 5.471223 -v 0.058496 -0.005151 0.152420 -vn -2.527796 -0.930253 5.471248 -v 0.058019 -0.004073 0.152420 -vn -2.626035 -0.599373 5.471224 -v 0.057683 -0.002942 0.152420 -vn -2.681073 -0.258642 5.471263 -v 0.057495 -0.001778 0.152420 -vn -2.692114 0.086330 5.471278 -v 0.057457 -0.000599 0.152420 -vn -2.658976 0.429883 5.471277 -v 0.057570 0.000575 0.152420 -vn -2.582200 0.766383 5.471271 -v 0.057833 0.001724 0.152420 -vn -2.463020 1.090306 5.471231 -v 0.058240 0.002831 0.152420 -vn -2.303392 1.396332 5.471220 -v 0.058786 0.003877 0.152420 -vn -2.105904 1.679399 5.471237 -v 0.059460 0.004844 0.152420 -vn -1.873850 1.934900 5.471246 -v 0.060253 0.005717 0.152420 -vn -1.611045 2.158656 5.471232 -v 0.061151 0.006482 0.152420 -vn -1.321771 2.346941 5.471239 -v 0.062140 0.007125 0.152420 -vn -1.010800 2.496693 5.471243 -v 0.063202 0.007637 0.152420 -vn -0.683239 2.605477 5.471220 -v 0.064321 0.008008 0.152420 -vn -0.344447 2.671429 5.471242 -v 0.065479 0.008234 0.152420 -vn 0.000001 2.693559 5.471230 -v 0.066656 0.008309 0.152420 -vn 0.093025 0.721485 6.197586 -v 0.067822 0.008148 0.152440 -vn 0.184521 0.703663 6.197588 -v 0.068968 0.007924 0.152440 -vn 0.272991 0.674291 6.197587 -v 0.070077 0.007556 0.152440 -vn 0.356961 0.633825 6.197592 -v 0.071130 0.007049 0.152440 -vn 0.435087 0.582979 6.197591 -v 0.072109 0.006412 0.152440 -vn 0.506087 0.522575 6.197586 -v 0.072998 0.005655 0.152440 -vn 0.568743 0.453559 6.197589 -v 0.073784 0.004790 0.152440 -vn 0.622111 0.377125 6.197577 -v 0.074452 0.003832 0.152440 -vn 0.665187 0.294461 6.197589 -v 0.074992 0.002796 0.152440 -vn 0.697384 0.206979 6.197588 -v 0.075396 0.001700 0.152440 -vn 0.718153 0.116103 6.197581 -v 0.075656 0.000561 0.152440 -vn 0.727075 0.023318 6.197588 -v 0.075768 -0.000602 0.152440 -vn 0.724095 -0.069852 6.197588 -v 0.075731 -0.001770 0.152440 -vn 0.709244 -0.161883 6.197579 -v 0.075544 -0.002923 0.152440 -vn 0.682713 -0.251244 6.197584 -v 0.075212 -0.004043 0.152440 -vn 0.644986 -0.336488 6.197579 -v 0.074739 -0.005111 0.152440 -vn 0.596637 -0.416188 6.197588 -v 0.074133 -0.006110 0.152440 -vn 0.538528 -0.489077 6.197584 -v 0.073405 -0.007024 0.152440 -vn 0.471556 -0.553916 6.197587 -v 0.072566 -0.007836 0.152440 -vn 0.396840 -0.609655 6.197591 -v 0.071629 -0.008535 0.152440 -vn 0.315638 -0.655429 6.197582 -v 0.070612 -0.009108 0.152440 -vn 0.229225 -0.690390 6.197588 -v 0.069529 -0.009547 0.152440 -vn 0.139059 -0.714039 6.197588 -v 0.068399 -0.009843 0.152440 -vn 0.046606 -0.725961 6.197589 -v 0.067240 -0.009992 0.152440 -vn -0.046609 -0.725964 6.197587 -v 0.066072 -0.009992 0.152440 -vn -0.139059 -0.714039 6.197587 -v 0.064913 -0.009843 0.152440 -vn -0.229223 -0.690390 6.197588 -v 0.063783 -0.009547 0.152440 -vn -0.315626 -0.655407 6.197589 -v 0.062700 -0.009108 0.152440 -vn -0.396850 -0.609668 6.197589 -v 0.061682 -0.008535 0.152440 -vn -0.471556 -0.553916 6.197588 -v 0.060746 -0.007836 0.152440 -vn -0.538511 -0.489062 6.197589 -v 0.059907 -0.007024 0.152440 -vn -0.596636 -0.416188 6.197587 -v 0.059179 -0.006110 0.152440 -vn -0.644963 -0.336476 6.197587 -v 0.058573 -0.005111 0.152440 -vn -0.682687 -0.251235 6.197588 -v 0.058100 -0.004043 0.152440 -vn -0.709218 -0.161874 6.197588 -v 0.057768 -0.002923 0.152440 -vn -0.724094 -0.069852 6.197587 -v 0.057581 -0.001770 0.152440 -vn -0.727075 0.023316 6.197589 -v 0.057544 -0.000602 0.152440 -vn -0.718125 0.116100 6.197588 -v 0.057656 0.000561 0.152440 -vn -0.697410 0.206988 6.197583 -v 0.057916 0.001700 0.152440 -vn -0.665188 0.294458 6.197588 -v 0.058320 0.002796 0.152440 -vn -0.622088 0.377115 6.197584 -v 0.058860 0.003832 0.152440 -vn -0.568743 0.453558 6.197587 -v 0.059528 0.004790 0.152440 -vn -0.506072 0.522561 6.197590 -v 0.060314 0.005655 0.152440 -vn -0.435099 0.582993 6.197588 -v 0.061203 0.006412 0.152440 -vn -0.356977 0.633849 6.197588 -v 0.062182 0.007049 0.152440 -vn -0.272990 0.674291 6.197586 -v 0.063235 0.007556 0.152440 -vn -0.184522 0.703663 6.197589 -v 0.064343 0.007924 0.152440 -vn -0.093022 0.721478 6.197589 -v 0.065490 0.008148 0.152440 -vn -0.000000 0.727456 6.197587 -v 0.066656 0.008222 0.152440 -vn 0.035279 0.335656 6.264974 -v 0.065782 -0.009206 0.152440 -vn 0.070171 0.330129 6.264974 -v 0.064918 -0.009070 0.152440 -vn 0.104294 0.320985 6.264974 -v 0.064073 -0.008843 0.152440 -vn 0.137275 0.308325 6.264974 -v 0.063257 -0.008530 0.152440 -vn 0.168752 0.292287 6.264974 -v 0.062477 -0.008132 0.152440 -vn 0.198380 0.273047 6.264974 -v 0.061743 -0.007656 0.152440 -vn 0.225836 0.250815 6.264974 -v 0.061063 -0.007105 0.152440 -vn 0.250815 0.225835 6.264974 -v 0.060445 -0.006487 0.152440 -vn 0.273046 0.198380 6.264974 -v 0.059894 -0.005807 0.152440 -vn 0.292286 0.168752 6.264974 -v 0.059418 -0.005073 0.152440 -vn 0.308327 0.137275 6.264974 -v 0.059021 -0.004294 0.152440 -vn 0.320987 0.104295 6.264974 -v 0.058707 -0.003477 0.152440 -vn 0.330128 0.070171 6.264974 -v 0.058481 -0.002632 0.152440 -vn 0.335657 0.035279 6.264974 -v 0.058344 -0.001768 0.152440 -vn 0.337504 0.000000 6.264974 -v 0.058298 -0.000894 0.152440 -vn 0.335657 -0.035279 6.264974 -v 0.058344 -0.000021 0.152440 -vn 0.330128 -0.070171 6.264974 -v 0.058481 0.000843 0.152440 -vn 0.320987 -0.104295 6.264974 -v 0.058707 0.001688 0.152440 -vn 0.308326 -0.137276 6.264974 -v 0.059021 0.002505 0.152440 -vn 0.292286 -0.168751 6.264974 -v 0.059418 0.003285 0.152440 -vn 0.273047 -0.198380 6.264974 -v 0.059894 0.004018 0.152440 -vn 0.250815 -0.225835 6.264973 -v 0.060445 0.004698 0.152440 -vn 0.225835 -0.250815 6.264974 -v 0.061063 0.005317 0.152440 -vn 0.198380 -0.273046 6.264974 -v 0.061743 0.005867 0.152440 -vn 0.168752 -0.292287 6.264974 -v 0.062477 0.006344 0.152440 -vn 0.137275 -0.308325 6.264974 -v 0.063257 0.006741 0.152440 -vn -0.335654 -0.035279 6.264974 -v 0.074968 -0.000021 0.152440 -vn -0.337504 0.000000 6.264974 -v 0.075014 -0.000894 0.152440 -vn -0.335654 0.035279 6.264974 -v 0.074968 -0.001768 0.152440 -vn -0.330129 0.070172 6.264974 -v 0.074831 -0.002632 0.152440 -vn -0.320985 0.104294 6.264974 -v 0.074605 -0.003477 0.152440 -vn -0.308326 0.137276 6.264974 -v 0.074291 -0.004294 0.152440 -vn -0.292287 0.168752 6.264974 -v 0.073894 -0.005073 0.152440 -vn -0.273048 0.198381 6.264973 -v 0.073418 -0.005807 0.152440 -vn -0.250817 0.225836 6.264974 -v 0.072867 -0.006487 0.152440 -vn -0.225835 0.250815 6.264974 -v 0.072249 -0.007105 0.152440 -vn -0.198380 0.273046 6.264974 -v 0.071569 -0.007656 0.152440 -vn -0.168752 0.292288 6.264974 -v 0.070835 -0.008132 0.152440 -vn -0.137276 0.308327 6.264974 -v 0.070055 -0.008530 0.152440 -vn -0.104295 0.320985 6.264974 -v 0.069239 -0.008843 0.152440 -vn -0.070171 0.330129 6.264974 -v 0.068394 -0.009070 0.152440 -vn -0.035279 0.335655 6.264974 -v 0.067530 -0.009206 0.152440 -vn -0.000000 0.337504 6.264974 -v 0.066656 -0.009252 0.152440 -vn 0.104294 -0.320985 6.264975 -v 0.064073 0.007054 0.152440 -vn 0.070171 -0.330129 6.264974 -v 0.064918 0.007281 0.152440 -vn 0.035279 -0.335656 6.264974 -v 0.065782 0.007418 0.152440 -vn 0.000000 -0.337504 6.264974 -v 0.066656 0.007464 0.152440 -vn -0.035279 -0.335656 6.264974 -v 0.067530 0.007418 0.152440 -vn -0.273047 -0.198380 6.264974 -v 0.073418 0.004018 0.152440 -vn -0.292286 -0.168752 6.264974 -v 0.073894 0.003285 0.152440 -vn -0.308326 -0.137275 6.264974 -v 0.074291 0.002505 0.152440 -vn -0.320985 -0.104294 6.264975 -v 0.074605 0.001688 0.152440 -vn -0.330129 -0.070172 6.264974 -v 0.074831 0.000843 0.152440 -vn -0.070171 -0.330129 6.264974 -v 0.068394 0.007281 0.152440 -vn -0.104294 -0.320985 6.264974 -v 0.069239 0.007054 0.152440 -vn -0.137276 -0.308327 6.264975 -v 0.070055 0.006741 0.152440 -vn -0.168752 -0.292288 6.264974 -v 0.070835 0.006344 0.152440 -vn -0.198380 -0.273047 6.264974 -v 0.071569 0.005867 0.152440 -vn -0.225836 -0.250815 6.264974 -v 0.072249 0.005317 0.152440 -vn -0.250817 -0.225836 6.264974 -v 0.072867 0.004698 0.152440 -vn -0.141943 -1.350498 6.099612 -v 0.067460 0.006759 0.152366 -vn -0.282331 -1.328263 6.099612 -v 0.068256 0.006633 0.152366 -vn -0.419625 -1.291476 6.099611 -v 0.069034 0.006424 0.152366 -vn -0.552323 -1.240537 6.099612 -v 0.069786 0.006136 0.152366 -vn -0.678970 -1.176010 6.099611 -v 0.070504 0.005770 0.152366 -vn -0.798174 -1.098593 6.099613 -v 0.071179 0.005331 0.152366 -vn -0.908634 -1.009141 6.099613 -v 0.071805 0.004824 0.152366 -vn -1.009145 -0.908635 6.099613 -v 0.072375 0.004255 0.152366 -vn -1.098598 -0.798175 6.099612 -v 0.072882 0.003629 0.152366 -vn -1.176014 -0.678972 6.099610 -v 0.073320 0.002953 0.152366 -vn -1.240535 -0.552324 6.099612 -v 0.073686 0.002236 0.152366 -vn -1.291482 -0.419625 6.099609 -v 0.073975 0.001484 0.152366 -vn -1.328268 -0.282334 6.099609 -v 0.074183 0.000706 0.152366 -vn -1.350494 -0.141947 6.099613 -v 0.074309 -0.000090 0.152366 -vn -1.357936 0.000000 6.099612 -v 0.074351 -0.000894 0.152366 -vn -1.350496 0.141945 6.099612 -v 0.074309 -0.001699 0.152366 -vn -1.328270 0.282336 6.099608 -v 0.074183 -0.002494 0.152366 -vn -1.291479 0.419625 6.099610 -v 0.073975 -0.003272 0.152366 -vn -1.240536 0.552321 6.099613 -v 0.073686 -0.004024 0.152366 -vn -1.176012 0.678975 6.099609 -v 0.073320 -0.004742 0.152366 -vn -1.098596 0.798172 6.099612 -v 0.072882 -0.005418 0.152366 -vn -1.009143 0.908635 6.099613 -v 0.072375 -0.006044 0.152366 -vn -0.908636 1.009140 6.099614 -v 0.071805 -0.006613 0.152366 -vn -0.798174 1.098594 6.099612 -v 0.071179 -0.007120 0.152366 -vn -0.678969 1.176010 6.099610 -v 0.070504 -0.007559 0.152366 -vn -0.552323 1.240536 6.099612 -v 0.069786 -0.007924 0.152366 -vn -0.419624 1.291476 6.099611 -v 0.069034 -0.008213 0.152366 -vn -0.282331 1.328262 6.099611 -v 0.068256 -0.008422 0.152366 -vn -0.141943 1.350497 6.099612 -v 0.067460 -0.008548 0.152366 -vn 0.000000 1.357937 6.099611 -v 0.066656 -0.008590 0.152366 -vn 0.141943 1.350497 6.099612 -v 0.065852 -0.008548 0.152366 -vn 0.282331 1.328263 6.099612 -v 0.065056 -0.008422 0.152366 -vn 0.419624 1.291475 6.099612 -v 0.064278 -0.008213 0.152366 -vn 0.552322 1.240535 6.099612 -v 0.063526 -0.007924 0.152366 -vn 0.678969 1.176009 6.099611 -v 0.062808 -0.007559 0.152366 -vn 0.798173 1.098593 6.099612 -v 0.062133 -0.007120 0.152366 -vn 0.908636 1.009142 6.099612 -v 0.061507 -0.006613 0.152366 -vn 1.009144 0.908635 6.099613 -v 0.060937 -0.006044 0.152366 -vn 1.098595 0.798174 6.099611 -v 0.060430 -0.005418 0.152366 -vn 1.176005 0.678968 6.099612 -v 0.059992 -0.004742 0.152366 -vn 1.240536 0.552323 6.099612 -v 0.059626 -0.004024 0.152366 -vn 1.291477 0.419625 6.099611 -v 0.059337 -0.003272 0.152366 -vn 1.328264 0.282331 6.099611 -v 0.059129 -0.002494 0.152366 -vn 1.350496 0.141943 6.099613 -v 0.059003 -0.001699 0.152366 -vn 1.357936 0.000000 6.099612 -v 0.058961 -0.000894 0.152366 -vn 1.350497 -0.141943 6.099613 -v 0.059003 -0.000090 0.152366 -vn 1.328265 -0.282331 6.099611 -v 0.059129 0.000706 0.152366 -vn 1.291476 -0.419626 6.099612 -v 0.059337 0.001484 0.152366 -vn 1.240536 -0.552323 6.099613 -v 0.059626 0.002236 0.152366 -vn 1.176006 -0.678968 6.099612 -v 0.059992 0.002953 0.152366 -vn 1.098594 -0.798174 6.099612 -v 0.060430 0.003629 0.152366 -vn 1.009143 -0.908634 6.099613 -v 0.060937 0.004255 0.152366 -vn 0.908637 -1.009143 6.099612 -v 0.061507 0.004824 0.152366 -vn 0.798174 -1.098594 6.099612 -v 0.062133 0.005331 0.152366 -vn 0.678968 -1.176010 6.099610 -v 0.062808 0.005770 0.152366 -vn 0.552322 -1.240536 6.099613 -v 0.063526 0.006136 0.152366 -vn 0.419624 -1.291476 6.099611 -v 0.064278 0.006424 0.152366 -vn 0.282331 -1.328262 6.099612 -v 0.065056 0.006633 0.152366 -vn 0.141943 -1.350498 6.099612 -v 0.065852 0.006759 0.152366 -vn 0.000000 -1.357936 6.099612 -v 0.066656 0.006801 0.152366 -vn -0.247058 -2.361769 5.810093 -v 0.067395 0.006133 0.152148 -vn -0.495121 -2.323893 5.809431 -v 0.068125 0.006017 0.152148 -vn -0.732967 -2.259621 5.809680 -v 0.068839 0.005825 0.152148 -vn -0.967422 -2.170091 5.809474 -v 0.069530 0.005560 0.152148 -vn -1.187221 -2.056327 5.810172 -v 0.070189 0.005225 0.152148 -vn -1.395665 -1.920960 5.810173 -v 0.070809 0.004822 0.152148 -vn -1.588303 -1.760572 5.811685 -v 0.071384 0.004356 0.152148 -vn -1.761520 -1.590552 5.810660 -v 0.071907 0.003833 0.152148 -vn -1.921821 -1.394845 5.810093 -v 0.072372 0.003259 0.152148 -vn -2.056331 -1.187221 5.810172 -v 0.072775 0.002638 0.152148 -vn -2.168880 -0.966928 5.810094 -v 0.073111 0.001979 0.152148 -vn -2.260113 -0.733158 5.809429 -v 0.073376 0.001289 0.152148 -vn -2.323378 -0.495040 5.809679 -v 0.073567 0.000575 0.152148 -vn -2.363064 -0.247233 5.809474 -v 0.073683 -0.000156 0.152148 -vn -2.374440 -0.000001 5.810173 -v 0.073722 -0.000894 0.152148 -vn -2.361431 0.248195 5.810174 -v 0.073683 -0.001633 0.152148 -vn -2.318859 0.495226 5.811684 -v 0.073567 -0.002363 0.152148 -vn -2.258225 0.730251 5.810658 -v 0.073376 -0.003078 0.152148 -vn -2.168882 0.966922 5.810093 -v 0.073111 -0.003768 0.152148 -vn -2.056328 1.187225 5.810172 -v 0.072775 -0.004427 0.152148 -vn -1.921824 1.394845 5.810092 -v 0.072372 -0.005047 0.152148 -vn -1.764985 1.590735 5.809432 -v 0.071907 -0.005622 0.152148 -vn -1.590404 1.764573 5.809683 -v 0.071384 -0.006145 0.152148 -vn -1.395645 1.922854 5.809475 -v 0.070809 -0.006611 0.152148 -vn -1.187220 2.056328 5.810172 -v 0.070189 -0.007013 0.152148 -vn -0.965772 2.169159 5.810174 -v 0.069530 -0.007349 0.152148 -vn -0.730548 2.255801 5.811685 -v 0.068839 -0.007614 0.152148 -vn -0.496697 2.320801 5.810660 -v 0.068125 -0.007806 0.152148 -vn -0.247059 2.361768 5.810093 -v 0.067395 -0.007921 0.152148 -vn 0.000001 2.374441 5.810173 -v 0.066656 -0.007960 0.152148 -vn 0.247059 2.361769 5.810093 -v 0.065917 -0.007921 0.152148 -vn 0.495122 2.323893 5.809431 -v 0.065187 -0.007806 0.152148 -vn 0.732966 2.259622 5.809680 -v 0.064473 -0.007614 0.152148 -vn 0.967422 2.170091 5.809473 -v 0.063782 -0.007349 0.152148 -vn 1.187221 2.056327 5.810172 -v 0.063123 -0.007013 0.152148 -vn 1.395662 1.920963 5.810173 -v 0.062503 -0.006611 0.152148 -vn 1.588306 1.760574 5.811685 -v 0.061928 -0.006145 0.152148 -vn 1.761524 1.590551 5.810660 -v 0.061405 -0.005622 0.152148 -vn 1.921824 1.394843 5.810093 -v 0.060940 -0.005047 0.152148 -vn 2.056326 1.187222 5.810173 -v 0.060537 -0.004427 0.152148 -vn 2.168879 0.966929 5.810094 -v 0.060201 -0.003768 0.152148 -vn 2.260111 0.733159 5.809431 -v 0.059936 -0.003078 0.152148 -vn 2.323375 0.495039 5.809680 -v 0.059745 -0.002363 0.152148 -vn 2.363065 0.247231 5.809474 -v 0.059629 -0.001633 0.152148 -vn 2.374441 0.000000 5.810173 -v 0.059590 -0.000894 0.152148 -vn 2.361433 -0.248195 5.810173 -v 0.059629 -0.000156 0.152148 -vn 2.318857 -0.495224 5.811685 -v 0.059745 0.000575 0.152148 -vn 2.258222 -0.730251 5.810659 -v 0.059936 0.001289 0.152148 -vn 2.168880 -0.966928 5.810093 -v 0.060201 0.001979 0.152148 -vn 2.056326 -1.187222 5.810173 -v 0.060537 0.002638 0.152148 -vn 1.921824 -1.394843 5.810093 -v 0.060940 0.003259 0.152148 -vn 1.764990 -1.590732 5.809433 -v 0.061405 0.003833 0.152148 -vn 1.590406 -1.764576 5.809681 -v 0.061928 0.004356 0.152148 -vn 1.395643 -1.922858 5.809473 -v 0.062503 0.004822 0.152148 -vn 1.187220 -2.056328 5.810173 -v 0.063123 0.005225 0.152148 -vn 0.965772 -2.169159 5.810173 -v 0.063782 0.005560 0.152148 -vn 0.730549 -2.255802 5.811684 -v 0.064473 0.005825 0.152148 -vn 0.496697 -2.320802 5.810660 -v 0.065187 0.006017 0.152148 -vn 0.247059 -2.361769 5.810094 -v 0.065917 0.006133 0.152148 -vn 0.000001 -2.374441 5.810173 -v 0.066656 0.006171 0.152148 -vn 0.000001 3.292325 5.317496 -v 0.066656 -0.005989 0.151207 -vn 0.466001 3.275944 5.302576 -v 0.065771 -0.005912 0.151207 -vn 0.775097 3.024009 5.436589 -v 0.065597 -0.005878 0.151207 -vn 1.063700 3.126341 5.307950 -v 0.064913 -0.005682 0.151207 -vn 1.265347 2.646811 5.552467 -v 0.064584 -0.005549 0.151207 -vn 1.622109 2.869236 5.313052 -v 0.064108 -0.005307 0.151207 -vn 1.786376 2.517983 5.460447 -v 0.063661 -0.005016 0.151207 -vn 2.173749 2.505194 5.298803 -v 0.063381 -0.004797 0.151207 -vn 2.278740 2.200864 5.406148 -v 0.062870 -0.004304 0.151207 -vn 2.604044 2.041522 5.302588 -v 0.062753 -0.004169 0.151207 -vn 2.851252 1.646168 5.317486 -v 0.062243 -0.003442 0.151207 -vn 3.070022 1.234380 5.302604 -v 0.061868 -0.002637 0.151207 -vn 3.006392 0.840729 5.436609 -v 0.061810 -0.002469 0.151207 -vn 3.239352 0.641987 5.307940 -v 0.061638 -0.001779 0.151207 -vn 2.924875 0.227592 5.552469 -v 0.061589 -0.001427 0.151207 -vn 3.295866 0.029824 5.313067 -v 0.061561 -0.000894 0.151207 -vn 3.073860 -0.288064 5.460425 -v 0.061589 -0.000362 0.151207 -vn 3.256502 -0.629936 5.298751 -v 0.061638 -0.000010 0.151207 -vn 3.045398 -0.873010 5.406131 -v 0.061810 0.000680 0.151207 -vn 3.070025 -1.234379 5.302602 -v 0.061868 0.000848 0.151207 -vn 2.851251 -1.646172 5.317486 -v 0.062243 0.001653 0.151207 -vn 2.604043 -2.041521 5.302589 -v 0.062753 0.002381 0.151207 -vn 2.231292 -2.183229 5.436617 -v 0.062870 0.002515 0.151207 -vn 2.175610 -2.484318 5.307991 -v 0.063381 0.003009 0.151207 -vn 1.659493 -2.419176 5.552504 -v 0.063661 0.003228 0.151207 -vn 1.673768 -2.839405 5.313054 -v 0.064108 0.003518 0.151207 -vn 1.287470 -2.806077 5.460420 -v 0.064584 0.003760 0.151207 -vn 1.082711 -3.135167 5.298762 -v 0.064913 0.003894 0.151207 -vn 0.766646 -3.073920 5.406116 -v 0.065597 0.004089 0.151207 -vn 0.466000 -3.275944 5.302576 -v 0.065771 0.004123 0.151207 -vn 0.000001 -3.292325 5.317496 -v 0.066656 0.004201 0.151207 -vn -0.465999 -3.275944 5.302576 -v 0.067541 0.004123 0.151207 -vn -0.775101 -3.024001 5.436594 -v 0.067715 0.004089 0.151207 -vn -1.063698 -3.126382 5.307920 -v 0.068399 0.003894 0.151207 -vn -1.265342 -2.646816 5.552464 -v 0.068728 0.003760 0.151207 -vn -1.622109 -2.869236 5.313052 -v 0.069204 0.003518 0.151207 -vn -1.786385 -2.517978 5.460446 -v 0.069651 0.003228 0.151207 -vn -2.173815 -2.505242 5.298740 -v 0.069931 0.003009 0.151207 -vn -2.278762 -2.200934 5.406101 -v 0.070442 0.002515 0.151207 -vn -2.604008 -2.041557 5.302595 -v 0.070559 0.002381 0.151207 -vn -2.851298 -1.646191 5.317446 -v 0.071069 0.001653 0.151207 -vn -3.070074 -1.234401 5.302560 -v 0.071444 0.000848 0.151207 -vn -3.006439 -0.840741 5.436576 -v 0.071502 0.000680 0.151207 -vn -3.239352 -0.641983 5.307940 -v 0.071674 -0.000010 0.151207 -vn -2.924898 -0.227606 5.552455 -v 0.071723 -0.000362 0.151207 -vn -3.295864 -0.029822 5.313069 -v 0.071751 -0.000894 0.151207 -vn -3.073874 0.288077 5.460415 -v 0.071723 -0.001427 0.151207 -vn -3.256499 0.629936 5.298753 -v 0.071674 -0.001779 0.151207 -vn -3.045438 0.873015 5.406104 -v 0.071502 -0.002469 0.151207 -vn -3.070075 1.234400 5.302559 -v 0.071444 -0.002637 0.151207 -vn -2.851294 1.646197 5.317447 -v 0.071069 -0.003442 0.151207 -vn -2.604010 2.041551 5.302597 -v 0.070559 -0.004169 0.151207 -vn -2.231309 2.183294 5.436577 -v 0.070442 -0.004304 0.151207 -vn -2.175675 2.484370 5.307928 -v 0.069931 -0.004797 0.151207 -vn -1.659505 2.419176 5.552501 -v 0.069651 -0.005016 0.151207 -vn -1.673768 2.839404 5.313053 -v 0.069204 -0.005307 0.151207 -vn -1.287466 2.806081 5.460419 -v 0.068728 -0.005549 0.151207 -vn -1.082710 3.135210 5.298730 -v 0.068399 -0.005682 0.151207 -vn -0.766648 3.073921 5.406116 -v 0.067715 -0.005878 0.151207 -vn -0.465999 3.275944 5.302576 -v 0.067541 -0.005912 0.151207 -vn -4.871992 0.492891 -3.923194 -v 0.071638 -0.001611 0.150892 -vn -4.954241 1.044240 -3.670909 -v 0.071613 -0.001768 0.150892 -vn -5.806787 1.086890 -1.740380 -v 0.071569 -0.001761 0.150972 -vn 2.862960 3.971411 -3.924433 -v 0.063544 -0.004851 0.150892 -vn 3.380865 3.768106 -3.671611 -v 0.063420 -0.004750 0.150892 -vn 3.844635 4.485321 -1.740504 -v 0.063449 -0.004716 0.150972 -vn 2.009994 -4.465858 -3.922657 -v 0.064785 0.003779 0.150892 -vn 1.573694 -4.810864 -3.672517 -v 0.064934 0.003836 0.150892 -vn 1.962090 -5.572227 -1.740490 -v 0.064950 0.003794 0.150972 -vn -4.635754 -3.889885 1.195378 -v 0.070475 0.002310 0.151065 -vn -3.717661 -3.052767 3.838364 -v 0.070504 0.002334 0.151149 -vn -3.113453 -3.665000 3.840485 -v 0.069885 0.002954 0.151149 -vn -5.959710 1.050858 1.195108 -v 0.071565 -0.001760 0.151065 -vn -4.730771 0.863843 3.840351 -v 0.071603 -0.001767 0.151149 -vn -4.824802 -0.033084 3.826098 -v 0.071679 -0.000894 0.151149 -vn -1.050841 5.959650 1.195236 -v 0.067522 -0.005804 0.151065 -vn -0.784926 4.746013 3.838303 -v 0.067528 -0.005841 0.151149 -vn -1.617277 4.528831 3.840487 -v 0.068374 -0.005615 0.151149 -vn 3.889880 4.635787 1.195255 -v 0.063452 -0.004713 0.151065 -vn 3.113389 3.664952 3.840553 -v 0.063427 -0.004742 0.151149 -vn 2.383791 4.195001 3.825976 -v 0.064144 -0.005245 0.151149 -vn 5.686633 -2.069766 1.195179 -v 0.061972 0.000811 0.151065 -vn 4.502606 -1.693224 3.838326 -v 0.061936 0.000824 0.151149 -vn 4.730723 -0.863823 3.840451 -v 0.061709 -0.000022 0.151149 -vn -1.607086 -4.541152 3.832677 -v 0.068374 0.003826 0.151149 -vn -2.383791 -4.195001 3.825976 -v 0.069168 0.003456 0.151149 -vn -4.504428 -1.689368 3.837833 -v 0.071376 0.000824 0.151149 -vn -3.129211 3.662337 3.832677 -v 0.069885 -0.004742 0.151149 -vn -2.441080 4.161927 3.825974 -v 0.069168 -0.005245 0.151149 -vn 0.789184 4.745648 3.837772 -v 0.065784 -0.005841 0.151149 -vn 4.736299 0.878804 3.832641 -v 0.061709 -0.001767 0.151149 -vn 4.824850 0.033075 3.826004 -v 0.061633 -0.000894 0.151149 -vn 3.715228 -3.056239 3.837845 -v 0.062808 0.002334 0.151149 -vn 0.000002 -4.840983 3.811107 -v 0.066656 0.004129 0.151149 -vn 0.784929 -4.746014 3.838303 -v 0.065784 0.004053 0.151149 -vn 1.617265 -4.528797 3.840516 -v 0.064938 0.003826 0.151149 -vn 2.441081 -4.161926 3.825974 -v 0.064144 0.003456 0.151149 -vn 3.129149 -3.662291 3.832737 -v 0.063427 0.002954 0.151149 -vn 4.504417 1.689360 3.837790 -v 0.061936 -0.002612 0.151149 -vn 1.607074 4.541118 3.832707 -v 0.064938 -0.005615 0.151149 -vn -3.715227 3.056261 3.837831 -v 0.070504 -0.004123 0.151149 -vn -4.736349 -0.878799 3.832544 -v 0.071603 -0.000022 0.151149 -vn -0.789183 -4.745647 3.837772 -v 0.067528 0.004053 0.151149 -vn 4.192420 -2.420497 3.811108 -v 0.062306 0.001617 0.151149 -vn 5.240831 -3.025794 1.195237 -v 0.062339 0.001598 0.151065 -vn 5.112679 -2.951791 -1.753063 -v 0.062336 0.001600 0.150972 -vn 3.717665 3.052740 3.838376 -v 0.062808 -0.004123 0.151149 -vn 4.635757 3.889886 1.195187 -v 0.062837 -0.004099 0.151065 -vn 4.556643 3.763037 -1.735316 -v 0.062834 -0.004101 0.150972 -vn 0.000002 4.840983 3.811108 -v 0.066656 -0.005918 0.151149 -vn 0.000002 6.051592 1.195243 -v 0.066656 -0.005879 0.151065 -vn 0.000001 5.903574 -1.753110 -v 0.066656 -0.005883 0.150972 -vn -4.502619 1.693214 3.838370 -v 0.071376 -0.002612 0.151149 -vn -5.686598 2.069753 1.195158 -v 0.071340 -0.002599 0.151065 -vn -5.537212 2.064619 -1.735373 -v 0.071344 -0.002601 0.150972 -vn -4.192475 -2.420507 3.811062 -v 0.071006 0.001617 0.151149 -vn -5.240831 -3.025793 1.195237 -v 0.070973 0.001598 0.151065 -vn -5.112670 -2.951816 -1.753055 -v 0.070976 0.001600 0.150972 -vn 2.069764 -5.686626 1.195257 -v 0.064951 0.003790 0.151065 -vn 1.050844 -5.959650 1.195235 -v 0.065790 0.004015 0.151065 -vn 0.000003 -6.051592 1.195243 -v 0.066656 0.004091 0.151065 -vn -1.050844 -5.959651 1.195235 -v 0.067522 0.004015 0.151065 -vn 3.889885 -4.635782 1.195256 -v 0.063452 0.002924 0.151065 -vn 3.753815 -4.567372 -1.732749 -v 0.063449 0.002927 0.150972 -vn 2.899196 -5.149347 -1.737617 -v 0.064162 0.003426 0.150972 -vn 5.686635 2.069762 1.195181 -v 0.061972 -0.002599 0.151065 -vn 5.534861 2.069514 -1.736889 -v 0.061968 -0.002601 0.150972 -vn 5.804671 1.081771 -1.748029 -v 0.061743 -0.001761 0.150972 -vn 5.137118 2.965916 -1.689935 -v 0.062336 -0.003389 0.150972 -vn 5.240828 3.025798 1.195241 -v 0.062339 -0.003387 0.151065 -vn 4.192424 2.420490 3.811104 -v 0.062306 -0.003406 0.151149 -vn 2.069759 5.686626 1.195258 -v 0.064951 -0.005579 0.151065 -vn 2.078545 5.534600 -1.732744 -v 0.064950 -0.005582 0.150972 -vn 3.009877 5.085448 -1.737612 -v 0.064162 -0.005215 0.150972 -vn -4.635762 3.889875 1.195373 -v 0.070475 -0.004099 0.151065 -vn -4.559632 3.758550 -1.736883 -v 0.070478 -0.004101 0.150972 -vn -3.839176 4.486088 -1.748062 -v 0.069863 -0.004716 0.150972 -vn -5.137117 2.965916 -1.689942 -v 0.070976 -0.003389 0.150972 -vn -5.240829 3.025797 1.195247 -v 0.070973 -0.003387 0.151065 -vn -4.192467 2.420521 3.811059 -v 0.071006 -0.003406 0.151149 -vn -5.959711 -1.050844 1.195112 -v 0.071565 -0.000029 0.151065 -vn -5.832426 -0.967219 -1.732638 -v 0.071569 -0.000028 0.150972 -vn -5.909054 0.063911 -1.737667 -v 0.071645 -0.000894 0.150972 -vn 0.980584 -5.827653 -1.735285 -v 0.065790 0.004019 0.150972 -vn 0.000002 -5.931801 -1.689988 -v 0.066656 0.004094 0.150972 -vn -0.975186 -5.828065 -1.736888 -v 0.067522 0.004019 0.150972 -vn -1.965495 -5.567877 -1.748047 -v 0.068362 0.003794 0.150972 -vn 3.025805 -5.240837 1.195195 -v 0.064163 0.003423 0.151065 -vn 1.164840 -4.854178 -3.784357 -v 0.065703 0.004048 0.150892 -vn 2.409046 -4.449630 -3.676102 -v 0.064139 0.003465 0.150892 -vn 3.949094 -2.777896 -4.015667 -v 0.062556 0.002025 0.150892 -vn 3.819830 -3.305997 -3.688173 -v 0.062800 0.002341 0.150892 -vn 4.493443 -3.846650 -1.727573 -v 0.062834 0.002312 0.150972 -vn 4.635753 -3.889889 1.195190 -v 0.062837 0.002310 0.151065 -vn 3.336876 -3.303978 -4.171547 -v 0.063182 0.002749 0.150892 -vn 3.166353 -3.941016 -3.682679 -v 0.063420 0.002962 0.150892 -vn 2.736308 -3.939033 -4.054077 -v 0.063935 0.003340 0.150892 -vn 4.389687 -2.536318 -3.661950 -v 0.062297 0.001622 0.150892 -vn 5.553524 -2.002735 -1.752948 -v 0.061968 0.000812 0.150972 -vn 4.775920 -1.694638 -3.664328 -v 0.061926 0.000827 0.150892 -vn 4.378738 -2.029331 -4.018100 -v 0.062077 0.001197 0.150892 -vn 5.959667 -1.050846 1.195212 -v 0.061747 -0.000029 0.151065 -vn 5.819710 -0.991578 -1.752440 -v 0.061743 -0.000028 0.150972 -vn 5.002223 -0.802610 -3.666016 -v 0.061699 -0.000020 0.150892 -vn 4.689430 -1.218686 -3.993676 -v 0.061764 0.000292 0.150892 -vn 6.051593 -0.000002 1.195166 -v 0.061671 -0.000894 0.151065 -vn 5.903550 0.048420 -1.751265 -v 0.061667 -0.000894 0.150972 -vn 5.068595 0.119124 -3.661572 -v 0.061622 -0.000894 0.150892 -vn 4.868381 -0.358071 -3.945401 -v 0.061628 -0.000655 0.150892 -vn 5.959669 1.050850 1.195212 -v 0.061747 -0.001760 0.151065 -vn 4.909176 0.525084 -3.868033 -v 0.061674 -0.001611 0.150892 -vn 3.621565 3.437536 -3.782941 -v 0.062852 -0.004191 0.150892 -vn 4.005089 3.102561 -3.665701 -v 0.062800 -0.004130 0.150892 -vn 4.378953 2.529553 -3.684401 -v 0.062297 -0.003411 0.150892 -vn 4.688740 1.915675 -3.667125 -v 0.061926 -0.002616 0.150892 -vn 4.793804 1.433610 -3.767354 -v 0.061899 -0.002541 0.150892 -vn 4.959616 1.035560 -3.665450 -v 0.061699 -0.001768 0.150892 -vn 3.025810 5.240833 1.195196 -v 0.064163 -0.005211 0.151065 -vn 2.646809 4.310763 -3.677735 -v 0.064139 -0.005254 0.150892 -vn 0.433783 4.806054 -4.018715 -v 0.066178 -0.005905 0.150892 -vn 0.953530 4.961086 -3.688091 -v 0.065782 -0.005852 0.150892 -vn 1.084558 5.814738 -1.727538 -v 0.065790 -0.005807 0.150972 -vn 1.050845 5.959651 1.195235 -v 0.065790 -0.005804 0.151065 -vn 1.192638 4.542457 -4.170922 -v 0.065238 -0.005724 0.150892 -vn 1.831461 4.713409 -3.681204 -v 0.064934 -0.005624 0.150892 -vn 2.042544 4.340744 -4.052823 -v 0.064349 -0.005368 0.150892 -vn -0.001190 5.067237 -3.664865 -v 0.066656 -0.005928 0.150892 -vn -1.042344 5.810839 -1.752949 -v 0.067522 -0.005807 0.150972 -vn -0.918279 4.985933 -3.661891 -v 0.067530 -0.005852 0.150892 -vn -0.434551 4.808735 -4.015576 -v 0.067134 -0.005905 0.150892 -vn -2.069764 5.686627 1.195257 -v 0.068361 -0.005579 0.151065 -vn -2.051121 5.535804 -1.752459 -v 0.068362 -0.005582 0.150972 -vn -1.808542 4.733737 -3.664571 -v 0.068378 -0.005624 0.150892 -vn -1.288932 4.670308 -3.994015 -v 0.068074 -0.005724 0.150892 -vn -3.025804 5.240838 1.195195 -v 0.069148 -0.005211 0.151065 -vn -2.993714 5.088416 -1.751219 -v 0.069150 -0.005215 0.150972 -vn -2.634068 4.327185 -3.666354 -v 0.069173 -0.005254 0.150892 -vn -2.120972 4.396961 -3.945148 -v 0.068963 -0.005368 0.150892 -vn -3.889884 4.635780 1.195261 -v 0.069860 -0.004713 0.151065 -vn -2.912402 3.984720 -3.869801 -v 0.069768 -0.004851 0.150892 -vn -4.787897 1.417302 -3.782877 -v 0.071413 -0.002541 0.150892 -vn -4.688778 1.915570 -3.667136 -v 0.071386 -0.002616 0.150892 -vn -4.378951 2.529557 -3.684403 -v 0.071015 -0.003411 0.150892 -vn -4.005018 3.102471 -3.665880 -v 0.070512 -0.004130 0.150892 -vn -3.638496 3.438399 -3.764496 -v 0.070460 -0.004191 0.150892 -vn -3.379607 3.779478 -3.661342 -v 0.069892 -0.004750 0.150892 -vn -6.051552 -0.000010 1.195267 -v 0.071641 -0.000894 0.151065 -vn -5.057120 0.137747 -3.677137 -v 0.071690 -0.000894 0.150892 -vn -4.379207 -2.027623 -4.018433 -v 0.071235 0.001197 0.150892 -vn -4.776824 -1.652893 -3.684857 -v 0.071386 0.000827 0.150892 -vn -5.578002 -1.968111 -1.727652 -v 0.071344 0.000812 0.150972 -vn -5.686595 -2.069753 1.195166 -v 0.071340 0.000811 0.151065 -vn -4.532068 -1.241853 -4.167860 -v 0.071548 0.000292 0.150892 -vn -4.995903 -0.772234 -3.682895 -v 0.071613 -0.000020 0.150892 -vn -4.778740 -0.399477 -4.054950 -v 0.071684 -0.000655 0.150892 -vn -4.387853 -2.534560 -3.664794 -v 0.071015 0.001622 0.150892 -vn -4.511135 -3.808107 -1.752922 -v 0.070478 0.002312 0.150972 -vn -3.855682 -3.286350 -3.666062 -v 0.070512 0.002341 0.150892 -vn -3.946796 -2.777511 -4.018066 -v 0.070756 0.002025 0.150892 -vn -3.889888 -4.635782 1.195256 -v 0.069860 0.002924 0.151065 -vn -3.768591 -4.544212 -1.752458 -v 0.069863 0.002927 0.150972 -vn -3.198085 -3.933909 -3.661805 -v 0.069892 0.002962 0.150892 -vn -3.397430 -3.454389 -3.993724 -v 0.070130 0.002749 0.150892 -vn -3.025810 -5.240833 1.195196 -v 0.069148 0.003423 0.151065 -vn -2.909844 -5.136838 -1.751223 -v 0.069150 0.003426 0.150972 -vn -2.429291 -4.446720 -3.664999 -v 0.069173 0.003465 0.150892 -vn -2.748322 -4.035109 -3.944739 -v 0.069377 0.003340 0.150892 -vn -2.069760 -5.686626 1.195258 -v 0.068361 0.003790 0.151065 -vn -1.997699 -4.513315 -3.869738 -v 0.068527 0.003779 0.150892 -vn 0.684179 -5.019610 -3.665948 -v 0.065782 0.004063 0.150892 -vn -0.003577 -5.061944 -3.678600 -v 0.066656 0.004139 0.150892 -vn -0.682851 -5.024146 -3.660974 -v 0.067530 0.004063 0.150892 -vn -1.152632 -4.869116 -3.767213 -v 0.067609 0.004048 0.150892 -vn -1.584059 -4.811297 -3.666845 -v 0.068378 0.003836 0.150892 -vn 3.731505 -3.446478 -3.578732 -v 0.060536 0.005025 0.147084 -vn 3.552459 -3.867604 -3.189907 -v 0.060781 0.005268 0.147084 -vn 3.141901 -3.987983 -3.578002 -v 0.061379 0.005788 0.147084 -vn 2.927130 -4.346420 -3.220237 -v 0.062053 0.006268 0.147084 -vn 5.041846 -0.609009 -3.577180 -v 0.058185 -0.000042 0.147084 -vn 4.979623 -1.018936 -3.583111 -v 0.058374 0.001079 0.147084 -vn 4.911386 -1.376425 -3.547923 -v 0.058382 0.001113 0.147084 -vn 4.770182 -1.741402 -3.575833 -v 0.058711 0.002166 0.147084 -vn 4.791699 -2.214622 -3.105606 -v 0.058911 0.002643 0.147084 -vn 4.424034 -2.488037 -3.579317 -v 0.059190 0.003197 0.147084 -vn 4.298985 -2.853078 -3.419260 -v 0.059721 0.004044 0.147084 -vn 4.001426 -3.129332 -3.583727 -v 0.059802 0.004156 0.147084 -vn 4.611145 2.123311 -3.578467 -v 0.058933 -0.004478 0.147084 -vn 4.898479 1.828743 -3.252585 -v 0.058610 -0.003679 0.147084 -vn 4.887354 1.381870 -3.581185 -v 0.058524 -0.003417 0.147084 -vn 4.984197 0.981133 -3.581963 -v 0.058260 -0.002310 0.147084 -vn 5.195512 0.560776 -3.256011 -v 0.058229 -0.002106 0.147084 -vn 5.074067 0.223769 -3.570618 -v 0.058147 -0.001179 0.147084 -vn 5.268826 -0.197013 -3.126471 -v 0.058152 -0.000489 0.147084 -vn 4.218108 2.826675 -3.579900 -v 0.059480 -0.005476 0.147084 -vn 4.596361 2.556759 -3.165172 -v 0.059283 -0.005151 0.147084 -vn 2.148875 4.604708 -3.583733 -v 0.062816 -0.008493 0.147084 -vn 2.512471 4.466272 -3.499298 -v 0.062755 -0.008462 0.147084 -vn 2.807129 4.232978 -3.573892 -v 0.061837 -0.007914 0.147084 -vn 3.270445 4.146841 -3.100014 -v 0.061393 -0.007587 0.147084 -vn 3.454966 3.719801 -3.578120 -v 0.060945 -0.007209 0.147084 -vn 3.766359 3.498605 -3.463671 -v 0.060221 -0.006470 0.147084 -vn 3.977515 3.161124 -3.583647 -v 0.060154 -0.006391 0.147084 -vn 0.207421 5.076474 -3.580185 -v 0.066087 -0.009389 0.147084 -vn 0.674383 5.209309 -3.184749 -v 0.065847 -0.009370 0.147084 -vn 0.968918 4.989003 -3.566378 -v 0.064960 -0.009238 0.147084 -vn 1.417664 5.072059 -3.144175 -v 0.064257 -0.009064 0.147084 -vn 1.766283 4.760558 -3.578955 -v 0.063863 -0.008937 0.147084 -vn -2.810881 4.228692 -3.577190 -v 0.071475 -0.007914 0.147084 -vn -2.503660 4.466617 -3.508013 -v 0.070557 -0.008462 0.147084 -vn -2.148871 4.604709 -3.583733 -v 0.070496 -0.008493 0.147084 -vn -1.766703 4.760753 -3.578645 -v 0.069449 -0.008937 0.147084 -vn -1.416213 5.071771 -3.144886 -v 0.069055 -0.009064 0.147084 -vn -0.986713 4.978445 -3.579744 -v 0.068352 -0.009238 0.147084 -vn -0.631902 5.173454 -3.292224 -v 0.067465 -0.009370 0.147084 -vn -0.209487 5.073841 -3.582872 -v 0.067225 -0.009389 0.147084 -vn -4.218153 2.826677 -3.579819 -v 0.073832 -0.005476 0.147084 -vn -3.977549 3.161116 -3.583618 -v 0.073158 -0.006391 0.147084 -vn -3.760690 3.513883 -3.447225 -v 0.073091 -0.006470 0.147084 -vn -3.461986 3.712904 -3.575766 -v 0.072367 -0.007209 0.147084 -vn -3.270504 4.146245 -3.100446 -v 0.071919 -0.007587 0.147084 -vn -4.887389 1.381902 -3.581090 -v 0.074788 -0.003417 0.147084 -vn -4.898489 1.828768 -3.252552 -v 0.074702 -0.003679 0.147084 -vn -4.611218 2.123354 -3.578291 -v 0.074379 -0.004478 0.147084 -vn -4.596369 2.556763 -3.165162 -v 0.074029 -0.005151 0.147084 -vn -5.041845 -0.609004 -3.577185 -v 0.075127 -0.000042 0.147084 -vn -5.269390 -0.197589 -3.125849 -v 0.075160 -0.000489 0.147084 -vn -5.072681 0.206130 -3.578081 -v 0.075165 -0.001179 0.147084 -vn -5.164889 0.589539 -3.329544 -v 0.075083 -0.002106 0.147084 -vn -4.984164 0.981083 -3.581971 -v 0.075052 -0.002310 0.147084 -vn -3.731515 -3.446516 -3.578664 -v 0.072776 0.005025 0.147084 -vn -4.001982 -3.131887 -3.581590 -v 0.073510 0.004156 0.147084 -vn -4.323470 -2.845842 -3.383880 -v 0.073591 0.004044 0.147084 -vn -4.422559 -2.499808 -3.571136 -v 0.074122 0.003197 0.147084 -vn -4.792399 -2.213567 -3.105470 -v 0.074401 0.002643 0.147084 -vn -4.767370 -1.743100 -3.578893 -v 0.074601 0.002166 0.147084 -vn -4.909070 -1.371657 -3.553086 -v 0.074930 0.001113 0.147084 -vn -4.977821 -1.019888 -3.584825 -v 0.074938 0.001079 0.147084 -vn -1.385039 -4.884544 -3.577812 -v 0.068905 0.007317 0.147084 -vn -1.774982 -4.868295 -3.371281 -v 0.069820 0.007010 0.147084 -vn -2.114570 -4.619259 -3.582387 -v 0.069980 0.006944 0.147084 -vn -2.481862 -4.431271 -3.580268 -v 0.070995 0.006431 0.147084 -vn -2.927754 -4.344659 -3.221452 -v 0.071259 0.006268 0.147084 -vn -3.140149 -3.986791 -3.580081 -v 0.071933 0.005788 0.147084 -vn -3.551512 -3.867556 -3.190629 -v 0.072531 0.005268 0.147084 -vn 2.481909 -4.431011 -3.580484 -v 0.062317 0.006431 0.147084 -vn 2.114552 -4.619223 -3.582464 -v 0.063332 0.006944 0.147084 -vn 1.759198 -4.896091 -3.319776 -v 0.063492 0.007010 0.147084 -vn 1.399261 -4.884336 -3.569591 -v 0.064407 0.007317 0.147084 -vn 1.036785 -5.174089 -3.113269 -v 0.065045 0.007466 0.147084 -vn 0.579566 -5.043482 -3.578193 -v 0.065521 0.007544 0.147084 -vn -0.002357 -5.067002 -3.569642 -v 0.066656 0.007620 0.147084 -vn -0.577072 -5.040989 -3.581072 -v 0.067791 0.007544 0.147084 -vn -1.036515 -5.173881 -3.113574 -v 0.068267 0.007466 0.147084 -vn -4.392142 -2.747445 3.342150 -v 0.074028 0.003362 0.146812 -vn -4.487731 -2.299966 3.634825 -v 0.074121 0.003197 0.146812 -vn -5.153510 -2.769573 1.457960 -v 0.074163 0.003219 0.146898 -vn -4.688631 1.939183 3.579618 -v 0.074399 -0.004431 0.146812 -vn -4.506719 2.267131 3.636013 -v 0.074378 -0.004478 0.146812 -vn -5.290389 2.480792 1.469342 -v 0.074421 -0.004498 0.146898 -vn -4.953540 3.105968 1.465153 -v 0.073871 -0.005500 0.146898 -vn 0.779944 5.039948 3.526807 -v 0.065045 -0.009253 0.146812 -vn 1.155438 4.910815 3.635101 -v 0.064960 -0.009236 0.146812 -vn 1.198322 5.723525 1.462156 -v 0.064951 -0.009283 0.146898 -vn 1.871729 5.539889 1.463860 -v 0.063848 -0.008981 0.146898 -vn 5.108940 0.432233 3.468491 -v 0.058153 -0.001299 0.146812 -vn 5.044530 0.019609 3.634636 -v 0.058148 -0.001179 0.146812 -vn 5.847597 0.154214 1.459033 -v 0.058101 -0.001180 0.146898 -vn 1.630399 -4.889645 3.406669 -v 0.064258 0.007274 0.146812 -vn 1.192950 -4.900721 3.634588 -v 0.064407 0.007316 0.146812 -vn 1.501717 -5.654372 1.457938 -v 0.064394 0.007362 0.146898 -vn -2.943191 -5.072064 -1.399727 -v 0.071019 0.006471 0.146997 -vn -2.336789 -5.380289 -1.396359 -v 0.069998 0.006987 0.146997 -vn -2.260058 -5.391165 1.467257 -v 0.069998 0.006987 0.146898 -vn -5.826758 -0.633244 -1.405333 -v 0.075174 -0.000037 0.146997 -vn -5.699605 -1.339289 -1.414186 -v 0.074983 0.001090 0.146997 -vn -5.685411 -1.359847 1.467432 -v 0.074983 0.001090 0.146898 -vn -1.968639 5.521374 -1.403809 -v 0.069464 -0.008981 0.146997 -vn -2.614317 5.245902 -1.403399 -v 0.070517 -0.008535 0.146997 -vn -2.645113 5.213180 1.467296 -v 0.070517 -0.008534 0.146898 -vn 4.914437 3.196718 -1.402417 -v 0.059440 -0.005501 0.146997 -vn 4.505187 3.753959 -1.398485 -v 0.060119 -0.006421 0.146997 -vn 4.454845 3.785220 1.467396 -v 0.060119 -0.006421 0.146898 -vn 5.483138 -2.065732 -1.408201 -v 0.058667 0.002182 0.146997 -vn 5.698637 -1.341097 -1.414963 -v 0.058329 0.001090 0.146997 -vn 5.685507 -1.359874 1.467264 -v 0.058329 0.001090 0.146898 -vn 0.000001 -5.842601 -1.435150 -v 0.066656 0.007666 0.146997 -vn 0.736504 -5.813736 -1.406674 -v 0.065515 0.007590 0.146997 -vn 0.830803 -5.789779 1.461148 -v 0.065515 0.007589 0.146898 -vn -1.569241 -5.646519 -1.406635 -v 0.068918 0.007362 0.146997 -vn -3.630219 -4.600904 -1.406561 -v 0.071961 0.005824 0.146997 -vn -4.250383 -4.039102 -1.401078 -v 0.072810 0.005057 0.146997 -vn -4.695418 -3.514163 -1.397539 -v 0.073548 0.004184 0.146997 -vn -5.118344 -2.846595 -1.412535 -v 0.074163 0.003220 0.146997 -vn -5.856689 0.212742 -1.406596 -v 0.075212 -0.001180 0.146997 -vn -5.775056 1.027550 -1.396567 -v 0.075097 -0.002318 0.146997 -vn -5.617008 1.686773 -1.398430 -v 0.074832 -0.003431 0.146997 -vn -3.957867 4.318236 -1.411077 -v 0.072398 -0.007243 0.146997 -vn -1.155490 5.745526 -1.406641 -v 0.068361 -0.009283 0.146997 -vn -0.338586 5.855539 -1.397493 -v 0.067228 -0.009436 0.146997 -vn 0.342254 5.854830 -1.398009 -v 0.066084 -0.009436 0.146997 -vn 3.281768 4.852980 -1.409682 -v 0.061811 -0.007952 0.146997 -vn 5.319138 2.460325 -1.406648 -v 0.058891 -0.004498 0.146997 -vn 5.616975 1.686758 -1.398620 -v 0.058480 -0.003431 0.146997 -vn 5.775128 1.023710 -1.397262 -v 0.058215 -0.002318 0.146997 -vn 5.850446 0.227613 -1.415594 -v 0.058100 -0.001180 0.146997 -vn 5.126565 -2.839616 -1.406639 -v 0.059149 0.003220 0.146997 -vn 4.693689 -3.517550 -1.396725 -v 0.059764 0.004184 0.146997 -vn 4.250371 -4.039059 -1.401058 -v 0.060502 0.005057 0.146997 -vn 1.580117 -5.638568 -1.414129 -v 0.064394 0.007362 0.146997 -vn 2.333073 -5.381207 -1.397027 -v 0.063314 0.006987 0.146997 -vn 2.943187 -5.072069 -1.399723 -v 0.062293 0.006471 0.146997 -vn 3.630198 -4.600886 -1.406611 -v 0.061351 0.005824 0.146997 -vn 5.826750 -0.633246 -1.405216 -v 0.058138 -0.000037 0.146997 -vn 3.954163 4.325436 -1.406648 -v 0.060914 -0.007243 0.146997 -vn 2.616719 5.243914 -1.404394 -v 0.062795 -0.008535 0.146997 -vn 1.968644 5.521406 -1.403752 -v 0.063848 -0.008981 0.146997 -vn 1.136955 5.742476 -1.417143 -v 0.064951 -0.009283 0.146997 -vn -3.287038 4.851707 -1.406686 -v 0.071501 -0.007952 0.146997 -vn -4.502391 3.756230 -1.399396 -v 0.073193 -0.006421 0.146997 -vn -4.914477 3.196729 -1.402355 -v 0.073872 -0.005501 0.146997 -vn -5.319217 2.460372 -1.406600 -v 0.074421 -0.004498 0.146997 -vn -5.483082 -2.068447 -1.406787 -v 0.074645 0.002182 0.146997 -vn 3.015407 -5.007709 1.467354 -v 0.062294 0.006471 0.146898 -vn 2.247976 -5.391553 1.474008 -v 0.063314 0.006987 0.146898 -vn 5.155758 -2.766541 1.457248 -v 0.059149 0.003219 0.146898 -vn 4.717618 -3.452116 1.467249 -v 0.059765 0.004183 0.146898 -vn 5.439751 -2.151389 1.459887 -v 0.058668 0.002182 0.146898 -vn 4.658844 -1.927604 3.633208 -v 0.058712 0.002165 0.146812 -vn 4.951138 -1.586635 3.293007 -v 0.058611 0.001890 0.146812 -vn 5.289954 2.483448 1.468408 -v 0.058891 -0.004498 0.146898 -vn 5.571731 1.768071 1.467343 -v 0.058480 -0.003430 0.146898 -vn 4.953502 3.105948 1.465221 -v 0.059441 -0.005500 0.146898 -vn 4.303643 2.624704 3.630714 -v 0.059481 -0.005475 0.146812 -vn 4.219876 3.088857 3.198262 -v 0.059722 -0.005832 0.146812 -vn 2.658522 5.198320 1.478408 -v 0.062795 -0.008534 0.146898 -vn 3.351261 4.794796 1.459284 -v 0.061811 -0.007952 0.146898 -vn -1.201713 5.723520 1.461238 -v 0.068361 -0.009283 0.146898 -vn -0.423683 5.830268 1.467328 -v 0.067228 -0.009435 0.146898 -vn -1.871732 5.539886 1.463866 -v 0.069464 -0.008981 0.146898 -vn -1.551315 4.797125 3.630721 -v 0.069448 -0.008936 0.146812 -vn -2.013829 4.827403 3.209602 -v 0.069820 -0.008797 0.146812 -vn -4.439551 3.793536 1.477085 -v 0.073193 -0.006421 0.146898 -vn -3.887821 4.371632 1.458375 -v 0.072398 -0.007243 0.146898 -vn -5.848365 0.150610 1.458187 -v 0.075211 -0.001180 0.146898 -vn -5.768972 0.944054 1.467342 -v 0.075097 -0.002318 0.146898 -vn -5.823746 -0.535138 1.462398 -v 0.075173 -0.000038 0.146898 -vn -5.026894 -0.391984 3.631180 -v 0.075126 -0.000042 0.146812 -vn -5.155393 -0.832418 3.233233 -v 0.075082 0.000317 0.146812 -vn -3.622479 -4.573627 1.484162 -v 0.071961 0.005824 0.146898 -vn -4.170278 -4.096643 1.466637 -v 0.072809 0.005057 0.146898 -vn -0.830802 -5.789779 1.461147 -v 0.067797 0.007589 0.146898 -vn -1.498248 -5.655933 1.457204 -v 0.068918 0.007362 0.146898 -vn -0.736506 -5.813732 -1.406676 -v 0.067797 0.007590 0.146997 -vn 0.000002 -5.845840 1.467326 -v 0.066656 0.007666 0.146898 -vn 0.788252 -4.979096 3.633098 -v 0.065521 0.007542 0.146812 -vn 0.391563 -5.195931 3.262037 -v 0.065847 0.007580 0.146812 -vn 1.911635 -4.667301 3.622808 -v 0.063333 0.006943 0.146812 -vn 2.375976 -4.676588 3.164903 -v 0.062755 0.006672 0.146812 -vn 2.647044 -4.288311 3.630800 -v 0.062318 0.006430 0.146812 -vn 3.623588 -4.573228 1.483602 -v 0.061351 0.005824 0.146898 -vn 3.254190 -3.854343 3.637254 -v 0.061380 0.005786 0.146812 -vn 2.985388 -4.075590 3.622752 -v 0.061394 0.005797 0.146812 -vn 4.170304 -4.096672 1.466665 -v 0.060503 0.005057 0.146898 -vn 3.553161 -3.574244 3.630878 -v 0.060537 0.005024 0.146812 -vn 3.991530 -3.397589 3.175928 -v 0.060223 0.004680 0.146812 -vn 4.487694 -2.300031 3.634814 -v 0.059191 0.003197 0.146812 -vn 4.384920 -2.711045 3.404687 -v 0.059284 0.003362 0.146812 -vn 4.080857 -2.957185 3.630700 -v 0.059803 0.004155 0.146812 -vn 4.898126 -1.178762 3.632420 -v 0.058375 0.001079 0.146812 -vn 5.823810 -0.535133 1.462417 -v 0.058139 -0.000038 0.146898 -vn 5.024286 -0.393912 3.633657 -v 0.058186 -0.000042 0.146812 -vn 5.152870 -0.830389 3.235998 -v 0.058230 0.000317 0.146812 -vn 5.767075 0.934821 1.472520 -v 0.058215 -0.002318 0.146898 -vn 4.983830 0.770040 3.624298 -v 0.058262 -0.002310 0.146812 -vn 5.103152 1.222075 3.158632 -v 0.058383 -0.002901 0.146812 -vn 4.506469 2.266485 3.636503 -v 0.058934 -0.004478 0.146812 -vn 4.683657 1.943753 3.585154 -v 0.058913 -0.004431 0.146812 -vn 4.788171 1.570837 3.631095 -v 0.058525 -0.003416 0.146812 -vn 3.826222 3.265469 3.640348 -v 0.060155 -0.006390 0.146812 -vn 3.885382 4.374485 1.457832 -v 0.060914 -0.007243 0.146898 -vn 3.279885 3.828500 3.635454 -v 0.060946 -0.007208 0.146812 -vn 3.672154 3.641355 3.364672 -v 0.060782 -0.007055 0.146812 -vn 2.959621 4.080872 3.634843 -v 0.061838 -0.007913 0.146812 -vn 1.551302 4.797129 3.630722 -v 0.063864 -0.008936 0.146812 -vn 2.014203 4.826448 3.210312 -v 0.063492 -0.008797 0.146812 -vn 2.312500 4.480376 3.621905 -v 0.062817 -0.008492 0.146812 -vn 2.677773 4.490394 3.209189 -v 0.062054 -0.008056 0.146812 -vn 0.429786 5.827419 1.471025 -v 0.066084 -0.009435 0.146898 -vn 0.414101 5.024786 3.626315 -v 0.066087 -0.009388 0.146812 -vn -0.000574 5.247451 3.157228 -v 0.066656 -0.009407 0.146812 -vn -1.153806 4.909596 3.636741 -v 0.068352 -0.009236 0.146812 -vn -0.789442 5.030165 3.542039 -v 0.068267 -0.009253 0.146812 -vn -0.407161 5.022101 3.631765 -v 0.067225 -0.009388 0.146812 -vn -2.291734 4.488400 3.630744 -v 0.070495 -0.008492 0.146812 -vn -3.354514 4.793077 1.458845 -v 0.071501 -0.007952 0.146898 -vn -2.959708 4.080859 3.634826 -v 0.071474 -0.007913 0.146812 -vn -2.691925 4.433562 3.326555 -v 0.071258 -0.008056 0.146812 -vn -3.279868 3.828517 3.635459 -v 0.072366 -0.007208 0.146812 -vn -4.303680 2.624718 3.630635 -v 0.073831 -0.005475 0.146812 -vn -4.230406 3.087032 3.190549 -v 0.073590 -0.005832 0.146812 -vn -3.820305 3.293707 3.620608 -v 0.073157 -0.006390 0.146812 -vn -3.719707 3.641930 3.275978 -v 0.072530 -0.007055 0.146812 -vn -5.569263 1.771248 1.469590 -v 0.074832 -0.003430 0.146898 -vn -4.787740 1.575095 3.628829 -v 0.074786 -0.003416 0.146812 -vn -5.101787 1.220132 3.160475 -v 0.074929 -0.002901 0.146812 -vn -5.044530 0.019610 3.634637 -v 0.075164 -0.001179 0.146812 -vn -5.097885 0.416813 3.494585 -v 0.075159 -0.001299 0.146812 -vn -4.976715 0.779084 3.633064 -v 0.075050 -0.002310 0.146812 -vn -4.899707 -1.178721 3.630942 -v 0.074937 0.001079 0.146812 -vn -5.439746 -2.151391 1.459895 -v 0.074644 0.002182 0.146898 -vn -4.658676 -1.927222 3.633515 -v 0.074600 0.002165 0.146812 -vn -4.951378 -1.588015 3.292408 -v 0.074700 0.001890 0.146812 -vn -4.721482 -3.437897 1.475400 -v 0.073547 0.004183 0.146898 -vn -4.093002 -2.947436 3.621749 -v 0.073509 0.004155 0.146812 -vn -3.991499 -3.397569 3.176006 -v 0.073089 0.004680 0.146812 -vn -2.371888 -4.674728 3.168536 -v 0.070557 0.006672 0.146812 -vn -2.648410 -4.285735 3.631879 -v 0.070994 0.006430 0.146812 -vn -3.016243 -5.006643 1.468093 -v 0.071018 0.006471 0.146898 -vn -2.982417 -4.076705 3.623120 -v 0.071918 0.005797 0.146812 -vn -3.254248 -3.854352 3.637203 -v 0.071932 0.005786 0.146812 -vn -3.553137 -3.574218 3.630944 -v 0.072775 0.005024 0.146812 -vn -1.921647 -4.654418 3.634953 -v 0.069979 0.006943 0.146812 -vn -1.605438 -4.878047 3.449234 -v 0.069054 0.007274 0.146812 -vn 0.000002 -5.039002 3.631397 -v 0.066656 0.007618 0.146812 -vn -0.390641 -5.197095 3.260907 -v 0.067465 0.007580 0.146812 -vn -0.789418 -4.980075 3.631917 -v 0.067791 0.007542 0.146812 -vn -1.192952 -4.900720 3.634589 -v 0.068905 0.007316 0.146812 -vn 1.653760 4.475484 4.083560 -v 0.064726 -0.005714 0.143254 -vn 2.166641 4.487643 3.791728 -v 0.064518 -0.005625 0.143254 -vn 2.465029 4.193118 3.963858 -v 0.063849 -0.005262 0.143254 -vn 2.933339 4.023868 3.795859 -v 0.063749 -0.005196 0.143254 -vn 3.282851 3.739846 3.802422 -v 0.063073 -0.004652 0.143254 -vn 3.597648 3.459808 3.781434 -v 0.063064 -0.004642 0.143254 -vn 3.890427 3.115776 3.790327 -v 0.062482 -0.003981 0.143254 -vn 4.091245 2.646961 3.950288 -v 0.062427 -0.003906 0.143254 -vn 4.372670 2.370897 3.803446 -v 0.062020 -0.003232 0.143254 -vn 4.975050 -0.224888 3.795426 -v 0.061469 -0.000674 0.143254 -vn 4.692882 0.207550 4.171030 -v 0.061470 -0.001141 0.143254 -vn 4.933897 0.668717 3.796682 -v 0.061507 -0.001554 0.143254 -vn 4.609598 1.034378 4.139977 -v 0.061611 -0.002118 0.143254 -vn 4.719114 1.563017 3.808099 -v 0.061692 -0.002415 0.143254 -vn 4.370549 1.794152 4.138739 -v 0.061934 -0.003051 0.143254 -vn 3.274493 -3.750182 3.796527 -v 0.063395 0.003145 0.143254 -vn 3.603112 -3.435213 3.796482 -v 0.062759 0.002536 0.143254 -vn 3.871677 -3.074090 3.848845 -v 0.062732 0.002505 0.143254 -vn 4.151137 -2.746669 3.798134 -v 0.062235 0.001828 0.143254 -vn 4.274024 -2.262166 4.001196 -v 0.062160 0.001701 0.143254 -vn 4.576452 -1.961926 3.796315 -v 0.061839 0.001041 0.143254 -vn 4.529078 -1.443749 4.105086 -v 0.061750 0.000804 0.143254 -vn 4.856394 -1.110927 3.793466 -v 0.061581 0.000199 0.143254 -vn 4.667433 -0.621800 4.158222 -v 0.061517 -0.000156 0.143254 -vn 0.920635 -4.880562 3.814316 -v 0.065779 0.004223 0.143254 -vn 1.157488 -4.463233 4.264667 -v 0.065193 0.004087 0.143254 -vn 1.767983 -4.645073 3.808950 -v 0.064926 0.004001 0.143254 -vn 2.008883 -4.315289 4.096151 -v 0.064277 0.003720 0.143254 -vn 2.564734 -4.264262 3.800712 -v 0.064124 0.003638 0.143254 -vn 2.857766 -3.992473 3.898858 -v 0.063447 0.003186 0.143254 -vn -1.245204 -4.575342 4.119489 -v 0.068119 0.004087 0.143254 -vn -0.891773 -4.898474 3.796702 -v 0.067533 0.004223 0.143254 -vn -0.412678 -4.682636 4.167231 -v 0.067149 0.004274 0.143254 -vn 0.000002 -4.980527 3.794969 -v 0.066656 0.004297 0.143254 -vn 0.413686 -4.683457 4.166216 -v 0.066163 0.004274 0.143254 -vn -4.563871 -1.974756 3.805630 -v 0.071473 0.001041 0.143254 -vn -4.254183 -2.221416 4.047606 -v 0.071152 0.001701 0.143254 -vn -4.151131 -2.746675 3.798137 -v 0.071077 0.001828 0.143254 -vn -3.871916 -3.073902 3.848726 -v 0.070579 0.002505 0.143254 -vn -3.603348 -3.434956 3.796508 -v 0.070553 0.002536 0.143254 -vn -3.274489 -3.750157 3.796532 -v 0.069917 0.003145 0.143254 -vn -2.870897 -3.995778 3.884988 -v 0.069865 0.003186 0.143254 -vn -2.562120 -4.272647 3.793218 -v 0.069188 0.003638 0.143254 -vn -2.059061 -4.351696 4.029724 -v 0.069035 0.003720 0.143254 -vn -1.752939 -4.667237 3.789204 -v 0.068385 0.004001 0.143254 -vn -4.695550 0.210823 4.167865 -v 0.071842 -0.001141 0.143254 -vn -4.973735 -0.223222 3.796994 -v 0.071843 -0.000674 0.143254 -vn -4.664658 -0.621765 4.161302 -v 0.071795 -0.000156 0.143254 -vn -4.835790 -1.136301 3.812968 -v 0.071731 0.000199 0.143254 -vn -4.441556 -1.369215 4.225192 -v 0.071562 0.000804 0.143254 -vn -2.933373 4.023665 3.796018 -v 0.069563 -0.005196 0.143254 -vn -3.272931 3.739790 3.809902 -v 0.070239 -0.004652 0.143254 -vn -3.588722 3.449786 3.796525 -v 0.070248 -0.004642 0.143254 -vn -3.889333 3.106138 3.798063 -v 0.070830 -0.003981 0.143254 -vn -4.095297 2.668928 3.929489 -v 0.070885 -0.003906 0.143254 -vn -4.381416 2.363494 3.797445 -v 0.071292 -0.003232 0.143254 -vn -4.418003 1.853512 4.059026 -v 0.071378 -0.003051 0.143254 -vn -4.735526 1.544048 3.794523 -v 0.071620 -0.002415 0.143254 -vn -4.611886 1.033127 4.137794 -v 0.071701 -0.002118 0.143254 -vn -4.938785 0.668069 3.791289 -v 0.071805 -0.001554 0.143254 -vn -1.349086 4.781560 3.811831 -v 0.067964 -0.005918 0.143254 -vn -1.582306 4.409040 4.184695 -v 0.068585 -0.005714 0.143254 -vn -2.174245 4.472247 3.805264 -v 0.068794 -0.005625 0.143254 -vn -2.434794 4.178619 3.999694 -v 0.069463 -0.005262 0.143254 -vn 1.326812 4.798455 3.797210 -v 0.065348 -0.005918 0.143254 -vn 0.826356 4.642238 4.150591 -v 0.065673 -0.005992 0.143254 -vn 0.448726 4.959671 3.795643 -v 0.066216 -0.006067 0.143254 -vn -0.000803 4.696299 4.172366 -v 0.066656 -0.006086 0.143254 -vn -0.449597 4.961709 3.793266 -v 0.067096 -0.006067 0.143254 -vn -0.825571 4.644107 4.148687 -v 0.067638 -0.005992 0.143254 -vn -2.943062 -3.230801 -4.497906 -v 0.070005 0.003097 0.142964 -vn -3.332812 -2.990656 -4.379193 -v 0.070567 0.002548 0.142964 -vn -4.094785 -3.655467 -2.864721 -v 0.070529 0.002514 0.143027 -vn -3.352691 -2.495940 -4.689167 -v 0.070835 0.002217 0.142964 -vn -3.905561 -2.262963 -4.348202 -v 0.071092 0.001837 0.142964 -vn -4.703369 -2.840547 -2.856601 -v 0.071049 0.001811 0.143027 -vn -4.234390 -0.621700 -4.593218 -v 0.071787 0.000010 0.142964 -vn -4.530018 -0.169936 -4.329043 -v 0.071861 -0.000673 0.142964 -vn -5.483413 -0.250743 -2.864918 -v 0.071811 -0.000675 0.143027 -vn -2.257601 3.781016 -4.460033 -v 0.069519 -0.005247 0.142964 -vn -1.913922 4.211784 -4.238985 -v 0.068802 -0.005642 0.142964 -vn -2.302334 4.982846 -2.864618 -v 0.068781 -0.005596 0.143027 -vn -1.438819 3.940173 -4.675275 -v 0.068438 -0.005790 0.142964 -vn -1.033720 4.631649 -4.111874 -v 0.067969 -0.005936 0.142964 -vn -1.342282 5.329519 -2.854655 -v 0.067956 -0.005887 0.143027 -vn 0.621863 4.236061 -4.587731 -v 0.066051 -0.006069 0.142964 -vn 1.106613 4.410242 -4.317734 -v 0.065343 -0.005936 0.142964 -vn 1.359078 5.318174 -2.864944 -v 0.065356 -0.005887 0.143027 -vn 1.410210 3.922504 -4.699052 -v 0.064874 -0.005790 0.142964 -vn 1.920232 4.087425 -4.346660 -v 0.064510 -0.005642 0.142964 -vn 2.310507 4.982093 -2.860458 -v 0.064531 -0.005596 0.143027 -vn 3.127220 2.827629 -4.653971 -v 0.062867 -0.004469 0.142964 -vn 3.634716 2.690159 -4.342866 -v 0.062467 -0.003992 0.142964 -vn 4.441012 3.247074 -2.846621 -v 0.062508 -0.003962 0.143027 -vn 4.158294 -0.581009 -4.669921 -v 0.061525 0.000010 0.142964 -vn 4.328228 -1.049495 -4.399611 -v 0.061563 0.000203 0.142964 -vn 5.348200 -1.213635 -2.870041 -v 0.061612 0.000193 0.143027 -vn 3.906728 -1.859246 -4.543114 -v 0.061872 0.001169 0.142964 -vn 3.876466 -2.281645 -4.361849 -v 0.062220 0.001837 0.142964 -vn 4.690694 -2.850801 -2.864863 -v 0.062263 0.001811 0.143027 -vn 3.344061 -2.489290 -4.698874 -v 0.062477 0.002217 0.142964 -vn 3.308007 -2.990806 -4.396770 -v 0.062745 0.002548 0.142964 -vn 4.090177 -3.666810 -2.858486 -v 0.062783 0.002514 0.143027 -vn 1.796531 -3.846396 -4.626589 -v 0.064318 0.003761 0.142964 -vn 1.520429 -4.201376 -4.388218 -v 0.064920 0.004018 0.142964 -vn 1.838704 -5.171966 -2.865060 -v 0.064937 0.003970 0.143027 -vn -3.753895 4.001114 -2.867264 -v 0.070226 -0.004619 0.143027 -vn -4.280937 4.466658 -0.391773 -v 0.070211 -0.004604 0.143105 -vn -4.974251 3.678943 -0.391827 -v 0.070787 -0.003950 0.143105 -vn 6.048015 -1.303446 -0.391830 -v 0.061633 0.000188 0.143105 -vn 6.181290 -0.262583 -0.391804 -v 0.061522 -0.000676 0.143105 -vn -4.034826 4.191908 2.128196 -v 0.070219 -0.004612 0.143185 -vn -4.629162 3.496014 2.160702 -v 0.070796 -0.003956 0.143185 -vn 5.661743 -1.249625 2.169768 -v 0.061622 0.000191 0.143185 -vn 5.792553 -0.251925 2.170115 -v 0.061511 -0.000676 0.143185 -vn -4.337650 -3.862249 2.147155 -v 0.070522 0.002508 0.143185 -vn -4.908036 -3.089030 2.164544 -v 0.071041 0.001806 0.143185 -vn -5.792581 -0.251926 2.169979 -v 0.071801 -0.000676 0.143185 -vn -3.295174 4.773198 2.162359 -v 0.069540 -0.005161 0.143185 -vn -0.503330 5.776140 2.170060 -v 0.067093 -0.006025 0.143185 -vn 0.503330 5.776140 2.170060 -v 0.066219 -0.006025 0.143185 -vn 1.494093 5.602214 2.169579 -v 0.065358 -0.005878 0.143185 -vn 2.437086 5.261130 2.168308 -v 0.064535 -0.005587 0.143185 -vn 3.299199 4.770155 2.163216 -v 0.063772 -0.005161 0.143185 -vn 5.361390 -2.207569 2.168772 -v 0.061878 0.001026 0.143185 -vn 4.905193 -3.093231 2.165427 -v 0.062271 0.001806 0.143185 -vn 3.679977 -4.487504 2.155363 -v 0.063421 0.003112 0.143185 -vn 1.038731 -5.714790 2.149131 -v 0.065786 0.004181 0.143185 -vn 0.000002 -5.798030 2.170116 -v 0.066656 0.004255 0.143185 -vn 1.992108 -5.451827 2.155772 -v 0.064940 0.003961 0.143185 -vn 2.884798 -5.032985 2.161067 -v 0.064145 0.003601 0.143185 -vn 5.748804 0.753756 2.170034 -v 0.061548 -0.001548 0.143185 -vn 5.531673 1.761785 2.154449 -v 0.061732 -0.002402 0.143185 -vn 5.151234 2.669353 2.159968 -v 0.062058 -0.003213 0.143185 -vn 4.632415 3.492302 2.159666 -v 0.062516 -0.003956 0.143185 -vn -2.448461 5.260730 2.158732 -v 0.068777 -0.005587 0.143185 -vn -5.151361 2.661590 2.167522 -v 0.071254 -0.003213 0.143185 -vn -5.532137 1.735552 2.169447 -v 0.071580 -0.002402 0.143185 -vn -5.748834 0.753770 2.170070 -v 0.071764 -0.001548 0.143185 -vn -5.361026 -2.222552 2.157284 -v 0.071434 0.001026 0.143185 -vn -2.880450 -5.032510 2.166809 -v 0.069167 0.003601 0.143185 -vn -1.973574 -5.451842 2.169117 -v 0.068371 0.003961 0.143185 -vn -1.002684 -5.710656 2.169913 -v 0.067526 0.004181 0.143185 -vn 1.045584 -6.097887 -0.391770 -v 0.065788 0.004170 0.143105 -vn 0.000003 -6.186882 -0.391751 -v 0.066656 0.004244 0.143105 -vn 6.136782 0.785846 -0.391689 -v 0.061559 -0.001547 0.143105 -vn 5.915687 1.811655 -0.391807 -v 0.061743 -0.002399 0.143105 -vn 5.524445 2.785359 -0.391799 -v 0.062068 -0.003208 0.143105 -vn 4.974234 3.678931 -0.391595 -v 0.062525 -0.003950 0.143105 -vn -5.524483 2.785368 -0.391805 -v 0.071244 -0.003208 0.143105 -vn -5.915686 1.811660 -0.391796 -v 0.071569 -0.002399 0.143105 -vn -6.136740 0.785852 -0.391685 -v 0.071752 -0.001547 0.143105 -vn -1.045585 -6.097887 -0.391770 -v 0.067524 0.004170 0.143105 -vn -2.061104 -5.833473 -0.391710 -v 0.068368 0.003950 0.143105 -vn -3.017312 -5.401234 -0.391787 -v 0.069162 0.003591 0.143105 -vn 0.869908 -5.419662 -2.864199 -v 0.065784 0.004191 0.143027 -vn 0.000003 -5.512321 -2.830161 -v 0.066656 0.004265 0.143027 -vn 4.337574 -3.862287 2.147210 -v 0.062790 0.002508 0.143185 -vn 3.886692 -4.813607 -0.391879 -v 0.063428 0.003103 0.143105 -vn 4.644338 -4.087526 -0.391779 -v 0.062799 0.002500 0.143105 -vn 3.405589 -4.297990 -2.869965 -v 0.063415 0.003120 0.143027 -vn 5.490468 -0.273900 -2.852737 -v 0.061501 -0.000675 0.143027 -vn 5.438519 0.752906 -2.862330 -v 0.061538 -0.001550 0.143027 -vn 5.270718 1.614137 -2.830148 -v 0.061723 -0.002405 0.143027 -vn 4.925406 2.419769 -2.865553 -v 0.062049 -0.003217 0.143027 -vn 3.464517 5.125915 -0.391653 -v 0.063779 -0.005151 0.143105 -vn 2.548379 5.637660 -0.391751 -v 0.064540 -0.005576 0.143105 -vn 3.105599 4.522983 -2.865586 -v 0.063767 -0.005169 0.143027 -vn -1.523695 5.602939 2.152770 -v 0.067954 -0.005878 0.143185 -vn -0.524682 6.164595 -0.391751 -v 0.067092 -0.006014 0.143105 -vn -1.558930 5.987238 -0.391786 -v 0.067951 -0.005867 0.143105 -vn -0.406510 5.468256 -2.870935 -v 0.067094 -0.006035 0.143027 -vn -4.401960 3.297616 -2.848567 -v 0.070804 -0.003962 0.143027 -vn -4.927197 2.416192 -2.865828 -v 0.071263 -0.003217 0.143027 -vn -5.270716 1.614141 -2.830149 -v 0.071589 -0.002405 0.143027 -vn -5.438487 0.752910 -2.862446 -v 0.071774 -0.001550 0.143027 -vn -5.740709 -2.306799 -0.391942 -v 0.071424 0.001021 0.143105 -vn -5.268291 -3.243818 -0.391797 -v 0.071031 0.001800 0.143105 -vn -5.108211 -1.992318 -2.871262 -v 0.071443 0.001029 0.143027 -vn -0.869909 -5.419662 -2.864201 -v 0.067528 0.004191 0.143027 -vn -1.866878 -5.172116 -2.850630 -v 0.068375 0.003970 0.143027 -vn -2.726813 -4.759427 -2.868755 -v 0.069172 0.003610 0.143027 -vn 2.061104 -5.833471 -0.391708 -v 0.064944 0.003950 0.143105 -vn 1.025365 -4.065846 -4.676517 -v 0.065455 0.004175 0.142964 -vn 2.311968 -3.837583 -4.376815 -v 0.064115 0.003654 0.142964 -vn 2.730550 -4.757206 -2.869252 -v 0.064140 0.003610 0.143027 -vn 3.017300 -5.401227 -0.391648 -v 0.064150 0.003591 0.143105 -vn 2.679610 -3.552312 -4.401730 -v 0.063383 0.003159 0.142964 -vn 2.933021 -3.204597 -4.524071 -v 0.063307 0.003097 0.142964 -vn 5.268318 -3.243829 -0.391673 -v 0.062281 0.001800 0.143105 -vn 4.243964 -1.530537 -4.348355 -v 0.061822 0.001048 0.142964 -vn 5.109633 -1.987887 -2.871909 -v 0.061869 0.001029 0.143027 -vn 5.740759 -2.306820 -0.391693 -v 0.061888 0.001021 0.143105 -vn 4.482567 -0.210425 -4.373215 -v 0.061451 -0.000673 0.142964 -vn 4.173872 0.189504 -4.690175 -v 0.061455 -0.001197 0.142964 -vn 4.468126 0.687953 -4.342078 -v 0.061488 -0.001556 0.142964 -vn 4.229592 1.313938 -4.427020 -v 0.061675 -0.002420 0.142964 -vn 4.036508 1.935387 -4.380977 -v 0.062004 -0.003240 0.142964 -vn 3.461575 2.123085 -4.792709 -v 0.062144 -0.003499 0.142964 -vn 3.041094 3.342956 -4.342716 -v 0.063051 -0.004656 0.142964 -vn 3.750864 4.003939 -2.867683 -v 0.063086 -0.004619 0.143027 -vn 4.280949 4.466647 -0.391768 -v 0.063101 -0.004604 0.143105 -vn 4.034885 4.191968 2.128045 -v 0.063093 -0.004612 0.143185 -vn 2.608853 3.606699 -4.400216 -v 0.063739 -0.005211 0.142964 -vn 2.259476 3.750098 -4.484022 -v 0.063793 -0.005247 0.142964 -vn 1.558969 5.987250 -0.391788 -v 0.065361 -0.005867 0.143105 -vn 0.241589 4.471717 -4.377953 -v 0.066214 -0.006085 0.142964 -vn 0.401882 5.468403 -2.871610 -v 0.066218 -0.006035 0.143027 -vn 0.524678 6.164595 -0.391752 -v 0.066220 -0.006014 0.143105 -vn -0.181710 4.555177 -4.304243 -v 0.067098 -0.006085 0.142964 -vn -0.662991 4.188164 -4.628577 -v 0.067261 -0.006069 0.142964 -vn -2.548378 5.637659 -0.391753 -v 0.068772 -0.005576 0.143105 -vn -2.621590 3.600054 -4.397935 -v 0.069573 -0.005211 0.142964 -vn -3.108631 4.520127 -2.866845 -v 0.069545 -0.005169 0.143027 -vn -3.464489 5.125877 -0.391647 -v 0.069533 -0.005151 0.143105 -vn -3.058861 3.498924 -4.217433 -v 0.070261 -0.004656 0.142964 -vn -4.190609 0.180735 -4.675595 -v 0.071857 -0.001197 0.142964 -vn -4.548332 0.770995 -4.252140 -v 0.071823 -0.001556 0.142964 -vn -4.245049 1.332552 -4.407176 -v 0.071637 -0.002420 0.142964 -vn -4.077324 1.985844 -4.326884 -v 0.071308 -0.003240 0.142964 -vn -3.625247 2.162214 -4.650581 -v 0.071168 -0.003499 0.142964 -vn -3.639981 2.832567 -4.254572 -v 0.070845 -0.003992 0.142964 -vn -3.098479 2.711128 -4.743979 -v 0.070445 -0.004469 0.142964 -vn -6.181334 -0.262580 -0.391808 -v 0.071789 -0.000676 0.143105 -vn -4.356375 -1.052543 -4.374391 -v 0.071749 0.000203 0.142964 -vn -5.347034 -1.217969 -2.870688 -v 0.071700 0.000193 0.143027 -vn -6.047997 -1.303463 -0.391695 -v 0.071679 0.000188 0.143105 -vn -5.664066 -1.282533 2.150959 -v 0.071690 0.000191 0.143185 -vn -4.304749 -1.502743 -4.303366 -v 0.071490 0.001048 0.142964 -vn -3.870700 -1.880270 -4.567962 -v 0.071440 0.001169 0.142964 -vn -4.644341 -4.087524 -0.391778 -v 0.070513 0.002500 0.143105 -vn -2.681565 -3.562880 -4.393165 -v 0.069929 0.003159 0.142964 -vn -3.401761 -4.300467 -2.870927 -v 0.069897 0.003120 0.143027 -vn -3.886699 -4.813603 -0.391876 -v 0.069884 0.003103 0.143105 -vn -3.683127 -4.484303 2.156677 -v 0.069891 0.003112 0.143185 -vn -2.332605 -3.841525 -4.363913 -v 0.069197 0.003654 0.142964 -vn 0.642897 -4.414171 -4.394423 -v 0.065776 0.004240 0.142964 -vn -0.002085 -4.459645 -4.398494 -v 0.066656 0.004315 0.142964 -vn -0.642982 -4.416204 -4.392567 -v 0.067536 0.004240 0.142964 -vn -1.028054 -4.068315 -4.673805 -v 0.067857 0.004175 0.142964 -vn -1.542015 -4.185913 -4.396706 -v 0.068392 0.004018 0.142964 -vn -1.727510 -3.789361 -4.702268 -v 0.068994 0.003761 0.142964 -vn 4.167474 -1.849074 -4.202685 -v 0.061732 0.001266 0.142824 -vn 4.335813 -1.216073 -4.265062 -v 0.061444 0.000426 0.142824 -vn 4.565450 -0.769950 -4.122443 -v 0.061361 0.000039 0.142824 -vn 4.513114 -0.334369 -4.244389 -v 0.061297 -0.000450 0.142824 -vn 4.598318 0.112124 -4.169985 -v 0.061288 -0.001207 0.142824 -vn 4.530320 0.507686 -4.229508 -v 0.061297 -0.001338 0.142824 -vn 4.376702 0.971202 -4.286061 -v 0.061444 -0.002214 0.142824 -vn -0.393100 4.638702 -4.078674 -v 0.067280 -0.006235 0.142824 -vn -0.094253 4.320785 -4.385828 -v 0.066656 -0.006271 0.142824 -vn 0.459641 4.599284 -4.139977 -v 0.066032 -0.006235 0.142824 -vn 0.853516 4.429310 -4.263689 -v 0.065771 -0.006198 0.142824 -vn 1.342782 4.349573 -4.235977 -v 0.064910 -0.005980 0.142824 -vn 1.713158 4.261519 -4.184532 -v 0.064817 -0.005947 0.142824 -vn 2.088648 3.972839 -4.274307 -v 0.064097 -0.005623 0.142824 -vn 2.532194 3.877012 -4.120922 -v 0.063701 -0.005387 0.142824 -vn 2.806850 3.482084 -4.289796 -v 0.063353 -0.005138 0.142824 -vn 3.231670 3.247532 -4.204929 -v 0.062745 -0.004584 0.142824 -vn 3.450420 2.961346 -4.241159 -v 0.062700 -0.004536 0.142824 -vn 3.739912 2.557478 -4.246793 -v 0.062155 -0.003835 0.142824 -vn 4.106260 2.238285 -4.048639 -v 0.061999 -0.003583 0.142824 -vn 4.116745 1.798189 -4.264601 -v 0.061732 -0.003054 0.142824 -vn 4.380621 1.417974 -4.158909 -v 0.061505 -0.002436 0.142824 -vn -0.901578 4.312756 -4.341037 -v 0.067541 -0.006198 0.142824 -vn -1.332534 4.250926 -4.310843 -v 0.068402 -0.005980 0.142824 -vn -1.682146 4.228852 -4.223093 -v 0.068495 -0.005947 0.142824 -vn -2.133900 3.864581 -4.316525 -v 0.069215 -0.005623 0.142824 -vn -2.490928 4.008124 -3.953455 -v 0.069611 -0.005387 0.142824 -vn -2.786686 3.337527 -4.375428 -v 0.069959 -0.005138 0.142824 -vn -3.212366 3.265763 -4.201927 -v 0.070567 -0.004584 0.142824 -vn -3.451701 2.921731 -4.260507 -v 0.070612 -0.004536 0.142824 -vn -3.701484 2.504596 -4.293389 -v 0.071157 -0.003835 0.142824 -vn -4.010778 2.250697 -4.154052 -v 0.071313 -0.003583 0.142824 -vn -4.095721 1.696782 -4.310063 -v 0.071580 -0.003054 0.142824 -vn -4.382490 1.480812 -4.115290 -v 0.071807 -0.002436 0.142824 -vn -4.311257 0.901144 -4.343321 -v 0.071868 -0.002214 0.142824 -vn -4.491584 0.501652 -4.260089 -v 0.072015 -0.001338 0.142824 -vn -4.566091 0.129665 -4.204289 -v 0.072024 -0.001207 0.142824 -vn -4.485585 -0.402845 -4.252215 -v 0.072015 -0.000450 0.142824 -vn -4.651081 -0.704492 -3.981939 -v 0.071951 0.000039 0.142824 -vn -4.282417 -1.235597 -4.299027 -v 0.071868 0.000426 0.142824 -vn -4.153549 -1.841932 -4.213841 -v 0.071580 0.001266 0.142824 -vn -3.840274 -2.404615 -4.244723 -v 0.071157 0.002047 0.142824 -vn -3.667699 -2.795056 -4.141341 -v 0.070969 0.002317 0.142824 -vn -3.272168 -3.116999 -4.246799 -v 0.070612 0.002747 0.142824 -vn -3.090027 -3.426499 -4.137074 -v 0.070112 0.003225 0.142824 -vn -2.635222 -3.658287 -4.266908 -v 0.069959 0.003349 0.142824 -vn -2.290328 -3.928265 -4.237273 -v 0.069215 0.003835 0.142824 -vn -1.936277 -4.154864 -4.185973 -v 0.069069 0.003911 0.142824 -vn -1.471005 -4.308565 -4.215018 -v 0.068402 0.004191 0.142824 -vn -1.192258 -4.541610 -4.004552 -v 0.067896 0.004338 0.142824 -vn -0.630597 -4.492056 -4.239726 -v 0.067541 0.004409 0.142824 -vn -0.001730 -4.534897 -4.221131 -v 0.066656 0.004483 0.142824 -vn 0.631538 -4.494057 -4.238123 -v 0.065771 0.004409 0.142824 -vn 1.109875 -4.486742 -4.130488 -v 0.065416 0.004338 0.142824 -vn 1.522658 -4.287239 -4.223967 -v 0.064910 0.004191 0.142824 -vn 1.923338 -4.185934 -4.154171 -v 0.064243 0.003911 0.142824 -vn 2.289633 -3.938938 -4.230375 -v 0.064097 0.003835 0.142824 -vn 2.654844 -3.661956 -4.255903 -v 0.063353 0.003349 0.142824 -vn 3.050560 -3.438699 -4.170162 -v 0.063200 0.003225 0.142824 -vn 3.327403 -3.084411 -4.228592 -v 0.062700 0.002747 0.142824 -vn 3.690856 -2.888053 -4.026685 -v 0.062343 0.002317 0.142824 -vn 3.857718 -2.410180 -4.231061 -v 0.062155 0.002047 0.142824 -vn 0.885004 -5.525799 -2.212584 -v 0.065747 0.004550 0.142629 -vn 1.842765 -5.278111 -2.219861 -v 0.064864 0.004327 0.142629 -vn 2.681852 -4.908913 -2.214590 -v 0.064029 0.003960 0.142629 -vn 3.411596 -4.437720 -2.210469 -v 0.063266 0.003462 0.142629 -vn 4.119503 -3.769012 -2.228403 -v 0.062595 0.002844 0.142629 -vn 4.699209 -3.036254 -2.213696 -v 0.062035 0.002125 0.142629 -vn 5.104846 -2.239191 -2.239196 -v 0.061601 0.001323 0.142629 -vn 5.415199 -1.408099 -2.213859 -v 0.061305 0.000461 0.142629 -vn 5.575209 -0.430778 -2.218268 -v 0.061155 -0.000438 0.142629 -vn 5.571246 0.480757 -2.216791 -v 0.061155 -0.001350 0.142629 -vn 5.435264 1.339817 -2.210030 -v 0.061305 -0.002249 0.142629 -vn 5.106622 2.261518 -2.226677 -v 0.061601 -0.003112 0.142629 -vn 4.668633 3.083886 -2.213032 -v 0.062035 -0.003913 0.142629 -vn 4.121377 3.773153 -2.222406 -v 0.062595 -0.004633 0.142629 -vn 3.460354 4.399499 -2.211650 -v 0.063266 -0.005250 0.142629 -vn 2.633064 4.934512 -2.216679 -v 0.064029 -0.005749 0.142629 -vn 1.800562 5.291368 -2.220072 -v 0.064864 -0.006115 0.142629 -vn 0.957527 5.515457 -2.210128 -v 0.065747 -0.006339 0.142629 -vn -0.022257 5.586391 -2.224926 -v 0.066656 -0.006414 0.142629 -vn -0.948199 5.514504 -2.212689 -v 0.067565 -0.006339 0.142629 -vn -1.795290 5.295811 -2.217283 -v 0.068448 -0.006115 0.142629 -vn -2.663056 4.902382 -2.233797 -v 0.069283 -0.005749 0.142629 -vn -3.455978 4.396760 -2.216855 -v 0.070046 -0.005250 0.142629 -vn -4.116566 3.775328 -2.224747 -v 0.070717 -0.004633 0.142629 -vn -4.665700 3.092634 -2.210664 -v 0.071277 -0.003913 0.142629 -vn -5.127072 2.221990 -2.223194 -v 0.071711 -0.003112 0.142629 -vn -5.430556 1.347920 -2.212741 -v 0.072007 -0.002249 0.142629 -vn -5.573308 0.488513 -2.213804 -v 0.072157 -0.001350 0.142629 -vn -5.560503 -0.472439 -2.231994 -v 0.072157 -0.000438 0.142629 -vn -5.415374 -1.399796 -2.215659 -v 0.072007 0.000461 0.142629 -vn -5.104872 -2.239193 -2.239166 -v 0.071711 0.001323 0.142629 -vn -4.705829 -3.030128 -2.211500 -v 0.071277 0.002125 0.142629 -vn -4.093803 -3.805274 -2.221483 -v 0.070717 0.002844 0.142629 -vn -3.416872 -4.430190 -2.213318 -v 0.070046 0.003462 0.142629 -vn -2.690484 -4.907339 -2.211624 -v 0.069283 0.003960 0.142629 -vn -1.798849 -5.284248 -2.230212 -v 0.068448 0.004327 0.142629 -vn -0.893001 -5.522398 -2.214584 -v 0.067565 0.004550 0.142629 -vn 0.000002 -5.574368 -2.239185 -v 0.066656 0.004626 0.142629 -vn -0.982431 -5.887404 0.607364 -v 0.067570 0.004584 0.142389 -vn -1.938066 -5.645402 0.607357 -v 0.068459 0.004359 0.142389 -vn -2.840845 -5.249410 0.607353 -v 0.069300 0.003991 0.142389 -vn -3.666127 -4.710244 0.607352 -v 0.070068 0.003489 0.142389 -vn -4.391403 -4.042583 0.607357 -v 0.070742 0.002867 0.142389 -vn -4.996899 -3.264634 0.607351 -v 0.071306 0.002144 0.142389 -vn -5.466091 -2.397644 0.607323 -v 0.071742 0.001337 0.142389 -vn -5.786164 -1.465266 0.607333 -v 0.072040 0.000469 0.142389 -vn -5.948412 -0.492912 0.607350 -v 0.072191 -0.000436 0.142389 -vn -5.948412 0.492914 0.607350 -v 0.072191 -0.001353 0.142389 -vn -5.786163 1.465265 0.607338 -v 0.072040 -0.002258 0.142389 -vn -5.466093 2.397639 0.607329 -v 0.071742 -0.003125 0.142389 -vn -4.996900 3.264637 0.607355 -v 0.071306 -0.003932 0.142389 -vn -4.391400 4.042584 0.607358 -v 0.070742 -0.004656 0.142389 -vn -3.666127 4.710244 0.607350 -v 0.070068 -0.005277 0.142389 -vn -2.840844 5.249410 0.607351 -v 0.069300 -0.005779 0.142389 -vn -1.938066 5.645402 0.607357 -v 0.068459 -0.006148 0.142389 -vn -0.982429 5.887404 0.607364 -v 0.067570 -0.006373 0.142389 -vn 0.000001 5.968807 0.607356 -v 0.066656 -0.006449 0.142389 -vn 0.982433 5.887404 0.607364 -v 0.065742 -0.006373 0.142389 -vn 1.938066 5.645402 0.607357 -v 0.064853 -0.006148 0.142389 -vn 2.840838 5.249415 0.607350 -v 0.064012 -0.005779 0.142389 -vn 3.666111 4.710210 0.607346 -v 0.063244 -0.005277 0.142389 -vn 4.391410 4.042578 0.607362 -v 0.062570 -0.004656 0.142389 -vn 4.996897 3.264644 0.607352 -v 0.062006 -0.003932 0.142389 -vn 5.466074 2.397642 0.607357 -v 0.061570 -0.003125 0.142389 -vn 5.786161 1.465258 0.607336 -v 0.061272 -0.002258 0.142389 -vn 5.948417 0.492901 0.607350 -v 0.061121 -0.001353 0.142389 -vn 5.948417 -0.492903 0.607350 -v 0.061121 -0.000436 0.142389 -vn 5.786164 -1.465253 0.607337 -v 0.061272 0.000469 0.142389 -vn 5.466072 -2.397645 0.607363 -v 0.061570 0.001337 0.142389 -vn 4.996895 -3.264642 0.607358 -v 0.062006 0.002144 0.142389 -vn 4.391409 -4.042580 0.607354 -v 0.062570 0.002867 0.142389 -vn 3.666114 -4.710208 0.607341 -v 0.063244 0.003489 0.142389 -vn 2.840839 -5.249414 0.607355 -v 0.064012 0.003991 0.142389 -vn 1.938066 -5.645402 0.607357 -v 0.064853 0.004359 0.142389 -vn 0.982431 -5.887404 0.607364 -v 0.065742 0.004584 0.142389 -vn 0.000003 -5.968808 0.607355 -v 0.066656 0.004660 0.142389 -vn -0.825766 -4.948575 3.323266 -v 0.067557 0.004503 0.142161 -vn -1.629014 -4.745154 3.323274 -v 0.068433 0.004281 0.142161 -vn -2.387827 -4.412308 3.323266 -v 0.069260 0.003918 0.142161 -vn -3.081503 -3.959110 3.323252 -v 0.070017 0.003424 0.142161 -vn -3.691124 -3.397926 3.323237 -v 0.070682 0.002812 0.142161 -vn -4.200065 -2.744034 3.323246 -v 0.071237 0.002098 0.142161 -vn -4.594424 -2.015290 3.323252 -v 0.071667 0.001304 0.142161 -vn -4.863479 -1.231606 3.323270 -v 0.071960 0.000449 0.142161 -vn -4.999826 -0.414302 3.323298 -v 0.072109 -0.000442 0.142161 -vn -4.999823 0.414308 3.323300 -v 0.072109 -0.001346 0.142161 -vn -4.863480 1.231600 3.323267 -v 0.071960 -0.002238 0.142161 -vn -4.594425 2.015291 3.323249 -v 0.071667 -0.003092 0.142161 -vn -4.200064 2.744034 3.323246 -v 0.071237 -0.003887 0.142161 -vn -3.691128 3.397925 3.323237 -v 0.070682 -0.004600 0.142161 -vn -3.081503 3.959110 3.323252 -v 0.070017 -0.005212 0.142161 -vn -2.387827 4.412309 3.323266 -v 0.069260 -0.005707 0.142161 -vn -1.629011 4.745154 3.323275 -v 0.068433 -0.006070 0.142161 -vn -0.825767 4.948573 3.323267 -v 0.067557 -0.006292 0.142161 -vn 0.000002 5.016999 3.323267 -v 0.066656 -0.006366 0.142161 -vn 0.825768 4.948575 3.323267 -v 0.065755 -0.006292 0.142161 -vn 1.629014 4.745154 3.323274 -v 0.064879 -0.006070 0.142161 -vn 2.387821 4.412311 3.323268 -v 0.064052 -0.005707 0.142161 -vn 3.081496 3.959096 3.323301 -v 0.063295 -0.005212 0.142161 -vn 3.691125 3.397926 3.323238 -v 0.062630 -0.004600 0.142161 -vn 4.200062 2.744038 3.323247 -v 0.062075 -0.003887 0.142161 -vn 4.594429 2.015302 3.323274 -v 0.061645 -0.003092 0.142161 -vn 4.863479 1.231602 3.323265 -v 0.061352 -0.002238 0.142161 -vn 4.999850 0.414297 3.323282 -v 0.061203 -0.001346 0.142161 -vn 4.999849 -0.414300 3.323282 -v 0.061203 -0.000442 0.142161 -vn 4.863479 -1.231598 3.323265 -v 0.061352 0.000449 0.142161 -vn 4.594428 -2.015307 3.323271 -v 0.061645 0.001304 0.142161 -vn 4.200063 -2.744037 3.323245 -v 0.062075 0.002098 0.142161 -vn 3.691132 -3.397918 3.323241 -v 0.062630 0.002812 0.142161 -vn 3.081486 -3.959105 3.323303 -v 0.063295 0.003424 0.142161 -vn 2.387826 -4.412307 3.323267 -v 0.064052 0.003918 0.142161 -vn 1.629011 -4.745154 3.323275 -v 0.064879 0.004281 0.142161 -vn 0.825769 -4.948574 3.323268 -v 0.065755 0.004503 0.142161 -vn 0.000002 -5.016998 3.323267 -v 0.066656 0.004577 0.142161 -vn -0.478213 -2.865772 5.311650 -v 0.067527 0.004325 0.141999 -vn -0.943376 -2.747962 5.311662 -v 0.068374 0.004111 0.141999 -vn -1.382811 -2.555212 5.311660 -v 0.069175 0.003760 0.141999 -vn -1.784520 -2.292755 5.311667 -v 0.069906 0.003282 0.141999 -vn -2.137563 -1.967774 5.311654 -v 0.070549 0.002690 0.141999 -vn -2.432297 -1.589096 5.311659 -v 0.071086 0.002000 0.141999 -vn -2.660664 -1.167067 5.311677 -v 0.071502 0.001231 0.141999 -vn -2.816482 -0.713233 5.311654 -v 0.071786 0.000405 0.141999 -vn -2.895439 -0.239921 5.311687 -v 0.071930 -0.000457 0.141999 -vn -2.895443 0.239926 5.311683 -v 0.071930 -0.001331 0.141999 -vn -2.816485 0.713226 5.311653 -v 0.071786 -0.002193 0.141999 -vn -2.660659 1.167072 5.311678 -v 0.071502 -0.003020 0.141999 -vn -2.432299 1.589094 5.311656 -v 0.071086 -0.003789 0.141999 -vn -2.137566 1.967772 5.311654 -v 0.070549 -0.004478 0.141999 -vn -1.784517 2.292756 5.311668 -v 0.069906 -0.005070 0.141999 -vn -1.382813 2.555212 5.311659 -v 0.069175 -0.005548 0.141999 -vn -0.943373 2.747965 5.311662 -v 0.068374 -0.005900 0.141999 -vn -0.478216 2.865772 5.311649 -v 0.067527 -0.006114 0.141999 -vn 0.000001 2.905397 5.311651 -v 0.066656 -0.006186 0.141999 -vn 0.478214 2.865772 5.311651 -v 0.065785 -0.006114 0.141999 -vn 0.943376 2.747970 5.311661 -v 0.064938 -0.005900 0.141999 -vn 1.382812 2.555214 5.311659 -v 0.064137 -0.005548 0.141999 -vn 1.784526 2.292766 5.311665 -v 0.063406 -0.005070 0.141999 -vn 2.137566 1.967774 5.311652 -v 0.062763 -0.004478 0.141999 -vn 2.432296 1.589097 5.311659 -v 0.062226 -0.003789 0.141999 -vn 2.660680 1.167083 5.311655 -v 0.061810 -0.003020 0.141999 -vn 2.816485 0.713230 5.311652 -v 0.061526 -0.002193 0.141999 -vn 2.895463 0.239923 5.311663 -v 0.061382 -0.001331 0.141999 -vn 2.895465 -0.239924 5.311662 -v 0.061382 -0.000457 0.141999 -vn 2.816486 -0.713230 5.311651 -v 0.061526 0.000405 0.141999 -vn 2.660678 -1.167082 5.311657 -v 0.061810 0.001231 0.141999 -vn 2.432295 -1.589098 5.311658 -v 0.062226 0.002000 0.141999 -vn 2.137565 -1.967771 5.311655 -v 0.062763 0.002690 0.141999 -vn 1.784525 -2.292764 5.311665 -v 0.063406 0.003282 0.141999 -vn 1.382812 -2.555213 5.311661 -v 0.064137 0.003760 0.141999 -vn 0.943375 -2.747970 5.311660 -v 0.064938 0.004111 0.141999 -vn 0.478216 -2.865772 5.311649 -v 0.065785 0.004325 0.141999 -vn 0.000001 -2.905397 5.311650 -v 0.066656 0.004398 0.141999 -vn -0.131626 -0.788785 6.179265 -v 0.067488 0.004094 0.141940 -vn -0.259659 -0.756359 6.179267 -v 0.068298 0.003889 0.141940 -vn -0.380612 -0.703310 6.179265 -v 0.069063 0.003553 0.141940 -vn -0.491178 -0.631067 6.179267 -v 0.069762 0.003096 0.141940 -vn -0.588353 -0.541620 6.179265 -v 0.070376 0.002531 0.141940 -vn -0.669479 -0.437390 6.179265 -v 0.070889 0.001872 0.141940 -vn -0.732333 -0.321229 6.179266 -v 0.071287 0.001137 0.141940 -vn -0.775213 -0.196309 6.179268 -v 0.071558 0.000347 0.141940 -vn -0.796964 -0.066039 6.179265 -v 0.071696 -0.000477 0.141940 -vn -0.796963 0.066038 6.179265 -v 0.071696 -0.001312 0.141940 -vn -0.775212 0.196312 6.179268 -v 0.071558 -0.002136 0.141940 -vn -0.732334 0.321229 6.179266 -v 0.071287 -0.002926 0.141940 -vn -0.669480 0.437390 6.179265 -v 0.070889 -0.003660 0.141940 -vn -0.588353 0.541619 6.179265 -v 0.070376 -0.004319 0.141940 -vn -0.491178 0.631068 6.179266 -v 0.069762 -0.004885 0.141940 -vn -0.380613 0.703309 6.179265 -v 0.069063 -0.005342 0.141940 -vn -0.259658 0.756360 6.179266 -v 0.068298 -0.005677 0.141940 -vn -0.131626 0.788785 6.179266 -v 0.067488 -0.005882 0.141940 -vn 0.000000 0.799691 6.179266 -v 0.066656 -0.005951 0.141940 -vn 0.131626 0.788785 6.179266 -v 0.065824 -0.005882 0.141940 -vn 0.259662 0.756368 6.179264 -v 0.065014 -0.005677 0.141940 -vn 0.380613 0.703309 6.179265 -v 0.064249 -0.005342 0.141940 -vn 0.491188 0.631080 6.179262 -v 0.063550 -0.004885 0.141940 -vn 0.588354 0.541617 6.179265 -v 0.062935 -0.004319 0.141940 -vn 0.669477 0.437391 6.179265 -v 0.062422 -0.003660 0.141940 -vn 0.732333 0.321231 6.179266 -v 0.062025 -0.002926 0.141940 -vn 0.775213 0.196309 6.179268 -v 0.061754 -0.002136 0.141940 -vn 0.796964 0.066039 6.179264 -v 0.061616 -0.001312 0.141940 -vn 0.796963 -0.066038 6.179265 -v 0.061616 -0.000477 0.141940 -vn 0.775212 -0.196312 6.179268 -v 0.061754 0.000347 0.141940 -vn 0.732334 -0.321231 6.179266 -v 0.062025 0.001137 0.141940 -vn 0.669478 -0.437391 6.179265 -v 0.062422 0.001872 0.141940 -vn 0.588353 -0.541619 6.179265 -v 0.062935 0.002531 0.141940 -vn 0.491190 -0.631078 6.179262 -v 0.063550 0.003096 0.141940 -vn 0.380611 -0.703309 6.179266 -v 0.064249 0.003553 0.141940 -vn 0.259663 -0.756367 6.179264 -v 0.065014 0.003889 0.141940 -vn 0.131625 -0.788785 6.179265 -v 0.065824 0.004094 0.141940 -vn 0.000000 -0.799691 6.179266 -v 0.066656 0.004163 0.141940 -vn 0.812812 1.874035 5.508947 -v 0.065910 -0.002696 0.141940 -vn 0.049199 2.046896 5.507302 -v 0.066656 -0.002844 0.141940 -vn -1.895994 -0.812265 5.493466 -v 0.068458 -0.000148 0.141940 -vn -2.072911 -0.024083 5.485355 -v 0.068606 -0.000894 0.141940 -vn -1.929512 0.777001 5.480010 -v 0.068458 -0.001641 0.141940 -vn -1.484456 1.463415 5.476729 -v 0.068035 -0.002273 0.141940 -vn 1.469670 1.421405 5.507013 -v 0.065277 -0.002273 0.141940 -vn 1.901728 0.752098 5.506272 -v 0.064854 -0.001641 0.141940 -vn 2.043497 -0.029802 5.507115 -v 0.064706 -0.000894 0.141940 -vn 1.874916 -0.803379 5.510306 -v 0.064854 -0.000148 0.141940 -vn -0.760024 -1.879064 5.522377 -v 0.067402 0.000907 0.141940 -vn -1.431967 -1.463722 5.505455 -v 0.068035 0.000485 0.141940 -vn -0.805851 1.925149 5.474909 -v 0.067402 -0.002696 0.141940 -vn 1.424756 -1.449764 5.516445 -v 0.065277 0.000485 0.141940 -vn 0.000001 -2.006001 5.540257 -v 0.066656 0.001056 0.141940 -vn 0.765150 -1.871176 5.526289 -v 0.065910 0.000907 0.141940 -vn 2.236502 5.001581 2.274135 -v 0.065986 -0.002511 0.141740 -vn 3.144445 4.769476 1.968968 -v 0.065627 -0.002310 0.141740 -vn 4.017820 3.717708 2.281046 -v 0.065419 -0.002132 0.141740 -vn 4.736261 3.097783 2.044832 -v 0.065140 -0.001769 0.141740 -vn 5.150581 1.838898 2.287863 -v 0.065039 -0.001564 0.141740 -vn 5.527235 0.949438 2.113328 -v 0.064916 -0.001077 0.141740 -vn 5.454055 -0.331653 2.294527 -v 0.064906 -0.000894 0.141740 -vn 5.401439 -1.319018 2.174305 -v 0.064992 -0.000354 0.141740 -vn 4.880896 -2.445161 2.301142 -v 0.065039 -0.000225 0.141740 -vn 4.393091 -3.336495 2.227129 -v 0.065355 0.000277 0.141740 -vn 3.525172 -4.161889 2.307626 -v 0.065419 0.000343 0.141740 -vn 2.678177 -4.778939 2.271561 -v 0.065944 0.000704 0.141740 -vn 1.605736 -5.207222 2.314007 -v 0.065986 0.000722 0.141740 -vn 0.000005 -5.474843 2.393571 -v 0.066656 0.000856 0.141740 -vn -1.605730 -5.207226 2.314007 -v 0.067326 0.000722 0.141740 -vn -2.660810 -4.778626 2.282259 -v 0.067368 0.000704 0.141740 -vn -3.531000 -4.148545 2.315508 -v 0.067893 0.000343 0.141740 -vn -4.354615 -3.349476 2.255377 -v 0.067956 0.000277 0.141740 -vn -4.881529 -2.415962 2.316742 -v 0.068273 -0.000225 0.141740 -vn -5.346520 -1.362018 2.228793 -v 0.068320 -0.000354 0.141740 -vn -5.437913 -0.291185 2.317807 -v 0.068406 -0.000894 0.141740 -vn -5.470861 0.860231 2.204752 -v 0.068396 -0.001077 0.141740 -vn -5.110045 1.880318 2.318602 -v 0.068273 -0.001564 0.141740 -vn -4.704273 2.953909 2.185063 -v 0.068172 -0.001769 0.141740 -vn -3.951395 3.745482 2.319209 -v 0.067893 -0.002132 0.141740 -vn -3.169961 4.575675 2.171165 -v 0.067685 -0.002310 0.141740 -vn -2.150476 5.001459 2.319525 -v 0.067326 -0.002511 0.141740 -vn -1.117561 5.459225 2.163973 -v 0.067020 -0.002606 0.141740 -vn 0.092044 5.482934 2.267115 -v 0.066656 -0.002644 0.141740 -vn 1.001706 5.679801 1.885979 -v 0.066292 -0.002606 0.141740 -vn 1.605712 -5.207145 -2.314097 -v 0.065986 0.000722 0.140640 -vn 0.000007 -5.474762 -2.393669 -v 0.066656 0.000856 0.140640 -vn -1.605707 -5.207147 -2.314099 -v 0.067326 0.000722 0.140640 -vn -2.678158 -4.778862 -2.271653 -v 0.067368 0.000704 0.140640 -vn -3.524978 -4.161896 -2.307712 -v 0.067893 0.000343 0.140640 -vn -4.392943 -3.336564 -2.227263 -v 0.067956 0.000277 0.140640 -vn -4.880857 -2.445130 -2.301198 -v 0.068273 -0.000225 0.140640 -vn -5.401432 -1.318965 -2.174339 -v 0.068320 -0.000354 0.140640 -vn -5.453924 -0.331742 -2.294627 -v 0.068406 -0.000894 0.140640 -vn -5.527176 0.949336 -2.113455 -v 0.068396 -0.001077 0.140640 -vn -5.150513 1.838967 -2.287931 -v 0.068273 -0.001564 0.140640 -vn -4.736172 3.097803 -2.044899 -v 0.068172 -0.001769 0.140640 -vn -4.017773 3.717593 -2.281162 -v 0.067893 -0.002132 0.140640 -vn -3.144439 4.769401 -1.969076 -v 0.067685 -0.002310 0.140640 -vn -2.236469 5.001506 -2.274228 -v 0.067326 -0.002511 0.140640 -vn -1.001686 5.679749 -1.886065 -v 0.067020 -0.002606 0.140640 -vn -0.092030 5.482853 -2.267209 -v 0.066656 -0.002644 0.140640 -vn 1.117552 5.459149 -2.164067 -v 0.066292 -0.002606 0.140640 -vn 2.150444 5.001384 -2.319616 -v 0.065986 -0.002511 0.140640 -vn 3.169889 4.575639 -2.171241 -v 0.065627 -0.002310 0.140640 -vn 3.951329 3.745483 -2.319274 -v 0.065419 -0.002132 0.140640 -vn 4.704246 2.953832 -2.185163 -v 0.065140 -0.001769 0.140640 -vn 5.109952 1.880200 -2.318722 -v 0.065039 -0.001564 0.140640 -vn 5.470765 0.860296 -2.204824 -v 0.064916 -0.001077 0.140640 -vn 5.437890 -0.291110 -2.317877 -v 0.064906 -0.000894 0.140640 -vn 5.346415 -1.362004 -2.228908 -v 0.064992 -0.000354 0.140640 -vn 4.881422 -2.415910 -2.316874 -v 0.065039 -0.000225 0.140640 -vn 4.354628 -3.349314 -2.255435 -v 0.065355 0.000277 0.140640 -vn 3.531085 -4.148421 -2.315601 -v 0.065419 0.000343 0.140640 -vn 2.660761 -4.778563 -2.282343 -v 0.065944 0.000704 0.140640 -vn 1.431919 -1.463678 -5.505514 -v 0.065277 0.000485 0.140440 -vn 0.759996 -1.878991 -5.522447 -v 0.065910 0.000907 0.140440 -vn 1.895885 -0.812212 -5.493573 -v 0.064854 -0.000148 0.140440 -vn 2.072856 -0.024082 -5.485407 -v 0.064706 -0.000894 0.140440 -vn 1.929414 0.776948 -5.480109 -v 0.064854 -0.001641 0.140440 -vn 1.484406 1.463384 -5.476780 -v 0.065277 -0.002273 0.140440 -vn 0.805821 1.925075 -5.474983 -v 0.065910 -0.002696 0.140440 -vn -0.049193 2.046814 -5.507373 -v 0.066656 -0.002844 0.140440 -vn -0.812780 1.873961 -5.509017 -v 0.067402 -0.002696 0.140440 -vn -1.469606 1.421315 -5.507108 -v 0.068035 -0.002273 0.140440 -vn -1.901678 0.752098 -5.506314 -v 0.068458 -0.001641 0.140440 -vn -2.043383 -0.029821 -5.507215 -v 0.068606 -0.000894 0.140440 -vn -1.874881 -0.803357 -5.510343 -v 0.068458 -0.000148 0.140440 -vn -1.424685 -1.449701 -5.516528 -v 0.068035 0.000485 0.140440 -vn -0.765120 -1.871099 -5.526361 -v 0.067402 0.000907 0.140440 -vn 0.000003 -2.005920 -5.540326 -v 0.066656 0.001056 0.140440 -vn 1.912057 -1.389194 -5.190839 -v 0.064391 0.000751 0.140440 -vn 1.389196 -1.912067 -5.190827 -v 0.065010 0.001371 0.140440 -vn 0.730344 -2.247766 -5.190830 -v 0.065791 0.001769 0.140440 -vn 0.000002 -2.363440 -5.190833 -v 0.066656 0.001906 0.140440 -vn 1.389199 1.912066 -5.190826 -v 0.065010 -0.003160 0.140440 -vn 1.912057 1.389196 -5.190837 -v 0.064391 -0.002540 0.140440 -vn 2.247757 0.730339 -5.190842 -v 0.063993 -0.001760 0.140440 -vn 2.363419 0.000002 -5.190858 -v 0.063856 -0.000894 0.140440 -vn 2.247756 -0.730340 -5.190843 -v 0.063993 -0.000029 0.140440 -vn -1.912063 1.389190 -5.190835 -v 0.068921 -0.002540 0.140440 -vn -1.389196 1.912067 -5.190827 -v 0.068302 -0.003160 0.140440 -vn -0.730343 2.247766 -5.190830 -v 0.067521 -0.003557 0.140440 -vn 0.000001 2.363439 -5.190833 -v 0.066656 -0.003694 0.140440 -vn 0.730344 2.247765 -5.190831 -v 0.065791 -0.003557 0.140440 -vn -0.730343 -2.247767 -5.190830 -v 0.067521 0.001769 0.140440 -vn -1.389199 -1.912066 -5.190826 -v 0.068302 0.001371 0.140440 -vn -1.912057 -1.389196 -5.190837 -v 0.068921 0.000751 0.140440 -vn -2.247794 -0.730341 -5.190801 -v 0.069319 -0.000029 0.140440 -vn -2.363422 -0.000010 -5.190853 -v 0.069456 -0.000894 0.140440 -vn -2.247787 0.730356 -5.190802 -v 0.069319 -0.001760 0.140440 -vn -1.592090 -4.903342 -2.056931 -v 0.067583 0.001959 0.140240 -vn -3.029657 -4.171546 -2.059977 -v 0.068419 0.001533 0.140240 -vn -4.170743 -3.031213 -2.062668 -v 0.069083 0.000869 0.140240 -vn -4.903605 -1.593995 -2.064989 -v 0.069509 0.000033 0.140240 -vn -5.156318 -0.000576 -2.066983 -v 0.069656 -0.000894 0.140240 -vn -4.904293 1.593033 -2.068576 -v 0.069509 -0.001821 0.140240 -vn -4.171996 3.030701 -2.069848 -v 0.069083 -0.002658 0.140240 -vn -3.031220 4.171743 -2.070745 -v 0.068419 -0.003321 0.140240 -vn -1.593634 4.904343 -2.071286 -v 0.067583 -0.003748 0.140240 -vn 0.000003 5.156782 -2.071467 -v 0.066656 -0.003894 0.140240 -vn 1.593637 4.904343 -2.071286 -v 0.065729 -0.003748 0.140240 -vn 3.031221 4.171741 -2.070745 -v 0.064893 -0.003321 0.140240 -vn 4.171989 3.030719 -2.069853 -v 0.064229 -0.002658 0.140240 -vn 4.904249 1.593009 -2.068598 -v 0.063803 -0.001821 0.140240 -vn 5.156326 -0.000567 -2.066993 -v 0.063656 -0.000894 0.140240 -vn 4.903559 -1.593984 -2.065008 -v 0.063803 0.000033 0.140240 -vn 4.170740 -3.031224 -2.062674 -v 0.064229 0.000869 0.140240 -vn 3.029656 -4.171548 -2.059977 -v 0.064893 0.001533 0.140240 -vn 1.592093 -4.903342 -2.056932 -v 0.065729 0.001959 0.140240 -vn 0.000003 -5.155160 -2.055216 -v 0.066656 0.002106 0.140240 -vn -1.222516 -5.291952 -2.293341 -v 0.067540 0.001972 0.134640 -vn -2.052905 -5.050608 -2.264612 -v 0.067583 0.001959 0.134640 -vn -2.758528 -4.682203 -2.289841 -v 0.068346 0.001584 0.134640 -vn -3.513051 -4.204369 -2.234534 -v 0.068419 0.001533 0.134640 -vn -4.040905 -3.638261 -2.286265 -v 0.069001 0.000976 0.134640 -vn -4.653368 -2.950014 -2.199278 -v 0.069083 0.000869 0.134640 -vn -4.950689 -2.256087 -2.282693 -v 0.069449 0.000202 0.134640 -vn -5.363316 -1.401378 -2.159337 -v 0.069509 0.000033 0.134640 -vn -5.402973 -0.663610 -2.279014 -v 0.069648 -0.000670 0.134640 -vn -5.571609 0.298399 -2.114974 -v 0.069656 -0.000894 0.134640 -vn -5.355436 0.992219 -2.275335 -v 0.069581 -0.001562 0.134640 -vn -5.252832 1.990859 -2.066731 -v 0.069509 -0.001821 0.134640 -vn -4.811961 2.557937 -2.271586 -v 0.069254 -0.002394 0.134640 -vn -4.431083 3.516185 -2.014645 -v 0.069083 -0.002658 0.134640 -vn -3.822272 3.888642 -2.267736 -v 0.068697 -0.003093 0.134640 -vn -3.177696 4.728178 -1.958943 -v 0.068419 -0.003321 0.134640 -vn -2.477506 4.860660 -2.263875 -v 0.067958 -0.003597 0.134640 -vn -1.605730 5.508163 -1.899756 -v 0.067583 -0.003748 0.134640 -vn -0.901808 5.383636 -2.259953 -v 0.067103 -0.003861 0.134640 -vn 0.140197 5.776693 -1.837049 -v 0.066656 -0.003894 0.134640 -vn 0.759156 5.408617 -2.255970 -v 0.066209 -0.003861 0.134640 -vn 1.672296 5.306207 -2.138077 -v 0.065729 -0.003748 0.134640 -vn 2.410879 4.863641 -2.297368 -v 0.065354 -0.003597 0.134640 -vn 3.187165 4.553532 -2.144507 -v 0.064893 -0.003321 0.134640 -vn 3.767234 3.908516 -2.297204 -v 0.064615 -0.003093 0.134640 -vn 4.402265 3.378588 -2.154991 -v 0.064229 -0.002658 0.134640 -vn 4.771897 2.588356 -2.296929 -v 0.064058 -0.002394 0.134640 -vn 5.203794 1.892614 -2.169152 -v 0.063803 -0.001821 0.134640 -vn 5.331055 1.026355 -2.296547 -v 0.063731 -0.001562 0.134640 -vn 5.517303 0.236048 -2.186468 -v 0.063656 -0.000894 0.134640 -vn 5.392474 -0.631585 -2.296057 -v 0.063664 -0.000670 0.134640 -vn 5.314684 -1.435081 -2.206282 -v 0.063803 0.000033 0.134640 -vn 4.950260 -2.230847 -2.295527 -v 0.063863 0.000202 0.134640 -vn 4.616602 -2.963678 -2.227625 -v 0.064229 0.000869 0.134640 -vn 4.045784 -3.621964 -2.294893 -v 0.064310 0.000976 0.134640 -vn 3.490260 -4.206968 -2.249400 -v 0.064893 0.001533 0.134640 -vn 2.763248 -4.675150 -2.294164 -v 0.064966 0.001584 0.134640 -vn 2.043067 -5.049303 -2.270344 -v 0.065729 0.001959 0.134640 -vn 1.222519 -5.291951 -2.293340 -v 0.065772 0.001972 0.134640 -vn 0.000004 -5.463933 -2.357387 -v 0.066656 0.002106 0.134640 -vn 1.161974 -1.739200 -5.474108 -v 0.064853 0.001750 0.134440 -vn 0.599111 -1.988142 -5.487111 -v 0.065713 0.002163 0.134440 -vn 1.629284 -1.329542 -5.464613 -v 0.064154 0.001101 0.134440 -vn 1.955754 -0.794794 -5.457868 -v 0.063677 0.000275 0.134440 -vn 2.109017 -0.183031 -5.453136 -v 0.063465 -0.000655 0.134440 -vn 2.072799 0.449819 -5.449914 -v 0.063536 -0.001606 0.134440 -vn 1.848802 1.045417 -5.447719 -v 0.063885 -0.002494 0.134440 -vn 1.456398 1.548562 -5.446271 -v 0.064479 -0.003240 0.134440 -vn 0.930874 1.912516 -5.445380 -v 0.065268 -0.003777 0.134440 -vn 0.268721 2.075761 -5.474379 -v 0.066179 -0.004059 0.134440 -vn -0.345577 2.062772 -5.474427 -v 0.067133 -0.004059 0.134440 -vn -0.940421 1.870486 -5.472454 -v 0.068044 -0.003777 0.134440 -vn -1.451606 1.510903 -5.470823 -v 0.068833 -0.003240 0.134440 -vn -1.833262 1.016546 -5.469726 -v 0.069427 -0.002494 0.134440 -vn -2.051452 0.432279 -5.469273 -v 0.069776 -0.001606 0.134440 -vn -2.087200 -0.189077 -5.469726 -v 0.069847 -0.000655 0.134440 -vn -1.938109 -0.791459 -5.471551 -v 0.069635 0.000275 0.134440 -vn -1.618939 -1.320828 -5.475077 -v 0.069158 0.001101 0.134440 -vn -1.159694 -1.730086 -5.480929 -v 0.068459 0.001750 0.134440 -vn -0.603041 -1.983666 -5.489528 -v 0.067599 0.002163 0.134440 -vn 0.000001 -2.060472 -5.501227 -v 0.066656 0.002306 0.134440 -vn -1.636218 1.636214 -5.259146 -v 0.061141 0.004621 0.134440 -vn -1.285562 1.923980 -5.259154 -v 0.062323 0.005591 0.134440 -vn -0.885505 2.137806 -5.259164 -v 0.063671 0.006312 0.134440 -vn -0.451430 2.269491 -5.259154 -v 0.065134 0.006756 0.134440 -vn -2.137819 -0.885514 -5.259146 -v 0.059450 -0.003879 0.134440 -vn -2.269498 -0.451433 -5.259144 -v 0.059006 -0.002416 0.134440 -vn -2.313954 0.000001 -5.259152 -v 0.058856 -0.000894 0.134440 -vn -2.269499 0.451432 -5.259145 -v 0.059006 0.000627 0.134440 -vn -2.137819 0.885512 -5.259148 -v 0.059450 0.002091 0.134440 -vn -1.923966 1.285557 -5.259170 -v 0.060171 0.003439 0.134440 -vn -1.285563 -1.923981 -5.259154 -v 0.062323 -0.007380 0.134440 -vn -1.636214 -1.636217 -5.259147 -v 0.061141 -0.006410 0.134440 -vn -1.923969 -1.285553 -5.259171 -v 0.060171 -0.005228 0.134440 -vn -0.000001 -2.313948 -5.259158 -v 0.066656 -0.008694 0.134440 -vn -0.451428 -2.269489 -5.259156 -v 0.065134 -0.008544 0.134440 -vn -0.885507 -2.137805 -5.259163 -v 0.063671 -0.008101 0.134440 -vn 2.269482 0.451428 -5.259164 -v 0.074306 0.000627 0.134440 -vn 2.313972 0.000004 -5.259132 -v 0.074456 -0.000894 0.134440 -vn 1.636196 1.636195 -5.259178 -v 0.072171 0.004621 0.134440 -vn 1.923994 1.285577 -5.259133 -v 0.073141 0.003439 0.134440 -vn 2.137784 0.885496 -5.259190 -v 0.073862 0.002091 0.134440 -vn 0.000000 2.313948 -5.259158 -v 0.066656 0.006906 0.134440 -vn 0.451428 2.269491 -5.259153 -v 0.068178 0.006756 0.134440 -vn 0.885508 2.137805 -5.259163 -v 0.069641 0.006312 0.134440 -vn 1.285567 1.923990 -5.259144 -v 0.070989 0.005591 0.134440 -vn 1.285573 -1.923986 -5.259142 -v 0.070989 -0.007380 0.134440 -vn 0.885505 -2.137806 -5.259163 -v 0.069641 -0.008101 0.134440 -vn 0.451429 -2.269489 -5.259156 -v 0.068178 -0.008544 0.134440 -vn 2.269479 -0.451428 -5.259167 -v 0.074306 -0.002416 0.134440 -vn 2.137781 -0.885505 -5.259189 -v 0.073862 -0.003879 0.134440 -vn 1.924001 -1.285567 -5.259133 -v 0.073141 -0.005228 0.134440 -vn 1.636189 -1.636201 -5.259179 -v 0.072171 -0.006410 0.134440 -vn -0.000001 -5.245751 -2.134626 -v 0.066656 -0.008894 0.134640 -vn 1.023395 -5.144958 -2.134625 -v 0.068217 -0.008741 0.134640 -vn 2.007462 -4.846435 -2.134628 -v 0.069717 -0.008285 0.134640 -vn 2.914393 -4.361695 -2.134617 -v 0.071101 -0.007546 0.134640 -vn 3.709290 -3.709295 -2.134638 -v 0.072313 -0.006551 0.134640 -vn 4.361703 -2.914393 -2.134610 -v 0.073308 -0.005339 0.134640 -vn 4.846413 -2.007457 -2.134647 -v 0.074047 -0.003956 0.134640 -vn 5.144950 -1.023389 -2.134629 -v 0.074502 -0.002455 0.134640 -vn 5.245779 0.000003 -2.134609 -v 0.074656 -0.000894 0.134640 -vn 5.144947 1.023387 -2.134632 -v 0.074502 0.000666 0.134640 -vn 4.846417 2.007451 -2.134646 -v 0.074047 0.002167 0.134640 -vn 4.361698 2.914401 -2.134609 -v 0.073308 0.003550 0.134640 -vn 3.709295 3.709289 -2.134639 -v 0.072313 0.004763 0.134640 -vn 2.914388 4.361699 -2.134617 -v 0.071101 0.005757 0.134640 -vn 2.007463 4.846434 -2.134629 -v 0.069717 0.006497 0.134640 -vn 1.023395 5.144961 -2.134623 -v 0.068217 0.006952 0.134640 -vn -0.000001 5.245751 -2.134626 -v 0.066656 0.007106 0.134640 -vn -1.023397 5.144960 -2.134623 -v 0.065095 0.006952 0.134640 -vn -2.007459 4.846437 -2.134630 -v 0.063595 0.006497 0.134640 -vn -2.914387 4.361684 -2.134623 -v 0.062211 0.005757 0.134640 -vn -3.709312 3.709314 -2.134618 -v 0.060999 0.004763 0.134640 -vn -4.361671 2.914377 -2.134634 -v 0.060004 0.003550 0.134640 -vn -4.846455 2.007462 -2.134618 -v 0.059265 0.002167 0.134640 -vn -5.144969 1.023400 -2.134617 -v 0.058810 0.000666 0.134640 -vn -5.245754 0.000001 -2.134620 -v 0.058656 -0.000894 0.134640 -vn -5.144969 -1.023401 -2.134615 -v 0.058810 -0.002455 0.134640 -vn -4.846452 -2.007464 -2.134619 -v 0.059265 -0.003956 0.134640 -vn -4.361673 -2.914374 -2.134634 -v 0.060004 -0.005339 0.134640 -vn -3.709311 -3.709317 -2.134617 -v 0.060999 -0.006551 0.134640 -vn -2.914387 -4.361684 -2.134624 -v 0.062211 -0.007546 0.134640 -vn -2.007461 -4.846435 -2.134630 -v 0.063595 -0.008285 0.134640 -vn -1.023396 -5.144959 -2.134625 -v 0.065095 -0.008741 0.134640 -# 2896 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 1//1 -f 1//1 128//128 2//2 -f 128//128 129//129 2//2 -f 2//2 129//129 130//130 -f 2//2 130//130 4//4 -f 4//4 130//130 131//131 -f 4//4 131//131 6//6 -f 6//6 131//131 132//132 -f 6//6 132//132 8//8 -f 8//8 132//132 133//133 -f 8//8 133//133 10//10 -f 10//10 133//133 134//134 -f 10//10 134//134 12//12 -f 12//12 134//134 135//135 -f 12//12 135//135 14//14 -f 14//14 135//135 136//136 -f 14//14 136//136 16//16 -f 16//16 136//136 137//137 -f 16//16 137//137 18//18 -f 18//18 137//137 138//138 -f 18//18 138//138 20//20 -f 20//20 138//138 139//139 -f 20//20 139//139 22//22 -f 22//22 139//139 140//140 -f 22//22 140//140 24//24 -f 24//24 140//140 141//141 -f 24//24 141//141 26//26 -f 26//26 141//141 142//142 -f 26//26 142//142 28//28 -f 28//28 142//142 143//143 -f 28//28 143//143 30//30 -f 30//30 143//143 144//144 -f 30//30 144//144 32//32 -f 32//32 144//144 145//145 -f 32//32 145//145 34//34 -f 34//34 145//145 146//146 -f 34//34 146//146 36//36 -f 36//36 146//146 147//147 -f 36//36 147//147 38//38 -f 38//38 147//147 148//148 -f 38//38 148//148 40//40 -f 40//40 148//148 149//149 -f 40//40 149//149 42//42 -f 42//42 149//149 150//150 -f 42//42 150//150 44//44 -f 44//44 150//150 151//151 -f 44//44 151//151 46//46 -f 46//46 151//151 152//152 -f 46//46 152//152 48//48 -f 48//48 152//152 153//153 -f 48//48 153//153 50//50 -f 50//50 153//153 154//154 -f 50//50 154//154 52//52 -f 52//52 154//154 155//155 -f 52//52 155//155 54//54 -f 54//54 155//155 156//156 -f 54//54 156//156 56//56 -f 56//56 156//156 157//157 -f 56//56 157//157 58//58 -f 58//58 157//157 158//158 -f 58//58 158//158 60//60 -f 60//60 158//158 159//159 -f 60//60 159//159 62//62 -f 62//62 159//159 160//160 -f 62//62 160//160 64//64 -f 64//64 160//160 161//161 -f 64//64 161//161 66//66 -f 66//66 161//161 162//162 -f 66//66 162//162 68//68 -f 68//68 162//162 163//163 -f 68//68 163//163 70//70 -f 70//70 163//163 164//164 -f 70//70 164//164 72//72 -f 72//72 164//164 165//165 -f 72//72 165//165 74//74 -f 74//74 165//165 166//166 -f 74//74 166//166 76//76 -f 76//76 166//166 167//167 -f 76//76 167//167 78//78 -f 78//78 167//167 168//168 -f 78//78 168//168 80//80 -f 80//80 168//168 169//169 -f 80//80 169//169 82//82 -f 82//82 169//169 170//170 -f 82//82 170//170 84//84 -f 84//84 170//170 171//171 -f 84//84 171//171 86//86 -f 86//86 171//171 172//172 -f 86//86 172//172 88//88 -f 88//88 172//172 173//173 -f 88//88 173//173 90//90 -f 90//90 173//173 174//174 -f 90//90 174//174 92//92 -f 92//92 174//174 175//175 -f 92//92 175//175 94//94 -f 94//94 175//175 176//176 -f 94//94 176//176 96//96 -f 96//96 176//176 177//177 -f 96//96 177//177 98//98 -f 98//98 177//177 178//178 -f 98//98 178//178 100//100 -f 100//100 178//178 179//179 -f 100//100 179//179 102//102 -f 102//102 179//179 180//180 -f 102//102 180//180 104//104 -f 104//104 180//180 181//181 -f 104//104 181//181 106//106 -f 106//106 181//181 182//182 -f 106//106 182//182 108//108 -f 108//108 182//182 183//183 -f 108//108 183//183 110//110 -f 110//110 183//183 184//184 -f 110//110 184//184 112//112 -f 112//112 184//184 185//185 -f 112//112 185//185 114//114 -f 114//114 185//185 186//186 -f 114//114 186//186 116//116 -f 116//116 186//186 187//187 -f 116//116 187//187 118//118 -f 118//118 187//187 188//188 -f 118//118 188//188 120//120 -f 120//120 188//188 189//189 -f 120//120 189//189 122//122 -f 122//122 189//189 190//190 -f 122//122 190//190 124//124 -f 124//124 190//190 191//191 -f 124//124 191//191 126//126 -f 126//126 191//191 192//192 -f 126//126 192//192 128//128 -f 128//128 192//192 129//129 -f 192//192 193//193 129//129 -f 129//129 193//193 194//194 -f 129//129 194//194 130//130 -f 130//130 194//194 195//195 -f 130//130 195//195 131//131 -f 131//131 195//195 196//196 -f 131//131 196//196 132//132 -f 132//132 196//196 197//197 -f 132//132 197//197 133//133 -f 133//133 197//197 198//198 -f 133//133 198//198 134//134 -f 134//134 198//198 199//199 -f 134//134 199//199 135//135 -f 135//135 199//199 200//200 -f 135//135 200//200 136//136 -f 136//136 200//200 201//201 -f 136//136 201//201 137//137 -f 137//137 201//201 202//202 -f 137//137 202//202 138//138 -f 138//138 202//202 203//203 -f 138//138 203//203 139//139 -f 139//139 203//203 204//204 -f 139//139 204//204 140//140 -f 140//140 204//204 205//205 -f 140//140 205//205 141//141 -f 141//141 205//205 206//206 -f 141//141 206//206 142//142 -f 142//142 206//206 207//207 -f 142//142 207//207 143//143 -f 143//143 207//207 208//208 -f 143//143 208//208 144//144 -f 144//144 208//208 209//209 -f 144//144 209//209 145//145 -f 145//145 209//209 210//210 -f 145//145 210//210 146//146 -f 146//146 210//210 211//211 -f 146//146 211//211 147//147 -f 147//147 211//211 212//212 -f 147//147 212//212 148//148 -f 148//148 212//212 213//213 -f 148//148 213//213 149//149 -f 149//149 213//213 214//214 -f 149//149 214//214 150//150 -f 150//150 214//214 215//215 -f 150//150 215//215 151//151 -f 151//151 215//215 216//216 -f 151//151 216//216 152//152 -f 152//152 216//216 217//217 -f 152//152 217//217 153//153 -f 153//153 217//217 218//218 -f 153//153 218//218 154//154 -f 154//154 218//218 219//219 -f 154//154 219//219 155//155 -f 155//155 219//219 220//220 -f 155//155 220//220 156//156 -f 156//156 220//220 221//221 -f 156//156 221//221 157//157 -f 157//157 221//221 222//222 -f 157//157 222//222 158//158 -f 158//158 222//222 223//223 -f 158//158 223//223 159//159 -f 159//159 223//223 224//224 -f 159//159 224//224 160//160 -f 160//160 224//224 225//225 -f 160//160 225//225 161//161 -f 161//161 225//225 226//226 -f 161//161 226//226 162//162 -f 162//162 226//226 227//227 -f 162//162 227//227 163//163 -f 163//163 227//227 228//228 -f 163//163 228//228 164//164 -f 164//164 228//228 229//229 -f 164//164 229//229 165//165 -f 165//165 229//229 230//230 -f 165//165 230//230 166//166 -f 166//166 230//230 231//231 -f 166//166 231//231 167//167 -f 167//167 231//231 232//232 -f 167//167 232//232 168//168 -f 168//168 232//232 233//233 -f 168//168 233//233 169//169 -f 169//169 233//233 234//234 -f 169//169 234//234 170//170 -f 170//170 234//234 235//235 -f 170//170 235//235 171//171 -f 171//171 235//235 236//236 -f 171//171 236//236 172//172 -f 172//172 236//236 237//237 -f 172//172 237//237 173//173 -f 173//173 237//237 238//238 -f 173//173 238//238 174//174 -f 174//174 238//238 239//239 -f 174//174 239//239 175//175 -f 175//175 239//239 240//240 -f 175//175 240//240 176//176 -f 176//176 240//240 241//241 -f 176//176 241//241 177//177 -f 177//177 241//241 242//242 -f 177//177 242//242 178//178 -f 178//178 242//242 243//243 -f 178//178 243//243 179//179 -f 179//179 243//243 244//244 -f 179//179 244//244 180//180 -f 180//180 244//244 245//245 -f 180//180 245//245 181//181 -f 181//181 245//245 246//246 -f 181//181 246//246 182//182 -f 182//182 246//246 247//247 -f 182//182 247//247 183//183 -f 183//183 247//247 248//248 -f 183//183 248//248 184//184 -f 184//184 248//248 249//249 -f 184//184 249//249 185//185 -f 185//185 249//249 250//250 -f 185//185 250//250 186//186 -f 186//186 250//250 251//251 -f 186//186 251//251 187//187 -f 187//187 251//251 252//252 -f 187//187 252//252 188//188 -f 188//188 252//252 253//253 -f 188//188 253//253 189//189 -f 189//189 253//253 254//254 -f 189//189 254//254 190//190 -f 190//190 254//254 255//255 -f 190//190 255//255 191//191 -f 191//191 255//255 256//256 -f 191//191 256//256 192//192 -f 192//192 256//256 193//193 -f 242//242 257//257 243//243 -f 243//243 257//257 258//258 -f 243//243 258//258 244//244 -f 244//244 258//258 259//259 -f 244//244 259//259 245//245 -f 245//245 259//259 260//260 -f 245//245 260//260 246//246 -f 246//246 260//260 261//261 -f 246//246 261//261 247//247 -f 247//247 261//261 262//262 -f 247//247 262//262 248//248 -f 236//236 263//263 237//237 -f 237//237 263//263 264//264 -f 237//237 264//264 238//238 -f 238//238 264//264 265//265 -f 238//238 265//265 239//239 -f 239//239 265//265 266//266 -f 239//239 266//266 240//240 -f 240//240 266//266 267//267 -f 240//240 267//267 241//241 -f 241//241 267//267 268//268 -f 241//241 268//268 242//242 -f 242//242 268//268 269//269 -f 242//242 269//269 257//257 -f 230//230 270//270 231//231 -f 231//231 270//270 271//271 -f 231//231 271//271 232//232 -f 232//232 271//271 272//272 -f 232//232 272//272 233//233 -f 233//233 272//272 273//273 -f 233//233 273//273 234//234 -f 234//234 273//273 274//274 -f 234//234 274//274 235//235 -f 235//235 274//274 275//275 -f 235//235 275//275 236//236 -f 236//236 275//275 276//276 -f 236//236 276//276 263//263 -f 216//216 277//277 217//217 -f 217//217 277//277 278//278 -f 217//217 278//278 218//218 -f 218//218 278//278 279//279 -f 218//218 279//279 219//219 -f 219//219 279//279 280//280 -f 219//219 280//280 220//220 -f 220//220 280//280 281//281 -f 220//220 281//281 221//221 -f 221//221 281//281 282//282 -f 221//221 282//282 222//222 -f 222//222 282//282 283//283 -f 222//222 283//283 223//223 -f 223//223 283//283 284//284 -f 223//223 284//284 224//224 -f 224//224 284//284 285//285 -f 224//224 285//285 225//225 -f 225//225 285//285 286//286 -f 225//225 286//286 226//226 -f 226//226 286//286 287//287 -f 226//226 287//287 227//227 -f 227//227 287//287 288//288 -f 227//227 288//288 228//228 -f 228//228 288//288 289//289 -f 228//228 289//289 229//229 -f 229//229 289//289 290//290 -f 229//229 290//290 230//230 -f 230//230 290//290 291//291 -f 230//230 291//291 270//270 -f 210//210 292//292 211//211 -f 211//211 292//292 293//293 -f 211//211 293//293 212//212 -f 212//212 293//293 294//294 -f 212//212 294//294 213//213 -f 213//213 294//294 295//295 -f 213//213 295//295 214//214 -f 214//214 295//295 296//296 -f 214//214 296//296 215//215 -f 215//215 296//296 297//297 -f 215//215 297//297 216//216 -f 216//216 297//297 298//298 -f 216//216 298//298 277//277 -f 204//204 299//299 205//205 -f 205//205 299//299 300//300 -f 205//205 300//300 206//206 -f 206//206 300//300 301//301 -f 206//206 301//301 207//207 -f 207//207 301//301 302//302 -f 207//207 302//302 208//208 -f 208//208 302//302 303//303 -f 208//208 303//303 209//209 -f 209//209 303//303 304//304 -f 209//209 304//304 210//210 -f 210//210 304//304 305//305 -f 210//210 305//305 292//292 -f 198//198 306//306 199//199 -f 199//199 306//306 307//307 -f 199//199 307//307 200//200 -f 200//200 307//307 308//308 -f 200//200 308//308 201//201 -f 201//201 308//308 309//309 -f 201//201 309//309 202//202 -f 202//202 309//309 310//310 -f 202//202 310//310 203//203 -f 203//203 310//310 311//311 -f 203//203 311//311 204//204 -f 204//204 311//311 312//312 -f 204//204 312//312 299//299 -f 262//262 313//313 248//248 -f 248//248 313//313 314//314 -f 248//248 314//314 249//249 -f 249//249 314//314 315//315 -f 249//249 315//315 250//250 -f 250//250 315//315 316//316 -f 250//250 316//316 251//251 -f 251//251 316//316 317//317 -f 251//251 317//317 252//252 -f 252//252 317//317 318//318 -f 252//252 318//318 253//253 -f 253//253 318//318 319//319 -f 253//253 319//319 254//254 -f 254//254 319//319 320//320 -f 254//254 320//320 255//255 -f 255//255 320//320 321//321 -f 255//255 321//321 256//256 -f 256//256 321//321 322//322 -f 256//256 322//322 193//193 -f 193//193 322//322 323//323 -f 193//193 323//323 194//194 -f 194//194 323//323 324//324 -f 194//194 324//324 195//195 -f 195//195 324//324 325//325 -f 195//195 325//325 196//196 -f 196//196 325//325 326//326 -f 196//196 326//326 197//197 -f 197//197 326//326 327//327 -f 197//197 327//327 198//198 -f 198//198 327//327 328//328 -f 198//198 328//328 306//306 -f 329//329 330//330 331//331 -f 332//332 333//333 334//334 -f 335//335 336//336 337//337 -f 338//338 339//339 340//340 -f 341//341 342//342 343//343 -f 344//344 345//345 346//346 -f 347//347 348//348 349//349 -f 328//328 327//327 350//350 -f 307//307 306//306 351//351 -f 308//308 307//307 352//352 -f 296//296 295//295 335//335 -f 298//298 297//297 353//353 -f 278//278 277//277 354//354 -f 279//279 278//278 355//355 -f 276//276 275//275 356//356 -f 265//265 264//264 357//357 -f 258//258 257//257 358//358 -f 261//261 260//260 359//359 -f 320//320 319//319 360//360 -f 322//322 321//321 361//361 -f 361//361 321//321 320//320 -f 317//317 316//316 347//347 -f 347//347 316//316 315//315 -f 347//347 315//315 348//348 -f 348//348 315//315 314//314 -f 348//348 314//314 313//313 -f 362//362 262//262 261//261 -f 260//260 259//259 363//363 -f 266//266 345//345 267//267 -f 267//267 345//345 344//344 -f 267//267 344//344 268//268 -f 268//268 344//344 269//269 -f 264//264 263//263 364//364 -f 364//364 263//263 276//276 -f 273//273 272//272 341//341 -f 341//341 272//272 271//271 -f 341//341 271//271 342//342 -f 342//342 271//271 270//270 -f 342//342 270//270 291//291 -f 365//365 290//290 289//289 -f 289//289 288//288 366//366 -f 366//366 288//288 287//287 -f 285//285 284//284 338//338 -f 338//338 284//284 283//283 -f 338//338 283//283 339//339 -f 339//339 283//283 282//282 -f 339//339 282//282 281//281 -f 279//279 355//355 280//280 -f 335//335 295//295 336//336 -f 336//336 295//295 294//294 -f 336//336 294//294 293//293 -f 367//367 292//292 305//305 -f 305//305 304//304 368//368 -f 368//368 304//304 303//303 -f 302//302 301//301 369//369 -f 300//300 299//299 332//332 -f 332//332 299//299 312//312 -f 332//332 312//312 333//333 -f 333//333 312//312 311//311 -f 333//333 311//311 310//310 -f 308//308 352//352 309//309 -f 326//326 325//325 329//329 -f 329//329 325//325 324//324 -f 329//329 324//324 330//330 -f 330//330 324//324 323//323 -f 370//370 371//371 360//360 -f 372//372 349//349 373//373 -f 373//373 349//349 348//348 -f 373//373 348//348 362//362 -f 362//362 348//348 313//313 -f 362//362 313//313 262//262 -f 374//374 375//375 363//363 -f 376//376 346//346 377//377 -f 377//377 346//346 345//345 -f 377//377 345//345 357//357 -f 357//357 345//345 266//266 -f 357//357 266//266 265//265 -f 378//378 379//379 356//356 -f 380//380 343//343 381//381 -f 381//381 343//343 342//342 -f 381//381 342//342 365//365 -f 365//365 342//342 291//291 -f 365//365 291//291 290//290 -f 382//382 383//383 384//384 -f 385//385 340//340 386//386 -f 386//386 340//340 339//339 -f 386//386 339//339 387//387 -f 387//387 339//339 281//281 -f 387//387 281//281 280//280 -f 388//388 389//389 354//354 -f 390//390 337//337 391//391 -f 391//391 337//337 336//336 -f 391//391 336//336 367//367 -f 367//367 336//336 293//293 -f 367//367 293//293 292//292 -f 392//392 393//393 394//394 -f 395//395 334//334 396//396 -f 396//396 334//334 333//333 -f 396//396 333//333 397//397 -f 397//397 333//333 310//310 -f 397//397 310//310 309//309 -f 398//398 399//399 351//351 -f 400//400 331//331 401//401 -f 401//401 331//331 330//330 -f 401//401 330//330 402//402 -f 402//402 330//330 323//323 -f 402//402 323//323 322//322 -f 403//403 371//371 404//404 -f 404//404 371//371 370//370 -f 404//404 370//370 405//405 -f 406//406 375//375 407//407 -f 407//407 375//375 374//374 -f 407//407 374//374 408//408 -f 409//409 379//379 410//410 -f 410//410 379//379 378//378 -f 410//410 378//378 411//411 -f 412//412 383//383 413//413 -f 413//413 383//383 382//382 -f 413//413 382//382 414//414 -f 415//415 389//389 416//416 -f 416//416 389//389 388//388 -f 416//416 388//388 417//417 -f 418//418 393//393 419//419 -f 419//419 393//393 392//392 -f 419//419 392//392 420//420 -f 421//421 399//399 422//422 -f 422//422 399//399 398//398 -f 422//422 398//398 423//423 -f 424//424 425//425 426//426 -f 322//322 361//361 402//402 -f 402//402 361//361 427//427 -f 402//402 427//427 401//401 -f 401//401 427//427 424//424 -f 401//401 424//424 400//400 -f 400//400 424//424 426//426 -f 400//400 426//426 428//428 -f 320//320 360//360 361//361 -f 361//361 360//360 371//371 -f 361//361 371//371 427//427 -f 427//427 371//371 403//403 -f 427//427 403//403 424//424 -f 424//424 403//403 429//429 -f 424//424 429//429 425//425 -f 430//430 431//431 432//432 -f 432//432 431//431 405//405 -f 432//432 405//405 433//433 -f 433//433 405//405 370//370 -f 433//433 370//370 434//434 -f 434//434 370//370 360//360 -f 434//434 360//360 318//318 -f 318//318 360//360 319//319 -f 431//431 435//435 405//405 -f 405//405 435//435 436//436 -f 405//405 436//436 404//404 -f 404//404 436//436 437//437 -f 404//404 437//437 403//403 -f 403//403 437//437 438//438 -f 403//403 438//438 429//429 -f 318//318 317//317 434//434 -f 434//434 317//317 347//347 -f 434//434 347//347 433//433 -f 433//433 347//347 349//349 -f 433//433 349//349 432//432 -f 432//432 349//349 372//372 -f 432//432 372//372 430//430 -f 430//430 372//372 439//439 -f 440//440 441//441 442//442 -f 261//261 359//359 362//362 -f 362//362 359//359 443//443 -f 362//362 443//443 373//373 -f 373//373 443//443 440//440 -f 373//373 440//440 372//372 -f 372//372 440//440 442//442 -f 372//372 442//442 439//439 -f 260//260 363//363 359//359 -f 359//359 363//363 375//375 -f 359//359 375//375 443//443 -f 443//443 375//375 406//406 -f 443//443 406//406 440//440 -f 440//440 406//406 444//444 -f 440//440 444//444 441//441 -f 445//445 446//446 447//447 -f 447//447 446//446 408//408 -f 447//447 408//408 448//448 -f 448//448 408//408 374//374 -f 448//448 374//374 358//358 -f 358//358 374//374 363//363 -f 358//358 363//363 258//258 -f 258//258 363//363 259//259 -f 446//446 449//449 408//408 -f 408//408 449//449 450//450 -f 408//408 450//450 407//407 -f 407//407 450//450 451//451 -f 407//407 451//451 406//406 -f 406//406 451//451 452//452 -f 406//406 452//452 444//444 -f 257//257 269//269 358//358 -f 358//358 269//269 344//344 -f 358//358 344//344 448//448 -f 448//448 344//344 346//346 -f 448//448 346//346 447//447 -f 447//447 346//346 376//376 -f 447//447 376//376 445//445 -f 445//445 376//376 453//453 -f 454//454 455//455 456//456 -f 264//264 364//364 357//357 -f 357//357 364//364 457//457 -f 357//357 457//457 377//377 -f 377//377 457//457 454//454 -f 377//377 454//454 376//376 -f 376//376 454//454 456//456 -f 376//376 456//456 453//453 -f 276//276 356//356 364//364 -f 364//364 356//356 379//379 -f 364//364 379//379 457//457 -f 457//457 379//379 409//409 -f 457//457 409//409 454//454 -f 454//454 409//409 458//458 -f 454//454 458//458 455//455 -f 459//459 460//460 461//461 -f 461//461 460//460 411//411 -f 461//461 411//411 462//462 -f 462//462 411//411 378//378 -f 462//462 378//378 463//463 -f 463//463 378//378 356//356 -f 463//463 356//356 274//274 -f 274//274 356//356 275//275 -f 460//460 464//464 411//411 -f 411//411 464//464 465//465 -f 411//411 465//465 410//410 -f 410//410 465//465 466//466 -f 410//410 466//466 409//409 -f 409//409 466//466 467//467 -f 409//409 467//467 458//458 -f 274//274 273//273 463//463 -f 463//463 273//273 341//341 -f 463//463 341//341 462//462 -f 462//462 341//341 343//343 -f 462//462 343//343 461//461 -f 461//461 343//343 380//380 -f 461//461 380//380 459//459 -f 459//459 380//380 468//468 -f 469//469 470//470 471//471 -f 289//289 366//366 365//365 -f 365//365 366//366 472//472 -f 365//365 472//472 381//381 -f 381//381 472//472 469//469 -f 381//381 469//469 380//380 -f 380//380 469//469 471//471 -f 380//380 471//471 468//468 -f 287//287 384//384 366//366 -f 366//366 384//384 383//383 -f 366//366 383//383 472//472 -f 472//472 383//383 412//412 -f 472//472 412//412 469//469 -f 469//469 412//412 473//473 -f 469//469 473//473 470//470 -f 474//474 475//475 476//476 -f 476//476 475//475 414//414 -f 476//476 414//414 477//477 -f 477//477 414//414 382//382 -f 477//477 382//382 478//478 -f 478//478 382//382 384//384 -f 478//478 384//384 286//286 -f 286//286 384//384 287//287 -f 475//475 479//479 414//414 -f 414//414 479//479 480//480 -f 414//414 480//480 413//413 -f 413//413 480//480 481//481 -f 413//413 481//481 412//412 -f 412//412 481//481 482//482 -f 412//412 482//482 473//473 -f 286//286 285//285 478//478 -f 478//478 285//285 338//338 -f 478//478 338//338 477//477 -f 477//477 338//338 340//340 -f 477//477 340//340 476//476 -f 476//476 340//340 385//385 -f 476//476 385//385 474//474 -f 474//474 385//385 483//483 -f 484//484 485//485 486//486 -f 280//280 355//355 387//387 -f 387//387 355//355 487//487 -f 387//387 487//487 386//386 -f 386//386 487//487 484//484 -f 386//386 484//484 385//385 -f 385//385 484//484 486//486 -f 385//385 486//486 483//483 -f 278//278 354//354 355//355 -f 355//355 354//354 389//389 -f 355//355 389//389 487//487 -f 487//487 389//389 415//415 -f 487//487 415//415 484//484 -f 484//484 415//415 488//488 -f 484//484 488//488 485//485 -f 489//489 490//490 491//491 -f 491//491 490//490 417//417 -f 491//491 417//417 492//492 -f 492//492 417//417 388//388 -f 492//492 388//388 353//353 -f 353//353 388//388 354//354 -f 353//353 354//354 298//298 -f 298//298 354//354 277//277 -f 490//490 493//493 417//417 -f 417//417 493//493 494//494 -f 417//417 494//494 416//416 -f 416//416 494//494 495//495 -f 416//416 495//495 415//415 -f 415//415 495//495 496//496 -f 415//415 496//496 488//488 -f 297//297 296//296 353//353 -f 353//353 296//296 335//335 -f 353//353 335//335 492//492 -f 492//492 335//335 337//337 -f 492//492 337//337 491//491 -f 491//491 337//337 390//390 -f 491//491 390//390 489//489 -f 489//489 390//390 497//497 -f 498//498 499//499 500//500 -f 305//305 368//368 367//367 -f 367//367 368//368 501//501 -f 367//367 501//501 391//391 -f 391//391 501//501 498//498 -f 391//391 498//498 390//390 -f 390//390 498//498 500//500 -f 390//390 500//500 497//497 -f 303//303 394//394 368//368 -f 368//368 394//394 393//393 -f 368//368 393//393 501//501 -f 501//501 393//393 418//418 -f 501//501 418//418 498//498 -f 498//498 418//418 502//502 -f 498//498 502//502 499//499 -f 503//503 504//504 505//505 -f 505//505 504//504 420//420 -f 505//505 420//420 506//506 -f 506//506 420//420 392//392 -f 506//506 392//392 369//369 -f 369//369 392//392 394//394 -f 369//369 394//394 302//302 -f 302//302 394//394 303//303 -f 504//504 507//507 420//420 -f 420//420 507//507 508//508 -f 420//420 508//508 419//419 -f 419//419 508//508 509//509 -f 419//419 509//509 418//418 -f 418//418 509//509 510//510 -f 418//418 510//510 502//502 -f 301//301 300//300 369//369 -f 369//369 300//300 332//332 -f 369//369 332//332 506//506 -f 506//506 332//332 334//334 -f 506//506 334//334 505//505 -f 505//505 334//334 395//395 -f 505//505 395//395 503//503 -f 503//503 395//395 511//511 -f 512//512 513//513 514//514 -f 309//309 352//352 397//397 -f 397//397 352//352 515//515 -f 397//397 515//515 396//396 -f 396//396 515//515 512//512 -f 396//396 512//512 395//395 -f 395//395 512//512 514//514 -f 395//395 514//514 511//511 -f 307//307 351//351 352//352 -f 352//352 351//351 399//399 -f 352//352 399//399 515//515 -f 515//515 399//399 421//421 -f 515//515 421//421 512//512 -f 512//512 421//421 516//516 -f 512//512 516//516 513//513 -f 517//517 518//518 519//519 -f 519//519 518//518 423//423 -f 519//519 423//423 520//520 -f 520//520 423//423 398//398 -f 520//520 398//398 350//350 -f 350//350 398//398 351//351 -f 350//350 351//351 328//328 -f 328//328 351//351 306//306 -f 518//518 521//521 423//423 -f 423//423 521//521 522//522 -f 423//423 522//522 422//422 -f 422//422 522//522 523//523 -f 422//422 523//523 421//421 -f 421//421 523//523 524//524 -f 421//421 524//524 516//516 -f 327//327 326//326 350//350 -f 350//350 326//326 329//329 -f 350//350 329//329 520//520 -f 520//520 329//329 331//331 -f 520//520 331//331 519//519 -f 519//519 331//331 400//400 -f 519//519 400//400 517//517 -f 517//517 400//400 428//428 -f 471//471 525//525 468//468 -f 468//468 525//525 526//526 -f 468//468 526//526 459//459 -f 459//459 526//526 527//527 -f 459//459 527//527 460//460 -f 460//460 527//527 528//528 -f 460//460 528//528 464//464 -f 464//464 528//528 529//529 -f 464//464 529//529 465//465 -f 530//530 451//451 450//450 -f 529//529 531//531 465//465 -f 465//465 531//531 532//532 -f 465//465 532//532 466//466 -f 466//466 532//532 533//533 -f 466//466 533//533 467//467 -f 467//467 533//533 534//534 -f 467//467 534//534 458//458 -f 458//458 534//534 535//535 -f 458//458 535//535 455//455 -f 455//455 535//535 536//536 -f 455//455 536//536 456//456 -f 456//456 536//536 537//537 -f 456//456 537//537 453//453 -f 453//453 537//537 538//538 -f 453//453 538//538 445//445 -f 445//445 538//538 539//539 -f 445//445 539//539 446//446 -f 446//446 539//539 540//540 -f 446//446 540//540 449//449 -f 449//449 540//540 541//541 -f 449//449 541//541 450//450 -f 450//450 541//541 542//542 -f 450//450 542//542 530//530 -f 530//530 543//543 451//451 -f 451//451 543//543 544//544 -f 451//451 544//544 452//452 -f 452//452 544//544 545//545 -f 452//452 545//545 444//444 -f 444//444 545//545 546//546 -f 444//444 546//546 441//441 -f 441//441 546//546 547//547 -f 441//441 547//547 442//442 -f 442//442 547//547 548//548 -f 442//442 548//548 439//439 -f 439//439 548//548 549//549 -f 439//439 549//549 430//430 -f 430//430 549//549 550//550 -f 430//430 550//550 431//431 -f 431//431 550//550 551//551 -f 431//431 551//551 435//435 -f 435//435 551//551 552//552 -f 435//435 552//552 436//436 -f 436//436 552//552 553//553 -f 436//436 553//553 437//437 -f 553//553 554//554 437//437 -f 437//437 554//554 555//555 -f 437//437 555//555 438//438 -f 438//438 555//555 556//556 -f 438//438 556//556 429//429 -f 429//429 556//556 557//557 -f 429//429 557//557 425//425 -f 425//425 557//557 558//558 -f 425//425 558//558 426//426 -f 426//426 558//558 559//559 -f 426//426 559//559 428//428 -f 428//428 559//559 560//560 -f 428//428 560//560 517//517 -f 517//517 560//560 561//561 -f 517//517 561//561 518//518 -f 561//561 562//562 518//518 -f 518//518 562//562 563//563 -f 518//518 563//563 521//521 -f 521//521 563//563 564//564 -f 521//521 564//564 522//522 -f 522//522 564//564 565//565 -f 522//522 565//565 523//523 -f 565//565 566//566 523//523 -f 523//523 566//566 567//567 -f 523//523 567//567 524//524 -f 524//524 567//567 568//568 -f 524//524 568//568 516//516 -f 516//516 568//568 513//513 -f 513//513 568//568 569//569 -f 513//513 569//569 514//514 -f 514//514 569//569 570//570 -f 514//514 570//570 511//511 -f 511//511 570//570 571//571 -f 511//511 571//571 503//503 -f 503//503 571//571 572//572 -f 503//503 572//572 504//504 -f 572//572 573//573 504//504 -f 504//504 573//573 574//574 -f 504//504 574//574 507//507 -f 507//507 574//574 575//575 -f 507//507 575//575 508//508 -f 508//508 575//575 576//576 -f 508//508 576//576 509//509 -f 576//576 577//577 509//509 -f 509//509 577//577 578//578 -f 509//509 578//578 510//510 -f 510//510 578//578 579//579 -f 510//510 579//579 502//502 -f 502//502 579//579 580//580 -f 502//502 580//580 499//499 -f 499//499 580//580 581//581 -f 499//499 581//581 500//500 -f 500//500 581//581 582//582 -f 500//500 582//582 497//497 -f 497//497 582//582 583//583 -f 497//497 583//583 489//489 -f 489//489 583//583 584//584 -f 489//489 584//584 490//490 -f 490//490 584//584 585//585 -f 490//490 585//585 493//493 -f 493//493 585//585 586//586 -f 493//493 586//586 494//494 -f 494//494 586//586 587//587 -f 494//494 587//587 495//495 -f 587//587 588//588 495//495 -f 495//495 588//588 589//589 -f 495//495 589//589 496//496 -f 496//496 589//589 590//590 -f 496//496 590//590 488//488 -f 488//488 590//590 591//591 -f 488//488 591//591 485//485 -f 485//485 591//591 592//592 -f 485//485 592//592 486//486 -f 486//486 592//592 593//593 -f 486//486 593//593 483//483 -f 593//593 594//594 483//483 -f 483//483 594//594 595//595 -f 483//483 595//595 474//474 -f 474//474 595//595 596//596 -f 474//474 596//596 475//475 -f 475//475 596//596 597//597 -f 475//475 597//597 479//479 -f 479//479 597//597 598//598 -f 479//479 598//598 480//480 -f 480//480 598//598 599//599 -f 480//480 599//599 481//481 -f 481//481 599//599 600//600 -f 481//481 600//600 482//482 -f 482//482 600//600 601//601 -f 482//482 601//601 473//473 -f 473//473 601//601 602//602 -f 473//473 602//602 470//470 -f 470//470 602//602 603//603 -f 470//470 603//603 471//471 -f 471//471 603//603 604//604 -f 471//471 604//604 525//525 -f 605//605 606//606 607//607 -f 608//608 609//609 610//610 -f 611//611 612//612 613//613 -f 614//614 615//615 616//616 -f 617//617 618//618 619//619 -f 620//620 621//621 622//622 -f 623//623 624//624 625//625 -f 626//626 627//627 628//628 -f 629//629 630//630 631//631 -f 621//621 632//632 633//633 -f 624//624 634//634 635//635 -f 627//627 636//636 637//637 -f 630//630 638//638 639//639 -f 570//570 569//569 640//640 -f 558//558 557//557 641//641 -f 641//641 557//557 642//642 -f 555//555 554//554 638//638 -f 554//554 553//553 638//638 -f 638//638 553//553 552//552 -f 638//638 552//552 639//639 -f 639//639 552//552 551//551 -f 639//639 551//551 643//643 -f 643//643 551//551 550//550 -f 643//643 550//550 644//644 -f 644//644 550//550 549//549 -f 644//644 549//549 645//645 -f 645//645 549//549 548//548 -f 548//548 547//547 645//645 -f 645//645 547//547 546//546 -f 645//645 546//546 646//646 -f 646//646 546//546 545//545 -f 646//646 545//545 647//647 -f 647//647 545//545 544//544 -f 647//647 544//544 648//648 -f 648//648 544//544 543//543 -f 543//543 530//530 648//648 -f 648//648 530//530 542//542 -f 648//648 542//542 649//649 -f 540//540 539//539 636//636 -f 539//539 538//538 636//636 -f 636//636 538//538 537//537 -f 636//636 537//537 637//637 -f 637//637 537//537 536//536 -f 637//637 536//536 650//650 -f 650//650 536//536 535//535 -f 650//650 535//535 651//651 -f 651//651 535//535 534//534 -f 651//651 534//534 652//652 -f 652//652 534//534 533//533 -f 533//533 532//532 652//652 -f 652//652 532//532 531//531 -f 652//652 531//531 653//653 -f 653//653 531//531 529//529 -f 653//653 529//529 654//654 -f 654//654 529//529 528//528 -f 654//654 528//528 655//655 -f 655//655 528//528 527//527 -f 527//527 526//526 655//655 -f 655//655 526//526 525//525 -f 655//655 525//525 656//656 -f 603//603 602//602 634//634 -f 602//602 601//601 634//634 -f 634//634 601//601 600//600 -f 634//634 600//600 635//635 -f 635//635 600//600 599//599 -f 635//635 599//599 657//657 -f 657//657 599//599 598//598 -f 657//657 598//598 658//658 -f 658//658 598//598 597//597 -f 658//658 597//597 659//659 -f 659//659 597//597 596//596 -f 596//596 595//595 659//659 -f 659//659 595//595 594//594 -f 659//659 594//594 660//660 -f 660//660 594//594 593//593 -f 660//660 593//593 661//661 -f 661//661 593//593 592//592 -f 661//661 592//592 662//662 -f 662//662 592//592 591//591 -f 591//591 590//590 662//662 -f 662//662 590//590 589//589 -f 662//662 589//589 663//663 -f 587//587 586//586 632//632 -f 586//586 585//585 632//632 -f 632//632 585//585 584//584 -f 632//632 584//584 633//633 -f 633//633 584//584 583//583 -f 633//633 583//583 664//664 -f 664//664 583//583 582//582 -f 664//664 582//582 665//665 -f 665//665 582//582 581//581 -f 665//665 581//581 666//666 -f 666//666 581//581 580//580 -f 580//580 579//579 666//666 -f 666//666 579//579 578//578 -f 666//666 578//578 667//667 -f 667//667 578//578 577//577 -f 667//667 577//577 668//668 -f 668//668 577//577 576//576 -f 668//668 576//576 669//669 -f 669//669 576//576 575//575 -f 575//575 574//574 669//669 -f 669//669 574//574 573//573 -f 669//669 573//573 670//670 -f 570//570 640//640 571//571 -f 564//564 671//671 565//565 -f 565//565 671//671 672//672 -f 565//565 672//672 566//566 -f 564//564 563//563 671//671 -f 671//671 563//563 562//562 -f 671//671 562//562 673//673 -f 673//673 562//562 561//561 -f 673//673 561//561 674//674 -f 674//674 561//561 560//560 -f 674//674 560//560 641//641 -f 641//641 560//560 559//559 -f 641//641 559//559 558//558 -f 642//642 675//675 676//676 -f 630//630 639//639 631//631 -f 631//631 639//639 643//643 -f 631//631 643//643 677//677 -f 677//677 643//643 644//644 -f 677//677 644//644 678//678 -f 678//678 644//644 645//645 -f 678//678 645//645 679//679 -f 679//679 645//645 646//646 -f 679//679 646//646 680//680 -f 680//680 646//646 647//647 -f 680//680 647//647 681//681 -f 681//681 647//647 648//648 -f 681//681 648//648 682//682 -f 682//682 648//648 649//649 -f 682//682 649//649 683//683 -f 627//627 637//637 628//628 -f 628//628 637//637 650//650 -f 628//628 650//650 684//684 -f 684//684 650//650 651//651 -f 684//684 651//651 685//685 -f 685//685 651//651 652//652 -f 685//685 652//652 686//686 -f 686//686 652//652 653//653 -f 686//686 653//653 687//687 -f 687//687 653//653 654//654 -f 687//687 654//654 688//688 -f 688//688 654//654 655//655 -f 688//688 655//655 689//689 -f 689//689 655//655 656//656 -f 689//689 656//656 690//690 -f 624//624 635//635 625//625 -f 625//625 635//635 657//657 -f 625//625 657//657 691//691 -f 691//691 657//657 658//658 -f 691//691 658//658 692//692 -f 692//692 658//658 659//659 -f 692//692 659//659 693//693 -f 693//693 659//659 660//660 -f 693//693 660//660 694//694 -f 694//694 660//660 661//661 -f 694//694 661//661 695//695 -f 695//695 661//661 662//662 -f 695//695 662//662 696//696 -f 696//696 662//662 663//663 -f 696//696 663//663 697//697 -f 621//621 633//633 622//622 -f 622//622 633//633 664//664 -f 622//622 664//664 698//698 -f 698//698 664//664 665//665 -f 698//698 665//665 699//699 -f 699//699 665//665 666//666 -f 699//699 666//666 700//700 -f 700//700 666//666 667//667 -f 700//700 667//667 701//701 -f 701//701 667//667 668//668 -f 701//701 668//668 702//702 -f 702//702 668//668 669//669 -f 702//702 669//669 703//703 -f 703//703 669//669 670//670 -f 703//703 670//670 704//704 -f 642//642 676//676 641//641 -f 641//641 676//676 705//705 -f 641//641 705//705 674//674 -f 674//674 705//705 706//706 -f 674//674 706//706 673//673 -f 673//673 706//706 707//707 -f 673//673 707//707 671//671 -f 671//671 707//707 708//708 -f 671//671 708//708 672//672 -f 675//675 709//709 710//710 -f 629//629 631//631 711//711 -f 711//711 631//631 677//677 -f 711//711 677//677 712//712 -f 712//712 677//677 678//678 -f 712//712 678//678 713//713 -f 713//713 678//678 679//679 -f 713//713 679//679 714//714 -f 714//714 679//679 680//680 -f 714//714 680//680 715//715 -f 715//715 680//680 681//681 -f 715//715 681//681 716//716 -f 716//716 681//681 682//682 -f 716//716 682//682 717//717 -f 717//717 682//682 683//683 -f 717//717 683//683 619//619 -f 626//626 628//628 718//718 -f 718//718 628//628 684//684 -f 718//718 684//684 719//719 -f 719//719 684//684 685//685 -f 719//719 685//685 720//720 -f 720//720 685//685 686//686 -f 720//720 686//686 721//721 -f 721//721 686//686 687//687 -f 721//721 687//687 722//722 -f 722//722 687//687 688//688 -f 722//722 688//688 723//723 -f 723//723 688//688 689//689 -f 723//723 689//689 724//724 -f 724//724 689//689 690//690 -f 724//724 690//690 616//616 -f 623//623 625//625 725//725 -f 725//725 625//625 691//691 -f 725//725 691//691 726//726 -f 726//726 691//691 692//692 -f 726//726 692//692 727//727 -f 727//727 692//692 693//693 -f 727//727 693//693 728//728 -f 728//728 693//693 694//694 -f 728//728 694//694 729//729 -f 729//729 694//694 695//695 -f 729//729 695//695 730//730 -f 730//730 695//695 696//696 -f 730//730 696//696 731//731 -f 731//731 696//696 697//697 -f 731//731 697//697 613//613 -f 620//620 622//622 732//732 -f 732//732 622//622 698//698 -f 732//732 698//698 733//733 -f 733//733 698//698 699//699 -f 733//733 699//699 734//734 -f 734//734 699//699 700//700 -f 734//734 700//700 735//735 -f 735//735 700//700 701//701 -f 735//735 701//701 736//736 -f 736//736 701//701 702//702 -f 736//736 702//702 737//737 -f 737//737 702//702 703//703 -f 737//737 703//703 738//738 -f 738//738 703//703 704//704 -f 738//738 704//704 610//610 -f 569//569 568//568 640//640 -f 640//640 568//568 739//739 -f 640//640 739//739 740//740 -f 740//740 739//739 741//741 -f 740//740 741//741 742//742 -f 742//742 741//741 607//607 -f 675//675 710//710 676//676 -f 676//676 710//710 743//743 -f 676//676 743//743 705//705 -f 705//705 743//743 744//744 -f 705//705 744//744 706//706 -f 706//706 744//744 745//745 -f 706//706 745//745 707//707 -f 707//707 745//745 746//746 -f 707//707 746//746 708//708 -f 747//747 710//710 748//748 -f 748//748 710//710 709//709 -f 748//748 709//709 749//749 -f 750//750 749//749 751//751 -f 751//751 749//749 709//709 -f 751//751 709//709 752//752 -f 752//752 709//709 675//675 -f 752//752 675//675 753//753 -f 753//753 675//675 642//642 -f 753//753 642//642 556//556 -f 556//556 642//642 557//557 -f 556//556 555//555 753//753 -f 753//753 555//555 638//638 -f 753//753 638//638 752//752 -f 752//752 638//638 630//630 -f 752//752 630//630 751//751 -f 751//751 630//630 629//629 -f 751//751 629//629 750//750 -f 750//750 629//629 754//754 -f 755//755 756//756 713//713 -f 713//713 756//756 757//757 -f 713//713 757//757 712//712 -f 712//712 757//757 758//758 -f 712//712 758//758 711//711 -f 711//711 758//758 759//759 -f 711//711 759//759 629//629 -f 629//629 759//759 760//760 -f 629//629 760//760 754//754 -f 755//755 713//713 761//761 -f 761//761 713//713 714//714 -f 761//761 714//714 762//762 -f 762//762 714//714 715//715 -f 762//762 715//715 763//763 -f 763//763 715//715 716//716 -f 763//763 716//716 764//764 -f 764//764 716//716 717//717 -f 764//764 717//717 765//765 -f 619//619 618//618 717//717 -f 717//717 618//618 766//766 -f 717//717 766//766 765//765 -f 767//767 617//617 768//768 -f 768//768 617//617 619//619 -f 768//768 619//619 769//769 -f 769//769 619//619 683//683 -f 769//769 683//683 770//770 -f 770//770 683//683 649//649 -f 770//770 649//649 541//541 -f 541//541 649//649 542//542 -f 541//541 540//540 770//770 -f 770//770 540//540 636//636 -f 770//770 636//636 769//769 -f 769//769 636//636 627//627 -f 769//769 627//627 768//768 -f 768//768 627//627 626//626 -f 768//768 626//626 767//767 -f 767//767 626//626 771//771 -f 772//772 773//773 720//720 -f 720//720 773//773 774//774 -f 720//720 774//774 719//719 -f 719//719 774//774 775//775 -f 719//719 775//775 718//718 -f 718//718 775//775 776//776 -f 718//718 776//776 626//626 -f 626//626 776//776 777//777 -f 626//626 777//777 771//771 -f 772//772 720//720 778//778 -f 778//778 720//720 721//721 -f 778//778 721//721 779//779 -f 779//779 721//721 722//722 -f 779//779 722//722 780//780 -f 780//780 722//722 723//723 -f 780//780 723//723 781//781 -f 781//781 723//723 724//724 -f 781//781 724//724 782//782 -f 616//616 615//615 724//724 -f 724//724 615//615 783//783 -f 724//724 783//783 782//782 -f 784//784 614//614 785//785 -f 785//785 614//614 616//616 -f 785//785 616//616 786//786 -f 786//786 616//616 690//690 -f 786//786 690//690 787//787 -f 787//787 690//690 656//656 -f 787//787 656//656 604//604 -f 604//604 656//656 525//525 -f 604//604 603//603 787//787 -f 787//787 603//603 634//634 -f 787//787 634//634 786//786 -f 786//786 634//634 624//624 -f 786//786 624//624 785//785 -f 785//785 624//624 623//623 -f 785//785 623//623 784//784 -f 784//784 623//623 788//788 -f 789//789 790//790 727//727 -f 727//727 790//790 791//791 -f 727//727 791//791 726//726 -f 726//726 791//791 792//792 -f 726//726 792//792 725//725 -f 725//725 792//792 793//793 -f 725//725 793//793 623//623 -f 623//623 793//793 794//794 -f 623//623 794//794 788//788 -f 789//789 727//727 795//795 -f 795//795 727//727 728//728 -f 795//795 728//728 796//796 -f 796//796 728//728 729//729 -f 796//796 729//729 797//797 -f 797//797 729//729 730//730 -f 797//797 730//730 798//798 -f 798//798 730//730 731//731 -f 798//798 731//731 799//799 -f 613//613 612//612 731//731 -f 731//731 612//612 800//800 -f 731//731 800//800 799//799 -f 801//801 611//611 802//802 -f 802//802 611//611 613//613 -f 802//802 613//613 803//803 -f 803//803 613//613 697//697 -f 803//803 697//697 804//804 -f 804//804 697//697 663//663 -f 804//804 663//663 588//588 -f 588//588 663//663 589//589 -f 588//588 587//587 804//804 -f 804//804 587//587 632//632 -f 804//804 632//632 803//803 -f 803//803 632//632 621//621 -f 803//803 621//621 802//802 -f 802//802 621//621 620//620 -f 802//802 620//620 801//801 -f 801//801 620//620 805//805 -f 806//806 807//807 734//734 -f 734//734 807//807 808//808 -f 734//734 808//808 733//733 -f 733//733 808//808 809//809 -f 733//733 809//809 732//732 -f 732//732 809//809 810//810 -f 732//732 810//810 620//620 -f 620//620 810//810 811//811 -f 620//620 811//811 805//805 -f 806//806 734//734 812//812 -f 812//812 734//734 735//735 -f 812//812 735//735 813//813 -f 813//813 735//735 736//736 -f 813//813 736//736 814//814 -f 814//814 736//736 737//737 -f 814//814 737//737 815//815 -f 815//815 737//737 738//738 -f 815//815 738//738 816//816 -f 610//610 609//609 738//738 -f 738//738 609//609 817//817 -f 738//738 817//817 816//816 -f 818//818 608//608 819//819 -f 819//819 608//608 610//610 -f 819//819 610//610 820//820 -f 820//820 610//610 704//704 -f 820//820 704//704 821//821 -f 821//821 704//704 670//670 -f 821//821 670//670 572//572 -f 572//572 670//670 573//573 -f 572//572 571//571 821//821 -f 821//821 571//571 640//640 -f 821//821 640//640 820//820 -f 820//820 640//640 740//740 -f 820//820 740//740 819//819 -f 819//819 740//740 742//742 -f 819//819 742//742 818//818 -f 818//818 742//742 822//822 -f 607//607 606//606 742//742 -f 742//742 606//606 823//823 -f 742//742 823//823 822//822 -f 824//824 605//605 825//825 -f 825//825 605//605 607//607 -f 825//825 607//607 826//826 -f 826//826 607//607 741//741 -f 826//826 741//741 827//827 -f 827//827 741//741 739//739 -f 827//827 739//739 567//567 -f 567//567 739//739 568//568 -f 567//567 566//566 827//827 -f 827//827 566//566 672//672 -f 827//827 672//672 826//826 -f 826//826 672//672 708//708 -f 826//826 708//708 825//825 -f 825//825 708//708 746//746 -f 825//825 746//746 824//824 -f 824//824 746//746 828//828 -f 747//747 829//829 710//710 -f 710//710 829//829 830//830 -f 710//710 830//830 743//743 -f 743//743 830//830 831//831 -f 743//743 831//831 744//744 -f 744//744 831//831 832//832 -f 744//744 832//832 745//745 -f 745//745 832//832 833//833 -f 745//745 833//833 746//746 -f 746//746 833//833 834//834 -f 746//746 834//834 828//828 -f 835//835 750//750 836//836 -f 836//836 750//750 754//754 -f 836//836 754//754 837//837 -f 837//837 754//754 760//760 -f 837//837 760//760 838//838 -f 838//838 760//760 759//759 -f 838//838 759//759 839//839 -f 839//839 759//759 758//758 -f 839//839 758//758 840//840 -f 771//771 841//841 842//842 -f 758//758 757//757 840//840 -f 840//840 757//757 756//756 -f 840//840 756//756 843//843 -f 843//843 756//756 755//755 -f 843//843 755//755 844//844 -f 844//844 755//755 761//761 -f 844//844 761//761 845//845 -f 845//845 761//761 762//762 -f 845//845 762//762 846//846 -f 846//846 762//762 763//763 -f 846//846 763//763 847//847 -f 847//847 763//763 764//764 -f 847//847 764//764 848//848 -f 848//848 764//764 765//765 -f 848//848 765//765 849//849 -f 849//849 765//765 766//766 -f 849//849 766//766 850//850 -f 850//850 766//766 618//618 -f 850//850 618//618 851//851 -f 851//851 618//618 617//617 -f 851//851 617//617 842//842 -f 842//842 617//617 767//767 -f 842//842 767//767 771//771 -f 771//771 777//777 841//841 -f 841//841 777//777 776//776 -f 841//841 776//776 852//852 -f 852//852 776//776 775//775 -f 852//852 775//775 853//853 -f 853//853 775//775 774//774 -f 853//853 774//774 854//854 -f 854//854 774//774 773//773 -f 854//854 773//773 855//855 -f 855//855 773//773 772//772 -f 855//855 772//772 856//856 -f 856//856 772//772 778//778 -f 856//856 778//778 857//857 -f 857//857 778//778 779//779 -f 857//857 779//779 858//858 -f 858//858 779//779 780//780 -f 858//858 780//780 859//859 -f 859//859 780//780 781//781 -f 859//859 781//781 860//860 -f 860//860 781//781 782//782 -f 860//860 782//782 861//861 -f 782//782 783//783 861//861 -f 861//861 783//783 615//615 -f 861//861 615//615 862//862 -f 862//862 615//615 614//614 -f 862//862 614//614 863//863 -f 863//863 614//614 784//784 -f 863//863 784//784 864//864 -f 864//864 784//784 788//788 -f 864//864 788//788 865//865 -f 865//865 788//788 794//794 -f 865//865 794//794 866//866 -f 866//866 794//794 793//793 -f 866//866 793//793 867//867 -f 867//867 793//793 792//792 -f 867//867 792//792 868//868 -f 792//792 791//791 868//868 -f 868//868 791//791 790//790 -f 868//868 790//790 869//869 -f 869//869 790//790 789//789 -f 869//869 789//789 870//870 -f 870//870 789//789 795//795 -f 870//870 795//795 871//871 -f 795//795 796//796 871//871 -f 871//871 796//796 797//797 -f 871//871 797//797 872//872 -f 872//872 797//797 798//798 -f 872//872 798//798 873//873 -f 873//873 798//798 874//874 -f 874//874 798//798 799//799 -f 874//874 799//799 875//875 -f 875//875 799//799 800//800 -f 875//875 800//800 876//876 -f 876//876 800//800 612//612 -f 876//876 612//612 877//877 -f 877//877 612//612 611//611 -f 877//877 611//611 878//878 -f 611//611 801//801 878//878 -f 878//878 801//801 805//805 -f 878//878 805//805 879//879 -f 879//879 805//805 811//811 -f 879//879 811//811 880//880 -f 880//880 811//811 810//810 -f 880//880 810//810 881//881 -f 810//810 809//809 881//881 -f 881//881 809//809 808//808 -f 881//881 808//808 882//882 -f 882//882 808//808 807//807 -f 882//882 807//807 883//883 -f 883//883 807//807 806//806 -f 883//883 806//806 884//884 -f 884//884 806//806 812//812 -f 884//884 812//812 885//885 -f 885//885 812//812 813//813 -f 885//885 813//813 886//886 -f 886//886 813//813 814//814 -f 886//886 814//814 887//887 -f 887//887 814//814 815//815 -f 887//887 815//815 888//888 -f 888//888 815//815 816//816 -f 888//888 816//816 889//889 -f 889//889 816//816 817//817 -f 889//889 817//817 890//890 -f 890//890 817//817 609//609 -f 890//890 609//609 891//891 -f 609//609 608//608 891//891 -f 891//891 608//608 818//818 -f 891//891 818//818 892//892 -f 892//892 818//818 822//822 -f 892//892 822//822 893//893 -f 893//893 822//822 823//823 -f 893//893 823//823 894//894 -f 894//894 823//823 606//606 -f 894//894 606//606 895//895 -f 895//895 606//606 605//605 -f 895//895 605//605 896//896 -f 605//605 824//824 896//896 -f 896//896 824//824 828//828 -f 896//896 828//828 897//897 -f 897//897 828//828 834//834 -f 897//897 834//834 898//898 -f 898//898 834//834 833//833 -f 898//898 833//833 899//899 -f 899//899 833//833 832//832 -f 899//899 832//832 900//900 -f 900//900 832//832 831//831 -f 900//900 831//831 901//901 -f 901//901 831//831 830//830 -f 901//901 830//830 902//902 -f 902//902 830//830 829//829 -f 902//902 829//829 903//903 -f 903//903 829//829 747//747 -f 903//903 747//747 904//904 -f 904//904 747//747 748//748 -f 904//904 748//748 835//835 -f 835//835 748//748 749//749 -f 835//835 749//749 750//750 -f 905//905 906//906 907//907 -f 908//908 909//909 910//910 -f 911//911 912//912 913//913 -f 914//914 915//915 916//916 -f 917//917 918//918 919//919 -f 920//920 921//921 922//922 -f 923//923 924//924 925//925 -f 897//897 898//898 905//905 -f 895//895 896//896 926//926 -f 893//893 894//894 927//927 -f 887//887 888//888 908//908 -f 885//885 886//886 928//928 -f 883//883 884//884 929//929 -f 877//877 878//878 911//911 -f 875//875 876//876 930//930 -f 873//873 874//874 931//931 -f 867//867 868//868 914//914 -f 865//865 866//866 932//932 -f 863//863 864//864 933//933 -f 857//857 858//858 917//917 -f 855//855 856//856 934//934 -f 853//853 854//854 935//935 -f 849//849 850//850 920//920 -f 847//847 848//848 936//936 -f 845//845 846//846 937//937 -f 837//837 838//838 923//923 -f 835//835 836//836 938//938 -f 903//903 904//904 939//939 -f 901//901 902//902 940//940 -f 940//940 902//902 903//903 -f 923//923 838//838 924//924 -f 924//924 838//838 839//839 -f 924//924 839//839 840//840 -f 843//843 844//844 941//941 -f 941//941 844//844 845//845 -f 920//920 850//850 921//921 -f 921//921 850//850 851//851 -f 921//921 851//851 842//842 -f 841//841 852//852 942//942 -f 942//942 852//852 853//853 -f 917//917 858//858 918//918 -f 918//918 858//858 859//859 -f 918//918 859//859 860//860 -f 861//861 862//862 943//943 -f 943//943 862//862 863//863 -f 914//914 868//868 915//915 -f 915//915 868//868 869//869 -f 915//915 869//869 870//870 -f 871//871 872//872 944//944 -f 944//944 872//872 873//873 -f 911//911 878//878 912//912 -f 912//912 878//878 879//879 -f 912//912 879//879 880//880 -f 881//881 882//882 945//945 -f 945//945 882//882 883//883 -f 908//908 888//888 909//909 -f 909//909 888//888 889//889 -f 909//909 889//889 890//890 -f 891//891 892//892 946//946 -f 946//946 892//892 893//893 -f 905//905 898//898 906//906 -f 906//906 898//898 899//899 -f 906//906 899//899 900//900 -f 947//947 948//948 939//939 -f 949//949 925//925 950//950 -f 950//950 925//925 924//924 -f 950//950 924//924 951//951 -f 951//951 924//924 840//840 -f 951//951 840//840 843//843 -f 952//952 953//953 937//937 -f 954//954 922//922 955//955 -f 955//955 922//922 921//921 -f 955//955 921//921 956//956 -f 956//956 921//921 842//842 -f 956//956 842//842 841//841 -f 957//957 958//958 935//935 -f 959//959 919//919 960//960 -f 960//960 919//919 918//918 -f 960//960 918//918 961//961 -f 961//961 918//918 860//860 -f 961//961 860//860 861//861 -f 962//962 963//963 933//933 -f 964//964 916//916 965//965 -f 965//965 916//916 915//915 -f 965//965 915//915 966//966 -f 966//966 915//915 870//870 -f 966//966 870//870 871//871 -f 967//967 968//968 931//931 -f 969//969 913//913 970//970 -f 970//970 913//913 912//912 -f 970//970 912//912 971//971 -f 971//971 912//912 880//880 -f 971//971 880//880 881//881 -f 972//972 973//973 929//929 -f 974//974 910//910 975//975 -f 975//975 910//910 909//909 -f 975//975 909//909 976//976 -f 976//976 909//909 890//890 -f 976//976 890//890 891//891 -f 977//977 978//978 927//927 -f 979//979 907//907 980//980 -f 980//980 907//907 906//906 -f 980//980 906//906 981//981 -f 981//981 906//906 900//900 -f 981//981 900//900 901//901 -f 982//982 948//948 983//983 -f 983//983 948//948 947//947 -f 983//983 947//947 984//984 -f 985//985 953//953 986//986 -f 986//986 953//953 952//952 -f 986//986 952//952 987//987 -f 988//988 958//958 989//989 -f 989//989 958//958 957//957 -f 989//989 957//957 990//990 -f 991//991 963//963 992//992 -f 992//992 963//963 962//962 -f 992//992 962//962 993//993 -f 994//994 968//968 995//995 -f 995//995 968//968 967//967 -f 995//995 967//967 996//996 -f 997//997 973//973 998//998 -f 998//998 973//973 972//972 -f 998//998 972//972 999//999 -f 1000//1000 978//978 1001//1001 -f 1001//1001 978//978 977//977 -f 1001//1001 977//977 1002//1002 -f 1003//1003 1004//1004 1005//1005 -f 901//901 940//940 981//981 -f 981//981 940//940 1006//1006 -f 981//981 1006//1006 980//980 -f 980//980 1006//1006 1003//1003 -f 980//980 1003//1003 979//979 -f 979//979 1003//1003 1005//1005 -f 979//979 1005//1005 1007//1007 -f 903//903 939//939 940//940 -f 940//940 939//939 948//948 -f 940//940 948//948 1006//1006 -f 1006//1006 948//948 982//982 -f 1006//1006 982//982 1003//1003 -f 1003//1003 982//982 1008//1008 -f 1003//1003 1008//1008 1004//1004 -f 1009//1009 1010//1010 1011//1011 -f 1011//1011 1010//1010 984//984 -f 1011//1011 984//984 1012//1012 -f 1012//1012 984//984 947//947 -f 1012//1012 947//947 938//938 -f 938//938 947//947 939//939 -f 938//938 939//939 835//835 -f 835//835 939//939 904//904 -f 1010//1010 1013//1013 984//984 -f 984//984 1013//1013 1014//1014 -f 984//984 1014//1014 983//983 -f 983//983 1014//1014 1015//1015 -f 983//983 1015//1015 982//982 -f 982//982 1015//1015 1016//1016 -f 982//982 1016//1016 1008//1008 -f 836//836 837//837 938//938 -f 938//938 837//837 923//923 -f 938//938 923//923 1012//1012 -f 1012//1012 923//923 925//925 -f 1012//1012 925//925 1011//1011 -f 1011//1011 925//925 949//949 -f 1011//1011 949//949 1009//1009 -f 1009//1009 949//949 1017//1017 -f 1018//1018 1019//1019 1020//1020 -f 843//843 941//941 951//951 -f 951//951 941//941 1021//1021 -f 951//951 1021//1021 950//950 -f 950//950 1021//1021 1018//1018 -f 950//950 1018//1018 949//949 -f 949//949 1018//1018 1020//1020 -f 949//949 1020//1020 1017//1017 -f 845//845 937//937 941//941 -f 941//941 937//937 953//953 -f 941//941 953//953 1021//1021 -f 1021//1021 953//953 985//985 -f 1021//1021 985//985 1018//1018 -f 1018//1018 985//985 1022//1022 -f 1018//1018 1022//1022 1019//1019 -f 1023//1023 1024//1024 1025//1025 -f 1025//1025 1024//1024 987//987 -f 1025//1025 987//987 1026//1026 -f 1026//1026 987//987 952//952 -f 1026//1026 952//952 936//936 -f 936//936 952//952 937//937 -f 936//936 937//937 847//847 -f 847//847 937//937 846//846 -f 1024//1024 1027//1027 987//987 -f 987//987 1027//1027 1028//1028 -f 987//987 1028//1028 986//986 -f 986//986 1028//1028 1029//1029 -f 986//986 1029//1029 985//985 -f 985//985 1029//1029 1030//1030 -f 985//985 1030//1030 1022//1022 -f 848//848 849//849 936//936 -f 936//936 849//849 920//920 -f 936//936 920//920 1026//1026 -f 1026//1026 920//920 922//922 -f 1026//1026 922//922 1025//1025 -f 1025//1025 922//922 954//954 -f 1025//1025 954//954 1023//1023 -f 1023//1023 954//954 1031//1031 -f 1032//1032 1033//1033 1034//1034 -f 841//841 942//942 956//956 -f 956//956 942//942 1035//1035 -f 956//956 1035//1035 955//955 -f 955//955 1035//1035 1032//1032 -f 955//955 1032//1032 954//954 -f 954//954 1032//1032 1034//1034 -f 954//954 1034//1034 1031//1031 -f 853//853 935//935 942//942 -f 942//942 935//935 958//958 -f 942//942 958//958 1035//1035 -f 1035//1035 958//958 988//988 -f 1035//1035 988//988 1032//1032 -f 1032//1032 988//988 1036//1036 -f 1032//1032 1036//1036 1033//1033 -f 1037//1037 1038//1038 1039//1039 -f 1039//1039 1038//1038 990//990 -f 1039//1039 990//990 1040//1040 -f 1040//1040 990//990 957//957 -f 1040//1040 957//957 934//934 -f 934//934 957//957 935//935 -f 934//934 935//935 855//855 -f 855//855 935//935 854//854 -f 1038//1038 1041//1041 990//990 -f 990//990 1041//1041 1042//1042 -f 990//990 1042//1042 989//989 -f 989//989 1042//1042 1043//1043 -f 989//989 1043//1043 988//988 -f 988//988 1043//1043 1044//1044 -f 988//988 1044//1044 1036//1036 -f 856//856 857//857 934//934 -f 934//934 857//857 917//917 -f 934//934 917//917 1040//1040 -f 1040//1040 917//917 919//919 -f 1040//1040 919//919 1039//1039 -f 1039//1039 919//919 959//959 -f 1039//1039 959//959 1037//1037 -f 1037//1037 959//959 1045//1045 -f 1046//1046 1047//1047 1048//1048 -f 861//861 943//943 961//961 -f 961//961 943//943 1049//1049 -f 961//961 1049//1049 960//960 -f 960//960 1049//1049 1046//1046 -f 960//960 1046//1046 959//959 -f 959//959 1046//1046 1048//1048 -f 959//959 1048//1048 1045//1045 -f 863//863 933//933 943//943 -f 943//943 933//933 963//963 -f 943//943 963//963 1049//1049 -f 1049//1049 963//963 991//991 -f 1049//1049 991//991 1046//1046 -f 1046//1046 991//991 1050//1050 -f 1046//1046 1050//1050 1047//1047 -f 1051//1051 1052//1052 1053//1053 -f 1053//1053 1052//1052 993//993 -f 1053//1053 993//993 1054//1054 -f 1054//1054 993//993 962//962 -f 1054//1054 962//962 932//932 -f 932//932 962//962 933//933 -f 932//932 933//933 865//865 -f 865//865 933//933 864//864 -f 1052//1052 1055//1055 993//993 -f 993//993 1055//1055 1056//1056 -f 993//993 1056//1056 992//992 -f 992//992 1056//1056 1057//1057 -f 992//992 1057//1057 991//991 -f 991//991 1057//1057 1058//1058 -f 991//991 1058//1058 1050//1050 -f 866//866 867//867 932//932 -f 932//932 867//867 914//914 -f 932//932 914//914 1054//1054 -f 1054//1054 914//914 916//916 -f 1054//1054 916//916 1053//1053 -f 1053//1053 916//916 964//964 -f 1053//1053 964//964 1051//1051 -f 1051//1051 964//964 1059//1059 -f 1060//1060 1061//1061 1062//1062 -f 871//871 944//944 966//966 -f 966//966 944//944 1063//1063 -f 966//966 1063//1063 965//965 -f 965//965 1063//1063 1060//1060 -f 965//965 1060//1060 964//964 -f 964//964 1060//1060 1062//1062 -f 964//964 1062//1062 1059//1059 -f 873//873 931//931 944//944 -f 944//944 931//931 968//968 -f 944//944 968//968 1063//1063 -f 1063//1063 968//968 994//994 -f 1063//1063 994//994 1060//1060 -f 1060//1060 994//994 1064//1064 -f 1060//1060 1064//1064 1061//1061 -f 1065//1065 1066//1066 1067//1067 -f 1067//1067 1066//1066 996//996 -f 1067//1067 996//996 1068//1068 -f 1068//1068 996//996 967//967 -f 1068//1068 967//967 930//930 -f 930//930 967//967 931//931 -f 930//930 931//931 875//875 -f 875//875 931//931 874//874 -f 1066//1066 1069//1069 996//996 -f 996//996 1069//1069 1070//1070 -f 996//996 1070//1070 995//995 -f 995//995 1070//1070 1071//1071 -f 995//995 1071//1071 994//994 -f 994//994 1071//1071 1072//1072 -f 994//994 1072//1072 1064//1064 -f 876//876 877//877 930//930 -f 930//930 877//877 911//911 -f 930//930 911//911 1068//1068 -f 1068//1068 911//911 913//913 -f 1068//1068 913//913 1067//1067 -f 1067//1067 913//913 969//969 -f 1067//1067 969//969 1065//1065 -f 1065//1065 969//969 1073//1073 -f 1074//1074 1075//1075 1076//1076 -f 881//881 945//945 971//971 -f 971//971 945//945 1077//1077 -f 971//971 1077//1077 970//970 -f 970//970 1077//1077 1074//1074 -f 970//970 1074//1074 969//969 -f 969//969 1074//1074 1076//1076 -f 969//969 1076//1076 1073//1073 -f 883//883 929//929 945//945 -f 945//945 929//929 973//973 -f 945//945 973//973 1077//1077 -f 1077//1077 973//973 997//997 -f 1077//1077 997//997 1074//1074 -f 1074//1074 997//997 1078//1078 -f 1074//1074 1078//1078 1075//1075 -f 1079//1079 1080//1080 1081//1081 -f 1081//1081 1080//1080 999//999 -f 1081//1081 999//999 1082//1082 -f 1082//1082 999//999 972//972 -f 1082//1082 972//972 928//928 -f 928//928 972//972 929//929 -f 928//928 929//929 885//885 -f 885//885 929//929 884//884 -f 1080//1080 1083//1083 999//999 -f 999//999 1083//1083 1084//1084 -f 999//999 1084//1084 998//998 -f 998//998 1084//1084 1085//1085 -f 998//998 1085//1085 997//997 -f 997//997 1085//1085 1086//1086 -f 997//997 1086//1086 1078//1078 -f 886//886 887//887 928//928 -f 928//928 887//887 908//908 -f 928//928 908//908 1082//1082 -f 1082//1082 908//908 910//910 -f 1082//1082 910//910 1081//1081 -f 1081//1081 910//910 974//974 -f 1081//1081 974//974 1079//1079 -f 1079//1079 974//974 1087//1087 -f 1088//1088 1089//1089 1090//1090 -f 891//891 946//946 976//976 -f 976//976 946//946 1091//1091 -f 976//976 1091//1091 975//975 -f 975//975 1091//1091 1088//1088 -f 975//975 1088//1088 974//974 -f 974//974 1088//1088 1090//1090 -f 974//974 1090//1090 1087//1087 -f 893//893 927//927 946//946 -f 946//946 927//927 978//978 -f 946//946 978//978 1091//1091 -f 1091//1091 978//978 1000//1000 -f 1091//1091 1000//1000 1088//1088 -f 1088//1088 1000//1000 1092//1092 -f 1088//1088 1092//1092 1089//1089 -f 1093//1093 1094//1094 1095//1095 -f 1095//1095 1094//1094 1002//1002 -f 1095//1095 1002//1002 1096//1096 -f 1096//1096 1002//1002 977//977 -f 1096//1096 977//977 926//926 -f 926//926 977//977 927//927 -f 926//926 927//927 895//895 -f 895//895 927//927 894//894 -f 1094//1094 1097//1097 1002//1002 -f 1002//1002 1097//1097 1098//1098 -f 1002//1002 1098//1098 1001//1001 -f 1001//1001 1098//1098 1099//1099 -f 1001//1001 1099//1099 1000//1000 -f 1000//1000 1099//1099 1100//1100 -f 1000//1000 1100//1100 1092//1092 -f 896//896 897//897 926//926 -f 926//926 897//897 905//905 -f 926//926 905//905 1096//1096 -f 1096//1096 905//905 907//907 -f 1096//1096 907//907 1095//1095 -f 1095//1095 907//907 979//979 -f 1095//1095 979//979 1093//1093 -f 1093//1093 979//979 1007//1007 -f 1057//1057 1101//1101 1058//1058 -f 1058//1058 1101//1101 1102//1102 -f 1058//1058 1102//1102 1050//1050 -f 1050//1050 1102//1102 1103//1103 -f 1050//1050 1103//1103 1047//1047 -f 1047//1047 1103//1103 1104//1104 -f 1047//1047 1104//1104 1048//1048 -f 1048//1048 1104//1104 1105//1105 -f 1048//1048 1105//1105 1045//1045 -f 1045//1045 1105//1105 1106//1106 -f 1045//1045 1106//1106 1037//1037 -f 1037//1037 1106//1106 1107//1107 -f 1037//1037 1107//1107 1038//1038 -f 1107//1107 1108//1108 1038//1038 -f 1038//1038 1108//1108 1109//1109 -f 1038//1038 1109//1109 1041//1041 -f 1041//1041 1109//1109 1110//1110 -f 1041//1041 1110//1110 1042//1042 -f 1042//1042 1110//1110 1111//1111 -f 1042//1042 1111//1111 1043//1043 -f 1111//1111 1112//1112 1043//1043 -f 1043//1043 1112//1112 1113//1113 -f 1043//1043 1113//1113 1044//1044 -f 1044//1044 1113//1113 1114//1114 -f 1044//1044 1114//1114 1036//1036 -f 1036//1036 1114//1114 1115//1115 -f 1036//1036 1115//1115 1033//1033 -f 1033//1033 1115//1115 1116//1116 -f 1033//1033 1116//1116 1034//1034 -f 1034//1034 1116//1116 1117//1117 -f 1034//1034 1117//1117 1031//1031 -f 1031//1031 1117//1117 1118//1118 -f 1031//1031 1118//1118 1023//1023 -f 1023//1023 1118//1118 1119//1119 -f 1023//1023 1119//1119 1024//1024 -f 1119//1119 1120//1120 1024//1024 -f 1024//1024 1120//1120 1121//1121 -f 1024//1024 1121//1121 1027//1027 -f 1027//1027 1121//1121 1122//1122 -f 1027//1027 1122//1122 1028//1028 -f 1028//1028 1122//1122 1123//1123 -f 1028//1028 1123//1123 1029//1029 -f 1123//1123 1124//1124 1029//1029 -f 1029//1029 1124//1124 1125//1125 -f 1029//1029 1125//1125 1030//1030 -f 1030//1030 1125//1125 1126//1126 -f 1030//1030 1126//1126 1022//1022 -f 1022//1022 1126//1126 1127//1127 -f 1022//1022 1127//1127 1019//1019 -f 1019//1019 1127//1127 1128//1128 -f 1019//1019 1128//1128 1020//1020 -f 1020//1020 1128//1128 1129//1129 -f 1020//1020 1129//1129 1017//1017 -f 1017//1017 1129//1129 1130//1130 -f 1017//1017 1130//1130 1009//1009 -f 1009//1009 1130//1130 1131//1131 -f 1009//1009 1131//1131 1010//1010 -f 1131//1131 1132//1132 1010//1010 -f 1010//1010 1132//1132 1133//1133 -f 1010//1010 1133//1133 1013//1013 -f 1013//1013 1133//1133 1134//1134 -f 1013//1013 1134//1134 1014//1014 -f 1014//1014 1134//1134 1135//1135 -f 1014//1014 1135//1135 1015//1015 -f 1135//1135 1136//1136 1015//1015 -f 1015//1015 1136//1136 1137//1137 -f 1015//1015 1137//1137 1016//1016 -f 1016//1016 1137//1137 1138//1138 -f 1016//1016 1138//1138 1008//1008 -f 1008//1008 1138//1138 1139//1139 -f 1008//1008 1139//1139 1004//1004 -f 1004//1004 1139//1139 1140//1140 -f 1004//1004 1140//1140 1005//1005 -f 1005//1005 1140//1140 1141//1141 -f 1005//1005 1141//1141 1007//1007 -f 1007//1007 1141//1141 1142//1142 -f 1007//1007 1142//1142 1093//1093 -f 1093//1093 1142//1142 1143//1143 -f 1093//1093 1143//1143 1094//1094 -f 1143//1143 1144//1144 1094//1094 -f 1094//1094 1144//1144 1145//1145 -f 1094//1094 1145//1145 1097//1097 -f 1097//1097 1145//1145 1146//1146 -f 1097//1097 1146//1146 1098//1098 -f 1098//1098 1146//1146 1147//1147 -f 1098//1098 1147//1147 1099//1099 -f 1147//1147 1148//1148 1099//1099 -f 1099//1099 1148//1148 1149//1149 -f 1099//1099 1149//1149 1100//1100 -f 1100//1100 1149//1149 1150//1150 -f 1100//1100 1150//1150 1092//1092 -f 1092//1092 1150//1150 1151//1151 -f 1092//1092 1151//1151 1089//1089 -f 1089//1089 1151//1151 1152//1152 -f 1089//1089 1152//1152 1090//1090 -f 1090//1090 1152//1152 1153//1153 -f 1090//1090 1153//1153 1087//1087 -f 1087//1087 1153//1153 1154//1154 -f 1087//1087 1154//1154 1079//1079 -f 1079//1079 1154//1154 1155//1155 -f 1079//1079 1155//1155 1080//1080 -f 1155//1155 1156//1156 1080//1080 -f 1080//1080 1156//1156 1157//1157 -f 1080//1080 1157//1157 1083//1083 -f 1083//1083 1157//1157 1158//1158 -f 1083//1083 1158//1158 1084//1084 -f 1084//1084 1158//1158 1159//1159 -f 1084//1084 1159//1159 1085//1085 -f 1159//1159 1160//1160 1085//1085 -f 1085//1085 1160//1160 1161//1161 -f 1085//1085 1161//1161 1086//1086 -f 1086//1086 1161//1161 1162//1162 -f 1086//1086 1162//1162 1078//1078 -f 1078//1078 1162//1162 1163//1163 -f 1078//1078 1163//1163 1075//1075 -f 1075//1075 1163//1163 1164//1164 -f 1075//1075 1164//1164 1076//1076 -f 1076//1076 1164//1164 1165//1165 -f 1076//1076 1165//1165 1073//1073 -f 1073//1073 1165//1165 1166//1166 -f 1073//1073 1166//1166 1065//1065 -f 1065//1065 1166//1166 1167//1167 -f 1065//1065 1167//1167 1066//1066 -f 1167//1167 1168//1168 1066//1066 -f 1066//1066 1168//1168 1169//1169 -f 1066//1066 1169//1169 1069//1069 -f 1069//1069 1169//1169 1170//1170 -f 1069//1069 1170//1170 1070//1070 -f 1070//1070 1170//1170 1171//1171 -f 1070//1070 1171//1171 1071//1071 -f 1171//1171 1172//1172 1071//1071 -f 1071//1071 1172//1172 1173//1173 -f 1071//1071 1173//1173 1072//1072 -f 1072//1072 1173//1173 1174//1174 -f 1072//1072 1174//1174 1064//1064 -f 1064//1064 1174//1174 1175//1175 -f 1064//1064 1175//1175 1061//1061 -f 1061//1061 1175//1175 1176//1176 -f 1061//1061 1176//1176 1062//1062 -f 1062//1062 1176//1176 1177//1177 -f 1062//1062 1177//1177 1059//1059 -f 1059//1059 1177//1177 1178//1178 -f 1059//1059 1178//1178 1051//1051 -f 1051//1051 1178//1178 1179//1179 -f 1051//1051 1179//1179 1052//1052 -f 1179//1179 1180//1180 1052//1052 -f 1052//1052 1180//1180 1181//1181 -f 1052//1052 1181//1181 1055//1055 -f 1055//1055 1181//1181 1182//1182 -f 1055//1055 1182//1182 1056//1056 -f 1056//1056 1182//1182 1183//1183 -f 1056//1056 1183//1183 1057//1057 -f 1057//1057 1183//1183 1184//1184 -f 1057//1057 1184//1184 1101//1101 -f 1141//1141 1185//1185 1186//1186 -f 1141//1141 1140//1140 1185//1185 -f 1185//1185 1140//1140 1139//1139 -f 1185//1185 1139//1139 1187//1187 -f 1187//1187 1139//1139 1138//1138 -f 1187//1187 1138//1138 1188//1188 -f 1138//1138 1137//1137 1188//1188 -f 1188//1188 1137//1137 1136//1136 -f 1188//1188 1136//1136 1189//1189 -f 1189//1189 1136//1136 1135//1135 -f 1189//1189 1135//1135 1190//1190 -f 1190//1190 1135//1135 1134//1134 -f 1129//1129 1191//1191 1192//1192 -f 1134//1134 1133//1133 1190//1190 -f 1190//1190 1133//1133 1132//1132 -f 1190//1190 1132//1132 1193//1193 -f 1193//1193 1132//1132 1131//1131 -f 1193//1193 1131//1131 1192//1192 -f 1192//1192 1131//1131 1130//1130 -f 1192//1192 1130//1130 1129//1129 -f 1129//1129 1128//1128 1191//1191 -f 1191//1191 1128//1128 1127//1127 -f 1191//1191 1127//1127 1194//1194 -f 1194//1194 1127//1127 1126//1126 -f 1194//1194 1126//1126 1195//1195 -f 1126//1126 1125//1125 1195//1195 -f 1195//1195 1125//1125 1124//1124 -f 1195//1195 1124//1124 1196//1196 -f 1196//1196 1124//1124 1123//1123 -f 1196//1196 1123//1123 1197//1197 -f 1197//1197 1123//1123 1122//1122 -f 1117//1117 1198//1198 1199//1199 -f 1122//1122 1121//1121 1197//1197 -f 1197//1197 1121//1121 1120//1120 -f 1197//1197 1120//1120 1200//1200 -f 1200//1200 1120//1120 1119//1119 -f 1200//1200 1119//1119 1199//1199 -f 1199//1199 1119//1119 1118//1118 -f 1199//1199 1118//1118 1117//1117 -f 1117//1117 1116//1116 1198//1198 -f 1198//1198 1116//1116 1115//1115 -f 1198//1198 1115//1115 1201//1201 -f 1201//1201 1115//1115 1114//1114 -f 1201//1201 1114//1114 1202//1202 -f 1114//1114 1113//1113 1202//1202 -f 1202//1202 1113//1113 1112//1112 -f 1202//1202 1112//1112 1203//1203 -f 1203//1203 1112//1112 1111//1111 -f 1203//1203 1111//1111 1204//1204 -f 1204//1204 1111//1111 1110//1110 -f 1105//1105 1205//1205 1206//1206 -f 1110//1110 1109//1109 1204//1204 -f 1204//1204 1109//1109 1108//1108 -f 1204//1204 1108//1108 1207//1207 -f 1207//1207 1108//1108 1107//1107 -f 1207//1207 1107//1107 1206//1206 -f 1206//1206 1107//1107 1106//1106 -f 1206//1206 1106//1106 1105//1105 -f 1105//1105 1104//1104 1205//1205 -f 1205//1205 1104//1104 1103//1103 -f 1205//1205 1103//1103 1208//1208 -f 1208//1208 1103//1103 1102//1102 -f 1208//1208 1102//1102 1209//1209 -f 1102//1102 1101//1101 1209//1209 -f 1209//1209 1101//1101 1184//1184 -f 1209//1209 1184//1184 1210//1210 -f 1210//1210 1184//1184 1183//1183 -f 1210//1210 1183//1183 1211//1211 -f 1211//1211 1183//1183 1182//1182 -f 1177//1177 1212//1212 1213//1213 -f 1182//1182 1181//1181 1211//1211 -f 1211//1211 1181//1181 1180//1180 -f 1211//1211 1180//1180 1214//1214 -f 1214//1214 1180//1180 1179//1179 -f 1214//1214 1179//1179 1213//1213 -f 1213//1213 1179//1179 1178//1178 -f 1213//1213 1178//1178 1177//1177 -f 1177//1177 1176//1176 1212//1212 -f 1212//1212 1176//1176 1175//1175 -f 1212//1212 1175//1175 1215//1215 -f 1215//1215 1175//1175 1174//1174 -f 1215//1215 1174//1174 1216//1216 -f 1174//1174 1173//1173 1216//1216 -f 1216//1216 1173//1173 1172//1172 -f 1216//1216 1172//1172 1217//1217 -f 1217//1217 1172//1172 1171//1171 -f 1217//1217 1171//1171 1218//1218 -f 1218//1218 1171//1171 1170//1170 -f 1165//1165 1219//1219 1220//1220 -f 1170//1170 1169//1169 1218//1218 -f 1218//1218 1169//1169 1168//1168 -f 1218//1218 1168//1168 1221//1221 -f 1221//1221 1168//1168 1167//1167 -f 1221//1221 1167//1167 1220//1220 -f 1220//1220 1167//1167 1166//1166 -f 1220//1220 1166//1166 1165//1165 -f 1165//1165 1164//1164 1219//1219 -f 1219//1219 1164//1164 1163//1163 -f 1219//1219 1163//1163 1222//1222 -f 1222//1222 1163//1163 1162//1162 -f 1222//1222 1162//1162 1223//1223 -f 1162//1162 1161//1161 1223//1223 -f 1223//1223 1161//1161 1160//1160 -f 1223//1223 1160//1160 1224//1224 -f 1224//1224 1160//1160 1159//1159 -f 1224//1224 1159//1159 1225//1225 -f 1225//1225 1159//1159 1158//1158 -f 1153//1153 1226//1226 1227//1227 -f 1158//1158 1157//1157 1225//1225 -f 1225//1225 1157//1157 1156//1156 -f 1225//1225 1156//1156 1228//1228 -f 1228//1228 1156//1156 1155//1155 -f 1228//1228 1155//1155 1227//1227 -f 1227//1227 1155//1155 1154//1154 -f 1227//1227 1154//1154 1153//1153 -f 1153//1153 1152//1152 1226//1226 -f 1226//1226 1152//1152 1151//1151 -f 1226//1226 1151//1151 1229//1229 -f 1229//1229 1151//1151 1150//1150 -f 1229//1229 1150//1150 1230//1230 -f 1150//1150 1149//1149 1230//1230 -f 1230//1230 1149//1149 1148//1148 -f 1230//1230 1148//1148 1231//1231 -f 1231//1231 1148//1148 1147//1147 -f 1231//1231 1147//1147 1232//1232 -f 1232//1232 1147//1147 1146//1146 -f 1146//1146 1145//1145 1232//1232 -f 1232//1232 1145//1145 1144//1144 -f 1232//1232 1144//1144 1233//1233 -f 1233//1233 1144//1144 1143//1143 -f 1233//1233 1143//1143 1186//1186 -f 1186//1186 1143//1143 1142//1142 -f 1186//1186 1142//1142 1141//1141 -f 1186//1186 1234//1234 1233//1233 -f 1233//1233 1234//1234 1235//1235 -f 1233//1233 1235//1235 1232//1232 -f 1232//1232 1235//1235 1236//1236 -f 1232//1232 1236//1236 1231//1231 -f 1231//1231 1236//1236 1237//1237 -f 1231//1231 1237//1237 1230//1230 -f 1230//1230 1237//1237 1238//1238 -f 1230//1230 1238//1238 1229//1229 -f 1229//1229 1238//1238 1239//1239 -f 1229//1229 1239//1239 1226//1226 -f 1226//1226 1239//1239 1240//1240 -f 1226//1226 1240//1240 1227//1227 -f 1227//1227 1240//1240 1241//1241 -f 1227//1227 1241//1241 1228//1228 -f 1228//1228 1241//1241 1242//1242 -f 1228//1228 1242//1242 1225//1225 -f 1225//1225 1242//1242 1243//1243 -f 1225//1225 1243//1243 1224//1224 -f 1224//1224 1243//1243 1244//1244 -f 1224//1224 1244//1244 1223//1223 -f 1223//1223 1244//1244 1245//1245 -f 1223//1223 1245//1245 1222//1222 -f 1222//1222 1245//1245 1246//1246 -f 1222//1222 1246//1246 1219//1219 -f 1219//1219 1246//1246 1247//1247 -f 1219//1219 1247//1247 1220//1220 -f 1220//1220 1247//1247 1248//1248 -f 1220//1220 1248//1248 1221//1221 -f 1221//1221 1248//1248 1249//1249 -f 1221//1221 1249//1249 1218//1218 -f 1218//1218 1249//1249 1250//1250 -f 1218//1218 1250//1250 1217//1217 -f 1217//1217 1250//1250 1251//1251 -f 1217//1217 1251//1251 1216//1216 -f 1216//1216 1251//1251 1252//1252 -f 1216//1216 1252//1252 1215//1215 -f 1215//1215 1252//1252 1253//1253 -f 1215//1215 1253//1253 1212//1212 -f 1212//1212 1253//1253 1254//1254 -f 1212//1212 1254//1254 1213//1213 -f 1213//1213 1254//1254 1255//1255 -f 1213//1213 1255//1255 1214//1214 -f 1214//1214 1255//1255 1256//1256 -f 1214//1214 1256//1256 1211//1211 -f 1211//1211 1256//1256 1257//1257 -f 1211//1211 1257//1257 1210//1210 -f 1210//1210 1257//1257 1258//1258 -f 1210//1210 1258//1258 1209//1209 -f 1209//1209 1258//1258 1259//1259 -f 1209//1209 1259//1259 1208//1208 -f 1208//1208 1259//1259 1260//1260 -f 1208//1208 1260//1260 1205//1205 -f 1205//1205 1260//1260 1261//1261 -f 1205//1205 1261//1261 1206//1206 -f 1206//1206 1261//1261 1262//1262 -f 1206//1206 1262//1262 1207//1207 -f 1207//1207 1262//1262 1263//1263 -f 1207//1207 1263//1263 1204//1204 -f 1204//1204 1263//1263 1264//1264 -f 1204//1204 1264//1264 1203//1203 -f 1203//1203 1264//1264 1265//1265 -f 1203//1203 1265//1265 1202//1202 -f 1202//1202 1265//1265 1266//1266 -f 1202//1202 1266//1266 1201//1201 -f 1201//1201 1266//1266 1267//1267 -f 1201//1201 1267//1267 1198//1198 -f 1198//1198 1267//1267 1268//1268 -f 1198//1198 1268//1268 1199//1199 -f 1199//1199 1268//1268 1269//1269 -f 1199//1199 1269//1269 1200//1200 -f 1200//1200 1269//1269 1270//1270 -f 1200//1200 1270//1270 1197//1197 -f 1197//1197 1270//1270 1271//1271 -f 1197//1197 1271//1271 1196//1196 -f 1196//1196 1271//1271 1272//1272 -f 1196//1196 1272//1272 1195//1195 -f 1195//1195 1272//1272 1273//1273 -f 1195//1195 1273//1273 1194//1194 -f 1194//1194 1273//1273 1274//1274 -f 1194//1194 1274//1274 1191//1191 -f 1191//1191 1274//1274 1275//1275 -f 1191//1191 1275//1275 1192//1192 -f 1192//1192 1275//1275 1276//1276 -f 1192//1192 1276//1276 1193//1193 -f 1193//1193 1276//1276 1277//1277 -f 1193//1193 1277//1277 1190//1190 -f 1190//1190 1277//1277 1278//1278 -f 1190//1190 1278//1278 1189//1189 -f 1189//1189 1278//1278 1279//1279 -f 1189//1189 1279//1279 1188//1188 -f 1188//1188 1279//1279 1280//1280 -f 1188//1188 1280//1280 1187//1187 -f 1187//1187 1280//1280 1281//1281 -f 1187//1187 1281//1281 1185//1185 -f 1185//1185 1281//1281 1282//1282 -f 1185//1185 1282//1282 1186//1186 -f 1186//1186 1282//1282 1234//1234 -f 1282//1282 1283//1283 1234//1234 -f 1234//1234 1283//1283 1284//1284 -f 1234//1234 1284//1284 1235//1235 -f 1235//1235 1284//1284 1285//1285 -f 1235//1235 1285//1285 1236//1236 -f 1236//1236 1285//1285 1286//1286 -f 1236//1236 1286//1286 1237//1237 -f 1237//1237 1286//1286 1287//1287 -f 1237//1237 1287//1287 1238//1238 -f 1238//1238 1287//1287 1288//1288 -f 1238//1238 1288//1288 1239//1239 -f 1239//1239 1288//1288 1289//1289 -f 1239//1239 1289//1289 1240//1240 -f 1240//1240 1289//1289 1290//1290 -f 1240//1240 1290//1290 1241//1241 -f 1241//1241 1290//1290 1291//1291 -f 1241//1241 1291//1291 1242//1242 -f 1242//1242 1291//1291 1292//1292 -f 1242//1242 1292//1292 1243//1243 -f 1243//1243 1292//1292 1293//1293 -f 1243//1243 1293//1293 1244//1244 -f 1244//1244 1293//1293 1294//1294 -f 1244//1244 1294//1294 1245//1245 -f 1245//1245 1294//1294 1295//1295 -f 1245//1245 1295//1295 1246//1246 -f 1246//1246 1295//1295 1296//1296 -f 1246//1246 1296//1296 1247//1247 -f 1247//1247 1296//1296 1297//1297 -f 1247//1247 1297//1297 1248//1248 -f 1248//1248 1297//1297 1298//1298 -f 1248//1248 1298//1298 1249//1249 -f 1249//1249 1298//1298 1299//1299 -f 1249//1249 1299//1299 1250//1250 -f 1250//1250 1299//1299 1300//1300 -f 1250//1250 1300//1300 1251//1251 -f 1251//1251 1300//1300 1301//1301 -f 1251//1251 1301//1301 1252//1252 -f 1252//1252 1301//1301 1302//1302 -f 1252//1252 1302//1302 1253//1253 -f 1253//1253 1302//1302 1303//1303 -f 1253//1253 1303//1303 1254//1254 -f 1254//1254 1303//1303 1304//1304 -f 1254//1254 1304//1304 1255//1255 -f 1255//1255 1304//1304 1305//1305 -f 1255//1255 1305//1305 1256//1256 -f 1256//1256 1305//1305 1306//1306 -f 1256//1256 1306//1306 1257//1257 -f 1257//1257 1306//1306 1307//1307 -f 1257//1257 1307//1307 1258//1258 -f 1258//1258 1307//1307 1308//1308 -f 1258//1258 1308//1308 1259//1259 -f 1259//1259 1308//1308 1309//1309 -f 1259//1259 1309//1309 1260//1260 -f 1260//1260 1309//1309 1310//1310 -f 1260//1260 1310//1310 1261//1261 -f 1261//1261 1310//1310 1311//1311 -f 1261//1261 1311//1311 1262//1262 -f 1262//1262 1311//1311 1312//1312 -f 1262//1262 1312//1312 1263//1263 -f 1263//1263 1312//1312 1313//1313 -f 1263//1263 1313//1313 1264//1264 -f 1264//1264 1313//1313 1314//1314 -f 1264//1264 1314//1314 1265//1265 -f 1265//1265 1314//1314 1315//1315 -f 1265//1265 1315//1315 1266//1266 -f 1266//1266 1315//1315 1316//1316 -f 1266//1266 1316//1316 1267//1267 -f 1267//1267 1316//1316 1317//1317 -f 1267//1267 1317//1317 1268//1268 -f 1268//1268 1317//1317 1318//1318 -f 1268//1268 1318//1318 1269//1269 -f 1269//1269 1318//1318 1319//1319 -f 1269//1269 1319//1319 1270//1270 -f 1270//1270 1319//1319 1320//1320 -f 1270//1270 1320//1320 1271//1271 -f 1271//1271 1320//1320 1321//1321 -f 1271//1271 1321//1321 1272//1272 -f 1272//1272 1321//1321 1322//1322 -f 1272//1272 1322//1322 1273//1273 -f 1273//1273 1322//1322 1323//1323 -f 1273//1273 1323//1323 1274//1274 -f 1274//1274 1323//1323 1324//1324 -f 1274//1274 1324//1324 1275//1275 -f 1275//1275 1324//1324 1325//1325 -f 1275//1275 1325//1325 1276//1276 -f 1276//1276 1325//1325 1326//1326 -f 1276//1276 1326//1326 1277//1277 -f 1277//1277 1326//1326 1327//1327 -f 1277//1277 1327//1327 1278//1278 -f 1278//1278 1327//1327 1328//1328 -f 1278//1278 1328//1328 1279//1279 -f 1279//1279 1328//1328 1329//1329 -f 1279//1279 1329//1329 1280//1280 -f 1280//1280 1329//1329 1330//1330 -f 1280//1280 1330//1330 1281//1281 -f 1281//1281 1330//1330 1331//1331 -f 1281//1281 1331//1331 1282//1282 -f 1282//1282 1331//1331 1283//1283 -f 1331//1331 1332//1332 1283//1283 -f 1283//1283 1332//1332 1333//1333 -f 1283//1283 1333//1333 1284//1284 -f 1284//1284 1333//1333 1334//1334 -f 1284//1284 1334//1334 1285//1285 -f 1285//1285 1334//1334 1335//1335 -f 1285//1285 1335//1335 1286//1286 -f 1286//1286 1335//1335 1336//1336 -f 1286//1286 1336//1336 1287//1287 -f 1287//1287 1336//1336 1337//1337 -f 1287//1287 1337//1337 1288//1288 -f 1288//1288 1337//1337 1338//1338 -f 1288//1288 1338//1338 1289//1289 -f 1289//1289 1338//1338 1339//1339 -f 1289//1289 1339//1339 1290//1290 -f 1290//1290 1339//1339 1340//1340 -f 1290//1290 1340//1340 1291//1291 -f 1291//1291 1340//1340 1341//1341 -f 1291//1291 1341//1341 1292//1292 -f 1292//1292 1341//1341 1342//1342 -f 1292//1292 1342//1342 1293//1293 -f 1293//1293 1342//1342 1343//1343 -f 1293//1293 1343//1343 1294//1294 -f 1294//1294 1343//1343 1344//1344 -f 1294//1294 1344//1344 1295//1295 -f 1295//1295 1344//1344 1345//1345 -f 1295//1295 1345//1345 1296//1296 -f 1296//1296 1345//1345 1346//1346 -f 1296//1296 1346//1346 1297//1297 -f 1297//1297 1346//1346 1347//1347 -f 1297//1297 1347//1347 1298//1298 -f 1298//1298 1347//1347 1348//1348 -f 1298//1298 1348//1348 1299//1299 -f 1299//1299 1348//1348 1349//1349 -f 1299//1299 1349//1349 1300//1300 -f 1300//1300 1349//1349 1350//1350 -f 1300//1300 1350//1350 1301//1301 -f 1301//1301 1350//1350 1351//1351 -f 1301//1301 1351//1351 1302//1302 -f 1302//1302 1351//1351 1352//1352 -f 1302//1302 1352//1352 1303//1303 -f 1303//1303 1352//1352 1353//1353 -f 1303//1303 1353//1353 1304//1304 -f 1304//1304 1353//1353 1354//1354 -f 1304//1304 1354//1354 1305//1305 -f 1305//1305 1354//1354 1355//1355 -f 1305//1305 1355//1355 1306//1306 -f 1306//1306 1355//1355 1356//1356 -f 1306//1306 1356//1356 1307//1307 -f 1307//1307 1356//1356 1357//1357 -f 1307//1307 1357//1357 1308//1308 -f 1308//1308 1357//1357 1358//1358 -f 1308//1308 1358//1358 1309//1309 -f 1309//1309 1358//1358 1359//1359 -f 1309//1309 1359//1359 1310//1310 -f 1310//1310 1359//1359 1360//1360 -f 1310//1310 1360//1360 1311//1311 -f 1311//1311 1360//1360 1361//1361 -f 1311//1311 1361//1361 1312//1312 -f 1312//1312 1361//1361 1362//1362 -f 1312//1312 1362//1362 1313//1313 -f 1313//1313 1362//1362 1363//1363 -f 1313//1313 1363//1363 1314//1314 -f 1314//1314 1363//1363 1364//1364 -f 1314//1314 1364//1364 1315//1315 -f 1315//1315 1364//1364 1365//1365 -f 1315//1315 1365//1365 1316//1316 -f 1316//1316 1365//1365 1366//1366 -f 1316//1316 1366//1366 1317//1317 -f 1317//1317 1366//1366 1367//1367 -f 1317//1317 1367//1367 1318//1318 -f 1318//1318 1367//1367 1368//1368 -f 1318//1318 1368//1368 1319//1319 -f 1319//1319 1368//1368 1369//1369 -f 1319//1319 1369//1369 1320//1320 -f 1320//1320 1369//1369 1370//1370 -f 1320//1320 1370//1370 1321//1321 -f 1321//1321 1370//1370 1371//1371 -f 1321//1321 1371//1371 1322//1322 -f 1322//1322 1371//1371 1372//1372 -f 1322//1322 1372//1372 1323//1323 -f 1323//1323 1372//1372 1373//1373 -f 1323//1323 1373//1373 1324//1324 -f 1324//1324 1373//1373 1374//1374 -f 1324//1324 1374//1374 1325//1325 -f 1325//1325 1374//1374 1375//1375 -f 1325//1325 1375//1375 1326//1326 -f 1326//1326 1375//1375 1376//1376 -f 1326//1326 1376//1376 1327//1327 -f 1327//1327 1376//1376 1377//1377 -f 1327//1327 1377//1377 1328//1328 -f 1328//1328 1377//1377 1378//1378 -f 1328//1328 1378//1378 1329//1329 -f 1329//1329 1378//1378 1379//1379 -f 1329//1329 1379//1379 1330//1330 -f 1330//1330 1379//1379 1380//1380 -f 1330//1330 1380//1380 1331//1331 -f 1331//1331 1380//1380 1332//1332 -f 1380//1380 1381//1381 1332//1332 -f 1332//1332 1381//1381 1382//1382 -f 1332//1332 1382//1382 1333//1333 -f 1333//1333 1382//1382 1383//1383 -f 1333//1333 1383//1383 1334//1334 -f 1334//1334 1383//1383 1384//1384 -f 1334//1334 1384//1384 1335//1335 -f 1335//1335 1384//1384 1385//1385 -f 1335//1335 1385//1385 1336//1336 -f 1336//1336 1385//1385 1386//1386 -f 1336//1336 1386//1386 1337//1337 -f 1337//1337 1386//1386 1387//1387 -f 1337//1337 1387//1387 1338//1338 -f 1338//1338 1387//1387 1388//1388 -f 1338//1338 1388//1388 1339//1339 -f 1339//1339 1388//1388 1389//1389 -f 1339//1339 1389//1389 1340//1340 -f 1340//1340 1389//1389 1390//1390 -f 1340//1340 1390//1390 1341//1341 -f 1341//1341 1390//1390 1391//1391 -f 1341//1341 1391//1391 1342//1342 -f 1342//1342 1391//1391 1392//1392 -f 1342//1342 1392//1392 1343//1343 -f 1343//1343 1392//1392 1393//1393 -f 1343//1343 1393//1393 1344//1344 -f 1344//1344 1393//1393 1394//1394 -f 1344//1344 1394//1394 1345//1345 -f 1345//1345 1394//1394 1395//1395 -f 1345//1345 1395//1395 1346//1346 -f 1346//1346 1395//1395 1396//1396 -f 1346//1346 1396//1396 1347//1347 -f 1347//1347 1396//1396 1397//1397 -f 1347//1347 1397//1397 1348//1348 -f 1348//1348 1397//1397 1398//1398 -f 1348//1348 1398//1398 1349//1349 -f 1349//1349 1398//1398 1399//1399 -f 1349//1349 1399//1399 1350//1350 -f 1350//1350 1399//1399 1400//1400 -f 1350//1350 1400//1400 1351//1351 -f 1351//1351 1400//1400 1401//1401 -f 1351//1351 1401//1401 1352//1352 -f 1352//1352 1401//1401 1402//1402 -f 1352//1352 1402//1402 1353//1353 -f 1353//1353 1402//1402 1403//1403 -f 1353//1353 1403//1403 1354//1354 -f 1354//1354 1403//1403 1404//1404 -f 1354//1354 1404//1404 1355//1355 -f 1355//1355 1404//1404 1405//1405 -f 1355//1355 1405//1405 1356//1356 -f 1356//1356 1405//1405 1406//1406 -f 1356//1356 1406//1406 1357//1357 -f 1357//1357 1406//1406 1407//1407 -f 1357//1357 1407//1407 1358//1358 -f 1358//1358 1407//1407 1408//1408 -f 1358//1358 1408//1408 1359//1359 -f 1359//1359 1408//1408 1409//1409 -f 1359//1359 1409//1409 1360//1360 -f 1360//1360 1409//1409 1410//1410 -f 1360//1360 1410//1410 1361//1361 -f 1361//1361 1410//1410 1411//1411 -f 1361//1361 1411//1411 1362//1362 -f 1362//1362 1411//1411 1412//1412 -f 1362//1362 1412//1412 1363//1363 -f 1363//1363 1412//1412 1413//1413 -f 1363//1363 1413//1413 1364//1364 -f 1364//1364 1413//1413 1414//1414 -f 1364//1364 1414//1414 1365//1365 -f 1365//1365 1414//1414 1415//1415 -f 1365//1365 1415//1415 1366//1366 -f 1366//1366 1415//1415 1416//1416 -f 1366//1366 1416//1416 1367//1367 -f 1367//1367 1416//1416 1417//1417 -f 1367//1367 1417//1417 1368//1368 -f 1368//1368 1417//1417 1418//1418 -f 1368//1368 1418//1418 1369//1369 -f 1369//1369 1418//1418 1419//1419 -f 1369//1369 1419//1419 1370//1370 -f 1370//1370 1419//1419 1420//1420 -f 1370//1370 1420//1420 1371//1371 -f 1371//1371 1420//1420 1421//1421 -f 1371//1371 1421//1421 1372//1372 -f 1372//1372 1421//1421 1422//1422 -f 1372//1372 1422//1422 1373//1373 -f 1373//1373 1422//1422 1423//1423 -f 1373//1373 1423//1423 1374//1374 -f 1374//1374 1423//1423 1424//1424 -f 1374//1374 1424//1424 1375//1375 -f 1375//1375 1424//1424 1425//1425 -f 1375//1375 1425//1425 1376//1376 -f 1376//1376 1425//1425 1426//1426 -f 1376//1376 1426//1426 1377//1377 -f 1377//1377 1426//1426 1427//1427 -f 1377//1377 1427//1427 1378//1378 -f 1378//1378 1427//1427 1428//1428 -f 1378//1378 1428//1428 1379//1379 -f 1379//1379 1428//1428 1429//1429 -f 1379//1379 1429//1429 1380//1380 -f 1380//1380 1429//1429 1381//1381 -f 1429//1429 1430//1430 1381//1381 -f 1381//1381 1430//1430 1431//1431 -f 1381//1381 1431//1431 1382//1382 -f 1382//1382 1431//1431 1432//1432 -f 1382//1382 1432//1432 1383//1383 -f 1383//1383 1432//1432 1433//1433 -f 1383//1383 1433//1433 1384//1384 -f 1384//1384 1433//1433 1434//1434 -f 1384//1384 1434//1434 1385//1385 -f 1385//1385 1434//1434 1435//1435 -f 1385//1385 1435//1435 1386//1386 -f 1386//1386 1435//1435 1436//1436 -f 1386//1386 1436//1436 1387//1387 -f 1387//1387 1436//1436 1437//1437 -f 1387//1387 1437//1437 1388//1388 -f 1388//1388 1437//1437 1438//1438 -f 1388//1388 1438//1438 1389//1389 -f 1389//1389 1438//1438 1439//1439 -f 1389//1389 1439//1439 1390//1390 -f 1390//1390 1439//1439 1440//1440 -f 1390//1390 1440//1440 1391//1391 -f 1391//1391 1440//1440 1441//1441 -f 1391//1391 1441//1441 1392//1392 -f 1392//1392 1441//1441 1442//1442 -f 1392//1392 1442//1442 1393//1393 -f 1393//1393 1442//1442 1443//1443 -f 1393//1393 1443//1443 1394//1394 -f 1394//1394 1443//1443 1444//1444 -f 1394//1394 1444//1444 1395//1395 -f 1395//1395 1444//1444 1445//1445 -f 1395//1395 1445//1445 1396//1396 -f 1396//1396 1445//1445 1446//1446 -f 1396//1396 1446//1446 1397//1397 -f 1397//1397 1446//1446 1447//1447 -f 1397//1397 1447//1447 1398//1398 -f 1398//1398 1447//1447 1448//1448 -f 1398//1398 1448//1448 1399//1399 -f 1399//1399 1448//1448 1449//1449 -f 1399//1399 1449//1449 1400//1400 -f 1400//1400 1449//1449 1450//1450 -f 1400//1400 1450//1450 1401//1401 -f 1401//1401 1450//1450 1451//1451 -f 1401//1401 1451//1451 1402//1402 -f 1402//1402 1451//1451 1452//1452 -f 1402//1402 1452//1452 1403//1403 -f 1403//1403 1452//1452 1453//1453 -f 1403//1403 1453//1453 1404//1404 -f 1404//1404 1453//1453 1454//1454 -f 1404//1404 1454//1454 1405//1405 -f 1405//1405 1454//1454 1455//1455 -f 1405//1405 1455//1455 1406//1406 -f 1406//1406 1455//1455 1456//1456 -f 1406//1406 1456//1456 1407//1407 -f 1407//1407 1456//1456 1457//1457 -f 1407//1407 1457//1457 1408//1408 -f 1408//1408 1457//1457 1458//1458 -f 1408//1408 1458//1458 1409//1409 -f 1409//1409 1458//1458 1459//1459 -f 1409//1409 1459//1459 1410//1410 -f 1410//1410 1459//1459 1460//1460 -f 1410//1410 1460//1460 1411//1411 -f 1411//1411 1460//1460 1461//1461 -f 1411//1411 1461//1461 1412//1412 -f 1412//1412 1461//1461 1462//1462 -f 1412//1412 1462//1462 1413//1413 -f 1413//1413 1462//1462 1463//1463 -f 1413//1413 1463//1463 1414//1414 -f 1414//1414 1463//1463 1464//1464 -f 1414//1414 1464//1464 1415//1415 -f 1415//1415 1464//1464 1465//1465 -f 1415//1415 1465//1465 1416//1416 -f 1416//1416 1465//1465 1466//1466 -f 1416//1416 1466//1466 1417//1417 -f 1417//1417 1466//1466 1467//1467 -f 1417//1417 1467//1467 1418//1418 -f 1418//1418 1467//1467 1468//1468 -f 1418//1418 1468//1468 1419//1419 -f 1419//1419 1468//1468 1469//1469 -f 1419//1419 1469//1469 1420//1420 -f 1420//1420 1469//1469 1470//1470 -f 1420//1420 1470//1470 1421//1421 -f 1421//1421 1470//1470 1471//1471 -f 1421//1421 1471//1471 1422//1422 -f 1422//1422 1471//1471 1472//1472 -f 1422//1422 1472//1472 1423//1423 -f 1423//1423 1472//1472 1473//1473 -f 1423//1423 1473//1473 1424//1424 -f 1424//1424 1473//1473 1474//1474 -f 1424//1424 1474//1474 1425//1425 -f 1425//1425 1474//1474 1475//1475 -f 1425//1425 1475//1475 1426//1426 -f 1426//1426 1475//1475 1476//1476 -f 1426//1426 1476//1476 1427//1427 -f 1427//1427 1476//1476 1477//1477 -f 1427//1427 1477//1477 1428//1428 -f 1428//1428 1477//1477 1478//1478 -f 1428//1428 1478//1478 1429//1429 -f 1429//1429 1478//1478 1430//1430 -f 1454//1454 1479//1479 1455//1455 -f 1455//1455 1479//1479 1480//1480 -f 1455//1455 1480//1480 1456//1456 -f 1456//1456 1480//1480 1481//1481 -f 1456//1456 1481//1481 1457//1457 -f 1457//1457 1481//1481 1482//1482 -f 1457//1457 1482//1482 1458//1458 -f 1482//1482 1483//1483 1458//1458 -f 1458//1458 1483//1483 1484//1484 -f 1458//1458 1484//1484 1459//1459 -f 1459//1459 1484//1484 1485//1485 -f 1459//1459 1485//1485 1460//1460 -f 1460//1460 1485//1485 1486//1486 -f 1460//1460 1486//1486 1461//1461 -f 1461//1461 1486//1486 1487//1487 -f 1461//1461 1487//1487 1462//1462 -f 1487//1487 1488//1488 1462//1462 -f 1462//1462 1488//1488 1489//1489 -f 1462//1462 1489//1489 1463//1463 -f 1463//1463 1489//1489 1490//1490 -f 1463//1463 1490//1490 1464//1464 -f 1464//1464 1490//1490 1491//1491 -f 1464//1464 1491//1491 1465//1465 -f 1465//1465 1491//1491 1492//1492 -f 1465//1465 1492//1492 1466//1466 -f 1466//1466 1492//1492 1493//1493 -f 1466//1466 1493//1493 1467//1467 -f 1493//1493 1494//1494 1467//1467 -f 1467//1467 1494//1494 1495//1495 -f 1467//1467 1495//1495 1468//1468 -f 1468//1468 1495//1495 1496//1496 -f 1468//1468 1496//1496 1469//1469 -f 1469//1469 1496//1496 1497//1497 -f 1469//1469 1497//1497 1470//1470 -f 1470//1470 1497//1497 1498//1498 -f 1470//1470 1498//1498 1471//1471 -f 1498//1498 1499//1499 1471//1471 -f 1471//1471 1499//1499 1500//1500 -f 1471//1471 1500//1500 1472//1472 -f 1472//1472 1500//1500 1501//1501 -f 1472//1472 1501//1501 1473//1473 -f 1473//1473 1501//1501 1502//1502 -f 1473//1473 1502//1502 1474//1474 -f 1474//1474 1502//1502 1503//1503 -f 1474//1474 1503//1503 1475//1475 -f 1475//1475 1503//1503 1504//1504 -f 1475//1475 1504//1504 1476//1476 -f 1440//1440 1505//1505 1441//1441 -f 1441//1441 1505//1505 1506//1506 -f 1441//1441 1506//1506 1442//1442 -f 1442//1442 1506//1506 1507//1507 -f 1442//1442 1507//1507 1443//1443 -f 1443//1443 1507//1507 1508//1508 -f 1443//1443 1508//1508 1444//1444 -f 1444//1444 1508//1508 1509//1509 -f 1444//1444 1509//1509 1445//1445 -f 1509//1509 1510//1510 1445//1445 -f 1445//1445 1510//1510 1511//1511 -f 1445//1445 1511//1511 1446//1446 -f 1446//1446 1511//1511 1512//1512 -f 1446//1446 1512//1512 1447//1447 -f 1447//1447 1512//1512 1513//1513 -f 1447//1447 1513//1513 1448//1448 -f 1448//1448 1513//1513 1514//1514 -f 1448//1448 1514//1514 1449//1449 -f 1514//1514 1515//1515 1449//1449 -f 1449//1449 1515//1515 1516//1516 -f 1449//1449 1516//1516 1450//1450 -f 1450//1450 1516//1516 1517//1517 -f 1450//1450 1517//1517 1451//1451 -f 1451//1451 1517//1517 1518//1518 -f 1451//1451 1518//1518 1452//1452 -f 1452//1452 1518//1518 1519//1519 -f 1452//1452 1519//1519 1453//1453 -f 1453//1453 1519//1519 1520//1520 -f 1453//1453 1520//1520 1454//1454 -f 1454//1454 1520//1520 1521//1521 -f 1454//1454 1521//1521 1479//1479 -f 1504//1504 1522//1522 1476//1476 -f 1476//1476 1522//1522 1523//1523 -f 1476//1476 1523//1523 1477//1477 -f 1477//1477 1523//1523 1524//1524 -f 1477//1477 1524//1524 1478//1478 -f 1478//1478 1524//1524 1525//1525 -f 1478//1478 1525//1525 1430//1430 -f 1430//1430 1525//1525 1526//1526 -f 1430//1430 1526//1526 1431//1431 -f 1436//1436 1527//1527 1437//1437 -f 1437//1437 1527//1527 1528//1528 -f 1437//1437 1528//1528 1438//1438 -f 1438//1438 1528//1528 1529//1529 -f 1438//1438 1529//1529 1439//1439 -f 1439//1439 1529//1529 1530//1530 -f 1439//1439 1530//1530 1440//1440 -f 1440//1440 1530//1530 1531//1531 -f 1440//1440 1531//1531 1505//1505 -f 1526//1526 1532//1532 1431//1431 -f 1431//1431 1532//1532 1533//1533 -f 1431//1431 1533//1533 1432//1432 -f 1432//1432 1533//1533 1534//1534 -f 1432//1432 1534//1534 1433//1433 -f 1433//1433 1534//1534 1535//1535 -f 1433//1433 1535//1535 1434//1434 -f 1434//1434 1535//1535 1536//1536 -f 1434//1434 1536//1536 1435//1435 -f 1435//1435 1536//1536 1537//1537 -f 1435//1435 1537//1537 1436//1436 -f 1436//1436 1537//1537 1538//1538 -f 1436//1436 1538//1538 1527//1527 -f 1525//1525 1539//1539 1526//1526 -f 1526//1526 1539//1539 1540//1540 -f 1526//1526 1540//1540 1532//1532 -f 1532//1532 1540//1540 1541//1541 -f 1532//1532 1541//1541 1533//1533 -f 1533//1533 1541//1541 1542//1542 -f 1533//1533 1542//1542 1534//1534 -f 1534//1534 1542//1542 1543//1543 -f 1534//1534 1543//1543 1535//1535 -f 1535//1535 1543//1543 1544//1544 -f 1535//1535 1544//1544 1536//1536 -f 1536//1536 1544//1544 1545//1545 -f 1536//1536 1545//1545 1537//1537 -f 1537//1537 1545//1545 1546//1546 -f 1537//1537 1546//1546 1538//1538 -f 1538//1538 1546//1546 1547//1547 -f 1538//1538 1547//1547 1527//1527 -f 1527//1527 1547//1547 1548//1548 -f 1527//1527 1548//1548 1528//1528 -f 1528//1528 1548//1548 1549//1549 -f 1528//1528 1549//1549 1529//1529 -f 1529//1529 1549//1549 1550//1550 -f 1529//1529 1550//1550 1530//1530 -f 1530//1530 1550//1550 1551//1551 -f 1530//1530 1551//1551 1531//1531 -f 1531//1531 1551//1551 1552//1552 -f 1531//1531 1552//1552 1505//1505 -f 1505//1505 1552//1552 1553//1553 -f 1505//1505 1553//1553 1506//1506 -f 1506//1506 1553//1553 1554//1554 -f 1506//1506 1554//1554 1507//1507 -f 1507//1507 1554//1554 1555//1555 -f 1507//1507 1555//1555 1508//1508 -f 1508//1508 1555//1555 1556//1556 -f 1508//1508 1556//1556 1509//1509 -f 1509//1509 1556//1556 1557//1557 -f 1509//1509 1557//1557 1510//1510 -f 1510//1510 1557//1557 1558//1558 -f 1510//1510 1558//1558 1511//1511 -f 1511//1511 1558//1558 1559//1559 -f 1511//1511 1559//1559 1512//1512 -f 1512//1512 1559//1559 1560//1560 -f 1512//1512 1560//1560 1513//1513 -f 1513//1513 1560//1560 1561//1561 -f 1513//1513 1561//1561 1514//1514 -f 1514//1514 1561//1561 1562//1562 -f 1514//1514 1562//1562 1515//1515 -f 1515//1515 1562//1562 1563//1563 -f 1515//1515 1563//1563 1516//1516 -f 1516//1516 1563//1563 1564//1564 -f 1516//1516 1564//1564 1517//1517 -f 1517//1517 1564//1564 1565//1565 -f 1517//1517 1565//1565 1518//1518 -f 1518//1518 1565//1565 1566//1566 -f 1518//1518 1566//1566 1519//1519 -f 1519//1519 1566//1566 1567//1567 -f 1519//1519 1567//1567 1520//1520 -f 1520//1520 1567//1567 1568//1568 -f 1520//1520 1568//1568 1521//1521 -f 1521//1521 1568//1568 1569//1569 -f 1521//1521 1569//1569 1479//1479 -f 1479//1479 1569//1569 1570//1570 -f 1479//1479 1570//1570 1480//1480 -f 1480//1480 1570//1570 1571//1571 -f 1480//1480 1571//1571 1481//1481 -f 1481//1481 1571//1571 1572//1572 -f 1481//1481 1572//1572 1482//1482 -f 1482//1482 1572//1572 1573//1573 -f 1482//1482 1573//1573 1483//1483 -f 1483//1483 1573//1573 1574//1574 -f 1483//1483 1574//1574 1484//1484 -f 1484//1484 1574//1574 1575//1575 -f 1484//1484 1575//1575 1485//1485 -f 1485//1485 1575//1575 1576//1576 -f 1485//1485 1576//1576 1486//1486 -f 1486//1486 1576//1576 1577//1577 -f 1486//1486 1577//1577 1487//1487 -f 1487//1487 1577//1577 1578//1578 -f 1487//1487 1578//1578 1488//1488 -f 1488//1488 1578//1578 1579//1579 -f 1488//1488 1579//1579 1489//1489 -f 1489//1489 1579//1579 1580//1580 -f 1489//1489 1580//1580 1490//1490 -f 1490//1490 1580//1580 1581//1581 -f 1490//1490 1581//1581 1491//1491 -f 1491//1491 1581//1581 1582//1582 -f 1491//1491 1582//1582 1492//1492 -f 1492//1492 1582//1582 1583//1583 -f 1492//1492 1583//1583 1493//1493 -f 1493//1493 1583//1583 1584//1584 -f 1493//1493 1584//1584 1494//1494 -f 1494//1494 1584//1584 1585//1585 -f 1494//1494 1585//1585 1495//1495 -f 1495//1495 1585//1585 1586//1586 -f 1495//1495 1586//1586 1496//1496 -f 1496//1496 1586//1586 1587//1587 -f 1496//1496 1587//1587 1497//1497 -f 1497//1497 1587//1587 1588//1588 -f 1497//1497 1588//1588 1498//1498 -f 1498//1498 1588//1588 1589//1589 -f 1498//1498 1589//1589 1499//1499 -f 1499//1499 1589//1589 1590//1590 -f 1499//1499 1590//1590 1500//1500 -f 1500//1500 1590//1590 1591//1591 -f 1500//1500 1591//1591 1501//1501 -f 1501//1501 1591//1591 1592//1592 -f 1501//1501 1592//1592 1502//1502 -f 1502//1502 1592//1592 1593//1593 -f 1502//1502 1593//1593 1503//1503 -f 1503//1503 1593//1593 1594//1594 -f 1503//1503 1594//1594 1504//1504 -f 1504//1504 1594//1594 1595//1595 -f 1504//1504 1595//1595 1522//1522 -f 1522//1522 1595//1595 1596//1596 -f 1522//1522 1596//1596 1523//1523 -f 1523//1523 1596//1596 1597//1597 -f 1523//1523 1597//1597 1524//1524 -f 1524//1524 1597//1597 1598//1598 -f 1524//1524 1598//1598 1525//1525 -f 1525//1525 1598//1598 1539//1539 -f 1598//1598 1599//1599 1539//1539 -f 1539//1539 1599//1599 1600//1600 -f 1539//1539 1600//1600 1540//1540 -f 1540//1540 1600//1600 1601//1601 -f 1540//1540 1601//1601 1541//1541 -f 1541//1541 1601//1601 1602//1602 -f 1541//1541 1602//1602 1542//1542 -f 1542//1542 1602//1602 1603//1603 -f 1542//1542 1603//1603 1543//1543 -f 1543//1543 1603//1603 1604//1604 -f 1543//1543 1604//1604 1544//1544 -f 1544//1544 1604//1604 1605//1605 -f 1544//1544 1605//1605 1545//1545 -f 1545//1545 1605//1605 1606//1606 -f 1545//1545 1606//1606 1546//1546 -f 1546//1546 1606//1606 1607//1607 -f 1546//1546 1607//1607 1547//1547 -f 1547//1547 1607//1607 1608//1608 -f 1547//1547 1608//1608 1548//1548 -f 1548//1548 1608//1608 1609//1609 -f 1548//1548 1609//1609 1549//1549 -f 1549//1549 1609//1609 1610//1610 -f 1549//1549 1610//1610 1550//1550 -f 1550//1550 1610//1610 1611//1611 -f 1550//1550 1611//1611 1551//1551 -f 1551//1551 1611//1611 1612//1612 -f 1551//1551 1612//1612 1552//1552 -f 1552//1552 1612//1612 1613//1613 -f 1552//1552 1613//1613 1553//1553 -f 1553//1553 1613//1613 1614//1614 -f 1553//1553 1614//1614 1554//1554 -f 1554//1554 1614//1614 1615//1615 -f 1554//1554 1615//1615 1555//1555 -f 1555//1555 1615//1615 1616//1616 -f 1555//1555 1616//1616 1556//1556 -f 1556//1556 1616//1616 1617//1617 -f 1556//1556 1617//1617 1557//1557 -f 1557//1557 1617//1617 1618//1618 -f 1557//1557 1618//1618 1558//1558 -f 1558//1558 1618//1618 1619//1619 -f 1558//1558 1619//1619 1559//1559 -f 1559//1559 1619//1619 1620//1620 -f 1559//1559 1620//1620 1560//1560 -f 1560//1560 1620//1620 1621//1621 -f 1560//1560 1621//1621 1561//1561 -f 1561//1561 1621//1621 1622//1622 -f 1561//1561 1622//1622 1562//1562 -f 1562//1562 1622//1622 1623//1623 -f 1562//1562 1623//1623 1563//1563 -f 1563//1563 1623//1623 1624//1624 -f 1563//1563 1624//1624 1564//1564 -f 1564//1564 1624//1624 1625//1625 -f 1564//1564 1625//1625 1565//1565 -f 1565//1565 1625//1625 1626//1626 -f 1565//1565 1626//1626 1566//1566 -f 1566//1566 1626//1626 1627//1627 -f 1566//1566 1627//1627 1567//1567 -f 1567//1567 1627//1627 1628//1628 -f 1567//1567 1628//1628 1568//1568 -f 1568//1568 1628//1628 1629//1629 -f 1568//1568 1629//1629 1569//1569 -f 1569//1569 1629//1629 1630//1630 -f 1569//1569 1630//1630 1570//1570 -f 1570//1570 1630//1630 1631//1631 -f 1570//1570 1631//1631 1571//1571 -f 1571//1571 1631//1631 1632//1632 -f 1571//1571 1632//1632 1572//1572 -f 1572//1572 1632//1632 1633//1633 -f 1572//1572 1633//1633 1573//1573 -f 1573//1573 1633//1633 1634//1634 -f 1573//1573 1634//1634 1574//1574 -f 1574//1574 1634//1634 1635//1635 -f 1574//1574 1635//1635 1575//1575 -f 1575//1575 1635//1635 1636//1636 -f 1575//1575 1636//1636 1576//1576 -f 1576//1576 1636//1636 1637//1637 -f 1576//1576 1637//1637 1577//1577 -f 1577//1577 1637//1637 1638//1638 -f 1577//1577 1638//1638 1578//1578 -f 1578//1578 1638//1638 1639//1639 -f 1578//1578 1639//1639 1579//1579 -f 1579//1579 1639//1639 1640//1640 -f 1579//1579 1640//1640 1580//1580 -f 1580//1580 1640//1640 1641//1641 -f 1580//1580 1641//1641 1581//1581 -f 1581//1581 1641//1641 1642//1642 -f 1581//1581 1642//1642 1582//1582 -f 1582//1582 1642//1642 1643//1643 -f 1582//1582 1643//1643 1583//1583 -f 1583//1583 1643//1643 1644//1644 -f 1583//1583 1644//1644 1584//1584 -f 1584//1584 1644//1644 1645//1645 -f 1584//1584 1645//1645 1585//1585 -f 1585//1585 1645//1645 1646//1646 -f 1585//1585 1646//1646 1586//1586 -f 1586//1586 1646//1646 1647//1647 -f 1586//1586 1647//1647 1587//1587 -f 1587//1587 1647//1647 1648//1648 -f 1587//1587 1648//1648 1588//1588 -f 1588//1588 1648//1648 1649//1649 -f 1588//1588 1649//1649 1589//1589 -f 1589//1589 1649//1649 1650//1650 -f 1589//1589 1650//1650 1590//1590 -f 1590//1590 1650//1650 1651//1651 -f 1590//1590 1651//1651 1591//1591 -f 1591//1591 1651//1651 1652//1652 -f 1591//1591 1652//1652 1592//1592 -f 1592//1592 1652//1652 1653//1653 -f 1592//1592 1653//1653 1593//1593 -f 1593//1593 1653//1653 1654//1654 -f 1593//1593 1654//1654 1594//1594 -f 1594//1594 1654//1654 1655//1655 -f 1594//1594 1655//1655 1595//1595 -f 1595//1595 1655//1655 1656//1656 -f 1595//1595 1656//1656 1596//1596 -f 1596//1596 1656//1656 1657//1657 -f 1596//1596 1657//1657 1597//1597 -f 1597//1597 1657//1657 1658//1658 -f 1597//1597 1658//1658 1598//1598 -f 1598//1598 1658//1658 1599//1599 -f 1659//1659 1660//1660 1629//1629 -f 1629//1629 1660//1660 1630//1630 -f 1630//1630 1660//1660 1661//1661 -f 1630//1630 1661//1661 1631//1631 -f 1631//1631 1661//1661 1662//1662 -f 1631//1631 1662//1662 1632//1632 -f 1632//1632 1662//1662 1663//1663 -f 1632//1632 1663//1663 1633//1633 -f 1633//1633 1663//1663 1664//1664 -f 1633//1633 1664//1664 1634//1634 -f 1634//1634 1664//1664 1665//1665 -f 1634//1634 1665//1665 1635//1635 -f 1635//1635 1665//1665 1666//1666 -f 1635//1635 1666//1666 1636//1636 -f 1666//1666 1667//1667 1636//1636 -f 1636//1636 1667//1667 1668//1668 -f 1636//1636 1668//1668 1637//1637 -f 1637//1637 1668//1668 1669//1669 -f 1637//1637 1669//1669 1638//1638 -f 1638//1638 1669//1669 1639//1639 -f 1639//1639 1669//1669 1670//1670 -f 1639//1639 1670//1670 1640//1640 -f 1640//1640 1670//1670 1671//1671 -f 1640//1640 1671//1671 1641//1641 -f 1641//1641 1671//1671 1672//1672 -f 1641//1641 1672//1672 1642//1642 -f 1642//1642 1672//1672 1673//1673 -f 1642//1642 1673//1673 1643//1643 -f 1643//1643 1673//1673 1674//1674 -f 1643//1643 1674//1674 1644//1644 -f 1644//1644 1674//1674 1675//1675 -f 1644//1644 1675//1675 1645//1645 -f 1645//1645 1675//1675 1676//1676 -f 1645//1645 1676//1676 1646//1646 -f 1676//1676 1677//1677 1646//1646 -f 1646//1646 1677//1677 1678//1678 -f 1646//1646 1678//1678 1647//1647 -f 1647//1647 1678//1678 1679//1679 -f 1647//1647 1679//1679 1648//1648 -f 1648//1648 1679//1679 1649//1649 -f 1649//1649 1679//1679 1680//1680 -f 1649//1649 1680//1680 1650//1650 -f 1650//1650 1680//1680 1681//1681 -f 1650//1650 1681//1681 1651//1651 -f 1651//1651 1681//1681 1682//1682 -f 1651//1651 1682//1682 1652//1652 -f 1652//1652 1682//1682 1683//1683 -f 1652//1652 1683//1683 1653//1653 -f 1653//1653 1683//1683 1684//1684 -f 1653//1653 1684//1684 1654//1654 -f 1654//1654 1684//1684 1685//1685 -f 1654//1654 1685//1685 1655//1655 -f 1655//1655 1685//1685 1686//1686 -f 1655//1655 1686//1686 1656//1656 -f 1686//1686 1687//1687 1656//1656 -f 1656//1656 1687//1687 1688//1688 -f 1656//1656 1688//1688 1657//1657 -f 1657//1657 1688//1688 1689//1689 -f 1657//1657 1689//1689 1658//1658 -f 1658//1658 1689//1689 1599//1599 -f 1599//1599 1689//1689 1690//1690 -f 1599//1599 1690//1690 1600//1600 -f 1600//1600 1690//1690 1691//1691 -f 1600//1600 1691//1691 1601//1601 -f 1601//1601 1691//1691 1692//1692 -f 1601//1601 1692//1692 1602//1602 -f 1602//1602 1692//1692 1693//1693 -f 1602//1602 1693//1693 1603//1603 -f 1603//1603 1693//1693 1694//1694 -f 1603//1603 1694//1694 1604//1604 -f 1604//1604 1694//1694 1695//1695 -f 1604//1604 1695//1695 1605//1605 -f 1605//1605 1695//1695 1696//1696 -f 1605//1605 1696//1696 1606//1606 -f 1696//1696 1697//1697 1606//1606 -f 1606//1606 1697//1697 1698//1698 -f 1606//1606 1698//1698 1607//1607 -f 1607//1607 1698//1698 1699//1699 -f 1607//1607 1699//1699 1608//1608 -f 1608//1608 1699//1699 1609//1609 -f 1609//1609 1699//1699 1700//1700 -f 1609//1609 1700//1700 1610//1610 -f 1610//1610 1700//1700 1701//1701 -f 1610//1610 1701//1701 1611//1611 -f 1611//1611 1701//1701 1702//1702 -f 1611//1611 1702//1702 1612//1612 -f 1612//1612 1702//1702 1703//1703 -f 1612//1612 1703//1703 1613//1613 -f 1613//1613 1703//1703 1704//1704 -f 1613//1613 1704//1704 1614//1614 -f 1614//1614 1704//1704 1705//1705 -f 1614//1614 1705//1705 1615//1615 -f 1615//1615 1705//1705 1706//1706 -f 1615//1615 1706//1706 1616//1616 -f 1706//1706 1707//1707 1616//1616 -f 1616//1616 1707//1707 1708//1708 -f 1616//1616 1708//1708 1617//1617 -f 1617//1617 1708//1708 1709//1709 -f 1617//1617 1709//1709 1618//1618 -f 1618//1618 1709//1709 1619//1619 -f 1619//1619 1709//1709 1710//1710 -f 1619//1619 1710//1710 1620//1620 -f 1620//1620 1710//1710 1711//1711 -f 1620//1620 1711//1711 1621//1621 -f 1621//1621 1711//1711 1712//1712 -f 1621//1621 1712//1712 1622//1622 -f 1622//1622 1712//1712 1713//1713 -f 1622//1622 1713//1713 1623//1623 -f 1623//1623 1713//1713 1714//1714 -f 1623//1623 1714//1714 1624//1624 -f 1624//1624 1714//1714 1715//1715 -f 1624//1624 1715//1715 1625//1625 -f 1625//1625 1715//1715 1716//1716 -f 1625//1625 1716//1716 1626//1626 -f 1716//1716 1717//1717 1626//1626 -f 1626//1626 1717//1717 1718//1718 -f 1626//1626 1718//1718 1627//1627 -f 1627//1627 1718//1718 1659//1659 -f 1627//1627 1659//1659 1628//1628 -f 1628//1628 1659//1659 1629//1629 -f 1719//1719 1720//1720 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1725//1725 1726//1726 1727//1727 -f 1728//1728 1729//1729 1730//1730 -f 1731//1731 1732//1732 1733//1733 -f 1734//1734 1735//1735 1736//1736 -f 1737//1737 1738//1738 1739//1739 -f 1740//1740 1741//1741 1742//1742 -f 1693//1693 1692//1692 1743//1743 -f 1695//1695 1694//1694 1744//1744 -f 1701//1701 1700//1700 1745//1745 -f 1713//1713 1712//1712 1746//1746 -f 1715//1715 1714//1714 1747//1747 -f 1661//1661 1660//1660 1748//1748 -f 1673//1673 1672//1672 1749//1749 -f 1675//1675 1674//1674 1750//1750 -f 1681//1681 1680//1680 1751//1751 -f 1752//1752 1689//1689 1688//1688 -f 1752//1752 1688//1688 1753//1753 -f 1753//1753 1688//1688 1687//1687 -f 1753//1753 1687//1687 1754//1754 -f 1684//1684 1755//1755 1685//1685 -f 1685//1685 1755//1755 1754//1754 -f 1685//1685 1754//1754 1686//1686 -f 1686//1686 1754//1754 1687//1687 -f 1684//1684 1683//1683 1756//1756 -f 1681//1681 1751//1751 1682//1682 -f 1741//1741 1678//1678 1677//1677 -f 1741//1741 1677//1677 1742//1742 -f 1742//1742 1677//1677 1676//1676 -f 1742//1742 1676//1676 1675//1675 -f 1673//1673 1749//1749 1674//1674 -f 1672//1672 1671//1671 1757//1757 -f 1757//1757 1671//1671 1670//1670 -f 1757//1757 1670//1670 1669//1669 -f 1664//1664 1739//1739 1665//1665 -f 1665//1665 1739//1739 1738//1738 -f 1665//1665 1738//1738 1666//1666 -f 1666//1666 1738//1738 1667//1667 -f 1664//1664 1663//1663 1758//1758 -f 1661//1661 1748//1748 1662//1662 -f 1735//1735 1718//1718 1717//1717 -f 1735//1735 1717//1717 1736//1736 -f 1736//1736 1717//1717 1716//1716 -f 1736//1736 1716//1716 1715//1715 -f 1713//1713 1746//1746 1714//1714 -f 1712//1712 1711//1711 1759//1759 -f 1759//1759 1711//1711 1710//1710 -f 1759//1759 1710//1710 1709//1709 -f 1704//1704 1733//1733 1705//1705 -f 1705//1705 1733//1733 1732//1732 -f 1705//1705 1732//1732 1706//1706 -f 1706//1706 1732//1732 1707//1707 -f 1704//1704 1703//1703 1760//1760 -f 1701//1701 1745//1745 1702//1702 -f 1729//1729 1698//1698 1697//1697 -f 1729//1729 1697//1697 1730//1730 -f 1730//1730 1697//1697 1696//1696 -f 1730//1730 1696//1696 1695//1695 -f 1693//1693 1743//1743 1694//1694 -f 1692//1692 1691//1691 1761//1761 -f 1761//1761 1691//1691 1690//1690 -f 1761//1761 1690//1690 1689//1689 -f 1679//1679 1678//1678 1762//1762 -f 1762//1762 1678//1678 1741//1741 -f 1762//1762 1741//1741 1763//1763 -f 1763//1763 1741//1741 1740//1740 -f 1763//1763 1740//1740 1764//1764 -f 1668//1668 1667//1667 1765//1765 -f 1765//1765 1667//1667 1738//1738 -f 1765//1765 1738//1738 1766//1766 -f 1766//1766 1738//1738 1737//1737 -f 1766//1766 1737//1737 1767//1767 -f 1659//1659 1718//1718 1768//1768 -f 1768//1768 1718//1718 1735//1735 -f 1768//1768 1735//1735 1769//1769 -f 1769//1769 1735//1735 1734//1734 -f 1769//1769 1734//1734 1770//1770 -f 1708//1708 1707//1707 1771//1771 -f 1771//1771 1707//1707 1732//1732 -f 1771//1771 1732//1732 1772//1772 -f 1772//1772 1732//1732 1731//1731 -f 1772//1772 1731//1731 1773//1773 -f 1699//1699 1698//1698 1774//1774 -f 1774//1774 1698//1698 1729//1729 -f 1774//1774 1729//1729 1775//1775 -f 1775//1775 1729//1729 1728//1728 -f 1775//1775 1728//1728 1776//1776 -f 1755//1755 1777//1777 1754//1754 -f 1754//1754 1777//1777 1778//1778 -f 1754//1754 1778//1778 1753//1753 -f 1753//1753 1778//1778 1779//1779 -f 1753//1753 1779//1779 1752//1752 -f 1752//1752 1779//1779 1780//1780 -f 1781//1781 1782//1782 1783//1783 -f 1784//1784 1785//1785 1786//1786 -f 1787//1787 1785//1785 1788//1788 -f 1788//1788 1785//1785 1784//1784 -f 1788//1788 1784//1784 1789//1789 -f 1669//1669 1668//1668 1789//1789 -f 1789//1789 1668//1668 1765//1765 -f 1789//1789 1765//1765 1788//1788 -f 1788//1788 1765//1765 1766//1766 -f 1788//1788 1766//1766 1787//1787 -f 1787//1787 1766//1766 1767//1767 -f 1790//1790 1791//1791 1792//1792 -f 1793//1793 1794//1794 1795//1795 -f 1796//1796 1794//1794 1797//1797 -f 1797//1797 1794//1794 1793//1793 -f 1797//1797 1793//1793 1798//1798 -f 1709//1709 1708//1708 1798//1798 -f 1798//1798 1708//1708 1771//1771 -f 1798//1798 1771//1771 1797//1797 -f 1797//1797 1771//1771 1772//1772 -f 1797//1797 1772//1772 1796//1796 -f 1796//1796 1772//1772 1773//1773 -f 1799//1799 1800//1800 1801//1801 -f 1777//1777 1802//1802 1778//1778 -f 1778//1778 1802//1802 1803//1803 -f 1778//1778 1803//1803 1779//1779 -f 1779//1779 1803//1803 1804//1804 -f 1779//1779 1804//1804 1780//1780 -f 1780//1780 1804//1804 1805//1805 -f 1684//1684 1756//1756 1755//1755 -f 1755//1755 1756//1756 1806//1806 -f 1755//1755 1806//1806 1777//1777 -f 1777//1777 1806//1806 1727//1727 -f 1777//1777 1727//1727 1802//1802 -f 1802//1802 1727//1727 1726//1726 -f 1802//1802 1726//1726 1807//1807 -f 1756//1756 1781//1781 1806//1806 -f 1806//1806 1781//1781 1783//1783 -f 1806//1806 1783//1783 1727//1727 -f 1727//1727 1783//1783 1808//1808 -f 1727//1727 1808//1808 1725//1725 -f 1809//1809 1810//1810 1811//1811 -f 1811//1811 1810//1810 1782//1782 -f 1811//1811 1782//1782 1812//1812 -f 1812//1812 1782//1782 1781//1781 -f 1812//1812 1781//1781 1751//1751 -f 1751//1751 1781//1781 1756//1756 -f 1751//1751 1756//1756 1682//1682 -f 1682//1682 1756//1756 1683//1683 -f 1810//1810 1813//1813 1782//1782 -f 1782//1782 1813//1813 1814//1814 -f 1782//1782 1814//1814 1783//1783 -f 1783//1783 1814//1814 1815//1815 -f 1783//1783 1815//1815 1808//1808 -f 1680//1680 1679//1679 1751//1751 -f 1751//1751 1679//1679 1762//1762 -f 1751//1751 1762//1762 1812//1812 -f 1812//1812 1762//1762 1763//1763 -f 1812//1812 1763//1763 1811//1811 -f 1811//1811 1763//1763 1764//1764 -f 1811//1811 1764//1764 1809//1809 -f 1809//1809 1764//1764 1816//1816 -f 1817//1817 1818//1818 1819//1819 -f 1675//1675 1750//1750 1742//1742 -f 1742//1742 1750//1750 1820//1820 -f 1742//1742 1820//1820 1740//1740 -f 1740//1740 1820//1820 1817//1817 -f 1740//1740 1817//1817 1764//1764 -f 1764//1764 1817//1817 1819//1819 -f 1764//1764 1819//1819 1816//1816 -f 1821//1821 1822//1822 1823//1823 -f 1674//1674 1749//1749 1750//1750 -f 1750//1750 1749//1749 1824//1824 -f 1750//1750 1824//1824 1820//1820 -f 1820//1820 1824//1824 1821//1821 -f 1820//1820 1821//1821 1817//1817 -f 1817//1817 1821//1821 1823//1823 -f 1817//1817 1823//1823 1818//1818 -f 1825//1825 1826//1826 1827//1827 -f 1672//1672 1757//1757 1749//1749 -f 1749//1749 1757//1757 1828//1828 -f 1749//1749 1828//1828 1824//1824 -f 1824//1824 1828//1828 1825//1825 -f 1824//1824 1825//1825 1821//1821 -f 1821//1821 1825//1825 1827//1827 -f 1821//1821 1827//1827 1822//1822 -f 1669//1669 1789//1789 1757//1757 -f 1757//1757 1789//1789 1784//1784 -f 1757//1757 1784//1784 1828//1828 -f 1828//1828 1784//1784 1786//1786 -f 1828//1828 1786//1786 1825//1825 -f 1825//1825 1786//1786 1829//1829 -f 1825//1825 1829//1829 1826//1826 -f 1830//1830 1831//1831 1767//1767 -f 1767//1767 1831//1831 1832//1832 -f 1767//1767 1832//1832 1787//1787 -f 1787//1787 1832//1832 1833//1833 -f 1787//1787 1833//1833 1785//1785 -f 1785//1785 1833//1833 1834//1834 -f 1785//1785 1834//1834 1786//1786 -f 1786//1786 1834//1834 1835//1835 -f 1786//1786 1835//1835 1829//1829 -f 1664//1664 1758//1758 1739//1739 -f 1739//1739 1758//1758 1836//1836 -f 1739//1739 1836//1836 1737//1737 -f 1737//1737 1836//1836 1724//1724 -f 1737//1737 1724//1724 1767//1767 -f 1767//1767 1724//1724 1723//1723 -f 1767//1767 1723//1723 1830//1830 -f 1758//1758 1790//1790 1836//1836 -f 1836//1836 1790//1790 1792//1792 -f 1836//1836 1792//1792 1724//1724 -f 1724//1724 1792//1792 1837//1837 -f 1724//1724 1837//1837 1722//1722 -f 1838//1838 1839//1839 1840//1840 -f 1840//1840 1839//1839 1791//1791 -f 1840//1840 1791//1791 1841//1841 -f 1841//1841 1791//1791 1790//1790 -f 1841//1841 1790//1790 1748//1748 -f 1748//1748 1790//1790 1758//1758 -f 1748//1748 1758//1758 1662//1662 -f 1662//1662 1758//1758 1663//1663 -f 1839//1839 1842//1842 1791//1791 -f 1791//1791 1842//1842 1843//1843 -f 1791//1791 1843//1843 1792//1792 -f 1792//1792 1843//1843 1844//1844 -f 1792//1792 1844//1844 1837//1837 -f 1660//1660 1659//1659 1748//1748 -f 1748//1748 1659//1659 1768//1768 -f 1748//1748 1768//1768 1841//1841 -f 1841//1841 1768//1768 1769//1769 -f 1841//1841 1769//1769 1840//1840 -f 1840//1840 1769//1769 1770//1770 -f 1840//1840 1770//1770 1838//1838 -f 1838//1838 1770//1770 1845//1845 -f 1846//1846 1847//1847 1848//1848 -f 1715//1715 1747//1747 1736//1736 -f 1736//1736 1747//1747 1849//1849 -f 1736//1736 1849//1849 1734//1734 -f 1734//1734 1849//1849 1846//1846 -f 1734//1734 1846//1846 1770//1770 -f 1770//1770 1846//1846 1848//1848 -f 1770//1770 1848//1848 1845//1845 -f 1850//1850 1851//1851 1852//1852 -f 1714//1714 1746//1746 1747//1747 -f 1747//1747 1746//1746 1853//1853 -f 1747//1747 1853//1853 1849//1849 -f 1849//1849 1853//1853 1850//1850 -f 1849//1849 1850//1850 1846//1846 -f 1846//1846 1850//1850 1852//1852 -f 1846//1846 1852//1852 1847//1847 -f 1854//1854 1855//1855 1856//1856 -f 1712//1712 1759//1759 1746//1746 -f 1746//1746 1759//1759 1857//1857 -f 1746//1746 1857//1857 1853//1853 -f 1853//1853 1857//1857 1854//1854 -f 1853//1853 1854//1854 1850//1850 -f 1850//1850 1854//1854 1856//1856 -f 1850//1850 1856//1856 1851//1851 -f 1709//1709 1798//1798 1759//1759 -f 1759//1759 1798//1798 1793//1793 -f 1759//1759 1793//1793 1857//1857 -f 1857//1857 1793//1793 1795//1795 -f 1857//1857 1795//1795 1854//1854 -f 1854//1854 1795//1795 1858//1858 -f 1854//1854 1858//1858 1855//1855 -f 1859//1859 1860//1860 1773//1773 -f 1773//1773 1860//1860 1861//1861 -f 1773//1773 1861//1861 1796//1796 -f 1796//1796 1861//1861 1862//1862 -f 1796//1796 1862//1862 1794//1794 -f 1794//1794 1862//1862 1863//1863 -f 1794//1794 1863//1863 1795//1795 -f 1795//1795 1863//1863 1864//1864 -f 1795//1795 1864//1864 1858//1858 -f 1704//1704 1760//1760 1733//1733 -f 1733//1733 1760//1760 1865//1865 -f 1733//1733 1865//1865 1731//1731 -f 1731//1731 1865//1865 1721//1721 -f 1731//1731 1721//1721 1773//1773 -f 1773//1773 1721//1721 1720//1720 -f 1773//1773 1720//1720 1859//1859 -f 1760//1760 1799//1799 1865//1865 -f 1865//1865 1799//1799 1801//1801 -f 1865//1865 1801//1801 1721//1721 -f 1721//1721 1801//1801 1866//1866 -f 1721//1721 1866//1866 1719//1719 -f 1867//1867 1868//1868 1869//1869 -f 1869//1869 1868//1868 1800//1800 -f 1869//1869 1800//1800 1870//1870 -f 1870//1870 1800//1800 1799//1799 -f 1870//1870 1799//1799 1745//1745 -f 1745//1745 1799//1799 1760//1760 -f 1745//1745 1760//1760 1702//1702 -f 1702//1702 1760//1760 1703//1703 -f 1868//1868 1871//1871 1800//1800 -f 1800//1800 1871//1871 1872//1872 -f 1800//1800 1872//1872 1801//1801 -f 1801//1801 1872//1872 1873//1873 -f 1801//1801 1873//1873 1866//1866 -f 1700//1700 1699//1699 1745//1745 -f 1745//1745 1699//1699 1774//1774 -f 1745//1745 1774//1774 1870//1870 -f 1870//1870 1774//1774 1775//1775 -f 1870//1870 1775//1775 1869//1869 -f 1869//1869 1775//1775 1776//1776 -f 1869//1869 1776//1776 1867//1867 -f 1867//1867 1776//1776 1874//1874 -f 1875//1875 1876//1876 1877//1877 -f 1695//1695 1744//1744 1730//1730 -f 1730//1730 1744//1744 1878//1878 -f 1730//1730 1878//1878 1728//1728 -f 1728//1728 1878//1878 1875//1875 -f 1728//1728 1875//1875 1776//1776 -f 1776//1776 1875//1875 1877//1877 -f 1776//1776 1877//1877 1874//1874 -f 1879//1879 1880//1880 1881//1881 -f 1694//1694 1743//1743 1744//1744 -f 1744//1744 1743//1743 1882//1882 -f 1744//1744 1882//1882 1878//1878 -f 1878//1878 1882//1882 1879//1879 -f 1878//1878 1879//1879 1875//1875 -f 1875//1875 1879//1879 1881//1881 -f 1875//1875 1881//1881 1876//1876 -f 1883//1883 1884//1884 1885//1885 -f 1692//1692 1761//1761 1743//1743 -f 1743//1743 1761//1761 1886//1886 -f 1743//1743 1886//1886 1882//1882 -f 1882//1882 1886//1886 1883//1883 -f 1882//1882 1883//1883 1879//1879 -f 1879//1879 1883//1883 1885//1885 -f 1879//1879 1885//1885 1880//1880 -f 1689//1689 1752//1752 1761//1761 -f 1761//1761 1752//1752 1780//1780 -f 1761//1761 1780//1780 1886//1886 -f 1886//1886 1780//1780 1805//1805 -f 1886//1886 1805//1805 1883//1883 -f 1883//1883 1805//1805 1887//1887 -f 1883//1883 1887//1887 1884//1884 -f 1807//1807 1888//1888 1802//1802 -f 1802//1802 1888//1888 1889//1889 -f 1802//1802 1889//1889 1803//1803 -f 1803//1803 1889//1889 1890//1890 -f 1803//1803 1890//1890 1804//1804 -f 1804//1804 1890//1890 1891//1891 -f 1804//1804 1891//1891 1805//1805 -f 1805//1805 1891//1891 1892//1892 -f 1805//1805 1892//1892 1887//1887 -f 1810//1810 1893//1893 1813//1813 -f 1813//1813 1893//1893 1894//1894 -f 1813//1813 1894//1894 1814//1814 -f 1814//1814 1894//1894 1895//1895 -f 1814//1814 1895//1895 1815//1815 -f 1815//1815 1895//1895 1896//1896 -f 1815//1815 1896//1896 1808//1808 -f 1827//1827 1897//1897 1822//1822 -f 1822//1822 1897//1897 1898//1898 -f 1822//1822 1898//1898 1823//1823 -f 1823//1823 1898//1898 1899//1899 -f 1823//1823 1899//1899 1818//1818 -f 1818//1818 1899//1899 1900//1900 -f 1818//1818 1900//1900 1819//1819 -f 1819//1819 1900//1900 1901//1901 -f 1819//1819 1901//1901 1816//1816 -f 1816//1816 1901//1901 1902//1902 -f 1816//1816 1902//1902 1809//1809 -f 1809//1809 1902//1902 1903//1903 -f 1809//1809 1903//1903 1810//1810 -f 1810//1810 1903//1903 1904//1904 -f 1810//1810 1904//1904 1893//1893 -f 1832//1832 1905//1905 1833//1833 -f 1833//1833 1905//1905 1906//1906 -f 1833//1833 1906//1906 1834//1834 -f 1834//1834 1906//1906 1907//1907 -f 1834//1834 1907//1907 1835//1835 -f 1835//1835 1907//1907 1908//1908 -f 1835//1835 1908//1908 1829//1829 -f 1829//1829 1908//1908 1909//1909 -f 1829//1829 1909//1909 1826//1826 -f 1826//1826 1909//1909 1910//1910 -f 1826//1826 1910//1910 1827//1827 -f 1827//1827 1910//1910 1911//1911 -f 1827//1827 1911//1911 1897//1897 -f 1831//1831 1912//1912 1832//1832 -f 1832//1832 1912//1912 1913//1913 -f 1832//1832 1913//1913 1905//1905 -f 1843//1843 1914//1914 1844//1844 -f 1844//1844 1914//1914 1915//1915 -f 1844//1844 1915//1915 1837//1837 -f 1837//1837 1915//1915 1916//1916 -f 1837//1837 1916//1916 1722//1722 -f 1722//1722 1916//1916 1917//1917 -f 1722//1722 1917//1917 1723//1723 -f 1723//1723 1917//1917 1918//1918 -f 1723//1723 1918//1918 1830//1830 -f 1830//1830 1918//1918 1919//1919 -f 1830//1830 1919//1919 1831//1831 -f 1831//1831 1919//1919 1920//1920 -f 1831//1831 1920//1920 1912//1912 -f 1845//1845 1921//1921 1838//1838 -f 1838//1838 1921//1921 1922//1922 -f 1838//1838 1922//1922 1839//1839 -f 1839//1839 1922//1922 1923//1923 -f 1839//1839 1923//1923 1842//1842 -f 1842//1842 1923//1923 1924//1924 -f 1842//1842 1924//1924 1843//1843 -f 1843//1843 1924//1924 1925//1925 -f 1843//1843 1925//1925 1914//1914 -f 1858//1858 1926//1926 1855//1855 -f 1855//1855 1926//1926 1927//1927 -f 1855//1855 1927//1927 1856//1856 -f 1856//1856 1927//1927 1928//1928 -f 1856//1856 1928//1928 1851//1851 -f 1851//1851 1928//1928 1929//1929 -f 1851//1851 1929//1929 1852//1852 -f 1852//1852 1929//1929 1930//1930 -f 1852//1852 1930//1930 1847//1847 -f 1847//1847 1930//1930 1931//1931 -f 1847//1847 1931//1931 1848//1848 -f 1848//1848 1931//1931 1932//1932 -f 1848//1848 1932//1932 1845//1845 -f 1845//1845 1932//1932 1933//1933 -f 1845//1845 1933//1933 1921//1921 -f 1861//1861 1934//1934 1862//1862 -f 1862//1862 1934//1934 1935//1935 -f 1862//1862 1935//1935 1863//1863 -f 1863//1863 1935//1935 1936//1936 -f 1863//1863 1936//1936 1864//1864 -f 1864//1864 1936//1936 1937//1937 -f 1864//1864 1937//1937 1858//1858 -f 1858//1858 1937//1937 1938//1938 -f 1858//1858 1938//1938 1926//1926 -f 1720//1720 1939//1939 1859//1859 -f 1859//1859 1939//1939 1940//1940 -f 1859//1859 1940//1940 1860//1860 -f 1860//1860 1940//1940 1941//1941 -f 1860//1860 1941//1941 1861//1861 -f 1861//1861 1941//1941 1942//1942 -f 1861//1861 1942//1942 1934//1934 -f 1872//1872 1943//1943 1873//1873 -f 1873//1873 1943//1943 1944//1944 -f 1873//1873 1944//1944 1866//1866 -f 1866//1866 1944//1944 1945//1945 -f 1866//1866 1945//1945 1719//1719 -f 1719//1719 1945//1945 1946//1946 -f 1719//1719 1946//1946 1720//1720 -f 1720//1720 1946//1946 1947//1947 -f 1720//1720 1947//1947 1939//1939 -f 1881//1881 1948//1948 1876//1876 -f 1876//1876 1948//1948 1949//1949 -f 1876//1876 1949//1949 1877//1877 -f 1877//1877 1949//1949 1950//1950 -f 1877//1877 1950//1950 1874//1874 -f 1874//1874 1950//1950 1951//1951 -f 1874//1874 1951//1951 1867//1867 -f 1867//1867 1951//1951 1952//1952 -f 1867//1867 1952//1952 1868//1868 -f 1868//1868 1952//1952 1953//1953 -f 1868//1868 1953//1953 1871//1871 -f 1871//1871 1953//1953 1954//1954 -f 1871//1871 1954//1954 1872//1872 -f 1872//1872 1954//1954 1955//1955 -f 1872//1872 1955//1955 1943//1943 -f 1891//1891 1956//1956 1892//1892 -f 1892//1892 1956//1956 1957//1957 -f 1892//1892 1957//1957 1887//1887 -f 1887//1887 1957//1957 1958//1958 -f 1887//1887 1958//1958 1884//1884 -f 1884//1884 1958//1958 1959//1959 -f 1884//1884 1959//1959 1885//1885 -f 1885//1885 1959//1959 1960//1960 -f 1885//1885 1960//1960 1880//1880 -f 1880//1880 1960//1960 1961//1961 -f 1880//1880 1961//1961 1881//1881 -f 1881//1881 1961//1961 1962//1962 -f 1881//1881 1962//1962 1948//1948 -f 1896//1896 1963//1963 1808//1808 -f 1808//1808 1963//1963 1964//1964 -f 1808//1808 1964//1964 1725//1725 -f 1725//1725 1964//1964 1965//1965 -f 1725//1725 1965//1965 1726//1726 -f 1726//1726 1965//1965 1966//1966 -f 1726//1726 1966//1966 1807//1807 -f 1807//1807 1966//1966 1967//1967 -f 1807//1807 1967//1967 1888//1888 -f 1888//1888 1967//1967 1968//1968 -f 1888//1888 1968//1968 1889//1889 -f 1889//1889 1968//1968 1969//1969 -f 1889//1889 1969//1969 1890//1890 -f 1890//1890 1969//1969 1970//1970 -f 1890//1890 1970//1970 1891//1891 -f 1891//1891 1970//1970 1971//1971 -f 1891//1891 1971//1971 1956//1956 -f 1972//1972 1973//1973 1974//1974 -f 1975//1975 1976//1976 1977//1977 -f 1977//1977 1976//1976 1978//1978 -f 1979//1979 1980//1980 1981//1981 -f 1981//1981 1980//1980 1982//1982 -f 1983//1983 1984//1984 1985//1985 -f 1986//1986 1987//1987 1988//1988 -f 1989//1989 1990//1990 1991//1991 -f 1992//1992 1993//1993 1994//1994 -f 1995//1995 1996//1996 1997//1997 -f 1998//1998 1999//1999 2000//2000 -f 2001//2001 2002//2002 2003//2003 -f 2004//2004 2005//2005 2006//2006 -f 1970//1970 1969//1969 2004//2004 -f 1957//1957 1956//1956 2007//2007 -f 1960//1960 1959//1959 1989//1989 -f 1962//1962 1961//1961 2008//2008 -f 1949//1949 1948//1948 2009//2009 -f 1950//1950 1949//1949 2010//2010 -f 1952//1952 1951//1951 2011//2011 -f 1944//1944 1943//1943 1992//1992 -f 1946//1946 1945//1945 2012//2012 -f 1939//1939 1947//1947 2013//2013 -f 1940//1940 1939//1939 2014//2014 -f 1938//1938 1937//1937 2015//2015 -f 1930//1930 1929//1929 1995//1995 -f 1932//1932 1931//1931 2016//2016 -f 1921//1921 1933//1933 2017//2017 -f 1922//1922 1921//1921 2018//2018 -f 1917//1917 1916//1916 2019//2019 -f 1913//1913 1912//1912 1998//1998 -f 1906//1906 1905//1905 2020//2020 -f 1908//1908 1907//1907 2021//2021 -f 1909//1909 1908//1908 2022//2022 -f 1911//1911 1910//1910 2023//2023 -f 1901//1901 1900//1900 2001//2001 -f 1903//1903 1902//1902 2024//2024 -f 1893//1893 1904//1904 2025//2025 -f 1894//1894 1893//1893 2026//2026 -f 1967//1967 1966//1966 2027//2027 -f 2004//2004 1969//1969 2005//2005 -f 2005//2005 1969//1969 1968//1968 -f 2005//2005 1968//1968 1967//1967 -f 2027//2027 1966//1966 2028//2028 -f 1966//1966 1965//1965 2028//2028 -f 2028//2028 1965//1965 1964//1964 -f 2028//2028 1964//1964 2029//2029 -f 2029//2029 1964//1964 1963//1963 -f 2029//2029 1963//1963 1896//1896 -f 1896//1896 1895//1895 2030//2030 -f 2030//2030 1895//1895 1894//1894 -f 2001//2001 1900//1900 2002//2002 -f 2002//2002 1900//1900 1899//1899 -f 2002//2002 1899//1899 1898//1898 -f 1898//1898 1897//1897 2031//2031 -f 2031//2031 1897//1897 1911//1911 -f 1909//1909 2022//2022 1910//1910 -f 1998//1998 1912//1912 1999//1999 -f 1999//1999 1912//1912 1920//1920 -f 1999//1999 1920//1920 1919//1919 -f 1919//1919 1918//1918 2032//2032 -f 2032//2032 1918//1918 1917//1917 -f 2019//2019 1916//1916 2033//2033 -f 1916//1916 1915//1915 2033//2033 -f 2033//2033 1915//1915 1914//1914 -f 2033//2033 1914//1914 2034//2034 -f 1923//1923 2035//2035 1924//1924 -f 1924//1924 2035//2035 2034//2034 -f 1924//1924 2034//2034 1925//1925 -f 1925//1925 2034//2034 1914//1914 -f 1922//1922 2018//2018 1923//1923 -f 1995//1995 1929//1929 1996//1996 -f 1996//1996 1929//1929 1928//1928 -f 1996//1996 1928//1928 1927//1927 -f 1927//1927 1926//1926 2036//2036 -f 2036//2036 1926//1926 1938//1938 -f 2015//2015 1937//1937 2037//2037 -f 1937//1937 1936//1936 2037//2037 -f 2037//2037 1936//1936 1935//1935 -f 2037//2037 1935//1935 2038//2038 -f 1935//1935 1934//1934 2038//2038 -f 2038//2038 1934//1934 1942//1942 -f 2038//2038 1942//1942 2039//2039 -f 2039//2039 1942//1942 1941//1941 -f 2039//2039 1941//1941 1940//1940 -f 1992//1992 1943//1943 1993//1993 -f 1993//1993 1943//1943 1955//1955 -f 1993//1993 1955//1955 1954//1954 -f 1954//1954 1953//1953 2040//2040 -f 2040//2040 1953//1953 1952//1952 -f 1950//1950 2010//2010 1951//1951 -f 1989//1989 1959//1959 1990//1990 -f 1990//1990 1959//1959 1958//1958 -f 1990//1990 1958//1958 1957//1957 -f 2029//2029 2041//2041 2028//2028 -f 2028//2028 2041//2041 2042//2042 -f 2028//2028 2042//2042 2027//2027 -f 2027//2027 2042//2042 1988//1988 -f 2043//2043 2044//2044 2025//2025 -f 1904//1904 1903//1903 2025//2025 -f 2025//2025 1903//1903 2024//2024 -f 2025//2025 2024//2024 2043//2043 -f 2043//2043 2024//2024 2045//2045 -f 2043//2043 2045//2045 2046//2046 -f 2046//2046 2045//2045 2047//2047 -f 2048//2048 2049//2049 2021//2021 -f 1907//1907 1906//1906 2021//2021 -f 2021//2021 1906//1906 2020//2020 -f 2021//2021 2020//2020 2048//2048 -f 2048//2048 2020//2020 2050//2050 -f 2048//2048 2050//2050 2051//2051 -f 2051//2051 2050//2050 2052//2052 -f 2035//2035 1981//1981 2034//2034 -f 2034//2034 1981//1981 1982//1982 -f 2034//2034 1982//1982 2033//2033 -f 2033//2033 1982//1982 2053//2053 -f 2033//2033 2053//2053 2019//2019 -f 2019//2019 2053//2053 2054//2054 -f 2055//2055 2056//2056 2017//2017 -f 1933//1933 1932//1932 2017//2017 -f 2017//2017 1932//1932 2016//2016 -f 2017//2017 2016//2016 2055//2055 -f 2055//2055 2016//2016 2057//2057 -f 2055//2055 2057//2057 2058//2058 -f 2058//2058 2057//2057 2059//2059 -f 2039//2039 1977//1977 2038//2038 -f 2038//2038 1977//1977 1978//1978 -f 2038//2038 1978//1978 2037//2037 -f 2037//2037 1978//1978 2060//2060 -f 2037//2037 2060//2060 2015//2015 -f 2015//2015 2060//2060 2061//2061 -f 2062//2062 2063//2063 2013//2013 -f 1947//1947 1946//1946 2013//2013 -f 2013//2013 1946//1946 2012//2012 -f 2013//2013 2012//2012 2062//2062 -f 2062//2062 2012//2012 2064//2064 -f 2062//2062 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2067//2067 2068//2068 2009//2009 -f 2069//2069 2070//2070 2007//2007 -f 1956//1956 1971//1971 2007//2007 -f 2007//2007 1971//1971 2071//2071 -f 2007//2007 2071//2071 2069//2069 -f 2069//2069 2071//2071 2072//2072 -f 2073//2073 2074//2074 2006//2006 -f 2006//2006 2074//2074 2072//2072 -f 2006//2006 2072//2072 2004//2004 -f 2004//2004 2072//2072 2071//2071 -f 2004//2004 2071//2071 1970//1970 -f 1970//1970 2071//2071 1971//1971 -f 1967//1967 2027//2027 2005//2005 -f 2005//2005 2027//2027 1988//1988 -f 2005//2005 1988//1988 2006//2006 -f 2006//2006 1988//1988 1987//1987 -f 2006//2006 1987//1987 2073//2073 -f 1986//1986 1988//1988 2075//2075 -f 2075//2075 1988//1988 2042//2042 -f 2075//2075 2042//2042 2076//2076 -f 2076//2076 2042//2042 2041//2041 -f 2076//2076 2041//2041 2077//2077 -f 2078//2078 2079//2079 2080//2080 -f 1896//1896 2030//2030 2029//2029 -f 2029//2029 2030//2030 2078//2078 -f 2029//2029 2078//2078 2041//2041 -f 2041//2041 2078//2078 2080//2080 -f 2041//2041 2080//2080 2077//2077 -f 1894//1894 2026//2026 2030//2030 -f 2030//2030 2026//2026 2081//2081 -f 2030//2030 2081//2081 2078//2078 -f 2078//2078 2081//2081 2082//2082 -f 2078//2078 2082//2082 2079//2079 -f 1893//1893 2025//2025 2026//2026 -f 2026//2026 2025//2025 2044//2044 -f 2026//2026 2044//2044 2081//2081 -f 2081//2081 2044//2044 2083//2083 -f 2081//2081 2083//2083 2082//2082 -f 2046//2046 2084//2084 2043//2043 -f 2043//2043 2084//2084 2085//2085 -f 2043//2043 2085//2085 2044//2044 -f 2044//2044 2085//2085 2086//2086 -f 2044//2044 2086//2086 2083//2083 -f 1902//1902 1901//1901 2024//2024 -f 2024//2024 1901//1901 2001//2001 -f 2024//2024 2001//2001 2045//2045 -f 2045//2045 2001//2001 2003//2003 -f 2045//2045 2003//2003 2047//2047 -f 2047//2047 2003//2003 2087//2087 -f 2088//2088 2089//2089 2090//2090 -f 1898//1898 2031//2031 2002//2002 -f 2002//2002 2031//2031 2088//2088 -f 2002//2002 2088//2088 2003//2003 -f 2003//2003 2088//2088 2090//2090 -f 2003//2003 2090//2090 2087//2087 -f 1911//1911 2023//2023 2031//2031 -f 2031//2031 2023//2023 1985//1985 -f 2031//2031 1985//1985 2088//2088 -f 2088//2088 1985//1985 1984//1984 -f 2088//2088 1984//1984 2089//2089 -f 1910//1910 2022//2022 2023//2023 -f 2023//2023 2022//2022 2091//2091 -f 2023//2023 2091//2091 1985//1985 -f 1985//1985 2091//2091 2092//2092 -f 1985//1985 2092//2092 1983//1983 -f 1908//1908 2021//2021 2022//2022 -f 2022//2022 2021//2021 2049//2049 -f 2022//2022 2049//2049 2091//2091 -f 2091//2091 2049//2049 2093//2093 -f 2091//2091 2093//2093 2092//2092 -f 2051//2051 2094//2094 2048//2048 -f 2048//2048 2094//2094 2095//2095 -f 2048//2048 2095//2095 2049//2049 -f 2049//2049 2095//2095 2096//2096 -f 2049//2049 2096//2096 2093//2093 -f 1905//1905 1913//1913 2020//2020 -f 2020//2020 1913//1913 1998//1998 -f 2020//2020 1998//1998 2050//2050 -f 2050//2050 1998//1998 2000//2000 -f 2050//2050 2000//2000 2052//2052 -f 2052//2052 2000//2000 2097//2097 -f 2098//2098 2099//2099 2100//2100 -f 1919//1919 2032//2032 1999//1999 -f 1999//1999 2032//2032 2098//2098 -f 1999//1999 2098//2098 2000//2000 -f 2000//2000 2098//2098 2100//2100 -f 2000//2000 2100//2100 2097//2097 -f 1917//1917 2019//2019 2032//2032 -f 2032//2032 2019//2019 2054//2054 -f 2032//2032 2054//2054 2098//2098 -f 2098//2098 2054//2054 2101//2101 -f 2098//2098 2101//2101 2099//2099 -f 1980//1980 2102//2102 1982//1982 -f 1982//1982 2102//2102 2103//2103 -f 1982//1982 2103//2103 2053//2053 -f 2053//2053 2103//2103 2104//2104 -f 2053//2053 2104//2104 2054//2054 -f 2054//2054 2104//2104 2105//2105 -f 2054//2054 2105//2105 2101//2101 -f 1923//1923 2018//2018 2035//2035 -f 2035//2035 2018//2018 2106//2106 -f 2035//2035 2106//2106 1981//1981 -f 1981//1981 2106//2106 2107//2107 -f 1981//1981 2107//2107 1979//1979 -f 1921//1921 2017//2017 2018//2018 -f 2018//2018 2017//2017 2056//2056 -f 2018//2018 2056//2056 2106//2106 -f 2106//2106 2056//2056 2108//2108 -f 2106//2106 2108//2108 2107//2107 -f 2058//2058 2109//2109 2055//2055 -f 2055//2055 2109//2109 2110//2110 -f 2055//2055 2110//2110 2056//2056 -f 2056//2056 2110//2110 2111//2111 -f 2056//2056 2111//2111 2108//2108 -f 1931//1931 1930//1930 2016//2016 -f 2016//2016 1930//1930 1995//1995 -f 2016//2016 1995//1995 2057//2057 -f 2057//2057 1995//1995 1997//1997 -f 2057//2057 1997//1997 2059//2059 -f 2059//2059 1997//1997 2112//2112 -f 2113//2113 2114//2114 2115//2115 -f 1927//1927 2036//2036 1996//1996 -f 1996//1996 2036//2036 2113//2113 -f 1996//1996 2113//2113 1997//1997 -f 1997//1997 2113//2113 2115//2115 -f 1997//1997 2115//2115 2112//2112 -f 1938//1938 2015//2015 2036//2036 -f 2036//2036 2015//2015 2061//2061 -f 2036//2036 2061//2061 2113//2113 -f 2113//2113 2061//2061 2116//2116 -f 2113//2113 2116//2116 2114//2114 -f 1976//1976 2117//2117 1978//1978 -f 1978//1978 2117//2117 2118//2118 -f 1978//1978 2118//2118 2060//2060 -f 2060//2060 2118//2118 2119//2119 -f 2060//2060 2119//2119 2061//2061 -f 2061//2061 2119//2119 2120//2120 -f 2061//2061 2120//2120 2116//2116 -f 1940//1940 2014//2014 2039//2039 -f 2039//2039 2014//2014 2121//2121 -f 2039//2039 2121//2121 1977//1977 -f 1977//1977 2121//2121 2122//2122 -f 1977//1977 2122//2122 1975//1975 -f 1939//1939 2013//2013 2014//2014 -f 2014//2014 2013//2013 2063//2063 -f 2014//2014 2063//2063 2121//2121 -f 2121//2121 2063//2063 2123//2123 -f 2121//2121 2123//2123 2122//2122 -f 2065//2065 2124//2124 2062//2062 -f 2062//2062 2124//2124 2125//2125 -f 2062//2062 2125//2125 2063//2063 -f 2063//2063 2125//2125 2126//2126 -f 2063//2063 2126//2126 2123//2123 -f 1945//1945 1944//1944 2012//2012 -f 2012//2012 1944//1944 1992//1992 -f 2012//2012 1992//1992 2064//2064 -f 2064//2064 1992//1992 1994//1994 -f 2064//2064 1994//1994 2066//2066 -f 2066//2066 1994//1994 2127//2127 -f 2128//2128 2129//2129 2130//2130 -f 1954//1954 2040//2040 1993//1993 -f 1993//1993 2040//2040 2128//2128 -f 1993//1993 2128//2128 1994//1994 -f 1994//1994 2128//2128 2130//2130 -f 1994//1994 2130//2130 2127//2127 -f 1952//1952 2011//2011 2040//2040 -f 2040//2040 2011//2011 1974//1974 -f 2040//2040 1974//1974 2128//2128 -f 2128//2128 1974//1974 1973//1973 -f 2128//2128 1973//1973 2129//2129 -f 1951//1951 2010//2010 2011//2011 -f 2011//2011 2010//2010 2131//2131 -f 2011//2011 2131//2131 1974//1974 -f 1974//1974 2131//2131 2132//2132 -f 1974//1974 2132//2132 1972//1972 -f 1949//1949 2009//2009 2010//2010 -f 2010//2010 2009//2009 2068//2068 -f 2010//2010 2068//2068 2131//2131 -f 2131//2131 2068//2068 2133//2133 -f 2131//2131 2133//2133 2132//2132 -f 2134//2134 2135//2135 2136//2136 -f 2136//2136 2135//2135 2067//2067 -f 2136//2136 2067//2067 2008//2008 -f 2008//2008 2067//2067 2009//2009 -f 2008//2008 2009//2009 1962//1962 -f 1962//1962 2009//2009 1948//1948 -f 2135//2135 2137//2137 2067//2067 -f 2067//2067 2137//2137 2138//2138 -f 2067//2067 2138//2138 2068//2068 -f 2068//2068 2138//2138 2139//2139 -f 2068//2068 2139//2139 2133//2133 -f 1961//1961 1960//1960 2008//2008 -f 2008//2008 1960//1960 1989//1989 -f 2008//2008 1989//1989 2136//2136 -f 2136//2136 1989//1989 1991//1991 -f 2136//2136 1991//1991 2134//2134 -f 2134//2134 1991//1991 2140//2140 -f 1957//1957 2007//2007 1990//1990 -f 1990//1990 2007//2007 2070//2070 -f 1990//1990 2070//2070 1991//1991 -f 1991//1991 2070//2070 2141//2141 -f 1991//1991 2141//2141 2140//2140 -f 2074//2074 2142//2142 2072//2072 -f 2072//2072 2142//2142 2143//2143 -f 2072//2072 2143//2143 2069//2069 -f 2069//2069 2143//2143 2144//2144 -f 2069//2069 2144//2144 2070//2070 -f 2070//2070 2144//2144 2145//2145 -f 2070//2070 2145//2145 2141//2141 -f 2146//2146 2147//2147 2104//2104 -f 2104//2104 2147//2147 2105//2105 -f 2105//2105 2147//2147 2148//2148 -f 2105//2105 2148//2148 2101//2101 -f 2101//2101 2148//2148 2149//2149 -f 2101//2101 2149//2149 2099//2099 -f 2099//2099 2149//2149 2150//2150 -f 2099//2099 2150//2150 2100//2100 -f 2100//2100 2150//2150 2097//2097 -f 2097//2097 2150//2150 2151//2151 -f 2097//2097 2151//2151 2052//2052 -f 2151//2151 2152//2152 2052//2052 -f 2052//2052 2152//2152 2153//2153 -f 2052//2052 2153//2153 2051//2051 -f 2051//2051 2153//2153 2154//2154 -f 2155//2155 1984//1984 2156//2156 -f 2156//2156 1984//1984 1983//1983 -f 2156//2156 1983//1983 2157//2157 -f 2157//2157 1983//1983 2092//2092 -f 2157//2157 2092//2092 2158//2158 -f 2158//2158 2092//2092 2093//2093 -f 2158//2158 2093//2093 2159//2159 -f 2159//2159 2093//2093 2096//2096 -f 2159//2159 2096//2096 2160//2160 -f 2160//2160 2096//2096 2095//2095 -f 2160//2160 2095//2095 2154//2154 -f 2154//2154 2095//2095 2094//2094 -f 2154//2154 2094//2094 2051//2051 -f 2161//2161 2082//2082 2162//2162 -f 2162//2162 2082//2082 2083//2083 -f 2162//2162 2083//2083 2163//2163 -f 2163//2163 2083//2083 2086//2086 -f 2163//2163 2086//2086 2164//2164 -f 2164//2164 2086//2086 2085//2085 -f 2164//2164 2085//2085 2165//2165 -f 2165//2165 2085//2085 2084//2084 -f 2165//2165 2084//2084 2166//2166 -f 2166//2166 2084//2084 2046//2046 -f 2166//2166 2046//2046 2167//2167 -f 2167//2167 2046//2046 2047//2047 -f 2167//2167 2047//2047 2168//2168 -f 2168//2168 2047//2047 2087//2087 -f 2168//2168 2087//2087 2169//2169 -f 2169//2169 2087//2087 2090//2090 -f 2169//2169 2090//2090 2155//2155 -f 2155//2155 2090//2090 2089//2089 -f 2155//2155 2089//2089 1984//1984 -f 2170//2170 1987//1987 2171//2171 -f 2171//2171 1987//1987 1986//1986 -f 2171//2171 1986//1986 2172//2172 -f 2172//2172 1986//1986 2075//2075 -f 2172//2172 2075//2075 2173//2173 -f 2173//2173 2075//2075 2076//2076 -f 2173//2173 2076//2076 2174//2174 -f 2174//2174 2076//2076 2077//2077 -f 2174//2174 2077//2077 2175//2175 -f 2175//2175 2077//2077 2080//2080 -f 2175//2175 2080//2080 2161//2161 -f 2161//2161 2080//2080 2079//2079 -f 2161//2161 2079//2079 2082//2082 -f 2176//2176 2145//2145 2177//2177 -f 2177//2177 2145//2145 2144//2144 -f 2177//2177 2144//2144 2178//2178 -f 2178//2178 2144//2144 2143//2143 -f 2178//2178 2143//2143 2179//2179 -f 2179//2179 2143//2143 2142//2142 -f 2179//2179 2142//2142 2180//2180 -f 2180//2180 2142//2142 2074//2074 -f 2180//2180 2074//2074 2170//2170 -f 2170//2170 2074//2074 2073//2073 -f 2170//2170 2073//2073 1987//1987 -f 2181//2181 1973//1973 2182//2182 -f 2182//2182 1973//1973 1972//1972 -f 2182//2182 1972//1972 2183//2183 -f 2183//2183 1972//1972 2132//2132 -f 2183//2183 2132//2132 2184//2184 -f 2184//2184 2132//2132 2133//2133 -f 2184//2184 2133//2133 2185//2185 -f 2185//2185 2133//2133 2139//2139 -f 2185//2185 2139//2139 2186//2186 -f 2186//2186 2139//2139 2138//2138 -f 2186//2186 2138//2138 2187//2187 -f 2187//2187 2138//2138 2137//2137 -f 2187//2187 2137//2137 2188//2188 -f 2188//2188 2137//2137 2135//2135 -f 2188//2188 2135//2135 2189//2189 -f 2189//2189 2135//2135 2134//2134 -f 2189//2189 2134//2134 2190//2190 -f 2190//2190 2134//2134 2140//2140 -f 2190//2190 2140//2140 2176//2176 -f 2176//2176 2140//2140 2141//2141 -f 2176//2176 2141//2141 2145//2145 -f 2191//2191 2124//2124 2192//2192 -f 2192//2192 2124//2124 2065//2065 -f 2192//2192 2065//2065 2193//2193 -f 2193//2193 2065//2065 2066//2066 -f 2193//2193 2066//2066 2194//2194 -f 2194//2194 2066//2066 2127//2127 -f 2194//2194 2127//2127 2195//2195 -f 2195//2195 2127//2127 2130//2130 -f 2195//2195 2130//2130 2181//2181 -f 2181//2181 2130//2130 2129//2129 -f 2181//2181 2129//2129 1973//1973 -f 2196//2196 2116//2116 2197//2197 -f 2197//2197 2116//2116 2120//2120 -f 2197//2197 2120//2120 2198//2198 -f 2198//2198 2120//2120 2119//2119 -f 2198//2198 2119//2119 2199//2199 -f 2199//2199 2119//2119 2118//2118 -f 2199//2199 2118//2118 2200//2200 -f 2200//2200 2118//2118 2117//2117 -f 2200//2200 2117//2117 2201//2201 -f 2201//2201 2117//2117 1976//1976 -f 2201//2201 1976//1976 2202//2202 -f 2202//2202 1976//1976 1975//1975 -f 2202//2202 1975//1975 2203//2203 -f 2203//2203 1975//1975 2122//2122 -f 2203//2203 2122//2122 2204//2204 -f 2204//2204 2122//2122 2123//2123 -f 2204//2204 2123//2123 2205//2205 -f 2205//2205 2123//2123 2126//2126 -f 2205//2205 2126//2126 2191//2191 -f 2191//2191 2126//2126 2125//2125 -f 2191//2191 2125//2125 2124//2124 -f 2206//2206 2058//2058 2207//2207 -f 2207//2207 2058//2058 2059//2059 -f 2207//2207 2059//2059 2208//2208 -f 2208//2208 2059//2059 2112//2112 -f 2208//2208 2112//2112 2209//2209 -f 2209//2209 2112//2112 2115//2115 -f 2209//2209 2115//2115 2196//2196 -f 2196//2196 2115//2115 2114//2114 -f 2196//2196 2114//2114 2116//2116 -f 2104//2104 2103//2103 2146//2146 -f 2146//2146 2103//2103 2102//2102 -f 2146//2146 2102//2102 2210//2210 -f 2210//2210 2102//2102 1980//1980 -f 2210//2210 1980//1980 2211//2211 -f 2211//2211 1980//1980 1979//1979 -f 2211//2211 1979//1979 2212//2212 -f 2212//2212 1979//1979 2107//2107 -f 2212//2212 2107//2107 2213//2213 -f 2213//2213 2107//2107 2108//2108 -f 2213//2213 2108//2108 2214//2214 -f 2214//2214 2108//2108 2111//2111 -f 2214//2214 2111//2111 2215//2215 -f 2215//2215 2111//2111 2110//2110 -f 2215//2215 2110//2110 2206//2206 -f 2206//2206 2110//2110 2109//2109 -f 2206//2206 2109//2109 2058//2058 -f 2216//2216 2217//2217 2218//2218 -f 2219//2219 2220//2220 2221//2221 -f 2222//2222 2223//2223 2224//2224 -f 2225//2225 2226//2226 2227//2227 -f 2228//2228 2229//2229 2230//2230 -f 2231//2231 2232//2232 2233//2233 -f 2234//2234 2235//2235 2236//2236 -f 2237//2237 2238//2238 2239//2239 -f 2240//2240 2241//2241 2242//2242 -f 2243//2243 2244//2244 2245//2245 -f 2246//2246 2247//2247 2248//2248 -f 2249//2249 2250//2250 2251//2251 -f 2252//2252 2253//2253 2254//2254 -f 2242//2242 2255//2255 2256//2256 -f 2253//2253 2257//2257 2258//2258 -f 2255//2255 2259//2259 2260//2260 -f 2184//2184 2185//2185 2261//2261 -f 2182//2182 2183//2183 2262//2262 -f 2191//2191 2192//2192 2263//2263 -f 2209//2209 2196//2196 2264//2264 -f 2213//2213 2214//2214 2265//2265 -f 2211//2211 2212//2212 2266//2266 -f 2146//2146 2210//2210 2267//2267 -f 2148//2148 2147//2147 2268//2268 -f 2150//2150 2149//2149 2269//2269 -f 2165//2165 2166//2166 2270//2270 -f 2163//2163 2164//2164 2271//2271 -f 2175//2175 2161//2161 2272//2272 -f 2180//2180 2273//2273 2274//2274 -f 2170//2170 2171//2171 2275//2275 -f 2172//2172 2173//2173 2276//2276 -f 2175//2175 2272//2272 2174//2174 -f 2156//2156 2277//2277 2260//2260 -f 2167//2167 2168//2168 2259//2259 -f 2259//2259 2168//2168 2169//2169 -f 2259//2259 2169//2169 2260//2260 -f 2260//2260 2169//2169 2155//2155 -f 2260//2260 2155//2155 2156//2156 -f 2156//2156 2157//2157 2277//2277 -f 2277//2277 2157//2157 2158//2158 -f 2277//2277 2158//2158 2278//2278 -f 2278//2278 2158//2158 2159//2159 -f 2278//2278 2159//2159 2279//2279 -f 2159//2159 2160//2160 2279//2279 -f 2279//2279 2160//2160 2154//2154 -f 2279//2279 2154//2154 2280//2280 -f 2280//2280 2154//2154 2153//2153 -f 2280//2280 2153//2153 2152//2152 -f 2206//2206 2207//2207 2281//2281 -f 2209//2209 2264//2264 2208//2208 -f 2197//2197 2198//2198 2257//2257 -f 2257//2257 2198//2198 2199//2199 -f 2257//2257 2199//2199 2258//2258 -f 2258//2258 2199//2199 2200//2200 -f 2258//2258 2200//2200 2282//2282 -f 2200//2200 2201//2201 2282//2282 -f 2282//2282 2201//2201 2202//2202 -f 2282//2282 2202//2202 2283//2283 -f 2205//2205 2284//2284 2204//2204 -f 2204//2204 2284//2284 2283//2283 -f 2204//2204 2283//2283 2203//2203 -f 2203//2203 2283//2283 2202//2202 -f 2194//2194 2195//2195 2285//2285 -f 2182//2182 2262//2262 2181//2181 -f 2187//2187 2188//2188 2286//2286 -f 2286//2286 2188//2188 2189//2189 -f 2286//2286 2189//2189 2287//2287 -f 2189//2189 2190//2190 2287//2287 -f 2287//2287 2190//2190 2176//2176 -f 2287//2287 2176//2176 2288//2288 -f 2176//2176 2177//2177 2288//2288 -f 2288//2288 2177//2177 2178//2178 -f 2288//2288 2178//2178 2274//2274 -f 2274//2274 2178//2178 2179//2179 -f 2274//2274 2179//2179 2180//2180 -f 2273//2273 2289//2289 2290//2290 -f 2255//2255 2260//2260 2256//2256 -f 2256//2256 2260//2260 2277//2277 -f 2256//2256 2277//2277 2291//2291 -f 2291//2291 2277//2277 2278//2278 -f 2291//2291 2278//2278 2292//2292 -f 2292//2292 2278//2278 2279//2279 -f 2292//2292 2279//2279 2293//2293 -f 2293//2293 2279//2279 2280//2280 -f 2293//2293 2280//2280 2294//2294 -f 2253//2253 2258//2258 2254//2254 -f 2254//2254 2258//2258 2282//2282 -f 2254//2254 2282//2282 2295//2295 -f 2295//2295 2282//2282 2283//2283 -f 2295//2295 2283//2283 2296//2296 -f 2296//2296 2283//2283 2284//2284 -f 2296//2296 2284//2284 2297//2297 -f 2273//2273 2290//2290 2274//2274 -f 2274//2274 2290//2290 2298//2298 -f 2274//2274 2298//2298 2288//2288 -f 2288//2288 2298//2298 2299//2299 -f 2288//2288 2299//2299 2287//2287 -f 2287//2287 2299//2299 2300//2300 -f 2287//2287 2300//2300 2286//2286 -f 2289//2289 2301//2301 2302//2302 -f 2161//2161 2162//2162 2272//2272 -f 2272//2272 2162//2162 2303//2303 -f 2272//2272 2303//2303 2304//2304 -f 2304//2304 2303//2303 2305//2305 -f 2304//2304 2305//2305 2306//2306 -f 2306//2306 2305//2305 2248//2248 -f 2242//2242 2256//2256 2307//2307 -f 2307//2307 2256//2256 2291//2291 -f 2307//2307 2291//2291 2308//2308 -f 2308//2308 2291//2291 2292//2292 -f 2308//2308 2292//2292 2309//2309 -f 2309//2309 2292//2292 2293//2293 -f 2309//2309 2293//2293 2310//2310 -f 2310//2310 2293//2293 2294//2294 -f 2310//2310 2294//2294 2239//2239 -f 2149//2149 2148//2148 2269//2269 -f 2269//2269 2148//2148 2268//2268 -f 2269//2269 2268//2268 2311//2311 -f 2311//2311 2268//2268 2312//2312 -f 2311//2311 2312//2312 2313//2313 -f 2313//2313 2312//2312 2236//2236 -f 2214//2214 2215//2215 2265//2265 -f 2265//2265 2215//2215 2314//2314 -f 2265//2265 2314//2314 2315//2315 -f 2315//2315 2314//2314 2316//2316 -f 2315//2315 2316//2316 2317//2317 -f 2317//2317 2316//2316 2230//2230 -f 2252//2252 2254//2254 2318//2318 -f 2318//2318 2254//2254 2295//2295 -f 2318//2318 2295//2295 2319//2319 -f 2319//2319 2295//2295 2296//2296 -f 2319//2319 2296//2296 2320//2320 -f 2320//2320 2296//2296 2297//2297 -f 2320//2320 2297//2297 2321//2321 -f 2195//2195 2181//2181 2285//2285 -f 2285//2285 2181//2181 2262//2262 -f 2285//2285 2262//2262 2322//2322 -f 2322//2322 2262//2262 2323//2323 -f 2322//2322 2323//2323 2324//2324 -f 2324//2324 2323//2323 2221//2221 -f 2289//2289 2302//2302 2290//2290 -f 2290//2290 2302//2302 2325//2325 -f 2290//2290 2325//2325 2298//2298 -f 2298//2298 2325//2325 2326//2326 -f 2298//2298 2326//2326 2299//2299 -f 2299//2299 2326//2326 2327//2327 -f 2299//2299 2327//2327 2300//2300 -f 2180//2180 2170//2170 2273//2273 -f 2273//2273 2170//2170 2275//2275 -f 2273//2273 2275//2275 2289//2289 -f 2289//2289 2275//2275 2328//2328 -f 2289//2289 2328//2328 2301//2301 -f 2301//2301 2328//2328 2251//2251 -f 2301//2301 2251//2251 2329//2329 -f 2329//2329 2251//2251 2250//2250 -f 2330//2330 2249//2249 2331//2331 -f 2331//2331 2249//2249 2251//2251 -f 2331//2331 2251//2251 2332//2332 -f 2332//2332 2251//2251 2328//2328 -f 2332//2332 2328//2328 2276//2276 -f 2276//2276 2328//2328 2275//2275 -f 2276//2276 2275//2275 2172//2172 -f 2172//2172 2275//2275 2171//2171 -f 2173//2173 2174//2174 2276//2276 -f 2276//2276 2174//2174 2272//2272 -f 2276//2276 2272//2272 2332//2332 -f 2332//2332 2272//2272 2304//2304 -f 2332//2332 2304//2304 2331//2331 -f 2331//2331 2304//2304 2306//2306 -f 2331//2331 2306//2306 2330//2330 -f 2330//2330 2306//2306 2333//2333 -f 2248//2248 2247//2247 2306//2306 -f 2306//2306 2247//2247 2334//2334 -f 2306//2306 2334//2334 2333//2333 -f 2162//2162 2163//2163 2303//2303 -f 2303//2303 2163//2163 2271//2271 -f 2303//2303 2271//2271 2305//2305 -f 2305//2305 2271//2271 2335//2335 -f 2305//2305 2335//2335 2248//2248 -f 2248//2248 2335//2335 2245//2245 -f 2248//2248 2245//2245 2246//2246 -f 2246//2246 2245//2245 2244//2244 -f 2336//2336 2243//2243 2337//2337 -f 2337//2337 2243//2243 2245//2245 -f 2337//2337 2245//2245 2338//2338 -f 2338//2338 2245//2245 2335//2335 -f 2338//2338 2335//2335 2270//2270 -f 2270//2270 2335//2335 2271//2271 -f 2270//2270 2271//2271 2165//2165 -f 2165//2165 2271//2271 2164//2164 -f 2166//2166 2167//2167 2270//2270 -f 2270//2270 2167//2167 2259//2259 -f 2270//2270 2259//2259 2338//2338 -f 2338//2338 2259//2259 2255//2255 -f 2338//2338 2255//2255 2337//2337 -f 2337//2337 2255//2255 2242//2242 -f 2337//2337 2242//2242 2336//2336 -f 2336//2336 2242//2242 2241//2241 -f 2240//2240 2242//2242 2339//2339 -f 2339//2339 2242//2242 2307//2307 -f 2339//2339 2307//2307 2340//2340 -f 2340//2340 2307//2307 2308//2308 -f 2340//2340 2308//2308 2341//2341 -f 2341//2341 2308//2308 2309//2309 -f 2341//2341 2309//2309 2342//2342 -f 2342//2342 2309//2309 2310//2310 -f 2342//2342 2310//2310 2343//2343 -f 2239//2239 2238//2238 2310//2310 -f 2310//2310 2238//2238 2344//2344 -f 2310//2310 2344//2344 2343//2343 -f 2345//2345 2237//2237 2346//2346 -f 2346//2346 2237//2237 2239//2239 -f 2346//2346 2239//2239 2347//2347 -f 2347//2347 2239//2239 2294//2294 -f 2347//2347 2294//2294 2348//2348 -f 2348//2348 2294//2294 2280//2280 -f 2348//2348 2280//2280 2151//2151 -f 2151//2151 2280//2280 2152//2152 -f 2151//2151 2150//2150 2348//2348 -f 2348//2348 2150//2150 2269//2269 -f 2348//2348 2269//2269 2347//2347 -f 2347//2347 2269//2269 2311//2311 -f 2347//2347 2311//2311 2346//2346 -f 2346//2346 2311//2311 2313//2313 -f 2346//2346 2313//2313 2345//2345 -f 2345//2345 2313//2313 2349//2349 -f 2236//2236 2235//2235 2313//2313 -f 2313//2313 2235//2235 2350//2350 -f 2313//2313 2350//2350 2349//2349 -f 2147//2147 2146//2146 2268//2268 -f 2268//2268 2146//2146 2267//2267 -f 2268//2268 2267//2267 2312//2312 -f 2312//2312 2267//2267 2351//2351 -f 2312//2312 2351//2351 2236//2236 -f 2236//2236 2351//2351 2233//2233 -f 2236//2236 2233//2233 2234//2234 -f 2234//2234 2233//2233 2232//2232 -f 2352//2352 2231//2231 2353//2353 -f 2353//2353 2231//2231 2233//2233 -f 2353//2353 2233//2233 2354//2354 -f 2354//2354 2233//2233 2351//2351 -f 2354//2354 2351//2351 2266//2266 -f 2266//2266 2351//2351 2267//2267 -f 2266//2266 2267//2267 2211//2211 -f 2211//2211 2267//2267 2210//2210 -f 2212//2212 2213//2213 2266//2266 -f 2266//2266 2213//2213 2265//2265 -f 2266//2266 2265//2265 2354//2354 -f 2354//2354 2265//2265 2315//2315 -f 2354//2354 2315//2315 2353//2353 -f 2353//2353 2315//2315 2317//2317 -f 2353//2353 2317//2317 2352//2352 -f 2352//2352 2317//2317 2355//2355 -f 2230//2230 2229//2229 2317//2317 -f 2317//2317 2229//2229 2356//2356 -f 2317//2317 2356//2356 2355//2355 -f 2226//2226 2228//2228 2227//2227 -f 2227//2227 2228//2228 2230//2230 -f 2227//2227 2230//2230 2357//2357 -f 2357//2357 2230//2230 2316//2316 -f 2357//2357 2316//2316 2281//2281 -f 2281//2281 2316//2316 2314//2314 -f 2281//2281 2314//2314 2206//2206 -f 2206//2206 2314//2314 2215//2215 -f 2358//2358 2225//2225 2359//2359 -f 2359//2359 2225//2225 2227//2227 -f 2359//2359 2227//2227 2360//2360 -f 2360//2360 2227//2227 2357//2357 -f 2360//2360 2357//2357 2264//2264 -f 2264//2264 2357//2357 2281//2281 -f 2264//2264 2281//2281 2208//2208 -f 2208//2208 2281//2281 2207//2207 -f 2196//2196 2197//2197 2264//2264 -f 2264//2264 2197//2197 2257//2257 -f 2264//2264 2257//2257 2360//2360 -f 2360//2360 2257//2257 2253//2253 -f 2360//2360 2253//2253 2359//2359 -f 2359//2359 2253//2253 2252//2252 -f 2359//2359 2252//2252 2358//2358 -f 2358//2358 2252//2252 2361//2361 -f 2362//2362 2363//2363 2321//2321 -f 2321//2321 2363//2363 2364//2364 -f 2321//2321 2364//2364 2320//2320 -f 2320//2320 2364//2364 2365//2365 -f 2320//2320 2365//2365 2319//2319 -f 2319//2319 2365//2365 2366//2366 -f 2319//2319 2366//2366 2318//2318 -f 2318//2318 2366//2366 2367//2367 -f 2318//2318 2367//2367 2252//2252 -f 2252//2252 2367//2367 2368//2368 -f 2252//2252 2368//2368 2361//2361 -f 2205//2205 2191//2191 2284//2284 -f 2284//2284 2191//2191 2263//2263 -f 2284//2284 2263//2263 2297//2297 -f 2297//2297 2263//2263 2369//2369 -f 2297//2297 2369//2369 2321//2321 -f 2321//2321 2369//2369 2224//2224 -f 2321//2321 2224//2224 2362//2362 -f 2362//2362 2224//2224 2223//2223 -f 2370//2370 2222//2222 2371//2371 -f 2371//2371 2222//2222 2224//2224 -f 2371//2371 2224//2224 2372//2372 -f 2372//2372 2224//2224 2369//2369 -f 2372//2372 2369//2369 2373//2373 -f 2373//2373 2369//2369 2263//2263 -f 2373//2373 2263//2263 2193//2193 -f 2193//2193 2263//2263 2192//2192 -f 2193//2193 2194//2194 2373//2373 -f 2373//2373 2194//2194 2285//2285 -f 2373//2373 2285//2285 2372//2372 -f 2372//2372 2285//2285 2322//2322 -f 2372//2372 2322//2322 2371//2371 -f 2371//2371 2322//2322 2324//2324 -f 2371//2371 2324//2324 2370//2370 -f 2370//2370 2324//2324 2374//2374 -f 2221//2221 2220//2220 2324//2324 -f 2324//2324 2220//2220 2375//2375 -f 2324//2324 2375//2375 2374//2374 -f 2217//2217 2219//2219 2218//2218 -f 2218//2218 2219//2219 2221//2221 -f 2218//2218 2221//2221 2376//2376 -f 2376//2376 2221//2221 2323//2323 -f 2376//2376 2323//2323 2261//2261 -f 2261//2261 2323//2323 2262//2262 -f 2261//2261 2262//2262 2184//2184 -f 2184//2184 2262//2262 2183//2183 -f 2377//2377 2216//2216 2378//2378 -f 2378//2378 2216//2216 2218//2218 -f 2378//2378 2218//2218 2379//2379 -f 2379//2379 2218//2218 2376//2376 -f 2379//2379 2376//2376 2380//2380 -f 2380//2380 2376//2376 2261//2261 -f 2380//2380 2261//2261 2186//2186 -f 2186//2186 2261//2261 2185//2185 -f 2186//2186 2187//2187 2380//2380 -f 2380//2380 2187//2187 2286//2286 -f 2380//2380 2286//2286 2379//2379 -f 2379//2379 2286//2286 2300//2300 -f 2379//2379 2300//2300 2378//2378 -f 2378//2378 2300//2300 2327//2327 -f 2378//2378 2327//2327 2377//2377 -f 2377//2377 2327//2327 2381//2381 -f 2329//2329 2382//2382 2301//2301 -f 2301//2301 2382//2382 2383//2383 -f 2301//2301 2383//2383 2302//2302 -f 2302//2302 2383//2383 2384//2384 -f 2302//2302 2384//2384 2325//2325 -f 2325//2325 2384//2384 2385//2385 -f 2325//2325 2385//2385 2326//2326 -f 2326//2326 2385//2385 2386//2386 -f 2326//2326 2386//2386 2327//2327 -f 2327//2327 2386//2386 2387//2387 -f 2327//2327 2387//2387 2381//2381 -f 2388//2388 2336//2336 2389//2389 -f 2389//2389 2336//2336 2241//2241 -f 2389//2389 2241//2241 2390//2390 -f 2390//2390 2241//2241 2240//2240 -f 2390//2390 2240//2240 2391//2391 -f 2391//2391 2240//2240 2339//2339 -f 2391//2391 2339//2339 2392//2392 -f 2392//2392 2339//2339 2340//2340 -f 2392//2392 2340//2340 2393//2393 -f 2393//2393 2340//2340 2341//2341 -f 2393//2393 2341//2341 2394//2394 -f 2394//2394 2341//2341 2342//2342 -f 2395//2395 2396//2396 2352//2352 -f 2352//2352 2396//2396 2397//2397 -f 2352//2352 2397//2397 2231//2231 -f 2231//2231 2397//2397 2398//2398 -f 2231//2231 2398//2398 2232//2232 -f 2232//2232 2398//2398 2399//2399 -f 2232//2232 2399//2399 2234//2234 -f 2234//2234 2399//2399 2400//2400 -f 2234//2234 2400//2400 2235//2235 -f 2235//2235 2400//2400 2401//2401 -f 2235//2235 2401//2401 2350//2350 -f 2350//2350 2401//2401 2402//2402 -f 2350//2350 2402//2402 2349//2349 -f 2349//2349 2402//2402 2403//2403 -f 2349//2349 2403//2403 2345//2345 -f 2345//2345 2403//2403 2404//2404 -f 2345//2345 2404//2404 2237//2237 -f 2237//2237 2404//2404 2405//2405 -f 2237//2237 2405//2405 2238//2238 -f 2238//2238 2405//2405 2406//2406 -f 2238//2238 2406//2406 2344//2344 -f 2344//2344 2406//2406 2407//2407 -f 2344//2344 2407//2407 2343//2343 -f 2343//2343 2407//2407 2408//2408 -f 2343//2343 2408//2408 2342//2342 -f 2342//2342 2408//2408 2409//2409 -f 2342//2342 2409//2409 2394//2394 -f 2352//2352 2355//2355 2395//2395 -f 2395//2395 2355//2355 2356//2356 -f 2395//2395 2356//2356 2410//2410 -f 2410//2410 2356//2356 2411//2411 -f 2411//2411 2356//2356 2229//2229 -f 2411//2411 2229//2229 2412//2412 -f 2412//2412 2229//2229 2228//2228 -f 2412//2412 2228//2228 2413//2413 -f 2413//2413 2228//2228 2226//2226 -f 2413//2413 2226//2226 2414//2414 -f 2226//2226 2225//2225 2414//2414 -f 2414//2414 2225//2225 2358//2358 -f 2414//2414 2358//2358 2415//2415 -f 2415//2415 2358//2358 2416//2416 -f 2358//2358 2361//2361 2416//2416 -f 2416//2416 2361//2361 2368//2368 -f 2416//2416 2368//2368 2417//2417 -f 2417//2417 2368//2368 2418//2418 -f 2418//2418 2368//2368 2367//2367 -f 2418//2418 2367//2367 2419//2419 -f 2419//2419 2367//2367 2366//2366 -f 2419//2419 2366//2366 2420//2420 -f 2420//2420 2366//2366 2365//2365 -f 2420//2420 2365//2365 2421//2421 -f 2421//2421 2365//2365 2364//2364 -f 2421//2421 2364//2364 2422//2422 -f 2422//2422 2364//2364 2423//2423 -f 2423//2423 2364//2364 2363//2363 -f 2423//2423 2363//2363 2424//2424 -f 2424//2424 2363//2363 2362//2362 -f 2424//2424 2362//2362 2425//2425 -f 2425//2425 2362//2362 2223//2223 -f 2425//2425 2223//2223 2426//2426 -f 2426//2426 2223//2223 2222//2222 -f 2426//2426 2222//2222 2427//2427 -f 2427//2427 2222//2222 2370//2370 -f 2427//2427 2370//2370 2428//2428 -f 2370//2370 2374//2374 2428//2428 -f 2428//2428 2374//2374 2375//2375 -f 2428//2428 2375//2375 2429//2429 -f 2429//2429 2375//2375 2220//2220 -f 2429//2429 2220//2220 2430//2430 -f 2430//2430 2220//2220 2219//2219 -f 2430//2430 2219//2219 2431//2431 -f 2431//2431 2219//2219 2217//2217 -f 2431//2431 2217//2217 2432//2432 -f 2432//2432 2217//2217 2216//2216 -f 2432//2432 2216//2216 2433//2433 -f 2433//2433 2216//2216 2377//2377 -f 2433//2433 2377//2377 2434//2434 -f 2434//2434 2377//2377 2381//2381 -f 2434//2434 2381//2381 2435//2435 -f 2435//2435 2381//2381 2387//2387 -f 2435//2435 2387//2387 2436//2436 -f 2436//2436 2387//2387 2386//2386 -f 2436//2436 2386//2386 2437//2437 -f 2437//2437 2386//2386 2385//2385 -f 2437//2437 2385//2385 2438//2438 -f 2438//2438 2385//2385 2384//2384 -f 2438//2438 2384//2384 2439//2439 -f 2439//2439 2384//2384 2383//2383 -f 2439//2439 2383//2383 2440//2440 -f 2440//2440 2383//2383 2382//2382 -f 2440//2440 2382//2382 2441//2441 -f 2441//2441 2382//2382 2329//2329 -f 2441//2441 2329//2329 2442//2442 -f 2442//2442 2329//2329 2250//2250 -f 2442//2442 2250//2250 2443//2443 -f 2443//2443 2250//2250 2249//2249 -f 2443//2443 2249//2249 2444//2444 -f 2444//2444 2249//2249 2330//2330 -f 2444//2444 2330//2330 2445//2445 -f 2445//2445 2330//2330 2333//2333 -f 2445//2445 2333//2333 2446//2446 -f 2446//2446 2333//2333 2334//2334 -f 2446//2446 2334//2334 2447//2447 -f 2447//2447 2334//2334 2247//2247 -f 2447//2447 2247//2247 2448//2448 -f 2448//2448 2247//2247 2246//2246 -f 2448//2448 2246//2246 2449//2449 -f 2449//2449 2246//2246 2244//2244 -f 2449//2449 2244//2244 2388//2388 -f 2388//2388 2244//2244 2243//2243 -f 2388//2388 2243//2243 2336//2336 -f 2450//2450 2441//2441 2451//2451 -f 2451//2451 2441//2441 2442//2442 -f 2451//2451 2442//2442 2452//2452 -f 2442//2442 2443//2443 2452//2452 -f 2452//2452 2443//2443 2444//2444 -f 2452//2452 2444//2444 2453//2453 -f 2444//2444 2445//2445 2453//2453 -f 2453//2453 2445//2445 2446//2446 -f 2453//2453 2446//2446 2454//2454 -f 2454//2454 2446//2446 2447//2447 -f 2454//2454 2447//2447 2455//2455 -f 2447//2447 2448//2448 2455//2455 -f 2455//2455 2448//2448 2449//2449 -f 2455//2455 2449//2449 2456//2456 -f 2456//2456 2449//2449 2388//2388 -f 2456//2456 2388//2388 2457//2457 -f 2388//2388 2389//2389 2457//2457 -f 2457//2457 2389//2389 2390//2390 -f 2457//2457 2390//2390 2458//2458 -f 2458//2458 2390//2390 2391//2391 -f 2458//2458 2391//2391 2459//2459 -f 2391//2391 2392//2392 2459//2459 -f 2459//2459 2392//2392 2393//2393 -f 2459//2459 2393//2393 2460//2460 -f 2393//2393 2394//2394 2460//2460 -f 2460//2460 2394//2394 2409//2409 -f 2460//2460 2409//2409 2461//2461 -f 2461//2461 2409//2409 2408//2408 -f 2461//2461 2408//2408 2462//2462 -f 2408//2408 2407//2407 2462//2462 -f 2462//2462 2407//2407 2406//2406 -f 2462//2462 2406//2406 2463//2463 -f 2406//2406 2405//2405 2463//2463 -f 2463//2463 2405//2405 2404//2404 -f 2463//2463 2404//2404 2464//2464 -f 2404//2404 2403//2403 2464//2464 -f 2464//2464 2403//2403 2402//2402 -f 2464//2464 2402//2402 2465//2465 -f 2465//2465 2402//2402 2401//2401 -f 2465//2465 2401//2401 2466//2466 -f 2401//2401 2400//2400 2466//2466 -f 2466//2466 2400//2400 2399//2399 -f 2466//2466 2399//2399 2467//2467 -f 2399//2399 2398//2398 2467//2467 -f 2467//2467 2398//2398 2397//2397 -f 2467//2467 2397//2397 2468//2468 -f 2468//2468 2397//2397 2396//2396 -f 2468//2468 2396//2396 2469//2469 -f 2396//2396 2395//2395 2469//2469 -f 2469//2469 2395//2395 2410//2410 -f 2469//2469 2410//2410 2470//2470 -f 2410//2410 2411//2411 2470//2470 -f 2470//2470 2411//2411 2412//2412 -f 2470//2470 2412//2412 2471//2471 -f 2471//2471 2412//2412 2413//2413 -f 2471//2471 2413//2413 2472//2472 -f 2413//2413 2414//2414 2472//2472 -f 2472//2472 2414//2414 2415//2415 -f 2472//2472 2415//2415 2473//2473 -f 2415//2415 2416//2416 2473//2473 -f 2473//2473 2416//2416 2417//2417 -f 2473//2473 2417//2417 2474//2474 -f 2417//2417 2418//2418 2474//2474 -f 2474//2474 2418//2418 2419//2419 -f 2474//2474 2419//2419 2475//2475 -f 2475//2475 2419//2419 2420//2420 -f 2475//2475 2420//2420 2476//2476 -f 2420//2420 2421//2421 2476//2476 -f 2476//2476 2421//2421 2422//2422 -f 2476//2476 2422//2422 2477//2477 -f 2422//2422 2423//2423 2477//2477 -f 2477//2477 2423//2423 2424//2424 -f 2477//2477 2424//2424 2478//2478 -f 2478//2478 2424//2424 2425//2425 -f 2478//2478 2425//2425 2479//2479 -f 2425//2425 2426//2426 2479//2479 -f 2479//2479 2426//2426 2427//2427 -f 2479//2479 2427//2427 2480//2480 -f 2480//2480 2427//2427 2428//2428 -f 2480//2480 2428//2428 2481//2481 -f 2428//2428 2429//2429 2481//2481 -f 2481//2481 2429//2429 2430//2430 -f 2481//2481 2430//2430 2482//2482 -f 2482//2482 2430//2430 2431//2431 -f 2482//2482 2431//2431 2483//2483 -f 2431//2431 2432//2432 2483//2483 -f 2483//2483 2432//2432 2433//2433 -f 2483//2483 2433//2433 2484//2484 -f 2433//2433 2434//2434 2484//2484 -f 2484//2484 2434//2434 2435//2435 -f 2484//2484 2435//2435 2485//2485 -f 2485//2485 2435//2435 2436//2436 -f 2485//2485 2436//2436 2486//2486 -f 2436//2436 2437//2437 2486//2486 -f 2486//2486 2437//2437 2438//2438 -f 2486//2486 2438//2438 2487//2487 -f 2487//2487 2438//2438 2439//2439 -f 2487//2487 2439//2439 2450//2450 -f 2450//2450 2439//2439 2440//2440 -f 2450//2450 2440//2440 2441//2441 -f 2486//2486 2488//2488 2485//2485 -f 2485//2485 2488//2488 2489//2489 -f 2485//2485 2489//2489 2484//2484 -f 2484//2484 2489//2489 2490//2490 -f 2484//2484 2490//2490 2483//2483 -f 2483//2483 2490//2490 2491//2491 -f 2483//2483 2491//2491 2482//2482 -f 2482//2482 2491//2491 2492//2492 -f 2482//2482 2492//2492 2481//2481 -f 2481//2481 2492//2492 2493//2493 -f 2481//2481 2493//2493 2480//2480 -f 2480//2480 2493//2493 2494//2494 -f 2480//2480 2494//2494 2479//2479 -f 2479//2479 2494//2494 2495//2495 -f 2479//2479 2495//2495 2478//2478 -f 2478//2478 2495//2495 2496//2496 -f 2478//2478 2496//2496 2477//2477 -f 2477//2477 2496//2496 2497//2497 -f 2477//2477 2497//2497 2476//2476 -f 2476//2476 2497//2497 2498//2498 -f 2476//2476 2498//2498 2475//2475 -f 2475//2475 2498//2498 2499//2499 -f 2475//2475 2499//2499 2474//2474 -f 2474//2474 2499//2499 2500//2500 -f 2474//2474 2500//2500 2473//2473 -f 2473//2473 2500//2500 2501//2501 -f 2473//2473 2501//2501 2472//2472 -f 2472//2472 2501//2501 2502//2502 -f 2472//2472 2502//2502 2471//2471 -f 2471//2471 2502//2502 2503//2503 -f 2471//2471 2503//2503 2470//2470 -f 2470//2470 2503//2503 2504//2504 -f 2470//2470 2504//2504 2469//2469 -f 2469//2469 2504//2504 2505//2505 -f 2469//2469 2505//2505 2468//2468 -f 2468//2468 2505//2505 2506//2506 -f 2468//2468 2506//2506 2467//2467 -f 2467//2467 2506//2506 2507//2507 -f 2467//2467 2507//2507 2466//2466 -f 2466//2466 2507//2507 2508//2508 -f 2466//2466 2508//2508 2465//2465 -f 2465//2465 2508//2508 2509//2509 -f 2465//2465 2509//2509 2464//2464 -f 2464//2464 2509//2509 2510//2510 -f 2464//2464 2510//2510 2463//2463 -f 2463//2463 2510//2510 2511//2511 -f 2463//2463 2511//2511 2462//2462 -f 2462//2462 2511//2511 2512//2512 -f 2462//2462 2512//2512 2461//2461 -f 2461//2461 2512//2512 2513//2513 -f 2461//2461 2513//2513 2460//2460 -f 2460//2460 2513//2513 2514//2514 -f 2460//2460 2514//2514 2459//2459 -f 2459//2459 2514//2514 2515//2515 -f 2459//2459 2515//2515 2458//2458 -f 2458//2458 2515//2515 2516//2516 -f 2458//2458 2516//2516 2457//2457 -f 2457//2457 2516//2516 2517//2517 -f 2457//2457 2517//2517 2456//2456 -f 2456//2456 2517//2517 2518//2518 -f 2456//2456 2518//2518 2455//2455 -f 2455//2455 2518//2518 2519//2519 -f 2455//2455 2519//2519 2454//2454 -f 2454//2454 2519//2519 2520//2520 -f 2454//2454 2520//2520 2453//2453 -f 2453//2453 2520//2520 2521//2521 -f 2453//2453 2521//2521 2452//2452 -f 2452//2452 2521//2521 2522//2522 -f 2452//2452 2522//2522 2451//2451 -f 2451//2451 2522//2522 2523//2523 -f 2451//2451 2523//2523 2450//2450 -f 2450//2450 2523//2523 2524//2524 -f 2450//2450 2524//2524 2487//2487 -f 2487//2487 2524//2524 2525//2525 -f 2487//2487 2525//2525 2486//2486 -f 2486//2486 2525//2525 2488//2488 -f 2488//2488 2526//2526 2489//2489 -f 2489//2489 2526//2526 2527//2527 -f 2489//2489 2527//2527 2490//2490 -f 2490//2490 2527//2527 2528//2528 -f 2490//2490 2528//2528 2491//2491 -f 2491//2491 2528//2528 2529//2529 -f 2491//2491 2529//2529 2492//2492 -f 2492//2492 2529//2529 2530//2530 -f 2492//2492 2530//2530 2493//2493 -f 2493//2493 2530//2530 2531//2531 -f 2493//2493 2531//2531 2494//2494 -f 2494//2494 2531//2531 2532//2532 -f 2494//2494 2532//2532 2495//2495 -f 2495//2495 2532//2532 2533//2533 -f 2495//2495 2533//2533 2496//2496 -f 2496//2496 2533//2533 2534//2534 -f 2496//2496 2534//2534 2497//2497 -f 2497//2497 2534//2534 2535//2535 -f 2497//2497 2535//2535 2498//2498 -f 2498//2498 2535//2535 2536//2536 -f 2498//2498 2536//2536 2499//2499 -f 2499//2499 2536//2536 2537//2537 -f 2499//2499 2537//2537 2500//2500 -f 2500//2500 2537//2537 2538//2538 -f 2500//2500 2538//2538 2501//2501 -f 2501//2501 2538//2538 2539//2539 -f 2501//2501 2539//2539 2502//2502 -f 2502//2502 2539//2539 2540//2540 -f 2502//2502 2540//2540 2503//2503 -f 2503//2503 2540//2540 2541//2541 -f 2503//2503 2541//2541 2504//2504 -f 2504//2504 2541//2541 2542//2542 -f 2504//2504 2542//2542 2505//2505 -f 2505//2505 2542//2542 2543//2543 -f 2505//2505 2543//2543 2506//2506 -f 2506//2506 2543//2543 2544//2544 -f 2506//2506 2544//2544 2507//2507 -f 2507//2507 2544//2544 2545//2545 -f 2507//2507 2545//2545 2508//2508 -f 2508//2508 2545//2545 2546//2546 -f 2508//2508 2546//2546 2509//2509 -f 2509//2509 2546//2546 2547//2547 -f 2509//2509 2547//2547 2510//2510 -f 2510//2510 2547//2547 2548//2548 -f 2510//2510 2548//2548 2511//2511 -f 2511//2511 2548//2548 2549//2549 -f 2511//2511 2549//2549 2512//2512 -f 2512//2512 2549//2549 2550//2550 -f 2512//2512 2550//2550 2513//2513 -f 2513//2513 2550//2550 2551//2551 -f 2513//2513 2551//2551 2514//2514 -f 2514//2514 2551//2551 2552//2552 -f 2514//2514 2552//2552 2515//2515 -f 2515//2515 2552//2552 2553//2553 -f 2515//2515 2553//2553 2516//2516 -f 2516//2516 2553//2553 2554//2554 -f 2516//2516 2554//2554 2517//2517 -f 2517//2517 2554//2554 2555//2555 -f 2517//2517 2555//2555 2518//2518 -f 2518//2518 2555//2555 2556//2556 -f 2518//2518 2556//2556 2519//2519 -f 2519//2519 2556//2556 2557//2557 -f 2519//2519 2557//2557 2520//2520 -f 2520//2520 2557//2557 2558//2558 -f 2520//2520 2558//2558 2521//2521 -f 2521//2521 2558//2558 2559//2559 -f 2521//2521 2559//2559 2522//2522 -f 2522//2522 2559//2559 2560//2560 -f 2522//2522 2560//2560 2523//2523 -f 2523//2523 2560//2560 2561//2561 -f 2523//2523 2561//2561 2524//2524 -f 2524//2524 2561//2561 2562//2562 -f 2524//2524 2562//2562 2525//2525 -f 2525//2525 2562//2562 2563//2563 -f 2525//2525 2563//2563 2488//2488 -f 2488//2488 2563//2563 2526//2526 -f 2526//2526 2564//2564 2527//2527 -f 2527//2527 2564//2564 2565//2565 -f 2527//2527 2565//2565 2528//2528 -f 2528//2528 2565//2565 2566//2566 -f 2528//2528 2566//2566 2529//2529 -f 2529//2529 2566//2566 2567//2567 -f 2529//2529 2567//2567 2530//2530 -f 2530//2530 2567//2567 2568//2568 -f 2530//2530 2568//2568 2531//2531 -f 2531//2531 2568//2568 2569//2569 -f 2531//2531 2569//2569 2532//2532 -f 2532//2532 2569//2569 2570//2570 -f 2532//2532 2570//2570 2533//2533 -f 2533//2533 2570//2570 2571//2571 -f 2533//2533 2571//2571 2534//2534 -f 2534//2534 2571//2571 2572//2572 -f 2534//2534 2572//2572 2535//2535 -f 2535//2535 2572//2572 2573//2573 -f 2535//2535 2573//2573 2536//2536 -f 2536//2536 2573//2573 2574//2574 -f 2536//2536 2574//2574 2537//2537 -f 2537//2537 2574//2574 2575//2575 -f 2537//2537 2575//2575 2538//2538 -f 2538//2538 2575//2575 2576//2576 -f 2538//2538 2576//2576 2539//2539 -f 2539//2539 2576//2576 2577//2577 -f 2539//2539 2577//2577 2540//2540 -f 2540//2540 2577//2577 2578//2578 -f 2540//2540 2578//2578 2541//2541 -f 2541//2541 2578//2578 2579//2579 -f 2541//2541 2579//2579 2542//2542 -f 2542//2542 2579//2579 2580//2580 -f 2542//2542 2580//2580 2543//2543 -f 2543//2543 2580//2580 2581//2581 -f 2543//2543 2581//2581 2544//2544 -f 2544//2544 2581//2581 2582//2582 -f 2544//2544 2582//2582 2545//2545 -f 2545//2545 2582//2582 2583//2583 -f 2545//2545 2583//2583 2546//2546 -f 2546//2546 2583//2583 2584//2584 -f 2546//2546 2584//2584 2547//2547 -f 2547//2547 2584//2584 2585//2585 -f 2547//2547 2585//2585 2548//2548 -f 2548//2548 2585//2585 2586//2586 -f 2548//2548 2586//2586 2549//2549 -f 2549//2549 2586//2586 2587//2587 -f 2549//2549 2587//2587 2550//2550 -f 2550//2550 2587//2587 2588//2588 -f 2550//2550 2588//2588 2551//2551 -f 2551//2551 2588//2588 2589//2589 -f 2551//2551 2589//2589 2552//2552 -f 2552//2552 2589//2589 2590//2590 -f 2552//2552 2590//2590 2553//2553 -f 2553//2553 2590//2590 2591//2591 -f 2553//2553 2591//2591 2554//2554 -f 2554//2554 2591//2591 2592//2592 -f 2554//2554 2592//2592 2555//2555 -f 2555//2555 2592//2592 2593//2593 -f 2555//2555 2593//2593 2556//2556 -f 2556//2556 2593//2593 2594//2594 -f 2556//2556 2594//2594 2557//2557 -f 2557//2557 2594//2594 2595//2595 -f 2557//2557 2595//2595 2558//2558 -f 2558//2558 2595//2595 2596//2596 -f 2558//2558 2596//2596 2559//2559 -f 2559//2559 2596//2596 2597//2597 -f 2559//2559 2597//2597 2560//2560 -f 2560//2560 2597//2597 2598//2598 -f 2560//2560 2598//2598 2561//2561 -f 2561//2561 2598//2598 2599//2599 -f 2561//2561 2599//2599 2562//2562 -f 2562//2562 2599//2599 2600//2600 -f 2562//2562 2600//2600 2563//2563 -f 2563//2563 2600//2600 2601//2601 -f 2563//2563 2601//2601 2526//2526 -f 2526//2526 2601//2601 2564//2564 -f 2564//2564 2602//2602 2565//2565 -f 2565//2565 2602//2602 2603//2603 -f 2565//2565 2603//2603 2566//2566 -f 2566//2566 2603//2603 2604//2604 -f 2566//2566 2604//2604 2567//2567 -f 2567//2567 2604//2604 2605//2605 -f 2567//2567 2605//2605 2568//2568 -f 2568//2568 2605//2605 2606//2606 -f 2568//2568 2606//2606 2569//2569 -f 2569//2569 2606//2606 2607//2607 -f 2569//2569 2607//2607 2570//2570 -f 2570//2570 2607//2607 2608//2608 -f 2570//2570 2608//2608 2571//2571 -f 2571//2571 2608//2608 2609//2609 -f 2571//2571 2609//2609 2572//2572 -f 2572//2572 2609//2609 2610//2610 -f 2572//2572 2610//2610 2573//2573 -f 2573//2573 2610//2610 2611//2611 -f 2573//2573 2611//2611 2574//2574 -f 2574//2574 2611//2611 2612//2612 -f 2574//2574 2612//2612 2575//2575 -f 2575//2575 2612//2612 2613//2613 -f 2575//2575 2613//2613 2576//2576 -f 2576//2576 2613//2613 2614//2614 -f 2576//2576 2614//2614 2577//2577 -f 2577//2577 2614//2614 2615//2615 -f 2577//2577 2615//2615 2578//2578 -f 2578//2578 2615//2615 2616//2616 -f 2578//2578 2616//2616 2579//2579 -f 2579//2579 2616//2616 2617//2617 -f 2579//2579 2617//2617 2580//2580 -f 2580//2580 2617//2617 2618//2618 -f 2580//2580 2618//2618 2581//2581 -f 2581//2581 2618//2618 2619//2619 -f 2581//2581 2619//2619 2582//2582 -f 2582//2582 2619//2619 2620//2620 -f 2582//2582 2620//2620 2583//2583 -f 2583//2583 2620//2620 2621//2621 -f 2583//2583 2621//2621 2584//2584 -f 2584//2584 2621//2621 2622//2622 -f 2584//2584 2622//2622 2585//2585 -f 2585//2585 2622//2622 2623//2623 -f 2585//2585 2623//2623 2586//2586 -f 2586//2586 2623//2623 2624//2624 -f 2586//2586 2624//2624 2587//2587 -f 2587//2587 2624//2624 2625//2625 -f 2587//2587 2625//2625 2588//2588 -f 2588//2588 2625//2625 2626//2626 -f 2588//2588 2626//2626 2589//2589 -f 2589//2589 2626//2626 2627//2627 -f 2589//2589 2627//2627 2590//2590 -f 2590//2590 2627//2627 2628//2628 -f 2590//2590 2628//2628 2591//2591 -f 2591//2591 2628//2628 2629//2629 -f 2591//2591 2629//2629 2592//2592 -f 2592//2592 2629//2629 2630//2630 -f 2592//2592 2630//2630 2593//2593 -f 2593//2593 2630//2630 2631//2631 -f 2593//2593 2631//2631 2594//2594 -f 2594//2594 2631//2631 2632//2632 -f 2594//2594 2632//2632 2595//2595 -f 2595//2595 2632//2632 2633//2633 -f 2595//2595 2633//2633 2596//2596 -f 2596//2596 2633//2633 2634//2634 -f 2596//2596 2634//2634 2597//2597 -f 2597//2597 2634//2634 2635//2635 -f 2597//2597 2635//2635 2598//2598 -f 2598//2598 2635//2635 2636//2636 -f 2598//2598 2636//2636 2599//2599 -f 2599//2599 2636//2636 2637//2637 -f 2599//2599 2637//2637 2600//2600 -f 2600//2600 2637//2637 2638//2638 -f 2600//2600 2638//2638 2601//2601 -f 2601//2601 2638//2638 2639//2639 -f 2601//2601 2639//2639 2564//2564 -f 2564//2564 2639//2639 2602//2602 -f 2622//2622 2621//2621 2640//2640 -f 2640//2640 2621//2621 2641//2641 -f 2609//2609 2642//2642 2643//2643 -f 2613//2613 2644//2644 2614//2614 -f 2614//2614 2644//2644 2645//2645 -f 2614//2614 2645//2645 2615//2615 -f 2646//2646 2624//2624 2640//2640 -f 2640//2640 2624//2624 2623//2623 -f 2640//2640 2623//2623 2622//2622 -f 2647//2647 2626//2626 2646//2646 -f 2646//2646 2626//2626 2625//2625 -f 2646//2646 2625//2625 2624//2624 -f 2630//2630 2629//2629 2648//2648 -f 2648//2648 2629//2629 2628//2628 -f 2648//2648 2628//2628 2647//2647 -f 2647//2647 2628//2628 2627//2627 -f 2647//2647 2627//2627 2626//2626 -f 2630//2630 2648//2648 2631//2631 -f 2631//2631 2648//2648 2649//2649 -f 2631//2631 2649//2649 2632//2632 -f 2604//2604 2650//2650 2605//2605 -f 2605//2605 2650//2650 2651//2651 -f 2609//2609 2608//2608 2642//2642 -f 2642//2642 2608//2608 2607//2607 -f 2642//2642 2607//2607 2651//2651 -f 2651//2651 2607//2607 2606//2606 -f 2651//2651 2606//2606 2605//2605 -f 2613//2613 2612//2612 2644//2644 -f 2644//2644 2612//2612 2611//2611 -f 2644//2644 2611//2611 2643//2643 -f 2643//2643 2611//2611 2610//2610 -f 2643//2643 2610//2610 2609//2609 -f 2615//2615 2645//2645 2616//2616 -f 2616//2616 2645//2645 2652//2652 -f 2616//2616 2652//2652 2617//2617 -f 2621//2621 2620//2620 2641//2641 -f 2641//2641 2620//2620 2619//2619 -f 2641//2641 2619//2619 2652//2652 -f 2652//2652 2619//2619 2618//2618 -f 2652//2652 2618//2618 2617//2617 -f 2632//2632 2649//2649 2633//2633 -f 2633//2633 2649//2649 2653//2653 -f 2633//2633 2653//2653 2634//2634 -f 2604//2604 2603//2603 2650//2650 -f 2650//2650 2603//2603 2602//2602 -f 2650//2650 2602//2602 2654//2654 -f 2602//2602 2639//2639 2654//2654 -f 2654//2654 2639//2639 2638//2638 -f 2654//2654 2638//2638 2655//2655 -f 2638//2638 2637//2637 2655//2655 -f 2655//2655 2637//2637 2636//2636 -f 2655//2655 2636//2636 2653//2653 -f 2653//2653 2636//2636 2635//2635 -f 2653//2653 2635//2635 2634//2634 -f 2646//2646 2640//2640 2656//2656 -f 2656//2656 2657//2657 2646//2646 -f 2646//2646 2657//2657 2658//2658 -f 2646//2646 2658//2658 2647//2647 -f 2658//2658 2659//2659 2647//2647 -f 2647//2647 2659//2659 2660//2660 -f 2647//2647 2660//2660 2648//2648 -f 2660//2660 2661//2661 2648//2648 -f 2648//2648 2661//2661 2662//2662 -f 2648//2648 2662//2662 2649//2649 -f 2662//2662 2663//2663 2649//2649 -f 2649//2649 2663//2663 2664//2664 -f 2649//2649 2664//2664 2653//2653 -f 2664//2664 2665//2665 2653//2653 -f 2653//2653 2665//2665 2666//2666 -f 2653//2653 2666//2666 2655//2655 -f 2666//2666 2667//2667 2655//2655 -f 2655//2655 2667//2667 2668//2668 -f 2655//2655 2668//2668 2654//2654 -f 2654//2654 2668//2668 2669//2669 -f 2654//2654 2669//2669 2650//2650 -f 2669//2669 2670//2670 2650//2650 -f 2650//2650 2670//2670 2671//2671 -f 2650//2650 2671//2671 2651//2651 -f 2671//2671 2672//2672 2651//2651 -f 2651//2651 2672//2672 2673//2673 -f 2651//2651 2673//2673 2642//2642 -f 2673//2673 2674//2674 2642//2642 -f 2642//2642 2674//2674 2675//2675 -f 2642//2642 2675//2675 2643//2643 -f 2675//2675 2676//2676 2643//2643 -f 2643//2643 2676//2676 2677//2677 -f 2643//2643 2677//2677 2644//2644 -f 2677//2677 2678//2678 2644//2644 -f 2644//2644 2678//2678 2679//2679 -f 2644//2644 2679//2679 2645//2645 -f 2679//2679 2680//2680 2645//2645 -f 2645//2645 2680//2680 2681//2681 -f 2645//2645 2681//2681 2652//2652 -f 2681//2681 2682//2682 2652//2652 -f 2652//2652 2682//2682 2683//2683 -f 2652//2652 2683//2683 2641//2641 -f 2641//2641 2683//2683 2684//2684 -f 2641//2641 2684//2684 2640//2640 -f 2640//2640 2684//2684 2685//2685 -f 2640//2640 2685//2685 2656//2656 -f 2668//2668 2686//2686 2669//2669 -f 2669//2669 2686//2686 2687//2687 -f 2669//2669 2687//2687 2670//2670 -f 2670//2670 2687//2687 2688//2688 -f 2670//2670 2688//2688 2671//2671 -f 2671//2671 2688//2688 2689//2689 -f 2671//2671 2689//2689 2672//2672 -f 2672//2672 2689//2689 2690//2690 -f 2672//2672 2690//2690 2673//2673 -f 2673//2673 2690//2690 2691//2691 -f 2673//2673 2691//2691 2674//2674 -f 2674//2674 2691//2691 2692//2692 -f 2674//2674 2692//2692 2675//2675 -f 2675//2675 2692//2692 2693//2693 -f 2675//2675 2693//2693 2676//2676 -f 2676//2676 2693//2693 2694//2694 -f 2676//2676 2694//2694 2677//2677 -f 2677//2677 2694//2694 2695//2695 -f 2677//2677 2695//2695 2678//2678 -f 2678//2678 2695//2695 2696//2696 -f 2678//2678 2696//2696 2679//2679 -f 2679//2679 2696//2696 2697//2697 -f 2679//2679 2697//2697 2680//2680 -f 2680//2680 2697//2697 2698//2698 -f 2680//2680 2698//2698 2681//2681 -f 2681//2681 2698//2698 2699//2699 -f 2681//2681 2699//2699 2682//2682 -f 2682//2682 2699//2699 2700//2700 -f 2682//2682 2700//2700 2683//2683 -f 2683//2683 2700//2700 2701//2701 -f 2683//2683 2701//2701 2684//2684 -f 2684//2684 2701//2701 2702//2702 -f 2684//2684 2702//2702 2685//2685 -f 2685//2685 2702//2702 2703//2703 -f 2685//2685 2703//2703 2656//2656 -f 2656//2656 2703//2703 2704//2704 -f 2656//2656 2704//2704 2657//2657 -f 2657//2657 2704//2704 2705//2705 -f 2657//2657 2705//2705 2658//2658 -f 2658//2658 2705//2705 2706//2706 -f 2658//2658 2706//2706 2659//2659 -f 2659//2659 2706//2706 2707//2707 -f 2659//2659 2707//2707 2660//2660 -f 2660//2660 2707//2707 2708//2708 -f 2660//2660 2708//2708 2661//2661 -f 2661//2661 2708//2708 2709//2709 -f 2661//2661 2709//2709 2662//2662 -f 2662//2662 2709//2709 2710//2710 -f 2662//2662 2710//2710 2663//2663 -f 2663//2663 2710//2710 2711//2711 -f 2663//2663 2711//2711 2664//2664 -f 2664//2664 2711//2711 2712//2712 -f 2664//2664 2712//2712 2665//2665 -f 2665//2665 2712//2712 2713//2713 -f 2665//2665 2713//2713 2666//2666 -f 2666//2666 2713//2713 2714//2714 -f 2666//2666 2714//2714 2667//2667 -f 2667//2667 2714//2714 2715//2715 -f 2667//2667 2715//2715 2668//2668 -f 2668//2668 2715//2715 2686//2686 -f 2716//2716 2717//2717 2715//2715 -f 2715//2715 2714//2714 2716//2716 -f 2716//2716 2714//2714 2713//2713 -f 2716//2716 2713//2713 2718//2718 -f 2713//2713 2712//2712 2718//2718 -f 2718//2718 2712//2712 2711//2711 -f 2718//2718 2711//2711 2719//2719 -f 2711//2711 2710//2710 2719//2719 -f 2719//2719 2710//2710 2709//2709 -f 2719//2719 2709//2709 2720//2720 -f 2709//2709 2708//2708 2720//2720 -f 2720//2720 2708//2708 2707//2707 -f 2720//2720 2707//2707 2721//2721 -f 2707//2707 2706//2706 2721//2721 -f 2721//2721 2706//2706 2705//2705 -f 2721//2721 2705//2705 2722//2722 -f 2705//2705 2704//2704 2722//2722 -f 2722//2722 2704//2704 2703//2703 -f 2722//2722 2703//2703 2723//2723 -f 2723//2723 2703//2703 2702//2702 -f 2723//2723 2702//2702 2724//2724 -f 2702//2702 2701//2701 2724//2724 -f 2724//2724 2701//2701 2700//2700 -f 2724//2724 2700//2700 2725//2725 -f 2700//2700 2699//2699 2725//2725 -f 2725//2725 2699//2699 2698//2698 -f 2725//2725 2698//2698 2726//2726 -f 2698//2698 2697//2697 2726//2726 -f 2726//2726 2697//2697 2696//2696 -f 2726//2726 2696//2696 2727//2727 -f 2696//2696 2695//2695 2727//2727 -f 2727//2727 2695//2695 2694//2694 -f 2727//2727 2694//2694 2728//2728 -f 2694//2694 2693//2693 2728//2728 -f 2728//2728 2693//2693 2692//2692 -f 2728//2728 2692//2692 2729//2729 -f 2692//2692 2691//2691 2729//2729 -f 2729//2729 2691//2691 2690//2690 -f 2729//2729 2690//2690 2730//2730 -f 2690//2690 2689//2689 2730//2730 -f 2730//2730 2689//2689 2688//2688 -f 2730//2730 2688//2688 2731//2731 -f 2731//2731 2688//2688 2687//2687 -f 2731//2731 2687//2687 2717//2717 -f 2717//2717 2687//2687 2686//2686 -f 2717//2717 2686//2686 2715//2715 -f 2718//2718 2732//2732 2716//2716 -f 2716//2716 2732//2732 2733//2733 -f 2716//2716 2733//2733 2717//2717 -f 2717//2717 2733//2733 2734//2734 -f 2717//2717 2734//2734 2731//2731 -f 2731//2731 2734//2734 2735//2735 -f 2731//2731 2735//2735 2730//2730 -f 2722//2722 2736//2736 2721//2721 -f 2721//2721 2736//2736 2737//2737 -f 2721//2721 2737//2737 2720//2720 -f 2720//2720 2737//2737 2738//2738 -f 2720//2720 2738//2738 2719//2719 -f 2719//2719 2738//2738 2739//2739 -f 2719//2719 2739//2739 2718//2718 -f 2718//2718 2739//2739 2740//2740 -f 2718//2718 2740//2740 2732//2732 -f 2726//2726 2741//2741 2725//2725 -f 2725//2725 2741//2741 2742//2742 -f 2725//2725 2742//2742 2724//2724 -f 2724//2724 2742//2742 2743//2743 -f 2724//2724 2743//2743 2723//2723 -f 2723//2723 2743//2743 2744//2744 -f 2723//2723 2744//2744 2722//2722 -f 2722//2722 2744//2744 2745//2745 -f 2722//2722 2745//2745 2736//2736 -f 2735//2735 2746//2746 2730//2730 -f 2730//2730 2746//2746 2747//2747 -f 2730//2730 2747//2747 2729//2729 -f 2729//2729 2747//2747 2748//2748 -f 2729//2729 2748//2748 2728//2728 -f 2728//2728 2748//2748 2749//2749 -f 2728//2728 2749//2749 2727//2727 -f 2727//2727 2749//2749 2750//2750 -f 2727//2727 2750//2750 2726//2726 -f 2726//2726 2750//2750 2751//2751 -f 2726//2726 2751//2751 2741//2741 -f 2746//2746 2752//2752 2747//2747 -f 2747//2747 2752//2752 2753//2753 -f 2747//2747 2753//2753 2748//2748 -f 2748//2748 2753//2753 2754//2754 -f 2748//2748 2754//2754 2749//2749 -f 2749//2749 2754//2754 2755//2755 -f 2749//2749 2755//2755 2750//2750 -f 2750//2750 2755//2755 2756//2756 -f 2750//2750 2756//2756 2751//2751 -f 2751//2751 2756//2756 2757//2757 -f 2751//2751 2757//2757 2741//2741 -f 2741//2741 2757//2757 2758//2758 -f 2741//2741 2758//2758 2742//2742 -f 2742//2742 2758//2758 2759//2759 -f 2742//2742 2759//2759 2743//2743 -f 2743//2743 2759//2759 2760//2760 -f 2743//2743 2760//2760 2744//2744 -f 2744//2744 2760//2760 2761//2761 -f 2744//2744 2761//2761 2745//2745 -f 2745//2745 2761//2761 2762//2762 -f 2745//2745 2762//2762 2736//2736 -f 2736//2736 2762//2762 2763//2763 -f 2736//2736 2763//2763 2737//2737 -f 2737//2737 2763//2763 2764//2764 -f 2737//2737 2764//2764 2738//2738 -f 2738//2738 2764//2764 2765//2765 -f 2738//2738 2765//2765 2739//2739 -f 2739//2739 2765//2765 2766//2766 -f 2739//2739 2766//2766 2740//2740 -f 2740//2740 2766//2766 2767//2767 -f 2740//2740 2767//2767 2732//2732 -f 2732//2732 2767//2767 2768//2768 -f 2732//2732 2768//2768 2733//2733 -f 2733//2733 2768//2768 2769//2769 -f 2733//2733 2769//2769 2734//2734 -f 2734//2734 2769//2769 2770//2770 -f 2734//2734 2770//2770 2735//2735 -f 2735//2735 2770//2770 2771//2771 -f 2735//2735 2771//2771 2746//2746 -f 2746//2746 2771//2771 2752//2752 -f 2772//2772 2752//2752 2771//2771 -f 2772//2772 2773//2773 2752//2752 -f 2752//2752 2773//2773 2774//2774 -f 2752//2752 2774//2774 2753//2753 -f 2774//2774 2775//2775 2753//2753 -f 2753//2753 2775//2775 2776//2776 -f 2753//2753 2776//2776 2754//2754 -f 2776//2776 2777//2777 2754//2754 -f 2754//2754 2777//2777 2778//2778 -f 2754//2754 2778//2778 2755//2755 -f 2778//2778 2779//2779 2755//2755 -f 2755//2755 2779//2779 2780//2780 -f 2755//2755 2780//2780 2756//2756 -f 2780//2780 2781//2781 2756//2756 -f 2756//2756 2781//2781 2782//2782 -f 2756//2756 2782//2782 2757//2757 -f 2782//2782 2783//2783 2757//2757 -f 2757//2757 2783//2783 2784//2784 -f 2757//2757 2784//2784 2758//2758 -f 2784//2784 2785//2785 2758//2758 -f 2758//2758 2785//2785 2786//2786 -f 2758//2758 2786//2786 2759//2759 -f 2786//2786 2787//2787 2759//2759 -f 2759//2759 2787//2787 2788//2788 -f 2759//2759 2788//2788 2760//2760 -f 2788//2788 2789//2789 2760//2760 -f 2760//2760 2789//2789 2790//2790 -f 2760//2760 2790//2790 2761//2761 -f 2790//2790 2791//2791 2761//2761 -f 2761//2761 2791//2791 2792//2792 -f 2761//2761 2792//2792 2762//2762 -f 2792//2792 2793//2793 2762//2762 -f 2762//2762 2793//2793 2794//2794 -f 2762//2762 2794//2794 2763//2763 -f 2794//2794 2795//2795 2763//2763 -f 2763//2763 2795//2795 2796//2796 -f 2763//2763 2796//2796 2764//2764 -f 2796//2796 2797//2797 2764//2764 -f 2764//2764 2797//2797 2798//2798 -f 2764//2764 2798//2798 2765//2765 -f 2798//2798 2799//2799 2765//2765 -f 2765//2765 2799//2799 2800//2800 -f 2765//2765 2800//2800 2766//2766 -f 2800//2800 2801//2801 2766//2766 -f 2766//2766 2801//2801 2802//2802 -f 2766//2766 2802//2802 2767//2767 -f 2802//2802 2803//2803 2767//2767 -f 2767//2767 2803//2803 2804//2804 -f 2767//2767 2804//2804 2768//2768 -f 2804//2804 2805//2805 2768//2768 -f 2768//2768 2805//2805 2806//2806 -f 2768//2768 2806//2806 2769//2769 -f 2806//2806 2807//2807 2769//2769 -f 2769//2769 2807//2807 2808//2808 -f 2769//2769 2808//2808 2770//2770 -f 2808//2808 2809//2809 2770//2770 -f 2770//2770 2809//2809 2810//2810 -f 2770//2770 2810//2810 2771//2771 -f 2771//2771 2810//2810 2811//2811 -f 2771//2771 2811//2811 2772//2772 -f 2812//2812 2813//2813 2809//2809 -f 2809//2809 2808//2808 2812//2812 -f 2812//2812 2808//2808 2807//2807 -f 2812//2812 2807//2807 2814//2814 -f 2807//2807 2806//2806 2814//2814 -f 2814//2814 2806//2806 2805//2805 -f 2814//2814 2805//2805 2815//2815 -f 2805//2805 2804//2804 2815//2815 -f 2815//2815 2804//2804 2803//2803 -f 2815//2815 2803//2803 2816//2816 -f 2803//2803 2802//2802 2816//2816 -f 2816//2816 2802//2802 2801//2801 -f 2816//2816 2801//2801 2817//2817 -f 2801//2801 2800//2800 2817//2817 -f 2817//2817 2800//2800 2799//2799 -f 2817//2817 2799//2799 2818//2818 -f 2799//2799 2798//2798 2818//2818 -f 2818//2818 2798//2798 2797//2797 -f 2818//2818 2797//2797 2819//2819 -f 2797//2797 2796//2796 2819//2819 -f 2819//2819 2796//2796 2795//2795 -f 2819//2819 2795//2795 2820//2820 -f 2795//2795 2794//2794 2820//2820 -f 2820//2820 2794//2794 2793//2793 -f 2820//2820 2793//2793 2821//2821 -f 2821//2821 2793//2793 2792//2792 -f 2821//2821 2792//2792 2822//2822 -f 2792//2792 2791//2791 2822//2822 -f 2822//2822 2791//2791 2790//2790 -f 2822//2822 2790//2790 2823//2823 -f 2790//2790 2789//2789 2823//2823 -f 2823//2823 2789//2789 2788//2788 -f 2823//2823 2788//2788 2824//2824 -f 2788//2788 2787//2787 2824//2824 -f 2824//2824 2787//2787 2786//2786 -f 2824//2824 2786//2786 2825//2825 -f 2786//2786 2785//2785 2825//2825 -f 2825//2825 2785//2785 2784//2784 -f 2825//2825 2784//2784 2826//2826 -f 2784//2784 2783//2783 2826//2826 -f 2826//2826 2783//2783 2782//2782 -f 2826//2826 2782//2782 2827//2827 -f 2782//2782 2781//2781 2827//2827 -f 2827//2827 2781//2781 2780//2780 -f 2827//2827 2780//2780 2828//2828 -f 2780//2780 2779//2779 2828//2828 -f 2828//2828 2779//2779 2778//2778 -f 2828//2828 2778//2778 2829//2829 -f 2778//2778 2777//2777 2829//2829 -f 2829//2829 2777//2777 2776//2776 -f 2829//2829 2776//2776 2830//2830 -f 2776//2776 2775//2775 2830//2830 -f 2830//2830 2775//2775 2774//2774 -f 2830//2830 2774//2774 2831//2831 -f 2774//2774 2773//2773 2831//2831 -f 2831//2831 2773//2773 2772//2772 -f 2831//2831 2772//2772 2832//2832 -f 2832//2832 2772//2772 2811//2811 -f 2832//2832 2811//2811 2813//2813 -f 2813//2813 2811//2811 2810//2810 -f 2813//2813 2810//2810 2809//2809 -f 2814//2814 2833//2833 2812//2812 -f 2812//2812 2833//2833 2834//2834 -f 2812//2812 2834//2834 2813//2813 -f 2834//2834 2835//2835 2813//2813 -f 2813//2813 2835//2835 2836//2836 -f 2813//2813 2836//2836 2832//2832 -f 2818//2818 2837//2837 2817//2817 -f 2817//2817 2837//2837 2838//2838 -f 2817//2817 2838//2838 2816//2816 -f 2838//2838 2839//2839 2816//2816 -f 2816//2816 2839//2839 2840//2840 -f 2816//2816 2840//2840 2815//2815 -f 2815//2815 2840//2840 2841//2841 -f 2815//2815 2841//2841 2814//2814 -f 2814//2814 2841//2841 2842//2842 -f 2814//2814 2842//2842 2833//2833 -f 2820//2820 2843//2843 2819//2819 -f 2819//2819 2843//2843 2844//2844 -f 2819//2819 2844//2844 2818//2818 -f 2818//2818 2844//2844 2845//2845 -f 2818//2818 2845//2845 2837//2837 -f 2822//2822 2846//2846 2821//2821 -f 2821//2821 2846//2846 2847//2847 -f 2821//2821 2847//2847 2820//2820 -f 2820//2820 2847//2847 2848//2848 -f 2820//2820 2848//2848 2843//2843 -f 2828//2828 2849//2849 2827//2827 -f 2827//2827 2849//2849 2850//2850 -f 2827//2827 2850//2850 2826//2826 -f 2830//2830 2851//2851 2829//2829 -f 2829//2829 2851//2851 2852//2852 -f 2829//2829 2852//2852 2828//2828 -f 2828//2828 2852//2852 2853//2853 -f 2828//2828 2853//2853 2849//2849 -f 2836//2836 2854//2854 2832//2832 -f 2832//2832 2854//2854 2855//2855 -f 2832//2832 2855//2855 2831//2831 -f 2831//2831 2855//2855 2856//2856 -f 2831//2831 2856//2856 2830//2830 -f 2830//2830 2856//2856 2857//2857 -f 2830//2830 2857//2857 2851//2851 -f 2824//2824 2858//2858 2823//2823 -f 2823//2823 2858//2858 2859//2859 -f 2823//2823 2859//2859 2822//2822 -f 2822//2822 2859//2859 2860//2860 -f 2822//2822 2860//2860 2846//2846 -f 2850//2850 2861//2861 2826//2826 -f 2826//2826 2861//2861 2862//2862 -f 2826//2826 2862//2862 2825//2825 -f 2825//2825 2862//2862 2863//2863 -f 2825//2825 2863//2863 2824//2824 -f 2824//2824 2863//2863 2864//2864 -f 2824//2824 2864//2864 2858//2858 -f 2865//2865 2860//2860 2866//2866 -f 2866//2866 2860//2860 2859//2859 -f 2866//2866 2859//2859 2867//2867 -f 2867//2867 2859//2859 2858//2858 -f 2867//2867 2858//2858 2868//2868 -f 2868//2868 2858//2858 2864//2864 -f 2868//2868 2864//2864 2869//2869 -f 2869//2869 2864//2864 2863//2863 -f 2869//2869 2863//2863 2870//2870 -f 2870//2870 2863//2863 2862//2862 -f 2870//2870 2862//2862 2871//2871 -f 2871//2871 2862//2862 2861//2861 -f 2871//2871 2861//2861 2872//2872 -f 2872//2872 2861//2861 2850//2850 -f 2872//2872 2850//2850 2873//2873 -f 2873//2873 2850//2850 2849//2849 -f 2873//2873 2849//2849 2874//2874 -f 2874//2874 2849//2849 2853//2853 -f 2874//2874 2853//2853 2875//2875 -f 2875//2875 2853//2853 2852//2852 -f 2875//2875 2852//2852 2876//2876 -f 2876//2876 2852//2852 2851//2851 -f 2876//2876 2851//2851 2877//2877 -f 2877//2877 2851//2851 2857//2857 -f 2877//2877 2857//2857 2878//2878 -f 2878//2878 2857//2857 2856//2856 -f 2878//2878 2856//2856 2879//2879 -f 2879//2879 2856//2856 2855//2855 -f 2879//2879 2855//2855 2880//2880 -f 2880//2880 2855//2855 2854//2854 -f 2880//2880 2854//2854 2881//2881 -f 2881//2881 2854//2854 2836//2836 -f 2881//2881 2836//2836 2882//2882 -f 2882//2882 2836//2836 2835//2835 -f 2882//2882 2835//2835 2883//2883 -f 2883//2883 2835//2835 2834//2834 -f 2883//2883 2834//2834 2884//2884 -f 2884//2884 2834//2834 2833//2833 -f 2884//2884 2833//2833 2885//2885 -f 2885//2885 2833//2833 2842//2842 -f 2885//2885 2842//2842 2886//2886 -f 2886//2886 2842//2842 2841//2841 -f 2886//2886 2841//2841 2887//2887 -f 2887//2887 2841//2841 2840//2840 -f 2887//2887 2840//2840 2888//2888 -f 2888//2888 2840//2840 2839//2839 -f 2888//2888 2839//2839 2889//2889 -f 2889//2889 2839//2839 2838//2838 -f 2889//2889 2838//2838 2890//2890 -f 2890//2890 2838//2838 2837//2837 -f 2890//2890 2837//2837 2891//2891 -f 2891//2891 2837//2837 2845//2845 -f 2891//2891 2845//2845 2892//2892 -f 2892//2892 2845//2845 2844//2844 -f 2892//2892 2844//2844 2893//2893 -f 2893//2893 2844//2844 2843//2843 -f 2893//2893 2843//2843 2894//2894 -f 2894//2894 2843//2843 2848//2848 -f 2894//2894 2848//2848 2895//2895 -f 2895//2895 2848//2848 2847//2847 -f 2895//2895 2847//2847 2896//2896 -f 2896//2896 2847//2847 2846//2846 -f 2896//2896 2846//2846 2865//2865 -f 2865//2865 2846//2846 2860//2860 -f 127//127 2881//2881 2882//2882 -f 2883//2883 123//123 2882//2882 -f 2882//2882 123//123 125//125 -f 2882//2882 125//125 127//127 -f 2884//2884 119//119 2883//2883 -f 2883//2883 119//119 121//121 -f 2883//2883 121//121 123//123 -f 2885//2885 115//115 2884//2884 -f 2884//2884 115//115 117//117 -f 2884//2884 117//117 119//119 -f 2886//2886 111//111 2885//2885 -f 2885//2885 111//111 113//113 -f 2885//2885 113//113 115//115 -f 2887//2887 107//107 2886//2886 -f 2886//2886 107//107 109//109 -f 2886//2886 109//109 111//111 -f 2888//2888 103//103 2887//2887 -f 2887//2887 103//103 105//105 -f 2887//2887 105//105 107//107 -f 2889//2889 99//99 2888//2888 -f 2888//2888 99//99 101//101 -f 2888//2888 101//101 103//103 -f 2890//2890 95//95 2889//2889 -f 2889//2889 95//95 97//97 -f 2889//2889 97//97 99//99 -f 2891//2891 91//91 2890//2890 -f 2890//2890 91//91 93//93 -f 2890//2890 93//93 95//95 -f 2892//2892 87//87 2891//2891 -f 2891//2891 87//87 89//89 -f 2891//2891 89//89 91//91 -f 2893//2893 83//83 2892//2892 -f 2892//2892 83//83 85//85 -f 2892//2892 85//85 87//87 -f 2894//2894 79//79 2893//2893 -f 2893//2893 79//79 81//81 -f 2893//2893 81//81 83//83 -f 2895//2895 75//75 2894//2894 -f 2894//2894 75//75 77//77 -f 2894//2894 77//77 79//79 -f 2896//2896 71//71 2895//2895 -f 2895//2895 71//71 73//73 -f 2895//2895 73//73 75//75 -f 2865//2865 67//67 2896//2896 -f 2896//2896 67//67 69//69 -f 2896//2896 69//69 71//71 -f 2866//2866 63//63 2865//2865 -f 2865//2865 63//63 65//65 -f 2865//2865 65//65 67//67 -f 2867//2867 59//59 2866//2866 -f 2866//2866 59//59 61//61 -f 2866//2866 61//61 63//63 -f 2868//2868 55//55 2867//2867 -f 2867//2867 55//55 57//57 -f 2867//2867 57//57 59//59 -f 2869//2869 51//51 2868//2868 -f 2868//2868 51//51 53//53 -f 2868//2868 53//53 55//55 -f 2870//2870 47//47 2869//2869 -f 2869//2869 47//47 49//49 -f 2869//2869 49//49 51//51 -f 2871//2871 43//43 2870//2870 -f 2870//2870 43//43 45//45 -f 2870//2870 45//45 47//47 -f 2872//2872 39//39 2871//2871 -f 2871//2871 39//39 41//41 -f 2871//2871 41//41 43//43 -f 2873//2873 35//35 2872//2872 -f 2872//2872 35//35 37//37 -f 2872//2872 37//37 39//39 -f 2874//2874 31//31 2873//2873 -f 2873//2873 31//31 33//33 -f 2873//2873 33//33 35//35 -f 2875//2875 27//27 2874//2874 -f 2874//2874 27//27 29//29 -f 2874//2874 29//29 31//31 -f 2876//2876 23//23 2875//2875 -f 2875//2875 23//23 25//25 -f 2875//2875 25//25 27//27 -f 2877//2877 19//19 2876//2876 -f 2876//2876 19//19 21//21 -f 2876//2876 21//21 23//23 -f 2878//2878 15//15 2877//2877 -f 2877//2877 15//15 17//17 -f 2877//2877 17//17 19//19 -f 2879//2879 11//11 2878//2878 -f 2878//2878 11//11 13//13 -f 2878//2878 13//13 15//15 -f 2880//2880 7//7 2879//2879 -f 2879//2879 7//7 9//9 -f 2879//2879 9//9 11//11 -f 127//127 1//1 2881//2881 -f 2881//2881 1//1 3//3 -f 2881//2881 3//3 2880//2880 -f 2880//2880 3//3 5//5 -f 2880//2880 5//5 7//7 -# 5792 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_baza.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_baza.obj deleted file mode 100644 index 051c95f35..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_baza.obj +++ /dev/null @@ -1,1288 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sisaljke_baza.obj -# -# Vertices: 314 -# Faces: 644 -# -#### -vn -4.188790 1.360350 2.356194 -v 0.013500 -0.077649 0.171750 -vn 4.188790 1.360350 2.356194 -v 0.028500 -0.077649 0.171750 -vn 3.111411 0.306448 2.945243 -v 0.028500 -0.075000 0.171750 -vn 2.178755 2.178758 2.748893 -v 0.027621 -0.072879 0.171750 -vn 1.179132 2.846684 2.748893 -v 0.026648 -0.072228 0.171750 -vn 0.306446 3.111411 2.945244 -v 0.025500 -0.072000 0.171750 -vn -0.306446 3.111411 2.945245 -v 0.016500 -0.072000 0.171750 -vn -1.179132 2.846684 2.748893 -v 0.015352 -0.072228 0.171750 -vn -2.178756 2.178758 2.748893 -v 0.014379 -0.072879 0.171750 -vn 2.846683 1.179136 2.748893 -v 0.028272 -0.073852 0.171750 -vn -3.111411 0.306446 2.945243 -v 0.013500 -0.075000 0.171750 -vn -2.846683 1.179134 2.748893 -v 0.013728 -0.073852 0.171750 -vn 3.034546 -0.000000 -3.665192 -v 0.025750 -0.115000 0.165750 -vn 2.627994 1.517273 -3.665191 -v 0.026051 -0.116125 0.165750 -vn -3.132252 -0.171045 -3.250700 -v 0.020500 -0.118533 0.165750 -vn -2.477303 -1.901461 -3.359804 -v 0.018433 -0.112444 0.165750 -vn 2.627994 -1.517273 -3.665191 -v 0.026051 -0.113875 0.165750 -vn -2.830194 -1.320068 -3.359808 -v 0.019563 -0.114306 0.165750 -vn -3.048855 -0.676065 -3.359805 -v 0.020263 -0.116368 0.165750 -vn -2.307827 -2.054448 -2.777903 -v 0.014259 -0.108995 0.165750 -vn -2.887693 -1.099114 -2.777902 -v 0.013696 -0.108067 0.165750 -vn -1.837439 -2.545658 -3.068853 -v 0.015115 -0.109661 0.165750 -vn -3.115694 -0.284068 -2.959748 -v 0.013500 -0.107000 0.165750 -vn -2.006914 -2.392670 -3.359809 -v 0.016926 -0.110871 0.165750 -vn -2.950217 -0.919318 -3.504085 -v 0.030913 -0.135282 0.165750 -vn -2.283182 -2.022726 -3.624921 -v 0.030246 -0.134011 0.165750 -vn 1.517273 2.627994 -3.665194 -v 0.026875 -0.116949 0.165750 -vn -1.081647 -2.852087 -3.624911 -v 0.029064 -0.133195 0.165750 -vn 0.367672 -3.028065 -3.624912 -v 0.027638 -0.133022 0.165750 -vn 3.111410 0.306450 -3.337944 -v 0.028500 -0.097000 0.165750 -vn 2.846683 1.179138 -3.534290 -v 0.028728 -0.098148 0.165750 -vn -0.000001 -3.034545 -3.665200 -v 0.028000 -0.112750 0.165750 -vn 1.732765 -2.510355 -3.624914 -v 0.026296 -0.133531 0.165750 -vn 2.700908 -1.417546 -3.624919 -v 0.025344 -0.134606 0.165750 -vn -3.111411 -0.306447 -2.945243 -v 0.020500 -0.139000 0.165750 -vn 3.050304 0.000004 -3.624913 -v 0.025000 -0.136000 0.165750 -vn -2.846683 -1.179135 -2.748893 -v 0.020728 -0.140148 0.165750 -vn 2.700907 1.417550 -3.624916 -v 0.025344 -0.137394 0.165750 -vn 1.517273 -2.627994 -3.665191 -v 0.026875 -0.113051 0.165750 -vn -4.188790 -1.360350 -2.356195 -v 0.013500 -0.090351 0.165750 -vn 4.188790 -1.360350 -2.356196 -v 0.028500 -0.090351 0.165750 -vn 2.178762 2.178754 -3.534287 -v 0.029379 -0.099121 0.165750 -vn 1.179139 2.846680 -3.534298 -v 0.030352 -0.099772 0.165750 -vn -1.517274 -2.627994 -3.665190 -v 0.029125 -0.113051 0.165750 -vn 2.846683 -1.179138 -2.748898 -v 0.035272 -0.140148 0.165750 -vn -2.283182 2.022726 -3.624920 -v 0.030246 -0.137989 0.165750 -vn -2.950216 0.919322 -3.504081 -v 0.030913 -0.136718 0.165750 -vn 0.306446 3.111411 -3.337941 -v 0.031500 -0.100000 0.165750 -vn 0.306445 3.111411 -2.945244 -v 0.032500 -0.100000 0.165750 -vn 1.179132 2.846684 -2.748893 -v 0.033648 -0.100228 0.165750 -vn 3.111410 -0.306452 -2.945238 -v 0.035500 -0.139000 0.165750 -vn -3.118654 0.000004 -3.386712 -v 0.031000 -0.136000 0.165750 -vn -3.034546 0.000000 -3.665191 -v 0.030250 -0.115000 0.165750 -vn 3.111409 0.306450 -2.945242 -v 0.035500 -0.103000 0.165750 -vn -2.627994 -1.517273 -3.665191 -v 0.029949 -0.113875 0.165750 -vn 2.846684 1.179136 -2.748895 -v 0.035272 -0.101852 0.165750 -vn 2.178757 2.178756 -2.748892 -v 0.034621 -0.100879 0.165750 -vn 2.178771 -2.178747 -2.748902 -v 0.034621 -0.141121 0.165750 -vn 1.179145 -2.846675 -2.748883 -v 0.033648 -0.141772 0.165750 -vn -1.081647 2.852087 -3.624912 -v 0.029064 -0.138805 0.165750 -vn 0.306445 -3.111411 -2.945245 -v 0.032500 -0.142000 0.165750 -vn 0.367672 3.028065 -3.624912 -v 0.027638 -0.138978 0.165750 -vn -0.306446 -3.111411 -2.945244 -v 0.023500 -0.142000 0.165750 -vn 1.732765 2.510355 -3.624914 -v 0.026296 -0.138469 0.165750 -vn -1.179145 -2.846676 -2.748884 -v 0.022352 -0.141772 0.165750 -vn -2.178768 -2.178750 -2.748903 -v 0.021379 -0.141121 0.165750 -vn -0.000001 3.034546 -3.665192 -v 0.028000 -0.117250 0.165750 -vn -1.517274 2.627994 -3.665191 -v 0.029125 -0.116949 0.165750 -vn -2.627994 1.517273 -3.665191 -v 0.029949 -0.116125 0.165750 -vn -3.132253 -0.171045 3.250700 -v 0.020500 -0.118533 0.171750 -vn -3.111411 -0.306447 2.945243 -v 0.020500 -0.139000 0.171750 -vn 0.306445 -3.111411 2.945245 -v 0.032500 -0.142000 0.171750 -vn -0.306446 -3.111411 2.945244 -v 0.023500 -0.142000 0.171750 -vn 3.111409 -0.306452 2.945239 -v 0.035500 -0.139000 0.171750 -vn 3.111410 0.306450 2.945245 -v 0.035500 -0.103000 0.171750 -vn -2.006914 -2.392671 3.359809 -v 0.016926 -0.110871 0.171750 -vn -2.477303 -1.901461 3.359804 -v 0.018433 -0.112444 0.171750 -vn 2.627994 -1.517273 3.665191 -v 0.026051 -0.113875 0.171750 -vn 3.034546 0.000000 3.665192 -v 0.025750 -0.115000 0.171750 -vn -2.627994 -1.517273 3.665191 -v 0.029949 -0.113875 0.171750 -vn -3.034546 -0.000000 3.665191 -v 0.030250 -0.115000 0.171750 -vn -2.627994 1.517273 3.665190 -v 0.029949 -0.116125 0.171750 -vn 1.732765 -2.510355 3.624914 -v 0.026296 -0.133531 0.171750 -vn 2.700908 -1.417546 3.624922 -v 0.025344 -0.134606 0.171750 -vn -1.517274 2.627994 3.665195 -v 0.029125 -0.116949 0.171750 -vn 3.050304 0.000004 3.624915 -v 0.025000 -0.136000 0.171750 -vn -0.000001 3.034545 3.665192 -v 0.028000 -0.117250 0.171750 -vn 1.517273 2.627994 3.665191 -v 0.026875 -0.116949 0.171750 -vn 2.846683 1.179138 3.534290 -v 0.028728 -0.098148 0.171750 -vn -0.000001 -3.034546 3.665200 -v 0.028000 -0.112750 0.171750 -vn 2.178763 2.178754 3.534287 -v 0.029379 -0.099121 0.171750 -vn 1.179139 2.846680 3.534297 -v 0.030352 -0.099772 0.171750 -vn 0.367672 -3.028065 3.624912 -v 0.027638 -0.133022 0.171750 -vn -1.081647 -2.852087 3.624911 -v 0.029064 -0.133195 0.171750 -vn -2.283182 -2.022726 3.624920 -v 0.030246 -0.134011 0.171750 -vn -2.887693 -1.099114 2.777902 -v 0.013696 -0.108067 0.171750 -vn -2.307827 -2.054448 2.777903 -v 0.014259 -0.108995 0.171750 -vn -3.115693 -0.284068 2.959749 -v 0.013500 -0.107000 0.171750 -vn -1.837439 -2.545658 3.068854 -v 0.015115 -0.109661 0.171750 -vn 3.111410 0.306450 3.337944 -v 0.028500 -0.097000 0.171750 -vn 4.188792 -1.360351 2.356196 -v 0.028500 -0.090351 0.171750 -vn 1.517273 -2.627994 3.665191 -v 0.026875 -0.113051 0.171750 -vn -4.188792 -1.360351 2.356192 -v 0.013500 -0.090351 0.171750 -vn -1.517274 -2.627994 3.665189 -v 0.029125 -0.113051 0.171750 -vn 2.846684 1.179136 2.748896 -v 0.035272 -0.101852 0.171750 -vn 2.178757 2.178757 2.748891 -v 0.034621 -0.100879 0.171750 -vn 0.306446 3.111411 3.337941 -v 0.031500 -0.100000 0.171750 -vn 0.306445 3.111411 2.945244 -v 0.032500 -0.100000 0.171750 -vn 1.179132 2.846684 2.748893 -v 0.033648 -0.100228 0.171750 -vn -2.961520 -0.744442 3.603823 -v 0.030913 -0.135282 0.171750 -vn -2.961521 0.744442 3.603822 -v 0.030913 -0.136718 0.171750 -vn 2.846684 -1.179138 2.748898 -v 0.035272 -0.140148 0.171750 -vn -2.283182 2.022726 3.624919 -v 0.030246 -0.137989 0.171750 -vn 2.178771 -2.178747 2.748902 -v 0.034621 -0.141121 0.171750 -vn -2.846683 -1.179135 2.748893 -v 0.020728 -0.140148 0.171750 -vn 2.700907 1.417550 3.624917 -v 0.025344 -0.137394 0.171750 -vn -1.081647 2.852087 3.624911 -v 0.029064 -0.138805 0.171750 -vn 2.627994 1.517273 3.665192 -v 0.026051 -0.116125 0.171750 -vn -3.048855 -0.676065 3.359805 -v 0.020263 -0.116368 0.171750 -vn -2.830194 -1.320068 3.359808 -v 0.019563 -0.114306 0.171750 -vn 1.179145 -2.846675 2.748883 -v 0.033648 -0.141772 0.171750 -vn 0.367672 3.028065 3.624912 -v 0.027638 -0.138978 0.171750 -vn 1.732765 2.510355 3.624914 -v 0.026296 -0.138469 0.171750 -vn -1.179145 -2.846676 2.748884 -v 0.022352 -0.141772 0.171750 -vn -2.178768 -2.178750 2.748903 -v 0.021379 -0.141121 0.171750 -vn -0.306446 3.111411 -2.945245 -v 0.016500 -0.072000 0.165750 -vn -4.188789 1.360348 -2.356196 -v 0.013500 -0.077649 0.165750 -vn -3.111410 0.306446 -2.945243 -v 0.013500 -0.075000 0.165750 -vn 2.178756 2.178759 -2.748893 -v 0.027621 -0.072879 0.165750 -vn 2.846683 1.179136 -2.748893 -v 0.028272 -0.073852 0.165750 -vn 3.111410 0.306448 -2.945243 -v 0.028500 -0.075000 0.165750 -vn -1.179132 2.846684 -2.748893 -v 0.015352 -0.072228 0.165750 -vn -2.178755 2.178758 -2.748893 -v 0.014379 -0.072879 0.165750 -vn -2.846684 1.179135 -2.748893 -v 0.013728 -0.073852 0.165750 -vn 4.188789 1.360348 -2.356196 -v 0.028500 -0.077649 0.165750 -vn 0.306446 3.111411 -2.945244 -v 0.025500 -0.072000 0.165750 -vn 1.179132 2.846684 -2.748893 -v 0.026648 -0.072228 0.165750 -vn -4.188790 2.720699 -0.000002 -v 0.013500 -0.088734 0.168750 -vn -4.188789 1.360349 -2.356196 -v 0.013500 -0.086367 0.172850 -vn -2.094393 -1.360351 2.356192 -v 0.013500 -0.088041 0.175750 -vn -4.188789 -1.360349 -2.356196 -v 0.013500 -0.081633 0.172850 -vn -2.094395 1.360350 2.356194 -v 0.013500 -0.079959 0.175750 -vn -4.188791 -2.720698 -0.000002 -v 0.013500 -0.079266 0.168750 -vn -4.188790 -1.360350 2.356194 -v 0.013500 -0.081633 0.164650 -vn -2.094397 1.360348 -2.356196 -v 0.013500 -0.079959 0.161750 -vn -4.188791 1.360350 2.356194 -v 0.013500 -0.086367 0.164650 -vn -2.094395 -1.360350 -2.356194 -v 0.013500 -0.088041 0.161750 -vn 4.188791 -2.720699 -0.000002 -v 0.028500 -0.079266 0.168750 -vn 4.188789 -1.360349 -2.356196 -v 0.028500 -0.081633 0.172850 -vn 2.094395 1.360350 2.356194 -v 0.028500 -0.079959 0.175750 -vn 4.188789 1.360349 -2.356196 -v 0.028500 -0.086367 0.172850 -vn 2.094393 -1.360351 2.356192 -v 0.028500 -0.088041 0.175750 -vn 4.188790 2.720699 -0.000002 -v 0.028500 -0.088734 0.168750 -vn 4.188790 1.360350 2.356194 -v 0.028500 -0.086367 0.164650 -vn 2.094395 -1.360350 -2.356194 -v 0.028500 -0.088041 0.161750 -vn 4.188791 -1.360350 2.356194 -v 0.028500 -0.081633 0.164650 -vn 2.094397 1.360348 -2.356196 -v 0.028500 -0.079959 0.161750 -vn -4.188789 -1.360348 -2.356196 -v 0.013500 0.077649 0.165750 -vn 4.188789 -1.360348 -2.356196 -v 0.028500 0.077649 0.165750 -vn 3.111411 -0.306448 -2.945243 -v 0.028500 0.075000 0.165750 -vn 2.178755 -2.178758 -2.748893 -v 0.027621 0.072879 0.165750 -vn 1.179132 -2.846684 -2.748893 -v 0.026648 0.072228 0.165750 -vn 0.306446 -3.111411 -2.945244 -v 0.025500 0.072000 0.165750 -vn -0.306446 -3.111411 -2.945245 -v 0.016500 0.072000 0.165750 -vn -1.179132 -2.846684 -2.748893 -v 0.015352 0.072228 0.165750 -vn -2.178756 -2.178758 -2.748893 -v 0.014379 0.072879 0.165750 -vn 2.846683 -1.179136 -2.748893 -v 0.028272 0.073852 0.165750 -vn -3.111411 -0.306446 -2.945243 -v 0.013500 0.075000 0.165750 -vn -2.846683 -1.179134 -2.748893 -v 0.013728 0.073852 0.165750 -vn 3.034546 0.000000 3.665192 -v 0.025750 0.115000 0.171750 -vn 2.627994 -1.517273 3.665191 -v 0.026051 0.116125 0.171750 -vn -3.132252 0.171045 3.250700 -v 0.020500 0.118533 0.171750 -vn -2.477303 1.901461 3.359804 -v 0.018433 0.112444 0.171750 -vn 2.627994 1.517273 3.665191 -v 0.026051 0.113875 0.171750 -vn -2.830194 1.320068 3.359808 -v 0.019563 0.114306 0.171750 -vn -3.048855 0.676065 3.359805 -v 0.020263 0.116368 0.171750 -vn -2.307827 2.054448 2.777903 -v 0.014259 0.108995 0.171750 -vn -2.887693 1.099114 2.777902 -v 0.013696 0.108067 0.171750 -vn -1.837439 2.545658 3.068853 -v 0.015115 0.109661 0.171750 -vn -3.115693 0.284068 2.959748 -v 0.013500 0.107000 0.171750 -vn -2.006914 2.392670 3.359809 -v 0.016926 0.110871 0.171750 -vn -2.950217 0.919318 3.504085 -v 0.030913 0.135282 0.171750 -vn -2.283182 2.022726 3.624921 -v 0.030246 0.134011 0.171750 -vn 1.517273 -2.627994 3.665194 -v 0.026875 0.116949 0.171750 -vn -1.081647 2.852087 3.624911 -v 0.029064 0.133195 0.171750 -vn 0.367672 3.028065 3.624912 -v 0.027638 0.133022 0.171750 -vn 3.111410 -0.306450 3.337944 -v 0.028500 0.097000 0.171750 -vn 2.846683 -1.179138 3.534290 -v 0.028728 0.098148 0.171750 -vn -0.000001 3.034545 3.665200 -v 0.028000 0.112750 0.171750 -vn 1.732765 2.510355 3.624914 -v 0.026296 0.133531 0.171750 -vn 2.700908 1.417546 3.624919 -v 0.025344 0.134606 0.171750 -vn -3.111411 0.306447 2.945243 -v 0.020500 0.139000 0.171750 -vn 3.050304 -0.000004 3.624913 -v 0.025000 0.136000 0.171750 -vn -2.846683 1.179135 2.748893 -v 0.020728 0.140148 0.171750 -vn 2.700907 -1.417550 3.624916 -v 0.025344 0.137394 0.171750 -vn 1.517273 2.627994 3.665191 -v 0.026875 0.113051 0.171750 -vn -4.188792 1.360351 2.356193 -v 0.013500 0.090351 0.171750 -vn 4.188792 1.360351 2.356194 -v 0.028500 0.090351 0.171750 -vn 2.178762 -2.178754 3.534287 -v 0.029379 0.099121 0.171750 -vn 1.179139 -2.846680 3.534298 -v 0.030352 0.099772 0.171750 -vn -1.517274 2.627994 3.665190 -v 0.029125 0.113051 0.171750 -vn 2.846683 1.179138 2.748898 -v 0.035272 0.140148 0.171750 -vn -2.283182 -2.022726 3.624920 -v 0.030246 0.137989 0.171750 -vn -2.950216 -0.919322 3.504081 -v 0.030913 0.136718 0.171750 -vn 0.306446 -3.111411 3.337941 -v 0.031500 0.100000 0.171750 -vn 0.306445 -3.111411 2.945244 -v 0.032500 0.100000 0.171750 -vn 1.179132 -2.846684 2.748893 -v 0.033648 0.100228 0.171750 -vn 3.111410 0.306452 2.945238 -v 0.035500 0.139000 0.171750 -vn -3.118654 -0.000004 3.386712 -v 0.031000 0.136000 0.171750 -vn -3.034546 -0.000000 3.665191 -v 0.030250 0.115000 0.171750 -vn 3.111409 -0.306450 2.945242 -v 0.035500 0.103000 0.171750 -vn -2.627994 1.517273 3.665191 -v 0.029949 0.113875 0.171750 -vn 2.846684 -1.179136 2.748895 -v 0.035272 0.101852 0.171750 -vn 2.178757 -2.178756 2.748892 -v 0.034621 0.100879 0.171750 -vn 2.178771 2.178747 2.748902 -v 0.034621 0.141121 0.171750 -vn 1.179145 2.846675 2.748883 -v 0.033648 0.141772 0.171750 -vn -1.081647 -2.852087 3.624912 -v 0.029064 0.138805 0.171750 -vn 0.306445 3.111411 2.945245 -v 0.032500 0.142000 0.171750 -vn 0.367672 -3.028065 3.624912 -v 0.027638 0.138978 0.171750 -vn -0.306446 3.111411 2.945244 -v 0.023500 0.142000 0.171750 -vn 1.732765 -2.510355 3.624914 -v 0.026296 0.138469 0.171750 -vn -1.179145 2.846676 2.748884 -v 0.022352 0.141772 0.171750 -vn -2.178768 2.178750 2.748903 -v 0.021379 0.141121 0.171750 -vn -0.000001 -3.034546 3.665192 -v 0.028000 0.117250 0.171750 -vn -1.517274 -2.627994 3.665191 -v 0.029125 0.116949 0.171750 -vn -2.627994 -1.517273 3.665191 -v 0.029949 0.116125 0.171750 -vn -3.132253 0.171045 -3.250700 -v 0.020500 0.118533 0.165750 -vn -3.111411 0.306447 -2.945243 -v 0.020500 0.139000 0.165750 -vn 0.306445 3.111411 -2.945245 -v 0.032500 0.142000 0.165750 -vn -0.306446 3.111411 -2.945244 -v 0.023500 0.142000 0.165750 -vn 3.111409 0.306452 -2.945239 -v 0.035500 0.139000 0.165750 -vn 3.111410 -0.306450 -2.945245 -v 0.035500 0.103000 0.165750 -vn -2.006914 2.392671 -3.359809 -v 0.016926 0.110871 0.165750 -vn -2.477303 1.901461 -3.359804 -v 0.018433 0.112444 0.165750 -vn 2.627994 1.517273 -3.665191 -v 0.026051 0.113875 0.165750 -vn 3.034546 -0.000000 -3.665192 -v 0.025750 0.115000 0.165750 -vn -2.627994 1.517273 -3.665191 -v 0.029949 0.113875 0.165750 -vn -3.034546 0.000000 -3.665191 -v 0.030250 0.115000 0.165750 -vn -2.627994 -1.517273 -3.665190 -v 0.029949 0.116125 0.165750 -vn 1.732765 2.510355 -3.624914 -v 0.026296 0.133531 0.165750 -vn 2.700908 1.417546 -3.624922 -v 0.025344 0.134606 0.165750 -vn -1.517274 -2.627994 -3.665195 -v 0.029125 0.116949 0.165750 -vn 3.050304 -0.000004 -3.624915 -v 0.025000 0.136000 0.165750 -vn -0.000001 -3.034545 -3.665192 -v 0.028000 0.117250 0.165750 -vn 1.517273 -2.627994 -3.665191 -v 0.026875 0.116949 0.165750 -vn 2.846683 -1.179138 -3.534290 -v 0.028728 0.098148 0.165750 -vn -0.000001 3.034546 -3.665200 -v 0.028000 0.112750 0.165750 -vn 2.178763 -2.178754 -3.534287 -v 0.029379 0.099121 0.165750 -vn 1.179139 -2.846680 -3.534297 -v 0.030352 0.099772 0.165750 -vn 0.367672 3.028065 -3.624912 -v 0.027638 0.133022 0.165750 -vn -1.081647 2.852087 -3.624911 -v 0.029064 0.133195 0.165750 -vn -2.283182 2.022726 -3.624920 -v 0.030246 0.134011 0.165750 -vn -2.887693 1.099114 -2.777902 -v 0.013696 0.108067 0.165750 -vn -2.307827 2.054448 -2.777903 -v 0.014259 0.108995 0.165750 -vn -3.115694 0.284068 -2.959749 -v 0.013500 0.107000 0.165750 -vn -1.837439 2.545658 -3.068854 -v 0.015115 0.109661 0.165750 -vn 3.111410 -0.306450 -3.337944 -v 0.028500 0.097000 0.165750 -vn 4.188790 1.360350 -2.356198 -v 0.028500 0.090351 0.165750 -vn 1.517273 2.627994 -3.665191 -v 0.026875 0.113051 0.165750 -vn -4.188790 1.360350 -2.356194 -v 0.013500 0.090351 0.165750 -vn -1.517274 2.627994 -3.665189 -v 0.029125 0.113051 0.165750 -vn 2.846684 -1.179136 -2.748896 -v 0.035272 0.101852 0.165750 -vn 2.178757 -2.178757 -2.748891 -v 0.034621 0.100879 0.165750 -vn 0.306446 -3.111411 -3.337941 -v 0.031500 0.100000 0.165750 -vn 0.306445 -3.111411 -2.945244 -v 0.032500 0.100000 0.165750 -vn 1.179132 -2.846684 -2.748893 -v 0.033648 0.100228 0.165750 -vn -2.961520 0.744442 -3.603823 -v 0.030913 0.135282 0.165750 -vn -2.961521 -0.744442 -3.603822 -v 0.030913 0.136718 0.165750 -vn 2.846684 1.179138 -2.748898 -v 0.035272 0.140148 0.165750 -vn -2.283182 -2.022726 -3.624919 -v 0.030246 0.137989 0.165750 -vn 2.178771 2.178747 -2.748902 -v 0.034621 0.141121 0.165750 -vn -2.846683 1.179135 -2.748893 -v 0.020728 0.140148 0.165750 -vn 2.700907 -1.417550 -3.624917 -v 0.025344 0.137394 0.165750 -vn -1.081647 -2.852087 -3.624911 -v 0.029064 0.138805 0.165750 -vn 2.627994 -1.517273 -3.665192 -v 0.026051 0.116125 0.165750 -vn -3.048855 0.676065 -3.359805 -v 0.020263 0.116368 0.165750 -vn -2.830194 1.320068 -3.359808 -v 0.019563 0.114306 0.165750 -vn 1.179145 2.846675 -2.748883 -v 0.033648 0.141772 0.165750 -vn 0.367672 -3.028065 -3.624912 -v 0.027638 0.138978 0.165750 -vn 1.732765 -2.510355 -3.624914 -v 0.026296 0.138469 0.165750 -vn -1.179145 2.846676 -2.748884 -v 0.022352 0.141772 0.165750 -vn -2.178768 2.178750 -2.748903 -v 0.021379 0.141121 0.165750 -vn -0.306446 -3.111411 2.945245 -v 0.016500 0.072000 0.171750 -vn -4.188790 -1.360350 2.356194 -v 0.013500 0.077649 0.171750 -vn -3.111410 -0.306446 2.945243 -v 0.013500 0.075000 0.171750 -vn 2.178756 -2.178759 2.748893 -v 0.027621 0.072879 0.171750 -vn 2.846683 -1.179136 2.748893 -v 0.028272 0.073852 0.171750 -vn 3.111410 -0.306448 2.945243 -v 0.028500 0.075000 0.171750 -vn -1.179132 -2.846684 2.748893 -v 0.015352 0.072228 0.171750 -vn -2.178755 -2.178758 2.748893 -v 0.014379 0.072879 0.171750 -vn -2.846684 -1.179135 2.748893 -v 0.013728 0.073852 0.171750 -vn 4.188790 -1.360350 2.356194 -v 0.028500 0.077649 0.171750 -vn 0.306446 -3.111411 2.945244 -v 0.025500 0.072000 0.171750 -vn 1.179132 -2.846684 2.748893 -v 0.026648 0.072228 0.171750 -vn -4.188791 -2.720699 -0.000002 -v 0.013500 0.088734 0.168750 -vn -4.188790 -1.360350 2.356194 -v 0.013500 0.086367 0.164650 -vn -2.094395 1.360350 -2.356194 -v 0.013500 0.088041 0.161750 -vn -4.188791 1.360350 2.356194 -v 0.013500 0.081633 0.164650 -vn -2.094397 -1.360348 -2.356196 -v 0.013500 0.079959 0.161750 -vn -4.188791 2.720699 -0.000002 -v 0.013500 0.079266 0.168750 -vn -4.188789 1.360349 -2.356196 -v 0.013500 0.081633 0.172850 -vn -2.094395 -1.360350 2.356194 -v 0.013500 0.079959 0.175750 -vn -4.188789 -1.360349 -2.356196 -v 0.013500 0.086367 0.172850 -vn -2.094393 1.360351 2.356192 -v 0.013500 0.088041 0.175750 -vn 4.188791 2.720699 -0.000002 -v 0.028500 0.079266 0.168750 -vn 4.188790 1.360350 2.356194 -v 0.028500 0.081633 0.164650 -vn 2.094397 -1.360348 -2.356196 -v 0.028500 0.079959 0.161750 -vn 4.188791 -1.360350 2.356194 -v 0.028500 0.086367 0.164650 -vn 2.094395 1.360350 -2.356194 -v 0.028500 0.088041 0.161750 -vn 4.188791 -2.720699 -0.000002 -v 0.028500 0.088734 0.168750 -vn 4.188789 -1.360349 -2.356196 -v 0.028500 0.086367 0.172850 -vn 2.094393 1.360351 2.356192 -v 0.028500 0.088041 0.175750 -vn 4.188789 1.360349 -2.356196 -v 0.028500 0.081633 0.172850 -vn 2.094395 -1.360350 2.356194 -v 0.028500 0.079959 0.175750 -# 314 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 10//10 4//4 3//3 -f 3//3 4//4 6//6 -f 3//3 6//6 1//1 -f 1//1 6//6 7//7 -f 1//1 7//7 11//11 -f 11//11 7//7 9//9 -f 11//11 9//9 12//12 -f 13//13 14//14 15//15 -f 16//16 17//17 18//18 -f 18//18 17//17 13//13 -f 18//18 13//13 19//19 -f 19//19 13//13 15//15 -f 20//20 21//21 22//22 -f 22//22 21//21 23//23 -f 22//22 23//23 24//24 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 14//14 -f 14//14 28//28 29//29 -f 14//14 29//29 15//15 -f 30//30 31//31 32//32 -f 29//29 33//33 15//15 -f 15//15 33//33 34//34 -f 15//15 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 16//16 24//24 17//17 -f 17//17 24//24 23//23 -f 17//17 23//23 39//39 -f 39//39 23//23 40//40 -f 39//39 40//40 32//32 -f 32//32 40//40 41//41 -f 32//32 41//41 30//30 -f 31//31 42//42 32//32 -f 32//32 42//42 43//43 -f 32//32 43//43 44//44 -f 45//45 46//46 47//47 -f 43//43 48//48 44//44 -f 44//44 48//48 49//49 -f 44//44 49//49 50//50 -f 45//45 47//47 51//51 -f 51//51 47//47 52//52 -f 51//51 52//52 25//25 -f 51//51 53//53 54//54 -f 54//54 53//53 55//55 -f 54//54 55//55 56//56 -f 56//56 55//55 44//44 -f 56//56 44//44 57//57 -f 57//57 44//44 50//50 -f 45//45 58//58 46//46 -f 46//46 58//58 59//59 -f 46//46 59//59 60//60 -f 60//60 59//59 61//61 -f 60//60 61//61 62//62 -f 62//62 61//61 63//63 -f 62//62 63//63 64//64 -f 64//64 63//63 65//65 -f 64//64 65//65 38//38 -f 38//38 65//65 66//66 -f 38//38 66//66 37//37 -f 27//27 67//67 25//25 -f 25//25 67//67 68//68 -f 25//25 68//68 51//51 -f 51//51 68//68 69//69 -f 51//51 69//69 53//53 -f 15//15 35//35 70//70 -f 70//70 35//35 71//71 -f 72//72 73//73 61//61 -f 61//61 73//73 63//63 -f 51//51 54//54 74//74 -f 74//74 54//54 75//75 -f 76//76 77//77 78//78 -f 78//78 77//77 79//79 -f 80//80 81//81 75//75 -f 75//75 81//81 82//82 -f 83//83 82//82 84//84 -f 84//84 82//82 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 86//86 87//87 88//88 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 83//83 93//93 82//82 -f 82//82 93//93 94//94 -f 82//82 94//94 75//75 -f 75//75 94//94 95//95 -f 75//75 95//95 74//74 -f 96//96 97//97 98//98 -f 98//98 97//97 99//99 -f 89//89 100//100 90//90 -f 90//90 100//100 101//101 -f 90//90 101//101 102//102 -f 102//102 101//101 103//103 -f 102//102 103//103 78//78 -f 78//78 103//103 98//98 -f 78//78 98//98 76//76 -f 76//76 98//98 99//99 -f 80//80 75//75 104//104 -f 104//104 75//75 105//105 -f 104//104 105//105 106//106 -f 92//92 90//90 107//107 -f 107//107 90//90 104//104 -f 107//107 104//104 108//108 -f 108//108 104//104 106//106 -f 108//108 106//106 109//109 -f 95//95 110//110 74//74 -f 74//74 110//110 111//111 -f 74//74 111//111 112//112 -f 112//112 111//111 113//113 -f 112//112 113//113 114//114 -f 71//71 115//115 116//116 -f 73//73 72//72 117//117 -f 116//116 86//86 71//71 -f 71//71 86//86 88//88 -f 71//71 88//88 70//70 -f 70//70 88//88 118//118 -f 70//70 118//118 119//119 -f 119//119 118//118 79//79 -f 119//119 79//79 120//120 -f 120//120 79//79 77//77 -f 117//117 72//72 113//113 -f 113//113 72//72 121//121 -f 113//113 121//121 114//114 -f 117//117 122//122 73//73 -f 73//73 122//122 123//123 -f 73//73 123//123 124//124 -f 124//124 123//123 116//116 -f 124//124 116//116 125//125 -f 125//125 116//116 115//115 -f 126//126 127//127 128//128 -f 129//129 130//130 131//131 -f 132//132 126//126 133//133 -f 133//133 126//126 128//128 -f 133//133 128//128 134//134 -f 127//127 126//126 135//135 -f 135//135 126//126 136//136 -f 135//135 136//136 131//131 -f 131//131 136//136 137//137 -f 131//131 137//137 129//129 -f 79//79 13//13 78//78 -f 78//78 13//13 17//17 -f 78//78 17//17 102//102 -f 102//102 17//17 39//39 -f 102//102 39//39 90//90 -f 90//90 39//39 32//32 -f 90//90 32//32 104//104 -f 104//104 32//32 44//44 -f 104//104 44//44 80//80 -f 80//80 44//44 55//55 -f 80//80 55//55 81//81 -f 81//81 55//55 53//53 -f 81//81 53//53 82//82 -f 82//82 53//53 69//69 -f 82//82 69//69 85//85 -f 85//85 69//69 68//68 -f 85//85 68//68 87//87 -f 87//87 68//68 67//67 -f 87//87 67//67 88//88 -f 88//88 67//67 27//27 -f 88//88 27//27 118//118 -f 118//118 27//27 14//14 -f 118//118 14//14 79//79 -f 79//79 14//14 13//13 -f 26//26 25//25 110//110 -f 110//110 25//25 52//52 -f 110//110 52//52 111//111 -f 111//111 52//52 47//47 -f 111//111 47//47 113//113 -f 113//113 47//47 46//46 -f 113//113 46//46 117//117 -f 117//117 46//46 60//60 -f 117//117 60//60 122//122 -f 122//122 60//60 62//62 -f 122//122 62//62 123//123 -f 123//123 62//62 64//64 -f 123//123 64//64 116//116 -f 116//116 64//64 38//38 -f 116//116 38//38 86//86 -f 86//86 38//38 36//36 -f 86//86 36//36 84//84 -f 84//84 36//36 34//34 -f 84//84 34//34 83//83 -f 83//83 34//34 33//33 -f 83//83 33//33 93//93 -f 93//93 33//33 29//29 -f 93//93 29//29 94//94 -f 94//94 29//29 28//28 -f 94//94 28//28 95//95 -f 95//95 28//28 26//26 -f 95//95 26//26 110//110 -f 72//72 61//61 59//59 -f 72//72 59//59 121//121 -f 121//121 59//59 58//58 -f 121//121 58//58 114//114 -f 114//114 58//58 45//45 -f 114//114 45//45 112//112 -f 112//112 45//45 51//51 -f 112//112 51//51 74//74 -f 71//71 35//35 37//37 -f 71//71 37//37 115//115 -f 115//115 37//37 66//66 -f 115//115 66//66 125//125 -f 125//125 66//66 65//65 -f 125//125 65//65 124//124 -f 124//124 65//65 63//63 -f 124//124 63//63 73//73 -f 22//22 99//99 97//97 -f 22//22 97//97 20//20 -f 20//20 97//97 96//96 -f 20//20 96//96 21//21 -f 21//21 96//96 98//98 -f 21//21 98//98 23//23 -f 23//23 98//98 138//138 -f 138//138 98//98 103//103 -f 138//138 103//103 139//139 -f 139//139 103//103 140//140 -f 139//139 140//140 141//141 -f 141//141 140//140 142//142 -f 141//141 142//142 143//143 -f 143//143 142//142 1//1 -f 143//143 1//1 11//11 -f 11//11 128//128 143//143 -f 143//143 128//128 127//127 -f 143//143 127//127 144//144 -f 144//144 127//127 145//145 -f 144//144 145//145 146//146 -f 146//146 145//145 147//147 -f 146//146 147//147 138//138 -f 138//138 147//147 40//40 -f 138//138 40//40 23//23 -f 128//128 11//11 12//12 -f 128//128 12//12 134//134 -f 134//134 12//12 9//9 -f 134//134 9//9 133//133 -f 133//133 9//9 8//8 -f 133//133 8//8 132//132 -f 132//132 8//8 7//7 -f 132//132 7//7 126//126 -f 7//7 6//6 126//126 -f 126//126 6//6 136//136 -f 136//136 6//6 5//5 -f 136//136 5//5 137//137 -f 137//137 5//5 4//4 -f 137//137 4//4 129//129 -f 129//129 4//4 10//10 -f 129//129 10//10 130//130 -f 130//130 10//10 3//3 -f 130//130 3//3 131//131 -f 131//131 3//3 148//148 -f 148//148 3//3 2//2 -f 148//148 2//2 149//149 -f 149//149 2//2 150//150 -f 149//149 150//150 151//151 -f 151//151 150//150 152//152 -f 151//151 152//152 153//153 -f 153//153 152//152 101//101 -f 153//153 101//101 100//100 -f 100//100 30//30 153//153 -f 153//153 30//30 41//41 -f 153//153 41//41 154//154 -f 154//154 41//41 155//155 -f 154//154 155//155 156//156 -f 156//156 155//155 157//157 -f 156//156 157//157 148//148 -f 148//148 157//157 135//135 -f 148//148 135//135 131//131 -f 30//30 100//100 31//31 -f 31//31 100//100 89//89 -f 31//31 89//89 42//42 -f 42//42 89//89 91//91 -f 42//42 91//91 43//43 -f 43//43 91//91 92//92 -f 43//43 92//92 48//48 -f 48//48 92//92 107//107 -f 107//107 108//108 48//48 -f 48//48 108//108 49//49 -f 49//49 108//108 109//109 -f 49//49 109//109 50//50 -f 50//50 109//109 106//106 -f 50//50 106//106 57//57 -f 57//57 106//106 105//105 -f 57//57 105//105 56//56 -f 56//56 105//105 75//75 -f 56//56 75//75 54//54 -f 15//15 70//70 19//19 -f 19//19 70//70 119//119 -f 19//19 119//119 18//18 -f 18//18 119//119 120//120 -f 18//18 120//120 16//16 -f 16//16 120//120 77//77 -f 16//16 77//77 24//24 -f 24//24 77//77 76//76 -f 24//24 76//76 22//22 -f 22//22 76//76 99//99 -f 145//145 157//157 147//147 -f 147//147 157//157 155//155 -f 157//157 145//145 135//135 -f 135//135 145//145 127//127 -f 147//147 155//155 40//40 -f 40//40 155//155 41//41 -f 1//1 142//142 2//2 -f 2//2 142//142 150//150 -f 140//140 152//152 142//142 -f 142//142 152//152 150//150 -f 101//101 152//152 103//103 -f 103//103 152//152 140//140 -f 156//156 148//148 144//144 -f 144//144 148//148 143//143 -f 154//154 156//156 146//146 -f 146//146 156//156 144//144 -f 153//153 154//154 138//138 -f 138//138 154//154 146//146 -f 151//151 153//153 139//139 -f 139//139 153//153 138//138 -f 149//149 151//151 141//141 -f 141//141 151//151 139//139 -f 148//148 149//149 143//143 -f 143//143 149//149 141//141 -f 158//158 159//159 160//160 -f 161//161 162//162 163//163 -f 164//164 165//165 166//166 -f 167//167 161//161 160//160 -f 160//160 161//161 163//163 -f 160//160 163//163 158//158 -f 158//158 163//163 164//164 -f 158//158 164//164 168//168 -f 168//168 164//164 166//166 -f 168//168 166//166 169//169 -f 170//170 171//171 172//172 -f 173//173 174//174 175//175 -f 175//175 174//174 170//170 -f 175//175 170//170 176//176 -f 176//176 170//170 172//172 -f 177//177 178//178 179//179 -f 179//179 178//178 180//180 -f 179//179 180//180 181//181 -f 182//182 183//183 184//184 -f 184//184 183//183 185//185 -f 184//184 185//185 171//171 -f 171//171 185//185 186//186 -f 171//171 186//186 172//172 -f 187//187 188//188 189//189 -f 186//186 190//190 172//172 -f 172//172 190//190 191//191 -f 172//172 191//191 192//192 -f 192//192 191//191 193//193 -f 192//192 193//193 194//194 -f 194//194 193//193 195//195 -f 173//173 181//181 174//174 -f 174//174 181//181 180//180 -f 174//174 180//180 196//196 -f 196//196 180//180 197//197 -f 196//196 197//197 189//189 -f 189//189 197//197 198//198 -f 189//189 198//198 187//187 -f 188//188 199//199 189//189 -f 189//189 199//199 200//200 -f 189//189 200//200 201//201 -f 202//202 203//203 204//204 -f 200//200 205//205 201//201 -f 201//201 205//205 206//206 -f 201//201 206//206 207//207 -f 202//202 204//204 208//208 -f 208//208 204//204 209//209 -f 208//208 209//209 182//182 -f 208//208 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 213//213 212//212 201//201 -f 213//213 201//201 214//214 -f 214//214 201//201 207//207 -f 202//202 215//215 203//203 -f 203//203 215//215 216//216 -f 203//203 216//216 217//217 -f 217//217 216//216 218//218 -f 217//217 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 195//195 -f 195//195 222//222 223//223 -f 195//195 223//223 194//194 -f 184//184 224//224 182//182 -f 182//182 224//224 225//225 -f 182//182 225//225 208//208 -f 208//208 225//225 226//226 -f 208//208 226//226 210//210 -f 172//172 192//192 227//227 -f 227//227 192//192 228//228 -f 229//229 230//230 218//218 -f 218//218 230//230 220//220 -f 208//208 211//211 231//231 -f 231//231 211//211 232//232 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 237//237 238//238 232//232 -f 232//232 238//238 239//239 -f 240//240 239//239 241//241 -f 241//241 239//239 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 246//246 247//247 248//248 -f 248//248 247//247 249//249 -f 240//240 250//250 239//239 -f 239//239 250//250 251//251 -f 239//239 251//251 232//232 -f 232//232 251//251 252//252 -f 232//232 252//252 231//231 -f 253//253 254//254 255//255 -f 255//255 254//254 256//256 -f 246//246 257//257 247//247 -f 247//247 257//257 258//258 -f 247//247 258//258 259//259 -f 259//259 258//258 260//260 -f 259//259 260//260 235//235 -f 235//235 260//260 255//255 -f 235//235 255//255 233//233 -f 233//233 255//255 256//256 -f 237//237 232//232 261//261 -f 261//261 232//232 262//262 -f 261//261 262//262 263//263 -f 249//249 247//247 264//264 -f 264//264 247//247 261//261 -f 264//264 261//261 265//265 -f 265//265 261//261 263//263 -f 265//265 263//263 266//266 -f 252//252 267//267 231//231 -f 231//231 267//267 268//268 -f 231//231 268//268 269//269 -f 269//269 268//268 270//270 -f 269//269 270//270 271//271 -f 228//228 272//272 273//273 -f 230//230 229//229 274//274 -f 273//273 243//243 228//228 -f 228//228 243//243 245//245 -f 228//228 245//245 227//227 -f 227//227 245//245 275//275 -f 227//227 275//275 276//276 -f 276//276 275//275 236//236 -f 276//276 236//236 277//277 -f 277//277 236//236 234//234 -f 274//274 229//229 270//270 -f 270//270 229//229 278//278 -f 270//270 278//278 271//271 -f 274//274 279//279 230//230 -f 230//230 279//279 280//280 -f 230//230 280//280 281//281 -f 281//281 280//280 273//273 -f 281//281 273//273 282//282 -f 282//282 273//273 272//272 -f 283//283 284//284 285//285 -f 286//286 287//287 288//288 -f 289//289 283//283 290//290 -f 290//290 283//283 285//285 -f 290//290 285//285 291//291 -f 284//284 283//283 292//292 -f 292//292 283//283 293//293 -f 292//292 293//293 288//288 -f 288//288 293//293 294//294 -f 288//288 294//294 286//286 -f 236//236 170//170 235//235 -f 235//235 170//170 174//174 -f 235//235 174//174 259//259 -f 259//259 174//174 196//196 -f 259//259 196//196 247//247 -f 247//247 196//196 189//189 -f 247//247 189//189 261//261 -f 261//261 189//189 201//201 -f 261//261 201//201 237//237 -f 237//237 201//201 212//212 -f 237//237 212//212 238//238 -f 238//238 212//212 210//210 -f 238//238 210//210 239//239 -f 239//239 210//210 226//226 -f 239//239 226//226 242//242 -f 242//242 226//226 225//225 -f 242//242 225//225 244//244 -f 244//244 225//225 224//224 -f 244//244 224//224 245//245 -f 245//245 224//224 184//184 -f 245//245 184//184 275//275 -f 275//275 184//184 171//171 -f 275//275 171//171 236//236 -f 236//236 171//171 170//170 -f 183//183 182//182 267//267 -f 267//267 182//182 209//209 -f 267//267 209//209 268//268 -f 268//268 209//209 204//204 -f 268//268 204//204 270//270 -f 270//270 204//204 203//203 -f 270//270 203//203 274//274 -f 274//274 203//203 217//217 -f 274//274 217//217 279//279 -f 279//279 217//217 219//219 -f 279//279 219//219 280//280 -f 280//280 219//219 221//221 -f 280//280 221//221 273//273 -f 273//273 221//221 195//195 -f 273//273 195//195 243//243 -f 243//243 195//195 193//193 -f 243//243 193//193 241//241 -f 241//241 193//193 191//191 -f 241//241 191//191 240//240 -f 240//240 191//191 190//190 -f 240//240 190//190 250//250 -f 250//250 190//190 186//186 -f 250//250 186//186 251//251 -f 251//251 186//186 185//185 -f 251//251 185//185 252//252 -f 252//252 185//185 183//183 -f 252//252 183//183 267//267 -f 229//229 218//218 216//216 -f 229//229 216//216 278//278 -f 278//278 216//216 215//215 -f 278//278 215//215 271//271 -f 271//271 215//215 202//202 -f 271//271 202//202 269//269 -f 269//269 202//202 208//208 -f 269//269 208//208 231//231 -f 228//228 192//192 194//194 -f 228//228 194//194 272//272 -f 272//272 194//194 223//223 -f 272//272 223//223 282//282 -f 282//282 223//223 222//222 -f 282//282 222//222 281//281 -f 281//281 222//222 220//220 -f 281//281 220//220 230//230 -f 179//179 256//256 254//254 -f 179//179 254//254 177//177 -f 177//177 254//254 253//253 -f 177//177 253//253 178//178 -f 178//178 253//253 255//255 -f 178//178 255//255 180//180 -f 180//180 255//255 295//295 -f 295//295 255//255 260//260 -f 295//295 260//260 296//296 -f 296//296 260//260 297//297 -f 296//296 297//297 298//298 -f 298//298 297//297 299//299 -f 298//298 299//299 300//300 -f 300//300 299//299 158//158 -f 300//300 158//158 168//168 -f 168//168 285//285 300//300 -f 300//300 285//285 284//284 -f 300//300 284//284 301//301 -f 301//301 284//284 302//302 -f 301//301 302//302 303//303 -f 303//303 302//302 304//304 -f 303//303 304//304 295//295 -f 295//295 304//304 197//197 -f 295//295 197//197 180//180 -f 285//285 168//168 169//169 -f 285//285 169//169 291//291 -f 291//291 169//169 166//166 -f 291//291 166//166 290//290 -f 290//290 166//166 165//165 -f 290//290 165//165 289//289 -f 289//289 165//165 164//164 -f 289//289 164//164 283//283 -f 164//164 163//163 283//283 -f 283//283 163//163 293//293 -f 293//293 163//163 162//162 -f 293//293 162//162 294//294 -f 294//294 162//162 161//161 -f 294//294 161//161 286//286 -f 286//286 161//161 167//167 -f 286//286 167//167 287//287 -f 287//287 167//167 160//160 -f 287//287 160//160 288//288 -f 288//288 160//160 305//305 -f 305//305 160//160 159//159 -f 305//305 159//159 306//306 -f 306//306 159//159 307//307 -f 306//306 307//307 308//308 -f 308//308 307//307 309//309 -f 308//308 309//309 310//310 -f 310//310 309//309 258//258 -f 310//310 258//258 257//257 -f 257//257 187//187 310//310 -f 310//310 187//187 198//198 -f 310//310 198//198 311//311 -f 311//311 198//198 312//312 -f 311//311 312//312 313//313 -f 313//313 312//312 314//314 -f 313//313 314//314 305//305 -f 305//305 314//314 292//292 -f 305//305 292//292 288//288 -f 187//187 257//257 188//188 -f 188//188 257//257 246//246 -f 188//188 246//246 199//199 -f 199//199 246//246 248//248 -f 199//199 248//248 200//200 -f 200//200 248//248 249//249 -f 200//200 249//249 205//205 -f 205//205 249//249 264//264 -f 264//264 265//265 205//205 -f 205//205 265//265 206//206 -f 206//206 265//265 266//266 -f 206//206 266//266 207//207 -f 207//207 266//266 263//263 -f 207//207 263//263 214//214 -f 214//214 263//263 262//262 -f 214//214 262//262 213//213 -f 213//213 262//262 232//232 -f 213//213 232//232 211//211 -f 172//172 227//227 176//176 -f 176//176 227//227 276//276 -f 176//176 276//276 175//175 -f 175//175 276//276 277//277 -f 175//175 277//277 173//173 -f 173//173 277//277 234//234 -f 173//173 234//234 181//181 -f 181//181 234//234 233//233 -f 181//181 233//233 179//179 -f 179//179 233//233 256//256 -f 302//302 314//314 304//304 -f 304//304 314//314 312//312 -f 314//314 302//302 292//292 -f 292//292 302//302 284//284 -f 304//304 312//312 197//197 -f 197//197 312//312 198//198 -f 158//158 299//299 159//159 -f 159//159 299//299 307//307 -f 297//297 309//309 299//299 -f 299//299 309//309 307//307 -f 258//258 309//309 260//260 -f 260//260 309//309 297//297 -f 313//313 305//305 301//301 -f 301//301 305//305 300//300 -f 311//311 313//313 303//303 -f 303//303 313//313 301//301 -f 310//310 311//311 295//295 -f 295//295 311//311 303//303 -f 308//308 310//310 296//296 -f 296//296 310//310 295//295 -f 306//306 308//308 298//298 -f 298//298 308//308 296//296 -f 305//305 306//306 300//300 -f 300//300 306//306 298//298 -# 644 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_kolena.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_kolena.obj deleted file mode 100644 index 60314cc42..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_kolena.obj +++ /dev/null @@ -1,15216 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sisaljke_kolena.obj -# -# Vertices: 3800 -# Faces: 7600 -# -#### -vn -3.128191 0.000000 2.956794 -v -0.000330 0.083827 0.184150 -vn -3.074928 -0.574803 -2.956793 -v -0.000258 0.083046 0.174150 -vn -3.074928 -0.574803 2.956793 -v -0.000258 0.083046 0.184150 -vn -2.916951 -1.130034 -2.956793 -v -0.000043 0.082292 0.174150 -vn -2.916951 -1.130034 2.956793 -v -0.000043 0.082292 0.184150 -vn -2.659642 -1.646780 -2.956794 -v 0.000307 0.081589 0.174150 -vn -2.659642 -1.646779 2.956794 -v 0.000307 0.081589 0.184150 -vn -2.311759 -2.107450 -2.956790 -v 0.000779 0.080964 0.174150 -vn -2.311759 -2.107450 2.956790 -v 0.000779 0.080964 0.184150 -vn -1.885159 -2.496350 -2.956799 -v 0.001359 0.080435 0.174150 -vn -1.885159 -2.496349 2.956799 -v 0.001359 0.080435 0.184150 -vn -1.394362 -2.800238 -2.956790 -v 0.002026 0.080022 0.174150 -vn -1.394362 -2.800238 2.956791 -v 0.002026 0.080022 0.184150 -vn -0.856068 -3.008774 -2.956789 -v 0.002757 0.079739 0.174150 -vn -0.856068 -3.008774 2.956789 -v 0.002757 0.079739 0.184150 -vn -0.288628 -3.114847 -2.956796 -v 0.003528 0.079595 0.174150 -vn -0.288628 -3.114848 2.956796 -v 0.003528 0.079595 0.184150 -vn 0.288628 -3.114848 -2.956796 -v 0.004312 0.079595 0.174150 -vn 0.288628 -3.114847 2.956796 -v 0.004312 0.079595 0.184150 -vn 0.856068 -3.008774 -2.956789 -v 0.005083 0.079739 0.174150 -vn 0.856068 -3.008774 2.956789 -v 0.005083 0.079739 0.184150 -vn 1.394360 -2.800239 -2.956792 -v 0.005814 0.080022 0.174150 -vn 1.394360 -2.800238 2.956792 -v 0.005814 0.080022 0.184150 -vn 1.885159 -2.496348 -2.956796 -v 0.006481 0.080435 0.174150 -vn 1.885159 -2.496349 2.956796 -v 0.006481 0.080435 0.184150 -vn 2.311761 -2.107448 -2.956791 -v 0.007061 0.080964 0.174150 -vn 2.311761 -2.107448 2.956791 -v 0.007061 0.080964 0.184150 -vn 2.659642 -1.646779 -2.956795 -v 0.007533 0.081589 0.174150 -vn 2.659642 -1.646780 2.956794 -v 0.007533 0.081589 0.184150 -vn 2.916951 -1.130034 -2.956793 -v 0.007883 0.082292 0.174150 -vn 2.916951 -1.130034 2.956793 -v 0.007883 0.082292 0.184150 -vn 3.074928 -0.574803 -2.956792 -v 0.008098 0.083046 0.174150 -vn 3.074928 -0.574803 2.956792 -v 0.008098 0.083046 0.184150 -vn 3.128191 0.000000 -2.956794 -v 0.008170 0.083827 0.174150 -vn 3.128191 0.000000 2.956794 -v 0.008170 0.083827 0.184150 -vn 3.074928 0.574803 -2.956792 -v 0.008098 0.084608 0.174150 -vn 3.074928 0.574803 2.956793 -v 0.008098 0.084608 0.184150 -vn 2.916951 1.130034 -2.956793 -v 0.007883 0.085362 0.174150 -vn 2.916951 1.130034 2.956793 -v 0.007883 0.085362 0.184150 -vn 2.659642 1.646780 -2.956794 -v 0.007533 0.086064 0.174150 -vn 2.659642 1.646779 2.956794 -v 0.007533 0.086064 0.184150 -vn 2.311761 2.107448 -2.956791 -v 0.007061 0.086690 0.174150 -vn 2.311761 2.107448 2.956791 -v 0.007061 0.086690 0.184150 -vn 1.885159 2.496349 -2.956796 -v 0.006481 0.087218 0.174150 -vn 1.885159 2.496348 2.956797 -v 0.006481 0.087218 0.184150 -vn 1.394360 2.800238 -2.956792 -v 0.005814 0.087631 0.174150 -vn 1.394360 2.800239 2.956792 -v 0.005814 0.087631 0.184150 -vn 0.856068 3.008774 -2.956789 -v 0.005083 0.087915 0.174150 -vn 0.856068 3.008774 2.956789 -v 0.005083 0.087915 0.184150 -vn 0.288628 3.114847 -2.956796 -v 0.004312 0.088059 0.174150 -vn 0.288628 3.114848 2.956796 -v 0.004312 0.088059 0.184150 -vn -0.288628 3.114848 -2.956796 -v 0.003528 0.088059 0.174150 -vn -0.288628 3.114847 2.956796 -v 0.003528 0.088059 0.184150 -vn -0.856068 3.008774 -2.956789 -v 0.002757 0.087915 0.174150 -vn -0.856068 3.008774 2.956789 -v 0.002757 0.087915 0.184150 -vn -1.394362 2.800238 -2.956790 -v 0.002026 0.087631 0.174150 -vn -1.394362 2.800238 2.956790 -v 0.002026 0.087631 0.184150 -vn -1.885159 2.496349 -2.956799 -v 0.001359 0.087218 0.174150 -vn -1.885159 2.496350 2.956799 -v 0.001359 0.087218 0.184150 -vn -2.311759 2.107450 -2.956790 -v 0.000779 0.086690 0.174150 -vn -2.311759 2.107450 2.956790 -v 0.000779 0.086690 0.184150 -vn -2.659642 1.646779 -2.956794 -v 0.000307 0.086064 0.174150 -vn -2.659642 1.646780 2.956795 -v 0.000307 0.086064 0.184150 -vn -2.916951 1.130034 -2.956793 -v -0.000043 0.085362 0.174150 -vn -2.916951 1.130034 2.956793 -v -0.000043 0.085362 0.184150 -vn -3.074928 0.574803 -2.956792 -v -0.000258 0.084608 0.174150 -vn -3.074928 0.574803 2.956792 -v -0.000258 0.084608 0.184150 -vn -3.128191 0.000000 -2.956794 -v -0.000330 0.083827 0.174150 -vn -0.996657 2.969503 -3.295502 -v 0.005112 0.080508 0.174150 -vn -1.448273 2.776519 -3.301628 -v 0.005610 0.080719 0.174150 -vn -1.873580 2.509049 -3.302787 -v 0.006100 0.081027 0.174150 -vn -2.248242 2.180360 -3.299040 -v 0.006512 0.081390 0.174150 -vn -2.570050 1.787631 -3.308805 -v 0.006864 0.081815 0.174150 -vn -2.836260 1.322639 -3.317160 -v 0.007173 0.082349 0.174150 -vn -3.023145 0.809956 -3.315189 -v 0.007381 0.082923 0.174150 -vn 1.132765 -2.920238 -3.295928 -v 0.002735 0.087090 0.174150 -vn 1.578326 -2.704395 -3.303760 -v 0.002246 0.086856 0.174150 -vn 1.995217 -2.413149 -3.304609 -v 0.001762 0.086517 0.174150 -vn 2.355574 -2.063864 -3.299441 -v 0.001368 0.086134 0.174150 -vn 2.657583 -1.654664 -3.308948 -v 0.001037 0.085690 0.174150 -vn 2.899616 -1.177509 -3.316515 -v 0.000757 0.085142 0.174150 -vn 3.059890 -0.658136 -3.314449 -v 0.000578 0.084560 0.174150 -vn 3.128011 -0.134063 -3.306786 -v 0.000503 0.083966 0.174150 -vn 3.108253 0.378367 -3.304332 -v 0.000525 0.083412 0.174150 -vn -3.117597 0.279538 -3.312686 -v 0.007486 0.083517 0.174150 -vn -3.120161 -0.252423 -3.310799 -v 0.007489 0.084110 0.174150 -vn -3.034074 -0.771428 -3.308895 -v 0.007391 0.084692 0.174150 -vn -2.865437 -1.261880 -3.305982 -v 0.007202 0.085240 0.174150 -vn -2.622966 -1.710365 -3.303215 -v 0.006930 0.085741 0.174150 -vn -2.316661 -2.107250 -3.300502 -v 0.006588 0.086184 0.174150 -vn 3.003659 0.882747 -3.308270 -v 0.000643 0.082838 0.174150 -vn 2.817716 1.365235 -3.305601 -v 0.000851 0.082299 0.174150 -vn 2.560205 1.803129 -3.302413 -v 0.001140 0.081809 0.174150 -vn 2.243532 2.185370 -3.298105 -v 0.001496 0.081381 0.174150 -vn 1.878661 2.506343 -3.295697 -v 0.001900 0.081027 0.174150 -vn 1.473105 2.764385 -3.294711 -v 0.002356 0.080737 0.174150 -vn 1.038780 2.955509 -3.291721 -v 0.002842 0.080524 0.174150 -vn -1.979402 -2.429773 -3.280867 -v 0.006186 0.086560 0.174150 -vn -1.625008 -2.679960 -3.279374 -v 0.005840 0.086804 0.174150 -vn -1.219964 -2.885164 -3.293890 -v 0.005359 0.087052 0.174150 -vn -0.773770 -3.035861 -3.290249 -v 0.004862 0.087219 0.174150 -vn -0.304142 -3.117244 -3.297542 -v 0.004355 0.087309 0.174150 -vn 0.187979 -3.126062 -3.300283 -v 0.003779 0.087320 0.174150 -vn 0.671754 -3.059469 -3.295053 -v 0.003250 0.087246 0.174150 -vn 0.588919 3.077187 -3.289245 -v 0.003345 0.080389 0.174150 -vn 0.213596 3.130823 -3.235896 -v 0.003852 0.080330 0.174150 -vn -0.100589 3.135563 -3.247664 -v 0.004000 0.080327 0.174150 -vn -0.517364 3.088287 -3.303350 -v 0.004593 0.080377 0.174150 -vn -3.117597 0.279538 3.312686 -v 0.007486 0.083517 0.184150 -vn -3.023145 0.809956 3.315189 -v 0.007381 0.082923 0.184150 -vn -2.836260 1.322639 3.317159 -v 0.007173 0.082349 0.184150 -vn -2.570049 1.787630 3.308804 -v 0.006864 0.081815 0.184150 -vn -2.248242 2.180360 3.299040 -v 0.006512 0.081390 0.184150 -vn -1.873580 2.509050 3.302787 -v 0.006100 0.081027 0.184150 -vn -1.448273 2.776519 3.301628 -v 0.005610 0.080719 0.184150 -vn -0.996657 2.969503 3.295502 -v 0.005112 0.080508 0.184150 -vn -0.517364 3.088288 3.303350 -v 0.004593 0.080377 0.184150 -vn -0.110187 0.011223 6.182842 -v 0.004000 0.080327 0.184150 -vn 3.003659 0.882748 3.308270 -v 0.000643 0.082838 0.184150 -vn 3.108254 0.378367 3.304332 -v 0.000525 0.083412 0.184150 -vn 3.128012 -0.134063 3.306786 -v 0.000503 0.083966 0.184150 -vn 3.059890 -0.658136 3.314448 -v 0.000578 0.084560 0.184150 -vn 2.899616 -1.177509 3.316516 -v 0.000757 0.085142 0.184150 -vn 2.657584 -1.654665 3.308948 -v 0.001037 0.085690 0.184150 -vn 2.355573 -2.063863 3.299441 -v 0.001368 0.086134 0.184150 -vn 1.995218 -2.413150 3.304609 -v 0.001762 0.086517 0.184150 -vn 1.578325 -2.704393 3.303760 -v 0.002246 0.086856 0.184150 -vn 0.213596 3.130823 3.235896 -v 0.003852 0.080330 0.184150 -vn 0.588919 3.077188 3.289245 -v 0.003345 0.080389 0.184150 -vn 1.038780 2.955508 3.291721 -v 0.002842 0.080524 0.184150 -vn 1.473105 2.764386 3.294711 -v 0.002356 0.080737 0.184150 -vn -0.039662 0.019847 6.384081 -v 0.001900 0.081027 0.184150 -vn 2.243532 2.185370 3.298105 -v 0.001496 0.081381 0.184150 -vn 2.560206 1.803130 3.302413 -v 0.001140 0.081809 0.184150 -vn 2.817715 1.365234 3.305601 -v 0.000851 0.082299 0.184150 -vn -1.979401 -2.429771 3.280867 -v 0.006186 0.086560 0.184150 -vn -2.316663 -2.107251 3.300502 -v 0.006588 0.086184 0.184150 -vn -2.622964 -1.710364 3.303216 -v 0.006930 0.085741 0.184150 -vn -2.865438 -1.261881 3.305982 -v 0.007202 0.085240 0.184150 -vn -3.034072 -0.771428 3.308895 -v 0.007391 0.084692 0.184150 -vn -3.120162 -0.252423 3.310799 -v 0.007489 0.084110 0.184150 -vn 1.132765 -2.920238 3.295928 -v 0.002735 0.087090 0.184150 -vn 0.671754 -3.059470 3.295053 -v 0.003250 0.087246 0.184150 -vn 0.187979 -3.126061 3.300283 -v 0.003779 0.087320 0.184150 -vn -0.304142 -3.117244 3.297543 -v 0.004355 0.087309 0.184150 -vn -0.773770 -3.035861 3.290249 -v 0.004862 0.087219 0.184150 -vn -1.219964 -2.885164 3.293890 -v 0.005359 0.087052 0.184150 -vn -1.625008 -2.679961 3.279374 -v 0.005840 0.086804 0.184150 -vn -0.951504 2.983434 2.979367 -v 0.002893 0.087147 0.184150 -vn -1.321639 2.846019 3.043264 -v 0.002466 0.086973 0.184150 -vn -1.587908 2.706644 3.046396 -v 0.002284 0.086877 0.184150 -vn -1.851619 2.532409 3.034980 -v 0.001900 0.086627 0.184150 -vn -3.090881 -0.526355 3.013340 -v 0.000578 0.083092 0.184150 -vn -3.008957 -0.884672 3.023232 -v 0.000608 0.082965 0.184150 -vn -2.333200 2.097309 3.032888 -v 0.001363 0.086128 0.184150 -vn -2.111919 2.319626 3.028943 -v 0.001678 0.086445 0.184150 -vn -2.106367 -2.325031 3.036509 -v 0.001682 0.081204 0.184150 -vn -2.335807 -2.094670 3.037970 -v 0.001363 0.081525 0.184150 -vn 2.822376 1.376589 3.081899 -v 0.007109 0.085434 0.184150 -vn 2.699448 1.598998 3.039316 -v 0.007088 0.085474 0.184150 -vn 1.429174 -2.793181 3.040474 -v 0.005534 0.080681 0.184150 -vn 1.164056 -2.914929 3.056645 -v 0.005334 0.080591 0.184150 -vn -1.727615 -2.619675 3.046448 -v 0.001974 0.080973 0.184150 -vn 1.706663 -2.632599 3.038307 -v 0.005957 0.080925 0.184150 -vn 1.937742 -2.469893 3.065036 -v 0.006147 0.081063 0.184150 -vn 2.146513 -2.288458 3.040483 -v 0.006375 0.081256 0.184150 -vn 2.374444 -2.049874 3.031773 -v 0.006656 0.081548 0.184150 -vn 2.578978 -1.786639 3.037949 -v 0.006877 0.081834 0.184150 -vn 2.717057 -1.574468 3.083718 -v 0.007067 0.082141 0.184150 -vn 2.509361 1.881531 3.025067 -v 0.006717 0.086033 0.184150 -vn 2.296121 2.138113 3.037503 -v 0.006637 0.086128 0.184150 -vn 2.061445 2.364859 3.034862 -v 0.006218 0.086534 0.184150 -vn 1.799451 2.569433 3.030942 -v 0.006100 0.086627 0.184150 -vn 1.398166 2.798213 2.956445 -v 0.005582 0.086949 0.184150 -vn 0.839224 3.011730 2.945327 -v 0.004939 0.087198 0.184150 -vn -2.826082 -1.337260 2.947561 -v 0.000832 0.082339 0.184150 -vn -2.565336 -1.800391 3.003913 -v 0.001201 0.081726 0.184150 -vn 2.834218 -1.344963 3.035225 -v 0.007088 0.082180 0.184150 -vn 2.967678 -1.012821 3.017658 -v 0.007354 0.082827 0.184150 -vn 3.064273 -0.670653 3.029273 -v 0.007392 0.082965 0.184150 -vn 3.121052 -0.286522 3.002569 -v 0.007491 0.083576 0.184150 -vn 3.136702 0.078007 3.039541 -v 0.007499 0.083911 0.184150 -vn 3.110008 0.407602 3.028278 -v 0.007473 0.084263 0.184150 -vn 3.039615 0.770134 3.018667 -v 0.007392 0.084688 0.184150 -vn 2.927841 1.124784 3.027260 -v 0.007262 0.085095 0.184150 -vn 0.229099 3.117231 2.942657 -v 0.004266 0.087317 0.184150 -vn -0.406033 3.099898 2.947477 -v 0.003528 0.087295 0.184150 -vn -2.569173 1.794563 3.002824 -v 0.001198 0.085924 0.184150 -vn -2.836070 1.311201 2.936774 -v 0.000825 0.085300 0.184150 -vn -3.123667 0.003411 2.930555 -v 0.000500 0.083827 0.184150 -vn -3.049287 0.677682 2.932912 -v 0.000584 0.084590 0.184150 -vn -1.463744 -2.775291 3.041264 -v 0.002466 0.080681 0.184150 -vn -1.199463 -2.900448 3.053715 -v 0.002583 0.080626 0.184150 -vn 0.897267 -3.007031 3.044935 -v 0.004980 0.080467 0.184150 -vn -0.932982 -2.995821 3.040972 -v 0.003020 0.080467 0.184150 -vn 0.540180 -3.086648 2.997006 -v 0.004707 0.080399 0.184150 -vn -0.568735 -3.081880 3.004929 -v 0.003234 0.080412 0.184150 -vn 6.221980 -0.781191 0.004798 -v 0.007473 0.083391 0.176409 -vn 6.079391 -1.539196 0.002856 -v 0.007392 0.082965 0.176345 -vn 6.079083 -1.540839 0.000000 -v 0.007392 0.082965 0.174393 -vn 4.281033 -4.587242 0.045154 -v 0.006375 0.081256 0.171491 -vn 3.458024 -5.205311 0.502048 -v 0.006100 0.081027 0.171167 -vn 3.182153 -5.145854 1.554575 -v 0.006161 0.081027 0.170938 -vn 2.050558 5.111330 3.005723 -v 0.006275 0.086627 0.170819 -vn 1.423009 5.121415 3.327531 -v 0.006326 0.086627 0.170790 -vn 1.404648 5.631565 2.364291 -v 0.006029 0.086973 0.170306 -vn -0.000352 5.611433 2.769706 -v 0.006983 0.086973 0.170184 -vn 0.000000 5.094141 3.649311 -v 0.007343 0.086627 0.170750 -vn 0.012019 5.067860 3.686975 -v 0.008767 0.086627 0.170750 -vn 0.053544 4.617401 4.243465 -v 0.008914 0.086397 0.171025 -vn 5.696838 2.636880 0.124227 -v 0.007180 0.085288 0.171939 -vn 5.499682 3.029830 0.038793 -v 0.007088 0.085474 0.171826 -vn 5.525371 2.971348 0.025884 -v 0.007088 0.085474 0.172078 -vn 3.048369 4.510803 2.965379 -v 0.006484 0.086301 0.171132 -vn 2.516630 4.518694 3.535512 -v 0.006466 0.086334 0.171103 -vn 3.562445 4.399593 2.593094 -v 0.006456 0.086334 0.171112 -vn 0.306298 4.555111 4.241963 -v 0.006514 0.086268 0.171158 -vn -0.186490 4.371837 4.508130 -v 0.006520 0.086268 0.171158 -vn 0.259055 4.250785 4.538530 -v 0.006498 0.086301 0.171126 -vn 1.910252 4.745624 3.399693 -v 0.006639 0.086128 0.171288 -vn 0.467259 4.407518 4.385529 -v 0.006643 0.086128 0.171287 -vn -0.174910 4.157453 4.703493 -v 0.006621 0.086164 0.171255 -vn 5.094066 3.607583 -0.330980 -v 0.006760 0.085979 0.171417 -vn 4.915877 3.912789 0.029175 -v 0.006760 0.085979 0.171425 -vn 5.088645 3.663715 -0.212097 -v 0.006790 0.085940 0.171461 -vn 0.828943 4.030629 4.693864 -v 0.006882 0.085820 0.171528 -vn 0.174932 3.759658 5.025049 -v 0.006887 0.085820 0.171527 -vn 0.068292 3.685798 5.087870 -v 0.006867 0.085860 0.171498 -vn 3.268481 4.002847 3.418838 -v 0.006963 0.085694 0.171612 -vn 4.255162 4.001341 2.158445 -v 0.006961 0.085694 0.171614 -vn 4.999532 3.639092 0.972433 -v 0.006974 0.085673 0.171631 -vn 0.186396 3.429885 5.209789 -v 0.006985 0.085673 0.171623 -vn -0.055965 3.306525 5.333305 -v 0.006976 0.085694 0.171610 -vn 1.431803 3.658186 4.715025 -v 0.006966 0.085694 0.171610 -vn 4.061160 3.471397 2.438234 -v 0.007100 0.085451 0.171754 -vn 3.559989 3.523803 3.264070 -v 0.007089 0.085474 0.171740 -vn 5.258632 3.049978 0.854534 -v 0.007088 0.085474 0.171743 -vn 1.642683 3.424415 4.871548 -v 0.007106 0.085451 0.171751 -vn 2.920184 3.547956 3.976132 -v 0.007115 0.085428 0.171764 -vn 0.555513 2.990796 5.391884 -v 0.007122 0.085428 0.171761 -vn 0.647519 2.789601 5.557422 -v 0.007198 0.085264 0.171841 -vn 0.060316 2.675378 5.684504 -v 0.007191 0.085288 0.171830 -vn 2.755068 2.802386 3.674675 -v 0.007181 0.085288 0.171831 -vn 5.839287 2.225389 -0.331137 -v 0.007233 0.085168 0.171895 -vn 5.773448 2.472572 -0.091438 -v 0.007223 0.085192 0.171882 -vn 5.768045 2.491046 0.019154 -v 0.007223 0.085192 0.171898 -vn 0.002494 2.476247 5.774264 -v 0.007271 0.085192 0.171873 -vn 0.043460 2.464252 5.778664 -v 0.007313 0.085192 0.171873 -vn 0.002619 2.666283 5.687726 -v 0.007284 0.085288 0.171830 -vn -0.040695 2.387280 5.811406 -v 0.007258 0.085168 0.171883 -vn -0.081678 2.341500 5.829438 -v 0.007265 0.085144 0.171893 -vn 0.016640 2.365885 5.820428 -v 0.007285 0.085144 0.171893 -vn 5.825457 1.986195 0.779462 -v 0.007348 0.084843 0.172007 -vn 6.005279 1.796244 -0.241465 -v 0.007333 0.084894 0.171996 -vn 5.956932 1.921552 0.305292 -v 0.007333 0.084894 0.172003 -vn 0.638680 2.363629 5.777688 -v 0.007291 0.085045 0.171931 -vn -0.002131 2.286148 5.852477 -v 0.007278 0.085095 0.171912 -vn 0.269100 2.433444 5.778840 -v 0.007268 0.085095 0.171912 -vn 4.606576 2.878956 3.144101 -v 0.007308 0.084970 0.171964 -vn 3.526970 2.894552 4.301157 -v 0.007300 0.084995 0.171954 -vn 4.871333 2.476818 1.854459 -v 0.007297 0.084995 0.171956 -vn 1.070565 1.890109 5.801921 -v 0.007372 0.084792 0.172013 -vn -0.238343 1.660954 6.048117 -v 0.007378 0.084792 0.172013 -vn -0.059418 1.791820 6.021713 -v 0.007368 0.084843 0.171999 -vn 6.217980 0.703583 -0.129354 -v 0.007473 0.084263 0.172138 -vn 6.235205 0.728719 0.186245 -v 0.007473 0.084263 0.172145 -vn 5.182886 0.459717 1.418083 -v 0.007493 0.084045 0.172156 -vn 6.119613 0.320637 -1.355470 -v 0.007492 0.084045 0.172151 -vn 6.197935 0.248383 0.989544 -v 0.007498 0.083936 0.172154 -vn 5.182886 -0.459717 1.418083 -v 0.007493 0.083608 0.172156 -vn 6.280019 0.000000 -0.001145 -v 0.007500 0.083827 0.172164 -vn 6.275090 0.000401 0.073745 -v 0.007500 0.083827 0.172179 -vn 4.997895 -0.989568 2.708244 -v 0.007465 0.083337 0.172117 -vn 4.206561 -0.809724 2.644540 -v 0.007472 0.083391 0.172124 -vn 6.224728 -0.637356 -0.563191 -v 0.007472 0.083391 0.172130 -vn 1.957850 -1.849901 5.486297 -v 0.007407 0.083018 0.172056 -vn 4.237349 -1.833257 3.891953 -v 0.007418 0.083070 0.172069 -vn 5.746119 -1.626784 1.385959 -v 0.007416 0.083070 0.172072 -vn 5.888729 -1.432881 1.247692 -v 0.007428 0.083123 0.172083 -vn 2.041323 -1.702084 5.564574 -v 0.007420 0.083070 0.172068 -vn 0.580016 -2.422149 5.745786 -v 0.007291 0.082608 0.171931 -vn 0.016682 -2.339935 5.830956 -v 0.007278 0.082559 0.171912 -vn 0.019975 -2.283391 5.853126 -v 0.007299 0.082559 0.171912 -vn 1.039829 -1.878426 5.819592 -v 0.007372 0.082862 0.172013 -vn 3.003233 -2.159937 4.960460 -v 0.007369 0.082862 0.172015 -vn 1.004377 -2.007583 5.854564 -v 0.007358 0.082810 0.171999 -vn 2.282424 -1.918402 5.148542 -v 0.007382 0.082913 0.172028 -vn 0.012401 -1.646829 6.048838 -v 0.007387 0.082913 0.172028 -vn 0.465667 -1.732205 5.947628 -v 0.007397 0.082965 0.172042 -vn 5.732201 -2.375678 0.350003 -v 0.007252 0.082534 0.171911 -vn 5.867712 -2.208837 -0.209404 -v 0.007253 0.082534 0.171919 -vn 5.844505 -2.216067 -0.356554 -v 0.007243 0.082510 0.171907 -vn 5.676585 -2.690314 0.069931 -v 0.007180 0.082365 0.171842 -vn 5.718803 -2.536600 -0.182427 -v 0.007180 0.082365 0.171838 -vn 5.797424 -2.273024 -0.582148 -v 0.007202 0.082413 0.171864 -vn 0.010057 -2.785713 5.630838 -v 0.007170 0.082272 0.171786 -vn 0.037984 -3.056161 5.486708 -v 0.007138 0.082180 0.171738 -vn 0.010137 -3.039955 5.492348 -v 0.007304 0.082180 0.171738 -vn 0.104583 -2.583987 5.725658 -v 0.007216 0.082413 0.171852 -vn 0.005138 -2.644668 5.699047 -v 0.007201 0.082365 0.171830 -vn 0.013981 -2.655123 5.693174 -v 0.007284 0.082365 0.171830 -vn 4.906394 -3.773510 0.597447 -v 0.006919 0.081896 0.171579 -vn 5.280370 -3.403332 0.024493 -v 0.006933 0.081917 0.171596 -vn 5.236714 -3.459429 0.079216 -v 0.006933 0.081917 0.171604 -vn 3.579262 -4.138480 2.834902 -v 0.006934 0.081917 0.171585 -vn 4.864440 -3.679169 0.997113 -v 0.006933 0.081917 0.171588 -vn 3.569670 -4.061278 2.690397 -v 0.006921 0.081896 0.171573 -vn 1.124276 -3.743440 4.645127 -v 0.006926 0.081896 0.171569 -vn 0.594533 -3.765292 4.914425 -v 0.006916 0.081875 0.171555 -vn -0.065493 -3.485609 5.225641 -v 0.006928 0.081875 0.171555 -vn 5.595941 -2.808032 -0.366978 -v 0.007088 0.082180 0.171752 -vn 5.517305 -2.997224 0.024565 -v 0.007088 0.082180 0.171756 -vn 5.589713 -2.835479 -0.423583 -v 0.007063 0.082135 0.171725 -vn 0.204254 -3.464513 5.231892 -v 0.006989 0.081917 0.171583 -vn 0.017024 -3.610453 5.140913 -v 0.006950 0.081834 0.171527 -vn 0.040655 -3.638399 5.117942 -v 0.006992 0.081834 0.171527 -vn 3.912470 -4.368375 2.054897 -v 0.006747 0.081656 0.171399 -vn 5.202838 -3.465427 -0.371418 -v 0.006760 0.081675 0.171417 -vn 4.933029 -3.889399 0.065591 -v 0.006760 0.081675 0.171425 -vn 1.752300 -3.936339 4.006004 -v 0.006867 0.081814 0.171513 -vn 0.951341 -3.999421 4.637848 -v 0.006856 0.081793 0.171499 -vn 0.084058 -3.690623 5.084189 -v 0.006867 0.081793 0.171498 -vn 3.929243 -3.816122 1.385003 -v 0.006760 0.081675 0.171412 -vn 2.963811 -4.418013 2.272361 -v 0.006714 0.081618 0.171368 -vn 2.156729 -4.452428 3.185678 -v 0.006700 0.081599 0.171350 -vn 0.261099 -4.245843 4.608421 -v 0.006709 0.081599 0.171349 -vn 1.059157 -4.442502 4.261774 -v 0.006721 0.081618 0.171365 -vn 0.031878 -4.046468 4.805964 -v 0.006720 0.081599 0.171349 -vn 4.686384 -4.172231 -0.112672 -v 0.006573 0.081454 0.171237 -vn 4.271232 -4.342096 0.694146 -v 0.006573 0.081454 0.171228 -vn 4.687793 -4.182917 -0.053357 -v 0.006604 0.081490 0.171267 -vn 2.640701 -4.785432 2.532599 -v 0.006558 0.081437 0.171210 -vn 0.492470 -4.469341 4.323676 -v 0.006599 0.081472 0.171239 -vn 0.115090 -4.361956 4.515073 -v 0.006588 0.081454 0.171223 -vn 0.028588 -4.309746 4.568117 -v 0.006610 0.081454 0.171223 -vn 0.012679 -5.089610 3.656577 -v 0.006987 0.081027 0.170750 -vn 0.050236 -5.058254 3.709821 -v 0.006631 0.081027 0.170750 -vn 0.502046 -5.660995 2.658946 -v 0.006276 0.080681 0.170210 -vn 0.967398 -5.662708 2.512293 -v 0.006144 0.080681 0.170252 -vn -2.639668 -5.643010 -0.546195 -v 0.002567 0.080681 0.170253 -vn -2.548590 -5.609366 -1.041694 -v 0.002749 0.080681 0.169667 -vn -1.716835 -5.991753 -0.526949 -v 0.003175 0.080467 0.170122 -vn -3.860020 -3.551993 -3.405056 -v 0.002470 0.081834 0.167590 -vn -4.114454 -2.934026 -3.680608 -v 0.002337 0.082180 0.167422 -vn -3.673959 -2.933748 -4.120993 -v 0.002780 0.082180 0.166980 -vn -4.181969 4.586415 -0.809201 -v 0.001715 0.086397 0.170213 -vn -3.726448 4.998694 -0.575313 -v 0.001956 0.086627 0.170435 -vn -3.546827 5.031294 -1.127881 -v 0.002104 0.086627 0.169794 -vn -0.015502 6.268634 -0.017856 -v 0.005216 0.087327 0.169005 -vn -0.004128 6.269032 -0.017148 -v 0.005464 0.087327 0.168875 -vn -0.379199 6.200803 -0.797315 -v 0.005220 0.087296 0.168476 -vn -0.009882 6.268803 -0.018752 -v 0.005740 0.087327 0.168768 -vn -0.003932 6.269048 -0.024061 -v 0.006051 0.087327 0.168691 -vn -0.201328 6.200181 -0.861916 -v 0.005804 0.087296 0.168268 -vn -2.768688 -5.612189 -0.002359 -v 0.002466 0.080681 0.178264 -vn -5.537698 -2.945427 -0.002293 -v 0.000912 0.082180 0.172745 -vn -5.503037 -2.971167 -0.222991 -v 0.000913 0.082180 0.171116 -vn -5.132142 -3.589859 -0.143033 -v 0.001122 0.081834 0.171287 -vn -2.767203 5.613091 -0.004235 -v 0.002466 0.086973 0.178264 -vn -5.160676 3.566369 0.000357 -v 0.001123 0.085820 0.174503 -vn -4.616663 4.232027 0.001837 -v 0.001363 0.086128 0.174649 -vn -4.725993 4.123156 -0.042360 -v 0.001362 0.086128 0.171481 -vn -0.859134 6.208214 0.000015 -v 0.003535 0.087296 0.173243 -vn -1.782379 6.004064 0.000089 -v 0.003020 0.087187 0.172826 -vn -1.781271 6.004286 0.002510 -v 0.003020 0.087187 0.178488 -vn 5.533961 2.951814 0.005399 -v 0.007088 0.085474 0.176102 -vn -3.229438 -2.401361 -2.021619 -v 0.009500 0.081094 0.166463 -vn -3.217360 -2.551943 -1.828396 -v 0.009500 0.081028 0.166549 -vn -0.021935 -4.991912 -3.767667 -v 0.008331 0.081027 0.166550 -vn -3.231333 -2.908553 1.179716 -v 0.009500 0.080607 0.170021 -vn -3.202008 -2.816082 1.389345 -v 0.009500 0.080681 0.170184 -vn -0.033220 -5.608333 2.781090 -v 0.008463 0.080681 0.170184 -vn -4.002995 -0.472099 2.983764 -v 0.009500 0.083366 0.172120 -vn 1.349228 -0.602900 5.880611 -v 0.009497 0.083391 0.172123 -vn 0.001145 -1.514460 6.086111 -v 0.009455 0.082965 0.172042 -vn -3.264136 -0.802538 3.031852 -v 0.009500 0.082953 0.172039 -vn 0.108021 -2.354754 5.804952 -v 0.009386 0.082559 0.171912 -vn -3.315416 -1.044669 2.954408 -v 0.009500 0.082633 0.171940 -vn 0.046871 -2.980265 5.515500 -v 0.009294 0.082180 0.171738 -vn -3.299708 -1.395325 2.806052 -v 0.009500 0.082244 0.171772 -vn 0.038726 -4.141768 4.709194 -v 0.009054 0.081525 0.171287 -vn -3.277264 -1.991046 2.422426 -v 0.009500 0.081611 0.171359 -vn -3.276064 -1.725971 2.617849 -v 0.009500 0.081881 0.171559 -vn 0.009259 -4.598963 4.267858 -v 0.008914 0.081256 0.171025 -vn -3.244091 -2.501043 1.893986 -v 0.009500 0.081027 0.170750 -vn -3.266911 -2.254739 2.179167 -v 0.009500 0.081300 0.171072 -vn -0.067169 -5.452836 3.119125 -v 0.009500 0.080795 0.170400 -vn -3.228651 -2.656058 1.674153 -v 0.009500 0.080839 0.170473 -vn -0.007349 -6.208770 0.856523 -v 0.007885 0.080358 0.169115 -vn -3.201994 -3.108723 0.443224 -v 0.009500 0.080358 0.169115 -vn -3.218775 -3.070963 0.651893 -v 0.009500 0.080404 0.169381 -vn -0.016072 -6.002467 -1.783989 -v 0.007100 0.080467 0.167670 -vn -3.270602 -3.112198 -0.381567 -v 0.009500 0.080352 0.168227 -vn 0.001655 -6.207338 -0.863251 -v 0.007381 0.080358 0.168185 -vn -3.256999 -3.136744 -0.019670 -v 0.009500 0.080327 0.168650 -vn -3.279235 -2.821232 -1.369417 -v 0.009500 0.080688 0.167102 -vn -3.258665 -2.950445 -1.064715 -v 0.009500 0.080524 0.167491 -vn -3.255724 -3.051916 -0.724713 -v 0.009500 0.080428 0.167814 -vn -0.026388 -5.679023 -2.643325 -v 0.006798 0.080681 0.167116 -vn -0.156390 -5.430735 -3.148377 -v 0.009500 0.080796 0.166900 -vn 0.006652 3.555412 -5.167792 -v 0.007984 0.085820 0.165773 -vn -3.265076 1.390394 -2.811277 -v 0.009500 0.085360 0.165504 -vn 0.013072 2.944577 -5.538003 -v 0.007890 0.085474 0.165562 -vn -3.259854 1.081679 -2.944181 -v 0.009500 0.085050 0.165371 -vn 0.008241 2.266008 -5.848302 -v 0.007812 0.085095 0.165389 -vn -3.268403 0.735345 -3.048138 -v 0.009500 0.084648 0.165248 -vn 0.007337 1.540671 -6.079137 -v 0.007754 0.084688 0.165258 -vn -3.253746 0.382938 -3.113394 -v 0.009500 0.084231 0.165174 -vn 0.002130 0.783110 -6.222324 -v 0.007718 0.084263 0.165178 -vn -3.249771 0.047074 -3.136646 -v 0.009500 0.083897 0.165151 -vn -0.002593 0.000451 -6.271266 -v 0.007706 0.083827 0.165151 -vn -3.257054 -0.313416 -3.120435 -v 0.009500 0.083478 0.165168 -vn -0.002945 -0.780160 -6.222941 -v 0.007718 0.083391 0.165178 -vn -3.246303 -0.669356 -3.064861 -v 0.009500 0.083059 0.165235 -vn -0.004741 -1.540989 -6.079600 -v 0.007754 0.082965 0.165258 -vn -3.243818 -0.995954 -2.974955 -v 0.009500 0.082733 0.165325 -vn -0.006256 -2.268879 -5.847820 -v 0.007812 0.082559 0.165389 -vn -3.253010 -1.329699 -2.840466 -v 0.009500 0.082343 0.165480 -vn -0.007670 -2.946266 -5.537919 -v 0.007890 0.082180 0.165562 -vn -3.242226 -1.647270 -2.670026 -v 0.009500 0.081971 0.165682 -vn -0.010080 -3.566062 -5.161314 -v 0.007984 0.081834 0.165773 -vn -3.240232 -1.923709 -2.478413 -v 0.009500 0.081696 0.165874 -vn -0.018216 -4.230830 -4.618628 -v 0.008091 0.081525 0.166013 -vn -3.270403 -2.202487 -2.231881 -v 0.009500 0.081378 0.166149 -vn -0.024755 5.001219 -3.753490 -v 0.008331 0.086627 0.166550 -vn -3.258462 2.248307 -2.187409 -v 0.009500 0.086316 0.166190 -vn -0.017780 4.228642 -4.620636 -v 0.008091 0.086128 0.166013 -vn -3.243143 1.994434 -2.421680 -v 0.009500 0.086067 0.165961 -vn -3.266726 1.695707 -2.637664 -v 0.009500 0.085728 0.165712 -vn -3.285143 2.834619 -1.339785 -v 0.009500 0.086989 0.167151 -vn -0.139785 5.471780 -3.080237 -v 0.009500 0.086858 0.166900 -vn -3.241538 2.662624 -1.662408 -v 0.009500 0.086832 0.166856 -vn -3.263582 2.476388 -1.923781 -v 0.009500 0.086595 0.166508 -vn -0.012688 6.003900 -1.783321 -v 0.007100 0.087187 0.167670 -vn -0.010893 6.210021 -0.851144 -v 0.007381 0.087296 0.168185 -vn -3.245510 3.070117 -0.645152 -v 0.009500 0.087256 0.167950 -vn -3.246038 3.121819 -0.309693 -v 0.009500 0.087307 0.168283 -vn -0.006160 6.269656 0.004455 -v 0.007633 0.087327 0.168650 -vn -3.259898 3.135580 0.050350 -v 0.009500 0.087326 0.168706 -vn -3.260449 3.051342 0.726386 -v 0.009500 0.087233 0.169455 -vn -0.010942 6.005275 1.779703 -v 0.008164 0.087187 0.169630 -vn -3.250874 2.947249 1.074425 -v 0.009500 0.087111 0.169861 -vn -0.033035 5.607919 2.782109 -v 0.008463 0.086973 0.170184 -vn -3.263308 2.607463 1.744419 -v 0.009500 0.086774 0.170537 -vn -0.075786 5.436193 3.147706 -v 0.009500 0.086858 0.170400 -vn -3.180493 2.783464 1.455549 -v 0.009500 0.086942 0.170246 -vn -3.201752 2.849745 1.318950 -v 0.009500 0.086973 0.170184 -vn -3.372448 0.987401 2.971329 -v 0.009500 0.084949 0.171965 -vn -3.452990 1.214659 2.878341 -v 0.009500 0.085262 0.171842 -vn 0.021482 2.960964 5.527287 -v 0.009294 0.085474 0.171738 -vn -0.002017 -0.780919 6.222333 -v 0.008208 0.083391 0.172123 -vn -3.204505 -0.115188 3.137957 -v 0.009500 0.083789 0.172150 -vn -0.008866 -0.002938 6.271346 -v 0.008225 0.083827 0.172150 -vn -0.048071 0.058252 6.281737 -v 0.009500 0.083827 0.172150 -vn -3.215819 0.257585 3.128462 -v 0.009500 0.084124 0.172137 -vn 4.264055 -4.603011 0.000205 -v 0.006375 0.081256 0.175531 -vn 4.731154 -4.120196 0.000412 -v 0.006637 0.081525 0.175741 -vn 5.160352 -3.566743 -0.000317 -v 0.006877 0.081834 0.175933 -vn 5.538095 -2.944582 0.003655 -v 0.007088 0.082180 0.176102 -vn 3.652267 -5.092339 -0.002948 -v 0.006100 0.081027 0.175310 -vn 2.773104 -5.610179 -0.003969 -v 0.005534 0.080681 0.174855 -vn 0.859699 6.208094 0.001780 -v 0.004465 0.087296 0.173994 -vn 1.777096 6.005141 0.004679 -v 0.004980 0.087187 0.174409 -vn 2.769292 5.611602 0.000402 -v 0.005534 0.086973 0.174855 -vn 3.650433 5.093462 -0.001058 -v 0.006100 0.086627 0.175310 -vn 4.264562 4.602486 0.002143 -v 0.006375 0.086397 0.175531 -vn 5.844824 -2.273402 0.006933 -v 0.007262 0.082559 0.176241 -vn -3.775945 4.982757 -0.000055 -v 0.001900 0.086627 0.174976 -vn -3.670272 5.076594 0.023775 -v 0.001900 0.086627 0.171918 -vn -4.258603 4.607407 0.004857 -v 0.001624 0.086397 0.171694 -vn -5.537043 2.946637 0.000085 -v 0.000912 0.085474 0.174374 -vn -5.535626 2.949205 0.001935 -v 0.000912 0.085474 0.177633 -vn -5.162660 3.563151 0.003507 -v 0.001123 0.085820 0.177718 -vn -4.615945 4.232915 -0.001335 -v 0.001363 0.086128 0.177816 -vn -3.776960 4.982146 -0.002991 -v 0.001900 0.086627 0.178034 -vn -0.031166 6.271168 -0.002158 -v 0.004000 0.087327 0.178884 -vn -0.862874 6.207409 0.004111 -v 0.003535 0.087296 0.178696 -vn -0.000001 6.269270 0.000000 -v 0.004000 0.087327 0.173619 -vn -5.848135 2.266004 0.000868 -v 0.000738 0.085095 0.177562 -vn -5.810328 -2.288338 -0.300339 -v 0.000742 0.082559 0.170977 -vn -5.846366 -2.269559 -0.008875 -v 0.000738 0.082559 0.172621 -vn -6.040402 -1.551827 -0.363698 -v 0.000615 0.082965 0.170874 -vn -6.078008 -1.541714 -0.014865 -v 0.000607 0.082965 0.172528 -vn -6.183201 -0.783015 -0.402636 -v 0.000537 0.083391 0.170811 -vn -6.221570 -0.779768 -0.019358 -v 0.000527 0.083391 0.172471 -vn -6.231942 -0.003545 -0.412800 -v 0.000511 0.083827 0.170790 -vn -6.269956 -0.000742 -0.019991 -v 0.000500 0.083827 0.172452 -vn -6.186786 0.775022 -0.392098 -v 0.000537 0.084263 0.170811 -vn -6.221905 0.778520 -0.016218 -v 0.000527 0.084263 0.172471 -vn -6.048119 1.541120 -0.341338 -v 0.000615 0.084688 0.170874 -vn -6.078540 1.540634 -0.010152 -v 0.000607 0.084688 0.172528 -vn -5.822349 2.274207 -0.267010 -v 0.000742 0.085095 0.170977 -vn -5.846938 2.268679 -0.004318 -v 0.000738 0.085095 0.172621 -vn -5.518748 2.954329 -0.181645 -v 0.000913 0.085474 0.171116 -vn -5.537371 2.946153 -0.000620 -v 0.000912 0.085474 0.172745 -vn -5.149365 3.572548 -0.101502 -v 0.001122 0.085820 0.171287 -vn -5.847398 -2.268061 0.000352 -v 0.000738 0.082559 0.174268 -vn -6.079074 -1.540573 0.000453 -v 0.000608 0.082965 0.174189 -vn -6.222558 -0.779256 0.000417 -v 0.000527 0.083391 0.174140 -vn -6.270864 -0.000020 0.000408 -v 0.000500 0.083827 0.174123 -vn -6.222560 0.779258 0.000458 -v 0.000527 0.084263 0.174140 -vn -6.079054 1.540643 0.000404 -v 0.000608 0.084688 0.174189 -vn -5.847360 2.268132 0.000207 -v 0.000738 0.085095 0.174268 -vn -5.537019 -2.946682 0.000147 -v 0.000912 0.082180 0.174374 -vn -5.160564 -3.566517 0.000194 -v 0.001123 0.081834 0.174503 -vn -4.625125 -4.224094 0.011695 -v 0.001363 0.081525 0.174649 -vn -5.848977 -2.263350 0.004710 -v 0.000738 0.082559 0.177562 -vn -6.078189 -1.543277 0.004663 -v 0.000608 0.082965 0.177509 -vn -6.222830 -0.774371 0.007795 -v 0.000527 0.083391 0.177476 -vn -6.270545 -0.004557 0.006866 -v 0.000500 0.083827 0.177465 -vn -6.222655 0.778696 -0.000673 -v 0.000527 0.084263 0.177476 -vn -6.078612 1.542299 0.000524 -v 0.000608 0.084688 0.177509 -vn -3.773725 -4.984798 0.006466 -v 0.001900 0.081027 0.174976 -vn -2.771023 -5.610796 0.000040 -v 0.002466 0.080681 0.172377 -vn -5.535984 -2.948613 0.000689 -v 0.000912 0.082180 0.177633 -vn -5.161656 -3.564696 0.002822 -v 0.001123 0.081834 0.177718 -vn -4.617937 -4.230823 -0.003546 -v 0.001363 0.081525 0.177816 -vn -3.773135 -4.985527 -0.006812 -v 0.001900 0.081027 0.178034 -vn -1.783306 -6.003855 -0.002009 -v 0.003020 0.080467 0.178488 -vn -1.782451 -6.004055 0.000205 -v 0.003020 0.080467 0.172826 -vn -0.856111 -6.208848 -0.002770 -v 0.003535 0.080358 0.178696 -vn -0.859136 -6.208215 0.000047 -v 0.003535 0.080358 0.173243 -vn 0.064566 -6.264291 0.005716 -v 0.004000 0.080327 0.178884 -vn 0.000001 -6.269271 0.000002 -v 0.004000 0.080327 0.173619 -vn 0.859124 -6.208212 0.000183 -v 0.004465 0.080358 0.173994 -vn -0.111516 5.045160 -3.687419 -v 0.006488 0.086627 0.166550 -vn -0.375636 5.586766 -2.755669 -v 0.005950 0.086973 0.167154 -vn -0.044700 5.609212 -2.769419 -v 0.006798 0.086973 0.167116 -vn -0.157434 5.990146 -1.790000 -v 0.006246 0.087187 0.167679 -vn -0.038652 6.205215 -0.865919 -v 0.006541 0.087296 0.168185 -vn 0.003287 6.269667 -0.009025 -v 0.006817 0.087327 0.168650 -vn -0.003656 6.208002 0.862667 -v 0.007885 0.087296 0.169115 -vn -3.261253 3.108692 0.416536 -v 0.009500 0.087294 0.169125 -vn -0.491857 5.988824 -1.730682 -v 0.005536 0.087187 0.167806 -vn -0.799973 5.989413 -1.611515 -v 0.004950 0.087187 0.168034 -vn -0.853493 5.589169 -2.645175 -v 0.005252 0.086973 0.167314 -vn -1.267548 5.589682 -2.474082 -v 0.004659 0.086973 0.167561 -vn -1.201059 5.062944 -3.457891 -v 0.004963 0.086627 0.166814 -vn -1.775435 4.975276 -3.311059 -v 0.004360 0.086627 0.167078 -vn -3.265775 2.972637 -0.998180 -v 0.009500 0.087147 0.167544 -vn -1.060188 5.988899 -1.454886 -v 0.004453 0.087187 0.168336 -vn -0.649508 6.199580 -0.602687 -v 0.004337 0.087296 0.169122 -vn -0.525721 6.200608 -0.708947 -v 0.004738 0.087296 0.168766 -vn -0.024439 6.268897 -0.016939 -v 0.004615 0.087327 0.169507 -vn -0.013726 6.268935 -0.019521 -v 0.004994 0.087327 0.169155 -vn 0.527292 6.214483 0.646646 -v 0.005250 0.087296 0.169544 -vn -1.820732 5.963603 -0.214073 -v 0.003046 0.087187 0.170724 -vn -2.522142 5.611972 -1.046404 -v 0.002749 0.086973 0.169667 -vn -2.530262 5.689617 -0.571469 -v 0.002567 0.086973 0.170253 -vn -3.143678 5.337509 -0.915450 -v 0.002333 0.086818 0.170021 -vn -3.242010 5.347952 -0.313960 -v 0.002209 0.086818 0.170669 -vn -3.139678 4.981927 -2.038271 -v 0.002614 0.086627 0.168688 -vn -3.285038 5.088991 -1.537873 -v 0.002327 0.086627 0.169214 -vn -2.640435 5.658976 -0.164424 -v 0.002474 0.086973 0.170912 -vn -2.770291 5.610855 -0.010205 -v 0.002466 0.086973 0.171641 -vn -1.775037 6.002259 -0.049590 -v 0.003020 0.087187 0.171410 -vn -0.860474 6.207935 -0.003105 -v 0.003535 0.087296 0.171880 -vn 0.000037 6.269272 0.000019 -v 0.004000 0.087327 0.172302 -vn -3.471692 4.224019 -3.011133 -v 0.002621 0.086128 0.167782 -vn -3.799135 4.221606 -2.592103 -v 0.002251 0.086128 0.168264 -vn -3.668552 5.073390 -0.084374 -v 0.001900 0.086627 0.171153 -vn -2.770700 5.610931 -0.000059 -v 0.002466 0.086973 0.172377 -vn -0.207149 4.622612 -4.208231 -v 0.006341 0.086397 0.166277 -vn -0.004190 4.222317 -4.625650 -v 0.007143 0.086128 0.166013 -vn -0.052398 3.575151 -5.151554 -v 0.007023 0.085820 0.165773 -vn -0.079808 2.957207 -5.526103 -v 0.006917 0.085474 0.165561 -vn -0.106753 2.277601 -5.836373 -v 0.006830 0.085095 0.165387 -vn -0.129389 1.547933 -6.068259 -v 0.006765 0.084688 0.165257 -vn -0.143619 0.783671 -6.212197 -v 0.006726 0.084263 0.165177 -vn -0.146678 0.001538 -6.260969 -v 0.006712 0.083827 0.165149 -vn -0.137397 -0.780563 -6.213277 -v 0.006726 0.083391 0.165177 -vn -0.117299 -1.544363 -6.070408 -v 0.006765 0.082965 0.165257 -vn -0.089861 -2.273412 -5.839540 -v 0.006830 0.082559 0.165387 -vn -0.060047 -2.952568 -5.530115 -v 0.006917 0.082180 0.165561 -vn -0.033641 -3.570889 -5.155742 -v 0.007023 0.081834 0.165773 -vn 0.003454 -4.225327 -4.623172 -v 0.007143 0.081525 0.166013 -vn -0.333779 -4.112158 -4.703107 -v 0.006204 0.081525 0.166022 -vn -0.435682 -3.552115 -5.125667 -v 0.006082 0.081834 0.165789 -vn -0.533739 -2.929032 -5.491906 -v 0.005976 0.082180 0.165586 -vn -0.619650 -2.251358 -5.790624 -v 0.005890 0.082559 0.165420 -vn -0.686655 -1.527138 -6.011758 -v 0.005826 0.082965 0.165296 -vn -0.729093 -0.770656 -6.147999 -v 0.005786 0.083391 0.165220 -vn -0.743510 0.002612 -6.192881 -v 0.005773 0.083827 0.165194 -vn -0.728815 0.775415 -6.145917 -v 0.005786 0.084263 0.165220 -vn -0.686623 1.530778 -6.007855 -v 0.005826 0.084688 0.165296 -vn -0.620823 2.253423 -5.785411 -v 0.005890 0.085095 0.165420 -vn -0.537621 2.929737 -5.485788 -v 0.005976 0.085474 0.165586 -vn -0.444784 3.552254 -5.118696 -v 0.006082 0.085820 0.165789 -vn -0.354537 4.111856 -4.695957 -v 0.006204 0.086128 0.166022 -vn -1.004260 -4.099688 -4.613339 -v 0.005391 0.081525 0.166134 -vn -1.160864 -3.547557 -5.013317 -v 0.005272 0.081834 0.165915 -vn -1.301175 -2.929261 -5.362659 -v 0.005167 0.082180 0.165723 -vn -1.418645 -2.253336 -5.649418 -v 0.005082 0.082559 0.165565 -vn -1.507106 -1.529413 -5.862493 -v 0.005018 0.082965 0.165447 -vn -1.561771 -0.772365 -5.994141 -v 0.004979 0.083391 0.165374 -vn -1.579464 0.002033 -6.037914 -v 0.004965 0.083827 0.165350 -vn -1.559308 0.776087 -5.993145 -v 0.004979 0.084263 0.165374 -vn -1.502234 1.532161 -5.860702 -v 0.005018 0.084688 0.165447 -vn -1.411517 2.254562 -5.647233 -v 0.005082 0.085095 0.165565 -vn -1.291941 2.928596 -5.360605 -v 0.005167 0.085474 0.165723 -vn -1.149395 3.544906 -5.011983 -v 0.005272 0.085820 0.165915 -vn -0.990551 4.094855 -4.613478 -v 0.005391 0.086128 0.166134 -vn -0.823309 4.575939 -4.177101 -v 0.005521 0.086397 0.166374 -vn -0.635423 5.046192 -3.620234 -v 0.005660 0.086627 0.166627 -vn -0.696810 -5.017531 -3.668342 -v 0.005660 0.081027 0.166627 -vn -0.838341 -4.582932 -4.174778 -v 0.005521 0.081256 0.166374 -vn -0.174407 -4.614552 -4.223569 -v 0.006341 0.081256 0.166277 -vn -1.679926 -4.134084 -4.376003 -v 0.004691 0.081525 0.166342 -vn -1.840376 -3.549961 -4.806793 -v 0.004569 0.081834 0.166131 -vn -2.004779 -2.931382 -5.142860 -v 0.004462 0.082180 0.165946 -vn -2.141343 -2.255258 -5.419023 -v 0.004374 0.082559 0.165794 -vn -2.243565 -1.531149 -5.624447 -v 0.004309 0.082965 0.165680 -vn -2.306836 -0.773716 -5.751609 -v 0.004268 0.083391 0.165610 -vn -2.327519 0.001167 -5.794151 -v 0.004254 0.083827 0.165586 -vn -2.304960 0.775920 -5.751399 -v 0.004268 0.084263 0.165610 -vn -2.239875 1.532728 -5.624160 -v 0.004309 0.084688 0.165680 -vn -2.135942 2.256084 -5.418838 -v 0.004374 0.085095 0.165794 -vn -1.997917 2.931113 -5.143079 -v 0.004462 0.085474 0.165946 -vn -1.832300 3.548625 -4.807652 -v 0.004569 0.085820 0.166131 -vn -1.646164 4.100001 -4.424189 -v 0.004691 0.086128 0.166342 -vn -1.469533 4.579464 -3.997532 -v 0.004824 0.086397 0.166572 -vn -2.171536 -4.210052 -4.063569 -v 0.004076 0.081525 0.166621 -vn -2.438758 -3.551110 -4.533489 -v 0.003949 0.081834 0.166416 -vn -2.626929 -2.932546 -4.855752 -v 0.003837 0.082180 0.166237 -vn -2.782339 -2.256479 -5.120943 -v 0.003745 0.082559 0.166089 -vn -2.898392 -1.532171 -5.318455 -v 0.003676 0.082965 0.165979 -vn -2.970169 -0.774645 -5.440924 -v 0.003634 0.083391 0.165910 -vn -2.993743 0.000464 -5.482130 -v 0.003619 0.083827 0.165887 -vn -2.968689 0.775552 -5.441329 -v 0.003634 0.084263 0.165910 -vn -2.895567 1.532843 -5.319247 -v 0.003676 0.084688 0.165979 -vn -2.778275 2.256796 -5.122197 -v 0.003745 0.085095 0.166089 -vn -2.621725 2.932467 -4.857560 -v 0.003837 0.085474 0.166237 -vn -2.432664 3.550612 -4.535858 -v 0.003949 0.085820 0.166416 -vn -2.196566 4.192192 -4.071636 -v 0.004076 0.086128 0.166621 -vn -1.764808 -4.966377 -3.323941 -v 0.004360 0.081027 0.167078 -vn -1.564451 -4.553638 -3.983443 -v 0.004824 0.081256 0.166572 -vn -1.214170 -5.074972 -3.436410 -v 0.004963 0.081027 0.166814 -vn -0.109997 -4.983169 -3.790768 -v 0.006488 0.081027 0.166550 -vn -0.067179 -5.372180 -3.235037 -v 0.006642 0.080836 0.166832 -vn -0.577368 -5.327619 -3.230903 -v 0.005804 0.080836 0.166889 -vn -0.352951 -5.674146 -2.603914 -v 0.005950 0.080681 0.167154 -vn -0.867662 -5.596641 -2.620451 -v 0.005252 0.080681 0.167314 -vn -0.165444 -5.983027 -1.794269 -v 0.006246 0.080467 0.167679 -vn -1.257471 -5.586564 -2.481149 -v 0.004659 0.080681 0.167561 -vn -0.477652 -5.980649 -1.746280 -v 0.005536 0.080467 0.167806 -vn -0.791709 -5.986797 -1.619566 -v 0.004950 0.080467 0.168034 -vn -0.189967 -6.194809 -0.886447 -v 0.005804 0.080358 0.168268 -vn -0.377257 -6.199101 -0.807701 -v 0.005220 0.080358 0.168476 -vn 0.004721 -6.268765 -0.036195 -v 0.006051 0.080327 0.168691 -vn -0.008633 -6.269301 -0.020279 -v 0.005740 0.080327 0.168768 -vn -2.659250 -4.209513 -3.764428 -v 0.003532 0.081525 0.166958 -vn -2.968657 -3.551795 -4.205949 -v 0.003397 0.081834 0.166759 -vn -3.179717 -2.933398 -4.513617 -v 0.003279 0.082180 0.166584 -vn -3.353482 -2.257253 -4.767269 -v 0.003182 0.082559 0.166439 -vn -3.482877 -1.532966 -4.956520 -v 0.003109 0.082965 0.166332 -vn -3.562784 -0.775550 -5.074020 -v 0.003064 0.083391 0.166265 -vn -3.589280 -0.000134 -5.113712 -v 0.003049 0.083827 0.166242 -vn -3.561822 0.775284 -5.074818 -v 0.003064 0.084263 0.166265 -vn -3.480884 1.532803 -4.958132 -v 0.003109 0.084688 0.166332 -vn -3.350574 2.257128 -4.769612 -v 0.003182 0.085095 0.166439 -vn -3.176015 2.933382 -4.516572 -v 0.003279 0.085474 0.166584 -vn -2.964193 3.551878 -4.209441 -v 0.003397 0.085820 0.166759 -vn -3.865326 -2.257800 -4.362393 -v 0.002677 0.082559 0.166839 -vn -4.322902 -2.258327 -3.908894 -v 0.002227 0.082559 0.167284 -vn -4.007541 -1.533660 -4.542870 -v 0.002600 0.082965 0.166733 -vn -4.477715 -1.534279 -4.079969 -v 0.002145 0.082965 0.167181 -vn -4.095487 -0.776168 -4.655064 -v 0.002552 0.083391 0.166668 -vn -4.573455 -0.776813 -4.186511 -v 0.002095 0.083391 0.167117 -vn -4.124774 -0.000703 -4.693172 -v 0.002536 0.083827 0.166646 -vn -4.605505 -0.001255 -4.222823 -v 0.002077 0.083827 0.167095 -vn -4.094899 0.774853 -4.656257 -v 0.002552 0.084263 0.166668 -vn -4.573380 0.774468 -4.187928 -v 0.002095 0.084263 0.167117 -vn -4.006385 1.532648 -4.545148 -v 0.002600 0.084688 0.166733 -vn -4.477458 1.532474 -4.082737 -v 0.002145 0.084688 0.167181 -vn -3.863521 2.257272 -4.365625 -v 0.002677 0.085095 0.166839 -vn -4.322341 2.257361 -3.912766 -v 0.002227 0.085095 0.167284 -vn -3.671498 2.933772 -4.124985 -v 0.002780 0.085474 0.166980 -vn -4.113415 2.934034 -3.685362 -v 0.002337 0.085474 0.167422 -vn -3.437703 3.552501 -3.833410 -v 0.002905 0.085820 0.167151 -vn -3.858340 3.552980 -3.410391 -v 0.002470 0.085820 0.167590 -vn -3.091228 4.218199 -3.408022 -v 0.003048 0.086128 0.167346 -vn -2.908351 4.953532 -2.406110 -v 0.002961 0.086627 0.168211 -vn -2.420107 5.580978 -1.376597 -v 0.003003 0.086973 0.169140 -vn -1.746610 5.972754 -0.516012 -v 0.003175 0.087187 0.170122 -vn -0.882594 6.199875 -0.040242 -v 0.003535 0.087296 0.171198 -vn -4.224718 3.553121 -2.945152 -v 0.002089 0.085820 0.168075 -vn -4.500173 2.934046 -3.202537 -v 0.001947 0.085474 0.167910 -vn -4.725429 2.257244 -3.415990 -v 0.001830 0.085095 0.167774 -vn -4.892402 1.532218 -3.575846 -v 0.001743 0.084688 0.167673 -vn -4.995458 0.773970 -3.674864 -v 0.001690 0.084263 0.167610 -vn -5.029828 -0.001807 -3.707644 -v 0.001671 0.083827 0.167589 -vn -4.995071 -0.777344 -3.673205 -v 0.001690 0.083391 0.167610 -vn -4.891727 -1.534826 -3.572681 -v 0.001743 0.082965 0.167673 -vn -4.724778 -2.258654 -3.411512 -v 0.001830 0.082559 0.167774 -vn -4.499831 -2.934071 -3.196998 -v 0.001947 0.082180 0.167910 -vn -4.225098 -3.551630 -2.938888 -v 0.002089 0.081834 0.168075 -vn -3.827680 -4.186589 -2.609545 -v 0.002251 0.081525 0.168264 -vn -3.440835 -3.551967 -3.828856 -v 0.002905 0.081834 0.167151 -vn -3.489933 -4.200286 -3.024782 -v 0.002621 0.081525 0.167782 -vn -2.903791 -4.960269 -2.413964 -v 0.002961 0.081027 0.168211 -vn -3.149164 -4.984280 -2.040530 -v 0.002614 0.081027 0.168688 -vn -3.345621 -5.053650 -1.527152 -v 0.002327 0.081027 0.169214 -vn -3.607136 -4.991475 -1.094759 -v 0.002104 0.081027 0.169794 -vn -3.824197 -4.573161 -1.894344 -v 0.002126 0.081256 0.168997 -vn -4.033370 -4.580349 -1.360597 -v 0.001886 0.081256 0.169576 -vn -4.197870 -4.101427 -2.159162 -v 0.001936 0.081525 0.168793 -vn -4.431740 -4.099145 -1.622086 -v 0.001681 0.081525 0.169372 -vn -4.536222 -3.550765 -2.428678 -v 0.001763 0.081834 0.168606 -vn -4.791711 -3.549734 -1.869380 -v 0.001494 0.081834 0.169186 -vn -4.830192 -2.933798 -2.669129 -v 0.001611 0.082180 0.168443 -vn -5.104463 -2.933622 -2.091794 -v 0.001332 0.082180 0.169024 -vn -5.070804 -2.258780 -2.869757 -v 0.001487 0.082559 0.168309 -vn -5.360616 -2.258921 -2.278207 -v 0.001199 0.082559 0.168891 -vn -5.249403 -1.535216 -3.020881 -v 0.001394 0.082965 0.168209 -vn -5.550771 -1.535605 -2.418981 -v 0.001100 0.082965 0.168792 -vn -5.359994 -0.777903 -3.115345 -v 0.001337 0.083391 0.168148 -vn -5.668575 -0.778502 -2.507114 -v 0.001039 0.083391 0.168731 -vn -5.397336 -0.002421 -3.147886 -v 0.001318 0.083827 0.168127 -vn -5.708568 -0.003092 -2.537633 -v 0.001018 0.083827 0.168710 -vn -5.360914 0.773433 -3.117210 -v 0.001337 0.084263 0.168148 -vn -5.670156 0.772806 -2.509079 -v 0.001039 0.084263 0.168731 -vn -5.251043 1.531759 -3.024505 -v 0.001394 0.084688 0.168209 -vn -5.553683 1.531180 -2.422790 -v 0.001100 0.084688 0.168792 -vn -5.072772 2.256874 -2.874932 -v 0.001487 0.085095 0.168309 -vn -5.364342 2.256417 -2.283764 -v 0.001199 0.085095 0.168891 -vn -4.831997 2.933819 -2.675627 -v 0.001611 0.085474 0.168443 -vn -5.108310 2.933638 -2.098969 -v 0.001332 0.085474 0.169024 -vn -4.537246 3.552911 -2.436149 -v 0.001763 0.085820 0.168606 -vn -4.794709 3.552708 -1.877896 -v 0.001494 0.085820 0.169186 -vn -4.141445 4.144269 -2.185286 -v 0.001936 0.086128 0.168793 -vn -4.433094 4.105054 -1.631615 -v 0.001681 0.086128 0.169372 -vn -3.787987 4.565771 -1.978707 -v 0.002126 0.086397 0.168997 -vn -4.032638 4.588582 -1.371135 -v 0.001886 0.086397 0.169576 -vn -3.735608 -4.977964 -0.578175 -v 0.001956 0.081027 0.170435 -vn -4.184388 -4.571391 -0.792752 -v 0.001715 0.081256 0.170213 -vn -4.603477 -4.095287 -1.031216 -v 0.001492 0.081525 0.170006 -vn -4.984045 -3.548613 -1.258717 -v 0.001290 0.081834 0.169819 -vn -5.316462 -2.932750 -1.462077 -v 0.001115 0.082180 0.169657 -vn -5.588581 -2.258456 -1.633211 -v 0.000972 0.082559 0.169524 -vn -5.790326 -1.535858 -1.763755 -v 0.000866 0.082965 0.169425 -vn -5.915393 -0.779160 -1.845775 -v 0.000800 0.083391 0.169365 -vn -5.958091 -0.003827 -1.874223 -v 0.000778 0.083827 0.169344 -vn -5.917733 0.771979 -1.847852 -v 0.000800 0.084263 0.169365 -vn -5.794637 1.530268 -1.768106 -v 0.000866 0.084688 0.169425 -vn -5.594197 2.255658 -1.639391 -v 0.000972 0.085095 0.169524 -vn -5.322793 2.933016 -1.469494 -v 0.001115 0.085474 0.169657 -vn -4.990106 3.551886 -1.268558 -v 0.001290 0.085820 0.169819 -vn -4.606453 4.103893 -1.045423 -v 0.001492 0.086128 0.170006 -vn -2.408600 -5.593854 -1.384060 -v 0.003003 0.080681 0.169140 -vn -1.605392 -5.992252 -0.804452 -v 0.003390 0.080467 0.169589 -vn -3.184401 -5.320855 -0.846180 -v 0.002333 0.080836 0.170021 -vn -3.203088 -5.362802 -0.374137 -v 0.002209 0.080836 0.170669 -vn -3.695193 -5.052366 -0.090429 -v 0.001900 0.081027 0.171153 -vn -4.221974 -4.605783 -0.277663 -v 0.001631 0.081256 0.170921 -vn -4.685387 -4.106965 -0.430026 -v 0.001382 0.081525 0.170706 -vn -5.103655 -3.542704 -0.599359 -v 0.001160 0.081834 0.170514 -vn -5.458566 -2.925581 -0.770139 -v 0.000969 0.082180 0.170349 -vn -5.744761 -2.256978 -0.925053 -v 0.000814 0.082559 0.170215 -vn -5.957756 -1.537329 -1.047714 -v 0.000699 0.082965 0.170115 -vn -6.090729 -0.780305 -1.125370 -v 0.000629 0.083391 0.170054 -vn -6.136467 -0.004793 -1.152408 -v 0.000605 0.083827 0.170033 -vn -6.094059 0.771039 -1.128028 -v 0.000629 0.084263 0.170054 -vn -5.964069 1.530244 -1.053238 -v 0.000699 0.084688 0.170115 -vn -5.752656 2.254706 -0.932840 -v 0.000814 0.085095 0.170215 -vn -5.467026 2.928207 -0.777658 -v 0.000969 0.085474 0.170349 -vn -5.113903 3.547110 -0.599889 -v 0.001160 0.085820 0.170514 -vn -4.701190 4.107097 -0.415204 -v 0.001382 0.086128 0.170706 -vn -4.244126 4.599010 -0.247302 -v 0.001631 0.086397 0.170921 -vn -1.783523 -5.990644 -0.221234 -v 0.003046 0.080467 0.170724 -vn -0.861797 -6.201691 -0.170734 -v 0.003594 0.080358 0.170564 -vn -0.870980 -6.204774 -0.033332 -v 0.003535 0.080358 0.171198 -vn -0.042539 -6.270390 0.003731 -v 0.004005 0.080327 0.170990 -vn -0.000320 -6.269287 0.000241 -v 0.004000 0.080327 0.171644 -vn -2.681472 -5.650518 -0.170108 -v 0.002474 0.080681 0.170912 -vn -1.787820 -6.001090 -0.025761 -v 0.003020 0.080467 0.171410 -vn -2.768916 -5.611745 -0.005019 -v 0.002466 0.080681 0.171641 -vn -3.649395 -5.094205 -0.003656 -v 0.001900 0.081027 0.171918 -vn -4.255225 -4.609568 -0.025254 -v 0.001624 0.081256 0.171694 -vn -4.712945 -4.134418 -0.073213 -v 0.001362 0.081525 0.171481 -vn -0.811307 -6.202191 -0.333981 -v 0.003760 0.080358 0.170017 -vn -0.039649 -6.270199 -0.009946 -v 0.004110 0.080327 0.170416 -vn 0.837036 -6.213106 0.024097 -v 0.004465 0.080358 0.171455 -vn -0.006679 -6.269303 -0.016159 -v 0.005464 0.080327 0.168875 -vn -0.009003 -6.269162 -0.014028 -v 0.005216 0.080327 0.169005 -vn -2.183286 -4.956994 -3.080767 -v 0.003831 0.081027 0.167404 -vn -1.615300 -5.590240 -2.262537 -v 0.004146 0.080681 0.167875 -vn -1.052413 -5.989865 -1.458984 -v 0.004453 0.080467 0.168336 -vn -0.522866 -6.201050 -0.711593 -v 0.004738 0.080358 0.168766 -vn -0.011972 -6.269318 -0.017298 -v 0.004994 0.080327 0.169155 -vn -0.000005 -6.269270 -0.000002 -v 0.007633 0.080327 0.168650 -vn 0.002473 -6.208236 0.859211 -v 0.007092 0.080358 0.169115 -vn 0.060475 -6.015002 1.759329 -v 0.006628 0.080467 0.169629 -vn -0.000548 -6.003999 1.782491 -v 0.007397 0.080467 0.169630 -vn -0.020088 -6.002457 1.792469 -v 0.008164 0.080467 0.169630 -vn -3.237561 -3.002992 0.910440 -v 0.009500 0.080465 0.169625 -vn 0.006005 -5.609973 2.773453 -v 0.006983 0.080681 0.170184 -vn 0.265090 -6.033627 1.701249 -v 0.006268 0.080467 0.169648 -vn 0.564288 -6.022532 1.652561 -v 0.005978 0.080467 0.169722 -vn 0.131380 -5.631095 2.750442 -v 0.006613 0.080681 0.170184 -vn -0.000009 -5.094127 3.649333 -v 0.007343 0.081027 0.170750 -vn -0.027954 -5.076605 3.677321 -v 0.008767 0.081027 0.170750 -vn 0.000000 -1.540813 6.079090 -v 0.008158 0.082965 0.172042 -vn 0.000000 -2.268050 5.847301 -v 0.008076 0.082559 0.171912 -vn 0.006050 -2.948822 5.536055 -v 0.007967 0.082180 0.171738 -vn 1.376956 -5.643226 2.354894 -v 0.006029 0.080681 0.170306 -vn 0.530842 -5.132209 3.564317 -v 0.006456 0.081027 0.170752 -vn 0.002716 -4.601812 4.265503 -v 0.006819 0.081256 0.171025 -vn 0.000000 -4.603045 4.264031 -v 0.007517 0.081256 0.171025 -vn 0.094873 -4.602433 4.268921 -v 0.006645 0.081256 0.171025 -vn 0.687349 -4.599587 4.178305 -v 0.006474 0.081256 0.171028 -vn 1.339811 -5.141061 3.332143 -v 0.006326 0.081027 0.170790 -vn 1.850553 -4.702074 3.712528 -v 0.006444 0.081256 0.171039 -vn 2.043150 -5.108598 3.013327 -v 0.006275 0.081027 0.170819 -vn 1.979653 -4.478652 3.492784 -v 0.006499 0.081369 0.171143 -vn 3.929272 -4.441390 1.740848 -v 0.006495 0.081369 0.171148 -vn 1.774284 -4.536333 3.884529 -v 0.006490 0.081353 0.171128 -vn 3.070523 -4.539439 2.819086 -v 0.006484 0.081353 0.171132 -vn 2.531598 -4.530677 3.500207 -v 0.006466 0.081320 0.171103 -vn 0.258731 -4.251821 4.537510 -v 0.006498 0.081353 0.171126 -vn 1.292107 -4.517016 4.088099 -v 0.006479 0.081320 0.171096 -vn -0.037621 -4.321649 4.559891 -v 0.006543 0.081386 0.171159 -vn 0.158414 -4.399743 4.480730 -v 0.006564 0.081386 0.171158 -vn 0.664526 -4.464022 4.255380 -v 0.006566 0.081437 0.171207 -vn 0.240853 -4.460724 4.403142 -v 0.006554 0.081420 0.171191 -vn 0.977346 -4.767935 3.922558 -v 0.006545 0.081420 0.171192 -vn -0.195463 -4.318367 4.559005 -v 0.006520 0.081386 0.171158 -vn 0.105198 -4.315693 4.560881 -v 0.006565 0.081420 0.171191 -vn -0.146932 -4.047379 4.798932 -v 0.006655 0.081525 0.171287 -vn -0.187133 -4.078364 4.774778 -v 0.006649 0.081525 0.171287 -vn -0.172627 -4.136743 4.718479 -v 0.006633 0.081490 0.171256 -vn -0.184452 -4.128243 4.729953 -v 0.006621 0.081490 0.171255 -vn 2.092382 -4.797760 3.065317 -v 0.006591 0.081472 0.171241 -vn 0.960757 -4.614865 4.038074 -v 0.006578 0.081454 0.171223 -vn 0.467638 -4.377183 4.432049 -v 0.006643 0.081525 0.171287 -vn 0.438351 -4.303735 4.525377 -v 0.006615 0.081490 0.171255 -vn 1.539156 -4.617715 3.789954 -v 0.006611 0.081490 0.171255 -vn 3.073540 -4.797082 2.272125 -v 0.006605 0.081490 0.171259 -vn 1.953550 -4.735029 3.415169 -v 0.006639 0.081525 0.171288 -vn 3.810286 -4.503195 1.526965 -v 0.006637 0.081525 0.171290 -vn 2.627656 -4.626300 2.842242 -v 0.006623 0.081507 0.171272 -vn 4.752620 -4.077076 0.036650 -v 0.006636 0.081525 0.171298 -vn 4.115924 -4.527575 0.915082 -v 0.006621 0.081507 0.171278 -vn 2.177760 -4.688218 3.074222 -v 0.006510 0.081386 0.171159 -vn 3.546828 -4.837655 1.361133 -v 0.006540 0.081420 0.171196 -vn 4.066881 -4.459141 1.100417 -v 0.006508 0.081386 0.171161 -vn 4.553486 -4.262879 -0.062814 -v 0.006539 0.081420 0.171200 -vn 4.763943 -4.085279 0.029798 -v 0.006508 0.081386 0.171165 -vn 2.645368 -4.704329 3.195926 -v 0.006420 0.081256 0.171054 -vn 4.103070 -4.652437 0.580781 -v 0.006556 0.081437 0.171216 -vn 4.601021 -4.274903 0.012556 -v 0.006573 0.081454 0.171245 -vn 4.711588 -4.138188 -0.371673 -v 0.006540 0.081420 0.171204 -vn 4.612636 -4.264140 0.042147 -v 0.006573 0.081454 0.171261 -vn 4.551577 -4.327978 0.013147 -v 0.006508 0.081386 0.171182 -vn 4.312394 -4.447054 0.630371 -v 0.006604 0.081490 0.171263 -vn 2.667134 -4.844496 2.669030 -v 0.006574 0.081454 0.171225 -vn 4.241796 -4.421391 1.103372 -v 0.006444 0.081320 0.171137 -vn 3.372427 -4.551814 2.597237 -v 0.006456 0.081320 0.171112 -vn 3.867024 -4.580464 1.428320 -v 0.006477 0.081353 0.171143 -vn 4.443339 -4.431265 0.249640 -v 0.006442 0.081320 0.171168 -vn 4.168284 -4.617273 0.579742 -v 0.006492 0.081369 0.171162 -vn 4.451097 -4.428401 0.111595 -v 0.006508 0.081386 0.171249 -vn 4.714863 -4.150789 0.017356 -v 0.006637 0.081525 0.171405 -vn 1.302403 -4.226370 4.136398 -v 0.006762 0.081675 0.171410 -vn 1.621477 -4.083924 3.889097 -v 0.006751 0.081656 0.171394 -vn -0.017610 -3.862318 4.950800 -v 0.006774 0.081675 0.171410 -vn -0.070545 -3.895616 4.923481 -v 0.006763 0.081637 0.171380 -vn 3.690513 -4.506623 1.687082 -v 0.006729 0.081637 0.171387 -vn 4.924902 -3.790201 -0.264879 -v 0.006729 0.081637 0.171390 -vn 0.082958 -4.006966 4.837287 -v 0.006784 0.081599 0.171349 -vn 0.042529 -3.840980 4.971622 -v 0.006784 0.081675 0.171410 -vn 0.117098 -3.851231 4.962814 -v 0.006779 0.081675 0.171410 -vn 0.045982 -3.728487 5.055847 -v 0.006868 0.081753 0.171470 -vn 0.000708 -3.872445 4.946159 -v 0.006826 0.081675 0.171410 -vn 0.166028 -3.870546 4.939420 -v 0.006911 0.081675 0.171410 -vn 0.029870 -4.194753 4.671998 -v 0.006826 0.081525 0.171287 -vn 0.026508 -4.145018 4.711373 -v 0.006997 0.081525 0.171287 -vn 0.042286 -3.741606 5.047173 -v 0.006847 0.081753 0.171470 -vn 0.273158 -3.836032 4.962338 -v 0.006846 0.081773 0.171484 -vn -0.117701 -3.751971 5.032794 -v 0.006836 0.081753 0.171470 -vn 0.717418 -4.072005 4.601615 -v 0.006814 0.081733 0.171454 -vn 0.062939 -3.768443 5.026741 -v 0.006804 0.081714 0.171439 -vn 0.183391 -3.694296 5.075961 -v 0.006887 0.081834 0.171527 -vn 1.025710 -4.074008 4.555261 -v 0.006798 0.081714 0.171439 -vn 3.123104 -4.215580 2.736130 -v 0.006807 0.081733 0.171456 -vn 2.192482 -4.532128 3.713634 -v 0.006795 0.081714 0.171441 -vn 4.633712 -4.079415 0.758117 -v 0.006805 0.081733 0.171463 -vn 3.292565 -4.616631 2.382731 -v 0.006790 0.081714 0.171445 -vn -0.000827 -4.105838 4.755786 -v 0.006740 0.081525 0.171287 -vn 5.085032 -3.667927 -0.220184 -v 0.006790 0.081714 0.171461 -vn 5.198405 -3.441495 -0.730742 -v 0.006790 0.081714 0.171453 -vn 4.751513 -3.776534 0.148191 -v 0.006789 0.081714 0.171448 -vn 4.901455 -3.731856 0.245339 -v 0.006848 0.081793 0.171508 -vn 3.084800 -4.155521 2.734147 -v 0.006849 0.081793 0.171501 -vn 5.136464 -3.604599 -0.037863 -v 0.006863 0.081814 0.171526 -vn 4.352582 -3.918607 1.543823 -v 0.006863 0.081814 0.171518 -vn 5.192832 -3.510439 -0.130988 -v 0.006877 0.081834 0.171544 -vn 5.142307 -3.598270 -0.089416 -v 0.006820 0.081753 0.171481 -vn 3.939914 -3.864527 1.645006 -v 0.006819 0.081753 0.171473 -vn 4.453151 -3.881151 0.888805 -v 0.006833 0.081773 0.171490 -vn 1.180036 -4.079430 4.251309 -v 0.006825 0.081753 0.171469 -vn 2.005297 -4.139952 3.632325 -v 0.006836 0.081773 0.171485 -vn 5.162853 -3.580213 0.043031 -v 0.006877 0.081834 0.171552 -vn 5.175975 -3.508801 -0.261875 -v 0.006849 0.081793 0.171517 -vn -0.016498 -3.995375 4.848282 -v 0.006741 0.081599 0.171349 -vn 0.905568 -4.167057 4.424903 -v 0.006740 0.081637 0.171379 -vn 5.074335 -3.700717 -0.109195 -v 0.006805 0.081733 0.171471 -vn -0.111678 -3.210209 5.393917 -v 0.007006 0.082002 0.171637 -vn 0.030289 -3.297316 5.347040 -v 0.007026 0.082002 0.171637 -vn 0.185445 -3.284105 5.345655 -v 0.007068 0.082002 0.171637 -vn 0.027094 -3.593482 5.143552 -v 0.007161 0.081834 0.171527 -vn 1.175250 -3.438511 5.091990 -v 0.007069 0.082135 0.171714 -vn -0.112833 -3.106725 5.456155 -v 0.007052 0.082090 0.171689 -vn 0.315394 -3.149775 5.415151 -v 0.007074 0.082135 0.171713 -vn 0.199945 -3.143977 5.431477 -v 0.007062 0.082090 0.171689 -vn 0.137799 -3.092006 5.464431 -v 0.007079 0.082135 0.171713 -vn 1.302585 -3.565775 4.820477 -v 0.007041 0.082090 0.171689 -vn -0.028955 -3.183064 5.412785 -v 0.007046 0.082090 0.171688 -vn 2.484789 -3.775012 4.257716 -v 0.007066 0.082135 0.171715 -vn 3.508063 -3.633267 3.252880 -v 0.007089 0.082180 0.171740 -vn 1.493351 -3.506798 4.900507 -v 0.007092 0.082180 0.171739 -vn 0.326155 -3.136338 5.423259 -v 0.007096 0.082180 0.171738 -vn 0.179788 -3.258545 5.362311 -v 0.007023 0.082046 0.171662 -vn 1.230397 -3.585277 4.928960 -v 0.007018 0.082046 0.171663 -vn -0.006983 -3.322915 5.309425 -v 0.006994 0.082002 0.171636 -vn -0.377541 -3.134078 5.430621 -v 0.007000 0.082002 0.171637 -vn 0.164760 -3.328978 5.284612 -v 0.006985 0.081981 0.171623 -vn -0.056260 -3.305957 5.327368 -v 0.006987 0.081959 0.171610 -vn -0.046098 -3.371418 5.290377 -v 0.006976 0.081959 0.171610 -vn -0.035528 -3.423030 5.267920 -v 0.006968 0.081917 0.171583 -vn -0.064145 -3.398454 5.284132 -v 0.006947 0.081917 0.171583 -vn 5.482723 -2.948318 -0.142720 -v 0.007038 0.082090 0.171694 -vn 5.596287 -2.754311 -0.686629 -v 0.007039 0.082090 0.171698 -vn 4.529720 -3.777246 1.796569 -v 0.007013 0.082046 0.171667 -vn 5.271790 -3.203858 0.423179 -v 0.007063 0.082135 0.171721 -vn -0.006757 -3.579804 5.162895 -v 0.006908 0.081834 0.171527 -vn 0.000000 -4.119874 4.731465 -v 0.007683 0.081525 0.171287 -vn 0.000000 -3.566633 5.160420 -v 0.007834 0.081834 0.171527 -vn 0.023621 -3.578658 5.150229 -v 0.009182 0.081834 0.171527 -vn 2.595762 -4.163184 3.529787 -v 0.006878 0.081834 0.171529 -vn 0.896015 -3.928172 4.771322 -v 0.006882 0.081834 0.171528 -vn 3.360485 -4.351882 2.910833 -v 0.006906 0.081875 0.171559 -vn 2.028477 -4.198229 4.118494 -v 0.006909 0.081875 0.171557 -vn 5.291306 -3.343776 -0.362405 -v 0.006905 0.081875 0.171570 -vn 5.296488 -3.362730 -0.277419 -v 0.006877 0.081834 0.171535 -vn 5.216724 -3.420259 -0.187021 -v 0.006904 0.081875 0.171566 -vn 4.522879 -3.901236 1.203927 -v 0.006877 0.081834 0.171531 -vn 1.847061 -3.957851 4.350334 -v 0.006937 0.081917 0.171583 -vn 0.467434 -3.587749 5.101952 -v 0.006941 0.081917 0.171583 -vn 3.217301 -4.113081 3.364981 -v 0.006963 0.081959 0.171612 -vn 1.371757 -3.751828 4.673822 -v 0.006966 0.081959 0.171610 -vn 2.784200 -3.671187 3.315390 -v 0.006976 0.081981 0.171624 -vn 4.897480 -3.753929 1.006160 -v 0.006974 0.081981 0.171631 -vn 4.209186 -4.085327 2.120704 -v 0.006961 0.081959 0.171614 -vn 4.900286 -3.759654 0.972448 -v 0.006960 0.081959 0.171618 -vn 5.235735 -3.454330 0.192934 -v 0.006960 0.081959 0.171621 -vn 4.438698 -4.074834 1.356837 -v 0.006905 0.081875 0.171562 -vn 5.172050 -3.566295 0.016027 -v 0.006877 0.081834 0.171568 -vn 5.524981 -2.990727 0.061908 -v 0.007088 0.082180 0.171763 -vn 5.492833 -3.015306 -0.183822 -v 0.007039 0.082090 0.171703 -vn 5.273148 -3.363534 0.354800 -v 0.007012 0.082046 0.171670 -vn 5.040316 -3.751207 0.013345 -v 0.006820 0.081753 0.171489 -vn 5.052608 -3.734302 0.030366 -v 0.006820 0.081753 0.171497 -vn 4.652646 -4.194333 0.271359 -v 0.006668 0.081562 0.171328 -vn 4.124392 -4.540021 1.188585 -v 0.006668 0.081562 0.171324 -vn 4.419855 -4.299658 0.851124 -v 0.006684 0.081580 0.171339 -vn 3.153898 -4.787931 2.414317 -v 0.006670 0.081562 0.171321 -vn 1.955692 -4.680789 3.592228 -v 0.006672 0.081562 0.171319 -vn 4.658836 -4.210458 0.147867 -v 0.006684 0.081580 0.171347 -vn 4.781914 -4.073795 0.089442 -v 0.006699 0.081599 0.171383 -vn 4.781087 -4.060703 -0.169674 -v 0.006637 0.081525 0.171306 -vn 4.483354 -4.096668 0.704803 -v 0.006698 0.081599 0.171353 -vn 5.147631 -3.555119 -0.574300 -v 0.006699 0.081599 0.171358 -vn 4.910429 -3.869040 -0.208230 -v 0.006700 0.081599 0.171367 -vn 4.965286 -3.805065 -0.138630 -v 0.006731 0.081637 0.171404 -vn 4.905711 -3.923988 0.080192 -v 0.006730 0.081637 0.171420 -vn 0.409305 -4.073504 4.743553 -v 0.006730 0.081618 0.171364 -vn 2.378829 -4.615966 3.419470 -v 0.006734 0.081637 0.171382 -vn 4.537611 -4.191794 0.664915 -v 0.006745 0.081656 0.171406 -vn 5.134303 -3.532327 -0.795070 -v 0.006729 0.081637 0.171395 -vn 4.729356 -4.135676 0.001717 -v 0.006637 0.081525 0.171339 -vn 4.824397 -4.023417 0.049361 -v 0.006699 0.081599 0.171415 -vn 2.212092 -5.034895 2.880630 -v 0.006542 0.081420 0.171193 -vn 0.326903 -4.500933 4.305737 -v 0.006514 0.081386 0.171158 -vn 4.910186 -3.912007 0.124618 -v 0.006760 0.081675 0.171554 -vn 5.140531 -3.599722 0.039481 -v 0.006877 0.081834 0.171825 -vn 4.694665 -4.166552 0.035361 -v 0.006637 0.081525 0.171536 -vn 4.731563 -4.119776 -0.000161 -v 0.006637 0.081525 0.171799 -vn 4.484568 -4.391487 0.157237 -v 0.006375 0.081256 0.171222 -vn 5.365787 -3.267399 0.031376 -v 0.006987 0.082002 0.171655 -vn 5.398504 -3.211867 0.098317 -v 0.006987 0.082002 0.171647 -vn 4.449099 -3.536549 1.682709 -v 0.006987 0.082002 0.171639 -vn 4.931894 -3.892630 0.002195 -v 0.006760 0.081675 0.171490 -vn 3.967292 -4.590013 1.339604 -v 0.006387 0.081256 0.171096 -vn 3.321932 -4.682775 2.525473 -v 0.006402 0.081256 0.171074 -vn -0.018513 -2.389909 5.810317 -v 0.007258 0.082485 0.171883 -vn -0.009570 -2.473263 5.775441 -v 0.007251 0.082461 0.171873 -vn 0.002294 -2.474577 5.774960 -v 0.007271 0.082461 0.171873 -vn 0.101270 -2.448779 5.783303 -v 0.007313 0.082461 0.171873 -vn 0.042564 -2.361265 5.821797 -v 0.007285 0.082510 0.171893 -vn -0.074226 -2.345256 5.827933 -v 0.007265 0.082510 0.171893 -vn 0.104136 -2.428869 5.790893 -v 0.007247 0.082485 0.171883 -vn 0.603223 -2.626486 5.644349 -v 0.007230 0.082461 0.171873 -vn 0.286864 -2.623653 5.695357 -v 0.007223 0.082437 0.171862 -vn 0.044570 -2.623878 5.705695 -v 0.007366 0.082365 0.171830 -vn 0.052541 -2.247442 5.860900 -v 0.007421 0.082559 0.171912 -vn 0.028561 -2.273794 5.855330 -v 0.007340 0.082559 0.171912 -vn -0.011272 -3.002129 5.517949 -v 0.007117 0.082180 0.171738 -vn 0.051363 -3.031782 5.502408 -v 0.007107 0.082180 0.171738 -vn 0.390504 -3.001640 5.495569 -v 0.007115 0.082203 0.171750 -vn 1.593061 -3.484997 4.802794 -v 0.007106 0.082203 0.171751 -vn 5.726747 -2.502211 -0.435620 -v 0.007158 0.082318 0.171818 -vn 5.740974 -2.541908 -0.178114 -v 0.007136 0.082272 0.171790 -vn 4.992425 -2.941656 1.020746 -v 0.007157 0.082318 0.171814 -vn 3.563866 -2.745897 2.479223 -v 0.007135 0.082272 0.171786 -vn 3.630061 -3.580449 3.582602 -v 0.007159 0.082318 0.171811 -vn 4.215701 -3.232639 2.696394 -v 0.007125 0.082248 0.171777 -vn 1.282373 -3.028891 4.964902 -v 0.007130 0.082248 0.171773 -vn 0.762957 -3.015343 5.366937 -v 0.007139 0.082272 0.171785 -vn 3.976713 -3.538926 2.429122 -v 0.007100 0.082203 0.171754 -vn 5.208385 -3.181394 0.851722 -v 0.007088 0.082180 0.171743 -vn 4.108450 -3.779371 2.529651 -v 0.007063 0.082135 0.171717 -vn 3.883333 -3.557058 2.438823 -v 0.007038 0.082090 0.171690 -vn 2.975879 -3.934261 3.691052 -v 0.007015 0.082046 0.171664 -vn 1.898020 -3.775658 4.281426 -v 0.006989 0.082002 0.171637 -vn 1.143023 -2.923430 5.260586 -v 0.007165 0.082318 0.171808 -vn 2.695453 -3.328434 4.572568 -v 0.007162 0.082318 0.171809 -vn -0.041318 -2.802274 5.622461 -v 0.007150 0.082272 0.171785 -vn -0.063332 -2.828230 5.594941 -v 0.007134 0.082225 0.171762 -vn 0.674873 -3.059762 5.319794 -v 0.007122 0.082225 0.171761 -vn 2.926587 -3.469325 3.928802 -v 0.007115 0.082225 0.171764 -vn 5.400184 -3.068878 0.593288 -v 0.007124 0.082248 0.171784 -vn 4.785205 -3.396514 1.642983 -v 0.007112 0.082225 0.171769 -vn 5.583593 -2.788815 -0.248719 -v 0.007111 0.082225 0.171773 -vn 5.619991 -2.748707 -0.346222 -v 0.007112 0.082225 0.171777 -vn 5.629131 -2.751349 -0.444388 -v 0.007088 0.082180 0.171747 -vn 5.630589 -2.783929 0.074074 -v 0.007136 0.082272 0.171798 -vn 5.630054 -2.788599 0.024909 -v 0.007135 0.082272 0.171806 -vn 5.621738 -2.802175 0.052787 -v 0.007135 0.082272 0.171822 -vn -0.061320 -2.304169 5.844385 -v 0.007271 0.082534 0.171903 -vn 0.340635 -2.451083 5.752638 -v 0.007254 0.082510 0.171892 -vn 1.369590 -2.813982 5.332996 -v 0.007238 0.082485 0.171883 -vn 3.541384 -2.428865 2.626650 -v 0.007222 0.082461 0.171874 -vn 2.930614 -2.714368 3.566655 -v 0.007214 0.082437 0.171863 -vn 1.890080 -2.949069 4.816273 -v 0.007206 0.082413 0.171852 -vn 0.749944 -2.865436 5.478840 -v 0.007198 0.082389 0.171841 -vn 0.125754 -2.761633 5.640213 -v 0.007191 0.082365 0.171830 -vn 2.648580 -2.899182 3.689514 -v 0.007181 0.082365 0.171831 -vn 3.406024 -2.891986 2.865416 -v 0.007191 0.082389 0.171843 -vn 5.514882 -2.656668 0.597720 -v 0.007180 0.082365 0.171834 -vn 5.763372 -2.338620 -0.428511 -v 0.007201 0.082413 0.171860 -vn 5.747815 -2.534988 0.003715 -v 0.007202 0.082413 0.171872 -vn 5.700309 -2.641347 -0.023974 -v 0.007180 0.082365 0.171846 -vn 5.774189 -2.477166 -0.016908 -v 0.007223 0.082461 0.171890 -vn 5.778937 -2.466043 0.014282 -v 0.007223 0.082461 0.171898 -vn 0.733420 -2.522894 5.633228 -v 0.007261 0.082534 0.171902 -vn 2.530914 -2.914648 4.567535 -v 0.007246 0.082510 0.171894 -vn 4.220861 -2.605699 1.976874 -v 0.007232 0.082485 0.171886 -vn 5.809004 -2.379405 -0.031512 -v 0.007223 0.082461 0.171882 -vn 5.442495 -2.853696 1.010459 -v 0.007212 0.082437 0.171869 -vn 4.476849 -3.010486 2.202955 -v 0.007201 0.082413 0.171856 -vn 5.762413 -2.503727 0.013041 -v 0.007223 0.082461 0.171886 -vn 5.831718 -2.240005 -0.367202 -v 0.007233 0.082485 0.171895 -vn 5.809425 -2.391950 0.083109 -v 0.007243 0.082510 0.171923 -vn 5.898345 -2.157006 -0.072756 -v 0.007262 0.082559 0.171931 -vn 5.885105 -2.197155 -0.001241 -v 0.007262 0.082559 0.171947 -vn 5.872649 -2.229673 0.004408 -v 0.007262 0.082559 0.171977 -vn 5.773844 -2.474260 0.071072 -v 0.007223 0.082461 0.171929 -vn 5.531794 -2.975594 0.021503 -v 0.007088 0.082180 0.171826 -vn 5.345559 -3.297414 0.053519 -v 0.006987 0.082002 0.171702 -vn 5.370305 -3.259827 -0.001581 -v 0.006987 0.082002 0.171671 -vn 1.287003 -2.692020 5.511643 -v 0.007283 0.082608 0.171933 -vn 2.682955 -2.529642 4.218374 -v 0.007263 0.082559 0.171913 -vn 0.294641 -2.396118 5.791654 -v 0.007268 0.082559 0.171912 -vn 3.579787 -2.782341 3.418770 -v 0.007254 0.082534 0.171905 -vn -0.061526 -1.788613 6.022605 -v 0.007368 0.082810 0.171999 -vn 0.016142 -1.966193 5.966191 -v 0.007368 0.082759 0.171983 -vn 0.019975 -1.712790 6.015689 -v 0.007389 0.082862 0.172014 -vn 0.501631 -1.935781 5.926505 -v 0.007388 0.082759 0.171983 -vn 0.076641 -1.602649 6.071099 -v 0.007428 0.082965 0.172042 -vn 0.058109 -2.096970 5.914370 -v 0.007324 0.082658 0.171949 -vn -0.030679 -1.935116 5.974679 -v 0.007357 0.082759 0.171983 -vn 0.227606 -2.149149 5.885312 -v 0.007313 0.082658 0.171949 -vn 1.225873 -2.305991 5.682721 -v 0.007309 0.082658 0.171949 -vn 3.530394 -2.525456 4.350729 -v 0.007312 0.082683 0.171960 -vn 2.444953 -2.583357 5.084132 -v 0.007305 0.082658 0.171950 -vn 4.617846 -2.784617 3.203000 -v 0.007308 0.082683 0.171964 -vn 3.401902 -2.924505 4.371147 -v 0.007300 0.082658 0.171954 -vn 6.004625 -1.803187 -0.117270 -v 0.007333 0.082759 0.171991 -vn 5.568935 -2.450265 1.563637 -v 0.007316 0.082708 0.171975 -vn 5.396597 -2.465998 2.014524 -v 0.007317 0.082708 0.171972 -vn 4.290599 -2.561719 3.571360 -v 0.007319 0.082708 0.171969 -vn 2.378930 -2.465540 5.141781 -v 0.007321 0.082708 0.171967 -vn 0.725685 -2.182327 5.811721 -v 0.007325 0.082708 0.171966 -vn 5.443223 -2.198875 1.672987 -v 0.007333 0.082759 0.171988 -vn 3.684898 -2.491046 4.131438 -v 0.007335 0.082759 0.171985 -vn 1.455929 -2.296488 5.562521 -v 0.007338 0.082759 0.171984 -vn 0.160220 -1.995842 5.950198 -v 0.007347 0.082759 0.171983 -vn 6.100854 -1.434613 -0.133292 -v 0.007392 0.082965 0.172054 -vn 5.883739 -1.936080 1.048950 -v 0.007379 0.082913 0.172037 -vn 5.888424 -1.838820 1.178625 -v 0.007379 0.082913 0.172033 -vn 5.934422 -1.899223 0.755007 -v 0.007378 0.082913 0.172040 -vn 6.095431 -1.517783 0.068233 -v 0.007392 0.082965 0.172061 -vn 5.997223 -1.835230 0.375060 -v 0.007378 0.082913 0.172044 -vn 6.073714 -1.491533 0.352798 -v 0.007404 0.083018 0.172061 -vn 5.838181 -1.614297 0.875285 -v 0.007392 0.082965 0.172045 -vn 3.459447 -1.912782 4.018909 -v 0.007393 0.082965 0.172043 -vn 4.997731 -1.951936 2.832451 -v 0.007380 0.082913 0.172030 -vn 5.737193 -2.263602 0.696997 -v 0.007315 0.082708 0.171978 -vn 5.999292 -1.812020 -0.258569 -v 0.007333 0.082759 0.171996 -vn 5.970363 -1.933536 0.117986 -v 0.007333 0.082759 0.172003 -vn 5.832271 -1.983952 0.759517 -v 0.007348 0.082810 0.172007 -vn 1.884847 -2.239977 5.534278 -v 0.007354 0.082810 0.172000 -vn 4.311068 -2.316144 3.911645 -v 0.007367 0.082862 0.172017 -vn 3.160697 -2.481423 4.743208 -v 0.007351 0.082810 0.172001 -vn 4.934163 -2.364125 3.052134 -v 0.007365 0.082862 0.172019 -vn 4.775396 -2.405562 2.938013 -v 0.007349 0.082810 0.172004 -vn 5.551347 -2.191393 1.740014 -v 0.007364 0.082862 0.172022 -vn 5.952344 -1.907622 0.538263 -v 0.007363 0.082862 0.172025 -vn 6.096460 -1.502497 0.036261 -v 0.007392 0.082965 0.172076 -vn 6.084123 -1.524367 0.021490 -v 0.007392 0.082965 0.172198 -vn -0.245444 -1.653470 6.050255 -v 0.007378 0.082862 0.172013 -vn 0.240465 -1.836076 5.997005 -v 0.007363 0.082810 0.171999 -vn 4.872436 -2.525157 1.830454 -v 0.007297 0.082658 0.171956 -vn 3.780845 -2.531159 2.837258 -v 0.007280 0.082608 0.171934 -vn 5.695191 -2.647670 0.062038 -v 0.007180 0.082365 0.171939 -vn 5.850924 -2.259944 0.014462 -v 0.007262 0.082559 0.172286 -vn 5.522021 -2.980005 0.039200 -v 0.007088 0.082180 0.172078 -vn 5.536952 -2.946926 0.000000 -v 0.007088 0.082180 0.172581 -vn 5.929766 -2.064481 -0.174898 -v 0.007298 0.082658 0.171960 -vn 5.939045 -2.040058 -0.093666 -v 0.007316 0.082708 0.171982 -vn 5.869844 -2.229159 0.040080 -v 0.007262 0.082559 0.172039 -vn 5.447472 -2.505641 1.256033 -v 0.007262 0.082559 0.171915 -vn 5.897892 -2.148313 0.085892 -v 0.007279 0.082608 0.171938 -vn -0.249613 -0.824579 6.219596 -v 0.007478 0.083391 0.172123 -vn 0.890483 -0.903386 6.035019 -v 0.007475 0.083391 0.172123 -vn 0.530345 -1.163547 6.120107 -v 0.007460 0.083176 0.172089 -vn 1.686975 -1.116204 5.946470 -v 0.007462 0.083283 0.172107 -vn 2.846740 -1.071119 5.398243 -v 0.007468 0.083337 0.172115 -vn -0.442849 -1.522328 6.079752 -v 0.007402 0.082965 0.172042 -vn -0.196557 -1.521155 6.085032 -v 0.007408 0.082965 0.172042 -vn 0.787972 -1.485955 6.052253 -v 0.007425 0.083070 0.172067 -vn 1.736472 -1.509732 5.779418 -v 0.007432 0.083123 0.172078 -vn 4.095758 -1.572441 3.868905 -v 0.007429 0.083123 0.172080 -vn 5.330192 -1.310483 1.983057 -v 0.007438 0.083176 0.172092 -vn 6.167710 -0.973633 -0.560770 -v 0.007438 0.083176 0.172096 -vn 0.579227 -1.583857 6.051154 -v 0.007412 0.083018 0.172055 -vn 6.112725 -1.391240 0.383888 -v 0.007428 0.083123 0.172086 -vn 6.154738 -1.017231 -0.615823 -v 0.007439 0.083176 0.172100 -vn -0.070730 -1.236869 6.157293 -v 0.007450 0.083176 0.172089 -vn 1.474185 -1.292012 5.878899 -v 0.007452 0.083230 0.172099 -vn 0.326988 -1.310578 6.121305 -v 0.007445 0.083176 0.172089 -vn 4.097200 -1.388310 3.830207 -v 0.007449 0.083230 0.172100 -vn 2.642478 -1.477390 5.072757 -v 0.007440 0.083176 0.172089 -vn 5.975090 -1.173693 0.789090 -v 0.007447 0.083230 0.172103 -vn 6.083179 -1.003354 0.203086 -v 0.007457 0.083283 0.172119 -vn 6.173069 -0.920334 -0.259083 -v 0.007457 0.083283 0.172114 -vn 5.573113 -1.184502 2.022316 -v 0.007457 0.083283 0.172111 -vn 6.235184 -0.729044 0.186007 -v 0.007473 0.083391 0.172145 -vn 6.126223 -0.988302 0.314010 -v 0.007466 0.083337 0.172129 -vn 6.218130 -0.702847 -0.128723 -v 0.007473 0.083391 0.172138 -vn 6.196543 -0.875189 0.033395 -v 0.007465 0.083337 0.172121 -vn 6.227987 -0.745345 0.020971 -v 0.007473 0.083391 0.172176 -vn 5.987633 -1.304883 0.770580 -v 0.007439 0.083176 0.172104 -vn 3.409949 -1.252960 4.723646 -v 0.007459 0.083283 0.172108 -vn 0.516211 -1.109957 6.162525 -v 0.007456 0.083230 0.172099 -vn 4.622161 -1.807927 2.885335 -v 0.007404 0.083018 0.172057 -vn 6.124260 -1.394343 0.147654 -v 0.007416 0.083070 0.172076 -vn 0.030348 -1.580000 6.071080 -v 0.007509 0.082965 0.172042 -vn 0.045419 -0.832120 6.218096 -v 0.007564 0.083391 0.172123 -vn -0.025346 -0.883990 6.216001 -v 0.007483 0.083391 0.172123 -vn 0.362166 -0.598243 6.242698 -v 0.007491 0.083499 0.172135 -vn 1.074437 -0.700848 6.130619 -v 0.007487 0.083499 0.172135 -vn 6.248134 -0.610132 0.232973 -v 0.007483 0.083499 0.172140 -vn 3.961837 -0.698818 3.219512 -v 0.007483 0.083499 0.172136 -vn 6.262526 -0.011633 -0.346828 -v 0.007500 0.083827 0.172156 -vn 6.198782 -0.240901 0.984920 -v 0.007498 0.083717 0.172154 -vn 6.186418 -0.012603 0.416419 -v 0.007500 0.083827 0.172154 -vn 4.991497 -0.256107 3.003871 -v 0.007498 0.083717 0.172150 -vn 3.129415 -0.000000 3.939943 -v 0.007501 0.083827 0.172151 -vn 2.045285 -0.306551 5.686461 -v 0.007501 0.083717 0.172149 -vn 1.964792 -0.443192 5.846609 -v 0.007495 0.083608 0.172144 -vn 4.580109 -0.550740 3.585651 -v 0.007492 0.083608 0.172146 -vn 6.118593 -0.449143 0.304885 -v 0.007492 0.083608 0.172149 -vn 6.117779 -0.330495 -1.362655 -v 0.007492 0.083608 0.172151 -vn 5.700824 -2.640653 0.009022 -v 0.007180 0.082365 0.171877 -vn 5.165592 -3.572661 0.005295 -v 0.006877 0.081834 0.171696 -vn 1.865909 -5.642806 1.988666 -v 0.005838 0.080681 0.170446 -vn 0.084488 3.555639 5.162448 -v 0.009182 0.085820 0.171527 -vn 0.000000 3.566607 5.160437 -v 0.007834 0.085820 0.171527 -vn 0.000000 4.119874 4.731465 -v 0.007683 0.086128 0.171287 -vn 0.026643 4.154006 4.704239 -v 0.006997 0.086128 0.171287 -vn 0.000000 4.603044 4.264030 -v 0.006819 0.086397 0.171025 -vn -0.011313 0.780020 6.222821 -v 0.008208 0.084263 0.172123 -vn 0.171106 0.953213 6.197097 -v 0.009420 0.084334 0.172113 -vn -0.003589 1.543225 6.078629 -v 0.008158 0.084688 0.172042 -vn 0.296569 1.591898 6.045027 -v 0.009455 0.084688 0.172042 -vn 0.009755 2.262636 5.849748 -v 0.008076 0.085095 0.171912 -vn 0.391636 2.436263 5.731660 -v 0.009386 0.085095 0.171912 -vn 0.014195 2.959360 5.531157 -v 0.007967 0.085474 0.171738 -vn 0.369462 0.625093 6.239387 -v 0.007491 0.084154 0.172135 -vn 1.074696 0.715942 6.128057 -v 0.007487 0.084154 0.172135 -vn 4.566492 0.524643 3.596356 -v 0.007492 0.084045 0.172146 -vn 4.992035 0.263090 2.999209 -v 0.007498 0.083936 0.172150 -vn 1.826036 0.454702 5.857243 -v 0.007495 0.084045 0.172144 -vn 1.958819 0.259647 5.694017 -v 0.007501 0.083936 0.172149 -vn 0.113027 -0.004771 6.274828 -v 0.007582 0.083827 0.172150 -vn 0.073749 0.803533 6.223266 -v 0.007564 0.084263 0.172123 -vn 4.205234 0.830138 2.656222 -v 0.007472 0.084263 0.172124 -vn 2.823923 1.106502 5.407251 -v 0.007468 0.084317 0.172115 -vn 5.004139 1.049877 2.734829 -v 0.007465 0.084317 0.172117 -vn 0.237030 1.217461 6.150624 -v 0.007460 0.084477 0.172089 -vn 0.879610 0.918594 6.032601 -v 0.007475 0.084263 0.172123 -vn 3.954462 0.692253 3.218709 -v 0.007483 0.084154 0.172136 -vn -0.060284 0.827866 6.225169 -v 0.007483 0.084263 0.172123 -vn -0.234164 0.837567 6.218826 -v 0.007478 0.084263 0.172123 -vn 6.118177 0.435734 0.297426 -v 0.007492 0.084045 0.172149 -vn 6.247167 0.618007 0.237428 -v 0.007483 0.084154 0.172140 -vn 6.222095 0.651974 -0.573450 -v 0.007472 0.084263 0.172130 -vn 6.200894 0.872528 -0.012399 -v 0.007465 0.084317 0.172121 -vn 6.126310 0.987091 0.313321 -v 0.007466 0.084317 0.172129 -vn 0.492106 1.097514 6.166464 -v 0.007456 0.084424 0.172099 -vn 1.651289 1.108842 5.958523 -v 0.007462 0.084370 0.172107 -vn 1.454333 1.276116 5.899343 -v 0.007452 0.084424 0.172099 -vn 3.406940 1.262235 4.762188 -v 0.007459 0.084370 0.172108 -vn 4.126564 1.400114 3.845359 -v 0.007449 0.084424 0.172100 -vn 5.605070 1.204946 1.986394 -v 0.007457 0.084370 0.172111 -vn 5.988681 1.168703 0.754022 -v 0.007447 0.084424 0.172103 -vn 6.171002 0.937911 -0.274148 -v 0.007457 0.084370 0.172114 -vn 6.083179 1.003354 0.203086 -v 0.007457 0.084370 0.172119 -vn -0.196556 1.521208 6.085016 -v 0.007408 0.084688 0.172042 -vn -0.457469 1.496192 6.085045 -v 0.007402 0.084688 0.172042 -vn 0.538410 1.562151 6.061251 -v 0.007412 0.084636 0.172055 -vn 0.475875 1.669222 5.968438 -v 0.007397 0.084688 0.172042 -vn 1.958624 1.845202 5.510372 -v 0.007407 0.084636 0.172056 -vn 0.046701 1.551273 6.086659 -v 0.007428 0.084688 0.172042 -vn 0.772268 1.457278 6.061714 -v 0.007425 0.084583 0.172067 -vn 1.699192 1.505478 5.797652 -v 0.007432 0.084530 0.172078 -vn 2.003004 1.677135 5.601666 -v 0.007420 0.084583 0.172068 -vn 4.103165 1.605796 3.903969 -v 0.007429 0.084530 0.172080 -vn 4.263803 1.854168 3.902699 -v 0.007418 0.084583 0.172069 -vn 5.904593 1.455768 1.227770 -v 0.007428 0.084530 0.172083 -vn 5.769132 1.630480 1.346205 -v 0.007416 0.084583 0.172072 -vn 6.115079 1.384809 0.348049 -v 0.007428 0.084530 0.172086 -vn -0.079340 1.222209 6.159713 -v 0.007450 0.084477 0.172089 -vn 0.318673 1.270553 6.131768 -v 0.007445 0.084477 0.172089 -vn 2.628340 1.462974 5.107221 -v 0.007440 0.084477 0.172089 -vn 5.353590 1.352967 1.971811 -v 0.007438 0.084477 0.172092 -vn 6.160959 1.023452 -0.568651 -v 0.007438 0.084477 0.172096 -vn 6.150802 1.030043 -0.627365 -v 0.007439 0.084477 0.172100 -vn 0.056906 1.560099 6.077736 -v 0.007509 0.084688 0.172042 -vn 5.987633 1.304883 0.770580 -v 0.007439 0.084477 0.172104 -vn 6.122673 1.401536 0.140824 -v 0.007416 0.084583 0.172076 -vn 6.079058 1.559979 0.065126 -v 0.007392 0.084688 0.172076 -vn 6.076797 1.490237 0.332584 -v 0.007404 0.084636 0.172061 -vn 0.019687 1.712758 6.015742 -v 0.007389 0.084792 0.172014 -vn 0.028801 1.659654 6.043994 -v 0.007387 0.084740 0.172028 -vn 3.487285 1.812765 4.030494 -v 0.007393 0.084688 0.172043 -vn 4.656940 1.823893 2.878601 -v 0.007404 0.084636 0.172057 -vn 2.302161 1.911450 5.118540 -v 0.007382 0.084740 0.172028 -vn 4.987706 1.892798 2.840415 -v 0.007380 0.084740 0.172030 -vn 5.850433 1.563188 0.887277 -v 0.007392 0.084688 0.172045 -vn 0.019221 2.245337 5.867023 -v 0.007340 0.085095 0.171912 -vn 0.016162 1.966166 5.966199 -v 0.007368 0.084894 0.171983 -vn 0.223722 1.970442 5.953152 -v 0.007388 0.084894 0.171983 -vn 0.275618 1.840444 5.992332 -v 0.007363 0.084843 0.171999 -vn 0.989072 2.032957 5.842803 -v 0.007358 0.084843 0.171999 -vn 3.013452 2.150041 4.935059 -v 0.007369 0.084792 0.172015 -vn 4.300037 2.307309 3.913829 -v 0.007367 0.084792 0.172017 -vn 5.909361 1.759111 1.188085 -v 0.007379 0.084740 0.172033 -vn 5.899347 1.883202 1.060470 -v 0.007379 0.084740 0.172037 -vn 6.100854 1.434613 -0.133292 -v 0.007392 0.084688 0.172054 -vn 1.934643 2.235567 5.509157 -v 0.007354 0.084843 0.172000 -vn 4.919003 2.358803 3.066351 -v 0.007365 0.084792 0.172019 -vn 5.939731 1.876014 0.765467 -v 0.007378 0.084740 0.172040 -vn 6.095431 1.517783 0.068233 -v 0.007392 0.084688 0.172061 -vn -0.038463 1.970676 5.962899 -v 0.007357 0.084894 0.171983 -vn 0.189342 2.071394 5.923036 -v 0.007347 0.084894 0.171983 -vn 3.123063 2.428984 4.769985 -v 0.007351 0.084843 0.172001 -vn 5.539662 2.187427 1.756883 -v 0.007364 0.084792 0.172022 -vn 5.998054 1.831530 0.379624 -v 0.007378 0.084740 0.172044 -vn 0.745350 2.191764 5.803117 -v 0.007325 0.084945 0.171966 -vn 2.366597 2.488614 5.127291 -v 0.007321 0.084945 0.171967 -vn 3.682407 2.472161 4.119955 -v 0.007335 0.084894 0.171985 -vn 5.440273 2.154711 1.681316 -v 0.007333 0.084894 0.171988 -vn 6.020473 1.739231 -0.117531 -v 0.007333 0.084894 0.171991 -vn 5.367445 2.484408 2.049509 -v 0.007317 0.084945 0.171972 -vn 4.314322 2.543624 3.522497 -v 0.007319 0.084945 0.171969 -vn 3.460225 2.641510 4.351001 -v 0.007312 0.084970 0.171960 -vn 5.932385 2.057505 -0.169793 -v 0.007298 0.084995 0.171960 -vn 5.938805 2.040670 -0.094364 -v 0.007316 0.084945 0.171982 -vn 5.736585 2.265462 0.697769 -v 0.007315 0.084945 0.171978 -vn 5.544506 2.496460 1.580796 -v 0.007316 0.084945 0.171975 -vn 0.123103 2.089414 5.912320 -v 0.007324 0.084995 0.171949 -vn 0.013966 2.268719 5.858973 -v 0.007299 0.085095 0.171912 -vn 0.235340 2.164189 5.878741 -v 0.007313 0.084995 0.171949 -vn 1.164165 2.377010 5.669998 -v 0.007309 0.084995 0.171949 -vn 1.460697 2.324749 5.541126 -v 0.007338 0.084894 0.171984 -vn 4.761621 2.390572 2.942685 -v 0.007349 0.084843 0.172004 -vn 5.950102 1.909280 0.549343 -v 0.007363 0.084792 0.172025 -vn 0.405721 2.487225 5.726707 -v 0.007254 0.085144 0.171892 -vn 0.173898 2.427689 5.787064 -v 0.007247 0.085168 0.171883 -vn 2.590588 2.860930 4.466319 -v 0.007246 0.085144 0.171894 -vn -0.060046 2.319213 5.838710 -v 0.007271 0.085119 0.171903 -vn 0.742167 2.439870 5.669161 -v 0.007261 0.085119 0.171902 -vn 3.673394 2.539774 3.397754 -v 0.007254 0.085119 0.171905 -vn 5.730521 2.353976 0.444281 -v 0.007252 0.085119 0.171911 -vn 5.418115 2.547273 1.267282 -v 0.007262 0.085095 0.171915 -vn 2.720195 2.670073 4.142683 -v 0.007263 0.085095 0.171913 -vn 5.852221 2.183900 -0.371230 -v 0.007243 0.085144 0.171907 -vn 1.422294 2.820518 5.266220 -v 0.007238 0.085168 0.171883 -vn 0.013383 2.484668 5.770763 -v 0.007251 0.085192 0.171873 -vn 0.590516 2.750033 5.577262 -v 0.007230 0.085192 0.171873 -vn 0.227759 2.585782 5.717793 -v 0.007223 0.085216 0.171862 -vn 2.858949 2.856328 3.709793 -v 0.007214 0.085216 0.171863 -vn 1.744964 2.957383 4.948813 -v 0.007206 0.085240 0.171852 -vn 4.639435 3.003190 2.071993 -v 0.007201 0.085240 0.171856 -vn 3.544693 2.924220 2.816393 -v 0.007191 0.085264 0.171843 -vn 0.019278 2.662553 5.690351 -v 0.007201 0.085288 0.171830 -vn 0.084095 2.559374 5.737399 -v 0.007216 0.085240 0.171852 -vn 5.750779 2.524301 0.047872 -v 0.007202 0.085240 0.171872 -vn 5.583642 2.665907 0.666577 -v 0.007212 0.085216 0.171869 -vn 5.783832 2.330862 -0.539634 -v 0.007202 0.085240 0.171864 -vn 5.755560 2.343342 -0.457759 -v 0.007201 0.085240 0.171860 -vn 5.556859 2.505585 0.586526 -v 0.007180 0.085288 0.171834 -vn 5.861673 2.218729 -0.172653 -v 0.007253 0.085119 0.171919 -vn 5.808925 2.391473 0.117513 -v 0.007243 0.085144 0.171923 -vn 5.768500 2.478270 0.146378 -v 0.007223 0.085192 0.171929 -vn 5.687307 2.668241 0.022331 -v 0.007180 0.085288 0.171877 -vn 4.994104 2.602210 1.331200 -v 0.007242 0.085144 0.171899 -vn 4.116682 2.528718 2.011487 -v 0.007232 0.085168 0.171886 -vn 3.452758 2.707718 2.624008 -v 0.007222 0.085192 0.171874 -vn 1.277456 3.058398 5.019538 -v 0.007130 0.085405 0.171773 -vn 3.579979 2.893229 2.382475 -v 0.007135 0.085382 0.171786 -vn 0.695495 3.176880 5.286870 -v 0.007139 0.085382 0.171785 -vn 4.959097 2.928319 1.067329 -v 0.007157 0.085335 0.171814 -vn 5.672702 2.697354 0.101595 -v 0.007180 0.085288 0.171842 -vn 5.759765 2.461129 -0.160933 -v 0.007180 0.085288 0.171838 -vn 3.575185 3.497347 3.657069 -v 0.007159 0.085335 0.171811 -vn 2.798423 3.302571 4.506361 -v 0.007162 0.085335 0.171809 -vn -0.031131 2.851501 5.597277 -v 0.007150 0.085382 0.171785 -vn -0.137112 2.817172 5.605221 -v 0.007134 0.085428 0.171762 -vn -0.011603 3.005682 5.516118 -v 0.007117 0.085474 0.171738 -vn 0.174729 2.950213 5.532624 -v 0.007115 0.085451 0.171750 -vn 0.019145 2.978790 5.530685 -v 0.007107 0.085474 0.171738 -vn 0.362564 3.107469 5.437981 -v 0.007096 0.085474 0.171738 -vn 4.204670 3.372509 2.705244 -v 0.007125 0.085405 0.171777 -vn 5.697359 2.647345 -0.032269 -v 0.007180 0.085288 0.171846 -vn 5.737540 2.473221 -0.441270 -v 0.007158 0.085335 0.171818 -vn 5.682295 2.666041 -0.126733 -v 0.007136 0.085382 0.171790 -vn 5.589921 2.772064 -0.254861 -v 0.007111 0.085428 0.171773 -vn 4.887476 3.360323 1.540823 -v 0.007112 0.085428 0.171769 -vn 5.455947 3.013438 0.496899 -v 0.007124 0.085405 0.171784 -vn 5.618956 2.751080 -0.333654 -v 0.007112 0.085428 0.171777 -vn 5.629810 2.789106 0.024316 -v 0.007135 0.085382 0.171806 -vn 5.619237 2.807216 0.039024 -v 0.007136 0.085382 0.171798 -vn 5.656847 2.692179 -0.426699 -v 0.007088 0.085474 0.171747 -vn 5.595568 2.810523 -0.347751 -v 0.007088 0.085474 0.171752 -vn 5.516388 2.998638 0.022228 -v 0.007088 0.085474 0.171756 -vn 0.091634 3.294785 5.346006 -v 0.007068 0.085651 0.171637 -vn 0.009971 3.012418 5.512626 -v 0.007138 0.085474 0.171738 -vn 0.027010 3.025097 5.500923 -v 0.007304 0.085474 0.171738 -vn 0.037449 2.770576 5.638031 -v 0.007170 0.085382 0.171786 -vn 1.207786 2.972986 5.218529 -v 0.007165 0.085335 0.171808 -vn 0.020081 2.639828 5.699174 -v 0.007366 0.085288 0.171830 -vn 0.040828 2.221780 5.872470 -v 0.007421 0.085095 0.171912 -vn 5.891010 2.175681 -0.064222 -v 0.007262 0.085095 0.171931 -vn 5.896464 2.147352 0.111803 -v 0.007279 0.085045 0.171938 -vn 3.763069 2.485079 2.824304 -v 0.007280 0.085045 0.171934 -vn 1.388218 2.715736 5.477103 -v 0.007283 0.085045 0.171933 -vn 2.387800 2.653959 5.107023 -v 0.007305 0.084995 0.171950 -vn 5.877984 2.214960 -0.001096 -v 0.007262 0.085095 0.171947 -vn 5.859024 2.262625 0.013502 -v 0.007262 0.085095 0.171977 -vn 5.846850 2.279840 0.059278 -v 0.007262 0.085095 0.172039 -vn 6.079085 1.540826 -0.000045 -v 0.007392 0.084688 0.172198 -vn 5.847293 2.268072 0.000000 -v 0.007262 0.085095 0.172286 -vn 5.615181 2.808549 0.130696 -v 0.007135 0.085382 0.171822 -vn 5.507659 3.021579 0.074409 -v 0.007088 0.085474 0.171763 -vn 0.044219 3.593800 5.144640 -v 0.007161 0.085820 0.171527 -vn -3.383440 0.631930 3.067048 -v 0.009500 0.084541 0.172076 -vn 0.147276 3.110122 5.454435 -v 0.007079 0.085519 0.171713 -vn 0.341765 3.171263 5.397497 -v 0.007074 0.085519 0.171713 -vn 1.511816 3.463585 4.918175 -v 0.007092 0.085474 0.171739 -vn 1.196489 3.443378 5.068613 -v 0.007069 0.085519 0.171714 -vn -0.097649 3.159769 5.427444 -v 0.007052 0.085564 0.171689 -vn 2.495851 3.748835 4.235140 -v 0.007066 0.085519 0.171715 -vn -0.026907 3.267026 5.359330 -v 0.007046 0.085564 0.171688 -vn 4.089978 3.727796 2.544960 -v 0.007063 0.085519 0.171717 -vn 1.328050 3.609412 4.760973 -v 0.007041 0.085564 0.171689 -vn 5.258808 3.189802 0.460937 -v 0.007063 0.085519 0.171721 -vn 0.023870 3.266982 5.366339 -v 0.007026 0.085651 0.171637 -vn -0.109426 3.215263 5.392611 -v 0.007006 0.085651 0.171637 -vn 0.230717 3.289824 5.339590 -v 0.007023 0.085608 0.171662 -vn 1.269263 3.598991 4.884237 -v 0.007018 0.085608 0.171663 -vn 3.896326 3.445752 2.422666 -v 0.007038 0.085564 0.171690 -vn 5.514850 2.844922 -0.127213 -v 0.007038 0.085564 0.171694 -vn 5.599427 2.816768 -0.418832 -v 0.007063 0.085519 0.171725 -vn 0.208543 3.159029 5.422957 -v 0.007062 0.085564 0.171689 -vn 5.488568 3.015984 -0.087140 -v 0.007039 0.085564 0.171703 -vn 5.625220 2.702602 -0.673248 -v 0.007039 0.085564 0.171698 -vn 4.503946 3.740128 1.829300 -v 0.007013 0.085608 0.171667 -vn 2.977856 3.880624 3.679501 -v 0.007015 0.085608 0.171664 -vn -0.000274 3.408216 5.247167 -v 0.006994 0.085651 0.171636 -vn -0.357598 3.201048 5.393841 -v 0.007000 0.085651 0.171637 -vn -0.126684 3.304774 5.331598 -v 0.006987 0.085694 0.171610 -vn 5.264565 3.364492 0.351313 -v 0.007012 0.085608 0.171670 -vn 2.094116 3.594790 4.236748 -v 0.006989 0.085651 0.171637 -vn 4.295846 3.570310 1.915744 -v 0.006987 0.085651 0.171639 -vn 2.766281 3.724732 3.314665 -v 0.006976 0.085673 0.171624 -vn 0.005856 3.616690 5.136283 -v 0.006950 0.085820 0.171527 -vn -0.034961 3.443665 5.254664 -v 0.006968 0.085737 0.171583 -vn 0.094208 3.464904 5.238725 -v 0.006989 0.085737 0.171583 -vn 5.365787 3.267399 0.031375 -v 0.006987 0.085651 0.171655 -vn 5.384218 3.237701 0.054912 -v 0.006987 0.085651 0.171647 -vn 4.930731 3.707498 0.987448 -v 0.006960 0.085694 0.171618 -vn 5.240042 3.446405 0.205595 -v 0.006960 0.085694 0.171621 -vn -0.037732 3.477735 5.230433 -v 0.006928 0.085778 0.171555 -vn 0.659933 3.607896 5.024920 -v 0.006916 0.085778 0.171555 -vn 1.223725 3.815504 4.625401 -v 0.006926 0.085758 0.171569 -vn -0.033438 3.478725 5.231911 -v 0.006947 0.085737 0.171583 -vn 0.418908 3.695177 5.024091 -v 0.006941 0.085737 0.171583 -vn 1.872794 4.062530 4.245526 -v 0.006937 0.085737 0.171583 -vn 3.539850 4.157417 2.834303 -v 0.006934 0.085737 0.171585 -vn 4.758280 3.826915 1.047616 -v 0.006933 0.085737 0.171588 -vn 3.590987 4.103000 2.659319 -v 0.006921 0.085758 0.171573 -vn 4.997747 3.676901 0.569341 -v 0.006919 0.085758 0.171579 -vn 3.412650 4.260784 2.956995 -v 0.006906 0.085778 0.171559 -vn 4.479486 4.000733 1.381681 -v 0.006905 0.085778 0.171562 -vn 2.073088 4.005243 4.253517 -v 0.006909 0.085778 0.171557 -vn 0.044003 3.652488 5.111753 -v 0.006908 0.085820 0.171527 -vn 5.293715 3.340770 -0.357322 -v 0.006905 0.085778 0.171570 -vn 5.233919 3.388012 -0.177437 -v 0.006904 0.085778 0.171566 -vn 4.486644 3.917942 1.223743 -v 0.006877 0.085820 0.171531 -vn 2.625417 4.245783 3.415461 -v 0.006878 0.085820 0.171529 -vn 1.817470 4.073191 3.986032 -v 0.006867 0.085840 0.171513 -vn 5.365480 3.268028 -0.008853 -v 0.006987 0.085651 0.171671 -vn 5.236713 3.459429 0.079216 -v 0.006933 0.085737 0.171604 -vn 5.267901 3.423518 -0.011727 -v 0.006933 0.085737 0.171596 -vn 5.110815 -2.578074 1.201388 -v 0.007242 0.082510 0.171899 -vn 3.127811 4.274021 2.710466 -v 0.006849 0.085860 0.171501 -vn 4.969175 3.678272 0.177082 -v 0.006848 0.085860 0.171508 -vn 4.275561 4.088738 1.488796 -v 0.006863 0.085840 0.171518 -vn 5.172583 3.557570 -0.090265 -v 0.006863 0.085840 0.171526 -vn 5.242406 3.450933 -0.244036 -v 0.006877 0.085820 0.171535 -vn 5.186203 3.518773 -0.147002 -v 0.006877 0.085820 0.171544 -vn 3.910484 4.042392 1.653952 -v 0.006819 0.085900 0.171473 -vn 4.536745 3.851353 0.820258 -v 0.006833 0.085880 0.171490 -vn 2.011863 4.224126 3.658375 -v 0.006836 0.085880 0.171485 -vn 5.175975 3.508801 -0.261875 -v 0.006849 0.085860 0.171517 -vn 5.127516 3.618009 -0.134232 -v 0.006820 0.085900 0.171481 -vn 4.702146 4.061129 0.658486 -v 0.006805 0.085920 0.171463 -vn 1.146432 4.090726 4.309729 -v 0.006825 0.085900 0.171469 -vn 0.743022 4.015261 4.670834 -v 0.006814 0.085920 0.171454 -vn 3.004604 4.327316 2.861666 -v 0.006807 0.085920 0.171456 -vn 0.034356 3.984484 4.855234 -v 0.006774 0.085979 0.171410 -vn 2.287036 4.322765 3.905803 -v 0.006795 0.085940 0.171441 -vn 0.135415 3.891389 4.930932 -v 0.006779 0.085979 0.171410 -vn 1.059284 4.046344 4.566840 -v 0.006798 0.085940 0.171439 -vn 5.053405 3.732464 0.057490 -v 0.006820 0.085900 0.171497 -vn 5.040606 3.750821 0.014117 -v 0.006820 0.085900 0.171489 -vn 5.064834 3.712907 -0.126412 -v 0.006805 0.085920 0.171471 -vn 3.448172 4.408639 2.516903 -v 0.006790 0.085940 0.171445 -vn 5.162853 3.580213 0.043031 -v 0.006877 0.085820 0.171552 -vn 5.153536 3.591878 0.028043 -v 0.006877 0.085820 0.171568 -vn -0.175552 3.687818 5.073931 -v 0.006836 0.085900 0.171470 -vn 0.042241 3.741801 5.047033 -v 0.006847 0.085900 0.171470 -vn -0.005704 3.847197 4.966592 -v 0.006826 0.085979 0.171410 -vn -0.016363 4.002930 4.842250 -v 0.006741 0.086055 0.171349 -vn -0.008085 3.980350 4.860212 -v 0.006720 0.086055 0.171349 -vn 0.250549 4.016597 4.808960 -v 0.006730 0.086036 0.171364 -vn 0.038379 4.015494 4.831683 -v 0.006784 0.086055 0.171349 -vn -0.096128 3.896396 4.924318 -v 0.006763 0.086017 0.171380 -vn 0.032728 3.825243 4.984124 -v 0.006784 0.085979 0.171410 -vn 0.063805 3.767803 5.027202 -v 0.006804 0.085940 0.171439 -vn 0.078308 3.723706 5.058263 -v 0.006868 0.085900 0.171470 -vn 0.080948 3.876875 4.940342 -v 0.006911 0.085979 0.171410 -vn 0.031863 4.197868 4.669542 -v 0.006826 0.086128 0.171287 -vn 0.771872 4.108002 4.533051 -v 0.006740 0.086017 0.171379 -vn 2.377166 4.660319 3.421698 -v 0.006734 0.086017 0.171382 -vn 1.465803 4.167280 3.911539 -v 0.006751 0.085998 0.171394 -vn 3.817700 4.499327 2.039004 -v 0.006747 0.085998 0.171399 -vn 3.904087 3.883238 1.315319 -v 0.006760 0.085979 0.171412 -vn 5.295798 3.266529 -0.795798 -v 0.006790 0.085940 0.171453 -vn 5.345647 3.293076 0.122839 -v 0.006987 0.085651 0.171702 -vn 0.821979 3.953747 4.734565 -v 0.006856 0.085860 0.171499 -vn 3.057822 4.445286 2.208889 -v 0.006714 0.086036 0.171368 -vn 4.488195 4.074749 0.742379 -v 0.006698 0.086055 0.171353 -vn 4.934104 3.774066 -0.270341 -v 0.006729 0.086017 0.171390 -vn 5.138300 3.526876 -0.793269 -v 0.006729 0.086017 0.171395 -vn 4.626015 4.134811 0.551999 -v 0.006745 0.085998 0.171406 -vn 3.798660 4.495696 1.600460 -v 0.006729 0.086017 0.171387 -vn 2.265937 4.369991 3.197059 -v 0.006700 0.086055 0.171350 -vn 0.673297 4.305265 4.453758 -v 0.006676 0.086092 0.171318 -vn 1.975564 4.616944 3.635454 -v 0.006672 0.086092 0.171319 -vn -0.125949 4.089170 4.765637 -v 0.006655 0.086128 0.171287 -vn -0.166294 4.142890 4.717008 -v 0.006649 0.086128 0.171287 -vn 5.081279 3.655904 -0.536909 -v 0.006699 0.086055 0.171358 -vn 4.451871 4.262447 0.860352 -v 0.006684 0.086073 0.171339 -vn 4.725249 4.131763 0.128891 -v 0.006684 0.086073 0.171347 -vn 4.607648 4.234347 0.306520 -v 0.006668 0.086092 0.171328 -vn 4.173771 4.478713 1.196477 -v 0.006668 0.086092 0.171324 -vn 3.226914 4.686390 2.473135 -v 0.006670 0.086092 0.171321 -vn 3.655398 4.651724 1.563782 -v 0.006637 0.086128 0.171290 -vn 4.739445 4.095556 -0.003786 -v 0.006636 0.086128 0.171298 -vn 4.909060 3.920723 0.009904 -v 0.006760 0.085979 0.171490 -vn 4.932293 3.892162 0.006830 -v 0.006760 0.085979 0.171457 -vn 4.814075 4.032457 0.111766 -v 0.006699 0.086055 0.171415 -vn 4.896484 3.935174 0.100973 -v 0.006730 0.086017 0.171420 -vn 4.962302 3.808492 -0.136480 -v 0.006731 0.086017 0.171404 -vn 4.900923 3.879913 -0.222487 -v 0.006700 0.086055 0.171367 -vn 4.786988 4.067898 0.087302 -v 0.006699 0.086055 0.171383 -vn 4.797947 4.042220 -0.177151 -v 0.006637 0.086128 0.171306 -vn 4.886700 3.925675 0.250774 -v 0.006760 0.085979 0.171554 -vn 4.778547 3.735870 0.196500 -v 0.006789 0.085940 0.171448 -vn 1.186004 4.290500 4.092252 -v 0.006762 0.085979 0.171410 -vn 4.707004 4.160363 0.015755 -v 0.006637 0.086128 0.171339 -vn 4.666812 4.201355 0.032056 -v 0.006637 0.086128 0.171405 -vn 0.165833 3.752500 5.035599 -v 0.006846 0.085880 0.171484 -vn 5.122205 3.630115 0.020989 -v 0.006877 0.085820 0.171696 -vn 5.144516 3.591994 0.026233 -v 0.006877 0.085820 0.171825 -vn -0.000827 4.106081 4.755571 -v 0.006740 0.086128 0.171287 -vn 0.251031 4.155595 4.698031 -v 0.006709 0.086055 0.171349 -vn 1.059636 4.431486 4.303933 -v 0.006721 0.086036 0.171365 -vn 0.006855 4.272829 4.604463 -v 0.006610 0.086199 0.171223 -vn -0.167618 4.145349 4.711704 -v 0.006633 0.086164 0.171256 -vn 0.358989 4.362572 4.480437 -v 0.006615 0.086164 0.171255 -vn 1.477022 4.701932 3.782315 -v 0.006611 0.086164 0.171255 -vn 2.491481 4.711930 2.913733 -v 0.006623 0.086146 0.171272 -vn 3.182642 4.802598 2.186987 -v 0.006605 0.086164 0.171259 -vn 4.212887 4.485635 0.828366 -v 0.006621 0.086146 0.171278 -vn 2.658808 4.837584 2.672403 -v 0.006574 0.086199 0.171225 -vn 2.180291 4.828905 3.011967 -v 0.006591 0.086182 0.171241 -vn 1.024645 4.614830 4.031270 -v 0.006578 0.086199 0.171223 -vn 0.479359 4.404255 4.419045 -v 0.006599 0.086182 0.171239 -vn 0.701854 4.519528 4.217063 -v 0.006566 0.086217 0.171207 -vn 0.051084 4.278425 4.598522 -v 0.006588 0.086199 0.171223 -vn 0.011467 4.307092 4.573221 -v 0.006565 0.086234 0.171191 -vn 0.122456 4.401550 4.480917 -v 0.006564 0.086268 0.171158 -vn 4.245746 4.544718 0.557362 -v 0.006556 0.086217 0.171216 -vn 4.090146 4.546308 0.761692 -v 0.006573 0.086199 0.171228 -vn 2.675265 4.827545 2.498469 -v 0.006558 0.086217 0.171210 -vn 2.197828 4.704126 3.015846 -v 0.006510 0.086268 0.171159 -vn 3.589152 4.779804 1.389976 -v 0.006540 0.086234 0.171196 -vn 2.254629 4.964971 2.939301 -v 0.006542 0.086234 0.171193 -vn 4.599762 4.275514 0.095447 -v 0.006573 0.086199 0.171261 -vn 4.699934 4.167899 -0.080525 -v 0.006604 0.086164 0.171267 -vn 4.601239 4.274655 0.012557 -v 0.006573 0.086199 0.171245 -vn 4.670605 4.188170 -0.151007 -v 0.006573 0.086199 0.171237 -vn 1.022823 4.664030 4.020789 -v 0.006545 0.086234 0.171192 -vn 0.239002 4.357509 4.511276 -v 0.006554 0.086234 0.171191 -vn -0.017599 4.349069 4.534112 -v 0.006543 0.086268 0.171159 -vn 1.947096 4.569077 3.469294 -v 0.006499 0.086284 0.171143 -vn 1.783979 4.464363 3.971219 -v 0.006490 0.086301 0.171128 -vn 0.912865 4.334784 4.280213 -v 0.006479 0.086334 0.171096 -vn 4.713969 4.135883 -0.366694 -v 0.006540 0.086234 0.171204 -vn 4.563446 4.313874 0.129754 -v 0.006508 0.086268 0.171165 -vn 4.531369 4.349285 -0.031033 -v 0.006508 0.086268 0.171182 -vn 4.334546 4.503534 0.457614 -v 0.006492 0.086284 0.171162 -vn 4.461818 4.403967 0.310622 -v 0.006442 0.086334 0.171168 -vn 4.576135 4.232622 -0.057266 -v 0.006539 0.086234 0.171200 -vn 4.035134 4.469403 1.117649 -v 0.006508 0.086268 0.171161 -vn 3.720763 4.655196 1.803474 -v 0.006495 0.086284 0.171148 -vn 4.042980 4.496856 1.352970 -v 0.006477 0.086301 0.171143 -vn 2.684086 4.714102 3.142621 -v 0.006420 0.086397 0.171054 -vn 1.784450 4.733471 3.699589 -v 0.006444 0.086397 0.171039 -vn 0.783238 4.757518 3.984340 -v 0.006474 0.086397 0.171028 -vn 4.062002 4.427406 1.259847 -v 0.006387 0.086397 0.171096 -vn 4.290874 4.565280 0.333532 -v 0.006375 0.086397 0.171222 -vn 4.424047 4.444309 0.228984 -v 0.006508 0.086268 0.171249 -vn 4.355147 4.397141 0.614964 -v 0.006604 0.086164 0.171263 -vn 0.007308 6.209172 0.855362 -v 0.007092 0.087296 0.169115 -vn 0.044943 4.128876 4.719832 -v 0.009054 0.086128 0.171287 -vn 0.000000 4.603044 4.264030 -v 0.007517 0.086397 0.171025 -vn 0.000011 5.094134 3.649321 -v 0.006987 0.086627 0.170750 -vn 0.103274 5.623947 2.753390 -v 0.006613 0.086973 0.170184 -vn 0.038159 6.007290 1.780239 -v 0.006628 0.087187 0.169629 -vn 0.259858 6.021070 1.726759 -v 0.006268 0.087187 0.169648 -vn 0.054203 4.632223 4.235894 -v 0.006645 0.086397 0.171025 -vn 0.501956 5.106382 3.604597 -v 0.006456 0.086627 0.170752 -vn 1.003564 5.631000 2.559658 -v 0.006144 0.086973 0.170252 -vn 1.890519 5.662935 1.916708 -v 0.005838 0.086973 0.170446 -vn 3.209820 5.100967 1.583163 -v 0.006161 0.086627 0.170938 -vn 2.519090 5.178824 2.483897 -v 0.006231 0.086627 0.170854 -vn 0.041355 5.086627 3.663529 -v 0.006631 0.086627 0.170750 -vn 0.526444 5.646533 2.669755 -v 0.006276 0.086973 0.170210 -vn 0.596057 6.018241 1.649265 -v 0.005978 0.087187 0.169722 -vn 0.000958 6.003824 1.783305 -v 0.007397 0.087187 0.169630 -vn 0.071178 6.213212 0.842692 -v 0.006310 0.087296 0.169123 -vn 0.209266 6.213365 0.811996 -v 0.005985 0.087296 0.169181 -vn 0.326535 6.213076 0.773845 -v 0.005707 0.087296 0.169275 -vn 0.880506 6.019228 1.514312 -v 0.005737 0.087187 0.169835 -vn 0.427886 6.213190 0.722345 -v 0.005464 0.087296 0.169398 -vn -3.415082 1.689893 2.630978 -v 0.009500 0.085635 0.171647 -vn -3.348753 1.939721 2.457971 -v 0.009500 0.085983 0.171407 -vn -3.310403 2.175060 2.255562 -v 0.009500 0.086238 0.171187 -vn -3.321098 2.424516 1.983456 -v 0.009500 0.086525 0.170880 -vn -0.048967 -6.203621 -0.867404 -v 0.006541 0.080358 0.168185 -vn -0.002720 -6.269227 -0.004829 -v 0.006817 0.080327 0.168650 -vn 0.089731 -6.218997 0.808742 -v 0.006310 0.080358 0.169123 -vn 0.200111 -6.217292 0.797487 -v 0.005985 0.080358 0.169181 -vn 0.318720 -6.214993 0.768525 -v 0.005707 0.080358 0.169275 -vn 0.423577 -6.213540 0.723232 -v 0.005464 0.080358 0.169398 -vn 0.532078 -6.214350 0.645350 -v 0.005250 0.080358 0.169544 -vn 0.660999 -6.214832 0.514286 -v 0.004897 0.080358 0.169896 -vn 0.877930 -6.017092 1.523780 -v 0.005737 0.080467 0.169835 -vn 1.124767 -6.015393 1.360113 -v 0.005533 0.080467 0.169978 -vn 1.321708 -6.014226 1.175553 -v 0.005360 0.080467 0.170145 -vn 1.488397 -6.017523 0.935525 -v 0.005217 0.080467 0.170336 -vn 2.276819 -5.659922 1.444328 -v 0.005691 0.080681 0.170622 -vn 2.530404 -5.677253 0.845936 -v 0.005588 0.080681 0.170831 -vn 2.698300 -5.656473 0.303880 -v 0.005536 0.080681 0.171081 -vn 1.604159 -6.023645 0.674831 -v 0.005103 0.080467 0.170550 -vn -3.099742 -4.204841 -3.417562 -v 0.003048 0.081525 0.167346 -vn -2.568201 -4.958884 -2.768255 -v 0.003366 0.081027 0.167783 -vn -1.924173 -5.592157 -2.005092 -v 0.003702 0.080681 0.168245 -vn -1.272739 -5.991360 -1.268630 -v 0.004030 0.080467 0.168698 -vn -0.639561 -6.201982 -0.601814 -v 0.004337 0.080358 0.169122 -vn -0.021953 -6.269564 -0.019512 -v 0.004615 0.080327 0.169507 -vn 0.772530 -6.216459 0.311254 -v 0.004639 0.080358 0.170325 -vn 1.794287 -6.005930 0.318524 -v 0.005023 0.080467 0.170791 -vn 2.845025 -5.582502 0.011220 -v 0.005534 0.080681 0.171370 -vn 2.773165 -5.610157 0.009335 -v 0.005534 0.080681 0.171950 -vn 3.649368 -5.094112 0.000069 -v 0.006100 0.081027 0.172548 -vn 3.649364 -5.094116 -0.000003 -v 0.006100 0.081027 0.173100 -vn 2.770418 -5.611135 0.000000 -v 0.005534 0.080681 0.173693 -vn 1.782411 -6.004045 -0.000001 -v 0.004980 0.080467 0.173192 -vn 1.783923 -6.003663 0.002583 -v 0.004980 0.080467 0.171974 -vn 0.763292 -6.228498 0.135793 -v 0.004488 0.080358 0.170839 -vn -0.029135 -6.269839 -0.015895 -v 0.004320 0.080327 0.169927 -vn -0.736343 -6.202324 -0.476562 -v 0.004011 0.080358 0.169539 -vn -1.456791 -5.992192 -1.050367 -v 0.003676 0.080467 0.169116 -vn -2.188555 -5.593416 -1.711576 -v 0.003321 0.080681 0.168667 -vn 3.671048 -5.080425 0.027345 -v 0.006100 0.081027 0.171443 -vn 4.263772 -4.603296 0.000211 -v 0.006375 0.081256 0.171760 -vn 4.731477 -4.119864 0.000031 -v 0.006637 0.081525 0.172062 -vn 4.263998 -4.603073 0.000010 -v 0.006375 0.081256 0.172299 -vn 3.649812 -5.093840 0.000009 -v 0.006100 0.081027 0.171995 -vn 3.650603 -5.093336 0.000920 -v 0.006100 0.081027 0.171719 -vn 4.731459 -4.119883 0.000001 -v 0.006637 0.081525 0.172587 -vn 5.160427 -3.566621 0.000000 -v 0.006877 0.081834 0.172852 -vn 5.160426 -3.566621 0.000000 -v 0.006877 0.081834 0.172338 -vn 5.536952 -2.946925 0.000000 -v 0.007088 0.082180 0.173084 -vn 4.263999 -4.603071 0.000000 -v 0.006375 0.081256 0.173376 -vn 4.731459 -4.119884 0.000000 -v 0.006637 0.081525 0.173639 -vn 5.160427 -3.566622 0.000000 -v 0.006877 0.081834 0.173879 -vn 5.536951 -2.946926 0.000000 -v 0.007088 0.082180 0.174090 -vn 5.847302 -2.268050 0.000000 -v 0.007262 0.082559 0.174264 -vn 5.847303 -2.268050 0.000000 -v 0.007262 0.082559 0.173275 -vn 1.741710 -6.024023 0.086501 -v 0.004980 0.080467 0.171365 -vn 2.770427 -5.611126 -0.000064 -v 0.005534 0.080681 0.172531 -vn 3.649365 -5.094114 0.000000 -v 0.006100 0.081027 0.174205 -vn -0.858804 -6.208282 0.000168 -v 0.003535 0.080358 0.171880 -vn 0.000038 -6.269272 0.000001 -v 0.004000 0.080327 0.172302 -vn 0.859133 -6.208214 -0.000002 -v 0.004465 0.080358 0.172724 -vn 6.079084 -1.540839 0.000000 -v 0.007392 0.082965 0.172442 -vn 6.079083 -1.540839 0.000000 -v 0.007392 0.082965 0.173418 -vn 6.222432 -0.779316 0.000000 -v 0.007473 0.083391 0.173506 -vn 6.222433 -0.779316 0.000000 -v 0.007473 0.083391 0.174474 -vn 6.270949 0.000000 0.000000 -v 0.007500 0.083827 0.174501 -vn 6.270895 -0.000872 0.001288 -v 0.007500 0.083827 0.176431 -vn 6.222434 0.779310 -0.000008 -v 0.007473 0.084263 0.176409 -vn 6.228011 0.744953 0.020734 -v 0.007473 0.084263 0.172176 -vn 6.222431 0.779320 -0.000004 -v 0.007473 0.084263 0.172297 -vn 6.079084 1.540839 0.000000 -v 0.007392 0.084688 0.172442 -vn 5.847293 2.268072 0.000000 -v 0.007262 0.085095 0.173275 -vn 0.013870 3.597730 5.148888 -v 0.006992 0.085820 0.171527 -vn 4.695303 4.165034 0.026149 -v 0.006637 0.086128 0.171536 -vn 4.731506 4.119835 0.000058 -v 0.006637 0.086128 0.171799 -vn 5.160442 3.566596 0.000000 -v 0.006877 0.085820 0.172338 -vn 6.222433 -0.779316 0.000000 -v 0.007473 0.083391 0.172297 -vn 6.222432 -0.779316 0.000000 -v 0.007473 0.083391 0.172538 -vn 6.270949 -0.000000 0.000000 -v 0.007500 0.083827 0.172571 -vn 6.270948 -0.000000 0.000000 -v 0.007500 0.083827 0.173536 -vn 6.222432 0.779316 0.000000 -v 0.007473 0.084263 0.173506 -vn 6.222432 0.779316 0.000000 -v 0.007473 0.084263 0.174474 -vn 6.079083 1.540839 0.000000 -v 0.007392 0.084688 0.174393 -vn 6.079085 1.540843 -0.000007 -v 0.007392 0.084688 0.176345 -vn 5.847493 2.267633 -0.000546 -v 0.007262 0.085095 0.176241 -vn 5.536957 2.946921 0.000000 -v 0.007088 0.085474 0.172581 -vn 5.160442 3.566596 0.000000 -v 0.006877 0.085820 0.172852 -vn 5.536957 2.946921 0.000000 -v 0.007088 0.085474 0.173084 -vn 5.160441 3.566595 0.000000 -v 0.006877 0.085820 0.173879 -vn 4.728452 4.122969 0.004009 -v 0.006637 0.086128 0.175741 -vn 4.731458 4.119884 0.000000 -v 0.006637 0.086128 0.173639 -vn 4.731458 4.119884 0.000000 -v 0.006637 0.086128 0.172587 -vn 4.731462 4.119880 0.000003 -v 0.006637 0.086128 0.172062 -vn 6.270977 0.000327 0.001050 -v 0.007500 0.083827 0.172209 -vn 6.270949 -0.000000 0.000000 -v 0.007500 0.083827 0.172330 -vn 6.222432 0.779316 0.000000 -v 0.007473 0.084263 0.172538 -vn 6.079084 1.540839 0.000000 -v 0.007392 0.084688 0.173418 -vn 5.847293 2.268072 0.000000 -v 0.007262 0.085095 0.174264 -vn 5.536957 2.946921 0.000000 -v 0.007088 0.085474 0.174090 -vn 5.161251 3.565259 0.003674 -v 0.006877 0.085820 0.175933 -vn 0.653240 6.215850 0.507611 -v 0.004897 0.087296 0.169896 -vn 1.455824 6.036580 0.894733 -v 0.005217 0.087187 0.170336 -vn 1.295382 6.029124 1.139799 -v 0.005360 0.087187 0.170145 -vn 2.491304 5.700080 0.835124 -v 0.005588 0.086973 0.170831 -vn 2.203740 5.712686 1.380322 -v 0.005691 0.086973 0.170622 -vn 3.786526 5.004299 0.041978 -v 0.006100 0.086627 0.171443 -vn 3.897685 4.881931 0.444344 -v 0.006100 0.086627 0.171167 -vn 4.264097 4.602867 -0.001041 -v 0.006375 0.086397 0.171491 -vn 4.434306 4.175041 1.090418 -v 0.006444 0.086334 0.171137 -vn 3.225872 4.781266 2.441688 -v 0.006402 0.086397 0.171074 -vn 1.115863 6.022061 1.342250 -v 0.005533 0.087187 0.169978 -vn -0.031872 6.268537 -0.012345 -v 0.004320 0.087327 0.169927 -vn 0.752334 6.216566 0.335066 -v 0.004639 0.087296 0.170325 -vn 1.580587 6.063319 0.368970 -v 0.005023 0.087187 0.170791 -vn 1.519269 6.053805 0.653092 -v 0.005103 0.087187 0.170550 -vn 2.788482 5.605641 0.056249 -v 0.005534 0.086973 0.171370 -vn 2.778442 5.622339 0.305013 -v 0.005536 0.086973 0.171081 -vn 3.649800 5.093846 0.000917 -v 0.006100 0.086627 0.171995 -vn 3.662409 5.085890 0.017852 -v 0.006100 0.086627 0.171719 -vn 4.264002 4.603068 0.000007 -v 0.006375 0.086397 0.172299 -vn 4.263895 4.603172 0.000184 -v 0.006375 0.086397 0.171760 -vn 4.263999 4.603071 0.000000 -v 0.006375 0.086397 0.173376 -vn 3.649359 5.094118 -0.000004 -v 0.006100 0.086627 0.172548 -vn 2.770165 5.611282 0.000334 -v 0.005534 0.086973 0.171950 -vn 1.767756 6.011027 0.061314 -v 0.004980 0.087187 0.171365 -vn 0.812563 6.216934 0.127952 -v 0.004488 0.087296 0.170839 -vn -0.044168 6.267889 -0.005498 -v 0.004110 0.087327 0.170416 -vn -0.753440 6.197787 -0.477474 -v 0.004011 0.087296 0.169539 -vn -1.282617 5.987264 -1.266359 -v 0.004030 0.087187 0.168698 -vn -1.623637 5.589204 -2.257099 -v 0.004146 0.086973 0.167875 -vn 4.938820 -3.883978 -0.002058 -v 0.006760 0.081675 0.171457 -vn 0.627554 -4.283178 4.493262 -v 0.006676 0.081562 0.171318 -vn 0.859131 6.208214 -0.000002 -v 0.004465 0.087296 0.172724 -vn 1.782411 6.004045 0.000000 -v 0.004980 0.087187 0.173192 -vn 2.770418 5.611135 0.000000 -v 0.005534 0.086973 0.173693 -vn 3.649365 5.094114 0.000000 -v 0.006100 0.086627 0.174205 -vn 3.649365 5.094114 0.000000 -v 0.006100 0.086627 0.173100 -vn 2.770426 5.611131 -0.000022 -v 0.005534 0.086973 0.172531 -vn 1.782505 6.004005 -0.000226 -v 0.004980 0.087187 0.171974 -vn 0.854689 6.209310 0.013506 -v 0.004465 0.087296 0.171455 -vn -0.001169 6.269227 -0.002121 -v 0.004000 0.087327 0.171644 -vn -0.039940 6.267864 0.000421 -v 0.004005 0.087327 0.170990 -vn -0.909560 6.188217 -0.160695 -v 0.003594 0.087296 0.170564 -vn -0.839651 6.194469 -0.331431 -v 0.003760 0.087296 0.170017 -vn -1.625799 5.980191 -0.799553 -v 0.003390 0.087187 0.169589 -vn -1.470642 5.984716 -1.048024 -v 0.003676 0.087187 0.169116 -vn -2.197846 5.585073 -1.706210 -v 0.003321 0.086973 0.168667 -vn -1.932552 5.587498 -2.000156 -v 0.003702 0.086973 0.168245 -vn -2.574340 4.955068 -2.761431 -v 0.003366 0.086627 0.167783 -vn -2.191089 4.956232 -3.074871 -v 0.003831 0.086627 0.167404 -vn -2.658555 4.212316 -3.761620 -v 0.003532 0.086128 0.166958 -vn 1.782060 -6.004180 -0.001100 -v 0.004980 0.080467 0.174409 -vn 2.529080 -5.116274 2.602828 -v 0.006231 0.081027 0.170854 -vn -3.218323 -3.130507 0.239165 -v 0.009500 0.080341 0.168964 -vn 2.094243 -1.360349 2.356195 -v 0.014500 0.081806 0.172150 -vn -2.094247 -1.360349 2.356195 -v 0.009500 0.081806 0.172150 -vn 0.056797 -5.455593 3.114654 -v 0.014500 0.080795 0.170400 -vn 2.094423 -2.720696 0.000001 -v 0.014500 0.079785 0.168650 -vn -2.094421 -2.720700 0.000008 -v 0.009500 0.079785 0.168650 -vn 2.094374 1.360350 2.356194 -v 0.014500 0.085848 0.172150 -vn -2.094432 1.360350 2.356194 -v 0.009500 0.085848 0.172150 -vn 0.053989 0.062496 6.281542 -v 0.014500 0.083827 0.172150 -vn 2.094431 2.720702 0.000005 -v 0.014500 0.087868 0.168650 -vn -2.094475 2.720706 0.000011 -v 0.009500 0.087868 0.168650 -vn 0.058199 5.438035 3.145197 -v 0.014500 0.086858 0.170400 -vn -2.094789 1.360345 -2.356256 -v 0.009500 0.085848 0.165150 -vn -2.094039 -1.360344 -2.356205 -v 0.009500 0.081806 0.165150 -vn 3.242991 2.612552 1.738797 -v 0.014500 0.086774 0.170537 -vn 3.272705 0.644623 3.068393 -v 0.014500 0.084541 0.172076 -vn 3.252864 0.291579 3.123555 -v 0.014500 0.084125 0.172137 -vn 3.257618 0.979651 2.979800 -v 0.014500 0.084950 0.171965 -vn 3.245082 1.304671 2.853007 -v 0.014500 0.085262 0.171842 -vn 3.233406 1.583373 2.709634 -v 0.014500 0.085635 0.171647 -vn 3.227058 2.143002 2.293595 -v 0.014500 0.086238 0.171187 -vn 3.201755 2.301196 2.136627 -v 0.014500 0.086397 0.171025 -vn 3.237303 2.454657 1.955429 -v 0.014500 0.086525 0.170880 -vn 3.202151 1.784891 2.583549 -v 0.014500 0.085820 0.171527 -vn 3.222054 1.959396 2.452586 -v 0.014500 0.085984 0.171406 -vn 3.206707 -0.120006 3.137618 -v 0.014500 0.083789 0.172150 -vn 3.255205 -2.263561 2.170699 -v 0.014500 0.081300 0.171072 -vn 3.243590 -2.000925 2.416260 -v 0.014500 0.081611 0.171359 -vn 3.209109 -2.654588 1.677176 -v 0.014500 0.080839 0.170473 -vn 3.243575 -2.498281 1.897584 -v 0.014500 0.081028 0.170751 -vn 3.245480 -1.728127 2.618320 -v 0.014500 0.081881 0.171559 -vn 3.255909 -1.418198 2.797134 -v 0.014500 0.082244 0.171772 -vn 3.257652 -1.081586 2.944418 -v 0.014500 0.082633 0.171940 -vn 3.258328 -0.768289 3.041131 -v 0.014500 0.082954 0.172039 -vn 3.262396 -0.413302 3.108516 -v 0.014500 0.083366 0.172120 -vn 3.231298 2.819904 1.377964 -v 0.014500 0.086942 0.170246 -vn 3.265481 2.940133 1.090205 -v 0.014500 0.087111 0.169860 -vn 3.249207 3.049043 0.737975 -v 0.014500 0.087233 0.169455 -vn 3.270573 3.111611 0.390344 -v 0.014500 0.087294 0.169124 -vn 3.288733 3.134035 0.068248 -v 0.014500 0.087326 0.168706 -vn 3.251532 3.121048 -0.315242 -v 0.014500 0.087307 0.168282 -vn 3.237011 3.077787 -0.613387 -v 0.014500 0.087256 0.167950 -vn 3.201300 3.023757 -0.847143 -v 0.014500 0.087187 0.167670 -vn 3.228421 2.955662 -1.056903 -v 0.014500 0.087147 0.167544 -vn 3.213905 2.874123 -1.263872 -v 0.014500 0.086989 0.167151 -vn 3.181238 2.803026 -1.417287 -v 0.014500 0.086973 0.167116 -vn 0.046566 5.460299 -3.106835 -v 0.014500 0.086858 0.166900 -vn 3.258568 0.369577 -3.114310 -v 0.014500 0.084231 0.165174 -vn 0.109811 0.007510 -6.278512 -v 0.014500 0.083827 0.165150 -vn 2.094211 1.360349 -2.356196 -v 0.014500 0.085848 0.165150 -vn 3.233267 2.647520 -1.686762 -v 0.014500 0.086832 0.166856 -vn 3.272306 2.487208 -1.908921 -v 0.014500 0.086595 0.166508 -vn 3.246828 2.243887 -2.192387 -v 0.014500 0.086316 0.166189 -vn 3.245911 1.993269 -2.422477 -v 0.014500 0.086067 0.165961 -vn 3.260757 1.703894 -2.632801 -v 0.014500 0.085728 0.165712 -vn 3.251364 1.386995 -2.813619 -v 0.014500 0.085360 0.165504 -vn 3.251427 1.090018 -2.941906 -v 0.014500 0.085050 0.165371 -vn 3.201825 0.846394 -3.023950 -v 0.014500 0.084688 0.165258 -vn 3.210570 0.651375 -3.071486 -v 0.014500 0.084648 0.165248 -vn 0.089984 -5.418458 -3.174292 -v 0.014500 0.080796 0.166900 -vn 2.094389 -1.360347 -2.355838 -v 0.014500 0.081806 0.165150 -vn 3.212488 -2.550575 -1.830510 -v 0.014500 0.081028 0.166549 -vn 3.231192 -2.399293 -2.023881 -v 0.014500 0.081094 0.166463 -vn 3.268059 -0.338209 -3.117738 -v 0.014500 0.083477 0.165168 -vn 3.267695 -0.656256 -3.066869 -v 0.014500 0.083059 0.165235 -vn 3.257693 -1.655126 -2.664485 -v 0.014500 0.081971 0.165682 -vn 3.257027 -1.916739 -2.483025 -v 0.014500 0.081696 0.165874 -vn 3.275456 -2.203607 -2.230367 -v 0.014500 0.081378 0.166149 -vn 3.253028 -1.002586 -2.972349 -v 0.014500 0.082733 0.165325 -vn 3.261759 -1.324133 -2.842607 -v 0.014500 0.082343 0.165480 -vn 0.000000 0.000000 -6.283185 -v 0.011679 0.083827 0.165150 -vn 0.000077 0.001754 -6.283183 -v 0.011621 0.083831 0.165150 -vn 0.000070 0.003336 -6.283185 -v 0.011406 0.083835 0.165150 -vn 0.000053 0.004114 -6.283183 -v 0.011287 0.083837 0.165150 -vn -0.000073 0.001367 -6.283183 -v 0.010543 0.083833 0.165150 -vn -0.000007 -0.000000 -6.283185 -v 0.010475 0.083827 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.011677 0.083828 0.165150 -vn -0.000076 0.000527 -6.283184 -v 0.010501 0.083831 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.010481 0.083829 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.011673 0.083826 0.165150 -vn 0.000000 0.000000 0.000001 -v 0.010476 0.083826 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.010479 0.083825 0.165150 -vn -0.000074 -0.000377 -6.283183 -v 0.010500 0.083823 0.165150 -vn -0.000079 -0.001465 -6.283176 -v 0.010543 0.083820 0.165150 -vn 0.000077 -0.005087 -6.283181 -v 0.011233 0.083816 0.165150 -vn 0.000086 -0.002722 -6.283184 -v 0.011568 0.083822 0.165150 -vn 0.000075 -0.000414 -6.283174 -v 0.011652 0.083824 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.011675 0.083828 0.165150 -vn 0.000007 0.000000 -6.283185 -v 0.011672 0.083828 0.165150 -vn 0.000078 0.000984 -6.283186 -v 0.011668 0.083828 0.165150 -vn 3.243159 -3.050653 -0.731921 -v 0.014500 0.080428 0.167814 -vn 3.258556 -3.113486 -0.375465 -v 0.014500 0.080352 0.168227 -vn 3.277384 -3.135700 -0.000514 -v 0.014500 0.080327 0.168650 -vn 3.230500 -2.832084 -1.352157 -v 0.014500 0.080688 0.167102 -vn 3.242822 -2.954268 -1.055771 -v 0.014500 0.080524 0.167491 -vn 3.293192 -3.122667 0.282275 -v 0.014500 0.080341 0.168965 -vn 3.239682 -3.076578 0.617302 -v 0.014500 0.080404 0.169381 -vn 3.237560 -3.002940 0.910616 -v 0.014500 0.080465 0.169625 -vn 3.226612 -2.908724 1.179416 -v 0.014500 0.080607 0.170021 -vn 3.201330 -2.815896 1.389755 -v 0.014500 0.080681 0.170184 -vn -0.000027 0.006067 -6.283242 -v 0.011077 0.083828 0.165150 -vn -0.000079 -0.000632 -6.283185 -v 0.010488 0.083825 0.165150 -vn -0.000045 -0.007920 -6.283156 -v 0.011077 0.083823 0.165150 -vn 3.049462 2.707482 1.586648 -v 0.016500 0.086878 0.170365 -vn 3.020297 2.525999 1.859474 -v 0.016500 0.086627 0.170750 -vn 3.063105 -0.190437 -3.133533 -v 0.016500 0.083571 0.165159 -vn 2.987378 -1.557555 -2.716273 -v 0.016500 0.082139 0.165584 -vn 3.026528 -1.162882 -2.913359 -v 0.016500 0.082559 0.165388 -vn 3.043071 2.846953 1.319639 -v 0.016500 0.086973 0.170184 -vn 2.952956 -2.038343 -2.370333 -v 0.016500 0.081545 0.165996 -vn 3.004550 -0.837708 -3.020832 -v 0.016500 0.082825 0.165296 -vn 3.027671 -0.483371 -3.099328 -v 0.016500 0.083391 0.165177 -vn 3.066061 -3.072572 -0.644096 -v 0.016500 0.080401 0.167933 -vn 3.053408 -3.005829 -0.902254 -v 0.016500 0.080467 0.167670 -vn 3.075556 2.387098 2.040287 -v 0.016500 0.086447 0.170971 -vn 3.059517 -2.912278 -1.170920 -v 0.016500 0.080595 0.167306 -vn 3.046541 -2.793407 -1.429169 -v 0.016500 0.080681 0.167116 -vn 3.052319 -2.635466 -1.703789 -v 0.016500 0.080931 0.166684 -vn 3.109868 -2.527287 -1.865461 -v 0.016500 0.081027 0.166550 -vn 3.037136 -2.389119 -2.033135 -v 0.016500 0.081061 0.166506 -vn 3.044523 -2.997286 0.928649 -v 0.016500 0.080467 0.169630 -vn 3.002565 -3.082188 0.565789 -v 0.016500 0.080411 0.169415 -vn 3.036159 -1.834512 2.544455 -v 0.016500 0.081727 0.171450 -vn 3.045645 -2.094000 2.336797 -v 0.016500 0.081525 0.171287 -vn 3.047297 2.222953 2.214524 -v 0.016500 0.086397 0.171025 -vn 3.030350 -2.338552 2.090031 -v 0.016500 0.081205 0.170969 -vn 2.966572 -3.128671 0.069481 -v 0.016500 0.080327 0.168650 -vn 3.039200 -3.115367 -0.371598 -v 0.016500 0.080358 0.168185 -vn 3.048920 2.135001 -2.299533 -v 0.016500 0.086128 0.166013 -vn 3.045377 2.367502 -2.058990 -v 0.016500 0.086534 0.166431 -vn 3.029345 2.571273 -1.796726 -v 0.016500 0.086627 0.166550 -vn 2.989814 2.981810 0.958221 -v 0.016500 0.087148 0.169755 -vn 3.017179 -2.579684 1.781235 -v 0.016500 0.080973 0.170676 -vn 3.049509 -2.778315 1.458564 -v 0.016500 0.080681 0.170184 -vn 3.058882 -2.899453 1.202239 -v 0.016500 0.080626 0.170066 -vn 3.039303 0.075376 -3.136698 -v 0.016500 0.083912 0.165151 -vn 3.029310 0.410641 -3.109676 -v 0.016500 0.084263 0.165177 -vn 2.979678 0.837754 -3.016021 -v 0.016500 0.084689 0.165258 -vn 3.046124 -1.543040 2.732091 -v 0.016500 0.082180 0.171738 -vn 3.039824 1.964634 2.445817 -v 0.016500 0.085925 0.171451 -vn 3.044445 1.704961 2.633891 -v 0.016500 0.085820 0.171527 -vn 2.953406 1.420818 -2.783626 -v 0.016500 0.085434 0.165541 -vn 3.034380 1.878567 -2.511640 -v 0.016500 0.086032 0.165932 -vn 3.033332 1.070218 2.948790 -v 0.016500 0.085095 0.171912 -vn 3.009437 0.723852 3.050531 -v 0.016500 0.084590 0.172066 -vn 3.024689 0.371949 3.114454 -v 0.016500 0.084263 0.172123 -vn 3.031573 -0.365657 3.115668 -v 0.016500 0.083391 0.172123 -vn 2.992546 -0.748038 3.041739 -v 0.016500 0.083096 0.172073 -vn 3.017529 -1.213553 2.890213 -v 0.016500 0.082341 0.171819 -vn 2.964165 2.794519 -1.406331 -v 0.016500 0.086948 0.167067 -vn 2.965789 3.011994 -0.843092 -v 0.016500 0.087198 0.167709 -vn 2.952995 3.101921 0.393361 -v 0.016500 0.087295 0.169121 -vn 2.951780 3.118416 -0.219437 -v 0.016500 0.087317 0.168382 -vn 3.032934 1.391462 2.810988 -v 0.016500 0.085300 0.171825 -vn 3.018414 0.001072 3.135543 -v 0.016500 0.083827 0.172150 -vn -3.128191 0.000000 2.956794 -v -0.000330 -0.083827 0.184150 -vn -3.074928 -0.574803 -2.956792 -v -0.000258 -0.084608 0.174150 -vn -3.074928 -0.574803 2.956793 -v -0.000258 -0.084608 0.184150 -vn -2.916951 -1.130034 -2.956793 -v -0.000043 -0.085362 0.174150 -vn -2.916951 -1.130034 2.956793 -v -0.000043 -0.085362 0.184150 -vn -2.659642 -1.646780 -2.956794 -v 0.000307 -0.086064 0.174150 -vn -2.659642 -1.646779 2.956794 -v 0.000307 -0.086064 0.184150 -vn -2.311759 -2.107450 -2.956790 -v 0.000779 -0.086690 0.174150 -vn -2.311759 -2.107450 2.956790 -v 0.000779 -0.086690 0.184150 -vn -1.885159 -2.496350 -2.956799 -v 0.001359 -0.087218 0.174150 -vn -1.885159 -2.496349 2.956799 -v 0.001359 -0.087218 0.184150 -vn -1.394362 -2.800238 -2.956790 -v 0.002026 -0.087631 0.174150 -vn -1.394362 -2.800238 2.956791 -v 0.002026 -0.087631 0.184150 -vn -0.856068 -3.008774 -2.956789 -v 0.002757 -0.087915 0.174150 -vn -0.856068 -3.008774 2.956789 -v 0.002757 -0.087915 0.184150 -vn -0.288628 -3.114847 -2.956796 -v 0.003528 -0.088059 0.174150 -vn -0.288628 -3.114848 2.956796 -v 0.003528 -0.088059 0.184150 -vn 0.288628 -3.114848 -2.956796 -v 0.004312 -0.088059 0.174150 -vn 0.288628 -3.114847 2.956796 -v 0.004312 -0.088059 0.184150 -vn 0.856068 -3.008774 -2.956789 -v 0.005083 -0.087915 0.174150 -vn 0.856068 -3.008774 2.956789 -v 0.005083 -0.087915 0.184150 -vn 1.394360 -2.800239 -2.956792 -v 0.005814 -0.087631 0.174150 -vn 1.394360 -2.800238 2.956792 -v 0.005814 -0.087631 0.184150 -vn 1.885159 -2.496348 -2.956796 -v 0.006481 -0.087218 0.174150 -vn 1.885159 -2.496349 2.956796 -v 0.006481 -0.087218 0.184150 -vn 2.311761 -2.107448 -2.956791 -v 0.007061 -0.086690 0.174150 -vn 2.311761 -2.107448 2.956791 -v 0.007061 -0.086690 0.184150 -vn 2.659642 -1.646779 -2.956795 -v 0.007533 -0.086064 0.174150 -vn 2.659642 -1.646780 2.956794 -v 0.007533 -0.086064 0.184150 -vn 2.916951 -1.130034 -2.956793 -v 0.007883 -0.085362 0.174150 -vn 2.916951 -1.130034 2.956793 -v 0.007883 -0.085362 0.184150 -vn 3.074928 -0.574803 -2.956792 -v 0.008098 -0.084608 0.174150 -vn 3.074928 -0.574803 2.956792 -v 0.008098 -0.084608 0.184150 -vn 3.128191 0.000000 -2.956794 -v 0.008170 -0.083827 0.174150 -vn 3.128191 0.000000 2.956794 -v 0.008170 -0.083827 0.184150 -vn 3.074928 0.574803 -2.956792 -v 0.008098 -0.083046 0.174150 -vn 3.074928 0.574803 2.956793 -v 0.008098 -0.083046 0.184150 -vn 2.916951 1.130034 -2.956793 -v 0.007883 -0.082292 0.174150 -vn 2.916951 1.130034 2.956793 -v 0.007883 -0.082292 0.184150 -vn 2.659642 1.646780 -2.956794 -v 0.007533 -0.081589 0.174150 -vn 2.659642 1.646779 2.956794 -v 0.007533 -0.081589 0.184150 -vn 2.311761 2.107448 -2.956791 -v 0.007061 -0.080964 0.174150 -vn 2.311761 2.107448 2.956791 -v 0.007061 -0.080964 0.184150 -vn 1.885159 2.496349 -2.956796 -v 0.006481 -0.080435 0.174150 -vn 1.885159 2.496348 2.956797 -v 0.006481 -0.080435 0.184150 -vn 1.394360 2.800238 -2.956792 -v 0.005814 -0.080022 0.174150 -vn 1.394360 2.800239 2.956792 -v 0.005814 -0.080022 0.184150 -vn 0.856068 3.008774 -2.956789 -v 0.005083 -0.079739 0.174150 -vn 0.856068 3.008774 2.956789 -v 0.005083 -0.079739 0.184150 -vn 0.288628 3.114847 -2.956796 -v 0.004312 -0.079595 0.174150 -vn 0.288628 3.114848 2.956796 -v 0.004312 -0.079595 0.184150 -vn -0.288628 3.114848 -2.956796 -v 0.003528 -0.079595 0.174150 -vn -0.288628 3.114847 2.956796 -v 0.003528 -0.079595 0.184150 -vn -0.856068 3.008774 -2.956789 -v 0.002757 -0.079739 0.174150 -vn -0.856068 3.008774 2.956789 -v 0.002757 -0.079739 0.184150 -vn -1.394362 2.800238 -2.956790 -v 0.002026 -0.080022 0.174150 -vn -1.394362 2.800238 2.956790 -v 0.002026 -0.080022 0.184150 -vn -1.885159 2.496349 -2.956799 -v 0.001359 -0.080435 0.174150 -vn -1.885159 2.496350 2.956799 -v 0.001359 -0.080435 0.184150 -vn -2.311759 2.107450 -2.956790 -v 0.000779 -0.080964 0.174150 -vn -2.311759 2.107450 2.956790 -v 0.000779 -0.080964 0.184150 -vn -2.659642 1.646779 -2.956794 -v 0.000307 -0.081589 0.174150 -vn -2.659642 1.646780 2.956795 -v 0.000307 -0.081589 0.184150 -vn -2.916951 1.130034 -2.956793 -v -0.000043 -0.082292 0.174150 -vn -2.916951 1.130034 2.956793 -v -0.000043 -0.082292 0.184150 -vn -3.074928 0.574803 -2.956792 -v -0.000258 -0.083046 0.174150 -vn -3.074928 0.574803 2.956793 -v -0.000258 -0.083046 0.184150 -vn -3.128191 0.000000 -2.956794 -v -0.000330 -0.083827 0.174150 -vn -0.996657 2.969503 -3.295502 -v 0.005112 -0.087145 0.174150 -vn -1.448273 2.776519 -3.301628 -v 0.005610 -0.086934 0.174150 -vn -1.873580 2.509049 -3.302787 -v 0.006100 -0.086627 0.174150 -vn -2.248242 2.180360 -3.299040 -v 0.006512 -0.086264 0.174150 -vn -2.570050 1.787631 -3.308805 -v 0.006864 -0.085839 0.174150 -vn -2.836260 1.322639 -3.317160 -v 0.007173 -0.085305 0.174150 -vn -3.023145 0.809956 -3.315189 -v 0.007381 -0.084731 0.174150 -vn 1.132765 -2.920238 -3.295928 -v 0.002735 -0.080563 0.174150 -vn 1.578326 -2.704395 -3.303760 -v 0.002246 -0.080798 0.174150 -vn 1.995217 -2.413149 -3.304609 -v 0.001762 -0.081136 0.174150 -vn 2.355574 -2.063864 -3.299441 -v 0.001368 -0.081519 0.174150 -vn 2.657583 -1.654664 -3.308948 -v 0.001037 -0.081964 0.174150 -vn 2.899613 -1.177514 -3.316512 -v 0.000757 -0.082512 0.174150 -vn 3.059888 -0.658141 -3.314452 -v 0.000578 -0.083093 0.174150 -vn 3.128010 -0.134064 -3.306785 -v 0.000503 -0.083688 0.174150 -vn 3.108253 0.378366 -3.304333 -v 0.000525 -0.084242 0.174150 -vn -3.117597 0.279538 -3.312686 -v 0.007486 -0.084137 0.174150 -vn -3.120161 -0.252423 -3.310799 -v 0.007489 -0.083544 0.174150 -vn -3.034074 -0.771428 -3.308895 -v 0.007391 -0.082962 0.174150 -vn -2.865437 -1.261880 -3.305982 -v 0.007202 -0.082414 0.174150 -vn -2.622966 -1.710365 -3.303215 -v 0.006930 -0.081913 0.174150 -vn -2.316661 -2.107250 -3.300502 -v 0.006588 -0.081470 0.174150 -vn 3.003659 0.882747 -3.308270 -v 0.000643 -0.084816 0.174150 -vn 2.817716 1.365235 -3.305601 -v 0.000851 -0.085355 0.174150 -vn 2.560205 1.803129 -3.302413 -v 0.001140 -0.085845 0.174150 -vn 2.243532 2.185370 -3.298105 -v 0.001496 -0.086273 0.174150 -vn 1.878661 2.506343 -3.295697 -v 0.001900 -0.086627 0.174150 -vn 1.473105 2.764385 -3.294711 -v 0.002356 -0.086917 0.174150 -vn 1.038780 2.955509 -3.291721 -v 0.002842 -0.087130 0.174150 -vn -1.979402 -2.429773 -3.280867 -v 0.006186 -0.081093 0.174150 -vn -1.625008 -2.679960 -3.279374 -v 0.005840 -0.080849 0.174150 -vn -1.219964 -2.885164 -3.293890 -v 0.005359 -0.080602 0.174150 -vn -0.773770 -3.035861 -3.290249 -v 0.004862 -0.080435 0.174150 -vn -0.304142 -3.117244 -3.297542 -v 0.004355 -0.080345 0.174150 -vn 0.187979 -3.126062 -3.300283 -v 0.003779 -0.080334 0.174150 -vn 0.671754 -3.059469 -3.295053 -v 0.003250 -0.080408 0.174150 -vn 0.588919 3.077187 -3.289245 -v 0.003345 -0.087265 0.174150 -vn 0.213596 3.130823 -3.235896 -v 0.003852 -0.087324 0.174150 -vn -0.100589 3.135563 -3.247664 -v 0.004000 -0.087327 0.174150 -vn -0.517364 3.088287 -3.303350 -v 0.004593 -0.087276 0.174150 -vn -3.117597 0.279538 3.312686 -v 0.007486 -0.084137 0.184150 -vn -3.023145 0.809956 3.315189 -v 0.007381 -0.084731 0.184150 -vn -2.836260 1.322639 3.317159 -v 0.007173 -0.085305 0.184150 -vn -2.570049 1.787630 3.308804 -v 0.006864 -0.085839 0.184150 -vn -2.248242 2.180360 3.299040 -v 0.006512 -0.086264 0.184150 -vn -1.873580 2.509050 3.302787 -v 0.006100 -0.086627 0.184150 -vn -1.448273 2.776519 3.301628 -v 0.005610 -0.086934 0.184150 -vn -0.996657 2.969503 3.295502 -v 0.005112 -0.087145 0.184150 -vn -0.517364 3.088288 3.303350 -v 0.004593 -0.087276 0.184150 -vn -0.110187 0.011223 6.182842 -v 0.004000 -0.087327 0.184150 -vn 3.003659 0.882748 3.308270 -v 0.000643 -0.084816 0.184150 -vn 3.108253 0.378366 3.304333 -v 0.000525 -0.084242 0.184150 -vn 3.128012 -0.134064 3.306786 -v 0.000503 -0.083688 0.184150 -vn 3.059887 -0.658141 3.314452 -v 0.000578 -0.083093 0.184150 -vn 2.899614 -1.177515 3.316512 -v 0.000757 -0.082512 0.184150 -vn 2.657584 -1.654665 3.308948 -v 0.001037 -0.081964 0.184150 -vn 2.355573 -2.063863 3.299441 -v 0.001368 -0.081519 0.184150 -vn 1.995218 -2.413150 3.304609 -v 0.001762 -0.081136 0.184150 -vn 1.578325 -2.704393 3.303760 -v 0.002246 -0.080798 0.184150 -vn 0.213596 3.130823 3.235896 -v 0.003852 -0.087324 0.184150 -vn 0.588919 3.077188 3.289245 -v 0.003345 -0.087265 0.184150 -vn 1.038780 2.955508 3.291721 -v 0.002842 -0.087130 0.184150 -vn 1.473105 2.764386 3.294711 -v 0.002356 -0.086917 0.184150 -vn -0.039662 0.019847 6.384070 -v 0.001900 -0.086627 0.184150 -vn 2.243532 2.185370 3.298105 -v 0.001496 -0.086273 0.184150 -vn 2.560206 1.803130 3.302413 -v 0.001140 -0.085845 0.184150 -vn 2.817715 1.365234 3.305601 -v 0.000851 -0.085355 0.184150 -vn -1.979401 -2.429771 3.280867 -v 0.006186 -0.081093 0.184150 -vn -2.316663 -2.107251 3.300502 -v 0.006588 -0.081470 0.184150 -vn -2.622964 -1.710364 3.303216 -v 0.006930 -0.081913 0.184150 -vn -2.865438 -1.261881 3.305982 -v 0.007202 -0.082414 0.184150 -vn -3.034072 -0.771428 3.308895 -v 0.007391 -0.082962 0.184150 -vn -3.120162 -0.252423 3.310799 -v 0.007489 -0.083544 0.184150 -vn 1.132765 -2.920238 3.295928 -v 0.002735 -0.080563 0.184150 -vn 0.671754 -3.059470 3.295053 -v 0.003250 -0.080408 0.184150 -vn 0.187979 -3.126061 3.300283 -v 0.003779 -0.080334 0.184150 -vn -0.304142 -3.117244 3.297543 -v 0.004355 -0.080345 0.184150 -vn -0.773770 -3.035861 3.290249 -v 0.004862 -0.080435 0.184150 -vn -1.219964 -2.885164 3.293890 -v 0.005359 -0.080602 0.184150 -vn -1.625008 -2.679961 3.279374 -v 0.005840 -0.080849 0.184150 -vn -0.951510 2.983428 2.979338 -v 0.002893 -0.080506 0.184150 -vn -1.321659 2.846011 3.043277 -v 0.002466 -0.080681 0.184150 -vn -1.587908 2.706644 3.046396 -v 0.002284 -0.080777 0.184150 -vn -1.851619 2.532409 3.034980 -v 0.001900 -0.081027 0.184150 -vn -3.090884 -0.526336 3.013361 -v 0.000578 -0.084561 0.184150 -vn -3.008962 -0.884653 3.023220 -v 0.000608 -0.084688 0.184150 -vn -2.333200 2.097309 3.032887 -v 0.001363 -0.081525 0.184150 -vn -2.111919 2.319626 3.028943 -v 0.001678 -0.081208 0.184150 -vn -2.106367 -2.325031 3.036509 -v 0.001682 -0.086449 0.184150 -vn -2.335807 -2.094670 3.037970 -v 0.001363 -0.086128 0.184150 -vn 2.822435 1.376482 3.081976 -v 0.007109 -0.082219 0.184150 -vn 2.699500 1.598898 3.039233 -v 0.007088 -0.082180 0.184150 -vn 1.429174 -2.793181 3.040474 -v 0.005534 -0.086973 0.184150 -vn 1.164056 -2.914929 3.056645 -v 0.005334 -0.087062 0.184150 -vn -1.727615 -2.619675 3.046448 -v 0.001974 -0.086681 0.184150 -vn 1.706663 -2.632599 3.038307 -v 0.005957 -0.086728 0.184150 -vn 1.937742 -2.469893 3.065036 -v 0.006147 -0.086591 0.184150 -vn 2.146513 -2.288458 3.040483 -v 0.006375 -0.086397 0.184150 -vn 2.374444 -2.049874 3.031773 -v 0.006656 -0.086106 0.184150 -vn 2.578978 -1.786639 3.037949 -v 0.006877 -0.085820 0.184150 -vn 2.717118 -1.574356 3.083637 -v 0.007067 -0.085512 0.184150 -vn 2.509356 1.881539 3.025073 -v 0.006717 -0.081621 0.184150 -vn 2.296121 2.138113 3.037503 -v 0.006637 -0.081525 0.184150 -vn 2.061445 2.364859 3.034862 -v 0.006218 -0.081119 0.184150 -vn 1.799451 2.569433 3.030942 -v 0.006100 -0.081027 0.184150 -vn 1.398166 2.798213 2.956445 -v 0.005582 -0.080704 0.184150 -vn 0.839224 3.011730 2.945327 -v 0.004939 -0.080455 0.184150 -vn -2.826082 -1.337260 2.947560 -v 0.000832 -0.085314 0.184150 -vn -2.565335 -1.800390 3.003912 -v 0.001201 -0.085927 0.184150 -vn 2.834276 -1.344857 3.035310 -v 0.007088 -0.085474 0.184150 -vn 2.967675 -1.012827 3.017654 -v 0.007354 -0.084827 0.184150 -vn 3.064273 -0.670653 3.029273 -v 0.007392 -0.084688 0.184150 -vn 3.121052 -0.286521 3.002569 -v 0.007491 -0.084078 0.184150 -vn 3.136702 0.078011 3.039540 -v 0.007499 -0.083743 0.184150 -vn 3.110008 0.407605 3.028280 -v 0.007473 -0.083391 0.184150 -vn 3.039615 0.770134 3.018667 -v 0.007392 -0.082966 0.184150 -vn 2.927841 1.124784 3.027260 -v 0.007262 -0.082559 0.184150 -vn 0.229099 3.117231 2.942657 -v 0.004266 -0.080337 0.184150 -vn -0.406016 3.099902 2.947488 -v 0.003528 -0.080359 0.184150 -vn -2.569173 1.794563 3.002824 -v 0.001198 -0.081729 0.184150 -vn -2.836069 1.311200 2.936775 -v 0.000825 -0.082354 0.184150 -vn -3.123667 0.003409 2.930554 -v 0.000500 -0.083827 0.184150 -vn -3.049287 0.677682 2.932912 -v 0.000584 -0.083064 0.184150 -vn -1.463744 -2.775291 3.041264 -v 0.002466 -0.086973 0.184150 -vn -1.199463 -2.900448 3.053715 -v 0.002583 -0.087027 0.184150 -vn 0.897267 -3.007031 3.044935 -v 0.004980 -0.087187 0.184150 -vn -0.932982 -2.995821 3.040972 -v 0.003020 -0.087187 0.184150 -vn 0.540180 -3.086648 2.997006 -v 0.004707 -0.087255 0.184150 -vn -0.568735 -3.081880 3.004929 -v 0.003234 -0.087242 0.184150 -vn 6.221979 -0.781191 0.004798 -v 0.007473 -0.084263 0.176409 -vn 6.079391 -1.539196 0.002856 -v 0.007392 -0.084688 0.176345 -vn 6.079083 -1.540839 0.000000 -v 0.007392 -0.084688 0.174393 -vn 4.281033 -4.587242 0.045154 -v 0.006375 -0.086397 0.171491 -vn 3.458024 -5.205311 0.502048 -v 0.006100 -0.086627 0.171167 -vn 3.182153 -5.145854 1.554575 -v 0.006161 -0.086627 0.170938 -vn 2.050558 5.111330 3.005723 -v 0.006275 -0.081027 0.170819 -vn 1.423009 5.121415 3.327531 -v 0.006326 -0.081027 0.170790 -vn 1.404648 5.631565 2.364291 -v 0.006029 -0.080681 0.170306 -vn -0.000352 5.611433 2.769706 -v 0.006983 -0.080681 0.170184 -vn 0.000000 5.094141 3.649311 -v 0.007343 -0.081027 0.170750 -vn 0.011996 5.067854 3.686985 -v 0.008767 -0.081027 0.170750 -vn 0.053538 4.617394 4.243473 -v 0.008914 -0.081256 0.171025 -vn 5.696865 2.636815 0.124240 -v 0.007180 -0.082365 0.171939 -vn 5.499689 3.029812 0.038752 -v 0.007088 -0.082180 0.171826 -vn 5.525362 2.971359 0.025890 -v 0.007088 -0.082180 0.172078 -vn 3.048369 4.510803 2.965379 -v 0.006484 -0.081353 0.171132 -vn 2.516630 4.518694 3.535512 -v 0.006466 -0.081320 0.171103 -vn 3.562445 4.399593 2.593094 -v 0.006456 -0.081320 0.171112 -vn 0.306298 4.555111 4.241963 -v 0.006514 -0.081386 0.171158 -vn -0.186490 4.371837 4.508130 -v 0.006520 -0.081386 0.171158 -vn 0.259055 4.250785 4.538530 -v 0.006498 -0.081353 0.171126 -vn 1.910203 4.745460 3.399878 -v 0.006639 -0.081525 0.171288 -vn 0.467284 4.407254 4.385740 -v 0.006643 -0.081525 0.171287 -vn -0.174911 4.157471 4.703496 -v 0.006621 -0.081490 0.171255 -vn 5.094066 3.607583 -0.330980 -v 0.006760 -0.081675 0.171417 -vn 4.915877 3.912789 0.029175 -v 0.006760 -0.081675 0.171425 -vn 5.088645 3.663715 -0.212097 -v 0.006790 -0.081714 0.171461 -vn 0.828943 4.030629 4.693864 -v 0.006882 -0.081834 0.171528 -vn 0.174932 3.759658 5.025049 -v 0.006887 -0.081834 0.171527 -vn 0.068292 3.685798 5.087870 -v 0.006867 -0.081793 0.171498 -vn 3.268481 4.002847 3.418838 -v 0.006963 -0.081959 0.171612 -vn 4.255162 4.001341 2.158445 -v 0.006961 -0.081959 0.171614 -vn 4.999532 3.639092 0.972433 -v 0.006974 -0.081981 0.171631 -vn 0.186396 3.429885 5.209789 -v 0.006985 -0.081981 0.171623 -vn -0.055965 3.306525 5.333305 -v 0.006976 -0.081959 0.171610 -vn 1.431803 3.658186 4.715025 -v 0.006966 -0.081959 0.171610 -vn 4.061848 3.470275 2.436860 -v 0.007100 -0.082203 0.171754 -vn 3.560140 3.523764 3.264201 -v 0.007089 -0.082180 0.171740 -vn 5.258799 3.049884 0.854489 -v 0.007088 -0.082180 0.171743 -vn 1.642777 3.423967 4.871753 -v 0.007106 -0.082203 0.171751 -vn 2.920184 3.547956 3.976132 -v 0.007115 -0.082225 0.171764 -vn 0.555513 2.990796 5.391884 -v 0.007122 -0.082225 0.171761 -vn 0.646804 2.789433 5.557458 -v 0.007198 -0.082389 0.171841 -vn 0.060288 2.675156 5.684606 -v 0.007191 -0.082365 0.171830 -vn 2.755184 2.802404 3.674834 -v 0.007181 -0.082365 0.171831 -vn 5.839287 2.225389 -0.331137 -v 0.007233 -0.082485 0.171895 -vn 5.773448 2.472572 -0.091438 -v 0.007223 -0.082461 0.171882 -vn 5.768083 2.490962 0.019143 -v 0.007223 -0.082461 0.171898 -vn 0.002494 2.476164 5.774301 -v 0.007271 -0.082461 0.171873 -vn 0.043427 2.464166 5.778702 -v 0.007313 -0.082461 0.171873 -vn 0.002630 2.666204 5.687761 -v 0.007284 -0.082365 0.171830 -vn -0.040695 2.387280 5.811406 -v 0.007258 -0.082485 0.171883 -vn -0.081678 2.341500 5.829438 -v 0.007265 -0.082510 0.171893 -vn 0.016640 2.365885 5.820428 -v 0.007285 -0.082510 0.171893 -vn 5.825409 1.986250 0.779078 -v 0.007348 -0.082810 0.172007 -vn 6.005279 1.796244 -0.241465 -v 0.007333 -0.082759 0.171996 -vn 5.956931 1.921557 0.305291 -v 0.007333 -0.082759 0.172003 -vn 0.638680 2.363629 5.777688 -v 0.007291 -0.082608 0.171931 -vn -0.002131 2.286148 5.852477 -v 0.007278 -0.082559 0.171912 -vn 0.269100 2.433444 5.778840 -v 0.007268 -0.082559 0.171912 -vn 4.606576 2.878956 3.144101 -v 0.007308 -0.082683 0.171964 -vn 3.526970 2.894552 4.301157 -v 0.007300 -0.082658 0.171954 -vn 4.871333 2.476818 1.854459 -v 0.007297 -0.082658 0.171956 -vn 1.070558 1.890121 5.801950 -v 0.007372 -0.082862 0.172013 -vn -0.238349 1.660959 6.048121 -v 0.007378 -0.082862 0.172013 -vn -0.059705 1.791889 6.021692 -v 0.007368 -0.082810 0.171999 -vn 6.217980 0.703583 -0.129354 -v 0.007473 -0.083391 0.172138 -vn 6.235205 0.728719 0.186245 -v 0.007473 -0.083391 0.172145 -vn 5.182886 0.459717 1.418083 -v 0.007493 -0.083608 0.172156 -vn 6.119613 0.320637 -1.355470 -v 0.007492 -0.083608 0.172151 -vn 6.197935 0.248383 0.989544 -v 0.007498 -0.083717 0.172154 -vn 5.182886 -0.459717 1.418083 -v 0.007493 -0.084045 0.172156 -vn 6.280019 0.000000 -0.001145 -v 0.007500 -0.083827 0.172164 -vn 6.275090 0.000401 0.073745 -v 0.007500 -0.083827 0.172179 -vn 4.997895 -0.989568 2.708244 -v 0.007465 -0.084317 0.172117 -vn 4.206561 -0.809724 2.644540 -v 0.007472 -0.084263 0.172124 -vn 6.224728 -0.637356 -0.563191 -v 0.007472 -0.084263 0.172130 -vn 1.957850 -1.849901 5.486297 -v 0.007407 -0.084636 0.172056 -vn 4.237349 -1.833257 3.891953 -v 0.007418 -0.084583 0.172069 -vn 5.746119 -1.626784 1.385959 -v 0.007416 -0.084583 0.172072 -vn 5.888729 -1.432881 1.247692 -v 0.007428 -0.084530 0.172083 -vn 2.041323 -1.702084 5.564574 -v 0.007420 -0.084583 0.172068 -vn 0.580016 -2.422149 5.745786 -v 0.007291 -0.085045 0.171931 -vn 0.016682 -2.339935 5.830956 -v 0.007278 -0.085095 0.171912 -vn 0.019975 -2.283391 5.853126 -v 0.007299 -0.085095 0.171912 -vn 1.039838 -1.878407 5.819570 -v 0.007372 -0.084792 0.172013 -vn 3.003229 -2.159905 4.960439 -v 0.007369 -0.084792 0.172015 -vn 1.004381 -2.007457 5.854612 -v 0.007358 -0.084843 0.171999 -vn 2.282408 -1.918545 5.148531 -v 0.007382 -0.084740 0.172028 -vn 0.012700 -1.646978 6.048823 -v 0.007387 -0.084740 0.172028 -vn 0.465667 -1.732205 5.947628 -v 0.007397 -0.084688 0.172042 -vn 5.732201 -2.375678 0.350003 -v 0.007252 -0.085119 0.171911 -vn 5.867712 -2.208837 -0.209404 -v 0.007253 -0.085119 0.171919 -vn 5.844505 -2.216067 -0.356554 -v 0.007243 -0.085144 0.171907 -vn 5.676668 -2.690139 0.069934 -v 0.007180 -0.085288 0.171842 -vn 5.718894 -2.536428 -0.182436 -v 0.007180 -0.085288 0.171838 -vn 5.797379 -2.273175 -0.582152 -v 0.007202 -0.085240 0.171864 -vn 0.010125 -2.785758 5.630809 -v 0.007170 -0.085382 0.171786 -vn 0.038026 -3.056266 5.486656 -v 0.007138 -0.085474 0.171738 -vn 0.010159 -3.039947 5.492355 -v 0.007304 -0.085474 0.171738 -vn 0.104443 -2.584353 5.725491 -v 0.007216 -0.085240 0.171852 -vn 0.005255 -2.644746 5.699013 -v 0.007201 -0.085288 0.171830 -vn 0.013994 -2.655177 5.693150 -v 0.007284 -0.085288 0.171830 -vn 4.906394 -3.773510 0.597447 -v 0.006919 -0.085758 0.171579 -vn 5.280370 -3.403332 0.024493 -v 0.006933 -0.085737 0.171596 -vn 5.236714 -3.459429 0.079216 -v 0.006933 -0.085737 0.171604 -vn 3.579262 -4.138480 2.834902 -v 0.006934 -0.085737 0.171585 -vn 4.864440 -3.679169 0.997113 -v 0.006933 -0.085737 0.171588 -vn 3.569670 -4.061278 2.690397 -v 0.006921 -0.085758 0.171573 -vn 1.124276 -3.743440 4.645127 -v 0.006926 -0.085758 0.171569 -vn 0.594533 -3.765292 4.914425 -v 0.006916 -0.085778 0.171555 -vn -0.065493 -3.485609 5.225641 -v 0.006928 -0.085778 0.171555 -vn 5.595965 -2.808026 -0.366986 -v 0.007088 -0.085474 0.171752 -vn 5.517334 -2.997197 0.024590 -v 0.007088 -0.085474 0.171756 -vn 5.589682 -2.835601 -0.422968 -v 0.007063 -0.085519 0.171725 -vn 0.204254 -3.464513 5.231892 -v 0.006989 -0.085737 0.171583 -vn 0.017024 -3.610453 5.140913 -v 0.006950 -0.085820 0.171527 -vn 0.040655 -3.638399 5.117942 -v 0.006992 -0.085820 0.171527 -vn 3.912470 -4.368375 2.054897 -v 0.006747 -0.085998 0.171399 -vn 5.202838 -3.465427 -0.371418 -v 0.006760 -0.085979 0.171417 -vn 4.933029 -3.889399 0.065591 -v 0.006760 -0.085979 0.171425 -vn 1.752300 -3.936339 4.006004 -v 0.006867 -0.085840 0.171513 -vn 0.951341 -3.999421 4.637848 -v 0.006856 -0.085860 0.171499 -vn 0.084058 -3.690623 5.084189 -v 0.006867 -0.085860 0.171498 -vn 3.929243 -3.816122 1.385003 -v 0.006760 -0.085979 0.171412 -vn 2.963811 -4.418013 2.272361 -v 0.006714 -0.086036 0.171368 -vn 2.156729 -4.452428 3.185678 -v 0.006700 -0.086055 0.171350 -vn 0.261099 -4.245843 4.608421 -v 0.006709 -0.086055 0.171349 -vn 1.059157 -4.442502 4.261774 -v 0.006721 -0.086036 0.171365 -vn 0.031878 -4.046468 4.805964 -v 0.006720 -0.086055 0.171349 -vn 4.686592 -4.171975 -0.112679 -v 0.006573 -0.086199 0.171237 -vn 4.271461 -4.341923 0.694198 -v 0.006573 -0.086199 0.171228 -vn 4.687712 -4.182989 -0.053623 -v 0.006604 -0.086164 0.171267 -vn 2.640701 -4.785432 2.532599 -v 0.006558 -0.086217 0.171210 -vn 0.493029 -4.468956 4.324159 -v 0.006599 -0.086182 0.171239 -vn 0.115090 -4.361956 4.515073 -v 0.006588 -0.086199 0.171223 -vn 0.028646 -4.309609 4.568240 -v 0.006610 -0.086199 0.171223 -vn 0.012679 -5.089610 3.656577 -v 0.006987 -0.086627 0.170750 -vn 0.050236 -5.058254 3.709821 -v 0.006631 -0.086627 0.170750 -vn 0.502046 -5.660995 2.658946 -v 0.006276 -0.086973 0.170210 -vn 0.967398 -5.662708 2.512293 -v 0.006144 -0.086973 0.170252 -vn -2.639668 -5.643010 -0.546195 -v 0.002567 -0.086973 0.170253 -vn -2.548590 -5.609366 -1.041694 -v 0.002749 -0.086973 0.169667 -vn -1.716835 -5.991753 -0.526949 -v 0.003175 -0.087187 0.170122 -vn -3.860031 -3.551966 -3.405066 -v 0.002470 -0.085820 0.167590 -vn -4.114460 -2.934023 -3.680613 -v 0.002337 -0.085474 0.167422 -vn -3.673963 -2.933745 -4.120997 -v 0.002780 -0.085474 0.166980 -vn -4.181969 4.586415 -0.809201 -v 0.001715 -0.081256 0.170213 -vn -3.726448 4.998694 -0.575313 -v 0.001956 -0.081027 0.170435 -vn -3.546827 5.031294 -1.127881 -v 0.002104 -0.081027 0.169794 -vn -0.015502 6.268634 -0.017856 -v 0.005216 -0.080327 0.169005 -vn -0.004128 6.269032 -0.017148 -v 0.005464 -0.080327 0.168875 -vn -0.379199 6.200803 -0.797315 -v 0.005220 -0.080358 0.168476 -vn -0.009882 6.268803 -0.018752 -v 0.005740 -0.080327 0.168768 -vn -0.003932 6.269048 -0.024061 -v 0.006051 -0.080327 0.168691 -vn -0.201328 6.200181 -0.861916 -v 0.005804 -0.080358 0.168268 -vn -2.768688 -5.612189 -0.002359 -v 0.002466 -0.086973 0.178264 -vn -5.537704 -2.945423 -0.002293 -v 0.000912 -0.085474 0.172745 -vn -5.503045 -2.971164 -0.222991 -v 0.000913 -0.085474 0.171116 -vn -5.132156 -3.589832 -0.143033 -v 0.001122 -0.085820 0.171287 -vn -2.767203 5.613091 -0.004235 -v 0.002466 -0.080681 0.178264 -vn -5.160660 3.566395 0.000357 -v 0.001123 -0.081834 0.174503 -vn -4.616663 4.232027 0.001837 -v 0.001363 -0.081525 0.174649 -vn -4.725993 4.123156 -0.042360 -v 0.001362 -0.081525 0.171481 -vn -0.859134 6.208214 0.000015 -v 0.003535 -0.080358 0.173243 -vn -1.782379 6.004064 0.000089 -v 0.003020 -0.080467 0.172826 -vn -1.781272 6.004285 0.002508 -v 0.003020 -0.080467 0.178488 -vn 5.533974 2.951827 0.005399 -v 0.007088 -0.082180 0.176102 -vn -3.229438 -2.401361 -2.021619 -v 0.009500 -0.086560 0.166463 -vn -3.217360 -2.551943 -1.828396 -v 0.009500 -0.086626 0.166549 -vn -0.021935 -4.991912 -3.767667 -v 0.008331 -0.086627 0.166550 -vn -3.231333 -2.908553 1.179716 -v 0.009500 -0.087047 0.170021 -vn -3.202010 -2.816082 1.389345 -v 0.009500 -0.086973 0.170184 -vn -0.033220 -5.608333 2.781090 -v 0.008463 -0.086973 0.170184 -vn -4.002995 -0.472099 2.983764 -v 0.009500 -0.084287 0.172120 -vn 1.349228 -0.602900 5.880611 -v 0.009497 -0.084263 0.172123 -vn 0.001145 -1.514460 6.086111 -v 0.009455 -0.084688 0.172042 -vn -3.264136 -0.802538 3.031852 -v 0.009500 -0.084700 0.172039 -vn 0.108036 -2.354782 5.804938 -v 0.009386 -0.085095 0.171912 -vn -3.315418 -1.044674 2.954406 -v 0.009500 -0.085021 0.171940 -vn 0.046805 -2.980236 5.515525 -v 0.009294 -0.085474 0.171738 -vn -3.299750 -1.395318 2.806053 -v 0.009500 -0.085410 0.171772 -vn 0.038726 -4.141768 4.709194 -v 0.009054 -0.086128 0.171287 -vn -3.277264 -1.991046 2.422426 -v 0.009500 -0.086043 0.171359 -vn -3.276064 -1.725971 2.617849 -v 0.009500 -0.085773 0.171559 -vn 0.009259 -4.598963 4.267858 -v 0.008914 -0.086397 0.171025 -vn -3.244091 -2.501043 1.893986 -v 0.009500 -0.086627 0.170750 -vn -3.266911 -2.254739 2.179167 -v 0.009500 -0.086354 0.171072 -vn -0.067169 -5.452839 3.119120 -v 0.009500 -0.086858 0.170400 -vn -3.228651 -2.656058 1.674153 -v 0.009500 -0.086815 0.170473 -vn -0.007349 -6.208770 0.856523 -v 0.007885 -0.087296 0.169115 -vn -3.201994 -3.108723 0.443224 -v 0.009500 -0.087296 0.169115 -vn -3.218775 -3.070963 0.651893 -v 0.009500 -0.087250 0.169381 -vn -0.016071 -6.002466 -1.783989 -v 0.007100 -0.087187 0.167670 -vn -3.270613 -3.112193 -0.381590 -v 0.009500 -0.087301 0.168227 -vn 0.001655 -6.207338 -0.863251 -v 0.007381 -0.087296 0.168185 -vn -3.256999 -3.136744 -0.019670 -v 0.009500 -0.087327 0.168650 -vn -3.279236 -2.821232 -1.369417 -v 0.009500 -0.086966 0.167102 -vn -3.258683 -2.950454 -1.064685 -v 0.009500 -0.087129 0.167491 -vn -3.255677 -3.051920 -0.724711 -v 0.009500 -0.087225 0.167814 -vn -0.026388 -5.679023 -2.643325 -v 0.006798 -0.086973 0.167116 -vn -0.156385 -5.430738 -3.148373 -v 0.009500 -0.086858 0.166900 -vn 0.006656 3.555434 -5.167779 -v 0.007984 -0.081834 0.165773 -vn -3.265072 1.390396 -2.811276 -v 0.009500 -0.082294 0.165504 -vn 0.013077 2.944584 -5.537996 -v 0.007890 -0.082180 0.165562 -vn -3.259851 1.081677 -2.944182 -v 0.009500 -0.082604 0.165371 -vn 0.008240 2.265987 -5.848312 -v 0.007812 -0.082559 0.165389 -vn -3.268403 0.735345 -3.048138 -v 0.009500 -0.083005 0.165248 -vn 0.007337 1.540671 -6.079137 -v 0.007754 -0.082965 0.165258 -vn -3.253746 0.382938 -3.113394 -v 0.009500 -0.083423 0.165174 -vn 0.002130 0.783110 -6.222324 -v 0.007718 -0.083391 0.165178 -vn -3.249771 0.047074 -3.136646 -v 0.009500 -0.083756 0.165151 -vn -0.002593 0.000451 -6.271266 -v 0.007706 -0.083827 0.165151 -vn -3.257054 -0.313416 -3.120435 -v 0.009500 -0.084176 0.165168 -vn -0.002945 -0.780160 -6.222941 -v 0.007718 -0.084263 0.165178 -vn -3.246308 -0.669365 -3.064858 -v 0.009500 -0.084594 0.165235 -vn -0.004739 -1.540990 -6.079600 -v 0.007754 -0.084688 0.165258 -vn -3.243804 -0.995952 -2.974956 -v 0.009500 -0.084920 0.165325 -vn -0.006255 -2.268898 -5.847811 -v 0.007812 -0.085095 0.165389 -vn -3.253019 -1.329693 -2.840468 -v 0.009500 -0.085310 0.165480 -vn -0.007674 -2.946262 -5.537924 -v 0.007890 -0.085474 0.165562 -vn -3.242229 -1.647268 -2.670027 -v 0.009500 -0.085682 0.165682 -vn -0.010082 -3.566038 -5.161329 -v 0.007984 -0.085820 0.165773 -vn -3.240232 -1.923709 -2.478413 -v 0.009500 -0.085958 0.165874 -vn -0.018216 -4.230830 -4.618628 -v 0.008091 -0.086128 0.166013 -vn -3.270403 -2.202487 -2.231881 -v 0.009500 -0.086275 0.166149 -vn -0.024755 5.001219 -3.753490 -v 0.008331 -0.081027 0.166550 -vn -3.258462 2.248307 -2.187409 -v 0.009500 -0.081337 0.166190 -vn -0.017780 4.228642 -4.620636 -v 0.008091 -0.081525 0.166013 -vn -3.243143 1.994434 -2.421680 -v 0.009500 -0.081587 0.165961 -vn -3.266726 1.695707 -2.637664 -v 0.009500 -0.081925 0.165712 -vn -3.285142 2.834619 -1.339785 -v 0.009500 -0.080664 0.167151 -vn -0.139790 5.471777 -3.080242 -v 0.009500 -0.080796 0.166900 -vn -3.241538 2.662624 -1.662408 -v 0.009500 -0.080822 0.166856 -vn -3.263582 2.476388 -1.923781 -v 0.009500 -0.081059 0.166508 -vn -0.012688 6.003900 -1.783321 -v 0.007100 -0.080467 0.167670 -vn -0.010893 6.210021 -0.851144 -v 0.007381 -0.080358 0.168185 -vn -3.245510 3.070117 -0.645152 -v 0.009500 -0.080397 0.167950 -vn -3.246038 3.121819 -0.309693 -v 0.009500 -0.080346 0.168283 -vn -0.006160 6.269656 0.004455 -v 0.007633 -0.080327 0.168650 -vn -3.259898 3.135580 0.050350 -v 0.009500 -0.080327 0.168706 -vn -3.260436 3.051349 0.726362 -v 0.009500 -0.080421 0.169455 -vn -0.010948 6.005276 1.779700 -v 0.008164 -0.080467 0.169630 -vn -3.250916 2.947245 1.074426 -v 0.009500 -0.080543 0.169861 -vn -0.033049 5.607916 2.782117 -v 0.008463 -0.080681 0.170184 -vn -3.263355 2.607478 1.744390 -v 0.009500 -0.080879 0.170537 -vn -0.075735 5.436229 3.147650 -v 0.009500 -0.080796 0.170400 -vn -3.180496 2.783464 1.455549 -v 0.009500 -0.080712 0.170246 -vn -3.201732 2.849733 1.318979 -v 0.009500 -0.080681 0.170184 -vn -3.372447 0.987398 2.971330 -v 0.009500 -0.082704 0.171965 -vn -3.452947 1.214654 2.878348 -v 0.009500 -0.082392 0.171842 -vn 0.021491 2.960958 5.527286 -v 0.009294 -0.082180 0.171738 -vn -0.002017 -0.780919 6.222333 -v 0.008208 -0.084263 0.172123 -vn -3.204505 -0.115188 3.137957 -v 0.009500 -0.083865 0.172150 -vn -0.008866 -0.002938 6.271346 -v 0.008225 -0.083827 0.172150 -vn -0.048071 0.058252 6.281737 -v 0.009500 -0.083827 0.172150 -vn -3.215819 0.257585 3.128462 -v 0.009500 -0.083529 0.172137 -vn 4.264055 -4.603011 0.000205 -v 0.006375 -0.086397 0.175531 -vn 4.731154 -4.120196 0.000412 -v 0.006637 -0.086128 0.175741 -vn 5.160367 -3.566718 -0.000318 -v 0.006877 -0.085820 0.175933 -vn 5.538100 -2.944576 0.003655 -v 0.007088 -0.085474 0.176102 -vn 3.652267 -5.092339 -0.002948 -v 0.006100 -0.086627 0.175310 -vn 2.773104 -5.610179 -0.003969 -v 0.005534 -0.086973 0.174855 -vn 0.859699 6.208094 0.001780 -v 0.004465 -0.080358 0.173994 -vn 1.777096 6.005141 0.004679 -v 0.004980 -0.080467 0.174409 -vn 2.769292 5.611602 0.000402 -v 0.005534 -0.080681 0.174855 -vn 3.650433 5.093462 -0.001058 -v 0.006100 -0.081027 0.175310 -vn 4.264562 4.602486 0.002143 -v 0.006375 -0.081256 0.175531 -vn 5.844814 -2.273424 0.006934 -v 0.007262 -0.085095 0.176241 -vn -3.775945 4.982757 -0.000055 -v 0.001900 -0.081027 0.174976 -vn -3.670272 5.076594 0.023775 -v 0.001900 -0.081027 0.171918 -vn -4.258603 4.607407 0.004857 -v 0.001624 -0.081256 0.171694 -vn -5.537036 2.946641 0.000085 -v 0.000912 -0.082180 0.174374 -vn -5.535619 2.949209 0.001936 -v 0.000912 -0.082180 0.177633 -vn -5.162644 3.563175 0.003508 -v 0.001123 -0.081834 0.177718 -vn -4.615945 4.232915 -0.001335 -v 0.001363 -0.081525 0.177816 -vn -3.776960 4.982146 -0.002991 -v 0.001900 -0.081027 0.178034 -vn -0.031166 6.271168 -0.002158 -v 0.004000 -0.080327 0.178884 -vn -0.862872 6.207409 0.004108 -v 0.003535 -0.080358 0.178696 -vn -0.000001 6.269270 0.000000 -v 0.004000 -0.080327 0.173619 -vn -5.848145 2.265982 0.000868 -v 0.000738 -0.082559 0.177562 -vn -5.810318 -2.288359 -0.300339 -v 0.000742 -0.085095 0.170977 -vn -5.846356 -2.269580 -0.008875 -v 0.000738 -0.085095 0.172621 -vn -6.040402 -1.551827 -0.363698 -v 0.000615 -0.084688 0.170874 -vn -6.078008 -1.541714 -0.014865 -v 0.000607 -0.084688 0.172528 -vn -6.183201 -0.783015 -0.402636 -v 0.000537 -0.084263 0.170811 -vn -6.221570 -0.779768 -0.019358 -v 0.000527 -0.084263 0.172471 -vn -6.231942 -0.003545 -0.412800 -v 0.000511 -0.083827 0.170790 -vn -6.269956 -0.000742 -0.019991 -v 0.000500 -0.083827 0.172452 -vn -6.186786 0.775022 -0.392098 -v 0.000537 -0.083391 0.170811 -vn -6.221905 0.778520 -0.016218 -v 0.000527 -0.083391 0.172471 -vn -6.048119 1.541120 -0.341338 -v 0.000615 -0.082965 0.170874 -vn -6.078540 1.540634 -0.010152 -v 0.000607 -0.082965 0.172528 -vn -5.822359 2.274186 -0.267010 -v 0.000742 -0.082559 0.170977 -vn -5.846948 2.268658 -0.004318 -v 0.000738 -0.082559 0.172621 -vn -5.518741 2.954333 -0.181645 -v 0.000913 -0.082180 0.171116 -vn -5.537365 2.946157 -0.000620 -v 0.000912 -0.082180 0.172745 -vn -5.149350 3.572575 -0.101501 -v 0.001122 -0.081834 0.171287 -vn -5.847388 -2.268082 0.000352 -v 0.000738 -0.085095 0.174268 -vn -6.079074 -1.540573 0.000453 -v 0.000608 -0.084688 0.174189 -vn -6.222558 -0.779256 0.000417 -v 0.000527 -0.084263 0.174140 -vn -6.270864 -0.000020 0.000408 -v 0.000500 -0.083827 0.174123 -vn -6.222560 0.779258 0.000458 -v 0.000527 -0.083391 0.174140 -vn -6.079054 1.540643 0.000404 -v 0.000608 -0.082965 0.174189 -vn -5.847369 2.268111 0.000207 -v 0.000738 -0.082559 0.174268 -vn -5.537024 -2.946677 0.000147 -v 0.000912 -0.085474 0.174374 -vn -5.160581 -3.566491 0.000194 -v 0.001123 -0.085820 0.174503 -vn -4.625125 -4.224094 0.011695 -v 0.001363 -0.086128 0.174649 -vn -5.848968 -2.263371 0.004709 -v 0.000738 -0.085095 0.177562 -vn -6.078189 -1.543277 0.004663 -v 0.000608 -0.084688 0.177509 -vn -6.222828 -0.774370 0.007795 -v 0.000527 -0.084263 0.177476 -vn -6.270544 -0.004557 0.006867 -v 0.000500 -0.083827 0.177465 -vn -6.222655 0.778696 -0.000673 -v 0.000527 -0.083391 0.177476 -vn -6.078612 1.542299 0.000524 -v 0.000608 -0.082965 0.177509 -vn -3.773725 -4.984798 0.006466 -v 0.001900 -0.086627 0.174976 -vn -2.771023 -5.610796 0.000040 -v 0.002466 -0.086973 0.172377 -vn -5.535989 -2.948609 0.000689 -v 0.000912 -0.085474 0.177633 -vn -5.161672 -3.564670 0.002822 -v 0.001123 -0.085820 0.177718 -vn -4.617937 -4.230823 -0.003546 -v 0.001363 -0.086128 0.177816 -vn -3.773135 -4.985527 -0.006812 -v 0.001900 -0.086627 0.178034 -vn -1.783306 -6.003855 -0.002009 -v 0.003020 -0.087187 0.178488 -vn -1.782451 -6.004055 0.000205 -v 0.003020 -0.087187 0.172826 -vn -0.856111 -6.208848 -0.002770 -v 0.003535 -0.087296 0.178696 -vn -0.859136 -6.208215 0.000047 -v 0.003535 -0.087296 0.173243 -vn 0.064566 -6.264291 0.005716 -v 0.004000 -0.087327 0.178884 -vn 0.000001 -6.269271 0.000002 -v 0.004000 -0.087327 0.173619 -vn 0.859124 -6.208212 0.000183 -v 0.004465 -0.087296 0.173994 -vn -0.111516 5.045160 -3.687419 -v 0.006488 -0.081027 0.166550 -vn -0.375636 5.586766 -2.755669 -v 0.005950 -0.080681 0.167154 -vn -0.044700 5.609212 -2.769419 -v 0.006798 -0.080681 0.167116 -vn -0.157434 5.990146 -1.790000 -v 0.006246 -0.080467 0.167679 -vn -0.038652 6.205215 -0.865919 -v 0.006541 -0.080358 0.168185 -vn 0.003287 6.269667 -0.009025 -v 0.006817 -0.080327 0.168650 -vn -0.003656 6.208002 0.862667 -v 0.007885 -0.080358 0.169115 -vn -3.261253 3.108692 0.416536 -v 0.009500 -0.080359 0.169125 -vn -0.491857 5.988824 -1.730682 -v 0.005536 -0.080467 0.167806 -vn -0.799973 5.989413 -1.611515 -v 0.004950 -0.080467 0.168034 -vn -0.853493 5.589169 -2.645175 -v 0.005252 -0.080681 0.167314 -vn -1.267548 5.589682 -2.474082 -v 0.004659 -0.080681 0.167561 -vn -1.201059 5.062944 -3.457891 -v 0.004963 -0.081027 0.166814 -vn -1.775435 4.975276 -3.311059 -v 0.004360 -0.081027 0.167078 -vn -3.265775 2.972637 -0.998180 -v 0.009500 -0.080506 0.167544 -vn -1.060188 5.988899 -1.454886 -v 0.004453 -0.080467 0.168336 -vn -0.649508 6.199580 -0.602687 -v 0.004337 -0.080358 0.169122 -vn -0.525721 6.200608 -0.708947 -v 0.004738 -0.080358 0.168766 -vn -0.024439 6.268897 -0.016939 -v 0.004615 -0.080327 0.169507 -vn -0.013726 6.268935 -0.019521 -v 0.004994 -0.080327 0.169155 -vn 0.527292 6.214483 0.646646 -v 0.005250 -0.080358 0.169544 -vn -1.820732 5.963603 -0.214073 -v 0.003046 -0.080467 0.170724 -vn -2.522142 5.611972 -1.046404 -v 0.002749 -0.080681 0.169667 -vn -2.530262 5.689617 -0.571469 -v 0.002567 -0.080681 0.170253 -vn -3.143678 5.337509 -0.915450 -v 0.002333 -0.080836 0.170021 -vn -3.242010 5.347952 -0.313960 -v 0.002209 -0.080836 0.170669 -vn -3.139678 4.981927 -2.038271 -v 0.002614 -0.081027 0.168688 -vn -3.285038 5.088991 -1.537873 -v 0.002327 -0.081027 0.169214 -vn -2.640435 5.658976 -0.164424 -v 0.002474 -0.080681 0.170912 -vn -2.770291 5.610855 -0.010205 -v 0.002466 -0.080681 0.171641 -vn -1.775037 6.002259 -0.049590 -v 0.003020 -0.080467 0.171410 -vn -0.860474 6.207935 -0.003105 -v 0.003535 -0.080358 0.171880 -vn 0.000037 6.269272 0.000019 -v 0.004000 -0.080327 0.172302 -vn -3.471692 4.224019 -3.011133 -v 0.002621 -0.081525 0.167782 -vn -3.799135 4.221606 -2.592103 -v 0.002251 -0.081525 0.168264 -vn -3.668552 5.073390 -0.084374 -v 0.001900 -0.081027 0.171153 -vn -2.770700 5.610931 -0.000059 -v 0.002466 -0.080681 0.172377 -vn -0.207149 4.622612 -4.208231 -v 0.006341 -0.081256 0.166277 -vn -0.004190 4.222317 -4.625650 -v 0.007143 -0.081525 0.166013 -vn -0.052398 3.575177 -5.151539 -v 0.007023 -0.081834 0.165773 -vn -0.079808 2.957210 -5.526097 -v 0.006917 -0.082180 0.165561 -vn -0.106753 2.277580 -5.836384 -v 0.006830 -0.082559 0.165387 -vn -0.129389 1.547933 -6.068259 -v 0.006765 -0.082965 0.165257 -vn -0.143619 0.783671 -6.212197 -v 0.006726 -0.083391 0.165177 -vn -0.146678 0.001538 -6.260969 -v 0.006712 -0.083827 0.165149 -vn -0.137397 -0.780563 -6.213277 -v 0.006726 -0.084263 0.165177 -vn -0.117299 -1.544363 -6.070408 -v 0.006765 -0.084688 0.165257 -vn -0.089861 -2.273434 -5.839529 -v 0.006830 -0.085095 0.165387 -vn -0.060047 -2.952564 -5.530121 -v 0.006917 -0.085474 0.165561 -vn -0.033641 -3.570863 -5.155758 -v 0.007023 -0.085820 0.165773 -vn 0.003454 -4.225327 -4.623172 -v 0.007143 -0.086128 0.166013 -vn -0.333779 -4.112158 -4.703107 -v 0.006204 -0.086128 0.166022 -vn -0.435683 -3.552089 -5.125681 -v 0.006082 -0.085820 0.165789 -vn -0.533740 -2.929030 -5.491914 -v 0.005976 -0.085474 0.165586 -vn -0.619650 -2.251379 -5.790613 -v 0.005890 -0.085095 0.165420 -vn -0.686655 -1.527138 -6.011758 -v 0.005826 -0.084688 0.165296 -vn -0.729093 -0.770656 -6.147999 -v 0.005786 -0.084263 0.165220 -vn -0.743510 0.002612 -6.192881 -v 0.005773 -0.083827 0.165194 -vn -0.728815 0.775415 -6.145917 -v 0.005786 -0.083391 0.165220 -vn -0.686623 1.530778 -6.007855 -v 0.005826 -0.082965 0.165296 -vn -0.620823 2.253402 -5.785421 -v 0.005890 -0.082559 0.165420 -vn -0.537621 2.929739 -5.485781 -v 0.005976 -0.082180 0.165586 -vn -0.444783 3.552281 -5.118681 -v 0.006082 -0.081834 0.165789 -vn -0.354537 4.111856 -4.695957 -v 0.006204 -0.081525 0.166022 -vn -1.004260 -4.099688 -4.613339 -v 0.005391 -0.086128 0.166134 -vn -1.160868 -3.547531 -5.013331 -v 0.005272 -0.085820 0.165915 -vn -1.301176 -2.929258 -5.362665 -v 0.005167 -0.085474 0.165723 -vn -1.418643 -2.253357 -5.649409 -v 0.005082 -0.085095 0.165565 -vn -1.507106 -1.529413 -5.862493 -v 0.005018 -0.084688 0.165447 -vn -1.561771 -0.772365 -5.994141 -v 0.004979 -0.084263 0.165374 -vn -1.579464 0.002033 -6.037914 -v 0.004965 -0.083827 0.165350 -vn -1.559308 0.776087 -5.993145 -v 0.004979 -0.083391 0.165374 -vn -1.502234 1.532161 -5.860702 -v 0.005018 -0.082965 0.165447 -vn -1.411519 2.254542 -5.647243 -v 0.005082 -0.082559 0.165565 -vn -1.291940 2.928598 -5.360598 -v 0.005167 -0.082180 0.165723 -vn -1.149391 3.544933 -5.011969 -v 0.005272 -0.081834 0.165915 -vn -0.990551 4.094855 -4.613478 -v 0.005391 -0.081525 0.166134 -vn -0.823309 4.575939 -4.177101 -v 0.005521 -0.081256 0.166374 -vn -0.635423 5.046192 -3.620234 -v 0.005660 -0.081027 0.166627 -vn -0.696810 -5.017531 -3.668342 -v 0.005660 -0.086627 0.166627 -vn -0.838341 -4.582932 -4.174778 -v 0.005521 -0.086397 0.166374 -vn -0.174407 -4.614552 -4.223569 -v 0.006341 -0.086397 0.166277 -vn -1.679926 -4.134084 -4.376003 -v 0.004691 -0.086128 0.166342 -vn -1.840381 -3.549934 -4.806807 -v 0.004569 -0.085820 0.166131 -vn -2.004781 -2.931379 -5.142866 -v 0.004462 -0.085474 0.165946 -vn -2.141339 -2.255279 -5.419013 -v 0.004374 -0.085095 0.165794 -vn -2.243565 -1.531149 -5.624447 -v 0.004309 -0.084688 0.165680 -vn -2.306836 -0.773716 -5.751609 -v 0.004268 -0.084263 0.165610 -vn -2.327519 0.001167 -5.794151 -v 0.004254 -0.083827 0.165586 -vn -2.304960 0.775920 -5.751399 -v 0.004268 -0.083391 0.165610 -vn -2.239875 1.532728 -5.624160 -v 0.004309 -0.082965 0.165680 -vn -2.135945 2.256063 -5.418848 -v 0.004374 -0.082559 0.165794 -vn -1.997915 2.931116 -5.143072 -v 0.004462 -0.082180 0.165946 -vn -1.832295 3.548652 -4.807639 -v 0.004569 -0.081834 0.166131 -vn -1.646164 4.100001 -4.424189 -v 0.004691 -0.081525 0.166342 -vn -1.469533 4.579464 -3.997532 -v 0.004824 -0.081256 0.166572 -vn -2.171536 -4.210052 -4.063569 -v 0.004076 -0.086128 0.166621 -vn -2.438765 -3.551083 -4.533502 -v 0.003949 -0.085820 0.166416 -vn -2.626932 -2.932543 -4.855758 -v 0.003837 -0.085474 0.166237 -vn -2.782333 -2.256499 -5.120934 -v 0.003745 -0.085095 0.166089 -vn -2.898392 -1.532171 -5.318455 -v 0.003676 -0.084688 0.165979 -vn -2.970169 -0.774645 -5.440924 -v 0.003634 -0.084263 0.165910 -vn -2.993743 0.000464 -5.482130 -v 0.003619 -0.083827 0.165887 -vn -2.968689 0.775552 -5.441329 -v 0.003634 -0.083391 0.165910 -vn -2.895567 1.532843 -5.319247 -v 0.003676 -0.082965 0.165979 -vn -2.778281 2.256775 -5.122206 -v 0.003745 -0.082559 0.166089 -vn -2.621722 2.932470 -4.857553 -v 0.003837 -0.082180 0.166237 -vn -2.432657 3.550640 -4.535845 -v 0.003949 -0.081834 0.166416 -vn -2.196566 4.192192 -4.071636 -v 0.004076 -0.081525 0.166621 -vn -1.764808 -4.966377 -3.323941 -v 0.004360 -0.086627 0.167078 -vn -1.564451 -4.553638 -3.983443 -v 0.004824 -0.086397 0.166572 -vn -1.214170 -5.074972 -3.436410 -v 0.004963 -0.086627 0.166814 -vn -0.109997 -4.983169 -3.790768 -v 0.006488 -0.086627 0.166550 -vn -0.067179 -5.372180 -3.235037 -v 0.006642 -0.086818 0.166832 -vn -0.577368 -5.327619 -3.230903 -v 0.005804 -0.086818 0.166889 -vn -0.352951 -5.674146 -2.603914 -v 0.005950 -0.086973 0.167154 -vn -0.867662 -5.596641 -2.620451 -v 0.005252 -0.086973 0.167314 -vn -0.165444 -5.983027 -1.794269 -v 0.006246 -0.087187 0.167679 -vn -1.257471 -5.586564 -2.481149 -v 0.004659 -0.086973 0.167561 -vn -0.477652 -5.980649 -1.746280 -v 0.005536 -0.087187 0.167806 -vn -0.791709 -5.986797 -1.619566 -v 0.004950 -0.087187 0.168034 -vn -0.189967 -6.194809 -0.886447 -v 0.005804 -0.087296 0.168268 -vn -0.377257 -6.199101 -0.807701 -v 0.005220 -0.087296 0.168476 -vn 0.004721 -6.268765 -0.036195 -v 0.006051 -0.087327 0.168691 -vn -0.008633 -6.269301 -0.020279 -v 0.005740 -0.087327 0.168768 -vn -2.659250 -4.209513 -3.764428 -v 0.003532 -0.086128 0.166958 -vn -2.968666 -3.551768 -4.205961 -v 0.003397 -0.085820 0.166759 -vn -3.179720 -2.933395 -4.513622 -v 0.003279 -0.085474 0.166584 -vn -3.353476 -2.257273 -4.767261 -v 0.003182 -0.085095 0.166439 -vn -3.482877 -1.532966 -4.956520 -v 0.003109 -0.084688 0.166332 -vn -3.562784 -0.775550 -5.074020 -v 0.003064 -0.084263 0.166265 -vn -3.589280 -0.000134 -5.113712 -v 0.003049 -0.083827 0.166242 -vn -3.561822 0.775284 -5.074818 -v 0.003064 -0.083391 0.166265 -vn -3.480884 1.532803 -4.958132 -v 0.003109 -0.082965 0.166332 -vn -3.350580 2.257108 -4.769620 -v 0.003182 -0.082559 0.166439 -vn -3.176011 2.933385 -4.516567 -v 0.003279 -0.082180 0.166584 -vn -2.964184 3.551904 -4.209428 -v 0.003397 -0.081834 0.166759 -vn -3.865319 -2.257821 -4.362385 -v 0.002677 -0.085095 0.166839 -vn -4.322894 -2.258347 -3.908887 -v 0.002227 -0.085095 0.167284 -vn -4.007541 -1.533660 -4.542870 -v 0.002600 -0.084688 0.166733 -vn -4.477715 -1.534279 -4.079969 -v 0.002145 -0.084688 0.167181 -vn -4.095487 -0.776168 -4.655064 -v 0.002552 -0.084263 0.166668 -vn -4.573455 -0.776813 -4.186511 -v 0.002095 -0.084263 0.167117 -vn -4.124774 -0.000703 -4.693172 -v 0.002536 -0.083827 0.166646 -vn -4.605505 -0.001255 -4.222823 -v 0.002077 -0.083827 0.167095 -vn -4.094899 0.774853 -4.656257 -v 0.002552 -0.083391 0.166668 -vn -4.573380 0.774468 -4.187928 -v 0.002095 -0.083391 0.167117 -vn -4.006385 1.532648 -4.545148 -v 0.002600 -0.082965 0.166733 -vn -4.477458 1.532474 -4.082737 -v 0.002145 -0.082965 0.167181 -vn -3.863528 2.257252 -4.365633 -v 0.002677 -0.082559 0.166839 -vn -4.322349 2.257341 -3.912773 -v 0.002227 -0.082559 0.167284 -vn -3.671493 2.933775 -4.124980 -v 0.002780 -0.082180 0.166980 -vn -4.113409 2.934037 -3.685357 -v 0.002337 -0.082180 0.167422 -vn -3.437693 3.552528 -3.833398 -v 0.002905 -0.081834 0.167151 -vn -3.858329 3.553006 -3.410381 -v 0.002470 -0.081834 0.167590 -vn -3.091228 4.218199 -3.408022 -v 0.003048 -0.081525 0.167346 -vn -2.908351 4.953532 -2.406110 -v 0.002961 -0.081027 0.168211 -vn -2.420107 5.580978 -1.376597 -v 0.003003 -0.080681 0.169140 -vn -1.746610 5.972754 -0.516012 -v 0.003175 -0.080467 0.170122 -vn -0.882594 6.199875 -0.040242 -v 0.003535 -0.080358 0.171198 -vn -4.224705 3.553148 -2.945143 -v 0.002089 -0.081834 0.168075 -vn -4.500167 2.934049 -3.202532 -v 0.001947 -0.082180 0.167910 -vn -4.725437 2.257223 -3.415996 -v 0.001830 -0.082559 0.167774 -vn -4.892402 1.532218 -3.575846 -v 0.001743 -0.082965 0.167673 -vn -4.995458 0.773970 -3.674864 -v 0.001690 -0.083391 0.167610 -vn -5.029828 -0.001807 -3.707644 -v 0.001671 -0.083827 0.167589 -vn -4.995071 -0.777344 -3.673205 -v 0.001690 -0.084263 0.167610 -vn -4.891727 -1.534826 -3.572681 -v 0.001743 -0.084688 0.167673 -vn -4.724770 -2.258675 -3.411506 -v 0.001830 -0.085095 0.167774 -vn -4.499837 -2.934068 -3.197002 -v 0.001947 -0.085474 0.167910 -vn -4.225111 -3.551604 -2.938897 -v 0.002089 -0.085820 0.168075 -vn -3.827680 -4.186589 -2.609545 -v 0.002251 -0.086128 0.168264 -vn -3.440845 -3.551941 -3.828867 -v 0.002905 -0.085820 0.167151 -vn -3.489933 -4.200286 -3.024782 -v 0.002621 -0.086128 0.167782 -vn -2.903791 -4.960269 -2.413964 -v 0.002961 -0.086627 0.168211 -vn -3.149164 -4.984280 -2.040530 -v 0.002614 -0.086627 0.168688 -vn -3.345621 -5.053650 -1.527152 -v 0.002327 -0.086627 0.169214 -vn -3.607136 -4.991475 -1.094759 -v 0.002104 -0.086627 0.169794 -vn -3.824197 -4.573161 -1.894344 -v 0.002126 -0.086397 0.168997 -vn -4.033370 -4.580349 -1.360597 -v 0.001886 -0.086397 0.169576 -vn -4.197870 -4.101427 -2.159162 -v 0.001936 -0.086128 0.168793 -vn -4.431740 -4.099145 -1.622086 -v 0.001681 -0.086128 0.169372 -vn -4.536235 -3.550738 -2.428685 -v 0.001763 -0.085820 0.168606 -vn -4.791724 -3.549707 -1.869386 -v 0.001494 -0.085820 0.169186 -vn -4.830198 -2.933794 -2.669132 -v 0.001611 -0.085474 0.168443 -vn -5.104470 -2.933619 -2.091796 -v 0.001332 -0.085474 0.169024 -vn -5.070795 -2.258801 -2.869752 -v 0.001487 -0.085095 0.168309 -vn -5.360606 -2.258941 -2.278203 -v 0.001199 -0.085095 0.168891 -vn -5.249403 -1.535216 -3.020881 -v 0.001394 -0.084688 0.168209 -vn -5.550771 -1.535605 -2.418981 -v 0.001100 -0.084688 0.168792 -vn -5.359994 -0.777903 -3.115345 -v 0.001337 -0.084263 0.168148 -vn -5.668575 -0.778502 -2.507114 -v 0.001039 -0.084263 0.168731 -vn -5.397336 -0.002421 -3.147886 -v 0.001318 -0.083827 0.168127 -vn -5.708568 -0.003092 -2.537633 -v 0.001018 -0.083827 0.168710 -vn -5.360914 0.773433 -3.117210 -v 0.001337 -0.083391 0.168148 -vn -5.670156 0.772806 -2.509079 -v 0.001039 -0.083391 0.168731 -vn -5.251043 1.531759 -3.024505 -v 0.001394 -0.082965 0.168209 -vn -5.553683 1.531180 -2.422790 -v 0.001100 -0.082965 0.168792 -vn -5.072781 2.256853 -2.874937 -v 0.001487 -0.082559 0.168309 -vn -5.364351 2.256396 -2.283768 -v 0.001199 -0.082559 0.168891 -vn -4.831991 2.933822 -2.675624 -v 0.001611 -0.082180 0.168443 -vn -5.108303 2.933641 -2.098966 -v 0.001332 -0.082180 0.169024 -vn -4.537232 3.552938 -2.436142 -v 0.001763 -0.081834 0.168606 -vn -4.794695 3.552734 -1.877890 -v 0.001494 -0.081834 0.169186 -vn -4.141445 4.144269 -2.185286 -v 0.001936 -0.081525 0.168793 -vn -4.433094 4.105054 -1.631615 -v 0.001681 -0.081525 0.169372 -vn -3.787987 4.565771 -1.978707 -v 0.002126 -0.081256 0.168997 -vn -4.032638 4.588582 -1.371135 -v 0.001886 -0.081256 0.169576 -vn -3.735608 -4.977964 -0.578175 -v 0.001956 -0.086627 0.170435 -vn -4.184388 -4.571391 -0.792752 -v 0.001715 -0.086397 0.170213 -vn -4.603477 -4.095287 -1.031216 -v 0.001492 -0.086128 0.170006 -vn -4.984059 -3.548586 -1.258721 -v 0.001290 -0.085820 0.169819 -vn -5.316469 -2.932747 -1.462079 -v 0.001115 -0.085474 0.169657 -vn -5.588571 -2.258476 -1.633209 -v 0.000972 -0.085095 0.169524 -vn -5.790326 -1.535858 -1.763755 -v 0.000866 -0.084688 0.169425 -vn -5.915393 -0.779160 -1.845775 -v 0.000800 -0.084263 0.169365 -vn -5.958091 -0.003827 -1.874223 -v 0.000778 -0.083827 0.169344 -vn -5.917733 0.771979 -1.847852 -v 0.000800 -0.083391 0.169365 -vn -5.794637 1.530268 -1.768106 -v 0.000866 -0.082965 0.169425 -vn -5.594207 2.255637 -1.639394 -v 0.000972 -0.082559 0.169524 -vn -5.322786 2.933019 -1.469493 -v 0.001115 -0.082180 0.169657 -vn -4.990091 3.551912 -1.268554 -v 0.001290 -0.081834 0.169819 -vn -4.606453 4.103893 -1.045423 -v 0.001492 -0.081525 0.170006 -vn -2.408600 -5.593854 -1.384060 -v 0.003003 -0.086973 0.169140 -vn -1.605392 -5.992252 -0.804452 -v 0.003390 -0.087187 0.169589 -vn -3.184401 -5.320855 -0.846180 -v 0.002333 -0.086818 0.170021 -vn -3.203088 -5.362802 -0.374137 -v 0.002209 -0.086818 0.170669 -vn -3.695193 -5.052366 -0.090429 -v 0.001900 -0.086627 0.171153 -vn -4.221974 -4.605783 -0.277663 -v 0.001631 -0.086397 0.170921 -vn -4.685387 -4.106965 -0.430026 -v 0.001382 -0.086128 0.170706 -vn -5.103670 -3.542677 -0.599361 -v 0.001160 -0.085820 0.170514 -vn -5.458574 -2.925578 -0.770139 -v 0.000969 -0.085474 0.170349 -vn -5.744750 -2.256998 -0.925052 -v 0.000814 -0.085095 0.170215 -vn -5.957756 -1.537329 -1.047714 -v 0.000699 -0.084688 0.170115 -vn -6.090729 -0.780305 -1.125370 -v 0.000629 -0.084263 0.170054 -vn -6.136467 -0.004793 -1.152408 -v 0.000605 -0.083827 0.170033 -vn -6.094059 0.771039 -1.128028 -v 0.000629 -0.083391 0.170054 -vn -5.964069 1.530244 -1.053238 -v 0.000699 -0.082965 0.170115 -vn -5.752666 2.254686 -0.932842 -v 0.000814 -0.082559 0.170215 -vn -5.467020 2.928210 -0.777658 -v 0.000969 -0.082180 0.170349 -vn -5.113889 3.547136 -0.599887 -v 0.001160 -0.081834 0.170514 -vn -4.701190 4.107097 -0.415204 -v 0.001382 -0.081525 0.170706 -vn -4.244126 4.599010 -0.247302 -v 0.001631 -0.081256 0.170921 -vn -1.783523 -5.990644 -0.221234 -v 0.003046 -0.087187 0.170724 -vn -0.861797 -6.201691 -0.170734 -v 0.003594 -0.087296 0.170564 -vn -0.870980 -6.204774 -0.033332 -v 0.003535 -0.087296 0.171198 -vn -0.042539 -6.270390 0.003731 -v 0.004005 -0.087327 0.170990 -vn -0.000320 -6.269287 0.000241 -v 0.004000 -0.087327 0.171644 -vn -2.681472 -5.650518 -0.170108 -v 0.002474 -0.086973 0.170912 -vn -1.787820 -6.001090 -0.025761 -v 0.003020 -0.087187 0.171410 -vn -2.768916 -5.611745 -0.005019 -v 0.002466 -0.086973 0.171641 -vn -3.649395 -5.094205 -0.003656 -v 0.001900 -0.086627 0.171918 -vn -4.255225 -4.609568 -0.025254 -v 0.001624 -0.086397 0.171694 -vn -4.712945 -4.134418 -0.073213 -v 0.001362 -0.086128 0.171481 -vn -0.811307 -6.202191 -0.333981 -v 0.003760 -0.087296 0.170017 -vn -0.039649 -6.270199 -0.009946 -v 0.004110 -0.087327 0.170416 -vn 0.837036 -6.213106 0.024097 -v 0.004465 -0.087296 0.171455 -vn -0.006679 -6.269303 -0.016159 -v 0.005464 -0.087327 0.168875 -vn -0.009003 -6.269162 -0.014028 -v 0.005216 -0.087327 0.169005 -vn -2.183286 -4.956994 -3.080767 -v 0.003831 -0.086627 0.167404 -vn -1.615300 -5.590240 -2.262537 -v 0.004146 -0.086973 0.167875 -vn -1.052413 -5.989865 -1.458984 -v 0.004453 -0.087187 0.168336 -vn -0.522866 -6.201050 -0.711593 -v 0.004738 -0.087296 0.168766 -vn -0.011972 -6.269318 -0.017298 -v 0.004994 -0.087327 0.169155 -vn -0.000005 -6.269270 -0.000002 -v 0.007633 -0.087327 0.168650 -vn 0.002473 -6.208236 0.859211 -v 0.007092 -0.087296 0.169115 -vn 0.060475 -6.015002 1.759329 -v 0.006628 -0.087187 0.169629 -vn -0.000548 -6.003999 1.782491 -v 0.007397 -0.087187 0.169630 -vn -0.020088 -6.002457 1.792469 -v 0.008164 -0.087187 0.169630 -vn -3.237561 -3.002992 0.910440 -v 0.009500 -0.087188 0.169625 -vn 0.006005 -5.609973 2.773453 -v 0.006983 -0.086973 0.170184 -vn 0.265090 -6.033627 1.701249 -v 0.006268 -0.087187 0.169648 -vn 0.564288 -6.022532 1.652561 -v 0.005978 -0.087187 0.169722 -vn 0.131380 -5.631095 2.750442 -v 0.006613 -0.086973 0.170184 -vn -0.000009 -5.094127 3.649333 -v 0.007343 -0.086627 0.170750 -vn -0.027954 -5.076605 3.677321 -v 0.008767 -0.086627 0.170750 -vn 0.000000 -1.540813 6.079090 -v 0.008158 -0.084688 0.172042 -vn 0.000000 -2.268071 5.847291 -v 0.008076 -0.085095 0.171912 -vn 0.006048 -2.948817 5.536061 -v 0.007967 -0.085474 0.171738 -vn 1.376956 -5.643226 2.354894 -v 0.006029 -0.086973 0.170306 -vn 0.530842 -5.132209 3.564317 -v 0.006456 -0.086627 0.170752 -vn 0.002716 -4.601812 4.265503 -v 0.006819 -0.086397 0.171025 -vn 0.000000 -4.603045 4.264031 -v 0.007517 -0.086397 0.171025 -vn 0.094873 -4.602433 4.268921 -v 0.006645 -0.086397 0.171025 -vn 0.687349 -4.599587 4.178305 -v 0.006474 -0.086397 0.171028 -vn 1.339811 -5.141061 3.332143 -v 0.006326 -0.086627 0.170790 -vn 1.850553 -4.702074 3.712528 -v 0.006444 -0.086397 0.171039 -vn 2.043150 -5.108598 3.013327 -v 0.006275 -0.086627 0.170819 -vn 1.979653 -4.478652 3.492784 -v 0.006499 -0.086284 0.171143 -vn 3.929272 -4.441390 1.740848 -v 0.006495 -0.086284 0.171148 -vn 1.774284 -4.536333 3.884529 -v 0.006490 -0.086301 0.171128 -vn 3.070523 -4.539439 2.819086 -v 0.006484 -0.086301 0.171132 -vn 2.531598 -4.530677 3.500207 -v 0.006466 -0.086334 0.171103 -vn 0.258731 -4.251821 4.537510 -v 0.006498 -0.086301 0.171126 -vn 1.292107 -4.517016 4.088099 -v 0.006479 -0.086334 0.171096 -vn -0.037621 -4.321649 4.559891 -v 0.006543 -0.086268 0.171159 -vn 0.158414 -4.399743 4.480730 -v 0.006564 -0.086268 0.171158 -vn 0.664526 -4.464022 4.255380 -v 0.006566 -0.086217 0.171207 -vn 0.240853 -4.460724 4.403142 -v 0.006554 -0.086234 0.171191 -vn 0.977346 -4.767935 3.922558 -v 0.006545 -0.086234 0.171192 -vn -0.195463 -4.318367 4.559005 -v 0.006520 -0.086268 0.171158 -vn 0.105198 -4.315693 4.560881 -v 0.006565 -0.086234 0.171191 -vn -0.146925 -4.047618 4.798719 -v 0.006655 -0.086128 0.171287 -vn -0.187124 -4.078614 4.774571 -v 0.006649 -0.086128 0.171287 -vn -0.172762 -4.136672 4.718575 -v 0.006633 -0.086164 0.171256 -vn -0.184451 -4.128226 4.729954 -v 0.006621 -0.086164 0.171255 -vn 2.090798 -4.797952 3.067627 -v 0.006591 -0.086182 0.171241 -vn 0.960757 -4.614865 4.038074 -v 0.006578 -0.086199 0.171223 -vn 0.467613 -4.377442 4.431833 -v 0.006643 -0.086128 0.171287 -vn 0.438417 -4.303834 4.525187 -v 0.006615 -0.086164 0.171255 -vn 1.539225 -4.617617 3.789805 -v 0.006611 -0.086164 0.171255 -vn 3.073578 -4.796792 2.272145 -v 0.006605 -0.086164 0.171259 -vn 1.953598 -4.735191 3.414981 -v 0.006639 -0.086128 0.171288 -vn 3.810286 -4.503195 1.526965 -v 0.006637 -0.086128 0.171290 -vn 2.629133 -4.627198 2.840989 -v 0.006623 -0.086146 0.171272 -vn 4.752620 -4.077076 0.036650 -v 0.006636 -0.086128 0.171298 -vn 4.115114 -4.528535 0.915820 -v 0.006621 -0.086146 0.171278 -vn 2.177760 -4.688218 3.074222 -v 0.006510 -0.086268 0.171159 -vn 3.546828 -4.837655 1.361133 -v 0.006540 -0.086234 0.171196 -vn 4.066881 -4.459141 1.100417 -v 0.006508 -0.086268 0.171161 -vn 4.553486 -4.262879 -0.062814 -v 0.006539 -0.086234 0.171200 -vn 4.763943 -4.085279 0.029798 -v 0.006508 -0.086268 0.171165 -vn 2.645368 -4.704329 3.195926 -v 0.006420 -0.086397 0.171054 -vn 4.103070 -4.652437 0.580781 -v 0.006556 -0.086217 0.171216 -vn 4.601239 -4.274655 0.012557 -v 0.006573 -0.086199 0.171245 -vn 4.711588 -4.138188 -0.371673 -v 0.006540 -0.086234 0.171204 -vn 4.612799 -4.263956 0.042062 -v 0.006573 -0.086199 0.171261 -vn 4.551577 -4.327978 0.013147 -v 0.006508 -0.086268 0.171182 -vn 4.312172 -4.447127 0.630417 -v 0.006604 -0.086164 0.171263 -vn 2.667164 -4.844431 2.669149 -v 0.006574 -0.086199 0.171225 -vn 4.241796 -4.421391 1.103372 -v 0.006444 -0.086334 0.171137 -vn 3.372427 -4.551814 2.597237 -v 0.006456 -0.086334 0.171112 -vn 3.867024 -4.580464 1.428320 -v 0.006477 -0.086301 0.171143 -vn 4.443339 -4.431265 0.249640 -v 0.006442 -0.086334 0.171168 -vn 4.168284 -4.617273 0.579742 -v 0.006492 -0.086284 0.171162 -vn 4.451097 -4.428401 0.111595 -v 0.006508 -0.086268 0.171249 -vn 4.714863 -4.150789 0.017356 -v 0.006637 -0.086128 0.171405 -vn 1.302403 -4.226370 4.136398 -v 0.006762 -0.085979 0.171410 -vn 1.621477 -4.083924 3.889097 -v 0.006751 -0.085998 0.171394 -vn -0.017610 -3.862318 4.950800 -v 0.006774 -0.085979 0.171410 -vn -0.070545 -3.895616 4.923481 -v 0.006763 -0.086017 0.171380 -vn 3.690513 -4.506623 1.687082 -v 0.006729 -0.086017 0.171387 -vn 4.924902 -3.790201 -0.264879 -v 0.006729 -0.086017 0.171390 -vn 0.082958 -4.006966 4.837287 -v 0.006784 -0.086055 0.171349 -vn 0.042529 -3.840980 4.971622 -v 0.006784 -0.085979 0.171410 -vn 0.117098 -3.851231 4.962814 -v 0.006779 -0.085979 0.171410 -vn 0.045982 -3.728487 5.055847 -v 0.006868 -0.085900 0.171470 -vn 0.000708 -3.872445 4.946159 -v 0.006826 -0.085979 0.171410 -vn 0.166028 -3.870546 4.939420 -v 0.006911 -0.085979 0.171410 -vn 0.029859 -4.194755 4.671996 -v 0.006826 -0.086128 0.171287 -vn 0.026508 -4.145018 4.711373 -v 0.006997 -0.086128 0.171287 -vn 0.042286 -3.741606 5.047173 -v 0.006847 -0.085900 0.171470 -vn 0.273158 -3.836032 4.962338 -v 0.006846 -0.085880 0.171484 -vn -0.117701 -3.751971 5.032794 -v 0.006836 -0.085900 0.171470 -vn 0.717418 -4.072005 4.601615 -v 0.006814 -0.085920 0.171454 -vn 0.062939 -3.768443 5.026741 -v 0.006804 -0.085940 0.171439 -vn 0.183391 -3.694296 5.075961 -v 0.006887 -0.085820 0.171527 -vn 1.025710 -4.074008 4.555261 -v 0.006798 -0.085940 0.171439 -vn 3.123104 -4.215580 2.736130 -v 0.006807 -0.085920 0.171456 -vn 2.192482 -4.532128 3.713634 -v 0.006795 -0.085940 0.171441 -vn 4.633712 -4.079415 0.758117 -v 0.006805 -0.085920 0.171463 -vn 3.292565 -4.616631 2.382731 -v 0.006790 -0.085940 0.171445 -vn -0.000827 -4.106081 4.755571 -v 0.006740 -0.086128 0.171287 -vn 5.085032 -3.667927 -0.220184 -v 0.006790 -0.085940 0.171461 -vn 5.198405 -3.441495 -0.730742 -v 0.006790 -0.085940 0.171453 -vn 4.751513 -3.776534 0.148191 -v 0.006789 -0.085940 0.171448 -vn 4.901455 -3.731856 0.245339 -v 0.006848 -0.085860 0.171508 -vn 3.084800 -4.155521 2.734147 -v 0.006849 -0.085860 0.171501 -vn 5.136464 -3.604599 -0.037863 -v 0.006863 -0.085840 0.171526 -vn 4.352582 -3.918607 1.543823 -v 0.006863 -0.085840 0.171518 -vn 5.192832 -3.510439 -0.130988 -v 0.006877 -0.085820 0.171544 -vn 5.142307 -3.598270 -0.089416 -v 0.006820 -0.085900 0.171481 -vn 3.939914 -3.864527 1.645006 -v 0.006819 -0.085900 0.171473 -vn 4.453151 -3.881151 0.888805 -v 0.006833 -0.085880 0.171490 -vn 1.180036 -4.079430 4.251309 -v 0.006825 -0.085900 0.171469 -vn 2.005297 -4.139952 3.632325 -v 0.006836 -0.085880 0.171485 -vn 5.162853 -3.580213 0.043031 -v 0.006877 -0.085820 0.171552 -vn 5.175975 -3.508801 -0.261875 -v 0.006849 -0.085860 0.171517 -vn -0.016498 -3.995375 4.848282 -v 0.006741 -0.086055 0.171349 -vn 0.905568 -4.167057 4.424903 -v 0.006740 -0.086017 0.171379 -vn 5.074335 -3.700717 -0.109195 -v 0.006805 -0.085920 0.171471 -vn -0.111678 -3.210209 5.393917 -v 0.007006 -0.085651 0.171637 -vn 0.030289 -3.297316 5.347040 -v 0.007026 -0.085651 0.171637 -vn 0.185519 -3.284079 5.345664 -v 0.007068 -0.085651 0.171637 -vn 0.027103 -3.593466 5.143564 -v 0.007161 -0.085820 0.171527 -vn 1.175279 -3.438326 5.092124 -v 0.007069 -0.085519 0.171714 -vn -0.112833 -3.106725 5.456155 -v 0.007052 -0.085564 0.171689 -vn 0.315398 -3.149587 5.415271 -v 0.007074 -0.085519 0.171713 -vn 0.199945 -3.143977 5.431477 -v 0.007062 -0.085564 0.171689 -vn 0.138227 -3.091895 5.464461 -v 0.007079 -0.085519 0.171713 -vn 1.302585 -3.565775 4.820477 -v 0.007041 -0.085564 0.171689 -vn -0.028955 -3.183064 5.412785 -v 0.007046 -0.085564 0.171688 -vn 2.484868 -3.774843 4.257850 -v 0.007066 -0.085519 0.171715 -vn 3.507923 -3.633303 3.252755 -v 0.007089 -0.085474 0.171740 -vn 1.493311 -3.506929 4.900332 -v 0.007092 -0.085474 0.171739 -vn 0.326155 -3.136511 5.423130 -v 0.007096 -0.085474 0.171738 -vn 0.179788 -3.258545 5.362311 -v 0.007023 -0.085608 0.171662 -vn 1.230397 -3.585277 4.928960 -v 0.007018 -0.085608 0.171663 -vn -0.006983 -3.322915 5.309425 -v 0.006994 -0.085651 0.171636 -vn -0.377541 -3.134078 5.430621 -v 0.007000 -0.085651 0.171637 -vn 0.164760 -3.328978 5.284612 -v 0.006985 -0.085673 0.171623 -vn -0.056260 -3.305957 5.327368 -v 0.006987 -0.085694 0.171610 -vn -0.046098 -3.371418 5.290377 -v 0.006976 -0.085694 0.171610 -vn -0.035528 -3.423030 5.267920 -v 0.006968 -0.085737 0.171583 -vn -0.064145 -3.398454 5.284132 -v 0.006947 -0.085737 0.171583 -vn 5.482723 -2.948318 -0.142720 -v 0.007038 -0.085564 0.171694 -vn 5.596287 -2.754311 -0.686629 -v 0.007039 -0.085564 0.171698 -vn 4.529720 -3.777246 1.796569 -v 0.007013 -0.085608 0.171667 -vn 5.271925 -3.203681 0.423187 -v 0.007063 -0.085519 0.171721 -vn -0.006757 -3.579804 5.162895 -v 0.006908 -0.085820 0.171527 -vn 0.000000 -4.119874 4.731465 -v 0.007683 -0.086128 0.171287 -vn 0.000000 -3.566607 5.160436 -v 0.007834 -0.085820 0.171527 -vn 0.023613 -3.578639 5.150240 -v 0.009182 -0.085820 0.171527 -vn 2.595762 -4.163184 3.529787 -v 0.006878 -0.085820 0.171529 -vn 0.896015 -3.928172 4.771322 -v 0.006882 -0.085820 0.171528 -vn 3.360485 -4.351882 2.910833 -v 0.006906 -0.085778 0.171559 -vn 2.028477 -4.198229 4.118494 -v 0.006909 -0.085778 0.171557 -vn 5.291306 -3.343776 -0.362405 -v 0.006905 -0.085778 0.171570 -vn 5.296488 -3.362730 -0.277419 -v 0.006877 -0.085820 0.171535 -vn 5.216724 -3.420259 -0.187021 -v 0.006904 -0.085778 0.171566 -vn 4.522879 -3.901236 1.203927 -v 0.006877 -0.085820 0.171531 -vn 1.847061 -3.957851 4.350334 -v 0.006937 -0.085737 0.171583 -vn 0.467434 -3.587749 5.101952 -v 0.006941 -0.085737 0.171583 -vn 3.217301 -4.113081 3.364981 -v 0.006963 -0.085694 0.171612 -vn 1.371757 -3.751828 4.673822 -v 0.006966 -0.085694 0.171610 -vn 2.784200 -3.671187 3.315390 -v 0.006976 -0.085673 0.171624 -vn 4.897480 -3.753929 1.006160 -v 0.006974 -0.085673 0.171631 -vn 4.209186 -4.085327 2.120704 -v 0.006961 -0.085694 0.171614 -vn 4.900286 -3.759654 0.972448 -v 0.006960 -0.085694 0.171618 -vn 5.235735 -3.454330 0.192934 -v 0.006960 -0.085694 0.171621 -vn 4.438698 -4.074834 1.356837 -v 0.006905 -0.085778 0.171562 -vn 5.172050 -3.566295 0.016027 -v 0.006877 -0.085820 0.171568 -vn 5.524995 -2.990707 0.061934 -v 0.007088 -0.085474 0.171763 -vn 5.492830 -3.015307 -0.183724 -v 0.007039 -0.085564 0.171703 -vn 5.273148 -3.363534 0.354800 -v 0.007012 -0.085608 0.171670 -vn 5.040316 -3.751207 0.013345 -v 0.006820 -0.085900 0.171489 -vn 5.052608 -3.734302 0.030366 -v 0.006820 -0.085900 0.171497 -vn 4.652646 -4.194333 0.271359 -v 0.006668 -0.086092 0.171328 -vn 4.124392 -4.540021 1.188585 -v 0.006668 -0.086092 0.171324 -vn 4.419855 -4.299658 0.851124 -v 0.006684 -0.086073 0.171339 -vn 3.153898 -4.787931 2.414317 -v 0.006670 -0.086092 0.171321 -vn 1.955692 -4.680789 3.592228 -v 0.006672 -0.086092 0.171319 -vn 4.658836 -4.210458 0.147867 -v 0.006684 -0.086073 0.171347 -vn 4.781914 -4.073795 0.089442 -v 0.006699 -0.086055 0.171383 -vn 4.780887 -4.060919 -0.169622 -v 0.006637 -0.086128 0.171306 -vn 4.483354 -4.096668 0.704803 -v 0.006698 -0.086055 0.171353 -vn 5.147631 -3.555119 -0.574300 -v 0.006699 -0.086055 0.171358 -vn 4.910429 -3.869040 -0.208230 -v 0.006700 -0.086055 0.171367 -vn 4.965286 -3.805065 -0.138630 -v 0.006731 -0.086017 0.171404 -vn 4.905711 -3.923988 0.080192 -v 0.006730 -0.086017 0.171420 -vn 0.409305 -4.073504 4.743553 -v 0.006730 -0.086036 0.171364 -vn 2.378829 -4.615966 3.419470 -v 0.006734 -0.086017 0.171382 -vn 4.537611 -4.191794 0.664915 -v 0.006745 -0.085998 0.171406 -vn 5.134303 -3.532327 -0.795070 -v 0.006729 -0.086017 0.171395 -vn 4.729340 -4.135694 0.001672 -v 0.006637 -0.086128 0.171339 -vn 4.824397 -4.023417 0.049361 -v 0.006699 -0.086055 0.171415 -vn 2.212092 -5.034895 2.880630 -v 0.006542 -0.086234 0.171193 -vn 0.326903 -4.500933 4.305737 -v 0.006514 -0.086268 0.171158 -vn 4.910186 -3.912007 0.124618 -v 0.006760 -0.085979 0.171554 -vn 5.140539 -3.599709 0.039490 -v 0.006877 -0.085820 0.171825 -vn 4.694665 -4.166552 0.035361 -v 0.006637 -0.086128 0.171536 -vn 4.731563 -4.119776 -0.000161 -v 0.006637 -0.086128 0.171799 -vn 4.484568 -4.391487 0.157237 -v 0.006375 -0.086397 0.171222 -vn 5.365787 -3.267399 0.031376 -v 0.006987 -0.085651 0.171655 -vn 5.398504 -3.211867 0.098317 -v 0.006987 -0.085651 0.171647 -vn 4.449099 -3.536549 1.682709 -v 0.006987 -0.085651 0.171639 -vn 4.931894 -3.892630 0.002195 -v 0.006760 -0.085979 0.171490 -vn 3.967292 -4.590013 1.339604 -v 0.006387 -0.086397 0.171096 -vn 3.321932 -4.682775 2.525473 -v 0.006402 -0.086397 0.171074 -vn -0.018513 -2.389909 5.810317 -v 0.007258 -0.085168 0.171883 -vn -0.009570 -2.473346 5.775404 -v 0.007251 -0.085192 0.171873 -vn 0.002294 -2.474659 5.774924 -v 0.007271 -0.085192 0.171873 -vn 0.101355 -2.448852 5.783266 -v 0.007313 -0.085192 0.171873 -vn 0.042564 -2.361265 5.821797 -v 0.007285 -0.085144 0.171893 -vn -0.074226 -2.345256 5.827933 -v 0.007265 -0.085144 0.171893 -vn 0.104136 -2.428869 5.790893 -v 0.007247 -0.085168 0.171883 -vn 0.603251 -2.626522 5.644333 -v 0.007230 -0.085192 0.171873 -vn 0.286867 -2.623899 5.695255 -v 0.007223 -0.085216 0.171862 -vn 0.044576 -2.623934 5.705671 -v 0.007366 -0.085288 0.171830 -vn 0.052536 -2.247477 5.860885 -v 0.007421 -0.085095 0.171912 -vn 0.028574 -2.273816 5.855320 -v 0.007340 -0.085095 0.171912 -vn -0.011207 -3.002359 5.517833 -v 0.007117 -0.085474 0.171738 -vn 0.051414 -3.032069 5.502255 -v 0.007107 -0.085474 0.171738 -vn 0.391396 -3.002087 5.495330 -v 0.007115 -0.085451 0.171750 -vn 1.592964 -3.485439 4.802604 -v 0.007106 -0.085451 0.171751 -vn 5.726774 -2.502122 -0.435444 -v 0.007158 -0.085335 0.171818 -vn 5.740974 -2.541908 -0.178114 -v 0.007136 -0.085382 0.171790 -vn 4.992551 -2.941514 1.020770 -v 0.007157 -0.085335 0.171814 -vn 3.563866 -2.745897 2.479223 -v 0.007135 -0.085382 0.171786 -vn 3.630157 -3.580282 3.582698 -v 0.007159 -0.085335 0.171811 -vn 4.215701 -3.232639 2.696394 -v 0.007125 -0.085405 0.171777 -vn 1.282373 -3.028891 4.964902 -v 0.007130 -0.085405 0.171773 -vn 0.762957 -3.015343 5.366937 -v 0.007139 -0.085382 0.171785 -vn 3.976025 -3.540048 2.430496 -v 0.007100 -0.085451 0.171754 -vn 5.208233 -3.181479 0.851766 -v 0.007088 -0.085474 0.171743 -vn 4.108581 -3.779215 2.529733 -v 0.007063 -0.085519 0.171717 -vn 3.883333 -3.557058 2.438823 -v 0.007038 -0.085564 0.171690 -vn 2.975879 -3.934261 3.691052 -v 0.007015 -0.085608 0.171664 -vn 1.898020 -3.775658 4.281426 -v 0.006989 -0.085651 0.171637 -vn 1.143435 -2.923308 5.260694 -v 0.007165 -0.085335 0.171808 -vn 2.695514 -3.328255 4.572675 -v 0.007162 -0.085335 0.171809 -vn -0.041287 -2.802333 5.622432 -v 0.007150 -0.085382 0.171785 -vn -0.062848 -2.828440 5.594794 -v 0.007134 -0.085428 0.171762 -vn 0.674938 -3.059880 5.319740 -v 0.007122 -0.085428 0.171761 -vn 2.926587 -3.469325 3.928802 -v 0.007115 -0.085428 0.171764 -vn 5.400184 -3.068878 0.593288 -v 0.007124 -0.085405 0.171784 -vn 4.785205 -3.396514 1.642983 -v 0.007112 -0.085428 0.171769 -vn 5.583534 -2.788962 -0.248673 -v 0.007111 -0.085428 0.171773 -vn 5.619777 -2.749091 -0.345781 -v 0.007112 -0.085428 0.171777 -vn 5.629133 -2.751338 -0.444385 -v 0.007088 -0.085474 0.171747 -vn 5.630589 -2.783929 0.074074 -v 0.007136 -0.085382 0.171798 -vn 5.630064 -2.788578 0.024934 -v 0.007135 -0.085382 0.171806 -vn 5.621714 -2.802200 0.052934 -v 0.007135 -0.085382 0.171822 -vn -0.061320 -2.304169 5.844385 -v 0.007271 -0.085119 0.171903 -vn 0.340635 -2.451083 5.752638 -v 0.007254 -0.085144 0.171892 -vn 1.369590 -2.813982 5.332996 -v 0.007238 -0.085168 0.171883 -vn 3.541384 -2.428865 2.626650 -v 0.007222 -0.085192 0.171874 -vn 2.930587 -2.714818 3.566615 -v 0.007214 -0.085216 0.171863 -vn 1.890175 -2.949142 4.816044 -v 0.007206 -0.085240 0.171852 -vn 0.751555 -2.865574 5.478861 -v 0.007198 -0.085264 0.171841 -vn 0.125764 -2.761897 5.640075 -v 0.007191 -0.085288 0.171830 -vn 2.648500 -2.899209 3.689324 -v 0.007181 -0.085288 0.171831 -vn 3.405525 -2.893244 2.868018 -v 0.007191 -0.085264 0.171843 -vn 5.514771 -2.656723 0.597816 -v 0.007180 -0.085288 0.171834 -vn 5.763261 -2.338832 -0.428356 -v 0.007201 -0.085240 0.171860 -vn 5.747761 -2.535120 0.003602 -v 0.007202 -0.085240 0.171872 -vn 5.700392 -2.641173 -0.023974 -v 0.007180 -0.085288 0.171846 -vn 5.774119 -2.477328 -0.016908 -v 0.007223 -0.085192 0.171890 -vn 5.778868 -2.466205 0.014282 -v 0.007223 -0.085192 0.171898 -vn 0.733420 -2.522894 5.633228 -v 0.007261 -0.085119 0.171902 -vn 2.530914 -2.914648 4.567535 -v 0.007246 -0.085144 0.171894 -vn 4.220861 -2.605699 1.976874 -v 0.007232 -0.085168 0.171886 -vn 5.809004 -2.379405 -0.031512 -v 0.007223 -0.085192 0.171882 -vn 5.442061 -2.854565 1.011669 -v 0.007212 -0.085216 0.171869 -vn 4.476707 -3.010313 2.202924 -v 0.007201 -0.085240 0.171856 -vn 5.762357 -2.503856 0.013084 -v 0.007223 -0.085192 0.171886 -vn 5.831718 -2.240005 -0.367202 -v 0.007233 -0.085168 0.171895 -vn 5.809425 -2.391950 0.083109 -v 0.007243 -0.085144 0.171923 -vn 5.898345 -2.157006 -0.072756 -v 0.007262 -0.085095 0.171931 -vn 5.885105 -2.197155 -0.001241 -v 0.007262 -0.085095 0.171947 -vn 5.872649 -2.229673 0.004408 -v 0.007262 -0.085095 0.171977 -vn 5.773794 -2.474368 0.071110 -v 0.007223 -0.085192 0.171929 -vn 5.531795 -2.975598 0.021543 -v 0.007088 -0.085474 0.171826 -vn 5.345567 -3.297400 0.053548 -v 0.006987 -0.085651 0.171702 -vn 5.370305 -3.259827 -0.001581 -v 0.006987 -0.085651 0.171671 -vn 1.287003 -2.692020 5.511643 -v 0.007283 -0.085045 0.171933 -vn 2.682955 -2.529642 4.218374 -v 0.007263 -0.085095 0.171913 -vn 0.294641 -2.396118 5.791654 -v 0.007268 -0.085095 0.171912 -vn 3.579787 -2.782341 3.418770 -v 0.007254 -0.085119 0.171905 -vn -0.061239 -1.788544 6.022625 -v 0.007368 -0.084843 0.171999 -vn 0.016162 -1.966167 5.966200 -v 0.007368 -0.084894 0.171983 -vn 0.019687 -1.712758 6.015742 -v 0.007389 -0.084792 0.172014 -vn 0.501611 -1.935747 5.926515 -v 0.007388 -0.084894 0.171983 -vn 0.076624 -1.602667 6.071094 -v 0.007428 -0.084688 0.172042 -vn 0.058109 -2.096970 5.914370 -v 0.007324 -0.084995 0.171949 -vn -0.030679 -1.935116 5.974679 -v 0.007357 -0.084894 0.171983 -vn 0.227606 -2.149149 5.885312 -v 0.007313 -0.084995 0.171949 -vn 1.225873 -2.305991 5.682721 -v 0.007309 -0.084995 0.171949 -vn 3.530394 -2.525456 4.350729 -v 0.007312 -0.084970 0.171960 -vn 2.444953 -2.583357 5.084132 -v 0.007305 -0.084995 0.171950 -vn 4.617846 -2.784617 3.203000 -v 0.007308 -0.084970 0.171964 -vn 3.401902 -2.924505 4.371147 -v 0.007300 -0.084995 0.171954 -vn 6.004625 -1.803187 -0.117270 -v 0.007333 -0.084894 0.171991 -vn 5.568935 -2.450265 1.563637 -v 0.007316 -0.084945 0.171975 -vn 5.396597 -2.465998 2.014524 -v 0.007317 -0.084945 0.171972 -vn 4.290599 -2.561719 3.571360 -v 0.007319 -0.084945 0.171969 -vn 2.378930 -2.465540 5.141781 -v 0.007321 -0.084945 0.171967 -vn 0.725685 -2.182327 5.811721 -v 0.007325 -0.084945 0.171966 -vn 5.443223 -2.198875 1.672987 -v 0.007333 -0.084894 0.171988 -vn 3.684898 -2.491046 4.131438 -v 0.007335 -0.084894 0.171985 -vn 1.455929 -2.296488 5.562521 -v 0.007338 -0.084894 0.171984 -vn 0.160220 -1.995842 5.950198 -v 0.007347 -0.084894 0.171983 -vn 6.100854 -1.434613 -0.133292 -v 0.007392 -0.084688 0.172054 -vn 5.883697 -1.936210 1.048945 -v 0.007379 -0.084740 0.172037 -vn 5.888386 -1.838947 1.178618 -v 0.007379 -0.084740 0.172033 -vn 5.934386 -1.899353 0.754999 -v 0.007378 -0.084740 0.172040 -vn 6.095431 -1.517783 0.068233 -v 0.007392 -0.084688 0.172061 -vn 5.997106 -1.835533 0.375506 -v 0.007378 -0.084740 0.172044 -vn 6.073714 -1.491533 0.352798 -v 0.007404 -0.084636 0.172061 -vn 5.838181 -1.614297 0.875285 -v 0.007392 -0.084688 0.172045 -vn 3.459447 -1.912782 4.018909 -v 0.007393 -0.084688 0.172043 -vn 4.997715 -1.952080 2.832434 -v 0.007380 -0.084740 0.172030 -vn 5.737193 -2.263602 0.696997 -v 0.007315 -0.084945 0.171978 -vn 5.999292 -1.812020 -0.258569 -v 0.007333 -0.084894 0.171996 -vn 5.970364 -1.933531 0.117987 -v 0.007333 -0.084894 0.172003 -vn 5.832315 -1.983898 0.759901 -v 0.007348 -0.084843 0.172007 -vn 1.884864 -2.239842 5.534337 -v 0.007354 -0.084843 0.172000 -vn 4.311068 -2.316122 3.911641 -v 0.007367 -0.084792 0.172017 -vn 3.160737 -2.481286 4.743271 -v 0.007351 -0.084843 0.172001 -vn 4.934159 -2.364105 3.052132 -v 0.007365 -0.084792 0.172019 -vn 4.775463 -2.405432 2.938050 -v 0.007349 -0.084843 0.172004 -vn 5.551322 -2.191372 1.740019 -v 0.007364 -0.084792 0.172022 -vn 5.952379 -1.907515 0.537867 -v 0.007363 -0.084792 0.172025 -vn 6.096458 -1.502500 0.036260 -v 0.007392 -0.084688 0.172076 -vn 6.084123 -1.524367 0.021490 -v 0.007392 -0.084688 0.172198 -vn -0.245439 -1.653463 6.050251 -v 0.007378 -0.084792 0.172013 -vn 0.240464 -1.835958 5.997044 -v 0.007363 -0.084843 0.171999 -vn 4.872436 -2.525157 1.830454 -v 0.007297 -0.084995 0.171956 -vn 3.780845 -2.531159 2.837258 -v 0.007280 -0.085045 0.171934 -vn 5.695169 -2.647724 0.062060 -v 0.007180 -0.085288 0.171939 -vn 5.850914 -2.259967 0.014459 -v 0.007262 -0.085095 0.172286 -vn 5.522032 -2.979989 0.039197 -v 0.007088 -0.085474 0.172078 -vn 5.536958 -2.946921 0.000000 -v 0.007088 -0.085474 0.172581 -vn 5.929766 -2.064481 -0.174898 -v 0.007298 -0.084995 0.171960 -vn 5.939045 -2.040058 -0.093666 -v 0.007316 -0.084945 0.171982 -vn 5.869830 -2.229194 0.040089 -v 0.007262 -0.085095 0.172039 -vn 5.447472 -2.505641 1.256033 -v 0.007262 -0.085095 0.171915 -vn 5.897892 -2.148313 0.085892 -v 0.007279 -0.085045 0.171938 -vn -0.249613 -0.824579 6.219596 -v 0.007478 -0.084263 0.172123 -vn 0.890483 -0.903386 6.035019 -v 0.007475 -0.084263 0.172123 -vn 0.530345 -1.163547 6.120107 -v 0.007460 -0.084477 0.172089 -vn 1.686975 -1.116204 5.946470 -v 0.007462 -0.084370 0.172107 -vn 2.846740 -1.071119 5.398243 -v 0.007468 -0.084317 0.172115 -vn -0.442832 -1.522361 6.079746 -v 0.007402 -0.084688 0.172042 -vn -0.196556 -1.521208 6.085017 -v 0.007408 -0.084688 0.172042 -vn 0.787972 -1.485955 6.052253 -v 0.007425 -0.084583 0.172067 -vn 1.736472 -1.509732 5.779418 -v 0.007432 -0.084530 0.172078 -vn 4.095758 -1.572441 3.868905 -v 0.007429 -0.084530 0.172080 -vn 5.330192 -1.310483 1.983057 -v 0.007438 -0.084477 0.172092 -vn 6.167710 -0.973633 -0.560770 -v 0.007438 -0.084477 0.172096 -vn 0.579227 -1.583857 6.051154 -v 0.007412 -0.084636 0.172055 -vn 6.112725 -1.391240 0.383888 -v 0.007428 -0.084530 0.172086 -vn 6.154738 -1.017231 -0.615823 -v 0.007439 -0.084477 0.172100 -vn -0.070730 -1.236869 6.157293 -v 0.007450 -0.084477 0.172089 -vn 1.474185 -1.292012 5.878899 -v 0.007452 -0.084424 0.172099 -vn 0.326988 -1.310578 6.121305 -v 0.007445 -0.084477 0.172089 -vn 4.097200 -1.388310 3.830207 -v 0.007449 -0.084424 0.172100 -vn 2.642478 -1.477390 5.072757 -v 0.007440 -0.084477 0.172089 -vn 5.975090 -1.173693 0.789090 -v 0.007447 -0.084424 0.172103 -vn 6.083179 -1.003354 0.203086 -v 0.007457 -0.084370 0.172119 -vn 6.173069 -0.920334 -0.259083 -v 0.007457 -0.084370 0.172114 -vn 5.573113 -1.184502 2.022316 -v 0.007457 -0.084370 0.172111 -vn 6.235184 -0.729044 0.186007 -v 0.007473 -0.084263 0.172145 -vn 6.126223 -0.988302 0.314010 -v 0.007466 -0.084317 0.172129 -vn 6.218130 -0.702847 -0.128723 -v 0.007473 -0.084263 0.172138 -vn 6.196543 -0.875189 0.033395 -v 0.007465 -0.084317 0.172121 -vn 6.227987 -0.745345 0.020971 -v 0.007473 -0.084263 0.172176 -vn 5.987633 -1.304883 0.770580 -v 0.007439 -0.084477 0.172104 -vn 3.409949 -1.252960 4.723646 -v 0.007459 -0.084370 0.172108 -vn 0.516211 -1.109957 6.162525 -v 0.007456 -0.084424 0.172099 -vn 4.622161 -1.807927 2.885335 -v 0.007404 -0.084636 0.172057 -vn 6.124260 -1.394343 0.147654 -v 0.007416 -0.084583 0.172076 -vn 0.030348 -1.580000 6.071080 -v 0.007509 -0.084688 0.172042 -vn 0.045419 -0.832120 6.218096 -v 0.007564 -0.084263 0.172123 -vn -0.025346 -0.883990 6.216001 -v 0.007483 -0.084263 0.172123 -vn 0.362166 -0.598243 6.242698 -v 0.007491 -0.084154 0.172135 -vn 1.074437 -0.700848 6.130619 -v 0.007487 -0.084154 0.172135 -vn 6.248134 -0.610132 0.232973 -v 0.007483 -0.084154 0.172140 -vn 3.961837 -0.698818 3.219512 -v 0.007483 -0.084154 0.172136 -vn 6.262526 -0.011633 -0.346828 -v 0.007500 -0.083827 0.172156 -vn 6.198782 -0.240901 0.984920 -v 0.007498 -0.083936 0.172154 -vn 6.186418 -0.012603 0.416419 -v 0.007500 -0.083827 0.172154 -vn 4.991497 -0.256107 3.003871 -v 0.007498 -0.083936 0.172150 -vn 3.129415 -0.000000 3.939943 -v 0.007501 -0.083827 0.172151 -vn 2.045285 -0.306551 5.686461 -v 0.007501 -0.083936 0.172149 -vn 1.964792 -0.443192 5.846609 -v 0.007495 -0.084045 0.172144 -vn 4.580109 -0.550740 3.585651 -v 0.007492 -0.084045 0.172146 -vn 6.118593 -0.449143 0.304885 -v 0.007492 -0.084045 0.172149 -vn 6.117779 -0.330495 -1.362655 -v 0.007492 -0.084045 0.172151 -vn 5.700856 -2.640587 0.009012 -v 0.007180 -0.085288 0.171877 -vn 5.165592 -3.572661 0.005295 -v 0.006877 -0.085820 0.171696 -vn 1.865909 -5.642806 1.988666 -v 0.005838 -0.086973 0.170446 -vn 0.084477 3.555668 5.162432 -v 0.009182 -0.081834 0.171527 -vn 0.000000 3.566633 5.160420 -v 0.007834 -0.081834 0.171527 -vn 0.000000 4.119874 4.731465 -v 0.007683 -0.081525 0.171287 -vn 0.026643 4.154006 4.704239 -v 0.006997 -0.081525 0.171287 -vn 0.000000 4.603044 4.264030 -v 0.006819 -0.081256 0.171025 -vn -0.011313 0.780020 6.222821 -v 0.008208 -0.083391 0.172123 -vn 0.171106 0.953213 6.197097 -v 0.009420 -0.083320 0.172113 -vn -0.003589 1.543225 6.078629 -v 0.008158 -0.082965 0.172042 -vn 0.296569 1.591898 6.045027 -v 0.009455 -0.082965 0.172042 -vn 0.009757 2.262614 5.849758 -v 0.008076 -0.082559 0.171912 -vn 0.391596 2.436230 5.731685 -v 0.009386 -0.082559 0.171912 -vn 0.014198 2.959368 5.531150 -v 0.007967 -0.082180 0.171738 -vn 0.369462 0.625093 6.239387 -v 0.007491 -0.083499 0.172135 -vn 1.074696 0.715942 6.128057 -v 0.007487 -0.083499 0.172135 -vn 4.566492 0.524643 3.596356 -v 0.007492 -0.083608 0.172146 -vn 4.992035 0.263090 2.999209 -v 0.007498 -0.083717 0.172150 -vn 1.826036 0.454702 5.857243 -v 0.007495 -0.083608 0.172144 -vn 1.958819 0.259647 5.694017 -v 0.007501 -0.083717 0.172149 -vn 0.113027 -0.004771 6.274828 -v 0.007582 -0.083827 0.172150 -vn 0.073749 0.803533 6.223266 -v 0.007564 -0.083391 0.172123 -vn 4.205234 0.830138 2.656222 -v 0.007472 -0.083391 0.172124 -vn 2.823923 1.106502 5.407251 -v 0.007468 -0.083337 0.172115 -vn 5.004139 1.049877 2.734829 -v 0.007465 -0.083337 0.172117 -vn 0.237030 1.217461 6.150624 -v 0.007460 -0.083176 0.172089 -vn 0.879610 0.918594 6.032601 -v 0.007475 -0.083391 0.172123 -vn 3.954462 0.692253 3.218709 -v 0.007483 -0.083499 0.172136 -vn -0.060284 0.827866 6.225169 -v 0.007483 -0.083391 0.172123 -vn -0.234164 0.837567 6.218826 -v 0.007478 -0.083391 0.172123 -vn 6.118177 0.435734 0.297426 -v 0.007492 -0.083608 0.172149 -vn 6.247167 0.618007 0.237428 -v 0.007483 -0.083499 0.172140 -vn 6.222095 0.651974 -0.573450 -v 0.007472 -0.083391 0.172130 -vn 6.200894 0.872528 -0.012399 -v 0.007465 -0.083337 0.172121 -vn 6.126310 0.987091 0.313321 -v 0.007466 -0.083337 0.172129 -vn 0.492106 1.097514 6.166464 -v 0.007456 -0.083230 0.172099 -vn 1.651289 1.108842 5.958523 -v 0.007462 -0.083283 0.172107 -vn 1.454333 1.276116 5.899343 -v 0.007452 -0.083230 0.172099 -vn 3.406940 1.262235 4.762188 -v 0.007459 -0.083283 0.172108 -vn 4.126564 1.400114 3.845359 -v 0.007449 -0.083230 0.172100 -vn 5.605070 1.204946 1.986394 -v 0.007457 -0.083283 0.172111 -vn 5.988681 1.168703 0.754022 -v 0.007447 -0.083230 0.172103 -vn 6.171002 0.937911 -0.274148 -v 0.007457 -0.083283 0.172114 -vn 6.083179 1.003354 0.203086 -v 0.007457 -0.083283 0.172119 -vn -0.196557 1.521155 6.085032 -v 0.007408 -0.082965 0.172042 -vn -0.457486 1.496159 6.085052 -v 0.007402 -0.082965 0.172042 -vn 0.538410 1.562151 6.061251 -v 0.007412 -0.083018 0.172055 -vn 0.475875 1.669222 5.968438 -v 0.007397 -0.082965 0.172042 -vn 1.958624 1.845202 5.510372 -v 0.007407 -0.083018 0.172056 -vn 0.046718 1.551254 6.086664 -v 0.007428 -0.082965 0.172042 -vn 0.772268 1.457278 6.061714 -v 0.007425 -0.083070 0.172067 -vn 1.699192 1.505478 5.797652 -v 0.007432 -0.083123 0.172078 -vn 2.003004 1.677135 5.601666 -v 0.007420 -0.083070 0.172068 -vn 4.103165 1.605796 3.903969 -v 0.007429 -0.083123 0.172080 -vn 4.263803 1.854168 3.902699 -v 0.007418 -0.083070 0.172069 -vn 5.904593 1.455768 1.227770 -v 0.007428 -0.083123 0.172083 -vn 5.769132 1.630480 1.346205 -v 0.007416 -0.083070 0.172072 -vn 6.115079 1.384809 0.348049 -v 0.007428 -0.083123 0.172086 -vn -0.079340 1.222209 6.159713 -v 0.007450 -0.083176 0.172089 -vn 0.318673 1.270553 6.131768 -v 0.007445 -0.083176 0.172089 -vn 2.628340 1.462974 5.107221 -v 0.007440 -0.083176 0.172089 -vn 5.353590 1.352967 1.971811 -v 0.007438 -0.083176 0.172092 -vn 6.160959 1.023452 -0.568651 -v 0.007438 -0.083176 0.172096 -vn 6.150802 1.030043 -0.627365 -v 0.007439 -0.083176 0.172100 -vn 0.056906 1.560099 6.077736 -v 0.007509 -0.082965 0.172042 -vn 5.987633 1.304883 0.770580 -v 0.007439 -0.083176 0.172104 -vn 6.122673 1.401536 0.140824 -v 0.007416 -0.083070 0.172076 -vn 6.079060 1.559976 0.065128 -v 0.007392 -0.082965 0.172076 -vn 6.076797 1.490237 0.332584 -v 0.007404 -0.083018 0.172061 -vn 0.019974 1.712789 6.015689 -v 0.007389 -0.082862 0.172014 -vn 0.028501 1.659505 6.044010 -v 0.007387 -0.082913 0.172028 -vn 3.487285 1.812765 4.030494 -v 0.007393 -0.082965 0.172043 -vn 4.656940 1.823893 2.878601 -v 0.007404 -0.083018 0.172057 -vn 2.302172 1.911311 5.118548 -v 0.007382 -0.082913 0.172028 -vn 4.987717 1.892665 2.840432 -v 0.007380 -0.082913 0.172030 -vn 5.850433 1.563188 0.887277 -v 0.007392 -0.082965 0.172045 -vn 0.019221 2.245337 5.867023 -v 0.007340 -0.082559 0.171912 -vn 0.016142 1.966193 5.966192 -v 0.007368 -0.082759 0.171983 -vn 0.223742 1.970477 5.953141 -v 0.007388 -0.082759 0.171983 -vn 0.275620 1.840564 5.992291 -v 0.007363 -0.082810 0.171999 -vn 0.989068 2.033089 5.842750 -v 0.007358 -0.082810 0.171999 -vn 3.013461 2.150059 4.935090 -v 0.007369 -0.082862 0.172015 -vn 4.300050 2.307318 3.913845 -v 0.007367 -0.082862 0.172017 -vn 5.909392 1.758992 1.188089 -v 0.007379 -0.082913 0.172033 -vn 5.899387 1.883077 1.060474 -v 0.007379 -0.082913 0.172037 -vn 6.100854 1.434613 -0.133292 -v 0.007392 -0.082965 0.172054 -vn 1.934625 2.235708 5.509093 -v 0.007354 -0.082810 0.172000 -vn 4.919016 2.358814 3.066360 -v 0.007365 -0.082862 0.172019 -vn 5.939767 1.875888 0.765473 -v 0.007378 -0.082913 0.172040 -vn 6.095431 1.517783 0.068233 -v 0.007392 -0.082965 0.172061 -vn -0.038463 1.970676 5.962899 -v 0.007357 -0.082759 0.171983 -vn 0.189342 2.071394 5.923036 -v 0.007347 -0.082759 0.171983 -vn 3.123022 2.429125 4.769918 -v 0.007351 -0.082810 0.172001 -vn 5.539693 2.187442 1.756881 -v 0.007364 -0.082862 0.172022 -vn 5.998169 1.831228 0.379177 -v 0.007378 -0.082913 0.172044 -vn 0.745350 2.191764 5.803117 -v 0.007325 -0.082708 0.171966 -vn 2.366597 2.488614 5.127291 -v 0.007321 -0.082708 0.171967 -vn 3.682407 2.472161 4.119955 -v 0.007335 -0.082759 0.171985 -vn 5.440273 2.154711 1.681316 -v 0.007333 -0.082759 0.171988 -vn 6.020473 1.739231 -0.117531 -v 0.007333 -0.082759 0.171991 -vn 5.367445 2.484408 2.049509 -v 0.007317 -0.082708 0.171972 -vn 4.314322 2.543624 3.522497 -v 0.007319 -0.082708 0.171969 -vn 3.460225 2.641510 4.351001 -v 0.007312 -0.082683 0.171960 -vn 5.932385 2.057505 -0.169793 -v 0.007298 -0.082658 0.171960 -vn 5.938805 2.040670 -0.094364 -v 0.007316 -0.082708 0.171982 -vn 5.736585 2.265462 0.697769 -v 0.007315 -0.082708 0.171978 -vn 5.544506 2.496460 1.580796 -v 0.007316 -0.082708 0.171975 -vn 0.123103 2.089414 5.912320 -v 0.007324 -0.082658 0.171949 -vn 0.013966 2.268719 5.858973 -v 0.007299 -0.082559 0.171912 -vn 0.235340 2.164189 5.878741 -v 0.007313 -0.082658 0.171949 -vn 1.164165 2.377010 5.669998 -v 0.007309 -0.082658 0.171949 -vn 1.460697 2.324749 5.541126 -v 0.007338 -0.082759 0.171984 -vn 4.761551 2.390703 2.942646 -v 0.007349 -0.082810 0.172004 -vn 5.950067 1.909385 0.549740 -v 0.007363 -0.082862 0.172025 -vn 0.405721 2.487225 5.726707 -v 0.007254 -0.082510 0.171892 -vn 0.173898 2.427689 5.787064 -v 0.007247 -0.082485 0.171883 -vn 2.590588 2.860930 4.466319 -v 0.007246 -0.082510 0.171894 -vn -0.060046 2.319213 5.838710 -v 0.007271 -0.082534 0.171903 -vn 0.742167 2.439870 5.669161 -v 0.007261 -0.082534 0.171902 -vn 3.673394 2.539774 3.397754 -v 0.007254 -0.082534 0.171905 -vn 5.730521 2.353976 0.444281 -v 0.007252 -0.082534 0.171911 -vn 5.418115 2.547273 1.267282 -v 0.007262 -0.082559 0.171915 -vn 2.720195 2.670073 4.142683 -v 0.007263 -0.082559 0.171913 -vn 5.852221 2.183900 -0.371230 -v 0.007243 -0.082510 0.171907 -vn 1.422294 2.820518 5.266220 -v 0.007238 -0.082485 0.171883 -vn 0.013359 2.484612 5.770787 -v 0.007251 -0.082461 0.171873 -vn 0.590516 2.750033 5.577262 -v 0.007230 -0.082461 0.171873 -vn 0.227803 2.585523 5.717902 -v 0.007223 -0.082437 0.171862 -vn 2.859023 2.855841 3.709838 -v 0.007214 -0.082437 0.171863 -vn 1.744947 2.957521 4.948906 -v 0.007206 -0.082413 0.171852 -vn 4.639546 3.003365 2.071988 -v 0.007201 -0.082413 0.171856 -vn 3.545198 2.922956 2.813824 -v 0.007191 -0.082389 0.171843 -vn 0.019133 2.662416 5.690413 -v 0.007201 -0.082365 0.171830 -vn 0.084140 2.559095 5.737525 -v 0.007216 -0.082413 0.171852 -vn 5.750861 2.524075 0.048085 -v 0.007202 -0.082413 0.171872 -vn 5.583789 2.665492 0.666421 -v 0.007212 -0.082437 0.171869 -vn 5.783938 2.330543 -0.539636 -v 0.007202 -0.082413 0.171864 -vn 5.755692 2.343099 -0.457876 -v 0.007201 -0.082413 0.171860 -vn 5.556983 2.505515 0.586429 -v 0.007180 -0.082365 0.171834 -vn 5.861673 2.218729 -0.172653 -v 0.007253 -0.082534 0.171919 -vn 5.808925 2.391473 0.117513 -v 0.007243 -0.082510 0.171923 -vn 5.768552 2.478174 0.146247 -v 0.007223 -0.082461 0.171929 -vn 5.687307 2.668239 0.022314 -v 0.007180 -0.082365 0.171877 -vn 4.994104 2.602210 1.331200 -v 0.007242 -0.082510 0.171899 -vn 4.116682 2.528718 2.011487 -v 0.007232 -0.082485 0.171886 -vn 3.452758 2.707718 2.624008 -v 0.007222 -0.082461 0.171874 -vn 1.277456 3.058398 5.019538 -v 0.007130 -0.082248 0.171773 -vn 3.579979 2.893229 2.382475 -v 0.007135 -0.082272 0.171786 -vn 0.695495 3.176880 5.286870 -v 0.007139 -0.082272 0.171785 -vn 4.958966 2.928462 1.067302 -v 0.007157 -0.082318 0.171814 -vn 5.672617 2.697533 0.101592 -v 0.007180 -0.082365 0.171842 -vn 5.759683 2.461296 -0.160924 -v 0.007180 -0.082365 0.171838 -vn 3.575081 3.497514 3.656966 -v 0.007159 -0.082318 0.171811 -vn 2.798355 3.302751 4.506245 -v 0.007162 -0.082318 0.171809 -vn -0.031131 2.851501 5.597277 -v 0.007150 -0.082272 0.171785 -vn -0.137374 2.816987 5.605327 -v 0.007134 -0.082225 0.171762 -vn -0.011667 3.005440 5.516241 -v 0.007117 -0.082180 0.171738 -vn 0.174364 2.949746 5.532842 -v 0.007115 -0.082203 0.171750 -vn 0.019100 2.978510 5.530825 -v 0.007107 -0.082180 0.171738 -vn 0.362564 3.107293 5.438109 -v 0.007096 -0.082180 0.171738 -vn 4.204670 3.372509 2.705244 -v 0.007125 -0.082248 0.171777 -vn 5.697272 2.647517 -0.032268 -v 0.007180 -0.082365 0.171846 -vn 5.737495 2.473351 -0.441388 -v 0.007158 -0.082318 0.171818 -vn 5.682295 2.666041 -0.126733 -v 0.007136 -0.082272 0.171790 -vn 5.589976 2.771919 -0.254907 -v 0.007111 -0.082225 0.171773 -vn 4.887476 3.360323 1.540823 -v 0.007112 -0.082225 0.171769 -vn 5.455947 3.013438 0.496899 -v 0.007124 -0.082248 0.171784 -vn 5.619126 2.750783 -0.333972 -v 0.007112 -0.082225 0.171777 -vn 5.629810 2.789106 0.024316 -v 0.007135 -0.082272 0.171806 -vn 5.619237 2.807216 0.039024 -v 0.007136 -0.082272 0.171798 -vn 5.656855 2.692184 -0.426704 -v 0.007088 -0.082180 0.171747 -vn 5.595541 2.810530 -0.347743 -v 0.007088 -0.082180 0.171752 -vn 5.516370 2.998643 0.022230 -v 0.007088 -0.082180 0.171756 -vn 0.091594 3.294804 5.345998 -v 0.007068 -0.082002 0.171637 -vn 0.009937 3.012321 5.512674 -v 0.007138 -0.082180 0.171738 -vn 0.026985 3.025116 5.500910 -v 0.007304 -0.082180 0.171738 -vn 0.037316 2.770564 5.638043 -v 0.007170 -0.082272 0.171786 -vn 1.207511 2.973110 5.218425 -v 0.007165 -0.082318 0.171808 -vn 0.020068 2.639771 5.699200 -v 0.007366 -0.082365 0.171830 -vn 0.040818 2.221747 5.872484 -v 0.007421 -0.082559 0.171912 -vn 5.891010 2.175681 -0.064222 -v 0.007262 -0.082559 0.171931 -vn 5.896464 2.147352 0.111803 -v 0.007279 -0.082608 0.171938 -vn 3.763069 2.485079 2.824304 -v 0.007280 -0.082608 0.171934 -vn 1.388218 2.715736 5.477103 -v 0.007283 -0.082608 0.171933 -vn 2.387800 2.653959 5.107023 -v 0.007305 -0.082658 0.171950 -vn 5.877984 2.214960 -0.001096 -v 0.007262 -0.082559 0.171947 -vn 5.859035 2.262598 0.013489 -v 0.007262 -0.082559 0.171977 -vn 5.846862 2.279811 0.059284 -v 0.007262 -0.082559 0.172039 -vn 6.079085 1.540826 -0.000045 -v 0.007392 -0.082965 0.172198 -vn 5.847303 2.268050 0.000000 -v 0.007262 -0.082559 0.172286 -vn 5.615247 2.808461 0.130350 -v 0.007135 -0.082272 0.171822 -vn 5.507701 3.021497 0.074340 -v 0.007088 -0.082180 0.171763 -vn 0.044210 3.593813 5.144631 -v 0.007161 -0.081834 0.171527 -vn -3.383440 0.631930 3.067048 -v 0.009500 -0.083113 0.172076 -vn 0.146848 3.110234 5.454402 -v 0.007079 -0.082135 0.171713 -vn 0.341761 3.171453 5.397373 -v 0.007074 -0.082135 0.171713 -vn 1.511858 3.463454 4.918353 -v 0.007092 -0.082180 0.171739 -vn 1.196460 3.443565 5.068471 -v 0.007069 -0.082135 0.171714 -vn -0.097649 3.159769 5.427444 -v 0.007052 -0.082090 0.171689 -vn 2.495767 3.749001 4.234999 -v 0.007066 -0.082135 0.171715 -vn -0.026907 3.267026 5.359330 -v 0.007046 -0.082090 0.171688 -vn 4.089840 3.727949 2.544874 -v 0.007063 -0.082135 0.171717 -vn 1.328050 3.609412 4.760973 -v 0.007041 -0.082090 0.171689 -vn 5.258665 3.189979 0.460927 -v 0.007063 -0.082135 0.171721 -vn 0.023870 3.266982 5.366339 -v 0.007026 -0.082002 0.171637 -vn -0.109426 3.215263 5.392611 -v 0.007006 -0.082002 0.171637 -vn 0.230717 3.289824 5.339590 -v 0.007023 -0.082046 0.171662 -vn 1.269263 3.598991 4.884237 -v 0.007018 -0.082046 0.171663 -vn 3.896326 3.445752 2.422666 -v 0.007038 -0.082090 0.171690 -vn 5.514850 2.844922 -0.127213 -v 0.007038 -0.082090 0.171694 -vn 5.599461 2.816646 -0.419447 -v 0.007063 -0.082135 0.171725 -vn 0.208543 3.159029 5.422957 -v 0.007062 -0.082090 0.171689 -vn 5.488585 3.015977 -0.087332 -v 0.007039 -0.082090 0.171703 -vn 5.625220 2.702602 -0.673248 -v 0.007039 -0.082090 0.171698 -vn 4.503946 3.740128 1.829300 -v 0.007013 -0.082046 0.171667 -vn 2.977856 3.880624 3.679501 -v 0.007015 -0.082046 0.171664 -vn -0.000274 3.408216 5.247167 -v 0.006994 -0.082002 0.171636 -vn -0.357598 3.201048 5.393841 -v 0.007000 -0.082002 0.171637 -vn -0.126684 3.304774 5.331598 -v 0.006987 -0.081959 0.171610 -vn 5.264565 3.364492 0.351313 -v 0.007012 -0.082046 0.171670 -vn 2.094116 3.594790 4.236748 -v 0.006989 -0.082002 0.171637 -vn 4.295846 3.570310 1.915744 -v 0.006987 -0.082002 0.171639 -vn 2.766281 3.724732 3.314665 -v 0.006976 -0.081981 0.171624 -vn 0.005856 3.616690 5.136283 -v 0.006950 -0.081834 0.171527 -vn -0.034961 3.443665 5.254664 -v 0.006968 -0.081917 0.171583 -vn 0.094208 3.464904 5.238725 -v 0.006989 -0.081917 0.171583 -vn 5.365787 3.267399 0.031375 -v 0.006987 -0.082002 0.171655 -vn 5.384218 3.237701 0.054912 -v 0.006987 -0.082002 0.171647 -vn 4.930731 3.707498 0.987448 -v 0.006960 -0.081959 0.171618 -vn 5.240042 3.446405 0.205595 -v 0.006960 -0.081959 0.171621 -vn -0.037732 3.477735 5.230433 -v 0.006928 -0.081875 0.171555 -vn 0.659933 3.607896 5.024920 -v 0.006916 -0.081875 0.171555 -vn 1.223725 3.815504 4.625401 -v 0.006926 -0.081896 0.171569 -vn -0.033438 3.478725 5.231911 -v 0.006947 -0.081917 0.171583 -vn 0.418908 3.695177 5.024091 -v 0.006941 -0.081917 0.171583 -vn 1.872794 4.062530 4.245526 -v 0.006937 -0.081917 0.171583 -vn 3.539850 4.157417 2.834303 -v 0.006934 -0.081917 0.171585 -vn 4.758280 3.826915 1.047616 -v 0.006933 -0.081917 0.171588 -vn 3.590987 4.103000 2.659319 -v 0.006921 -0.081896 0.171573 -vn 4.997747 3.676901 0.569341 -v 0.006919 -0.081896 0.171579 -vn 3.412650 4.260784 2.956995 -v 0.006906 -0.081875 0.171559 -vn 4.479486 4.000733 1.381681 -v 0.006905 -0.081875 0.171562 -vn 2.073088 4.005243 4.253517 -v 0.006909 -0.081875 0.171557 -vn 0.044003 3.652488 5.111753 -v 0.006908 -0.081834 0.171527 -vn 5.293715 3.340770 -0.357322 -v 0.006905 -0.081875 0.171570 -vn 5.233919 3.388012 -0.177437 -v 0.006904 -0.081875 0.171566 -vn 4.486644 3.917942 1.223743 -v 0.006877 -0.081834 0.171531 -vn 2.625417 4.245783 3.415461 -v 0.006878 -0.081834 0.171529 -vn 1.817470 4.073191 3.986032 -v 0.006867 -0.081814 0.171513 -vn 5.365480 3.268028 -0.008853 -v 0.006987 -0.082002 0.171671 -vn 5.236713 3.459429 0.079216 -v 0.006933 -0.081917 0.171604 -vn 5.267901 3.423518 -0.011727 -v 0.006933 -0.081917 0.171596 -vn 5.110815 -2.578074 1.201388 -v 0.007242 -0.085144 0.171899 -vn 3.127811 4.274021 2.710466 -v 0.006849 -0.081793 0.171501 -vn 4.969175 3.678272 0.177082 -v 0.006848 -0.081793 0.171508 -vn 4.275561 4.088738 1.488796 -v 0.006863 -0.081814 0.171518 -vn 5.172583 3.557570 -0.090265 -v 0.006863 -0.081814 0.171526 -vn 5.242406 3.450933 -0.244036 -v 0.006877 -0.081834 0.171535 -vn 5.186203 3.518773 -0.147002 -v 0.006877 -0.081834 0.171544 -vn 3.910484 4.042392 1.653952 -v 0.006819 -0.081753 0.171473 -vn 4.536745 3.851353 0.820258 -v 0.006833 -0.081773 0.171490 -vn 2.011863 4.224126 3.658375 -v 0.006836 -0.081773 0.171485 -vn 5.175975 3.508801 -0.261875 -v 0.006849 -0.081793 0.171517 -vn 5.127516 3.618009 -0.134232 -v 0.006820 -0.081753 0.171481 -vn 4.702146 4.061129 0.658486 -v 0.006805 -0.081733 0.171463 -vn 1.146432 4.090726 4.309729 -v 0.006825 -0.081753 0.171469 -vn 0.743022 4.015261 4.670834 -v 0.006814 -0.081733 0.171454 -vn 3.004604 4.327316 2.861666 -v 0.006807 -0.081733 0.171456 -vn 0.034356 3.984484 4.855234 -v 0.006774 -0.081675 0.171410 -vn 2.287036 4.322765 3.905803 -v 0.006795 -0.081714 0.171441 -vn 0.135415 3.891389 4.930932 -v 0.006779 -0.081675 0.171410 -vn 1.059284 4.046344 4.566840 -v 0.006798 -0.081714 0.171439 -vn 5.053405 3.732464 0.057490 -v 0.006820 -0.081753 0.171497 -vn 5.040606 3.750821 0.014117 -v 0.006820 -0.081753 0.171489 -vn 5.064834 3.712907 -0.126412 -v 0.006805 -0.081733 0.171471 -vn 3.448172 4.408639 2.516903 -v 0.006790 -0.081714 0.171445 -vn 5.162853 3.580213 0.043031 -v 0.006877 -0.081834 0.171552 -vn 5.153536 3.591878 0.028043 -v 0.006877 -0.081834 0.171568 -vn -0.175552 3.687818 5.073931 -v 0.006836 -0.081753 0.171470 -vn 0.042241 3.741801 5.047033 -v 0.006847 -0.081753 0.171470 -vn -0.005704 3.847197 4.966592 -v 0.006826 -0.081675 0.171410 -vn -0.016363 4.002930 4.842250 -v 0.006741 -0.081599 0.171349 -vn -0.008085 3.980350 4.860212 -v 0.006720 -0.081599 0.171349 -vn 0.250549 4.016597 4.808960 -v 0.006730 -0.081618 0.171364 -vn 0.038379 4.015494 4.831683 -v 0.006784 -0.081599 0.171349 -vn -0.096128 3.896396 4.924318 -v 0.006763 -0.081637 0.171380 -vn 0.032728 3.825243 4.984124 -v 0.006784 -0.081675 0.171410 -vn 0.063805 3.767803 5.027202 -v 0.006804 -0.081714 0.171439 -vn 0.078308 3.723706 5.058263 -v 0.006868 -0.081753 0.171470 -vn 0.080948 3.876875 4.940342 -v 0.006911 -0.081675 0.171410 -vn 0.031873 4.197866 4.669543 -v 0.006826 -0.081525 0.171287 -vn 0.771872 4.108002 4.533051 -v 0.006740 -0.081637 0.171379 -vn 2.377166 4.660319 3.421698 -v 0.006734 -0.081637 0.171382 -vn 1.465803 4.167280 3.911539 -v 0.006751 -0.081656 0.171394 -vn 3.817700 4.499327 2.039004 -v 0.006747 -0.081656 0.171399 -vn 3.904087 3.883238 1.315319 -v 0.006760 -0.081675 0.171412 -vn 5.295798 3.266529 -0.795798 -v 0.006790 -0.081714 0.171453 -vn 5.345636 3.293097 0.122789 -v 0.006987 -0.082002 0.171702 -vn 0.821979 3.953747 4.734565 -v 0.006856 -0.081793 0.171499 -vn 3.057822 4.445286 2.208889 -v 0.006714 -0.081618 0.171368 -vn 4.488195 4.074749 0.742379 -v 0.006698 -0.081599 0.171353 -vn 4.934104 3.774066 -0.270341 -v 0.006729 -0.081637 0.171390 -vn 5.138300 3.526876 -0.793269 -v 0.006729 -0.081637 0.171395 -vn 4.626015 4.134811 0.551999 -v 0.006745 -0.081656 0.171406 -vn 3.798660 4.495696 1.600460 -v 0.006729 -0.081637 0.171387 -vn 2.265937 4.369991 3.197059 -v 0.006700 -0.081599 0.171350 -vn 0.673297 4.305265 4.453758 -v 0.006676 -0.081562 0.171318 -vn 1.975564 4.616944 3.635454 -v 0.006672 -0.081562 0.171319 -vn -0.125956 4.088931 4.765851 -v 0.006655 -0.081525 0.171287 -vn -0.166302 4.142641 4.717215 -v 0.006649 -0.081525 0.171287 -vn 5.081279 3.655904 -0.536909 -v 0.006699 -0.081599 0.171358 -vn 4.451871 4.262447 0.860352 -v 0.006684 -0.081580 0.171339 -vn 4.725249 4.131763 0.128891 -v 0.006684 -0.081580 0.171347 -vn 4.607648 4.234347 0.306520 -v 0.006668 -0.081562 0.171328 -vn 4.173771 4.478713 1.196477 -v 0.006668 -0.081562 0.171324 -vn 3.226914 4.686390 2.473135 -v 0.006670 -0.081562 0.171321 -vn 3.655398 4.651724 1.563782 -v 0.006637 -0.081525 0.171290 -vn 4.739445 4.095556 -0.003786 -v 0.006636 -0.081525 0.171298 -vn 4.909060 3.920723 0.009904 -v 0.006760 -0.081675 0.171490 -vn 4.932293 3.892162 0.006830 -v 0.006760 -0.081675 0.171457 -vn 4.814075 4.032457 0.111766 -v 0.006699 -0.081599 0.171415 -vn 4.896484 3.935174 0.100973 -v 0.006730 -0.081637 0.171420 -vn 4.962302 3.808492 -0.136480 -v 0.006731 -0.081637 0.171404 -vn 4.900923 3.879913 -0.222487 -v 0.006700 -0.081599 0.171367 -vn 4.786988 4.067898 0.087302 -v 0.006699 -0.081599 0.171383 -vn 4.797965 4.042202 -0.177131 -v 0.006637 -0.081525 0.171306 -vn 4.886700 3.925675 0.250774 -v 0.006760 -0.081675 0.171554 -vn 4.778547 3.735870 0.196500 -v 0.006789 -0.081714 0.171448 -vn 1.186004 4.290500 4.092252 -v 0.006762 -0.081675 0.171410 -vn 4.707004 4.160363 0.015755 -v 0.006637 -0.081525 0.171339 -vn 4.666812 4.201355 0.032056 -v 0.006637 -0.081525 0.171405 -vn 0.165833 3.752500 5.035599 -v 0.006846 -0.081773 0.171484 -vn 5.122205 3.630115 0.020989 -v 0.006877 -0.081834 0.171696 -vn 5.144506 3.592011 0.026224 -v 0.006877 -0.081834 0.171825 -vn -0.000827 4.105837 4.755785 -v 0.006740 -0.081525 0.171287 -vn 0.251031 4.155595 4.698031 -v 0.006709 -0.081599 0.171349 -vn 1.059636 4.431486 4.303933 -v 0.006721 -0.081618 0.171365 -vn 0.006797 4.272959 4.604347 -v 0.006610 -0.081454 0.171223 -vn -0.167483 4.145417 4.711607 -v 0.006633 -0.081490 0.171256 -vn 0.358815 4.362544 4.480560 -v 0.006615 -0.081490 0.171255 -vn 1.477022 4.702112 3.782293 -v 0.006611 -0.081490 0.171255 -vn 2.490022 4.711059 2.915001 -v 0.006623 -0.081507 0.171272 -vn 3.182601 4.802844 2.186963 -v 0.006605 -0.081490 0.171259 -vn 4.213699 4.484692 0.827620 -v 0.006621 -0.081507 0.171278 -vn 2.658778 4.837645 2.672284 -v 0.006574 -0.081454 0.171225 -vn 2.181869 4.828728 3.009657 -v 0.006591 -0.081472 0.171241 -vn 1.024645 4.614830 4.031270 -v 0.006578 -0.081454 0.171223 -vn 0.478911 4.404659 4.418598 -v 0.006599 -0.081472 0.171239 -vn 0.701854 4.519528 4.217063 -v 0.006566 -0.081437 0.171207 -vn 0.051084 4.278425 4.598522 -v 0.006588 -0.081454 0.171223 -vn 0.011467 4.307092 4.573221 -v 0.006565 -0.081420 0.171191 -vn 0.122456 4.401550 4.480917 -v 0.006564 -0.081386 0.171158 -vn 4.245746 4.544718 0.557362 -v 0.006556 -0.081437 0.171216 -vn 4.089916 4.546477 0.761637 -v 0.006573 -0.081454 0.171228 -vn 2.675265 4.827545 2.498469 -v 0.006558 -0.081437 0.171210 -vn 2.197828 4.704126 3.015846 -v 0.006510 -0.081386 0.171159 -vn 3.589152 4.779804 1.389976 -v 0.006540 -0.081420 0.171196 -vn 2.254629 4.964971 2.939301 -v 0.006542 -0.081420 0.171193 -vn 4.599614 4.275680 0.095542 -v 0.006573 -0.081454 0.171261 -vn 4.699958 4.167923 -0.079848 -v 0.006604 -0.081490 0.171267 -vn 4.601021 4.274904 0.012557 -v 0.006573 -0.081454 0.171245 -vn 4.670396 4.188426 -0.151000 -v 0.006573 -0.081454 0.171237 -vn 1.022823 4.664030 4.020789 -v 0.006545 -0.081420 0.171192 -vn 0.239002 4.357509 4.511276 -v 0.006554 -0.081420 0.171191 -vn -0.017599 4.349069 4.534112 -v 0.006543 -0.081386 0.171159 -vn 1.947096 4.569077 3.469294 -v 0.006499 -0.081369 0.171143 -vn 1.783979 4.464363 3.971219 -v 0.006490 -0.081353 0.171128 -vn 0.912865 4.334784 4.280213 -v 0.006479 -0.081320 0.171096 -vn 4.713969 4.135883 -0.366694 -v 0.006540 -0.081420 0.171204 -vn 4.563446 4.313874 0.129754 -v 0.006508 -0.081386 0.171165 -vn 4.531369 4.349285 -0.031033 -v 0.006508 -0.081386 0.171182 -vn 4.334546 4.503534 0.457614 -v 0.006492 -0.081369 0.171162 -vn 4.461818 4.403967 0.310622 -v 0.006442 -0.081320 0.171168 -vn 4.576135 4.232622 -0.057266 -v 0.006539 -0.081420 0.171200 -vn 4.035134 4.469403 1.117649 -v 0.006508 -0.081386 0.171161 -vn 3.720763 4.655196 1.803474 -v 0.006495 -0.081369 0.171148 -vn 4.042980 4.496856 1.352970 -v 0.006477 -0.081353 0.171143 -vn 2.684086 4.714102 3.142621 -v 0.006420 -0.081256 0.171054 -vn 1.784450 4.733471 3.699589 -v 0.006444 -0.081256 0.171039 -vn 0.783238 4.757518 3.984340 -v 0.006474 -0.081256 0.171028 -vn 4.062002 4.427406 1.259847 -v 0.006387 -0.081256 0.171096 -vn 4.290874 4.565280 0.333532 -v 0.006375 -0.081256 0.171222 -vn 4.424047 4.444309 0.228984 -v 0.006508 -0.081386 0.171249 -vn 4.355377 4.397071 0.614918 -v 0.006604 -0.081490 0.171263 -vn 0.007308 6.209172 0.855362 -v 0.007092 -0.080358 0.169115 -vn 0.044943 4.128876 4.719832 -v 0.009054 -0.081525 0.171287 -vn 0.000000 4.603044 4.264030 -v 0.007517 -0.081256 0.171025 -vn 0.000011 5.094134 3.649321 -v 0.006987 -0.081027 0.170750 -vn 0.103274 5.623947 2.753390 -v 0.006613 -0.080681 0.170184 -vn 0.038159 6.007290 1.780239 -v 0.006628 -0.080467 0.169629 -vn 0.259858 6.021070 1.726759 -v 0.006268 -0.080467 0.169648 -vn 0.054203 4.632223 4.235894 -v 0.006645 -0.081256 0.171025 -vn 0.501956 5.106382 3.604597 -v 0.006456 -0.081027 0.170752 -vn 1.003564 5.631000 2.559658 -v 0.006144 -0.080681 0.170252 -vn 1.890519 5.662935 1.916708 -v 0.005838 -0.080681 0.170446 -vn 3.209820 5.100967 1.583163 -v 0.006161 -0.081027 0.170938 -vn 2.519090 5.178824 2.483897 -v 0.006231 -0.081027 0.170854 -vn 0.041355 5.086627 3.663529 -v 0.006631 -0.081027 0.170750 -vn 0.526444 5.646533 2.669755 -v 0.006276 -0.080681 0.170210 -vn 0.596057 6.018241 1.649265 -v 0.005978 -0.080467 0.169722 -vn 0.000958 6.003824 1.783305 -v 0.007397 -0.080467 0.169630 -vn 0.071178 6.213212 0.842692 -v 0.006310 -0.080358 0.169123 -vn 0.209266 6.213365 0.811996 -v 0.005985 -0.080358 0.169181 -vn 0.326535 6.213076 0.773845 -v 0.005707 -0.080358 0.169275 -vn 0.880506 6.019228 1.514312 -v 0.005737 -0.080467 0.169835 -vn 0.427886 6.213190 0.722345 -v 0.005464 -0.080358 0.169398 -vn -3.415114 1.689905 2.630966 -v 0.009500 -0.082019 0.171647 -vn -3.348750 1.939728 2.457966 -v 0.009500 -0.081670 0.171407 -vn -3.310403 2.175060 2.255562 -v 0.009500 -0.081416 0.171187 -vn -3.321075 2.424501 1.983479 -v 0.009500 -0.081129 0.170880 -vn -0.048967 -6.203621 -0.867404 -v 0.006541 -0.087296 0.168185 -vn -0.002720 -6.269227 -0.004829 -v 0.006817 -0.087327 0.168650 -vn 0.089731 -6.218997 0.808742 -v 0.006310 -0.087296 0.169123 -vn 0.200111 -6.217292 0.797487 -v 0.005985 -0.087296 0.169181 -vn 0.318720 -6.214993 0.768525 -v 0.005707 -0.087296 0.169275 -vn 0.423577 -6.213540 0.723232 -v 0.005464 -0.087296 0.169398 -vn 0.532078 -6.214350 0.645350 -v 0.005250 -0.087296 0.169544 -vn 0.660999 -6.214832 0.514286 -v 0.004897 -0.087296 0.169896 -vn 0.877930 -6.017092 1.523780 -v 0.005737 -0.087187 0.169835 -vn 1.124767 -6.015393 1.360113 -v 0.005533 -0.087187 0.169978 -vn 1.321708 -6.014226 1.175553 -v 0.005360 -0.087187 0.170145 -vn 1.488397 -6.017523 0.935525 -v 0.005217 -0.087187 0.170336 -vn 2.276819 -5.659922 1.444328 -v 0.005691 -0.086973 0.170622 -vn 2.530404 -5.677253 0.845936 -v 0.005588 -0.086973 0.170831 -vn 2.698300 -5.656473 0.303880 -v 0.005536 -0.086973 0.171081 -vn 1.604159 -6.023645 0.674831 -v 0.005103 -0.087187 0.170550 -vn -3.099742 -4.204841 -3.417562 -v 0.003048 -0.086128 0.167346 -vn -2.568201 -4.958884 -2.768255 -v 0.003366 -0.086627 0.167783 -vn -1.924173 -5.592157 -2.005092 -v 0.003702 -0.086973 0.168245 -vn -1.272739 -5.991360 -1.268630 -v 0.004030 -0.087187 0.168698 -vn -0.639561 -6.201982 -0.601814 -v 0.004337 -0.087296 0.169122 -vn -0.021953 -6.269564 -0.019512 -v 0.004615 -0.087327 0.169507 -vn 0.772530 -6.216459 0.311254 -v 0.004639 -0.087296 0.170325 -vn 1.794287 -6.005930 0.318524 -v 0.005023 -0.087187 0.170791 -vn 2.845025 -5.582502 0.011220 -v 0.005534 -0.086973 0.171370 -vn 2.773165 -5.610157 0.009335 -v 0.005534 -0.086973 0.171950 -vn 3.649368 -5.094112 0.000069 -v 0.006100 -0.086627 0.172548 -vn 3.649364 -5.094116 -0.000003 -v 0.006100 -0.086627 0.173100 -vn 2.770418 -5.611135 0.000000 -v 0.005534 -0.086973 0.173693 -vn 1.782411 -6.004045 -0.000001 -v 0.004980 -0.087187 0.173192 -vn 1.783923 -6.003663 0.002583 -v 0.004980 -0.087187 0.171974 -vn 0.763292 -6.228498 0.135793 -v 0.004488 -0.087296 0.170839 -vn -0.029135 -6.269839 -0.015895 -v 0.004320 -0.087327 0.169927 -vn -0.736343 -6.202324 -0.476562 -v 0.004011 -0.087296 0.169539 -vn -1.456791 -5.992192 -1.050367 -v 0.003676 -0.087187 0.169116 -vn -2.188555 -5.593416 -1.711576 -v 0.003321 -0.086973 0.168667 -vn 3.671048 -5.080425 0.027345 -v 0.006100 -0.086627 0.171443 -vn 4.263772 -4.603296 0.000211 -v 0.006375 -0.086397 0.171760 -vn 4.731477 -4.119864 0.000031 -v 0.006637 -0.086128 0.172062 -vn 4.263998 -4.603073 0.000010 -v 0.006375 -0.086397 0.172299 -vn 3.649812 -5.093840 0.000009 -v 0.006100 -0.086627 0.171995 -vn 3.650603 -5.093336 0.000920 -v 0.006100 -0.086627 0.171719 -vn 4.731459 -4.119883 0.000001 -v 0.006637 -0.086128 0.172587 -vn 5.160441 -3.566596 0.000000 -v 0.006877 -0.085820 0.172852 -vn 5.160442 -3.566596 0.000000 -v 0.006877 -0.085820 0.172338 -vn 5.536957 -2.946921 0.000000 -v 0.007088 -0.085474 0.173084 -vn 4.263999 -4.603071 0.000000 -v 0.006375 -0.086397 0.173376 -vn 4.731459 -4.119884 0.000000 -v 0.006637 -0.086128 0.173639 -vn 5.160442 -3.566596 0.000000 -v 0.006877 -0.085820 0.173879 -vn 5.536957 -2.946921 0.000000 -v 0.007088 -0.085474 0.174090 -vn 5.847293 -2.268072 0.000000 -v 0.007262 -0.085095 0.174264 -vn 5.847293 -2.268072 0.000000 -v 0.007262 -0.085095 0.173275 -vn 1.741710 -6.024023 0.086501 -v 0.004980 -0.087187 0.171365 -vn 2.770427 -5.611126 -0.000064 -v 0.005534 -0.086973 0.172531 -vn 3.649365 -5.094114 0.000000 -v 0.006100 -0.086627 0.174205 -vn -0.858804 -6.208282 0.000168 -v 0.003535 -0.087296 0.171880 -vn 0.000038 -6.269272 0.000001 -v 0.004000 -0.087327 0.172302 -vn 0.859133 -6.208214 -0.000002 -v 0.004465 -0.087296 0.172724 -vn 6.079084 -1.540839 0.000000 -v 0.007392 -0.084688 0.172442 -vn 6.079083 -1.540839 0.000000 -v 0.007392 -0.084688 0.173418 -vn 6.222432 -0.779316 0.000000 -v 0.007473 -0.084263 0.173506 -vn 6.222433 -0.779316 0.000000 -v 0.007473 -0.084263 0.174474 -vn 6.270949 0.000000 0.000000 -v 0.007500 -0.083827 0.174501 -vn 6.270895 -0.000873 0.001288 -v 0.007500 -0.083827 0.176431 -vn 6.222434 0.779310 -0.000008 -v 0.007473 -0.083391 0.176409 -vn 6.228011 0.744953 0.020734 -v 0.007473 -0.083391 0.172176 -vn 6.222431 0.779320 -0.000004 -v 0.007473 -0.083391 0.172297 -vn 6.079084 1.540839 0.000000 -v 0.007392 -0.082965 0.172442 -vn 5.847302 2.268051 0.000000 -v 0.007262 -0.082559 0.173275 -vn 0.013870 3.597730 5.148888 -v 0.006992 -0.081834 0.171527 -vn 4.695303 4.165034 0.026149 -v 0.006637 -0.081525 0.171536 -vn 4.731506 4.119835 0.000058 -v 0.006637 -0.081525 0.171799 -vn 5.160427 3.566622 0.000000 -v 0.006877 -0.081834 0.172338 -vn 6.222433 -0.779316 0.000000 -v 0.007473 -0.084263 0.172297 -vn 6.222432 -0.779316 0.000000 -v 0.007473 -0.084263 0.172538 -vn 6.270949 -0.000000 0.000000 -v 0.007500 -0.083827 0.172571 -vn 6.270948 -0.000000 0.000000 -v 0.007500 -0.083827 0.173536 -vn 6.222432 0.779316 0.000000 -v 0.007473 -0.083391 0.173506 -vn 6.222432 0.779316 0.000000 -v 0.007473 -0.083391 0.174474 -vn 6.079083 1.540839 0.000000 -v 0.007392 -0.082965 0.174393 -vn 6.079085 1.540843 -0.000007 -v 0.007392 -0.082965 0.176345 -vn 5.847503 2.267612 -0.000545 -v 0.007262 -0.082559 0.176241 -vn 5.536952 2.946925 0.000000 -v 0.007088 -0.082180 0.172581 -vn 5.160427 3.566621 0.000000 -v 0.006877 -0.081834 0.172852 -vn 5.536952 2.946926 0.000000 -v 0.007088 -0.082180 0.173084 -vn 5.160426 3.566621 0.000000 -v 0.006877 -0.081834 0.173879 -vn 4.728452 4.122969 0.004009 -v 0.006637 -0.081525 0.175741 -vn 4.731458 4.119884 0.000000 -v 0.006637 -0.081525 0.173639 -vn 4.731458 4.119884 0.000000 -v 0.006637 -0.081525 0.172587 -vn 4.731462 4.119880 0.000003 -v 0.006637 -0.081525 0.172062 -vn 6.270977 0.000327 0.001050 -v 0.007500 -0.083827 0.172209 -vn 6.270949 -0.000000 0.000000 -v 0.007500 -0.083827 0.172330 -vn 6.222432 0.779316 0.000000 -v 0.007473 -0.083391 0.172538 -vn 6.079084 1.540839 0.000000 -v 0.007392 -0.082965 0.173418 -vn 5.847302 2.268050 0.000000 -v 0.007262 -0.082559 0.174264 -vn 5.536952 2.946926 0.000000 -v 0.007088 -0.082180 0.174090 -vn 5.161236 3.565286 0.003674 -v 0.006877 -0.081834 0.175933 -vn 0.653240 6.215850 0.507611 -v 0.004897 -0.080358 0.169896 -vn 1.455824 6.036580 0.894733 -v 0.005217 -0.080467 0.170336 -vn 1.295382 6.029124 1.139799 -v 0.005360 -0.080467 0.170145 -vn 2.491304 5.700080 0.835124 -v 0.005588 -0.080681 0.170831 -vn 2.203740 5.712686 1.380322 -v 0.005691 -0.080681 0.170622 -vn 3.786526 5.004299 0.041978 -v 0.006100 -0.081027 0.171443 -vn 3.897685 4.881931 0.444344 -v 0.006100 -0.081027 0.171167 -vn 4.264097 4.602867 -0.001041 -v 0.006375 -0.081256 0.171491 -vn 4.434306 4.175041 1.090418 -v 0.006444 -0.081320 0.171137 -vn 3.225872 4.781266 2.441688 -v 0.006402 -0.081256 0.171074 -vn 1.115863 6.022061 1.342250 -v 0.005533 -0.080467 0.169978 -vn -0.031872 6.268537 -0.012345 -v 0.004320 -0.080327 0.169927 -vn 0.752334 6.216566 0.335066 -v 0.004639 -0.080358 0.170325 -vn 1.580587 6.063319 0.368970 -v 0.005023 -0.080467 0.170791 -vn 1.519269 6.053805 0.653092 -v 0.005103 -0.080467 0.170550 -vn 2.788482 5.605641 0.056249 -v 0.005534 -0.080681 0.171370 -vn 2.778442 5.622339 0.305013 -v 0.005536 -0.080681 0.171081 -vn 3.649800 5.093846 0.000917 -v 0.006100 -0.081027 0.171995 -vn 3.662409 5.085890 0.017852 -v 0.006100 -0.081027 0.171719 -vn 4.264002 4.603068 0.000007 -v 0.006375 -0.081256 0.172299 -vn 4.263895 4.603172 0.000184 -v 0.006375 -0.081256 0.171760 -vn 4.263999 4.603071 0.000000 -v 0.006375 -0.081256 0.173376 -vn 3.649359 5.094118 -0.000004 -v 0.006100 -0.081027 0.172548 -vn 2.770165 5.611282 0.000334 -v 0.005534 -0.080681 0.171950 -vn 1.767756 6.011027 0.061314 -v 0.004980 -0.080467 0.171365 -vn 0.812563 6.216934 0.127952 -v 0.004488 -0.080358 0.170839 -vn -0.044168 6.267889 -0.005498 -v 0.004110 -0.080327 0.170416 -vn -0.753440 6.197787 -0.477474 -v 0.004011 -0.080358 0.169539 -vn -1.282617 5.987264 -1.266359 -v 0.004030 -0.080467 0.168698 -vn -1.623637 5.589204 -2.257099 -v 0.004146 -0.080681 0.167875 -vn 4.938820 -3.883978 -0.002058 -v 0.006760 -0.085979 0.171457 -vn 0.627554 -4.283178 4.493262 -v 0.006676 -0.086092 0.171318 -vn 0.859131 6.208214 -0.000002 -v 0.004465 -0.080358 0.172724 -vn 1.782411 6.004045 0.000000 -v 0.004980 -0.080467 0.173192 -vn 2.770418 5.611135 0.000000 -v 0.005534 -0.080681 0.173693 -vn 3.649365 5.094114 0.000000 -v 0.006100 -0.081027 0.174205 -vn 3.649365 5.094114 0.000000 -v 0.006100 -0.081027 0.173100 -vn 2.770426 5.611131 -0.000022 -v 0.005534 -0.080681 0.172531 -vn 1.782505 6.004005 -0.000226 -v 0.004980 -0.080467 0.171974 -vn 0.854689 6.209310 0.013506 -v 0.004465 -0.080358 0.171455 -vn -0.001169 6.269227 -0.002121 -v 0.004000 -0.080327 0.171644 -vn -0.039940 6.267864 0.000421 -v 0.004005 -0.080327 0.170990 -vn -0.909560 6.188217 -0.160695 -v 0.003594 -0.080358 0.170564 -vn -0.839651 6.194469 -0.331431 -v 0.003760 -0.080358 0.170017 -vn -1.625799 5.980191 -0.799553 -v 0.003390 -0.080467 0.169589 -vn -1.470642 5.984716 -1.048024 -v 0.003676 -0.080467 0.169116 -vn -2.197846 5.585073 -1.706210 -v 0.003321 -0.080681 0.168667 -vn -1.932552 5.587498 -2.000156 -v 0.003702 -0.080681 0.168245 -vn -2.574340 4.955068 -2.761431 -v 0.003366 -0.081027 0.167783 -vn -2.191089 4.956232 -3.074871 -v 0.003831 -0.081027 0.167404 -vn -2.658555 4.212316 -3.761620 -v 0.003532 -0.081525 0.166958 -vn 1.782060 -6.004180 -0.001100 -v 0.004980 -0.087187 0.174409 -vn 2.529080 -5.116274 2.602828 -v 0.006231 -0.086627 0.170854 -vn -3.218323 -3.130507 0.239165 -v 0.009500 -0.087313 0.168964 -vn 2.094243 -1.360349 2.356195 -v 0.014500 -0.085848 0.172150 -vn -2.094247 -1.360349 2.356195 -v 0.009500 -0.085848 0.172150 -vn 0.056858 -5.455542 3.114739 -v 0.014500 -0.086858 0.170400 -vn 2.094435 -2.720701 0.000001 -v 0.014500 -0.087868 0.168650 -vn -2.094408 -2.720705 0.000008 -v 0.009500 -0.087868 0.168650 -vn 2.094374 1.360350 2.356194 -v 0.014500 -0.081806 0.172150 -vn -2.094404 1.360350 2.356194 -v 0.009500 -0.081806 0.172150 -vn 0.053989 0.062496 6.281542 -v 0.014500 -0.083827 0.172150 -vn 2.094513 2.720697 0.000005 -v 0.014500 -0.079785 0.168650 -vn -2.094465 2.720701 0.000011 -v 0.009500 -0.079785 0.168650 -vn 0.058204 5.438032 3.145202 -v 0.014500 -0.080796 0.170400 -vn -2.094789 1.360345 -2.356256 -v 0.009500 -0.081806 0.165150 -vn -2.094038 -1.360344 -2.356205 -v 0.009500 -0.085848 0.165150 -vn 3.242991 2.612552 1.738797 -v 0.014500 -0.080879 0.170537 -vn 3.272705 0.644623 3.068393 -v 0.014500 -0.083113 0.172076 -vn 3.252864 0.291579 3.123555 -v 0.014500 -0.083529 0.172137 -vn 3.257611 0.979640 2.979805 -v 0.014500 -0.082704 0.171965 -vn 3.245101 1.304671 2.853005 -v 0.014500 -0.082391 0.171842 -vn 3.233400 1.583383 2.709629 -v 0.014500 -0.082019 0.171647 -vn 3.227058 2.143002 2.293595 -v 0.014500 -0.081416 0.171187 -vn 3.201755 2.301196 2.136627 -v 0.014500 -0.081256 0.171025 -vn 3.237303 2.454657 1.955429 -v 0.014500 -0.081129 0.170880 -vn 3.202151 1.784891 2.583549 -v 0.014500 -0.081834 0.171527 -vn 3.222054 1.959396 2.452586 -v 0.014500 -0.081670 0.171406 -vn 3.206707 -0.120006 3.137618 -v 0.014500 -0.083865 0.172150 -vn 3.255205 -2.263561 2.170699 -v 0.014500 -0.086354 0.171072 -vn 3.243590 -2.000925 2.416260 -v 0.014500 -0.086043 0.171359 -vn 3.208992 -2.654539 1.677263 -v 0.014500 -0.086814 0.170473 -vn 3.243591 -2.498297 1.897561 -v 0.014500 -0.086626 0.170751 -vn 3.245483 -1.728125 2.618320 -v 0.014500 -0.085773 0.171559 -vn 3.255913 -1.418200 2.797133 -v 0.014500 -0.085410 0.171772 -vn 3.257656 -1.081577 2.944421 -v 0.014500 -0.085021 0.171940 -vn 3.258315 -0.768283 3.041132 -v 0.014500 -0.084700 0.172039 -vn 3.262399 -0.413308 3.108515 -v 0.014500 -0.084287 0.172120 -vn 3.231297 2.819904 1.377964 -v 0.014500 -0.080712 0.170246 -vn 3.265481 2.940133 1.090205 -v 0.014500 -0.080543 0.169860 -vn 3.249202 3.049042 0.737979 -v 0.014500 -0.080421 0.169455 -vn 3.270566 3.111611 0.390341 -v 0.014500 -0.080359 0.169124 -vn 3.288733 3.134035 0.068248 -v 0.014500 -0.080327 0.168706 -vn 3.251532 3.121048 -0.315242 -v 0.014500 -0.080346 0.168282 -vn 3.237011 3.077787 -0.613387 -v 0.014500 -0.080398 0.167950 -vn 3.201299 3.023757 -0.847143 -v 0.014500 -0.080467 0.167670 -vn 3.228421 2.955662 -1.056903 -v 0.014500 -0.080506 0.167544 -vn 3.213904 2.874123 -1.263872 -v 0.014500 -0.080664 0.167151 -vn 3.181238 2.803026 -1.417287 -v 0.014500 -0.080681 0.167116 -vn 0.046568 5.460297 -3.106840 -v 0.014500 -0.080796 0.166900 -vn 3.258568 0.369577 -3.114310 -v 0.014500 -0.083423 0.165174 -vn 0.109811 0.007509 -6.278512 -v 0.014500 -0.083827 0.165150 -vn 2.094211 1.360349 -2.356196 -v 0.014500 -0.081806 0.165150 -vn 3.233267 2.647520 -1.686762 -v 0.014500 -0.080822 0.166856 -vn 3.272306 2.487208 -1.908921 -v 0.014500 -0.081059 0.166508 -vn 3.246828 2.243887 -2.192387 -v 0.014500 -0.081338 0.166189 -vn 3.245907 1.993270 -2.422475 -v 0.014500 -0.081587 0.165961 -vn 3.260754 1.703893 -2.632802 -v 0.014500 -0.081925 0.165712 -vn 3.251364 1.386995 -2.813619 -v 0.014500 -0.082294 0.165504 -vn 3.251427 1.090018 -2.941906 -v 0.014500 -0.082604 0.165371 -vn 3.201825 0.846394 -3.023950 -v 0.014500 -0.082965 0.165258 -vn 3.210570 0.651375 -3.071486 -v 0.014500 -0.083005 0.165248 -vn 0.089980 -5.418461 -3.174288 -v 0.014500 -0.086858 0.166900 -vn 2.094389 -1.360347 -2.355838 -v 0.014500 -0.085848 0.165150 -vn 3.212488 -2.550575 -1.830510 -v 0.014500 -0.086626 0.166549 -vn 3.231192 -2.399293 -2.023881 -v 0.014500 -0.086560 0.166463 -vn 3.268056 -0.338207 -3.117738 -v 0.014500 -0.084177 0.165168 -vn 3.267699 -0.656251 -3.066870 -v 0.014500 -0.084594 0.165235 -vn 3.257693 -1.655126 -2.664485 -v 0.014500 -0.085682 0.165682 -vn 3.257027 -1.916739 -2.483025 -v 0.014500 -0.085958 0.165874 -vn 3.275456 -2.203607 -2.230367 -v 0.014500 -0.086275 0.166149 -vn 3.253028 -1.002586 -2.972349 -v 0.014500 -0.084920 0.165325 -vn 3.261759 -1.324133 -2.842607 -v 0.014500 -0.085311 0.165480 -vn 0.000000 0.000000 -6.283185 -v 0.011679 -0.083827 0.165150 -vn 0.000077 0.001754 -6.283183 -v 0.011621 -0.083823 0.165150 -vn 0.000070 0.003336 -6.283185 -v 0.011406 -0.083819 0.165150 -vn 0.000053 0.004114 -6.283183 -v 0.011287 -0.083817 0.165150 -vn -0.000073 0.001367 -6.283183 -v 0.010543 -0.083820 0.165150 -vn -0.000007 -0.000000 -6.283185 -v 0.010475 -0.083827 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.011677 -0.083826 0.165150 -vn -0.000076 0.000527 -6.283184 -v 0.010501 -0.083823 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.010481 -0.083825 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.011673 -0.083828 0.165150 -vn 0.000000 0.000000 0.000001 -v 0.010476 -0.083828 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.010479 -0.083828 0.165150 -vn -0.000074 -0.000377 -6.283183 -v 0.010500 -0.083831 0.165150 -vn -0.000079 -0.001465 -6.283176 -v 0.010543 -0.083833 0.165150 -vn 0.000077 -0.005087 -6.283181 -v 0.011233 -0.083837 0.165150 -vn 0.000086 -0.002722 -6.283184 -v 0.011568 -0.083832 0.165150 -vn 0.000075 -0.000414 -6.283174 -v 0.011652 -0.083829 0.165150 -vn 0.000000 0.000000 -6.283185 -v 0.011675 -0.083826 0.165150 -vn 0.000007 0.000000 -6.283185 -v 0.011672 -0.083825 0.165150 -vn 0.000078 0.000984 -6.283186 -v 0.011668 -0.083825 0.165150 -vn 3.243159 -3.050653 -0.731921 -v 0.014500 -0.087225 0.167814 -vn 3.258556 -3.113486 -0.375465 -v 0.014500 -0.087301 0.168227 -vn 3.277384 -3.135700 -0.000514 -v 0.014500 -0.087327 0.168650 -vn 3.230500 -2.832084 -1.352157 -v 0.014500 -0.086966 0.167102 -vn 3.242822 -2.954268 -1.055771 -v 0.014500 -0.087129 0.167491 -vn 3.293192 -3.122667 0.282275 -v 0.014500 -0.087313 0.168965 -vn 3.239682 -3.076578 0.617302 -v 0.014500 -0.087250 0.169381 -vn 3.237561 -3.002940 0.910616 -v 0.014500 -0.087188 0.169625 -vn 3.226612 -2.908724 1.179416 -v 0.014500 -0.087047 0.170021 -vn 3.201332 -2.815896 1.389755 -v 0.014500 -0.086973 0.170184 -vn -0.000027 0.006067 -6.283242 -v 0.011077 -0.083826 0.165150 -vn -0.000079 -0.000632 -6.283185 -v 0.010488 -0.083828 0.165150 -vn -0.000045 -0.007920 -6.283156 -v 0.011077 -0.083830 0.165150 -vn 3.049462 2.707482 1.586648 -v 0.016500 -0.080776 0.170365 -vn 3.020297 2.525999 1.859474 -v 0.016500 -0.081027 0.170750 -vn 3.063105 -0.190437 -3.133533 -v 0.016500 -0.084082 0.165159 -vn 2.987378 -1.557555 -2.716273 -v 0.016500 -0.085515 0.165584 -vn 3.026528 -1.162882 -2.913359 -v 0.016500 -0.085095 0.165388 -vn 3.043072 2.846953 1.319639 -v 0.016500 -0.080681 0.170184 -vn 2.952956 -2.038343 -2.370333 -v 0.016500 -0.086109 0.165996 -vn 3.004549 -0.837707 -3.020831 -v 0.016500 -0.084828 0.165296 -vn 3.027669 -0.483371 -3.099328 -v 0.016500 -0.084263 0.165177 -vn 3.066061 -3.072572 -0.644096 -v 0.016500 -0.087253 0.167933 -vn 3.053408 -3.005829 -0.902254 -v 0.016500 -0.087187 0.167670 -vn 3.075556 2.387098 2.040287 -v 0.016500 -0.081207 0.170971 -vn 3.059517 -2.912278 -1.170920 -v 0.016500 -0.087059 0.167306 -vn 3.046541 -2.793407 -1.429169 -v 0.016500 -0.086973 0.167116 -vn 3.052319 -2.635466 -1.703789 -v 0.016500 -0.086723 0.166684 -vn 3.109868 -2.527287 -1.865461 -v 0.016500 -0.086627 0.166550 -vn 3.037136 -2.389119 -2.033135 -v 0.016500 -0.086593 0.166506 -vn 3.044523 -2.997286 0.928649 -v 0.016500 -0.087187 0.169630 -vn 3.002565 -3.082188 0.565789 -v 0.016500 -0.087242 0.169415 -vn 3.036152 -1.834503 2.544460 -v 0.016500 -0.085926 0.171450 -vn 3.045645 -2.094000 2.336797 -v 0.016500 -0.086128 0.171287 -vn 3.047298 2.222953 2.214524 -v 0.016500 -0.081256 0.171025 -vn 3.030350 -2.338552 2.090031 -v 0.016500 -0.086448 0.170969 -vn 2.966572 -3.128671 0.069481 -v 0.016500 -0.087327 0.168650 -vn 3.039200 -3.115367 -0.371598 -v 0.016500 -0.087296 0.168185 -vn 3.048956 2.135045 -2.299495 -v 0.016500 -0.081525 0.166013 -vn 3.045377 2.367502 -2.058990 -v 0.016500 -0.081120 0.166431 -vn 3.029345 2.571273 -1.796726 -v 0.016500 -0.081027 0.166550 -vn 2.989822 2.981806 0.958236 -v 0.016500 -0.080506 0.169755 -vn 3.017179 -2.579685 1.781236 -v 0.016500 -0.086681 0.170676 -vn 3.049509 -2.778315 1.458564 -v 0.016500 -0.086973 0.170184 -vn 3.058882 -2.899453 1.202239 -v 0.016500 -0.087028 0.170066 -vn 3.039303 0.075376 -3.136698 -v 0.016500 -0.083742 0.165151 -vn 3.029310 0.410641 -3.109676 -v 0.016500 -0.083391 0.165177 -vn 2.979678 0.837754 -3.016021 -v 0.016500 -0.082965 0.165258 -vn 3.046157 -1.543056 2.732084 -v 0.016500 -0.085474 0.171738 -vn 3.039824 1.964634 2.445817 -v 0.016500 -0.081728 0.171451 -vn 3.044445 1.704961 2.633891 -v 0.016500 -0.081834 0.171527 -vn 2.953411 1.420811 -2.783630 -v 0.016500 -0.082219 0.165541 -vn 3.034332 1.878606 -2.511606 -v 0.016500 -0.081622 0.165932 -vn 3.033334 1.070217 2.948791 -v 0.016500 -0.082559 0.171912 -vn 3.009437 0.723852 3.050531 -v 0.016500 -0.083064 0.172066 -vn 3.024689 0.371949 3.114454 -v 0.016500 -0.083391 0.172123 -vn 3.031572 -0.365658 3.115668 -v 0.016500 -0.084263 0.172123 -vn 2.992544 -0.748037 3.041739 -v 0.016500 -0.084558 0.172073 -vn 3.017513 -1.213578 2.890201 -v 0.016500 -0.085312 0.171819 -vn 2.964165 2.794519 -1.406331 -v 0.016500 -0.080705 0.167067 -vn 2.965789 3.011994 -0.843092 -v 0.016500 -0.080456 0.167709 -vn 2.952965 3.101918 0.393361 -v 0.016500 -0.080359 0.169121 -vn 2.951785 3.118417 -0.219449 -v 0.016500 -0.080337 0.168382 -vn 3.032936 1.391463 2.810987 -v 0.016500 -0.082354 0.171825 -vn 3.018414 0.001072 3.135543 -v 0.016500 -0.083827 0.172150 -# 3800 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 1//1 -f 1//1 68//68 2//2 -f 20//20 69//69 22//22 -f 22//22 69//69 70//70 -f 22//22 70//70 24//24 -f 24//24 70//70 71//71 -f 24//24 71//71 26//26 -f 26//26 71//71 72//72 -f 26//26 72//72 28//28 -f 28//28 72//72 73//73 -f 28//28 73//73 30//30 -f 30//30 73//73 74//74 -f 30//30 74//74 32//32 -f 32//32 74//74 75//75 -f 32//32 75//75 34//34 -f 54//54 76//76 56//56 -f 56//56 76//76 77//77 -f 56//56 77//77 58//58 -f 58//58 77//77 78//78 -f 58//58 78//78 60//60 -f 60//60 78//78 79//79 -f 60//60 79//79 62//62 -f 62//62 79//79 80//80 -f 62//62 80//80 64//64 -f 64//64 80//80 81//81 -f 64//64 81//81 66//66 -f 66//66 81//81 82//82 -f 66//66 82//82 68//68 -f 68//68 82//82 83//83 -f 68//68 83//83 2//2 -f 2//2 83//83 84//84 -f 2//2 84//84 4//4 -f 75//75 85//85 34//34 -f 34//34 85//85 86//86 -f 34//34 86//86 36//36 -f 36//36 86//86 87//87 -f 36//36 87//87 38//38 -f 38//38 87//87 88//88 -f 38//38 88//88 40//40 -f 40//40 88//88 89//89 -f 40//40 89//89 42//42 -f 42//42 89//89 90//90 -f 42//42 90//90 44//44 -f 84//84 91//91 4//4 -f 4//4 91//91 92//92 -f 4//4 92//92 6//6 -f 6//6 92//92 93//93 -f 6//6 93//93 8//8 -f 8//8 93//93 94//94 -f 8//8 94//94 10//10 -f 10//10 94//94 95//95 -f 10//10 95//95 12//12 -f 12//12 95//95 96//96 -f 12//12 96//96 14//14 -f 14//14 96//96 97//97 -f 14//14 97//97 16//16 -f 90//90 98//98 44//44 -f 44//44 98//98 99//99 -f 44//44 99//99 46//46 -f 46//46 99//99 100//100 -f 46//46 100//100 48//48 -f 48//48 100//100 101//101 -f 48//48 101//101 50//50 -f 50//50 101//101 102//102 -f 50//50 102//102 52//52 -f 52//52 102//102 103//103 -f 52//52 103//103 54//54 -f 54//54 103//103 104//104 -f 54//54 104//104 76//76 -f 97//97 105//105 16//16 -f 16//16 105//105 106//106 -f 16//16 106//106 18//18 -f 18//18 106//106 107//107 -f 18//18 107//107 20//20 -f 20//20 107//107 108//108 -f 20//20 108//108 69//69 -f 35//35 109//109 33//33 -f 33//33 109//109 110//110 -f 33//33 110//110 31//31 -f 31//31 110//110 111//111 -f 31//31 111//111 29//29 -f 29//29 111//111 112//112 -f 29//29 112//112 27//27 -f 27//27 112//112 113//113 -f 27//27 113//113 25//25 -f 25//25 113//113 114//114 -f 25//25 114//114 23//23 -f 23//23 114//114 115//115 -f 23//23 115//115 21//21 -f 115//115 116//116 21//21 -f 21//21 116//116 117//117 -f 21//21 117//117 19//19 -f 19//19 117//117 118//118 -f 19//19 118//118 17//17 -f 5//5 119//119 3//3 -f 3//3 119//119 120//120 -f 3//3 120//120 1//1 -f 1//1 120//120 121//121 -f 1//1 121//121 67//67 -f 67//67 121//121 122//122 -f 67//67 122//122 65//65 -f 65//65 122//122 123//123 -f 65//65 123//123 63//63 -f 63//63 123//123 124//124 -f 63//63 124//124 61//61 -f 61//61 124//124 125//125 -f 61//61 125//125 59//59 -f 59//59 125//125 126//126 -f 59//59 126//126 57//57 -f 57//57 126//126 127//127 -f 57//57 127//127 55//55 -f 118//118 128//128 17//17 -f 17//17 128//128 129//129 -f 17//17 129//129 15//15 -f 15//15 129//129 130//130 -f 15//15 130//130 13//13 -f 13//13 130//130 131//131 -f 13//13 131//131 11//11 -f 11//11 131//131 132//132 -f 11//11 132//132 9//9 -f 9//9 132//132 133//133 -f 9//9 133//133 7//7 -f 7//7 133//133 134//134 -f 7//7 134//134 5//5 -f 5//5 134//134 135//135 -f 5//5 135//135 119//119 -f 45//45 136//136 43//43 -f 43//43 136//136 137//137 -f 43//43 137//137 41//41 -f 41//41 137//137 138//138 -f 41//41 138//138 39//39 -f 39//39 138//138 139//139 -f 39//39 139//139 37//37 -f 37//37 139//139 140//140 -f 37//37 140//140 35//35 -f 35//35 140//140 141//141 -f 35//35 141//141 109//109 -f 127//127 142//142 55//55 -f 55//55 142//142 143//143 -f 55//55 143//143 53//53 -f 53//53 143//143 144//144 -f 53//53 144//144 51//51 -f 51//51 144//144 145//145 -f 51//51 145//145 49//49 -f 49//49 145//145 146//146 -f 49//49 146//146 47//47 -f 47//47 146//146 147//147 -f 47//47 147//147 45//45 -f 45//45 147//147 148//148 -f 45//45 148//148 136//136 -f 106//106 118//118 107//107 -f 107//107 118//118 117//117 -f 107//107 117//117 108//108 -f 108//108 117//117 116//116 -f 108//108 116//116 69//69 -f 69//69 116//116 115//115 -f 69//69 115//115 70//70 -f 70//70 115//115 114//114 -f 70//70 114//114 71//71 -f 71//71 114//114 113//113 -f 71//71 113//113 72//72 -f 72//72 113//113 112//112 -f 72//72 112//112 73//73 -f 73//73 112//112 111//111 -f 73//73 111//111 74//74 -f 74//74 111//111 110//110 -f 74//74 110//110 75//75 -f 75//75 110//110 109//109 -f 75//75 109//109 85//85 -f 85//85 109//109 141//141 -f 85//85 141//141 86//86 -f 86//86 141//141 140//140 -f 86//86 140//140 87//87 -f 87//87 140//140 139//139 -f 87//87 139//139 88//88 -f 88//88 139//139 138//138 -f 88//88 138//138 89//89 -f 89//89 138//138 137//137 -f 89//89 137//137 90//90 -f 90//90 137//137 136//136 -f 90//90 136//136 98//98 -f 98//98 136//136 148//148 -f 98//98 148//148 99//99 -f 99//99 148//148 147//147 -f 99//99 147//147 100//100 -f 100//100 147//147 146//146 -f 100//100 146//146 101//101 -f 101//101 146//146 145//145 -f 101//101 145//145 102//102 -f 102//102 145//145 144//144 -f 102//102 144//144 103//103 -f 103//103 144//144 143//143 -f 103//103 143//143 104//104 -f 104//104 143//143 142//142 -f 104//104 142//142 76//76 -f 76//76 142//142 127//127 -f 76//76 127//127 77//77 -f 77//77 127//127 126//126 -f 77//77 126//126 78//78 -f 78//78 126//126 125//125 -f 78//78 125//125 79//79 -f 79//79 125//125 124//124 -f 79//79 124//124 80//80 -f 80//80 124//124 123//123 -f 80//80 123//123 81//81 -f 81//81 123//123 122//122 -f 81//81 122//122 82//82 -f 82//82 122//122 121//121 -f 82//82 121//121 83//83 -f 83//83 121//121 120//120 -f 83//83 120//120 84//84 -f 84//84 120//120 119//119 -f 84//84 119//119 91//91 -f 91//91 119//119 135//135 -f 91//91 135//135 92//92 -f 92//92 135//135 134//134 -f 92//92 134//134 93//93 -f 93//93 134//134 133//133 -f 93//93 133//133 94//94 -f 94//94 133//133 132//132 -f 94//94 132//132 95//95 -f 95//95 132//132 131//131 -f 95//95 131//131 96//96 -f 96//96 131//131 130//130 -f 96//96 130//130 97//97 -f 97//97 130//130 129//129 -f 97//97 129//129 105//105 -f 105//105 129//129 128//128 -f 105//105 128//128 106//106 -f 106//106 128//128 118//118 -f 149//149 150//150 132//132 -f 132//132 150//150 151//151 -f 132//132 151//151 152//152 -f 153//153 154//154 155//155 -f 152//152 156//156 132//132 -f 132//132 156//156 155//155 -f 132//132 155//155 157//157 -f 157//157 155//155 158//158 -f 132//132 159//159 160//160 -f 161//161 132//132 162//162 -f 162//162 132//132 163//163 -f 161//161 164//164 132//132 -f 132//132 164//164 165//165 -f 132//132 165//165 166//166 -f 166//166 167//167 132//132 -f 132//132 167//167 168//168 -f 132//132 168//168 169//169 -f 160//160 170//170 132//132 -f 132//132 170//170 171//171 -f 132//132 171//171 172//172 -f 172//172 173//173 132//132 -f 132//132 173//173 174//174 -f 132//132 174//174 175//175 -f 154//154 176//176 155//155 -f 155//155 176//176 177//177 -f 155//155 177//177 158//158 -f 169//169 178//178 132//132 -f 132//132 178//178 179//179 -f 132//132 179//179 180//180 -f 180//180 181//181 132//132 -f 132//132 181//181 182//182 -f 132//132 182//182 183//183 -f 183//183 184//184 132//132 -f 132//132 184//184 185//185 -f 132//132 185//185 159//159 -f 175//175 186//186 132//132 -f 132//132 186//186 187//187 -f 132//132 187//187 149//149 -f 155//155 188//188 153//153 -f 153//153 188//188 189//189 -f 153//153 189//189 190//190 -f 190//190 189//189 191//191 -f 163//163 192//192 162//162 -f 162//162 192//192 193//193 -f 162//162 193//193 194//194 -f 194//194 193//193 195//195 -f 194//194 195//195 196//196 -f 196//196 195//195 197//197 -f 196//196 197//197 118//118 -f 198//198 199//199 200//200 -f 201//201 202//202 203//203 -f 204//204 205//205 206//206 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 211//211 212//212 213//213 -f 214//214 215//215 216//216 -f 217//217 218//218 219//219 -f 220//220 221//221 222//222 -f 223//223 224//224 225//225 -f 226//226 227//227 228//228 -f 229//229 230//230 231//231 -f 232//232 233//233 234//234 -f 235//235 236//236 237//237 -f 238//238 239//239 240//240 -f 241//241 242//242 243//243 -f 244//244 245//245 246//246 -f 247//247 248//248 249//249 -f 250//250 251//251 252//252 -f 253//253 254//254 255//255 -f 256//256 257//257 258//258 -f 259//259 260//260 261//261 -f 262//262 263//263 264//264 -f 265//265 266//266 267//267 -f 268//268 267//267 269//269 -f 270//270 271//271 272//272 -f 273//273 274//274 275//275 -f 276//276 277//277 278//278 -f 279//279 277//277 280//280 -f 281//281 282//282 283//283 -f 284//284 285//285 286//286 -f 287//287 288//288 289//289 -f 290//290 291//291 292//292 -f 293//293 294//294 295//295 -f 296//296 297//297 298//298 -f 299//299 300//300 301//301 -f 302//302 303//303 304//304 -f 305//305 306//306 307//307 -f 308//308 309//309 310//310 -f 311//311 312//312 313//313 -f 314//314 315//315 316//316 -f 317//317 318//318 319//319 -f 320//320 321//321 322//322 -f 318//318 317//317 323//323 -f 324//324 325//325 326//326 -f 327//327 326//326 328//328 -f 329//329 330//330 331//331 -f 330//330 329//329 332//332 -f 333//333 334//334 335//335 -f 336//336 337//337 338//338 -f 338//338 337//337 339//339 -f 340//340 341//341 342//342 -f 343//343 344//344 345//345 -f 346//346 347//347 348//348 -f 349//349 350//350 351//351 -f 352//352 353//353 354//354 -f 193//193 192//192 355//355 -f 356//356 357//357 358//358 -f 151//151 150//150 359//359 -f 360//360 361//361 362//362 -f 363//363 364//364 365//365 -f 170//170 160//160 366//366 -f 367//367 368//368 369//369 -f 370//370 371//371 372//372 -f 373//373 374//374 375//375 -f 373//373 375//375 376//376 -f 376//376 375//375 377//377 -f 376//376 377//377 378//378 -f 378//378 377//377 379//379 -f 378//378 379//379 380//380 -f 381//381 382//382 383//383 -f 384//384 385//385 386//386 -f 384//384 386//386 382//382 -f 371//371 387//387 372//372 -f 372//372 387//387 388//388 -f 389//389 390//390 391//391 -f 392//392 393//393 394//394 -f 394//394 393//393 395//395 -f 396//396 397//397 392//392 -f 392//392 397//397 398//398 -f 392//392 398//398 393//393 -f 392//392 399//399 396//396 -f 396//396 399//399 369//369 -f 396//396 369//369 400//400 -f 400//400 369//369 368//368 -f 401//401 402//402 403//403 -f 403//403 402//402 404//404 -f 403//403 404//404 405//405 -f 405//405 404//404 406//406 -f 405//405 406//406 407//407 -f 407//407 406//406 408//408 -f 407//407 408//408 409//409 -f 409//409 408//408 410//410 -f 409//409 410//410 411//411 -f 411//411 410//410 412//412 -f 411//411 412//412 413//413 -f 413//413 412//412 414//414 -f 413//413 414//414 415//415 -f 415//415 414//414 416//416 -f 415//415 416//416 417//417 -f 417//417 416//416 418//418 -f 417//417 418//418 419//419 -f 419//419 418//418 420//420 -f 419//419 420//420 421//421 -f 421//421 420//420 422//422 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 425//425 426//426 427//427 -f 427//427 426//426 428//428 -f 427//427 428//428 401//401 -f 401//401 428//428 429//429 -f 401//401 429//429 402//402 -f 425//425 430//430 431//431 -f 431//431 432//432 425//425 -f 425//425 432//432 433//433 -f 425//425 433//433 426//426 -f 434//434 435//435 436//436 -f 436//436 435//435 437//437 -f 437//437 435//435 438//438 -f 437//437 438//438 439//439 -f 440//440 441//441 442//442 -f 442//442 441//441 443//443 -f 444//444 445//445 443//443 -f 445//445 446//446 443//443 -f 443//443 446//446 447//447 -f 443//443 447//447 442//442 -f 448//448 449//449 450//450 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 453//453 454//454 455//455 -f 166//166 456//456 167//167 -f 167//167 456//456 457//457 -f 167//167 457//457 168//168 -f 168//168 457//457 458//458 -f 168//168 458//458 169//169 -f 169//169 458//458 459//459 -f 169//169 459//459 178//178 -f 460//460 165//165 164//164 -f 460//460 164//164 461//461 -f 462//462 186//186 463//463 -f 463//463 186//186 175//175 -f 463//463 175//175 464//464 -f 464//464 175//175 174//174 -f 464//464 174//174 465//465 -f 173//173 172//172 466//466 -f 178//178 459//459 179//179 -f 179//179 459//459 467//467 -f 179//179 467//467 180//180 -f 180//180 467//467 199//199 -f 180//180 199//199 181//181 -f 181//181 199//199 198//198 -f 181//181 198//198 182//182 -f 468//468 469//469 361//361 -f 361//361 469//469 470//470 -f 361//361 470//470 362//362 -f 471//471 472//472 360//360 -f 360//360 472//472 473//473 -f 360//360 473//473 361//361 -f 361//361 473//473 474//474 -f 361//361 474//474 468//468 -f 468//468 474//474 475//475 -f 187//187 476//476 477//477 -f 477//477 476//476 478//478 -f 477//477 478//478 363//363 -f 363//363 365//365 477//477 -f 477//477 365//365 149//149 -f 477//477 149//149 187//187 -f 191//191 189//189 479//479 -f 471//471 479//479 472//472 -f 472//472 479//479 189//189 -f 472//472 189//189 473//473 -f 473//473 189//189 188//188 -f 473//473 188//188 474//474 -f 474//474 188//188 155//155 -f 474//474 155//155 475//475 -f 475//475 155//155 156//156 -f 475//475 156//156 152//152 -f 480//480 481//481 482//482 -f 482//482 481//481 483//483 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 486//486 -f 486//486 485//485 487//487 -f 486//486 487//487 488//488 -f 488//488 487//487 489//489 -f 488//488 489//489 490//490 -f 490//490 489//489 491//491 -f 490//490 491//491 492//492 -f 492//492 491//491 493//493 -f 492//492 493//493 494//494 -f 494//494 493//493 495//495 -f 494//494 495//495 496//496 -f 481//481 497//497 483//483 -f 483//483 497//497 498//498 -f 483//483 498//498 485//485 -f 485//485 498//498 499//499 -f 485//485 499//499 487//487 -f 487//487 499//499 500//500 -f 487//487 500//500 489//489 -f 489//489 500//500 501//501 -f 489//489 501//501 491//491 -f 491//491 501//501 502//502 -f 491//491 502//502 493//493 -f 493//493 502//502 503//503 -f 493//493 503//503 495//495 -f 504//504 356//356 505//505 -f 505//505 356//356 358//358 -f 505//505 358//358 506//506 -f 497//497 507//507 498//498 -f 498//498 507//507 508//508 -f 498//498 508//508 499//499 -f 499//499 508//508 509//509 -f 499//499 509//509 500//500 -f 500//500 509//509 510//510 -f 500//500 510//510 501//501 -f 501//501 510//510 511//511 -f 501//501 511//511 502//502 -f 502//502 511//511 512//512 -f 502//502 512//512 503//503 -f 513//513 514//514 355//355 -f 515//515 504//504 516//516 -f 516//516 504//504 505//505 -f 516//516 505//505 517//517 -f 517//517 505//505 506//506 -f 517//517 506//506 518//518 -f 192//192 163//163 355//355 -f 355//355 163//163 518//518 -f 355//355 518//518 513//513 -f 513//513 518//518 506//506 -f 176//176 515//515 177//177 -f 177//177 515//515 516//516 -f 177//177 516//516 158//158 -f 158//158 516//516 517//517 -f 158//158 517//517 157//157 -f 157//157 517//517 518//518 -f 157//157 518//518 132//132 -f 132//132 518//518 163//163 -f 519//519 520//520 521//521 -f 521//521 520//520 522//522 -f 521//521 522//522 523//523 -f 523//523 522//522 524//524 -f 523//523 524//524 525//525 -f 362//362 496//496 360//360 -f 360//360 496//496 495//495 -f 360//360 495//495 471//471 -f 471//471 495//495 503//503 -f 471//471 503//503 479//479 -f 479//479 503//503 512//512 -f 479//479 512//512 191//191 -f 191//191 512//512 511//511 -f 191//191 511//511 190//190 -f 190//190 511//511 510//510 -f 190//190 510//510 153//153 -f 153//153 510//510 509//509 -f 153//153 509//509 154//154 -f 154//154 509//509 508//508 -f 154//154 508//508 176//176 -f 176//176 508//508 507//507 -f 176//176 507//507 515//515 -f 515//515 507//507 497//497 -f 515//515 497//497 504//504 -f 504//504 497//497 481//481 -f 504//504 481//481 356//356 -f 356//356 481//481 480//480 -f 356//356 480//480 357//357 -f 352//352 354//354 350//350 -f 526//526 527//527 528//528 -f 528//528 527//527 529//529 -f 528//528 529//529 434//434 -f 434//434 529//529 530//530 -f 434//434 530//530 435//435 -f 435//435 530//530 531//531 -f 435//435 531//531 438//438 -f 438//438 531//531 532//532 -f 438//438 532//532 439//439 -f 439//439 532//532 533//533 -f 350//350 354//354 351//351 -f 351//351 354//354 534//534 -f 351//351 534//534 535//535 -f 535//535 534//534 536//536 -f 535//535 536//536 537//537 -f 537//537 536//536 538//538 -f 537//537 538//538 539//539 -f 436//436 540//540 434//434 -f 434//434 540//540 430//430 -f 434//434 430//430 528//528 -f 528//528 430//430 425//425 -f 528//528 425//425 526//526 -f 526//526 425//425 427//427 -f 541//541 542//542 543//543 -f 543//543 542//542 544//544 -f 543//543 544//544 545//545 -f 545//545 544//544 546//546 -f 547//547 548//548 549//549 -f 549//549 548//548 550//550 -f 549//549 550//550 551//551 -f 552//552 553//553 548//548 -f 548//548 553//553 348//348 -f 548//548 348//348 550//550 -f 550//550 348//348 347//347 -f 550//550 347//347 551//551 -f 554//554 555//555 556//556 -f 556//556 555//555 364//364 -f 556//556 364//364 557//557 -f 557//557 364//364 363//363 -f 557//557 363//363 558//558 -f 558//558 363//363 478//478 -f 559//559 560//560 552//552 -f 554//554 561//561 555//555 -f 555//555 561//561 562//562 -f 555//555 562//562 364//364 -f 364//364 562//562 359//359 -f 364//364 359//359 365//365 -f 365//365 359//359 150//150 -f 365//365 150//150 149//149 -f 563//563 526//526 564//564 -f 564//564 526//526 427//427 -f 564//564 427//427 565//565 -f 565//565 427//427 401//401 -f 565//565 401//401 566//566 -f 566//566 401//401 403//403 -f 566//566 403//403 567//567 -f 567//567 403//403 405//405 -f 567//567 405//405 568//568 -f 568//568 405//405 407//407 -f 568//568 407//407 569//569 -f 569//569 407//407 409//409 -f 569//569 409//409 570//570 -f 570//570 409//409 411//411 -f 570//570 411//411 571//571 -f 571//571 411//411 413//413 -f 571//571 413//413 572//572 -f 572//572 413//413 415//415 -f 572//572 415//415 573//573 -f 573//573 415//415 417//417 -f 573//573 417//417 574//574 -f 574//574 417//417 419//419 -f 574//574 419//419 575//575 -f 575//575 419//419 421//421 -f 575//575 421//421 576//576 -f 576//576 421//421 423//423 -f 576//576 423//423 369//369 -f 369//369 423//423 424//424 -f 369//369 424//424 367//367 -f 576//576 577//577 575//575 -f 575//575 577//577 578//578 -f 575//575 578//578 574//574 -f 574//574 578//578 579//579 -f 574//574 579//579 573//573 -f 573//573 579//579 580//580 -f 573//573 580//580 572//572 -f 572//572 580//580 581//581 -f 572//572 581//581 571//571 -f 571//571 581//581 582//582 -f 571//571 582//582 570//570 -f 570//570 582//582 583//583 -f 570//570 583//583 569//569 -f 569//569 583//583 584//584 -f 569//569 584//584 568//568 -f 568//568 584//584 585//585 -f 568//568 585//585 567//567 -f 567//567 585//585 586//586 -f 567//567 586//586 566//566 -f 566//566 586//586 587//587 -f 566//566 587//587 565//565 -f 565//565 587//587 588//588 -f 565//565 588//588 564//564 -f 564//564 588//588 589//589 -f 564//564 589//589 563//563 -f 577//577 590//590 578//578 -f 578//578 590//590 591//591 -f 578//578 591//591 579//579 -f 579//579 591//591 592//592 -f 579//579 592//592 580//580 -f 580//580 592//592 593//593 -f 580//580 593//593 581//581 -f 581//581 593//593 594//594 -f 581//581 594//594 582//582 -f 582//582 594//594 595//595 -f 582//582 595//595 583//583 -f 583//583 595//595 596//596 -f 583//583 596//596 584//584 -f 584//584 596//596 597//597 -f 584//584 597//597 585//585 -f 585//585 597//597 598//598 -f 585//585 598//598 586//586 -f 586//586 598//598 599//599 -f 586//586 599//599 587//587 -f 587//587 599//599 600//600 -f 587//587 600//600 588//588 -f 588//588 600//600 601//601 -f 588//588 601//601 589//589 -f 589//589 601//601 602//602 -f 589//589 602//602 563//563 -f 563//563 602//602 603//603 -f 563//563 603//603 526//526 -f 526//526 603//603 604//604 -f 526//526 604//604 527//527 -f 605//605 606//606 607//607 -f 590//590 608//608 591//591 -f 591//591 608//608 609//609 -f 591//591 609//609 592//592 -f 592//592 609//609 610//610 -f 592//592 610//610 593//593 -f 593//593 610//610 611//611 -f 593//593 611//611 594//594 -f 594//594 611//611 612//612 -f 594//594 612//612 595//595 -f 595//595 612//612 613//613 -f 595//595 613//613 596//596 -f 596//596 613//613 614//614 -f 596//596 614//614 597//597 -f 597//597 614//614 615//615 -f 597//597 615//615 598//598 -f 598//598 615//615 616//616 -f 598//598 616//616 599//599 -f 599//599 616//616 617//617 -f 599//599 617//617 600//600 -f 600//600 617//617 618//618 -f 600//600 618//618 601//601 -f 601//601 618//618 619//619 -f 601//601 619//619 602//602 -f 602//602 619//619 620//620 -f 602//602 620//620 603//603 -f 603//603 620//620 621//621 -f 603//603 621//621 604//604 -f 608//608 622//622 609//609 -f 609//609 622//622 623//623 -f 609//609 623//623 610//610 -f 610//610 623//623 624//624 -f 610//610 624//624 611//611 -f 611//611 624//624 625//625 -f 611//611 625//625 612//612 -f 612//612 625//625 626//626 -f 612//612 626//626 613//613 -f 613//613 626//626 627//627 -f 613//613 627//627 614//614 -f 614//614 627//627 628//628 -f 614//614 628//628 615//615 -f 615//615 628//628 629//629 -f 615//615 629//629 616//616 -f 616//616 629//629 630//630 -f 616//616 630//630 617//617 -f 617//617 630//630 631//631 -f 617//617 631//631 618//618 -f 618//618 631//631 632//632 -f 618//618 632//632 619//619 -f 619//619 632//632 633//633 -f 619//619 633//633 620//620 -f 620//620 633//633 634//634 -f 620//620 634//634 621//621 -f 635//635 636//636 637//637 -f 637//637 636//636 606//606 -f 638//638 639//639 640//640 -f 640//640 639//639 641//641 -f 606//606 605//605 637//637 -f 637//637 605//605 642//642 -f 637//637 642//642 635//635 -f 607//607 638//638 605//605 -f 605//605 638//638 640//640 -f 605//605 640//640 642//642 -f 642//642 640//640 641//641 -f 642//642 641//641 643//643 -f 644//644 645//645 646//646 -f 646//646 645//645 647//647 -f 646//646 647//647 648//648 -f 647//647 649//649 650//650 -f 394//394 643//643 392//392 -f 392//392 643//643 641//641 -f 392//392 641//641 399//399 -f 399//399 641//641 639//639 -f 399//399 639//639 369//369 -f 369//369 639//639 638//638 -f 369//369 638//638 576//576 -f 576//576 638//638 607//607 -f 576//576 607//607 577//577 -f 577//577 607//607 606//606 -f 577//577 606//606 590//590 -f 590//590 606//606 636//636 -f 590//590 636//636 608//608 -f 608//608 636//636 635//635 -f 608//608 635//635 622//622 -f 622//622 635//635 651//651 -f 622//622 651//651 623//623 -f 623//623 651//651 652//652 -f 623//623 652//652 624//624 -f 624//624 652//652 653//653 -f 624//624 653//653 625//625 -f 625//625 653//653 654//654 -f 625//625 654//654 626//626 -f 626//626 654//654 655//655 -f 626//626 655//655 627//627 -f 627//627 655//655 656//656 -f 627//627 656//656 628//628 -f 628//628 656//656 657//657 -f 628//628 657//657 629//629 -f 629//629 657//657 658//658 -f 629//629 658//658 630//630 -f 630//630 658//658 659//659 -f 630//630 659//659 631//631 -f 631//631 659//659 660//660 -f 631//631 660//660 632//632 -f 632//632 660//660 661//661 -f 632//632 661//661 633//633 -f 633//633 661//661 662//662 -f 633//633 662//662 634//634 -f 345//345 344//344 663//663 -f 663//663 344//344 664//664 -f 663//663 664//664 665//665 -f 665//665 664//664 666//666 -f 665//665 666//666 667//667 -f 667//667 666//666 668//668 -f 667//667 668//668 669//669 -f 669//669 668//668 670//670 -f 669//669 670//670 671//671 -f 671//671 670//670 672//672 -f 671//671 672//672 673//673 -f 673//673 672//672 674//674 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 677//677 -f 677//677 676//676 678//678 -f 677//677 678//678 679//679 -f 679//679 678//678 680//680 -f 679//679 680//680 681//681 -f 681//681 680//680 559//559 -f 681//681 559//559 682//682 -f 682//682 559//559 552//552 -f 682//682 552//552 683//683 -f 683//683 552//552 548//548 -f 683//683 548//548 684//684 -f 684//684 548//548 547//547 -f 684//684 547//547 685//685 -f 560//560 559//559 686//686 -f 686//686 559//559 680//680 -f 686//686 680//680 687//687 -f 687//687 680//680 678//678 -f 687//687 678//678 688//688 -f 688//688 678//678 676//676 -f 688//688 676//676 689//689 -f 689//689 676//676 674//674 -f 689//689 674//674 690//690 -f 690//690 674//674 672//672 -f 690//690 672//672 691//691 -f 691//691 672//672 670//670 -f 691//691 670//670 692//692 -f 692//692 670//670 668//668 -f 692//692 668//668 693//693 -f 693//693 668//668 666//666 -f 693//693 666//666 694//694 -f 694//694 666//666 664//664 -f 694//694 664//664 695//695 -f 695//695 664//664 344//344 -f 695//695 344//344 696//696 -f 696//696 344//344 343//343 -f 696//696 343//343 697//697 -f 345//345 698//698 343//343 -f 343//343 698//698 699//699 -f 343//343 699//699 697//697 -f 697//697 699//699 700//700 -f 697//697 700//700 701//701 -f 702//702 703//703 704//704 -f 704//704 703//703 705//705 -f 704//704 705//705 706//706 -f 706//706 705//705 707//707 -f 706//706 707//707 708//708 -f 708//708 707//707 709//709 -f 708//708 709//709 710//710 -f 710//710 709//709 711//711 -f 710//710 711//711 712//712 -f 712//712 711//711 713//713 -f 712//712 713//713 714//714 -f 714//714 713//713 715//715 -f 714//714 715//715 716//716 -f 716//716 715//715 717//717 -f 716//716 717//717 718//718 -f 718//718 717//717 719//719 -f 718//718 719//719 720//720 -f 720//720 719//719 721//721 -f 720//720 721//721 722//722 -f 722//722 721//721 723//723 -f 722//722 723//723 724//724 -f 724//724 723//723 725//725 -f 724//724 725//725 726//726 -f 726//726 725//725 727//727 -f 726//726 727//727 728//728 -f 728//728 727//727 729//729 -f 728//728 729//729 730//730 -f 730//730 729//729 731//731 -f 730//730 731//731 732//732 -f 732//732 731//731 733//733 -f 703//703 734//734 705//705 -f 705//705 734//734 735//735 -f 705//705 735//735 707//707 -f 707//707 735//735 736//736 -f 707//707 736//736 709//709 -f 709//709 736//736 737//737 -f 709//709 737//737 711//711 -f 711//711 737//737 738//738 -f 711//711 738//738 713//713 -f 713//713 738//738 739//739 -f 713//713 739//739 715//715 -f 715//715 739//739 740//740 -f 715//715 740//740 717//717 -f 717//717 740//740 741//741 -f 717//717 741//741 719//719 -f 719//719 741//741 742//742 -f 719//719 742//742 721//721 -f 721//721 742//742 743//743 -f 721//721 743//743 723//723 -f 723//723 743//743 744//744 -f 723//723 744//744 725//725 -f 725//725 744//744 745//745 -f 725//725 745//745 727//727 -f 727//727 745//745 746//746 -f 727//727 746//746 729//729 -f 729//729 746//746 747//747 -f 729//729 747//747 731//731 -f 731//731 747//747 748//748 -f 731//731 748//748 733//733 -f 733//733 748//748 346//346 -f 346//346 348//348 733//733 -f 733//733 348//348 553//553 -f 733//733 553//553 732//732 -f 732//732 553//553 552//552 -f 732//732 552//552 730//730 -f 730//730 552//552 560//560 -f 730//730 560//560 728//728 -f 728//728 560//560 686//686 -f 728//728 686//686 726//726 -f 726//726 686//686 687//687 -f 726//726 687//687 724//724 -f 724//724 687//687 688//688 -f 724//724 688//688 722//722 -f 722//722 688//688 689//689 -f 722//722 689//689 720//720 -f 720//720 689//689 690//690 -f 720//720 690//690 718//718 -f 718//718 690//690 691//691 -f 718//718 691//691 716//716 -f 716//716 691//691 692//692 -f 716//716 692//692 714//714 -f 714//714 692//692 693//693 -f 714//714 693//693 712//712 -f 712//712 693//693 694//694 -f 712//712 694//694 710//710 -f 710//710 694//694 695//695 -f 710//710 695//695 708//708 -f 708//708 695//695 696//696 -f 708//708 696//696 706//706 -f 706//706 696//696 697//697 -f 706//706 697//697 704//704 -f 704//704 697//697 701//701 -f 704//704 701//701 702//702 -f 341//341 749//749 750//750 -f 702//702 751//751 703//703 -f 703//703 751//751 752//752 -f 703//703 752//752 734//734 -f 734//734 752//752 753//753 -f 734//734 753//753 735//735 -f 735//735 753//753 754//754 -f 735//735 754//754 736//736 -f 736//736 754//754 755//755 -f 736//736 755//755 737//737 -f 737//737 755//755 756//756 -f 737//737 756//756 738//738 -f 738//738 756//756 757//757 -f 738//738 757//757 739//739 -f 739//739 757//757 758//758 -f 739//739 758//758 740//740 -f 740//740 758//758 759//759 -f 740//740 759//759 741//741 -f 741//741 759//759 760//760 -f 741//741 760//760 742//742 -f 742//742 760//760 761//761 -f 742//742 761//761 743//743 -f 743//743 761//761 762//762 -f 743//743 762//762 744//744 -f 744//744 762//762 763//763 -f 744//744 763//763 745//745 -f 745//745 763//763 764//764 -f 745//745 764//764 746//746 -f 746//746 764//764 765//765 -f 746//746 765//765 747//747 -f 747//747 765//765 766//766 -f 747//747 766//766 748//748 -f 748//748 766//766 767//767 -f 748//748 767//767 346//346 -f 346//346 767//767 768//768 -f 346//346 768//768 347//347 -f 347//347 768//768 561//561 -f 347//347 561//561 551//551 -f 551//551 561//561 554//554 -f 551//551 554//554 549//549 -f 549//549 554//554 556//556 -f 549//549 556//556 547//547 -f 547//547 556//556 557//557 -f 547//547 557//557 685//685 -f 685//685 557//557 558//558 -f 340//340 342//342 769//769 -f 769//769 342//342 770//770 -f 769//769 770//770 771//771 -f 771//771 770//770 772//772 -f 771//771 772//772 773//773 -f 774//774 775//775 776//776 -f 776//776 775//775 514//514 -f 776//776 514//514 777//777 -f 777//777 514//514 513//513 -f 777//777 513//513 778//778 -f 778//778 513//513 506//506 -f 778//778 506//506 779//779 -f 779//779 506//506 358//358 -f 341//341 750//750 342//342 -f 342//342 750//750 780//780 -f 342//342 780//780 770//770 -f 770//770 780//780 781//781 -f 770//770 781//781 772//772 -f 772//772 781//781 782//782 -f 772//772 782//782 773//773 -f 647//647 650//650 648//648 -f 648//648 650//650 783//783 -f 648//648 783//783 784//784 -f 785//785 644//644 786//786 -f 786//786 644//644 646//646 -f 786//786 646//646 787//787 -f 787//787 646//646 648//648 -f 787//787 648//648 788//788 -f 788//788 648//648 784//784 -f 788//788 784//784 789//789 -f 751//751 774//774 752//752 -f 752//752 774//774 776//776 -f 752//752 776//776 753//753 -f 753//753 776//776 777//777 -f 753//753 777//777 754//754 -f 754//754 777//777 778//778 -f 754//754 778//778 755//755 -f 755//755 778//778 779//779 -f 755//755 779//779 756//756 -f 756//756 779//779 358//358 -f 756//756 358//358 757//757 -f 757//757 358//358 357//357 -f 757//757 357//357 758//758 -f 758//758 357//357 480//480 -f 758//758 480//480 759//759 -f 759//759 480//480 482//482 -f 759//759 482//482 760//760 -f 760//760 482//482 484//484 -f 760//760 484//484 761//761 -f 761//761 484//484 486//486 -f 761//761 486//486 762//762 -f 762//762 486//486 488//488 -f 762//762 488//488 763//763 -f 763//763 488//488 490//490 -f 763//763 490//490 764//764 -f 764//764 490//490 492//492 -f 764//764 492//492 765//765 -f 765//765 492//492 494//494 -f 765//765 494//494 766//766 -f 766//766 494//494 496//496 -f 766//766 496//496 767//767 -f 767//767 496//496 362//362 -f 767//767 362//362 768//768 -f 768//768 362//362 470//470 -f 768//768 470//470 561//561 -f 561//561 470//470 469//469 -f 561//561 469//469 562//562 -f 562//562 469//469 468//468 -f 562//562 468//468 359//359 -f 359//359 468//468 475//475 -f 359//359 475//475 151//151 -f 151//151 475//475 152//152 -f 790//790 389//389 791//791 -f 792//792 791//791 793//793 -f 793//793 791//791 389//389 -f 793//793 389//389 794//794 -f 794//794 389//389 391//391 -f 794//794 391//391 795//795 -f 795//795 370//370 794//794 -f 794//794 370//370 372//372 -f 794//794 372//372 793//793 -f 793//793 372//372 796//796 -f 793//793 796//796 792//792 -f 792//792 796//796 797//797 -f 798//798 797//797 799//799 -f 799//799 797//797 796//796 -f 799//799 796//796 800//800 -f 800//800 796//796 372//372 -f 800//800 372//372 801//801 -f 801//801 372//372 388//388 -f 801//801 388//388 385//385 -f 373//373 452//452 374//374 -f 374//374 452//452 451//451 -f 374//374 451//451 375//375 -f 375//375 451//451 802//802 -f 375//375 802//802 377//377 -f 377//377 802//802 803//803 -f 377//377 803//803 379//379 -f 379//379 803//803 804//804 -f 805//805 339//339 806//806 -f 806//806 339//339 337//337 -f 806//806 337//337 807//807 -f 807//807 337//337 336//336 -f 807//807 336//336 808//808 -f 809//809 810//810 811//811 -f 811//811 810//810 812//812 -f 811//811 812//812 813//813 -f 814//814 815//815 816//816 -f 816//816 815//815 817//817 -f 816//816 817//817 818//818 -f 819//819 820//820 821//821 -f 821//821 820//820 822//822 -f 823//823 332//332 824//824 -f 824//824 332//332 825//825 -f 824//824 825//825 826//826 -f 335//335 334//334 822//822 -f 822//822 334//334 827//827 -f 822//822 827//827 821//821 -f 828//828 829//829 830//830 -f 830//830 829//829 831//831 -f 830//830 831//831 335//335 -f 333//333 832//832 334//334 -f 334//334 832//832 833//833 -f 334//334 833//833 827//827 -f 829//829 834//834 831//831 -f 831//831 834//834 835//835 -f 831//831 835//835 335//335 -f 335//335 835//835 836//836 -f 335//335 836//836 333//333 -f 333//333 836//836 837//837 -f 333//333 837//837 832//832 -f 838//838 839//839 840//840 -f 840//840 839//839 841//841 -f 840//840 841//841 842//842 -f 843//843 844//844 845//845 -f 845//845 844//844 846//846 -f 846//846 847//847 845//845 -f 845//845 847//847 815//815 -f 845//845 815//815 843//843 -f 843//843 815//815 814//814 -f 843//843 814//814 819//819 -f 819//819 814//814 816//816 -f 819//819 816//816 820//820 -f 820//820 816//816 818//818 -f 820//820 818//818 848//848 -f 849//849 850//850 851//851 -f 851//851 850//850 852//852 -f 851//851 852//852 853//853 -f 834//834 838//838 835//835 -f 835//835 838//838 840//840 -f 835//835 840//840 836//836 -f 836//836 840//840 842//842 -f 836//836 842//842 837//837 -f 837//837 842//842 854//854 -f 837//837 854//854 832//832 -f 832//832 854//854 855//855 -f 832//832 855//855 833//833 -f 856//856 857//857 858//858 -f 856//856 858//858 859//859 -f 859//859 858//858 860//860 -f 859//859 860//860 861//861 -f 860//860 853//853 861//861 -f 861//861 853//853 852//852 -f 861//861 852//852 862//862 -f 863//863 864//864 865//865 -f 865//865 864//864 866//866 -f 326//326 327//327 324//324 -f 324//324 327//327 867//867 -f 324//324 867//867 868//868 -f 869//869 870//870 866//866 -f 866//866 870//870 871//871 -f 866//866 871//871 865//865 -f 872//872 873//873 874//874 -f 874//874 873//873 875//875 -f 874//874 875//875 876//876 -f 876//876 875//875 809//809 -f 322//322 321//321 877//877 -f 877//877 321//321 878//878 -f 877//877 878//878 879//879 -f 880//880 881//881 873//873 -f 882//882 322//322 872//872 -f 872//872 322//322 877//877 -f 872//872 877//877 873//873 -f 873//873 877//877 879//879 -f 873//873 879//879 880//880 -f 881//881 880//880 883//883 -f 883//883 880//880 884//884 -f 883//883 884//884 885//885 -f 885//885 884//884 886//886 -f 885//885 886//886 887//887 -f 887//887 863//863 885//885 -f 885//885 863//863 865//865 -f 885//885 865//865 883//883 -f 883//883 865//865 871//871 -f 883//883 871//871 881//881 -f 881//881 871//871 870//870 -f 881//881 870//870 873//873 -f 873//873 870//870 869//869 -f 873//873 869//869 875//875 -f 875//875 869//869 888//888 -f 889//889 319//319 890//890 -f 890//890 319//319 318//318 -f 890//890 318//318 891//891 -f 891//891 318//318 323//323 -f 892//892 893//893 894//894 -f 894//894 893//893 895//895 -f 894//894 895//895 896//896 -f 897//897 898//898 899//899 -f 899//899 898//898 900//900 -f 899//899 900//900 901//901 -f 896//896 902//902 894//894 -f 894//894 902//902 903//903 -f 894//894 903//903 892//892 -f 888//888 869//869 904//904 -f 904//904 869//869 866//866 -f 904//904 866//866 905//905 -f 905//905 866//866 864//864 -f 905//905 864//864 317//317 -f 317//317 864//864 863//863 -f 317//317 863//863 323//323 -f 323//323 863//863 887//887 -f 323//323 887//887 891//891 -f 891//891 887//887 886//886 -f 891//891 886//886 890//890 -f 890//890 886//886 906//906 -f 890//890 906//906 889//889 -f 907//907 314//314 908//908 -f 908//908 314//314 316//316 -f 908//908 316//316 909//909 -f 909//909 316//316 910//910 -f 911//911 912//912 913//913 -f 913//913 912//912 914//914 -f 913//913 914//914 915//915 -f 916//916 917//917 918//918 -f 919//919 911//911 920//920 -f 920//920 911//911 913//913 -f 920//920 913//913 921//921 -f 921//921 913//913 915//915 -f 917//917 916//916 908//908 -f 908//908 916//916 922//922 -f 908//908 922//922 907//907 -f 923//923 924//924 925//925 -f 925//925 924//924 926//926 -f 925//925 926//926 927//927 -f 927//927 926//926 928//928 -f 927//927 928//928 929//929 -f 929//929 928//928 930//930 -f 929//929 930//930 310//310 -f 931//931 932//932 933//933 -f 932//932 931//931 313//313 -f 313//313 931//931 934//934 -f 313//313 934//934 311//311 -f 916//916 923//923 922//922 -f 922//922 923//923 925//925 -f 922//922 925//925 907//907 -f 907//907 925//925 927//927 -f 907//907 927//927 314//314 -f 314//314 927//927 929//929 -f 314//314 929//929 315//315 -f 315//315 929//929 310//310 -f 315//315 310//310 935//935 -f 935//935 310//310 309//309 -f 309//309 882//882 935//935 -f 935//935 882//882 872//872 -f 935//935 872//872 315//315 -f 315//315 872//872 874//874 -f 315//315 874//874 316//316 -f 316//316 874//874 876//876 -f 316//316 876//876 910//910 -f 910//910 876//876 936//936 -f 910//910 936//936 937//937 -f 937//937 936//936 381//381 -f 937//937 381//381 938//938 -f 938//938 381//381 383//383 -f 938//938 383//383 380//380 -f 939//939 940//940 941//941 -f 941//941 940//940 942//942 -f 941//941 942//942 307//307 -f 943//943 944//944 945//945 -f 945//945 944//944 946//946 -f 305//305 307//307 947//947 -f 947//947 948//948 949//949 -f 948//948 950//950 949//949 -f 949//949 950//950 951//951 -f 949//949 951//951 952//952 -f 947//947 953//953 305//305 -f 305//305 953//953 954//954 -f 305//305 954//954 306//306 -f 304//304 303//303 955//955 -f 946//946 956//956 945//945 -f 945//945 956//956 302//302 -f 945//945 302//302 943//943 -f 943//943 302//302 304//304 -f 943//943 304//304 957//957 -f 312//312 958//958 313//313 -f 313//313 958//958 959//959 -f 313//313 959//959 932//932 -f 932//932 959//959 960//960 -f 932//932 960//960 933//933 -f 961//961 897//897 903//903 -f 903//903 897//897 899//899 -f 903//903 899//899 892//892 -f 892//892 899//899 901//901 -f 892//892 901//901 893//893 -f 947//947 949//949 953//953 -f 953//953 949//949 952//952 -f 953//953 952//952 954//954 -f 954//954 952//952 955//955 -f 954//954 955//955 306//306 -f 306//306 955//955 303//303 -f 306//306 303//303 307//307 -f 307//307 303//303 302//302 -f 307//307 302//302 941//941 -f 941//941 302//302 956//956 -f 941//941 956//956 939//939 -f 939//939 956//956 946//946 -f 939//939 946//946 895//895 -f 895//895 946//946 944//944 -f 895//895 944//944 896//896 -f 896//896 944//944 943//943 -f 896//896 943//943 902//902 -f 902//902 943//943 957//957 -f 902//902 957//957 903//903 -f 903//903 957//957 962//962 -f 903//903 962//962 961//961 -f 963//963 964//964 965//965 -f 965//965 964//964 966//966 -f 965//965 966//966 967//967 -f 968//968 969//969 963//963 -f 963//963 969//969 970//970 -f 325//325 324//324 971//971 -f 971//971 324//324 868//868 -f 971//971 868//868 972//972 -f 963//963 965//965 968//968 -f 968//968 965//965 973//973 -f 968//968 973//973 969//969 -f 969//969 973//973 974//974 -f 969//969 974//974 975//975 -f 328//328 976//976 327//327 -f 327//327 976//976 977//977 -f 327//327 977//977 867//867 -f 867//867 977//977 978//978 -f 867//867 978//978 868//868 -f 868//868 978//978 979//979 -f 868//868 979//979 972//972 -f 331//331 970//970 980//980 -f 980//980 970//970 969//969 -f 980//980 969//969 981//981 -f 981//981 969//969 975//975 -f 981//981 862//862 980//980 -f 980//980 862//862 852//852 -f 980//980 852//852 331//331 -f 331//331 852//852 850//850 -f 331//331 850//850 329//329 -f 329//329 850//850 849//849 -f 329//329 849//849 332//332 -f 332//332 849//849 982//982 -f 332//332 982//982 825//825 -f 825//825 982//982 983//983 -f 825//825 983//983 826//826 -f 984//984 985//985 986//986 -f 986//986 985//985 987//987 -f 986//986 987//987 988//988 -f 989//989 990//990 960//960 -f 960//960 990//990 991//991 -f 960//960 991//991 933//933 -f 975//975 992//992 981//981 -f 981//981 992//992 984//984 -f 981//981 984//984 862//862 -f 862//862 984//984 986//986 -f 862//862 986//986 861//861 -f 861//861 986//986 988//988 -f 861//861 988//988 859//859 -f 859//859 988//988 993//993 -f 859//859 993//993 856//856 -f 856//856 993//993 994//994 -f 856//856 994//994 857//857 -f 995//995 996//996 997//997 -f 997//997 996//996 301//301 -f 997//997 301//301 998//998 -f 998//998 999//999 997//997 -f 997//997 999//999 1000//1000 -f 997//997 1000//1000 995//995 -f 995//995 1000//1000 1001//1001 -f 995//995 1001//1001 996//996 -f 996//996 1001//1001 1002//1002 -f 996//996 1002//1002 301//301 -f 301//301 1002//1002 1003//1003 -f 301//301 1003//1003 299//299 -f 1004//1004 1005//1005 1006//1006 -f 380//380 379//379 938//938 -f 938//938 379//379 804//804 -f 938//938 804//804 937//937 -f 937//937 804//804 298//298 -f 937//937 298//298 910//910 -f 910//910 298//298 297//297 -f 910//910 297//297 909//909 -f 909//909 297//297 1007//1007 -f 909//909 1007//1007 1008//1008 -f 1008//1008 1007//1007 1009//1009 -f 1008//1008 1009//1009 1010//1010 -f 1011//1011 1012//1012 1013//1013 -f 1013//1013 1012//1012 1014//1014 -f 1013//1013 1014//1014 1015//1015 -f 1016//1016 1017//1017 1018//1018 -f 919//919 918//918 911//911 -f 911//911 918//918 917//917 -f 911//911 917//917 912//912 -f 912//912 917//917 908//908 -f 912//912 908//908 914//914 -f 914//914 908//908 909//909 -f 914//914 909//909 915//915 -f 915//915 909//909 1008//1008 -f 915//915 1008//1008 921//921 -f 921//921 1008//1008 1010//1010 -f 921//921 1010//1010 920//920 -f 920//920 1010//1010 1019//1019 -f 920//920 1019//1019 919//919 -f 919//919 1019//1019 1020//1020 -f 919//919 1020//1020 918//918 -f 918//918 1020//1020 1021//1021 -f 918//918 1021//1021 916//916 -f 916//916 1021//1021 1022//1022 -f 916//916 1022//1022 923//923 -f 923//923 1022//1022 1023//1023 -f 923//923 1023//1023 924//924 -f 924//924 1023//1023 1024//1024 -f 924//924 1024//1024 926//926 -f 926//926 1024//1024 951//951 -f 926//926 951//951 928//928 -f 928//928 951//951 950//950 -f 928//928 950//950 930//930 -f 930//930 950//950 948//948 -f 930//930 948//948 310//310 -f 310//310 948//948 947//947 -f 310//310 947//947 308//308 -f 308//308 947//947 307//307 -f 308//308 307//307 309//309 -f 309//309 307//307 942//942 -f 309//309 942//942 882//882 -f 882//882 942//942 940//940 -f 882//882 940//940 322//322 -f 322//322 940//940 939//939 -f 322//322 939//939 320//320 -f 320//320 939//939 895//895 -f 320//320 895//895 321//321 -f 321//321 895//895 893//893 -f 321//321 893//893 878//878 -f 878//878 893//893 901//901 -f 878//878 901//901 879//879 -f 879//879 901//901 900//900 -f 879//879 900//900 880//880 -f 880//880 900//900 898//898 -f 880//880 898//898 884//884 -f 884//884 898//898 897//897 -f 884//884 897//897 886//886 -f 886//886 897//897 961//961 -f 886//886 961//961 906//906 -f 906//906 961//961 962//962 -f 906//906 962//962 889//889 -f 1025//1025 1026//1026 1027//1027 -f 1027//1027 1026//1026 1018//1018 -f 1027//1027 1018//1018 1028//1028 -f 1028//1028 1018//1018 1017//1017 -f 1028//1028 1017//1017 1029//1029 -f 1029//1029 1017//1017 1016//1016 -f 1029//1029 1016//1016 1030//1030 -f 1030//1030 1016//1016 1031//1031 -f 1030//1030 1031//1031 1032//1032 -f 1032//1032 1031//1031 1033//1033 -f 1033//1033 1031//1031 1034//1034 -f 1033//1033 1034//1034 1035//1035 -f 1016//1016 1036//1036 1031//1031 -f 1031//1031 1036//1036 1037//1037 -f 1031//1031 1037//1037 1034//1034 -f 1034//1034 1037//1037 1038//1038 -f 999//999 1039//1039 1000//1000 -f 1000//1000 1039//1039 1040//1040 -f 1000//1000 1040//1040 1001//1001 -f 1001//1001 1040//1040 1041//1041 -f 1001//1001 1041//1041 1002//1002 -f 1002//1002 1041//1041 1042//1042 -f 1002//1002 1042//1042 1003//1003 -f 1003//1003 1042//1042 1043//1043 -f 1003//1003 1043//1043 299//299 -f 299//299 1043//1043 1044//1044 -f 299//299 1044//1044 300//300 -f 300//300 1044//1044 1045//1045 -f 296//296 1046//1046 1047//1047 -f 1047//1047 1046//1046 1048//1048 -f 1047//1047 1048//1048 1049//1049 -f 1049//1049 1048//1048 1050//1050 -f 1049//1049 1050//1050 294//294 -f 1051//1051 1052//1052 293//293 -f 293//293 295//295 1051//1051 -f 1051//1051 295//295 1053//1053 -f 1051//1051 1053//1053 1054//1054 -f 998//998 283//283 999//999 -f 999//999 283//283 282//282 -f 999//999 282//282 1039//1039 -f 1039//1039 282//282 1055//1055 -f 1039//1039 1055//1055 1040//1040 -f 1040//1040 1055//1055 1056//1056 -f 1040//1040 1056//1056 1041//1041 -f 1041//1041 1056//1056 1057//1057 -f 1041//1041 1057//1057 1042//1042 -f 1042//1042 1057//1057 1058//1058 -f 1042//1042 1058//1058 1043//1043 -f 1043//1043 1058//1058 1059//1059 -f 1043//1043 1059//1059 1044//1044 -f 1044//1044 1059//1059 1060//1060 -f 1044//1044 1060//1060 1045//1045 -f 294//294 1050//1050 295//295 -f 295//295 1050//1050 1061//1061 -f 295//295 1061//1061 1053//1053 -f 1053//1053 1061//1061 1062//1062 -f 1053//1053 1062//1062 1054//1054 -f 292//292 291//291 1063//1063 -f 290//290 1064//1064 291//291 -f 291//291 1064//1064 1065//1065 -f 291//291 1065//1065 1063//1063 -f 1063//1063 1065//1065 1066//1066 -f 1063//1063 1066//1066 1067//1067 -f 934//934 1035//1035 311//311 -f 311//311 1035//1035 1034//1034 -f 311//311 1034//1034 312//312 -f 312//312 1034//1034 1038//1038 -f 312//312 1038//1038 958//958 -f 958//958 1038//1038 1068//1068 -f 958//958 1068//1068 959//959 -f 959//959 1068//1068 1069//1069 -f 959//959 1069//1069 960//960 -f 960//960 1069//1069 1070//1070 -f 960//960 1070//1070 989//989 -f 1071//1071 1072//1072 1073//1073 -f 1073//1073 1072//1072 1074//1074 -f 1075//1075 1076//1076 1077//1077 -f 1077//1077 1076//1076 1078//1078 -f 1077//1077 1078//1078 1079//1079 -f 1080//1080 1006//1006 1081//1081 -f 301//301 1004//1004 998//998 -f 998//998 1004//1004 1006//1006 -f 998//998 1006//1006 283//283 -f 283//283 1006//1006 1080//1080 -f 283//283 1080//1080 1082//1082 -f 1083//1083 1084//1084 1085//1085 -f 1085//1085 1084//1084 1086//1086 -f 1085//1085 1086//1086 1087//1087 -f 1088//1088 1089//1089 1090//1090 -f 1090//1090 1089//1089 1086//1086 -f 1090//1090 1086//1086 1091//1091 -f 1091//1091 1086//1086 1084//1084 -f 1091//1091 1084//1084 1092//1092 -f 1092//1092 1084//1084 1083//1083 -f 1092//1092 1083//1083 1093//1093 -f 1088//1088 1090//1090 1094//1094 -f 1094//1094 1090//1090 1091//1091 -f 1094//1094 1091//1091 1095//1095 -f 1095//1095 1091//1091 1092//1092 -f 1095//1095 1092//1092 1096//1096 -f 1096//1096 1092//1092 1093//1093 -f 1096//1096 1093//1093 1097//1097 -f 1098//1098 1099//1099 1100//1100 -f 1099//1099 1098//1098 1101//1101 -f 1101//1101 1098//1098 1102//1102 -f 1101//1101 1102//1102 1103//1103 -f 1104//1104 1105//1105 1106//1106 -f 1106//1106 1105//1105 1107//1107 -f 1106//1106 1107//1107 287//287 -f 1108//1108 1109//1109 1110//1110 -f 1110//1110 1109//1109 1111//1111 -f 286//286 285//285 1112//1112 -f 1112//1112 285//285 1113//1113 -f 1112//1112 1113//1113 1114//1114 -f 1114//1114 1113//1113 1115//1115 -f 1114//1114 1115//1115 1116//1116 -f 1116//1116 1115//1115 1117//1117 -f 1116//1116 1117//1117 1111//1111 -f 1111//1111 1117//1117 1118//1118 -f 1111//1111 1118//1118 1110//1110 -f 1110//1110 1118//1118 1119//1119 -f 1110//1110 1119//1119 1120//1120 -f 1121//1121 284//284 1122//1122 -f 1122//1122 284//284 286//286 -f 1122//1122 286//286 1097//1097 -f 1097//1097 286//286 1112//1112 -f 1097//1097 1112//1112 1096//1096 -f 1096//1096 1112//1112 1114//1114 -f 1096//1096 1114//1114 1095//1095 -f 1095//1095 1114//1114 1116//1116 -f 1095//1095 1116//1116 1094//1094 -f 1094//1094 1116//1116 1111//1111 -f 1094//1094 1111//1111 1088//1088 -f 1088//1088 1111//1111 1109//1109 -f 1088//1088 1109//1109 1089//1089 -f 1089//1089 1109//1109 1108//1108 -f 1089//1089 1108//1108 1086//1086 -f 1086//1086 1108//1108 1123//1123 -f 1086//1086 1123//1123 1087//1087 -f 1087//1087 1123//1123 1124//1124 -f 1125//1125 1126//1126 1127//1127 -f 1127//1127 1126//1126 1128//1128 -f 1127//1127 1128//1128 985//985 -f 1129//1129 1130//1130 1131//1131 -f 290//290 1132//1132 1064//1064 -f 1064//1064 1132//1132 1133//1133 -f 1064//1064 1133//1133 1065//1065 -f 1065//1065 1133//1133 1129//1129 -f 1065//1065 1129//1129 1066//1066 -f 1066//1066 1129//1129 1131//1131 -f 1066//1066 1131//1131 1067//1067 -f 1134//1134 1135//1135 1136//1136 -f 273//273 1137//1137 1138//1138 -f 1138//1138 1137//1137 1136//1136 -f 1136//1136 1135//1135 1138//1138 -f 1138//1138 1135//1135 274//274 -f 1138//1138 274//274 273//273 -f 1139//1139 1077//1077 1140//1140 -f 1140//1140 1077//1077 1079//1079 -f 1140//1140 1079//1079 1141//1141 -f 1141//1141 1079//1079 1142//1142 -f 1141//1141 1142//1142 1143//1143 -f 1143//1143 1142//1142 1144//1144 -f 1143//1143 1144//1144 1145//1145 -f 280//280 277//277 1146//1146 -f 1146//1146 277//277 276//276 -f 1146//1146 276//276 1139//1139 -f 278//278 277//277 1147//1147 -f 1147//1147 277//277 279//279 -f 1147//1147 279//279 1148//1148 -f 1139//1139 1140//1140 1146//1146 -f 1146//1146 1140//1140 1141//1141 -f 1146//1146 1141//1141 280//280 -f 280//280 1141//1141 1143//1143 -f 280//280 1143//1143 279//279 -f 279//279 1143//1143 1145//1145 -f 279//279 1145//1145 1148//1148 -f 1149//1149 1150//1150 1151//1151 -f 1151//1151 1150//1150 1152//1152 -f 1151//1151 1152//1152 1153//1153 -f 1153//1153 1152//1152 1154//1154 -f 1155//1155 1154//1154 1156//1156 -f 1156//1156 1154//1154 1152//1152 -f 1156//1156 1152//1152 1157//1157 -f 1157//1157 1152//1152 1150//1150 -f 1158//1158 1159//1159 1160//1160 -f 1160//1160 1159//1159 1161//1161 -f 1162//1162 1163//1163 1158//1158 -f 1158//1158 1163//1163 1155//1155 -f 1158//1158 1155//1155 1159//1159 -f 1159//1159 1155//1155 1156//1156 -f 1159//1159 1156//1156 1161//1161 -f 1161//1161 1156//1156 1157//1157 -f 1161//1161 1157//1157 1164//1164 -f 1164//1164 1157//1157 1150//1150 -f 1164//1164 1150//1150 1165//1165 -f 1165//1165 1150//1150 1149//1149 -f 287//287 289//289 1106//1106 -f 1106//1106 289//289 1166//1166 -f 1106//1106 1166//1166 1104//1104 -f 1104//1104 1166//1166 1167//1167 -f 1104//1104 1167//1167 1119//1119 -f 1121//1121 288//288 284//284 -f 284//284 288//288 287//287 -f 284//284 287//287 285//285 -f 285//285 287//287 1107//1107 -f 285//285 1107//1107 1113//1113 -f 1113//1113 1107//1107 1100//1100 -f 1113//1113 1100//1100 1115//1115 -f 1115//1115 1100//1100 1099//1099 -f 1115//1115 1099//1099 1117//1117 -f 1117//1117 1099//1099 1101//1101 -f 1117//1117 1101//1101 1118//1118 -f 1118//1118 1101//1101 1103//1103 -f 1118//1118 1103//1103 1119//1119 -f 1119//1119 1103//1103 1102//1102 -f 1119//1119 1102//1102 1104//1104 -f 1104//1104 1102//1102 1098//1098 -f 1104//1104 1098//1098 1105//1105 -f 1105//1105 1098//1098 1100//1100 -f 1105//1105 1100//1100 1107//1107 -f 1168//1168 1169//1169 1170//1170 -f 1170//1170 1169//1169 1171//1171 -f 1170//1170 1171//1171 1172//1172 -f 270//270 275//275 1173//1173 -f 1173//1173 275//275 274//274 -f 1173//1173 274//274 1174//1174 -f 1174//1174 274//274 1135//1135 -f 1174//1174 1135//1135 1172//1172 -f 1172//1172 1135//1135 1134//1134 -f 1172//1172 1134//1134 1170//1170 -f 1170//1170 1134//1134 1136//1136 -f 1170//1170 1136//1136 1168//1168 -f 1168//1168 1136//1136 1079//1079 -f 1168//1168 1079//1079 1005//1005 -f 1005//1005 1079//1079 1078//1078 -f 1005//1005 1078//1078 1006//1006 -f 1006//1006 1078//1078 1076//1076 -f 1006//1006 1076//1076 1081//1081 -f 1081//1081 1076//1076 1075//1075 -f 1175//1175 1176//1176 1177//1177 -f 1177//1177 1176//1176 1178//1178 -f 1177//1177 1178//1178 1179//1179 -f 1179//1179 1178//1178 1180//1180 -f 1181//1181 1180//1180 1178//1178 -f 1181//1181 1178//1178 1182//1182 -f 1182//1182 1178//1178 1176//1176 -f 1182//1182 1176//1176 1183//1183 -f 1183//1183 1176//1176 1184//1184 -f 1026//1026 1015//1015 1018//1018 -f 1018//1018 1015//1015 1014//1014 -f 1018//1018 1014//1014 1016//1016 -f 1016//1016 1014//1014 1012//1012 -f 1016//1016 1012//1012 1036//1036 -f 1036//1036 1012//1012 1011//1011 -f 1036//1036 1011//1011 1037//1037 -f 1037//1037 1011//1011 1185//1185 -f 1037//1037 1185//1185 1038//1038 -f 1038//1038 1185//1185 1125//1125 -f 1038//1038 1125//1125 1068//1068 -f 1068//1068 1125//1125 1127//1127 -f 1068//1068 1127//1127 1069//1069 -f 1069//1069 1127//1127 985//985 -f 1069//1069 985//985 1186//1186 -f 1186//1186 985//985 984//984 -f 382//382 381//381 384//384 -f 384//384 381//381 936//936 -f 384//384 936//936 808//808 -f 808//808 936//936 876//876 -f 808//808 876//876 807//807 -f 807//807 876//876 809//809 -f 807//807 809//809 806//806 -f 806//806 809//809 811//811 -f 806//806 811//811 805//805 -f 805//805 811//811 813//813 -f 805//805 813//813 1187//1187 -f 450//450 1188//1188 1189//1189 -f 1189//1189 1188//1188 1190//1190 -f 1189//1189 1190//1190 1191//1191 -f 1191//1191 1190//1190 1192//1192 -f 1193//1193 1194//1194 1195//1195 -f 1195//1195 1194//1194 1196//1196 -f 1195//1195 1196//1196 1197//1197 -f 1197//1197 1196//1196 1198//1198 -f 1197//1197 1198//1198 1199//1199 -f 1200//1200 1201//1201 1202//1202 -f 1203//1203 1202//1202 269//269 -f 1204//1204 1203//1203 1205//1205 -f 1204//1204 1205//1205 1206//1206 -f 1202//1202 1203//1203 1204//1204 -f 1202//1202 1204//1204 1200//1200 -f 1200//1200 1204//1204 1207//1207 -f 1207//1207 1204//1204 1206//1206 -f 1208//1208 1209//1209 1210//1210 -f 1211//1211 1209//1209 1212//1212 -f 1212//1212 1209//1209 1208//1208 -f 1212//1212 1208//1208 1213//1213 -f 1214//1214 1211//1211 1215//1215 -f 1215//1215 1211//1211 1212//1212 -f 1215//1215 1212//1212 1213//1213 -f 1202//1202 1213//1213 1216//1216 -f 1217//1217 1208//1208 1218//1218 -f 1218//1218 1208//1208 1219//1219 -f 1218//1218 1219//1219 1220//1220 -f 1211//1211 1221//1221 1222//1222 -f 1222//1222 1221//1221 1223//1223 -f 1222//1222 1223//1223 1224//1224 -f 1224//1224 1223//1223 1225//1225 -f 1224//1224 1225//1225 1226//1226 -f 1226//1226 1225//1225 1227//1227 -f 1226//1226 1227//1227 1228//1228 -f 1228//1228 1227//1227 1229//1229 -f 1230//1230 1231//1231 1232//1232 -f 1232//1232 1231//1231 1233//1233 -f 1232//1232 1233//1233 1234//1234 -f 268//268 1217//1217 267//267 -f 267//267 1217//1217 1218//1218 -f 267//267 1218//1218 265//265 -f 265//265 1218//1218 1220//1220 -f 265//265 1220//1220 266//266 -f 1235//1235 1236//1236 1237//1237 -f 1237//1237 1236//1236 1238//1238 -f 1237//1237 1238//1238 1239//1239 -f 1239//1239 1238//1238 1240//1240 -f 1239//1239 1240//1240 1241//1241 -f 1241//1241 1240//1240 1242//1242 -f 1241//1241 1242//1242 1243//1243 -f 1244//1244 1235//1235 1245//1245 -f 1245//1245 1235//1235 1237//1237 -f 1245//1245 1237//1237 1246//1246 -f 1246//1246 1237//1237 1239//1239 -f 1246//1246 1239//1239 1247//1247 -f 1247//1247 1239//1239 1241//1241 -f 1247//1247 1241//1241 1248//1248 -f 1248//1248 1241//1241 1243//1243 -f 1248//1248 1243//1243 1249//1249 -f 1250//1250 1211//1211 1207//1207 -f 1207//1207 1211//1211 1214//1214 -f 1207//1207 1214//1214 1200//1200 -f 1200//1200 1214//1214 1215//1215 -f 1200//1200 1215//1215 1201//1201 -f 1201//1201 1215//1215 1213//1213 -f 1201//1201 1213//1213 1202//1202 -f 269//269 1202//1202 1216//1216 -f 269//269 1216//1216 268//268 -f 268//268 1216//1216 1213//1213 -f 268//268 1213//1213 1217//1217 -f 1217//1217 1213//1213 1208//1208 -f 1208//1208 1210//1210 1219//1219 -f 1251//1251 1252//1252 1253//1253 -f 1253//1253 1252//1252 1254//1254 -f 1230//1230 1255//1255 1231//1231 -f 1231//1231 1255//1255 1256//1256 -f 1231//1231 1256//1256 1233//1233 -f 1233//1233 1256//1256 1257//1257 -f 1233//1233 1257//1257 1234//1234 -f 1234//1234 1257//1257 1258//1258 -f 263//263 262//262 1259//1259 -f 1259//1259 262//262 1260//1260 -f 1259//1259 1260//1260 1261//1261 -f 1262//1262 1263//1263 1264//1264 -f 1264//1264 1263//1263 1255//1255 -f 1264//1264 1255//1255 1235//1235 -f 1235//1235 1255//1255 1230//1230 -f 1235//1235 1230//1230 1236//1236 -f 1236//1236 1230//1230 1232//1232 -f 1236//1236 1232//1232 1238//1238 -f 1238//1238 1232//1232 1234//1234 -f 1238//1238 1234//1234 1240//1240 -f 1240//1240 1234//1234 1258//1258 -f 1240//1240 1258//1258 1242//1242 -f 1265//1265 1266//1266 1267//1267 -f 1267//1267 1266//1266 1268//1268 -f 1267//1267 1268//1268 1269//1269 -f 1269//1269 1268//1268 1270//1270 -f 1269//1269 1270//1270 1271//1271 -f 1266//1266 1272//1272 1268//1268 -f 1268//1268 1272//1272 1273//1273 -f 1268//1268 1273//1273 1270//1270 -f 1270//1270 1273//1273 1274//1274 -f 1270//1270 1274//1274 1271//1271 -f 1271//1271 1274//1274 1275//1275 -f 1265//1265 1276//1276 1266//1266 -f 1266//1266 1276//1276 1277//1277 -f 1266//1266 1277//1277 1272//1272 -f 1272//1272 1277//1277 1278//1278 -f 1272//1272 1278//1278 1273//1273 -f 1273//1273 1278//1278 1279//1279 -f 1273//1273 1279//1279 1274//1274 -f 1274//1274 1279//1279 1280//1280 -f 1274//1274 1280//1280 1275//1275 -f 1281//1281 1282//1282 1283//1283 -f 1283//1283 1282//1282 1284//1284 -f 1283//1283 1284//1284 253//253 -f 254//254 1285//1285 1286//1286 -f 1286//1286 1285//1285 1287//1287 -f 1286//1286 1287//1287 1288//1288 -f 1289//1289 1290//1290 261//261 -f 261//261 1290//1290 1291//1291 -f 261//261 1291//1291 259//259 -f 259//259 1291//1291 1292//1292 -f 1293//1293 1294//1294 1295//1295 -f 1295//1295 1294//1294 1296//1296 -f 254//254 253//253 1285//1285 -f 1285//1285 253//253 1284//1284 -f 1285//1285 1284//1284 1287//1287 -f 1287//1287 1284//1284 1282//1282 -f 1287//1287 1282//1282 1288//1288 -f 1277//1277 1297//1297 1278//1278 -f 1278//1278 1297//1297 1298//1298 -f 1278//1278 1298//1298 1279//1279 -f 1279//1279 1298//1298 1299//1299 -f 1279//1279 1299//1299 1280//1280 -f 1280//1280 1299//1299 1253//1253 -f 1280//1280 1253//1253 1275//1275 -f 1275//1275 1253//1253 1254//1254 -f 1275//1275 1254//1254 1271//1271 -f 1271//1271 1254//1254 1261//1261 -f 1271//1271 1261//1261 1269//1269 -f 1269//1269 1261//1261 1260//1260 -f 1269//1269 1260//1260 1267//1267 -f 1267//1267 1260//1260 262//262 -f 1267//1267 262//262 1265//1265 -f 1265//1265 262//262 264//264 -f 1265//1265 264//264 1276//1276 -f 251//251 250//250 1300//1300 -f 1300//1300 250//250 1301//1301 -f 1300//1300 1301//1301 1302//1302 -f 1293//1293 1262//1262 1294//1294 -f 1294//1294 1262//1262 252//252 -f 1294//1294 252//252 1303//1303 -f 1303//1303 252//252 251//251 -f 1303//1303 251//251 1304//1304 -f 1304//1304 251//251 1300//1300 -f 1304//1304 1300//1300 1305//1305 -f 1305//1305 1300//1300 1302//1302 -f 1305//1305 1302//1302 1306//1306 -f 1306//1306 1307//1307 1305//1305 -f 1305//1305 1307//1307 1308//1308 -f 1305//1305 1308//1308 1304//1304 -f 1304//1304 1308//1308 258//258 -f 1304//1304 258//258 1303//1303 -f 1303//1303 258//258 257//257 -f 1303//1303 257//257 1294//1294 -f 1294//1294 257//257 256//256 -f 1294//1294 256//256 1296//1296 -f 244//244 246//246 1309//1309 -f 1310//1310 1311//1311 1312//1312 -f 1312//1312 1311//1311 1313//1313 -f 1312//1312 1313//1313 1314//1314 -f 1314//1314 1313//1313 1315//1315 -f 1314//1314 1315//1315 1316//1316 -f 1316//1316 1315//1315 1317//1317 -f 242//242 241//241 1318//1318 -f 1318//1318 241//241 1319//1319 -f 1318//1318 1319//1319 249//249 -f 1320//1320 1321//1321 1322//1322 -f 1322//1322 1321//1321 1323//1323 -f 1322//1322 1323//1323 1324//1324 -f 243//243 1317//1317 241//241 -f 241//241 1317//1317 1315//1315 -f 241//241 1315//1315 1319//1319 -f 1319//1319 1315//1315 1313//1313 -f 1319//1319 1313//1313 249//249 -f 249//249 1313//1313 1311//1311 -f 249//249 1311//1311 247//247 -f 1325//1325 1309//1309 1326//1326 -f 1326//1326 1309//1309 246//246 -f 1326//1326 246//246 1327//1327 -f 1327//1327 246//246 1328//1328 -f 1327//1327 1328//1328 211//211 -f 1325//1325 1329//1329 1309//1309 -f 1309//1309 1329//1329 1330//1330 -f 1309//1309 1330//1330 244//244 -f 244//244 1330//1330 1331//1331 -f 244//244 1331//1331 245//245 -f 245//245 1331//1331 1321//1321 -f 245//245 1321//1321 246//246 -f 246//246 1321//1321 1320//1320 -f 246//246 1320//1320 1328//1328 -f 1332//1332 1333//1333 1334//1334 -f 1334//1334 1333//1333 1335//1335 -f 1336//1336 1337//1337 1338//1338 -f 1338//1338 1337//1337 1339//1339 -f 1338//1338 1339//1339 1340//1340 -f 1341//1341 1342//1342 1343//1343 -f 1343//1343 1342//1342 1344//1344 -f 1343//1343 1344//1344 1345//1345 -f 240//240 239//239 1332//1332 -f 1332//1332 239//239 1346//1346 -f 1332//1332 1346//1346 1333//1333 -f 1347//1347 1335//1335 1348//1348 -f 1348//1348 1335//1335 1333//1333 -f 1348//1348 1333//1333 1349//1349 -f 1349//1349 1333//1333 1346//1346 -f 1350//1350 1351//1351 235//235 -f 1351//1351 1350//1350 1352//1352 -f 235//235 237//237 1350//1350 -f 1350//1350 237//237 1353//1353 -f 1350//1350 1353//1353 1352//1352 -f 1352//1352 1353//1353 1354//1354 -f 1352//1352 1354//1354 1355//1355 -f 1347//1347 1336//1336 1335//1335 -f 1335//1335 1336//1336 1338//1338 -f 1335//1335 1338//1338 1334//1334 -f 1334//1334 1338//1338 1340//1340 -f 1334//1334 1340//1340 1332//1332 -f 1332//1332 1340//1340 1341//1341 -f 1332//1332 1341//1341 240//240 -f 240//240 1341//1341 1343//1343 -f 240//240 1343//1343 238//238 -f 238//238 1343//1343 1345//1345 -f 237//237 1356//1356 1353//1353 -f 1353//1353 1356//1356 1357//1357 -f 1353//1353 1357//1357 1358//1358 -f 1359//1359 1360//1360 1361//1361 -f 1361//1361 1360//1360 1362//1362 -f 1329//1329 1310//1310 1330//1330 -f 1330//1330 1310//1310 1312//1312 -f 1330//1330 1312//1312 1331//1331 -f 1331//1331 1312//1312 1314//1314 -f 1331//1331 1314//1314 1321//1321 -f 1321//1321 1314//1314 1316//1316 -f 1321//1321 1316//1316 1323//1323 -f 1323//1323 1316//1316 1317//1317 -f 1323//1323 1317//1317 1324//1324 -f 1324//1324 1317//1317 243//243 -f 1324//1324 243//243 1363//1363 -f 1363//1363 243//243 242//242 -f 1363//1363 242//242 1362//1362 -f 1362//1362 242//242 1318//1318 -f 1362//1362 1318//1318 1361//1361 -f 1361//1361 1318//1318 249//249 -f 1361//1361 249//249 1364//1364 -f 1364//1364 249//249 248//248 -f 1364//1364 248//248 1365//1365 -f 1306//1306 1366//1366 1307//1307 -f 1307//1307 1366//1366 1367//1367 -f 1307//1307 1367//1367 1308//1308 -f 1308//1308 1367//1367 1368//1368 -f 1308//1308 1368//1368 258//258 -f 258//258 1368//1368 1369//1369 -f 258//258 1369//1369 256//256 -f 256//256 1369//1369 1370//1370 -f 256//256 1370//1370 1296//1296 -f 1371//1371 1372//1372 1289//1289 -f 1289//1289 1372//1372 1373//1373 -f 1289//1289 1373//1373 1290//1290 -f 1290//1290 1373//1373 255//255 -f 1290//1290 255//255 1291//1291 -f 1291//1291 255//255 254//254 -f 1291//1291 254//254 1292//1292 -f 1292//1292 254//254 1286//1286 -f 1292//1292 1286//1286 259//259 -f 259//259 1286//1286 1288//1288 -f 259//259 1288//1288 260//260 -f 1277//1277 1281//1281 1297//1297 -f 1297//1297 1281//1281 1283//1283 -f 1297//1297 1283//1283 1298//1298 -f 1298//1298 1283//1283 253//253 -f 1298//1298 253//253 1299//1299 -f 1299//1299 253//253 255//255 -f 1299//1299 255//255 1253//1253 -f 1253//1253 255//255 1373//1373 -f 1253//1253 1373//1373 1374//1374 -f 1374//1374 1373//1373 1375//1375 -f 211//211 1328//1328 212//212 -f 212//212 1328//1328 1376//1376 -f 212//212 1376//1376 1377//1377 -f 1191//1191 1378//1378 1189//1189 -f 1189//1189 1378//1378 1199//1199 -f 1189//1189 1199//1199 450//450 -f 450//450 1199//1199 1198//1198 -f 450//450 1198//1198 448//448 -f 448//448 1198//1198 1196//1196 -f 448//448 1196//1196 1379//1379 -f 1379//1379 1196//1196 1194//1194 -f 1379//1379 1194//1194 455//455 -f 455//455 1194//1194 1193//1193 -f 455//455 1193//1193 453//453 -f 1380//1380 1381//1381 1382//1382 -f 1383//1383 1384//1384 1385//1385 -f 1385//1385 1384//1384 1386//1386 -f 1385//1385 1386//1386 1387//1387 -f 1387//1387 1386//1386 1388//1388 -f 1387//1387 1388//1388 1389//1389 -f 236//236 1383//1383 237//237 -f 237//237 1383//1383 1385//1385 -f 237//237 1385//1385 1356//1356 -f 1356//1356 1385//1385 1387//1387 -f 1356//1356 1387//1387 1357//1357 -f 1357//1357 1387//1387 1389//1389 -f 1357//1357 1389//1389 1358//1358 -f 1390//1390 1391//1391 1392//1392 -f 1392//1392 1391//1391 1393//1393 -f 1392//1392 1393//1393 1394//1394 -f 1394//1394 1393//1393 1395//1395 -f 1394//1394 1395//1395 1396//1396 -f 1381//1381 1380//1380 1397//1397 -f 1397//1397 1380//1380 1359//1359 -f 1397//1397 1359//1359 1390//1390 -f 235//235 1382//1382 236//236 -f 236//236 1382//1382 1381//1381 -f 236//236 1381//1381 1383//1383 -f 1383//1383 1381//1381 1397//1397 -f 1383//1383 1397//1397 1384//1384 -f 1384//1384 1397//1397 1390//1390 -f 1384//1384 1390//1390 1386//1386 -f 1386//1386 1390//1390 1392//1392 -f 1386//1386 1392//1392 1388//1388 -f 1388//1388 1392//1392 1394//1394 -f 1388//1388 1394//1394 1389//1389 -f 1389//1389 1394//1394 1396//1396 -f 1389//1389 1396//1396 1358//1358 -f 1358//1358 1396//1396 1377//1377 -f 1358//1358 1377//1377 1353//1353 -f 1353//1353 1377//1377 1376//1376 -f 1353//1353 1376//1376 1354//1354 -f 1354//1354 1376//1376 1348//1348 -f 1354//1354 1348//1348 1355//1355 -f 1355//1355 1348//1348 1349//1349 -f 1355//1355 1349//1349 1352//1352 -f 1352//1352 1349//1349 1346//1346 -f 1352//1352 1346//1346 1351//1351 -f 1351//1351 1346//1346 239//239 -f 1351//1351 239//239 235//235 -f 235//235 239//239 238//238 -f 235//235 238//238 1382//1382 -f 1382//1382 238//238 1345//1345 -f 1382//1382 1345//1345 1380//1380 -f 1380//1380 1345//1345 1344//1344 -f 1380//1380 1344//1344 1359//1359 -f 1359//1359 1344//1344 1342//1342 -f 1359//1359 1342//1342 1360//1360 -f 1360//1360 1342//1342 1341//1341 -f 1360//1360 1341//1341 1362//1362 -f 1362//1362 1341//1341 1340//1340 -f 1362//1362 1340//1340 1363//1363 -f 1363//1363 1340//1340 1339//1339 -f 1363//1363 1339//1339 1324//1324 -f 1324//1324 1339//1339 1337//1337 -f 1324//1324 1337//1337 1322//1322 -f 1322//1322 1337//1337 1336//1336 -f 1322//1322 1336//1336 1320//1320 -f 1320//1320 1336//1336 1347//1347 -f 1320//1320 1347//1347 1328//1328 -f 1328//1328 1347//1347 1348//1348 -f 1328//1328 1348//1348 1376//1376 -f 1398//1398 1399//1399 1400//1400 -f 1400//1400 1399//1399 1401//1401 -f 1400//1400 1401//1401 1402//1402 -f 1402//1402 1401//1401 1403//1403 -f 1402//1402 1403//1403 1404//1404 -f 1405//1405 1406//1406 1407//1407 -f 1407//1407 1406//1406 232//232 -f 1407//1407 232//232 1408//1408 -f 1408//1408 232//232 234//234 -f 1409//1409 1410//1410 1411//1411 -f 1411//1411 1410//1410 1404//1404 -f 1412//1412 1413//1413 231//231 -f 230//230 1414//1414 231//231 -f 231//231 1414//1414 1415//1415 -f 231//231 1415//1415 1412//1412 -f 1416//1416 1417//1417 1418//1418 -f 1419//1419 1416//1416 1420//1420 -f 1420//1420 1416//1416 1418//1418 -f 1420//1420 1418//1418 1421//1421 -f 1421//1421 1418//1418 1422//1422 -f 1423//1423 1424//1424 1425//1425 -f 227//227 226//226 1426//1426 -f 1426//1426 226//226 1427//1427 -f 1426//1426 1427//1427 1425//1425 -f 1425//1425 1424//1424 1426//1426 -f 1426//1426 1424//1424 1428//1428 -f 1426//1426 1428//1428 227//227 -f 227//227 1428//1428 1429//1429 -f 227//227 1429//1429 228//228 -f 1430//1430 1431//1431 1432//1432 -f 1432//1432 1431//1431 1433//1433 -f 1432//1432 1433//1433 1434//1434 -f 234//234 229//229 1408//1408 -f 1408//1408 229//229 231//231 -f 1408//1408 231//231 1407//1407 -f 1407//1407 231//231 1413//1413 -f 1407//1407 1413//1413 1405//1405 -f 1405//1405 1413//1413 1412//1412 -f 1405//1405 1412//1412 1435//1435 -f 1435//1435 1412//1412 1415//1415 -f 1435//1435 1415//1415 1436//1436 -f 1436//1436 1415//1415 1437//1437 -f 1423//1423 1422//1422 1424//1424 -f 1424//1424 1422//1422 1418//1418 -f 1424//1424 1418//1418 1428//1428 -f 1428//1428 1418//1418 1417//1417 -f 1428//1428 1417//1417 1429//1429 -f 1429//1429 1417//1417 1416//1416 -f 1429//1429 1416//1416 1409//1409 -f 1409//1409 1416//1416 1419//1419 -f 1409//1409 1419//1419 1410//1410 -f 281//281 1071//1071 282//282 -f 282//282 1071//1071 1073//1073 -f 282//282 1073//1073 1055//1055 -f 1055//1055 1073//1073 1074//1074 -f 1055//1055 1074//1074 1056//1056 -f 1056//1056 1074//1074 1438//1438 -f 1056//1056 1438//1438 1057//1057 -f 1057//1057 1438//1438 1062//1062 -f 1057//1057 1062//1062 1058//1058 -f 1058//1058 1062//1062 1061//1061 -f 1058//1058 1061//1061 1059//1059 -f 1059//1059 1061//1061 1050//1050 -f 1059//1059 1050//1050 1060//1060 -f 1060//1060 1050//1050 1048//1048 -f 1060//1060 1048//1048 1045//1045 -f 1045//1045 1048//1048 1046//1046 -f 1045//1045 1046//1046 300//300 -f 300//300 1046//1046 296//296 -f 300//300 296//296 301//301 -f 301//301 296//296 298//298 -f 301//301 298//298 1004//1004 -f 1004//1004 298//298 804//804 -f 1004//1004 804//804 1005//1005 -f 1005//1005 804//804 803//803 -f 1005//1005 803//803 1168//1168 -f 1168//1168 803//803 802//802 -f 1168//1168 802//802 1169//1169 -f 1169//1169 802//802 451//451 -f 1169//1169 451//451 1206//1206 -f 1206//1206 451//451 453//453 -f 1206//1206 453//453 1207//1207 -f 1207//1207 453//453 1193//1193 -f 1207//1207 1193//1193 1250//1250 -f 1250//1250 1193//1193 1195//1195 -f 1250//1250 1195//1195 1365//1365 -f 1365//1365 1195//1195 1197//1197 -f 1365//1365 1197//1197 1364//1364 -f 1364//1364 1197//1197 1199//1199 -f 1364//1364 1199//1199 1361//1361 -f 1361//1361 1199//1199 1378//1378 -f 1361//1361 1378//1378 1359//1359 -f 1439//1439 1440//1440 1441//1441 -f 1441//1441 1440//1440 1442//1442 -f 1441//1441 1442//1442 1443//1443 -f 1443//1443 1442//1442 1444//1444 -f 1445//1445 1446//1446 1447//1447 -f 1448//1448 1446//1446 1449//1449 -f 1449//1449 1446//1446 1445//1445 -f 1449//1449 1445//1445 1450//1450 -f 1451//1451 1452//1452 1453//1453 -f 1454//1454 1455//1455 1456//1456 -f 1456//1456 1455//1455 1457//1457 -f 1458//1458 1459//1459 1460//1460 -f 1452//1452 1457//1457 1453//1453 -f 1453//1453 1457//1457 1455//1455 -f 1453//1453 1455//1455 1461//1461 -f 1461//1461 1455//1455 1454//1454 -f 1430//1430 1462//1462 1463//1463 -f 1463//1463 1462//1462 1448//1448 -f 1464//1464 1465//1465 1466//1466 -f 1467//1467 1468//1468 1469//1469 -f 1470//1470 1471//1471 1466//1466 -f 1466//1466 1471//1471 1472//1472 -f 1466//1466 1472//1472 1473//1473 -f 1465//1465 1474//1474 1466//1466 -f 1466//1466 1474//1474 1475//1475 -f 1466//1466 1475//1475 1470//1470 -f 1470//1470 1475//1475 1476//1476 -f 1477//1477 1478//1478 1479//1479 -f 1479//1479 1478//1478 1480//1480 -f 1479//1479 1480//1480 1481//1481 -f 1481//1481 1480//1480 223//223 -f 1481//1481 223//223 1482//1482 -f 1482//1482 223//223 225//225 -f 1436//1436 1483//1483 1435//1435 -f 1435//1435 1483//1483 1398//1398 -f 1435//1435 1398//1398 1405//1405 -f 1405//1405 1398//1398 1400//1400 -f 1405//1405 1400//1400 1406//1406 -f 1406//1406 1400//1400 1402//1402 -f 1406//1406 1402//1402 232//232 -f 232//232 1402//1402 1404//1404 -f 232//232 1404//1404 233//233 -f 233//233 1404//1404 1410//1410 -f 233//233 1410//1410 234//234 -f 234//234 1410//1410 1419//1419 -f 234//234 1419//1419 229//229 -f 229//229 1419//1419 1420//1420 -f 229//229 1420//1420 230//230 -f 230//230 1420//1420 1421//1421 -f 230//230 1421//1421 1414//1414 -f 1414//1414 1421//1421 1422//1422 -f 1414//1414 1422//1422 1415//1415 -f 1415//1415 1422//1422 1423//1423 -f 1415//1415 1423//1423 1437//1437 -f 1437//1437 1423//1423 1425//1425 -f 1437//1437 1425//1425 1436//1436 -f 1484//1484 1447//1447 1439//1439 -f 1439//1439 1447//1447 1446//1446 -f 1439//1439 1446//1446 1440//1440 -f 1440//1440 1446//1446 1448//1448 -f 1440//1440 1448//1448 1442//1442 -f 1442//1442 1448//1448 1462//1462 -f 1442//1442 1462//1462 1444//1444 -f 1444//1444 1462//1462 1430//1430 -f 1444//1444 1430//1430 1443//1443 -f 1443//1443 1430//1430 1432//1432 -f 1443//1443 1432//1432 1441//1441 -f 1441//1441 1432//1432 1434//1434 -f 1441//1441 1434//1434 1439//1439 -f 1439//1439 1434//1434 1484//1484 -f 1485//1485 1486//1486 1487//1487 -f 1487//1487 1486//1486 1488//1488 -f 1488//1488 1489//1489 1487//1487 -f 1487//1487 1489//1489 1490//1490 -f 1487//1487 1490//1490 1485//1485 -f 1485//1485 1491//1491 1486//1486 -f 1486//1486 1491//1491 1492//1492 -f 1486//1486 1492//1492 1493//1493 -f 1493//1493 1492//1492 1494//1494 -f 1493//1493 1494//1494 1495//1495 -f 1496//1496 1497//1497 1498//1498 -f 1499//1499 1498//1498 1500//1500 -f 1500//1500 1498//1498 1497//1497 -f 1500//1500 1497//1497 1501//1501 -f 1501//1501 221//221 1500//1500 -f 1500//1500 221//221 220//220 -f 1500//1500 220//220 1499//1499 -f 1499//1499 220//220 1502//1502 -f 1499//1499 1502//1502 1503//1503 -f 1504//1504 1505//1505 1506//1506 -f 1506//1506 1505//1505 1507//1507 -f 1508//1508 1509//1509 1507//1507 -f 1507//1507 1509//1509 1510//1510 -f 1507//1507 1510//1510 1506//1506 -f 1506//1506 1510//1510 1511//1511 -f 1512//1512 1458//1458 225//225 -f 225//225 1458//1458 1460//1460 -f 225//225 1460//1460 1482//1482 -f 1482//1482 1460//1460 1513//1513 -f 1482//1482 1513//1513 1481//1481 -f 1481//1481 1513//1513 1514//1514 -f 1481//1481 1514//1514 1479//1479 -f 1479//1479 1514//1514 1471//1471 -f 1479//1479 1471//1471 1477//1477 -f 1511//1511 1515//1515 1506//1506 -f 1506//1506 1515//1515 1516//1516 -f 1506//1506 1516//1516 1504//1504 -f 1461//1461 1450//1450 1453//1453 -f 1453//1453 1450//1450 1445//1445 -f 1453//1453 1445//1445 1451//1451 -f 1451//1451 1445//1445 1447//1447 -f 1451//1451 1447//1447 1517//1517 -f 1517//1517 1447//1447 1484//1484 -f 1517//1517 1484//1484 228//228 -f 228//228 1484//1484 1434//1434 -f 228//228 1434//1434 226//226 -f 226//226 1434//1434 1433//1433 -f 226//226 1433//1433 1427//1427 -f 1427//1427 1433//1433 1431//1431 -f 1427//1427 1431//1431 1425//1425 -f 1425//1425 1431//1431 1430//1430 -f 1425//1425 1430//1430 1436//1436 -f 1436//1436 1430//1430 1463//1463 -f 1436//1436 1463//1463 1483//1483 -f 1483//1483 1463//1463 1518//1518 -f 1483//1483 1518//1518 1519//1519 -f 1467//1467 1520//1520 1468//1468 -f 1468//1468 1520//1520 1521//1521 -f 1468//1468 1521//1521 1469//1469 -f 1469//1469 1521//1521 1522//1522 -f 1523//1523 1524//1524 1476//1476 -f 1476//1476 1524//1524 1520//1520 -f 1476//1476 1520//1520 1470//1470 -f 1470//1470 1520//1520 1467//1467 -f 1470//1470 1467//1467 1471//1471 -f 1471//1471 1467//1467 1469//1469 -f 1471//1471 1469//1469 1477//1477 -f 1477//1477 1469//1469 1522//1522 -f 1477//1477 1522//1522 1478//1478 -f 224//224 223//223 1489//1489 -f 1489//1489 223//223 1480//1480 -f 1489//1489 1480//1480 1490//1490 -f 1490//1490 1480//1480 1478//1478 -f 1490//1490 1478//1478 1485//1485 -f 1485//1485 1478//1478 1522//1522 -f 1485//1485 1522//1522 1491//1491 -f 1491//1491 1522//1522 1521//1521 -f 1491//1491 1521//1521 1492//1492 -f 1492//1492 1521//1521 1520//1520 -f 1492//1492 1520//1520 1494//1494 -f 1494//1494 1520//1520 1524//1524 -f 1494//1494 1524//1524 1495//1495 -f 1525//1525 1526//1526 1527//1527 -f 1527//1527 1526//1526 1528//1528 -f 1527//1527 1528//1528 1529//1529 -f 1530//1530 1531//1531 1532//1532 -f 1532//1532 1531//1531 1533//1533 -f 222//222 1525//1525 220//220 -f 220//220 1525//1525 1527//1527 -f 220//220 1527//1527 1502//1502 -f 1502//1502 1527//1527 1529//1529 -f 1502//1502 1529//1529 1503//1503 -f 1503//1503 1529//1529 1511//1511 -f 1503//1503 1511//1511 1499//1499 -f 1499//1499 1511//1511 1510//1510 -f 1499//1499 1510//1510 1498//1498 -f 1498//1498 1510//1510 1509//1509 -f 1498//1498 1509//1509 1496//1496 -f 1496//1496 1509//1509 1508//1508 -f 1534//1534 1535//1535 1536//1536 -f 1536//1536 1535//1535 1523//1523 -f 1536//1536 1523//1523 1537//1537 -f 1538//1538 1539//1539 1540//1540 -f 1540//1540 1539//1539 1530//1530 -f 1540//1540 1530//1530 1534//1534 -f 1534//1534 1530//1530 1532//1532 -f 1534//1534 1532//1532 1535//1535 -f 1535//1535 1532//1532 1533//1533 -f 1535//1535 1533//1533 1523//1523 -f 1541//1541 1542//1542 217//217 -f 217//217 1542//1542 1543//1543 -f 217//217 1543//1543 218//218 -f 1544//1544 1545//1545 1546//1546 -f 1546//1546 1545//1545 1547//1547 -f 1548//1548 1549//1549 1550//1550 -f 1541//1541 217//217 1551//1551 -f 1551//1551 217//217 219//219 -f 1551//1551 219//219 1552//1552 -f 215//215 214//214 1553//1553 -f 1543//1543 1548//1548 218//218 -f 218//218 1548//1548 1550//1550 -f 218//218 1550//1550 219//219 -f 219//219 1550//1550 1553//1553 -f 219//219 1553//1553 1552//1552 -f 1552//1552 1553//1553 214//214 -f 1552//1552 214//214 1551//1551 -f 1554//1554 1555//1555 1556//1556 -f 1556//1556 1555//1555 1557//1557 -f 1556//1556 1557//1557 1558//1558 -f 1538//1538 1559//1559 1554//1554 -f 1554//1554 1559//1559 1560//1560 -f 1554//1554 1560//1560 1555//1555 -f 1555//1555 1560//1560 1561//1561 -f 1555//1555 1561//1561 1557//1557 -f 1557//1557 1561//1561 1562//1562 -f 1557//1557 1562//1562 1558//1558 -f 204//204 1563//1563 205//205 -f 205//205 1563//1563 1564//1564 -f 205//205 1564//1564 1565//1565 -f 1565//1565 1564//1564 1537//1537 -f 1566//1566 1567//1567 1558//1558 -f 1558//1558 1567//1567 1568//1568 -f 1558//1558 1568//1568 1556//1556 -f 1556//1556 1568//1568 1544//1544 -f 1556//1556 1544//1544 1554//1554 -f 1554//1554 1544//1544 1546//1546 -f 1554//1554 1546//1546 1538//1538 -f 1538//1538 1546//1546 1547//1547 -f 1538//1538 1547//1547 1539//1539 -f 1539//1539 1547//1547 1545//1545 -f 1539//1539 1545//1545 1530//1530 -f 1530//1530 1545//1545 1569//1569 -f 1530//1530 1569//1569 1531//1531 -f 440//440 533//533 441//441 -f 441//441 533//533 532//532 -f 441//441 532//532 1570//1570 -f 1570//1570 532//532 531//531 -f 1570//1570 531//531 353//353 -f 353//353 531//531 530//530 -f 353//353 530//530 354//354 -f 354//354 530//530 529//529 -f 354//354 529//529 534//534 -f 534//534 529//529 527//527 -f 534//534 527//527 536//536 -f 536//536 527//527 604//604 -f 536//536 604//604 538//538 -f 538//538 604//604 621//621 -f 538//538 621//621 539//539 -f 539//539 621//621 634//634 -f 1571//1571 210//210 1572//1572 -f 1572//1572 210//210 208//208 -f 1572//1572 208//208 1573//1573 -f 1573//1573 208//208 207//207 -f 1573//1573 207//207 1574//1574 -f 1574//1574 207//207 1575//1575 -f 1574//1574 1575//1575 1576//1576 -f 1523//1523 1476//1476 1537//1537 -f 1537//1537 1476//1476 1577//1577 -f 1537//1537 1577//1577 1565//1565 -f 1565//1565 1577//1577 1578//1578 -f 1565//1565 1578//1578 205//205 -f 205//205 1578//1578 1579//1579 -f 205//205 1579//1579 206//206 -f 1580//1580 1581//1581 1582//1582 -f 1188//1188 1571//1571 1190//1190 -f 1190//1190 1571//1571 1572//1572 -f 1190//1190 1572//1572 1192//1192 -f 1192//1192 1572//1572 1573//1573 -f 1192//1192 1573//1573 1583//1583 -f 1583//1583 1573//1573 1574//1574 -f 1583//1583 1574//1574 1584//1584 -f 1584//1584 1574//1574 1576//1576 -f 1584//1584 1576//1576 1585//1585 -f 207//207 1586//1586 1575//1575 -f 1575//1575 1586//1586 1587//1587 -f 1575//1575 1587//1587 1576//1576 -f 1576//1576 1587//1587 1588//1588 -f 1576//1576 1588//1588 1585//1585 -f 1585//1585 1588//1588 1589//1589 -f 1585//1585 1589//1589 1590//1590 -f 1590//1590 1589//1589 1591//1591 -f 449//449 1592//1592 450//450 -f 450//450 1592//1592 1593//1593 -f 450//450 1593//1593 1188//1188 -f 1188//1188 1593//1593 1594//1594 -f 1188//1188 1594//1594 1571//1571 -f 1571//1571 1594//1594 1595//1595 -f 1571//1571 1595//1595 210//210 -f 210//210 1595//1595 444//444 -f 210//210 444//444 209//209 -f 209//209 444//444 443//443 -f 209//209 443//443 207//207 -f 207//207 443//443 441//441 -f 207//207 441//441 1586//1586 -f 1586//1586 441//441 1570//1570 -f 1586//1586 1570//1570 1587//1587 -f 1587//1587 1570//1570 353//353 -f 1587//1587 353//353 1588//1588 -f 1588//1588 353//353 352//352 -f 1588//1588 352//352 1589//1589 -f 1589//1589 352//352 350//350 -f 1589//1589 350//350 1591//1591 -f 1591//1591 350//350 349//349 -f 645//645 1596//1596 647//647 -f 647//647 1596//1596 1597//1597 -f 647//647 1597//1597 649//649 -f 649//649 1597//1597 1598//1598 -f 649//649 1598//1598 650//650 -f 650//650 1598//1598 1599//1599 -f 650//650 1599//1599 783//783 -f 783//783 1599//1599 1600//1600 -f 783//783 1600//1600 784//784 -f 784//784 1600//1600 1601//1601 -f 784//784 1601//1601 789//789 -f 789//789 1601//1601 1602//1602 -f 789//789 1602//1602 1603//1603 -f 1596//1596 790//790 1597//1597 -f 1597//1597 790//790 791//791 -f 1597//1597 791//791 1598//1598 -f 1598//1598 791//791 792//792 -f 1598//1598 792//792 1599//1599 -f 1599//1599 792//792 797//797 -f 1599//1599 797//797 1600//1600 -f 1600//1600 797//797 798//798 -f 1600//1600 798//798 1601//1601 -f 1601//1601 798//798 1604//1604 -f 1601//1601 1604//1604 1602//1602 -f 1602//1602 1604//1604 1605//1605 -f 1602//1602 1605//1605 1603//1603 -f 1603//1603 1605//1605 1606//1606 -f 1603//1603 1606//1606 1607//1607 -f 385//385 384//384 801//801 -f 801//801 384//384 808//808 -f 801//801 808//808 800//800 -f 800//800 808//808 336//336 -f 800//800 336//336 799//799 -f 799//799 336//336 338//338 -f 799//799 338//338 798//798 -f 798//798 338//338 339//339 -f 798//798 339//339 1604//1604 -f 1604//1604 339//339 805//805 -f 1604//1604 805//805 1605//1605 -f 1605//1605 805//805 1187//1187 -f 1605//1605 1187//1187 1606//1606 -f 1606//1606 1187//1187 1608//1608 -f 1606//1606 1608//1608 1607//1607 -f 1609//1609 1610//1610 1611//1611 -f 1612//1612 785//785 1613//1613 -f 1613//1613 785//785 786//786 -f 1613//1613 786//786 1614//1614 -f 1614//1614 786//786 787//787 -f 1614//1614 787//787 1615//1615 -f 1615//1615 787//787 788//788 -f 1615//1615 788//788 1616//1616 -f 1616//1616 788//788 789//789 -f 1616//1616 789//789 1617//1617 -f 1617//1617 789//789 1603//1603 -f 1617//1617 1603//1603 1618//1618 -f 1618//1618 1603//1603 1607//1607 -f 1611//1611 1610//1610 1619//1619 -f 1619//1619 1610//1610 1620//1620 -f 1619//1619 1620//1620 1621//1621 -f 1621//1621 1620//1620 1622//1622 -f 1621//1621 1622//1622 1623//1623 -f 1624//1624 1625//1625 1626//1626 -f 1626//1626 1625//1625 782//782 -f 1626//1626 782//782 1627//1627 -f 1627//1627 782//782 781//781 -f 1627//1627 781//781 1628//1628 -f 1628//1628 781//781 780//780 -f 1628//1628 780//780 1629//1629 -f 1629//1629 780//780 750//750 -f 1629//1629 750//750 1630//1630 -f 1630//1630 750//750 749//749 -f 1630//1630 749//749 1631//1631 -f 1632//1632 202//202 1633//1633 -f 1633//1633 202//202 201//201 -f 1633//1633 201//201 1634//1634 -f 1635//1635 1636//1636 1633//1633 -f 1633//1633 1636//1636 1637//1637 -f 1633//1633 1637//1637 1632//1632 -f 1635//1635 1633//1633 1638//1638 -f 1638//1638 1633//1633 1634//1634 -f 1638//1638 1634//1634 1639//1639 -f 1639//1639 1634//1634 1640//1640 -f 1639//1639 1640//1640 1641//1641 -f 1642//1642 1635//1635 1643//1643 -f 1643//1643 1635//1635 1638//1638 -f 1643//1643 1638//1638 1644//1644 -f 1644//1644 1638//1638 1639//1639 -f 1644//1644 1639//1639 1645//1645 -f 1645//1645 1639//1639 1641//1641 -f 1645//1645 1641//1641 1646//1646 -f 1646//1646 1641//1641 1647//1647 -f 1646//1646 1647//1647 200//200 -f 1608//1608 1609//1609 1607//1607 -f 1607//1607 1609//1609 1611//1611 -f 1607//1607 1611//1611 1618//1618 -f 1618//1618 1611//1611 1619//1619 -f 1618//1618 1619//1619 1648//1648 -f 1648//1648 1619//1619 1621//1621 -f 1648//1648 1621//1621 1649//1649 -f 1649//1649 1621//1621 1623//1623 -f 1649//1649 1623//1623 1650//1650 -f 700//700 1631//1631 701//701 -f 701//701 1631//1631 749//749 -f 701//701 749//749 702//702 -f 702//702 749//749 341//341 -f 702//702 341//341 751//751 -f 751//751 341//341 340//340 -f 751//751 340//340 774//774 -f 774//774 340//340 769//769 -f 774//774 769//769 775//775 -f 775//775 769//769 771//771 -f 775//775 771//771 1651//1651 -f 1651//1651 771//771 773//773 -f 1651//1651 773//773 1652//1652 -f 1652//1652 773//773 782//782 -f 1652//1652 782//782 1653//1653 -f 1653//1653 782//782 1625//1625 -f 698//698 1612//1612 699//699 -f 699//699 1612//1612 1613//1613 -f 699//699 1613//1613 700//700 -f 700//700 1613//1613 1614//1614 -f 700//700 1614//1614 1631//1631 -f 1631//1631 1614//1614 1615//1615 -f 1631//1631 1615//1615 1630//1630 -f 1630//1630 1615//1615 1616//1616 -f 1630//1630 1616//1616 1629//1629 -f 1629//1629 1616//1616 1617//1617 -f 1629//1629 1617//1617 1628//1628 -f 1628//1628 1617//1617 1618//1618 -f 1628//1628 1618//1618 1627//1627 -f 1627//1627 1618//1618 1648//1648 -f 1627//1627 1648//1648 1626//1626 -f 1626//1626 1648//1648 1649//1649 -f 1626//1626 1649//1649 1624//1624 -f 1624//1624 1649//1649 1650//1650 -f 200//200 199//199 1646//1646 -f 1646//1646 199//199 467//467 -f 1646//1646 467//467 1645//1645 -f 1645//1645 467//467 459//459 -f 1645//1645 459//459 1644//1644 -f 1644//1644 459//459 458//458 -f 1644//1644 458//458 1643//1643 -f 1643//1643 458//458 457//457 -f 1643//1643 457//457 1642//1642 -f 1642//1642 457//457 456//456 -f 1642//1642 456//456 460//460 -f 460//460 456//456 166//166 -f 460//460 166//166 165//165 -f 1185//1185 1067//1067 1125//1125 -f 1125//1125 1067//1067 1131//1131 -f 1125//1125 1131//1131 1126//1126 -f 1126//1126 1131//1131 1654//1654 -f 1126//1126 1654//1654 1655//1655 -f 1655//1655 1654//1654 1656//1656 -f 1655//1655 1656//1656 1657//1657 -f 1657//1657 1656//1656 1658//1658 -f 1657//1657 1658//1658 1659//1659 -f 1659//1659 1658//1658 1660//1660 -f 1659//1659 1660//1660 183//183 -f 183//183 1660//1660 184//184 -f 1211//1211 1222//1222 1209//1209 -f 1209//1209 1222//1222 1224//1224 -f 1209//1209 1224//1224 1210//1210 -f 1210//1210 1224//1224 1226//1226 -f 1210//1210 1226//1226 1219//1219 -f 1219//1219 1226//1226 1228//1228 -f 1219//1219 1228//1228 1220//1220 -f 1220//1220 1228//1228 1229//1229 -f 1220//1220 1229//1229 266//266 -f 266//266 1229//1229 1251//1251 -f 266//266 1251//1251 1661//1661 -f 1661//1661 1251//1251 1253//1253 -f 1661//1661 1253//1253 1662//1662 -f 1662//1662 1253//1253 1374//1374 -f 1662//1662 1374//1374 1663//1663 -f 1663//1663 1374//1374 1375//1375 -f 1663//1663 1375//1375 1664//1664 -f 1411//1411 1665//1665 1409//1409 -f 1409//1409 1665//1665 1475//1475 -f 1409//1409 1475//1475 1429//1429 -f 1429//1429 1475//1475 1474//1474 -f 1429//1429 1474//1474 228//228 -f 228//228 1474//1474 1465//1465 -f 228//228 1465//1465 1517//1517 -f 1517//1517 1465//1465 1464//1464 -f 1517//1517 1464//1464 1451//1451 -f 1451//1451 1464//1464 1466//1466 -f 1451//1451 1466//1466 1452//1452 -f 1452//1452 1466//1466 1473//1473 -f 1452//1452 1473//1473 1457//1457 -f 1457//1457 1473//1473 1472//1472 -f 1457//1457 1472//1472 1456//1456 -f 1456//1456 1472//1472 1471//1471 -f 1456//1456 1471//1471 1454//1454 -f 1454//1454 1471//1471 1514//1514 -f 1454//1454 1514//1514 1461//1461 -f 1461//1461 1514//1514 1513//1513 -f 1461//1461 1513//1513 1450//1450 -f 1450//1450 1513//1513 1460//1460 -f 1450//1450 1460//1460 1449//1449 -f 1449//1449 1460//1460 1459//1459 -f 1449//1449 1459//1459 1448//1448 -f 1448//1448 1459//1459 1458//1458 -f 1448//1448 1458//1458 1463//1463 -f 1463//1463 1458//1458 1512//1512 -f 1463//1463 1512//1512 1518//1518 -f 1518//1518 1512//1512 1666//1666 -f 1518//1518 1666//1666 1519//1519 -f 1519//1519 1666//1666 1667//1667 -f 1519//1519 1667//1667 1668//1668 -f 1167//1167 1163//1163 1119//1119 -f 1119//1119 1163//1163 1162//1162 -f 1119//1119 1162//1162 1120//1120 -f 1120//1120 1162//1162 1669//1669 -f 1120//1120 1669//1669 1670//1670 -f 1670//1670 1669//1669 1671//1671 -f 1670//1670 1671//1671 1672//1672 -f 1672//1672 1671//1671 1673//1673 -f 1672//1672 1673//1673 1674//1674 -f 1674//1674 1673//1673 1675//1675 -f 1674//1674 1675//1675 1676//1676 -f 1676//1676 1675//1675 1677//1677 -f 1676//1676 1677//1677 185//185 -f 185//185 1677//1677 159//159 -f 1590//1590 206//206 1585//1585 -f 1585//1585 206//206 1579//1579 -f 1585//1585 1579//1579 1584//1584 -f 1584//1584 1579//1579 1578//1578 -f 1584//1584 1578//1578 1583//1583 -f 1583//1583 1578//1578 1577//1577 -f 1583//1583 1577//1577 1192//1192 -f 1192//1192 1577//1577 1476//1476 -f 1192//1192 1476//1476 1191//1191 -f 1191//1191 1476//1476 1475//1475 -f 1191//1191 1475//1475 1378//1378 -f 1378//1378 1475//1475 1665//1665 -f 1378//1378 1665//1665 1359//1359 -f 1359//1359 1665//1665 1411//1411 -f 1359//1359 1411//1411 1390//1390 -f 1390//1390 1411//1411 1404//1404 -f 1390//1390 1404//1404 1391//1391 -f 1391//1391 1404//1404 1403//1403 -f 1391//1391 1403//1403 1393//1393 -f 1393//1393 1403//1403 1401//1401 -f 1393//1393 1401//1401 1395//1395 -f 1395//1395 1401//1401 1399//1399 -f 1395//1395 1399//1399 1396//1396 -f 1396//1396 1399//1399 1398//1398 -f 1396//1396 1398//1398 1377//1377 -f 1377//1377 1398//1398 1483//1483 -f 1377//1377 1483//1483 212//212 -f 212//212 1483//1483 1519//1519 -f 212//212 1519//1519 213//213 -f 213//213 1519//1519 1668//1668 -f 213//213 1668//1668 1678//1678 -f 1678//1678 1668//1668 1679//1679 -f 1678//1678 1679//1679 1680//1680 -f 1680//1680 1679//1679 1681//1681 -f 1682//1682 1681//1681 1683//1683 -f 1683//1683 1681//1681 1679//1679 -f 1683//1683 1679//1679 1684//1684 -f 1684//1684 1679//1679 1668//1668 -f 1684//1684 1668//1668 1685//1685 -f 1685//1685 1668//1668 1667//1667 -f 1175//1175 271//271 1176//1176 -f 1176//1176 271//271 270//270 -f 1176//1176 270//270 1184//1184 -f 1184//1184 270//270 1173//1173 -f 1184//1184 1173//1173 1183//1183 -f 1183//1183 1173//1173 1174//1174 -f 1183//1183 1174//1174 1182//1182 -f 1182//1182 1174//1174 1172//1172 -f 1182//1182 1172//1172 1181//1181 -f 1181//1181 1172//1172 1171//1171 -f 1181//1181 1171//1171 1169//1169 -f 1181//1181 1169//1169 1180//1180 -f 1180//1180 1169//1169 1206//1206 -f 1180//1180 1206//1206 1179//1179 -f 1179//1179 1206//1206 1205//1205 -f 1179//1179 1205//1205 1203//1203 -f 1179//1179 1203//1203 1177//1177 -f 1177//1177 1203//1203 1175//1175 -f 1175//1175 1203//1203 269//269 -f 1175//1175 269//269 271//271 -f 271//271 269//269 267//267 -f 271//271 267//267 272//272 -f 272//272 267//267 266//266 -f 272//272 266//266 1686//1686 -f 1686//1686 266//266 1661//1661 -f 1686//1686 1661//1661 1687//1687 -f 1687//1687 1661//1661 1662//1662 -f 1687//1687 1662//1662 1688//1688 -f 1688//1688 1662//1662 1663//1663 -f 1688//1688 1663//1663 1689//1689 -f 1689//1689 1663//1663 1664//1664 -f 1689//1689 1664//1664 1690//1690 -f 1690//1690 1664//1664 1691//1691 -f 1690//1690 1691//1691 366//366 -f 366//366 1691//1691 1692//1692 -f 366//366 1692//1692 170//170 -f 170//170 1692//1692 171//171 -f 1693//1693 1694//1694 1695//1695 -f 1695//1695 1694//1694 1696//1696 -f 1695//1695 1696//1696 1697//1697 -f 1697//1697 1696//1696 1698//1698 -f 1697//1697 1698//1698 1699//1699 -f 1699//1699 1698//1698 1700//1700 -f 1699//1699 1700//1700 1567//1567 -f 1562//1562 1701//1701 1558//1558 -f 1558//1558 1701//1701 1702//1702 -f 1558//1558 1702//1702 1566//1566 -f 1566//1566 1702//1702 1582//1582 -f 1566//1566 1582//1582 1567//1567 -f 1567//1567 1582//1582 1581//1581 -f 1567//1567 1581//1581 1699//1699 -f 1699//1699 1581//1581 1580//1580 -f 1699//1699 1580//1580 1697//1697 -f 1697//1697 1580//1580 1703//1703 -f 1697//1697 1703//1703 1695//1695 -f 1695//1695 1703//1703 546//546 -f 1695//1695 546//546 1693//1693 -f 1693//1693 546//546 544//544 -f 1693//1693 544//544 1704//1704 -f 1704//1704 544//544 542//542 -f 1705//1705 1706//1706 1707//1707 -f 1707//1707 1706//1706 1708//1708 -f 1707//1707 1708//1708 1709//1709 -f 1709//1709 1708//1708 1710//1710 -f 1709//1709 1710//1710 1711//1711 -f 1711//1711 1710//1710 1712//1712 -f 1711//1711 1712//1712 1713//1713 -f 1704//1704 1705//1705 1693//1693 -f 1693//1693 1705//1705 1707//1707 -f 1693//1693 1707//1707 1694//1694 -f 1694//1694 1707//1707 1709//1709 -f 1694//1694 1709//1709 1696//1696 -f 1696//1696 1709//1709 1711//1711 -f 1696//1696 1711//1711 1698//1698 -f 1698//1698 1711//1711 1713//1713 -f 1698//1698 1713//1713 1700//1700 -f 1714//1714 1712//1712 1715//1715 -f 1715//1715 1712//1712 1710//1710 -f 1715//1715 1710//1710 1716//1716 -f 1716//1716 1710//1710 1708//1708 -f 1716//1716 1708//1708 1717//1717 -f 1717//1717 1708//1708 1706//1706 -f 1717//1717 1706//1706 1718//1718 -f 1718//1718 1706//1706 1705//1705 -f 1718//1718 1705//1705 1719//1719 -f 1719//1719 1705//1705 1704//1704 -f 1719//1719 1704//1704 1720//1720 -f 1720//1720 1704//1704 542//542 -f 1720//1720 542//542 1721//1721 -f 1721//1721 542//542 541//541 -f 1721//1721 541//541 1722//1722 -f 1132//1132 1124//1124 1133//1133 -f 1133//1133 1124//1124 1123//1123 -f 1133//1133 1123//1123 1129//1129 -f 1129//1129 1123//1123 1108//1108 -f 1129//1129 1108//1108 1130//1130 -f 1130//1130 1108//1108 1110//1110 -f 1130//1130 1110//1110 1131//1131 -f 1131//1131 1110//1110 1120//1120 -f 1131//1131 1120//1120 1654//1654 -f 1654//1654 1120//1120 1670//1670 -f 1654//1654 1670//1670 1656//1656 -f 1656//1656 1670//1670 1672//1672 -f 1656//1656 1672//1672 1658//1658 -f 1658//1658 1672//1672 1674//1674 -f 1658//1658 1674//1674 1660//1660 -f 1660//1660 1674//1674 1676//1676 -f 1660//1660 1676//1676 184//184 -f 184//184 1676//1676 185//185 -f 172//172 1682//1682 466//466 -f 466//466 1682//1682 1683//1683 -f 466//466 1683//1683 1714//1714 -f 1714//1714 1683//1683 1684//1684 -f 1714//1714 1684//1684 1712//1712 -f 1712//1712 1684//1684 1685//1685 -f 1712//1712 1685//1685 1713//1713 -f 1713//1713 1685//1685 1667//1667 -f 1713//1713 1667//1667 1700//1700 -f 1700//1700 1667//1667 1666//1666 -f 1700//1700 1666//1666 1567//1567 -f 1567//1567 1666//1666 1516//1516 -f 1567//1567 1516//1516 1568//1568 -f 1568//1568 1516//1516 1515//1515 -f 1568//1568 1515//1515 1544//1544 -f 1544//1544 1515//1515 1511//1511 -f 1544//1544 1511//1511 1545//1545 -f 1545//1545 1511//1511 1529//1529 -f 1545//1545 1529//1529 1569//1569 -f 1569//1569 1529//1529 1528//1528 -f 1569//1569 1528//1528 1531//1531 -f 1531//1531 1528//1528 1526//1526 -f 1531//1531 1526//1526 1533//1533 -f 1533//1533 1526//1526 1525//1525 -f 1533//1533 1525//1525 1523//1523 -f 1523//1523 1525//1525 222//222 -f 1523//1523 222//222 1524//1524 -f 1524//1524 222//222 221//221 -f 1524//1524 221//221 1495//1495 -f 1495//1495 221//221 1501//1501 -f 1495//1495 1501//1501 1493//1493 -f 1493//1493 1501//1501 1497//1497 -f 1493//1493 1497//1497 1486//1486 -f 1486//1486 1497//1497 1496//1496 -f 1486//1486 1496//1496 1488//1488 -f 1488//1488 1496//1496 1508//1508 -f 1488//1488 1508//1508 1489//1489 -f 1489//1489 1508//1508 1507//1507 -f 1489//1489 1507//1507 224//224 -f 224//224 1507//1507 1505//1505 -f 224//224 1505//1505 225//225 -f 225//225 1505//1505 1504//1504 -f 225//225 1504//1504 1512//1512 -f 1512//1512 1504//1504 1516//1516 -f 1512//1512 1516//1516 1666//1666 -f 1366//1366 1371//1371 1367//1367 -f 1367//1367 1371//1371 1289//1289 -f 1367//1367 1289//1289 1368//1368 -f 1368//1368 1289//1289 261//261 -f 1368//1368 261//261 1369//1369 -f 1369//1369 261//261 260//260 -f 1369//1369 260//260 1370//1370 -f 1370//1370 260//260 1288//1288 -f 1370//1370 1288//1288 1296//1296 -f 1296//1296 1288//1288 1282//1282 -f 1296//1296 1282//1282 1295//1295 -f 1295//1295 1282//1282 1281//1281 -f 1295//1295 1281//1281 1293//1293 -f 1293//1293 1281//1281 1277//1277 -f 1293//1293 1277//1277 1262//1262 -f 1262//1262 1277//1277 1276//1276 -f 1262//1262 1276//1276 1263//1263 -f 1263//1263 1276//1276 264//264 -f 1263//1263 264//264 1255//1255 -f 1255//1255 264//264 263//263 -f 1255//1255 263//263 1256//1256 -f 1256//1256 263//263 1259//1259 -f 1256//1256 1259//1259 1257//1257 -f 1257//1257 1259//1259 1261//1261 -f 1257//1257 1261//1261 1258//1258 -f 1258//1258 1261//1261 1254//1254 -f 1258//1258 1254//1254 1242//1242 -f 1242//1242 1254//1254 1252//1252 -f 1242//1242 1252//1252 1243//1243 -f 1243//1243 1252//1252 1251//1251 -f 1243//1243 1251//1251 1249//1249 -f 1249//1249 1251//1251 1229//1229 -f 1249//1249 1229//1229 1248//1248 -f 1248//1248 1229//1229 1227//1227 -f 1248//1248 1227//1227 1247//1247 -f 1247//1247 1227//1227 1225//1225 -f 1247//1247 1225//1225 1246//1246 -f 1246//1246 1225//1225 1223//1223 -f 1246//1246 1223//1223 1245//1245 -f 1245//1245 1223//1223 1221//1221 -f 1245//1245 1221//1221 1244//1244 -f 1244//1244 1221//1221 1211//1211 -f 1244//1244 1211//1211 1235//1235 -f 1235//1235 1211//1211 1250//1250 -f 1235//1235 1250//1250 1264//1264 -f 1264//1264 1250//1250 1365//1365 -f 1264//1264 1365//1365 1262//1262 -f 1262//1262 1365//1365 248//248 -f 1262//1262 248//248 252//252 -f 252//252 248//248 247//247 -f 252//252 247//247 250//250 -f 250//250 247//247 1311//1311 -f 250//250 1311//1311 1301//1301 -f 1301//1301 1311//1311 1310//1310 -f 1301//1301 1310//1310 1302//1302 -f 1302//1302 1310//1310 1329//1329 -f 1302//1302 1329//1329 1306//1306 -f 1306//1306 1329//1329 1325//1325 -f 1306//1306 1325//1325 1366//1366 -f 1366//1366 1325//1325 1326//1326 -f 1366//1366 1326//1326 1371//1371 -f 1371//1371 1326//1326 1327//1327 -f 1371//1371 1327//1327 1372//1372 -f 1372//1372 1327//1327 211//211 -f 1372//1372 211//211 1373//1373 -f 1373//1373 211//211 213//213 -f 1373//1373 213//213 1375//1375 -f 1375//1375 213//213 1678//1678 -f 1375//1375 1678//1678 1664//1664 -f 1664//1664 1678//1678 1680//1680 -f 1664//1664 1680//1680 1691//1691 -f 1691//1691 1680//1680 1681//1681 -f 1691//1691 1681//1681 1692//1692 -f 1692//1692 1681//1681 1682//1682 -f 1692//1692 1682//1682 171//171 -f 171//171 1682//1682 172//172 -f 889//889 1723//1723 319//319 -f 319//319 1723//1723 978//978 -f 319//319 978//978 317//317 -f 317//317 978//978 977//977 -f 317//317 977//977 905//905 -f 905//905 977//977 976//976 -f 905//905 976//976 904//904 -f 904//904 976//976 328//328 -f 904//904 328//328 888//888 -f 888//888 328//328 326//326 -f 888//888 326//326 1724//1724 -f 1724//1724 326//326 325//325 -f 1724//1724 325//325 967//967 -f 967//967 325//325 971//971 -f 967//967 971//971 965//965 -f 965//965 971//971 972//972 -f 965//965 972//972 973//973 -f 973//973 972//972 979//979 -f 973//973 979//979 974//974 -f 974//974 979//979 978//978 -f 974//974 978//978 975//975 -f 975//975 978//978 1723//1723 -f 975//975 1723//1723 992//992 -f 992//992 1723//1723 889//889 -f 992//992 889//889 984//984 -f 984//984 889//889 962//962 -f 984//984 962//962 1186//1186 -f 1186//1186 962//962 957//957 -f 1186//1186 957//957 1069//1069 -f 1069//1069 957//957 304//304 -f 1069//1069 304//304 1070//1070 -f 1070//1070 304//304 955//955 -f 1070//1070 955//955 989//989 -f 989//989 955//955 952//952 -f 989//989 952//952 990//990 -f 990//990 952//952 951//951 -f 990//990 951//951 991//991 -f 991//991 951//951 1024//1024 -f 991//991 1024//1024 933//933 -f 933//933 1024//1024 1023//1023 -f 933//933 1023//1023 931//931 -f 931//931 1023//1023 1022//1022 -f 931//931 1022//1022 934//934 -f 934//934 1022//1022 1021//1021 -f 934//934 1021//1021 1035//1035 -f 1035//1035 1021//1021 1020//1020 -f 1035//1035 1020//1020 1033//1033 -f 1033//1033 1020//1020 1019//1019 -f 1033//1033 1019//1019 1032//1032 -f 1032//1032 1019//1019 1010//1010 -f 1032//1032 1010//1010 1030//1030 -f 1030//1030 1010//1010 1009//1009 -f 1030//1030 1009//1009 1029//1029 -f 1029//1029 1009//1009 1007//1007 -f 1029//1029 1007//1007 1028//1028 -f 1028//1028 1007//1007 297//297 -f 1028//1028 297//297 1027//1027 -f 1027//1027 297//297 296//296 -f 1027//1027 296//296 1025//1025 -f 1025//1025 296//296 1047//1047 -f 1025//1025 1047//1047 1026//1026 -f 1026//1026 1047//1047 1049//1049 -f 1026//1026 1049//1049 1015//1015 -f 1015//1015 1049//1049 294//294 -f 1015//1015 294//294 1013//1013 -f 1013//1013 294//294 293//293 -f 1013//1013 293//293 1011//1011 -f 1011//1011 293//293 1052//1052 -f 1011//1011 1052//1052 1185//1185 -f 1185//1185 1052//1052 1051//1051 -f 1185//1185 1051//1051 1067//1067 -f 1067//1067 1051//1051 1054//1054 -f 1067//1067 1054//1054 1063//1063 -f 1063//1063 1054//1054 1062//1062 -f 1063//1063 1062//1062 292//292 -f 292//292 1062//1062 1438//1438 -f 292//292 1438//1438 290//290 -f 290//290 1438//1438 1074//1074 -f 290//290 1074//1074 1132//1132 -f 1132//1132 1074//1074 1072//1072 -f 1132//1132 1072//1072 1124//1124 -f 1124//1124 1072//1072 1071//1071 -f 1124//1124 1071//1071 1087//1087 -f 1087//1087 1071//1071 281//281 -f 1087//1087 281//281 1085//1085 -f 1085//1085 281//281 283//283 -f 1085//1085 283//283 1083//1083 -f 1083//1083 283//283 1082//1082 -f 1083//1083 1082//1082 1093//1093 -f 1093//1093 1082//1082 1080//1080 -f 1093//1093 1080//1080 1097//1097 -f 1097//1097 1080//1080 1081//1081 -f 1097//1097 1081//1081 1122//1122 -f 1122//1122 1081//1081 1075//1075 -f 1122//1122 1075//1075 1121//1121 -f 1121//1121 1075//1075 1077//1077 -f 1121//1121 1077//1077 288//288 -f 288//288 1077//1077 1139//1139 -f 288//288 1139//1139 289//289 -f 289//289 1139//1139 276//276 -f 289//289 276//276 1166//1166 -f 1166//1166 276//276 278//278 -f 1166//1166 278//278 1167//1167 -f 1167//1167 278//278 1147//1147 -f 1167//1167 1147//1147 1163//1163 -f 1163//1163 1147//1147 1148//1148 -f 1163//1163 1148//1148 1155//1155 -f 1155//1155 1148//1148 1145//1145 -f 1155//1155 1145//1145 1154//1154 -f 1154//1154 1145//1145 1144//1144 -f 1154//1154 1144//1144 1153//1153 -f 1153//1153 1144//1144 1142//1142 -f 1153//1153 1142//1142 1151//1151 -f 1151//1151 1142//1142 1079//1079 -f 1151//1151 1079//1079 1149//1149 -f 1149//1149 1079//1079 1136//1136 -f 1149//1149 1136//1136 1165//1165 -f 1165//1165 1136//1136 1137//1137 -f 1165//1165 1137//1137 1164//1164 -f 1164//1164 1137//1137 273//273 -f 1164//1164 273//273 1161//1161 -f 1161//1161 273//273 275//275 -f 1161//1161 275//275 1160//1160 -f 1160//1160 275//275 270//270 -f 1160//1160 270//270 1158//1158 -f 1158//1158 270//270 272//272 -f 1158//1158 272//272 1162//1162 -f 1162//1162 272//272 1686//1686 -f 1162//1162 1686//1686 1669//1669 -f 1669//1669 1686//1686 1687//1687 -f 1669//1669 1687//1687 1671//1671 -f 1671//1671 1687//1687 1688//1688 -f 1671//1671 1688//1688 1673//1673 -f 1673//1673 1688//1688 1689//1689 -f 1673//1673 1689//1689 1675//1675 -f 1675//1675 1689//1689 1690//1690 -f 1675//1675 1690//1690 1677//1677 -f 1677//1677 1690//1690 366//366 -f 1677//1677 366//366 159//159 -f 159//159 366//366 160//160 -f 1725//1725 462//462 1726//1726 -f 1726//1726 462//462 463//463 -f 1726//1726 463//463 1727//1727 -f 1727//1727 463//463 464//464 -f 1727//1727 464//464 1728//1728 -f 1728//1728 464//464 465//465 -f 1728//1728 1729//1729 1727//1727 -f 1727//1727 1729//1729 1730//1730 -f 1727//1727 1730//1730 1726//1726 -f 1726//1726 1730//1730 1731//1731 -f 1726//1726 1731//1731 1725//1725 -f 1725//1725 1731//1731 1732//1732 -f 1725//1725 1732//1732 1733//1733 -f 1733//1733 1732//1732 1734//1734 -f 1733//1733 1734//1734 1735//1735 -f 1735//1735 1734//1734 1736//1736 -f 1735//1735 1736//1736 1737//1737 -f 1737//1737 1736//1736 1738//1738 -f 1737//1737 1738//1738 1739//1739 -f 1739//1739 1738//1738 1740//1740 -f 1739//1739 1740//1740 1741//1741 -f 1741//1741 1740//1740 1742//1742 -f 1741//1741 1742//1742 1743//1743 -f 174//174 173//173 465//465 -f 465//465 173//173 466//466 -f 465//465 466//466 1728//1728 -f 1728//1728 466//466 1714//1714 -f 1728//1728 1714//1714 1729//1729 -f 1729//1729 1714//1714 1715//1715 -f 1729//1729 1715//1715 1730//1730 -f 1730//1730 1715//1715 1716//1716 -f 1730//1730 1716//1716 1731//1731 -f 1731//1731 1716//1716 1717//1717 -f 1731//1731 1717//1717 1732//1732 -f 1732//1732 1717//1717 1718//1718 -f 1732//1732 1718//1718 1734//1734 -f 1734//1734 1718//1718 1719//1719 -f 1734//1734 1719//1719 1736//1736 -f 1736//1736 1719//1719 1720//1720 -f 1736//1736 1720//1720 1738//1738 -f 1738//1738 1720//1720 1721//1721 -f 1738//1738 1721//1721 1740//1740 -f 1740//1740 1721//1721 1722//1722 -f 1740//1740 1722//1722 1742//1742 -f 662//662 1743//1743 634//634 -f 634//634 1743//1743 1742//1742 -f 634//634 1742//1742 539//539 -f 539//539 1742//1742 1722//1722 -f 539//539 1722//1722 537//537 -f 537//537 1722//1722 541//541 -f 537//537 541//541 535//535 -f 535//535 541//541 543//543 -f 535//535 543//543 351//351 -f 351//351 543//543 545//545 -f 351//351 545//545 349//349 -f 349//349 545//545 546//546 -f 349//349 546//546 1591//1591 -f 1591//1591 546//546 1703//1703 -f 1591//1591 1703//1703 1590//1590 -f 1590//1590 1703//1703 1580//1580 -f 1590//1590 1580//1580 206//206 -f 206//206 1580//1580 1582//1582 -f 206//206 1582//1582 204//204 -f 204//204 1582//1582 1702//1702 -f 204//204 1702//1702 1563//1563 -f 1563//1563 1702//1702 1701//1701 -f 1563//1563 1701//1701 216//216 -f 216//216 1701//1701 1562//1562 -f 216//216 1562//1562 214//214 -f 214//214 1562//1562 1561//1561 -f 214//214 1561//1561 1551//1551 -f 1551//1551 1561//1561 1560//1560 -f 1551//1551 1560//1560 1541//1541 -f 1541//1541 1560//1560 1559//1559 -f 1541//1541 1559//1559 1542//1542 -f 1542//1542 1559//1559 1538//1538 -f 1542//1542 1538//1538 1543//1543 -f 1543//1543 1538//1538 1540//1540 -f 1543//1543 1540//1540 1548//1548 -f 1548//1548 1540//1540 1534//1534 -f 1548//1548 1534//1534 1549//1549 -f 1549//1549 1534//1534 1536//1536 -f 1549//1549 1536//1536 1550//1550 -f 1550//1550 1536//1536 1537//1537 -f 1550//1550 1537//1537 1553//1553 -f 1553//1553 1537//1537 1564//1564 -f 1553//1553 1564//1564 215//215 -f 215//215 1564//1564 1563//1563 -f 215//215 1563//1563 216//216 -f 164//164 161//161 461//461 -f 461//461 161//161 162//162 -f 461//461 162//162 1744//1744 -f 1744//1744 162//162 194//194 -f 1744//1744 194//194 525//525 -f 525//525 194//194 196//196 -f 525//525 196//196 523//523 -f 523//523 196//196 118//118 -f 523//523 118//118 521//521 -f 521//521 118//118 197//197 -f 521//521 197//197 519//519 -f 519//519 197//197 195//195 -f 183//183 182//182 1659//1659 -f 1659//1659 182//182 198//198 -f 1659//1659 198//198 1657//1657 -f 1657//1657 198//198 200//200 -f 1657//1657 200//200 1655//1655 -f 1655//1655 200//200 1647//1647 -f 1655//1655 1647//1647 1126//1126 -f 1126//1126 1647//1647 1641//1641 -f 1126//1126 1641//1641 1128//1128 -f 1128//1128 1641//1641 1640//1640 -f 1128//1128 1640//1640 985//985 -f 985//985 1640//1640 1634//1634 -f 985//985 1634//1634 987//987 -f 987//987 1634//1634 201//201 -f 987//987 201//201 988//988 -f 988//988 201//201 203//203 -f 988//988 203//203 993//993 -f 993//993 203//203 1745//1745 -f 993//993 1745//1745 994//994 -f 994//994 1745//1745 848//848 -f 994//994 848//848 857//857 -f 857//857 848//848 818//818 -f 857//857 818//818 858//858 -f 858//858 818//818 817//817 -f 858//858 817//817 860//860 -f 860//860 817//817 815//815 -f 860//860 815//815 853//853 -f 853//853 815//815 847//847 -f 853//853 847//847 851//851 -f 851//851 847//847 846//846 -f 851//851 846//846 849//849 -f 849//849 846//846 844//844 -f 849//849 844//844 982//982 -f 982//982 844//844 843//843 -f 982//982 843//843 983//983 -f 983//983 843//843 819//819 -f 983//983 819//819 826//826 -f 826//826 819//819 821//821 -f 826//826 821//821 824//824 -f 824//824 821//821 827//827 -f 824//824 827//827 823//823 -f 823//823 827//827 833//833 -f 823//823 833//833 332//332 -f 332//332 833//833 855//855 -f 332//332 855//855 330//330 -f 330//330 855//855 854//854 -f 330//330 854//854 331//331 -f 331//331 854//854 842//842 -f 331//331 842//842 970//970 -f 970//970 842//842 841//841 -f 970//970 841//841 963//963 -f 963//963 841//841 839//839 -f 963//963 839//839 964//964 -f 964//964 839//839 838//838 -f 964//964 838//838 966//966 -f 966//966 838//838 834//834 -f 966//966 834//834 967//967 -f 967//967 834//834 829//829 -f 967//967 829//829 1724//1724 -f 1724//1724 829//829 828//828 -f 1724//1724 828//828 888//888 -f 888//888 828//828 830//830 -f 888//888 830//830 875//875 -f 875//875 830//830 335//335 -f 875//875 335//335 809//809 -f 809//809 335//335 822//822 -f 809//809 822//822 810//810 -f 810//810 822//822 820//820 -f 810//810 820//820 812//812 -f 812//812 820//820 848//848 -f 812//812 848//848 813//813 -f 813//813 848//848 1745//1745 -f 813//813 1745//1745 1187//1187 -f 1187//1187 1745//1745 203//203 -f 1187//1187 203//203 1608//1608 -f 1608//1608 203//203 202//202 -f 1608//1608 202//202 1609//1609 -f 1609//1609 202//202 1632//1632 -f 1609//1609 1632//1632 1610//1610 -f 1610//1610 1632//1632 1637//1637 -f 1610//1610 1637//1637 1620//1620 -f 1620//1620 1637//1637 1636//1636 -f 1620//1620 1636//1636 1622//1622 -f 1622//1622 1636//1636 1635//1635 -f 1622//1622 1635//1635 1623//1623 -f 1623//1623 1635//1635 1642//1642 -f 1623//1623 1642//1642 1650//1650 -f 1650//1650 1642//1642 460//460 -f 1650//1650 460//460 1624//1624 -f 1624//1624 460//460 461//461 -f 1624//1624 461//461 1625//1625 -f 1625//1625 461//461 1744//1744 -f 1625//1625 1744//1744 1653//1653 -f 1653//1653 1744//1744 525//525 -f 1653//1653 525//525 1652//1652 -f 1652//1652 525//525 524//524 -f 1652//1652 524//524 1651//1651 -f 1651//1651 524//524 522//522 -f 1651//1651 522//522 775//775 -f 775//775 522//522 520//520 -f 775//775 520//520 514//514 -f 514//514 520//520 519//519 -f 514//514 519//519 355//355 -f 355//355 519//519 195//195 -f 355//355 195//195 193//193 -f 187//187 186//186 476//476 -f 476//476 186//186 462//462 -f 476//476 462//462 478//478 -f 478//478 462//462 1725//1725 -f 478//478 1725//1725 558//558 -f 558//558 1725//1725 1733//1733 -f 558//558 1733//1733 685//685 -f 685//685 1733//1733 1735//1735 -f 685//685 1735//1735 684//684 -f 684//684 1735//1735 1737//1737 -f 684//684 1737//1737 683//683 -f 683//683 1737//1737 1739//1739 -f 683//683 1739//1739 682//682 -f 682//682 1739//1739 1741//1741 -f 682//682 1741//1741 681//681 -f 681//681 1741//1741 1743//1743 -f 681//681 1743//1743 679//679 -f 679//679 1743//1743 662//662 -f 679//679 662//662 677//677 -f 677//677 662//662 661//661 -f 677//677 661//661 675//675 -f 675//675 661//661 660//660 -f 675//675 660//660 673//673 -f 673//673 660//660 659//659 -f 673//673 659//659 671//671 -f 671//671 659//659 658//658 -f 671//671 658//658 669//669 -f 669//669 658//658 657//657 -f 669//669 657//657 667//667 -f 667//667 657//657 656//656 -f 667//667 656//656 665//665 -f 665//665 656//656 655//655 -f 665//665 655//655 663//663 -f 663//663 655//655 654//654 -f 663//663 654//654 345//345 -f 345//345 654//654 653//653 -f 345//345 653//653 698//698 -f 698//698 653//653 652//652 -f 698//698 652//652 1612//1612 -f 1612//1612 652//652 651//651 -f 1612//1612 651//651 785//785 -f 785//785 651//651 635//635 -f 785//785 635//635 644//644 -f 644//644 635//635 642//642 -f 644//644 642//642 645//645 -f 645//645 642//642 643//643 -f 645//645 643//643 1596//1596 -f 1596//1596 643//643 394//394 -f 1596//1596 394//394 790//790 -f 790//790 394//394 395//395 -f 790//790 395//395 389//389 -f 389//389 395//395 1746//1746 -f 389//389 1746//1746 390//390 -f 1747//1747 1748//1748 1749//1749 -f 1749//1749 1748//1748 387//387 -f 1749//1749 387//387 1750//1750 -f 1750//1750 387//387 1751//1751 -f 1752//1752 1753//1753 1754//1754 -f 1754//1754 1753//1753 454//454 -f 1754//1754 454//454 1747//1747 -f 1747//1747 454//454 1748//1748 -f 1755//1755 1756//1756 1757//1757 -f 1757//1757 1756//1756 445//445 -f 1757//1757 445//445 1752//1752 -f 1752//1752 445//445 1753//1753 -f 454//454 1753//1753 455//455 -f 455//455 1753//1753 1379//1379 -f 1595//1595 1753//1753 444//444 -f 444//444 1753//1753 445//445 -f 1592//1592 449//449 1753//1753 -f 1753//1753 449//449 448//448 -f 1753//1753 448//448 1379//1379 -f 1595//1595 1594//1594 1753//1753 -f 1753//1753 1594//1594 1593//1593 -f 1753//1753 1593//1593 1592//1592 -f 373//373 1748//1748 452//452 -f 452//452 1748//1748 454//454 -f 1748//1748 386//386 385//385 -f 373//373 376//376 1748//1748 -f 1748//1748 376//376 378//378 -f 1748//1748 378//378 380//380 -f 380//380 383//383 1748//1748 -f 1748//1748 383//383 382//382 -f 1748//1748 382//382 386//386 -f 1748//1748 385//385 388//388 -f 1748//1748 388//388 387//387 -f 540//540 1756//1756 430//430 -f 430//430 1756//1756 431//431 -f 540//540 436//436 1756//1756 -f 1756//1756 436//436 437//437 -f 1756//1756 437//437 439//439 -f 439//439 533//533 1756//1756 -f 1756//1756 533//533 440//440 -f 1756//1756 440//440 442//442 -f 442//442 447//447 1756//1756 -f 1756//1756 447//447 446//446 -f 1756//1756 446//446 445//445 -f 431//431 1758//1758 432//432 -f 432//432 1758//1758 433//433 -f 367//367 1759//1759 368//368 -f 368//368 1759//1759 400//400 -f 367//367 424//424 1759//1759 -f 1759//1759 424//424 422//422 -f 1759//1759 422//422 420//420 -f 406//406 404//404 1758//1758 -f 1758//1758 404//404 402//402 -f 1758//1758 402//402 429//429 -f 429//429 428//428 1758//1758 -f 1758//1758 428//428 426//426 -f 1758//1758 426//426 433//433 -f 420//420 418//418 1759//1759 -f 1759//1759 418//418 416//416 -f 1759//1759 416//416 414//414 -f 414//414 412//412 1759//1759 -f 1759//1759 412//412 410//410 -f 1759//1759 410//410 1758//1758 -f 1758//1758 410//410 408//408 -f 1758//1758 408//408 406//406 -f 1760//1760 1757//1757 1752//1752 -f 1761//1761 1752//1752 1762//1762 -f 1762//1762 1752//1752 1754//1754 -f 1761//1761 1763//1763 1752//1752 -f 1752//1752 1763//1763 1764//1764 -f 1752//1752 1764//1764 1765//1765 -f 1766//1766 1767//1767 1752//1752 -f 1752//1752 1767//1767 1768//1768 -f 1752//1752 1768//1768 1760//1760 -f 1765//1765 1769//1769 1752//1752 -f 1752//1752 1769//1769 1770//1770 -f 1752//1752 1770//1770 1766//1766 -f 1771//1771 1754//1754 1747//1747 -f 1747//1747 1772//1772 1773//1773 -f 1749//1749 1774//1774 1747//1747 -f 1747//1747 1774//1774 1775//1775 -f 1747//1747 1775//1775 1772//1772 -f 1773//1773 1776//1776 1747//1747 -f 1747//1747 1776//1776 1777//1777 -f 1747//1747 1777//1777 1778//1778 -f 1778//1778 1779//1779 1747//1747 -f 1747//1747 1779//1779 1780//1780 -f 1747//1747 1780//1780 1771//1771 -f 1757//1757 1781//1781 1755//1755 -f 1755//1755 1781//1781 1782//1782 -f 1755//1755 1782//1782 1783//1783 -f 1783//1783 1784//1784 1755//1755 -f 1755//1755 1784//1784 1785//1785 -f 1755//1755 1785//1785 1786//1786 -f 1786//1786 1787//1787 1755//1755 -f 1755//1755 1787//1787 1788//1788 -f 1755//1755 1788//1788 1789//1789 -f 1789//1789 1790//1790 1755//1755 -f 1755//1755 1790//1790 1791//1791 -f 1755//1755 1791//1791 1792//1792 -f 1793//1793 1794//1794 1795//1795 -f 1795//1795 1792//1792 1796//1796 -f 1796//1796 1797//1797 1795//1795 -f 1795//1795 1797//1797 1798//1798 -f 1795//1795 1798//1798 1799//1799 -f 1799//1799 1800//1800 1795//1795 -f 1795//1795 1800//1800 1801//1801 -f 1795//1795 1801//1801 1802//1802 -f 1802//1802 1803//1803 1795//1795 -f 1795//1795 1803//1803 1804//1804 -f 1795//1795 1804//1804 1793//1793 -f 1805//1805 1806//1806 1807//1807 -f 1807//1807 1806//1806 1808//1808 -f 1794//1794 1809//1809 1806//1806 -f 1806//1806 1809//1809 1810//1810 -f 1811//1811 1812//1812 1806//1806 -f 1806//1806 1812//1812 1813//1813 -f 1806//1806 1813//1813 1808//1808 -f 1810//1810 1814//1814 1806//1806 -f 1806//1806 1814//1814 1815//1815 -f 1806//1806 1815//1815 1811//1811 -f 1750//1750 1751//1751 1805//1805 -f 1805//1805 1751//1751 400//400 -f 1805//1805 400//400 1806//1806 -f 1806//1806 400//400 1759//1759 -f 1795//1795 1758//1758 1792//1792 -f 1792//1792 1758//1758 431//431 -f 1792//1792 431//431 1755//1755 -f 1755//1755 431//431 1756//1756 -f 1816//1816 1795//1795 1794//1794 -f 1816//1816 1794//1794 1806//1806 -f 1817//1817 1818//1818 1758//1758 -f 1758//1758 1818//1818 1819//1819 -f 1758//1758 1819//1819 1820//1820 -f 1758//1758 1821//1821 1759//1759 -f 1795//1795 1816//1816 1758//1758 -f 1758//1758 1816//1816 1822//1822 -f 1820//1820 1823//1823 1758//1758 -f 1758//1758 1823//1823 1824//1824 -f 1758//1758 1824//1824 1821//1821 -f 1825//1825 1822//1822 1806//1806 -f 1806//1806 1822//1822 1816//1816 -f 1759//1759 1821//1821 1806//1806 -f 1806//1806 1821//1821 1826//1826 -f 1806//1806 1826//1826 1827//1827 -f 1827//1827 1828//1828 1806//1806 -f 1806//1806 1828//1828 1829//1829 -f 1806//1806 1829//1829 1830//1830 -f 1830//1830 1831//1831 1806//1806 -f 1806//1806 1831//1831 1832//1832 -f 1806//1806 1832//1832 1825//1825 -f 1758//1758 1822//1822 1833//1833 -f 1833//1833 1834//1834 1758//1758 -f 1758//1758 1834//1834 1835//1835 -f 1758//1758 1835//1835 1817//1817 -f 395//395 393//393 1751//1751 -f 1751//1751 393//393 398//398 -f 1751//1751 795//795 391//391 -f 398//398 397//397 1751//1751 -f 1751//1751 397//397 396//396 -f 1751//1751 396//396 400//400 -f 387//387 371//371 1751//1751 -f 1751//1751 371//371 370//370 -f 1751//1751 370//370 795//795 -f 391//391 390//390 1751//1751 -f 1751//1751 390//390 1746//1746 -f 1751//1751 1746//1746 395//395 -f 1836//1836 1837//1837 1750//1750 -f 1750//1750 1837//1837 1838//1838 -f 1805//1805 1839//1839 1750//1750 -f 1750//1750 1839//1839 1840//1840 -f 1750//1750 1840//1840 1836//1836 -f 1838//1838 1841//1841 1750//1750 -f 1750//1750 1841//1841 1842//1842 -f 1750//1750 1842//1842 1843//1843 -f 1843//1843 1844//1844 1750//1750 -f 1750//1750 1844//1844 1845//1845 -f 1750//1750 1845//1845 1749//1749 -f 1820//1820 1846//1846 1823//1823 -f 1823//1823 1846//1846 1821//1821 -f 1823//1823 1821//1821 1824//1824 -f 1846//1846 1847//1847 1821//1821 -f 1831//1831 1830//1830 1848//1848 -f 1848//1848 1830//1830 1829//1829 -f 1848//1848 1829//1829 1828//1828 -f 1826//1826 1821//1821 1827//1827 -f 1827//1827 1821//1821 1847//1847 -f 1827//1827 1847//1847 1828//1828 -f 1828//1828 1847//1847 1846//1846 -f 1828//1828 1846//1846 1848//1848 -f 1848//1848 1846//1846 1832//1832 -f 1848//1848 1832//1832 1831//1831 -f 1825//1825 1834//1834 1833//1833 -f 1825//1825 1833//1833 1822//1822 -f 1820//1820 1819//1819 1846//1846 -f 1846//1846 1819//1819 1818//1818 -f 1846//1846 1818//1818 1817//1817 -f 1825//1825 1832//1832 1834//1834 -f 1834//1834 1832//1832 1846//1846 -f 1834//1834 1846//1846 1835//1835 -f 1835//1835 1846//1846 1817//1817 -f 1849//1849 1850//1850 1851//1851 -f 1852//1852 1853//1853 1850//1850 -f 1849//1849 1851//1851 1854//1854 -f 1852//1852 1850//1850 1855//1855 -f 1853//1853 1856//1856 1850//1850 -f 1850//1850 1856//1856 1857//1857 -f 1850//1850 1857//1857 1851//1851 -f 1858//1858 1859//1859 1860//1860 -f 1860//1860 1859//1859 1861//1861 -f 1860//1860 1861//1861 1862//1862 -f 1862//1862 1863//1863 1860//1860 -f 1860//1860 1863//1863 1864//1864 -f 1860//1860 1864//1864 1850//1850 -f 1850//1850 1864//1864 1865//1865 -f 1850//1850 1865//1865 1855//1855 -f 1860//1860 1866//1866 1867//1867 -f 1868//1868 1869//1869 1870//1870 -f 1870//1870 1869//1869 1871//1871 -f 1867//1867 1872//1872 1860//1860 -f 1860//1860 1872//1872 1873//1873 -f 1860//1860 1873//1873 1858//1858 -f 1874//1874 1875//1875 1854//1854 -f 1854//1854 1875//1875 1876//1876 -f 1854//1854 1876//1876 1877//1877 -f 1871//1871 1878//1878 1870//1870 -f 1870//1870 1878//1878 1879//1879 -f 1870//1870 1879//1879 1860//1860 -f 1860//1860 1879//1879 1880//1880 -f 1860//1860 1880//1880 1866//1866 -f 1851//1851 1881//1881 1854//1854 -f 1854//1854 1881//1881 1882//1882 -f 1854//1854 1882//1882 1883//1883 -f 1868//1868 1870//1870 1884//1884 -f 1884//1884 1870//1870 1885//1885 -f 1884//1884 1885//1885 1886//1886 -f 1883//1883 1887//1887 1854//1854 -f 1854//1854 1887//1887 1888//1888 -f 1854//1854 1888//1888 1874//1874 -f 1889//1889 1890//1890 1891//1891 -f 1892//1892 1893//1893 1886//1886 -f 1886//1886 1893//1893 1894//1894 -f 1886//1886 1894//1894 1884//1884 -f 1876//1876 1895//1895 1877//1877 -f 1877//1877 1895//1895 1896//1896 -f 1877//1877 1896//1896 1897//1897 -f 1897//1897 1896//1896 1898//1898 -f 1886//1886 1899//1899 1892//1892 -f 1892//1892 1899//1899 1889//1889 -f 1892//1892 1889//1889 1900//1900 -f 1900//1900 1889//1889 1891//1891 -f 1809//1809 1857//1857 1856//1856 -f 1802//1802 1887//1887 1883//1883 -f 1797//1797 1796//1796 1895//1895 -f 1895//1895 1796//1796 1792//1792 -f 1895//1895 1792//1792 1791//1791 -f 1895//1895 1876//1876 1797//1797 -f 1797//1797 1876//1876 1875//1875 -f 1797//1797 1875//1875 1798//1798 -f 1798//1798 1875//1875 1874//1874 -f 1798//1798 1874//1874 1799//1799 -f 1799//1799 1874//1874 1888//1888 -f 1799//1799 1888//1888 1800//1800 -f 1800//1800 1888//1888 1887//1887 -f 1800//1800 1887//1887 1801//1801 -f 1801//1801 1887//1887 1802//1802 -f 1793//1793 1804//1804 1883//1883 -f 1883//1883 1804//1804 1803//1803 -f 1883//1883 1803//1803 1802//1802 -f 1883//1883 1882//1882 1793//1793 -f 1793//1793 1882//1882 1881//1881 -f 1793//1793 1881//1881 1794//1794 -f 1794//1794 1881//1881 1809//1809 -f 1809//1809 1881//1881 1851//1851 -f 1809//1809 1851//1851 1857//1857 -f 1815//1815 1814//1814 1856//1856 -f 1856//1856 1814//1814 1810//1810 -f 1856//1856 1810//1810 1809//1809 -f 1856//1856 1853//1853 1815//1815 -f 1815//1815 1853//1853 1852//1852 -f 1815//1815 1852//1852 1811//1811 -f 1811//1811 1852//1852 1855//1855 -f 1811//1811 1855//1855 1812//1812 -f 1812//1812 1855//1855 1813//1813 -f 1813//1813 1855//1855 1808//1808 -f 1808//1808 1855//1855 1865//1865 -f 1808//1808 1865//1865 1807//1807 -f 1865//1865 1864//1864 1807//1807 -f 1807//1807 1864//1864 1863//1863 -f 1807//1807 1863//1863 1805//1805 -f 1805//1805 1863//1863 1862//1862 -f 1805//1805 1862//1862 1839//1839 -f 1839//1839 1862//1862 1861//1861 -f 1839//1839 1861//1861 1840//1840 -f 1840//1840 1861//1861 1859//1859 -f 1840//1840 1859//1859 1836//1836 -f 1836//1836 1859//1859 1858//1858 -f 1836//1836 1858//1858 1837//1837 -f 1858//1858 1873//1873 1837//1837 -f 1837//1837 1873//1873 1872//1872 -f 1837//1837 1872//1872 1838//1838 -f 1838//1838 1872//1872 1867//1867 -f 1838//1838 1867//1867 1841//1841 -f 1841//1841 1867//1867 1842//1842 -f 1842//1842 1867//1867 1866//1866 -f 1842//1842 1866//1866 1843//1843 -f 1843//1843 1866//1866 1844//1844 -f 1844//1844 1866//1866 1880//1880 -f 1844//1844 1880//1880 1845//1845 -f 1845//1845 1880//1880 1879//1879 -f 1845//1845 1879//1879 1749//1749 -f 1749//1749 1879//1879 1878//1878 -f 1749//1749 1878//1878 1774//1774 -f 1774//1774 1878//1878 1775//1775 -f 1775//1775 1878//1878 1871//1871 -f 1775//1775 1871//1871 1772//1772 -f 1772//1772 1871//1871 1869//1869 -f 1772//1772 1869//1869 1773//1773 -f 1773//1773 1869//1869 1868//1868 -f 1773//1773 1868//1868 1776//1776 -f 1776//1776 1868//1868 1884//1884 -f 1776//1776 1884//1884 1777//1777 -f 1777//1777 1884//1884 1894//1894 -f 1777//1777 1894//1894 1778//1778 -f 1778//1778 1894//1894 1893//1893 -f 1778//1778 1893//1893 1779//1779 -f 1779//1779 1893//1893 1892//1892 -f 1779//1779 1892//1892 1780//1780 -f 1780//1780 1892//1892 1771//1771 -f 1771//1771 1892//1892 1900//1900 -f 1771//1771 1900//1900 1754//1754 -f 1754//1754 1900//1900 1891//1891 -f 1754//1754 1891//1891 1762//1762 -f 1762//1762 1891//1891 1890//1890 -f 1762//1762 1890//1890 1761//1761 -f 1761//1761 1890//1890 1889//1889 -f 1761//1761 1889//1889 1763//1763 -f 1763//1763 1889//1889 1764//1764 -f 1764//1764 1889//1889 1899//1899 -f 1764//1764 1899//1899 1765//1765 -f 1765//1765 1899//1899 1886//1886 -f 1765//1765 1886//1886 1769//1769 -f 1769//1769 1886//1886 1770//1770 -f 1770//1770 1886//1886 1885//1885 -f 1770//1770 1885//1885 1766//1766 -f 1766//1766 1885//1885 1870//1870 -f 1766//1766 1870//1870 1767//1767 -f 1767//1767 1870//1870 1768//1768 -f 1768//1768 1870//1870 1860//1860 -f 1768//1768 1860//1860 1760//1760 -f 1760//1760 1860//1860 1850//1850 -f 1760//1760 1850//1850 1757//1757 -f 1757//1757 1850//1850 1849//1849 -f 1757//1757 1849//1849 1781//1781 -f 1849//1849 1854//1854 1781//1781 -f 1781//1781 1854//1854 1877//1877 -f 1781//1781 1877//1877 1782//1782 -f 1782//1782 1877//1877 1783//1783 -f 1783//1783 1877//1877 1897//1897 -f 1783//1783 1897//1897 1784//1784 -f 1784//1784 1897//1897 1898//1898 -f 1784//1784 1898//1898 1785//1785 -f 1896//1896 1787//1787 1898//1898 -f 1898//1898 1787//1787 1786//1786 -f 1898//1898 1786//1786 1785//1785 -f 1791//1791 1790//1790 1895//1895 -f 1895//1895 1790//1790 1789//1789 -f 1895//1895 1789//1789 1896//1896 -f 1896//1896 1789//1789 1788//1788 -f 1896//1896 1788//1788 1787//1787 -f 1901//1901 1902//1902 1903//1903 -f 1903//1903 1902//1902 1904//1904 -f 1903//1903 1904//1904 1905//1905 -f 1905//1905 1904//1904 1906//1906 -f 1905//1905 1906//1906 1907//1907 -f 1907//1907 1906//1906 1908//1908 -f 1907//1907 1908//1908 1909//1909 -f 1909//1909 1908//1908 1910//1910 -f 1909//1909 1910//1910 1911//1911 -f 1911//1911 1910//1910 1912//1912 -f 1911//1911 1912//1912 1913//1913 -f 1913//1913 1912//1912 1914//1914 -f 1913//1913 1914//1914 1915//1915 -f 1915//1915 1914//1914 1916//1916 -f 1915//1915 1916//1916 1917//1917 -f 1917//1917 1916//1916 1918//1918 -f 1917//1917 1918//1918 1919//1919 -f 1919//1919 1918//1918 1920//1920 -f 1919//1919 1920//1920 1921//1921 -f 1921//1921 1920//1920 1922//1922 -f 1921//1921 1922//1922 1923//1923 -f 1923//1923 1922//1922 1924//1924 -f 1923//1923 1924//1924 1925//1925 -f 1925//1925 1924//1924 1926//1926 -f 1925//1925 1926//1926 1927//1927 -f 1927//1927 1926//1926 1928//1928 -f 1927//1927 1928//1928 1929//1929 -f 1929//1929 1928//1928 1930//1930 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1935//1935 -f 1935//1935 1934//1934 1936//1936 -f 1935//1935 1936//1936 1937//1937 -f 1937//1937 1936//1936 1938//1938 -f 1937//1937 1938//1938 1939//1939 -f 1939//1939 1938//1938 1940//1940 -f 1939//1939 1940//1940 1941//1941 -f 1941//1941 1940//1940 1942//1942 -f 1941//1941 1942//1942 1943//1943 -f 1943//1943 1942//1942 1944//1944 -f 1943//1943 1944//1944 1945//1945 -f 1945//1945 1944//1944 1946//1946 -f 1945//1945 1946//1946 1947//1947 -f 1947//1947 1946//1946 1948//1948 -f 1947//1947 1948//1948 1949//1949 -f 1949//1949 1948//1948 1950//1950 -f 1949//1949 1950//1950 1951//1951 -f 1951//1951 1950//1950 1952//1952 -f 1951//1951 1952//1952 1953//1953 -f 1953//1953 1952//1952 1954//1954 -f 1953//1953 1954//1954 1955//1955 -f 1955//1955 1954//1954 1956//1956 -f 1955//1955 1956//1956 1957//1957 -f 1957//1957 1956//1956 1958//1958 -f 1957//1957 1958//1958 1959//1959 -f 1959//1959 1958//1958 1960//1960 -f 1959//1959 1960//1960 1961//1961 -f 1961//1961 1960//1960 1962//1962 -f 1961//1961 1962//1962 1963//1963 -f 1963//1963 1962//1962 1964//1964 -f 1963//1963 1964//1964 1965//1965 -f 1965//1965 1964//1964 1966//1966 -f 1965//1965 1966//1966 1967//1967 -f 1967//1967 1966//1966 1968//1968 -f 1967//1967 1968//1968 1901//1901 -f 1901//1901 1968//1968 1902//1902 -f 1920//1920 1969//1969 1922//1922 -f 1922//1922 1969//1969 1970//1970 -f 1922//1922 1970//1970 1924//1924 -f 1924//1924 1970//1970 1971//1971 -f 1924//1924 1971//1971 1926//1926 -f 1926//1926 1971//1971 1972//1972 -f 1926//1926 1972//1972 1928//1928 -f 1928//1928 1972//1972 1973//1973 -f 1928//1928 1973//1973 1930//1930 -f 1930//1930 1973//1973 1974//1974 -f 1930//1930 1974//1974 1932//1932 -f 1932//1932 1974//1974 1975//1975 -f 1932//1932 1975//1975 1934//1934 -f 1954//1954 1976//1976 1956//1956 -f 1956//1956 1976//1976 1977//1977 -f 1956//1956 1977//1977 1958//1958 -f 1958//1958 1977//1977 1978//1978 -f 1958//1958 1978//1978 1960//1960 -f 1960//1960 1978//1978 1979//1979 -f 1960//1960 1979//1979 1962//1962 -f 1962//1962 1979//1979 1980//1980 -f 1962//1962 1980//1980 1964//1964 -f 1964//1964 1980//1980 1981//1981 -f 1964//1964 1981//1981 1966//1966 -f 1966//1966 1981//1981 1982//1982 -f 1966//1966 1982//1982 1968//1968 -f 1968//1968 1982//1982 1983//1983 -f 1968//1968 1983//1983 1902//1902 -f 1902//1902 1983//1983 1984//1984 -f 1902//1902 1984//1984 1904//1904 -f 1975//1975 1985//1985 1934//1934 -f 1934//1934 1985//1985 1986//1986 -f 1934//1934 1986//1986 1936//1936 -f 1936//1936 1986//1986 1987//1987 -f 1936//1936 1987//1987 1938//1938 -f 1938//1938 1987//1987 1988//1988 -f 1938//1938 1988//1988 1940//1940 -f 1940//1940 1988//1988 1989//1989 -f 1940//1940 1989//1989 1942//1942 -f 1942//1942 1989//1989 1990//1990 -f 1942//1942 1990//1990 1944//1944 -f 1984//1984 1991//1991 1904//1904 -f 1904//1904 1991//1991 1992//1992 -f 1904//1904 1992//1992 1906//1906 -f 1906//1906 1992//1992 1993//1993 -f 1906//1906 1993//1993 1908//1908 -f 1908//1908 1993//1993 1994//1994 -f 1908//1908 1994//1994 1910//1910 -f 1910//1910 1994//1994 1995//1995 -f 1910//1910 1995//1995 1912//1912 -f 1912//1912 1995//1995 1996//1996 -f 1912//1912 1996//1996 1914//1914 -f 1914//1914 1996//1996 1997//1997 -f 1914//1914 1997//1997 1916//1916 -f 1990//1990 1998//1998 1944//1944 -f 1944//1944 1998//1998 1999//1999 -f 1944//1944 1999//1999 1946//1946 -f 1946//1946 1999//1999 2000//2000 -f 1946//1946 2000//2000 1948//1948 -f 1948//1948 2000//2000 2001//2001 -f 1948//1948 2001//2001 1950//1950 -f 1950//1950 2001//2001 2002//2002 -f 1950//1950 2002//2002 1952//1952 -f 1952//1952 2002//2002 2003//2003 -f 1952//1952 2003//2003 1954//1954 -f 1954//1954 2003//2003 2004//2004 -f 1954//1954 2004//2004 1976//1976 -f 1997//1997 2005//2005 1916//1916 -f 1916//1916 2005//2005 2006//2006 -f 1916//1916 2006//2006 1918//1918 -f 1918//1918 2006//2006 2007//2007 -f 1918//1918 2007//2007 1920//1920 -f 1920//1920 2007//2007 2008//2008 -f 1920//1920 2008//2008 1969//1969 -f 1935//1935 2009//2009 1933//1933 -f 1933//1933 2009//2009 2010//2010 -f 1933//1933 2010//2010 1931//1931 -f 1931//1931 2010//2010 2011//2011 -f 1931//1931 2011//2011 1929//1929 -f 1929//1929 2011//2011 2012//2012 -f 1929//1929 2012//2012 1927//1927 -f 1927//1927 2012//2012 2013//2013 -f 1927//1927 2013//2013 1925//1925 -f 1925//1925 2013//2013 2014//2014 -f 1925//1925 2014//2014 1923//1923 -f 1923//1923 2014//2014 2015//2015 -f 1923//1923 2015//2015 1921//1921 -f 2015//2015 2016//2016 1921//1921 -f 1921//1921 2016//2016 2017//2017 -f 1921//1921 2017//2017 1919//1919 -f 1919//1919 2017//2017 2018//2018 -f 1919//1919 2018//2018 1917//1917 -f 1905//1905 2019//2019 1903//1903 -f 1903//1903 2019//2019 2020//2020 -f 1903//1903 2020//2020 1901//1901 -f 1901//1901 2020//2020 2021//2021 -f 1901//1901 2021//2021 1967//1967 -f 1967//1967 2021//2021 2022//2022 -f 1967//1967 2022//2022 1965//1965 -f 1965//1965 2022//2022 2023//2023 -f 1965//1965 2023//2023 1963//1963 -f 1963//1963 2023//2023 2024//2024 -f 1963//1963 2024//2024 1961//1961 -f 1961//1961 2024//2024 2025//2025 -f 1961//1961 2025//2025 1959//1959 -f 1959//1959 2025//2025 2026//2026 -f 1959//1959 2026//2026 1957//1957 -f 1957//1957 2026//2026 2027//2027 -f 1957//1957 2027//2027 1955//1955 -f 2018//2018 2028//2028 1917//1917 -f 1917//1917 2028//2028 2029//2029 -f 1917//1917 2029//2029 1915//1915 -f 1915//1915 2029//2029 2030//2030 -f 1915//1915 2030//2030 1913//1913 -f 1913//1913 2030//2030 2031//2031 -f 1913//1913 2031//2031 1911//1911 -f 1911//1911 2031//2031 2032//2032 -f 1911//1911 2032//2032 1909//1909 -f 1909//1909 2032//2032 2033//2033 -f 1909//1909 2033//2033 1907//1907 -f 1907//1907 2033//2033 2034//2034 -f 1907//1907 2034//2034 1905//1905 -f 1905//1905 2034//2034 2035//2035 -f 1905//1905 2035//2035 2019//2019 -f 1945//1945 2036//2036 1943//1943 -f 1943//1943 2036//2036 2037//2037 -f 1943//1943 2037//2037 1941//1941 -f 1941//1941 2037//2037 2038//2038 -f 1941//1941 2038//2038 1939//1939 -f 1939//1939 2038//2038 2039//2039 -f 1939//1939 2039//2039 1937//1937 -f 1937//1937 2039//2039 2040//2040 -f 1937//1937 2040//2040 1935//1935 -f 1935//1935 2040//2040 2041//2041 -f 1935//1935 2041//2041 2009//2009 -f 2027//2027 2042//2042 1955//1955 -f 1955//1955 2042//2042 2043//2043 -f 1955//1955 2043//2043 1953//1953 -f 1953//1953 2043//2043 2044//2044 -f 1953//1953 2044//2044 1951//1951 -f 1951//1951 2044//2044 2045//2045 -f 1951//1951 2045//2045 1949//1949 -f 1949//1949 2045//2045 2046//2046 -f 1949//1949 2046//2046 1947//1947 -f 1947//1947 2046//2046 2047//2047 -f 1947//1947 2047//2047 1945//1945 -f 1945//1945 2047//2047 2048//2048 -f 1945//1945 2048//2048 2036//2036 -f 2006//2006 2018//2018 2007//2007 -f 2007//2007 2018//2018 2017//2017 -f 2007//2007 2017//2017 2008//2008 -f 2008//2008 2017//2017 2016//2016 -f 2008//2008 2016//2016 1969//1969 -f 1969//1969 2016//2016 2015//2015 -f 1969//1969 2015//2015 1970//1970 -f 1970//1970 2015//2015 2014//2014 -f 1970//1970 2014//2014 1971//1971 -f 1971//1971 2014//2014 2013//2013 -f 1971//1971 2013//2013 1972//1972 -f 1972//1972 2013//2013 2012//2012 -f 1972//1972 2012//2012 1973//1973 -f 1973//1973 2012//2012 2011//2011 -f 1973//1973 2011//2011 1974//1974 -f 1974//1974 2011//2011 2010//2010 -f 1974//1974 2010//2010 1975//1975 -f 1975//1975 2010//2010 2009//2009 -f 1975//1975 2009//2009 1985//1985 -f 1985//1985 2009//2009 2041//2041 -f 1985//1985 2041//2041 1986//1986 -f 1986//1986 2041//2041 2040//2040 -f 1986//1986 2040//2040 1987//1987 -f 1987//1987 2040//2040 2039//2039 -f 1987//1987 2039//2039 1988//1988 -f 1988//1988 2039//2039 2038//2038 -f 1988//1988 2038//2038 1989//1989 -f 1989//1989 2038//2038 2037//2037 -f 1989//1989 2037//2037 1990//1990 -f 1990//1990 2037//2037 2036//2036 -f 1990//1990 2036//2036 1998//1998 -f 1998//1998 2036//2036 2048//2048 -f 1998//1998 2048//2048 1999//1999 -f 1999//1999 2048//2048 2047//2047 -f 1999//1999 2047//2047 2000//2000 -f 2000//2000 2047//2047 2046//2046 -f 2000//2000 2046//2046 2001//2001 -f 2001//2001 2046//2046 2045//2045 -f 2001//2001 2045//2045 2002//2002 -f 2002//2002 2045//2045 2044//2044 -f 2002//2002 2044//2044 2003//2003 -f 2003//2003 2044//2044 2043//2043 -f 2003//2003 2043//2043 2004//2004 -f 2004//2004 2043//2043 2042//2042 -f 2004//2004 2042//2042 1976//1976 -f 1976//1976 2042//2042 2027//2027 -f 1976//1976 2027//2027 1977//1977 -f 1977//1977 2027//2027 2026//2026 -f 1977//1977 2026//2026 1978//1978 -f 1978//1978 2026//2026 2025//2025 -f 1978//1978 2025//2025 1979//1979 -f 1979//1979 2025//2025 2024//2024 -f 1979//1979 2024//2024 1980//1980 -f 1980//1980 2024//2024 2023//2023 -f 1980//1980 2023//2023 1981//1981 -f 1981//1981 2023//2023 2022//2022 -f 1981//1981 2022//2022 1982//1982 -f 1982//1982 2022//2022 2021//2021 -f 1982//1982 2021//2021 1983//1983 -f 1983//1983 2021//2021 2020//2020 -f 1983//1983 2020//2020 1984//1984 -f 1984//1984 2020//2020 2019//2019 -f 1984//1984 2019//2019 1991//1991 -f 1991//1991 2019//2019 2035//2035 -f 1991//1991 2035//2035 1992//1992 -f 1992//1992 2035//2035 2034//2034 -f 1992//1992 2034//2034 1993//1993 -f 1993//1993 2034//2034 2033//2033 -f 1993//1993 2033//2033 1994//1994 -f 1994//1994 2033//2033 2032//2032 -f 1994//1994 2032//2032 1995//1995 -f 1995//1995 2032//2032 2031//2031 -f 1995//1995 2031//2031 1996//1996 -f 1996//1996 2031//2031 2030//2030 -f 1996//1996 2030//2030 1997//1997 -f 1997//1997 2030//2030 2029//2029 -f 1997//1997 2029//2029 2005//2005 -f 2005//2005 2029//2029 2028//2028 -f 2005//2005 2028//2028 2006//2006 -f 2006//2006 2028//2028 2018//2018 -f 2049//2049 2050//2050 2032//2032 -f 2032//2032 2050//2050 2051//2051 -f 2032//2032 2051//2051 2052//2052 -f 2053//2053 2054//2054 2055//2055 -f 2052//2052 2056//2056 2032//2032 -f 2032//2032 2056//2056 2055//2055 -f 2032//2032 2055//2055 2057//2057 -f 2057//2057 2055//2055 2058//2058 -f 2032//2032 2059//2059 2060//2060 -f 2061//2061 2032//2032 2062//2062 -f 2062//2062 2032//2032 2063//2063 -f 2061//2061 2064//2064 2032//2032 -f 2032//2032 2064//2064 2065//2065 -f 2032//2032 2065//2065 2066//2066 -f 2066//2066 2067//2067 2032//2032 -f 2032//2032 2067//2067 2068//2068 -f 2032//2032 2068//2068 2069//2069 -f 2060//2060 2070//2070 2032//2032 -f 2032//2032 2070//2070 2071//2071 -f 2032//2032 2071//2071 2072//2072 -f 2072//2072 2073//2073 2032//2032 -f 2032//2032 2073//2073 2074//2074 -f 2032//2032 2074//2074 2075//2075 -f 2054//2054 2076//2076 2055//2055 -f 2055//2055 2076//2076 2077//2077 -f 2055//2055 2077//2077 2058//2058 -f 2069//2069 2078//2078 2032//2032 -f 2032//2032 2078//2078 2079//2079 -f 2032//2032 2079//2079 2080//2080 -f 2080//2080 2081//2081 2032//2032 -f 2032//2032 2081//2081 2082//2082 -f 2032//2032 2082//2082 2083//2083 -f 2083//2083 2084//2084 2032//2032 -f 2032//2032 2084//2084 2085//2085 -f 2032//2032 2085//2085 2059//2059 -f 2075//2075 2086//2086 2032//2032 -f 2032//2032 2086//2086 2087//2087 -f 2032//2032 2087//2087 2049//2049 -f 2055//2055 2088//2088 2053//2053 -f 2053//2053 2088//2088 2089//2089 -f 2053//2053 2089//2089 2090//2090 -f 2090//2090 2089//2089 2091//2091 -f 2063//2063 2092//2092 2062//2062 -f 2062//2062 2092//2092 2093//2093 -f 2062//2062 2093//2093 2094//2094 -f 2094//2094 2093//2093 2095//2095 -f 2094//2094 2095//2095 2096//2096 -f 2096//2096 2095//2095 2097//2097 -f 2096//2096 2097//2097 2018//2018 -f 2098//2098 2099//2099 2100//2100 -f 2101//2101 2102//2102 2103//2103 -f 2104//2104 2105//2105 2106//2106 -f 2107//2107 2108//2108 2109//2109 -f 2109//2109 2108//2108 2110//2110 -f 2111//2111 2112//2112 2113//2113 -f 2114//2114 2115//2115 2116//2116 -f 2117//2117 2118//2118 2119//2119 -f 2120//2120 2121//2121 2122//2122 -f 2123//2123 2124//2124 2125//2125 -f 2126//2126 2127//2127 2128//2128 -f 2129//2129 2130//2130 2131//2131 -f 2132//2132 2133//2133 2134//2134 -f 2135//2135 2136//2136 2137//2137 -f 2138//2138 2139//2139 2140//2140 -f 2141//2141 2142//2142 2143//2143 -f 2144//2144 2145//2145 2146//2146 -f 2147//2147 2148//2148 2149//2149 -f 2150//2150 2151//2151 2152//2152 -f 2153//2153 2154//2154 2155//2155 -f 2156//2156 2157//2157 2158//2158 -f 2159//2159 2160//2160 2161//2161 -f 2162//2162 2163//2163 2164//2164 -f 2165//2165 2166//2166 2167//2167 -f 2168//2168 2167//2167 2169//2169 -f 2170//2170 2171//2171 2172//2172 -f 2173//2173 2174//2174 2175//2175 -f 2176//2176 2177//2177 2178//2178 -f 2179//2179 2177//2177 2180//2180 -f 2181//2181 2182//2182 2183//2183 -f 2184//2184 2185//2185 2186//2186 -f 2187//2187 2188//2188 2189//2189 -f 2190//2190 2191//2191 2192//2192 -f 2193//2193 2194//2194 2195//2195 -f 2196//2196 2197//2197 2198//2198 -f 2199//2199 2200//2200 2201//2201 -f 2202//2202 2203//2203 2204//2204 -f 2205//2205 2206//2206 2207//2207 -f 2208//2208 2209//2209 2210//2210 -f 2211//2211 2212//2212 2213//2213 -f 2214//2214 2215//2215 2216//2216 -f 2217//2217 2218//2218 2219//2219 -f 2220//2220 2221//2221 2222//2222 -f 2218//2218 2217//2217 2223//2223 -f 2224//2224 2225//2225 2226//2226 -f 2227//2227 2226//2226 2228//2228 -f 2229//2229 2230//2230 2231//2231 -f 2230//2230 2229//2229 2232//2232 -f 2233//2233 2234//2234 2235//2235 -f 2236//2236 2237//2237 2238//2238 -f 2238//2238 2237//2237 2239//2239 -f 2240//2240 2241//2241 2242//2242 -f 2243//2243 2244//2244 2245//2245 -f 2246//2246 2247//2247 2248//2248 -f 2249//2249 2250//2250 2251//2251 -f 2252//2252 2253//2253 2254//2254 -f 2093//2093 2092//2092 2255//2255 -f 2256//2256 2257//2257 2258//2258 -f 2051//2051 2050//2050 2259//2259 -f 2260//2260 2261//2261 2262//2262 -f 2263//2263 2264//2264 2265//2265 -f 2070//2070 2060//2060 2266//2266 -f 2267//2267 2268//2268 2269//2269 -f 2270//2270 2271//2271 2272//2272 -f 2273//2273 2274//2274 2275//2275 -f 2273//2273 2275//2275 2276//2276 -f 2276//2276 2275//2275 2277//2277 -f 2276//2276 2277//2277 2278//2278 -f 2278//2278 2277//2277 2279//2279 -f 2278//2278 2279//2279 2280//2280 -f 2281//2281 2282//2282 2283//2283 -f 2284//2284 2285//2285 2286//2286 -f 2284//2284 2286//2286 2282//2282 -f 2271//2271 2287//2287 2272//2272 -f 2272//2272 2287//2287 2288//2288 -f 2289//2289 2290//2290 2291//2291 -f 2292//2292 2293//2293 2294//2294 -f 2294//2294 2293//2293 2295//2295 -f 2296//2296 2297//2297 2292//2292 -f 2292//2292 2297//2297 2298//2298 -f 2292//2292 2298//2298 2293//2293 -f 2292//2292 2299//2299 2296//2296 -f 2296//2296 2299//2299 2269//2269 -f 2296//2296 2269//2269 2300//2300 -f 2300//2300 2269//2269 2268//2268 -f 2301//2301 2302//2302 2303//2303 -f 2303//2303 2302//2302 2304//2304 -f 2303//2303 2304//2304 2305//2305 -f 2305//2305 2304//2304 2306//2306 -f 2305//2305 2306//2306 2307//2307 -f 2307//2307 2306//2306 2308//2308 -f 2307//2307 2308//2308 2309//2309 -f 2309//2309 2308//2308 2310//2310 -f 2309//2309 2310//2310 2311//2311 -f 2311//2311 2310//2310 2312//2312 -f 2311//2311 2312//2312 2313//2313 -f 2313//2313 2312//2312 2314//2314 -f 2313//2313 2314//2314 2315//2315 -f 2315//2315 2314//2314 2316//2316 -f 2315//2315 2316//2316 2317//2317 -f 2317//2317 2316//2316 2318//2318 -f 2317//2317 2318//2318 2319//2319 -f 2319//2319 2318//2318 2320//2320 -f 2319//2319 2320//2320 2321//2321 -f 2321//2321 2320//2320 2322//2322 -f 2321//2321 2322//2322 2323//2323 -f 2323//2323 2322//2322 2324//2324 -f 2325//2325 2326//2326 2327//2327 -f 2327//2327 2326//2326 2328//2328 -f 2327//2327 2328//2328 2301//2301 -f 2301//2301 2328//2328 2329//2329 -f 2301//2301 2329//2329 2302//2302 -f 2325//2325 2330//2330 2331//2331 -f 2331//2331 2332//2332 2325//2325 -f 2325//2325 2332//2332 2333//2333 -f 2325//2325 2333//2333 2326//2326 -f 2334//2334 2335//2335 2336//2336 -f 2336//2336 2335//2335 2337//2337 -f 2337//2337 2335//2335 2338//2338 -f 2337//2337 2338//2338 2339//2339 -f 2340//2340 2341//2341 2342//2342 -f 2342//2342 2341//2341 2343//2343 -f 2344//2344 2345//2345 2343//2343 -f 2345//2345 2346//2346 2343//2343 -f 2343//2343 2346//2346 2347//2347 -f 2343//2343 2347//2347 2342//2342 -f 2348//2348 2349//2349 2350//2350 -f 2351//2351 2352//2352 2353//2353 -f 2353//2353 2352//2352 2354//2354 -f 2353//2353 2354//2354 2355//2355 -f 2066//2066 2356//2356 2067//2067 -f 2067//2067 2356//2356 2357//2357 -f 2067//2067 2357//2357 2068//2068 -f 2068//2068 2357//2357 2358//2358 -f 2068//2068 2358//2358 2069//2069 -f 2069//2069 2358//2358 2359//2359 -f 2069//2069 2359//2359 2078//2078 -f 2360//2360 2065//2065 2064//2064 -f 2360//2360 2064//2064 2361//2361 -f 2362//2362 2086//2086 2363//2363 -f 2363//2363 2086//2086 2075//2075 -f 2363//2363 2075//2075 2364//2364 -f 2364//2364 2075//2075 2074//2074 -f 2364//2364 2074//2074 2365//2365 -f 2073//2073 2072//2072 2366//2366 -f 2078//2078 2359//2359 2079//2079 -f 2079//2079 2359//2359 2367//2367 -f 2079//2079 2367//2367 2080//2080 -f 2080//2080 2367//2367 2099//2099 -f 2080//2080 2099//2099 2081//2081 -f 2081//2081 2099//2099 2098//2098 -f 2081//2081 2098//2098 2082//2082 -f 2368//2368 2369//2369 2261//2261 -f 2261//2261 2369//2369 2370//2370 -f 2261//2261 2370//2370 2262//2262 -f 2371//2371 2372//2372 2260//2260 -f 2260//2260 2372//2372 2373//2373 -f 2260//2260 2373//2373 2261//2261 -f 2261//2261 2373//2373 2374//2374 -f 2261//2261 2374//2374 2368//2368 -f 2368//2368 2374//2374 2375//2375 -f 2087//2087 2376//2376 2377//2377 -f 2377//2377 2376//2376 2378//2378 -f 2377//2377 2378//2378 2263//2263 -f 2263//2263 2265//2265 2377//2377 -f 2377//2377 2265//2265 2049//2049 -f 2377//2377 2049//2049 2087//2087 -f 2091//2091 2089//2089 2379//2379 -f 2371//2371 2379//2379 2372//2372 -f 2372//2372 2379//2379 2089//2089 -f 2372//2372 2089//2089 2373//2373 -f 2373//2373 2089//2089 2088//2088 -f 2373//2373 2088//2088 2374//2374 -f 2374//2374 2088//2088 2055//2055 -f 2374//2374 2055//2055 2375//2375 -f 2375//2375 2055//2055 2056//2056 -f 2375//2375 2056//2056 2052//2052 -f 2380//2380 2381//2381 2382//2382 -f 2382//2382 2381//2381 2383//2383 -f 2382//2382 2383//2383 2384//2384 -f 2384//2384 2383//2383 2385//2385 -f 2384//2384 2385//2385 2386//2386 -f 2386//2386 2385//2385 2387//2387 -f 2386//2386 2387//2387 2388//2388 -f 2388//2388 2387//2387 2389//2389 -f 2388//2388 2389//2389 2390//2390 -f 2390//2390 2389//2389 2391//2391 -f 2390//2390 2391//2391 2392//2392 -f 2392//2392 2391//2391 2393//2393 -f 2392//2392 2393//2393 2394//2394 -f 2394//2394 2393//2393 2395//2395 -f 2394//2394 2395//2395 2396//2396 -f 2381//2381 2397//2397 2383//2383 -f 2383//2383 2397//2397 2398//2398 -f 2383//2383 2398//2398 2385//2385 -f 2385//2385 2398//2398 2399//2399 -f 2385//2385 2399//2399 2387//2387 -f 2387//2387 2399//2399 2400//2400 -f 2387//2387 2400//2400 2389//2389 -f 2389//2389 2400//2400 2401//2401 -f 2389//2389 2401//2401 2391//2391 -f 2391//2391 2401//2401 2402//2402 -f 2391//2391 2402//2402 2393//2393 -f 2393//2393 2402//2402 2403//2403 -f 2393//2393 2403//2403 2395//2395 -f 2404//2404 2256//2256 2405//2405 -f 2405//2405 2256//2256 2258//2258 -f 2405//2405 2258//2258 2406//2406 -f 2397//2397 2407//2407 2398//2398 -f 2398//2398 2407//2407 2408//2408 -f 2398//2398 2408//2408 2399//2399 -f 2399//2399 2408//2408 2409//2409 -f 2399//2399 2409//2409 2400//2400 -f 2400//2400 2409//2409 2410//2410 -f 2400//2400 2410//2410 2401//2401 -f 2401//2401 2410//2410 2411//2411 -f 2401//2401 2411//2411 2402//2402 -f 2402//2402 2411//2411 2412//2412 -f 2402//2402 2412//2412 2403//2403 -f 2413//2413 2414//2414 2255//2255 -f 2415//2415 2404//2404 2416//2416 -f 2416//2416 2404//2404 2405//2405 -f 2416//2416 2405//2405 2417//2417 -f 2417//2417 2405//2405 2406//2406 -f 2417//2417 2406//2406 2418//2418 -f 2092//2092 2063//2063 2255//2255 -f 2255//2255 2063//2063 2418//2418 -f 2255//2255 2418//2418 2413//2413 -f 2413//2413 2418//2418 2406//2406 -f 2076//2076 2415//2415 2077//2077 -f 2077//2077 2415//2415 2416//2416 -f 2077//2077 2416//2416 2058//2058 -f 2058//2058 2416//2416 2417//2417 -f 2058//2058 2417//2417 2057//2057 -f 2057//2057 2417//2417 2418//2418 -f 2057//2057 2418//2418 2032//2032 -f 2032//2032 2418//2418 2063//2063 -f 2419//2419 2420//2420 2421//2421 -f 2421//2421 2420//2420 2422//2422 -f 2421//2421 2422//2422 2423//2423 -f 2423//2423 2422//2422 2424//2424 -f 2423//2423 2424//2424 2425//2425 -f 2262//2262 2396//2396 2260//2260 -f 2260//2260 2396//2396 2395//2395 -f 2260//2260 2395//2395 2371//2371 -f 2371//2371 2395//2395 2403//2403 -f 2371//2371 2403//2403 2379//2379 -f 2379//2379 2403//2403 2412//2412 -f 2379//2379 2412//2412 2091//2091 -f 2091//2091 2412//2412 2411//2411 -f 2091//2091 2411//2411 2090//2090 -f 2090//2090 2411//2411 2410//2410 -f 2090//2090 2410//2410 2053//2053 -f 2053//2053 2410//2410 2409//2409 -f 2053//2053 2409//2409 2054//2054 -f 2054//2054 2409//2409 2408//2408 -f 2054//2054 2408//2408 2076//2076 -f 2076//2076 2408//2408 2407//2407 -f 2076//2076 2407//2407 2415//2415 -f 2415//2415 2407//2407 2397//2397 -f 2415//2415 2397//2397 2404//2404 -f 2404//2404 2397//2397 2381//2381 -f 2404//2404 2381//2381 2256//2256 -f 2256//2256 2381//2381 2380//2380 -f 2256//2256 2380//2380 2257//2257 -f 2252//2252 2254//2254 2250//2250 -f 2426//2426 2427//2427 2428//2428 -f 2428//2428 2427//2427 2429//2429 -f 2428//2428 2429//2429 2334//2334 -f 2334//2334 2429//2429 2430//2430 -f 2334//2334 2430//2430 2335//2335 -f 2335//2335 2430//2430 2431//2431 -f 2335//2335 2431//2431 2338//2338 -f 2338//2338 2431//2431 2432//2432 -f 2338//2338 2432//2432 2339//2339 -f 2339//2339 2432//2432 2433//2433 -f 2250//2250 2254//2254 2251//2251 -f 2251//2251 2254//2254 2434//2434 -f 2251//2251 2434//2434 2435//2435 -f 2435//2435 2434//2434 2436//2436 -f 2435//2435 2436//2436 2437//2437 -f 2437//2437 2436//2436 2438//2438 -f 2437//2437 2438//2438 2439//2439 -f 2336//2336 2440//2440 2334//2334 -f 2334//2334 2440//2440 2330//2330 -f 2334//2334 2330//2330 2428//2428 -f 2428//2428 2330//2330 2325//2325 -f 2428//2428 2325//2325 2426//2426 -f 2426//2426 2325//2325 2327//2327 -f 2441//2441 2442//2442 2443//2443 -f 2443//2443 2442//2442 2444//2444 -f 2443//2443 2444//2444 2445//2445 -f 2445//2445 2444//2444 2446//2446 -f 2447//2447 2448//2448 2449//2449 -f 2449//2449 2448//2448 2450//2450 -f 2449//2449 2450//2450 2451//2451 -f 2452//2452 2453//2453 2448//2448 -f 2448//2448 2453//2453 2248//2248 -f 2448//2448 2248//2248 2450//2450 -f 2450//2450 2248//2248 2247//2247 -f 2450//2450 2247//2247 2451//2451 -f 2454//2454 2455//2455 2456//2456 -f 2456//2456 2455//2455 2264//2264 -f 2456//2456 2264//2264 2457//2457 -f 2457//2457 2264//2264 2263//2263 -f 2457//2457 2263//2263 2458//2458 -f 2458//2458 2263//2263 2378//2378 -f 2459//2459 2460//2460 2452//2452 -f 2454//2454 2461//2461 2455//2455 -f 2455//2455 2461//2461 2462//2462 -f 2455//2455 2462//2462 2264//2264 -f 2264//2264 2462//2462 2259//2259 -f 2264//2264 2259//2259 2265//2265 -f 2265//2265 2259//2259 2050//2050 -f 2265//2265 2050//2050 2049//2049 -f 2463//2463 2426//2426 2464//2464 -f 2464//2464 2426//2426 2327//2327 -f 2464//2464 2327//2327 2465//2465 -f 2465//2465 2327//2327 2301//2301 -f 2465//2465 2301//2301 2466//2466 -f 2466//2466 2301//2301 2303//2303 -f 2466//2466 2303//2303 2467//2467 -f 2467//2467 2303//2303 2305//2305 -f 2467//2467 2305//2305 2468//2468 -f 2468//2468 2305//2305 2307//2307 -f 2468//2468 2307//2307 2469//2469 -f 2469//2469 2307//2307 2309//2309 -f 2469//2469 2309//2309 2470//2470 -f 2470//2470 2309//2309 2311//2311 -f 2470//2470 2311//2311 2471//2471 -f 2471//2471 2311//2311 2313//2313 -f 2471//2471 2313//2313 2472//2472 -f 2472//2472 2313//2313 2315//2315 -f 2472//2472 2315//2315 2473//2473 -f 2473//2473 2315//2315 2317//2317 -f 2473//2473 2317//2317 2474//2474 -f 2474//2474 2317//2317 2319//2319 -f 2474//2474 2319//2319 2475//2475 -f 2475//2475 2319//2319 2321//2321 -f 2475//2475 2321//2321 2476//2476 -f 2476//2476 2321//2321 2323//2323 -f 2476//2476 2323//2323 2269//2269 -f 2269//2269 2323//2323 2324//2324 -f 2269//2269 2324//2324 2267//2267 -f 2476//2476 2477//2477 2475//2475 -f 2475//2475 2477//2477 2478//2478 -f 2475//2475 2478//2478 2474//2474 -f 2474//2474 2478//2478 2479//2479 -f 2474//2474 2479//2479 2473//2473 -f 2473//2473 2479//2479 2480//2480 -f 2473//2473 2480//2480 2472//2472 -f 2472//2472 2480//2480 2481//2481 -f 2472//2472 2481//2481 2471//2471 -f 2471//2471 2481//2481 2482//2482 -f 2471//2471 2482//2482 2470//2470 -f 2470//2470 2482//2482 2483//2483 -f 2470//2470 2483//2483 2469//2469 -f 2469//2469 2483//2483 2484//2484 -f 2469//2469 2484//2484 2468//2468 -f 2468//2468 2484//2484 2485//2485 -f 2468//2468 2485//2485 2467//2467 -f 2467//2467 2485//2485 2486//2486 -f 2467//2467 2486//2486 2466//2466 -f 2466//2466 2486//2486 2487//2487 -f 2466//2466 2487//2487 2465//2465 -f 2465//2465 2487//2487 2488//2488 -f 2465//2465 2488//2488 2464//2464 -f 2464//2464 2488//2488 2489//2489 -f 2464//2464 2489//2489 2463//2463 -f 2477//2477 2490//2490 2478//2478 -f 2478//2478 2490//2490 2491//2491 -f 2478//2478 2491//2491 2479//2479 -f 2479//2479 2491//2491 2492//2492 -f 2479//2479 2492//2492 2480//2480 -f 2480//2480 2492//2492 2493//2493 -f 2480//2480 2493//2493 2481//2481 -f 2481//2481 2493//2493 2494//2494 -f 2481//2481 2494//2494 2482//2482 -f 2482//2482 2494//2494 2495//2495 -f 2482//2482 2495//2495 2483//2483 -f 2483//2483 2495//2495 2496//2496 -f 2483//2483 2496//2496 2484//2484 -f 2484//2484 2496//2496 2497//2497 -f 2484//2484 2497//2497 2485//2485 -f 2485//2485 2497//2497 2498//2498 -f 2485//2485 2498//2498 2486//2486 -f 2486//2486 2498//2498 2499//2499 -f 2486//2486 2499//2499 2487//2487 -f 2487//2487 2499//2499 2500//2500 -f 2487//2487 2500//2500 2488//2488 -f 2488//2488 2500//2500 2501//2501 -f 2488//2488 2501//2501 2489//2489 -f 2489//2489 2501//2501 2502//2502 -f 2489//2489 2502//2502 2463//2463 -f 2463//2463 2502//2502 2503//2503 -f 2463//2463 2503//2503 2426//2426 -f 2426//2426 2503//2503 2504//2504 -f 2426//2426 2504//2504 2427//2427 -f 2505//2505 2506//2506 2507//2507 -f 2490//2490 2508//2508 2491//2491 -f 2491//2491 2508//2508 2509//2509 -f 2491//2491 2509//2509 2492//2492 -f 2492//2492 2509//2509 2510//2510 -f 2492//2492 2510//2510 2493//2493 -f 2493//2493 2510//2510 2511//2511 -f 2493//2493 2511//2511 2494//2494 -f 2494//2494 2511//2511 2512//2512 -f 2494//2494 2512//2512 2495//2495 -f 2495//2495 2512//2512 2513//2513 -f 2495//2495 2513//2513 2496//2496 -f 2496//2496 2513//2513 2514//2514 -f 2496//2496 2514//2514 2497//2497 -f 2497//2497 2514//2514 2515//2515 -f 2497//2497 2515//2515 2498//2498 -f 2498//2498 2515//2515 2516//2516 -f 2498//2498 2516//2516 2499//2499 -f 2499//2499 2516//2516 2517//2517 -f 2499//2499 2517//2517 2500//2500 -f 2500//2500 2517//2517 2518//2518 -f 2500//2500 2518//2518 2501//2501 -f 2501//2501 2518//2518 2519//2519 -f 2501//2501 2519//2519 2502//2502 -f 2502//2502 2519//2519 2520//2520 -f 2502//2502 2520//2520 2503//2503 -f 2503//2503 2520//2520 2521//2521 -f 2503//2503 2521//2521 2504//2504 -f 2508//2508 2522//2522 2509//2509 -f 2509//2509 2522//2522 2523//2523 -f 2509//2509 2523//2523 2510//2510 -f 2510//2510 2523//2523 2524//2524 -f 2510//2510 2524//2524 2511//2511 -f 2511//2511 2524//2524 2525//2525 -f 2511//2511 2525//2525 2512//2512 -f 2512//2512 2525//2525 2526//2526 -f 2512//2512 2526//2526 2513//2513 -f 2513//2513 2526//2526 2527//2527 -f 2513//2513 2527//2527 2514//2514 -f 2514//2514 2527//2527 2528//2528 -f 2514//2514 2528//2528 2515//2515 -f 2515//2515 2528//2528 2529//2529 -f 2515//2515 2529//2529 2516//2516 -f 2516//2516 2529//2529 2530//2530 -f 2516//2516 2530//2530 2517//2517 -f 2517//2517 2530//2530 2531//2531 -f 2517//2517 2531//2531 2518//2518 -f 2518//2518 2531//2531 2532//2532 -f 2518//2518 2532//2532 2519//2519 -f 2519//2519 2532//2532 2533//2533 -f 2519//2519 2533//2533 2520//2520 -f 2520//2520 2533//2533 2534//2534 -f 2520//2520 2534//2534 2521//2521 -f 2535//2535 2536//2536 2537//2537 -f 2537//2537 2536//2536 2506//2506 -f 2538//2538 2539//2539 2540//2540 -f 2540//2540 2539//2539 2541//2541 -f 2506//2506 2505//2505 2537//2537 -f 2537//2537 2505//2505 2542//2542 -f 2537//2537 2542//2542 2535//2535 -f 2507//2507 2538//2538 2505//2505 -f 2505//2505 2538//2538 2540//2540 -f 2505//2505 2540//2540 2542//2542 -f 2542//2542 2540//2540 2541//2541 -f 2542//2542 2541//2541 2543//2543 -f 2544//2544 2545//2545 2546//2546 -f 2546//2546 2545//2545 2547//2547 -f 2546//2546 2547//2547 2548//2548 -f 2547//2547 2549//2549 2550//2550 -f 2294//2294 2543//2543 2292//2292 -f 2292//2292 2543//2543 2541//2541 -f 2292//2292 2541//2541 2299//2299 -f 2299//2299 2541//2541 2539//2539 -f 2299//2299 2539//2539 2269//2269 -f 2269//2269 2539//2539 2538//2538 -f 2269//2269 2538//2538 2476//2476 -f 2476//2476 2538//2538 2507//2507 -f 2476//2476 2507//2507 2477//2477 -f 2477//2477 2507//2507 2506//2506 -f 2477//2477 2506//2506 2490//2490 -f 2490//2490 2506//2506 2536//2536 -f 2490//2490 2536//2536 2508//2508 -f 2508//2508 2536//2536 2535//2535 -f 2508//2508 2535//2535 2522//2522 -f 2522//2522 2535//2535 2551//2551 -f 2522//2522 2551//2551 2523//2523 -f 2523//2523 2551//2551 2552//2552 -f 2523//2523 2552//2552 2524//2524 -f 2524//2524 2552//2552 2553//2553 -f 2524//2524 2553//2553 2525//2525 -f 2525//2525 2553//2553 2554//2554 -f 2525//2525 2554//2554 2526//2526 -f 2526//2526 2554//2554 2555//2555 -f 2526//2526 2555//2555 2527//2527 -f 2527//2527 2555//2555 2556//2556 -f 2527//2527 2556//2556 2528//2528 -f 2528//2528 2556//2556 2557//2557 -f 2528//2528 2557//2557 2529//2529 -f 2529//2529 2557//2557 2558//2558 -f 2529//2529 2558//2558 2530//2530 -f 2530//2530 2558//2558 2559//2559 -f 2530//2530 2559//2559 2531//2531 -f 2531//2531 2559//2559 2560//2560 -f 2531//2531 2560//2560 2532//2532 -f 2532//2532 2560//2560 2561//2561 -f 2532//2532 2561//2561 2533//2533 -f 2533//2533 2561//2561 2562//2562 -f 2533//2533 2562//2562 2534//2534 -f 2245//2245 2244//2244 2563//2563 -f 2563//2563 2244//2244 2564//2564 -f 2563//2563 2564//2564 2565//2565 -f 2565//2565 2564//2564 2566//2566 -f 2565//2565 2566//2566 2567//2567 -f 2567//2567 2566//2566 2568//2568 -f 2567//2567 2568//2568 2569//2569 -f 2569//2569 2568//2568 2570//2570 -f 2569//2569 2570//2570 2571//2571 -f 2571//2571 2570//2570 2572//2572 -f 2571//2571 2572//2572 2573//2573 -f 2573//2573 2572//2572 2574//2574 -f 2573//2573 2574//2574 2575//2575 -f 2575//2575 2574//2574 2576//2576 -f 2575//2575 2576//2576 2577//2577 -f 2577//2577 2576//2576 2578//2578 -f 2577//2577 2578//2578 2579//2579 -f 2579//2579 2578//2578 2580//2580 -f 2579//2579 2580//2580 2581//2581 -f 2581//2581 2580//2580 2459//2459 -f 2581//2581 2459//2459 2582//2582 -f 2582//2582 2459//2459 2452//2452 -f 2582//2582 2452//2452 2583//2583 -f 2583//2583 2452//2452 2448//2448 -f 2583//2583 2448//2448 2584//2584 -f 2584//2584 2448//2448 2447//2447 -f 2584//2584 2447//2447 2585//2585 -f 2460//2460 2459//2459 2586//2586 -f 2586//2586 2459//2459 2580//2580 -f 2586//2586 2580//2580 2587//2587 -f 2587//2587 2580//2580 2578//2578 -f 2587//2587 2578//2578 2588//2588 -f 2588//2588 2578//2578 2576//2576 -f 2588//2588 2576//2576 2589//2589 -f 2589//2589 2576//2576 2574//2574 -f 2589//2589 2574//2574 2590//2590 -f 2590//2590 2574//2574 2572//2572 -f 2590//2590 2572//2572 2591//2591 -f 2591//2591 2572//2572 2570//2570 -f 2591//2591 2570//2570 2592//2592 -f 2592//2592 2570//2570 2568//2568 -f 2592//2592 2568//2568 2593//2593 -f 2593//2593 2568//2568 2566//2566 -f 2593//2593 2566//2566 2594//2594 -f 2594//2594 2566//2566 2564//2564 -f 2594//2594 2564//2564 2595//2595 -f 2595//2595 2564//2564 2244//2244 -f 2595//2595 2244//2244 2596//2596 -f 2596//2596 2244//2244 2243//2243 -f 2596//2596 2243//2243 2597//2597 -f 2245//2245 2598//2598 2243//2243 -f 2243//2243 2598//2598 2599//2599 -f 2243//2243 2599//2599 2597//2597 -f 2597//2597 2599//2599 2600//2600 -f 2597//2597 2600//2600 2601//2601 -f 2602//2602 2603//2603 2604//2604 -f 2604//2604 2603//2603 2605//2605 -f 2604//2604 2605//2605 2606//2606 -f 2606//2606 2605//2605 2607//2607 -f 2606//2606 2607//2607 2608//2608 -f 2608//2608 2607//2607 2609//2609 -f 2608//2608 2609//2609 2610//2610 -f 2610//2610 2609//2609 2611//2611 -f 2610//2610 2611//2611 2612//2612 -f 2612//2612 2611//2611 2613//2613 -f 2612//2612 2613//2613 2614//2614 -f 2614//2614 2613//2613 2615//2615 -f 2614//2614 2615//2615 2616//2616 -f 2616//2616 2615//2615 2617//2617 -f 2616//2616 2617//2617 2618//2618 -f 2618//2618 2617//2617 2619//2619 -f 2618//2618 2619//2619 2620//2620 -f 2620//2620 2619//2619 2621//2621 -f 2620//2620 2621//2621 2622//2622 -f 2622//2622 2621//2621 2623//2623 -f 2622//2622 2623//2623 2624//2624 -f 2624//2624 2623//2623 2625//2625 -f 2624//2624 2625//2625 2626//2626 -f 2626//2626 2625//2625 2627//2627 -f 2626//2626 2627//2627 2628//2628 -f 2628//2628 2627//2627 2629//2629 -f 2628//2628 2629//2629 2630//2630 -f 2630//2630 2629//2629 2631//2631 -f 2630//2630 2631//2631 2632//2632 -f 2632//2632 2631//2631 2633//2633 -f 2603//2603 2634//2634 2605//2605 -f 2605//2605 2634//2634 2635//2635 -f 2605//2605 2635//2635 2607//2607 -f 2607//2607 2635//2635 2636//2636 -f 2607//2607 2636//2636 2609//2609 -f 2609//2609 2636//2636 2637//2637 -f 2609//2609 2637//2637 2611//2611 -f 2611//2611 2637//2637 2638//2638 -f 2611//2611 2638//2638 2613//2613 -f 2613//2613 2638//2638 2639//2639 -f 2613//2613 2639//2639 2615//2615 -f 2615//2615 2639//2639 2640//2640 -f 2615//2615 2640//2640 2617//2617 -f 2617//2617 2640//2640 2641//2641 -f 2617//2617 2641//2641 2619//2619 -f 2619//2619 2641//2641 2642//2642 -f 2619//2619 2642//2642 2621//2621 -f 2621//2621 2642//2642 2643//2643 -f 2621//2621 2643//2643 2623//2623 -f 2623//2623 2643//2643 2644//2644 -f 2623//2623 2644//2644 2625//2625 -f 2625//2625 2644//2644 2645//2645 -f 2625//2625 2645//2645 2627//2627 -f 2627//2627 2645//2645 2646//2646 -f 2627//2627 2646//2646 2629//2629 -f 2629//2629 2646//2646 2647//2647 -f 2629//2629 2647//2647 2631//2631 -f 2631//2631 2647//2647 2648//2648 -f 2631//2631 2648//2648 2633//2633 -f 2633//2633 2648//2648 2246//2246 -f 2246//2246 2248//2248 2633//2633 -f 2633//2633 2248//2248 2453//2453 -f 2633//2633 2453//2453 2632//2632 -f 2632//2632 2453//2453 2452//2452 -f 2632//2632 2452//2452 2630//2630 -f 2630//2630 2452//2452 2460//2460 -f 2630//2630 2460//2460 2628//2628 -f 2628//2628 2460//2460 2586//2586 -f 2628//2628 2586//2586 2626//2626 -f 2626//2626 2586//2586 2587//2587 -f 2626//2626 2587//2587 2624//2624 -f 2624//2624 2587//2587 2588//2588 -f 2624//2624 2588//2588 2622//2622 -f 2622//2622 2588//2588 2589//2589 -f 2622//2622 2589//2589 2620//2620 -f 2620//2620 2589//2589 2590//2590 -f 2620//2620 2590//2590 2618//2618 -f 2618//2618 2590//2590 2591//2591 -f 2618//2618 2591//2591 2616//2616 -f 2616//2616 2591//2591 2592//2592 -f 2616//2616 2592//2592 2614//2614 -f 2614//2614 2592//2592 2593//2593 -f 2614//2614 2593//2593 2612//2612 -f 2612//2612 2593//2593 2594//2594 -f 2612//2612 2594//2594 2610//2610 -f 2610//2610 2594//2594 2595//2595 -f 2610//2610 2595//2595 2608//2608 -f 2608//2608 2595//2595 2596//2596 -f 2608//2608 2596//2596 2606//2606 -f 2606//2606 2596//2596 2597//2597 -f 2606//2606 2597//2597 2604//2604 -f 2604//2604 2597//2597 2601//2601 -f 2604//2604 2601//2601 2602//2602 -f 2241//2241 2649//2649 2650//2650 -f 2602//2602 2651//2651 2603//2603 -f 2603//2603 2651//2651 2652//2652 -f 2603//2603 2652//2652 2634//2634 -f 2634//2634 2652//2652 2653//2653 -f 2634//2634 2653//2653 2635//2635 -f 2635//2635 2653//2653 2654//2654 -f 2635//2635 2654//2654 2636//2636 -f 2636//2636 2654//2654 2655//2655 -f 2636//2636 2655//2655 2637//2637 -f 2637//2637 2655//2655 2656//2656 -f 2637//2637 2656//2656 2638//2638 -f 2638//2638 2656//2656 2657//2657 -f 2638//2638 2657//2657 2639//2639 -f 2639//2639 2657//2657 2658//2658 -f 2639//2639 2658//2658 2640//2640 -f 2640//2640 2658//2658 2659//2659 -f 2640//2640 2659//2659 2641//2641 -f 2641//2641 2659//2659 2660//2660 -f 2641//2641 2660//2660 2642//2642 -f 2642//2642 2660//2660 2661//2661 -f 2642//2642 2661//2661 2643//2643 -f 2643//2643 2661//2661 2662//2662 -f 2643//2643 2662//2662 2644//2644 -f 2644//2644 2662//2662 2663//2663 -f 2644//2644 2663//2663 2645//2645 -f 2645//2645 2663//2663 2664//2664 -f 2645//2645 2664//2664 2646//2646 -f 2646//2646 2664//2664 2665//2665 -f 2646//2646 2665//2665 2647//2647 -f 2647//2647 2665//2665 2666//2666 -f 2647//2647 2666//2666 2648//2648 -f 2648//2648 2666//2666 2667//2667 -f 2648//2648 2667//2667 2246//2246 -f 2246//2246 2667//2667 2668//2668 -f 2246//2246 2668//2668 2247//2247 -f 2247//2247 2668//2668 2461//2461 -f 2247//2247 2461//2461 2451//2451 -f 2451//2451 2461//2461 2454//2454 -f 2451//2451 2454//2454 2449//2449 -f 2449//2449 2454//2454 2456//2456 -f 2449//2449 2456//2456 2447//2447 -f 2447//2447 2456//2456 2457//2457 -f 2447//2447 2457//2457 2585//2585 -f 2585//2585 2457//2457 2458//2458 -f 2240//2240 2242//2242 2669//2669 -f 2669//2669 2242//2242 2670//2670 -f 2669//2669 2670//2670 2671//2671 -f 2671//2671 2670//2670 2672//2672 -f 2671//2671 2672//2672 2673//2673 -f 2674//2674 2675//2675 2676//2676 -f 2676//2676 2675//2675 2414//2414 -f 2676//2676 2414//2414 2677//2677 -f 2677//2677 2414//2414 2413//2413 -f 2677//2677 2413//2413 2678//2678 -f 2678//2678 2413//2413 2406//2406 -f 2678//2678 2406//2406 2679//2679 -f 2679//2679 2406//2406 2258//2258 -f 2241//2241 2650//2650 2242//2242 -f 2242//2242 2650//2650 2680//2680 -f 2242//2242 2680//2680 2670//2670 -f 2670//2670 2680//2680 2681//2681 -f 2670//2670 2681//2681 2672//2672 -f 2672//2672 2681//2681 2682//2682 -f 2672//2672 2682//2682 2673//2673 -f 2547//2547 2550//2550 2548//2548 -f 2548//2548 2550//2550 2683//2683 -f 2548//2548 2683//2683 2684//2684 -f 2685//2685 2544//2544 2686//2686 -f 2686//2686 2544//2544 2546//2546 -f 2686//2686 2546//2546 2687//2687 -f 2687//2687 2546//2546 2548//2548 -f 2687//2687 2548//2548 2688//2688 -f 2688//2688 2548//2548 2684//2684 -f 2688//2688 2684//2684 2689//2689 -f 2651//2651 2674//2674 2652//2652 -f 2652//2652 2674//2674 2676//2676 -f 2652//2652 2676//2676 2653//2653 -f 2653//2653 2676//2676 2677//2677 -f 2653//2653 2677//2677 2654//2654 -f 2654//2654 2677//2677 2678//2678 -f 2654//2654 2678//2678 2655//2655 -f 2655//2655 2678//2678 2679//2679 -f 2655//2655 2679//2679 2656//2656 -f 2656//2656 2679//2679 2258//2258 -f 2656//2656 2258//2258 2657//2657 -f 2657//2657 2258//2258 2257//2257 -f 2657//2657 2257//2257 2658//2658 -f 2658//2658 2257//2257 2380//2380 -f 2658//2658 2380//2380 2659//2659 -f 2659//2659 2380//2380 2382//2382 -f 2659//2659 2382//2382 2660//2660 -f 2660//2660 2382//2382 2384//2384 -f 2660//2660 2384//2384 2661//2661 -f 2661//2661 2384//2384 2386//2386 -f 2661//2661 2386//2386 2662//2662 -f 2662//2662 2386//2386 2388//2388 -f 2662//2662 2388//2388 2663//2663 -f 2663//2663 2388//2388 2390//2390 -f 2663//2663 2390//2390 2664//2664 -f 2664//2664 2390//2390 2392//2392 -f 2664//2664 2392//2392 2665//2665 -f 2665//2665 2392//2392 2394//2394 -f 2665//2665 2394//2394 2666//2666 -f 2666//2666 2394//2394 2396//2396 -f 2666//2666 2396//2396 2667//2667 -f 2667//2667 2396//2396 2262//2262 -f 2667//2667 2262//2262 2668//2668 -f 2668//2668 2262//2262 2370//2370 -f 2668//2668 2370//2370 2461//2461 -f 2461//2461 2370//2370 2369//2369 -f 2461//2461 2369//2369 2462//2462 -f 2462//2462 2369//2369 2368//2368 -f 2462//2462 2368//2368 2259//2259 -f 2259//2259 2368//2368 2375//2375 -f 2259//2259 2375//2375 2051//2051 -f 2051//2051 2375//2375 2052//2052 -f 2690//2690 2289//2289 2691//2691 -f 2692//2692 2691//2691 2693//2693 -f 2693//2693 2691//2691 2289//2289 -f 2693//2693 2289//2289 2694//2694 -f 2694//2694 2289//2289 2291//2291 -f 2694//2694 2291//2291 2695//2695 -f 2695//2695 2270//2270 2694//2694 -f 2694//2694 2270//2270 2272//2272 -f 2694//2694 2272//2272 2693//2693 -f 2693//2693 2272//2272 2696//2696 -f 2693//2693 2696//2696 2692//2692 -f 2692//2692 2696//2696 2697//2697 -f 2698//2698 2697//2697 2699//2699 -f 2699//2699 2697//2697 2696//2696 -f 2699//2699 2696//2696 2700//2700 -f 2700//2700 2696//2696 2272//2272 -f 2700//2700 2272//2272 2701//2701 -f 2701//2701 2272//2272 2288//2288 -f 2701//2701 2288//2288 2285//2285 -f 2273//2273 2352//2352 2274//2274 -f 2274//2274 2352//2352 2351//2351 -f 2274//2274 2351//2351 2275//2275 -f 2275//2275 2351//2351 2702//2702 -f 2275//2275 2702//2702 2277//2277 -f 2277//2277 2702//2702 2703//2703 -f 2277//2277 2703//2703 2279//2279 -f 2279//2279 2703//2703 2704//2704 -f 2705//2705 2239//2239 2706//2706 -f 2706//2706 2239//2239 2237//2237 -f 2706//2706 2237//2237 2707//2707 -f 2707//2707 2237//2237 2236//2236 -f 2707//2707 2236//2236 2708//2708 -f 2709//2709 2710//2710 2711//2711 -f 2711//2711 2710//2710 2712//2712 -f 2711//2711 2712//2712 2713//2713 -f 2714//2714 2715//2715 2716//2716 -f 2716//2716 2715//2715 2717//2717 -f 2716//2716 2717//2717 2718//2718 -f 2719//2719 2720//2720 2721//2721 -f 2721//2721 2720//2720 2722//2722 -f 2723//2723 2232//2232 2724//2724 -f 2724//2724 2232//2232 2725//2725 -f 2724//2724 2725//2725 2726//2726 -f 2235//2235 2234//2234 2722//2722 -f 2722//2722 2234//2234 2727//2727 -f 2722//2722 2727//2727 2721//2721 -f 2728//2728 2729//2729 2730//2730 -f 2730//2730 2729//2729 2731//2731 -f 2730//2730 2731//2731 2235//2235 -f 2233//2233 2732//2732 2234//2234 -f 2234//2234 2732//2732 2733//2733 -f 2234//2234 2733//2733 2727//2727 -f 2729//2729 2734//2734 2731//2731 -f 2731//2731 2734//2734 2735//2735 -f 2731//2731 2735//2735 2235//2235 -f 2235//2235 2735//2735 2736//2736 -f 2235//2235 2736//2736 2233//2233 -f 2233//2233 2736//2736 2737//2737 -f 2233//2233 2737//2737 2732//2732 -f 2738//2738 2739//2739 2740//2740 -f 2740//2740 2739//2739 2741//2741 -f 2740//2740 2741//2741 2742//2742 -f 2743//2743 2744//2744 2745//2745 -f 2745//2745 2744//2744 2746//2746 -f 2746//2746 2747//2747 2745//2745 -f 2745//2745 2747//2747 2715//2715 -f 2745//2745 2715//2715 2743//2743 -f 2743//2743 2715//2715 2714//2714 -f 2743//2743 2714//2714 2719//2719 -f 2719//2719 2714//2714 2716//2716 -f 2719//2719 2716//2716 2720//2720 -f 2720//2720 2716//2716 2718//2718 -f 2720//2720 2718//2718 2748//2748 -f 2749//2749 2750//2750 2751//2751 -f 2751//2751 2750//2750 2752//2752 -f 2751//2751 2752//2752 2753//2753 -f 2734//2734 2738//2738 2735//2735 -f 2735//2735 2738//2738 2740//2740 -f 2735//2735 2740//2740 2736//2736 -f 2736//2736 2740//2740 2742//2742 -f 2736//2736 2742//2742 2737//2737 -f 2737//2737 2742//2742 2754//2754 -f 2737//2737 2754//2754 2732//2732 -f 2732//2732 2754//2754 2755//2755 -f 2732//2732 2755//2755 2733//2733 -f 2756//2756 2757//2757 2758//2758 -f 2756//2756 2758//2758 2759//2759 -f 2759//2759 2758//2758 2760//2760 -f 2759//2759 2760//2760 2761//2761 -f 2760//2760 2753//2753 2761//2761 -f 2761//2761 2753//2753 2752//2752 -f 2761//2761 2752//2752 2762//2762 -f 2763//2763 2764//2764 2765//2765 -f 2765//2765 2764//2764 2766//2766 -f 2226//2226 2227//2227 2224//2224 -f 2224//2224 2227//2227 2767//2767 -f 2224//2224 2767//2767 2768//2768 -f 2769//2769 2770//2770 2766//2766 -f 2766//2766 2770//2770 2771//2771 -f 2766//2766 2771//2771 2765//2765 -f 2772//2772 2773//2773 2774//2774 -f 2774//2774 2773//2773 2775//2775 -f 2774//2774 2775//2775 2776//2776 -f 2776//2776 2775//2775 2709//2709 -f 2222//2222 2221//2221 2777//2777 -f 2777//2777 2221//2221 2778//2778 -f 2777//2777 2778//2778 2779//2779 -f 2780//2780 2781//2781 2773//2773 -f 2782//2782 2222//2222 2772//2772 -f 2772//2772 2222//2222 2777//2777 -f 2772//2772 2777//2777 2773//2773 -f 2773//2773 2777//2777 2779//2779 -f 2773//2773 2779//2779 2780//2780 -f 2781//2781 2780//2780 2783//2783 -f 2783//2783 2780//2780 2784//2784 -f 2783//2783 2784//2784 2785//2785 -f 2785//2785 2784//2784 2786//2786 -f 2785//2785 2786//2786 2787//2787 -f 2787//2787 2763//2763 2785//2785 -f 2785//2785 2763//2763 2765//2765 -f 2785//2785 2765//2765 2783//2783 -f 2783//2783 2765//2765 2771//2771 -f 2783//2783 2771//2771 2781//2781 -f 2781//2781 2771//2771 2770//2770 -f 2781//2781 2770//2770 2773//2773 -f 2773//2773 2770//2770 2769//2769 -f 2773//2773 2769//2769 2775//2775 -f 2775//2775 2769//2769 2788//2788 -f 2789//2789 2219//2219 2790//2790 -f 2790//2790 2219//2219 2218//2218 -f 2790//2790 2218//2218 2791//2791 -f 2791//2791 2218//2218 2223//2223 -f 2792//2792 2793//2793 2794//2794 -f 2794//2794 2793//2793 2795//2795 -f 2794//2794 2795//2795 2796//2796 -f 2797//2797 2798//2798 2799//2799 -f 2799//2799 2798//2798 2800//2800 -f 2799//2799 2800//2800 2801//2801 -f 2796//2796 2802//2802 2794//2794 -f 2794//2794 2802//2802 2803//2803 -f 2794//2794 2803//2803 2792//2792 -f 2788//2788 2769//2769 2804//2804 -f 2804//2804 2769//2769 2766//2766 -f 2804//2804 2766//2766 2805//2805 -f 2805//2805 2766//2766 2764//2764 -f 2805//2805 2764//2764 2217//2217 -f 2217//2217 2764//2764 2763//2763 -f 2217//2217 2763//2763 2223//2223 -f 2223//2223 2763//2763 2787//2787 -f 2223//2223 2787//2787 2791//2791 -f 2791//2791 2787//2787 2786//2786 -f 2791//2791 2786//2786 2790//2790 -f 2790//2790 2786//2786 2806//2806 -f 2790//2790 2806//2806 2789//2789 -f 2807//2807 2214//2214 2808//2808 -f 2808//2808 2214//2214 2216//2216 -f 2808//2808 2216//2216 2809//2809 -f 2809//2809 2216//2216 2810//2810 -f 2811//2811 2812//2812 2813//2813 -f 2813//2813 2812//2812 2814//2814 -f 2813//2813 2814//2814 2815//2815 -f 2816//2816 2817//2817 2818//2818 -f 2819//2819 2811//2811 2820//2820 -f 2820//2820 2811//2811 2813//2813 -f 2820//2820 2813//2813 2821//2821 -f 2821//2821 2813//2813 2815//2815 -f 2817//2817 2816//2816 2808//2808 -f 2808//2808 2816//2816 2822//2822 -f 2808//2808 2822//2822 2807//2807 -f 2823//2823 2824//2824 2825//2825 -f 2825//2825 2824//2824 2826//2826 -f 2825//2825 2826//2826 2827//2827 -f 2827//2827 2826//2826 2828//2828 -f 2827//2827 2828//2828 2829//2829 -f 2829//2829 2828//2828 2830//2830 -f 2829//2829 2830//2830 2210//2210 -f 2831//2831 2832//2832 2833//2833 -f 2832//2832 2831//2831 2213//2213 -f 2213//2213 2831//2831 2834//2834 -f 2213//2213 2834//2834 2211//2211 -f 2816//2816 2823//2823 2822//2822 -f 2822//2822 2823//2823 2825//2825 -f 2822//2822 2825//2825 2807//2807 -f 2807//2807 2825//2825 2827//2827 -f 2807//2807 2827//2827 2214//2214 -f 2214//2214 2827//2827 2829//2829 -f 2214//2214 2829//2829 2215//2215 -f 2215//2215 2829//2829 2210//2210 -f 2215//2215 2210//2210 2835//2835 -f 2835//2835 2210//2210 2209//2209 -f 2209//2209 2782//2782 2835//2835 -f 2835//2835 2782//2782 2772//2772 -f 2835//2835 2772//2772 2215//2215 -f 2215//2215 2772//2772 2774//2774 -f 2215//2215 2774//2774 2216//2216 -f 2216//2216 2774//2774 2776//2776 -f 2216//2216 2776//2776 2810//2810 -f 2810//2810 2776//2776 2836//2836 -f 2810//2810 2836//2836 2837//2837 -f 2837//2837 2836//2836 2281//2281 -f 2837//2837 2281//2281 2838//2838 -f 2838//2838 2281//2281 2283//2283 -f 2838//2838 2283//2283 2280//2280 -f 2839//2839 2840//2840 2841//2841 -f 2841//2841 2840//2840 2842//2842 -f 2841//2841 2842//2842 2207//2207 -f 2843//2843 2844//2844 2845//2845 -f 2845//2845 2844//2844 2846//2846 -f 2205//2205 2207//2207 2847//2847 -f 2847//2847 2848//2848 2849//2849 -f 2848//2848 2850//2850 2849//2849 -f 2849//2849 2850//2850 2851//2851 -f 2849//2849 2851//2851 2852//2852 -f 2847//2847 2853//2853 2205//2205 -f 2205//2205 2853//2853 2854//2854 -f 2205//2205 2854//2854 2206//2206 -f 2204//2204 2203//2203 2855//2855 -f 2846//2846 2856//2856 2845//2845 -f 2845//2845 2856//2856 2202//2202 -f 2845//2845 2202//2202 2843//2843 -f 2843//2843 2202//2202 2204//2204 -f 2843//2843 2204//2204 2857//2857 -f 2212//2212 2858//2858 2213//2213 -f 2213//2213 2858//2858 2859//2859 -f 2213//2213 2859//2859 2832//2832 -f 2832//2832 2859//2859 2860//2860 -f 2832//2832 2860//2860 2833//2833 -f 2861//2861 2797//2797 2803//2803 -f 2803//2803 2797//2797 2799//2799 -f 2803//2803 2799//2799 2792//2792 -f 2792//2792 2799//2799 2801//2801 -f 2792//2792 2801//2801 2793//2793 -f 2847//2847 2849//2849 2853//2853 -f 2853//2853 2849//2849 2852//2852 -f 2853//2853 2852//2852 2854//2854 -f 2854//2854 2852//2852 2855//2855 -f 2854//2854 2855//2855 2206//2206 -f 2206//2206 2855//2855 2203//2203 -f 2206//2206 2203//2203 2207//2207 -f 2207//2207 2203//2203 2202//2202 -f 2207//2207 2202//2202 2841//2841 -f 2841//2841 2202//2202 2856//2856 -f 2841//2841 2856//2856 2839//2839 -f 2839//2839 2856//2856 2846//2846 -f 2839//2839 2846//2846 2795//2795 -f 2795//2795 2846//2846 2844//2844 -f 2795//2795 2844//2844 2796//2796 -f 2796//2796 2844//2844 2843//2843 -f 2796//2796 2843//2843 2802//2802 -f 2802//2802 2843//2843 2857//2857 -f 2802//2802 2857//2857 2803//2803 -f 2803//2803 2857//2857 2862//2862 -f 2803//2803 2862//2862 2861//2861 -f 2863//2863 2864//2864 2865//2865 -f 2865//2865 2864//2864 2866//2866 -f 2865//2865 2866//2866 2867//2867 -f 2868//2868 2869//2869 2863//2863 -f 2863//2863 2869//2869 2870//2870 -f 2225//2225 2224//2224 2871//2871 -f 2871//2871 2224//2224 2768//2768 -f 2871//2871 2768//2768 2872//2872 -f 2863//2863 2865//2865 2868//2868 -f 2868//2868 2865//2865 2873//2873 -f 2868//2868 2873//2873 2869//2869 -f 2869//2869 2873//2873 2874//2874 -f 2869//2869 2874//2874 2875//2875 -f 2228//2228 2876//2876 2227//2227 -f 2227//2227 2876//2876 2877//2877 -f 2227//2227 2877//2877 2767//2767 -f 2767//2767 2877//2877 2878//2878 -f 2767//2767 2878//2878 2768//2768 -f 2768//2768 2878//2878 2879//2879 -f 2768//2768 2879//2879 2872//2872 -f 2231//2231 2870//2870 2880//2880 -f 2880//2880 2870//2870 2869//2869 -f 2880//2880 2869//2869 2881//2881 -f 2881//2881 2869//2869 2875//2875 -f 2881//2881 2762//2762 2880//2880 -f 2880//2880 2762//2762 2752//2752 -f 2880//2880 2752//2752 2231//2231 -f 2231//2231 2752//2752 2750//2750 -f 2231//2231 2750//2750 2229//2229 -f 2229//2229 2750//2750 2749//2749 -f 2229//2229 2749//2749 2232//2232 -f 2232//2232 2749//2749 2882//2882 -f 2232//2232 2882//2882 2725//2725 -f 2725//2725 2882//2882 2883//2883 -f 2725//2725 2883//2883 2726//2726 -f 2884//2884 2885//2885 2886//2886 -f 2886//2886 2885//2885 2887//2887 -f 2886//2886 2887//2887 2888//2888 -f 2889//2889 2890//2890 2860//2860 -f 2860//2860 2890//2890 2891//2891 -f 2860//2860 2891//2891 2833//2833 -f 2875//2875 2892//2892 2881//2881 -f 2881//2881 2892//2892 2884//2884 -f 2881//2881 2884//2884 2762//2762 -f 2762//2762 2884//2884 2886//2886 -f 2762//2762 2886//2886 2761//2761 -f 2761//2761 2886//2886 2888//2888 -f 2761//2761 2888//2888 2759//2759 -f 2759//2759 2888//2888 2893//2893 -f 2759//2759 2893//2893 2756//2756 -f 2756//2756 2893//2893 2894//2894 -f 2756//2756 2894//2894 2757//2757 -f 2895//2895 2896//2896 2897//2897 -f 2897//2897 2896//2896 2201//2201 -f 2897//2897 2201//2201 2898//2898 -f 2898//2898 2899//2899 2897//2897 -f 2897//2897 2899//2899 2900//2900 -f 2897//2897 2900//2900 2895//2895 -f 2895//2895 2900//2900 2901//2901 -f 2895//2895 2901//2901 2896//2896 -f 2896//2896 2901//2901 2902//2902 -f 2896//2896 2902//2902 2201//2201 -f 2201//2201 2902//2902 2903//2903 -f 2201//2201 2903//2903 2199//2199 -f 2904//2904 2905//2905 2906//2906 -f 2280//2280 2279//2279 2838//2838 -f 2838//2838 2279//2279 2704//2704 -f 2838//2838 2704//2704 2837//2837 -f 2837//2837 2704//2704 2198//2198 -f 2837//2837 2198//2198 2810//2810 -f 2810//2810 2198//2198 2197//2197 -f 2810//2810 2197//2197 2809//2809 -f 2809//2809 2197//2197 2907//2907 -f 2809//2809 2907//2907 2908//2908 -f 2908//2908 2907//2907 2909//2909 -f 2908//2908 2909//2909 2910//2910 -f 2911//2911 2912//2912 2913//2913 -f 2913//2913 2912//2912 2914//2914 -f 2913//2913 2914//2914 2915//2915 -f 2916//2916 2917//2917 2918//2918 -f 2819//2819 2818//2818 2811//2811 -f 2811//2811 2818//2818 2817//2817 -f 2811//2811 2817//2817 2812//2812 -f 2812//2812 2817//2817 2808//2808 -f 2812//2812 2808//2808 2814//2814 -f 2814//2814 2808//2808 2809//2809 -f 2814//2814 2809//2809 2815//2815 -f 2815//2815 2809//2809 2908//2908 -f 2815//2815 2908//2908 2821//2821 -f 2821//2821 2908//2908 2910//2910 -f 2821//2821 2910//2910 2820//2820 -f 2820//2820 2910//2910 2919//2919 -f 2820//2820 2919//2919 2819//2819 -f 2819//2819 2919//2919 2920//2920 -f 2819//2819 2920//2920 2818//2818 -f 2818//2818 2920//2920 2921//2921 -f 2818//2818 2921//2921 2816//2816 -f 2816//2816 2921//2921 2922//2922 -f 2816//2816 2922//2922 2823//2823 -f 2823//2823 2922//2922 2923//2923 -f 2823//2823 2923//2923 2824//2824 -f 2824//2824 2923//2923 2924//2924 -f 2824//2824 2924//2924 2826//2826 -f 2826//2826 2924//2924 2851//2851 -f 2826//2826 2851//2851 2828//2828 -f 2828//2828 2851//2851 2850//2850 -f 2828//2828 2850//2850 2830//2830 -f 2830//2830 2850//2850 2848//2848 -f 2830//2830 2848//2848 2210//2210 -f 2210//2210 2848//2848 2847//2847 -f 2210//2210 2847//2847 2208//2208 -f 2208//2208 2847//2847 2207//2207 -f 2208//2208 2207//2207 2209//2209 -f 2209//2209 2207//2207 2842//2842 -f 2209//2209 2842//2842 2782//2782 -f 2782//2782 2842//2842 2840//2840 -f 2782//2782 2840//2840 2222//2222 -f 2222//2222 2840//2840 2839//2839 -f 2222//2222 2839//2839 2220//2220 -f 2220//2220 2839//2839 2795//2795 -f 2220//2220 2795//2795 2221//2221 -f 2221//2221 2795//2795 2793//2793 -f 2221//2221 2793//2793 2778//2778 -f 2778//2778 2793//2793 2801//2801 -f 2778//2778 2801//2801 2779//2779 -f 2779//2779 2801//2801 2800//2800 -f 2779//2779 2800//2800 2780//2780 -f 2780//2780 2800//2800 2798//2798 -f 2780//2780 2798//2798 2784//2784 -f 2784//2784 2798//2798 2797//2797 -f 2784//2784 2797//2797 2786//2786 -f 2786//2786 2797//2797 2861//2861 -f 2786//2786 2861//2861 2806//2806 -f 2806//2806 2861//2861 2862//2862 -f 2806//2806 2862//2862 2789//2789 -f 2925//2925 2926//2926 2927//2927 -f 2927//2927 2926//2926 2918//2918 -f 2927//2927 2918//2918 2928//2928 -f 2928//2928 2918//2918 2917//2917 -f 2928//2928 2917//2917 2929//2929 -f 2929//2929 2917//2917 2916//2916 -f 2929//2929 2916//2916 2930//2930 -f 2930//2930 2916//2916 2931//2931 -f 2930//2930 2931//2931 2932//2932 -f 2932//2932 2931//2931 2933//2933 -f 2933//2933 2931//2931 2934//2934 -f 2933//2933 2934//2934 2935//2935 -f 2916//2916 2936//2936 2931//2931 -f 2931//2931 2936//2936 2937//2937 -f 2931//2931 2937//2937 2934//2934 -f 2934//2934 2937//2937 2938//2938 -f 2899//2899 2939//2939 2900//2900 -f 2900//2900 2939//2939 2940//2940 -f 2900//2900 2940//2940 2901//2901 -f 2901//2901 2940//2940 2941//2941 -f 2901//2901 2941//2941 2902//2902 -f 2902//2902 2941//2941 2942//2942 -f 2902//2902 2942//2942 2903//2903 -f 2903//2903 2942//2942 2943//2943 -f 2903//2903 2943//2943 2199//2199 -f 2199//2199 2943//2943 2944//2944 -f 2199//2199 2944//2944 2200//2200 -f 2200//2200 2944//2944 2945//2945 -f 2196//2196 2946//2946 2947//2947 -f 2947//2947 2946//2946 2948//2948 -f 2947//2947 2948//2948 2949//2949 -f 2949//2949 2948//2948 2950//2950 -f 2949//2949 2950//2950 2194//2194 -f 2951//2951 2952//2952 2193//2193 -f 2193//2193 2195//2195 2951//2951 -f 2951//2951 2195//2195 2953//2953 -f 2951//2951 2953//2953 2954//2954 -f 2898//2898 2183//2183 2899//2899 -f 2899//2899 2183//2183 2182//2182 -f 2899//2899 2182//2182 2939//2939 -f 2939//2939 2182//2182 2955//2955 -f 2939//2939 2955//2955 2940//2940 -f 2940//2940 2955//2955 2956//2956 -f 2940//2940 2956//2956 2941//2941 -f 2941//2941 2956//2956 2957//2957 -f 2941//2941 2957//2957 2942//2942 -f 2942//2942 2957//2957 2958//2958 -f 2942//2942 2958//2958 2943//2943 -f 2943//2943 2958//2958 2959//2959 -f 2943//2943 2959//2959 2944//2944 -f 2944//2944 2959//2959 2960//2960 -f 2944//2944 2960//2960 2945//2945 -f 2194//2194 2950//2950 2195//2195 -f 2195//2195 2950//2950 2961//2961 -f 2195//2195 2961//2961 2953//2953 -f 2953//2953 2961//2961 2962//2962 -f 2953//2953 2962//2962 2954//2954 -f 2192//2192 2191//2191 2963//2963 -f 2190//2190 2964//2964 2191//2191 -f 2191//2191 2964//2964 2965//2965 -f 2191//2191 2965//2965 2963//2963 -f 2963//2963 2965//2965 2966//2966 -f 2963//2963 2966//2966 2967//2967 -f 2834//2834 2935//2935 2211//2211 -f 2211//2211 2935//2935 2934//2934 -f 2211//2211 2934//2934 2212//2212 -f 2212//2212 2934//2934 2938//2938 -f 2212//2212 2938//2938 2858//2858 -f 2858//2858 2938//2938 2968//2968 -f 2858//2858 2968//2968 2859//2859 -f 2859//2859 2968//2968 2969//2969 -f 2859//2859 2969//2969 2860//2860 -f 2860//2860 2969//2969 2970//2970 -f 2860//2860 2970//2970 2889//2889 -f 2971//2971 2972//2972 2973//2973 -f 2973//2973 2972//2972 2974//2974 -f 2975//2975 2976//2976 2977//2977 -f 2977//2977 2976//2976 2978//2978 -f 2977//2977 2978//2978 2979//2979 -f 2980//2980 2906//2906 2981//2981 -f 2201//2201 2904//2904 2898//2898 -f 2898//2898 2904//2904 2906//2906 -f 2898//2898 2906//2906 2183//2183 -f 2183//2183 2906//2906 2980//2980 -f 2183//2183 2980//2980 2982//2982 -f 2983//2983 2984//2984 2985//2985 -f 2985//2985 2984//2984 2986//2986 -f 2985//2985 2986//2986 2987//2987 -f 2988//2988 2989//2989 2990//2990 -f 2990//2990 2989//2989 2986//2986 -f 2990//2990 2986//2986 2991//2991 -f 2991//2991 2986//2986 2984//2984 -f 2991//2991 2984//2984 2992//2992 -f 2992//2992 2984//2984 2983//2983 -f 2992//2992 2983//2983 2993//2993 -f 2988//2988 2990//2990 2994//2994 -f 2994//2994 2990//2990 2991//2991 -f 2994//2994 2991//2991 2995//2995 -f 2995//2995 2991//2991 2992//2992 -f 2995//2995 2992//2992 2996//2996 -f 2996//2996 2992//2992 2993//2993 -f 2996//2996 2993//2993 2997//2997 -f 2998//2998 2999//2999 3000//3000 -f 2999//2999 2998//2998 3001//3001 -f 3001//3001 2998//2998 3002//3002 -f 3001//3001 3002//3002 3003//3003 -f 3004//3004 3005//3005 3006//3006 -f 3006//3006 3005//3005 3007//3007 -f 3006//3006 3007//3007 2187//2187 -f 3008//3008 3009//3009 3010//3010 -f 3010//3010 3009//3009 3011//3011 -f 2186//2186 2185//2185 3012//3012 -f 3012//3012 2185//2185 3013//3013 -f 3012//3012 3013//3013 3014//3014 -f 3014//3014 3013//3013 3015//3015 -f 3014//3014 3015//3015 3016//3016 -f 3016//3016 3015//3015 3017//3017 -f 3016//3016 3017//3017 3011//3011 -f 3011//3011 3017//3017 3018//3018 -f 3011//3011 3018//3018 3010//3010 -f 3010//3010 3018//3018 3019//3019 -f 3010//3010 3019//3019 3020//3020 -f 3021//3021 2184//2184 3022//3022 -f 3022//3022 2184//2184 2186//2186 -f 3022//3022 2186//2186 2997//2997 -f 2997//2997 2186//2186 3012//3012 -f 2997//2997 3012//3012 2996//2996 -f 2996//2996 3012//3012 3014//3014 -f 2996//2996 3014//3014 2995//2995 -f 2995//2995 3014//3014 3016//3016 -f 2995//2995 3016//3016 2994//2994 -f 2994//2994 3016//3016 3011//3011 -f 2994//2994 3011//3011 2988//2988 -f 2988//2988 3011//3011 3009//3009 -f 2988//2988 3009//3009 2989//2989 -f 2989//2989 3009//3009 3008//3008 -f 2989//2989 3008//3008 2986//2986 -f 2986//2986 3008//3008 3023//3023 -f 2986//2986 3023//3023 2987//2987 -f 2987//2987 3023//3023 3024//3024 -f 3025//3025 3026//3026 3027//3027 -f 3027//3027 3026//3026 3028//3028 -f 3027//3027 3028//3028 2885//2885 -f 3029//3029 3030//3030 3031//3031 -f 2190//2190 3032//3032 2964//2964 -f 2964//2964 3032//3032 3033//3033 -f 2964//2964 3033//3033 2965//2965 -f 2965//2965 3033//3033 3029//3029 -f 2965//2965 3029//3029 2966//2966 -f 2966//2966 3029//3029 3031//3031 -f 2966//2966 3031//3031 2967//2967 -f 3034//3034 3035//3035 3036//3036 -f 2173//2173 3037//3037 3038//3038 -f 3038//3038 3037//3037 3036//3036 -f 3036//3036 3035//3035 3038//3038 -f 3038//3038 3035//3035 2174//2174 -f 3038//3038 2174//2174 2173//2173 -f 3039//3039 2977//2977 3040//3040 -f 3040//3040 2977//2977 2979//2979 -f 3040//3040 2979//2979 3041//3041 -f 3041//3041 2979//2979 3042//3042 -f 3041//3041 3042//3042 3043//3043 -f 3043//3043 3042//3042 3044//3044 -f 3043//3043 3044//3044 3045//3045 -f 2180//2180 2177//2177 3046//3046 -f 3046//3046 2177//2177 2176//2176 -f 3046//3046 2176//2176 3039//3039 -f 2178//2178 2177//2177 3047//3047 -f 3047//3047 2177//2177 2179//2179 -f 3047//3047 2179//2179 3048//3048 -f 3039//3039 3040//3040 3046//3046 -f 3046//3046 3040//3040 3041//3041 -f 3046//3046 3041//3041 2180//2180 -f 2180//2180 3041//3041 3043//3043 -f 2180//2180 3043//3043 2179//2179 -f 2179//2179 3043//3043 3045//3045 -f 2179//2179 3045//3045 3048//3048 -f 3049//3049 3050//3050 3051//3051 -f 3051//3051 3050//3050 3052//3052 -f 3051//3051 3052//3052 3053//3053 -f 3053//3053 3052//3052 3054//3054 -f 3055//3055 3054//3054 3056//3056 -f 3056//3056 3054//3054 3052//3052 -f 3056//3056 3052//3052 3057//3057 -f 3057//3057 3052//3052 3050//3050 -f 3058//3058 3059//3059 3060//3060 -f 3060//3060 3059//3059 3061//3061 -f 3062//3062 3063//3063 3058//3058 -f 3058//3058 3063//3063 3055//3055 -f 3058//3058 3055//3055 3059//3059 -f 3059//3059 3055//3055 3056//3056 -f 3059//3059 3056//3056 3061//3061 -f 3061//3061 3056//3056 3057//3057 -f 3061//3061 3057//3057 3064//3064 -f 3064//3064 3057//3057 3050//3050 -f 3064//3064 3050//3050 3065//3065 -f 3065//3065 3050//3050 3049//3049 -f 2187//2187 2189//2189 3006//3006 -f 3006//3006 2189//2189 3066//3066 -f 3006//3006 3066//3066 3004//3004 -f 3004//3004 3066//3066 3067//3067 -f 3004//3004 3067//3067 3019//3019 -f 3021//3021 2188//2188 2184//2184 -f 2184//2184 2188//2188 2187//2187 -f 2184//2184 2187//2187 2185//2185 -f 2185//2185 2187//2187 3007//3007 -f 2185//2185 3007//3007 3013//3013 -f 3013//3013 3007//3007 3000//3000 -f 3013//3013 3000//3000 3015//3015 -f 3015//3015 3000//3000 2999//2999 -f 3015//3015 2999//2999 3017//3017 -f 3017//3017 2999//2999 3001//3001 -f 3017//3017 3001//3001 3018//3018 -f 3018//3018 3001//3001 3003//3003 -f 3018//3018 3003//3003 3019//3019 -f 3019//3019 3003//3003 3002//3002 -f 3019//3019 3002//3002 3004//3004 -f 3004//3004 3002//3002 2998//2998 -f 3004//3004 2998//2998 3005//3005 -f 3005//3005 2998//2998 3000//3000 -f 3005//3005 3000//3000 3007//3007 -f 3068//3068 3069//3069 3070//3070 -f 3070//3070 3069//3069 3071//3071 -f 3070//3070 3071//3071 3072//3072 -f 2170//2170 2175//2175 3073//3073 -f 3073//3073 2175//2175 2174//2174 -f 3073//3073 2174//2174 3074//3074 -f 3074//3074 2174//2174 3035//3035 -f 3074//3074 3035//3035 3072//3072 -f 3072//3072 3035//3035 3034//3034 -f 3072//3072 3034//3034 3070//3070 -f 3070//3070 3034//3034 3036//3036 -f 3070//3070 3036//3036 3068//3068 -f 3068//3068 3036//3036 2979//2979 -f 3068//3068 2979//2979 2905//2905 -f 2905//2905 2979//2979 2978//2978 -f 2905//2905 2978//2978 2906//2906 -f 2906//2906 2978//2978 2976//2976 -f 2906//2906 2976//2976 2981//2981 -f 2981//2981 2976//2976 2975//2975 -f 3075//3075 3076//3076 3077//3077 -f 3077//3077 3076//3076 3078//3078 -f 3077//3077 3078//3078 3079//3079 -f 3079//3079 3078//3078 3080//3080 -f 3081//3081 3080//3080 3078//3078 -f 3081//3081 3078//3078 3082//3082 -f 3082//3082 3078//3078 3076//3076 -f 3082//3082 3076//3076 3083//3083 -f 3083//3083 3076//3076 3084//3084 -f 2926//2926 2915//2915 2918//2918 -f 2918//2918 2915//2915 2914//2914 -f 2918//2918 2914//2914 2916//2916 -f 2916//2916 2914//2914 2912//2912 -f 2916//2916 2912//2912 2936//2936 -f 2936//2936 2912//2912 2911//2911 -f 2936//2936 2911//2911 2937//2937 -f 2937//2937 2911//2911 3085//3085 -f 2937//2937 3085//3085 2938//2938 -f 2938//2938 3085//3085 3025//3025 -f 2938//2938 3025//3025 2968//2968 -f 2968//2968 3025//3025 3027//3027 -f 2968//2968 3027//3027 2969//2969 -f 2969//2969 3027//3027 2885//2885 -f 2969//2969 2885//2885 3086//3086 -f 3086//3086 2885//2885 2884//2884 -f 2282//2282 2281//2281 2284//2284 -f 2284//2284 2281//2281 2836//2836 -f 2284//2284 2836//2836 2708//2708 -f 2708//2708 2836//2836 2776//2776 -f 2708//2708 2776//2776 2707//2707 -f 2707//2707 2776//2776 2709//2709 -f 2707//2707 2709//2709 2706//2706 -f 2706//2706 2709//2709 2711//2711 -f 2706//2706 2711//2711 2705//2705 -f 2705//2705 2711//2711 2713//2713 -f 2705//2705 2713//2713 3087//3087 -f 2350//2350 3088//3088 3089//3089 -f 3089//3089 3088//3088 3090//3090 -f 3089//3089 3090//3090 3091//3091 -f 3091//3091 3090//3090 3092//3092 -f 3093//3093 3094//3094 3095//3095 -f 3095//3095 3094//3094 3096//3096 -f 3095//3095 3096//3096 3097//3097 -f 3097//3097 3096//3096 3098//3098 -f 3097//3097 3098//3098 3099//3099 -f 3100//3100 3101//3101 3102//3102 -f 3103//3103 3102//3102 2169//2169 -f 3104//3104 3103//3103 3105//3105 -f 3104//3104 3105//3105 3106//3106 -f 3102//3102 3103//3103 3104//3104 -f 3102//3102 3104//3104 3100//3100 -f 3100//3100 3104//3104 3107//3107 -f 3107//3107 3104//3104 3106//3106 -f 3108//3108 3109//3109 3110//3110 -f 3111//3111 3109//3109 3112//3112 -f 3112//3112 3109//3109 3108//3108 -f 3112//3112 3108//3108 3113//3113 -f 3114//3114 3111//3111 3115//3115 -f 3115//3115 3111//3111 3112//3112 -f 3115//3115 3112//3112 3113//3113 -f 3102//3102 3113//3113 3116//3116 -f 3117//3117 3108//3108 3118//3118 -f 3118//3118 3108//3108 3119//3119 -f 3118//3118 3119//3119 3120//3120 -f 3111//3111 3121//3121 3122//3122 -f 3122//3122 3121//3121 3123//3123 -f 3122//3122 3123//3123 3124//3124 -f 3124//3124 3123//3123 3125//3125 -f 3124//3124 3125//3125 3126//3126 -f 3126//3126 3125//3125 3127//3127 -f 3126//3126 3127//3127 3128//3128 -f 3128//3128 3127//3127 3129//3129 -f 3130//3130 3131//3131 3132//3132 -f 3132//3132 3131//3131 3133//3133 -f 3132//3132 3133//3133 3134//3134 -f 2168//2168 3117//3117 2167//2167 -f 2167//2167 3117//3117 3118//3118 -f 2167//2167 3118//3118 2165//2165 -f 2165//2165 3118//3118 3120//3120 -f 2165//2165 3120//3120 2166//2166 -f 3135//3135 3136//3136 3137//3137 -f 3137//3137 3136//3136 3138//3138 -f 3137//3137 3138//3138 3139//3139 -f 3139//3139 3138//3138 3140//3140 -f 3139//3139 3140//3140 3141//3141 -f 3141//3141 3140//3140 3142//3142 -f 3141//3141 3142//3142 3143//3143 -f 3144//3144 3135//3135 3145//3145 -f 3145//3145 3135//3135 3137//3137 -f 3145//3145 3137//3137 3146//3146 -f 3146//3146 3137//3137 3139//3139 -f 3146//3146 3139//3139 3147//3147 -f 3147//3147 3139//3139 3141//3141 -f 3147//3147 3141//3141 3148//3148 -f 3148//3148 3141//3141 3143//3143 -f 3148//3148 3143//3143 3149//3149 -f 3150//3150 3111//3111 3107//3107 -f 3107//3107 3111//3111 3114//3114 -f 3107//3107 3114//3114 3100//3100 -f 3100//3100 3114//3114 3115//3115 -f 3100//3100 3115//3115 3101//3101 -f 3101//3101 3115//3115 3113//3113 -f 3101//3101 3113//3113 3102//3102 -f 2169//2169 3102//3102 3116//3116 -f 2169//2169 3116//3116 2168//2168 -f 2168//2168 3116//3116 3113//3113 -f 2168//2168 3113//3113 3117//3117 -f 3117//3117 3113//3113 3108//3108 -f 3108//3108 3110//3110 3119//3119 -f 3151//3151 3152//3152 3153//3153 -f 3153//3153 3152//3152 3154//3154 -f 3130//3130 3155//3155 3131//3131 -f 3131//3131 3155//3155 3156//3156 -f 3131//3131 3156//3156 3133//3133 -f 3133//3133 3156//3156 3157//3157 -f 3133//3133 3157//3157 3134//3134 -f 3134//3134 3157//3157 3158//3158 -f 2163//2163 2162//2162 3159//3159 -f 3159//3159 2162//2162 3160//3160 -f 3159//3159 3160//3160 3161//3161 -f 3162//3162 3163//3163 3164//3164 -f 3164//3164 3163//3163 3155//3155 -f 3164//3164 3155//3155 3135//3135 -f 3135//3135 3155//3155 3130//3130 -f 3135//3135 3130//3130 3136//3136 -f 3136//3136 3130//3130 3132//3132 -f 3136//3136 3132//3132 3138//3138 -f 3138//3138 3132//3132 3134//3134 -f 3138//3138 3134//3134 3140//3140 -f 3140//3140 3134//3134 3158//3158 -f 3140//3140 3158//3158 3142//3142 -f 3165//3165 3166//3166 3167//3167 -f 3167//3167 3166//3166 3168//3168 -f 3167//3167 3168//3168 3169//3169 -f 3169//3169 3168//3168 3170//3170 -f 3169//3169 3170//3170 3171//3171 -f 3166//3166 3172//3172 3168//3168 -f 3168//3168 3172//3172 3173//3173 -f 3168//3168 3173//3173 3170//3170 -f 3170//3170 3173//3173 3174//3174 -f 3170//3170 3174//3174 3171//3171 -f 3171//3171 3174//3174 3175//3175 -f 3165//3165 3176//3176 3166//3166 -f 3166//3166 3176//3176 3177//3177 -f 3166//3166 3177//3177 3172//3172 -f 3172//3172 3177//3177 3178//3178 -f 3172//3172 3178//3178 3173//3173 -f 3173//3173 3178//3178 3179//3179 -f 3173//3173 3179//3179 3174//3174 -f 3174//3174 3179//3179 3180//3180 -f 3174//3174 3180//3180 3175//3175 -f 3181//3181 3182//3182 3183//3183 -f 3183//3183 3182//3182 3184//3184 -f 3183//3183 3184//3184 2153//2153 -f 2154//2154 3185//3185 3186//3186 -f 3186//3186 3185//3185 3187//3187 -f 3186//3186 3187//3187 3188//3188 -f 3189//3189 3190//3190 2161//2161 -f 2161//2161 3190//3190 3191//3191 -f 2161//2161 3191//3191 2159//2159 -f 2159//2159 3191//3191 3192//3192 -f 3193//3193 3194//3194 3195//3195 -f 3195//3195 3194//3194 3196//3196 -f 2154//2154 2153//2153 3185//3185 -f 3185//3185 2153//2153 3184//3184 -f 3185//3185 3184//3184 3187//3187 -f 3187//3187 3184//3184 3182//3182 -f 3187//3187 3182//3182 3188//3188 -f 3177//3177 3197//3197 3178//3178 -f 3178//3178 3197//3197 3198//3198 -f 3178//3178 3198//3198 3179//3179 -f 3179//3179 3198//3198 3199//3199 -f 3179//3179 3199//3199 3180//3180 -f 3180//3180 3199//3199 3153//3153 -f 3180//3180 3153//3153 3175//3175 -f 3175//3175 3153//3153 3154//3154 -f 3175//3175 3154//3154 3171//3171 -f 3171//3171 3154//3154 3161//3161 -f 3171//3171 3161//3161 3169//3169 -f 3169//3169 3161//3161 3160//3160 -f 3169//3169 3160//3160 3167//3167 -f 3167//3167 3160//3160 2162//2162 -f 3167//3167 2162//2162 3165//3165 -f 3165//3165 2162//2162 2164//2164 -f 3165//3165 2164//2164 3176//3176 -f 2151//2151 2150//2150 3200//3200 -f 3200//3200 2150//2150 3201//3201 -f 3200//3200 3201//3201 3202//3202 -f 3193//3193 3162//3162 3194//3194 -f 3194//3194 3162//3162 2152//2152 -f 3194//3194 2152//2152 3203//3203 -f 3203//3203 2152//2152 2151//2151 -f 3203//3203 2151//2151 3204//3204 -f 3204//3204 2151//2151 3200//3200 -f 3204//3204 3200//3200 3205//3205 -f 3205//3205 3200//3200 3202//3202 -f 3205//3205 3202//3202 3206//3206 -f 3206//3206 3207//3207 3205//3205 -f 3205//3205 3207//3207 3208//3208 -f 3205//3205 3208//3208 3204//3204 -f 3204//3204 3208//3208 2158//2158 -f 3204//3204 2158//2158 3203//3203 -f 3203//3203 2158//2158 2157//2157 -f 3203//3203 2157//2157 3194//3194 -f 3194//3194 2157//2157 2156//2156 -f 3194//3194 2156//2156 3196//3196 -f 2144//2144 2146//2146 3209//3209 -f 3210//3210 3211//3211 3212//3212 -f 3212//3212 3211//3211 3213//3213 -f 3212//3212 3213//3213 3214//3214 -f 3214//3214 3213//3213 3215//3215 -f 3214//3214 3215//3215 3216//3216 -f 3216//3216 3215//3215 3217//3217 -f 2142//2142 2141//2141 3218//3218 -f 3218//3218 2141//2141 3219//3219 -f 3218//3218 3219//3219 2149//2149 -f 3220//3220 3221//3221 3222//3222 -f 3222//3222 3221//3221 3223//3223 -f 3222//3222 3223//3223 3224//3224 -f 2143//2143 3217//3217 2141//2141 -f 2141//2141 3217//3217 3215//3215 -f 2141//2141 3215//3215 3219//3219 -f 3219//3219 3215//3215 3213//3213 -f 3219//3219 3213//3213 2149//2149 -f 2149//2149 3213//3213 3211//3211 -f 2149//2149 3211//3211 2147//2147 -f 3225//3225 3209//3209 3226//3226 -f 3226//3226 3209//3209 2146//2146 -f 3226//3226 2146//2146 3227//3227 -f 3227//3227 2146//2146 3228//3228 -f 3227//3227 3228//3228 2111//2111 -f 3225//3225 3229//3229 3209//3209 -f 3209//3209 3229//3229 3230//3230 -f 3209//3209 3230//3230 2144//2144 -f 2144//2144 3230//3230 3231//3231 -f 2144//2144 3231//3231 2145//2145 -f 2145//2145 3231//3231 3221//3221 -f 2145//2145 3221//3221 2146//2146 -f 2146//2146 3221//3221 3220//3220 -f 2146//2146 3220//3220 3228//3228 -f 3232//3232 3233//3233 3234//3234 -f 3234//3234 3233//3233 3235//3235 -f 3236//3236 3237//3237 3238//3238 -f 3238//3238 3237//3237 3239//3239 -f 3238//3238 3239//3239 3240//3240 -f 3241//3241 3242//3242 3243//3243 -f 3243//3243 3242//3242 3244//3244 -f 3243//3243 3244//3244 3245//3245 -f 2140//2140 2139//2139 3232//3232 -f 3232//3232 2139//2139 3246//3246 -f 3232//3232 3246//3246 3233//3233 -f 3247//3247 3235//3235 3248//3248 -f 3248//3248 3235//3235 3233//3233 -f 3248//3248 3233//3233 3249//3249 -f 3249//3249 3233//3233 3246//3246 -f 3250//3250 3251//3251 2135//2135 -f 3251//3251 3250//3250 3252//3252 -f 2135//2135 2137//2137 3250//3250 -f 3250//3250 2137//2137 3253//3253 -f 3250//3250 3253//3253 3252//3252 -f 3252//3252 3253//3253 3254//3254 -f 3252//3252 3254//3254 3255//3255 -f 3247//3247 3236//3236 3235//3235 -f 3235//3235 3236//3236 3238//3238 -f 3235//3235 3238//3238 3234//3234 -f 3234//3234 3238//3238 3240//3240 -f 3234//3234 3240//3240 3232//3232 -f 3232//3232 3240//3240 3241//3241 -f 3232//3232 3241//3241 2140//2140 -f 2140//2140 3241//3241 3243//3243 -f 2140//2140 3243//3243 2138//2138 -f 2138//2138 3243//3243 3245//3245 -f 2137//2137 3256//3256 3253//3253 -f 3253//3253 3256//3256 3257//3257 -f 3253//3253 3257//3257 3258//3258 -f 3259//3259 3260//3260 3261//3261 -f 3261//3261 3260//3260 3262//3262 -f 3229//3229 3210//3210 3230//3230 -f 3230//3230 3210//3210 3212//3212 -f 3230//3230 3212//3212 3231//3231 -f 3231//3231 3212//3212 3214//3214 -f 3231//3231 3214//3214 3221//3221 -f 3221//3221 3214//3214 3216//3216 -f 3221//3221 3216//3216 3223//3223 -f 3223//3223 3216//3216 3217//3217 -f 3223//3223 3217//3217 3224//3224 -f 3224//3224 3217//3217 2143//2143 -f 3224//3224 2143//2143 3263//3263 -f 3263//3263 2143//2143 2142//2142 -f 3263//3263 2142//2142 3262//3262 -f 3262//3262 2142//2142 3218//3218 -f 3262//3262 3218//3218 3261//3261 -f 3261//3261 3218//3218 2149//2149 -f 3261//3261 2149//2149 3264//3264 -f 3264//3264 2149//2149 2148//2148 -f 3264//3264 2148//2148 3265//3265 -f 3206//3206 3266//3266 3207//3207 -f 3207//3207 3266//3266 3267//3267 -f 3207//3207 3267//3267 3208//3208 -f 3208//3208 3267//3267 3268//3268 -f 3208//3208 3268//3268 2158//2158 -f 2158//2158 3268//3268 3269//3269 -f 2158//2158 3269//3269 2156//2156 -f 2156//2156 3269//3269 3270//3270 -f 2156//2156 3270//3270 3196//3196 -f 3271//3271 3272//3272 3189//3189 -f 3189//3189 3272//3272 3273//3273 -f 3189//3189 3273//3273 3190//3190 -f 3190//3190 3273//3273 2155//2155 -f 3190//3190 2155//2155 3191//3191 -f 3191//3191 2155//2155 2154//2154 -f 3191//3191 2154//2154 3192//3192 -f 3192//3192 2154//2154 3186//3186 -f 3192//3192 3186//3186 2159//2159 -f 2159//2159 3186//3186 3188//3188 -f 2159//2159 3188//3188 2160//2160 -f 3177//3177 3181//3181 3197//3197 -f 3197//3197 3181//3181 3183//3183 -f 3197//3197 3183//3183 3198//3198 -f 3198//3198 3183//3183 2153//2153 -f 3198//3198 2153//2153 3199//3199 -f 3199//3199 2153//2153 2155//2155 -f 3199//3199 2155//2155 3153//3153 -f 3153//3153 2155//2155 3273//3273 -f 3153//3153 3273//3273 3274//3274 -f 3274//3274 3273//3273 3275//3275 -f 2111//2111 3228//3228 2112//2112 -f 2112//2112 3228//3228 3276//3276 -f 2112//2112 3276//3276 3277//3277 -f 3091//3091 3278//3278 3089//3089 -f 3089//3089 3278//3278 3099//3099 -f 3089//3089 3099//3099 2350//2350 -f 2350//2350 3099//3099 3098//3098 -f 2350//2350 3098//3098 2348//2348 -f 2348//2348 3098//3098 3096//3096 -f 2348//2348 3096//3096 3279//3279 -f 3279//3279 3096//3096 3094//3094 -f 3279//3279 3094//3094 2355//2355 -f 2355//2355 3094//3094 3093//3093 -f 2355//2355 3093//3093 2353//2353 -f 3280//3280 3281//3281 3282//3282 -f 3283//3283 3284//3284 3285//3285 -f 3285//3285 3284//3284 3286//3286 -f 3285//3285 3286//3286 3287//3287 -f 3287//3287 3286//3286 3288//3288 -f 3287//3287 3288//3288 3289//3289 -f 2136//2136 3283//3283 2137//2137 -f 2137//2137 3283//3283 3285//3285 -f 2137//2137 3285//3285 3256//3256 -f 3256//3256 3285//3285 3287//3287 -f 3256//3256 3287//3287 3257//3257 -f 3257//3257 3287//3287 3289//3289 -f 3257//3257 3289//3289 3258//3258 -f 3290//3290 3291//3291 3292//3292 -f 3292//3292 3291//3291 3293//3293 -f 3292//3292 3293//3293 3294//3294 -f 3294//3294 3293//3293 3295//3295 -f 3294//3294 3295//3295 3296//3296 -f 3281//3281 3280//3280 3297//3297 -f 3297//3297 3280//3280 3259//3259 -f 3297//3297 3259//3259 3290//3290 -f 2135//2135 3282//3282 2136//2136 -f 2136//2136 3282//3282 3281//3281 -f 2136//2136 3281//3281 3283//3283 -f 3283//3283 3281//3281 3297//3297 -f 3283//3283 3297//3297 3284//3284 -f 3284//3284 3297//3297 3290//3290 -f 3284//3284 3290//3290 3286//3286 -f 3286//3286 3290//3290 3292//3292 -f 3286//3286 3292//3292 3288//3288 -f 3288//3288 3292//3292 3294//3294 -f 3288//3288 3294//3294 3289//3289 -f 3289//3289 3294//3294 3296//3296 -f 3289//3289 3296//3296 3258//3258 -f 3258//3258 3296//3296 3277//3277 -f 3258//3258 3277//3277 3253//3253 -f 3253//3253 3277//3277 3276//3276 -f 3253//3253 3276//3276 3254//3254 -f 3254//3254 3276//3276 3248//3248 -f 3254//3254 3248//3248 3255//3255 -f 3255//3255 3248//3248 3249//3249 -f 3255//3255 3249//3249 3252//3252 -f 3252//3252 3249//3249 3246//3246 -f 3252//3252 3246//3246 3251//3251 -f 3251//3251 3246//3246 2139//2139 -f 3251//3251 2139//2139 2135//2135 -f 2135//2135 2139//2139 2138//2138 -f 2135//2135 2138//2138 3282//3282 -f 3282//3282 2138//2138 3245//3245 -f 3282//3282 3245//3245 3280//3280 -f 3280//3280 3245//3245 3244//3244 -f 3280//3280 3244//3244 3259//3259 -f 3259//3259 3244//3244 3242//3242 -f 3259//3259 3242//3242 3260//3260 -f 3260//3260 3242//3242 3241//3241 -f 3260//3260 3241//3241 3262//3262 -f 3262//3262 3241//3241 3240//3240 -f 3262//3262 3240//3240 3263//3263 -f 3263//3263 3240//3240 3239//3239 -f 3263//3263 3239//3239 3224//3224 -f 3224//3224 3239//3239 3237//3237 -f 3224//3224 3237//3237 3222//3222 -f 3222//3222 3237//3237 3236//3236 -f 3222//3222 3236//3236 3220//3220 -f 3220//3220 3236//3236 3247//3247 -f 3220//3220 3247//3247 3228//3228 -f 3228//3228 3247//3247 3248//3248 -f 3228//3228 3248//3248 3276//3276 -f 3298//3298 3299//3299 3300//3300 -f 3300//3300 3299//3299 3301//3301 -f 3300//3300 3301//3301 3302//3302 -f 3302//3302 3301//3301 3303//3303 -f 3302//3302 3303//3303 3304//3304 -f 3305//3305 3306//3306 3307//3307 -f 3307//3307 3306//3306 2132//2132 -f 3307//3307 2132//2132 3308//3308 -f 3308//3308 2132//2132 2134//2134 -f 3309//3309 3310//3310 3311//3311 -f 3311//3311 3310//3310 3304//3304 -f 3312//3312 3313//3313 2131//2131 -f 2130//2130 3314//3314 2131//2131 -f 2131//2131 3314//3314 3315//3315 -f 2131//2131 3315//3315 3312//3312 -f 3316//3316 3317//3317 3318//3318 -f 3319//3319 3316//3316 3320//3320 -f 3320//3320 3316//3316 3318//3318 -f 3320//3320 3318//3318 3321//3321 -f 3321//3321 3318//3318 3322//3322 -f 3323//3323 3324//3324 3325//3325 -f 2127//2127 2126//2126 3326//3326 -f 3326//3326 2126//2126 3327//3327 -f 3326//3326 3327//3327 3325//3325 -f 3325//3325 3324//3324 3326//3326 -f 3326//3326 3324//3324 3328//3328 -f 3326//3326 3328//3328 2127//2127 -f 2127//2127 3328//3328 3329//3329 -f 2127//2127 3329//3329 2128//2128 -f 3330//3330 3331//3331 3332//3332 -f 3332//3332 3331//3331 3333//3333 -f 3332//3332 3333//3333 3334//3334 -f 2134//2134 2129//2129 3308//3308 -f 3308//3308 2129//2129 2131//2131 -f 3308//3308 2131//2131 3307//3307 -f 3307//3307 2131//2131 3313//3313 -f 3307//3307 3313//3313 3305//3305 -f 3305//3305 3313//3313 3312//3312 -f 3305//3305 3312//3312 3335//3335 -f 3335//3335 3312//3312 3315//3315 -f 3335//3335 3315//3315 3336//3336 -f 3336//3336 3315//3315 3337//3337 -f 3323//3323 3322//3322 3324//3324 -f 3324//3324 3322//3322 3318//3318 -f 3324//3324 3318//3318 3328//3328 -f 3328//3328 3318//3318 3317//3317 -f 3328//3328 3317//3317 3329//3329 -f 3329//3329 3317//3317 3316//3316 -f 3329//3329 3316//3316 3309//3309 -f 3309//3309 3316//3316 3319//3319 -f 3309//3309 3319//3319 3310//3310 -f 2181//2181 2971//2971 2182//2182 -f 2182//2182 2971//2971 2973//2973 -f 2182//2182 2973//2973 2955//2955 -f 2955//2955 2973//2973 2974//2974 -f 2955//2955 2974//2974 2956//2956 -f 2956//2956 2974//2974 3338//3338 -f 2956//2956 3338//3338 2957//2957 -f 2957//2957 3338//3338 2962//2962 -f 2957//2957 2962//2962 2958//2958 -f 2958//2958 2962//2962 2961//2961 -f 2958//2958 2961//2961 2959//2959 -f 2959//2959 2961//2961 2950//2950 -f 2959//2959 2950//2950 2960//2960 -f 2960//2960 2950//2950 2948//2948 -f 2960//2960 2948//2948 2945//2945 -f 2945//2945 2948//2948 2946//2946 -f 2945//2945 2946//2946 2200//2200 -f 2200//2200 2946//2946 2196//2196 -f 2200//2200 2196//2196 2201//2201 -f 2201//2201 2196//2196 2198//2198 -f 2201//2201 2198//2198 2904//2904 -f 2904//2904 2198//2198 2704//2704 -f 2904//2904 2704//2704 2905//2905 -f 2905//2905 2704//2704 2703//2703 -f 2905//2905 2703//2703 3068//3068 -f 3068//3068 2703//2703 2702//2702 -f 3068//3068 2702//2702 3069//3069 -f 3069//3069 2702//2702 2351//2351 -f 3069//3069 2351//2351 3106//3106 -f 3106//3106 2351//2351 2353//2353 -f 3106//3106 2353//2353 3107//3107 -f 3107//3107 2353//2353 3093//3093 -f 3107//3107 3093//3093 3150//3150 -f 3150//3150 3093//3093 3095//3095 -f 3150//3150 3095//3095 3265//3265 -f 3265//3265 3095//3095 3097//3097 -f 3265//3265 3097//3097 3264//3264 -f 3264//3264 3097//3097 3099//3099 -f 3264//3264 3099//3099 3261//3261 -f 3261//3261 3099//3099 3278//3278 -f 3261//3261 3278//3278 3259//3259 -f 3339//3339 3340//3340 3341//3341 -f 3341//3341 3340//3340 3342//3342 -f 3341//3341 3342//3342 3343//3343 -f 3343//3343 3342//3342 3344//3344 -f 3345//3345 3346//3346 3347//3347 -f 3348//3348 3346//3346 3349//3349 -f 3349//3349 3346//3346 3345//3345 -f 3349//3349 3345//3345 3350//3350 -f 3351//3351 3352//3352 3353//3353 -f 3354//3354 3355//3355 3356//3356 -f 3356//3356 3355//3355 3357//3357 -f 3358//3358 3359//3359 3360//3360 -f 3352//3352 3357//3357 3353//3353 -f 3353//3353 3357//3357 3355//3355 -f 3353//3353 3355//3355 3361//3361 -f 3361//3361 3355//3355 3354//3354 -f 3330//3330 3362//3362 3363//3363 -f 3363//3363 3362//3362 3348//3348 -f 3364//3364 3365//3365 3366//3366 -f 3367//3367 3368//3368 3369//3369 -f 3370//3370 3371//3371 3366//3366 -f 3366//3366 3371//3371 3372//3372 -f 3366//3366 3372//3372 3373//3373 -f 3365//3365 3374//3374 3366//3366 -f 3366//3366 3374//3374 3375//3375 -f 3366//3366 3375//3375 3370//3370 -f 3370//3370 3375//3375 3376//3376 -f 3377//3377 3378//3378 3379//3379 -f 3379//3379 3378//3378 3380//3380 -f 3379//3379 3380//3380 3381//3381 -f 3381//3381 3380//3380 2123//2123 -f 3381//3381 2123//2123 3382//3382 -f 3382//3382 2123//2123 2125//2125 -f 3336//3336 3383//3383 3335//3335 -f 3335//3335 3383//3383 3298//3298 -f 3335//3335 3298//3298 3305//3305 -f 3305//3305 3298//3298 3300//3300 -f 3305//3305 3300//3300 3306//3306 -f 3306//3306 3300//3300 3302//3302 -f 3306//3306 3302//3302 2132//2132 -f 2132//2132 3302//3302 3304//3304 -f 2132//2132 3304//3304 2133//2133 -f 2133//2133 3304//3304 3310//3310 -f 2133//2133 3310//3310 2134//2134 -f 2134//2134 3310//3310 3319//3319 -f 2134//2134 3319//3319 2129//2129 -f 2129//2129 3319//3319 3320//3320 -f 2129//2129 3320//3320 2130//2130 -f 2130//2130 3320//3320 3321//3321 -f 2130//2130 3321//3321 3314//3314 -f 3314//3314 3321//3321 3322//3322 -f 3314//3314 3322//3322 3315//3315 -f 3315//3315 3322//3322 3323//3323 -f 3315//3315 3323//3323 3337//3337 -f 3337//3337 3323//3323 3325//3325 -f 3337//3337 3325//3325 3336//3336 -f 3384//3384 3347//3347 3339//3339 -f 3339//3339 3347//3347 3346//3346 -f 3339//3339 3346//3346 3340//3340 -f 3340//3340 3346//3346 3348//3348 -f 3340//3340 3348//3348 3342//3342 -f 3342//3342 3348//3348 3362//3362 -f 3342//3342 3362//3362 3344//3344 -f 3344//3344 3362//3362 3330//3330 -f 3344//3344 3330//3330 3343//3343 -f 3343//3343 3330//3330 3332//3332 -f 3343//3343 3332//3332 3341//3341 -f 3341//3341 3332//3332 3334//3334 -f 3341//3341 3334//3334 3339//3339 -f 3339//3339 3334//3334 3384//3384 -f 3385//3385 3386//3386 3387//3387 -f 3387//3387 3386//3386 3388//3388 -f 3388//3388 3389//3389 3387//3387 -f 3387//3387 3389//3389 3390//3390 -f 3387//3387 3390//3390 3385//3385 -f 3385//3385 3391//3391 3386//3386 -f 3386//3386 3391//3391 3392//3392 -f 3386//3386 3392//3392 3393//3393 -f 3393//3393 3392//3392 3394//3394 -f 3393//3393 3394//3394 3395//3395 -f 3396//3396 3397//3397 3398//3398 -f 3399//3399 3398//3398 3400//3400 -f 3400//3400 3398//3398 3397//3397 -f 3400//3400 3397//3397 3401//3401 -f 3401//3401 2121//2121 3400//3400 -f 3400//3400 2121//2121 2120//2120 -f 3400//3400 2120//2120 3399//3399 -f 3399//3399 2120//2120 3402//3402 -f 3399//3399 3402//3402 3403//3403 -f 3404//3404 3405//3405 3406//3406 -f 3406//3406 3405//3405 3407//3407 -f 3408//3408 3409//3409 3407//3407 -f 3407//3407 3409//3409 3410//3410 -f 3407//3407 3410//3410 3406//3406 -f 3406//3406 3410//3410 3411//3411 -f 3412//3412 3358//3358 2125//2125 -f 2125//2125 3358//3358 3360//3360 -f 2125//2125 3360//3360 3382//3382 -f 3382//3382 3360//3360 3413//3413 -f 3382//3382 3413//3413 3381//3381 -f 3381//3381 3413//3413 3414//3414 -f 3381//3381 3414//3414 3379//3379 -f 3379//3379 3414//3414 3371//3371 -f 3379//3379 3371//3371 3377//3377 -f 3411//3411 3415//3415 3406//3406 -f 3406//3406 3415//3415 3416//3416 -f 3406//3406 3416//3416 3404//3404 -f 3361//3361 3350//3350 3353//3353 -f 3353//3353 3350//3350 3345//3345 -f 3353//3353 3345//3345 3351//3351 -f 3351//3351 3345//3345 3347//3347 -f 3351//3351 3347//3347 3417//3417 -f 3417//3417 3347//3347 3384//3384 -f 3417//3417 3384//3384 2128//2128 -f 2128//2128 3384//3384 3334//3334 -f 2128//2128 3334//3334 2126//2126 -f 2126//2126 3334//3334 3333//3333 -f 2126//2126 3333//3333 3327//3327 -f 3327//3327 3333//3333 3331//3331 -f 3327//3327 3331//3331 3325//3325 -f 3325//3325 3331//3331 3330//3330 -f 3325//3325 3330//3330 3336//3336 -f 3336//3336 3330//3330 3363//3363 -f 3336//3336 3363//3363 3383//3383 -f 3383//3383 3363//3363 3418//3418 -f 3383//3383 3418//3418 3419//3419 -f 3367//3367 3420//3420 3368//3368 -f 3368//3368 3420//3420 3421//3421 -f 3368//3368 3421//3421 3369//3369 -f 3369//3369 3421//3421 3422//3422 -f 3423//3423 3424//3424 3376//3376 -f 3376//3376 3424//3424 3420//3420 -f 3376//3376 3420//3420 3370//3370 -f 3370//3370 3420//3420 3367//3367 -f 3370//3370 3367//3367 3371//3371 -f 3371//3371 3367//3367 3369//3369 -f 3371//3371 3369//3369 3377//3377 -f 3377//3377 3369//3369 3422//3422 -f 3377//3377 3422//3422 3378//3378 -f 2124//2124 2123//2123 3389//3389 -f 3389//3389 2123//2123 3380//3380 -f 3389//3389 3380//3380 3390//3390 -f 3390//3390 3380//3380 3378//3378 -f 3390//3390 3378//3378 3385//3385 -f 3385//3385 3378//3378 3422//3422 -f 3385//3385 3422//3422 3391//3391 -f 3391//3391 3422//3422 3421//3421 -f 3391//3391 3421//3421 3392//3392 -f 3392//3392 3421//3421 3420//3420 -f 3392//3392 3420//3420 3394//3394 -f 3394//3394 3420//3420 3424//3424 -f 3394//3394 3424//3424 3395//3395 -f 3425//3425 3426//3426 3427//3427 -f 3427//3427 3426//3426 3428//3428 -f 3427//3427 3428//3428 3429//3429 -f 3430//3430 3431//3431 3432//3432 -f 3432//3432 3431//3431 3433//3433 -f 2122//2122 3425//3425 2120//2120 -f 2120//2120 3425//3425 3427//3427 -f 2120//2120 3427//3427 3402//3402 -f 3402//3402 3427//3427 3429//3429 -f 3402//3402 3429//3429 3403//3403 -f 3403//3403 3429//3429 3411//3411 -f 3403//3403 3411//3411 3399//3399 -f 3399//3399 3411//3411 3410//3410 -f 3399//3399 3410//3410 3398//3398 -f 3398//3398 3410//3410 3409//3409 -f 3398//3398 3409//3409 3396//3396 -f 3396//3396 3409//3409 3408//3408 -f 3434//3434 3435//3435 3436//3436 -f 3436//3436 3435//3435 3423//3423 -f 3436//3436 3423//3423 3437//3437 -f 3438//3438 3439//3439 3440//3440 -f 3440//3440 3439//3439 3430//3430 -f 3440//3440 3430//3430 3434//3434 -f 3434//3434 3430//3430 3432//3432 -f 3434//3434 3432//3432 3435//3435 -f 3435//3435 3432//3432 3433//3433 -f 3435//3435 3433//3433 3423//3423 -f 3441//3441 3442//3442 2117//2117 -f 2117//2117 3442//3442 3443//3443 -f 2117//2117 3443//3443 2118//2118 -f 3444//3444 3445//3445 3446//3446 -f 3446//3446 3445//3445 3447//3447 -f 3448//3448 3449//3449 3450//3450 -f 3441//3441 2117//2117 3451//3451 -f 3451//3451 2117//2117 2119//2119 -f 3451//3451 2119//2119 3452//3452 -f 2115//2115 2114//2114 3453//3453 -f 3443//3443 3448//3448 2118//2118 -f 2118//2118 3448//3448 3450//3450 -f 2118//2118 3450//3450 2119//2119 -f 2119//2119 3450//3450 3453//3453 -f 2119//2119 3453//3453 3452//3452 -f 3452//3452 3453//3453 2114//2114 -f 3452//3452 2114//2114 3451//3451 -f 3454//3454 3455//3455 3456//3456 -f 3456//3456 3455//3455 3457//3457 -f 3456//3456 3457//3457 3458//3458 -f 3438//3438 3459//3459 3454//3454 -f 3454//3454 3459//3459 3460//3460 -f 3454//3454 3460//3460 3455//3455 -f 3455//3455 3460//3460 3461//3461 -f 3455//3455 3461//3461 3457//3457 -f 3457//3457 3461//3461 3462//3462 -f 3457//3457 3462//3462 3458//3458 -f 2104//2104 3463//3463 2105//2105 -f 2105//2105 3463//3463 3464//3464 -f 2105//2105 3464//3464 3465//3465 -f 3465//3465 3464//3464 3437//3437 -f 3466//3466 3467//3467 3458//3458 -f 3458//3458 3467//3467 3468//3468 -f 3458//3458 3468//3468 3456//3456 -f 3456//3456 3468//3468 3444//3444 -f 3456//3456 3444//3444 3454//3454 -f 3454//3454 3444//3444 3446//3446 -f 3454//3454 3446//3446 3438//3438 -f 3438//3438 3446//3446 3447//3447 -f 3438//3438 3447//3447 3439//3439 -f 3439//3439 3447//3447 3445//3445 -f 3439//3439 3445//3445 3430//3430 -f 3430//3430 3445//3445 3469//3469 -f 3430//3430 3469//3469 3431//3431 -f 2340//2340 2433//2433 2341//2341 -f 2341//2341 2433//2433 2432//2432 -f 2341//2341 2432//2432 3470//3470 -f 3470//3470 2432//2432 2431//2431 -f 3470//3470 2431//2431 2253//2253 -f 2253//2253 2431//2431 2430//2430 -f 2253//2253 2430//2430 2254//2254 -f 2254//2254 2430//2430 2429//2429 -f 2254//2254 2429//2429 2434//2434 -f 2434//2434 2429//2429 2427//2427 -f 2434//2434 2427//2427 2436//2436 -f 2436//2436 2427//2427 2504//2504 -f 2436//2436 2504//2504 2438//2438 -f 2438//2438 2504//2504 2521//2521 -f 2438//2438 2521//2521 2439//2439 -f 2439//2439 2521//2521 2534//2534 -f 3471//3471 2110//2110 3472//3472 -f 3472//3472 2110//2110 2108//2108 -f 3472//3472 2108//2108 3473//3473 -f 3473//3473 2108//2108 2107//2107 -f 3473//3473 2107//2107 3474//3474 -f 3474//3474 2107//2107 3475//3475 -f 3474//3474 3475//3475 3476//3476 -f 3423//3423 3376//3376 3437//3437 -f 3437//3437 3376//3376 3477//3477 -f 3437//3437 3477//3477 3465//3465 -f 3465//3465 3477//3477 3478//3478 -f 3465//3465 3478//3478 2105//2105 -f 2105//2105 3478//3478 3479//3479 -f 2105//2105 3479//3479 2106//2106 -f 3480//3480 3481//3481 3482//3482 -f 3088//3088 3471//3471 3090//3090 -f 3090//3090 3471//3471 3472//3472 -f 3090//3090 3472//3472 3092//3092 -f 3092//3092 3472//3472 3473//3473 -f 3092//3092 3473//3473 3483//3483 -f 3483//3483 3473//3473 3474//3474 -f 3483//3483 3474//3474 3484//3484 -f 3484//3484 3474//3474 3476//3476 -f 3484//3484 3476//3476 3485//3485 -f 2107//2107 3486//3486 3475//3475 -f 3475//3475 3486//3486 3487//3487 -f 3475//3475 3487//3487 3476//3476 -f 3476//3476 3487//3487 3488//3488 -f 3476//3476 3488//3488 3485//3485 -f 3485//3485 3488//3488 3489//3489 -f 3485//3485 3489//3489 3490//3490 -f 3490//3490 3489//3489 3491//3491 -f 2349//2349 3492//3492 2350//2350 -f 2350//2350 3492//3492 3493//3493 -f 2350//2350 3493//3493 3088//3088 -f 3088//3088 3493//3493 3494//3494 -f 3088//3088 3494//3494 3471//3471 -f 3471//3471 3494//3494 3495//3495 -f 3471//3471 3495//3495 2110//2110 -f 2110//2110 3495//3495 2344//2344 -f 2110//2110 2344//2344 2109//2109 -f 2109//2109 2344//2344 2343//2343 -f 2109//2109 2343//2343 2107//2107 -f 2107//2107 2343//2343 2341//2341 -f 2107//2107 2341//2341 3486//3486 -f 3486//3486 2341//2341 3470//3470 -f 3486//3486 3470//3470 3487//3487 -f 3487//3487 3470//3470 2253//2253 -f 3487//3487 2253//2253 3488//3488 -f 3488//3488 2253//2253 2252//2252 -f 3488//3488 2252//2252 3489//3489 -f 3489//3489 2252//2252 2250//2250 -f 3489//3489 2250//2250 3491//3491 -f 3491//3491 2250//2250 2249//2249 -f 2545//2545 3496//3496 2547//2547 -f 2547//2547 3496//3496 3497//3497 -f 2547//2547 3497//3497 2549//2549 -f 2549//2549 3497//3497 3498//3498 -f 2549//2549 3498//3498 2550//2550 -f 2550//2550 3498//3498 3499//3499 -f 2550//2550 3499//3499 2683//2683 -f 2683//2683 3499//3499 3500//3500 -f 2683//2683 3500//3500 2684//2684 -f 2684//2684 3500//3500 3501//3501 -f 2684//2684 3501//3501 2689//2689 -f 2689//2689 3501//3501 3502//3502 -f 2689//2689 3502//3502 3503//3503 -f 3496//3496 2690//2690 3497//3497 -f 3497//3497 2690//2690 2691//2691 -f 3497//3497 2691//2691 3498//3498 -f 3498//3498 2691//2691 2692//2692 -f 3498//3498 2692//2692 3499//3499 -f 3499//3499 2692//2692 2697//2697 -f 3499//3499 2697//2697 3500//3500 -f 3500//3500 2697//2697 2698//2698 -f 3500//3500 2698//2698 3501//3501 -f 3501//3501 2698//2698 3504//3504 -f 3501//3501 3504//3504 3502//3502 -f 3502//3502 3504//3504 3505//3505 -f 3502//3502 3505//3505 3503//3503 -f 3503//3503 3505//3505 3506//3506 -f 3503//3503 3506//3506 3507//3507 -f 2285//2285 2284//2284 2701//2701 -f 2701//2701 2284//2284 2708//2708 -f 2701//2701 2708//2708 2700//2700 -f 2700//2700 2708//2708 2236//2236 -f 2700//2700 2236//2236 2699//2699 -f 2699//2699 2236//2236 2238//2238 -f 2699//2699 2238//2238 2698//2698 -f 2698//2698 2238//2238 2239//2239 -f 2698//2698 2239//2239 3504//3504 -f 3504//3504 2239//2239 2705//2705 -f 3504//3504 2705//2705 3505//3505 -f 3505//3505 2705//2705 3087//3087 -f 3505//3505 3087//3087 3506//3506 -f 3506//3506 3087//3087 3508//3508 -f 3506//3506 3508//3508 3507//3507 -f 3509//3509 3510//3510 3511//3511 -f 3512//3512 2685//2685 3513//3513 -f 3513//3513 2685//2685 2686//2686 -f 3513//3513 2686//2686 3514//3514 -f 3514//3514 2686//2686 2687//2687 -f 3514//3514 2687//2687 3515//3515 -f 3515//3515 2687//2687 2688//2688 -f 3515//3515 2688//2688 3516//3516 -f 3516//3516 2688//2688 2689//2689 -f 3516//3516 2689//2689 3517//3517 -f 3517//3517 2689//2689 3503//3503 -f 3517//3517 3503//3503 3518//3518 -f 3518//3518 3503//3503 3507//3507 -f 3511//3511 3510//3510 3519//3519 -f 3519//3519 3510//3510 3520//3520 -f 3519//3519 3520//3520 3521//3521 -f 3521//3521 3520//3520 3522//3522 -f 3521//3521 3522//3522 3523//3523 -f 3524//3524 3525//3525 3526//3526 -f 3526//3526 3525//3525 2682//2682 -f 3526//3526 2682//2682 3527//3527 -f 3527//3527 2682//2682 2681//2681 -f 3527//3527 2681//2681 3528//3528 -f 3528//3528 2681//2681 2680//2680 -f 3528//3528 2680//2680 3529//3529 -f 3529//3529 2680//2680 2650//2650 -f 3529//3529 2650//2650 3530//3530 -f 3530//3530 2650//2650 2649//2649 -f 3530//3530 2649//2649 3531//3531 -f 3532//3532 2102//2102 3533//3533 -f 3533//3533 2102//2102 2101//2101 -f 3533//3533 2101//2101 3534//3534 -f 3535//3535 3536//3536 3533//3533 -f 3533//3533 3536//3536 3537//3537 -f 3533//3533 3537//3537 3532//3532 -f 3535//3535 3533//3533 3538//3538 -f 3538//3538 3533//3533 3534//3534 -f 3538//3538 3534//3534 3539//3539 -f 3539//3539 3534//3534 3540//3540 -f 3539//3539 3540//3540 3541//3541 -f 3542//3542 3535//3535 3543//3543 -f 3543//3543 3535//3535 3538//3538 -f 3543//3543 3538//3538 3544//3544 -f 3544//3544 3538//3538 3539//3539 -f 3544//3544 3539//3539 3545//3545 -f 3545//3545 3539//3539 3541//3541 -f 3545//3545 3541//3541 3546//3546 -f 3546//3546 3541//3541 3547//3547 -f 3546//3546 3547//3547 2100//2100 -f 3508//3508 3509//3509 3507//3507 -f 3507//3507 3509//3509 3511//3511 -f 3507//3507 3511//3511 3518//3518 -f 3518//3518 3511//3511 3519//3519 -f 3518//3518 3519//3519 3548//3548 -f 3548//3548 3519//3519 3521//3521 -f 3548//3548 3521//3521 3549//3549 -f 3549//3549 3521//3521 3523//3523 -f 3549//3549 3523//3523 3550//3550 -f 2600//2600 3531//3531 2601//2601 -f 2601//2601 3531//3531 2649//2649 -f 2601//2601 2649//2649 2602//2602 -f 2602//2602 2649//2649 2241//2241 -f 2602//2602 2241//2241 2651//2651 -f 2651//2651 2241//2241 2240//2240 -f 2651//2651 2240//2240 2674//2674 -f 2674//2674 2240//2240 2669//2669 -f 2674//2674 2669//2669 2675//2675 -f 2675//2675 2669//2669 2671//2671 -f 2675//2675 2671//2671 3551//3551 -f 3551//3551 2671//2671 2673//2673 -f 3551//3551 2673//2673 3552//3552 -f 3552//3552 2673//2673 2682//2682 -f 3552//3552 2682//2682 3553//3553 -f 3553//3553 2682//2682 3525//3525 -f 2598//2598 3512//3512 2599//2599 -f 2599//2599 3512//3512 3513//3513 -f 2599//2599 3513//3513 2600//2600 -f 2600//2600 3513//3513 3514//3514 -f 2600//2600 3514//3514 3531//3531 -f 3531//3531 3514//3514 3515//3515 -f 3531//3531 3515//3515 3530//3530 -f 3530//3530 3515//3515 3516//3516 -f 3530//3530 3516//3516 3529//3529 -f 3529//3529 3516//3516 3517//3517 -f 3529//3529 3517//3517 3528//3528 -f 3528//3528 3517//3517 3518//3518 -f 3528//3528 3518//3518 3527//3527 -f 3527//3527 3518//3518 3548//3548 -f 3527//3527 3548//3548 3526//3526 -f 3526//3526 3548//3548 3549//3549 -f 3526//3526 3549//3549 3524//3524 -f 3524//3524 3549//3549 3550//3550 -f 2100//2100 2099//2099 3546//3546 -f 3546//3546 2099//2099 2367//2367 -f 3546//3546 2367//2367 3545//3545 -f 3545//3545 2367//2367 2359//2359 -f 3545//3545 2359//2359 3544//3544 -f 3544//3544 2359//2359 2358//2358 -f 3544//3544 2358//2358 3543//3543 -f 3543//3543 2358//2358 2357//2357 -f 3543//3543 2357//2357 3542//3542 -f 3542//3542 2357//2357 2356//2356 -f 3542//3542 2356//2356 2360//2360 -f 2360//2360 2356//2356 2066//2066 -f 2360//2360 2066//2066 2065//2065 -f 3085//3085 2967//2967 3025//3025 -f 3025//3025 2967//2967 3031//3031 -f 3025//3025 3031//3031 3026//3026 -f 3026//3026 3031//3031 3554//3554 -f 3026//3026 3554//3554 3555//3555 -f 3555//3555 3554//3554 3556//3556 -f 3555//3555 3556//3556 3557//3557 -f 3557//3557 3556//3556 3558//3558 -f 3557//3557 3558//3558 3559//3559 -f 3559//3559 3558//3558 3560//3560 -f 3559//3559 3560//3560 2083//2083 -f 2083//2083 3560//3560 2084//2084 -f 3111//3111 3122//3122 3109//3109 -f 3109//3109 3122//3122 3124//3124 -f 3109//3109 3124//3124 3110//3110 -f 3110//3110 3124//3124 3126//3126 -f 3110//3110 3126//3126 3119//3119 -f 3119//3119 3126//3126 3128//3128 -f 3119//3119 3128//3128 3120//3120 -f 3120//3120 3128//3128 3129//3129 -f 3120//3120 3129//3129 2166//2166 -f 2166//2166 3129//3129 3151//3151 -f 2166//2166 3151//3151 3561//3561 -f 3561//3561 3151//3151 3153//3153 -f 3561//3561 3153//3153 3562//3562 -f 3562//3562 3153//3153 3274//3274 -f 3562//3562 3274//3274 3563//3563 -f 3563//3563 3274//3274 3275//3275 -f 3563//3563 3275//3275 3564//3564 -f 3311//3311 3565//3565 3309//3309 -f 3309//3309 3565//3565 3375//3375 -f 3309//3309 3375//3375 3329//3329 -f 3329//3329 3375//3375 3374//3374 -f 3329//3329 3374//3374 2128//2128 -f 2128//2128 3374//3374 3365//3365 -f 2128//2128 3365//3365 3417//3417 -f 3417//3417 3365//3365 3364//3364 -f 3417//3417 3364//3364 3351//3351 -f 3351//3351 3364//3364 3366//3366 -f 3351//3351 3366//3366 3352//3352 -f 3352//3352 3366//3366 3373//3373 -f 3352//3352 3373//3373 3357//3357 -f 3357//3357 3373//3373 3372//3372 -f 3357//3357 3372//3372 3356//3356 -f 3356//3356 3372//3372 3371//3371 -f 3356//3356 3371//3371 3354//3354 -f 3354//3354 3371//3371 3414//3414 -f 3354//3354 3414//3414 3361//3361 -f 3361//3361 3414//3414 3413//3413 -f 3361//3361 3413//3413 3350//3350 -f 3350//3350 3413//3413 3360//3360 -f 3350//3350 3360//3360 3349//3349 -f 3349//3349 3360//3360 3359//3359 -f 3349//3349 3359//3359 3348//3348 -f 3348//3348 3359//3359 3358//3358 -f 3348//3348 3358//3358 3363//3363 -f 3363//3363 3358//3358 3412//3412 -f 3363//3363 3412//3412 3418//3418 -f 3418//3418 3412//3412 3566//3566 -f 3418//3418 3566//3566 3419//3419 -f 3419//3419 3566//3566 3567//3567 -f 3419//3419 3567//3567 3568//3568 -f 3067//3067 3063//3063 3019//3019 -f 3019//3019 3063//3063 3062//3062 -f 3019//3019 3062//3062 3020//3020 -f 3020//3020 3062//3062 3569//3569 -f 3020//3020 3569//3569 3570//3570 -f 3570//3570 3569//3569 3571//3571 -f 3570//3570 3571//3571 3572//3572 -f 3572//3572 3571//3571 3573//3573 -f 3572//3572 3573//3573 3574//3574 -f 3574//3574 3573//3573 3575//3575 -f 3574//3574 3575//3575 3576//3576 -f 3576//3576 3575//3575 3577//3577 -f 3576//3576 3577//3577 2085//2085 -f 2085//2085 3577//3577 2059//2059 -f 3490//3490 2106//2106 3485//3485 -f 3485//3485 2106//2106 3479//3479 -f 3485//3485 3479//3479 3484//3484 -f 3484//3484 3479//3479 3478//3478 -f 3484//3484 3478//3478 3483//3483 -f 3483//3483 3478//3478 3477//3477 -f 3483//3483 3477//3477 3092//3092 -f 3092//3092 3477//3477 3376//3376 -f 3092//3092 3376//3376 3091//3091 -f 3091//3091 3376//3376 3375//3375 -f 3091//3091 3375//3375 3278//3278 -f 3278//3278 3375//3375 3565//3565 -f 3278//3278 3565//3565 3259//3259 -f 3259//3259 3565//3565 3311//3311 -f 3259//3259 3311//3311 3290//3290 -f 3290//3290 3311//3311 3304//3304 -f 3290//3290 3304//3304 3291//3291 -f 3291//3291 3304//3304 3303//3303 -f 3291//3291 3303//3303 3293//3293 -f 3293//3293 3303//3303 3301//3301 -f 3293//3293 3301//3301 3295//3295 -f 3295//3295 3301//3301 3299//3299 -f 3295//3295 3299//3299 3296//3296 -f 3296//3296 3299//3299 3298//3298 -f 3296//3296 3298//3298 3277//3277 -f 3277//3277 3298//3298 3383//3383 -f 3277//3277 3383//3383 2112//2112 -f 2112//2112 3383//3383 3419//3419 -f 2112//2112 3419//3419 2113//2113 -f 2113//2113 3419//3419 3568//3568 -f 2113//2113 3568//3568 3578//3578 -f 3578//3578 3568//3568 3579//3579 -f 3578//3578 3579//3579 3580//3580 -f 3580//3580 3579//3579 3581//3581 -f 3582//3582 3581//3581 3583//3583 -f 3583//3583 3581//3581 3579//3579 -f 3583//3583 3579//3579 3584//3584 -f 3584//3584 3579//3579 3568//3568 -f 3584//3584 3568//3568 3585//3585 -f 3585//3585 3568//3568 3567//3567 -f 3075//3075 2171//2171 3076//3076 -f 3076//3076 2171//2171 2170//2170 -f 3076//3076 2170//2170 3084//3084 -f 3084//3084 2170//2170 3073//3073 -f 3084//3084 3073//3073 3083//3083 -f 3083//3083 3073//3073 3074//3074 -f 3083//3083 3074//3074 3082//3082 -f 3082//3082 3074//3074 3072//3072 -f 3082//3082 3072//3072 3081//3081 -f 3081//3081 3072//3072 3071//3071 -f 3081//3081 3071//3071 3069//3069 -f 3081//3081 3069//3069 3080//3080 -f 3080//3080 3069//3069 3106//3106 -f 3080//3080 3106//3106 3079//3079 -f 3079//3079 3106//3106 3105//3105 -f 3079//3079 3105//3105 3103//3103 -f 3079//3079 3103//3103 3077//3077 -f 3077//3077 3103//3103 3075//3075 -f 3075//3075 3103//3103 2169//2169 -f 3075//3075 2169//2169 2171//2171 -f 2171//2171 2169//2169 2167//2167 -f 2171//2171 2167//2167 2172//2172 -f 2172//2172 2167//2167 2166//2166 -f 2172//2172 2166//2166 3586//3586 -f 3586//3586 2166//2166 3561//3561 -f 3586//3586 3561//3561 3587//3587 -f 3587//3587 3561//3561 3562//3562 -f 3587//3587 3562//3562 3588//3588 -f 3588//3588 3562//3562 3563//3563 -f 3588//3588 3563//3563 3589//3589 -f 3589//3589 3563//3563 3564//3564 -f 3589//3589 3564//3564 3590//3590 -f 3590//3590 3564//3564 3591//3591 -f 3590//3590 3591//3591 2266//2266 -f 2266//2266 3591//3591 3592//3592 -f 2266//2266 3592//3592 2070//2070 -f 2070//2070 3592//3592 2071//2071 -f 3593//3593 3594//3594 3595//3595 -f 3595//3595 3594//3594 3596//3596 -f 3595//3595 3596//3596 3597//3597 -f 3597//3597 3596//3596 3598//3598 -f 3597//3597 3598//3598 3599//3599 -f 3599//3599 3598//3598 3600//3600 -f 3599//3599 3600//3600 3467//3467 -f 3462//3462 3601//3601 3458//3458 -f 3458//3458 3601//3601 3602//3602 -f 3458//3458 3602//3602 3466//3466 -f 3466//3466 3602//3602 3482//3482 -f 3466//3466 3482//3482 3467//3467 -f 3467//3467 3482//3482 3481//3481 -f 3467//3467 3481//3481 3599//3599 -f 3599//3599 3481//3481 3480//3480 -f 3599//3599 3480//3480 3597//3597 -f 3597//3597 3480//3480 3603//3603 -f 3597//3597 3603//3603 3595//3595 -f 3595//3595 3603//3603 2446//2446 -f 3595//3595 2446//2446 3593//3593 -f 3593//3593 2446//2446 2444//2444 -f 3593//3593 2444//2444 3604//3604 -f 3604//3604 2444//2444 2442//2442 -f 3605//3605 3606//3606 3607//3607 -f 3607//3607 3606//3606 3608//3608 -f 3607//3607 3608//3608 3609//3609 -f 3609//3609 3608//3608 3610//3610 -f 3609//3609 3610//3610 3611//3611 -f 3611//3611 3610//3610 3612//3612 -f 3611//3611 3612//3612 3613//3613 -f 3604//3604 3605//3605 3593//3593 -f 3593//3593 3605//3605 3607//3607 -f 3593//3593 3607//3607 3594//3594 -f 3594//3594 3607//3607 3609//3609 -f 3594//3594 3609//3609 3596//3596 -f 3596//3596 3609//3609 3611//3611 -f 3596//3596 3611//3611 3598//3598 -f 3598//3598 3611//3611 3613//3613 -f 3598//3598 3613//3613 3600//3600 -f 3614//3614 3612//3612 3615//3615 -f 3615//3615 3612//3612 3610//3610 -f 3615//3615 3610//3610 3616//3616 -f 3616//3616 3610//3610 3608//3608 -f 3616//3616 3608//3608 3617//3617 -f 3617//3617 3608//3608 3606//3606 -f 3617//3617 3606//3606 3618//3618 -f 3618//3618 3606//3606 3605//3605 -f 3618//3618 3605//3605 3619//3619 -f 3619//3619 3605//3605 3604//3604 -f 3619//3619 3604//3604 3620//3620 -f 3620//3620 3604//3604 2442//2442 -f 3620//3620 2442//2442 3621//3621 -f 3621//3621 2442//2442 2441//2441 -f 3621//3621 2441//2441 3622//3622 -f 3032//3032 3024//3024 3033//3033 -f 3033//3033 3024//3024 3023//3023 -f 3033//3033 3023//3023 3029//3029 -f 3029//3029 3023//3023 3008//3008 -f 3029//3029 3008//3008 3030//3030 -f 3030//3030 3008//3008 3010//3010 -f 3030//3030 3010//3010 3031//3031 -f 3031//3031 3010//3010 3020//3020 -f 3031//3031 3020//3020 3554//3554 -f 3554//3554 3020//3020 3570//3570 -f 3554//3554 3570//3570 3556//3556 -f 3556//3556 3570//3570 3572//3572 -f 3556//3556 3572//3572 3558//3558 -f 3558//3558 3572//3572 3574//3574 -f 3558//3558 3574//3574 3560//3560 -f 3560//3560 3574//3574 3576//3576 -f 3560//3560 3576//3576 2084//2084 -f 2084//2084 3576//3576 2085//2085 -f 2072//2072 3582//3582 2366//2366 -f 2366//2366 3582//3582 3583//3583 -f 2366//2366 3583//3583 3614//3614 -f 3614//3614 3583//3583 3584//3584 -f 3614//3614 3584//3584 3612//3612 -f 3612//3612 3584//3584 3585//3585 -f 3612//3612 3585//3585 3613//3613 -f 3613//3613 3585//3585 3567//3567 -f 3613//3613 3567//3567 3600//3600 -f 3600//3600 3567//3567 3566//3566 -f 3600//3600 3566//3566 3467//3467 -f 3467//3467 3566//3566 3416//3416 -f 3467//3467 3416//3416 3468//3468 -f 3468//3468 3416//3416 3415//3415 -f 3468//3468 3415//3415 3444//3444 -f 3444//3444 3415//3415 3411//3411 -f 3444//3444 3411//3411 3445//3445 -f 3445//3445 3411//3411 3429//3429 -f 3445//3445 3429//3429 3469//3469 -f 3469//3469 3429//3429 3428//3428 -f 3469//3469 3428//3428 3431//3431 -f 3431//3431 3428//3428 3426//3426 -f 3431//3431 3426//3426 3433//3433 -f 3433//3433 3426//3426 3425//3425 -f 3433//3433 3425//3425 3423//3423 -f 3423//3423 3425//3425 2122//2122 -f 3423//3423 2122//2122 3424//3424 -f 3424//3424 2122//2122 2121//2121 -f 3424//3424 2121//2121 3395//3395 -f 3395//3395 2121//2121 3401//3401 -f 3395//3395 3401//3401 3393//3393 -f 3393//3393 3401//3401 3397//3397 -f 3393//3393 3397//3397 3386//3386 -f 3386//3386 3397//3397 3396//3396 -f 3386//3386 3396//3396 3388//3388 -f 3388//3388 3396//3396 3408//3408 -f 3388//3388 3408//3408 3389//3389 -f 3389//3389 3408//3408 3407//3407 -f 3389//3389 3407//3407 2124//2124 -f 2124//2124 3407//3407 3405//3405 -f 2124//2124 3405//3405 2125//2125 -f 2125//2125 3405//3405 3404//3404 -f 2125//2125 3404//3404 3412//3412 -f 3412//3412 3404//3404 3416//3416 -f 3412//3412 3416//3416 3566//3566 -f 3266//3266 3271//3271 3267//3267 -f 3267//3267 3271//3271 3189//3189 -f 3267//3267 3189//3189 3268//3268 -f 3268//3268 3189//3189 2161//2161 -f 3268//3268 2161//2161 3269//3269 -f 3269//3269 2161//2161 2160//2160 -f 3269//3269 2160//2160 3270//3270 -f 3270//3270 2160//2160 3188//3188 -f 3270//3270 3188//3188 3196//3196 -f 3196//3196 3188//3188 3182//3182 -f 3196//3196 3182//3182 3195//3195 -f 3195//3195 3182//3182 3181//3181 -f 3195//3195 3181//3181 3193//3193 -f 3193//3193 3181//3181 3177//3177 -f 3193//3193 3177//3177 3162//3162 -f 3162//3162 3177//3177 3176//3176 -f 3162//3162 3176//3176 3163//3163 -f 3163//3163 3176//3176 2164//2164 -f 3163//3163 2164//2164 3155//3155 -f 3155//3155 2164//2164 2163//2163 -f 3155//3155 2163//2163 3156//3156 -f 3156//3156 2163//2163 3159//3159 -f 3156//3156 3159//3159 3157//3157 -f 3157//3157 3159//3159 3161//3161 -f 3157//3157 3161//3161 3158//3158 -f 3158//3158 3161//3161 3154//3154 -f 3158//3158 3154//3154 3142//3142 -f 3142//3142 3154//3154 3152//3152 -f 3142//3142 3152//3152 3143//3143 -f 3143//3143 3152//3152 3151//3151 -f 3143//3143 3151//3151 3149//3149 -f 3149//3149 3151//3151 3129//3129 -f 3149//3149 3129//3129 3148//3148 -f 3148//3148 3129//3129 3127//3127 -f 3148//3148 3127//3127 3147//3147 -f 3147//3147 3127//3127 3125//3125 -f 3147//3147 3125//3125 3146//3146 -f 3146//3146 3125//3125 3123//3123 -f 3146//3146 3123//3123 3145//3145 -f 3145//3145 3123//3123 3121//3121 -f 3145//3145 3121//3121 3144//3144 -f 3144//3144 3121//3121 3111//3111 -f 3144//3144 3111//3111 3135//3135 -f 3135//3135 3111//3111 3150//3150 -f 3135//3135 3150//3150 3164//3164 -f 3164//3164 3150//3150 3265//3265 -f 3164//3164 3265//3265 3162//3162 -f 3162//3162 3265//3265 2148//2148 -f 3162//3162 2148//2148 2152//2152 -f 2152//2152 2148//2148 2147//2147 -f 2152//2152 2147//2147 2150//2150 -f 2150//2150 2147//2147 3211//3211 -f 2150//2150 3211//3211 3201//3201 -f 3201//3201 3211//3211 3210//3210 -f 3201//3201 3210//3210 3202//3202 -f 3202//3202 3210//3210 3229//3229 -f 3202//3202 3229//3229 3206//3206 -f 3206//3206 3229//3229 3225//3225 -f 3206//3206 3225//3225 3266//3266 -f 3266//3266 3225//3225 3226//3226 -f 3266//3266 3226//3226 3271//3271 -f 3271//3271 3226//3226 3227//3227 -f 3271//3271 3227//3227 3272//3272 -f 3272//3272 3227//3227 2111//2111 -f 3272//3272 2111//2111 3273//3273 -f 3273//3273 2111//2111 2113//2113 -f 3273//3273 2113//2113 3275//3275 -f 3275//3275 2113//2113 3578//3578 -f 3275//3275 3578//3578 3564//3564 -f 3564//3564 3578//3578 3580//3580 -f 3564//3564 3580//3580 3591//3591 -f 3591//3591 3580//3580 3581//3581 -f 3591//3591 3581//3581 3592//3592 -f 3592//3592 3581//3581 3582//3582 -f 3592//3592 3582//3582 2071//2071 -f 2071//2071 3582//3582 2072//2072 -f 2789//2789 3623//3623 2219//2219 -f 2219//2219 3623//3623 2878//2878 -f 2219//2219 2878//2878 2217//2217 -f 2217//2217 2878//2878 2877//2877 -f 2217//2217 2877//2877 2805//2805 -f 2805//2805 2877//2877 2876//2876 -f 2805//2805 2876//2876 2804//2804 -f 2804//2804 2876//2876 2228//2228 -f 2804//2804 2228//2228 2788//2788 -f 2788//2788 2228//2228 2226//2226 -f 2788//2788 2226//2226 3624//3624 -f 3624//3624 2226//2226 2225//2225 -f 3624//3624 2225//2225 2867//2867 -f 2867//2867 2225//2225 2871//2871 -f 2867//2867 2871//2871 2865//2865 -f 2865//2865 2871//2871 2872//2872 -f 2865//2865 2872//2872 2873//2873 -f 2873//2873 2872//2872 2879//2879 -f 2873//2873 2879//2879 2874//2874 -f 2874//2874 2879//2879 2878//2878 -f 2874//2874 2878//2878 2875//2875 -f 2875//2875 2878//2878 3623//3623 -f 2875//2875 3623//3623 2892//2892 -f 2892//2892 3623//3623 2789//2789 -f 2892//2892 2789//2789 2884//2884 -f 2884//2884 2789//2789 2862//2862 -f 2884//2884 2862//2862 3086//3086 -f 3086//3086 2862//2862 2857//2857 -f 3086//3086 2857//2857 2969//2969 -f 2969//2969 2857//2857 2204//2204 -f 2969//2969 2204//2204 2970//2970 -f 2970//2970 2204//2204 2855//2855 -f 2970//2970 2855//2855 2889//2889 -f 2889//2889 2855//2855 2852//2852 -f 2889//2889 2852//2852 2890//2890 -f 2890//2890 2852//2852 2851//2851 -f 2890//2890 2851//2851 2891//2891 -f 2891//2891 2851//2851 2924//2924 -f 2891//2891 2924//2924 2833//2833 -f 2833//2833 2924//2924 2923//2923 -f 2833//2833 2923//2923 2831//2831 -f 2831//2831 2923//2923 2922//2922 -f 2831//2831 2922//2922 2834//2834 -f 2834//2834 2922//2922 2921//2921 -f 2834//2834 2921//2921 2935//2935 -f 2935//2935 2921//2921 2920//2920 -f 2935//2935 2920//2920 2933//2933 -f 2933//2933 2920//2920 2919//2919 -f 2933//2933 2919//2919 2932//2932 -f 2932//2932 2919//2919 2910//2910 -f 2932//2932 2910//2910 2930//2930 -f 2930//2930 2910//2910 2909//2909 -f 2930//2930 2909//2909 2929//2929 -f 2929//2929 2909//2909 2907//2907 -f 2929//2929 2907//2907 2928//2928 -f 2928//2928 2907//2907 2197//2197 -f 2928//2928 2197//2197 2927//2927 -f 2927//2927 2197//2197 2196//2196 -f 2927//2927 2196//2196 2925//2925 -f 2925//2925 2196//2196 2947//2947 -f 2925//2925 2947//2947 2926//2926 -f 2926//2926 2947//2947 2949//2949 -f 2926//2926 2949//2949 2915//2915 -f 2915//2915 2949//2949 2194//2194 -f 2915//2915 2194//2194 2913//2913 -f 2913//2913 2194//2194 2193//2193 -f 2913//2913 2193//2193 2911//2911 -f 2911//2911 2193//2193 2952//2952 -f 2911//2911 2952//2952 3085//3085 -f 3085//3085 2952//2952 2951//2951 -f 3085//3085 2951//2951 2967//2967 -f 2967//2967 2951//2951 2954//2954 -f 2967//2967 2954//2954 2963//2963 -f 2963//2963 2954//2954 2962//2962 -f 2963//2963 2962//2962 2192//2192 -f 2192//2192 2962//2962 3338//3338 -f 2192//2192 3338//3338 2190//2190 -f 2190//2190 3338//3338 2974//2974 -f 2190//2190 2974//2974 3032//3032 -f 3032//3032 2974//2974 2972//2972 -f 3032//3032 2972//2972 3024//3024 -f 3024//3024 2972//2972 2971//2971 -f 3024//3024 2971//2971 2987//2987 -f 2987//2987 2971//2971 2181//2181 -f 2987//2987 2181//2181 2985//2985 -f 2985//2985 2181//2181 2183//2183 -f 2985//2985 2183//2183 2983//2983 -f 2983//2983 2183//2183 2982//2982 -f 2983//2983 2982//2982 2993//2993 -f 2993//2993 2982//2982 2980//2980 -f 2993//2993 2980//2980 2997//2997 -f 2997//2997 2980//2980 2981//2981 -f 2997//2997 2981//2981 3022//3022 -f 3022//3022 2981//2981 2975//2975 -f 3022//3022 2975//2975 3021//3021 -f 3021//3021 2975//2975 2977//2977 -f 3021//3021 2977//2977 2188//2188 -f 2188//2188 2977//2977 3039//3039 -f 2188//2188 3039//3039 2189//2189 -f 2189//2189 3039//3039 2176//2176 -f 2189//2189 2176//2176 3066//3066 -f 3066//3066 2176//2176 2178//2178 -f 3066//3066 2178//2178 3067//3067 -f 3067//3067 2178//2178 3047//3047 -f 3067//3067 3047//3047 3063//3063 -f 3063//3063 3047//3047 3048//3048 -f 3063//3063 3048//3048 3055//3055 -f 3055//3055 3048//3048 3045//3045 -f 3055//3055 3045//3045 3054//3054 -f 3054//3054 3045//3045 3044//3044 -f 3054//3054 3044//3044 3053//3053 -f 3053//3053 3044//3044 3042//3042 -f 3053//3053 3042//3042 3051//3051 -f 3051//3051 3042//3042 2979//2979 -f 3051//3051 2979//2979 3049//3049 -f 3049//3049 2979//2979 3036//3036 -f 3049//3049 3036//3036 3065//3065 -f 3065//3065 3036//3036 3037//3037 -f 3065//3065 3037//3037 3064//3064 -f 3064//3064 3037//3037 2173//2173 -f 3064//3064 2173//2173 3061//3061 -f 3061//3061 2173//2173 2175//2175 -f 3061//3061 2175//2175 3060//3060 -f 3060//3060 2175//2175 2170//2170 -f 3060//3060 2170//2170 3058//3058 -f 3058//3058 2170//2170 2172//2172 -f 3058//3058 2172//2172 3062//3062 -f 3062//3062 2172//2172 3586//3586 -f 3062//3062 3586//3586 3569//3569 -f 3569//3569 3586//3586 3587//3587 -f 3569//3569 3587//3587 3571//3571 -f 3571//3571 3587//3587 3588//3588 -f 3571//3571 3588//3588 3573//3573 -f 3573//3573 3588//3588 3589//3589 -f 3573//3573 3589//3589 3575//3575 -f 3575//3575 3589//3589 3590//3590 -f 3575//3575 3590//3590 3577//3577 -f 3577//3577 3590//3590 2266//2266 -f 3577//3577 2266//2266 2059//2059 -f 2059//2059 2266//2266 2060//2060 -f 3625//3625 2362//2362 3626//3626 -f 3626//3626 2362//2362 2363//2363 -f 3626//3626 2363//2363 3627//3627 -f 3627//3627 2363//2363 2364//2364 -f 3627//3627 2364//2364 3628//3628 -f 3628//3628 2364//2364 2365//2365 -f 3628//3628 3629//3629 3627//3627 -f 3627//3627 3629//3629 3630//3630 -f 3627//3627 3630//3630 3626//3626 -f 3626//3626 3630//3630 3631//3631 -f 3626//3626 3631//3631 3625//3625 -f 3625//3625 3631//3631 3632//3632 -f 3625//3625 3632//3632 3633//3633 -f 3633//3633 3632//3632 3634//3634 -f 3633//3633 3634//3634 3635//3635 -f 3635//3635 3634//3634 3636//3636 -f 3635//3635 3636//3636 3637//3637 -f 3637//3637 3636//3636 3638//3638 -f 3637//3637 3638//3638 3639//3639 -f 3639//3639 3638//3638 3640//3640 -f 3639//3639 3640//3640 3641//3641 -f 3641//3641 3640//3640 3642//3642 -f 3641//3641 3642//3642 3643//3643 -f 2074//2074 2073//2073 2365//2365 -f 2365//2365 2073//2073 2366//2366 -f 2365//2365 2366//2366 3628//3628 -f 3628//3628 2366//2366 3614//3614 -f 3628//3628 3614//3614 3629//3629 -f 3629//3629 3614//3614 3615//3615 -f 3629//3629 3615//3615 3630//3630 -f 3630//3630 3615//3615 3616//3616 -f 3630//3630 3616//3616 3631//3631 -f 3631//3631 3616//3616 3617//3617 -f 3631//3631 3617//3617 3632//3632 -f 3632//3632 3617//3617 3618//3618 -f 3632//3632 3618//3618 3634//3634 -f 3634//3634 3618//3618 3619//3619 -f 3634//3634 3619//3619 3636//3636 -f 3636//3636 3619//3619 3620//3620 -f 3636//3636 3620//3620 3638//3638 -f 3638//3638 3620//3620 3621//3621 -f 3638//3638 3621//3621 3640//3640 -f 3640//3640 3621//3621 3622//3622 -f 3640//3640 3622//3622 3642//3642 -f 2562//2562 3643//3643 2534//2534 -f 2534//2534 3643//3643 3642//3642 -f 2534//2534 3642//3642 2439//2439 -f 2439//2439 3642//3642 3622//3622 -f 2439//2439 3622//3622 2437//2437 -f 2437//2437 3622//3622 2441//2441 -f 2437//2437 2441//2441 2435//2435 -f 2435//2435 2441//2441 2443//2443 -f 2435//2435 2443//2443 2251//2251 -f 2251//2251 2443//2443 2445//2445 -f 2251//2251 2445//2445 2249//2249 -f 2249//2249 2445//2445 2446//2446 -f 2249//2249 2446//2446 3491//3491 -f 3491//3491 2446//2446 3603//3603 -f 3491//3491 3603//3603 3490//3490 -f 3490//3490 3603//3603 3480//3480 -f 3490//3490 3480//3480 2106//2106 -f 2106//2106 3480//3480 3482//3482 -f 2106//2106 3482//3482 2104//2104 -f 2104//2104 3482//3482 3602//3602 -f 2104//2104 3602//3602 3463//3463 -f 3463//3463 3602//3602 3601//3601 -f 3463//3463 3601//3601 2116//2116 -f 2116//2116 3601//3601 3462//3462 -f 2116//2116 3462//3462 2114//2114 -f 2114//2114 3462//3462 3461//3461 -f 2114//2114 3461//3461 3451//3451 -f 3451//3451 3461//3461 3460//3460 -f 3451//3451 3460//3460 3441//3441 -f 3441//3441 3460//3460 3459//3459 -f 3441//3441 3459//3459 3442//3442 -f 3442//3442 3459//3459 3438//3438 -f 3442//3442 3438//3438 3443//3443 -f 3443//3443 3438//3438 3440//3440 -f 3443//3443 3440//3440 3448//3448 -f 3448//3448 3440//3440 3434//3434 -f 3448//3448 3434//3434 3449//3449 -f 3449//3449 3434//3434 3436//3436 -f 3449//3449 3436//3436 3450//3450 -f 3450//3450 3436//3436 3437//3437 -f 3450//3450 3437//3437 3453//3453 -f 3453//3453 3437//3437 3464//3464 -f 3453//3453 3464//3464 2115//2115 -f 2115//2115 3464//3464 3463//3463 -f 2115//2115 3463//3463 2116//2116 -f 2064//2064 2061//2061 2361//2361 -f 2361//2361 2061//2061 2062//2062 -f 2361//2361 2062//2062 3644//3644 -f 3644//3644 2062//2062 2094//2094 -f 3644//3644 2094//2094 2425//2425 -f 2425//2425 2094//2094 2096//2096 -f 2425//2425 2096//2096 2423//2423 -f 2423//2423 2096//2096 2018//2018 -f 2423//2423 2018//2018 2421//2421 -f 2421//2421 2018//2018 2097//2097 -f 2421//2421 2097//2097 2419//2419 -f 2419//2419 2097//2097 2095//2095 -f 2083//2083 2082//2082 3559//3559 -f 3559//3559 2082//2082 2098//2098 -f 3559//3559 2098//2098 3557//3557 -f 3557//3557 2098//2098 2100//2100 -f 3557//3557 2100//2100 3555//3555 -f 3555//3555 2100//2100 3547//3547 -f 3555//3555 3547//3547 3026//3026 -f 3026//3026 3547//3547 3541//3541 -f 3026//3026 3541//3541 3028//3028 -f 3028//3028 3541//3541 3540//3540 -f 3028//3028 3540//3540 2885//2885 -f 2885//2885 3540//3540 3534//3534 -f 2885//2885 3534//3534 2887//2887 -f 2887//2887 3534//3534 2101//2101 -f 2887//2887 2101//2101 2888//2888 -f 2888//2888 2101//2101 2103//2103 -f 2888//2888 2103//2103 2893//2893 -f 2893//2893 2103//2103 3645//3645 -f 2893//2893 3645//3645 2894//2894 -f 2894//2894 3645//3645 2748//2748 -f 2894//2894 2748//2748 2757//2757 -f 2757//2757 2748//2748 2718//2718 -f 2757//2757 2718//2718 2758//2758 -f 2758//2758 2718//2718 2717//2717 -f 2758//2758 2717//2717 2760//2760 -f 2760//2760 2717//2717 2715//2715 -f 2760//2760 2715//2715 2753//2753 -f 2753//2753 2715//2715 2747//2747 -f 2753//2753 2747//2747 2751//2751 -f 2751//2751 2747//2747 2746//2746 -f 2751//2751 2746//2746 2749//2749 -f 2749//2749 2746//2746 2744//2744 -f 2749//2749 2744//2744 2882//2882 -f 2882//2882 2744//2744 2743//2743 -f 2882//2882 2743//2743 2883//2883 -f 2883//2883 2743//2743 2719//2719 -f 2883//2883 2719//2719 2726//2726 -f 2726//2726 2719//2719 2721//2721 -f 2726//2726 2721//2721 2724//2724 -f 2724//2724 2721//2721 2727//2727 -f 2724//2724 2727//2727 2723//2723 -f 2723//2723 2727//2727 2733//2733 -f 2723//2723 2733//2733 2232//2232 -f 2232//2232 2733//2733 2755//2755 -f 2232//2232 2755//2755 2230//2230 -f 2230//2230 2755//2755 2754//2754 -f 2230//2230 2754//2754 2231//2231 -f 2231//2231 2754//2754 2742//2742 -f 2231//2231 2742//2742 2870//2870 -f 2870//2870 2742//2742 2741//2741 -f 2870//2870 2741//2741 2863//2863 -f 2863//2863 2741//2741 2739//2739 -f 2863//2863 2739//2739 2864//2864 -f 2864//2864 2739//2739 2738//2738 -f 2864//2864 2738//2738 2866//2866 -f 2866//2866 2738//2738 2734//2734 -f 2866//2866 2734//2734 2867//2867 -f 2867//2867 2734//2734 2729//2729 -f 2867//2867 2729//2729 3624//3624 -f 3624//3624 2729//2729 2728//2728 -f 3624//3624 2728//2728 2788//2788 -f 2788//2788 2728//2728 2730//2730 -f 2788//2788 2730//2730 2775//2775 -f 2775//2775 2730//2730 2235//2235 -f 2775//2775 2235//2235 2709//2709 -f 2709//2709 2235//2235 2722//2722 -f 2709//2709 2722//2722 2710//2710 -f 2710//2710 2722//2722 2720//2720 -f 2710//2710 2720//2720 2712//2712 -f 2712//2712 2720//2720 2748//2748 -f 2712//2712 2748//2748 2713//2713 -f 2713//2713 2748//2748 3645//3645 -f 2713//2713 3645//3645 3087//3087 -f 3087//3087 3645//3645 2103//2103 -f 3087//3087 2103//2103 3508//3508 -f 3508//3508 2103//2103 2102//2102 -f 3508//3508 2102//2102 3509//3509 -f 3509//3509 2102//2102 3532//3532 -f 3509//3509 3532//3532 3510//3510 -f 3510//3510 3532//3532 3537//3537 -f 3510//3510 3537//3537 3520//3520 -f 3520//3520 3537//3537 3536//3536 -f 3520//3520 3536//3536 3522//3522 -f 3522//3522 3536//3536 3535//3535 -f 3522//3522 3535//3535 3523//3523 -f 3523//3523 3535//3535 3542//3542 -f 3523//3523 3542//3542 3550//3550 -f 3550//3550 3542//3542 2360//2360 -f 3550//3550 2360//2360 3524//3524 -f 3524//3524 2360//2360 2361//2361 -f 3524//3524 2361//2361 3525//3525 -f 3525//3525 2361//2361 3644//3644 -f 3525//3525 3644//3644 3553//3553 -f 3553//3553 3644//3644 2425//2425 -f 3553//3553 2425//2425 3552//3552 -f 3552//3552 2425//2425 2424//2424 -f 3552//3552 2424//2424 3551//3551 -f 3551//3551 2424//2424 2422//2422 -f 3551//3551 2422//2422 2675//2675 -f 2675//2675 2422//2422 2420//2420 -f 2675//2675 2420//2420 2414//2414 -f 2414//2414 2420//2420 2419//2419 -f 2414//2414 2419//2419 2255//2255 -f 2255//2255 2419//2419 2095//2095 -f 2255//2255 2095//2095 2093//2093 -f 2087//2087 2086//2086 2376//2376 -f 2376//2376 2086//2086 2362//2362 -f 2376//2376 2362//2362 2378//2378 -f 2378//2378 2362//2362 3625//3625 -f 2378//2378 3625//3625 2458//2458 -f 2458//2458 3625//3625 3633//3633 -f 2458//2458 3633//3633 2585//2585 -f 2585//2585 3633//3633 3635//3635 -f 2585//2585 3635//3635 2584//2584 -f 2584//2584 3635//3635 3637//3637 -f 2584//2584 3637//3637 2583//2583 -f 2583//2583 3637//3637 3639//3639 -f 2583//2583 3639//3639 2582//2582 -f 2582//2582 3639//3639 3641//3641 -f 2582//2582 3641//3641 2581//2581 -f 2581//2581 3641//3641 3643//3643 -f 2581//2581 3643//3643 2579//2579 -f 2579//2579 3643//3643 2562//2562 -f 2579//2579 2562//2562 2577//2577 -f 2577//2577 2562//2562 2561//2561 -f 2577//2577 2561//2561 2575//2575 -f 2575//2575 2561//2561 2560//2560 -f 2575//2575 2560//2560 2573//2573 -f 2573//2573 2560//2560 2559//2559 -f 2573//2573 2559//2559 2571//2571 -f 2571//2571 2559//2559 2558//2558 -f 2571//2571 2558//2558 2569//2569 -f 2569//2569 2558//2558 2557//2557 -f 2569//2569 2557//2557 2567//2567 -f 2567//2567 2557//2557 2556//2556 -f 2567//2567 2556//2556 2565//2565 -f 2565//2565 2556//2556 2555//2555 -f 2565//2565 2555//2555 2563//2563 -f 2563//2563 2555//2555 2554//2554 -f 2563//2563 2554//2554 2245//2245 -f 2245//2245 2554//2554 2553//2553 -f 2245//2245 2553//2553 2598//2598 -f 2598//2598 2553//2553 2552//2552 -f 2598//2598 2552//2552 3512//3512 -f 3512//3512 2552//2552 2551//2551 -f 3512//3512 2551//2551 2685//2685 -f 2685//2685 2551//2551 2535//2535 -f 2685//2685 2535//2535 2544//2544 -f 2544//2544 2535//2535 2542//2542 -f 2544//2544 2542//2542 2545//2545 -f 2545//2545 2542//2542 2543//2543 -f 2545//2545 2543//2543 3496//3496 -f 3496//3496 2543//2543 2294//2294 -f 3496//3496 2294//2294 2690//2690 -f 2690//2690 2294//2294 2295//2295 -f 2690//2690 2295//2295 2289//2289 -f 2289//2289 2295//2295 3646//3646 -f 2289//2289 3646//3646 2290//2290 -f 3647//3647 3648//3648 3649//3649 -f 3649//3649 3648//3648 2287//2287 -f 3649//3649 2287//2287 3650//3650 -f 3650//3650 2287//2287 3651//3651 -f 3652//3652 3653//3653 3654//3654 -f 3654//3654 3653//3653 2354//2354 -f 3654//3654 2354//2354 3647//3647 -f 3647//3647 2354//2354 3648//3648 -f 3655//3655 3656//3656 3657//3657 -f 3657//3657 3656//3656 2345//2345 -f 3657//3657 2345//2345 3652//3652 -f 3652//3652 2345//2345 3653//3653 -f 2354//2354 3653//3653 2355//2355 -f 2355//2355 3653//3653 3279//3279 -f 3495//3495 3653//3653 2344//2344 -f 2344//2344 3653//3653 2345//2345 -f 3492//3492 2349//2349 3653//3653 -f 3653//3653 2349//2349 2348//2348 -f 3653//3653 2348//2348 3279//3279 -f 3495//3495 3494//3494 3653//3653 -f 3653//3653 3494//3494 3493//3493 -f 3653//3653 3493//3493 3492//3492 -f 2273//2273 3648//3648 2352//2352 -f 2352//2352 3648//3648 2354//2354 -f 3648//3648 2286//2286 2285//2285 -f 2273//2273 2276//2276 3648//3648 -f 3648//3648 2276//2276 2278//2278 -f 3648//3648 2278//2278 2280//2280 -f 2280//2280 2283//2283 3648//3648 -f 3648//3648 2283//2283 2282//2282 -f 3648//3648 2282//2282 2286//2286 -f 3648//3648 2285//2285 2288//2288 -f 3648//3648 2288//2288 2287//2287 -f 2440//2440 3656//3656 2330//2330 -f 2330//2330 3656//3656 2331//2331 -f 2440//2440 2336//2336 3656//3656 -f 3656//3656 2336//2336 2337//2337 -f 3656//3656 2337//2337 2339//2339 -f 2339//2339 2433//2433 3656//3656 -f 3656//3656 2433//2433 2340//2340 -f 3656//3656 2340//2340 2342//2342 -f 2342//2342 2347//2347 3656//3656 -f 3656//3656 2347//2347 2346//2346 -f 3656//3656 2346//2346 2345//2345 -f 2331//2331 3658//3658 2332//2332 -f 2332//2332 3658//3658 2333//2333 -f 2267//2267 3659//3659 2268//2268 -f 2268//2268 3659//3659 2300//2300 -f 2267//2267 2324//2324 3659//3659 -f 3659//3659 2324//2324 2322//2322 -f 3659//3659 2322//2322 2320//2320 -f 2306//2306 2304//2304 3658//3658 -f 3658//3658 2304//2304 2302//2302 -f 3658//3658 2302//2302 2329//2329 -f 2329//2329 2328//2328 3658//3658 -f 3658//3658 2328//2328 2326//2326 -f 3658//3658 2326//2326 2333//2333 -f 2320//2320 2318//2318 3659//3659 -f 3659//3659 2318//2318 2316//2316 -f 3659//3659 2316//2316 2314//2314 -f 2314//2314 2312//2312 3659//3659 -f 3659//3659 2312//2312 2310//2310 -f 3659//3659 2310//2310 3658//3658 -f 3658//3658 2310//2310 2308//2308 -f 3658//3658 2308//2308 2306//2306 -f 3660//3660 3657//3657 3652//3652 -f 3661//3661 3652//3652 3662//3662 -f 3662//3662 3652//3652 3654//3654 -f 3661//3661 3663//3663 3652//3652 -f 3652//3652 3663//3663 3664//3664 -f 3652//3652 3664//3664 3665//3665 -f 3666//3666 3667//3667 3652//3652 -f 3652//3652 3667//3667 3668//3668 -f 3652//3652 3668//3668 3660//3660 -f 3665//3665 3669//3669 3652//3652 -f 3652//3652 3669//3669 3670//3670 -f 3652//3652 3670//3670 3666//3666 -f 3671//3671 3654//3654 3647//3647 -f 3647//3647 3672//3672 3673//3673 -f 3649//3649 3674//3674 3647//3647 -f 3647//3647 3674//3674 3675//3675 -f 3647//3647 3675//3675 3672//3672 -f 3673//3673 3676//3676 3647//3647 -f 3647//3647 3676//3676 3677//3677 -f 3647//3647 3677//3677 3678//3678 -f 3678//3678 3679//3679 3647//3647 -f 3647//3647 3679//3679 3680//3680 -f 3647//3647 3680//3680 3671//3671 -f 3657//3657 3681//3681 3655//3655 -f 3655//3655 3681//3681 3682//3682 -f 3655//3655 3682//3682 3683//3683 -f 3683//3683 3684//3684 3655//3655 -f 3655//3655 3684//3684 3685//3685 -f 3655//3655 3685//3685 3686//3686 -f 3686//3686 3687//3687 3655//3655 -f 3655//3655 3687//3687 3688//3688 -f 3655//3655 3688//3688 3689//3689 -f 3689//3689 3690//3690 3655//3655 -f 3655//3655 3690//3690 3691//3691 -f 3655//3655 3691//3691 3692//3692 -f 3693//3693 3694//3694 3695//3695 -f 3695//3695 3692//3692 3696//3696 -f 3696//3696 3697//3697 3695//3695 -f 3695//3695 3697//3697 3698//3698 -f 3695//3695 3698//3698 3699//3699 -f 3699//3699 3700//3700 3695//3695 -f 3695//3695 3700//3700 3701//3701 -f 3695//3695 3701//3701 3702//3702 -f 3702//3702 3703//3703 3695//3695 -f 3695//3695 3703//3703 3704//3704 -f 3695//3695 3704//3704 3693//3693 -f 3705//3705 3706//3706 3707//3707 -f 3707//3707 3706//3706 3708//3708 -f 3694//3694 3709//3709 3706//3706 -f 3706//3706 3709//3709 3710//3710 -f 3711//3711 3712//3712 3706//3706 -f 3706//3706 3712//3712 3713//3713 -f 3706//3706 3713//3713 3708//3708 -f 3710//3710 3714//3714 3706//3706 -f 3706//3706 3714//3714 3715//3715 -f 3706//3706 3715//3715 3711//3711 -f 3650//3650 3651//3651 3705//3705 -f 3705//3705 3651//3651 2300//2300 -f 3705//3705 2300//2300 3706//3706 -f 3706//3706 2300//2300 3659//3659 -f 3695//3695 3658//3658 3692//3692 -f 3692//3692 3658//3658 2331//2331 -f 3692//3692 2331//2331 3655//3655 -f 3655//3655 2331//2331 3656//3656 -f 3716//3716 3695//3695 3694//3694 -f 3716//3716 3694//3694 3706//3706 -f 3717//3717 3718//3718 3658//3658 -f 3658//3658 3718//3718 3719//3719 -f 3658//3658 3719//3719 3720//3720 -f 3658//3658 3721//3721 3659//3659 -f 3695//3695 3716//3716 3658//3658 -f 3658//3658 3716//3716 3722//3722 -f 3720//3720 3723//3723 3658//3658 -f 3658//3658 3723//3723 3724//3724 -f 3658//3658 3724//3724 3721//3721 -f 3725//3725 3722//3722 3706//3706 -f 3706//3706 3722//3722 3716//3716 -f 3659//3659 3721//3721 3706//3706 -f 3706//3706 3721//3721 3726//3726 -f 3706//3706 3726//3726 3727//3727 -f 3727//3727 3728//3728 3706//3706 -f 3706//3706 3728//3728 3729//3729 -f 3706//3706 3729//3729 3730//3730 -f 3730//3730 3731//3731 3706//3706 -f 3706//3706 3731//3731 3732//3732 -f 3706//3706 3732//3732 3725//3725 -f 3658//3658 3722//3722 3733//3733 -f 3733//3733 3734//3734 3658//3658 -f 3658//3658 3734//3734 3735//3735 -f 3658//3658 3735//3735 3717//3717 -f 2295//2295 2293//2293 3651//3651 -f 3651//3651 2293//2293 2298//2298 -f 3651//3651 2695//2695 2291//2291 -f 2298//2298 2297//2297 3651//3651 -f 3651//3651 2297//2297 2296//2296 -f 3651//3651 2296//2296 2300//2300 -f 2287//2287 2271//2271 3651//3651 -f 3651//3651 2271//2271 2270//2270 -f 3651//3651 2270//2270 2695//2695 -f 2291//2291 2290//2290 3651//3651 -f 3651//3651 2290//2290 3646//3646 -f 3651//3651 3646//3646 2295//2295 -f 3736//3736 3737//3737 3650//3650 -f 3650//3650 3737//3737 3738//3738 -f 3705//3705 3739//3739 3650//3650 -f 3650//3650 3739//3739 3740//3740 -f 3650//3650 3740//3740 3736//3736 -f 3738//3738 3741//3741 3650//3650 -f 3650//3650 3741//3741 3742//3742 -f 3650//3650 3742//3742 3743//3743 -f 3743//3743 3744//3744 3650//3650 -f 3650//3650 3744//3744 3745//3745 -f 3650//3650 3745//3745 3649//3649 -f 3720//3720 3746//3746 3723//3723 -f 3723//3723 3746//3746 3721//3721 -f 3723//3723 3721//3721 3724//3724 -f 3746//3746 3747//3747 3721//3721 -f 3731//3731 3730//3730 3748//3748 -f 3748//3748 3730//3730 3729//3729 -f 3748//3748 3729//3729 3728//3728 -f 3726//3726 3721//3721 3727//3727 -f 3727//3727 3721//3721 3747//3747 -f 3727//3727 3747//3747 3728//3728 -f 3728//3728 3747//3747 3746//3746 -f 3728//3728 3746//3746 3748//3748 -f 3748//3748 3746//3746 3732//3732 -f 3748//3748 3732//3732 3731//3731 -f 3725//3725 3734//3734 3733//3733 -f 3725//3725 3733//3733 3722//3722 -f 3720//3720 3719//3719 3746//3746 -f 3746//3746 3719//3719 3718//3718 -f 3746//3746 3718//3718 3717//3717 -f 3725//3725 3732//3732 3734//3734 -f 3734//3734 3732//3732 3746//3746 -f 3734//3734 3746//3746 3735//3735 -f 3735//3735 3746//3746 3717//3717 -f 3749//3749 3750//3750 3751//3751 -f 3752//3752 3753//3753 3750//3750 -f 3749//3749 3751//3751 3754//3754 -f 3752//3752 3750//3750 3755//3755 -f 3753//3753 3756//3756 3750//3750 -f 3750//3750 3756//3756 3757//3757 -f 3750//3750 3757//3757 3751//3751 -f 3758//3758 3759//3759 3760//3760 -f 3760//3760 3759//3759 3761//3761 -f 3760//3760 3761//3761 3762//3762 -f 3762//3762 3763//3763 3760//3760 -f 3760//3760 3763//3763 3764//3764 -f 3760//3760 3764//3764 3750//3750 -f 3750//3750 3764//3764 3765//3765 -f 3750//3750 3765//3765 3755//3755 -f 3760//3760 3766//3766 3767//3767 -f 3768//3768 3769//3769 3770//3770 -f 3770//3770 3769//3769 3771//3771 -f 3767//3767 3772//3772 3760//3760 -f 3760//3760 3772//3772 3773//3773 -f 3760//3760 3773//3773 3758//3758 -f 3774//3774 3775//3775 3754//3754 -f 3754//3754 3775//3775 3776//3776 -f 3754//3754 3776//3776 3777//3777 -f 3771//3771 3778//3778 3770//3770 -f 3770//3770 3778//3778 3779//3779 -f 3770//3770 3779//3779 3760//3760 -f 3760//3760 3779//3779 3780//3780 -f 3760//3760 3780//3780 3766//3766 -f 3751//3751 3781//3781 3754//3754 -f 3754//3754 3781//3781 3782//3782 -f 3754//3754 3782//3782 3783//3783 -f 3768//3768 3770//3770 3784//3784 -f 3784//3784 3770//3770 3785//3785 -f 3784//3784 3785//3785 3786//3786 -f 3783//3783 3787//3787 3754//3754 -f 3754//3754 3787//3787 3788//3788 -f 3754//3754 3788//3788 3774//3774 -f 3789//3789 3790//3790 3791//3791 -f 3792//3792 3793//3793 3786//3786 -f 3786//3786 3793//3793 3794//3794 -f 3786//3786 3794//3794 3784//3784 -f 3776//3776 3795//3795 3777//3777 -f 3777//3777 3795//3795 3796//3796 -f 3777//3777 3796//3796 3797//3797 -f 3797//3797 3796//3796 3798//3798 -f 3786//3786 3799//3799 3792//3792 -f 3792//3792 3799//3799 3789//3789 -f 3792//3792 3789//3789 3800//3800 -f 3800//3800 3789//3789 3791//3791 -f 3709//3709 3757//3757 3756//3756 -f 3702//3702 3787//3787 3783//3783 -f 3697//3697 3696//3696 3795//3795 -f 3795//3795 3696//3696 3692//3692 -f 3795//3795 3692//3692 3691//3691 -f 3795//3795 3776//3776 3697//3697 -f 3697//3697 3776//3776 3775//3775 -f 3697//3697 3775//3775 3698//3698 -f 3698//3698 3775//3775 3774//3774 -f 3698//3698 3774//3774 3699//3699 -f 3699//3699 3774//3774 3788//3788 -f 3699//3699 3788//3788 3700//3700 -f 3700//3700 3788//3788 3787//3787 -f 3700//3700 3787//3787 3701//3701 -f 3701//3701 3787//3787 3702//3702 -f 3693//3693 3704//3704 3783//3783 -f 3783//3783 3704//3704 3703//3703 -f 3783//3783 3703//3703 3702//3702 -f 3783//3783 3782//3782 3693//3693 -f 3693//3693 3782//3782 3781//3781 -f 3693//3693 3781//3781 3694//3694 -f 3694//3694 3781//3781 3709//3709 -f 3709//3709 3781//3781 3751//3751 -f 3709//3709 3751//3751 3757//3757 -f 3715//3715 3714//3714 3756//3756 -f 3756//3756 3714//3714 3710//3710 -f 3756//3756 3710//3710 3709//3709 -f 3756//3756 3753//3753 3715//3715 -f 3715//3715 3753//3753 3752//3752 -f 3715//3715 3752//3752 3711//3711 -f 3711//3711 3752//3752 3755//3755 -f 3711//3711 3755//3755 3712//3712 -f 3712//3712 3755//3755 3713//3713 -f 3713//3713 3755//3755 3708//3708 -f 3708//3708 3755//3755 3765//3765 -f 3708//3708 3765//3765 3707//3707 -f 3765//3765 3764//3764 3707//3707 -f 3707//3707 3764//3764 3763//3763 -f 3707//3707 3763//3763 3705//3705 -f 3705//3705 3763//3763 3762//3762 -f 3705//3705 3762//3762 3739//3739 -f 3739//3739 3762//3762 3761//3761 -f 3739//3739 3761//3761 3740//3740 -f 3740//3740 3761//3761 3759//3759 -f 3740//3740 3759//3759 3736//3736 -f 3736//3736 3759//3759 3758//3758 -f 3736//3736 3758//3758 3737//3737 -f 3758//3758 3773//3773 3737//3737 -f 3737//3737 3773//3773 3772//3772 -f 3737//3737 3772//3772 3738//3738 -f 3738//3738 3772//3772 3767//3767 -f 3738//3738 3767//3767 3741//3741 -f 3741//3741 3767//3767 3742//3742 -f 3742//3742 3767//3767 3766//3766 -f 3742//3742 3766//3766 3743//3743 -f 3743//3743 3766//3766 3744//3744 -f 3744//3744 3766//3766 3780//3780 -f 3744//3744 3780//3780 3745//3745 -f 3745//3745 3780//3780 3779//3779 -f 3745//3745 3779//3779 3649//3649 -f 3649//3649 3779//3779 3778//3778 -f 3649//3649 3778//3778 3674//3674 -f 3674//3674 3778//3778 3675//3675 -f 3675//3675 3778//3778 3771//3771 -f 3675//3675 3771//3771 3672//3672 -f 3672//3672 3771//3771 3769//3769 -f 3672//3672 3769//3769 3673//3673 -f 3673//3673 3769//3769 3768//3768 -f 3673//3673 3768//3768 3676//3676 -f 3676//3676 3768//3768 3784//3784 -f 3676//3676 3784//3784 3677//3677 -f 3677//3677 3784//3784 3794//3794 -f 3677//3677 3794//3794 3678//3678 -f 3678//3678 3794//3794 3793//3793 -f 3678//3678 3793//3793 3679//3679 -f 3679//3679 3793//3793 3792//3792 -f 3679//3679 3792//3792 3680//3680 -f 3680//3680 3792//3792 3671//3671 -f 3671//3671 3792//3792 3800//3800 -f 3671//3671 3800//3800 3654//3654 -f 3654//3654 3800//3800 3791//3791 -f 3654//3654 3791//3791 3662//3662 -f 3662//3662 3791//3791 3790//3790 -f 3662//3662 3790//3790 3661//3661 -f 3661//3661 3790//3790 3789//3789 -f 3661//3661 3789//3789 3663//3663 -f 3663//3663 3789//3789 3664//3664 -f 3664//3664 3789//3789 3799//3799 -f 3664//3664 3799//3799 3665//3665 -f 3665//3665 3799//3799 3786//3786 -f 3665//3665 3786//3786 3669//3669 -f 3669//3669 3786//3786 3670//3670 -f 3670//3670 3786//3786 3785//3785 -f 3670//3670 3785//3785 3666//3666 -f 3666//3666 3785//3785 3770//3770 -f 3666//3666 3770//3770 3667//3667 -f 3667//3667 3770//3770 3668//3668 -f 3668//3668 3770//3770 3760//3760 -f 3668//3668 3760//3760 3660//3660 -f 3660//3660 3760//3760 3750//3750 -f 3660//3660 3750//3750 3657//3657 -f 3657//3657 3750//3750 3749//3749 -f 3657//3657 3749//3749 3681//3681 -f 3749//3749 3754//3754 3681//3681 -f 3681//3681 3754//3754 3777//3777 -f 3681//3681 3777//3777 3682//3682 -f 3682//3682 3777//3777 3683//3683 -f 3683//3683 3777//3777 3797//3797 -f 3683//3683 3797//3797 3684//3684 -f 3684//3684 3797//3797 3798//3798 -f 3684//3684 3798//3798 3685//3685 -f 3796//3796 3687//3687 3798//3798 -f 3798//3798 3687//3687 3686//3686 -f 3798//3798 3686//3686 3685//3685 -f 3691//3691 3690//3690 3795//3795 -f 3795//3795 3690//3690 3689//3689 -f 3795//3795 3689//3689 3796//3796 -f 3796//3796 3689//3689 3688//3688 -f 3796//3796 3688//3688 3687//3687 -# 7600 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_osnovno.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_osnovno.obj deleted file mode 100644 index 57d2d77ad..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/sisaljke_osnovno.obj +++ /dev/null @@ -1,23184 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object sisaljke_osnovno.obj -# -# Vertices: 5792 -# Faces: 11584 -# -#### -vn 0.454450 -6.228202 0.000006 -v 0.035532 0.075827 0.168650 -vn 1.772198 -5.894598 0.580577 -v 0.035820 0.075907 0.169430 -vn 0.453178 -6.198199 0.610475 -v 0.035532 0.075865 0.169434 -vn 1.772166 -5.809321 1.155566 -v 0.035820 0.076022 0.170202 -vn 0.454456 -6.108527 1.215074 -v 0.035532 0.075981 0.170211 -vn 1.772183 -5.668077 1.719399 -v 0.035820 0.076212 0.170960 -vn 0.453184 -5.960011 1.807938 -v 0.035532 0.076171 0.170972 -vn 1.772197 -5.472286 2.266679 -v 0.035820 0.076475 0.171695 -vn 0.454519 -5.754101 2.383409 -v 0.035532 0.076436 0.171711 -vn 1.772205 -5.223711 2.792122 -v 0.035820 0.076809 0.172401 -vn 0.453139 -5.492773 2.935969 -v 0.035532 0.076771 0.172421 -vn 1.772159 -4.924897 3.290738 -v 0.035820 0.077210 0.173071 -vn 0.454455 -5.178560 3.460204 -v 0.035532 0.077175 0.173095 -vn 1.772198 -4.578633 3.757587 -v 0.035820 0.077675 0.173698 -vn 0.453175 -4.814464 3.951118 -v 0.035532 0.077643 0.173725 -vn 1.772187 -4.188300 4.188277 -v 0.035820 0.078200 0.174277 -vn 0.454469 -4.404018 4.403986 -v 0.035532 0.078170 0.174307 -vn 1.772184 -3.757580 4.578631 -v 0.035820 0.078779 0.174801 -vn 0.453174 -3.951121 4.814458 -v 0.035532 0.078752 0.174834 -vn 1.772187 -3.290713 4.924953 -v 0.035820 0.079406 0.175267 -vn 0.454553 -3.460188 5.178549 -v 0.035532 0.079382 0.175302 -vn 1.772247 -2.792153 5.223706 -v 0.035820 0.080076 0.175668 -vn 0.453201 -2.935937 5.492779 -v 0.035532 0.080056 0.175705 -vn 1.772179 -2.266712 5.472257 -v 0.035820 0.080782 0.176002 -vn 0.454460 -2.383420 5.754109 -v 0.035532 0.080765 0.176041 -vn 1.772073 -1.719396 5.668099 -v 0.035820 0.081517 0.176265 -vn 0.453077 -1.807956 5.960029 -v 0.035532 0.081505 0.176306 -vn 1.772150 -1.155518 5.809302 -v 0.035820 0.082274 0.176455 -vn 0.454410 -1.215080 6.108531 -v 0.035532 0.082266 0.176496 -vn 1.772273 -0.580575 5.894600 -v 0.035820 0.083047 0.176569 -vn 0.453252 -0.610492 6.198184 -v 0.035532 0.083043 0.176611 -vn 1.772204 0.000014 5.923109 -v 0.035820 0.083827 0.176608 -vn 0.454459 0.000015 6.228200 -v 0.035532 0.083827 0.176650 -vn 1.772288 0.580544 5.894598 -v 0.035820 0.084607 0.176569 -vn 0.453246 0.610453 6.198190 -v 0.035532 0.084611 0.176611 -vn 1.772169 1.155518 5.809302 -v 0.035820 0.085379 0.176455 -vn 0.454388 1.215099 6.108531 -v 0.035532 0.085388 0.176496 -vn 1.772057 1.719432 5.668093 -v 0.035820 0.086137 0.176265 -vn 0.453085 1.807976 5.960022 -v 0.035532 0.086149 0.176306 -vn 1.772170 2.266705 5.472258 -v 0.035820 0.086872 0.176002 -vn 0.454475 2.383407 5.754110 -v 0.035532 0.086888 0.176041 -vn 1.772225 2.792137 5.223723 -v 0.035820 0.087578 0.175668 -vn 0.453213 2.935942 5.492774 -v 0.035532 0.087598 0.175705 -vn 1.772190 3.290726 4.924944 -v 0.035820 0.088248 0.175267 -vn 0.454549 3.460166 5.178564 -v 0.035532 0.088271 0.175302 -vn 1.772206 3.757569 4.578631 -v 0.035820 0.088875 0.174801 -vn 0.453164 3.951136 4.814448 -v 0.035532 0.088902 0.174834 -vn 1.772187 4.188304 4.188273 -v 0.035820 0.089454 0.174277 -vn 0.454470 4.404015 4.403989 -v 0.035532 0.089484 0.174307 -vn 1.772207 4.578628 3.757587 -v 0.035820 0.089978 0.173698 -vn 0.453171 4.814464 3.951119 -v 0.035532 0.090011 0.173725 -vn 1.772210 4.924888 3.290704 -v 0.035820 0.090443 0.173071 -vn 0.454457 5.178565 3.460197 -v 0.035532 0.090479 0.173095 -vn 1.772206 5.223729 2.792150 -v 0.035820 0.090845 0.172401 -vn 0.453209 5.492768 2.935952 -v 0.035532 0.090882 0.172421 -vn 1.772193 5.472281 2.266688 -v 0.035820 0.091179 0.171695 -vn 0.454524 5.754090 2.383432 -v 0.035532 0.091218 0.171711 -vn 1.772200 5.668070 1.719405 -v 0.035820 0.091442 0.170960 -vn 0.453174 5.960015 1.807932 -v 0.035532 0.091482 0.170972 -vn 1.772168 5.809322 1.155555 -v 0.035820 0.091632 0.170202 -vn 0.454445 6.108531 1.215052 -v 0.035532 0.091673 0.170211 -vn 1.772135 5.894603 0.580573 -v 0.035820 0.091746 0.169430 -vn 0.453108 6.198217 0.610471 -v 0.035532 0.091788 0.169434 -vn 1.772190 5.923117 0.000010 -v 0.035820 0.091784 0.168650 -vn 0.454442 6.228199 0.000009 -v 0.035532 0.091827 0.168650 -vn 1.772143 5.894604 -0.580583 -v 0.035820 0.091746 0.167870 -vn 0.453122 6.198212 -0.610496 -v 0.035532 0.091788 0.167866 -vn 1.772159 5.809323 -1.155559 -v 0.035820 0.091632 0.167098 -vn 0.454455 6.108529 -1.215054 -v 0.035532 0.091673 0.167089 -vn 1.772183 5.668077 -1.719399 -v 0.035820 0.091442 0.166340 -vn 0.453184 5.960011 -1.807938 -v 0.035532 0.091482 0.166328 -vn 1.772183 5.472287 -2.266688 -v 0.035820 0.091179 0.165605 -vn 0.454527 5.754096 -2.383418 -v 0.035532 0.091218 0.165589 -vn 1.772165 5.223754 -2.792152 -v 0.035820 0.090845 0.164899 -vn 0.453210 5.492779 -2.935938 -v 0.035532 0.090882 0.164879 -vn 1.772221 4.924921 -3.290702 -v 0.035820 0.090443 0.164229 -vn 0.454530 5.178546 -3.460189 -v 0.035532 0.090479 0.164205 -vn 1.772137 4.578644 -3.757628 -v 0.035820 0.089978 0.163602 -vn 0.453175 4.814444 -3.951147 -v 0.035532 0.090011 0.163575 -vn 1.772187 4.188300 -4.188277 -v 0.035820 0.089454 0.163023 -vn 0.454469 4.404018 -4.403986 -v 0.035532 0.089484 0.162993 -vn 1.772199 3.757602 -4.578613 -v 0.035820 0.088875 0.162499 -vn 0.453160 3.951137 -4.814448 -v 0.035532 0.088902 0.162466 -vn 1.772144 3.290698 -4.924917 -v 0.035820 0.088248 0.162033 -vn 0.454438 3.460185 -5.178575 -v 0.035532 0.088271 0.161998 -vn 1.772134 2.792140 -5.223778 -v 0.035820 0.087578 0.161632 -vn 0.453201 2.935937 -5.492779 -v 0.035532 0.087598 0.161595 -vn 1.772179 2.266712 -5.472257 -v 0.035820 0.086872 0.161298 -vn 0.454477 2.383452 -5.754098 -v 0.035532 0.086888 0.161259 -vn 1.772208 1.719414 -5.668077 -v 0.035820 0.086137 0.161035 -vn 0.453208 1.807964 -5.959991 -v 0.035532 0.086149 0.160994 -vn 1.772154 1.155515 -5.809308 -v 0.035820 0.085379 0.160845 -vn 0.454411 1.215025 -6.108547 -v 0.035532 0.085388 0.160804 -vn 1.772166 0.580563 -5.894655 -v 0.035820 0.084607 0.160731 -vn 0.453252 0.610492 -6.198184 -v 0.035532 0.084611 0.160689 -vn 1.772189 0.000007 -5.923116 -v 0.035820 0.083827 0.160692 -vn 0.454459 -0.000015 -6.228200 -v 0.035532 0.083827 0.160650 -vn 1.772170 -0.580570 -5.894655 -v 0.035820 0.083047 0.160731 -vn 0.453246 -0.610453 -6.198190 -v 0.035532 0.083043 0.160689 -vn 1.772169 -1.155518 -5.809302 -v 0.035820 0.082274 0.160845 -vn 0.454405 -1.215065 -6.108541 -v 0.035532 0.082266 0.160804 -vn 1.772191 -1.719407 -5.668083 -v 0.035820 0.081517 0.161035 -vn 0.453216 -1.807942 -5.959996 -v 0.035532 0.081505 0.160994 -vn 1.772173 -2.266710 -5.472261 -v 0.035820 0.080782 0.161298 -vn 0.454476 -2.383461 -5.754094 -v 0.035532 0.080765 0.161259 -vn 1.772140 -2.792150 -5.223772 -v 0.035820 0.080076 0.161632 -vn 0.453198 -2.935926 -5.492785 -v 0.035532 0.080056 0.161595 -vn 1.772163 -3.290697 -4.924909 -v 0.035820 0.079406 0.162033 -vn 0.454433 -3.460195 -5.178569 -v 0.035532 0.079382 0.161998 -vn 1.772194 -3.757595 -4.578619 -v 0.035820 0.078779 0.162499 -vn 0.453164 -3.951136 -4.814448 -v 0.035532 0.078752 0.162466 -vn 1.772177 -4.188298 -4.188286 -v 0.035820 0.078200 0.163023 -vn 0.454470 -4.404015 -4.403989 -v 0.035532 0.078170 0.162993 -vn 1.772120 -4.578659 -3.757619 -v 0.035820 0.077675 0.163602 -vn 0.453182 -4.814450 -3.951136 -v 0.035532 0.077643 0.163575 -vn 1.772177 -4.924922 -3.290743 -v 0.035820 0.077210 0.164229 -vn 0.454526 -5.178532 -3.460212 -v 0.035532 0.077175 0.164205 -vn 1.772146 -5.223744 -2.792125 -v 0.035820 0.076809 0.164899 -vn 0.453149 -5.492799 -2.935924 -v 0.035532 0.076771 0.164879 -vn 1.772187 -5.472291 -2.266675 -v 0.035820 0.076475 0.165605 -vn 0.454524 -5.754090 -2.383432 -v 0.035532 0.076436 0.165589 -vn 1.772200 -5.668070 -1.719405 -v 0.035820 0.076212 0.166340 -vn 0.453174 -5.960015 -1.807932 -v 0.035532 0.076171 0.166328 -vn 1.772168 -5.809322 -1.155555 -v 0.035820 0.076022 0.167098 -vn 0.454457 -6.108528 -1.215075 -v 0.035532 0.075981 0.167089 -vn 1.772218 -5.894593 -0.580582 -v 0.035820 0.075907 0.167870 -vn 0.453190 -6.198195 -0.610492 -v 0.035532 0.075865 0.167866 -vn 1.772200 -5.923116 0.000003 -v 0.035820 0.075869 0.168650 -vn 3.398997 -5.145549 0.506782 -v 0.036083 0.076030 0.169418 -vn 3.398941 -5.071132 1.008722 -v 0.036083 0.076143 0.170178 -vn 3.398954 -4.947849 1.500901 -v 0.036083 0.076330 0.170924 -vn 3.398897 -4.776906 1.978677 -v 0.036083 0.076589 0.171648 -vn 3.399004 -4.559943 2.437327 -v 0.036083 0.076918 0.172343 -vn 3.398965 -4.299080 2.872552 -v 0.036083 0.077313 0.173002 -vn 3.398959 -3.996841 3.280117 -v 0.036083 0.077771 0.173620 -vn 3.398950 -3.656085 3.656074 -v 0.036083 0.078287 0.174190 -vn 3.399020 -3.280102 3.996780 -v 0.036083 0.078857 0.174706 -vn 3.398907 -2.872524 4.299106 -v 0.036083 0.079474 0.175164 -vn 3.398975 -2.437346 4.559950 -v 0.036083 0.080134 0.175559 -vn 3.398980 -1.978667 4.776859 -v 0.036083 0.080829 0.175888 -vn 3.398994 -1.500901 4.947776 -v 0.036083 0.081553 0.176147 -vn 3.399025 -1.008678 5.071088 -v 0.036083 0.082298 0.176334 -vn 3.398967 -0.506784 5.145583 -v 0.036083 0.083059 0.176447 -vn 3.398990 -0.000006 5.170450 -v 0.036083 0.083827 0.176484 -vn 3.398973 0.506801 5.145578 -v 0.036083 0.084595 0.176447 -vn 3.399041 1.008655 5.071080 -v 0.036083 0.085355 0.176334 -vn 3.399004 1.500896 4.947773 -v 0.036083 0.086101 0.176147 -vn 3.398964 1.978678 4.776867 -v 0.036083 0.086825 0.175888 -vn 3.398992 2.437336 4.559944 -v 0.036083 0.087520 0.175559 -vn 3.398934 2.872532 4.299072 -v 0.036083 0.088179 0.175164 -vn 3.399001 3.280085 3.996810 -v 0.036083 0.088797 0.174706 -vn 3.398942 3.656102 3.656067 -v 0.036083 0.089366 0.174190 -vn 3.398955 3.996850 3.280107 -v 0.036083 0.089883 0.173620 -vn 3.398983 4.299090 2.872559 -v 0.036083 0.090341 0.173002 -vn 3.398960 4.559946 2.437360 -v 0.036083 0.090736 0.172343 -vn 3.398895 4.776914 1.978662 -v 0.036083 0.091065 0.171648 -vn 3.398950 4.947848 1.500901 -v 0.036083 0.091324 0.170924 -vn 3.398981 5.071094 1.008711 -v 0.036083 0.091511 0.170178 -vn 3.398994 5.145548 0.506794 -v 0.036083 0.091623 0.169418 -vn 3.399001 5.170448 -0.000001 -v 0.036083 0.091661 0.168650 -vn 3.399001 5.145544 -0.506788 -v 0.036083 0.091623 0.167882 -vn 3.398964 5.071113 -1.008710 -v 0.036083 0.091511 0.167122 -vn 3.398954 4.947849 -1.500901 -v 0.036083 0.091324 0.166376 -vn 3.398900 4.776916 -1.978658 -v 0.036083 0.091065 0.165652 -vn 3.398890 4.559970 -2.437369 -v 0.036083 0.090736 0.164957 -vn 3.398954 4.299081 -2.872552 -v 0.036083 0.090341 0.164298 -vn 3.398921 3.996819 -3.280122 -v 0.036083 0.089883 0.163680 -vn 3.398943 3.656077 -3.656092 -v 0.036083 0.089366 0.163110 -vn 3.399016 3.280112 -3.996778 -v 0.036083 0.088797 0.162594 -vn 3.398979 2.872554 -4.299074 -v 0.036083 0.088179 0.162136 -vn 3.398938 2.437307 -4.559939 -v 0.036083 0.087520 0.161741 -vn 3.398972 1.978647 -4.776877 -v 0.036083 0.086825 0.161412 -vn 3.398994 1.500901 -4.947776 -v 0.036083 0.086101 0.161153 -vn 3.399041 1.008706 -5.071076 -v 0.036083 0.085355 0.160966 -vn 3.398917 0.506772 -5.145555 -v 0.036083 0.084595 0.160853 -vn 3.398997 0.000014 -5.170454 -v 0.036083 0.083827 0.160816 -vn 3.398911 -0.506809 -5.145554 -v 0.036083 0.083059 0.160853 -vn 3.399031 -1.008687 -5.071085 -v 0.036083 0.082298 0.160966 -vn 3.399004 -1.500896 -4.947773 -v 0.036083 0.081553 0.161153 -vn 3.398978 -1.978649 -4.776875 -v 0.036083 0.080829 0.161412 -vn 3.398932 -2.437313 -4.559942 -v 0.036083 0.080134 0.161741 -vn 3.398941 -2.872578 -4.299093 -v 0.036083 0.079474 0.162136 -vn 3.399013 -3.280095 -3.996795 -v 0.036083 0.078857 0.162594 -vn 3.398953 -3.656083 -3.656080 -v 0.036083 0.078287 0.163110 -vn 3.398936 -3.996808 -3.280122 -v 0.036083 0.077771 0.163680 -vn 3.398926 -4.299068 -2.872557 -v 0.036083 0.077313 0.164298 -vn 3.398942 -4.559961 -2.437346 -v 0.036083 0.076918 0.164957 -vn 3.398899 -4.776923 -1.978642 -v 0.036083 0.076589 0.165652 -vn 3.398943 -4.947851 -1.500915 -v 0.036083 0.076330 0.166376 -vn 3.398928 -5.071145 -1.008707 -v 0.036083 0.076143 0.167122 -vn 3.398994 -5.145548 -0.506794 -v 0.036083 0.076030 0.167882 -vn 3.399001 -5.170448 0.000001 -v 0.036083 0.075993 0.168650 -vn 4.492386 -4.328835 0.422176 -v 0.036300 0.076223 0.169399 -vn 4.488431 -4.269774 0.853113 -v 0.036300 0.076333 0.170141 -vn 4.491238 -4.163535 1.262214 -v 0.036300 0.076516 0.170868 -vn 4.491220 -4.019260 1.665529 -v 0.036300 0.076768 0.171574 -vn 4.501243 -3.821368 2.053293 -v 0.036300 0.077089 0.172252 -vn 4.495959 -3.617543 2.406020 -v 0.036300 0.077474 0.172895 -vn 4.491974 -3.364116 2.757588 -v 0.036300 0.077921 0.173497 -vn 4.488489 -3.076278 3.081328 -v 0.036300 0.078424 0.174052 -vn 4.490717 -2.762026 3.362353 -v 0.036300 0.078980 0.174556 -vn 4.490381 -2.416257 3.619329 -v 0.036300 0.079582 0.175003 -vn 4.498236 -2.040571 3.832466 -v 0.036300 0.080225 0.175388 -vn 4.493655 -1.671323 4.013448 -v 0.036300 0.080903 0.175709 -vn 4.491887 -1.263586 4.162492 -v 0.036300 0.081609 0.175961 -vn 4.488862 -0.846316 4.270586 -v 0.036300 0.082336 0.176143 -vn 4.490532 -0.429525 4.330333 -v 0.036300 0.083078 0.176253 -vn 4.489582 0.002626 4.352742 -v 0.036300 0.083827 0.176290 -vn 4.495742 0.430575 4.323602 -v 0.036300 0.084576 0.176253 -vn 4.491723 0.841707 4.267784 -v 0.036300 0.085317 0.176143 -vn 4.491886 1.263567 4.162498 -v 0.036300 0.086045 0.175961 -vn 4.489500 1.667931 4.020597 -v 0.036300 0.086751 0.175709 -vn 4.490783 2.047935 3.839239 -v 0.036300 0.087428 0.175388 -vn 4.489069 2.421329 3.617924 -v 0.036300 0.088071 0.175003 -vn 4.493808 2.760010 3.358954 -v 0.036300 0.088674 0.174556 -vn 4.490148 3.073215 3.081419 -v 0.036300 0.089229 0.174052 -vn 4.491971 3.364126 2.757579 -v 0.036300 0.089733 0.173497 -vn 4.490391 3.619041 2.416582 -v 0.036300 0.090179 0.172895 -vn 4.491399 3.834920 2.054445 -v 0.036300 0.090565 0.172252 -vn 4.488616 4.023908 1.662825 -v 0.036300 0.090885 0.171574 -vn 4.492262 4.162319 1.261746 -v 0.036300 0.091138 0.170868 -vn 4.492264 4.265672 0.849203 -v 0.036300 0.091320 0.170141 -vn 4.504797 4.313899 0.412744 -v 0.036300 0.091430 0.169399 -vn 4.498668 4.341134 0.010154 -v 0.036300 0.091467 0.168650 -vn 4.492383 4.328834 -0.422190 -v 0.036300 0.091430 0.167901 -vn 4.488453 4.269758 -0.853112 -v 0.036300 0.091320 0.167159 -vn 4.491243 4.163528 -1.262211 -v 0.036300 0.091138 0.166432 -vn 4.491220 4.019272 -1.665507 -v 0.036300 0.090885 0.165726 -vn 4.501244 3.821357 -2.053299 -v 0.036300 0.090565 0.165048 -vn 4.495975 3.617525 -2.406023 -v 0.036300 0.090179 0.164405 -vn 4.492029 3.364087 -2.757550 -v 0.036300 0.089733 0.163803 -vn 4.488496 3.076265 -3.081332 -v 0.036300 0.089229 0.163248 -vn 4.490713 2.762052 -3.362343 -v 0.036300 0.088674 0.162744 -vn 4.490333 2.416256 -3.619374 -v 0.036300 0.088071 0.162297 -vn 4.498308 2.040548 -3.832411 -v 0.036300 0.087428 0.161912 -vn 4.493658 1.671314 -4.013451 -v 0.036300 0.086751 0.161591 -vn 4.491880 1.263583 -4.162502 -v 0.036300 0.086045 0.161339 -vn 4.488862 0.846312 -4.270586 -v 0.036300 0.085317 0.161157 -vn 4.490606 0.429543 -4.330271 -v 0.036300 0.084576 0.161047 -vn 4.489587 -0.002649 -4.352740 -v 0.036300 0.083827 0.161010 -vn 4.495814 -0.430548 -4.323545 -v 0.036300 0.083078 0.161047 -vn 4.491730 -0.841733 -4.267776 -v 0.036300 0.082336 0.161157 -vn 4.491880 -1.263564 -4.162508 -v 0.036300 0.081609 0.161339 -vn 4.489493 -1.667940 -4.020602 -v 0.036300 0.080903 0.161591 -vn 4.490861 -2.047852 -3.839211 -v 0.036300 0.080225 0.161912 -vn 4.488991 -2.421391 -3.617946 -v 0.036300 0.079582 0.162297 -vn 4.493797 -2.760031 -3.358954 -v 0.036300 0.078980 0.162744 -vn 4.490144 -3.073221 -3.081419 -v 0.036300 0.078424 0.163248 -vn 4.492023 -3.364086 -2.757558 -v 0.036300 0.077921 0.163803 -vn 4.490479 -3.618965 -2.416564 -v 0.036300 0.077474 0.164405 -vn 4.491409 -3.834915 -2.054425 -v 0.036300 0.077089 0.165048 -vn 4.488616 -4.023916 -1.662813 -v 0.036300 0.076768 0.165726 -vn 4.492259 -4.162319 -1.261780 -v 0.036300 0.076516 0.166432 -vn 4.492207 -4.265716 -0.849198 -v 0.036300 0.076333 0.167159 -vn 4.504796 -4.313903 -0.412732 -v 0.036300 0.076223 0.167901 -vn 4.498668 -4.341134 -0.010154 -v 0.036300 0.076187 0.168650 -vn 4.393102 -1.113779 -4.317733 -v 0.037115 0.082344 0.162155 -vn 4.392216 -1.502343 -4.198739 -v 0.037115 0.081393 0.162448 -vn 4.544329 -1.809142 -3.928107 -v 0.037115 0.081277 0.162495 -vn 4.397492 -2.161557 -3.897330 -v 0.037115 0.080496 0.162880 -vn 4.690251 -2.346225 -3.457690 -v 0.037115 0.080125 0.163110 -vn 4.386262 -2.807813 -3.475741 -v 0.037115 0.079673 0.163441 -vn 4.392215 1.502346 -4.198738 -v 0.037115 0.086261 0.162448 -vn 4.393103 1.113759 -4.317738 -v 0.037115 0.085309 0.162155 -vn 4.625001 0.676410 -4.191636 -v 0.037115 0.085127 0.162115 -vn 4.399083 0.395555 -4.437858 -v 0.037115 0.084325 0.162006 -vn 4.693562 -0.004196 -4.175038 -v 0.037115 0.083827 0.161987 -vn 4.384747 -0.380783 -4.453603 -v 0.037115 0.083329 0.162006 -vn 4.576056 -0.704759 -4.237358 -v 0.037115 0.082527 0.162115 -vn 4.390987 3.600451 -2.632260 -v 0.037115 0.089332 0.164897 -vn 4.393476 3.345807 -2.947849 -v 0.037115 0.088711 0.164118 -vn 4.698015 2.849483 -3.043451 -v 0.037115 0.088538 0.163939 -vn 4.400837 2.815187 -3.451660 -v 0.037115 0.087981 0.163441 -vn 4.687831 2.340806 -3.464680 -v 0.037115 0.087528 0.163110 -vn 4.383214 2.178795 -3.904845 -v 0.037115 0.087158 0.162880 -vn 4.517405 1.810918 -3.956466 -v 0.037115 0.086376 0.162495 -vn 4.393698 3.345658 2.947736 -v 0.037115 0.088711 0.173182 -vn 4.390992 3.600445 2.632264 -v 0.037115 0.089332 0.172403 -vn 4.460041 3.752378 2.299999 -v 0.037115 0.089366 0.172352 -vn 4.395757 3.976248 2.015533 -v 0.037115 0.089830 0.171541 -vn 4.677866 3.893609 1.552727 -v 0.037115 0.089982 0.171200 -vn 4.387333 4.271201 1.307631 -v 0.037115 0.090193 0.170614 -vn 4.648589 4.127217 0.895267 -v 0.037115 0.090361 0.169950 -vn 4.379641 4.439685 0.565300 -v 0.037115 0.090415 0.169643 -vn 4.402056 4.454805 0.009529 -v 0.037115 0.090489 0.168650 -vn 4.394109 4.423693 -0.560779 -v 0.037115 0.090415 0.167657 -vn 4.655898 4.117316 -0.901725 -v 0.037115 0.090361 0.167350 -vn 4.388580 4.269858 -1.307186 -v 0.037115 0.090193 0.166686 -vn 4.673045 3.895571 -1.562569 -v 0.037115 0.089982 0.166100 -vn 4.381430 3.993273 -2.016486 -v 0.037115 0.089830 0.165759 -vn 4.447612 3.763338 -2.306370 -v 0.037115 0.089366 0.164948 -vn 4.393109 1.113788 4.317725 -v 0.037115 0.085309 0.175145 -vn 4.391882 1.502221 4.199063 -v 0.037115 0.086261 0.174852 -vn 4.544291 1.809010 3.928213 -v 0.037115 0.086376 0.174805 -vn 4.397484 2.161569 3.897333 -v 0.037115 0.087158 0.174420 -vn 4.690264 2.346231 3.457669 -v 0.037115 0.087528 0.174190 -vn 4.386108 2.807918 3.475814 -v 0.037115 0.087981 0.173859 -vn 4.621611 2.927238 3.081604 -v 0.037115 0.088538 0.173361 -vn 4.391872 -1.502242 4.199065 -v 0.037115 0.081393 0.174852 -vn 4.393098 -1.113789 4.317735 -v 0.037115 0.082344 0.175145 -vn 4.625072 -0.676364 4.191569 -v 0.037115 0.082527 0.175185 -vn 4.398756 -0.395619 4.438120 -v 0.037115 0.083329 0.175294 -vn 4.693544 0.004186 4.175057 -v 0.037115 0.083827 0.175313 -vn 4.384414 0.380847 4.453869 -v 0.037115 0.084325 0.175294 -vn 4.576034 0.704731 4.237387 -v 0.037115 0.085127 0.175185 -vn 4.390987 -3.600451 2.632260 -v 0.037115 0.078322 0.172403 -vn 4.393695 -3.345656 2.947743 -v 0.037115 0.078943 0.173182 -vn 4.698240 -2.849290 3.043295 -v 0.037115 0.079116 0.173361 -vn 4.400484 -2.815407 3.451858 -v 0.037115 0.079673 0.173859 -vn 4.687788 -2.340849 3.464707 -v 0.037115 0.080125 0.174190 -vn 4.383214 -2.178795 3.904845 -v 0.037115 0.080496 0.174420 -vn 4.517366 -1.810786 3.956572 -v 0.037115 0.081277 0.174805 -vn 4.621456 -2.927350 -3.081716 -v 0.037115 0.079116 0.163939 -vn 4.393473 -3.345805 -2.947853 -v 0.037115 0.078943 0.164118 -vn 4.390985 -3.600455 -2.632258 -v 0.037115 0.078322 0.164897 -vn 4.460044 -3.752373 -2.300000 -v 0.037115 0.078287 0.164948 -vn 4.395756 -3.976234 -2.015559 -v 0.037115 0.077824 0.165759 -vn 4.677939 -3.893527 -1.552720 -v 0.037115 0.077671 0.166100 -vn 4.387497 -4.271074 -1.307582 -v 0.037115 0.077460 0.166686 -vn 4.648565 -4.127244 -0.895261 -v 0.037115 0.077292 0.167350 -vn 4.379598 -4.439722 -0.565291 -v 0.037115 0.077239 0.167657 -vn 4.402056 -4.454806 -0.009527 -v 0.037115 0.077164 0.168650 -vn 4.394153 -4.423654 0.560787 -v 0.037115 0.077239 0.169643 -vn 4.655940 -4.117275 0.901703 -v 0.037115 0.077292 0.169950 -vn 4.388745 -4.269726 1.307157 -v 0.037115 0.077460 0.170614 -vn 4.672974 -3.895639 1.562607 -v 0.037115 0.077671 0.171200 -vn 4.381425 -3.993299 2.016452 -v 0.037115 0.077824 0.171541 -vn 4.447613 -3.763339 2.306370 -v 0.037115 0.078287 0.172352 -vn 2.858558 -5.246207 1.612733 -v 0.037178 0.077508 0.170599 -vn 2.857623 -5.435208 0.763210 -v 0.037178 0.077288 0.169635 -vn 0.391162 -6.114683 0.921650 -v 0.037256 0.077309 0.169632 -vn 2.862526 -1.953954 5.124606 -v 0.037178 0.081411 0.174805 -vn 2.858347 -2.712658 4.771192 -v 0.037178 0.080521 0.174376 -vn 0.391192 -3.091866 5.355279 -v 0.037256 0.080531 0.174358 -vn 2.852245 2.704777 4.780427 -v 0.037178 0.087133 0.174376 -vn 2.861861 1.957519 5.123555 -v 0.037178 0.086242 0.174805 -vn 0.391123 2.259155 5.756186 -v 0.037256 0.086235 0.174785 -vn 2.857624 5.435207 0.763216 -v 0.037178 0.090365 0.169635 -vn 2.858398 5.246325 1.612771 -v 0.037178 0.090145 0.170599 -vn 0.391255 5.909040 1.822706 -v 0.037256 0.090125 0.170593 -vn 2.859857 4.058669 -3.692032 -v 0.037178 0.088674 0.164153 -vn 2.857083 4.512973 -3.122804 -v 0.037178 0.089290 0.164925 -vn 0.391367 5.109222 -3.483392 -v 0.037256 0.089272 0.164937 -vn 2.858548 -0.436284 -5.471051 -v 0.037178 0.083333 0.162056 -vn 2.849389 0.453765 -5.475893 -v 0.037178 0.084321 0.162056 -vn 0.391118 0.462114 -6.166433 -v 0.037256 0.084319 0.162077 -vn 2.856218 -4.515177 -3.120481 -v 0.037178 0.078364 0.164925 -vn 2.860209 -4.060966 -3.689426 -v 0.037178 0.078980 0.164153 -vn 0.391443 -4.532981 -4.205938 -v 0.037256 0.078995 0.164167 -vn 2.858020 -4.924762 2.422878 -v 0.037178 0.077869 0.171519 -vn 2.857093 -4.512963 3.122814 -v 0.037178 0.078364 0.172375 -vn 2.859734 -4.058643 3.691961 -v 0.037178 0.078980 0.173147 -vn 2.858370 3.434383 4.281268 -v 0.037178 0.087949 0.173820 -vn 2.860086 4.060927 3.689373 -v 0.037178 0.088674 0.173147 -vn 2.856212 4.515173 3.120495 -v 0.037178 0.089290 0.172375 -vn 2.858346 2.712659 -4.771192 -v 0.037178 0.087133 0.162924 -vn 2.861645 1.273197 -5.335223 -v 0.037178 0.085298 0.162204 -vn 2.862115 -1.276713 -5.334240 -v 0.037178 0.082355 0.162204 -vn 2.852242 -2.704772 -4.780432 -v 0.037178 0.080521 0.162924 -vn 2.858563 -5.246205 -1.612733 -v 0.037178 0.077508 0.166701 -vn 2.857658 -5.435210 -0.763256 -v 0.037178 0.077288 0.167664 -vn 2.858676 -3.434287 -4.281136 -v 0.037178 0.079704 0.163480 -vn 2.862146 -1.957534 -5.123318 -v 0.037178 0.081411 0.162495 -vn 2.862802 1.953954 -5.124381 -v 0.037178 0.086242 0.162495 -vn 2.858030 4.924748 -2.422891 -v 0.037178 0.089784 0.165781 -vn 2.858401 5.246325 -1.612756 -v 0.037178 0.090145 0.166701 -vn 2.862100 1.276725 5.334247 -v 0.037178 0.085298 0.175096 -vn 2.858212 0.436319 5.471306 -v 0.037178 0.084321 0.175244 -vn 2.861649 -1.273198 5.335217 -v 0.037178 0.082355 0.175096 -vn 0.391302 -5.571359 -2.683030 -v 0.037256 0.077889 0.165790 -vn 0.391258 -5.909037 -1.822711 -v 0.037256 0.077529 0.166707 -vn -2.155023 -3.616995 -4.535566 -v 0.037336 0.079710 0.163488 -vn 0.391155 -3.855490 -4.834643 -v 0.037256 0.079717 0.163497 -vn 0.390992 -1.376018 -6.028718 -v 0.037256 0.082360 0.162224 -vn 0.391123 -2.259155 -5.756186 -v 0.037256 0.081419 0.162515 -vn -2.155150 1.290878 -5.655699 -v 0.037336 0.085296 0.162213 -vn 0.390979 1.376029 -6.028716 -v 0.037256 0.085293 0.162224 -vn 0.391153 3.855551 -4.834666 -v 0.037256 0.087936 0.163497 -vn 0.391197 3.091872 -5.355275 -v 0.037256 0.087122 0.162942 -vn -2.154935 5.226705 -2.517046 -v 0.037336 0.089775 0.165785 -vn 0.391318 5.571353 -2.683037 -v 0.037256 0.089765 0.165790 -vn 0.391205 6.183732 -0.000000 -v 0.037256 0.090418 0.168650 -vn 0.391157 6.114665 -0.921596 -v 0.037256 0.090344 0.167668 -vn 2.857659 5.435212 -0.763255 -v 0.037178 0.090365 0.167664 -vn -2.154932 5.226705 2.517045 -v 0.037336 0.089775 0.171515 -vn 0.391308 5.571356 2.683039 -v 0.037256 0.089765 0.171510 -vn 2.854958 4.924087 2.428948 -v 0.037178 0.089784 0.171519 -vn 0.391152 3.855553 4.834664 -v 0.037256 0.087936 0.173803 -vn 0.391082 4.533013 4.206024 -v 0.037256 0.088658 0.173133 -vn -2.155138 1.290920 5.655700 -v 0.037336 0.085296 0.175087 -vn 0.390992 1.376018 6.028718 -v 0.037256 0.085293 0.175076 -vn 0.390979 -1.376029 6.028716 -v 0.037256 0.082360 0.175076 -vn 0.391118 -0.462114 6.166433 -v 0.037256 0.083334 0.175223 -vn 2.849039 -0.453822 5.476152 -v 0.037178 0.083333 0.175244 -vn -2.155021 -3.616997 4.535566 -v 0.037336 0.079710 0.173812 -vn 0.391146 -3.855502 4.834636 -v 0.037256 0.079717 0.173803 -vn 2.846241 -3.457220 4.273603 -v 0.037178 0.079704 0.173820 -vn 0.391318 -5.571353 2.683037 -v 0.037256 0.077889 0.171510 -vn 0.391128 -5.109199 3.483390 -v 0.037256 0.078381 0.172363 -vn -2.154978 -5.801223 0.000001 -v 0.037336 0.077225 0.168650 -vn 0.391202 -6.183732 0.000003 -v 0.037256 0.077236 0.168650 -vn 2.825422 -5.511123 0.000008 -v 0.037178 0.077215 0.168650 -vn -2.152486 -5.524865 -1.769864 -v 0.037336 0.077518 0.166704 -vn -2.109361 -5.247586 -2.527077 -v 0.037336 0.077878 0.165785 -vn -2.152135 -4.826323 -3.219362 -v 0.037336 0.078372 0.164931 -vn -2.152672 -2.060970 -5.423079 -v 0.037336 0.081415 0.162504 -vn -2.109573 -1.296035 -5.678294 -v 0.037336 0.082358 0.162213 -vn -2.151763 -0.492197 -5.780773 -v 0.037336 0.083333 0.162066 -vn -2.152595 2.954846 -4.992528 -v 0.037336 0.087128 0.162932 -vn -2.109406 3.631400 -4.553655 -v 0.037336 0.087943 0.163488 -vn -2.152139 4.212541 -3.988892 -v 0.037336 0.088667 0.164159 -vn -2.152497 5.745718 -0.802580 -v 0.037336 0.090355 0.167666 -vn -2.109404 5.824389 0.000001 -v 0.037336 0.090429 0.168650 -vn -2.151935 5.745224 0.806463 -v 0.037336 0.090355 0.169634 -vn -2.152675 4.209767 3.991723 -v 0.037336 0.088667 0.173141 -vn -2.109397 3.631402 4.553659 -v 0.037336 0.087943 0.173812 -vn -2.151727 2.951633 4.994720 -v 0.037336 0.087128 0.174368 -vn -2.152306 -0.496115 5.780369 -v 0.037336 0.083333 0.175234 -vn -2.109571 -1.296051 5.678289 -v 0.037336 0.082358 0.175087 -vn -2.152134 -2.064702 5.421731 -v 0.037336 0.081415 0.174796 -vn -2.152674 -4.828471 3.216023 -v 0.037336 0.078372 0.172369 -vn -2.109376 -5.247579 2.527085 -v 0.037336 0.077878 0.171515 -vn -2.151941 -5.526144 1.766100 -v 0.037336 0.077518 0.170596 -vn -2.154644 -5.731083 -0.899122 -v 0.037336 0.077298 0.167666 -vn -3.795888 -4.911956 -0.814959 -v 0.037405 0.077257 0.167660 -vn -4.161551 -4.691157 -0.372236 -v 0.037405 0.077209 0.168054 -vn 0.391167 -6.114663 -0.921601 -v 0.037256 0.077309 0.167668 -vn -3.794177 -4.980650 -0.000001 -v 0.037405 0.077182 0.168650 -vn -4.039442 -4.669152 -1.139098 -v 0.037405 0.077422 0.166882 -vn -4.162019 -3.217025 -3.433994 -v 0.037405 0.079235 0.163847 -vn -3.803654 -3.709257 -3.314239 -v 0.037405 0.078956 0.164131 -vn -2.143346 -4.293633 -3.909553 -v 0.037336 0.078987 0.164159 -vn 0.391129 -5.109196 -3.483394 -v 0.037256 0.078381 0.164937 -vn 2.854969 -4.924072 -2.428961 -v 0.037178 0.077869 0.165781 -vn -4.100497 -3.743441 -2.935026 -v 0.037405 0.078451 0.164745 -vn -3.797250 -4.192605 -2.683388 -v 0.037405 0.078337 0.164907 -vn -3.811913 -4.477031 -2.156444 -v 0.037405 0.077840 0.165767 -vn -3.798117 -4.711445 -1.604189 -v 0.037405 0.077478 0.166692 -vn -3.795219 -3.103875 -3.894055 -v 0.037405 0.079684 0.163455 -vn -2.154777 -2.870294 -5.041219 -v 0.037336 0.080526 0.162932 -vn -3.796906 -2.425984 -4.347144 -v 0.037405 0.080505 0.162896 -vn -4.161510 -2.633805 -3.899868 -v 0.037405 0.080166 0.163105 -vn 0.391177 -3.091869 -5.355276 -v 0.037256 0.080531 0.162942 -vn -4.040412 -2.019273 -4.360325 -v 0.037405 0.081215 0.162540 -vn -4.162595 0.678343 -4.655800 -v 0.037405 0.084719 0.162066 -vn -3.805211 0.280168 -4.964808 -v 0.037405 0.084323 0.162024 -vn -2.142964 0.379534 -5.794713 -v 0.037336 0.084320 0.162066 -vn 0.391114 -0.462119 -6.166432 -v 0.037256 0.083334 0.162077 -vn -4.102112 -0.041049 -4.755200 -v 0.037405 0.083529 0.162012 -vn -3.796243 -0.517125 -4.951715 -v 0.037405 0.083330 0.162024 -vn -3.810671 -1.104895 -4.846037 -v 0.037405 0.082348 0.162172 -vn -3.797922 -1.683229 -4.683892 -v 0.037405 0.081399 0.162465 -vn -3.795555 1.109747 -4.854228 -v 0.037405 0.085305 0.162172 -vn -2.154840 2.151873 -5.387302 -v 0.037336 0.086239 0.162504 -vn -3.785180 1.884998 -4.618749 -v 0.037405 0.086254 0.162465 -vn -4.153900 1.416472 -4.494784 -v 0.037405 0.085880 0.162331 -vn 0.391121 2.259152 -5.756190 -v 0.037256 0.086235 0.162515 -vn -4.034719 2.152287 -4.301936 -v 0.037405 0.086975 0.162799 -vn -4.162604 4.063004 -2.372451 -v 0.037405 0.089531 0.165242 -vn -3.806801 4.056036 -2.874595 -v 0.037405 0.089317 0.164907 -vn -2.143255 4.766976 -3.316068 -v 0.037336 0.089282 0.164931 -vn 0.391430 4.532965 -4.205955 -v 0.037256 0.088658 0.164167 -vn 2.846474 3.457026 -4.273442 -v 0.037178 0.087949 0.163480 -vn -4.103660 3.690333 -2.996974 -v 0.037405 0.088830 0.164278 -vn -3.795477 3.548512 -3.493233 -v 0.037405 0.088697 0.164131 -vn -3.804155 3.100793 -3.891782 -v 0.037405 0.087969 0.163455 -vn -3.791062 2.617310 -4.240663 -v 0.037405 0.087149 0.162896 -vn -3.796542 4.485804 -2.159603 -v 0.037405 0.089813 0.165767 -vn -2.154629 5.553559 -1.676560 -v 0.037336 0.090136 0.166704 -vn -3.789058 4.783876 -1.402447 -v 0.037405 0.090176 0.166692 -vn -4.157606 4.393679 -1.695290 -v 0.037405 0.090047 0.166315 -vn 0.391254 5.909036 -1.822711 -v 0.037256 0.090125 0.166707 -vn -4.036314 4.703640 -1.000631 -v 0.037405 0.090364 0.167464 -vn -4.162036 4.388371 1.698096 -v 0.037405 0.090047 0.170985 -vn -3.807238 4.775795 1.379375 -v 0.037405 0.090176 0.170608 -vn -2.143141 5.564780 1.659450 -v 0.037336 0.090136 0.170596 -vn 0.391168 6.114681 0.921655 -v 0.037256 0.090344 0.169632 -vn 2.825420 5.511123 -0.000005 -v 0.037178 0.090439 0.168650 -vn -4.104347 4.643537 1.015838 -v 0.037405 0.090364 0.169836 -vn -3.796134 4.942876 0.596856 -v 0.037405 0.090397 0.169640 -vn -3.804207 4.975986 -0.002709 -v 0.037405 0.090471 0.168650 -vn -3.792408 4.946323 -0.595804 -v 0.037405 0.090397 0.167660 -vn -3.794967 4.486329 2.161729 -v 0.037405 0.089813 0.171533 -vn -2.154750 4.773351 3.296633 -v 0.037336 0.089282 0.172369 -vn -3.791688 4.075974 2.866252 -v 0.037405 0.089317 0.172393 -vn -4.158358 4.065962 2.374939 -v 0.037405 0.089531 0.172058 -vn 0.391360 5.109223 3.483393 -v 0.037256 0.089272 0.172363 -vn -4.037424 3.714855 3.052214 -v 0.037405 0.088830 0.173022 -vn -4.156751 1.405066 4.495744 -v 0.037405 0.085880 0.174969 -vn -3.806724 1.899316 4.594298 -v 0.037405 0.086254 0.174835 -vn -2.143318 2.172182 5.385446 -v 0.037336 0.086239 0.174796 -vn 0.391173 3.091875 5.355274 -v 0.037256 0.087122 0.174358 -vn -4.104379 2.101081 4.263729 -v 0.037405 0.086975 0.174501 -vn -3.797258 2.613504 4.236434 -v 0.037405 0.087149 0.174404 -vn -3.808175 3.101815 3.886546 -v 0.037405 0.087969 0.173845 -vn -3.795272 3.548777 3.493226 -v 0.037405 0.088697 0.173169 -vn -3.789647 1.113244 4.858811 -v 0.037405 0.085305 0.175128 -vn -2.154463 0.398711 5.787579 -v 0.037336 0.084320 0.175234 -vn -3.793003 0.298541 4.972642 -v 0.037405 0.084323 0.175276 -vn -4.159996 0.679622 4.657976 -v 0.037405 0.084719 0.175234 -vn 0.391113 0.462119 6.166432 -v 0.037256 0.084319 0.175223 -vn -4.037554 -0.069771 4.807272 -v 0.037405 0.083529 0.175288 -vn -4.159071 -2.635837 3.901133 -v 0.037405 0.080166 0.174195 -vn -3.806205 -2.407476 4.350105 -v 0.037405 0.080505 0.174404 -vn -2.142940 -2.856173 5.056162 -v 0.037336 0.080526 0.174368 -vn 0.391121 -2.259152 5.756191 -v 0.037256 0.081419 0.174785 -vn -4.104042 -2.024129 4.301144 -v 0.037405 0.081215 0.174760 -vn -3.797928 -1.683220 4.683892 -v 0.037405 0.081399 0.174835 -vn -3.810668 -1.104919 4.846034 -v 0.037405 0.082348 0.175128 -vn -3.796435 -0.517285 4.951519 -v 0.037405 0.083330 0.175276 -vn -3.792321 -3.105023 3.896432 -v 0.037405 0.079684 0.173845 -vn -2.154829 -4.276104 3.920097 -v 0.037336 0.078987 0.173141 -vn -3.794301 -3.701557 3.332337 -v 0.037405 0.078956 0.173169 -vn -4.161136 -3.216532 3.435548 -v 0.037405 0.079235 0.173453 -vn 0.391065 -4.533022 4.206015 -v 0.037256 0.078995 0.173133 -vn -4.037554 -3.802106 2.942606 -v 0.037405 0.078451 0.172555 -vn -4.160742 -4.691820 0.373061 -v 0.037405 0.077209 0.169246 -vn -3.805501 -4.902581 0.831137 -v 0.037405 0.077257 0.169640 -vn -2.143127 -5.733755 0.919354 -v 0.037336 0.077298 0.169634 -vn 0.391257 -5.909036 1.822706 -v 0.037256 0.077529 0.170593 -vn -4.103015 -4.625956 1.098408 -v 0.037405 0.077422 0.170418 -vn -3.798119 -4.711464 1.604138 -v 0.037405 0.077478 0.170608 -vn -3.811906 -4.477036 2.156445 -v 0.037405 0.077840 0.171533 -vn -3.797248 -4.192605 2.683393 -v 0.037405 0.078337 0.172393 -vn -3.806775 4.551062 -1.942670 -v 0.040325 0.092539 0.165201 -vn -3.805054 4.386584 -2.287475 -v 0.040325 0.092038 0.164136 -vn -3.707518 4.242452 -2.660730 -v 0.040325 0.091870 0.163844 -vn -3.791916 4.017131 -2.895046 -v 0.040325 0.091407 0.163143 -vn -3.751933 3.803149 -3.218847 -v 0.040325 0.090883 0.162485 -vn -3.806936 -0.818232 -4.877195 -v 0.040325 0.082071 0.159446 -vn -3.807740 3.527206 -3.465216 -v 0.040325 0.090657 0.162236 -vn -3.809777 3.254144 -3.724004 -v 0.040325 0.089799 0.161430 -vn -3.770930 2.988726 -3.970593 -v 0.040325 0.089669 0.161324 -vn -3.803483 2.697426 -4.142215 -v 0.040325 0.088847 0.160739 -vn -3.740502 2.382838 -4.381167 -v 0.040325 0.088267 0.160399 -vn -3.810886 2.026365 -4.503667 -v 0.040325 0.087816 0.160172 -vn -3.795234 1.528493 -4.698324 -v 0.040325 0.086722 0.159739 -vn -3.803515 1.011962 -4.841060 -v 0.040325 0.085583 0.159446 -vn -3.640238 0.601653 -5.007972 -v 0.040325 0.085085 0.159365 -vn -3.785938 0.296376 -4.945751 -v 0.040325 0.084415 0.159299 -vn -3.780709 -0.100847 -4.964323 -v 0.040325 0.083406 0.159290 -vn -3.808433 -0.442267 -4.926930 -v 0.040325 0.083238 0.159299 -vn -3.708608 -1.220293 -4.855744 -v 0.040325 0.081742 0.159515 -vn -3.792301 -1.509880 -4.715439 -v 0.040325 0.080931 0.159739 -vn -3.750900 -1.887552 -4.612155 -v 0.040325 0.080144 0.160034 -vn -3.805521 -2.204335 -4.428471 -v 0.040325 0.079837 0.160172 -vn -3.806863 -2.539780 -4.246734 -v 0.040325 0.078806 0.160739 -vn -3.766461 -2.851494 -4.075512 -v 0.040325 0.078665 0.160830 -vn -3.798257 -3.112655 -3.846538 -v 0.040325 0.077854 0.161430 -vn -3.736016 -3.430204 -3.626204 -v 0.040325 0.077352 0.161878 -vn -3.805674 -3.663767 -3.319053 -v 0.040325 0.076997 0.162236 -vn -3.795332 -3.996082 -2.905325 -v 0.040325 0.076246 0.163143 -vn -3.804358 -4.290606 -2.458239 -v 0.040325 0.075616 0.164136 -vn -3.640737 -4.576708 -2.119179 -v 0.040325 0.075385 0.164585 -vn -3.785510 -4.611882 -1.812006 -v 0.040325 0.075115 0.165201 -vn -3.778933 -4.754496 -1.437371 -v 0.040325 0.074795 0.166157 -vn -3.807843 -4.823015 -1.102218 -v 0.040325 0.074751 0.166320 -vn -3.805764 -4.892542 -0.728471 -v 0.040325 0.074531 0.167476 -vn -3.708625 -4.995167 -0.339935 -v 0.040325 0.074495 0.167810 -vn -3.792818 -4.950694 -0.020100 -v 0.040325 0.074457 0.168650 -vn -3.752966 -4.967745 0.369524 -v 0.040325 0.074495 0.169490 -vn -3.806742 -4.891731 0.727498 -v 0.040325 0.074531 0.169824 -vn -3.807851 -4.823008 1.102227 -v 0.040325 0.074751 0.170980 -vn -3.765942 -4.757825 1.452161 -v 0.040325 0.074795 0.171143 -vn -3.798462 -4.619845 1.771986 -v 0.040325 0.075115 0.172099 -vn -3.735830 -4.508985 2.141657 -v 0.040325 0.075385 0.172715 -vn -3.804353 -4.290621 2.458211 -v 0.040325 0.075616 0.173164 -vn -3.794921 -3.996648 2.905241 -v 0.040325 0.076246 0.174157 -vn -3.805038 -3.664093 3.319619 -v 0.040325 0.076997 0.175064 -vn -3.641721 -3.428391 3.697816 -v 0.040325 0.077352 0.175422 -vn -3.787291 -3.147047 3.825102 -v 0.040325 0.077854 0.175870 -vn -3.782050 -2.834419 4.075226 -v 0.040325 0.078665 0.176470 -vn -3.808723 -2.539991 4.244576 -v 0.040325 0.078806 0.176561 -vn -3.805444 -2.204369 4.428502 -v 0.040325 0.079837 0.177128 -vn -3.707378 -1.868337 4.646297 -v 0.040325 0.080144 0.177266 -vn -3.792293 -1.548136 4.703013 -v 0.040325 0.080931 0.177561 -vn -3.752041 -1.184692 4.839465 -v 0.040325 0.081742 0.177785 -vn -3.806940 -0.818239 4.877192 -v 0.040325 0.082071 0.177854 -vn -3.808190 -0.442493 4.927152 -v 0.040325 0.083238 0.178001 -vn -3.768326 -0.086784 4.971503 -v 0.040325 0.083406 0.178010 -vn -3.800166 0.255381 4.939726 -v 0.040325 0.084415 0.178001 -vn -3.737744 0.645130 4.948000 -v 0.040325 0.085085 0.177935 -vn -3.807435 1.011144 4.837327 -v 0.040325 0.085583 0.177854 -vn -3.794723 1.524805 4.700048 -v 0.040325 0.086722 0.177561 -vn -3.803330 2.027279 4.511311 -v 0.040325 0.087816 0.177128 -vn -3.639901 2.456769 4.405618 -v 0.040325 0.088267 0.176901 -vn -3.786035 2.667487 4.175192 -v 0.040325 0.088847 0.176561 -vn -3.780425 2.999592 3.957212 -v 0.040325 0.089669 0.175976 -vn -3.809778 3.254141 3.724004 -v 0.040325 0.089799 0.175870 -vn -3.807853 3.527249 3.465007 -v 0.040325 0.090657 0.175064 -vn -3.710779 3.841159 3.208181 -v 0.040325 0.090883 0.174815 -vn -3.795211 3.990282 2.926527 -v 0.040325 0.091407 0.174157 -vn -3.755063 4.235512 2.618261 -v 0.040325 0.091870 0.173456 -vn -3.808424 4.382399 2.288431 -v 0.040325 0.092038 0.173164 -vn -3.806813 4.551021 1.942728 -v 0.040325 0.092539 0.172099 -vn -3.765647 4.702898 1.622114 -v 0.040325 0.092599 0.171942 -vn -3.797711 4.779837 1.281788 -v 0.040325 0.092902 0.170980 -vn -3.735304 4.907076 0.918170 -v 0.040325 0.093046 0.170323 -vn -3.805349 4.915345 0.531040 -v 0.040325 0.093123 0.169824 -vn -3.799122 4.936826 -0.001979 -v 0.040325 0.093197 0.168650 -vn -3.807898 4.913040 -0.529163 -v 0.040325 0.093123 0.167476 -vn -3.644080 4.944459 -0.978341 -v 0.040325 0.093046 0.166977 -vn -3.790135 4.792281 -1.241777 -v 0.040325 0.092902 0.166320 -vn -3.780414 4.690485 -1.629895 -v 0.040325 0.092599 0.165358 -vn 3.702533 -4.268673 2.638710 -v 0.041682 0.075777 0.173459 -vn 3.743327 -4.021838 2.949654 -v 0.041682 0.076241 0.174162 -vn 2.173341 -4.622728 3.379471 -v 0.041367 0.076083 0.174276 -vn 3.728171 -3.023246 3.988447 -v 0.041682 0.077980 0.175981 -vn 3.733966 -2.688618 4.208100 -v 0.041682 0.078802 0.176567 -vn 2.179109 -3.058655 4.836258 -v 0.041367 0.078698 0.176732 -vn 3.729851 2.856773 4.107385 -v 0.041682 0.088992 0.176476 -vn 3.735236 3.171860 3.855329 -v 0.041682 0.089804 0.175875 -vn 2.179123 3.654375 4.403494 -v 0.041367 0.089928 0.176025 -vn 3.726660 4.791984 -1.448755 -v 0.041682 0.092866 0.166155 -vn 3.733457 4.648282 -1.826261 -v 0.041682 0.092545 0.165198 -vn 2.179102 5.317194 -2.114784 -v 0.041367 0.092727 0.165126 -vn 3.728418 0.101744 -5.003501 -v 0.041682 0.084247 0.159283 -vn 3.733860 -0.298651 -4.984797 -v 0.041682 0.083238 0.159292 -vn 2.179137 -0.368144 -5.710480 -v 0.041367 0.083226 0.159097 -vn 2.164017 2.457963 5.178306 -v 0.041367 0.087902 0.177311 -vn -0.031683 2.604411 5.534629 -v 0.041002 0.087931 0.177371 -vn -0.031617 1.890203 5.817440 -v 0.041002 0.086805 0.177817 -vn 2.164006 5.684405 -0.737459 -v 0.041367 0.093323 0.167450 -vn -0.031665 6.068581 -0.766625 -v 0.041002 0.093390 0.167442 -vn -0.031661 6.116805 0.000000 -v 0.041002 0.093466 0.168650 -vn 2.163985 1.055205 -5.634086 -v 0.041367 0.085620 0.159248 -vn -0.031711 1.146170 -6.008447 -v 0.041002 0.085633 0.159182 -vn -0.031610 1.890215 -5.817441 -v 0.041002 0.086805 0.159483 -vn 2.164045 -5.032241 -2.744577 -v 0.041367 0.075439 0.164039 -vn -0.031681 -5.360189 -2.946783 -v 0.041002 0.075380 0.164007 -vn -0.031677 -4.948573 -3.595369 -v 0.041002 0.076029 0.162984 -vn -2.225039 2.412498 5.173761 -v 0.040638 0.087901 0.177307 -vn -2.244228 1.759973 5.416647 -v 0.040638 0.086784 0.177750 -vn -2.225018 5.666027 -0.695602 -v 0.040638 0.093319 0.167451 -vn -2.244263 5.695411 0.000004 -v 0.040638 0.093395 0.168650 -vn -2.225039 1.089336 -5.603691 -v 0.040638 0.085620 0.159251 -vn -2.244240 1.759967 -5.416648 -v 0.040638 0.086784 0.159550 -vn -2.225049 -4.992776 -2.767647 -v 0.040638 0.075442 0.164041 -vn -2.244342 -4.607674 -3.347653 -v 0.040638 0.076086 0.163026 -vn -2.224952 -4.175057 3.893163 -v 0.040638 0.076852 0.175200 -vn -2.223529 -5.661991 -0.734471 -v 0.040638 0.074334 0.167451 -vn -2.225064 -5.533762 -1.401653 -v 0.040638 0.074559 0.166271 -vn -2.222976 -4.181193 -3.889014 -v 0.040638 0.076852 0.162100 -vn -2.227438 -3.620034 -4.412333 -v 0.040638 0.077728 0.161278 -vn -2.227807 -3.047185 -4.824749 -v 0.040638 0.078700 0.160571 -vn -2.220907 -2.456069 -5.156441 -v 0.040638 0.079753 0.159993 -vn -2.232701 -1.746566 -5.429646 -v 0.040638 0.080870 0.159550 -vn -2.223577 -1.051146 -5.611837 -v 0.040638 0.082034 0.159251 -vn -2.225044 -0.376942 -5.696060 -v 0.040638 0.083226 0.159101 -vn -2.223023 2.406591 -5.178304 -v 0.040638 0.087901 0.159993 -vn -2.227446 3.077719 -4.806345 -v 0.040638 0.088954 0.160571 -vn -2.227804 3.646988 -4.388965 -v 0.040638 0.089926 0.161278 -vn -2.220863 4.145117 -3.929296 -v 0.040638 0.090802 0.162100 -vn -2.232806 4.624154 -3.338954 -v 0.040638 0.091568 0.163026 -vn -2.223592 5.012343 -2.733816 -v 0.040638 0.092211 0.164041 -vn -2.225036 5.300822 -2.118670 -v 0.040638 0.092723 0.165128 -vn -2.223035 5.668554 0.688616 -v 0.040638 0.093319 0.169849 -vn -2.227498 5.522164 1.441849 -v 0.040638 0.093094 0.171029 -vn -2.227828 5.301126 2.112224 -v 0.040638 0.092723 0.172172 -vn -2.220911 5.017888 2.728017 -v 0.040638 0.092211 0.173259 -vn -2.232747 4.604488 3.366035 -v 0.040638 0.091568 0.174274 -vn -2.223500 4.148920 3.922226 -v 0.040638 0.090802 0.175200 -vn -2.225028 3.653035 4.386657 -v 0.040638 0.089926 0.176022 -vn -2.223049 1.096785 5.603937 -v 0.040638 0.085620 0.178049 -vn -2.227432 0.335166 5.697448 -v 0.040638 0.084428 0.178199 -vn -2.227797 -0.370708 5.694379 -v 0.040638 0.083226 0.178199 -vn -2.220952 -1.043891 5.615321 -v 0.040638 0.082034 0.178049 -vn -2.232708 -1.778456 5.419279 -v 0.040638 0.080870 0.177750 -vn -2.223571 -2.448188 5.157912 -v 0.040638 0.079753 0.177307 -vn -2.224989 -3.043086 4.829786 -v 0.040638 0.078700 0.176729 -vn -2.227823 -5.530226 1.407092 -v 0.040638 0.074559 0.171029 -vn -2.227452 -5.315001 2.079356 -v 0.040638 0.074931 0.172172 -vn -2.220898 -5.663068 0.742414 -v 0.040638 0.074334 0.169849 -vn -2.232738 -5.703629 -0.016736 -v 0.040638 0.074259 0.168650 -vn -0.031675 -5.924634 -1.521184 -v 0.041002 0.074491 0.166253 -vn -0.031668 -6.068582 -0.766634 -v 0.041002 0.074264 0.167442 -vn -0.031626 -4.458971 -4.187270 -v 0.041002 0.076800 0.162052 -vn -0.031707 -3.899024 -4.713070 -v 0.041002 0.077683 0.161223 -vn -0.031624 -3.277533 -5.164578 -v 0.041002 0.078662 0.160512 -vn -0.031576 -2.604394 -5.534666 -v 0.041002 0.079723 0.159929 -vn -0.031617 -1.890203 -5.817440 -v 0.041002 0.080848 0.159483 -vn -0.031719 -1.146201 -6.008441 -v 0.041002 0.082021 0.159182 -vn -0.031606 -0.384070 -6.104731 -v 0.041002 0.083222 0.159030 -vn -0.031588 2.604402 -5.534661 -v 0.041002 0.087931 0.159929 -vn -0.031623 3.277535 -5.164571 -v 0.041002 0.088991 0.160512 -vn -0.031688 3.899007 -4.713083 -v 0.041002 0.089971 0.161223 -vn -0.031638 4.458983 -4.187258 -v 0.041002 0.090853 0.162052 -vn -0.031649 4.948564 -3.595364 -v 0.041002 0.091625 0.162984 -vn -0.031667 5.360188 -2.946782 -v 0.041002 0.092273 0.164007 -vn -0.031712 5.687270 -2.251742 -v 0.041002 0.092789 0.165102 -vn -0.031668 6.068578 0.766633 -v 0.041002 0.093390 0.169858 -vn -0.031733 5.924621 1.521180 -v 0.041002 0.093163 0.171047 -vn -0.031707 5.687267 2.251750 -v 0.041002 0.092789 0.172198 -vn -0.031677 5.360213 2.946797 -v 0.041002 0.092273 0.173293 -vn -0.031641 4.948604 3.595370 -v 0.041002 0.091625 0.174315 -vn -0.031629 4.458982 4.187253 -v 0.041002 0.090853 0.175248 -vn -0.031614 3.898985 4.713074 -v 0.041002 0.089971 0.176077 -vn -0.031719 1.146201 6.008441 -v 0.041002 0.085633 0.178118 -vn -0.031606 0.384070 6.104731 -v 0.041002 0.084432 0.178270 -vn -0.031608 -0.384085 6.104726 -v 0.041002 0.083222 0.178270 -vn -0.031711 -1.146170 6.008447 -v 0.041002 0.082021 0.178118 -vn -0.031620 -1.890227 5.817434 -v 0.041002 0.080848 0.177817 -vn -0.031676 -2.604395 5.534636 -v 0.041002 0.079723 0.177371 -vn -0.031623 -3.277569 5.164612 -v 0.041002 0.078662 0.176788 -vn -0.031716 -6.116817 0.000007 -v 0.041002 0.074188 0.168650 -vn -0.031665 -6.068582 0.766625 -v 0.041002 0.074264 0.169858 -vn -0.031681 -5.924631 1.521188 -v 0.041002 0.074491 0.171047 -vn -0.031661 -5.687276 2.251756 -v 0.041002 0.074865 0.172198 -vn 2.179106 -5.544738 -1.414485 -v 0.041367 0.074556 0.166270 -vn 2.165504 -5.688499 -0.698283 -v 0.041367 0.074330 0.167450 -vn 2.173364 -4.642571 -3.352192 -v 0.041367 0.076083 0.163024 -vn 2.161318 -4.161463 -3.944920 -v 0.041367 0.076849 0.162098 -vn 2.168314 -3.661489 -4.406329 -v 0.041367 0.077725 0.161275 -vn 2.167996 -3.089991 -4.825384 -v 0.041367 0.078698 0.160568 -vn 2.163495 -2.416042 -5.198896 -v 0.041367 0.079751 0.159989 -vn 2.185005 -1.767026 -5.438280 -v 0.041367 0.080869 0.159547 -vn 2.165473 -1.093744 -5.625878 -v 0.041367 0.082033 0.159248 -vn 2.173320 1.753498 -5.451254 -v 0.041367 0.086785 0.159547 -vn 2.161355 2.465895 -5.176838 -v 0.041367 0.087902 0.159989 -vn 2.168355 3.059225 -4.843928 -v 0.041367 0.088956 0.160568 -vn 2.167957 3.634305 -4.429877 -v 0.041367 0.089928 0.161275 -vn 2.163500 4.197822 -3.904321 -v 0.041367 0.090804 0.162098 -vn 2.185072 4.626077 -3.361050 -v 0.041367 0.091571 0.163024 -vn 2.165520 5.012529 -2.778685 -v 0.041367 0.092215 0.164039 -vn 2.173346 5.726293 -0.016868 -v 0.041367 0.093399 0.168650 -vn 2.161345 5.685455 0.745463 -v 0.041367 0.093323 0.169850 -vn 2.168334 5.552179 1.412627 -v 0.041367 0.093098 0.171030 -vn 2.167959 5.336127 2.087540 -v 0.041367 0.092727 0.172174 -vn 2.163471 5.010433 2.785877 -v 0.041367 0.092215 0.173261 -vn 2.185045 4.626057 3.361045 -v 0.041367 0.091571 0.174276 -vn 2.165492 4.191648 3.908527 -v 0.041367 0.090804 0.175202 -vn 2.173330 1.785573 5.440822 -v 0.041367 0.086785 0.177753 -vn 2.161417 1.047910 5.637500 -v 0.041367 0.085620 0.178052 -vn 2.168358 0.372228 5.716984 -v 0.041367 0.084428 0.178203 -vn 2.168004 -0.336416 5.720057 -v 0.041367 0.083226 0.178203 -vn 2.163550 -1.101200 5.626049 -v 0.041367 0.082033 0.178052 -vn 2.185018 -1.767009 5.438279 -v 0.041367 0.080869 0.177753 -vn 2.165498 -2.421972 5.194312 -v 0.041367 0.079751 0.177311 -vn -2.244267 -4.607676 3.347671 -v 0.040638 0.076086 0.174274 -vn -0.031623 -4.458982 4.187253 -v 0.041002 0.076800 0.175248 -vn -0.031686 -4.948608 3.595378 -v 0.041002 0.076029 0.174315 -vn 2.163973 -4.165306 3.937837 -v 0.041367 0.076849 0.175202 -vn 2.185015 -5.718112 0.000002 -v 0.041367 0.074255 0.168650 -vn 2.163492 -5.691027 0.691242 -v 0.041367 0.074330 0.169850 -vn 2.167984 -5.544032 1.447648 -v 0.041367 0.074556 0.171030 -vn 2.168316 -5.322132 2.120661 -v 0.041367 0.074927 0.172174 -vn 3.590303 -4.981833 -0.985624 -v 0.041682 0.074601 0.166976 -vn 3.738204 -4.830091 -1.251595 -v 0.041682 0.074745 0.166318 -vn 3.728216 -4.727428 -1.642820 -v 0.041682 0.075048 0.165355 -vn 3.754947 -4.587199 -1.958130 -v 0.041682 0.075108 0.165198 -vn 2.165517 -5.321776 -2.127150 -v 0.041367 0.074927 0.165126 -vn -0.031661 -5.687280 -2.251753 -v 0.041002 0.074865 0.165102 -vn -2.238411 -5.296119 -2.106363 -v 0.040638 0.074931 0.165128 -vn 3.753178 -4.421423 -2.305646 -v 0.041682 0.075610 0.164133 -vn 3.718685 -3.012179 -4.001787 -v 0.041682 0.077980 0.161319 -vn 3.758003 -3.279966 -3.753622 -v 0.041682 0.077850 0.161425 -vn 3.755923 -3.555253 -3.492719 -v 0.041682 0.076991 0.162231 -vn 3.699341 -3.832877 -3.244050 -v 0.041682 0.076765 0.162481 -vn 3.739903 -4.048852 -2.918001 -v 0.041682 0.076241 0.163138 -vn 3.654373 -4.275248 -2.681172 -v 0.041682 0.075777 0.163841 -vn 3.751706 -2.718828 -4.175022 -v 0.041682 0.078802 0.160733 -vn 3.687732 -2.401376 -4.415344 -v 0.041682 0.079383 0.160393 -vn 3.759145 -2.042490 -4.539454 -v 0.041682 0.079834 0.160166 -vn 3.743383 -1.540604 -4.735462 -v 0.041682 0.080929 0.159732 -vn 3.751678 -1.019963 -4.879464 -v 0.041682 0.082070 0.159439 -vn 3.586350 -0.606279 -5.045788 -v 0.041682 0.082568 0.159358 -vn 3.756577 0.445860 -4.966114 -v 0.041682 0.084416 0.159292 -vn 2.165540 0.378508 -5.718660 -v 0.041367 0.084428 0.159097 -vn -0.031608 0.384085 -6.104726 -v 0.041002 0.084432 0.159030 -vn -2.238423 0.366681 -5.687811 -v 0.040638 0.084428 0.159101 -vn 3.755146 0.824682 -4.915924 -v 0.041682 0.085584 0.159439 -vn 3.714045 2.873863 -4.107553 -v 0.041682 0.088992 0.160824 -vn 3.754972 2.560022 -4.280460 -v 0.041682 0.088851 0.160733 -vn 3.753591 2.221823 -4.463693 -v 0.041682 0.087819 0.160166 -vn 3.698210 1.902344 -4.648250 -v 0.041682 0.087512 0.160028 -vn 3.740288 1.521878 -4.752724 -v 0.041682 0.086724 0.159732 -vn 3.655473 1.229633 -4.893239 -v 0.041682 0.085913 0.159508 -vn 3.746376 3.137337 -3.876960 -v 0.041682 0.089804 0.161425 -vn 3.683264 3.456917 -3.654387 -v 0.041682 0.090307 0.161872 -vn 3.753883 3.692815 -3.345418 -v 0.041682 0.090662 0.162231 -vn 3.743453 4.027658 -2.928338 -v 0.041682 0.091413 0.163138 -vn 3.752523 4.324677 -2.477700 -v 0.041682 0.092044 0.164133 -vn 3.586865 4.611237 -2.135275 -v 0.041682 0.092275 0.164582 -vn 3.755959 4.861341 -1.111064 -v 0.041682 0.092909 0.166318 -vn 2.165514 5.555722 -1.407159 -v 0.041367 0.093098 0.166270 -vn -0.031733 5.924619 -1.521192 -v 0.041002 0.093163 0.166253 -vn -2.238490 5.522736 -1.408918 -v 0.040638 0.093094 0.166271 -vn 3.753951 4.931380 -0.734284 -v 0.041682 0.093130 0.167475 -vn 3.713547 4.795189 1.463560 -v 0.041682 0.092866 0.171145 -vn 3.755980 4.861328 1.111066 -v 0.041682 0.092909 0.170982 -vn 3.754946 4.930571 0.733300 -v 0.041682 0.093130 0.169825 -vn 3.700382 5.006597 0.372471 -v 0.041682 0.093166 0.169491 -vn 3.740862 4.989834 -0.020224 -v 0.041682 0.093204 0.168650 -vn 3.655480 5.033717 -0.342670 -v 0.041682 0.093166 0.167809 -vn 3.746542 4.656435 1.786050 -v 0.041682 0.092545 0.172102 -vn 3.683009 4.544085 2.158342 -v 0.041682 0.092275 0.172718 -vn 3.752520 4.324669 2.477716 -v 0.041682 0.092044 0.173167 -vn 3.743086 4.028220 2.928219 -v 0.041682 0.091413 0.174162 -vn 3.753238 3.693143 3.345979 -v 0.041682 0.090662 0.175069 -vn 3.587915 3.454382 3.725639 -v 0.041682 0.090307 0.175428 -vn 3.756877 2.560253 4.278286 -v 0.041682 0.088851 0.176567 -vn 2.165505 3.055100 4.848962 -v 0.041367 0.088956 0.176732 -vn -0.031626 3.277563 5.164615 -v 0.041002 0.088991 0.176788 -vn -2.238396 3.046530 4.817065 -v 0.040638 0.088954 0.176729 -vn 3.753587 2.221846 4.463682 -v 0.041682 0.087819 0.177134 -vn 3.715880 0.087578 5.010592 -v 0.041682 0.084247 0.178017 -vn 3.756320 0.446125 4.966328 -v 0.041682 0.084416 0.178008 -vn 3.755228 0.824689 4.915880 -v 0.041682 0.085584 0.177861 -vn 3.699501 1.193908 4.877293 -v 0.041682 0.085913 0.177792 -vn 3.740280 1.560311 4.740236 -v 0.041682 0.086724 0.177568 -vn 3.654253 1.882820 4.682111 -v 0.041682 0.087512 0.177272 -vn 3.748267 -0.257473 4.978875 -v 0.041682 0.083238 0.178008 -vn 3.685076 -0.650158 4.986479 -v 0.041682 0.082568 0.177942 -vn 3.755772 -1.019124 4.875676 -v 0.041682 0.082070 0.177861 -vn 3.742850 -1.536812 4.737227 -v 0.041682 0.080929 0.177568 -vn 3.751480 -2.043362 4.547103 -v 0.041682 0.079834 0.177134 -vn 3.585922 -2.475266 4.438965 -v 0.041682 0.079383 0.176907 -vn 3.757935 -3.279988 3.753655 -v 0.041682 0.077850 0.175875 -vn 2.165536 -3.667576 4.404008 -v 0.041367 0.077725 0.176025 -vn -0.031614 -3.898987 4.713072 -v 0.041002 0.077683 0.176077 -vn -2.238426 -3.639848 4.386033 -v 0.040638 0.077728 0.176022 -vn 3.756039 -3.555243 3.492570 -v 0.041682 0.076991 0.175069 -vn 3.657648 -3.870783 3.233023 -v 0.041682 0.076765 0.174819 -vn 3.756639 -4.417192 2.306649 -v 0.041682 0.075610 0.173167 -vn 2.161323 -5.037801 2.738729 -v 0.041367 0.075439 0.173261 -vn -0.031672 -5.360213 2.946798 -v 0.041002 0.075380 0.173293 -vn -2.223026 -4.990714 2.774792 -v 0.040638 0.075442 0.173259 -vn 3.754950 -4.587199 1.958127 -v 0.041682 0.075108 0.172102 -vn 3.756144 -4.952044 -0.533359 -v 0.041682 0.074524 0.167475 -vn 3.747453 -4.975821 -0.002022 -v 0.041682 0.074450 0.168650 -vn 3.753534 -4.954353 0.535274 -v 0.041682 0.074524 0.169825 -vn 3.682510 -4.945261 0.925298 -v 0.041682 0.074601 0.170324 -vn 3.745828 -4.817680 1.291890 -v 0.041682 0.074745 0.170982 -vn 3.713239 -4.739810 1.634891 -v 0.041682 0.075048 0.171945 -vn 4.001643 -4.514734 -1.741813 -v 0.044630 0.077571 0.166302 -vn 3.665136 -4.564762 -2.197572 -v 0.044630 0.077806 0.165751 -vn 4.006857 -4.174791 -2.438025 -v 0.044630 0.078091 0.165223 -vn 3.676064 -4.127573 -2.925449 -v 0.044630 0.078306 0.164886 -vn 3.949835 -3.784741 -3.075786 -v 0.044630 0.078795 0.164254 -vn 3.663957 -3.610883 -3.554807 -v 0.044630 0.078929 0.164105 -vn 3.680877 1.124611 -4.932272 -v 0.044630 0.085314 0.162135 -vn 3.665469 0.526147 -5.038450 -v 0.044630 0.084326 0.161987 -vn 3.674537 -3.155827 -3.960796 -v 0.044630 0.079661 0.163426 -vn 3.659528 -2.663522 -4.315067 -v 0.044630 0.080486 0.162863 -vn 3.883167 -2.205655 -4.405043 -v 0.044630 0.080660 0.162766 -vn 3.653959 -1.917974 -4.699629 -v 0.044630 0.081386 0.162430 -vn 3.997729 -1.455609 -4.618528 -v 0.044630 0.081762 0.162295 -vn 3.664060 -1.129327 -4.939665 -v 0.044630 0.082340 0.162135 -vn 4.006883 -0.696791 -4.784057 -v 0.044630 0.082930 0.162028 -vn 3.674917 -0.285057 -5.052145 -v 0.044630 0.083327 0.161987 -vn 3.948559 0.043702 -4.877906 -v 0.044630 0.084127 0.161975 -vn 3.666989 1.712718 -4.766087 -v 0.044630 0.086268 0.162430 -vn 3.888884 2.066750 -4.466352 -v 0.044630 0.086453 0.162506 -vn 3.665464 2.468656 -4.423689 -v 0.044630 0.087168 0.162863 -vn 4.005621 2.706148 -4.007505 -v 0.044630 0.087508 0.163073 -vn 3.664217 3.158348 -3.962350 -v 0.044630 0.087993 0.163426 -vn 4.006074 3.305922 -3.528507 -v 0.044630 0.088445 0.163820 -vn 3.672604 3.774845 -3.372782 -v 0.044630 0.088725 0.164105 -vn 3.946934 3.841015 -3.009466 -v 0.044630 0.089233 0.164722 -vn 3.666189 4.266256 -2.730433 -v 0.044630 0.089348 0.164886 -vn 3.682174 4.556733 -2.194798 -v 0.044630 0.089847 0.165751 -vn 3.666841 4.794275 -1.632509 -v 0.044630 0.090212 0.166680 -vn 3.887812 4.781711 -1.168131 -v 0.044630 0.090268 0.166872 -vn 3.664762 4.998202 -0.829301 -v 0.044630 0.090434 0.167654 -vn 4.005695 4.820395 -0.382780 -v 0.044630 0.090482 0.168051 -vn 3.662929 5.068137 0.000005 -v 0.044630 0.090509 0.168650 -vn 4.004837 4.821082 0.383602 -v 0.044630 0.090482 0.169249 -vn 3.674818 4.989063 0.845825 -v 0.044630 0.090434 0.169646 -vn 3.949257 4.745146 1.128427 -v 0.044630 0.090268 0.170428 -vn 3.666723 4.794347 1.632513 -v 0.044630 0.090212 0.170620 -vn 3.682332 4.556638 2.194770 -v 0.044630 0.089847 0.171549 -vn 3.666205 4.266199 2.730510 -v 0.044630 0.089348 0.172414 -vn 3.885842 3.894962 3.012571 -v 0.044630 0.089233 0.172578 -vn 3.662730 3.766743 3.390973 -v 0.044630 0.088725 0.173195 -vn 4.005177 3.305416 3.530069 -v 0.044630 0.088445 0.173480 -vn 3.661262 3.159488 3.964729 -v 0.044630 0.087993 0.173874 -vn 4.003150 2.708217 4.008728 -v 0.044630 0.087508 0.174227 -vn 3.675637 2.449897 4.426808 -v 0.044630 0.087168 0.174437 -vn 3.950416 2.074980 4.412950 -v 0.044630 0.086453 0.174794 -vn 3.666993 1.712712 4.766088 -v 0.044630 0.086268 0.174870 -vn 3.681226 1.124548 4.932071 -v 0.044630 0.085314 0.175165 -vn 3.665679 0.526339 5.038245 -v 0.044630 0.084326 0.175313 -vn 3.886124 0.072953 4.923278 -v 0.044630 0.084127 0.175325 -vn 3.662161 -0.303833 5.059700 -v 0.044630 0.083327 0.175313 -vn 4.004092 -0.698144 4.786328 -v 0.044630 0.082930 0.175272 -vn 3.658399 -1.132678 4.944054 -v 0.044630 0.082340 0.175165 -vn 4.000998 -1.443991 4.619246 -v 0.044630 0.081762 0.175005 -vn 3.676245 -1.932828 4.675245 -v 0.044630 0.081386 0.174870 -vn 3.950875 -2.156758 4.373113 -v 0.044630 0.080660 0.174534 -vn 3.666206 -2.659472 4.310744 -v 0.044630 0.080486 0.174437 -vn 3.678630 -3.156884 3.955547 -v 0.044630 0.079661 0.173874 -vn 3.663738 -3.611164 3.554790 -v 0.044630 0.078929 0.173195 -vn 3.885655 -3.803706 3.127265 -v 0.044630 0.078795 0.173046 -vn 3.660337 -4.147490 2.916687 -v 0.044630 0.078306 0.172414 -vn 4.002586 -4.177707 2.440473 -v 0.044630 0.078091 0.172077 -vn 3.663696 -4.565185 2.199682 -v 0.044630 0.077806 0.171549 -vn 4.006193 -4.509397 1.744645 -v 0.044630 0.077571 0.170998 -vn 3.676337 -4.860253 1.403644 -v 0.044630 0.077442 0.170620 -vn 3.950641 -4.763915 1.040580 -v 0.044630 0.077252 0.169843 -vn 3.664975 -5.029687 0.607320 -v 0.044630 0.077219 0.169646 -vn 3.674507 -5.064298 -0.002740 -v 0.044630 0.077145 0.168650 -vn 3.661225 -5.033097 -0.606260 -v 0.044630 0.077219 0.167654 -vn 3.884647 -4.817611 -1.023333 -v 0.044630 0.077252 0.167457 -vn 3.657581 -4.867914 -1.426999 -v 0.044630 0.077442 0.166680 -vn 1.720380 -5.664599 1.690109 -v 0.044711 0.077485 0.170606 -vn 1.729233 -5.848598 0.823872 -v 0.044711 0.077264 0.169639 -vn -1.191818 -5.979417 0.901243 -v 0.044803 0.077268 0.169639 -vn 1.720535 -2.210378 5.482460 -v 0.044711 0.081402 0.174828 -vn 1.729159 -3.002491 5.086304 -v 0.044711 0.080508 0.174398 -vn -1.191836 -3.023475 5.236801 -v 0.044803 0.080510 0.174395 -vn 1.720541 2.908246 5.146464 -v 0.044711 0.087145 0.174398 -vn 1.729118 2.104638 5.518626 -v 0.044711 0.086252 0.174828 -vn -1.191951 2.209201 5.628960 -v 0.044803 0.086250 0.174825 -vn 1.720630 5.836874 0.935006 -v 0.044711 0.090390 0.169639 -vn 1.728967 5.626928 1.795392 -v 0.044711 0.090169 0.170606 -vn -1.192002 5.778281 1.782391 -v 0.044803 0.090165 0.170605 -vn 1.720505 4.370311 -3.980541 -v 0.044711 0.088692 0.164136 -vn 1.729008 4.911952 -3.279850 -v 0.044711 0.089311 0.164911 -vn -1.192062 4.996239 -3.406394 -v 0.044803 0.089308 0.164913 -vn 1.720691 -0.387210 -5.898524 -v 0.044711 0.083331 0.162031 -vn 1.729274 0.498189 -5.885236 -v 0.044711 0.084323 0.162031 -vn -1.191901 0.451870 -6.030041 -v 0.044803 0.084323 0.162035 -vn 1.720402 -4.853129 -3.374957 -v 0.044711 0.078343 0.164911 -vn 1.729115 -4.290699 -4.059028 -v 0.044711 0.078961 0.164136 -vn -1.191800 -4.432729 -4.112954 -v 0.044803 0.078964 0.164138 -vn 1.732974 -5.321014 2.562433 -v 0.044711 0.077847 0.171530 -vn 1.732666 -4.859907 3.355529 -v 0.044711 0.078343 0.172389 -vn 1.732960 -1.314171 5.757734 -v 0.044711 0.082350 0.175121 -vn 1.732658 -0.406682 5.891744 -v 0.044711 0.083331 0.175269 -vn 1.733295 3.682179 4.617312 -v 0.044711 0.087965 0.173839 -vn 1.732512 4.352900 3.991481 -v 0.044711 0.088692 0.173164 -vn 1.733068 5.905881 -0.000002 -v 0.044711 0.090464 0.168650 -vn 1.732632 5.834569 -0.914568 -v 0.044711 0.090390 0.167661 -vn 1.732915 3.682221 -4.617320 -v 0.044711 0.087965 0.163461 -vn 1.732530 2.922778 -5.131931 -v 0.044711 0.087145 0.162902 -vn 1.733099 -1.314237 -5.757870 -v 0.044711 0.082350 0.162179 -vn 1.732519 -2.189939 -5.484766 -v 0.044711 0.081402 0.162472 -vn 1.733024 -5.321075 -2.562477 -v 0.044711 0.077847 0.165770 -vn 1.732470 -5.653605 -1.707521 -v 0.044711 0.077485 0.166694 -vn 1.729931 -5.849138 -0.819368 -v 0.044711 0.077264 0.167661 -vn 1.729867 -3.006332 -5.083925 -v 0.044711 0.080508 0.162902 -vn 1.729822 2.100402 -5.520140 -v 0.044711 0.086252 0.162472 -vn 1.729796 5.625409 -1.799625 -v 0.044711 0.090169 0.166694 -vn 1.729955 4.914352 3.276074 -v 0.044711 0.089311 0.172389 -vn 1.729975 0.502721 5.884760 -v 0.044711 0.084323 0.175269 -vn 1.729842 -4.287515 4.062247 -v 0.044711 0.078961 0.173164 -vn -1.191772 -5.448093 -2.623636 -v 0.044803 0.077850 0.165772 -vn -1.192007 -5.778281 -1.782383 -v 0.044803 0.077488 0.166695 -vn -3.827480 -3.001137 -3.763309 -v 0.044888 0.079667 0.163434 -vn -1.192088 -3.770211 -4.727729 -v 0.044803 0.079691 0.163464 -vn 1.685411 -3.695771 -4.634327 -v 0.044711 0.079689 0.163461 -vn -1.191595 -1.345573 -5.895336 -v 0.044803 0.082351 0.162183 -vn -1.191951 -2.209201 -5.628960 -v 0.044803 0.081403 0.162475 -vn -3.827614 1.071066 -4.692656 -v 0.044888 0.085311 0.162146 -vn -1.191647 1.345557 -5.895339 -v 0.044803 0.085303 0.162183 -vn 1.685548 1.319008 -5.779074 -v 0.044711 0.085304 0.162179 -vn -1.192088 3.770229 -4.727714 -v 0.044803 0.087963 0.163464 -vn -1.191824 3.023458 -5.236813 -v 0.044803 0.087143 0.162905 -vn -3.827545 4.336775 -2.088482 -v 0.044888 0.089838 0.165755 -vn -1.191780 5.448081 -2.623656 -v 0.044803 0.089803 0.165772 -vn 1.685493 5.340652 -2.571949 -v 0.044711 0.089807 0.165770 -vn -1.191900 6.046894 0.000004 -v 0.044803 0.090460 0.168650 -vn -1.191818 5.979416 -0.901243 -v 0.044803 0.090386 0.167661 -vn -3.827458 4.336771 2.088448 -v 0.044888 0.089838 0.171545 -vn -1.191811 5.448134 2.623715 -v 0.044803 0.089803 0.171528 -vn 1.685445 5.340612 2.571873 -v 0.044711 0.089807 0.171530 -vn -1.192030 3.770153 4.727603 -v 0.044803 0.087963 0.173836 -vn -1.191802 4.432729 4.112959 -v 0.044803 0.088689 0.173162 -vn -3.827604 1.071044 4.692673 -v 0.044888 0.085311 0.175154 -vn -1.192129 1.345555 5.895337 -v 0.044803 0.085303 0.175117 -vn 1.685449 1.318981 5.778920 -v 0.044711 0.085304 0.175121 -vn -1.192071 -1.345559 5.895336 -v 0.044803 0.082351 0.175117 -vn -1.191901 -0.451870 6.030041 -v 0.044803 0.083331 0.175265 -vn -3.827785 -3.001038 3.763192 -v 0.044888 0.079667 0.173866 -vn -1.192033 -3.770168 4.727588 -v 0.044803 0.079691 0.173836 -vn 1.685794 -3.695721 4.634320 -v 0.044711 0.079689 0.173839 -vn -1.191801 -5.448127 2.623734 -v 0.044803 0.077850 0.171528 -vn -1.192017 -4.996188 3.406297 -v 0.044803 0.078346 0.172387 -vn -3.827602 -4.813434 -0.000007 -v 0.044888 0.077155 0.168650 -vn -1.191900 -6.046894 -0.000004 -v 0.044803 0.077193 0.168650 -vn 1.685551 -5.927626 0.000000 -v 0.044711 0.077190 0.168650 -vn -3.825755 -4.587173 -1.462385 -v 0.044888 0.077452 0.166684 -vn -3.802318 -4.361858 -2.100574 -v 0.044888 0.077816 0.165755 -vn -3.825335 -4.001788 -2.677455 -v 0.044888 0.078314 0.164892 -vn -3.825737 -1.716674 -4.498166 -v 0.044888 0.081389 0.162440 -vn -3.802383 -1.077251 -4.719811 -v 0.044888 0.082342 0.162146 -vn -3.825526 -0.401745 -4.797894 -v 0.044888 0.083328 0.161997 -vn -3.825816 2.446439 -4.146658 -v 0.044888 0.087163 0.162872 -vn -3.802249 3.018501 -3.785083 -v 0.044888 0.087986 0.163434 -vn -3.825370 3.500792 -3.305676 -v 0.044888 0.088717 0.164112 -vn -3.825752 4.767372 -0.672715 -v 0.044888 0.090424 0.167656 -vn -3.802364 4.841292 0.000000 -v 0.044888 0.090498 0.168650 -vn -3.825396 4.767146 0.675974 -v 0.044888 0.090424 0.169644 -vn -3.825741 3.498383 3.307875 -v 0.044888 0.088717 0.173188 -vn -3.802557 3.018389 3.784972 -v 0.044888 0.087986 0.173866 -vn -3.825464 2.443751 4.148511 -v 0.044888 0.087163 0.174428 -vn -3.825857 -0.404928 4.797423 -v 0.044888 0.083328 0.175303 -vn -3.802381 -1.077254 4.719816 -v 0.044888 0.082342 0.175154 -vn -3.825347 -1.719851 4.497241 -v 0.044888 0.081389 0.174860 -vn -3.825826 -4.003414 2.674598 -v 0.044888 0.078314 0.172408 -vn -3.802235 -4.361856 2.100538 -v 0.044888 0.077816 0.171545 -vn -3.825333 -4.588445 1.459401 -v 0.044888 0.077452 0.170616 -vn -3.827277 -4.755878 -0.742637 -v 0.044888 0.077230 0.167656 -vn -5.298489 -3.269508 -0.542548 -v 0.044946 0.077159 0.167645 -vn -5.460867 -3.075278 -0.243496 -v 0.044946 0.077110 0.168046 -vn -1.191809 -5.979418 -0.901230 -v 0.044803 0.077268 0.167661 -vn -5.297900 -3.315396 -0.000002 -v 0.044946 0.077083 0.168650 -vn -5.406057 -3.076568 -0.749868 -v 0.044946 0.077326 0.166856 -vn -5.460483 -2.108768 -2.252670 -v 0.044946 0.079167 0.163776 -vn -5.303592 -2.465990 -2.204203 -v 0.044946 0.078883 0.164063 -vn -3.820943 -3.560874 -3.249202 -v 0.044888 0.078936 0.164112 -vn -1.192057 -4.996226 -3.406415 -v 0.044803 0.078346 0.164913 -vn -5.434572 -2.458521 -1.927985 -v 0.044946 0.078371 0.164686 -vn -5.299439 -2.788848 -1.786659 -v 0.044946 0.078255 0.164851 -vn -5.312840 -2.970989 -1.430738 -v 0.044946 0.077751 0.165724 -vn -5.299404 -3.135718 -1.066486 -v 0.044946 0.077383 0.166662 -vn -5.297967 -2.067057 -2.592021 -v 0.044946 0.079622 0.163378 -vn -3.827325 -2.384611 -4.181285 -v 0.044888 0.080491 0.162872 -vn -5.298513 -1.614344 -2.894433 -v 0.044946 0.080455 0.162810 -vn -5.460834 -1.727060 -2.556206 -v 0.044946 0.080112 0.163022 -vn -1.191830 -3.023472 -5.236803 -v 0.044803 0.080510 0.162905 -vn -5.406160 -1.331831 -2.872782 -v 0.044946 0.081176 0.162449 -vn -5.460566 0.446390 -3.053095 -v 0.044946 0.084732 0.161968 -vn -5.303666 0.185779 -3.302188 -v 0.044946 0.084331 0.161925 -vn -3.821015 0.320115 -4.809756 -v 0.044888 0.084325 0.161997 -vn -1.191891 -0.451857 -6.030042 -v 0.044803 0.083331 0.162035 -vn -5.434731 -0.025532 -3.123992 -v 0.044946 0.083524 0.161913 -vn -5.299548 -0.341990 -3.294226 -v 0.044946 0.083323 0.161925 -vn -5.312950 -0.733749 -3.214725 -v 0.044946 0.082326 0.162076 -vn -5.299418 -1.121205 -3.116547 -v 0.044946 0.081363 0.162373 -vn -5.298025 0.737727 -3.232111 -v 0.044946 0.085327 0.162076 -vn -3.827246 1.782310 -4.471414 -v 0.044888 0.086264 0.162440 -vn -5.298464 1.256481 -3.066843 -v 0.044946 0.086290 0.162373 -vn -5.460877 0.921704 -2.943972 -v 0.044946 0.085911 0.162237 -vn -1.191945 2.209218 -5.628953 -v 0.044803 0.086250 0.162475 -vn -5.406157 1.415639 -2.832431 -v 0.044946 0.087022 0.162712 -vn -5.460446 2.665493 -1.554645 -v 0.044946 0.089616 0.165191 -vn -5.303555 2.697709 -1.913709 -v 0.044946 0.089399 0.164851 -vn -3.820831 3.960165 -2.748656 -v 0.044888 0.089339 0.164892 -vn -1.191799 4.432713 -4.112971 -v 0.044803 0.088689 0.164138 -vn -5.434585 2.426676 -1.967886 -v 0.044946 0.088905 0.164213 -vn -5.299405 2.362448 -2.321406 -v 0.044946 0.088770 0.164063 -vn -5.312897 2.055946 -2.578062 -v 0.044946 0.088031 0.163378 -vn -5.299466 1.737501 -2.819692 -v 0.044946 0.087199 0.162810 -vn -5.297911 2.987060 -1.438480 -v 0.044946 0.089902 0.165724 -vn -3.827274 4.607161 -1.394411 -v 0.044888 0.090202 0.166684 -vn -5.298440 3.181183 -0.929813 -v 0.044946 0.090271 0.166662 -vn -5.460813 2.876449 -1.114974 -v 0.044946 0.090140 0.166280 -vn -1.192000 5.778287 -1.782364 -v 0.044803 0.090165 0.166695 -vn -5.406096 3.097195 -0.659226 -v 0.044946 0.090462 0.167446 -vn -5.460445 2.877381 1.114660 -v 0.044946 0.090140 0.171020 -vn -5.303463 3.178308 0.915998 -v 0.044946 0.090271 0.170638 -vn -3.820831 4.618171 1.382440 -v 0.044888 0.090202 0.170616 -vn -1.191809 5.979418 0.901230 -v 0.044803 0.090386 0.169639 -vn -5.434638 3.051480 0.670309 -v 0.044946 0.090462 0.169854 -vn -5.299448 3.287860 0.399655 -v 0.044946 0.090495 0.169655 -vn -5.312835 3.297552 -0.000006 -v 0.044946 0.090570 0.168650 -vn -5.299449 3.287856 -0.399649 -v 0.044946 0.090495 0.167645 -vn -5.297994 2.986961 1.438442 -v 0.044946 0.089902 0.171576 -vn -3.827333 3.962708 2.732658 -v 0.044888 0.089339 0.172408 -vn -5.298367 2.710449 1.907500 -v 0.044946 0.089399 0.172449 -vn -5.460855 2.665104 1.553695 -v 0.044946 0.089616 0.172109 -vn -1.192022 4.996174 3.406315 -v 0.044803 0.089308 0.172387 -vn -5.406064 2.446514 2.010497 -v 0.044946 0.088905 0.173087 -vn -5.460492 0.922534 2.944533 -v 0.044946 0.085911 0.175063 -vn -5.303544 1.265443 3.055923 -v 0.044946 0.086290 0.174927 -vn -3.820853 1.798527 4.472497 -v 0.044888 0.086264 0.174860 -vn -1.191819 3.023490 5.236795 -v 0.044803 0.087143 0.174395 -vn -5.434694 1.378476 2.803598 -v 0.044946 0.087022 0.174588 -vn -5.299465 1.737499 2.819695 -v 0.044946 0.087199 0.174490 -vn -5.312894 2.055949 2.578063 -v 0.044946 0.088031 0.173922 -vn -5.299405 2.362449 2.321405 -v 0.044946 0.088770 0.173237 -vn -5.298028 0.737690 3.232121 -v 0.044946 0.085327 0.175224 -vn -3.827382 0.334261 4.801771 -v 0.044888 0.084325 0.175303 -vn -5.298603 0.198615 3.308121 -v 0.044946 0.084331 0.175375 -vn -5.460834 0.446937 3.052403 -v 0.044946 0.084732 0.175332 -vn -1.191907 0.451880 6.030040 -v 0.044803 0.084323 0.175265 -vn -5.406081 -0.046438 3.166254 -v 0.044946 0.083524 0.175387 -vn -5.460448 -1.726979 2.557206 -v 0.044946 0.080112 0.174278 -vn -5.303588 -1.600218 2.894644 -v 0.044946 0.080455 0.174490 -vn -3.820934 -2.375358 4.194630 -v 0.044888 0.080491 0.174428 -vn -1.191957 -2.209200 5.628958 -v 0.044803 0.081403 0.174825 -vn -5.434552 -1.332581 2.825928 -v 0.044946 0.081176 0.174851 -vn -5.299436 -1.121299 3.116495 -v 0.044946 0.081363 0.174927 -vn -5.312952 -0.733746 3.214724 -v 0.044946 0.082326 0.175224 -vn -5.299565 -0.341878 3.294222 -v 0.044946 0.083323 0.175375 -vn -5.297967 -2.067057 2.592021 -v 0.044946 0.079622 0.173922 -vn -3.827334 -3.545807 3.255251 -v 0.044888 0.078936 0.173188 -vn -5.298518 -2.462657 2.217911 -v 0.044946 0.078883 0.173237 -vn -5.460867 -2.107777 2.252528 -v 0.044946 0.079167 0.173524 -vn -1.191798 -4.432714 4.112975 -v 0.044803 0.078964 0.173162 -vn -5.406057 -2.504500 1.937803 -v 0.044946 0.078371 0.172614 -vn -5.460482 -3.076007 0.244186 -v 0.044946 0.077110 0.169254 -vn -5.303562 -3.260869 0.553701 -v 0.044946 0.077159 0.169655 -vn -3.820889 -4.760539 0.758194 -v 0.044888 0.077230 0.169644 -vn -1.192005 -5.778286 1.782372 -v 0.044803 0.077488 0.170605 -vn -5.434570 -3.040223 0.720102 -v 0.044946 0.077326 0.170444 -vn -5.299341 -3.135784 1.066535 -v 0.044946 0.077383 0.170638 -vn -5.312920 -2.970893 1.430702 -v 0.044946 0.077751 0.171576 -vn -5.299329 -2.789001 1.786674 -v 0.044946 0.078255 0.172449 -vn -5.277609 3.303262 -0.253588 -v 0.046120 0.093011 0.168060 -vn -5.201190 3.372817 -0.494161 -v 0.046120 0.092882 0.167007 -vn -5.281242 3.232281 -0.726006 -v 0.046120 0.092860 0.166891 -vn -5.278458 3.167280 -0.974189 -v 0.046120 0.092561 0.165750 -vn -5.036682 3.327554 -1.322458 -v 0.046120 0.092443 0.165416 -vn -5.278059 2.984088 -1.437060 -v 0.046120 0.092118 0.164657 -vn -5.037095 3.107563 -1.777156 -v 0.046120 0.091727 0.163930 -vn -5.278807 2.736098 -1.867866 -v 0.046120 0.091540 0.163630 -vn -5.281219 2.582928 -2.074466 -v 0.046120 0.090834 0.162684 -vn -5.187814 2.492763 -2.346920 -v 0.046120 0.090757 0.162595 -vn -5.274922 2.264518 -2.422448 -v 0.046120 0.090014 0.161837 -vn -4.970972 2.271267 -2.848077 -v 0.046120 0.089565 0.161455 -vn -5.277626 1.861284 -2.740679 -v 0.046120 0.089092 0.161102 -vn -5.201231 1.716555 -2.945036 -v 0.046120 0.088188 0.160546 -vn -5.281254 1.447700 -2.979729 -v 0.046120 0.088083 0.160491 -vn -5.278597 1.213101 -3.083506 -v 0.046120 0.087005 0.160013 -vn -5.036672 1.040776 -3.426124 -v 0.046120 0.086671 0.159898 -vn -5.278007 0.737029 -3.229108 -v 0.046120 0.085875 0.159678 -vn -5.036938 0.548085 -3.537777 -v 0.046120 0.085062 0.159530 -vn -5.278875 0.245517 -3.303693 -v 0.046120 0.084710 0.159490 -vn -5.281223 -0.011526 -3.312806 -v 0.046120 0.083532 0.159452 -vn -5.187960 -0.280701 -3.412052 -v 0.046120 0.083414 0.159456 -vn -5.274847 -0.482040 -3.280937 -v 0.046120 0.082358 0.159565 -vn -4.970732 -0.810677 -3.551696 -v 0.046120 0.081779 0.159678 -vn -5.277628 -0.982286 -3.163991 -v 0.046120 0.081208 0.159828 -vn -5.201125 -1.232315 -3.178359 -v 0.046120 0.080210 0.160188 -vn -5.281209 -1.427082 -2.989725 -v 0.046120 0.080102 0.160235 -vn -5.278496 -1.654551 -2.871034 -v 0.046120 0.079056 0.160780 -vn -5.036820 -2.029700 -2.949730 -v 0.046120 0.078757 0.160970 -vn -5.278087 -2.065014 -2.589488 -v 0.046120 0.078089 0.161455 -vn -5.036912 -2.424215 -2.634308 -v 0.046120 0.077467 0.161998 -vn -5.278879 -2.429847 -2.251765 -v 0.046120 0.077216 0.162248 -vn -5.281366 -2.597058 -2.056461 -v 0.046120 0.076451 0.163146 -vn -5.187988 -2.842596 -1.907936 -v 0.046120 0.076382 0.163241 -vn -5.274932 -2.865607 -1.668694 -v 0.046120 0.075808 0.164134 -vn -4.970919 -3.282121 -1.580574 -v 0.046120 0.075535 0.164657 -vn -5.277596 -3.086177 -1.204764 -v 0.046120 0.075296 0.165196 -vn -5.201314 -3.253071 -1.018182 -v 0.046120 0.074956 0.166202 -vn -5.281311 -3.227091 -0.748343 -v 0.046120 0.074925 0.166316 -vn -5.278415 -3.276359 -0.496509 -v 0.046120 0.074699 0.167473 -vn -5.036672 -3.571832 -0.252271 -v 0.046120 0.074661 0.167825 -vn -5.278002 -3.312156 -0.000001 -v 0.046120 0.074624 0.168650 -vn -5.037079 -3.570910 0.252850 -v 0.046120 0.074661 0.169475 -vn -5.278853 -3.275518 0.495731 -v 0.046120 0.074699 0.169827 -vn -5.281312 -3.227090 0.748345 -v 0.046120 0.074925 0.170984 -vn -5.188005 -3.263993 1.032889 -v 0.046120 0.074956 0.171098 -vn -5.274934 -3.091312 1.200003 -v 0.046120 0.075296 0.172104 -vn -4.970919 -3.282122 1.580574 -v 0.046120 0.075535 0.172643 -vn -5.277596 -2.866123 1.661709 -v 0.046120 0.075808 0.173166 -vn -5.201303 -2.824286 1.908564 -v 0.046120 0.076382 0.174059 -vn -5.281363 -2.597057 2.056465 -v 0.046120 0.076451 0.174154 -vn -5.278434 -2.430947 2.251974 -v 0.046120 0.077216 0.175052 -vn -5.036727 -2.424193 2.635247 -v 0.046120 0.077467 0.175302 -vn -5.278083 -2.065032 2.589476 -v 0.046120 0.078089 0.175845 -vn -5.037050 -2.028756 2.949522 -v 0.046120 0.078757 0.176330 -vn -5.278754 -1.654733 2.870089 -v 0.046120 0.079056 0.176520 -vn -5.281422 -1.427145 2.989433 -v 0.046120 0.080102 0.177065 -vn -5.187801 -1.227717 3.196017 -v 0.046120 0.080210 0.177112 -vn -5.274952 -0.989188 3.165056 -v 0.046120 0.081208 0.177473 -vn -4.971054 -0.810596 3.551421 -v 0.046120 0.081779 0.177622 -vn -5.277719 -0.487808 3.276738 -v 0.046120 0.082358 0.177735 -vn -5.201271 -0.268807 3.398131 -v 0.046120 0.083414 0.177844 -vn -5.281228 -0.011531 3.312802 -v 0.046120 0.083532 0.177848 -vn -5.278430 0.245022 3.304676 -v 0.046120 0.084710 0.177810 -vn -5.036832 0.548839 3.538265 -v 0.046120 0.085062 0.177770 -vn -5.278215 0.736948 3.228871 -v 0.046120 0.085875 0.177622 -vn -5.037082 1.041119 3.425096 -v 0.046120 0.086671 0.177402 -vn -5.279030 1.212173 3.082863 -v 0.046120 0.087005 0.177287 -vn -5.281250 1.447693 2.979739 -v 0.046120 0.088083 0.176809 -vn -5.187903 1.733343 2.952421 -v 0.046120 0.088188 0.176754 -vn -5.274960 1.857782 2.746751 -v 0.046120 0.089092 0.176198 -vn -4.970972 2.271267 2.848077 -v 0.046120 0.089565 0.175845 -vn -5.277590 2.257815 2.424512 -v 0.046120 0.090014 0.175463 -vn -5.201161 2.489336 2.328819 -v 0.046120 0.090757 0.174705 -vn -5.281366 2.582888 2.074256 -v 0.046120 0.090834 0.174616 -vn -5.278366 2.736509 1.868938 -v 0.046120 0.091540 0.173671 -vn -5.036687 3.108644 1.777035 -v 0.046120 0.091727 0.173370 -vn -5.278059 2.984087 1.437061 -v 0.046120 0.092118 0.172643 -vn -5.037090 3.326974 1.321538 -v 0.046120 0.092443 0.171884 -vn -5.278894 3.166191 0.974518 -v 0.046120 0.092561 0.171550 -vn -5.281241 3.232282 0.726012 -v 0.046120 0.092860 0.170409 -vn -5.187855 3.389063 0.485635 -v 0.046120 0.092882 0.170293 -vn -5.274959 3.305808 0.260102 -v 0.046120 0.093011 0.169240 -vn -4.970908 3.642882 0.000001 -v 0.046120 0.093030 0.168650 -vn -3.758020 -4.737701 -0.646334 -v 0.046175 0.074630 0.167464 -vn -3.760343 -4.778866 0.000002 -v 0.046175 0.074554 0.168650 -vn -3.756000 -4.635314 -1.182979 -v 0.046175 0.074857 0.166298 -vn -3.760384 -4.437450 -1.773560 -v 0.046175 0.075232 0.165170 -vn -3.762455 -4.147878 -2.366834 -v 0.046175 0.075747 0.164100 -vn -3.756163 -3.815890 -2.884414 -v 0.046175 0.076395 0.163104 -vn -3.758133 -2.448534 -4.106955 -v 0.046175 0.079020 0.160720 -vn -3.760432 -2.979519 -3.736193 -v 0.046175 0.078045 0.161400 -vn -3.758024 -3.459233 -3.301085 -v 0.046175 0.077166 0.162199 -vn -3.756043 -1.965222 -4.361688 -v 0.046175 0.080073 0.160171 -vn -3.760708 -1.380057 -4.574984 -v 0.046175 0.081188 0.159761 -vn -3.762703 -0.735693 -4.718597 -v 0.046175 0.082347 0.159496 -vn -3.756483 -0.124058 -4.781729 -v 0.046175 0.083530 0.159382 -vn -3.758023 1.684337 -4.474966 -v 0.046175 0.087029 0.159948 -vn -3.760091 1.063425 -4.659159 -v 0.046175 0.085890 0.159610 -vn -3.758122 0.424094 -4.762691 -v 0.046175 0.084717 0.159420 -vn -3.755891 2.184833 -4.255952 -v 0.046175 0.088116 0.160429 -vn -3.760493 2.716461 -3.931491 -v 0.046175 0.089132 0.161045 -vn -3.762802 3.230394 -3.517092 -v 0.046175 0.090061 0.161786 -vn -3.756478 3.661199 -3.078357 -v 0.046175 0.090887 0.162639 -vn -3.758200 4.548851 -1.473240 -v 0.046175 0.092627 0.165728 -vn -3.760339 4.305573 -2.073456 -v 0.046175 0.092181 0.164627 -vn -3.757955 3.988145 -2.637956 -v 0.046175 0.091598 0.163591 -vn -3.755968 4.689630 -0.945397 -v 0.046175 0.092929 0.166877 -vn -3.760268 4.767569 -0.327418 -v 0.046175 0.093080 0.168056 -vn -3.762573 4.763966 0.332765 -v 0.046175 0.093080 0.169244 -vn -3.756306 4.689529 0.943126 -v 0.046175 0.092929 0.170423 -vn -3.757951 3.988133 2.637970 -v 0.046175 0.091598 0.173709 -vn -3.760340 4.305574 2.073454 -v 0.046175 0.092181 0.172673 -vn -3.758067 4.548903 1.473266 -v 0.046175 0.092627 0.171572 -vn -3.755947 3.663055 3.077000 -v 0.046175 0.090887 0.174661 -vn -3.760184 3.228544 3.523337 -v 0.046175 0.090061 0.175514 -vn -3.762785 2.710074 3.932005 -v 0.046175 0.089132 0.176255 -vn -3.756243 2.186530 4.254454 -v 0.046175 0.088116 0.176871 -vn -3.758126 0.424135 4.762671 -v 0.046175 0.084717 0.177880 -vn -3.760269 1.063343 4.658936 -v 0.046175 0.085890 0.177690 -vn -3.758029 1.684342 4.474954 -v 0.046175 0.087029 0.177352 -vn -3.755709 -0.121888 4.782523 -v 0.046175 0.083530 0.177918 -vn -3.760161 -0.741692 4.720847 -v 0.046175 0.082347 0.177804 -vn -3.762589 -1.384471 4.570478 -v 0.046175 0.081188 0.177539 -vn -3.756511 -1.962965 4.361910 -v 0.046175 0.080073 0.177129 -vn -3.758042 -3.459202 3.301089 -v 0.046175 0.077166 0.175101 -vn -3.760429 -2.979510 3.736196 -v 0.046175 0.078045 0.175900 -vn -3.757984 -2.448652 4.107133 -v 0.046175 0.079020 0.176580 -vn -3.755826 -3.814995 2.886496 -v 0.046175 0.076395 0.174196 -vn -3.760158 -4.153421 2.363583 -v 0.046175 0.075747 0.173200 -vn -3.762673 -4.436536 1.767218 -v 0.046175 0.075232 0.172130 -vn -3.756341 -4.634237 1.184981 -v 0.046175 0.074857 0.171002 -vn -3.758017 -4.737702 0.646329 -v 0.046175 0.074630 0.169836 -vn -1.350131 -5.858923 0.755397 -v 0.046255 0.074592 0.169841 -vn -1.350008 -5.714194 1.498433 -v 0.046255 0.074820 0.171012 -vn -1.350204 -5.475616 2.216841 -v 0.046255 0.075196 0.172144 -vn -1.350010 -5.147280 2.898893 -v 0.046255 0.075713 0.173219 -vn -1.349768 -4.734360 3.533330 -v 0.046255 0.076364 0.174219 -vn -1.349877 -4.243581 4.109679 -v 0.046255 0.077138 0.175128 -vn -1.349991 -3.683172 4.618565 -v 0.046255 0.078021 0.175930 -vn -1.350496 -3.062355 5.051682 -v 0.046255 0.079000 0.176613 -vn -1.350255 -2.391187 5.401731 -v 0.046255 0.080058 0.177165 -vn -1.350332 -1.680801 5.663254 -v 0.046255 0.081177 0.177577 -vn -1.349953 -0.942834 5.831789 -v 0.046255 0.082341 0.177842 -vn -1.349848 -0.189384 5.904486 -v 0.046255 0.083528 0.177957 -vn -1.350152 0.567243 5.880071 -v 0.046255 0.084721 0.177919 -vn -1.350011 1.314550 5.759394 -v 0.046255 0.085899 0.177728 -vn -1.349868 2.040227 5.543976 -v 0.046255 0.087043 0.177389 -vn -1.350273 2.732428 5.237535 -v 0.046255 0.088134 0.176906 -vn -1.349784 3.379644 4.844992 -v 0.046255 0.089154 0.176287 -vn -1.350023 3.971595 4.373142 -v 0.046255 0.090087 0.175543 -vn -1.350236 4.498196 3.829371 -v 0.046255 0.090917 0.174686 -vn -1.350121 4.950953 3.222703 -v 0.046255 0.091631 0.173730 -vn -1.349878 5.322373 2.563135 -v 0.046255 0.092216 0.172690 -vn -1.350160 5.606464 1.861464 -v 0.046255 0.092664 0.171584 -vn -1.350284 5.798462 1.129211 -v 0.046255 0.092967 0.170430 -vn -1.350075 5.895273 0.378482 -v 0.046255 0.093119 0.169247 -vn -1.350078 5.895276 -0.378475 -v 0.046255 0.093119 0.168053 -vn -1.350280 5.798461 -1.129219 -v 0.046255 0.092967 0.166870 -vn -1.350120 5.606377 -1.861475 -v 0.046255 0.092664 0.165716 -vn -1.350103 5.322388 -2.563119 -v 0.046255 0.092216 0.164610 -vn -1.350124 4.950958 -3.222699 -v 0.046255 0.091631 0.163570 -vn -1.350152 4.498056 -3.829293 -v 0.046255 0.090917 0.162614 -vn -1.349933 3.971457 -4.373028 -v 0.046255 0.090087 0.161757 -vn -1.350217 3.379659 -4.845005 -v 0.046255 0.089154 0.161013 -vn -1.350293 2.732398 -5.237549 -v 0.046255 0.088134 0.160394 -vn -1.349869 2.040246 -5.543968 -v 0.046255 0.087043 0.159911 -vn -1.350008 1.314551 -5.759398 -v 0.046255 0.085899 0.159572 -vn -1.350152 0.567262 -5.880075 -v 0.046255 0.084721 0.159381 -vn -1.350242 -0.189358 -5.904263 -v 0.046255 0.083528 0.159343 -vn -1.349842 -0.942780 -5.831565 -v 0.046255 0.082341 0.159458 -vn -1.350222 -1.680757 -5.663028 -v 0.046255 0.081177 0.159723 -vn -1.350261 -2.391181 -5.401737 -v 0.046255 0.080058 0.160135 -vn -1.350050 -3.062338 -5.051659 -v 0.046255 0.079000 0.160687 -vn -1.349989 -3.683176 -4.618567 -v 0.046255 0.078021 0.161370 -vn -1.350240 -4.243609 -4.109667 -v 0.046255 0.077138 0.162172 -vn -1.349776 -4.734352 -3.533341 -v 0.046255 0.076364 0.163081 -vn -1.350009 -5.147284 -2.898896 -v 0.046255 0.075713 0.164081 -vn -1.350201 -5.475625 -2.216828 -v 0.046255 0.075196 0.165156 -vn -1.350012 -5.714189 -1.498444 -v 0.046255 0.074820 0.166288 -vn -1.350132 -5.858924 -0.755392 -v 0.046255 0.074592 0.167459 -vn -1.350114 -5.907377 -0.000001 -v 0.046255 0.074515 0.168650 -vn 1.326445 -5.864121 0.756106 -v 0.046344 0.074591 0.169841 -vn 1.326599 -5.719285 1.499775 -v 0.046344 0.074820 0.171012 -vn 1.326436 -5.480565 2.218866 -v 0.046344 0.075196 0.172144 -vn 1.326431 -5.151829 2.901476 -v 0.046344 0.075713 0.173219 -vn 1.326359 -4.738613 3.536514 -v 0.046344 0.076364 0.174219 -vn 1.326427 -4.247480 4.113435 -v 0.046344 0.077138 0.175128 -vn 1.326713 -3.686495 4.622690 -v 0.046344 0.078021 0.175930 -vn 1.326369 -3.065010 5.056049 -v 0.046344 0.079000 0.176613 -vn 1.326490 -2.393350 5.406603 -v 0.046344 0.080058 0.177165 -vn 1.326184 -1.682300 5.668323 -v 0.046344 0.081177 0.177577 -vn 1.326393 -0.943666 5.836899 -v 0.046344 0.082341 0.177842 -vn 1.326152 -0.189520 5.909831 -v 0.046344 0.083528 0.177957 -vn 1.326390 0.567750 5.885404 -v 0.046344 0.084721 0.177919 -vn 1.326612 1.315657 5.764311 -v 0.046344 0.085899 0.177728 -vn 1.326558 2.042044 5.548868 -v 0.046344 0.087043 0.177389 -vn 1.326348 2.734819 5.242100 -v 0.046344 0.088134 0.176906 -vn 1.326597 3.382871 4.849586 -v 0.046344 0.089154 0.176287 -vn 1.326319 3.975166 4.377094 -v 0.046344 0.090087 0.175543 -vn 1.326410 4.502128 3.832719 -v 0.046344 0.090917 0.174686 -vn 1.326420 4.955324 3.225578 -v 0.046344 0.091631 0.173730 -vn 1.326600 5.327196 2.565443 -v 0.046344 0.092216 0.172690 -vn 1.326425 5.611454 1.863139 -v 0.046344 0.092664 0.171584 -vn 1.326356 5.803614 1.130264 -v 0.046344 0.092967 0.170430 -vn 1.326532 5.900506 0.378827 -v 0.046344 0.093119 0.169247 -vn 1.326534 5.900507 -0.378821 -v 0.046344 0.093119 0.168053 -vn 1.326355 5.803612 -1.130272 -v 0.046344 0.092967 0.166870 -vn 1.326579 5.611469 -1.863114 -v 0.046344 0.092664 0.165716 -vn 1.326555 5.327087 -2.565427 -v 0.046344 0.092216 0.164610 -vn 1.326430 4.955316 -3.225590 -v 0.046344 0.091631 0.163570 -vn 1.326734 4.502162 -3.832705 -v 0.046344 0.090917 0.162614 -vn 1.326689 3.975192 -4.377100 -v 0.046344 0.090087 0.161757 -vn 1.326527 3.382735 -4.849432 -v 0.046344 0.089154 0.161013 -vn 1.326359 2.734794 -5.242115 -v 0.046344 0.088134 0.160394 -vn 1.326549 2.042063 -5.548864 -v 0.046344 0.087043 0.159911 -vn 1.326220 1.315703 -5.764509 -v 0.046344 0.085899 0.159572 -vn 1.326384 0.567771 -5.885410 -v 0.046344 0.084721 0.159381 -vn 1.326553 -0.189515 -5.909607 -v 0.046344 0.083528 0.159343 -vn 1.326914 -0.943672 -5.836923 -v 0.046344 0.082341 0.159458 -vn 1.326685 -1.682331 -5.668334 -v 0.046344 0.081177 0.159723 -vn 1.326514 -2.393351 -5.406600 -v 0.046344 0.080058 0.160135 -vn 1.326795 -3.065019 -5.056071 -v 0.046344 0.079000 0.160687 -vn 1.326391 -3.686604 -4.622826 -v 0.046344 0.078021 0.161370 -vn 1.326339 -4.247344 -4.113331 -v 0.046344 0.077138 0.162172 -vn 1.326357 -4.738622 -3.536509 -v 0.046344 0.076364 0.163081 -vn 1.326243 -5.151927 -2.901510 -v 0.046344 0.075713 0.164081 -vn 1.326436 -5.480566 -2.218859 -v 0.046344 0.075196 0.165156 -vn 1.326602 -5.719283 -1.499787 -v 0.046344 0.074820 0.166288 -vn 1.326445 -5.864124 -0.756102 -v 0.046344 0.074591 0.167459 -vn 1.326419 -5.912723 0.000002 -v 0.046344 0.074515 0.168650 -vn 3.754987 -4.735312 0.610557 -v 0.046425 0.074630 0.169836 -vn 3.755070 -4.618275 1.211030 -v 0.046425 0.074857 0.171002 -vn 3.755067 -4.425424 1.791661 -v 0.046425 0.075231 0.172130 -vn 3.755017 -4.160063 2.342891 -v 0.046425 0.075747 0.173201 -vn 3.754812 -3.826339 2.855667 -v 0.046425 0.076395 0.174196 -vn 3.754754 -3.429771 3.321588 -v 0.046425 0.077165 0.175101 -vn 3.755041 -2.976833 3.732826 -v 0.046425 0.078045 0.175900 -vn 3.755298 -2.474993 4.082724 -v 0.046425 0.079020 0.176580 -vn 3.755107 -1.932597 4.365737 -v 0.046425 0.080073 0.177130 -vn 3.755020 -1.358415 4.577049 -v 0.046425 0.081188 0.177540 -vn 3.755038 -0.761992 4.713221 -v 0.046425 0.082347 0.177804 -vn 3.754765 -0.153025 4.771985 -v 0.046425 0.083530 0.177918 -vn 3.755055 0.458438 4.752227 -v 0.046425 0.084717 0.177880 -vn 3.755185 1.062432 4.654754 -v 0.046425 0.085890 0.177691 -vn 3.754990 1.648946 4.480692 -v 0.046425 0.087029 0.177353 -vn 3.755159 2.208317 4.232977 -v 0.046425 0.088116 0.176872 -vn 3.754736 2.731551 3.915894 -v 0.046425 0.089132 0.176256 -vn 3.754805 3.209944 3.534484 -v 0.046425 0.090061 0.175515 -vn 3.755146 3.635435 3.094909 -v 0.046425 0.090888 0.174661 -vn 3.755088 4.001357 2.604574 -v 0.046425 0.091599 0.173709 -vn 3.754976 4.301598 2.071555 -v 0.046425 0.092182 0.172674 -vn 3.755114 4.531087 1.504449 -v 0.046425 0.092628 0.171572 -vn 3.755126 4.686293 0.912639 -v 0.046425 0.092929 0.170423 -vn 3.755059 4.764634 0.305892 -v 0.046425 0.093081 0.169244 -vn 3.755049 4.764647 -0.305886 -v 0.046425 0.093081 0.168056 -vn 3.755128 4.686289 -0.912631 -v 0.046425 0.092929 0.166877 -vn 3.755056 4.531168 -1.504458 -v 0.046425 0.092628 0.165728 -vn 3.755078 4.301630 -2.071549 -v 0.046425 0.092182 0.164626 -vn 3.755087 4.001356 -2.604580 -v 0.046425 0.091599 0.163591 -vn 3.755148 3.635443 -3.094897 -v 0.046425 0.090888 0.162639 -vn 3.754818 3.209929 -3.534486 -v 0.046425 0.090061 0.161785 -vn 3.755083 2.731473 -3.915766 -v 0.046425 0.089132 0.161044 -vn 3.755155 2.208326 -4.232978 -v 0.046425 0.088116 0.160428 -vn 3.754996 1.648950 -4.480691 -v 0.046425 0.087029 0.159947 -vn 3.754937 1.062421 -4.654692 -v 0.046425 0.085890 0.159609 -vn 3.754886 0.458452 -4.752465 -v 0.046425 0.084717 0.159420 -vn 3.755186 -0.153014 -4.771810 -v 0.046425 0.083530 0.159382 -vn 3.754855 -0.762051 -4.713457 -v 0.046425 0.082347 0.159496 -vn 3.755020 -1.358417 -4.577048 -v 0.046425 0.081188 0.159760 -vn 3.755094 -1.932598 -4.365751 -v 0.046425 0.080073 0.160170 -vn 3.755145 -2.475087 -4.082914 -v 0.046425 0.079020 0.160720 -vn 3.754855 -2.976785 -3.732793 -v 0.046425 0.078045 0.161400 -vn 3.755060 -3.429693 -3.321480 -v 0.046425 0.077165 0.162199 -vn 3.754816 -3.826341 -2.855668 -v 0.046425 0.076395 0.163104 -vn 3.754794 -4.160134 -2.342947 -v 0.046425 0.075747 0.164099 -vn 3.755062 -4.425429 -1.791662 -v 0.046425 0.075231 0.165170 -vn 3.755064 -4.618280 -1.211037 -v 0.046425 0.074857 0.166298 -vn 3.754966 -4.735343 -0.610542 -v 0.046425 0.074630 0.167464 -vn 3.754976 -4.774416 -0.000002 -v 0.046425 0.074554 0.168650 -vn 5.471131 -2.671713 0.344472 -v 0.046480 0.074699 0.169827 -vn 5.471188 -2.605707 0.683304 -v 0.046480 0.074924 0.170985 -vn 5.471276 -2.496850 1.010855 -v 0.046480 0.075296 0.172104 -vn 5.471198 -2.347152 1.321892 -v 0.046480 0.075808 0.173166 -vn 5.471243 -2.158805 1.611146 -v 0.046480 0.076451 0.174155 -vn 5.471205 -1.935067 1.874003 -v 0.046480 0.077215 0.175053 -vn 5.471143 -1.679597 2.106169 -v 0.046480 0.078088 0.175846 -vn 5.471166 -1.396493 2.303641 -v 0.046480 0.079056 0.176520 -vn 5.471220 -1.090406 2.463227 -v 0.046480 0.080101 0.177066 -vn 5.471259 -0.766441 2.582401 -v 0.046480 0.081208 0.177473 -vn 5.471202 -0.429933 2.659301 -v 0.046480 0.082358 0.177736 -vn 5.471316 -0.086347 2.692286 -v 0.046480 0.083532 0.177849 -vn 5.471363 0.258649 2.681176 -v 0.046480 0.084711 0.177811 -vn 5.471075 0.599463 2.626394 -v 0.046480 0.085875 0.177623 -vn 5.471164 0.930338 2.528047 -v 0.046480 0.087005 0.177287 -vn 5.471185 1.245996 2.388321 -v 0.046480 0.088084 0.176810 -vn 5.471303 1.541078 2.209271 -v 0.046480 0.089092 0.176199 -vn 5.471173 1.811053 1.994161 -v 0.046480 0.090014 0.175463 -vn 5.471178 2.051213 1.746212 -v 0.046480 0.090835 0.174616 -vn 5.471230 2.257603 1.469546 -v 0.046480 0.091540 0.173671 -vn 5.471237 2.426999 1.168768 -v 0.046480 0.092119 0.172643 -vn 5.471283 2.556486 0.848809 -v 0.046480 0.092562 0.171550 -vn 5.471265 2.644047 0.514936 -v 0.046480 0.092861 0.170409 -vn 5.471172 2.688277 0.172577 -v 0.046480 0.093011 0.169240 -vn 5.471154 2.688287 -0.172603 -v 0.046480 0.093011 0.168060 -vn 5.471264 2.644052 -0.514930 -v 0.046480 0.092861 0.166891 -vn 5.471223 2.556524 -0.848836 -v 0.046480 0.092562 0.165750 -vn 5.471151 2.427047 -1.168818 -v 0.046480 0.092119 0.164657 -vn 5.471218 2.257652 -1.469575 -v 0.046480 0.091540 0.163629 -vn 5.471179 2.051208 -1.746213 -v 0.046480 0.090835 0.162684 -vn 5.471169 1.811050 -1.994167 -v 0.046480 0.090014 0.161837 -vn 5.471301 1.541090 -2.209262 -v 0.046480 0.089092 0.161101 -vn 5.471189 1.245988 -2.388321 -v 0.046480 0.088084 0.160490 -vn 5.471166 0.930343 -2.528042 -v 0.046480 0.087005 0.160013 -vn 5.471282 0.599415 -2.626155 -v 0.046480 0.085875 0.159677 -vn 5.471163 0.258659 -2.681328 -v 0.046480 0.084711 0.159489 -vn 5.471325 -0.086333 -2.692280 -v 0.046480 0.083532 0.159451 -vn 5.471007 -0.429973 -2.659444 -v 0.046480 0.082358 0.159564 -vn 5.471258 -0.766440 -2.582404 -v 0.046480 0.081208 0.159827 -vn 5.471225 -1.090391 -2.463227 -v 0.046480 0.080101 0.160234 -vn 5.470998 -1.396560 -2.303750 -v 0.046480 0.079056 0.160780 -vn 5.471309 -1.679481 -2.106010 -v 0.046480 0.078088 0.161454 -vn 5.471206 -1.935070 -1.873998 -v 0.046480 0.077215 0.162247 -vn 5.471244 -2.158796 -1.611156 -v 0.046480 0.076451 0.163145 -vn 5.471192 -2.347157 -1.321888 -v 0.046480 0.075808 0.164134 -vn 5.471278 -2.496848 -1.010856 -v 0.046480 0.075296 0.165196 -vn 5.471193 -2.605701 -0.683302 -v 0.046480 0.074924 0.166315 -vn 5.471107 -2.671733 -0.344485 -v 0.046480 0.074699 0.167473 -vn 5.471250 -2.693714 -0.000006 -v 0.046480 0.074623 0.168650 -vn 6.197536 -0.721699 0.093053 -v 0.046500 0.074785 0.169816 -vn 6.197519 -0.703940 0.184595 -v 0.046500 0.075008 0.170962 -vn 6.197518 -0.674563 0.273100 -v 0.046500 0.075376 0.172071 -vn 6.197520 -0.634092 0.357112 -v 0.046500 0.075883 0.173124 -vn 6.197518 -0.583222 0.435270 -v 0.046500 0.076521 0.174103 -vn 6.197527 -0.522749 0.506253 -v 0.046500 0.077278 0.174992 -vn 6.197512 -0.453755 0.568993 -v 0.046500 0.078143 0.175778 -vn 6.197506 -0.377283 0.622373 -v 0.046500 0.079101 0.176446 -vn 6.197515 -0.294588 0.665478 -v 0.046500 0.080136 0.176986 -vn 6.197513 -0.207067 0.697684 -v 0.046500 0.081233 0.177390 -vn 6.197506 -0.116154 0.718468 -v 0.046500 0.082372 0.177650 -vn 6.197513 -0.023325 0.727394 -v 0.046500 0.083535 0.177762 -vn 6.197514 0.069882 0.724407 -v 0.046500 0.084702 0.177725 -vn 6.197518 0.161937 0.709498 -v 0.046500 0.085855 0.177538 -vn 6.197534 0.251317 0.682908 -v 0.046500 0.086975 0.177206 -vn 6.197521 0.336603 0.645206 -v 0.046500 0.088044 0.176733 -vn 6.197525 0.416342 0.596859 -v 0.046500 0.089043 0.176127 -vn 6.197525 0.489240 0.538712 -v 0.046500 0.089956 0.175399 -vn 6.197515 0.554146 0.471750 -v 0.046500 0.090769 0.174560 -vn 6.197521 0.609909 0.397004 -v 0.046500 0.091467 0.173623 -vn 6.197515 0.655684 0.315765 -v 0.046500 0.092041 0.172606 -vn 6.197511 0.690693 0.229326 -v 0.046500 0.092479 0.171523 -vn 6.197517 0.714334 0.139113 -v 0.046500 0.092775 0.170393 -vn 6.197525 0.726219 0.046628 -v 0.046500 0.092925 0.169234 -vn 6.197528 0.726211 -0.046621 -v 0.046500 0.092925 0.168066 -vn 6.197515 0.714332 -0.139114 -v 0.046500 0.092775 0.166907 -vn 6.197522 0.690660 -0.229310 -v 0.046500 0.092479 0.165777 -vn 6.197527 0.655641 -0.315736 -v 0.046500 0.092041 0.164694 -vn 6.197505 0.609959 -0.397046 -v 0.046500 0.091467 0.163677 -vn 6.197516 0.554145 -0.471753 -v 0.046500 0.090769 0.162740 -vn 6.197526 0.489242 -0.538711 -v 0.046500 0.089956 0.161901 -vn 6.197523 0.416342 -0.596858 -v 0.046500 0.089043 0.161173 -vn 6.197521 0.336602 -0.645207 -v 0.046500 0.088044 0.160567 -vn 6.197533 0.251321 -0.682907 -v 0.046500 0.086975 0.160094 -vn 6.197519 0.161936 -0.709497 -v 0.046500 0.085855 0.159762 -vn 6.197539 0.069874 -0.724291 -v 0.046500 0.084702 0.159575 -vn 6.197514 -0.023328 -0.727390 -v 0.046500 0.083535 0.159538 -vn 6.197533 -0.116135 -0.718355 -v 0.046500 0.082372 0.159650 -vn 6.197514 -0.207069 -0.697681 -v 0.046500 0.081233 0.159910 -vn 6.197514 -0.294586 -0.665477 -v 0.046500 0.080136 0.160314 -vn 6.197529 -0.377232 -0.622288 -v 0.046500 0.079101 0.160854 -vn 6.197514 -0.453759 -0.568990 -v 0.046500 0.078143 0.161522 -vn 6.197526 -0.522747 -0.506256 -v 0.046500 0.077278 0.162308 -vn 6.197520 -0.583219 -0.435270 -v 0.046500 0.076521 0.163197 -vn 6.197519 -0.634094 -0.357114 -v 0.046500 0.075883 0.164176 -vn 6.197515 -0.674562 -0.273097 -v 0.046500 0.075376 0.165229 -vn 6.197518 -0.703942 -0.184594 -v 0.046500 0.075008 0.166338 -vn 6.197539 -0.721685 -0.093051 -v 0.046500 0.074785 0.167484 -vn 6.197527 -0.727706 0.000002 -v 0.046500 0.074710 0.168650 -vn 6.264976 -0.335638 0.035276 -v 0.046500 0.092139 0.167776 -vn 6.264975 -0.330112 0.070167 -v 0.046500 0.092002 0.166912 -vn 6.264976 -0.320969 0.104289 -v 0.046500 0.091776 0.166067 -vn 6.264977 -0.308308 0.137267 -v 0.046500 0.091462 0.165251 -vn 6.264976 -0.292274 0.168744 -v 0.046500 0.091065 0.164471 -vn 6.264976 -0.273035 0.198372 -v 0.046500 0.090588 0.163737 -vn 6.264976 -0.250803 0.225823 -v 0.046500 0.090038 0.163057 -vn 6.264977 -0.225822 0.250800 -v 0.046500 0.089419 0.162439 -vn 6.264976 -0.198369 0.273032 -v 0.046500 0.088739 0.161888 -vn 6.264976 -0.168742 0.292275 -v 0.046500 0.088006 0.161412 -vn 6.264975 -0.137269 0.308312 -v 0.046500 0.087226 0.161015 -vn 6.264976 -0.104291 0.320969 -v 0.046500 0.086410 0.160701 -vn 6.264976 -0.070168 0.330115 -v 0.046500 0.085565 0.160475 -vn 6.264976 -0.035277 0.335642 -v 0.046500 0.084700 0.160338 -vn 6.264976 -0.000001 0.337487 -v 0.046500 0.083827 0.160292 -vn 6.264976 0.035278 0.335643 -v 0.046500 0.082953 0.160338 -vn 6.264976 0.070168 0.330114 -v 0.046500 0.082089 0.160475 -vn 6.264976 0.104290 0.320969 -v 0.046500 0.081244 0.160701 -vn 6.264975 0.137269 0.308313 -v 0.046500 0.080427 0.161015 -vn 6.264977 0.168743 0.292274 -v 0.046500 0.079648 0.161412 -vn 6.264977 0.198368 0.273032 -v 0.046500 0.078914 0.161888 -vn 6.264976 0.225822 0.250800 -v 0.046500 0.078234 0.162439 -vn 6.264976 0.250804 0.225824 -v 0.046500 0.077616 0.163057 -vn 6.264976 0.273036 0.198371 -v 0.046500 0.077065 0.163737 -vn 6.264976 0.292273 0.168744 -v 0.046500 0.076589 0.164471 -vn 6.264976 0.308307 0.137268 -v 0.046500 0.076191 0.165251 -vn 6.264976 0.035277 -0.335642 -v 0.046500 0.082953 0.176962 -vn 6.264977 0.000001 -0.337487 -v 0.046500 0.083827 0.177008 -vn 6.264976 -0.035280 -0.335641 -v 0.046500 0.084700 0.176962 -vn 6.264977 -0.070165 -0.330109 -v 0.046500 0.085565 0.176825 -vn 6.264976 -0.104290 -0.320969 -v 0.046500 0.086410 0.176599 -vn 6.264976 -0.137270 -0.308311 -v 0.046500 0.087226 0.176285 -vn 6.264976 -0.168740 -0.292269 -v 0.046500 0.088006 0.175888 -vn 6.264975 -0.198375 -0.273037 -v 0.046500 0.088739 0.175412 -vn 6.264976 -0.225825 -0.250805 -v 0.046500 0.089419 0.174861 -vn 6.264976 -0.250802 -0.225824 -v 0.046500 0.090038 0.174243 -vn 6.264976 -0.273036 -0.198371 -v 0.046500 0.090588 0.173563 -vn 6.264976 -0.292273 -0.168744 -v 0.046500 0.091065 0.172829 -vn 6.264977 -0.308307 -0.137268 -v 0.046500 0.091462 0.172049 -vn 6.264976 -0.320969 -0.104288 -v 0.046500 0.091776 0.171233 -vn 6.264976 -0.330112 -0.070167 -v 0.046500 0.092002 0.170388 -vn 6.264976 -0.335638 -0.035277 -v 0.046500 0.092139 0.169524 -vn 6.264976 -0.337488 0.000000 -v 0.046500 0.092185 0.168650 -vn 6.264976 0.320969 0.104288 -v 0.046500 0.075878 0.166067 -vn 6.264977 0.330112 0.070167 -v 0.046500 0.075652 0.166912 -vn 6.264976 0.335638 0.035277 -v 0.046500 0.075515 0.167776 -vn 6.264975 0.337488 -0.000000 -v 0.046500 0.075469 0.168650 -vn 6.264976 0.335638 -0.035276 -v 0.046500 0.075515 0.169524 -vn 6.264976 0.198372 -0.273036 -v 0.046500 0.078914 0.175412 -vn 6.264977 0.168742 -0.292267 -v 0.046500 0.079648 0.175888 -vn 6.264975 0.137269 -0.308312 -v 0.046500 0.080427 0.176285 -vn 6.264976 0.104289 -0.320968 -v 0.046500 0.081244 0.176599 -vn 6.264977 0.070168 -0.330109 -v 0.046500 0.082089 0.176825 -vn 6.264975 0.330112 -0.070167 -v 0.046500 0.075652 0.170388 -vn 6.264976 0.320969 -0.104289 -v 0.046500 0.075878 0.171233 -vn 6.264977 0.308308 -0.137267 -v 0.046500 0.076191 0.172049 -vn 6.264976 0.292274 -0.168744 -v 0.046500 0.076589 0.172829 -vn 6.264976 0.273035 -0.198372 -v 0.046500 0.077065 0.173563 -vn 6.264975 0.250802 -0.225823 -v 0.046500 0.077616 0.174243 -vn 6.264976 0.225825 -0.250806 -v 0.046500 0.078234 0.174861 -vn 6.099597 1.350531 -0.141947 -v 0.046426 0.076174 0.169454 -vn 6.099599 1.328288 -0.282333 -v 0.046426 0.076300 0.170250 -vn 6.099600 1.291497 -0.419631 -v 0.046426 0.076508 0.171028 -vn 6.099597 1.240565 -0.552338 -v 0.046426 0.076797 0.171780 -vn 6.099599 1.176033 -0.678975 -v 0.046426 0.077162 0.172498 -vn 6.099601 1.098613 -0.798192 -v 0.046426 0.077601 0.173173 -vn 6.099603 1.009156 -0.908649 -v 0.046426 0.078108 0.173799 -vn 6.099602 0.908649 -1.009162 -v 0.046426 0.078678 0.174369 -vn 6.099602 0.798183 -1.098617 -v 0.046426 0.079304 0.174876 -vn 6.099599 0.678983 -1.176030 -v 0.046426 0.079979 0.175314 -vn 6.099597 0.552337 -1.240565 -v 0.046426 0.080697 0.175680 -vn 6.099600 0.419635 -1.291497 -v 0.046426 0.081449 0.175969 -vn 6.099592 0.282340 -1.328304 -v 0.046426 0.082227 0.176177 -vn 6.099602 0.141951 -1.350519 -v 0.046426 0.083022 0.176303 -vn 6.099602 0.000003 -1.357956 -v 0.046426 0.083827 0.176345 -vn 6.099599 -0.141952 -1.350526 -v 0.046426 0.084631 0.176303 -vn 6.099592 -0.282347 -1.328303 -v 0.046426 0.085427 0.176177 -vn 6.099601 -0.419627 -1.291496 -v 0.046426 0.086205 0.175969 -vn 6.099597 -0.552344 -1.240564 -v 0.046426 0.086957 0.175680 -vn 6.099599 -0.678976 -1.176028 -v 0.046426 0.087674 0.175314 -vn 6.099602 -0.798182 -1.098614 -v 0.046426 0.088350 0.174876 -vn 6.099602 -0.908650 -1.009160 -v 0.046426 0.088976 0.174369 -vn 6.099602 -1.009152 -0.908655 -v 0.046426 0.089546 0.173799 -vn 6.099599 -1.098618 -0.798189 -v 0.046426 0.090052 0.173173 -vn 6.099599 -1.176034 -0.678979 -v 0.046426 0.090491 0.172498 -vn 6.099597 -1.240567 -0.552334 -v 0.046426 0.090857 0.171780 -vn 6.099601 -1.291494 -0.419633 -v 0.046426 0.091146 0.171028 -vn 6.099599 -1.328289 -0.282332 -v 0.046426 0.091354 0.170250 -vn 6.099599 -1.350523 -0.141944 -v 0.046426 0.091480 0.169454 -vn 6.099599 -1.357963 0.000000 -v 0.046426 0.091522 0.168650 -vn 6.099599 -1.350525 0.141943 -v 0.046426 0.091480 0.167846 -vn 6.099599 -1.328288 0.282333 -v 0.046426 0.091354 0.167050 -vn 6.099600 -1.291497 0.419631 -v 0.046426 0.091146 0.166272 -vn 6.099597 -1.240565 0.552338 -v 0.046426 0.090857 0.165520 -vn 6.099599 -1.176033 0.678975 -v 0.046426 0.090491 0.164802 -vn 6.099600 -1.098617 0.798191 -v 0.046426 0.090052 0.164127 -vn 6.099599 -1.009161 0.908658 -v 0.046426 0.089546 0.163501 -vn 6.099602 -0.908647 1.009158 -v 0.046426 0.088976 0.162931 -vn 6.099600 -0.798190 1.098608 -v 0.046426 0.088350 0.162424 -vn 6.099600 -0.678977 1.176029 -v 0.046426 0.087674 0.161986 -vn 6.099595 -0.552331 1.240574 -v 0.046426 0.086957 0.161620 -vn 6.099600 -0.419642 1.291494 -v 0.046426 0.086205 0.161331 -vn 6.099601 -0.282339 1.328286 -v 0.046426 0.085427 0.161123 -vn 6.099600 -0.141941 1.350525 -v 0.046426 0.084631 0.160997 -vn 6.099602 -0.000003 1.357956 -v 0.046426 0.083827 0.160955 -vn 6.099599 0.141945 1.350526 -v 0.046426 0.083022 0.160997 -vn 6.099601 0.282340 1.328286 -v 0.046426 0.082227 0.161123 -vn 6.099599 0.419639 1.291498 -v 0.046426 0.081449 0.161331 -vn 6.099595 0.552335 1.240572 -v 0.046426 0.080697 0.161620 -vn 6.099601 0.678977 1.176026 -v 0.046426 0.079979 0.161986 -vn 6.099601 0.798188 1.098609 -v 0.046426 0.079304 0.162424 -vn 6.099602 0.908646 1.009160 -v 0.046426 0.078678 0.162931 -vn 6.099598 1.009163 0.908657 -v 0.046426 0.078108 0.163501 -vn 6.099599 1.098618 0.798189 -v 0.046426 0.077601 0.164127 -vn 6.099599 1.176034 0.678979 -v 0.046426 0.077162 0.164802 -vn 6.099597 1.240567 0.552334 -v 0.046426 0.076797 0.165520 -vn 6.099601 1.291494 0.419633 -v 0.046426 0.076508 0.166272 -vn 6.099598 1.328291 0.282336 -v 0.046426 0.076300 0.167050 -vn 6.099595 1.350536 0.141944 -v 0.046426 0.076174 0.167846 -vn 6.099595 1.357974 -0.000000 -v 0.046426 0.076131 0.168650 -vn 5.810076 2.361819 -0.247071 -v 0.046207 0.076800 0.169389 -vn 5.809416 2.323937 -0.495137 -v 0.046207 0.076916 0.170119 -vn 5.809666 2.259662 -0.732971 -v 0.046207 0.077107 0.170833 -vn 5.809457 2.170135 -0.967444 -v 0.046207 0.077372 0.171524 -vn 5.810156 2.056369 -1.187235 -v 0.046207 0.077708 0.172183 -vn 5.810160 1.920988 -1.395693 -v 0.046207 0.078111 0.172803 -vn 5.811672 1.760597 -1.588335 -v 0.046207 0.078576 0.173378 -vn 5.810650 1.590576 -1.761546 -v 0.046207 0.079099 0.173901 -vn 5.810081 1.394860 -1.921855 -v 0.046207 0.079674 0.174366 -vn 5.810155 1.187252 -2.056362 -v 0.046207 0.080294 0.174769 -vn 5.810076 0.966949 -2.168925 -v 0.046207 0.080953 0.175105 -vn 5.809416 0.733178 -2.260150 -v 0.046207 0.081643 0.175370 -vn 5.809662 0.495057 -2.323424 -v 0.046207 0.082358 0.175561 -vn 5.809460 0.247226 -2.363109 -v 0.046207 0.083088 0.175677 -vn 5.810159 0.000006 -2.374478 -v 0.046207 0.083827 0.175716 -vn 5.810160 -0.248193 -2.361471 -v 0.046207 0.084565 0.175677 -vn 5.811666 -0.495251 -2.318904 -v 0.046207 0.085296 0.175561 -vn 5.810644 -0.730259 -2.258266 -v 0.046207 0.086010 0.175370 -vn 5.810077 -0.966955 -2.168922 -v 0.046207 0.086701 0.175105 -vn 5.810154 -1.187252 -2.056366 -v 0.046207 0.087360 0.174769 -vn 5.810081 -1.394860 -1.921857 -v 0.046207 0.087980 0.174366 -vn 5.809421 -1.590760 -1.765010 -v 0.046207 0.088555 0.173901 -vn 5.809669 -1.764593 -1.590437 -v 0.046207 0.089078 0.173378 -vn 5.809462 -1.922885 -1.395667 -v 0.046207 0.089543 0.172803 -vn 5.810158 -2.056365 -1.187238 -v 0.046207 0.089946 0.172183 -vn 5.810156 -2.169206 -0.965787 -v 0.046207 0.090282 0.171524 -vn 5.811669 -2.255844 -0.730560 -v 0.046207 0.090547 0.170833 -vn 5.810645 -2.320844 -0.496702 -v 0.046207 0.090738 0.170119 -vn 5.810078 -2.361813 -0.247060 -v 0.046207 0.090854 0.169389 -vn 5.810157 -2.374485 -0.000001 -v 0.046207 0.090892 0.168650 -vn 5.810077 -2.361814 0.247063 -v 0.046207 0.090854 0.167911 -vn 5.809417 -2.323936 0.495131 -v 0.046207 0.090738 0.167181 -vn 5.809665 -2.259664 0.732971 -v 0.046207 0.090547 0.166467 -vn 5.809456 -2.170135 0.967446 -v 0.046207 0.090282 0.165776 -vn 5.810156 -2.056369 1.187235 -v 0.046207 0.089946 0.165117 -vn 5.810159 -1.920998 1.395682 -v 0.046207 0.089543 0.164497 -vn 5.811670 -1.760598 1.588345 -v 0.046207 0.089078 0.163922 -vn 5.810648 -1.590575 1.761560 -v 0.046207 0.088555 0.163399 -vn 5.810080 -1.394875 1.921848 -v 0.046207 0.087980 0.162934 -vn 5.810161 -1.187245 2.056354 -v 0.046207 0.087360 0.162531 -vn 5.810076 -0.966932 2.168933 -v 0.046207 0.086701 0.162195 -vn 5.809414 -0.733181 2.260153 -v 0.046207 0.086010 0.161930 -vn 5.809668 -0.495057 2.323410 -v 0.046207 0.085296 0.161739 -vn 5.809460 -0.247223 2.363109 -v 0.046207 0.084565 0.161623 -vn 5.810157 -0.000004 2.374481 -v 0.046207 0.083827 0.161584 -vn 5.810158 0.248190 2.361476 -v 0.046207 0.083088 0.161623 -vn 5.811671 0.495245 2.318892 -v 0.046207 0.082358 0.161739 -vn 5.810645 0.730263 2.258260 -v 0.046207 0.081643 0.161930 -vn 5.810077 0.966937 2.168930 -v 0.046207 0.080953 0.162195 -vn 5.810159 1.187246 2.056358 -v 0.046207 0.080294 0.162531 -vn 5.810079 1.394874 1.921850 -v 0.046207 0.079674 0.162934 -vn 5.809419 1.590753 1.765027 -v 0.046207 0.079099 0.163399 -vn 5.809666 1.764603 1.590443 -v 0.046207 0.078576 0.163922 -vn 5.809460 1.922896 1.395661 -v 0.046207 0.078111 0.164497 -vn 5.810158 2.056365 1.187238 -v 0.046207 0.077708 0.165117 -vn 5.810156 2.169206 0.965787 -v 0.046207 0.077372 0.165776 -vn 5.811668 2.255845 0.730561 -v 0.046207 0.077107 0.166467 -vn 5.810645 2.320843 0.496716 -v 0.046207 0.076916 0.167181 -vn 5.810077 2.361817 0.247071 -v 0.046207 0.076800 0.167911 -vn 5.810155 2.374492 -0.000001 -v 0.046207 0.076761 0.168650 -vn 5.317628 -3.292153 -0.000003 -v 0.045267 0.088922 0.168650 -vn 5.302678 -3.275812 0.465985 -v 0.045267 0.088845 0.167765 -vn 5.436656 -3.023912 0.775066 -v 0.045267 0.088811 0.167591 -vn 5.308131 -3.126117 1.063623 -v 0.045267 0.088615 0.166907 -vn 5.552598 -2.646596 1.265257 -v 0.045267 0.088481 0.166578 -vn 5.313200 -2.869064 1.622013 -v 0.045267 0.088239 0.166102 -vn 5.460568 -2.517835 1.786261 -v 0.045267 0.087949 0.165655 -vn 5.298936 -2.505067 2.173633 -v 0.045267 0.087730 0.165375 -vn 5.406255 -2.200755 2.278625 -v 0.045267 0.087236 0.164864 -vn 5.302698 -2.041424 2.603942 -v 0.045267 0.087102 0.164747 -vn 5.317644 -1.646058 2.851070 -v 0.045267 0.086374 0.164237 -vn 5.302765 -1.234345 3.069808 -v 0.045267 0.085569 0.163862 -vn 5.436811 -0.840670 3.006095 -v 0.045267 0.085401 0.163804 -vn 5.307980 -0.642017 3.239289 -v 0.045267 0.084712 0.163632 -vn 5.552568 -0.227584 2.924701 -v 0.045267 0.084359 0.163583 -vn 5.313181 -0.029825 3.295714 -v 0.045267 0.083827 0.163555 -vn 5.460537 0.288051 3.073686 -v 0.045267 0.083294 0.163583 -vn 5.298783 0.629953 3.256452 -v 0.045267 0.082942 0.163632 -vn 5.406325 0.872989 3.045118 -v 0.045267 0.082252 0.163804 -vn 5.302762 1.234365 3.069806 -v 0.045267 0.082084 0.163862 -vn 5.317642 1.646060 2.851073 -v 0.045267 0.081279 0.164237 -vn 5.302696 2.041427 2.603941 -v 0.045267 0.080552 0.164747 -vn 5.436721 2.183117 2.231181 -v 0.045267 0.080417 0.164864 -vn 5.308123 2.484192 2.175489 -v 0.045267 0.079924 0.165375 -vn 5.552603 2.419036 1.659389 -v 0.045267 0.079705 0.165655 -vn 5.313200 2.839239 1.673674 -v 0.045267 0.079414 0.166102 -vn 5.460564 2.805871 1.287384 -v 0.045267 0.079172 0.166578 -vn 5.298949 3.134942 1.082623 -v 0.045267 0.079039 0.166907 -vn 5.406204 3.073793 0.766622 -v 0.045267 0.078843 0.167591 -vn 5.302678 3.275812 0.465991 -v 0.045267 0.078809 0.167765 -vn 5.317542 3.292264 -0.000006 -v 0.045267 0.078732 0.168650 -vn 5.302706 3.275775 -0.465991 -v 0.045267 0.078809 0.169535 -vn 5.436702 3.023842 -0.775060 -v 0.045267 0.078843 0.169709 -vn 5.308131 3.126124 -1.063604 -v 0.045267 0.079039 0.170393 -vn 5.552639 2.646538 -1.265213 -v 0.045267 0.079172 0.170722 -vn 5.313203 2.869064 -1.622005 -v 0.045267 0.079414 0.171198 -vn 5.460564 2.517829 -1.786282 -v 0.045267 0.079705 0.171645 -vn 5.298809 2.505165 -2.173764 -v 0.045267 0.079924 0.171925 -vn 5.406154 2.200860 -2.278728 -v 0.045267 0.080417 0.172436 -vn 5.302553 2.041549 -2.604075 -v 0.045267 0.080552 0.172553 -vn 5.317647 1.646074 -2.851058 -v 0.045267 0.081279 0.173063 -vn 5.302780 1.234242 -3.069833 -v 0.045267 0.082084 0.173438 -vn 5.436683 0.840687 -3.006285 -v 0.045267 0.082252 0.173496 -vn 5.308164 0.641903 -3.239069 -v 0.045267 0.082942 0.173668 -vn 5.552520 0.227605 -2.924782 -v 0.045267 0.083294 0.173717 -vn 5.313190 0.029819 -3.295708 -v 0.045267 0.083827 0.173745 -vn 5.460501 -0.288073 -3.073737 -v 0.045267 0.084359 0.173717 -vn 5.298981 -0.629867 -3.256213 -v 0.045267 0.084712 0.173668 -vn 5.406216 -0.872933 -3.045287 -v 0.045267 0.085401 0.173496 -vn 5.302783 -1.234219 -3.069841 -v 0.045267 0.085569 0.173438 -vn 5.317640 -1.646070 -2.851072 -v 0.045267 0.086374 0.173063 -vn 5.302547 -2.041565 -2.604073 -v 0.045267 0.087102 0.172553 -vn 5.436627 -2.183220 -2.231277 -v 0.045267 0.087236 0.172436 -vn 5.307994 -2.484295 -2.175625 -v 0.045267 0.087730 0.171925 -vn 5.552598 -2.419031 -1.659412 -v 0.045267 0.087949 0.171645 -vn 5.313200 -2.839239 -1.673674 -v 0.045267 0.088239 0.171198 -vn 5.460594 -2.805837 -1.287344 -v 0.045267 0.088481 0.170722 -vn 5.298947 -3.134948 -1.082605 -v 0.045267 0.088615 0.170393 -vn 5.406240 -3.073740 -0.766614 -v 0.045267 0.088811 0.169709 -vn 5.302705 -3.275777 -0.465988 -v 0.045267 0.088845 0.169535 -vn -3.923355 -0.492927 -4.871871 -v 0.044951 0.084543 0.173632 -vn -3.670903 -1.044356 -4.954213 -v 0.044951 0.084701 0.173607 -vn -1.740445 -1.086927 -5.806755 -v 0.045032 0.084693 0.173563 -vn -3.924301 -3.971505 2.862994 -v 0.044951 0.087784 0.165538 -vn -3.671535 -3.768184 3.380850 -v 0.044951 0.087683 0.165414 -vn -1.740501 -4.485352 3.844667 -v 0.045032 0.087648 0.165443 -vn -3.922744 4.465811 2.009964 -v 0.044951 0.079154 0.166779 -vn -3.672614 4.810812 1.573667 -v 0.044951 0.079097 0.166928 -vn -1.740643 5.572165 1.962082 -v 0.045032 0.079139 0.166944 -vn 1.195416 3.889909 -4.635811 -v 0.045125 0.080623 0.172469 -vn 3.838199 3.052801 -3.717775 -v 0.045209 0.080598 0.172498 -vn 3.840335 3.665011 -3.113477 -v 0.045209 0.079979 0.171879 -vn 1.194949 -1.050877 -5.959761 -v 0.045125 0.084692 0.173559 -vn 3.840446 -0.863811 -4.730570 -v 0.045209 0.084699 0.173597 -vn 3.826294 0.033088 -4.824623 -v 0.045209 0.083827 0.173673 -vn 1.195157 -5.959699 -1.050924 -v 0.045125 0.088736 0.169516 -vn 3.838296 -4.745932 -0.784894 -v 0.045209 0.088774 0.169522 -vn 3.840424 -4.528718 -1.617207 -v 0.045209 0.088547 0.170368 -vn 1.194906 -4.635887 3.889924 -v 0.045125 0.087646 0.165446 -vn 3.840462 -3.664917 3.113354 -v 0.045209 0.087675 0.165421 -vn 3.826002 -4.194898 2.383723 -v 0.045209 0.088177 0.166138 -vn 1.195098 2.069814 5.686790 -v 0.045125 0.082122 0.163966 -vn 3.838129 1.693274 4.502551 -v 0.045209 0.082109 0.163930 -vn 3.840661 0.863781 4.730586 -v 0.045209 0.082955 0.163703 -vn 3.832622 4.541028 -1.607038 -v 0.045209 0.079107 0.170368 -vn 3.826005 4.194906 -2.383708 -v 0.045209 0.079477 0.171162 -vn 3.837940 1.689273 -4.504246 -v 0.045209 0.082109 0.173370 -vn 3.832523 -3.662355 -3.129228 -v 0.045209 0.087675 0.171879 -vn 3.826005 -4.161819 -2.441014 -v 0.045209 0.088177 0.171162 -vn 3.837808 -4.745560 0.789167 -v 0.045209 0.088774 0.167778 -vn 3.832847 -0.878836 4.736156 -v 0.045209 0.084699 0.163703 -vn 3.825912 -0.033054 4.824807 -v 0.045209 0.083827 0.163627 -vn 3.837833 3.056181 3.715178 -v 0.045209 0.080598 0.164802 -vn 3.811121 4.840947 -0.000006 -v 0.045209 0.078804 0.168650 -vn 3.838339 4.745920 0.784936 -v 0.045209 0.078880 0.167778 -vn 3.840558 4.528645 1.617225 -v 0.045209 0.079107 0.166932 -vn 3.826005 4.161818 2.441015 -v 0.045209 0.079477 0.166138 -vn 3.832653 3.662262 3.129101 -v 0.045209 0.079979 0.165421 -vn 3.837601 -1.689358 4.504382 -v 0.045209 0.085545 0.163930 -vn 3.832752 -4.540955 1.607052 -v 0.045209 0.088547 0.166932 -vn 3.837674 -3.056303 -3.715325 -v 0.045209 0.087056 0.172498 -vn 3.832654 0.878740 -4.736143 -v 0.045209 0.082955 0.173597 -vn 3.837760 4.745569 -0.789149 -v 0.045209 0.078880 0.169522 -vn 3.811133 2.420415 4.192315 -v 0.045209 0.081315 0.164300 -vn 1.195137 3.025831 5.240890 -v 0.045125 0.081334 0.164333 -vn -1.752978 2.951781 5.112687 -v 0.045032 0.081332 0.164330 -vn 3.838368 -3.052680 3.717618 -v 0.045209 0.087056 0.164802 -vn 1.195038 -3.889904 4.635821 -v 0.045125 0.087031 0.164831 -vn -1.735214 -3.763033 4.556718 -v 0.045032 0.087034 0.164828 -vn 3.811028 -4.840923 0.000004 -v 0.045209 0.088850 0.168650 -vn 1.194898 -6.051694 0.000012 -v 0.045125 0.088812 0.168650 -vn -1.753190 -5.903573 0.000003 -v 0.045032 0.088816 0.168650 -vn 3.838474 -1.693112 -4.502445 -v 0.045209 0.085545 0.173370 -vn 1.195014 -2.069766 -5.686646 -v 0.045125 0.085532 0.173334 -vn -1.735410 -2.064611 -5.537201 -v 0.045032 0.085533 0.173338 -vn 3.811125 2.420419 -4.192320 -v 0.045209 0.081315 0.173000 -vn 1.195150 3.025817 -5.240896 -v 0.045125 0.081334 0.172967 -vn -1.752972 2.951819 -5.112675 -v 0.045032 0.081332 0.172970 -vn 1.195038 5.686700 2.069763 -v 0.045125 0.079142 0.166945 -vn 1.195147 5.959681 1.050864 -v 0.045125 0.078918 0.167784 -vn 1.195113 6.051610 -0.000004 -v 0.045125 0.078842 0.168650 -vn 1.195162 5.959699 -1.050909 -v 0.045125 0.078918 0.169516 -vn 1.194905 4.635891 3.889917 -v 0.045125 0.080008 0.165446 -vn -1.732760 4.567386 3.753855 -v 0.045032 0.080005 0.165443 -vn -1.737848 5.149283 2.899180 -v 0.045032 0.079506 0.166156 -vn 1.195086 -2.069801 5.686798 -v 0.045125 0.085532 0.163966 -vn -1.736662 -2.069605 5.534806 -v 0.045032 0.085533 0.163962 -vn -1.748003 -1.081770 5.804694 -v 0.045032 0.084693 0.163737 -vn -1.689967 -2.965891 5.137127 -v 0.045032 0.086321 0.164330 -vn 1.195145 -3.025793 5.240857 -v 0.045125 0.086319 0.164333 -vn 3.811217 -2.420413 4.192268 -v 0.045209 0.086338 0.164300 -vn 1.195041 -5.686699 2.069763 -v 0.045125 0.088511 0.166945 -vn -1.732881 -5.534550 2.078527 -v 0.045032 0.088515 0.166944 -vn -1.737855 -5.085391 3.009840 -v 0.045032 0.088147 0.166156 -vn 1.195429 -3.889884 -4.635829 -v 0.045125 0.087031 0.172469 -vn -1.736749 -3.758523 -4.559641 -v 0.045032 0.087034 0.172472 -vn -1.747987 -4.486058 -3.839120 -v 0.045032 0.087648 0.171857 -vn -1.689977 -2.965909 -5.137117 -v 0.045032 0.086321 0.172970 -vn 1.195151 -3.025781 -5.240865 -v 0.045125 0.086319 0.172967 -vn 3.811229 -2.420394 -4.192270 -v 0.045209 0.086338 0.173000 -vn 1.194945 1.050851 -5.959768 -v 0.045125 0.082961 0.173559 -vn -1.732667 0.967221 -5.832421 -v 0.045032 0.082961 0.173563 -vn -1.737705 -0.063942 -5.909040 -v 0.045032 0.083827 0.173639 -vn -1.735409 5.827589 0.980574 -v 0.045032 0.078914 0.167784 -vn -1.690086 5.931790 -0.000000 -v 0.045032 0.078838 0.168650 -vn -1.736987 5.827985 -0.975121 -v 0.045032 0.078914 0.169516 -vn -1.748102 5.567867 -1.965492 -v 0.045032 0.079139 0.170356 -vn 1.194900 5.240903 3.025808 -v 0.045125 0.079510 0.166158 -vn -3.784476 4.854110 1.164799 -v 0.044951 0.078884 0.167697 -vn -3.676207 4.449560 2.409046 -v 0.044951 0.079468 0.166133 -vn -4.015694 2.777861 3.949093 -v 0.044951 0.080907 0.164550 -vn -3.688068 3.306054 3.819868 -v 0.044951 0.080591 0.164794 -vn -1.727474 3.846663 4.493501 -v 0.045032 0.080620 0.164828 -vn 1.195037 3.889908 4.635817 -v 0.045125 0.080623 0.164831 -vn -4.171423 3.304042 3.336970 -v 0.044951 0.080184 0.165176 -vn -3.682610 3.941043 3.166385 -v 0.044951 0.079971 0.165414 -vn -4.054061 3.939040 2.736322 -v 0.044951 0.079592 0.165929 -vn -3.661944 2.536321 4.389687 -v 0.044951 0.081310 0.164291 -vn -1.752657 2.002708 5.553548 -v 0.045032 0.082121 0.163962 -vn -3.664345 1.694595 4.775922 -v 0.044951 0.082105 0.163920 -vn -4.018223 2.029289 4.378653 -v 0.044951 0.081736 0.164071 -vn 1.195363 1.050831 5.959600 -v 0.045125 0.082961 0.163741 -vn -1.752381 0.991615 5.819740 -v 0.045032 0.082961 0.163737 -vn -3.665926 0.802640 5.002270 -v 0.044951 0.082953 0.163693 -vn -3.993675 1.218676 4.689444 -v 0.044951 0.082640 0.163758 -vn 1.195398 0.000001 6.051688 -v 0.045125 0.083827 0.163665 -vn -1.750830 -0.048482 5.903574 -v 0.045032 0.083827 0.163661 -vn -3.661564 -0.119221 5.068592 -v 0.044951 0.083827 0.163616 -vn -3.945577 0.358009 4.868252 -v 0.044951 0.083587 0.163622 -vn 1.195361 -1.050849 5.959598 -v 0.045125 0.084692 0.163741 -vn -3.868103 -0.525132 4.909123 -v 0.044951 0.084543 0.163668 -vn -3.782878 -3.437517 3.621643 -v 0.044951 0.087123 0.164846 -vn -3.665587 -3.102545 4.005194 -v 0.044951 0.087062 0.164794 -vn -3.684396 -2.529543 4.378963 -v 0.044951 0.086344 0.164291 -vn -3.667118 -1.915968 4.688612 -v 0.044951 0.085548 0.163920 -vn -3.767556 -1.433792 4.793626 -v 0.044951 0.085473 0.163893 -vn -3.665355 -1.035646 4.959650 -v 0.044951 0.084701 0.163693 -vn 1.194907 -5.240899 3.025814 -v 0.045125 0.088144 0.166158 -vn -3.677825 -4.310724 2.646777 -v 0.044951 0.088186 0.166133 -vn -4.018660 -4.806098 0.433789 -v 0.044951 0.088838 0.168172 -vn -3.688205 -4.961028 0.953479 -v 0.044951 0.088784 0.167776 -vn -1.727645 -5.814687 1.084528 -v 0.045032 0.088740 0.167784 -vn 1.195146 -5.959685 1.050844 -v 0.045125 0.088736 0.167784 -vn -4.170912 -4.542467 1.192639 -v 0.044951 0.088657 0.167232 -vn -3.681300 -4.713367 1.831409 -v 0.044951 0.088557 0.166928 -vn -4.052873 -4.340708 2.042531 -v 0.044951 0.088301 0.166343 -vn -3.664869 -5.067235 -0.001192 -v 0.044951 0.088860 0.168650 -vn -1.753031 -5.810764 -1.042285 -v 0.045032 0.088740 0.169516 -vn -3.662075 -4.985832 -0.918241 -v 0.044951 0.088784 0.169524 -vn -4.015526 -4.808774 -0.434565 -v 0.044951 0.088838 0.169128 -vn 1.194899 -5.686749 -2.069790 -v 0.045125 0.088511 0.170355 -vn -1.752472 -5.535810 -2.051151 -v 0.045032 0.088515 0.170356 -vn -3.664534 -4.733759 -1.808543 -v 0.044951 0.088557 0.170372 -vn -3.994054 -4.670280 -1.288922 -v 0.044951 0.088657 0.170068 -vn 1.194900 -5.240903 -3.025808 -v 0.045125 0.088144 0.171142 -vn -1.751429 -5.088382 -2.993668 -v 0.045032 0.088147 0.171144 -vn -3.666462 -4.327168 -2.633982 -v 0.044951 0.088186 0.171167 -vn -3.945106 -4.397016 -2.120945 -v 0.044951 0.088301 0.170957 -vn 1.195220 -4.635864 -3.889943 -v 0.045125 0.087646 0.171854 -vn -3.869850 -3.984707 -2.912361 -v 0.044951 0.087784 0.171762 -vn -3.782884 -1.417292 -4.787898 -v 0.044951 0.085473 0.173407 -vn -3.667159 -1.915556 -4.688770 -v 0.044951 0.085548 0.173380 -vn -3.684401 -2.529548 -4.378954 -v 0.044951 0.086344 0.173009 -vn -3.665908 -3.102398 -4.005052 -v 0.044951 0.087062 0.172506 -vn -3.764569 -3.438323 -3.638512 -v 0.044951 0.087123 0.172454 -vn -3.661512 -3.779443 -3.379498 -v 0.044951 0.087683 0.171886 -vn 1.195314 0.000022 -6.051527 -v 0.045125 0.083827 0.173635 -vn -3.677136 -0.137811 -5.057116 -v 0.044951 0.083827 0.173684 -vn -4.018555 2.027579 -4.379122 -v 0.044951 0.081736 0.173229 -vn -3.684872 1.652853 -4.776827 -v 0.044951 0.082105 0.173380 -vn -1.727700 1.968081 -5.577995 -v 0.045032 0.082121 0.173338 -vn 1.195018 2.069760 -5.686646 -v 0.045125 0.082122 0.173334 -vn -4.167853 1.241855 -4.532075 -v 0.044951 0.082640 0.173542 -vn -3.682907 0.772253 -4.995890 -v 0.044951 0.082953 0.173607 -vn -4.055115 0.399454 -4.778605 -v 0.044951 0.083587 0.173678 -vn -3.664791 2.534593 -4.387835 -v 0.044951 0.081310 0.173009 -vn -1.752774 3.808088 -4.511147 -v 0.045032 0.080620 0.172472 -vn -3.666098 3.286303 -3.855695 -v 0.044951 0.080591 0.172506 -vn -4.018057 2.777504 -3.946815 -v 0.044951 0.080907 0.172750 -vn 1.195232 4.635870 -3.889936 -v 0.045125 0.080008 0.171854 -vn -1.752410 4.544181 -3.768521 -v 0.045032 0.080005 0.171857 -vn -3.661966 3.933846 -3.198012 -v 0.044951 0.079971 0.171886 -vn -3.993860 3.454307 -3.397358 -v 0.044951 0.080184 0.172124 -vn 1.194910 5.240897 -3.025818 -v 0.045125 0.079510 0.171142 -vn -1.751464 5.136761 -2.909848 -v 0.045032 0.079506 0.171144 -vn -3.665102 4.446651 -2.429294 -v 0.044951 0.079468 0.171167 -vn -3.944765 4.035080 -2.748330 -v 0.044951 0.079592 0.171371 -vn 1.194890 5.686746 -2.069807 -v 0.045125 0.079142 0.170355 -vn -3.869812 4.513300 -1.997625 -v 0.044951 0.079154 0.170521 -vn -3.666060 5.019549 0.684139 -v 0.044951 0.078870 0.167776 -vn -3.678602 5.061943 -0.003571 -v 0.044951 0.078793 0.168650 -vn -3.661132 5.024054 -0.682830 -v 0.044951 0.078870 0.169524 -vn -3.767406 4.869002 -1.152582 -v 0.044951 0.078884 0.169603 -vn -3.666817 4.811338 -1.583977 -v 0.044951 0.079097 0.170372 -vn -3.578990 3.446399 3.731405 -v 0.041143 0.077908 0.162530 -vn -3.190133 3.867566 3.552389 -v 0.041143 0.077665 0.162775 -vn -3.578004 3.987965 3.141927 -v 0.041143 0.077145 0.163373 -vn -3.220178 4.346430 2.927131 -v 0.041143 0.076664 0.164047 -vn -3.577414 0.609028 5.041732 -v 0.041143 0.082975 0.160179 -vn -3.583116 1.018808 4.979659 -v 0.041143 0.081853 0.160368 -vn -3.547873 1.376333 4.911420 -v 0.041143 0.081820 0.160376 -vn -3.575960 1.741381 4.770122 -v 0.041143 0.080767 0.160705 -vn -3.105740 2.214610 4.791656 -v 0.041143 0.080290 0.160905 -vn -3.579533 2.487980 4.423949 -v 0.041143 0.079735 0.161184 -vn -3.419041 2.853209 4.298985 -v 0.041143 0.078888 0.161715 -vn -3.583730 3.129487 4.001329 -v 0.041143 0.078776 0.161796 -vn -3.578695 -2.123287 4.611031 -v 0.041143 0.087411 0.160927 -vn -3.252682 -1.828760 4.898444 -v 0.041143 0.086611 0.160604 -vn -3.581124 -1.381914 4.887366 -v 0.041143 0.086349 0.160518 -vn -3.582111 -0.981079 4.984127 -v 0.041143 0.085243 0.160254 -vn -3.256287 -0.560756 5.195417 -v 0.041143 0.085038 0.160223 -vn -3.570486 -0.223767 5.074132 -v 0.041143 0.084111 0.160141 -vn -3.126424 0.197019 5.268835 -v 0.041143 0.083422 0.160146 -vn -3.579886 -2.826638 4.218131 -v 0.041143 0.088408 0.161474 -vn -3.165427 -2.556716 4.596297 -v 0.041143 0.088084 0.161277 -vn -3.583774 -4.604641 2.148947 -v 0.041143 0.091426 0.164810 -vn -3.499414 -4.466203 2.512506 -v 0.041143 0.091394 0.164749 -vn -3.573800 -4.233003 2.807171 -v 0.041143 0.090846 0.163831 -vn -3.100038 -4.146841 3.270436 -v 0.041143 0.090519 0.163387 -vn -3.578259 -3.719762 3.454907 -v 0.041143 0.090141 0.162939 -vn -3.463621 -3.498518 3.766447 -v 0.041143 0.089402 0.162215 -vn -3.583740 -3.160991 3.977588 -v 0.041143 0.089324 0.162148 -vn -3.580138 -5.076493 0.207445 -v 0.041143 0.092322 0.168081 -vn -3.184738 -5.209318 0.674392 -v 0.041143 0.092302 0.167841 -vn -3.566297 -4.989032 0.968955 -v 0.041143 0.092170 0.166954 -vn -3.144351 -5.072011 1.417645 -v 0.041143 0.091996 0.166251 -vn -3.579114 -4.760490 1.766237 -v 0.041143 0.091870 0.165857 -vn -3.577091 -4.228725 -2.810916 -v 0.041143 0.090846 0.173469 -vn -3.508115 -4.466548 -2.503712 -v 0.041143 0.091394 0.172551 -vn -3.583772 -4.604646 -2.148933 -v 0.041143 0.091426 0.172490 -vn -3.578868 -4.760653 -1.766655 -v 0.041143 0.091870 0.171443 -vn -3.145069 -5.071716 -1.416193 -v 0.041143 0.091996 0.171049 -vn -3.579736 -4.978448 -0.986713 -v 0.041143 0.092170 0.170346 -vn -3.292255 -5.173444 -0.631917 -v 0.041143 0.092302 0.169459 -vn -3.582832 -5.073857 -0.209512 -v 0.041143 0.092322 0.169219 -vn -3.579885 -2.826641 -4.218130 -v 0.041143 0.088408 0.175826 -vn -3.583710 -3.160983 -3.977616 -v 0.041143 0.089324 0.175152 -vn -3.447150 -3.513816 -3.760771 -v 0.041143 0.089402 0.175085 -vn -3.575710 -3.712930 -3.461998 -v 0.041143 0.090141 0.174361 -vn -3.100366 -4.146261 -3.270529 -v 0.041143 0.090519 0.173913 -vn -3.581490 -1.381755 -4.887238 -v 0.041143 0.086349 0.176782 -vn -3.252609 -1.828722 -4.898468 -v 0.041143 0.086611 0.176696 -vn -3.578349 -2.123355 -4.611190 -v 0.041143 0.087411 0.176373 -vn -3.165293 -2.556711 -4.596351 -v 0.041143 0.088084 0.176023 -vn -3.577408 0.609038 -5.041733 -v 0.041143 0.082975 0.177121 -vn -3.125803 0.197593 -5.269399 -v 0.041143 0.083422 0.177154 -vn -3.577936 -0.206154 -5.072751 -v 0.041143 0.084111 0.177159 -vn -3.329561 -0.589500 -5.164900 -v 0.041143 0.085038 0.177077 -vn -3.581838 -0.981038 -4.984228 -v 0.041143 0.085243 0.177046 -vn -3.578722 3.446497 -3.731498 -v 0.041143 0.077908 0.174770 -vn -3.581583 3.131898 -4.001982 -v 0.041143 0.078776 0.175504 -vn -3.383860 2.845847 -4.323477 -v 0.041143 0.078888 0.175585 -vn -3.571343 2.499794 -4.422452 -v 0.041143 0.079735 0.176116 -vn -3.105503 2.213572 -4.792381 -v 0.041143 0.080290 0.176395 -vn -3.578938 1.743094 -4.767349 -v 0.041143 0.080767 0.176595 -vn -3.552954 1.371567 -4.909151 -v 0.041143 0.081820 0.176924 -vn -3.584727 1.019765 -4.977911 -v 0.041143 0.081853 0.176932 -vn -3.577885 4.884506 -1.385046 -v 0.041143 0.075615 0.170899 -vn -3.371323 4.868305 -1.774939 -v 0.041143 0.075923 0.171814 -vn -3.582284 4.619323 -2.114535 -v 0.041143 0.075988 0.171974 -vn -3.580476 4.431194 -2.481794 -v 0.041143 0.076501 0.172989 -vn -3.221587 4.344614 -2.927729 -v 0.041143 0.076664 0.173253 -vn -3.580139 3.986768 -3.140135 -v 0.041143 0.077145 0.173927 -vn -3.190648 3.867549 -3.551510 -v 0.041143 0.077665 0.174525 -vn -3.580705 4.430951 2.481811 -v 0.041143 0.076501 0.164311 -vn -3.582446 4.619256 2.114486 -v 0.041143 0.075988 0.165326 -vn -3.319886 4.896078 1.759146 -v 0.041143 0.075923 0.165486 -vn -3.569664 4.884301 1.399258 -v 0.041143 0.075615 0.166401 -vn -3.113217 5.174107 1.036772 -v 0.041143 0.075467 0.167039 -vn -3.578248 5.043460 0.579559 -v 0.041143 0.075389 0.167515 -vn -3.569618 5.067010 -0.002364 -v 0.041143 0.075313 0.168650 -vn -3.581166 5.040950 -0.577029 -v 0.041143 0.075389 0.169785 -vn -3.113481 5.173907 -1.036497 -v 0.041143 0.075467 0.170261 -vn 3.342183 2.747455 -4.392136 -v 0.040872 0.079570 0.176022 -vn 3.634720 2.300033 -4.487753 -v 0.040872 0.079736 0.176115 -vn 1.458073 2.769628 -5.153546 -v 0.040958 0.079713 0.176157 -vn 3.579563 -1.939041 -4.688752 -v 0.040872 0.087363 0.176393 -vn 3.635832 -2.266940 -4.506889 -v 0.040872 0.087410 0.176372 -vn 1.469236 -2.480784 -5.290473 -v 0.040958 0.087430 0.176415 -vn 1.465144 -3.105975 -4.953524 -v 0.040958 0.088433 0.175865 -vn 3.526859 -5.039959 0.779831 -v 0.040872 0.092186 0.167039 -vn 3.635040 -4.910862 1.155297 -v 0.040872 0.092169 0.166954 -vn 1.462027 -5.723533 1.198277 -v 0.040958 0.092215 0.166945 -vn 1.463945 -5.539877 1.871714 -v 0.040958 0.091913 0.165842 -vn 3.468477 -0.432246 5.108944 -v 0.040872 0.084232 0.160147 -vn 3.634636 -0.019606 5.044530 -v 0.040872 0.084111 0.160142 -vn 1.458801 -0.154229 5.847590 -v 0.040958 0.084113 0.160095 -vn 3.406550 4.889696 1.630438 -v 0.040872 0.075659 0.166252 -vn 3.634427 4.900787 1.193019 -v 0.040872 0.075617 0.166401 -vn 1.457911 5.654456 1.501742 -v 0.040958 0.075571 0.166388 -vn -1.399669 5.071946 -2.943135 -v 0.041057 0.076461 0.173013 -vn -1.396377 5.380336 -2.336772 -v 0.041057 0.075945 0.171992 -vn 1.467116 5.391204 -2.260046 -v 0.040958 0.075946 0.171992 -vn -1.405061 0.633238 -5.826616 -v 0.041057 0.082970 0.177168 -vn -1.413857 1.339267 -5.699667 -v 0.041057 0.081842 0.176977 -vn 1.467525 1.359869 -5.685511 -v 0.040958 0.081842 0.176977 -vn -1.403967 -5.521250 -1.968610 -v 0.041057 0.091914 0.171458 -vn -1.403264 -5.245847 -2.614314 -v 0.041057 0.091467 0.172511 -vn 1.467507 -5.213196 -2.645110 -v 0.040958 0.091467 0.172511 -vn -1.402451 -3.196703 4.914441 -v 0.041057 0.088433 0.161434 -vn -1.398768 -3.753943 4.505194 -v 0.041057 0.089354 0.162113 -vn 1.467088 -3.785236 4.454851 -v 0.040958 0.089353 0.162113 -vn -1.408310 2.065709 5.483069 -v 0.041057 0.080750 0.160661 -vn -1.415164 1.341096 5.698666 -v 0.041057 0.081842 0.160323 -vn 1.467397 1.359820 5.685297 -v 0.040958 0.081842 0.160323 -vn -1.435106 5.842606 -0.000010 -v 0.041057 0.075266 0.168650 -vn -1.406830 5.813719 0.736489 -v 0.041057 0.075343 0.167509 -vn 1.461068 5.789748 0.830812 -v 0.040958 0.075343 0.167509 -vn -1.406589 5.646472 -1.569242 -v 0.041057 0.075570 0.170912 -vn -1.406767 4.600894 -3.630192 -v 0.041057 0.077108 0.173955 -vn -1.401281 4.039093 -4.250364 -v 0.041057 0.077876 0.174804 -vn -1.397709 3.514185 -4.695418 -v 0.041057 0.078749 0.175542 -vn -1.412539 2.846542 -5.118236 -v 0.041057 0.079713 0.176157 -vn -1.406694 -0.212731 -5.856774 -v 0.041057 0.084113 0.177206 -vn -1.396474 -1.027550 -5.775105 -v 0.041057 0.085251 0.177091 -vn -1.398728 -1.686669 -5.616827 -v 0.041057 0.086363 0.176826 -vn -1.411057 -4.318264 -3.957883 -v 0.041057 0.090176 0.174392 -vn -1.406758 -5.745530 -1.155503 -v 0.041057 0.092216 0.170355 -vn -1.397381 -5.855548 -0.338615 -v 0.041057 0.092368 0.169222 -vn -1.397913 -5.854847 0.342263 -v 0.041057 0.092368 0.168078 -vn -1.409681 -4.853034 3.281787 -v 0.041057 0.090885 0.163805 -vn -1.406546 -2.460263 5.319015 -v 0.041057 0.087430 0.160885 -vn -1.398432 -1.686788 5.616981 -v 0.041057 0.086363 0.160474 -vn -1.397386 -1.023684 5.775038 -v 0.041057 0.085251 0.160209 -vn -1.415701 -0.227603 5.850542 -v 0.041057 0.084113 0.160094 -vn -1.406933 2.839563 5.126477 -v 0.041057 0.079713 0.161143 -vn -1.396859 3.517626 4.693684 -v 0.041057 0.078749 0.161758 -vn -1.401206 4.038953 4.250257 -v 0.041057 0.077876 0.162496 -vn -1.414082 5.638529 1.580095 -v 0.041057 0.075570 0.166388 -vn -1.397017 5.381206 2.333061 -v 0.041057 0.075945 0.165308 -vn -1.399645 5.071980 2.943113 -v 0.041057 0.076461 0.164287 -vn -1.406771 4.600885 3.630213 -v 0.041057 0.077108 0.163345 -vn -1.405526 0.633241 5.826642 -v 0.041057 0.082970 0.160132 -vn -1.406481 -4.325345 3.954132 -v 0.041057 0.090176 0.162908 -vn -1.404248 -5.243851 2.616734 -v 0.041057 0.091467 0.164789 -vn -1.403856 -5.521322 1.968612 -v 0.041057 0.091914 0.165842 -vn -1.417192 -5.742520 1.136959 -v 0.041057 0.092216 0.166945 -vn -1.406691 -4.851748 -3.287068 -v 0.041057 0.090885 0.173495 -vn -1.399685 -3.756203 -4.502405 -v 0.041057 0.089354 0.175187 -vn -1.402439 -3.196695 -4.914444 -v 0.041057 0.088433 0.175866 -vn -1.406658 -2.460368 -5.319195 -v 0.041057 0.087430 0.176415 -vn -1.406793 2.068438 -5.483059 -v 0.041057 0.080750 0.176639 -vn 1.467415 5.007827 3.015457 -v 0.040958 0.076462 0.164288 -vn 1.473952 5.391592 2.247977 -v 0.040958 0.075946 0.165308 -vn 1.457332 2.766472 5.155647 -v 0.040958 0.079713 0.161143 -vn 1.467055 3.452115 4.717637 -v 0.040958 0.078749 0.161759 -vn 1.460086 2.151362 5.439656 -v 0.040958 0.080750 0.160662 -vn 3.633403 1.927589 4.658748 -v 0.040872 0.080767 0.160706 -vn 3.293170 1.586632 4.951069 -v 0.040872 0.081043 0.160605 -vn 1.468581 -2.483549 5.290017 -v 0.040958 0.087430 0.160885 -vn 1.467414 -1.768068 5.571788 -v 0.040958 0.086363 0.160474 -vn 1.465158 -3.105979 4.953520 -v 0.040958 0.088433 0.161435 -vn 3.630630 -2.624749 4.303660 -v 0.040872 0.088407 0.161475 -vn 3.198428 -3.088825 4.219842 -v 0.040872 0.088765 0.161716 -vn 1.478612 -5.198327 2.658540 -v 0.040958 0.091467 0.164789 -vn 1.459237 -4.794772 3.351254 -v 0.040958 0.090884 0.163805 -vn 1.461136 -5.723507 -1.201697 -v 0.040958 0.092215 0.170355 -vn 1.467346 -5.830320 -0.423645 -v 0.040958 0.092368 0.169222 -vn 1.463950 -5.539866 -1.871718 -v 0.040958 0.091913 0.171458 -vn 3.630760 -4.797105 -1.551311 -v 0.040872 0.091868 0.171442 -vn 3.209596 -4.827396 -2.013845 -v 0.040872 0.091730 0.171814 -vn 1.476974 -3.793473 -4.439478 -v 0.040958 0.089353 0.175187 -vn 1.458276 -4.371679 -3.887843 -v 0.040958 0.090175 0.174392 -vn 1.457935 -0.150596 -5.848354 -v 0.040958 0.084113 0.177205 -vn 1.467213 -0.944078 -5.769064 -v 0.040958 0.085251 0.177091 -vn 1.462495 0.535162 -5.823981 -v 0.040958 0.082970 0.177167 -vn 3.630805 0.392017 -5.027086 -v 0.040872 0.082975 0.177120 -vn 3.232766 0.832457 -5.155554 -v 0.040872 0.082615 0.177076 -vn 1.484131 4.573565 -3.622420 -v 0.040958 0.077109 0.173955 -vn 1.466466 4.096647 -4.170287 -v 0.040958 0.077876 0.174803 -vn 1.461075 5.789747 -0.830804 -v 0.040958 0.075343 0.169791 -vn 1.457201 5.655993 -1.498303 -v 0.040958 0.075571 0.170912 -vn -1.406874 5.813698 -0.736474 -v 0.041057 0.075343 0.169791 -vn 1.467252 5.845903 -0.000004 -v 0.040958 0.075267 0.168650 -vn 3.633141 4.979079 0.788242 -v 0.040872 0.075390 0.167515 -vn 3.262052 5.195928 0.391562 -v 0.040872 0.075353 0.167841 -vn 3.622731 4.667336 1.911654 -v 0.040872 0.075990 0.165327 -vn 3.164755 4.676628 2.376009 -v 0.040872 0.076260 0.164749 -vn 3.630577 4.288408 2.647103 -v 0.040872 0.076502 0.164312 -vn 1.483499 4.573164 3.623614 -v 0.040958 0.077109 0.163345 -vn 3.637469 3.853729 3.254914 -v 0.040872 0.077146 0.163374 -vn 3.622689 4.074998 2.986065 -v 0.040872 0.077135 0.163388 -vn 1.466800 4.096670 4.170280 -v 0.040958 0.077876 0.162497 -vn 3.630916 3.574237 3.553136 -v 0.040872 0.077909 0.162531 -vn 3.175947 3.397586 3.991517 -v 0.040872 0.078252 0.162217 -vn 3.635042 2.299945 4.487609 -v 0.040872 0.079736 0.161185 -vn 3.404856 2.710998 4.384864 -v 0.040872 0.079570 0.161278 -vn 3.630656 2.957200 4.080872 -v 0.040872 0.078777 0.161797 -vn 3.632816 1.178719 4.897936 -v 0.040872 0.081853 0.160369 -vn 1.462383 0.535133 5.823755 -v 0.040958 0.082970 0.160133 -vn 3.633739 0.393936 5.024239 -v 0.040872 0.082975 0.160180 -vn 3.236198 0.830399 5.152798 -v 0.040872 0.082615 0.160224 -vn 1.472715 -0.934803 5.766965 -v 0.040958 0.085251 0.160209 -vn 3.624481 -0.770049 4.983737 -v 0.040872 0.085243 0.160256 -vn 3.158907 -1.222067 5.103078 -v 0.040872 0.085834 0.160377 -vn 3.636458 -2.266890 4.506351 -v 0.040872 0.087410 0.160928 -vn 3.584882 -1.944103 4.683610 -v 0.040872 0.087363 0.160907 -vn 3.630989 -1.570801 4.788238 -v 0.040872 0.086349 0.160519 -vn 3.640277 -3.265467 3.826263 -v 0.040872 0.089323 0.162149 -vn 1.458037 -4.374550 3.885411 -v 0.040958 0.090175 0.162908 -vn 3.635375 -3.828570 3.279880 -v 0.040872 0.090140 0.162940 -vn 3.364510 -3.641443 3.672156 -v 0.040872 0.089988 0.162776 -vn 3.634871 -4.080857 2.959621 -v 0.040872 0.090845 0.163832 -vn 3.630765 -4.797115 1.551290 -v 0.040872 0.091868 0.165858 -vn 3.210224 -4.826468 2.014227 -v 0.040872 0.091730 0.165486 -vn 3.621904 -4.480375 2.312514 -v 0.040872 0.091425 0.164811 -vn 3.209171 -4.490407 2.677766 -v 0.040872 0.090988 0.164048 -vn 1.471032 -5.827452 0.429785 -v 0.040958 0.092368 0.168078 -vn 3.626258 -5.024816 0.414078 -v 0.040872 0.092320 0.168081 -vn 3.157221 -5.247461 -0.000575 -v 0.040872 0.092339 0.168650 -vn 3.636731 -4.909610 -1.153738 -v 0.040872 0.092169 0.170346 -vn 3.542062 -5.030170 -0.789381 -v 0.040872 0.092186 0.170261 -vn 3.631675 -5.022147 -0.407157 -v 0.040872 0.092320 0.169219 -vn 3.630742 -4.488405 -2.291739 -v 0.040872 0.091425 0.172489 -vn 1.458748 -4.793070 -3.354529 -v 0.040958 0.090884 0.173495 -vn 3.634800 -4.080877 -2.959705 -v 0.040872 0.090845 0.173468 -vn 3.326540 -4.433582 -2.691912 -v 0.040872 0.090988 0.173252 -vn 3.635379 -3.828565 -3.279885 -v 0.040872 0.090140 0.174360 -vn 3.630631 -2.624750 -4.303658 -v 0.040872 0.088407 0.175825 -vn 3.190783 -3.087005 -4.230344 -v 0.040872 0.088765 0.175584 -vn 3.620747 -3.293663 -3.820248 -v 0.040872 0.089323 0.175151 -vn 3.275775 -3.641952 -3.719731 -v 0.040872 0.089988 0.174524 -vn 1.469620 -1.771236 -5.569266 -v 0.040958 0.086363 0.176826 -vn 3.628811 -1.575084 -4.787751 -v 0.040872 0.086349 0.176781 -vn 3.160544 -1.220110 -5.101780 -v 0.040872 0.085834 0.176923 -vn 3.634633 -0.019603 -5.044530 -v 0.040872 0.084111 0.177158 -vn 3.494559 -0.416827 -5.097898 -v 0.040872 0.084232 0.177153 -vn 3.632881 -0.779123 -4.976804 -v 0.040872 0.085243 0.177044 -vn 3.630794 1.178740 -4.899791 -v 0.040872 0.081853 0.176931 -vn 1.460071 2.151364 -5.439653 -v 0.040958 0.080750 0.176638 -vn 3.633713 1.927230 -4.658574 -v 0.040872 0.080767 0.176594 -vn 3.292335 1.588012 -4.951398 -v 0.040872 0.081043 0.176695 -vn 1.475197 3.437902 -4.721498 -v 0.040958 0.078749 0.175541 -vn 3.621705 2.947438 -4.093025 -v 0.040872 0.078777 0.175503 -vn 3.175947 3.397586 -3.991517 -v 0.040872 0.078252 0.175083 -vn 3.168390 4.674770 -2.371921 -v 0.040872 0.076260 0.172551 -vn 3.631669 4.285830 -2.648465 -v 0.040872 0.076502 0.172988 -vn 1.468145 5.006758 -3.016306 -v 0.040958 0.076462 0.173012 -vn 3.623299 4.076863 -2.982124 -v 0.040872 0.077135 0.173912 -vn 3.637282 3.854542 -3.253917 -v 0.040872 0.077146 0.173926 -vn 3.630916 3.574239 -3.553136 -v 0.040872 0.077909 0.174769 -vn 3.634875 4.654457 -1.921655 -v 0.040872 0.075990 0.171973 -vn 3.449242 4.878044 -1.605491 -v 0.040872 0.075659 0.171048 -vn 3.631274 5.039062 -0.000000 -v 0.040872 0.075314 0.168650 -vn 3.260930 5.197091 -0.390642 -v 0.040872 0.075353 0.169459 -vn 3.631955 4.980058 -0.789417 -v 0.040872 0.075390 0.169785 -vn 3.634416 4.900770 -1.193074 -v 0.040872 0.075617 0.170899 -vn 4.083569 -4.475473 1.653771 -v 0.037314 0.088646 0.166721 -vn 3.791631 -4.487697 2.166675 -v 0.037314 0.088557 0.166512 -vn 3.963940 -4.193058 2.465007 -v 0.037314 0.088194 0.165843 -vn 3.795973 -4.023797 2.933314 -v 0.037314 0.088128 0.165743 -vn 3.802515 -3.739728 3.282897 -v 0.037314 0.087584 0.165067 -vn 3.781493 -3.459669 3.597728 -v 0.037314 0.087575 0.165058 -vn 3.790265 -3.115870 3.890397 -v 0.037314 0.086914 0.164476 -vn 3.950331 -2.647014 4.091174 -v 0.037314 0.086838 0.164421 -vn 3.803230 -2.370963 4.372796 -v 0.037314 0.086164 0.164014 -vn 3.795421 0.224914 4.975049 -v 0.037314 0.083606 0.163463 -vn 4.171068 -0.207548 4.692841 -v 0.037314 0.084074 0.163464 -vn 3.796365 -0.668751 4.934097 -v 0.037314 0.084486 0.163501 -vn 4.140065 -1.034356 4.609526 -v 0.037314 0.085051 0.163605 -vn 3.808177 -1.563023 4.719062 -v 0.037314 0.085347 0.163686 -vn 4.138508 -1.794237 4.370729 -v 0.037314 0.085983 0.163928 -vn 3.796374 3.750214 3.274609 -v 0.037314 0.079788 0.165389 -vn 3.796551 3.435003 3.603264 -v 0.037314 0.080397 0.164753 -vn 3.848804 3.073932 3.871830 -v 0.037314 0.080427 0.164727 -vn 3.797868 2.746851 4.151220 -v 0.037314 0.081105 0.164229 -vn 4.001121 2.262259 4.274039 -v 0.037314 0.081231 0.164154 -vn 3.796243 1.961974 4.576483 -v 0.037314 0.081891 0.163833 -vn 4.105149 1.443754 4.529024 -v 0.037314 0.082129 0.163744 -vn 3.793747 1.110844 4.856231 -v 0.037314 0.082733 0.163575 -vn 4.158290 0.621759 4.667378 -v 0.037314 0.083088 0.163511 -vn 3.814399 4.880508 0.920617 -v 0.037314 0.078710 0.167773 -vn 4.264602 4.463292 1.157527 -v 0.037314 0.078846 0.167187 -vn 3.808951 4.645082 1.767957 -v 0.037314 0.078932 0.166920 -vn 4.096295 4.315167 2.008862 -v 0.037314 0.079212 0.166271 -vn 3.800760 4.264196 2.564782 -v 0.037314 0.079295 0.166118 -vn 3.898767 3.992492 2.857854 -v 0.037314 0.079746 0.165441 -vn 4.119466 4.575370 -1.245201 -v 0.037314 0.078846 0.170113 -vn 3.796714 4.898471 -0.891757 -v 0.037314 0.078710 0.169527 -vn 4.167190 4.682673 -0.412656 -v 0.037314 0.078659 0.169143 -vn 3.794940 4.980545 -0.000001 -v 0.037314 0.078635 0.168650 -vn 4.166184 4.683487 0.413654 -v 0.037314 0.078659 0.168157 -vn 3.805559 1.974773 -4.563914 -v 0.037314 0.081891 0.173467 -vn 4.047539 2.221508 -4.254199 -v 0.037314 0.081231 0.173146 -vn 3.797868 2.746851 -4.151220 -v 0.037314 0.081105 0.173071 -vn 3.848804 3.073932 -3.871830 -v 0.037314 0.080427 0.172573 -vn 3.796555 3.435007 -3.603255 -v 0.037314 0.080397 0.172547 -vn 3.796383 3.750177 -3.274608 -v 0.037314 0.079788 0.171911 -vn 3.884880 3.995799 -2.870965 -v 0.037314 0.079746 0.171859 -vn 3.792950 4.272715 -2.562332 -v 0.037314 0.079295 0.171182 -vn 4.029774 4.351616 -2.059137 -v 0.037314 0.079212 0.171029 -vn 3.789273 4.667213 -1.752884 -v 0.037314 0.078932 0.170380 -vn 4.167911 -0.210806 -4.695502 -v 0.037314 0.084074 0.173836 -vn 3.796989 0.223230 -4.973736 -v 0.037314 0.083606 0.173837 -vn 4.161421 0.621761 -4.664552 -v 0.037314 0.083088 0.173789 -vn 3.812945 1.136326 -4.835798 -v 0.037314 0.082733 0.173725 -vn 4.225211 1.369178 -4.441549 -v 0.037314 0.082129 0.173556 -vn 3.796133 -4.023595 -2.933349 -v 0.037314 0.088128 0.171557 -vn 3.810140 -3.738435 -3.274328 -v 0.037314 0.087584 0.172233 -vn 3.796284 -3.448393 -3.590191 -v 0.037314 0.087575 0.172242 -vn 3.797924 -3.106301 -3.889316 -v 0.037314 0.086914 0.172824 -vn 3.929468 -2.668999 -4.095273 -v 0.037314 0.086838 0.172879 -vn 3.797582 -2.363395 -4.381373 -v 0.037314 0.086164 0.173286 -vn 4.059026 -1.853509 -4.418023 -v 0.037314 0.085983 0.173372 -vn 3.794525 -1.544009 -4.735541 -v 0.037314 0.085347 0.173614 -vn 4.137650 -1.033120 -4.612015 -v 0.037314 0.085051 0.173695 -vn 3.791083 -0.668137 -4.938910 -v 0.037314 0.084486 0.173799 -vn 3.811822 -4.781562 -1.349063 -v 0.037314 0.088851 0.169958 -vn 4.184705 -4.409029 -1.582306 -v 0.037314 0.088646 0.170579 -vn 3.805173 -4.472292 -2.174287 -v 0.037314 0.088557 0.170788 -vn 3.999802 -4.178553 -2.434750 -v 0.037314 0.088194 0.171457 -vn 3.797319 -4.798393 1.326778 -v 0.037314 0.088851 0.167342 -vn 4.150569 -4.642265 0.826335 -v 0.037314 0.088924 0.167667 -vn 3.795673 -4.959653 0.448710 -v 0.037314 0.089000 0.168210 -vn 4.172366 -4.696299 -0.000804 -v 0.037314 0.089018 0.168650 -vn 3.793294 -4.961692 -0.449583 -v 0.037314 0.089000 0.169090 -vn 4.148659 -4.644135 -0.825563 -v 0.037314 0.088924 0.169633 -vn -4.497765 3.230889 -2.943160 -v 0.037024 0.079836 0.171999 -vn -4.379058 2.990741 -3.332903 -v 0.037024 0.080385 0.172561 -vn -2.864762 3.655473 -4.094832 -v 0.037087 0.080418 0.172523 -vn -4.688982 2.496038 -3.352873 -v 0.037024 0.080716 0.172829 -vn -4.348163 2.262991 -3.905589 -v 0.037024 0.081095 0.173086 -vn -2.856437 2.840600 -4.703411 -v 0.037087 0.081122 0.173043 -vn -4.593038 0.621718 -4.234574 -v 0.037024 0.082922 0.173781 -vn -4.328812 0.169910 -4.530237 -v 0.037024 0.083606 0.173855 -vn -2.865124 0.250735 -5.483414 -v 0.037087 0.083608 0.173805 -vn -4.459876 -3.781168 -2.257621 -v 0.037024 0.088179 0.171513 -vn -4.238894 -4.211864 -1.913964 -v 0.037024 0.088574 0.170796 -vn -2.864760 -4.982817 -2.302300 -v 0.037087 0.088528 0.170775 -vn -4.675191 -3.940264 -1.438840 -v 0.037024 0.088722 0.170432 -vn -4.111774 -4.631727 -1.033762 -v 0.037024 0.088868 0.169963 -vn -2.854604 -5.329592 -1.342266 -v 0.037087 0.088820 0.169950 -vn -4.587549 -4.236243 0.621907 -v 0.037024 0.089001 0.168045 -vn -4.317518 -4.410423 1.106654 -v 0.037024 0.088868 0.167337 -vn -2.864878 -5.318281 1.359106 -v 0.037087 0.088820 0.167350 -vn -4.698943 -3.922627 1.410223 -v 0.037024 0.088722 0.166868 -vn -4.346623 -4.087459 1.920253 -v 0.037024 0.088574 0.166504 -vn -2.860597 -4.982067 2.310468 -v 0.037087 0.088528 0.166525 -vn -4.653824 -2.827729 3.127335 -v 0.037024 0.087402 0.164861 -vn -4.342696 -2.690268 3.634819 -v 0.037024 0.086925 0.164461 -vn -2.846817 -3.247087 4.441016 -v 0.037087 0.086895 0.164502 -vn -4.669835 0.580959 4.158388 -v 0.037024 0.082922 0.163519 -vn -4.399716 1.049385 4.328168 -v 0.037024 0.082729 0.163557 -vn -2.869742 1.213597 5.348280 -v 0.037087 0.082740 0.163606 -vn -4.542996 1.859320 3.906821 -v 0.037024 0.081763 0.163866 -vn -4.361756 2.281674 3.876538 -v 0.037024 0.081095 0.164214 -vn -2.864729 2.850842 4.690771 -v 0.037087 0.081122 0.164257 -vn -4.698774 2.489338 3.344161 -v 0.037024 0.080716 0.164471 -vn -4.396642 2.990893 3.308084 -v 0.037024 0.080385 0.164739 -vn -2.858529 3.666829 4.090209 -v 0.037087 0.080418 0.164777 -vn -4.626464 3.846512 1.796600 -v 0.037024 0.079171 0.166312 -vn -4.388083 4.201497 1.520459 -v 0.037024 0.078915 0.166914 -vn -2.865114 5.171989 1.838732 -v 0.037087 0.078962 0.166931 -vn -2.867053 -4.001215 -3.754039 -v 0.037087 0.087552 0.172220 -vn -0.392126 -4.466673 -4.280956 -v 0.037165 0.087536 0.172205 -vn -0.391979 -3.678870 -4.974167 -v 0.037165 0.086882 0.172781 -vn -0.391844 1.303433 6.048139 -v 0.037165 0.082744 0.163627 -vn -0.392178 0.262608 6.181249 -v 0.037165 0.083609 0.163517 -vn 2.127926 -4.191856 -4.034923 -v 0.037245 0.087544 0.172213 -vn 2.160829 -3.496031 -4.629169 -v 0.037245 0.086889 0.172790 -vn 2.169673 1.249612 5.661654 -v 0.037245 0.082742 0.163616 -vn 2.169973 0.251928 5.792574 -v 0.037245 0.083608 0.163505 -vn 2.147149 3.862249 -4.337614 -v 0.037245 0.080425 0.172516 -vn 2.164334 3.089144 -4.908119 -v 0.037245 0.081127 0.173035 -vn 2.169990 0.251930 -5.792570 -v 0.037245 0.083608 0.173795 -vn 2.162388 -4.773167 -3.295126 -v 0.037245 0.088093 0.171534 -vn 2.170025 -5.776134 -0.503346 -v 0.037245 0.088958 0.169087 -vn 2.170027 -5.776134 0.503349 -v 0.037245 0.088958 0.168213 -vn 2.169701 -5.602165 1.494030 -v 0.037245 0.088810 0.167352 -vn 2.168420 -5.261131 2.437106 -v 0.037245 0.088519 0.166529 -vn 2.163388 -4.770088 3.299152 -v 0.037245 0.088093 0.165766 -vn 2.168777 2.207596 5.361401 -v 0.037245 0.081907 0.163872 -vn 2.165205 3.093345 4.905279 -v 0.037245 0.081127 0.164265 -vn 2.155230 4.487542 3.680050 -v 0.037245 0.079820 0.165415 -vn 2.149186 5.714757 1.038674 -v 0.037245 0.078751 0.167780 -vn 2.169864 5.798089 -0.000010 -v 0.037245 0.078677 0.168650 -vn 2.155869 5.451799 1.992136 -v 0.037245 0.078971 0.166935 -vn 2.160888 5.032996 2.884779 -v 0.037245 0.079331 0.166139 -vn 2.169881 -0.753774 5.748942 -v 0.037245 0.084481 0.163542 -vn 2.154250 -1.761755 5.531679 -v 0.037245 0.085335 0.163726 -vn 2.160069 -2.669421 5.151281 -v 0.037245 0.086145 0.164052 -vn 2.159664 -3.492320 4.632408 -v 0.037245 0.086889 0.164510 -vn 2.158838 -5.260722 -2.448505 -v 0.037245 0.088519 0.170771 -vn 2.167629 -2.661552 -5.151302 -v 0.037245 0.086145 0.173248 -vn 2.169638 -1.735516 -5.532118 -v 0.037245 0.085335 0.173574 -vn 2.169872 -0.753800 -5.748946 -v 0.037245 0.084481 0.173758 -vn 2.157283 2.222565 -5.361048 -v 0.037245 0.081907 0.173428 -vn 2.166459 5.032599 -2.880592 -v 0.037245 0.079331 0.171161 -vn 2.169286 5.451792 -1.973540 -v 0.037245 0.078971 0.170365 -vn 2.169894 5.710662 -1.002664 -v 0.037245 0.078751 0.169520 -vn -0.391953 6.097854 1.045598 -v 0.037165 0.078763 0.167782 -vn -0.391874 6.186925 0.000003 -v 0.037165 0.078689 0.168650 -vn -0.391555 -0.785853 6.136772 -v 0.037165 0.084479 0.163553 -vn -0.391927 -1.811672 5.915758 -v 0.037165 0.085331 0.163737 -vn -0.391903 -2.785345 5.524300 -v 0.037165 0.086140 0.164062 -vn -0.391980 -3.678875 4.974161 -v 0.037165 0.086882 0.164519 -vn -0.391936 -2.785364 -5.524459 -v 0.037165 0.086140 0.173238 -vn -0.391912 -1.811682 -5.915583 -v 0.037165 0.085331 0.173563 -vn -0.391550 -0.785833 -6.136778 -v 0.037165 0.084479 0.173747 -vn -0.391972 6.097849 -1.045609 -v 0.037165 0.078763 0.169518 -vn -0.391780 5.833435 -2.061056 -v 0.037165 0.078982 0.170362 -vn -0.391821 5.401273 -3.017313 -v 0.037165 0.079341 0.171156 -vn -2.864170 5.419752 0.869922 -v 0.037087 0.078742 0.167778 -vn -2.830022 5.512380 0.000002 -v 0.037087 0.078667 0.168650 -vn 2.147154 3.862251 4.337609 -v 0.037245 0.080425 0.164784 -vn -0.391769 4.813607 3.886731 -v 0.037165 0.079829 0.165422 -vn -0.392022 4.087534 4.644290 -v 0.037165 0.080432 0.164793 -vn -2.869746 4.298077 3.405671 -v 0.037087 0.079813 0.165409 -vn -2.852718 0.273933 5.490582 -v 0.037087 0.083608 0.163495 -vn -2.862136 -0.752913 5.438649 -v 0.037087 0.084482 0.163532 -vn -2.829867 -1.614161 5.270855 -v 0.037087 0.085338 0.163717 -vn -2.865721 -2.419775 4.925479 -v 0.037087 0.086150 0.164043 -vn -0.391850 -5.125870 3.464483 -v 0.037165 0.088084 0.165773 -vn -0.391719 -5.637619 2.548341 -v 0.037165 0.088509 0.166534 -vn -2.865705 -4.522994 3.105612 -v 0.037087 0.088101 0.165761 -vn 2.152848 -5.602929 -1.523676 -v 0.037245 0.088810 0.169948 -vn -0.392063 -6.164547 -0.524660 -v 0.037165 0.088946 0.169086 -vn -0.391777 -5.987208 -1.558945 -v 0.037165 0.088799 0.169945 -vn -2.871006 -5.468301 -0.406522 -v 0.037087 0.088968 0.169088 -vn -2.848842 -3.297575 -4.401932 -v 0.037087 0.086895 0.172798 -vn -2.865957 -2.416195 -4.927136 -v 0.037087 0.086150 0.173257 -vn -2.830343 -1.614129 -5.270704 -v 0.037087 0.085338 0.173583 -vn -2.862147 -0.752902 -5.438646 -v 0.037087 0.084482 0.173768 -vn -0.391790 2.306771 -5.740736 -v 0.037165 0.081911 0.173418 -vn -0.391637 3.243846 -5.268312 -v 0.037165 0.081133 0.173025 -vn -2.871176 1.992353 -5.108225 -v 0.037087 0.081903 0.173437 -vn -2.864113 5.419790 -0.869940 -v 0.037087 0.078742 0.169522 -vn -2.850688 5.172131 -1.866923 -v 0.037087 0.078962 0.170369 -vn -2.868522 4.759536 -2.726895 -v 0.037087 0.079323 0.171166 -vn -0.391795 5.833431 2.061066 -v 0.037165 0.078982 0.166938 -vn -4.676356 4.066012 1.025420 -v 0.037024 0.078758 0.167449 -vn -4.376657 3.837700 2.312046 -v 0.037024 0.079279 0.166109 -vn -2.869011 4.757312 2.730651 -v 0.037087 0.079323 0.166134 -vn -0.391832 5.401274 3.017308 -v 0.037165 0.079341 0.166144 -vn -4.401623 3.552353 2.679714 -v 0.037024 0.079773 0.165377 -vn -4.523896 3.204719 2.933140 -v 0.037024 0.079836 0.165301 -vn -0.391633 3.243824 5.268325 -v 0.037165 0.081133 0.164275 -vn -4.348270 1.530573 4.244035 -v 0.037024 0.081884 0.163816 -vn -2.871971 1.987918 5.109635 -v 0.037087 0.081903 0.163863 -vn -0.391794 2.306801 5.740724 -v 0.037165 0.081911 0.163882 -vn -4.372977 0.210428 4.482775 -v 0.037024 0.083606 0.163445 -vn -4.689972 -0.189538 4.174088 -v 0.037024 0.084130 0.163449 -vn -4.341950 -0.687939 4.468236 -v 0.037024 0.084489 0.163483 -vn -4.426870 -1.313977 4.229730 -v 0.037024 0.085352 0.163669 -vn -4.380656 -1.935541 4.036750 -v 0.037024 0.086172 0.163998 -vn -4.792438 -2.123231 3.461862 -v 0.037024 0.086432 0.164138 -vn -4.342698 -3.342933 3.041156 -v 0.037024 0.087588 0.165045 -vn -2.867692 -4.003926 3.750878 -v 0.037087 0.087552 0.165080 -vn -0.391748 -4.466662 4.280917 -v 0.037165 0.087536 0.165095 -vn 2.128188 -4.191898 4.034873 -v 0.037245 0.087544 0.165087 -vn -4.400097 -3.606833 2.608856 -v 0.037024 0.088143 0.165733 -vn -4.483850 -3.750260 2.259510 -v 0.037024 0.088179 0.165787 -vn -0.391923 -5.987215 1.558981 -v 0.037165 0.088799 0.167355 -vn -4.377767 -4.471888 0.241620 -v 0.037024 0.089018 0.168208 -vn -2.871696 -5.468440 0.401887 -v 0.037087 0.088968 0.168212 -vn -0.392065 -6.164549 0.524663 -v 0.037165 0.088946 0.168214 -vn -4.304029 -4.555369 -0.181705 -v 0.037024 0.089018 0.169092 -vn -4.628403 -4.188344 -0.663027 -v 0.037024 0.089001 0.169255 -vn -0.391719 -5.637620 -2.548339 -v 0.037165 0.088509 0.170766 -vn -4.397815 -3.600186 -2.621596 -v 0.037024 0.088143 0.171567 -vn -2.866811 -4.520196 -3.108644 -v 0.037087 0.088101 0.171539 -vn -0.391870 -5.125866 -3.464486 -v 0.037165 0.088084 0.171527 -vn -4.217175 -3.499076 -3.059026 -v 0.037024 0.087588 0.172255 -vn -4.675440 -0.180754 -4.190776 -v 0.037024 0.084130 0.173851 -vn -4.251991 -0.770994 -4.548461 -v 0.037024 0.084489 0.173818 -vn -4.407000 -1.332616 -4.245207 -v 0.037024 0.085352 0.173631 -vn -4.326841 -1.985940 -4.077341 -v 0.037024 0.086172 0.173302 -vn -4.650392 -2.162317 -3.625424 -v 0.037024 0.086432 0.173162 -vn -4.254419 -2.832660 -3.640085 -v 0.037024 0.086925 0.172839 -vn -4.743709 -2.711365 -3.098682 -v 0.037024 0.087402 0.172439 -vn -0.392187 0.262588 -6.181251 -v 0.037165 0.083609 0.173783 -vn -4.374353 1.052458 -4.356448 -v 0.037024 0.082729 0.173743 -vn -2.870805 1.217945 -5.347003 -v 0.037087 0.082740 0.173694 -vn -0.391826 1.303427 -6.047966 -v 0.037165 0.082744 0.173673 -vn 2.150979 1.282539 -5.664059 -v 0.037245 0.082742 0.173684 -vn -4.303354 1.502763 -4.304761 -v 0.037024 0.081884 0.173484 -vn -4.567895 1.880310 -3.870757 -v 0.037024 0.081763 0.173434 -vn -0.392020 4.087512 -4.644310 -v 0.037165 0.080432 0.172507 -vn -4.393073 3.562921 -2.681644 -v 0.037024 0.079773 0.171923 -vn -2.870703 4.300558 -3.401838 -v 0.037087 0.079813 0.171891 -vn -0.391774 4.813615 -3.886720 -v 0.037165 0.079829 0.171878 -vn 2.156539 4.484343 -3.683204 -v 0.037245 0.079820 0.171885 -vn -4.363725 3.841663 -2.332705 -v 0.037024 0.079279 0.171191 -vn -4.394207 4.414364 0.642923 -v 0.037024 0.078692 0.167770 -vn -4.398415 4.459723 -0.002098 -v 0.037024 0.078617 0.168650 -vn -4.392313 4.416431 -0.642975 -v 0.037024 0.078692 0.169530 -vn -4.673640 4.068487 -1.028092 -v 0.037024 0.078758 0.169851 -vn -4.396572 4.186031 -1.542050 -v 0.037024 0.078915 0.170386 -vn -4.702149 3.789476 -1.727577 -v 0.037024 0.079171 0.170988 -vn -4.202575 1.849120 4.167547 -v 0.036884 0.081667 0.163726 -vn -4.265007 1.216100 4.335859 -v 0.036884 0.082507 0.163438 -vn -4.122405 0.769906 4.565454 -v 0.036884 0.082893 0.163355 -vn -4.244355 0.334361 4.513146 -v 0.036884 0.083383 0.163291 -vn -4.169963 -0.112135 4.598325 -v 0.036884 0.084139 0.163282 -vn -4.229490 -0.507674 4.530331 -v 0.036884 0.084271 0.163291 -vn -4.286000 -0.971261 4.376729 -v 0.036884 0.085147 0.163438 -vn -4.078647 -4.638744 -0.393113 -v 0.036884 0.089167 0.169274 -vn -4.385819 -4.320811 -0.094259 -v 0.036884 0.089204 0.168650 -vn -4.139948 -4.599326 0.459656 -v 0.036884 0.089167 0.168026 -vn -4.263672 -4.429340 0.853522 -v 0.036884 0.089130 0.167765 -vn -4.235985 -4.349623 1.342673 -v 0.036884 0.088912 0.166904 -vn -4.184478 -4.261570 1.713084 -v 0.036884 0.088880 0.166811 -vn -4.274294 -3.972866 2.088667 -v 0.036884 0.088556 0.166091 -vn -4.120914 -3.877039 2.532185 -v 0.036884 0.088319 0.165695 -vn -4.289774 -3.482103 2.806865 -v 0.036884 0.088070 0.165347 -vn -4.204936 -3.247563 3.231649 -v 0.036884 0.087517 0.164739 -vn -4.241149 -2.961400 3.450371 -v 0.036884 0.087469 0.164694 -vn -4.246678 -2.557452 3.740025 -v 0.036884 0.086768 0.164149 -vn -4.048646 -2.238304 4.106319 -v 0.036884 0.086515 0.163993 -vn -4.264487 -1.798214 4.116827 -v 0.036884 0.085987 0.163726 -vn -4.158858 -1.418058 4.380679 -v 0.036884 0.085369 0.163499 -vn -4.341013 -4.312799 -0.901581 -v 0.036884 0.089130 0.169535 -vn -4.310831 -4.250952 -1.332525 -v 0.036884 0.088912 0.170396 -vn -4.223063 -4.228892 -1.682150 -v 0.036884 0.088880 0.170489 -vn -4.316508 -3.864649 -2.133919 -v 0.036884 0.088556 0.171209 -vn -3.953402 -4.008186 -2.490919 -v 0.036884 0.088319 0.171605 -vn -4.375422 -3.337522 -2.786697 -v 0.036884 0.088070 0.171953 -vn -4.201964 -3.265923 -3.212237 -v 0.036884 0.087517 0.172561 -vn -4.260460 -2.921907 -3.451555 -v 0.036884 0.087469 0.172606 -vn -4.293305 -2.504547 -3.701561 -v 0.036884 0.086768 0.173151 -vn -4.154010 -2.250712 -4.010838 -v 0.036884 0.086515 0.173307 -vn -4.309981 -1.696821 -4.095772 -v 0.036884 0.085987 0.173574 -vn -4.115308 -1.480860 -4.382525 -v 0.036884 0.085369 0.173801 -vn -4.343276 -0.901194 -4.311284 -v 0.036884 0.085147 0.173862 -vn -4.260033 -0.501801 -4.491669 -v 0.036884 0.084271 0.174009 -vn -4.204229 -0.129723 -4.566114 -v 0.036884 0.084139 0.174018 -vn -4.252170 0.402856 -4.485651 -v 0.036884 0.083383 0.174009 -vn -3.981986 0.704473 -4.651088 -v 0.036884 0.082893 0.173945 -vn -4.298986 1.235579 -4.282460 -v 0.036884 0.082507 0.173862 -vn -4.213756 1.841959 -4.153615 -v 0.036884 0.081667 0.173574 -vn -4.244671 2.404712 -3.840231 -v 0.036884 0.080886 0.173151 -vn -4.141342 2.795095 -3.667741 -v 0.036884 0.080616 0.172963 -vn -4.246756 3.117003 -3.272219 -v 0.036884 0.080185 0.172606 -vn -4.137107 3.426473 -3.090043 -v 0.036884 0.079708 0.172106 -vn -4.266906 3.658260 -2.635245 -v 0.036884 0.079584 0.171953 -vn -4.237291 3.928262 -2.290375 -v 0.036884 0.079098 0.171209 -vn -4.185953 4.154876 -1.936314 -v 0.036884 0.079022 0.171063 -vn -4.214993 4.308598 -1.471019 -v 0.036884 0.078741 0.170396 -vn -4.004493 4.541649 -1.192265 -v 0.036884 0.078595 0.169890 -vn -4.239712 4.492088 -0.630582 -v 0.036884 0.078523 0.169535 -vn -4.221111 4.534934 -0.001731 -v 0.036884 0.078450 0.168650 -vn -4.238095 4.494106 0.631515 -v 0.036884 0.078523 0.167765 -vn -4.130453 4.486773 1.109879 -v 0.036884 0.078595 0.167410 -vn -4.223949 4.287265 1.522672 -v 0.036884 0.078741 0.166904 -vn -4.154151 4.185961 1.923350 -v 0.036884 0.079022 0.166237 -vn -4.230371 3.938951 2.289647 -v 0.036884 0.079098 0.166091 -vn -4.255883 3.661906 2.654918 -v 0.036884 0.079584 0.165347 -vn -4.170199 3.438662 3.050614 -v 0.036884 0.079708 0.165194 -vn -4.228553 3.084455 3.327413 -v 0.036884 0.080185 0.164694 -vn -4.026605 2.888085 3.690888 -v 0.036884 0.080616 0.164337 -vn -4.231012 2.410177 3.857757 -v 0.036884 0.080886 0.164149 -vn -2.212597 5.525797 0.885007 -v 0.036689 0.078382 0.167741 -vn -2.219845 5.278112 1.842758 -v 0.036689 0.078606 0.166858 -vn -2.214606 4.908902 2.681847 -v 0.036689 0.078972 0.166023 -vn -2.210417 4.437696 3.411606 -v 0.036689 0.079471 0.165260 -vn -2.228366 3.769008 4.119513 -v 0.036689 0.080088 0.164589 -vn -2.213615 3.036265 4.699247 -v 0.036689 0.080808 0.164029 -vn -2.239139 2.239218 5.104913 -v 0.036689 0.081609 0.163595 -vn -2.213741 1.408129 5.415229 -v 0.036689 0.082472 0.163299 -vn -2.218241 0.430762 5.575239 -v 0.036689 0.083371 0.163149 -vn -2.216763 -0.480760 5.571269 -v 0.036689 0.084283 0.163149 -vn -2.209937 -1.339835 5.435276 -v 0.036689 0.085182 0.163299 -vn -2.226633 -2.261541 5.106679 -v 0.036689 0.086044 0.163595 -vn -2.212986 -3.083876 4.668696 -v 0.036689 0.086846 0.164029 -vn -2.222355 -3.773147 4.121392 -v 0.036689 0.087565 0.164589 -vn -2.211582 -4.399491 3.460367 -v 0.036689 0.088183 0.165260 -vn -2.216704 -4.934506 2.633045 -v 0.036689 0.088681 0.166023 -vn -2.220045 -5.291381 1.800548 -v 0.036689 0.089048 0.166858 -vn -2.210144 -5.515449 0.957526 -v 0.036689 0.089272 0.167741 -vn -2.224895 -5.586379 -0.022252 -v 0.036689 0.089347 0.168650 -vn -2.212710 -5.514494 -0.948210 -v 0.036689 0.089272 0.169559 -vn -2.217271 -5.295812 -1.795276 -v 0.036689 0.089048 0.170442 -vn -2.233846 -4.902351 -2.663041 -v 0.036689 0.088681 0.171277 -vn -2.216837 -4.396757 -3.455975 -v 0.036689 0.088183 0.172040 -vn -2.224726 -3.775311 -4.116567 -v 0.036689 0.087565 0.172711 -vn -2.210630 -3.092633 -4.665755 -v 0.036689 0.086846 0.173271 -vn -2.223165 -2.222029 -5.127101 -v 0.036689 0.086044 0.173705 -vn -2.212672 -1.347935 -5.430545 -v 0.036689 0.085182 0.174001 -vn -2.213794 -0.488515 -5.573327 -v 0.036689 0.084283 0.174151 -vn -2.231992 0.472439 -5.560511 -v 0.036689 0.083371 0.174151 -vn -2.215586 1.399775 -5.415376 -v 0.036689 0.082472 0.174001 -vn -2.239139 2.239224 -5.104910 -v 0.036689 0.081609 0.173705 -vn -2.211439 3.030160 -4.705834 -v 0.036689 0.080808 0.173271 -vn -2.221449 3.805247 -4.093832 -v 0.036689 0.080088 0.172711 -vn -2.213309 4.430176 -3.416878 -v 0.036689 0.079471 0.172040 -vn -2.211662 4.907320 -2.690466 -v 0.036689 0.078972 0.171277 -vn -2.230200 5.284246 -1.798842 -v 0.036689 0.078606 0.170442 -vn -2.214591 5.522398 -0.893000 -v 0.036689 0.078382 0.169559 -vn -2.239153 5.574355 -0.000006 -v 0.036689 0.078307 0.168650 -vn 0.607371 5.887396 -0.982424 -v 0.036449 0.078348 0.169564 -vn 0.607377 5.645411 -1.938060 -v 0.036449 0.078573 0.170453 -vn 0.607373 5.249403 -2.840827 -v 0.036449 0.078942 0.171294 -vn 0.607382 4.710233 -3.666133 -v 0.036449 0.079444 0.172062 -vn 0.607355 4.042595 -4.391426 -v 0.036449 0.080065 0.172736 -vn 0.607378 3.264627 -4.996918 -v 0.036449 0.080789 0.173300 -vn 0.607325 2.397657 -5.466070 -v 0.036449 0.081596 0.173736 -vn 0.607417 1.465264 -5.786171 -v 0.036449 0.082463 0.174034 -vn 0.607269 0.492926 -5.948442 -v 0.036449 0.083368 0.174185 -vn 0.607268 -0.492908 -5.948448 -v 0.036449 0.084285 0.174185 -vn 0.607413 -1.465295 -5.786165 -v 0.036449 0.085190 0.174034 -vn 0.607327 -2.397643 -5.466073 -v 0.036449 0.086058 0.173736 -vn 0.607346 -3.264629 -4.996904 -v 0.036449 0.086865 0.173300 -vn 0.607356 -4.042589 -4.391430 -v 0.036449 0.087589 0.172736 -vn 0.607372 -4.710236 -3.666130 -v 0.036449 0.088210 0.172062 -vn 0.607372 -5.249403 -2.840829 -v 0.036449 0.088712 0.171294 -vn 0.607378 -5.645410 -1.938061 -v 0.036449 0.089080 0.170453 -vn 0.607380 -5.887395 -0.982420 -v 0.036449 0.089305 0.169564 -vn 0.607347 -5.968843 -0.000003 -v 0.036449 0.089381 0.168650 -vn 0.607345 -5.887408 0.982416 -v 0.036449 0.089305 0.167736 -vn 0.607374 -5.645411 1.938065 -v 0.036449 0.089080 0.166847 -vn 0.607373 -5.249403 2.840827 -v 0.036449 0.088712 0.166006 -vn 0.607382 -4.710233 3.666133 -v 0.036449 0.088210 0.165238 -vn 0.607351 -4.042590 4.391429 -v 0.036449 0.087589 0.164564 -vn 0.607331 -3.264630 4.996905 -v 0.036449 0.086865 0.164000 -vn 0.607325 -2.397657 5.466070 -v 0.036449 0.086058 0.163564 -vn 0.607417 -1.465264 5.786171 -v 0.036449 0.085190 0.163266 -vn 0.607269 -0.492926 5.948442 -v 0.036449 0.084285 0.163115 -vn 0.607268 0.492908 5.948448 -v 0.036449 0.083368 0.163115 -vn 0.607413 1.465295 5.786165 -v 0.036449 0.082463 0.163266 -vn 0.607331 2.397639 5.466076 -v 0.036449 0.081596 0.163564 -vn 0.607393 3.264636 4.996910 -v 0.036449 0.080789 0.164000 -vn 0.607356 4.042589 4.391430 -v 0.036449 0.080065 0.164564 -vn 0.607372 4.710236 3.666130 -v 0.036449 0.079444 0.165238 -vn 0.607372 5.249403 2.840829 -v 0.036449 0.078942 0.166006 -vn 0.607378 5.645410 1.938061 -v 0.036449 0.078573 0.166847 -vn 0.607356 5.887406 0.982418 -v 0.036449 0.078348 0.167736 -vn 0.607346 5.968843 0.000001 -v 0.036449 0.078273 0.168650 -vn 3.323310 4.948545 -0.825764 -v 0.036221 0.078430 0.169551 -vn 3.323315 4.745113 -1.628991 -v 0.036221 0.078651 0.170427 -vn 3.323330 4.412264 -2.387799 -v 0.036221 0.079014 0.171254 -vn 3.323292 3.959076 -3.081481 -v 0.036221 0.079509 0.172011 -vn 3.323262 3.397860 -3.691090 -v 0.036221 0.080121 0.172676 -vn 3.323283 2.744007 -4.200039 -v 0.036221 0.080834 0.173231 -vn 3.323319 2.015261 -4.594376 -v 0.036221 0.081629 0.173661 -vn 3.323326 1.231600 -4.863428 -v 0.036221 0.082484 0.173954 -vn 3.323287 0.414313 -4.999752 -v 0.036221 0.083375 0.174103 -vn 3.323301 -0.414313 -4.999743 -v 0.036221 0.084279 0.174103 -vn 3.323335 -1.231598 -4.863422 -v 0.036221 0.085170 0.173954 -vn 3.323314 -2.015268 -4.594374 -v 0.036221 0.086025 0.173661 -vn 3.323274 -2.744003 -4.200046 -v 0.036221 0.086820 0.173231 -vn 3.323260 -3.397860 -3.691092 -v 0.036221 0.087533 0.172676 -vn 3.323300 -3.959071 -3.081481 -v 0.036221 0.088145 0.172011 -vn 3.323330 -4.412268 -2.387794 -v 0.036221 0.088639 0.171254 -vn 3.323318 -4.745110 -1.628988 -v 0.036221 0.089002 0.170427 -vn 3.323305 -4.948546 -0.825764 -v 0.036221 0.089224 0.169551 -vn 3.323257 -5.016950 -0.000006 -v 0.036221 0.089299 0.168650 -vn 3.323295 -4.948534 0.825781 -v 0.036221 0.089224 0.167749 -vn 3.323318 -4.745110 1.628997 -v 0.036221 0.089002 0.166873 -vn 3.323330 -4.412264 2.387799 -v 0.036221 0.088639 0.166046 -vn 3.323292 -3.959076 3.081481 -v 0.036221 0.088145 0.165289 -vn 3.323262 -3.397860 3.691090 -v 0.036221 0.087533 0.164624 -vn 3.323283 -2.744007 4.200039 -v 0.036221 0.086820 0.164069 -vn 3.323319 -2.015261 4.594376 -v 0.036221 0.086025 0.163639 -vn 3.323326 -1.231600 4.863428 -v 0.036221 0.085170 0.163346 -vn 3.323215 -0.414334 4.999836 -v 0.036221 0.084279 0.163197 -vn 3.323221 0.414322 4.999836 -v 0.036221 0.083375 0.163197 -vn 3.323328 1.231613 4.863427 -v 0.036221 0.082484 0.163346 -vn 3.323314 2.015268 4.594374 -v 0.036221 0.081629 0.163639 -vn 3.323274 2.744003 4.200046 -v 0.036221 0.080834 0.164069 -vn 3.323260 3.397860 3.691092 -v 0.036221 0.080121 0.164624 -vn 3.323300 3.959071 3.081481 -v 0.036221 0.079509 0.165289 -vn 3.323330 4.412268 2.387794 -v 0.036221 0.079014 0.166046 -vn 3.323316 4.745111 1.628994 -v 0.036221 0.078651 0.166873 -vn 3.323286 4.948536 0.825784 -v 0.036221 0.078430 0.167749 -vn 3.323259 5.016949 0.000002 -v 0.036221 0.078355 0.168650 -vn 5.311654 2.865821 -0.478226 -v 0.036059 0.078607 0.169521 -vn 5.311690 2.747999 -0.943396 -v 0.036059 0.078822 0.170368 -vn 5.311683 2.555249 -1.382826 -v 0.036059 0.079173 0.171169 -vn 5.311681 2.292795 -1.784550 -v 0.036059 0.079651 0.171900 -vn 5.311719 1.967757 -2.137571 -v 0.036059 0.080243 0.172543 -vn 5.311667 1.589140 -2.432349 -v 0.036059 0.080932 0.173080 -vn 5.311701 1.167086 -2.660716 -v 0.036059 0.081701 0.173496 -vn 5.311683 0.713256 -2.816530 -v 0.036059 0.082528 0.173780 -vn 5.311765 0.239916 -2.895425 -v 0.036059 0.083390 0.173924 -vn 5.311759 -0.239932 -2.895430 -v 0.036059 0.084264 0.173924 -vn 5.311678 -0.713238 -2.816539 -v 0.036059 0.085126 0.173780 -vn 5.311700 -1.167095 -2.660711 -v 0.036059 0.085953 0.173496 -vn 5.311668 -1.589125 -2.432359 -v 0.036059 0.086721 0.173080 -vn 5.311720 -1.967771 -2.137559 -v 0.036059 0.087411 0.172543 -vn 5.311679 -2.292791 -1.784557 -v 0.036059 0.088003 0.171900 -vn 5.311684 -2.555249 -1.382824 -v 0.036059 0.088481 0.171169 -vn 5.311687 -2.748006 -0.943393 -v 0.036059 0.088832 0.170368 -vn 5.311653 -2.865821 -0.478237 -v 0.036059 0.089047 0.169521 -vn 5.311696 -2.905414 0.000005 -v 0.036059 0.089119 0.168650 -vn 5.311666 -2.865815 0.478219 -v 0.036059 0.089047 0.167779 -vn 5.311687 -2.748013 0.943399 -v 0.036059 0.088832 0.166932 -vn 5.311683 -2.555249 1.382829 -v 0.036059 0.088481 0.166131 -vn 5.311681 -2.292795 1.784550 -v 0.036059 0.088003 0.165400 -vn 5.311712 -1.967780 2.137589 -v 0.036059 0.087411 0.164757 -vn 5.311666 -1.589138 2.432354 -v 0.036059 0.086721 0.164220 -vn 5.311701 -1.167086 2.660716 -v 0.036059 0.085953 0.163804 -vn 5.311682 -0.713266 2.816532 -v 0.036059 0.085126 0.163520 -vn 5.311675 -0.239941 2.895484 -v 0.036059 0.084264 0.163376 -vn 5.311676 0.239944 2.895478 -v 0.036059 0.083390 0.163376 -vn 5.311687 0.713256 2.816527 -v 0.036059 0.082528 0.163520 -vn 5.311700 1.167095 2.660711 -v 0.036059 0.081701 0.163804 -vn 5.311668 1.589125 2.432359 -v 0.036059 0.080932 0.164220 -vn 5.311713 1.967789 2.137581 -v 0.036059 0.080243 0.164757 -vn 5.311678 2.292796 1.784556 -v 0.036059 0.079651 0.165400 -vn 5.311684 2.555249 1.382824 -v 0.036059 0.079173 0.166131 -vn 5.311686 2.748014 0.943400 -v 0.036059 0.078822 0.166932 -vn 5.311666 2.865814 0.478225 -v 0.036059 0.078607 0.167779 -vn 5.311696 2.905416 -0.000006 -v 0.036059 0.078535 0.168650 -vn 6.179245 0.788865 -0.131638 -v 0.036000 0.078839 0.169482 -vn 6.179239 0.756460 -0.259689 -v 0.036000 0.079044 0.170292 -vn 6.179241 0.703389 -0.380655 -v 0.036000 0.079379 0.171057 -vn 6.179240 0.631146 -0.491242 -v 0.036000 0.079836 0.171756 -vn 6.179244 0.541673 -0.588414 -v 0.036000 0.080402 0.172370 -vn 6.179233 0.437459 -0.669576 -v 0.036000 0.081061 0.172883 -vn 6.179236 0.321273 -0.732439 -v 0.036000 0.081795 0.173281 -vn 6.179236 0.196338 -0.775328 -v 0.036000 0.082585 0.173552 -vn 6.179240 0.066043 -0.797058 -v 0.036000 0.083409 0.173690 -vn 6.179240 -0.066045 -0.797058 -v 0.036000 0.084244 0.173690 -vn 6.179236 -0.196338 -0.775329 -v 0.036000 0.085068 0.173552 -vn 6.179236 -0.321274 -0.732440 -v 0.036000 0.085858 0.173281 -vn 6.179234 -0.437453 -0.669578 -v 0.036000 0.086593 0.172883 -vn 6.179244 -0.541676 -0.588409 -v 0.036000 0.087252 0.172370 -vn 6.179240 -0.631145 -0.491243 -v 0.036000 0.087817 0.171756 -vn 6.179241 -0.703390 -0.380654 -v 0.036000 0.088274 0.171057 -vn 6.179239 -0.756457 -0.259692 -v 0.036000 0.088610 0.170292 -vn 6.179245 -0.788864 -0.131633 -v 0.036000 0.088815 0.169482 -vn 6.179241 -0.799784 -0.000001 -v 0.036000 0.088884 0.168650 -vn 6.179242 -0.788873 0.131642 -v 0.036000 0.088815 0.167818 -vn 6.179235 -0.756474 0.259697 -v 0.036000 0.088610 0.167008 -vn 6.179242 -0.703386 0.380657 -v 0.036000 0.088274 0.166243 -vn 6.179240 -0.631146 0.491241 -v 0.036000 0.087817 0.165544 -vn 6.179234 -0.541700 0.588440 -v 0.036000 0.087252 0.164929 -vn 6.179234 -0.437452 0.669577 -v 0.036000 0.086593 0.164417 -vn 6.179236 -0.321273 0.732439 -v 0.036000 0.085858 0.164019 -vn 6.179238 -0.196343 0.775323 -v 0.036000 0.085068 0.163748 -vn 6.179253 -0.066040 0.797010 -v 0.036000 0.084244 0.163610 -vn 6.179252 0.066048 0.797015 -v 0.036000 0.083409 0.163610 -vn 6.179236 0.196338 0.775329 -v 0.036000 0.082585 0.163748 -vn 6.179236 0.321274 0.732440 -v 0.036000 0.081795 0.164019 -vn 6.179233 0.437452 0.669578 -v 0.036000 0.081061 0.164417 -vn 6.179234 0.541696 0.588442 -v 0.036000 0.080402 0.164929 -vn 6.179240 0.631146 0.491237 -v 0.036000 0.079836 0.165544 -vn 6.179242 0.703390 0.380654 -v 0.036000 0.079379 0.166243 -vn 6.179235 0.756471 0.259703 -v 0.036000 0.079044 0.167008 -vn 6.179243 0.788872 0.131637 -v 0.036000 0.078839 0.167818 -vn 6.179242 0.799784 0.000001 -v 0.036000 0.078770 0.168650 -vn 5.508965 -1.874018 0.812800 -v 0.036000 0.085628 0.167904 -vn 5.507341 -2.046851 0.049193 -v 0.036000 0.085777 0.168650 -vn 5.493523 0.812214 -1.895944 -v 0.036000 0.083081 0.170452 -vn 5.485377 0.024096 -2.072889 -v 0.036000 0.083827 0.170600 -vn 5.480050 -0.776989 -1.929466 -v 0.036000 0.084573 0.170452 -vn 5.476744 -1.463391 -1.484453 -v 0.036000 0.085206 0.170029 -vn 5.507046 -1.421365 1.469657 -v 0.036000 0.085206 0.167271 -vn 5.506265 -0.752108 1.901733 -v 0.036000 0.084573 0.166848 -vn 5.507106 0.029794 2.043508 -v 0.036000 0.083827 0.166700 -vn 5.510295 0.803385 1.874927 -v 0.036000 0.083081 0.166848 -vn 5.522403 1.879037 -0.760017 -v 0.036000 0.082025 0.169396 -vn 5.505479 1.463695 -1.431956 -v 0.036000 0.082448 0.170029 -vn 5.474945 -1.925116 -0.805833 -v 0.036000 0.085628 0.169396 -vn 5.516479 1.449734 1.424732 -v 0.036000 0.082448 0.167271 -vn 5.540291 2.005962 -0.000005 -v 0.036000 0.081877 0.168650 -vn 5.526305 1.871154 0.765153 -v 0.036000 0.082025 0.167904 -vn 2.274156 -5.001595 2.236451 -v 0.035800 0.085444 0.167980 -vn 1.968982 -4.769452 3.144483 -v 0.035800 0.085243 0.167621 -vn 2.281076 -3.717641 4.017818 -v 0.035800 0.085064 0.167413 -vn 2.044822 -3.097820 4.736246 -v 0.035800 0.084702 0.167134 -vn 2.287863 -1.838890 5.150598 -v 0.035800 0.084496 0.167033 -vn 2.113326 -0.949479 5.527200 -v 0.035800 0.084010 0.166910 -vn 2.294523 0.331545 5.454090 -v 0.035800 0.083827 0.166900 -vn 2.174280 1.319013 5.401459 -v 0.035800 0.083286 0.166986 -vn 2.301147 2.445165 4.880898 -v 0.035800 0.083157 0.167033 -vn 2.227185 3.336477 4.393031 -v 0.035800 0.082656 0.167350 -vn 2.307669 4.161845 3.525164 -v 0.035800 0.082589 0.167413 -vn 2.271574 4.778882 2.678228 -v 0.035800 0.082228 0.167938 -vn 2.314039 5.207196 1.605790 -v 0.035800 0.082210 0.167980 -vn 2.393616 5.474804 -0.000016 -v 0.035800 0.082077 0.168650 -vn 2.313996 5.207253 -1.605438 -v 0.035800 0.082210 0.169320 -vn 2.282347 4.778751 -2.660565 -v 0.035800 0.082228 0.169362 -vn 2.315555 4.148437 -3.531132 -v 0.035800 0.082589 0.169887 -vn 2.255382 3.349336 -4.354653 -v 0.035800 0.082656 0.169951 -vn 2.316828 2.415730 -4.881643 -v 0.035800 0.083157 0.170267 -vn 2.228812 1.361769 -5.346488 -v 0.035800 0.083286 0.170314 -vn 2.317835 0.291225 -5.437895 -v 0.035800 0.083827 0.170400 -vn 2.204777 -0.860187 -5.470840 -v 0.035800 0.084010 0.170390 -vn 2.318653 -1.880369 -5.110012 -v 0.035800 0.084496 0.170267 -vn 2.185102 -2.953914 -4.704194 -v 0.035800 0.084702 0.170166 -vn 2.319229 -3.745429 -3.951432 -v 0.035800 0.085064 0.169887 -vn 2.171192 -4.575683 -3.169938 -v 0.035800 0.085243 0.169679 -vn 2.319570 -5.001444 -2.150388 -v 0.035800 0.085444 0.169320 -vn 2.164023 -5.459176 -1.117561 -v 0.035800 0.085539 0.169014 -vn 2.267168 -5.482897 0.092033 -v 0.035800 0.085577 0.168650 -vn 1.886030 -5.679762 1.001680 -v 0.035800 0.085539 0.168286 -vn -2.314034 5.207203 1.605784 -v 0.034700 0.082210 0.167980 -vn -2.393613 5.474806 -0.000004 -v 0.034700 0.082077 0.168650 -vn -2.313998 5.207251 -1.605440 -v 0.034700 0.082210 0.169320 -vn -2.271654 4.779057 -2.677945 -v 0.034700 0.082228 0.169362 -vn -2.307669 4.161845 -3.525164 -v 0.034700 0.082589 0.169887 -vn -2.227185 3.336477 -4.393031 -v 0.034700 0.082656 0.169951 -vn -2.301196 2.444925 -4.881042 -v 0.034700 0.083157 0.170267 -vn -2.174305 1.318766 -5.401437 -v 0.034700 0.083286 0.170314 -vn -2.294577 0.331762 -5.453977 -v 0.034700 0.083827 0.170400 -vn -2.113394 -0.949296 -5.527224 -v 0.034700 0.084010 0.170390 -vn -2.287890 -1.839047 -5.150556 -v 0.034700 0.084496 0.170267 -vn -2.044904 -3.097792 -4.736144 -v 0.034700 0.084702 0.170166 -vn -2.281101 -3.717603 -4.017848 -v 0.034700 0.085064 0.169887 -vn -1.968948 -4.769515 -3.144444 -v 0.034700 0.085243 0.169679 -vn -2.274173 -5.001566 -2.236431 -v 0.034700 0.085444 0.169320 -vn -1.886042 -5.679755 -1.001707 -v 0.034700 0.085539 0.169014 -vn -2.267168 -5.482897 -0.092033 -v 0.034700 0.085577 0.168650 -vn -2.164010 -5.459183 1.117533 -v 0.034700 0.085539 0.168286 -vn -2.319548 -5.001474 2.150423 -v 0.034700 0.085444 0.167980 -vn -2.171176 -4.575665 3.169968 -v 0.034700 0.085243 0.167621 -vn -2.319218 -3.745476 3.951377 -v 0.034700 0.085064 0.167413 -vn -2.185087 -2.953882 4.704289 -v 0.034700 0.084702 0.167134 -vn -2.318626 -1.880213 5.110054 -v 0.034700 0.084496 0.167033 -vn -2.204709 -0.860369 5.470816 -v 0.034700 0.084010 0.166910 -vn -2.317782 0.291007 5.438008 -v 0.034700 0.083827 0.166900 -vn -2.228793 1.362018 5.346508 -v 0.034700 0.083286 0.166986 -vn -2.316779 2.415969 4.881498 -v 0.034700 0.083157 0.167033 -vn -2.255382 3.349336 4.354653 -v 0.034700 0.082656 0.167350 -vn -2.315555 4.148437 3.531132 -v 0.034700 0.082589 0.167413 -vn -2.282268 4.778576 2.660848 -v 0.034700 0.082228 0.167938 -vn -5.505479 1.463695 1.431956 -v 0.034500 0.082448 0.167271 -vn -5.522396 1.879043 0.760022 -v 0.034500 0.082025 0.167904 -vn -5.493497 0.812253 1.895960 -v 0.034500 0.083081 0.166848 -vn -5.485327 0.024069 2.072944 -v 0.034500 0.083827 0.166700 -vn -5.480032 -0.776975 1.929494 -v 0.034500 0.084573 0.166848 -vn -5.476735 -1.463412 1.484450 -v 0.034500 0.085206 0.167271 -vn -5.474927 -1.925134 0.805837 -v 0.034500 0.085628 0.167904 -vn -5.507341 -2.046851 -0.049193 -v 0.034500 0.085777 0.168650 -vn -5.508990 -1.873986 -0.812802 -v 0.034500 0.085628 0.169396 -vn -5.507047 -1.421366 -1.469652 -v 0.034500 0.085206 0.170029 -vn -5.506280 -0.752115 -1.901712 -v 0.034500 0.084573 0.170452 -vn -5.507154 0.029819 -2.043453 -v 0.034500 0.083827 0.170600 -vn -5.510322 0.803346 -1.874911 -v 0.034500 0.083081 0.170452 -vn -5.516479 1.449734 -1.424732 -v 0.034500 0.082448 0.170029 -vn -5.526314 1.871148 -0.765144 -v 0.034500 0.082025 0.169396 -vn -5.540292 2.005960 0.000002 -v 0.034500 0.081877 0.168650 -vn -5.190921 1.389141 1.912009 -v 0.034500 0.082181 0.166385 -vn -5.190858 1.912047 1.389181 -v 0.034500 0.081562 0.167004 -vn -5.190856 2.247743 0.730348 -v 0.034500 0.081164 0.167785 -vn -5.190829 2.363442 -0.000006 -v 0.034500 0.081027 0.168650 -vn -5.190850 -1.912045 1.389192 -v 0.034500 0.086092 0.167004 -vn -5.190920 -1.389160 1.911996 -v 0.034500 0.085473 0.166385 -vn -5.190872 -0.730335 2.247732 -v 0.034500 0.084692 0.165987 -vn -5.190872 -0.000001 2.363405 -v 0.034500 0.083827 0.165850 -vn -5.190867 0.730347 2.247732 -v 0.034500 0.082962 0.165987 -vn -5.190921 -1.389141 -1.912009 -v 0.034500 0.085473 0.170915 -vn -5.190858 -1.912047 -1.389181 -v 0.034500 0.086092 0.170296 -vn -5.190856 -2.247743 -0.730348 -v 0.034500 0.086490 0.169515 -vn -5.190829 -2.363442 0.000006 -v 0.034500 0.086627 0.168650 -vn -5.190851 -2.247746 0.730346 -v 0.034500 0.086490 0.167785 -vn -5.190851 2.247746 -0.730346 -v 0.034500 0.081164 0.169515 -vn -5.190850 1.912045 -1.389192 -v 0.034500 0.081562 0.170296 -vn -5.190920 1.389160 -1.911996 -v 0.034500 0.082181 0.170915 -vn -5.190872 0.730335 -2.247732 -v 0.034500 0.082962 0.171313 -vn -5.190872 0.000001 -2.363405 -v 0.034500 0.083827 0.171450 -vn -5.190867 -0.730347 -2.247732 -v 0.034500 0.084692 0.171313 -vn -2.056948 4.903312 -1.592071 -v 0.034300 0.080974 0.169577 -vn -2.060001 4.171529 -3.029641 -v 0.034300 0.081400 0.170413 -vn -2.062724 3.031183 -4.170678 -v 0.034300 0.082063 0.171077 -vn -2.065036 1.593981 -4.903553 -v 0.034300 0.082900 0.171503 -vn -2.067004 0.000570 -5.156291 -v 0.034300 0.083827 0.171650 -vn -2.068628 -1.593014 -4.904238 -v 0.034300 0.084754 0.171503 -vn -2.069905 -3.030662 -4.171939 -v 0.034300 0.085590 0.171077 -vn -2.070766 -4.171736 -3.031201 -v 0.034300 0.086254 0.170413 -vn -2.071301 -4.904330 -1.593624 -v 0.034300 0.086680 0.169577 -vn -2.071470 -5.156786 0.000004 -v 0.034300 0.086827 0.168650 -vn -2.071303 -4.904327 1.593620 -v 0.034300 0.086680 0.167723 -vn -2.070772 -4.171726 3.031203 -v 0.034300 0.086254 0.166887 -vn -2.069906 -3.030674 4.171929 -v 0.034300 0.085590 0.166223 -vn -2.068625 -1.593008 4.904244 -v 0.034300 0.084754 0.165797 -vn -2.067004 0.000568 5.156291 -v 0.034300 0.083827 0.165650 -vn -2.065040 1.593987 4.903546 -v 0.034300 0.082900 0.165797 -vn -2.062726 3.031168 4.170689 -v 0.034300 0.082063 0.166223 -vn -2.059998 4.171540 3.029637 -v 0.034300 0.081400 0.166887 -vn -2.056945 4.903315 1.592075 -v 0.034300 0.080974 0.167723 -vn -2.055217 5.155160 -0.000004 -v 0.034300 0.080827 0.168650 -vn -2.293325 5.291950 -1.222308 -v 0.028700 0.080960 0.169534 -vn -2.264663 5.050697 -2.052714 -v 0.028700 0.080974 0.169577 -vn -2.289853 4.682204 -2.758496 -v 0.028700 0.081348 0.170340 -vn -2.234545 4.204367 -3.513052 -v 0.028700 0.081400 0.170413 -vn -2.286290 3.638336 -4.040738 -v 0.028700 0.081956 0.170995 -vn -2.199343 2.950130 -4.653279 -v 0.028700 0.082063 0.171077 -vn -2.282713 2.256081 -4.950672 -v 0.028700 0.082731 0.171443 -vn -2.159359 1.401372 -5.363301 -v 0.028700 0.082900 0.171503 -vn -2.279035 0.663605 -5.402952 -v 0.028700 0.083603 0.171642 -vn -2.114999 -0.298396 -5.571589 -v 0.028700 0.083827 0.171650 -vn -2.275315 -0.992228 -5.355453 -v 0.028700 0.084494 0.171575 -vn -2.066695 -1.990869 -5.252858 -v 0.028700 0.084754 0.171503 -vn -2.271518 -2.557971 -4.812014 -v 0.028700 0.085327 0.171248 -vn -2.014546 -3.516235 -4.431137 -v 0.028700 0.085590 0.171077 -vn -2.267732 -3.888661 -3.822265 -v 0.028700 0.086026 0.170691 -vn -1.958943 -4.728193 -3.177666 -v 0.028700 0.086254 0.170413 -vn -2.263907 -4.860636 -2.477485 -v 0.028700 0.086530 0.169952 -vn -1.899781 -5.508146 -1.605729 -v 0.028700 0.086680 0.169577 -vn -2.259982 -5.383614 -0.901799 -v 0.028700 0.086793 0.169097 -vn -1.837137 -5.776632 0.140180 -v 0.028700 0.086827 0.168650 -vn -2.256017 -5.408582 0.759140 -v 0.028700 0.086793 0.168203 -vn -2.138117 -5.306173 1.672295 -v 0.028700 0.086680 0.167723 -vn -2.297400 -4.863618 2.410855 -v 0.028700 0.086530 0.167348 -vn -2.144504 -4.553540 3.187150 -v 0.028700 0.086254 0.166887 -vn -2.297177 -3.908560 3.767237 -v 0.028700 0.086026 0.166609 -vn -2.154974 -3.378606 4.402269 -v 0.028700 0.085590 0.166223 -vn -2.296940 -2.588329 4.771909 -v 0.028700 0.085327 0.166052 -vn -2.169147 -1.892631 5.203765 -v 0.028700 0.084754 0.165797 -vn -2.296536 -1.026430 5.331071 -v 0.028700 0.084494 0.165725 -vn -2.186477 -0.236058 5.517295 -v 0.028700 0.083827 0.165650 -vn -2.296083 0.631609 5.392453 -v 0.028700 0.083603 0.165658 -vn -2.206309 1.434997 5.314647 -v 0.028700 0.082900 0.165797 -vn -2.295566 2.230747 4.950297 -v 0.028700 0.082731 0.165857 -vn -2.227623 2.963728 4.616588 -v 0.028700 0.082063 0.166223 -vn -2.294883 3.621998 4.045748 -v 0.028700 0.081956 0.166304 -vn -2.249412 4.206975 3.490243 -v 0.028700 0.081400 0.166887 -vn -2.294178 4.675148 2.763217 -v 0.028700 0.081348 0.166960 -vn -2.270397 5.049391 2.042873 -v 0.028700 0.080974 0.167723 -vn -2.293324 5.291953 1.222305 -v 0.028700 0.080960 0.167766 -vn -2.357433 5.463895 0.000004 -v 0.028700 0.080827 0.168650 -vn -5.474120 1.739193 1.161963 -v 0.028500 0.081183 0.166847 -vn -5.487123 1.988136 0.599100 -v 0.028500 0.080769 0.167707 -vn -5.464605 1.329559 1.629282 -v 0.028500 0.081832 0.166148 -vn -5.457898 0.794769 1.955728 -v 0.028500 0.082658 0.165671 -vn -5.453161 0.183030 2.108991 -v 0.028500 0.083588 0.165459 -vn -5.449901 -0.449832 2.072810 -v 0.028500 0.084539 0.165530 -vn -5.447728 -1.045403 1.848797 -v 0.028500 0.085427 0.165879 -vn -5.446247 -1.548586 1.456412 -v 0.028500 0.086173 0.166473 -vn -5.445406 -1.912489 0.930866 -v 0.028500 0.086710 0.167262 -vn -5.474413 -2.075723 0.268722 -v 0.028500 0.086991 0.168173 -vn -5.474451 -2.062746 -0.345566 -v 0.028500 0.086991 0.169127 -vn -5.472483 -1.870455 -0.940413 -v 0.028500 0.086710 0.170038 -vn -5.470832 -1.510890 -1.451604 -v 0.028500 0.086173 0.170827 -vn -5.469661 -1.016586 -1.833323 -v 0.028500 0.085427 0.171421 -vn -5.469248 -0.432292 -2.051476 -v 0.028500 0.084539 0.171770 -vn -5.469745 0.189073 -2.087180 -v 0.028500 0.083588 0.171841 -vn -5.471569 0.791451 -1.938091 -v 0.028500 0.082658 0.171629 -vn -5.475118 1.320815 -1.618891 -v 0.028500 0.081832 0.171152 -vn -5.480942 1.730077 -1.159681 -v 0.028500 0.081183 0.170453 -vn -5.489537 1.983660 -0.603036 -v 0.028500 0.080769 0.169593 -vn -5.501266 2.060428 0.000003 -v 0.028500 0.080627 0.168650 -vn -5.259131 -1.636218 -1.636235 -v 0.028500 0.078311 0.163135 -vn -5.259207 -1.923945 -1.285531 -v 0.028500 0.077341 0.164317 -vn -5.259193 -2.137784 -0.885488 -v 0.028500 0.076621 0.165665 -vn -5.259183 -2.269465 -0.451429 -v 0.028500 0.076177 0.167128 -vn -5.259157 0.885515 -2.137807 -v 0.028500 0.086812 0.161444 -vn -5.259192 0.451421 -2.269458 -v 0.028500 0.085349 0.161000 -vn -5.259197 -0.000001 -2.313913 -v 0.028500 0.083827 0.160850 -vn -5.259189 -0.451424 -2.269458 -v 0.028500 0.082305 0.161000 -vn -5.259159 -0.885506 -2.137810 -v 0.028500 0.080842 0.161444 -vn -5.259180 -1.285554 -1.923958 -v 0.028500 0.079493 0.162165 -vn -5.259202 1.923942 -1.285540 -v 0.028500 0.090312 0.164317 -vn -5.259129 1.636228 -1.636226 -v 0.028500 0.089342 0.163135 -vn -5.259209 1.285526 -1.923946 -v 0.028500 0.088160 0.162165 -vn -5.259197 2.313913 -0.000002 -v 0.028500 0.091627 0.168650 -vn -5.259182 2.269465 -0.451427 -v 0.028500 0.091477 0.167128 -vn -5.259194 2.137783 -0.885488 -v 0.028500 0.091033 0.165665 -vn -5.259192 -0.451421 2.269458 -v 0.028500 0.082305 0.176300 -vn -5.259198 0.000001 2.313913 -v 0.028500 0.083827 0.176450 -vn -5.259196 -1.636185 1.636183 -v 0.028500 0.078311 0.174165 -vn -5.259178 -1.285555 1.923959 -v 0.028500 0.079493 0.175135 -vn -5.259159 -0.885512 2.137808 -v 0.028500 0.080842 0.175856 -vn -5.259197 -2.313913 0.000002 -v 0.028500 0.076027 0.168650 -vn -5.259182 -2.269465 0.451427 -v 0.028500 0.076177 0.170172 -vn -5.259192 -2.137783 0.885494 -v 0.028500 0.076621 0.171635 -vn -5.259156 -1.923978 1.285565 -v 0.028500 0.077341 0.172983 -vn -5.259155 1.923973 1.285572 -v 0.028500 0.090312 0.172983 -vn -5.259193 2.137784 0.885488 -v 0.028500 0.091033 0.171635 -vn -5.259182 2.269465 0.451429 -v 0.028500 0.091477 0.170172 -vn -5.259189 0.451424 2.269458 -v 0.028500 0.085349 0.176300 -vn -5.259159 0.885506 2.137810 -v 0.028500 0.086812 0.175856 -vn -5.259206 1.285540 1.923938 -v 0.028500 0.088160 0.175135 -vn -5.259193 1.636189 1.636183 -v 0.028500 0.089342 0.174165 -vn -2.134655 5.245713 -0.000001 -v 0.028700 0.091827 0.168650 -vn -2.134647 5.144938 1.023388 -v 0.028700 0.091673 0.170211 -vn -2.134652 4.846411 2.007450 -v 0.028700 0.091218 0.171711 -vn -2.134628 4.361683 2.914387 -v 0.028700 0.090479 0.173095 -vn -2.134657 3.709287 3.709280 -v 0.028700 0.089484 0.174307 -vn -2.134663 2.914363 4.361645 -v 0.028700 0.088271 0.175302 -vn -2.134629 2.007453 4.846445 -v 0.028700 0.086888 0.176041 -vn -2.134653 1.023395 5.144927 -v 0.028700 0.085388 0.176496 -vn -2.134659 0.000001 5.245713 -v 0.028700 0.083827 0.176650 -vn -2.134651 -1.023394 5.144929 -v 0.028700 0.082266 0.176496 -vn -2.134629 -2.007458 4.846443 -v 0.028700 0.080765 0.176041 -vn -2.134645 -2.914369 4.361663 -v 0.028700 0.079382 0.175302 -vn -2.134655 -3.709287 3.709284 -v 0.028700 0.078170 0.174307 -vn -2.134629 -4.361688 2.914381 -v 0.028700 0.077175 0.173095 -vn -2.134653 -4.846407 2.007454 -v 0.028700 0.076436 0.171711 -vn -2.134649 -5.144939 1.023387 -v 0.028700 0.075981 0.170211 -vn -2.134659 -5.245714 0.000001 -v 0.028700 0.075827 0.168650 -vn -2.134649 -5.144939 -1.023389 -v 0.028700 0.075981 0.167089 -vn -2.134655 -4.846414 -2.007444 -v 0.028700 0.076436 0.165589 -vn -2.134658 -4.361646 -2.914360 -v 0.028700 0.077175 0.164205 -vn -2.134608 -3.709319 -3.709332 -v 0.028700 0.078170 0.162993 -vn -2.134643 -2.914371 -4.361665 -v 0.028700 0.079382 0.161998 -vn -2.134632 -2.007455 -4.846444 -v 0.028700 0.080765 0.161259 -vn -2.134656 -1.023393 -5.144928 -v 0.028700 0.082266 0.160804 -vn -2.134659 -0.000001 -5.245713 -v 0.028700 0.083827 0.160650 -vn -2.134654 1.023392 -5.144930 -v 0.028700 0.085388 0.160804 -vn -2.134632 2.007461 -4.846440 -v 0.028700 0.086888 0.161259 -vn -2.134661 2.914354 -4.361653 -v 0.028700 0.088271 0.161998 -vn -2.134609 3.709327 -3.709323 -v 0.028700 0.089484 0.162993 -vn -2.134660 4.361639 -2.914364 -v 0.028700 0.090479 0.164205 -vn -2.134654 4.846415 -2.007445 -v 0.028700 0.091218 0.165589 -vn -2.134647 5.144938 -1.023386 -v 0.028700 0.091673 0.167089 -vn 0.454441 -6.228199 -0.000005 -v 0.035532 -0.091827 0.168650 -vn 1.772128 -5.894605 0.580589 -v 0.035820 -0.091746 0.169430 -vn 0.453110 -6.198215 0.610489 -v 0.035532 -0.091788 0.169434 -vn 1.772157 -5.809324 1.155555 -v 0.035820 -0.091632 0.170202 -vn 0.454455 -6.108530 1.215045 -v 0.035532 -0.091673 0.170211 -vn 1.772183 -5.668077 1.719399 -v 0.035820 -0.091442 0.170960 -vn 0.453184 -5.960011 1.807938 -v 0.035532 -0.091482 0.170972 -vn 1.772189 -5.472280 2.266695 -v 0.035820 -0.091179 0.171695 -vn 0.454527 -5.754096 2.383418 -v 0.035532 -0.091218 0.171711 -vn 1.772226 -5.223726 2.792141 -v 0.035820 -0.090845 0.172401 -vn 0.453201 -5.492769 2.935954 -v 0.035532 -0.090882 0.172421 -vn 1.772213 -4.924888 3.290704 -v 0.035820 -0.090443 0.173071 -vn 0.454455 -5.178560 3.460204 -v 0.035532 -0.090479 0.173095 -vn 1.772198 -4.578633 3.757587 -v 0.035820 -0.089978 0.173698 -vn 0.453175 -4.814464 3.951118 -v 0.035532 -0.090011 0.173725 -vn 1.772187 -4.188300 4.188277 -v 0.035820 -0.089454 0.174277 -vn 0.454469 -4.404018 4.403986 -v 0.035532 -0.089484 0.174307 -vn 1.772184 -3.757580 4.578631 -v 0.035820 -0.088875 0.174801 -vn 0.453174 -3.951121 4.814458 -v 0.035532 -0.088902 0.174834 -vn 1.772187 -3.290713 4.924953 -v 0.035820 -0.088248 0.175267 -vn 0.454553 -3.460188 5.178549 -v 0.035532 -0.088271 0.175302 -vn 1.772247 -2.792153 5.223706 -v 0.035820 -0.087578 0.175668 -vn 0.453201 -2.935937 5.492779 -v 0.035532 -0.087598 0.175705 -vn 1.772179 -2.266712 5.472257 -v 0.035820 -0.086872 0.176002 -vn 0.454460 -2.383420 5.754109 -v 0.035532 -0.086888 0.176041 -vn 1.772073 -1.719396 5.668099 -v 0.035820 -0.086137 0.176265 -vn 0.453077 -1.807956 5.960029 -v 0.035532 -0.086149 0.176306 -vn 1.772151 -1.155516 5.809302 -v 0.035820 -0.085379 0.176455 -vn 0.454410 -1.215080 6.108531 -v 0.035532 -0.085388 0.176496 -vn 1.772279 -0.580577 5.894597 -v 0.035820 -0.084607 0.176569 -vn 0.453252 -0.610492 6.198184 -v 0.035532 -0.084611 0.176611 -vn 1.772204 0.000013 5.923108 -v 0.035820 -0.083827 0.176608 -vn 0.454459 0.000015 6.228200 -v 0.035532 -0.083827 0.176650 -vn 1.772283 0.580544 5.894601 -v 0.035820 -0.083047 0.176569 -vn 0.453246 0.610453 6.198190 -v 0.035532 -0.083043 0.176611 -vn 1.772169 1.155518 5.809302 -v 0.035820 -0.082274 0.176455 -vn 0.454388 1.215099 6.108531 -v 0.035532 -0.082266 0.176496 -vn 1.772057 1.719432 5.668093 -v 0.035820 -0.081517 0.176265 -vn 0.453085 1.807976 5.960022 -v 0.035532 -0.081505 0.176306 -vn 1.772170 2.266705 5.472258 -v 0.035820 -0.080782 0.176002 -vn 0.454475 2.383407 5.754110 -v 0.035532 -0.080765 0.176041 -vn 1.772225 2.792137 5.223723 -v 0.035820 -0.080076 0.175668 -vn 0.453213 2.935942 5.492774 -v 0.035532 -0.080056 0.175705 -vn 1.772190 3.290726 4.924944 -v 0.035820 -0.079406 0.175267 -vn 0.454549 3.460166 5.178564 -v 0.035532 -0.079382 0.175302 -vn 1.772206 3.757569 4.578631 -v 0.035820 -0.078779 0.174801 -vn 0.453164 3.951136 4.814448 -v 0.035532 -0.078752 0.174834 -vn 1.772187 4.188304 4.188273 -v 0.035820 -0.078200 0.174277 -vn 0.454470 4.404015 4.403989 -v 0.035532 -0.078170 0.174307 -vn 1.772201 4.578626 3.757595 -v 0.035820 -0.077675 0.173698 -vn 0.453171 4.814464 3.951119 -v 0.035532 -0.077643 0.173725 -vn 1.772170 4.924902 3.290724 -v 0.035820 -0.077210 0.173071 -vn 0.454449 5.178560 3.460207 -v 0.035532 -0.077175 0.173095 -vn 1.772191 5.223710 2.792134 -v 0.035820 -0.076809 0.172401 -vn 0.453148 5.492782 2.935949 -v 0.035532 -0.076771 0.172421 -vn 1.772187 5.472291 2.266675 -v 0.035820 -0.076475 0.171695 -vn 0.454524 5.754090 2.383432 -v 0.035532 -0.076436 0.171711 -vn 1.772200 5.668070 1.719405 -v 0.035820 -0.076212 0.170960 -vn 0.453174 5.960015 1.807932 -v 0.035532 -0.076171 0.170972 -vn 1.772168 5.809322 1.155555 -v 0.035820 -0.076022 0.170202 -vn 0.454454 6.108528 1.215070 -v 0.035532 -0.075981 0.170211 -vn 1.772205 5.894594 0.580584 -v 0.035820 -0.075907 0.169430 -vn 0.453176 6.198199 0.610480 -v 0.035532 -0.075865 0.169434 -vn 1.772199 5.923117 -0.000001 -v 0.035820 -0.075869 0.168650 -vn 0.454451 6.228202 -0.000002 -v 0.035532 -0.075827 0.168650 -vn 1.772213 5.894597 -0.580571 -v 0.035820 -0.075907 0.167870 -vn 0.453190 6.198195 -0.610483 -v 0.035532 -0.075865 0.167866 -vn 1.772168 5.809320 -1.155570 -v 0.035820 -0.076022 0.167098 -vn 0.454456 6.108526 -1.215083 -v 0.035532 -0.075981 0.167089 -vn 1.772183 5.668077 -1.719399 -v 0.035820 -0.076212 0.166340 -vn 0.453184 5.960011 -1.807938 -v 0.035532 -0.076171 0.166328 -vn 1.772191 5.472292 -2.266673 -v 0.035820 -0.076475 0.165605 -vn 0.454519 5.754101 -2.383409 -v 0.035532 -0.076436 0.165589 -vn 1.772144 5.223740 -2.792133 -v 0.035820 -0.076809 0.164899 -vn 0.453149 5.492784 -2.935953 -v 0.035532 -0.076771 0.164879 -vn 1.772167 4.924931 -3.290737 -v 0.035820 -0.077210 0.164229 -vn 0.454530 5.178546 -3.460189 -v 0.035532 -0.077175 0.164205 -vn 1.772137 4.578644 -3.757628 -v 0.035820 -0.077675 0.163602 -vn 0.453175 4.814444 -3.951147 -v 0.035532 -0.077643 0.163575 -vn 1.772187 4.188300 -4.188277 -v 0.035820 -0.078200 0.163023 -vn 0.454469 4.404018 -4.403986 -v 0.035532 -0.078170 0.162993 -vn 1.772199 3.757602 -4.578613 -v 0.035820 -0.078779 0.162499 -vn 0.453160 3.951137 -4.814448 -v 0.035532 -0.078752 0.162466 -vn 1.772144 3.290698 -4.924917 -v 0.035820 -0.079406 0.162033 -vn 0.454438 3.460185 -5.178575 -v 0.035532 -0.079382 0.161998 -vn 1.772134 2.792140 -5.223778 -v 0.035820 -0.080076 0.161632 -vn 0.453201 2.935937 -5.492779 -v 0.035532 -0.080056 0.161595 -vn 1.772179 2.266712 -5.472257 -v 0.035820 -0.080782 0.161298 -vn 0.454477 2.383452 -5.754098 -v 0.035532 -0.080765 0.161259 -vn 1.772208 1.719414 -5.668077 -v 0.035820 -0.081517 0.161035 -vn 0.453208 1.807964 -5.959991 -v 0.035532 -0.081505 0.160994 -vn 1.772153 1.155517 -5.809309 -v 0.035820 -0.082274 0.160845 -vn 0.454411 1.215025 -6.108547 -v 0.035532 -0.082266 0.160804 -vn 1.772160 0.580561 -5.894658 -v 0.035820 -0.083047 0.160731 -vn 0.453252 0.610492 -6.198184 -v 0.035532 -0.083043 0.160689 -vn 1.772190 0.000007 -5.923116 -v 0.035820 -0.083827 0.160692 -vn 0.454459 -0.000015 -6.228200 -v 0.035532 -0.083827 0.160650 -vn 1.772175 -0.580571 -5.894652 -v 0.035820 -0.084607 0.160731 -vn 0.453246 -0.610453 -6.198190 -v 0.035532 -0.084611 0.160689 -vn 1.772169 -1.155518 -5.809302 -v 0.035820 -0.085379 0.160845 -vn 0.454405 -1.215065 -6.108541 -v 0.035532 -0.085388 0.160804 -vn 1.772191 -1.719407 -5.668083 -v 0.035820 -0.086137 0.161035 -vn 0.453216 -1.807942 -5.959996 -v 0.035532 -0.086149 0.160994 -vn 1.772173 -2.266710 -5.472261 -v 0.035820 -0.086872 0.161298 -vn 0.454476 -2.383461 -5.754094 -v 0.035532 -0.086888 0.161259 -vn 1.772140 -2.792150 -5.223772 -v 0.035820 -0.087578 0.161632 -vn 0.453198 -2.935926 -5.492785 -v 0.035532 -0.087598 0.161595 -vn 1.772163 -3.290697 -4.924909 -v 0.035820 -0.088248 0.162033 -vn 0.454433 -3.460195 -5.178569 -v 0.035532 -0.088271 0.161998 -vn 1.772194 -3.757595 -4.578619 -v 0.035820 -0.088875 0.162499 -vn 0.453164 -3.951136 -4.814448 -v 0.035532 -0.088902 0.162466 -vn 1.772177 -4.188298 -4.188286 -v 0.035820 -0.089454 0.163023 -vn 0.454470 -4.404015 -4.403989 -v 0.035532 -0.089484 0.162993 -vn 1.772126 -4.578662 -3.757610 -v 0.035820 -0.089978 0.163602 -vn 0.453182 -4.814450 -3.951136 -v 0.035532 -0.090011 0.163575 -vn 1.772216 -4.924907 -3.290724 -v 0.035820 -0.090443 0.164229 -vn 0.454534 -5.178536 -3.460203 -v 0.035532 -0.090479 0.164205 -vn 1.772161 -5.223764 -2.792140 -v 0.035820 -0.090845 0.164899 -vn 0.453209 -5.492785 -2.935927 -v 0.035532 -0.090882 0.164879 -vn 1.772193 -5.472281 -2.266688 -v 0.035820 -0.091179 0.165605 -vn 0.454524 -5.754090 -2.383432 -v 0.035532 -0.091218 0.165589 -vn 1.772200 -5.668070 -1.719405 -v 0.035820 -0.091442 0.166340 -vn 0.453174 -5.960015 -1.807932 -v 0.035532 -0.091482 0.166328 -vn 1.772168 -5.809322 -1.155555 -v 0.035820 -0.091632 0.167098 -vn 0.454448 -6.108530 -1.215058 -v 0.035532 -0.091673 0.167089 -vn 1.772148 -5.894602 -0.580571 -v 0.035820 -0.091746 0.167870 -vn 0.453122 -6.198213 -0.610483 -v 0.035532 -0.091788 0.167866 -vn 1.772191 -5.923117 -0.000009 -v 0.035820 -0.091784 0.168650 -vn 3.399002 -5.145543 0.506790 -v 0.036083 -0.091623 0.169418 -vn 3.398978 -5.071100 1.008707 -v 0.036083 -0.091511 0.170178 -vn 3.398954 -4.947849 1.500901 -v 0.036083 -0.091324 0.170924 -vn 3.398897 -4.776906 1.978677 -v 0.036083 -0.091065 0.171648 -vn 3.398945 -4.559955 2.437359 -v 0.036083 -0.090736 0.172343 -vn 3.398981 -4.299095 2.872553 -v 0.036083 -0.090341 0.173002 -vn 3.398963 -3.996845 3.280106 -v 0.036083 -0.089883 0.173620 -vn 3.398950 -3.656085 3.656074 -v 0.036083 -0.089366 0.174190 -vn 3.399023 -3.280097 3.996781 -v 0.036083 -0.088797 0.174706 -vn 3.398928 -2.872519 4.299086 -v 0.036083 -0.088179 0.175164 -vn 3.398975 -2.437346 4.559950 -v 0.036083 -0.087520 0.175559 -vn 3.398980 -1.978667 4.776859 -v 0.036083 -0.086825 0.175888 -vn 3.398994 -1.500901 4.947776 -v 0.036083 -0.086101 0.176147 -vn 3.399025 -1.008674 5.071088 -v 0.036083 -0.085355 0.176334 -vn 3.398973 -0.506781 5.145581 -v 0.036083 -0.084595 0.176447 -vn 3.398990 -0.000008 5.170450 -v 0.036083 -0.083827 0.176484 -vn 3.398966 0.506807 5.145580 -v 0.036083 -0.083059 0.176447 -vn 3.399040 1.008657 5.071080 -v 0.036083 -0.082298 0.176334 -vn 3.399004 1.500896 4.947773 -v 0.036083 -0.081553 0.176147 -vn 3.398964 1.978678 4.776867 -v 0.036083 -0.080829 0.175888 -vn 3.398989 2.437333 4.559949 -v 0.036083 -0.080134 0.175559 -vn 3.398913 2.872545 4.299086 -v 0.036083 -0.079474 0.175164 -vn 3.399001 3.280085 3.996810 -v 0.036083 -0.078857 0.174706 -vn 3.398942 3.656102 3.656067 -v 0.036083 -0.078287 0.174190 -vn 3.398961 3.996840 3.280116 -v 0.036083 -0.077771 0.173620 -vn 3.398959 4.299083 2.872548 -v 0.036083 -0.077313 0.173002 -vn 3.399008 4.559929 2.437349 -v 0.036083 -0.076918 0.172343 -vn 3.398902 4.776915 1.978651 -v 0.036083 -0.076589 0.171648 -vn 3.398945 4.947850 1.500911 -v 0.036083 -0.076330 0.170924 -vn 3.398944 5.071130 1.008710 -v 0.036083 -0.076143 0.170178 -vn 3.398994 5.145548 0.506794 -v 0.036083 -0.076030 0.169418 -vn 3.399001 5.170448 -0.000001 -v 0.036083 -0.075993 0.168650 -vn 3.398996 5.145550 -0.506780 -v 0.036083 -0.076030 0.167882 -vn 3.398926 5.071145 -1.008725 -v 0.036083 -0.076143 0.167122 -vn 3.398954 4.947849 -1.500901 -v 0.036083 -0.076330 0.166376 -vn 3.398900 4.776916 -1.978658 -v 0.036083 -0.076589 0.165652 -vn 3.398950 4.559958 -2.437336 -v 0.036083 -0.076918 0.164957 -vn 3.398937 4.299066 -2.872551 -v 0.036083 -0.077313 0.164298 -vn 3.398917 3.996815 -3.280133 -v 0.036083 -0.077771 0.163680 -vn 3.398943 3.656077 -3.656092 -v 0.036083 -0.078287 0.163110 -vn 3.399013 3.280118 -3.996777 -v 0.036083 -0.078857 0.162594 -vn 3.398958 2.872560 -4.299093 -v 0.036083 -0.079474 0.162136 -vn 3.398938 2.437307 -4.559939 -v 0.036083 -0.080134 0.161741 -vn 3.398972 1.978647 -4.776877 -v 0.036083 -0.080829 0.161412 -vn 3.398994 1.500901 -4.947776 -v 0.036083 -0.081553 0.161153 -vn 3.399041 1.008710 -5.071076 -v 0.036083 -0.082298 0.160966 -vn 3.398911 0.506775 -5.145558 -v 0.036083 -0.083059 0.160853 -vn 3.398996 0.000012 -5.170455 -v 0.036083 -0.083827 0.160816 -vn 3.398917 -0.506803 -5.145552 -v 0.036083 -0.084595 0.160853 -vn 3.399031 -1.008685 -5.071084 -v 0.036083 -0.085355 0.160966 -vn 3.399004 -1.500896 -4.947773 -v 0.036083 -0.086101 0.161153 -vn 3.398978 -1.978649 -4.776875 -v 0.036083 -0.086825 0.161412 -vn 3.398935 -2.437315 -4.559937 -v 0.036083 -0.087520 0.161741 -vn 3.398962 -2.872565 -4.299078 -v 0.036083 -0.088179 0.162136 -vn 3.399013 -3.280095 -3.996795 -v 0.036083 -0.088797 0.162594 -vn 3.398953 -3.656083 -3.656080 -v 0.036083 -0.089366 0.163110 -vn 3.398929 -3.996818 -3.280113 -v 0.036083 -0.089883 0.163680 -vn 3.398951 -4.299076 -2.872567 -v 0.036083 -0.090341 0.164298 -vn 3.398893 -4.559977 -2.437357 -v 0.036083 -0.090736 0.164957 -vn 3.398891 -4.776922 -1.978652 -v 0.036083 -0.091065 0.165652 -vn 3.398947 -4.947849 -1.500906 -v 0.036083 -0.091324 0.166376 -vn 3.398966 -5.071109 -1.008708 -v 0.036083 -0.091511 0.167122 -vn 3.398994 -5.145548 -0.506794 -v 0.036083 -0.091623 0.167882 -vn 3.399001 -5.170448 0.000001 -v 0.036083 -0.091661 0.168650 -vn 4.492383 -4.328834 0.422196 -v 0.036300 -0.091430 0.169399 -vn 4.488469 -4.269750 0.853098 -v 0.036300 -0.091320 0.170141 -vn 4.491243 -4.163529 1.262206 -v 0.036300 -0.091138 0.170868 -vn 4.491222 -4.019258 1.665525 -v 0.036300 -0.090885 0.171574 -vn 4.501243 -3.821368 2.053293 -v 0.036300 -0.090565 0.172252 -vn 4.495925 -3.617564 2.406042 -v 0.036300 -0.090179 0.172895 -vn 4.491970 -3.364123 2.757584 -v 0.036300 -0.089733 0.173497 -vn 4.488489 -3.076278 3.081328 -v 0.036300 -0.089229 0.174052 -vn 4.490716 -2.762016 3.362361 -v 0.036300 -0.088674 0.174556 -vn 4.490403 -2.416251 3.619315 -v 0.036300 -0.088071 0.175003 -vn 4.498237 -2.040575 3.832463 -v 0.036300 -0.087428 0.175388 -vn 4.493655 -1.671323 4.013448 -v 0.036300 -0.086751 0.175709 -vn 4.491887 -1.263586 4.162492 -v 0.036300 -0.086045 0.175961 -vn 4.488862 -0.846312 4.270586 -v 0.036300 -0.085317 0.176143 -vn 4.490533 -0.429523 4.330333 -v 0.036300 -0.084576 0.176253 -vn 4.489582 0.002624 4.352742 -v 0.036300 -0.083827 0.176290 -vn 4.495742 0.430578 4.323601 -v 0.036300 -0.083078 0.176253 -vn 4.491724 0.841710 4.267783 -v 0.036300 -0.082336 0.176143 -vn 4.491886 1.263567 4.162498 -v 0.036300 -0.081609 0.175961 -vn 4.489500 1.667931 4.020597 -v 0.036300 -0.080903 0.175709 -vn 4.490784 2.047926 3.839243 -v 0.036300 -0.080225 0.175388 -vn 4.489048 2.421345 3.617931 -v 0.036300 -0.079582 0.175003 -vn 4.493807 2.760015 3.358951 -v 0.036300 -0.078980 0.174556 -vn 4.490148 3.073215 3.081419 -v 0.036300 -0.078424 0.174052 -vn 4.491971 3.364126 2.757579 -v 0.036300 -0.077921 0.173497 -vn 4.490425 3.619012 2.416573 -v 0.036300 -0.077474 0.172895 -vn 4.491404 3.834920 2.054436 -v 0.036300 -0.077089 0.172252 -vn 4.488616 4.023908 1.662825 -v 0.036300 -0.076768 0.171574 -vn 4.492260 4.162319 1.261771 -v 0.036300 -0.076516 0.170868 -vn 4.492222 4.265705 0.849194 -v 0.036300 -0.076333 0.170141 -vn 4.504796 4.313901 0.412735 -v 0.036300 -0.076223 0.169399 -vn 4.498668 4.341134 0.010154 -v 0.036300 -0.076187 0.168650 -vn 4.492387 4.328834 -0.422170 -v 0.036300 -0.076223 0.167901 -vn 4.488416 4.269783 -0.853127 -v 0.036300 -0.076333 0.167159 -vn 4.491237 4.163534 -1.262219 -v 0.036300 -0.076516 0.166432 -vn 4.491219 4.019274 -1.665511 -v 0.036300 -0.076768 0.165726 -vn 4.501244 3.821357 -2.053299 -v 0.036300 -0.077089 0.165048 -vn 4.496010 3.617505 -2.406001 -v 0.036300 -0.077474 0.164405 -vn 4.492033 3.364079 -2.757554 -v 0.036300 -0.077921 0.163803 -vn 4.488496 3.076265 -3.081332 -v 0.036300 -0.078424 0.163248 -vn 4.490714 2.762062 -3.362334 -v 0.036300 -0.078980 0.162744 -vn 4.490311 2.416261 -3.619389 -v 0.036300 -0.079582 0.162297 -vn 4.498306 2.040545 -3.832414 -v 0.036300 -0.080225 0.161912 -vn 4.493658 1.671314 -4.013451 -v 0.036300 -0.080903 0.161591 -vn 4.491880 1.263583 -4.162502 -v 0.036300 -0.081609 0.161339 -vn 4.488862 0.846316 -4.270586 -v 0.036300 -0.082336 0.161157 -vn 4.490606 0.429544 -4.330272 -v 0.036300 -0.083078 0.161047 -vn 4.489587 -0.002651 -4.352740 -v 0.036300 -0.083827 0.161010 -vn 4.495814 -0.430545 -4.323546 -v 0.036300 -0.084576 0.161047 -vn 4.491729 -0.841730 -4.267776 -v 0.036300 -0.085317 0.161157 -vn 4.491880 -1.263564 -4.162508 -v 0.036300 -0.086045 0.161339 -vn 4.489493 -1.667940 -4.020602 -v 0.036300 -0.086751 0.161591 -vn 4.490860 -2.047862 -3.839207 -v 0.036300 -0.087428 0.161912 -vn 4.489014 -2.421375 -3.617939 -v 0.036300 -0.088071 0.162297 -vn 4.493798 -2.760026 -3.358957 -v 0.036300 -0.088674 0.162744 -vn 4.490144 -3.073221 -3.081419 -v 0.036300 -0.089229 0.163248 -vn 4.492023 -3.364086 -2.757558 -v 0.036300 -0.089733 0.163803 -vn 4.490444 -3.618994 -2.416574 -v 0.036300 -0.090179 0.164405 -vn 4.491405 -3.834914 -2.054434 -v 0.036300 -0.090565 0.165048 -vn 4.488616 -4.023916 -1.662813 -v 0.036300 -0.090885 0.165726 -vn 4.492262 -4.162319 -1.261755 -v 0.036300 -0.091138 0.166432 -vn 4.492249 -4.265682 -0.849208 -v 0.036300 -0.091320 0.167159 -vn 4.504797 -4.313899 -0.412741 -v 0.036300 -0.091430 0.167901 -vn 4.498668 -4.341134 -0.010154 -v 0.036300 -0.091467 0.168650 -vn 4.393105 -1.113762 -4.317736 -v 0.037115 -0.085309 0.162155 -vn 4.392216 -1.502343 -4.198739 -v 0.037115 -0.086261 0.162448 -vn 4.544329 -1.809142 -3.928107 -v 0.037115 -0.086376 0.162495 -vn 4.397491 -2.161560 -3.897331 -v 0.037115 -0.087158 0.162880 -vn 4.690277 -2.346215 -3.457664 -v 0.037115 -0.087528 0.163110 -vn 4.386369 -2.807760 -3.475668 -v 0.037115 -0.087981 0.163441 -vn 4.392215 1.502346 -4.198738 -v 0.037115 -0.081393 0.162448 -vn 4.393100 1.113777 -4.317734 -v 0.037115 -0.082344 0.162155 -vn 4.625018 0.676418 -4.191618 -v 0.037115 -0.082527 0.162115 -vn 4.399084 0.395553 -4.437857 -v 0.037115 -0.083329 0.162006 -vn 4.693562 -0.004196 -4.175038 -v 0.037115 -0.083827 0.161987 -vn 4.384748 -0.380785 -4.453603 -v 0.037115 -0.084325 0.162006 -vn 4.576042 -0.704750 -4.237375 -v 0.037115 -0.085127 0.162115 -vn 4.390987 3.600451 -2.632260 -v 0.037115 -0.078322 0.164897 -vn 4.393476 3.345807 -2.947849 -v 0.037115 -0.078943 0.164118 -vn 4.698015 2.849483 -3.043451 -v 0.037115 -0.079116 0.163939 -vn 4.400734 2.815243 -3.451725 -v 0.037115 -0.079673 0.163441 -vn 4.687806 2.340813 -3.464707 -v 0.037115 -0.080125 0.163110 -vn 4.383214 2.178795 -3.904845 -v 0.037115 -0.080496 0.162880 -vn 4.517405 1.810918 -3.956466 -v 0.037115 -0.081277 0.162495 -vn 4.393698 3.345658 2.947736 -v 0.037115 -0.078943 0.173182 -vn 4.390992 3.600445 2.632264 -v 0.037115 -0.078322 0.172403 -vn 4.460041 3.752378 2.299999 -v 0.037115 -0.078287 0.172352 -vn 4.395757 3.976248 2.015533 -v 0.037115 -0.077824 0.171541 -vn 4.677868 3.893605 1.552735 -v 0.037115 -0.077671 0.171200 -vn 4.387497 4.271070 1.307598 -v 0.037115 -0.077460 0.170614 -vn 4.648599 4.127210 0.895249 -v 0.037115 -0.077292 0.169950 -vn 4.379641 4.439685 0.565300 -v 0.037115 -0.077239 0.169643 -vn 4.402056 4.454805 0.009529 -v 0.037115 -0.077164 0.168650 -vn 4.394113 4.423688 -0.560775 -v 0.037115 -0.077239 0.167657 -vn 4.655904 4.117309 -0.901719 -v 0.037115 -0.077292 0.167350 -vn 4.388742 4.269733 -1.307143 -v 0.037115 -0.077460 0.166686 -vn 4.673049 3.895561 -1.562579 -v 0.037115 -0.077671 0.166100 -vn 4.381430 3.993273 -2.016486 -v 0.037115 -0.077824 0.165759 -vn 4.447612 3.763338 -2.306370 -v 0.037115 -0.078287 0.164948 -vn 4.393107 1.113805 4.317722 -v 0.037115 -0.082344 0.175145 -vn 4.391882 1.502221 4.199063 -v 0.037115 -0.081393 0.174852 -vn 4.544291 1.809010 3.928213 -v 0.037115 -0.081277 0.174805 -vn 4.397486 2.161566 3.897333 -v 0.037115 -0.080496 0.174420 -vn 4.690239 2.346242 3.457695 -v 0.037115 -0.080125 0.174190 -vn 4.386001 2.807970 3.475886 -v 0.037115 -0.079673 0.173859 -vn 4.621590 2.927260 3.081614 -v 0.037115 -0.079116 0.173361 -vn 4.391872 -1.502242 4.199065 -v 0.037115 -0.086261 0.174852 -vn 4.393100 -1.113772 4.317738 -v 0.037115 -0.085309 0.175145 -vn 4.625055 -0.676356 4.191587 -v 0.037115 -0.085127 0.175185 -vn 4.398755 -0.395621 4.438121 -v 0.037115 -0.084325 0.175294 -vn 4.693544 0.004185 4.175056 -v 0.037115 -0.083827 0.175313 -vn 4.384414 0.380844 4.453870 -v 0.037115 -0.083329 0.175294 -vn 4.576049 0.704740 4.237370 -v 0.037115 -0.082527 0.175185 -vn 4.390987 -3.600451 2.632260 -v 0.037115 -0.089332 0.172403 -vn 4.393695 -3.345656 2.947743 -v 0.037115 -0.088711 0.173182 -vn 4.698240 -2.849290 3.043295 -v 0.037115 -0.088538 0.173361 -vn 4.400587 -2.815351 3.451793 -v 0.037115 -0.087981 0.173859 -vn 4.687813 -2.340842 3.464679 -v 0.037115 -0.087528 0.174190 -vn 4.383214 -2.178795 3.904845 -v 0.037115 -0.087158 0.174420 -vn 4.517366 -1.810786 3.956572 -v 0.037115 -0.086376 0.174805 -vn 4.621477 -2.927328 -3.081705 -v 0.037115 -0.088538 0.163939 -vn 4.393473 -3.345805 -2.947853 -v 0.037115 -0.088711 0.164118 -vn 4.390985 -3.600455 -2.632258 -v 0.037115 -0.089332 0.164897 -vn 4.460044 -3.752373 -2.300000 -v 0.037115 -0.089366 0.164948 -vn 4.395756 -3.976234 -2.015559 -v 0.037115 -0.089830 0.165759 -vn 4.677937 -3.893533 -1.552712 -v 0.037115 -0.089982 0.166100 -vn 4.387333 -4.271205 -1.307614 -v 0.037115 -0.090193 0.166686 -vn 4.648555 -4.127252 -0.895279 -v 0.037115 -0.090361 0.167350 -vn 4.379598 -4.439722 -0.565291 -v 0.037115 -0.090415 0.167657 -vn 4.402056 -4.454806 -0.009527 -v 0.037115 -0.090489 0.168650 -vn 4.394149 -4.423658 0.560791 -v 0.037115 -0.090415 0.169643 -vn 4.655933 -4.117281 0.901710 -v 0.037115 -0.090361 0.169950 -vn 4.388584 -4.269851 1.307200 -v 0.037115 -0.090193 0.170614 -vn 4.672969 -3.895648 1.562597 -v 0.037115 -0.089982 0.171200 -vn 4.381425 -3.993299 2.016452 -v 0.037115 -0.089830 0.171541 -vn 4.447613 -3.763339 2.306370 -v 0.037115 -0.089366 0.172352 -vn 2.858396 -5.246325 1.612766 -v 0.037178 -0.090145 0.170599 -vn 2.857623 -5.435208 0.763210 -v 0.037178 -0.090365 0.169635 -vn 0.391162 -6.114683 0.921650 -v 0.037256 -0.090344 0.169632 -vn 2.862526 -1.953954 5.124606 -v 0.037178 -0.086242 0.174805 -vn 2.858347 -2.712659 4.771192 -v 0.037178 -0.087133 0.174376 -vn 0.391197 -3.091872 5.355275 -v 0.037256 -0.087122 0.174358 -vn 2.852242 2.704772 4.780432 -v 0.037178 -0.080521 0.174376 -vn 2.861861 1.957519 5.123555 -v 0.037178 -0.081411 0.174805 -vn 0.391123 2.259155 5.756186 -v 0.037256 -0.081419 0.174785 -vn 2.857624 5.435207 0.763216 -v 0.037178 -0.077288 0.169635 -vn 2.858560 5.246206 1.612738 -v 0.037178 -0.077508 0.170599 -vn 0.391255 5.909040 1.822706 -v 0.037256 -0.077529 0.170593 -vn 2.859853 4.058676 -3.692027 -v 0.037178 -0.078980 0.164153 -vn 2.857083 4.512973 -3.122804 -v 0.037178 -0.078364 0.164925 -vn 0.391136 5.109205 -3.483378 -v 0.037256 -0.078381 0.164937 -vn 2.858548 -0.436286 -5.471052 -v 0.037178 -0.084321 0.162056 -vn 2.849389 0.453765 -5.475893 -v 0.037178 -0.083333 0.162056 -vn 0.391118 0.462114 -6.166433 -v 0.037256 -0.083334 0.162077 -vn 2.856218 -4.515177 -3.120481 -v 0.037178 -0.089290 0.164925 -vn 2.860209 -4.060965 -3.689427 -v 0.037178 -0.088674 0.164153 -vn 0.391448 -4.532976 -4.205944 -v 0.037256 -0.088658 0.164167 -vn 2.858020 -4.924762 2.422878 -v 0.037178 -0.089784 0.171519 -vn 2.857093 -4.512963 3.122814 -v 0.037178 -0.089290 0.172375 -vn 2.859739 -4.058637 3.691966 -v 0.037178 -0.088674 0.173147 -vn 2.858423 3.434422 4.281279 -v 0.037178 -0.079704 0.173820 -vn 2.860087 4.060928 3.689371 -v 0.037178 -0.078980 0.173147 -vn 2.856212 4.515173 3.120495 -v 0.037178 -0.078364 0.172375 -vn 2.858347 2.712658 -4.771193 -v 0.037178 -0.080521 0.162924 -vn 2.861650 1.273202 -5.335218 -v 0.037178 -0.082355 0.162204 -vn 2.862110 -1.276706 -5.334245 -v 0.037178 -0.085298 0.162204 -vn 2.852245 -2.704777 -4.780427 -v 0.037178 -0.087133 0.162924 -vn 2.858401 -5.246325 -1.612766 -v 0.037178 -0.090145 0.166701 -vn 2.857658 -5.435210 -0.763256 -v 0.037178 -0.090365 0.167664 -vn 2.858624 -3.434248 -4.281125 -v 0.037178 -0.087949 0.163480 -vn 2.862146 -1.957534 -5.123318 -v 0.037178 -0.086242 0.162495 -vn 2.862802 1.953954 -5.124381 -v 0.037178 -0.081411 0.162495 -vn 2.858030 4.924748 -2.422891 -v 0.037178 -0.077869 0.165781 -vn 2.858564 5.246206 -1.612723 -v 0.037178 -0.077508 0.166701 -vn 2.862105 1.276731 5.334242 -v 0.037178 -0.082355 0.175096 -vn 2.858212 0.436318 5.471305 -v 0.037178 -0.083333 0.175244 -vn 2.861644 -1.273192 5.335223 -v 0.037178 -0.085298 0.175096 -vn 0.391309 -5.571356 -2.683039 -v 0.037256 -0.089765 0.165790 -vn 0.391258 -5.909037 -1.822711 -v 0.037256 -0.090125 0.166707 -vn -2.154979 -3.616959 -4.535538 -v 0.037336 -0.087943 0.163488 -vn 0.391162 -3.855539 -4.834673 -v 0.037256 -0.087936 0.163497 -vn 0.390992 -1.376018 -6.028718 -v 0.037256 -0.085293 0.162224 -vn 0.391123 -2.259155 -5.756186 -v 0.037256 -0.086235 0.162515 -vn -2.155150 1.290878 -5.655699 -v 0.037336 -0.082358 0.162213 -vn 0.390979 1.376029 -6.028716 -v 0.037256 -0.082360 0.162224 -vn 0.391147 3.855502 -4.834636 -v 0.037256 -0.079717 0.163497 -vn 0.391192 3.091866 -5.355278 -v 0.037256 -0.080531 0.162942 -vn -2.154935 5.226706 -2.517045 -v 0.037336 -0.077878 0.165785 -vn 0.391318 5.571353 -2.683037 -v 0.037256 -0.077889 0.165790 -vn 0.391205 6.183732 -0.000000 -v 0.037256 -0.077236 0.168650 -vn 0.391157 6.114665 -0.921596 -v 0.037256 -0.077309 0.167668 -vn 2.857659 5.435212 -0.763255 -v 0.037178 -0.077288 0.167664 -vn -2.154925 5.226711 2.517036 -v 0.037336 -0.077878 0.171515 -vn 0.391302 5.571360 2.683030 -v 0.037256 -0.077889 0.171510 -vn 2.854958 4.924087 2.428948 -v 0.037178 -0.077869 0.171519 -vn 0.391144 3.855504 4.834634 -v 0.037256 -0.079717 0.173803 -vn 0.391077 4.533018 4.206018 -v 0.037256 -0.078995 0.173133 -vn -2.155138 1.290920 5.655700 -v 0.037336 -0.082358 0.175087 -vn 0.390992 1.376018 6.028718 -v 0.037256 -0.082360 0.175076 -vn 0.390979 -1.376029 6.028716 -v 0.037256 -0.085293 0.175076 -vn 0.391118 -0.462114 6.166433 -v 0.037256 -0.084319 0.175223 -vn 2.849039 -0.453822 5.476152 -v 0.037178 -0.084321 0.175244 -vn -2.154977 -3.616949 4.535544 -v 0.037336 -0.087943 0.173812 -vn 0.391152 -3.855551 4.834666 -v 0.037256 -0.087936 0.173803 -vn 2.846195 -3.457182 4.273586 -v 0.037178 -0.087949 0.173820 -vn 0.391318 -5.571353 2.683037 -v 0.037256 -0.089765 0.171510 -vn 0.391358 -5.109216 3.483404 -v 0.037256 -0.089272 0.172363 -vn -2.154978 -5.801223 0.000001 -v 0.037336 -0.090429 0.168650 -vn 0.391202 -6.183732 0.000003 -v 0.037256 -0.090418 0.168650 -vn 2.825422 -5.511123 0.000008 -v 0.037178 -0.090439 0.168650 -vn -2.152486 -5.524865 -1.769864 -v 0.037336 -0.090136 0.166704 -vn -2.109367 -5.247580 -2.527086 -v 0.037336 -0.089775 0.165785 -vn -2.152065 -4.826257 -3.219370 -v 0.037336 -0.089282 0.164931 -vn -2.152672 -2.060970 -5.423079 -v 0.037336 -0.086239 0.162504 -vn -2.109573 -1.296035 -5.678294 -v 0.037336 -0.085296 0.162213 -vn -2.151763 -0.492197 -5.780773 -v 0.037336 -0.084320 0.162066 -vn -2.152604 2.954854 -4.992518 -v 0.037336 -0.080526 0.162932 -vn -2.109444 3.631446 -4.553678 -v 0.037336 -0.079710 0.163488 -vn -2.152138 4.212541 -3.988894 -v 0.037336 -0.078987 0.164159 -vn -2.152497 5.745718 -0.802580 -v 0.037336 -0.077298 0.167666 -vn -2.109404 5.824389 0.000001 -v 0.037336 -0.077225 0.168650 -vn -2.151935 5.745224 0.806463 -v 0.037336 -0.077298 0.169634 -vn -2.152671 4.209773 3.991720 -v 0.037336 -0.078987 0.173141 -vn -2.109434 3.631447 4.553682 -v 0.037336 -0.079710 0.173812 -vn -2.151742 2.951638 4.994708 -v 0.037336 -0.080526 0.174368 -vn -2.152306 -0.496115 5.780369 -v 0.037336 -0.084320 0.175234 -vn -2.109571 -1.296051 5.678289 -v 0.037336 -0.085296 0.175087 -vn -2.152134 -2.064702 5.421731 -v 0.037336 -0.086239 0.174796 -vn -2.152599 -4.828402 3.216042 -v 0.037336 -0.089282 0.172369 -vn -2.109371 -5.247576 2.527095 -v 0.037336 -0.089775 0.171515 -vn -2.151941 -5.526144 1.766100 -v 0.037336 -0.090136 0.170596 -vn -2.154644 -5.731083 -0.899122 -v 0.037336 -0.090355 0.167666 -vn -3.795886 -4.911958 -0.814958 -v 0.037405 -0.090397 0.167660 -vn -4.161550 -4.691158 -0.372237 -v 0.037405 -0.090444 0.168054 -vn 0.391167 -6.114663 -0.921601 -v 0.037256 -0.090344 0.167668 -vn -3.794177 -4.980650 -0.000001 -v 0.037405 -0.090471 0.168650 -vn -4.039442 -4.669152 -1.139098 -v 0.037405 -0.090232 0.166882 -vn -4.162059 -3.216994 -3.433975 -v 0.037405 -0.088418 0.163847 -vn -3.803654 -3.709269 -3.314227 -v 0.037405 -0.088697 0.164131 -vn -2.143346 -4.293633 -3.909553 -v 0.037336 -0.088667 0.164159 -vn 0.391360 -5.109223 -3.483393 -v 0.037256 -0.089272 0.164937 -vn 2.854969 -4.924072 -2.428961 -v 0.037178 -0.089784 0.165781 -vn -4.100488 -3.743432 -2.935050 -v 0.037405 -0.089202 0.164745 -vn -3.797425 -4.192469 -2.683395 -v 0.037405 -0.089317 0.164907 -vn -3.811913 -4.477031 -2.156444 -v 0.037405 -0.089813 0.165767 -vn -3.798117 -4.711445 -1.604189 -v 0.037405 -0.090176 0.166692 -vn -3.795347 -3.103828 -3.893988 -v 0.037405 -0.087969 0.163455 -vn -2.154777 -2.870294 -5.041218 -v 0.037336 -0.087128 0.162932 -vn -3.796906 -2.425984 -4.347144 -v 0.037405 -0.087149 0.162896 -vn -4.161543 -2.633795 -3.899839 -v 0.037405 -0.087487 0.163105 -vn 0.391173 -3.091876 -5.355274 -v 0.037256 -0.087122 0.162942 -vn -4.040410 -2.019272 -4.360325 -v 0.037405 -0.086438 0.162540 -vn -4.162595 0.678343 -4.655800 -v 0.037405 -0.082935 0.162066 -vn -3.805211 0.280168 -4.964808 -v 0.037405 -0.083330 0.162024 -vn -2.142964 0.379534 -5.794713 -v 0.037336 -0.083333 0.162066 -vn 0.391114 -0.462119 -6.166432 -v 0.037256 -0.084319 0.162077 -vn -4.102112 -0.041049 -4.755200 -v 0.037405 -0.084125 0.162012 -vn -3.796243 -0.517125 -4.951715 -v 0.037405 -0.084323 0.162024 -vn -3.810671 -1.104895 -4.846037 -v 0.037405 -0.085305 0.162172 -vn -3.797922 -1.683230 -4.683892 -v 0.037405 -0.086254 0.162465 -vn -3.795555 1.109747 -4.854228 -v 0.037405 -0.082348 0.162172 -vn -2.154843 2.151867 -5.387302 -v 0.037336 -0.081415 0.162504 -vn -3.785179 1.884990 -4.618752 -v 0.037405 -0.081399 0.162465 -vn -4.153900 1.416472 -4.494784 -v 0.037405 -0.081774 0.162331 -vn 0.391121 2.259152 -5.756190 -v 0.037256 -0.081419 0.162515 -vn -4.034781 2.152285 -4.301884 -v 0.037405 -0.080678 0.162799 -vn -4.162528 4.063069 -2.372473 -v 0.037405 -0.078123 0.165242 -vn -3.806639 4.056114 -2.874665 -v 0.037405 -0.078337 0.164907 -vn -2.143310 4.767031 -3.316091 -v 0.037336 -0.078372 0.164931 -vn 0.391429 4.532965 -4.205956 -v 0.037256 -0.078995 0.164167 -vn 2.846521 3.457064 -4.273460 -v 0.037178 -0.079704 0.163480 -vn -4.103660 3.690333 -2.996974 -v 0.037405 -0.078823 0.164278 -vn -3.795475 3.548519 -3.493231 -v 0.037405 -0.078956 0.164131 -vn -3.804033 3.100832 -3.891854 -v 0.037405 -0.079684 0.163455 -vn -3.791060 2.617349 -4.240638 -v 0.037405 -0.080505 0.162896 -vn -3.796542 4.485804 -2.159603 -v 0.037405 -0.077840 0.165767 -vn -2.154629 5.553559 -1.676560 -v 0.037336 -0.077518 0.166704 -vn -3.789058 4.783876 -1.402447 -v 0.037405 -0.077478 0.166692 -vn -4.157606 4.393679 -1.695290 -v 0.037405 -0.077606 0.166315 -vn 0.391254 5.909036 -1.822711 -v 0.037256 -0.077529 0.166707 -vn -4.036315 4.703639 -1.000632 -v 0.037405 -0.077289 0.167464 -vn -4.162036 4.388371 1.698096 -v 0.037405 -0.077606 0.170985 -vn -3.807238 4.775795 1.379375 -v 0.037405 -0.077478 0.170608 -vn -2.143141 5.564780 1.659450 -v 0.037336 -0.077518 0.170596 -vn 0.391168 6.114681 0.921655 -v 0.037256 -0.077309 0.169632 -vn 2.825420 5.511123 -0.000005 -v 0.037178 -0.077215 0.168650 -vn -4.104347 4.643537 1.015838 -v 0.037405 -0.077289 0.169836 -vn -3.796135 4.942874 0.596858 -v 0.037405 -0.077257 0.169640 -vn -3.804208 4.975985 -0.002711 -v 0.037405 -0.077182 0.168650 -vn -3.792409 4.946322 -0.595803 -v 0.037405 -0.077257 0.167660 -vn -3.794967 4.486329 2.161729 -v 0.037405 -0.077840 0.171533 -vn -2.154808 4.773398 3.296663 -v 0.037336 -0.078372 0.172369 -vn -3.791521 4.076061 2.866317 -v 0.037405 -0.078337 0.172393 -vn -4.158282 4.066026 2.374960 -v 0.037405 -0.078123 0.172058 -vn 0.391129 5.109195 3.483394 -v 0.037256 -0.078381 0.172363 -vn -4.037397 3.714863 3.052236 -v 0.037405 -0.078823 0.173022 -vn -4.156751 1.405066 4.495744 -v 0.037405 -0.081774 0.174969 -vn -3.806726 1.899312 4.594298 -v 0.037405 -0.081399 0.174835 -vn -2.143318 2.172182 5.385446 -v 0.037336 -0.081415 0.174796 -vn 0.391177 3.091869 5.355276 -v 0.037256 -0.080531 0.174358 -vn -4.104449 2.101071 4.263670 -v 0.037405 -0.080678 0.174501 -vn -3.797250 2.613539 4.236415 -v 0.037405 -0.080505 0.174404 -vn -3.808053 3.101863 3.886611 -v 0.037405 -0.079684 0.173845 -vn -3.795272 3.548777 3.493226 -v 0.037405 -0.078956 0.173169 -vn -3.789647 1.113244 4.858811 -v 0.037405 -0.082348 0.175128 -vn -2.154463 0.398711 5.787579 -v 0.037336 -0.083333 0.175234 -vn -3.793003 0.298541 4.972642 -v 0.037405 -0.083330 0.175276 -vn -4.159996 0.679622 4.657976 -v 0.037405 -0.082935 0.175234 -vn 0.391113 0.462119 6.166432 -v 0.037256 -0.083334 0.175223 -vn -4.037554 -0.069771 4.807272 -v 0.037405 -0.084125 0.175288 -vn -4.159103 -2.635828 3.901104 -v 0.037405 -0.087487 0.174195 -vn -3.806205 -2.407476 4.350105 -v 0.037405 -0.087149 0.174404 -vn -2.142943 -2.856178 5.056158 -v 0.037336 -0.087128 0.174368 -vn 0.391121 -2.259152 5.756191 -v 0.037256 -0.086235 0.174785 -vn -4.104040 -2.024128 4.301143 -v 0.037405 -0.086438 0.174760 -vn -3.797928 -1.683220 4.683893 -v 0.037405 -0.086254 0.174835 -vn -3.810668 -1.104919 4.846034 -v 0.037405 -0.085305 0.175128 -vn -3.796435 -0.517285 4.951519 -v 0.037405 -0.084323 0.175276 -vn -3.792449 -3.104977 3.896364 -v 0.037405 -0.087969 0.173845 -vn -2.154830 -4.276117 3.920085 -v 0.037336 -0.088667 0.173141 -vn -3.794303 -3.701567 3.332324 -v 0.037405 -0.088697 0.173169 -vn -4.161176 -3.216501 3.435530 -v 0.037405 -0.088418 0.173453 -vn 0.391065 -4.533023 4.206013 -v 0.037256 -0.088658 0.173133 -vn -4.037550 -3.802093 2.942627 -v 0.037405 -0.089202 0.172555 -vn -4.160742 -4.691820 0.373061 -v 0.037405 -0.090444 0.169246 -vn -3.805501 -4.902582 0.831137 -v 0.037405 -0.090397 0.169640 -vn -2.143127 -5.733755 0.919354 -v 0.037336 -0.090355 0.169634 -vn 0.391257 -5.909036 1.822706 -v 0.037256 -0.090125 0.170593 -vn -4.103015 -4.625956 1.098408 -v 0.037405 -0.090232 0.170418 -vn -3.798119 -4.711464 1.604138 -v 0.037405 -0.090176 0.170608 -vn -3.811911 -4.477030 2.156451 -v 0.037405 -0.089813 0.171533 -vn -3.797428 -4.192471 2.683392 -v 0.037405 -0.089317 0.172393 -vn -3.806813 4.551037 -1.942667 -v 0.040325 -0.075115 0.165201 -vn -3.805054 4.386584 -2.287475 -v 0.040325 -0.075616 0.164136 -vn -3.707518 4.242452 -2.660730 -v 0.040325 -0.075783 0.163844 -vn -3.791916 4.017131 -2.895046 -v 0.040325 -0.076246 0.163143 -vn -3.751933 3.803149 -3.218847 -v 0.040325 -0.076771 0.162485 -vn -3.806936 -0.818232 -4.877195 -v 0.040325 -0.085583 0.159446 -vn -3.807740 3.527206 -3.465216 -v 0.040325 -0.076997 0.162236 -vn -3.809777 3.254144 -3.724004 -v 0.040325 -0.077854 0.161430 -vn -3.770930 2.988726 -3.970593 -v 0.040325 -0.077985 0.161324 -vn -3.803481 2.697427 -4.142215 -v 0.040325 -0.078806 0.160739 -vn -3.740501 2.382838 -4.381169 -v 0.040325 -0.079387 0.160399 -vn -3.810886 2.026365 -4.503667 -v 0.040325 -0.079837 0.160172 -vn -3.795234 1.528493 -4.698324 -v 0.040325 -0.080931 0.159739 -vn -3.803515 1.011962 -4.841060 -v 0.040325 -0.082071 0.159446 -vn -3.640238 0.601653 -5.007972 -v 0.040325 -0.082569 0.159365 -vn -3.785938 0.296376 -4.945751 -v 0.040325 -0.083238 0.159299 -vn -3.780709 -0.100847 -4.964323 -v 0.040325 -0.084247 0.159290 -vn -3.808433 -0.442267 -4.926930 -v 0.040325 -0.084415 0.159299 -vn -3.708608 -1.220293 -4.855744 -v 0.040325 -0.085912 0.159515 -vn -3.792300 -1.509887 -4.715436 -v 0.040325 -0.086722 0.159739 -vn -3.750911 -1.887538 -4.612155 -v 0.040325 -0.087509 0.160034 -vn -3.805519 -2.204315 -4.428480 -v 0.040325 -0.087816 0.160172 -vn -3.806863 -2.539780 -4.246734 -v 0.040325 -0.088847 0.160739 -vn -3.766461 -2.851494 -4.075512 -v 0.040325 -0.088989 0.160830 -vn -3.798257 -3.112655 -3.846538 -v 0.040325 -0.089799 0.161430 -vn -3.736016 -3.430204 -3.626204 -v 0.040325 -0.090302 0.161878 -vn -3.805675 -3.663767 -3.319052 -v 0.040325 -0.090657 0.162236 -vn -3.795334 -3.996080 -2.905325 -v 0.040325 -0.091407 0.163143 -vn -3.804358 -4.290606 -2.458239 -v 0.040325 -0.092038 0.164136 -vn -3.640737 -4.576708 -2.119179 -v 0.040325 -0.092269 0.164585 -vn -3.785470 -4.611906 -1.812009 -v 0.040325 -0.092539 0.165201 -vn -3.778888 -4.754522 -1.437379 -v 0.040325 -0.092859 0.166157 -vn -3.807804 -4.823037 -1.102221 -v 0.040325 -0.092902 0.166320 -vn -3.805814 -4.892514 -0.728505 -v 0.040325 -0.093123 0.167476 -vn -3.708633 -4.995154 -0.339974 -v 0.040325 -0.093159 0.167810 -vn -3.792818 -4.950694 -0.020100 -v 0.040325 -0.093197 0.168650 -vn -3.752972 -4.967734 0.369562 -v 0.040325 -0.093159 0.169490 -vn -3.806782 -4.891708 0.727548 -v 0.040325 -0.093123 0.169824 -vn -3.807803 -4.823039 1.102219 -v 0.040325 -0.092902 0.170980 -vn -3.765897 -4.757851 1.452169 -v 0.040325 -0.092859 0.171143 -vn -3.798419 -4.619870 1.771994 -v 0.040325 -0.092539 0.172099 -vn -3.735811 -4.508998 2.141653 -v 0.040325 -0.092269 0.172715 -vn -3.804353 -4.290621 2.458211 -v 0.040325 -0.092038 0.173164 -vn -3.794922 -3.996649 2.905241 -v 0.040325 -0.091407 0.174157 -vn -3.805038 -3.664093 3.319619 -v 0.040325 -0.090657 0.175064 -vn -3.641721 -3.428391 3.697816 -v 0.040325 -0.090302 0.175422 -vn -3.787291 -3.147047 3.825102 -v 0.040325 -0.089799 0.175870 -vn -3.782050 -2.834419 4.075226 -v 0.040325 -0.088989 0.176470 -vn -3.808723 -2.539991 4.244576 -v 0.040325 -0.088847 0.176561 -vn -3.805442 -2.204349 4.428512 -v 0.040325 -0.087816 0.177128 -vn -3.707396 -1.868327 4.646291 -v 0.040325 -0.087509 0.177266 -vn -3.792295 -1.548140 4.703011 -v 0.040325 -0.086722 0.177561 -vn -3.752041 -1.184692 4.839465 -v 0.040325 -0.085912 0.177785 -vn -3.806940 -0.818239 4.877192 -v 0.040325 -0.085583 0.177854 -vn -3.808190 -0.442493 4.927152 -v 0.040325 -0.084415 0.178001 -vn -3.768326 -0.086784 4.971503 -v 0.040325 -0.084247 0.178010 -vn -3.800166 0.255381 4.939726 -v 0.040325 -0.083238 0.178001 -vn -3.737744 0.645130 4.948000 -v 0.040325 -0.082569 0.177935 -vn -3.807435 1.011144 4.837327 -v 0.040325 -0.082071 0.177854 -vn -3.794723 1.524805 4.700048 -v 0.040325 -0.080931 0.177561 -vn -3.803330 2.027279 4.511312 -v 0.040325 -0.079837 0.177128 -vn -3.639900 2.456770 4.405619 -v 0.040325 -0.079387 0.176901 -vn -3.786035 2.667487 4.175192 -v 0.040325 -0.078806 0.176561 -vn -3.780425 2.999592 3.957212 -v 0.040325 -0.077985 0.175976 -vn -3.809778 3.254141 3.724004 -v 0.040325 -0.077854 0.175870 -vn -3.807853 3.527249 3.465007 -v 0.040325 -0.076997 0.175064 -vn -3.710779 3.841159 3.208181 -v 0.040325 -0.076771 0.174815 -vn -3.795211 3.990282 2.926527 -v 0.040325 -0.076246 0.174157 -vn -3.755063 4.235512 2.618261 -v 0.040325 -0.075783 0.173456 -vn -3.808429 4.382394 2.288436 -v 0.040325 -0.075616 0.173164 -vn -3.806855 4.550997 1.942718 -v 0.040325 -0.075115 0.172099 -vn -3.765692 4.702873 1.622106 -v 0.040325 -0.075054 0.171942 -vn -3.797756 4.779810 1.281782 -v 0.040325 -0.074751 0.170980 -vn -3.735319 4.907067 0.918182 -v 0.040325 -0.074608 0.170323 -vn -3.805304 4.915363 0.531070 -v 0.040325 -0.074531 0.169824 -vn -3.799122 4.936829 -0.001987 -v 0.040325 -0.074457 0.168650 -vn -3.807850 4.913062 -0.529185 -v 0.040325 -0.074531 0.167476 -vn -3.644074 4.944462 -0.978366 -v 0.040325 -0.074608 0.166977 -vn -3.790176 4.792259 -1.241765 -v 0.040325 -0.074751 0.166320 -vn -3.780459 4.690460 -1.629887 -v 0.040325 -0.075054 0.165358 -vn 3.702522 -4.268673 2.638722 -v 0.041682 -0.091876 0.173459 -vn 3.743294 -4.021858 2.949660 -v 0.041682 -0.091413 0.174162 -vn 2.173357 -4.622748 3.379477 -v 0.041367 -0.091571 0.174276 -vn 3.728171 -3.023246 3.988447 -v 0.041682 -0.089673 0.175981 -vn 3.733966 -2.688618 4.208100 -v 0.041682 -0.088851 0.176567 -vn 2.179109 -3.058655 4.836258 -v 0.041367 -0.088956 0.176732 -vn 3.729851 2.856773 4.107385 -v 0.041682 -0.078661 0.176476 -vn 3.735236 3.171860 3.855329 -v 0.041682 -0.077850 0.175875 -vn 2.179123 3.654375 4.403494 -v 0.041367 -0.077725 0.176025 -vn 3.726660 4.791984 -1.448755 -v 0.041682 -0.074788 0.166155 -vn 3.733457 4.648282 -1.826261 -v 0.041682 -0.075108 0.165198 -vn 2.179102 5.317194 -2.114784 -v 0.041367 -0.074927 0.165126 -vn 3.728418 0.101744 -5.003501 -v 0.041682 -0.083406 0.159283 -vn 3.733860 -0.298651 -4.984797 -v 0.041682 -0.084416 0.159292 -vn 2.179137 -0.368144 -5.710480 -v 0.041367 -0.084428 0.159097 -vn 2.164017 2.457963 5.178306 -v 0.041367 -0.079751 0.177311 -vn -0.031683 2.604411 5.534629 -v 0.041002 -0.079723 0.177371 -vn -0.031617 1.890203 5.817440 -v 0.041002 -0.080848 0.177817 -vn 2.164006 5.684405 -0.737462 -v 0.041367 -0.074330 0.167450 -vn -0.031665 6.068581 -0.766625 -v 0.041002 -0.074264 0.167442 -vn -0.031716 6.116817 -0.000007 -v 0.041002 -0.074188 0.168650 -vn 2.163980 1.055206 -5.634089 -v 0.041367 -0.082033 0.159248 -vn -0.031711 1.146170 -6.008447 -v 0.041002 -0.082021 0.159182 -vn -0.031610 1.890215 -5.817441 -v 0.041002 -0.080848 0.159483 -vn 2.164045 -5.032240 -2.744579 -v 0.041367 -0.092215 0.164039 -vn -0.031681 -5.360189 -2.946783 -v 0.041002 -0.092273 0.164007 -vn -0.031633 -4.948563 -3.595367 -v 0.041002 -0.091625 0.162984 -vn -2.225039 2.412498 5.173761 -v 0.040638 -0.079753 0.177307 -vn -2.244228 1.759973 5.416647 -v 0.040638 -0.080870 0.177750 -vn -2.224987 5.666047 -0.695605 -v 0.040638 -0.074334 0.167451 -vn -2.244258 5.695415 -0.000003 -v 0.040638 -0.074259 0.168650 -vn -2.225039 1.089336 -5.603691 -v 0.040638 -0.082034 0.159251 -vn -2.244240 1.759967 -5.416648 -v 0.040638 -0.080870 0.159550 -vn -2.225049 -4.992777 -2.767644 -v 0.040638 -0.092211 0.164041 -vn -2.244342 -4.607674 -3.347653 -v 0.040638 -0.091568 0.163026 -vn -2.224952 -4.175057 3.893163 -v 0.040638 -0.090802 0.175200 -vn -2.223551 -5.661971 -0.734486 -v 0.040638 -0.093319 0.167451 -vn -2.225077 -5.533781 -1.401669 -v 0.040638 -0.093094 0.166271 -vn -2.222976 -4.181193 -3.889014 -v 0.040638 -0.090802 0.162100 -vn -2.227438 -3.620034 -4.412333 -v 0.040638 -0.089926 0.161278 -vn -2.227807 -3.047185 -4.824749 -v 0.040638 -0.088954 0.160571 -vn -2.220912 -2.456063 -5.156441 -v 0.040638 -0.087901 0.159993 -vn -2.232703 -1.746569 -5.429644 -v 0.040638 -0.086784 0.159550 -vn -2.223577 -1.051146 -5.611837 -v 0.040638 -0.085620 0.159251 -vn -2.225044 -0.376942 -5.696060 -v 0.040638 -0.084428 0.159101 -vn -2.223023 2.406591 -5.178304 -v 0.040638 -0.079753 0.159993 -vn -2.227446 3.077719 -4.806345 -v 0.040638 -0.078700 0.160571 -vn -2.227804 3.646988 -4.388965 -v 0.040638 -0.077728 0.161278 -vn -2.220863 4.145117 -3.929296 -v 0.040638 -0.076852 0.162100 -vn -2.232806 4.624154 -3.338954 -v 0.040638 -0.076086 0.163026 -vn -2.223597 5.012338 -2.733824 -v 0.040638 -0.075442 0.164041 -vn -2.225023 5.300799 -2.118669 -v 0.040638 -0.074931 0.165128 -vn -2.223006 5.668578 0.688617 -v 0.040638 -0.074334 0.169849 -vn -2.227480 5.522147 1.441839 -v 0.040638 -0.074559 0.171029 -vn -2.227806 5.301105 2.112225 -v 0.040638 -0.074931 0.172172 -vn -2.220907 5.017886 2.728026 -v 0.040638 -0.075442 0.173259 -vn -2.232747 4.604488 3.366035 -v 0.040638 -0.076086 0.174274 -vn -2.223500 4.148920 3.922226 -v 0.040638 -0.076852 0.175200 -vn -2.225028 3.653035 4.386657 -v 0.040638 -0.077728 0.176022 -vn -2.223049 1.096785 5.603937 -v 0.040638 -0.082034 0.178049 -vn -2.227432 0.335166 5.697448 -v 0.040638 -0.083226 0.178199 -vn -2.227797 -0.370708 5.694379 -v 0.040638 -0.084428 0.178199 -vn -2.220952 -1.043891 5.615321 -v 0.040638 -0.085620 0.178049 -vn -2.232708 -1.778456 5.419279 -v 0.040638 -0.086784 0.177750 -vn -2.223575 -2.448184 5.157911 -v 0.040638 -0.087901 0.177307 -vn -2.224989 -3.043086 4.829786 -v 0.040638 -0.088954 0.176729 -vn -2.227851 -5.530240 1.407101 -v 0.040638 -0.093094 0.171029 -vn -2.227468 -5.315019 2.079360 -v 0.040638 -0.092723 0.172172 -vn -2.220933 -5.663041 0.742433 -v 0.040638 -0.093319 0.169849 -vn -2.232738 -5.703629 -0.016736 -v 0.040638 -0.093395 0.168650 -vn -0.031733 -5.924621 -1.521180 -v 0.041002 -0.093163 0.166253 -vn -0.031668 -6.068579 -0.766633 -v 0.041002 -0.093390 0.167442 -vn -0.031622 -4.458974 -4.187265 -v 0.041002 -0.090853 0.162052 -vn -0.031707 -3.899024 -4.713070 -v 0.041002 -0.089971 0.161223 -vn -0.031624 -3.277533 -5.164578 -v 0.041002 -0.088991 0.160512 -vn -0.031576 -2.604394 -5.534666 -v 0.041002 -0.087931 0.159929 -vn -0.031617 -1.890203 -5.817440 -v 0.041002 -0.086805 0.159483 -vn -0.031719 -1.146201 -6.008441 -v 0.041002 -0.085633 0.159182 -vn -0.031606 -0.384070 -6.104731 -v 0.041002 -0.084432 0.159030 -vn -0.031588 2.604402 -5.534661 -v 0.041002 -0.079723 0.159929 -vn -0.031623 3.277535 -5.164571 -v 0.041002 -0.078662 0.160512 -vn -0.031688 3.899007 -4.713083 -v 0.041002 -0.077683 0.161223 -vn -0.031638 4.458983 -4.187258 -v 0.041002 -0.076800 0.162052 -vn -0.031693 4.948567 -3.595376 -v 0.041002 -0.076029 0.162984 -vn -0.031667 5.360190 -2.946784 -v 0.041002 -0.075380 0.164007 -vn -0.031656 5.687282 -2.251748 -v 0.041002 -0.074865 0.165102 -vn -0.031668 6.068581 0.766634 -v 0.041002 -0.074264 0.169858 -vn -0.031675 5.924634 1.521184 -v 0.041002 -0.074491 0.171047 -vn -0.031657 5.687275 2.251761 -v 0.041002 -0.074865 0.172198 -vn -0.031677 5.360213 2.946797 -v 0.041002 -0.075380 0.173293 -vn -0.031684 4.948614 3.595371 -v 0.041002 -0.076029 0.174315 -vn -0.031633 4.458979 4.187259 -v 0.041002 -0.076800 0.175248 -vn -0.031614 3.898985 4.713074 -v 0.041002 -0.077683 0.176077 -vn -0.031719 1.146201 6.008441 -v 0.041002 -0.082021 0.178118 -vn -0.031606 0.384070 6.104731 -v 0.041002 -0.083222 0.178270 -vn -0.031608 -0.384085 6.104726 -v 0.041002 -0.084432 0.178270 -vn -0.031711 -1.146170 6.008447 -v 0.041002 -0.085633 0.178118 -vn -0.031620 -1.890227 5.817434 -v 0.041002 -0.086805 0.177817 -vn -0.031676 -2.604395 5.534636 -v 0.041002 -0.087931 0.177371 -vn -0.031623 -3.277569 5.164612 -v 0.041002 -0.088991 0.176788 -vn -0.031661 -6.116805 -0.000000 -v 0.041002 -0.093466 0.168650 -vn -0.031665 -6.068582 0.766625 -v 0.041002 -0.093390 0.169858 -vn -0.031733 -5.924618 1.521192 -v 0.041002 -0.093163 0.171047 -vn -0.031717 -5.687264 2.251750 -v 0.041002 -0.092789 0.172198 -vn 2.179106 -5.544738 -1.414485 -v 0.041367 -0.093098 0.166270 -vn 2.165498 -5.688501 -0.698272 -v 0.041367 -0.093323 0.167450 -vn 2.173380 -4.642578 -3.352215 -v 0.041367 -0.091571 0.163024 -vn 2.161336 -4.161453 -3.944908 -v 0.041367 -0.090804 0.162098 -vn 2.168317 -3.661490 -4.406324 -v 0.041367 -0.089928 0.161275 -vn 2.167996 -3.089991 -4.825384 -v 0.041367 -0.088956 0.160568 -vn 2.163495 -2.416042 -5.198896 -v 0.041367 -0.087902 0.159989 -vn 2.185005 -1.767026 -5.438280 -v 0.041367 -0.086785 0.159547 -vn 2.165479 -1.093745 -5.625874 -v 0.041367 -0.085620 0.159248 -vn 2.173320 1.753498 -5.451254 -v 0.041367 -0.080869 0.159547 -vn 2.161355 2.465895 -5.176838 -v 0.041367 -0.079751 0.159989 -vn 2.168355 3.059225 -4.843928 -v 0.041367 -0.078698 0.160568 -vn 2.167957 3.634305 -4.429877 -v 0.041367 -0.077725 0.161275 -vn 2.163471 4.197824 -3.904346 -v 0.041367 -0.076849 0.162098 -vn 2.185052 4.626067 -3.361034 -v 0.041367 -0.076083 0.163024 -vn 2.165525 5.012534 -2.778676 -v 0.041367 -0.075439 0.164039 -vn 2.173327 5.726271 -0.016882 -v 0.041367 -0.074255 0.168650 -vn 2.161350 5.685453 0.745476 -v 0.041367 -0.074330 0.169850 -vn 2.168334 5.552179 1.412627 -v 0.041367 -0.074556 0.171030 -vn 2.167959 5.336127 2.087540 -v 0.041367 -0.074927 0.172174 -vn 2.163468 5.010439 2.785871 -v 0.041367 -0.075439 0.173261 -vn 2.185029 4.626044 3.361029 -v 0.041367 -0.076083 0.174276 -vn 2.165473 4.191650 3.908546 -v 0.041367 -0.076849 0.175202 -vn 2.173330 1.785573 5.440822 -v 0.041367 -0.080869 0.177753 -vn 2.161412 1.047912 5.637503 -v 0.041367 -0.082033 0.178052 -vn 2.168358 0.372227 5.716985 -v 0.041367 -0.083226 0.178203 -vn 2.168004 -0.336416 5.720057 -v 0.041367 -0.084428 0.178203 -vn 2.163558 -1.101202 5.626044 -v 0.041367 -0.085620 0.178052 -vn 2.185019 -1.767007 5.438279 -v 0.041367 -0.086785 0.177753 -vn 2.165498 -2.421972 5.194312 -v 0.041367 -0.087902 0.177311 -vn -2.244267 -4.607676 3.347671 -v 0.040638 -0.091568 0.174274 -vn -0.031623 -4.458982 4.187253 -v 0.041002 -0.090853 0.175248 -vn -0.031642 -4.948604 3.595366 -v 0.041002 -0.091625 0.174315 -vn 2.163993 -4.165296 3.937829 -v 0.041367 -0.090804 0.175202 -vn 2.185035 -5.718133 0.000000 -v 0.041367 -0.093399 0.168650 -vn 2.163496 -5.691025 0.691232 -v 0.041367 -0.093323 0.169850 -vn 2.167984 -5.544032 1.447648 -v 0.041367 -0.093098 0.171030 -vn 2.168316 -5.322132 2.120661 -v 0.041367 -0.092727 0.172174 -vn 3.590303 -4.981833 -0.985624 -v 0.041682 -0.093053 0.166976 -vn 3.738204 -4.830091 -1.251595 -v 0.041682 -0.092909 0.166318 -vn 3.728216 -4.727428 -1.642820 -v 0.041682 -0.092606 0.165355 -vn 3.754947 -4.587199 -1.958130 -v 0.041682 -0.092545 0.165198 -vn 2.165517 -5.321776 -2.127150 -v 0.041367 -0.092727 0.165126 -vn -0.031712 -5.687272 -2.251742 -v 0.041002 -0.092789 0.165102 -vn -2.238430 -5.296144 -2.106358 -v 0.040638 -0.092723 0.165128 -vn 3.753180 -4.421422 -2.305647 -v 0.041682 -0.092044 0.164133 -vn 3.718685 -3.012179 -4.001787 -v 0.041682 -0.089673 0.161319 -vn 3.758001 -3.279974 -3.753615 -v 0.041682 -0.089804 0.161425 -vn 3.755956 -3.555219 -3.492735 -v 0.041682 -0.090662 0.162231 -vn 3.699334 -3.832863 -3.244066 -v 0.041682 -0.090888 0.162481 -vn 3.739869 -4.048866 -2.918016 -v 0.041682 -0.091413 0.163138 -vn 3.654373 -4.275247 -2.681170 -v 0.041682 -0.091876 0.163841 -vn 3.751706 -2.718828 -4.175022 -v 0.041682 -0.088851 0.160733 -vn 3.687732 -2.401376 -4.415344 -v 0.041682 -0.088270 0.160393 -vn 3.759145 -2.042490 -4.539454 -v 0.041682 -0.087819 0.160166 -vn 3.743384 -1.540602 -4.735462 -v 0.041682 -0.086724 0.159732 -vn 3.751689 -1.019962 -4.879458 -v 0.041682 -0.085584 0.159439 -vn 3.586352 -0.606282 -5.045786 -v 0.041682 -0.085085 0.159358 -vn 3.756577 0.445859 -4.966115 -v 0.041682 -0.083238 0.159292 -vn 2.165540 0.378508 -5.718660 -v 0.041367 -0.083226 0.159097 -vn -0.031608 0.384085 -6.104726 -v 0.041002 -0.083222 0.159030 -vn -2.238423 0.366681 -5.687811 -v 0.040638 -0.083226 0.159101 -vn 3.755137 0.824693 -4.915926 -v 0.041682 -0.082070 0.159439 -vn 3.714045 2.873863 -4.107553 -v 0.041682 -0.078661 0.160824 -vn 3.754972 2.560022 -4.280460 -v 0.041682 -0.078802 0.160733 -vn 3.753591 2.221823 -4.463693 -v 0.041682 -0.079834 0.160166 -vn 3.698210 1.902344 -4.648250 -v 0.041682 -0.080141 0.160028 -vn 3.740288 1.521878 -4.752724 -v 0.041682 -0.080929 0.159732 -vn 3.655471 1.229642 -4.893239 -v 0.041682 -0.081740 0.159508 -vn 3.746376 3.137337 -3.876960 -v 0.041682 -0.077850 0.161425 -vn 3.683260 3.456908 -3.654402 -v 0.041682 -0.077347 0.161872 -vn 3.753854 3.692808 -3.345445 -v 0.041682 -0.076991 0.162231 -vn 3.743489 4.027653 -2.928312 -v 0.041682 -0.076241 0.163138 -vn 3.752523 4.324677 -2.477700 -v 0.041682 -0.075610 0.164133 -vn 3.586865 4.611237 -2.135275 -v 0.041682 -0.075379 0.164582 -vn 3.755959 4.861341 -1.111064 -v 0.041682 -0.074745 0.166318 -vn 2.165514 5.555722 -1.407159 -v 0.041367 -0.074556 0.166270 -vn -0.031681 5.924632 -1.521189 -v 0.041002 -0.074491 0.166253 -vn -2.238470 5.522720 -1.408895 -v 0.040638 -0.074559 0.166271 -vn 3.753951 4.931380 -0.734284 -v 0.041682 -0.074524 0.167475 -vn 3.713547 4.795189 1.463560 -v 0.041682 -0.074788 0.171145 -vn 3.755980 4.861328 1.111066 -v 0.041682 -0.074745 0.170982 -vn 3.754946 4.930571 0.733300 -v 0.041682 -0.074524 0.169825 -vn 3.700397 5.006588 0.372481 -v 0.041682 -0.074488 0.169491 -vn 3.740905 4.989809 -0.020230 -v 0.041682 -0.074450 0.168650 -vn 3.655480 5.033717 -0.342670 -v 0.041682 -0.074488 0.167809 -vn 3.746542 4.656435 1.786050 -v 0.041682 -0.075108 0.172102 -vn 3.683009 4.544085 2.158342 -v 0.041682 -0.075379 0.172718 -vn 3.752523 4.324670 2.477710 -v 0.041682 -0.075610 0.173167 -vn 3.743120 4.028205 2.928209 -v 0.041682 -0.076241 0.174162 -vn 3.753199 3.693146 3.345999 -v 0.041682 -0.076991 0.175069 -vn 3.587911 3.454373 3.725655 -v 0.041682 -0.077347 0.175428 -vn 3.756877 2.560253 4.278286 -v 0.041682 -0.078802 0.176567 -vn 2.165505 3.055100 4.848962 -v 0.041367 -0.078698 0.176732 -vn -0.031626 3.277563 5.164615 -v 0.041002 -0.078662 0.176788 -vn -2.238396 3.046530 4.817065 -v 0.040638 -0.078700 0.176729 -vn 3.753587 2.221846 4.463682 -v 0.041682 -0.079834 0.177134 -vn 3.715880 0.087578 5.010592 -v 0.041682 -0.083406 0.178017 -vn 3.756321 0.446123 4.966328 -v 0.041682 -0.083238 0.178008 -vn 3.755219 0.824701 4.915881 -v 0.041682 -0.082070 0.177861 -vn 3.699499 1.193917 4.877293 -v 0.041682 -0.081740 0.177792 -vn 3.740280 1.560311 4.740236 -v 0.041682 -0.080929 0.177568 -vn 3.654253 1.882820 4.682111 -v 0.041682 -0.080141 0.177272 -vn 3.748267 -0.257473 4.978875 -v 0.041682 -0.084416 0.178008 -vn 3.685077 -0.650161 4.986477 -v 0.041682 -0.085085 0.177942 -vn 3.755781 -1.019126 4.875671 -v 0.041682 -0.085584 0.177861 -vn 3.742850 -1.536808 4.737227 -v 0.041682 -0.086724 0.177568 -vn 3.751480 -2.043362 4.547103 -v 0.041682 -0.087819 0.177134 -vn 3.585922 -2.475266 4.438965 -v 0.041682 -0.088270 0.176907 -vn 3.757937 -3.279991 3.753651 -v 0.041682 -0.089804 0.175875 -vn 2.165536 -3.667576 4.404008 -v 0.041367 -0.089928 0.176025 -vn -0.031614 -3.898987 4.713072 -v 0.041002 -0.089971 0.176077 -vn -2.238426 -3.639848 4.386033 -v 0.040638 -0.089926 0.176022 -vn 3.756076 -3.555212 3.492581 -v 0.041682 -0.090662 0.175069 -vn 3.657654 -3.870759 3.233041 -v 0.041682 -0.090888 0.174819 -vn 3.756639 -4.417192 2.306649 -v 0.041682 -0.092044 0.173167 -vn 2.161318 -5.037795 2.738739 -v 0.041367 -0.092215 0.173261 -vn -0.031672 -5.360211 2.946796 -v 0.041002 -0.092273 0.173293 -vn -2.223021 -4.990720 2.774782 -v 0.040638 -0.092211 0.173259 -vn 3.754950 -4.587199 1.958127 -v 0.041682 -0.092545 0.172102 -vn 3.756144 -4.952044 -0.533359 -v 0.041682 -0.093130 0.167475 -vn 3.747410 -4.975846 -0.002015 -v 0.041682 -0.093204 0.168650 -vn 3.753529 -4.954356 0.535267 -v 0.041682 -0.093130 0.169825 -vn 3.682510 -4.945261 0.925298 -v 0.041682 -0.093053 0.170324 -vn 3.745828 -4.817680 1.291890 -v 0.041682 -0.092909 0.170982 -vn 3.713239 -4.739810 1.634891 -v 0.041682 -0.092606 0.171945 -vn 4.001643 -4.514734 -1.741813 -v 0.044630 -0.090083 0.166302 -vn 3.665139 -4.564749 -2.197596 -v 0.044630 -0.089847 0.165751 -vn 4.006751 -4.174866 -2.438058 -v 0.044630 -0.089563 0.165223 -vn 3.676069 -4.127593 -2.925416 -v 0.044630 -0.089348 0.164886 -vn 3.949835 -3.784741 -3.075786 -v 0.044630 -0.088859 0.164254 -vn 3.663957 -3.610884 -3.554808 -v 0.044630 -0.088725 0.164105 -vn 3.680839 1.124609 -4.932298 -v 0.044630 -0.082340 0.162135 -vn 3.665468 0.526145 -5.038448 -v 0.044630 -0.083327 0.161987 -vn 3.674537 -3.155827 -3.960796 -v 0.044630 -0.087993 0.163426 -vn 3.659528 -2.663522 -4.315067 -v 0.044630 -0.087168 0.162863 -vn 3.883167 -2.205655 -4.405043 -v 0.044630 -0.086993 0.162766 -vn 3.653959 -1.917974 -4.699629 -v 0.044630 -0.086268 0.162430 -vn 3.997745 -1.455600 -4.618517 -v 0.044630 -0.085892 0.162295 -vn 3.664102 -1.129328 -4.939641 -v 0.044630 -0.085314 0.162135 -vn 4.006891 -0.696793 -4.784050 -v 0.044630 -0.084724 0.162028 -vn 3.674917 -0.285057 -5.052145 -v 0.044630 -0.084326 0.161987 -vn 3.948559 0.043702 -4.877906 -v 0.044630 -0.083527 0.161975 -vn 3.666989 1.712718 -4.766087 -v 0.044630 -0.081386 0.162430 -vn 3.888884 2.066750 -4.466352 -v 0.044630 -0.081201 0.162506 -vn 3.665464 2.468656 -4.423689 -v 0.044630 -0.080486 0.162863 -vn 4.005621 2.706148 -4.007505 -v 0.044630 -0.080146 0.163073 -vn 3.664217 3.158348 -3.962350 -v 0.044630 -0.079661 0.163426 -vn 4.006074 3.305922 -3.528507 -v 0.044630 -0.079209 0.163820 -vn 3.672605 3.774843 -3.372782 -v 0.044630 -0.078929 0.164105 -vn 3.946935 3.841015 -3.009465 -v 0.044630 -0.078421 0.164722 -vn 3.666189 4.266256 -2.730433 -v 0.044630 -0.078306 0.164886 -vn 3.682174 4.556733 -2.194798 -v 0.044630 -0.077806 0.165751 -vn 3.666841 4.794275 -1.632509 -v 0.044630 -0.077442 0.166680 -vn 3.887812 4.781711 -1.168131 -v 0.044630 -0.077386 0.166872 -vn 3.664762 4.998202 -0.829301 -v 0.044630 -0.077219 0.167654 -vn 4.005695 4.820395 -0.382780 -v 0.044630 -0.077172 0.168051 -vn 3.662929 5.068137 0.000005 -v 0.044630 -0.077145 0.168650 -vn 4.004837 4.821082 0.383602 -v 0.044630 -0.077172 0.169249 -vn 3.674818 4.989063 0.845825 -v 0.044630 -0.077219 0.169646 -vn 3.949257 4.745146 1.128427 -v 0.044630 -0.077386 0.170428 -vn 3.666723 4.794347 1.632513 -v 0.044630 -0.077442 0.170620 -vn 3.682332 4.556638 2.194770 -v 0.044630 -0.077806 0.171549 -vn 3.666205 4.266199 2.730510 -v 0.044630 -0.078306 0.172414 -vn 3.885842 3.894962 3.012571 -v 0.044630 -0.078421 0.172578 -vn 3.662731 3.766743 3.390971 -v 0.044630 -0.078929 0.173195 -vn 4.005177 3.305414 3.530068 -v 0.044630 -0.079209 0.173480 -vn 3.661262 3.159488 3.964729 -v 0.044630 -0.079661 0.173874 -vn 4.003150 2.708217 4.008728 -v 0.044630 -0.080146 0.174227 -vn 3.675637 2.449897 4.426808 -v 0.044630 -0.080486 0.174437 -vn 3.950416 2.074980 4.412950 -v 0.044630 -0.081201 0.174794 -vn 3.666992 1.712715 4.766087 -v 0.044630 -0.081386 0.174870 -vn 3.681186 1.124543 4.932097 -v 0.044630 -0.082340 0.175165 -vn 3.665679 0.526338 5.038245 -v 0.044630 -0.083327 0.175313 -vn 3.886124 0.072953 4.923278 -v 0.044630 -0.083527 0.175325 -vn 3.662161 -0.303833 5.059700 -v 0.044630 -0.084326 0.175313 -vn 4.004100 -0.698146 4.786321 -v 0.044630 -0.084724 0.175272 -vn 3.658441 -1.132678 4.944029 -v 0.044630 -0.085314 0.175165 -vn 4.001015 -1.443983 4.619236 -v 0.044630 -0.085892 0.175005 -vn 3.676245 -1.932828 4.675245 -v 0.044630 -0.086268 0.174870 -vn 3.950875 -2.156758 4.373113 -v 0.044630 -0.086993 0.174534 -vn 3.666206 -2.659472 4.310744 -v 0.044630 -0.087168 0.174437 -vn 3.678630 -3.156884 3.955547 -v 0.044630 -0.087993 0.173874 -vn 3.663737 -3.611166 3.554790 -v 0.044630 -0.088725 0.173195 -vn 3.885655 -3.803706 3.127267 -v 0.044630 -0.088859 0.173046 -vn 3.660339 -4.147514 2.916654 -v 0.044630 -0.089348 0.172414 -vn 4.002478 -4.177782 2.440511 -v 0.044630 -0.089563 0.172077 -vn 3.663699 -4.565172 2.199705 -v 0.044630 -0.089847 0.171549 -vn 4.006193 -4.509397 1.744645 -v 0.044630 -0.090083 0.170998 -vn 3.676337 -4.860253 1.403644 -v 0.044630 -0.090212 0.170620 -vn 3.950641 -4.763915 1.040580 -v 0.044630 -0.090401 0.169843 -vn 3.664975 -5.029687 0.607320 -v 0.044630 -0.090434 0.169646 -vn 3.674507 -5.064298 -0.002740 -v 0.044630 -0.090509 0.168650 -vn 3.661225 -5.033097 -0.606260 -v 0.044630 -0.090434 0.167654 -vn 3.884647 -4.817611 -1.023333 -v 0.044630 -0.090401 0.167457 -vn 3.657581 -4.867914 -1.426999 -v 0.044630 -0.090212 0.166680 -vn 1.720380 -5.664599 1.690109 -v 0.044711 -0.090169 0.170606 -vn 1.729233 -5.848598 0.823872 -v 0.044711 -0.090390 0.169639 -vn -1.191818 -5.979417 0.901243 -v 0.044803 -0.090386 0.169639 -vn 1.720538 -2.210375 5.482461 -v 0.044711 -0.086252 0.174828 -vn 1.729159 -3.002491 5.086304 -v 0.044711 -0.087145 0.174398 -vn -1.191836 -3.023475 5.236801 -v 0.044803 -0.087143 0.174395 -vn 1.720541 2.908246 5.146464 -v 0.044711 -0.080508 0.174398 -vn 1.729120 2.104641 5.518624 -v 0.044711 -0.081402 0.174828 -vn -1.191951 2.209201 5.628960 -v 0.044803 -0.081403 0.174825 -vn 1.720630 5.836874 0.935006 -v 0.044711 -0.077264 0.169639 -vn 1.728967 5.626928 1.795392 -v 0.044711 -0.077485 0.170606 -vn -1.192002 5.778281 1.782391 -v 0.044803 -0.077488 0.170605 -vn 1.720505 4.370311 -3.980541 -v 0.044711 -0.078961 0.164136 -vn 1.729008 4.911952 -3.279850 -v 0.044711 -0.078343 0.164911 -vn -1.192062 4.996239 -3.406394 -v 0.044803 -0.078346 0.164913 -vn 1.720692 -0.387211 -5.898524 -v 0.044711 -0.084323 0.162031 -vn 1.729275 0.498187 -5.885235 -v 0.044711 -0.083331 0.162031 -vn -1.191901 0.451870 -6.030041 -v 0.044803 -0.083331 0.162035 -vn 1.720390 -4.853145 -3.374944 -v 0.044711 -0.089311 0.164911 -vn 1.729115 -4.290699 -4.059028 -v 0.044711 -0.088692 0.164136 -vn -1.191800 -4.432729 -4.112954 -v 0.044803 -0.088689 0.164138 -vn 1.732965 -5.321012 2.562448 -v 0.044711 -0.089807 0.171530 -vn 1.732654 -4.859923 3.355517 -v 0.044711 -0.089311 0.172389 -vn 1.732947 -1.314151 5.757720 -v 0.044711 -0.085304 0.175121 -vn 1.732658 -0.406682 5.891744 -v 0.044711 -0.084323 0.175269 -vn 1.733295 3.682179 4.617312 -v 0.044711 -0.079689 0.173839 -vn 1.732512 4.352900 3.991481 -v 0.044711 -0.078961 0.173164 -vn 1.733068 5.905881 -0.000002 -v 0.044711 -0.077190 0.168650 -vn 1.732632 5.834569 -0.914568 -v 0.044711 -0.077264 0.167661 -vn 1.732915 3.682221 -4.617320 -v 0.044711 -0.079689 0.163461 -vn 1.732530 2.922778 -5.131931 -v 0.044711 -0.080508 0.162902 -vn 1.733085 -1.314212 -5.757857 -v 0.044711 -0.085304 0.162179 -vn 1.732519 -2.189938 -5.484766 -v 0.044711 -0.086252 0.162472 -vn 1.733015 -5.321073 -2.562491 -v 0.044711 -0.089807 0.165770 -vn 1.732470 -5.653605 -1.707521 -v 0.044711 -0.090169 0.166694 -vn 1.729931 -5.849138 -0.819368 -v 0.044711 -0.090390 0.167661 -vn 1.729867 -3.006332 -5.083925 -v 0.044711 -0.087145 0.162902 -vn 1.729820 2.100405 -5.520139 -v 0.044711 -0.081402 0.162472 -vn 1.729796 5.625409 -1.799625 -v 0.044711 -0.077485 0.166694 -vn 1.729955 4.914352 3.276074 -v 0.044711 -0.078343 0.172389 -vn 1.729975 0.502719 5.884760 -v 0.044711 -0.083331 0.175269 -vn 1.729842 -4.287515 4.062247 -v 0.044711 -0.088692 0.173164 -vn -1.191772 -5.448093 -2.623636 -v 0.044803 -0.089803 0.165772 -vn -1.192007 -5.778281 -1.782383 -v 0.044803 -0.090165 0.166695 -vn -3.827480 -3.001137 -3.763309 -v 0.044888 -0.087986 0.163434 -vn -1.192088 -3.770211 -4.727729 -v 0.044803 -0.087963 0.163464 -vn 1.685411 -3.695771 -4.634327 -v 0.044711 -0.087965 0.163461 -vn -1.191650 -1.345581 -5.895333 -v 0.044803 -0.085303 0.162183 -vn -1.191951 -2.209201 -5.628960 -v 0.044803 -0.086250 0.162475 -vn -3.827614 1.071066 -4.692656 -v 0.044888 -0.082342 0.162146 -vn -1.191592 1.345544 -5.895342 -v 0.044803 -0.082351 0.162183 -vn 1.685558 1.319035 -5.779086 -v 0.044711 -0.082350 0.162179 -vn -1.192088 3.770229 -4.727714 -v 0.044803 -0.079691 0.163464 -vn -1.191824 3.023458 -5.236813 -v 0.044803 -0.080510 0.162905 -vn -3.827549 4.336765 -2.088489 -v 0.044888 -0.077816 0.165755 -vn -1.191780 5.448081 -2.623656 -v 0.044803 -0.077850 0.165772 -vn 1.685493 5.340652 -2.571949 -v 0.044711 -0.077847 0.165770 -vn -1.191900 6.046894 0.000004 -v 0.044803 -0.077193 0.168650 -vn -1.191818 5.979416 -0.901243 -v 0.044803 -0.077268 0.167661 -vn -3.827462 4.336761 2.088455 -v 0.044888 -0.077816 0.171545 -vn -1.191811 5.448134 2.623715 -v 0.044803 -0.077850 0.171528 -vn 1.685445 5.340612 2.571873 -v 0.044711 -0.077847 0.171530 -vn -1.192030 3.770153 4.727603 -v 0.044803 -0.079691 0.173836 -vn -1.191802 4.432729 4.112959 -v 0.044803 -0.078964 0.173162 -vn -3.827604 1.071044 4.692673 -v 0.044888 -0.082342 0.175154 -vn -1.192075 1.345547 5.895339 -v 0.044803 -0.082351 0.175117 -vn 1.685461 1.319009 5.778931 -v 0.044711 -0.082350 0.175121 -vn -1.192126 -1.345572 5.895333 -v 0.044803 -0.085303 0.175117 -vn -1.191901 -0.451870 6.030041 -v 0.044803 -0.084323 0.175265 -vn -3.827785 -3.001038 3.763192 -v 0.044888 -0.087986 0.173866 -vn -1.192033 -3.770168 4.727588 -v 0.044803 -0.087963 0.173836 -vn 1.685794 -3.695721 4.634320 -v 0.044711 -0.087965 0.173839 -vn -1.191801 -5.448127 2.623734 -v 0.044803 -0.089803 0.171528 -vn -1.192017 -4.996188 3.406297 -v 0.044803 -0.089308 0.172387 -vn -3.827602 -4.813434 -0.000007 -v 0.044888 -0.090498 0.168650 -vn -1.191900 -6.046894 -0.000004 -v 0.044803 -0.090460 0.168650 -vn 1.685551 -5.927626 0.000000 -v 0.044711 -0.090464 0.168650 -vn -3.825755 -4.587173 -1.462385 -v 0.044888 -0.090202 0.166684 -vn -3.802318 -4.361858 -2.100574 -v 0.044888 -0.089838 0.165755 -vn -3.825334 -4.001787 -2.677455 -v 0.044888 -0.089339 0.164892 -vn -3.825737 -1.716674 -4.498166 -v 0.044888 -0.086264 0.162440 -vn -3.802383 -1.077251 -4.719811 -v 0.044888 -0.085311 0.162146 -vn -3.825526 -0.401745 -4.797894 -v 0.044888 -0.084325 0.161997 -vn -3.825816 2.446439 -4.146658 -v 0.044888 -0.080491 0.162872 -vn -3.802252 3.018496 -3.785085 -v 0.044888 -0.079667 0.163434 -vn -3.825434 3.500750 -3.305610 -v 0.044888 -0.078936 0.164112 -vn -3.825752 4.767372 -0.672715 -v 0.044888 -0.077230 0.167656 -vn -3.802364 4.841292 0.000000 -v 0.044888 -0.077155 0.168650 -vn -3.825396 4.767146 0.675974 -v 0.044888 -0.077230 0.169644 -vn -3.825803 3.498338 3.307814 -v 0.044888 -0.078936 0.173188 -vn -3.802557 3.018389 3.784972 -v 0.044888 -0.079667 0.173866 -vn -3.825464 2.443751 4.148511 -v 0.044888 -0.080491 0.174428 -vn -3.825857 -0.404928 4.797423 -v 0.044888 -0.084325 0.175303 -vn -3.802381 -1.077254 4.719816 -v 0.044888 -0.085311 0.175154 -vn -3.825347 -1.719851 4.497241 -v 0.044888 -0.086264 0.174860 -vn -3.825826 -4.003414 2.674598 -v 0.044888 -0.089339 0.172408 -vn -3.802235 -4.361856 2.100538 -v 0.044888 -0.089838 0.171545 -vn -3.825333 -4.588445 1.459401 -v 0.044888 -0.090202 0.170616 -vn -3.827277 -4.755878 -0.742637 -v 0.044888 -0.090424 0.167656 -vn -5.298489 -3.269508 -0.542548 -v 0.044946 -0.090495 0.167645 -vn -5.460867 -3.075278 -0.243496 -v 0.044946 -0.090543 0.168046 -vn -1.191809 -5.979418 -0.901230 -v 0.044803 -0.090386 0.167661 -vn -5.297900 -3.315396 -0.000002 -v 0.044946 -0.090570 0.168650 -vn -5.406057 -3.076568 -0.749868 -v 0.044946 -0.090327 0.166856 -vn -5.460480 -2.108779 -2.252665 -v 0.044946 -0.088487 0.163776 -vn -5.303518 -2.466066 -2.204252 -v 0.044946 -0.088770 0.164063 -vn -3.820870 -3.560950 -3.249249 -v 0.044888 -0.088717 0.164112 -vn -1.192057 -4.996226 -3.406415 -v 0.044803 -0.089308 0.164913 -vn -5.434584 -2.458499 -1.927986 -v 0.044946 -0.089282 0.164686 -vn -5.299439 -2.788848 -1.786659 -v 0.044946 -0.089399 0.164851 -vn -5.312840 -2.970989 -1.430738 -v 0.044946 -0.089902 0.165724 -vn -5.299404 -3.135718 -1.066486 -v 0.044946 -0.090271 0.166662 -vn -5.297967 -2.067057 -2.592021 -v 0.044946 -0.088031 0.163378 -vn -3.827325 -2.384611 -4.181285 -v 0.044888 -0.087163 0.162872 -vn -5.298513 -1.614344 -2.894433 -v 0.044946 -0.087199 0.162810 -vn -5.460834 -1.727060 -2.556206 -v 0.044946 -0.087542 0.163022 -vn -1.191830 -3.023472 -5.236803 -v 0.044803 -0.087143 0.162905 -vn -5.406161 -1.331831 -2.872784 -v 0.044946 -0.086477 0.162449 -vn -5.460566 0.446390 -3.053095 -v 0.044946 -0.082922 0.161968 -vn -5.303666 0.185779 -3.302188 -v 0.044946 -0.083323 0.161925 -vn -3.821015 0.320115 -4.809756 -v 0.044888 -0.083328 0.161997 -vn -1.191892 -0.451858 -6.030043 -v 0.044803 -0.084323 0.162035 -vn -5.434731 -0.025532 -3.123992 -v 0.044946 -0.084129 0.161913 -vn -5.299548 -0.341990 -3.294226 -v 0.044946 -0.084331 0.161925 -vn -5.312950 -0.733749 -3.214725 -v 0.044946 -0.085327 0.162076 -vn -5.299418 -1.121205 -3.116547 -v 0.044946 -0.086290 0.162373 -vn -5.298025 0.737727 -3.232111 -v 0.044946 -0.082326 0.162076 -vn -3.827246 1.782310 -4.471414 -v 0.044888 -0.081389 0.162440 -vn -5.298464 1.256481 -3.066843 -v 0.044946 -0.081363 0.162373 -vn -5.460877 0.921704 -2.943972 -v 0.044946 -0.081743 0.162237 -vn -1.191943 2.209221 -5.628952 -v 0.044803 -0.081403 0.162475 -vn -5.406157 1.415639 -2.832431 -v 0.044946 -0.080631 0.162712 -vn -5.460446 2.665493 -1.554645 -v 0.044946 -0.078038 0.165191 -vn -5.303555 2.697709 -1.913709 -v 0.044946 -0.078255 0.164851 -vn -3.820831 3.960165 -2.748656 -v 0.044888 -0.078314 0.164892 -vn -1.191799 4.432713 -4.112971 -v 0.044803 -0.078964 0.164138 -vn -5.434589 2.426686 -1.967860 -v 0.044946 -0.078748 0.164213 -vn -5.299478 2.362415 -2.321312 -v 0.044946 -0.078883 0.164063 -vn -5.312896 2.055941 -2.578068 -v 0.044946 -0.079622 0.163378 -vn -5.299466 1.737501 -2.819692 -v 0.044946 -0.080455 0.162810 -vn -5.297908 2.987056 -1.438497 -v 0.044946 -0.077751 0.165724 -vn -3.827281 4.607157 -1.394394 -v 0.044888 -0.077452 0.166684 -vn -5.298436 3.181195 -0.929787 -v 0.044946 -0.077383 0.166662 -vn -5.460866 2.876376 -1.114940 -v 0.044946 -0.077513 0.166280 -vn -1.192000 5.778287 -1.782364 -v 0.044803 -0.077488 0.166695 -vn -5.406096 3.097195 -0.659226 -v 0.044946 -0.077192 0.167446 -vn -5.460500 2.877309 1.114624 -v 0.044946 -0.077513 0.171020 -vn -5.303459 3.178319 0.915973 -v 0.044946 -0.077383 0.170638 -vn -3.820838 4.618167 1.382423 -v 0.044888 -0.077452 0.170616 -vn -1.191809 5.979418 0.901230 -v 0.044803 -0.077268 0.169639 -vn -5.434638 3.051480 0.670309 -v 0.044946 -0.077192 0.169854 -vn -5.299448 3.287860 0.399655 -v 0.044946 -0.077159 0.169655 -vn -5.312835 3.297552 -0.000006 -v 0.044946 -0.077083 0.168650 -vn -5.299449 3.287856 -0.399649 -v 0.044946 -0.077159 0.167645 -vn -5.297992 2.986954 1.438459 -v 0.044946 -0.077751 0.171576 -vn -3.827333 3.962708 2.732658 -v 0.044888 -0.078314 0.172408 -vn -5.298367 2.710449 1.907500 -v 0.044946 -0.078255 0.172449 -vn -5.460855 2.665104 1.553695 -v 0.044946 -0.078038 0.172109 -vn -1.192022 4.996174 3.406315 -v 0.044803 -0.078346 0.172387 -vn -5.406068 2.446524 2.010471 -v 0.044946 -0.078748 0.173087 -vn -5.460492 0.922534 2.944533 -v 0.044946 -0.081743 0.175063 -vn -5.303544 1.265443 3.055923 -v 0.044946 -0.081363 0.174927 -vn -3.820853 1.798527 4.472497 -v 0.044888 -0.081389 0.174860 -vn -1.191819 3.023490 5.236795 -v 0.044803 -0.080510 0.174395 -vn -5.434694 1.378476 2.803598 -v 0.044946 -0.080631 0.174588 -vn -5.299465 1.737499 2.819695 -v 0.044946 -0.080455 0.174490 -vn -5.312895 2.055945 2.578064 -v 0.044946 -0.079622 0.173922 -vn -5.299479 2.362411 2.321313 -v 0.044946 -0.078883 0.173237 -vn -5.298028 0.737690 3.232121 -v 0.044946 -0.082326 0.175224 -vn -3.827382 0.334261 4.801771 -v 0.044888 -0.083328 0.175303 -vn -5.298603 0.198615 3.308121 -v 0.044946 -0.083323 0.175375 -vn -5.460834 0.446937 3.052403 -v 0.044946 -0.082922 0.175332 -vn -1.191906 0.451879 6.030040 -v 0.044803 -0.083331 0.175265 -vn -5.406081 -0.046438 3.166254 -v 0.044946 -0.084129 0.175387 -vn -5.460448 -1.726979 2.557206 -v 0.044946 -0.087542 0.174278 -vn -5.303588 -1.600218 2.894644 -v 0.044946 -0.087199 0.174490 -vn -3.820934 -2.375358 4.194630 -v 0.044888 -0.087163 0.174428 -vn -1.191959 -2.209198 5.628961 -v 0.044803 -0.086250 0.174825 -vn -5.434550 -1.332580 2.825928 -v 0.044946 -0.086477 0.174851 -vn -5.299435 -1.121300 3.116495 -v 0.044946 -0.086290 0.174927 -vn -5.312952 -0.733746 3.214724 -v 0.044946 -0.085327 0.175224 -vn -5.299565 -0.341878 3.294222 -v 0.044946 -0.084331 0.175375 -vn -5.297967 -2.067057 2.592021 -v 0.044946 -0.088031 0.173922 -vn -3.827265 -3.545874 3.255301 -v 0.044888 -0.088717 0.173188 -vn -5.298443 -2.462732 2.217968 -v 0.044946 -0.088770 0.173237 -vn -5.460865 -2.107787 2.252524 -v 0.044946 -0.088487 0.173524 -vn -1.191798 -4.432714 4.112975 -v 0.044803 -0.088689 0.173162 -vn -5.406055 -2.504498 1.937808 -v 0.044946 -0.089282 0.172614 -vn -5.460482 -3.076007 0.244186 -v 0.044946 -0.090543 0.169254 -vn -5.303562 -3.260869 0.553701 -v 0.044946 -0.090495 0.169655 -vn -3.820889 -4.760539 0.758194 -v 0.044888 -0.090424 0.169644 -vn -1.192005 -5.778286 1.782372 -v 0.044803 -0.090165 0.170605 -vn -5.434570 -3.040223 0.720102 -v 0.044946 -0.090327 0.170444 -vn -5.299341 -3.135784 1.066535 -v 0.044946 -0.090271 0.170638 -vn -5.312920 -2.970893 1.430702 -v 0.044946 -0.089902 0.171576 -vn -5.299329 -2.789001 1.786674 -v 0.044946 -0.089399 0.172449 -vn -5.277609 3.303262 -0.253588 -v 0.046120 -0.074643 0.168060 -vn -5.201297 3.372696 -0.494135 -v 0.046120 -0.074772 0.167007 -vn -5.281342 3.232160 -0.725986 -v 0.046120 -0.074794 0.166891 -vn -5.278458 3.167282 -0.974188 -v 0.046120 -0.075093 0.165750 -vn -5.036682 3.327556 -1.322460 -v 0.046120 -0.075211 0.165416 -vn -5.278059 2.984088 -1.437060 -v 0.046120 -0.075535 0.164657 -vn -5.037095 3.107563 -1.777156 -v 0.046120 -0.075927 0.163930 -vn -5.278807 2.736098 -1.867866 -v 0.046120 -0.076114 0.163630 -vn -5.281219 2.582928 -2.074466 -v 0.046120 -0.076819 0.162684 -vn -5.187815 2.492764 -2.346921 -v 0.046120 -0.076896 0.162595 -vn -5.274922 2.264518 -2.422449 -v 0.046120 -0.077640 0.161837 -vn -4.971025 2.271243 -2.848034 -v 0.046120 -0.078089 0.161455 -vn -5.277686 1.861241 -2.740621 -v 0.046120 -0.078562 0.161102 -vn -5.201238 1.716547 -2.945033 -v 0.046120 -0.079466 0.160546 -vn -5.281254 1.447700 -2.979729 -v 0.046120 -0.079570 0.160491 -vn -5.278597 1.213101 -3.083506 -v 0.046120 -0.080648 0.160013 -vn -5.036672 1.040776 -3.426124 -v 0.046120 -0.080983 0.159898 -vn -5.278007 0.737029 -3.229108 -v 0.046120 -0.081779 0.159678 -vn -5.036938 0.548085 -3.537777 -v 0.046120 -0.082591 0.159530 -vn -5.278875 0.245517 -3.303693 -v 0.046120 -0.082943 0.159490 -vn -5.281223 -0.011526 -3.312806 -v 0.046120 -0.084122 0.159452 -vn -5.187960 -0.280701 -3.412052 -v 0.046120 -0.084240 0.159456 -vn -5.274832 -0.482048 -3.280954 -v 0.046120 -0.085296 0.159565 -vn -4.970713 -0.810678 -3.551714 -v 0.046120 -0.085875 0.159678 -vn -5.277627 -0.982290 -3.163990 -v 0.046120 -0.086445 0.159828 -vn -5.201162 -1.232277 -3.178333 -v 0.046120 -0.087444 0.160188 -vn -5.281203 -1.427045 -2.989744 -v 0.046120 -0.087552 0.160235 -vn -5.278496 -1.654551 -2.871034 -v 0.046120 -0.088597 0.160780 -vn -5.036820 -2.029700 -2.949730 -v 0.046120 -0.088897 0.160970 -vn -5.278087 -2.065014 -2.589488 -v 0.046120 -0.089565 0.161455 -vn -5.036913 -2.424215 -2.634307 -v 0.046120 -0.090187 0.161998 -vn -5.278880 -2.429845 -2.251764 -v 0.046120 -0.090438 0.162248 -vn -5.281366 -2.597057 -2.056461 -v 0.046120 -0.091202 0.163146 -vn -5.187988 -2.842596 -1.907936 -v 0.046120 -0.091272 0.163241 -vn -5.274932 -2.865607 -1.668694 -v 0.046120 -0.091845 0.164134 -vn -4.970919 -3.282121 -1.580574 -v 0.046120 -0.092118 0.164657 -vn -5.277596 -3.086177 -1.204764 -v 0.046120 -0.092357 0.165196 -vn -5.201314 -3.253071 -1.018182 -v 0.046120 -0.092698 0.166202 -vn -5.281311 -3.227091 -0.748343 -v 0.046120 -0.092729 0.166316 -vn -5.278415 -3.276359 -0.496509 -v 0.046120 -0.092954 0.167473 -vn -5.036672 -3.571832 -0.252271 -v 0.046120 -0.092993 0.167825 -vn -5.278002 -3.312156 -0.000001 -v 0.046120 -0.093030 0.168650 -vn -5.037079 -3.570910 0.252850 -v 0.046120 -0.092993 0.169475 -vn -5.278853 -3.275518 0.495731 -v 0.046120 -0.092954 0.169827 -vn -5.281312 -3.227090 0.748345 -v 0.046120 -0.092729 0.170984 -vn -5.188005 -3.263993 1.032889 -v 0.046120 -0.092698 0.171098 -vn -5.274934 -3.091312 1.200003 -v 0.046120 -0.092357 0.172104 -vn -4.970919 -3.282122 1.580574 -v 0.046120 -0.092118 0.172643 -vn -5.277596 -2.866123 1.661709 -v 0.046120 -0.091845 0.173166 -vn -5.201303 -2.824286 1.908564 -v 0.046120 -0.091272 0.174059 -vn -5.281364 -2.597055 2.056466 -v 0.046120 -0.091202 0.174154 -vn -5.278434 -2.430947 2.251972 -v 0.046120 -0.090438 0.175052 -vn -5.036727 -2.424193 2.635247 -v 0.046120 -0.090187 0.175302 -vn -5.278083 -2.065032 2.589476 -v 0.046120 -0.089565 0.175845 -vn -5.037050 -2.028756 2.949522 -v 0.046120 -0.088897 0.176330 -vn -5.278754 -1.654733 2.870089 -v 0.046120 -0.088597 0.176520 -vn -5.281417 -1.427109 2.989452 -v 0.046120 -0.087552 0.177065 -vn -5.187844 -1.227682 3.195985 -v 0.046120 -0.087444 0.177112 -vn -5.274953 -0.989189 3.165055 -v 0.046120 -0.086445 0.177473 -vn -4.971035 -0.810597 3.551438 -v 0.046120 -0.085875 0.177622 -vn -5.277703 -0.487815 3.276756 -v 0.046120 -0.085296 0.177735 -vn -5.201269 -0.268808 3.398132 -v 0.046120 -0.084240 0.177844 -vn -5.281228 -0.011531 3.312802 -v 0.046120 -0.084122 0.177848 -vn -5.278430 0.245022 3.304676 -v 0.046120 -0.082943 0.177810 -vn -5.036832 0.548839 3.538265 -v 0.046120 -0.082591 0.177770 -vn -5.278215 0.736948 3.228871 -v 0.046120 -0.081779 0.177622 -vn -5.037082 1.041119 3.425096 -v 0.046120 -0.080983 0.177402 -vn -5.279030 1.212173 3.082863 -v 0.046120 -0.080648 0.177287 -vn -5.281250 1.447693 2.979739 -v 0.046120 -0.079570 0.176809 -vn -5.187903 1.733343 2.952421 -v 0.046120 -0.079466 0.176754 -vn -5.275018 1.857737 2.746697 -v 0.046120 -0.078562 0.176198 -vn -4.971025 2.271244 2.848034 -v 0.046120 -0.078089 0.175845 -vn -5.277589 2.257815 2.424513 -v 0.046120 -0.077640 0.175463 -vn -5.201161 2.489337 2.328819 -v 0.046120 -0.076896 0.174705 -vn -5.281366 2.582888 2.074256 -v 0.046120 -0.076819 0.174616 -vn -5.278366 2.736509 1.868938 -v 0.046120 -0.076114 0.173671 -vn -5.036687 3.108644 1.777035 -v 0.046120 -0.075927 0.173370 -vn -5.278059 2.984088 1.437063 -v 0.046120 -0.075535 0.172643 -vn -5.037089 3.326976 1.321538 -v 0.046120 -0.075211 0.171884 -vn -5.278896 3.166186 0.974523 -v 0.046120 -0.075093 0.171550 -vn -5.281343 3.232160 0.725985 -v 0.046120 -0.074794 0.170409 -vn -5.187978 3.388926 0.485618 -v 0.046120 -0.074772 0.170293 -vn -5.274961 3.305805 0.260095 -v 0.046120 -0.074643 0.169240 -vn -4.970908 3.642882 0.000001 -v 0.046120 -0.074624 0.168650 -vn -3.758020 -4.737701 -0.646334 -v 0.046175 -0.093023 0.167464 -vn -3.760343 -4.778866 0.000002 -v 0.046175 -0.093100 0.168650 -vn -3.756000 -4.635314 -1.182979 -v 0.046175 -0.092796 0.166298 -vn -3.760384 -4.437450 -1.773560 -v 0.046175 -0.092422 0.165170 -vn -3.762455 -4.147878 -2.366834 -v 0.046175 -0.091906 0.164100 -vn -3.756163 -3.815890 -2.884414 -v 0.046175 -0.091258 0.163104 -vn -3.758133 -2.448534 -4.106955 -v 0.046175 -0.088634 0.160720 -vn -3.760432 -2.979519 -3.736193 -v 0.046175 -0.089608 0.161400 -vn -3.758024 -3.459233 -3.301085 -v 0.046175 -0.090488 0.162199 -vn -3.756051 -1.965206 -4.361684 -v 0.046175 -0.087580 0.160171 -vn -3.760706 -1.380057 -4.574983 -v 0.046175 -0.086465 0.159761 -vn -3.762725 -0.735680 -4.718605 -v 0.046175 -0.085307 0.159496 -vn -3.756475 -0.124068 -4.781730 -v 0.046175 -0.084124 0.159382 -vn -3.758023 1.684337 -4.474966 -v 0.046175 -0.080624 0.159948 -vn -3.760091 1.063425 -4.659159 -v 0.046175 -0.081763 0.159610 -vn -3.758122 0.424095 -4.762691 -v 0.046175 -0.082936 0.159420 -vn -3.755993 2.184796 -4.255921 -v 0.046175 -0.079538 0.160429 -vn -3.760421 2.716470 -3.931464 -v 0.046175 -0.078522 0.161045 -vn -3.762800 3.230394 -3.517090 -v 0.046175 -0.077593 0.161786 -vn -3.756478 3.661199 -3.078357 -v 0.046175 -0.076766 0.162639 -vn -3.758205 4.548847 -1.473248 -v 0.046175 -0.075026 0.165728 -vn -3.760339 4.305573 -2.073456 -v 0.046175 -0.075472 0.164627 -vn -3.757955 3.988145 -2.637956 -v 0.046175 -0.076055 0.163591 -vn -3.755845 4.689603 -0.945380 -v 0.046175 -0.074725 0.166877 -vn -3.760268 4.767569 -0.327417 -v 0.046175 -0.074573 0.168056 -vn -3.762577 4.763968 0.332751 -v 0.046175 -0.074573 0.169244 -vn -3.756180 4.689502 0.943124 -v 0.046175 -0.074725 0.170423 -vn -3.757951 3.988133 2.637970 -v 0.046175 -0.076055 0.173709 -vn -3.760340 4.305574 2.073454 -v 0.046175 -0.075472 0.172673 -vn -3.758065 4.548904 1.473273 -v 0.046175 -0.075026 0.171572 -vn -3.755947 3.663055 3.077000 -v 0.046175 -0.076766 0.174661 -vn -3.760188 3.228547 3.523331 -v 0.046175 -0.077593 0.175514 -vn -3.762710 2.710068 3.931986 -v 0.046175 -0.078522 0.176255 -vn -3.756341 2.186505 4.254417 -v 0.046175 -0.079538 0.176871 -vn -3.758126 0.424135 4.762671 -v 0.046175 -0.082936 0.177880 -vn -3.760269 1.063343 4.658936 -v 0.046175 -0.081763 0.177690 -vn -3.758032 1.684338 4.474955 -v 0.046175 -0.080624 0.177352 -vn -3.755702 -0.121899 4.782525 -v 0.046175 -0.084124 0.177918 -vn -3.760182 -0.741675 4.720852 -v 0.046175 -0.085307 0.177804 -vn -3.762590 -1.384471 4.570480 -v 0.046175 -0.086465 0.177539 -vn -3.756519 -1.962949 4.361906 -v 0.046175 -0.087580 0.177129 -vn -3.758042 -3.459202 3.301089 -v 0.046175 -0.090488 0.175101 -vn -3.760429 -2.979510 3.736196 -v 0.046175 -0.089608 0.175900 -vn -3.757984 -2.448652 4.107133 -v 0.046175 -0.088634 0.176580 -vn -3.755826 -3.814995 2.886496 -v 0.046175 -0.091258 0.174196 -vn -3.760158 -4.153421 2.363583 -v 0.046175 -0.091906 0.173200 -vn -3.762673 -4.436536 1.767218 -v 0.046175 -0.092422 0.172130 -vn -3.756341 -4.634237 1.184981 -v 0.046175 -0.092796 0.171002 -vn -3.758017 -4.737702 0.646329 -v 0.046175 -0.093023 0.169836 -vn -1.350131 -5.858923 0.755397 -v 0.046255 -0.093062 0.169841 -vn -1.350008 -5.714194 1.498433 -v 0.046255 -0.092834 0.171012 -vn -1.350204 -5.475616 2.216841 -v 0.046255 -0.092458 0.172144 -vn -1.350010 -5.147280 2.898893 -v 0.046255 -0.091940 0.173219 -vn -1.349768 -4.734360 3.533330 -v 0.046255 -0.091289 0.174219 -vn -1.349877 -4.243581 4.109679 -v 0.046255 -0.090516 0.175128 -vn -1.349991 -3.683172 4.618565 -v 0.046255 -0.089632 0.175930 -vn -1.350496 -3.062355 5.051682 -v 0.046255 -0.088654 0.176613 -vn -1.350255 -2.391187 5.401731 -v 0.046255 -0.087596 0.177165 -vn -1.350332 -1.680801 5.663254 -v 0.046255 -0.086476 0.177577 -vn -1.349985 -0.942837 5.831771 -v 0.046255 -0.085313 0.177842 -vn -1.349851 -0.189364 5.904489 -v 0.046255 -0.084125 0.177957 -vn -1.350152 0.567243 5.880071 -v 0.046255 -0.082933 0.177919 -vn -1.350011 1.314550 5.759394 -v 0.046255 -0.081755 0.177728 -vn -1.349866 2.040224 5.543978 -v 0.046255 -0.080611 0.177389 -vn -1.350247 2.732419 5.237478 -v 0.046255 -0.079520 0.176906 -vn -1.349673 3.379674 4.845046 -v 0.046255 -0.078499 0.176287 -vn -1.350020 3.971599 4.373140 -v 0.046255 -0.077567 0.175543 -vn -1.350236 4.498196 3.829371 -v 0.046255 -0.076737 0.174686 -vn -1.350121 4.950953 3.222703 -v 0.046255 -0.076023 0.173730 -vn -1.349878 5.322373 2.563135 -v 0.046255 -0.075437 0.172690 -vn -1.350160 5.606464 1.861464 -v 0.046255 -0.074990 0.171584 -vn -1.350087 5.798562 1.129241 -v 0.046255 -0.074687 0.170430 -vn -1.350071 5.895276 0.378474 -v 0.046255 -0.074534 0.169247 -vn -1.350078 5.895276 -0.378475 -v 0.046255 -0.074534 0.168053 -vn -1.350083 5.798564 -1.129233 -v 0.046255 -0.074687 0.166870 -vn -1.350115 5.606377 -1.861483 -v 0.046255 -0.074990 0.165716 -vn -1.350103 5.322388 -2.563119 -v 0.046255 -0.075437 0.164610 -vn -1.350124 4.950958 -3.222699 -v 0.046255 -0.076023 0.163570 -vn -1.350152 4.498056 -3.829293 -v 0.046255 -0.076737 0.162614 -vn -1.349933 3.971457 -4.373028 -v 0.046255 -0.077567 0.161757 -vn -1.350101 3.379696 -4.845055 -v 0.046255 -0.078499 0.161013 -vn -1.350263 2.732386 -5.237494 -v 0.046255 -0.079520 0.160394 -vn -1.349871 2.040242 -5.543970 -v 0.046255 -0.080611 0.159911 -vn -1.350008 1.314551 -5.759398 -v 0.046255 -0.081755 0.159572 -vn -1.350152 0.567262 -5.880075 -v 0.046255 -0.082933 0.159381 -vn -1.350242 -0.189337 -5.904266 -v 0.046255 -0.084125 0.159343 -vn -1.349873 -0.942787 -5.831546 -v 0.046255 -0.085313 0.159458 -vn -1.350223 -1.680755 -5.663028 -v 0.046255 -0.086476 0.159723 -vn -1.350261 -2.391181 -5.401737 -v 0.046255 -0.087596 0.160135 -vn -1.350050 -3.062338 -5.051659 -v 0.046255 -0.088654 0.160687 -vn -1.349989 -3.683176 -4.618567 -v 0.046255 -0.089632 0.161370 -vn -1.350240 -4.243609 -4.109667 -v 0.046255 -0.090516 0.162172 -vn -1.349776 -4.734352 -3.533341 -v 0.046255 -0.091289 0.163081 -vn -1.350009 -5.147284 -2.898896 -v 0.046255 -0.091940 0.164081 -vn -1.350201 -5.475625 -2.216828 -v 0.046255 -0.092458 0.165156 -vn -1.350012 -5.714189 -1.498444 -v 0.046255 -0.092834 0.166288 -vn -1.350132 -5.858924 -0.755392 -v 0.046255 -0.093062 0.167459 -vn -1.350114 -5.907377 -0.000001 -v 0.046255 -0.093138 0.168650 -vn 1.326445 -5.864121 0.756106 -v 0.046344 -0.093062 0.169841 -vn 1.326599 -5.719285 1.499775 -v 0.046344 -0.092834 0.171012 -vn 1.326436 -5.480565 2.218866 -v 0.046344 -0.092458 0.172144 -vn 1.326431 -5.151829 2.901476 -v 0.046344 -0.091940 0.173219 -vn 1.326359 -4.738613 3.536514 -v 0.046344 -0.091289 0.174219 -vn 1.326427 -4.247480 4.113435 -v 0.046344 -0.090516 0.175128 -vn 1.326713 -3.686495 4.622690 -v 0.046344 -0.089633 0.175930 -vn 1.326369 -3.065010 5.056049 -v 0.046344 -0.088654 0.176613 -vn 1.326490 -2.393350 5.406603 -v 0.046344 -0.087596 0.177165 -vn 1.326184 -1.682300 5.668323 -v 0.046344 -0.086476 0.177577 -vn 1.326393 -0.943666 5.836899 -v 0.046344 -0.085313 0.177842 -vn 1.326144 -0.189530 5.909830 -v 0.046344 -0.084125 0.177957 -vn 1.326390 0.567750 5.885403 -v 0.046344 -0.082933 0.177919 -vn 1.326612 1.315657 5.764311 -v 0.046344 -0.081755 0.177728 -vn 1.326558 2.042044 5.548868 -v 0.046344 -0.080611 0.177389 -vn 1.326466 2.734810 5.242111 -v 0.046344 -0.079520 0.176906 -vn 1.326601 3.382876 4.849585 -v 0.046344 -0.078499 0.176287 -vn 1.326316 3.975163 4.377100 -v 0.046344 -0.077566 0.175543 -vn 1.326258 4.502190 3.832770 -v 0.046344 -0.076736 0.174686 -vn 1.326420 4.955324 3.225578 -v 0.046344 -0.076023 0.173730 -vn 1.326600 5.327196 2.565443 -v 0.046344 -0.075437 0.172690 -vn 1.326425 5.611454 1.863139 -v 0.046344 -0.074989 0.171584 -vn 1.326352 5.803615 1.130272 -v 0.046344 -0.074687 0.170430 -vn 1.326327 5.900614 0.378835 -v 0.046344 -0.074534 0.169247 -vn 1.326334 5.900611 -0.378837 -v 0.046344 -0.074534 0.168053 -vn 1.326355 5.803612 -1.130272 -v 0.046344 -0.074687 0.166870 -vn 1.326579 5.611469 -1.863114 -v 0.046344 -0.074989 0.165716 -vn 1.326555 5.327087 -2.565427 -v 0.046344 -0.075437 0.164610 -vn 1.326426 4.955321 -3.225585 -v 0.046344 -0.076023 0.163570 -vn 1.326581 4.502215 -3.832766 -v 0.046344 -0.076736 0.162614 -vn 1.326689 3.975192 -4.377100 -v 0.046344 -0.077566 0.161757 -vn 1.326527 3.382735 -4.849432 -v 0.046344 -0.078499 0.161013 -vn 1.326477 2.734793 -5.242122 -v 0.046344 -0.079520 0.160394 -vn 1.326552 2.042060 -5.548866 -v 0.046344 -0.080611 0.159911 -vn 1.326220 1.315703 -5.764509 -v 0.046344 -0.081755 0.159572 -vn 1.326384 0.567771 -5.885410 -v 0.046344 -0.082933 0.159381 -vn 1.326544 -0.189526 -5.909607 -v 0.046344 -0.084125 0.159343 -vn 1.326914 -0.943671 -5.836924 -v 0.046344 -0.085313 0.159458 -vn 1.326685 -1.682331 -5.668334 -v 0.046344 -0.086476 0.159723 -vn 1.326514 -2.393351 -5.406600 -v 0.046344 -0.087596 0.160135 -vn 1.326795 -3.065019 -5.056071 -v 0.046344 -0.088654 0.160687 -vn 1.326391 -3.686604 -4.622826 -v 0.046344 -0.089633 0.161370 -vn 1.326339 -4.247344 -4.113331 -v 0.046344 -0.090516 0.162172 -vn 1.326357 -4.738622 -3.536509 -v 0.046344 -0.091289 0.163081 -vn 1.326243 -5.151927 -2.901510 -v 0.046344 -0.091940 0.164081 -vn 1.326436 -5.480566 -2.218859 -v 0.046344 -0.092458 0.165156 -vn 1.326602 -5.719283 -1.499787 -v 0.046344 -0.092834 0.166288 -vn 1.326445 -5.864124 -0.756102 -v 0.046344 -0.093062 0.167459 -vn 1.326419 -5.912723 0.000002 -v 0.046344 -0.093139 0.168650 -vn 3.755080 -4.735192 0.610535 -v 0.046425 -0.093024 0.169836 -vn 3.755070 -4.618275 1.211030 -v 0.046425 -0.092797 0.171002 -vn 3.755067 -4.425424 1.791661 -v 0.046425 -0.092422 0.172130 -vn 3.755017 -4.160063 2.342891 -v 0.046425 -0.091907 0.173201 -vn 3.754812 -3.826339 2.855667 -v 0.046425 -0.091258 0.174196 -vn 3.754754 -3.429771 3.321588 -v 0.046425 -0.090488 0.175101 -vn 3.755041 -2.976833 3.732826 -v 0.046425 -0.089609 0.175900 -vn 3.755298 -2.474993 4.082724 -v 0.046425 -0.088634 0.176580 -vn 3.755107 -1.932597 4.365737 -v 0.046425 -0.087580 0.177130 -vn 3.755020 -1.358415 4.577049 -v 0.046425 -0.086465 0.177540 -vn 3.755038 -0.761992 4.713221 -v 0.046425 -0.085307 0.177804 -vn 3.754765 -0.153025 4.771985 -v 0.046425 -0.084124 0.177918 -vn 3.755055 0.458438 4.752227 -v 0.046425 -0.082936 0.177880 -vn 3.755185 1.062432 4.654754 -v 0.046425 -0.081763 0.177691 -vn 3.754990 1.648946 4.480692 -v 0.046425 -0.080624 0.177353 -vn 3.755159 2.208317 4.232977 -v 0.046425 -0.079538 0.176872 -vn 3.754736 2.731551 3.915894 -v 0.046425 -0.078521 0.176256 -vn 3.754808 3.209938 3.534488 -v 0.046425 -0.077592 0.175515 -vn 3.755046 3.635425 3.094888 -v 0.046425 -0.076766 0.174661 -vn 3.755008 4.001449 2.604627 -v 0.046425 -0.076055 0.173709 -vn 3.754976 4.301598 2.071555 -v 0.046425 -0.075472 0.172674 -vn 3.755112 4.531088 1.504455 -v 0.046425 -0.075026 0.171572 -vn 3.755041 4.686409 0.912667 -v 0.046425 -0.074725 0.170423 -vn 3.754937 4.764602 0.305895 -v 0.046425 -0.074573 0.169244 -vn 3.754918 4.764623 -0.305887 -v 0.046425 -0.074573 0.168056 -vn 3.755034 4.686410 -0.912668 -v 0.046425 -0.074725 0.166877 -vn 3.755056 4.531168 -1.504458 -v 0.046425 -0.075026 0.165728 -vn 3.755076 4.301634 -2.071546 -v 0.046425 -0.075472 0.164626 -vn 3.755014 4.001441 -2.604636 -v 0.046425 -0.076055 0.163591 -vn 3.755050 3.635429 -3.094873 -v 0.046425 -0.076766 0.162639 -vn 3.754816 3.209927 -3.534491 -v 0.046425 -0.077592 0.161785 -vn 3.755083 2.731473 -3.915766 -v 0.046425 -0.078521 0.161044 -vn 3.755155 2.208326 -4.232978 -v 0.046425 -0.079538 0.160428 -vn 3.754996 1.648950 -4.480691 -v 0.046425 -0.080624 0.159947 -vn 3.754937 1.062421 -4.654692 -v 0.046425 -0.081763 0.159609 -vn 3.754886 0.458452 -4.752465 -v 0.046425 -0.082936 0.159420 -vn 3.755186 -0.153014 -4.771810 -v 0.046425 -0.084124 0.159382 -vn 3.754855 -0.762051 -4.713457 -v 0.046425 -0.085307 0.159496 -vn 3.755020 -1.358417 -4.577048 -v 0.046425 -0.086465 0.159760 -vn 3.755094 -1.932598 -4.365751 -v 0.046425 -0.087580 0.160170 -vn 3.755145 -2.475087 -4.082914 -v 0.046425 -0.088634 0.160720 -vn 3.754855 -2.976785 -3.732793 -v 0.046425 -0.089609 0.161400 -vn 3.755060 -3.429693 -3.321480 -v 0.046425 -0.090488 0.162199 -vn 3.754816 -3.826341 -2.855668 -v 0.046425 -0.091258 0.163104 -vn 3.754794 -4.160134 -2.342947 -v 0.046425 -0.091907 0.164099 -vn 3.755062 -4.425429 -1.791662 -v 0.046425 -0.092422 0.165170 -vn 3.755065 -4.618278 -1.211031 -v 0.046425 -0.092797 0.166298 -vn 3.755059 -4.735221 -0.610532 -v 0.046425 -0.093024 0.167464 -vn 3.754978 -4.774413 0.000003 -v 0.046425 -0.093100 0.168650 -vn 5.471231 -2.671638 0.344461 -v 0.046480 -0.092955 0.169827 -vn 5.471200 -2.605657 0.683286 -v 0.046480 -0.092729 0.170985 -vn 5.471277 -2.496848 1.010856 -v 0.046480 -0.092358 0.172104 -vn 5.471208 -2.347113 1.321866 -v 0.046480 -0.091846 0.173166 -vn 5.471243 -2.158805 1.611146 -v 0.046480 -0.091203 0.174155 -vn 5.471205 -1.935067 1.874003 -v 0.046480 -0.090438 0.175053 -vn 5.471143 -1.679597 2.106169 -v 0.046480 -0.089565 0.175846 -vn 5.471166 -1.396493 2.303641 -v 0.046480 -0.088598 0.176520 -vn 5.471220 -1.090406 2.463227 -v 0.046480 -0.087552 0.177066 -vn 5.471259 -0.766441 2.582401 -v 0.046480 -0.086445 0.177473 -vn 5.471202 -0.429933 2.659301 -v 0.046480 -0.085296 0.177736 -vn 5.471316 -0.086347 2.692286 -v 0.046480 -0.084122 0.177849 -vn 5.471363 0.258649 2.681177 -v 0.046480 -0.082943 0.177811 -vn 5.471072 0.599464 2.626406 -v 0.046480 -0.081779 0.177623 -vn 5.471164 0.930338 2.528047 -v 0.046480 -0.080648 0.177287 -vn 5.471185 1.245996 2.388321 -v 0.046480 -0.079570 0.176810 -vn 5.471303 1.541078 2.209271 -v 0.046480 -0.078561 0.176199 -vn 5.471173 1.811053 1.994161 -v 0.046480 -0.077639 0.175463 -vn 5.471262 2.051129 1.746159 -v 0.046480 -0.076819 0.174616 -vn 5.471147 2.257662 1.469567 -v 0.046480 -0.076113 0.173671 -vn 5.471235 2.427000 1.168766 -v 0.046480 -0.075535 0.172643 -vn 5.471285 2.556481 0.848814 -v 0.046480 -0.075092 0.171550 -vn 5.471167 2.644121 0.514944 -v 0.046480 -0.074793 0.170409 -vn 5.471277 2.688151 0.172573 -v 0.046480 -0.074642 0.169240 -vn 5.471265 2.688156 -0.172588 -v 0.046480 -0.074642 0.168060 -vn 5.471168 2.644120 -0.514952 -v 0.046480 -0.074793 0.166891 -vn 5.471222 2.556525 -0.848838 -v 0.046480 -0.075092 0.165750 -vn 5.471154 2.427048 -1.168812 -v 0.046480 -0.075535 0.164657 -vn 5.471133 2.257706 -1.469608 -v 0.046480 -0.076113 0.163629 -vn 5.471260 2.051135 -1.746153 -v 0.046480 -0.076819 0.162684 -vn 5.471170 1.811045 -1.994169 -v 0.046480 -0.077639 0.161837 -vn 5.471301 1.541090 -2.209262 -v 0.046480 -0.078561 0.161101 -vn 5.471189 1.245988 -2.388321 -v 0.046480 -0.079570 0.160490 -vn 5.471166 0.930343 -2.528042 -v 0.046480 -0.080648 0.160013 -vn 5.471279 0.599415 -2.626167 -v 0.046480 -0.081779 0.159677 -vn 5.471163 0.258659 -2.681328 -v 0.046480 -0.082943 0.159489 -vn 5.471325 -0.086333 -2.692280 -v 0.046480 -0.084122 0.159451 -vn 5.471007 -0.429973 -2.659444 -v 0.046480 -0.085296 0.159564 -vn 5.471258 -0.766440 -2.582404 -v 0.046480 -0.086445 0.159827 -vn 5.471225 -1.090391 -2.463227 -v 0.046480 -0.087552 0.160234 -vn 5.470998 -1.396560 -2.303750 -v 0.046480 -0.088598 0.160780 -vn 5.471309 -1.679481 -2.106010 -v 0.046480 -0.089565 0.161454 -vn 5.471206 -1.935070 -1.873998 -v 0.046480 -0.090438 0.162247 -vn 5.471244 -2.158796 -1.611154 -v 0.046480 -0.091203 0.163145 -vn 5.471202 -2.347117 -1.321866 -v 0.046480 -0.091846 0.164134 -vn 5.471278 -2.496848 -1.010854 -v 0.046480 -0.092358 0.165196 -vn 5.471201 -2.605655 -0.683285 -v 0.046480 -0.092729 0.166315 -vn 5.471203 -2.671656 -0.344481 -v 0.046480 -0.092955 0.167473 -vn 5.471247 -2.693715 -0.000002 -v 0.046480 -0.093030 0.168650 -vn 6.197522 -0.721756 0.093065 -v 0.046500 -0.092869 0.169816 -vn 6.197532 -0.703885 0.184577 -v 0.046500 -0.092645 0.170962 -vn 6.197518 -0.674563 0.273103 -v 0.046500 -0.092277 0.172071 -vn 6.197532 -0.634047 0.357086 -v 0.046500 -0.091770 0.173124 -vn 6.197519 -0.583222 0.435270 -v 0.046500 -0.091133 0.174103 -vn 6.197527 -0.522749 0.506253 -v 0.046500 -0.090376 0.174992 -vn 6.197512 -0.453755 0.568993 -v 0.046500 -0.089511 0.175778 -vn 6.197506 -0.377283 0.622373 -v 0.046500 -0.088553 0.176446 -vn 6.197515 -0.294588 0.665478 -v 0.046500 -0.087517 0.176986 -vn 6.197513 -0.207067 0.697684 -v 0.046500 -0.086421 0.177390 -vn 6.197506 -0.116154 0.718468 -v 0.046500 -0.085282 0.177650 -vn 6.197513 -0.023325 0.727394 -v 0.046500 -0.084119 0.177762 -vn 6.197514 0.069881 0.724407 -v 0.046500 -0.082951 0.177725 -vn 6.197515 0.161943 0.709511 -v 0.046500 -0.081798 0.177538 -vn 6.197531 0.251317 0.682908 -v 0.046500 -0.080678 0.177206 -vn 6.197521 0.336603 0.645206 -v 0.046500 -0.079610 0.176733 -vn 6.197525 0.416342 0.596859 -v 0.046500 -0.078611 0.176127 -vn 6.197525 0.489240 0.538712 -v 0.046500 -0.077698 0.175399 -vn 6.197515 0.554146 0.471750 -v 0.046500 -0.076885 0.174560 -vn 6.197533 0.609867 0.396980 -v 0.046500 -0.076186 0.173623 -vn 6.197516 0.655684 0.315762 -v 0.046500 -0.075613 0.172606 -vn 6.197511 0.690693 0.229326 -v 0.046500 -0.075175 0.171523 -vn 6.197530 0.714278 0.139105 -v 0.046500 -0.074878 0.170393 -vn 6.197526 0.726218 0.046626 -v 0.046500 -0.074729 0.169234 -vn 6.197528 0.726211 -0.046621 -v 0.046500 -0.074729 0.168066 -vn 6.197529 0.714277 -0.139101 -v 0.046500 -0.074878 0.166907 -vn 6.197522 0.690658 -0.229312 -v 0.046500 -0.075175 0.165777 -vn 6.197527 0.655641 -0.315736 -v 0.046500 -0.075613 0.164694 -vn 6.197516 0.609919 -0.397019 -v 0.046500 -0.076186 0.163677 -vn 6.197515 0.554143 -0.471753 -v 0.046500 -0.076885 0.162740 -vn 6.197526 0.489242 -0.538711 -v 0.046500 -0.077698 0.161901 -vn 6.197523 0.416342 -0.596858 -v 0.046500 -0.078611 0.161173 -vn 6.197521 0.336602 -0.645207 -v 0.046500 -0.079610 0.160567 -vn 6.197533 0.251321 -0.682906 -v 0.046500 -0.080678 0.160094 -vn 6.197515 0.161941 -0.709509 -v 0.046500 -0.081798 0.159762 -vn 6.197539 0.069874 -0.724291 -v 0.046500 -0.082951 0.159575 -vn 6.197514 -0.023328 -0.727390 -v 0.046500 -0.084119 0.159538 -vn 6.197533 -0.116135 -0.718355 -v 0.046500 -0.085282 0.159650 -vn 6.197514 -0.207069 -0.697681 -v 0.046500 -0.086421 0.159910 -vn 6.197514 -0.294586 -0.665477 -v 0.046500 -0.087517 0.160314 -vn 6.197529 -0.377232 -0.622288 -v 0.046500 -0.088553 0.160854 -vn 6.197514 -0.453759 -0.568990 -v 0.046500 -0.089511 0.161522 -vn 6.197526 -0.522747 -0.506256 -v 0.046500 -0.090376 0.162308 -vn 6.197520 -0.583222 -0.435269 -v 0.046500 -0.091133 0.163197 -vn 6.197532 -0.634046 -0.357091 -v 0.046500 -0.091770 0.164176 -vn 6.197516 -0.674564 -0.273095 -v 0.046500 -0.092277 0.165229 -vn 6.197533 -0.703885 -0.184582 -v 0.046500 -0.092645 0.166338 -vn 6.197525 -0.721742 -0.093055 -v 0.046500 -0.092869 0.167484 -vn 6.197528 -0.727708 -0.000000 -v 0.046500 -0.092944 0.168650 -vn 6.264976 -0.335638 0.035276 -v 0.046500 -0.075515 0.167776 -vn 6.264975 -0.330112 0.070167 -v 0.046500 -0.075652 0.166912 -vn 6.264976 -0.320969 0.104289 -v 0.046500 -0.075878 0.166067 -vn 6.264977 -0.308308 0.137267 -v 0.046500 -0.076191 0.165251 -vn 6.264976 -0.292274 0.168744 -v 0.046500 -0.076589 0.164471 -vn 6.264976 -0.273035 0.198372 -v 0.046500 -0.077065 0.163737 -vn 6.264976 -0.250803 0.225823 -v 0.046500 -0.077616 0.163057 -vn 6.264977 -0.225822 0.250800 -v 0.046500 -0.078234 0.162439 -vn 6.264976 -0.198369 0.273032 -v 0.046500 -0.078914 0.161888 -vn 6.264976 -0.168742 0.292275 -v 0.046500 -0.079648 0.161412 -vn 6.264975 -0.137269 0.308312 -v 0.046500 -0.080427 0.161015 -vn 6.264976 -0.104291 0.320969 -v 0.046500 -0.081244 0.160701 -vn 6.264976 -0.070168 0.330115 -v 0.046500 -0.082089 0.160475 -vn 6.264976 -0.035277 0.335642 -v 0.046500 -0.082953 0.160338 -vn 6.264976 -0.000001 0.337487 -v 0.046500 -0.083827 0.160292 -vn 6.264976 0.035278 0.335643 -v 0.046500 -0.084700 0.160338 -vn 6.264976 0.070168 0.330114 -v 0.046500 -0.085565 0.160475 -vn 6.264976 0.104290 0.320969 -v 0.046500 -0.086410 0.160701 -vn 6.264975 0.137269 0.308313 -v 0.046500 -0.087226 0.161015 -vn 6.264977 0.168743 0.292274 -v 0.046500 -0.088006 0.161412 -vn 6.264977 0.198368 0.273032 -v 0.046500 -0.088739 0.161888 -vn 6.264976 0.225822 0.250800 -v 0.046500 -0.089419 0.162439 -vn 6.264976 0.250804 0.225824 -v 0.046500 -0.090038 0.163057 -vn 6.264975 0.273036 0.198371 -v 0.046500 -0.090588 0.163737 -vn 6.264976 0.292273 0.168744 -v 0.046500 -0.091065 0.164471 -vn 6.264976 0.308307 0.137268 -v 0.046500 -0.091462 0.165251 -vn 6.264976 0.035277 -0.335642 -v 0.046500 -0.084700 0.176962 -vn 6.264977 0.000001 -0.337487 -v 0.046500 -0.083827 0.177008 -vn 6.264976 -0.035280 -0.335641 -v 0.046500 -0.082953 0.176962 -vn 6.264977 -0.070165 -0.330109 -v 0.046500 -0.082089 0.176825 -vn 6.264976 -0.104290 -0.320969 -v 0.046500 -0.081244 0.176599 -vn 6.264976 -0.137270 -0.308311 -v 0.046500 -0.080427 0.176285 -vn 6.264976 -0.168740 -0.292269 -v 0.046500 -0.079648 0.175888 -vn 6.264975 -0.198375 -0.273037 -v 0.046500 -0.078914 0.175412 -vn 6.264976 -0.225825 -0.250805 -v 0.046500 -0.078234 0.174861 -vn 6.264976 -0.250802 -0.225824 -v 0.046500 -0.077616 0.174243 -vn 6.264976 -0.273036 -0.198371 -v 0.046500 -0.077065 0.173563 -vn 6.264976 -0.292273 -0.168744 -v 0.046500 -0.076589 0.172829 -vn 6.264977 -0.308307 -0.137268 -v 0.046500 -0.076191 0.172049 -vn 6.264976 -0.320969 -0.104288 -v 0.046500 -0.075878 0.171233 -vn 6.264976 -0.330112 -0.070167 -v 0.046500 -0.075652 0.170388 -vn 6.264976 -0.335638 -0.035277 -v 0.046500 -0.075515 0.169524 -vn 6.264976 -0.337488 0.000000 -v 0.046500 -0.075469 0.168650 -vn 6.264976 0.320969 0.104288 -v 0.046500 -0.091776 0.166067 -vn 6.264976 0.330112 0.070167 -v 0.046500 -0.092002 0.166912 -vn 6.264976 0.335638 0.035277 -v 0.046500 -0.092139 0.167776 -vn 6.264975 0.337488 -0.000000 -v 0.046500 -0.092185 0.168650 -vn 6.264976 0.335638 -0.035276 -v 0.046500 -0.092139 0.169524 -vn 6.264976 0.198372 -0.273036 -v 0.046500 -0.088739 0.175412 -vn 6.264977 0.168742 -0.292267 -v 0.046500 -0.088006 0.175888 -vn 6.264975 0.137269 -0.308312 -v 0.046500 -0.087226 0.176285 -vn 6.264976 0.104289 -0.320968 -v 0.046500 -0.086410 0.176599 -vn 6.264977 0.070168 -0.330109 -v 0.046500 -0.085565 0.176825 -vn 6.264975 0.330112 -0.070167 -v 0.046500 -0.092002 0.170388 -vn 6.264976 0.320969 -0.104289 -v 0.046500 -0.091776 0.171233 -vn 6.264977 0.308308 -0.137267 -v 0.046500 -0.091462 0.172049 -vn 6.264975 0.292274 -0.168744 -v 0.046500 -0.091065 0.172829 -vn 6.264976 0.273035 -0.198372 -v 0.046500 -0.090588 0.173563 -vn 6.264975 0.250802 -0.225823 -v 0.046500 -0.090038 0.174243 -vn 6.264976 0.225825 -0.250806 -v 0.046500 -0.089419 0.174861 -vn 6.099600 1.350523 -0.141943 -v 0.046426 -0.091480 0.169454 -vn 6.099599 1.328288 -0.282333 -v 0.046426 -0.091354 0.170250 -vn 6.099600 1.291497 -0.419631 -v 0.046426 -0.091146 0.171028 -vn 6.099597 1.240565 -0.552338 -v 0.046426 -0.090857 0.171780 -vn 6.099599 1.176033 -0.678975 -v 0.046426 -0.090491 0.172498 -vn 6.099601 1.098613 -0.798192 -v 0.046426 -0.090052 0.173173 -vn 6.099603 1.009156 -0.908649 -v 0.046426 -0.089546 0.173799 -vn 6.099602 0.908649 -1.009162 -v 0.046426 -0.088976 0.174369 -vn 6.099602 0.798183 -1.098617 -v 0.046426 -0.088350 0.174876 -vn 6.099599 0.678983 -1.176030 -v 0.046426 -0.087674 0.175314 -vn 6.099597 0.552337 -1.240565 -v 0.046426 -0.086957 0.175680 -vn 6.099600 0.419635 -1.291497 -v 0.046426 -0.086205 0.175969 -vn 6.099592 0.282340 -1.328304 -v 0.046426 -0.085427 0.176177 -vn 6.099602 0.141951 -1.350519 -v 0.046426 -0.084631 0.176303 -vn 6.099602 0.000003 -1.357956 -v 0.046426 -0.083827 0.176345 -vn 6.099599 -0.141952 -1.350526 -v 0.046426 -0.083022 0.176303 -vn 6.099592 -0.282347 -1.328303 -v 0.046426 -0.082227 0.176177 -vn 6.099601 -0.419627 -1.291496 -v 0.046426 -0.081449 0.175969 -vn 6.099597 -0.552344 -1.240564 -v 0.046426 -0.080697 0.175680 -vn 6.099599 -0.678976 -1.176028 -v 0.046426 -0.079979 0.175314 -vn 6.099602 -0.798182 -1.098614 -v 0.046426 -0.079304 0.174876 -vn 6.099602 -0.908650 -1.009160 -v 0.046426 -0.078678 0.174369 -vn 6.099602 -1.009152 -0.908655 -v 0.046426 -0.078108 0.173799 -vn 6.099599 -1.098618 -0.798189 -v 0.046426 -0.077601 0.173173 -vn 6.099599 -1.176034 -0.678979 -v 0.046426 -0.077162 0.172498 -vn 6.099597 -1.240567 -0.552334 -v 0.046426 -0.076797 0.171780 -vn 6.099601 -1.291494 -0.419633 -v 0.046426 -0.076508 0.171028 -vn 6.099598 -1.328291 -0.282335 -v 0.046426 -0.076300 0.170250 -vn 6.099596 -1.350534 -0.141945 -v 0.046426 -0.076174 0.169454 -vn 6.099595 -1.357974 0.000000 -v 0.046426 -0.076131 0.168650 -vn 6.099596 -1.350533 0.141947 -v 0.046426 -0.076174 0.167846 -vn 6.099599 -1.328288 0.282333 -v 0.046426 -0.076300 0.167050 -vn 6.099600 -1.291497 0.419631 -v 0.046426 -0.076508 0.166272 -vn 6.099597 -1.240565 0.552338 -v 0.046426 -0.076797 0.165520 -vn 6.099599 -1.176033 0.678975 -v 0.046426 -0.077162 0.164802 -vn 6.099600 -1.098617 0.798191 -v 0.046426 -0.077601 0.164127 -vn 6.099599 -1.009161 0.908658 -v 0.046426 -0.078108 0.163501 -vn 6.099602 -0.908647 1.009158 -v 0.046426 -0.078678 0.162931 -vn 6.099600 -0.798190 1.098608 -v 0.046426 -0.079304 0.162424 -vn 6.099600 -0.678977 1.176029 -v 0.046426 -0.079979 0.161986 -vn 6.099595 -0.552331 1.240574 -v 0.046426 -0.080697 0.161620 -vn 6.099600 -0.419642 1.291494 -v 0.046426 -0.081449 0.161331 -vn 6.099601 -0.282339 1.328286 -v 0.046426 -0.082227 0.161123 -vn 6.099600 -0.141941 1.350525 -v 0.046426 -0.083022 0.160997 -vn 6.099602 -0.000003 1.357956 -v 0.046426 -0.083827 0.160955 -vn 6.099599 0.141945 1.350526 -v 0.046426 -0.084631 0.160997 -vn 6.099601 0.282340 1.328286 -v 0.046426 -0.085427 0.161123 -vn 6.099599 0.419639 1.291498 -v 0.046426 -0.086205 0.161331 -vn 6.099595 0.552335 1.240572 -v 0.046426 -0.086957 0.161620 -vn 6.099601 0.678977 1.176026 -v 0.046426 -0.087674 0.161986 -vn 6.099601 0.798188 1.098609 -v 0.046426 -0.088350 0.162424 -vn 6.099602 0.908646 1.009160 -v 0.046426 -0.088976 0.162931 -vn 6.099598 1.009163 0.908657 -v 0.046426 -0.089546 0.163501 -vn 6.099599 1.098618 0.798189 -v 0.046426 -0.090052 0.164127 -vn 6.099599 1.176034 0.678979 -v 0.046426 -0.090491 0.164802 -vn 6.099597 1.240567 0.552334 -v 0.046426 -0.090857 0.165520 -vn 6.099601 1.291494 0.419633 -v 0.046426 -0.091146 0.166272 -vn 6.099599 1.328290 0.282333 -v 0.046426 -0.091354 0.167050 -vn 6.099598 1.350525 0.141943 -v 0.046426 -0.091480 0.167846 -vn 6.099599 1.357963 -0.000000 -v 0.046426 -0.091522 0.168650 -vn 5.810078 2.361813 -0.247060 -v 0.046207 -0.090854 0.169389 -vn 5.809417 2.323936 -0.495128 -v 0.046207 -0.090738 0.170119 -vn 5.809666 2.259662 -0.732971 -v 0.046207 -0.090547 0.170833 -vn 5.809457 2.170135 -0.967444 -v 0.046207 -0.090282 0.171524 -vn 5.810156 2.056369 -1.187235 -v 0.046207 -0.089946 0.172183 -vn 5.810160 1.920988 -1.395693 -v 0.046207 -0.089543 0.172803 -vn 5.811672 1.760597 -1.588335 -v 0.046207 -0.089078 0.173378 -vn 5.810650 1.590576 -1.761546 -v 0.046207 -0.088555 0.173901 -vn 5.810081 1.394860 -1.921855 -v 0.046207 -0.087980 0.174366 -vn 5.810155 1.187252 -2.056362 -v 0.046207 -0.087360 0.174769 -vn 5.810076 0.966949 -2.168925 -v 0.046207 -0.086701 0.175105 -vn 5.809416 0.733178 -2.260150 -v 0.046207 -0.086010 0.175370 -vn 5.809663 0.495057 -2.323423 -v 0.046207 -0.085296 0.175561 -vn 5.809460 0.247226 -2.363109 -v 0.046207 -0.084565 0.175677 -vn 5.810159 0.000006 -2.374478 -v 0.046207 -0.083827 0.175716 -vn 5.810160 -0.248193 -2.361471 -v 0.046207 -0.083088 0.175677 -vn 5.811666 -0.495251 -2.318904 -v 0.046207 -0.082358 0.175561 -vn 5.810644 -0.730259 -2.258266 -v 0.046207 -0.081643 0.175370 -vn 5.810077 -0.966955 -2.168922 -v 0.046207 -0.080953 0.175105 -vn 5.810154 -1.187252 -2.056366 -v 0.046207 -0.080294 0.174769 -vn 5.810081 -1.394860 -1.921857 -v 0.046207 -0.079674 0.174366 -vn 5.809421 -1.590760 -1.765010 -v 0.046207 -0.079099 0.173901 -vn 5.809669 -1.764593 -1.590437 -v 0.046207 -0.078576 0.173378 -vn 5.809462 -1.922885 -1.395667 -v 0.046207 -0.078111 0.172803 -vn 5.810158 -2.056365 -1.187238 -v 0.046207 -0.077708 0.172183 -vn 5.810156 -2.169206 -0.965787 -v 0.046207 -0.077372 0.171524 -vn 5.811669 -2.255844 -0.730560 -v 0.046207 -0.077107 0.170833 -vn 5.810645 -2.320842 -0.496713 -v 0.046207 -0.076916 0.170119 -vn 5.810077 -2.361817 -0.247068 -v 0.046207 -0.076800 0.169389 -vn 5.810155 -2.374492 -0.000001 -v 0.046207 -0.076761 0.168650 -vn 5.810075 -2.361820 0.247075 -v 0.046207 -0.076800 0.167911 -vn 5.809415 -2.323937 0.495140 -v 0.046207 -0.076916 0.167181 -vn 5.809665 -2.259664 0.732971 -v 0.046207 -0.077107 0.166467 -vn 5.809456 -2.170135 0.967446 -v 0.046207 -0.077372 0.165776 -vn 5.810156 -2.056369 1.187235 -v 0.046207 -0.077708 0.165117 -vn 5.810159 -1.920998 1.395682 -v 0.046207 -0.078111 0.164497 -vn 5.811670 -1.760598 1.588345 -v 0.046207 -0.078576 0.163922 -vn 5.810648 -1.590575 1.761560 -v 0.046207 -0.079099 0.163399 -vn 5.810080 -1.394875 1.921848 -v 0.046207 -0.079674 0.162934 -vn 5.810161 -1.187245 2.056354 -v 0.046207 -0.080294 0.162531 -vn 5.810076 -0.966932 2.168933 -v 0.046207 -0.080953 0.162195 -vn 5.809414 -0.733182 2.260153 -v 0.046207 -0.081643 0.161930 -vn 5.809667 -0.495057 2.323410 -v 0.046207 -0.082358 0.161739 -vn 5.809460 -0.247223 2.363109 -v 0.046207 -0.083088 0.161623 -vn 5.810157 -0.000004 2.374481 -v 0.046207 -0.083827 0.161584 -vn 5.810158 0.248190 2.361476 -v 0.046207 -0.084565 0.161623 -vn 5.811671 0.495245 2.318892 -v 0.046207 -0.085296 0.161739 -vn 5.810645 0.730263 2.258260 -v 0.046207 -0.086010 0.161930 -vn 5.810077 0.966937 2.168930 -v 0.046207 -0.086701 0.162195 -vn 5.810159 1.187246 2.056358 -v 0.046207 -0.087360 0.162531 -vn 5.810079 1.394874 1.921850 -v 0.046207 -0.087980 0.162934 -vn 5.809419 1.590753 1.765027 -v 0.046207 -0.088555 0.163399 -vn 5.809666 1.764603 1.590443 -v 0.046207 -0.089078 0.163922 -vn 5.809460 1.922896 1.395661 -v 0.046207 -0.089543 0.164497 -vn 5.810158 2.056365 1.187238 -v 0.046207 -0.089946 0.165117 -vn 5.810156 2.169206 0.965787 -v 0.046207 -0.090282 0.165776 -vn 5.811668 2.255845 0.730561 -v 0.046207 -0.090547 0.166467 -vn 5.810646 2.320845 0.496705 -v 0.046207 -0.090738 0.167181 -vn 5.810078 2.361814 0.247062 -v 0.046207 -0.090854 0.167911 -vn 5.810157 2.374485 -0.000001 -v 0.046207 -0.090892 0.168650 -vn 5.317542 -3.292265 0.000004 -v 0.045267 -0.078732 0.168650 -vn 5.302679 -3.275810 0.465986 -v 0.045267 -0.078809 0.167765 -vn 5.436656 -3.023912 0.775066 -v 0.045267 -0.078843 0.167591 -vn 5.308131 -3.126117 1.063623 -v 0.045267 -0.079039 0.166907 -vn 5.552598 -2.646596 1.265257 -v 0.045267 -0.079172 0.166578 -vn 5.313200 -2.869064 1.622013 -v 0.045267 -0.079414 0.166102 -vn 5.460568 -2.517835 1.786261 -v 0.045267 -0.079705 0.165655 -vn 5.298936 -2.505067 2.173633 -v 0.045267 -0.079924 0.165375 -vn 5.406255 -2.200755 2.278625 -v 0.045267 -0.080417 0.164864 -vn 5.302698 -2.041424 2.603942 -v 0.045267 -0.080552 0.164747 -vn 5.317644 -1.646058 2.851070 -v 0.045267 -0.081279 0.164237 -vn 5.302762 -1.234366 3.069803 -v 0.045267 -0.082084 0.163862 -vn 5.436829 -0.840673 3.006067 -v 0.045267 -0.082252 0.163804 -vn 5.307980 -0.642015 3.239289 -v 0.045267 -0.082942 0.163632 -vn 5.552568 -0.227584 2.924701 -v 0.045267 -0.083294 0.163583 -vn 5.313181 -0.029825 3.295714 -v 0.045267 -0.083827 0.163555 -vn 5.460537 0.288051 3.073686 -v 0.045267 -0.084359 0.163583 -vn 5.298784 0.629956 3.256450 -v 0.045267 -0.084712 0.163632 -vn 5.406308 0.872983 3.045142 -v 0.045267 -0.085401 0.163804 -vn 5.302765 1.234343 3.069811 -v 0.045267 -0.085569 0.163862 -vn 5.317642 1.646060 2.851073 -v 0.045267 -0.086374 0.164237 -vn 5.302696 2.041427 2.603941 -v 0.045267 -0.087102 0.164747 -vn 5.436721 2.183117 2.231181 -v 0.045267 -0.087236 0.164864 -vn 5.308123 2.484192 2.175489 -v 0.045267 -0.087730 0.165375 -vn 5.552603 2.419036 1.659389 -v 0.045267 -0.087949 0.165655 -vn 5.313200 2.839239 1.673674 -v 0.045267 -0.088239 0.166102 -vn 5.460564 2.805871 1.287384 -v 0.045267 -0.088481 0.166578 -vn 5.298949 3.134942 1.082623 -v 0.045267 -0.088615 0.166907 -vn 5.406204 3.073793 0.766622 -v 0.045267 -0.088811 0.167591 -vn 5.302679 3.275811 0.465982 -v 0.045267 -0.088845 0.167765 -vn 5.317629 3.292152 0.000001 -v 0.045267 -0.088922 0.168650 -vn 5.302704 3.275777 -0.465989 -v 0.045267 -0.088845 0.169535 -vn 5.436702 3.023842 -0.775060 -v 0.045267 -0.088811 0.169709 -vn 5.308131 3.126124 -1.063604 -v 0.045267 -0.088615 0.170393 -vn 5.552639 2.646538 -1.265213 -v 0.045267 -0.088481 0.170722 -vn 5.313203 2.869064 -1.622005 -v 0.045267 -0.088239 0.171198 -vn 5.460564 2.517829 -1.786282 -v 0.045267 -0.087949 0.171645 -vn 5.298809 2.505165 -2.173764 -v 0.045267 -0.087730 0.171925 -vn 5.406154 2.200860 -2.278728 -v 0.045267 -0.087236 0.172436 -vn 5.302553 2.041549 -2.604075 -v 0.045267 -0.087102 0.172553 -vn 5.317647 1.646074 -2.851058 -v 0.045267 -0.086374 0.173063 -vn 5.302783 1.234221 -3.069839 -v 0.045267 -0.085569 0.173438 -vn 5.436665 0.840684 -3.006312 -v 0.045267 -0.085401 0.173496 -vn 5.308165 0.641905 -3.239070 -v 0.045267 -0.084712 0.173668 -vn 5.552520 0.227605 -2.924782 -v 0.045267 -0.084359 0.173717 -vn 5.313190 0.029819 -3.295708 -v 0.045267 -0.083827 0.173745 -vn 5.460501 -0.288073 -3.073737 -v 0.045267 -0.083294 0.173717 -vn 5.298981 -0.629863 -3.256215 -v 0.045267 -0.082942 0.173668 -vn 5.406231 -0.872939 -3.045262 -v 0.045267 -0.082252 0.173496 -vn 5.302780 -1.234240 -3.069836 -v 0.045267 -0.082084 0.173438 -vn 5.317640 -1.646070 -2.851072 -v 0.045267 -0.081279 0.173063 -vn 5.302547 -2.041565 -2.604073 -v 0.045267 -0.080552 0.172553 -vn 5.436627 -2.183220 -2.231277 -v 0.045267 -0.080417 0.172436 -vn 5.307994 -2.484295 -2.175625 -v 0.045267 -0.079924 0.171925 -vn 5.552598 -2.419031 -1.659412 -v 0.045267 -0.079705 0.171645 -vn 5.313200 -2.839239 -1.673674 -v 0.045267 -0.079414 0.171198 -vn 5.460594 -2.805837 -1.287344 -v 0.045267 -0.079172 0.170722 -vn 5.298947 -3.134948 -1.082605 -v 0.045267 -0.079039 0.170393 -vn 5.406240 -3.073740 -0.766614 -v 0.045267 -0.078843 0.169709 -vn 5.302704 -3.275778 -0.465997 -v 0.045267 -0.078809 0.169535 -vn -3.923355 -0.492927 -4.871871 -v 0.044951 -0.083110 0.173632 -vn -3.670903 -1.044356 -4.954213 -v 0.044951 -0.082953 0.173607 -vn -1.740445 -1.086927 -5.806755 -v 0.045032 -0.082961 0.173563 -vn -3.924301 -3.971505 2.862994 -v 0.044951 -0.079870 0.165538 -vn -3.671535 -3.768184 3.380850 -v 0.044951 -0.079971 0.165414 -vn -1.740501 -4.485352 3.844667 -v 0.045032 -0.080005 0.165443 -vn -3.922744 4.465811 2.009964 -v 0.044951 -0.088500 0.166779 -vn -3.672614 4.810812 1.573667 -v 0.044951 -0.088557 0.166928 -vn -1.740643 5.572165 1.962082 -v 0.045032 -0.088515 0.166944 -vn 1.195412 3.889904 -4.635816 -v 0.045125 -0.087031 0.172469 -vn 3.838202 3.052795 -3.717777 -v 0.045209 -0.087056 0.172498 -vn 3.840335 3.665011 -3.113477 -v 0.045209 -0.087675 0.171879 -vn 1.194949 -1.050877 -5.959761 -v 0.045125 -0.082961 0.173559 -vn 3.840447 -0.863808 -4.730569 -v 0.045209 -0.082955 0.173597 -vn 3.826294 0.033088 -4.824623 -v 0.045209 -0.083827 0.173673 -vn 1.195157 -5.959699 -1.050924 -v 0.045125 -0.078918 0.169516 -vn 3.838299 -4.745925 -0.784903 -v 0.045209 -0.078880 0.169522 -vn 3.840424 -4.528718 -1.617207 -v 0.045209 -0.079107 0.170368 -vn 1.194906 -4.635887 3.889924 -v 0.045125 -0.080008 0.165446 -vn 3.840462 -3.664917 3.113354 -v 0.045209 -0.079979 0.165421 -vn 3.826002 -4.194898 2.383723 -v 0.045209 -0.079477 0.166138 -vn 1.195094 2.069820 5.686790 -v 0.045125 -0.085532 0.163966 -vn 3.838127 1.693271 4.502555 -v 0.045209 -0.085545 0.163930 -vn 3.840660 0.863783 4.730587 -v 0.045209 -0.084699 0.163703 -vn 3.832622 4.541028 -1.607038 -v 0.045209 -0.088547 0.170368 -vn 3.826005 4.194906 -2.383708 -v 0.045209 -0.088177 0.171162 -vn 3.837935 1.689268 -4.504254 -v 0.045209 -0.085545 0.173370 -vn 3.832523 -3.662355 -3.129228 -v 0.045209 -0.079979 0.171879 -vn 3.826005 -4.161819 -2.441014 -v 0.045209 -0.079477 0.171162 -vn 3.837802 -4.745562 0.789180 -v 0.045209 -0.078880 0.167778 -vn 3.832847 -0.878836 4.736156 -v 0.045209 -0.082955 0.163703 -vn 3.825912 -0.033054 4.824807 -v 0.045209 -0.083827 0.163627 -vn 3.837833 3.056181 3.715178 -v 0.045209 -0.087056 0.164802 -vn 3.811027 4.840925 -0.000008 -v 0.045209 -0.088850 0.168650 -vn 3.838335 4.745925 0.784927 -v 0.045209 -0.088774 0.167778 -vn 3.840558 4.528645 1.617225 -v 0.045209 -0.088547 0.166932 -vn 3.826005 4.161818 2.441015 -v 0.045209 -0.088177 0.166138 -vn 3.832653 3.662262 3.129101 -v 0.045209 -0.087675 0.165421 -vn 3.837606 -1.689364 4.504373 -v 0.045209 -0.082109 0.163930 -vn 3.832752 -4.540955 1.607052 -v 0.045209 -0.079107 0.166932 -vn 3.837674 -3.056303 -3.715325 -v 0.045209 -0.080598 0.172498 -vn 3.832654 0.878740 -4.736143 -v 0.045209 -0.084699 0.173597 -vn 3.837767 4.745567 -0.789136 -v 0.045209 -0.088774 0.169522 -vn 3.811229 2.420394 4.192270 -v 0.045209 -0.086338 0.164300 -vn 1.195121 3.025787 5.240866 -v 0.045125 -0.086319 0.164333 -vn -1.753100 2.951790 5.112668 -v 0.045032 -0.086321 0.164330 -vn 3.838364 -3.052686 3.717615 -v 0.045209 -0.080598 0.164802 -vn 1.195043 -3.889910 4.635816 -v 0.045125 -0.080623 0.164831 -vn -1.735214 -3.763033 4.556718 -v 0.045032 -0.080620 0.164828 -vn 3.811122 -4.840945 0.000002 -v 0.045209 -0.078804 0.168650 -vn 1.195110 -6.051611 0.000000 -v 0.045125 -0.078842 0.168650 -vn -1.753215 -5.903562 0.000003 -v 0.045032 -0.078838 0.168650 -vn 3.838476 -1.693115 -4.502441 -v 0.045209 -0.082109 0.173370 -vn 1.195017 -2.069760 -5.686647 -v 0.045125 -0.082122 0.173334 -vn -1.735410 -2.064611 -5.537201 -v 0.045032 -0.082121 0.173338 -vn 3.811222 2.420408 -4.192270 -v 0.045209 -0.086338 0.173000 -vn 1.195131 3.025773 -5.240872 -v 0.045125 -0.086319 0.172967 -vn -1.753092 2.951817 -5.112663 -v 0.045032 -0.086321 0.172970 -vn 1.195038 5.686700 2.069763 -v 0.045125 -0.088511 0.166945 -vn 1.195147 5.959681 1.050864 -v 0.045125 -0.088736 0.167784 -vn 1.194901 6.051694 -0.000016 -v 0.045125 -0.088812 0.168650 -vn 1.195155 5.959704 -1.050898 -v 0.045125 -0.088736 0.169516 -vn 1.194905 4.635891 3.889917 -v 0.045125 -0.087646 0.165446 -vn -1.732746 4.567379 3.753873 -v 0.045032 -0.087648 0.165443 -vn -1.737828 5.149280 2.899208 -v 0.045032 -0.088147 0.166156 -vn 1.195083 -2.069795 5.686800 -v 0.045125 -0.082122 0.163966 -vn -1.736659 -2.069601 5.534809 -v 0.045032 -0.082121 0.163962 -vn -1.748003 -1.081770 5.804694 -v 0.045032 -0.082961 0.163737 -vn -1.689847 -2.965892 5.137139 -v 0.045032 -0.081332 0.164330 -vn 1.195163 -3.025837 5.240880 -v 0.045125 -0.081334 0.164333 -vn 3.811120 -2.420425 4.192318 -v 0.045209 -0.081315 0.164300 -vn 1.195041 -5.686699 2.069763 -v 0.045125 -0.079142 0.166945 -vn -1.732881 -5.534550 2.078527 -v 0.045032 -0.079139 0.166944 -vn -1.737855 -5.085391 3.009840 -v 0.045032 -0.079506 0.166156 -vn 1.195424 -3.889890 -4.635824 -v 0.045125 -0.080623 0.172469 -vn -1.736744 -3.758530 -4.559638 -v 0.045032 -0.080620 0.172472 -vn -1.747987 -4.486058 -3.839120 -v 0.045032 -0.080005 0.171857 -vn -1.689855 -2.965899 -5.137135 -v 0.045032 -0.081332 0.172970 -vn 1.195167 -3.025825 -5.240891 -v 0.045125 -0.081334 0.172967 -vn 3.811133 -2.420415 -4.192315 -v 0.045209 -0.081315 0.173000 -vn 1.194945 1.050851 -5.959768 -v 0.045125 -0.084692 0.173559 -vn -1.732667 0.967221 -5.832421 -v 0.045032 -0.084693 0.173563 -vn -1.737705 -0.063942 -5.909040 -v 0.045032 -0.083827 0.173639 -vn -1.735409 5.827589 0.980574 -v 0.045032 -0.088740 0.167784 -vn -1.690086 5.931790 -0.000000 -v 0.045032 -0.088816 0.168650 -vn -1.736987 5.827985 -0.975121 -v 0.045032 -0.088740 0.169516 -vn -1.748102 5.567867 -1.965492 -v 0.045032 -0.088515 0.170356 -vn 1.194900 5.240903 3.025808 -v 0.045125 -0.088144 0.166158 -vn -3.784476 4.854110 1.164799 -v 0.044951 -0.088769 0.167697 -vn -3.676214 4.449527 2.409103 -v 0.044951 -0.088186 0.166133 -vn -4.015694 2.777862 3.949094 -v 0.044951 -0.086747 0.164550 -vn -3.688064 3.306065 3.819865 -v 0.044951 -0.087062 0.164794 -vn -1.727479 3.846657 4.493504 -v 0.045032 -0.087034 0.164828 -vn 1.195042 3.889901 4.635821 -v 0.045125 -0.087031 0.164831 -vn -4.171311 3.304115 3.337043 -v 0.044951 -0.087470 0.165176 -vn -3.682609 3.941025 3.166410 -v 0.044951 -0.087683 0.165414 -vn -4.053932 3.939119 2.736395 -v 0.044951 -0.088061 0.165929 -vn -3.661944 2.536321 4.389687 -v 0.044951 -0.086344 0.164291 -vn -1.752657 2.002708 5.553548 -v 0.045032 -0.085533 0.163962 -vn -3.664345 1.694595 4.775923 -v 0.044951 -0.085548 0.163920 -vn -4.018223 2.029289 4.378653 -v 0.044951 -0.085918 0.164071 -vn 1.195363 1.050831 5.959600 -v 0.045125 -0.084692 0.163741 -vn -1.752381 0.991615 5.819740 -v 0.045032 -0.084693 0.163737 -vn -3.665926 0.802640 5.002270 -v 0.044951 -0.084701 0.163693 -vn -3.993664 1.218673 4.689432 -v 0.044951 -0.085014 0.163758 -vn 1.195398 0.000001 6.051688 -v 0.045125 -0.083827 0.163665 -vn -1.750830 -0.048482 5.903574 -v 0.045032 -0.083827 0.163661 -vn -3.661564 -0.119221 5.068592 -v 0.044951 -0.083827 0.163616 -vn -3.945577 0.358009 4.868252 -v 0.044951 -0.084066 0.163622 -vn 1.195361 -1.050849 5.959598 -v 0.045125 -0.082961 0.163741 -vn -3.868103 -0.525132 4.909123 -v 0.044951 -0.083110 0.163668 -vn -3.782878 -3.437517 3.621643 -v 0.044951 -0.080530 0.164846 -vn -3.665587 -3.102545 4.005194 -v 0.044951 -0.080591 0.164794 -vn -3.684396 -2.529543 4.378963 -v 0.044951 -0.081310 0.164291 -vn -3.667118 -1.915968 4.688612 -v 0.044951 -0.082105 0.163920 -vn -3.767557 -1.433792 4.793626 -v 0.044951 -0.082180 0.163893 -vn -3.665355 -1.035646 4.959650 -v 0.044951 -0.082953 0.163693 -vn 1.194907 -5.240899 3.025814 -v 0.045125 -0.079510 0.166158 -vn -3.677825 -4.310724 2.646777 -v 0.044951 -0.079468 0.166133 -vn -4.018777 -4.806002 0.433786 -v 0.044951 -0.078816 0.168172 -vn -3.688200 -4.961021 0.953524 -v 0.044951 -0.078870 0.167776 -vn -1.727659 -5.814676 1.084549 -v 0.045032 -0.078914 0.167784 -vn 1.195153 -5.959680 1.050855 -v 0.045125 -0.078918 0.167784 -vn -4.170912 -4.542467 1.192639 -v 0.044951 -0.078997 0.167232 -vn -3.681300 -4.713367 1.831409 -v 0.044951 -0.079097 0.166928 -vn -4.052873 -4.340708 2.042531 -v 0.044951 -0.079353 0.166343 -vn -3.664861 -5.067239 -0.001192 -v 0.044951 -0.078793 0.168650 -vn -1.753046 -5.810753 -1.042306 -v 0.045032 -0.078914 0.169516 -vn -3.662073 -4.985823 -0.918287 -v 0.044951 -0.078870 0.169524 -vn -4.015646 -4.808680 -0.434559 -v 0.044951 -0.078816 0.169128 -vn 1.194899 -5.686749 -2.069790 -v 0.045125 -0.079142 0.170355 -vn -1.752472 -5.535810 -2.051151 -v 0.045032 -0.079139 0.170356 -vn -3.664534 -4.733759 -1.808543 -v 0.044951 -0.079097 0.170372 -vn -3.994054 -4.670280 -1.288922 -v 0.044951 -0.078997 0.170068 -vn 1.194900 -5.240903 -3.025808 -v 0.045125 -0.079510 0.171142 -vn -1.751429 -5.088382 -2.993668 -v 0.045032 -0.079506 0.171144 -vn -3.666462 -4.327168 -2.633982 -v 0.044951 -0.079468 0.171167 -vn -3.945106 -4.397016 -2.120945 -v 0.044951 -0.079353 0.170957 -vn 1.195220 -4.635864 -3.889943 -v 0.045125 -0.080008 0.171854 -vn -3.869850 -3.984707 -2.912361 -v 0.044951 -0.079870 0.171762 -vn -3.782884 -1.417292 -4.787897 -v 0.044951 -0.082180 0.173407 -vn -3.667160 -1.915556 -4.688770 -v 0.044951 -0.082105 0.173380 -vn -3.684401 -2.529548 -4.378954 -v 0.044951 -0.081310 0.173009 -vn -3.665908 -3.102398 -4.005052 -v 0.044951 -0.080591 0.172506 -vn -3.764569 -3.438323 -3.638512 -v 0.044951 -0.080530 0.172454 -vn -3.661512 -3.779443 -3.379498 -v 0.044951 -0.079971 0.171886 -vn 1.195314 0.000022 -6.051527 -v 0.045125 -0.083827 0.173635 -vn -3.677136 -0.137811 -5.057116 -v 0.044951 -0.083827 0.173684 -vn -4.018555 2.027579 -4.379122 -v 0.044951 -0.085918 0.173229 -vn -3.684872 1.652853 -4.776827 -v 0.044951 -0.085548 0.173380 -vn -1.727703 1.968085 -5.577992 -v 0.045032 -0.085533 0.173338 -vn 1.195022 2.069766 -5.686644 -v 0.045125 -0.085532 0.173334 -vn -4.167852 1.241855 -4.532075 -v 0.044951 -0.085014 0.173542 -vn -3.682902 0.772252 -4.995884 -v 0.044951 -0.084701 0.173607 -vn -4.055115 0.399454 -4.778605 -v 0.044951 -0.084066 0.173678 -vn -3.664790 2.534594 -4.387836 -v 0.044951 -0.086344 0.173009 -vn -1.752767 3.808099 -4.511142 -v 0.045032 -0.087034 0.172472 -vn -3.666100 3.286320 -3.855680 -v 0.044951 -0.087062 0.172506 -vn -4.018058 2.777505 -3.946818 -v 0.044951 -0.086747 0.172750 -vn 1.195232 4.635870 -3.889936 -v 0.045125 -0.087646 0.171854 -vn -1.752389 4.544185 -3.768534 -v 0.045032 -0.087648 0.171857 -vn -3.661971 3.933830 -3.198029 -v 0.044951 -0.087683 0.171886 -vn -3.993773 3.454347 -3.397414 -v 0.044951 -0.087470 0.172124 -vn 1.194910 5.240897 -3.025818 -v 0.045125 -0.088144 0.171142 -vn -1.751444 5.136755 -2.909878 -v 0.045032 -0.088147 0.171144 -vn -3.665107 4.446619 -2.429353 -v 0.044951 -0.088186 0.171167 -vn -3.944661 4.035126 -2.748395 -v 0.044951 -0.088061 0.171371 -vn 1.194890 5.686746 -2.069807 -v 0.045125 -0.088511 0.170355 -vn -3.869812 4.513300 -1.997625 -v 0.044951 -0.088500 0.170521 -vn -3.666060 5.019549 0.684139 -v 0.044951 -0.088784 0.167776 -vn -3.678602 5.061943 -0.003571 -v 0.044951 -0.088860 0.168650 -vn -3.661132 5.024054 -0.682830 -v 0.044951 -0.088784 0.169524 -vn -3.767406 4.869002 -1.152582 -v 0.044951 -0.088769 0.169603 -vn -3.666817 4.811338 -1.583977 -v 0.044951 -0.088557 0.170372 -vn -3.578990 3.446398 3.731404 -v 0.041143 -0.089746 0.162530 -vn -3.190134 3.867565 3.552389 -v 0.041143 -0.089989 0.162775 -vn -3.578005 3.987965 3.141926 -v 0.041143 -0.090509 0.163373 -vn -3.220180 4.346430 2.927132 -v 0.041143 -0.090989 0.164047 -vn -3.577414 0.609028 5.041732 -v 0.041143 -0.084679 0.160179 -vn -3.583105 1.018932 4.979625 -v 0.041143 -0.085801 0.160368 -vn -3.547925 1.376430 4.911384 -v 0.041143 -0.085834 0.160376 -vn -3.575961 1.741379 4.770122 -v 0.041143 -0.086887 0.160705 -vn -3.105740 2.214610 4.791656 -v 0.041143 -0.087364 0.160905 -vn -3.579531 2.487988 4.423944 -v 0.041143 -0.087919 0.161184 -vn -3.419138 2.853154 4.298986 -v 0.041143 -0.088765 0.161715 -vn -3.583724 3.129418 4.001374 -v 0.041143 -0.088877 0.161796 -vn -3.578696 -2.123295 4.611027 -v 0.041143 -0.080243 0.160927 -vn -3.252612 -1.828762 4.898471 -v 0.041143 -0.081042 0.160604 -vn -3.581126 -1.381894 4.887373 -v 0.041143 -0.081304 0.160518 -vn -3.582111 -0.981079 4.984127 -v 0.041143 -0.082411 0.160254 -vn -3.256287 -0.560756 5.195417 -v 0.041143 -0.082615 0.160223 -vn -3.570486 -0.223767 5.074132 -v 0.041143 -0.083542 0.160141 -vn -3.126424 0.197019 5.268835 -v 0.041143 -0.084232 0.160146 -vn -3.579886 -2.826638 4.218131 -v 0.041143 -0.079246 0.161474 -vn -3.165427 -2.556716 4.596297 -v 0.041143 -0.079570 0.161277 -vn -3.583774 -4.604641 2.148947 -v 0.041143 -0.076228 0.164810 -vn -3.499414 -4.466203 2.512506 -v 0.041143 -0.076259 0.164749 -vn -3.573800 -4.233003 2.807171 -v 0.041143 -0.076807 0.163831 -vn -3.100038 -4.146841 3.270436 -v 0.041143 -0.077134 0.163387 -vn -3.578259 -3.719762 3.454907 -v 0.041143 -0.077512 0.162939 -vn -3.463621 -3.498518 3.766447 -v 0.041143 -0.078251 0.162215 -vn -3.583740 -3.160991 3.977588 -v 0.041143 -0.078330 0.162148 -vn -3.580137 -5.076495 0.207444 -v 0.041143 -0.075332 0.168081 -vn -3.184735 -5.209318 0.674392 -v 0.041143 -0.075351 0.167841 -vn -3.566297 -4.989032 0.968955 -v 0.041143 -0.075483 0.166954 -vn -3.144351 -5.072011 1.417645 -v 0.041143 -0.075658 0.166251 -vn -3.579114 -4.760490 1.766237 -v 0.041143 -0.075784 0.165857 -vn -3.577091 -4.228725 -2.810916 -v 0.041143 -0.076807 0.173469 -vn -3.508115 -4.466548 -2.503712 -v 0.041143 -0.076259 0.172551 -vn -3.583772 -4.604646 -2.148933 -v 0.041143 -0.076228 0.172490 -vn -3.578868 -4.760653 -1.766655 -v 0.041143 -0.075784 0.171443 -vn -3.145069 -5.071716 -1.416193 -v 0.041143 -0.075658 0.171049 -vn -3.579735 -4.978449 -0.986715 -v 0.041143 -0.075483 0.170346 -vn -3.292254 -5.173446 -0.631917 -v 0.041143 -0.075351 0.169459 -vn -3.582832 -5.073857 -0.209512 -v 0.041143 -0.075332 0.169219 -vn -3.579885 -2.826641 -4.218130 -v 0.041143 -0.079246 0.175826 -vn -3.583710 -3.160983 -3.977616 -v 0.041143 -0.078330 0.175152 -vn -3.447150 -3.513816 -3.760771 -v 0.041143 -0.078251 0.175085 -vn -3.575710 -3.712930 -3.461998 -v 0.041143 -0.077512 0.174361 -vn -3.100366 -4.146261 -3.270529 -v 0.041143 -0.077134 0.173913 -vn -3.581492 -1.381735 -4.887244 -v 0.041143 -0.081304 0.176782 -vn -3.252537 -1.828724 -4.898492 -v 0.041143 -0.081042 0.176696 -vn -3.578351 -2.123362 -4.611187 -v 0.041143 -0.080243 0.176373 -vn -3.165293 -2.556711 -4.596351 -v 0.041143 -0.079570 0.176023 -vn -3.577408 0.609038 -5.041733 -v 0.041143 -0.084679 0.177121 -vn -3.125803 0.197593 -5.269399 -v 0.041143 -0.084232 0.177154 -vn -3.577936 -0.206154 -5.072751 -v 0.041143 -0.083542 0.177159 -vn -3.329561 -0.589500 -5.164900 -v 0.041143 -0.082615 0.177077 -vn -3.581838 -0.981038 -4.984228 -v 0.041143 -0.082411 0.177046 -vn -3.578722 3.446497 -3.731497 -v 0.041143 -0.089746 0.174770 -vn -3.581576 3.131831 -4.002028 -v 0.041143 -0.088877 0.175504 -vn -3.383972 2.845795 -4.323471 -v 0.041143 -0.088765 0.175585 -vn -3.571345 2.499796 -4.422448 -v 0.041143 -0.087919 0.176116 -vn -3.105503 2.213572 -4.792381 -v 0.041143 -0.087364 0.176395 -vn -3.578937 1.743089 -4.767350 -v 0.041143 -0.086887 0.176595 -vn -3.553003 1.371664 -4.909111 -v 0.041143 -0.085834 0.176924 -vn -3.584719 1.019891 -4.977873 -v 0.041143 -0.085801 0.176932 -vn -3.577885 4.884506 -1.385046 -v 0.041143 -0.092038 0.170899 -vn -3.371323 4.868305 -1.774939 -v 0.041143 -0.091731 0.171814 -vn -3.582284 4.619323 -2.114535 -v 0.041143 -0.091665 0.171974 -vn -3.580476 4.431191 -2.481793 -v 0.041143 -0.091152 0.172989 -vn -3.221588 4.344614 -2.927728 -v 0.041143 -0.090989 0.173253 -vn -3.580138 3.986766 -3.140134 -v 0.041143 -0.090509 0.173927 -vn -3.190649 3.867548 -3.551509 -v 0.041143 -0.089989 0.174525 -vn -3.580705 4.430951 2.481811 -v 0.041143 -0.091152 0.164311 -vn -3.582446 4.619256 2.114486 -v 0.041143 -0.091665 0.165326 -vn -3.319886 4.896078 1.759146 -v 0.041143 -0.091731 0.165486 -vn -3.569664 4.884301 1.399258 -v 0.041143 -0.092038 0.166401 -vn -3.113217 5.174107 1.036772 -v 0.041143 -0.092187 0.167039 -vn -3.578248 5.043460 0.579559 -v 0.041143 -0.092265 0.167515 -vn -3.569618 5.067010 -0.002364 -v 0.041143 -0.092341 0.168650 -vn -3.581166 5.040950 -0.577029 -v 0.041143 -0.092265 0.169785 -vn -3.113481 5.173907 -1.036497 -v 0.041143 -0.092187 0.170261 -vn 3.342183 2.747455 -4.392136 -v 0.040872 -0.088083 0.176022 -vn 3.634720 2.300033 -4.487753 -v 0.040872 -0.087918 0.176115 -vn 1.458073 2.769628 -5.153546 -v 0.040958 -0.087941 0.176157 -vn 3.579563 -1.939041 -4.688752 -v 0.040872 -0.080290 0.176393 -vn 3.635831 -2.266940 -4.506890 -v 0.040872 -0.080244 0.176372 -vn 1.469238 -2.480788 -5.290472 -v 0.040958 -0.080224 0.176415 -vn 1.465144 -3.105975 -4.953524 -v 0.040958 -0.079221 0.175865 -vn 3.526859 -5.039959 0.779831 -v 0.040872 -0.075468 0.167039 -vn 3.635040 -4.910862 1.155297 -v 0.040872 -0.075485 0.166954 -vn 1.462034 -5.723532 1.198287 -v 0.040958 -0.075438 0.166945 -vn 1.463945 -5.539877 1.871714 -v 0.040958 -0.075740 0.165842 -vn 3.468478 -0.432248 5.108945 -v 0.040872 -0.083422 0.160147 -vn 3.634634 -0.019618 5.044528 -v 0.040872 -0.083542 0.160142 -vn 1.458801 -0.154226 5.847589 -v 0.040958 -0.083541 0.160095 -vn 3.406550 4.889696 1.630438 -v 0.040872 -0.091995 0.166252 -vn 3.634427 4.900787 1.193019 -v 0.040872 -0.092037 0.166401 -vn 1.457911 5.654456 1.501742 -v 0.040958 -0.092083 0.166388 -vn -1.399669 5.071946 -2.943135 -v 0.041057 -0.091192 0.173013 -vn -1.396377 5.380336 -2.336772 -v 0.041057 -0.091708 0.171992 -vn 1.467116 5.391204 -2.260046 -v 0.040958 -0.091708 0.171992 -vn -1.405061 0.633238 -5.826616 -v 0.041057 -0.084684 0.177168 -vn -1.413877 1.339282 -5.699651 -v 0.041057 -0.085811 0.176977 -vn 1.467525 1.359869 -5.685511 -v 0.040958 -0.085811 0.176977 -vn -1.403967 -5.521250 -1.968610 -v 0.041057 -0.075740 0.171458 -vn -1.403264 -5.245847 -2.614314 -v 0.041057 -0.076186 0.172511 -vn 1.467507 -5.213196 -2.645110 -v 0.040958 -0.076187 0.172511 -vn -1.402451 -3.196703 4.914441 -v 0.041057 -0.079220 0.161434 -vn -1.398768 -3.753943 4.505194 -v 0.041057 -0.078300 0.162113 -vn 1.467088 -3.785236 4.454851 -v 0.040958 -0.078300 0.162113 -vn -1.408310 2.065709 5.483069 -v 0.041057 -0.086904 0.160661 -vn -1.415183 1.341110 5.698651 -v 0.041057 -0.085811 0.160323 -vn 1.467397 1.359820 5.685297 -v 0.040958 -0.085811 0.160323 -vn -1.435106 5.842606 -0.000010 -v 0.041057 -0.092387 0.168650 -vn -1.406830 5.813719 0.736489 -v 0.041057 -0.092311 0.167509 -vn 1.461068 5.789748 0.830812 -v 0.040958 -0.092311 0.167509 -vn -1.406589 5.646472 -1.569242 -v 0.041057 -0.092083 0.170912 -vn -1.406767 4.600894 -3.630192 -v 0.041057 -0.090545 0.173955 -vn -1.401281 4.039093 -4.250364 -v 0.041057 -0.089778 0.174804 -vn -1.397730 3.514160 -4.695423 -v 0.041057 -0.088905 0.175542 -vn -1.412539 2.846542 -5.118236 -v 0.041057 -0.087941 0.176157 -vn -1.406694 -0.212731 -5.856774 -v 0.041057 -0.083541 0.177206 -vn -1.396474 -1.027550 -5.775105 -v 0.041057 -0.082403 0.177091 -vn -1.398791 -1.686651 -5.616839 -v 0.041057 -0.081290 0.176826 -vn -1.411057 -4.318264 -3.957883 -v 0.041057 -0.077478 0.174392 -vn -1.406758 -5.745530 -1.155503 -v 0.041057 -0.075438 0.170355 -vn -1.397611 -5.855558 -0.338626 -v 0.041057 -0.075285 0.169222 -vn -1.398150 -5.854858 0.342264 -v 0.041057 -0.075285 0.168078 -vn -1.409681 -4.853034 3.281787 -v 0.041057 -0.076769 0.163805 -vn -1.406543 -2.460267 5.319014 -v 0.041057 -0.080223 0.160885 -vn -1.398494 -1.686775 5.616991 -v 0.041057 -0.081290 0.160474 -vn -1.397388 -1.023682 5.775040 -v 0.041057 -0.082403 0.160209 -vn -1.415701 -0.227603 5.850542 -v 0.041057 -0.083541 0.160094 -vn -1.406936 2.839567 5.126474 -v 0.041057 -0.087941 0.161143 -vn -1.396880 3.517599 4.693689 -v 0.041057 -0.088905 0.161758 -vn -1.401206 4.038953 4.250257 -v 0.041057 -0.089778 0.162496 -vn -1.414082 5.638529 1.580095 -v 0.041057 -0.092083 0.166388 -vn -1.397017 5.381206 2.333061 -v 0.041057 -0.091708 0.165308 -vn -1.399645 5.071980 2.943113 -v 0.041057 -0.091192 0.164287 -vn -1.406771 4.600885 3.630213 -v 0.041057 -0.090545 0.163345 -vn -1.405526 0.633241 5.826642 -v 0.041057 -0.084684 0.160132 -vn -1.406481 -4.325345 3.954132 -v 0.041057 -0.077478 0.162908 -vn -1.404248 -5.243851 2.616734 -v 0.041057 -0.076186 0.164789 -vn -1.403856 -5.521322 1.968612 -v 0.041057 -0.075740 0.165842 -vn -1.417199 -5.742518 1.136969 -v 0.041057 -0.075438 0.166945 -vn -1.406691 -4.851748 -3.287068 -v 0.041057 -0.076769 0.173495 -vn -1.399685 -3.756203 -4.502405 -v 0.041057 -0.078300 0.175187 -vn -1.402439 -3.196695 -4.914444 -v 0.041057 -0.079220 0.175866 -vn -1.406658 -2.460376 -5.319194 -v 0.041057 -0.080223 0.176415 -vn -1.406795 2.068435 -5.483058 -v 0.041057 -0.086904 0.176639 -vn 1.467415 5.007827 3.015457 -v 0.040958 -0.091192 0.164288 -vn 1.473952 5.391592 2.247977 -v 0.040958 -0.091708 0.165308 -vn 1.457332 2.766472 5.155647 -v 0.040958 -0.087941 0.161143 -vn 1.467055 3.452115 4.717637 -v 0.040958 -0.088904 0.161759 -vn 1.460086 2.151362 5.439656 -v 0.040958 -0.086903 0.160662 -vn 3.633403 1.927589 4.658748 -v 0.040872 -0.086886 0.160706 -vn 3.293170 1.586632 4.951069 -v 0.040872 -0.086611 0.160605 -vn 1.468580 -2.483552 5.290016 -v 0.040958 -0.080224 0.160885 -vn 1.467396 -1.768075 5.571750 -v 0.040958 -0.081291 0.160474 -vn 1.465158 -3.105979 4.953520 -v 0.040958 -0.079221 0.161435 -vn 3.630630 -2.624750 4.303660 -v 0.040872 -0.079246 0.161475 -vn 3.198428 -3.088825 4.219842 -v 0.040872 -0.078889 0.161716 -vn 1.478612 -5.198327 2.658540 -v 0.040958 -0.076187 0.164789 -vn 1.459237 -4.794772 3.351254 -v 0.040958 -0.076770 0.163805 -vn 1.461134 -5.723508 -1.201702 -v 0.040958 -0.075438 0.170355 -vn 1.467270 -5.830213 -0.423661 -v 0.040958 -0.075286 0.169222 -vn 1.463950 -5.539866 -1.871718 -v 0.040958 -0.075740 0.171458 -vn 3.630760 -4.797105 -1.551311 -v 0.040872 -0.075785 0.171442 -vn 3.209596 -4.827396 -2.013845 -v 0.040872 -0.075924 0.171814 -vn 1.476974 -3.793473 -4.439478 -v 0.040958 -0.078300 0.175187 -vn 1.458276 -4.371679 -3.887843 -v 0.040958 -0.077478 0.174392 -vn 1.457936 -0.150594 -5.848354 -v 0.040958 -0.083541 0.177205 -vn 1.467188 -0.944077 -5.769080 -v 0.040958 -0.082403 0.177091 -vn 1.462495 0.535162 -5.823981 -v 0.040958 -0.084684 0.177167 -vn 3.630805 0.392017 -5.027085 -v 0.040872 -0.084679 0.177120 -vn 3.232766 0.832457 -5.155554 -v 0.040872 -0.085038 0.177076 -vn 1.484131 4.573565 -3.622420 -v 0.040958 -0.090545 0.173955 -vn 1.466466 4.096647 -4.170287 -v 0.040958 -0.089778 0.174803 -vn 1.461075 5.789747 -0.830804 -v 0.040958 -0.092311 0.169791 -vn 1.457201 5.655993 -1.498303 -v 0.040958 -0.092083 0.170912 -vn -1.406874 5.813698 -0.736474 -v 0.041057 -0.092311 0.169791 -vn 1.467416 5.845808 -0.000004 -v 0.040958 -0.092387 0.168650 -vn 3.633141 4.979079 0.788242 -v 0.040872 -0.092264 0.167515 -vn 3.262057 5.195925 0.391551 -v 0.040872 -0.092301 0.167841 -vn 3.622731 4.667336 1.911654 -v 0.040872 -0.091664 0.165327 -vn 3.164755 4.676628 2.376009 -v 0.040872 -0.091393 0.164749 -vn 3.630577 4.288408 2.647103 -v 0.040872 -0.091151 0.164312 -vn 1.483499 4.573164 3.623614 -v 0.040958 -0.090545 0.163345 -vn 3.637469 3.853729 3.254914 -v 0.040872 -0.090508 0.163374 -vn 3.622689 4.074998 2.986065 -v 0.040872 -0.090518 0.163388 -vn 1.466800 4.096670 4.170280 -v 0.040958 -0.089778 0.162497 -vn 3.630917 3.574236 3.553136 -v 0.040872 -0.089745 0.162531 -vn 3.175944 3.397583 3.991513 -v 0.040872 -0.089401 0.162217 -vn 3.635042 2.299945 4.487609 -v 0.040872 -0.087918 0.161185 -vn 3.404856 2.710998 4.384864 -v 0.040872 -0.088083 0.161278 -vn 3.630656 2.957200 4.080872 -v 0.040872 -0.088876 0.161797 -vn 3.632816 1.178719 4.897936 -v 0.040872 -0.085800 0.160369 -vn 1.462383 0.535133 5.823754 -v 0.040958 -0.084684 0.160133 -vn 3.633739 0.393935 5.024239 -v 0.040872 -0.084679 0.160180 -vn 3.236198 0.830399 5.152798 -v 0.040872 -0.085038 0.160224 -vn 1.472691 -0.934800 5.766980 -v 0.040958 -0.082403 0.160209 -vn 3.624451 -0.770063 4.983747 -v 0.040872 -0.082411 0.160256 -vn 3.158933 -1.222064 5.103069 -v 0.040872 -0.081820 0.160377 -vn 3.636457 -2.266891 4.506351 -v 0.040872 -0.080244 0.160928 -vn 3.584884 -1.944105 4.683607 -v 0.040872 -0.080290 0.160907 -vn 3.631047 -1.570786 4.788211 -v 0.040872 -0.081305 0.160519 -vn 3.640277 -3.265467 3.826263 -v 0.040872 -0.078331 0.162149 -vn 1.458037 -4.374550 3.885411 -v 0.040958 -0.077478 0.162908 -vn 3.635375 -3.828570 3.279880 -v 0.040872 -0.077513 0.162940 -vn 3.364510 -3.641443 3.672156 -v 0.040872 -0.077666 0.162776 -vn 3.634871 -4.080857 2.959621 -v 0.040872 -0.076809 0.163832 -vn 3.630765 -4.797115 1.551290 -v 0.040872 -0.075785 0.165858 -vn 3.210224 -4.826468 2.014227 -v 0.040872 -0.075924 0.165486 -vn 3.621904 -4.480375 2.312514 -v 0.040872 -0.076229 0.164811 -vn 3.209171 -4.490407 2.677766 -v 0.040872 -0.076665 0.164048 -vn 1.470967 -5.827340 0.429800 -v 0.040958 -0.075286 0.168078 -vn 3.626445 -5.024721 0.414112 -v 0.040872 -0.075333 0.168081 -vn 3.157233 -5.247444 -0.000574 -v 0.040872 -0.075314 0.168650 -vn 3.636731 -4.909610 -1.153738 -v 0.040872 -0.075485 0.170346 -vn 3.542079 -5.030160 -0.789392 -v 0.040872 -0.075468 0.170261 -vn 3.631866 -5.022051 -0.407183 -v 0.040872 -0.075333 0.169219 -vn 3.630742 -4.488405 -2.291739 -v 0.040872 -0.076229 0.172489 -vn 1.458748 -4.793070 -3.354529 -v 0.040958 -0.076770 0.173495 -vn 3.634800 -4.080877 -2.959705 -v 0.040872 -0.076809 0.173468 -vn 3.326540 -4.433582 -2.691912 -v 0.040872 -0.076665 0.173252 -vn 3.635379 -3.828565 -3.279885 -v 0.040872 -0.077513 0.174360 -vn 3.630631 -2.624751 -4.303658 -v 0.040872 -0.079246 0.175825 -vn 3.190783 -3.087005 -4.230344 -v 0.040872 -0.078889 0.175584 -vn 3.620747 -3.293663 -3.820248 -v 0.040872 -0.078331 0.175151 -vn 3.275775 -3.641952 -3.719731 -v 0.040872 -0.077666 0.174524 -vn 1.469606 -1.771240 -5.569226 -v 0.040958 -0.081291 0.176826 -vn 3.628869 -1.575072 -4.787724 -v 0.040872 -0.081305 0.176781 -vn 3.160571 -1.220107 -5.101771 -v 0.040872 -0.081820 0.176923 -vn 3.634633 -0.019615 -5.044531 -v 0.040872 -0.083542 0.177158 -vn 3.494557 -0.416831 -5.097898 -v 0.040872 -0.083422 0.177153 -vn 3.632852 -0.779136 -4.976817 -v 0.040872 -0.082411 0.177044 -vn 3.630794 1.178740 -4.899791 -v 0.040872 -0.085800 0.176931 -vn 1.460071 2.151364 -5.439653 -v 0.040958 -0.086903 0.176638 -vn 3.633713 1.927230 -4.658574 -v 0.040872 -0.086886 0.176594 -vn 3.292335 1.588012 -4.951398 -v 0.040872 -0.086611 0.176695 -vn 1.475197 3.437902 -4.721498 -v 0.040958 -0.088904 0.175541 -vn 3.621705 2.947438 -4.093025 -v 0.040872 -0.088876 0.175503 -vn 3.175944 3.397583 -3.991513 -v 0.040872 -0.089401 0.175083 -vn 3.168390 4.674770 -2.371921 -v 0.040872 -0.091393 0.172551 -vn 3.631669 4.285830 -2.648465 -v 0.040872 -0.091151 0.172988 -vn 1.468145 5.006758 -3.016306 -v 0.040958 -0.091192 0.173012 -vn 3.623299 4.076863 -2.982124 -v 0.040872 -0.090518 0.173912 -vn 3.637282 3.854542 -3.253917 -v 0.040872 -0.090508 0.173926 -vn 3.630917 3.574238 -3.553135 -v 0.040872 -0.089745 0.174769 -vn 3.634875 4.654457 -1.921655 -v 0.040872 -0.091664 0.171973 -vn 3.449242 4.878044 -1.605491 -v 0.040872 -0.091995 0.171048 -vn 3.631467 5.038971 0.000001 -v 0.040872 -0.092339 0.168650 -vn 3.260934 5.197088 -0.390631 -v 0.040872 -0.092301 0.169459 -vn 3.631955 4.980058 -0.789417 -v 0.040872 -0.092264 0.169785 -vn 3.634416 4.900770 -1.193074 -v 0.040872 -0.092037 0.170899 -vn 4.083569 -4.475473 1.653771 -v 0.037314 -0.079007 0.166721 -vn 3.791631 -4.487697 2.166675 -v 0.037314 -0.079096 0.166512 -vn 3.963940 -4.193058 2.465007 -v 0.037314 -0.079459 0.165843 -vn 3.795973 -4.023797 2.933314 -v 0.037314 -0.079526 0.165743 -vn 3.802367 -3.739803 3.282956 -v 0.037314 -0.080070 0.165067 -vn 3.781355 -3.459722 3.597799 -v 0.037314 -0.080079 0.165058 -vn 3.790265 -3.115870 3.890397 -v 0.037314 -0.080740 0.164476 -vn 3.950323 -2.647030 4.091172 -v 0.037314 -0.080815 0.164421 -vn 3.803327 -2.370909 4.372753 -v 0.037314 -0.081490 0.164014 -vn 3.795421 0.224914 4.975050 -v 0.037314 -0.084047 0.163463 -vn 4.171067 -0.207548 4.692840 -v 0.037314 -0.083580 0.163464 -vn 3.796365 -0.668745 4.934097 -v 0.037314 -0.083167 0.163501 -vn 4.140091 -1.034357 4.609501 -v 0.037314 -0.082603 0.163605 -vn 3.808175 -1.563038 4.719059 -v 0.037314 -0.082307 0.163686 -vn 4.138516 -1.794213 4.370732 -v 0.037314 -0.081670 0.163928 -vn 3.796376 3.750204 3.274619 -v 0.037314 -0.087866 0.165389 -vn 3.796388 3.435277 3.603131 -v 0.037314 -0.087257 0.164753 -vn 3.848779 3.074150 3.871688 -v 0.037314 -0.087227 0.164727 -vn 3.797868 2.746851 4.151220 -v 0.037314 -0.086549 0.164229 -vn 4.001134 2.262248 4.274035 -v 0.037314 -0.086423 0.164154 -vn 3.796323 1.961959 4.576432 -v 0.037314 -0.085762 0.163833 -vn 4.105181 1.443751 4.528997 -v 0.037314 -0.085525 0.163744 -vn 3.793747 1.110844 4.856231 -v 0.037314 -0.084921 0.163575 -vn 4.158290 0.621759 4.667378 -v 0.037314 -0.084566 0.163511 -vn 3.814399 4.880508 0.920617 -v 0.037314 -0.088944 0.167773 -vn 4.264602 4.463292 1.157527 -v 0.037314 -0.088808 0.167187 -vn 3.808951 4.645082 1.767957 -v 0.037314 -0.088722 0.166920 -vn 4.096295 4.315167 2.008862 -v 0.037314 -0.088441 0.166271 -vn 3.800760 4.264196 2.564782 -v 0.037314 -0.088359 0.166118 -vn 3.898767 3.992492 2.857854 -v 0.037314 -0.087908 0.165441 -vn 4.119466 4.575370 -1.245201 -v 0.037314 -0.088808 0.170113 -vn 3.796714 4.898471 -0.891757 -v 0.037314 -0.088944 0.169527 -vn 4.167190 4.682673 -0.412656 -v 0.037314 -0.088995 0.169143 -vn 3.794939 4.980547 0.000000 -v 0.037314 -0.089018 0.168650 -vn 4.166183 4.683488 0.413653 -v 0.037314 -0.088995 0.168157 -vn 3.805638 1.974755 -4.563866 -v 0.037314 -0.085762 0.173467 -vn 4.047539 2.221508 -4.254199 -v 0.037314 -0.086423 0.173146 -vn 3.797868 2.746851 -4.151220 -v 0.037314 -0.086549 0.173071 -vn 3.848779 3.074150 -3.871688 -v 0.037314 -0.087227 0.172573 -vn 3.796390 3.435278 -3.603129 -v 0.037314 -0.087257 0.172547 -vn 3.796381 3.750174 -3.274614 -v 0.037314 -0.087866 0.171911 -vn 3.884880 3.995799 -2.870965 -v 0.037314 -0.087908 0.171859 -vn 3.792950 4.272715 -2.562332 -v 0.037314 -0.088359 0.171182 -vn 4.029774 4.351616 -2.059137 -v 0.037314 -0.088441 0.171029 -vn 3.789273 4.667213 -1.752884 -v 0.037314 -0.088722 0.170380 -vn 4.167911 -0.210806 -4.695502 -v 0.037314 -0.083580 0.173836 -vn 3.796989 0.223230 -4.973736 -v 0.037314 -0.084047 0.173837 -vn 4.161421 0.621761 -4.664552 -v 0.037314 -0.084566 0.173789 -vn 3.812947 1.136328 -4.835796 -v 0.037314 -0.084921 0.173725 -vn 4.225247 1.369169 -4.441517 -v 0.037314 -0.085525 0.173556 -vn 3.796133 -4.023595 -2.933349 -v 0.037314 -0.079526 0.171557 -vn 3.809993 -3.738510 -3.274387 -v 0.037314 -0.080070 0.172233 -vn 3.796142 -3.448453 -3.590261 -v 0.037314 -0.080079 0.172242 -vn 3.797921 -3.106297 -3.889323 -v 0.037314 -0.080740 0.172824 -vn 3.929471 -2.669003 -4.095267 -v 0.037314 -0.080815 0.172879 -vn 3.797682 -2.363346 -4.381327 -v 0.037314 -0.081490 0.173286 -vn 4.059034 -1.853484 -4.418026 -v 0.037314 -0.081670 0.173372 -vn 3.794524 -1.544025 -4.735536 -v 0.037314 -0.082307 0.173614 -vn 4.137677 -1.033121 -4.611991 -v 0.037314 -0.082603 0.173695 -vn 3.791082 -0.668132 -4.938911 -v 0.037314 -0.083167 0.173799 -vn 3.811822 -4.781562 -1.349063 -v 0.037314 -0.078803 0.169958 -vn 4.184705 -4.409029 -1.582306 -v 0.037314 -0.079007 0.170579 -vn 3.805173 -4.472292 -2.174287 -v 0.037314 -0.079096 0.170788 -vn 3.999802 -4.178553 -2.434750 -v 0.037314 -0.079459 0.171457 -vn 3.797319 -4.798393 1.326778 -v 0.037314 -0.078803 0.167342 -vn 4.150569 -4.642265 0.826335 -v 0.037314 -0.078729 0.167667 -vn 3.795673 -4.959653 0.448710 -v 0.037314 -0.078654 0.168210 -vn 4.172367 -4.696297 -0.000803 -v 0.037314 -0.078635 0.168650 -vn 3.793295 -4.961690 -0.449584 -v 0.037314 -0.078654 0.169090 -vn 4.148659 -4.644135 -0.825563 -v 0.037314 -0.078729 0.169633 -vn -4.497765 3.230889 -2.943160 -v 0.037024 -0.087818 0.171999 -vn -4.379058 2.990741 -3.332903 -v 0.037024 -0.087269 0.172561 -vn -2.864930 3.655439 -4.094790 -v 0.037087 -0.087235 0.172523 -vn -4.688982 2.496038 -3.352873 -v 0.037024 -0.086938 0.172829 -vn -4.348163 2.262991 -3.905589 -v 0.037024 -0.086558 0.173086 -vn -2.856442 2.840605 -4.703405 -v 0.037087 -0.086532 0.173043 -vn -4.593038 0.621718 -4.234574 -v 0.037024 -0.084731 0.173781 -vn -4.328812 0.169910 -4.530237 -v 0.037024 -0.084048 0.173855 -vn -2.865124 0.250735 -5.483414 -v 0.037087 -0.084046 0.173805 -vn -4.459876 -3.781168 -2.257621 -v 0.037024 -0.079474 0.171513 -vn -4.238894 -4.211864 -1.913964 -v 0.037024 -0.079080 0.170796 -vn -2.864760 -4.982817 -2.302300 -v 0.037087 -0.079125 0.170775 -vn -4.675197 -3.940252 -1.438854 -v 0.037024 -0.078931 0.170432 -vn -4.111835 -4.631680 -1.033743 -v 0.037024 -0.078785 0.169963 -vn -2.854776 -5.329463 -1.342255 -v 0.037087 -0.078834 0.169950 -vn -4.587550 -4.236243 0.621902 -v 0.037024 -0.078652 0.168045 -vn -4.317643 -4.410329 1.106636 -v 0.037024 -0.078785 0.167337 -vn -2.865042 -5.318159 1.359083 -v 0.037087 -0.078834 0.167350 -vn -4.698946 -3.922620 1.410234 -v 0.037024 -0.078931 0.166868 -vn -4.346623 -4.087459 1.920253 -v 0.037024 -0.079080 0.166504 -vn -2.860597 -4.982067 2.310468 -v 0.037087 -0.079125 0.166525 -vn -4.653824 -2.827729 3.127335 -v 0.037024 -0.080252 0.164861 -vn -4.342696 -2.690268 3.634819 -v 0.037024 -0.080729 0.164461 -vn -2.846817 -3.247087 4.441016 -v 0.037087 -0.080759 0.164502 -vn -4.669835 0.580959 4.158388 -v 0.037024 -0.084731 0.163519 -vn -4.399716 1.049385 4.328168 -v 0.037024 -0.084924 0.163557 -vn -2.869742 1.213597 5.348280 -v 0.037087 -0.084914 0.163606 -vn -4.542996 1.859320 3.906821 -v 0.037024 -0.085890 0.163866 -vn -4.361756 2.281674 3.876538 -v 0.037024 -0.086558 0.164214 -vn -2.864729 2.850842 4.690771 -v 0.037087 -0.086532 0.164257 -vn -4.698774 2.489338 3.344161 -v 0.037024 -0.086938 0.164471 -vn -4.396642 2.990893 3.308084 -v 0.037024 -0.087269 0.164739 -vn -2.858698 3.666806 4.090157 -v 0.037087 -0.087235 0.164777 -vn -4.626464 3.846512 1.796600 -v 0.037024 -0.088482 0.166312 -vn -4.388083 4.201497 1.520459 -v 0.037024 -0.088739 0.166914 -vn -2.865114 5.171989 1.838732 -v 0.037087 -0.088691 0.166931 -vn -2.867053 -4.001215 -3.754039 -v 0.037087 -0.080102 0.172220 -vn -0.391924 -4.466647 -4.280957 -v 0.037165 -0.080117 0.172205 -vn -0.391979 -3.678870 -4.974167 -v 0.037165 -0.080771 0.172781 -vn -0.391844 1.303433 6.048139 -v 0.037165 -0.084909 0.163627 -vn -0.392178 0.262608 6.181249 -v 0.037165 -0.084045 0.163517 -vn 2.127970 -4.191905 -4.034944 -v 0.037245 -0.080109 0.172213 -vn 2.160834 -3.496022 -4.629172 -v 0.037245 -0.080765 0.172790 -vn 2.169673 1.249612 5.661654 -v 0.037245 -0.084912 0.163616 -vn 2.169973 0.251928 5.792574 -v 0.037245 -0.084045 0.163505 -vn 2.147232 3.862312 -4.337584 -v 0.037245 -0.087229 0.172516 -vn 2.164334 3.089143 -4.908119 -v 0.037245 -0.086527 0.173035 -vn 2.169990 0.251930 -5.792570 -v 0.037245 -0.084045 0.173795 -vn 2.162382 -4.773175 -3.295118 -v 0.037245 -0.079560 0.171534 -vn 2.170025 -5.776134 -0.503346 -v 0.037245 -0.078696 0.169087 -vn 2.170027 -5.776134 0.503349 -v 0.037245 -0.078696 0.168213 -vn 2.169701 -5.602165 1.494030 -v 0.037245 -0.078843 0.167352 -vn 2.168420 -5.261131 2.437106 -v 0.037245 -0.079134 0.166529 -vn 2.163387 -4.770088 3.299151 -v 0.037245 -0.079560 0.165766 -vn 2.168756 2.207568 5.361382 -v 0.037245 -0.085747 0.163872 -vn 2.165214 3.093344 4.905277 -v 0.037245 -0.086527 0.164265 -vn 2.155225 4.487538 3.680058 -v 0.037245 -0.087833 0.165415 -vn 2.149194 5.714757 1.038661 -v 0.037245 -0.088902 0.167780 -vn 2.170135 5.798036 0.000003 -v 0.037245 -0.088976 0.168650 -vn 2.155869 5.451799 1.992136 -v 0.037245 -0.088682 0.166935 -vn 2.160888 5.032996 2.884779 -v 0.037245 -0.088322 0.166139 -vn 2.169883 -0.753771 5.748941 -v 0.037245 -0.083173 0.163542 -vn 2.154254 -1.761761 5.531674 -v 0.037245 -0.082319 0.163726 -vn 2.160162 -2.669374 5.151246 -v 0.037245 -0.081508 0.164052 -vn 2.159659 -3.492316 4.632413 -v 0.037245 -0.080765 0.164510 -vn 2.158838 -5.260722 -2.448505 -v 0.037245 -0.079134 0.170771 -vn 2.167717 -2.661513 -5.151265 -v 0.037245 -0.081508 0.173248 -vn 2.169643 -1.735522 -5.532113 -v 0.037245 -0.082319 0.173574 -vn 2.169873 -0.753797 -5.748946 -v 0.037245 -0.083173 0.173758 -vn 2.157265 2.222521 -5.361033 -v 0.037245 -0.085747 0.173428 -vn 2.166459 5.032599 -2.880592 -v 0.037245 -0.088322 0.171161 -vn 2.169286 5.451792 -1.973540 -v 0.037245 -0.088682 0.170365 -vn 2.169894 5.710662 -1.002664 -v 0.037245 -0.088902 0.169520 -vn -0.391961 6.097857 1.045584 -v 0.037165 -0.088891 0.167782 -vn -0.391863 6.186841 0.000003 -v 0.037165 -0.088965 0.168650 -vn -0.391555 -0.785853 6.136772 -v 0.037165 -0.083174 0.163553 -vn -0.391927 -1.811672 5.915758 -v 0.037165 -0.082322 0.163737 -vn -0.391903 -2.785345 5.524300 -v 0.037165 -0.081514 0.164062 -vn -0.391975 -3.678869 4.974166 -v 0.037165 -0.080771 0.164519 -vn -0.391936 -2.785364 -5.524459 -v 0.037165 -0.081514 0.173238 -vn -0.391912 -1.811682 -5.915583 -v 0.037165 -0.082322 0.173563 -vn -0.391550 -0.785833 -6.136778 -v 0.037165 -0.083174 0.173747 -vn -0.391964 6.097853 -1.045596 -v 0.037165 -0.088891 0.169518 -vn -0.391780 5.833435 -2.061056 -v 0.037165 -0.088671 0.170362 -vn -0.391821 5.401273 -3.017313 -v 0.037165 -0.088312 0.171156 -vn -2.864170 5.419752 0.869922 -v 0.037087 -0.088912 0.167778 -vn -2.830276 5.512297 -0.000010 -v 0.037087 -0.088986 0.168650 -vn 2.147231 3.862310 4.337586 -v 0.037245 -0.087229 0.164784 -vn -0.391762 4.813601 3.886740 -v 0.037165 -0.087824 0.165422 -vn -0.392013 4.087476 4.644263 -v 0.037165 -0.087221 0.164793 -vn -2.869751 4.298069 3.405676 -v 0.037087 -0.087841 0.165409 -vn -2.852718 0.273933 5.490582 -v 0.037087 -0.084046 0.163495 -vn -2.862136 -0.752913 5.438649 -v 0.037087 -0.083171 0.163532 -vn -2.829867 -1.614161 5.270855 -v 0.037087 -0.082316 0.163717 -vn -2.865721 -2.419775 4.925479 -v 0.037087 -0.081504 0.164043 -vn -0.391850 -5.125870 3.464483 -v 0.037165 -0.079570 0.165773 -vn -0.391719 -5.637619 2.548341 -v 0.037165 -0.079145 0.166534 -vn -2.865705 -4.522994 3.105612 -v 0.037087 -0.079552 0.165761 -vn 2.152848 -5.602929 -1.523676 -v 0.037245 -0.078843 0.169948 -vn -0.392063 -6.164547 -0.524660 -v 0.037165 -0.078707 0.169086 -vn -0.391777 -5.987208 -1.558945 -v 0.037165 -0.078854 0.169945 -vn -2.871007 -5.468303 -0.406519 -v 0.037087 -0.078686 0.169088 -vn -2.848842 -3.297575 -4.401932 -v 0.037087 -0.080759 0.172798 -vn -2.865957 -2.416195 -4.927136 -v 0.037087 -0.081504 0.173257 -vn -2.830343 -1.614129 -5.270704 -v 0.037087 -0.082316 0.173583 -vn -2.862147 -0.752902 -5.438646 -v 0.037087 -0.083171 0.173768 -vn -0.391893 2.306783 -5.740742 -v 0.037165 -0.085743 0.173418 -vn -0.391632 3.243854 -5.268309 -v 0.037165 -0.086521 0.173025 -vn -2.871176 1.992353 -5.108225 -v 0.037087 -0.085750 0.173437 -vn -2.864120 5.419789 -0.869928 -v 0.037087 -0.088912 0.169522 -vn -2.850688 5.172131 -1.866923 -v 0.037087 -0.088691 0.170369 -vn -2.868522 4.759536 -2.726895 -v 0.037087 -0.088331 0.171166 -vn -0.391795 5.833431 2.061066 -v 0.037165 -0.088671 0.166938 -vn -4.676356 4.066012 1.025420 -v 0.037024 -0.088896 0.167449 -vn -4.376657 3.837700 2.312046 -v 0.037024 -0.088375 0.166109 -vn -2.869011 4.757312 2.730651 -v 0.037087 -0.088331 0.166134 -vn -0.391832 5.401274 3.017308 -v 0.037165 -0.088312 0.166144 -vn -4.401623 3.552353 2.679714 -v 0.037024 -0.087880 0.165377 -vn -4.523896 3.204719 2.933140 -v 0.037024 -0.087818 0.165301 -vn -0.391641 3.243826 5.268324 -v 0.037165 -0.086521 0.164275 -vn -4.348270 1.530573 4.244035 -v 0.037024 -0.085769 0.163816 -vn -2.871971 1.987918 5.109635 -v 0.037087 -0.085750 0.163863 -vn -0.391898 2.306822 5.740726 -v 0.037165 -0.085743 0.163882 -vn -4.372977 0.210428 4.482775 -v 0.037024 -0.084048 0.163445 -vn -4.689972 -0.189538 4.174088 -v 0.037024 -0.083524 0.163449 -vn -4.341950 -0.687939 4.468236 -v 0.037024 -0.083165 0.163483 -vn -4.426870 -1.313977 4.229730 -v 0.037024 -0.082301 0.163669 -vn -4.380667 -1.935529 4.036743 -v 0.037024 -0.081481 0.163998 -vn -4.792456 -2.123227 3.461840 -v 0.037024 -0.081222 0.164138 -vn -4.342698 -3.342933 3.041156 -v 0.037024 -0.080066 0.165045 -vn -2.867692 -4.003926 3.750878 -v 0.037087 -0.080102 0.165080 -vn -0.391548 -4.466649 4.280905 -v 0.037165 -0.080117 0.165095 -vn 2.128229 -4.191955 4.034886 -v 0.037245 -0.080109 0.165087 -vn -4.400097 -3.606833 2.608856 -v 0.037024 -0.079511 0.165733 -vn -4.483850 -3.750260 2.259510 -v 0.037024 -0.079474 0.165787 -vn -0.391923 -5.987215 1.558981 -v 0.037165 -0.078854 0.167355 -vn -4.377767 -4.471888 0.241620 -v 0.037024 -0.078636 0.168208 -vn -2.871696 -5.468440 0.401887 -v 0.037087 -0.078686 0.168212 -vn -0.392065 -6.164549 0.524663 -v 0.037165 -0.078707 0.168214 -vn -4.304029 -4.555369 -0.181705 -v 0.037024 -0.078636 0.169092 -vn -4.628375 -4.188375 -0.663013 -v 0.037024 -0.078652 0.169255 -vn -0.391719 -5.637620 -2.548339 -v 0.037165 -0.079145 0.170766 -vn -4.397815 -3.600186 -2.621596 -v 0.037024 -0.079511 0.171567 -vn -2.866811 -4.520196 -3.108644 -v 0.037087 -0.079552 0.171539 -vn -0.391863 -5.125873 -3.464478 -v 0.037165 -0.079570 0.171527 -vn -4.217175 -3.499076 -3.059026 -v 0.037024 -0.080066 0.172255 -vn -4.675440 -0.180754 -4.190776 -v 0.037024 -0.083524 0.173851 -vn -4.251991 -0.770994 -4.548461 -v 0.037024 -0.083165 0.173818 -vn -4.407000 -1.332616 -4.245207 -v 0.037024 -0.082301 0.173631 -vn -4.326841 -1.985940 -4.077341 -v 0.037024 -0.081481 0.173302 -vn -4.650413 -2.162299 -3.625407 -v 0.037024 -0.081222 0.173162 -vn -4.254419 -2.832662 -3.640083 -v 0.037024 -0.080729 0.172839 -vn -4.743709 -2.711365 -3.098682 -v 0.037024 -0.080252 0.172439 -vn -0.392187 0.262588 -6.181251 -v 0.037165 -0.084045 0.173783 -vn -4.374353 1.052458 -4.356448 -v 0.037024 -0.084924 0.173743 -vn -2.870805 1.217945 -5.347003 -v 0.037087 -0.084914 0.173694 -vn -0.391829 1.303431 -6.047966 -v 0.037165 -0.084909 0.173673 -vn 2.150979 1.282546 -5.664057 -v 0.037245 -0.084912 0.173684 -vn -4.303354 1.502763 -4.304761 -v 0.037024 -0.085769 0.173484 -vn -4.567895 1.880310 -3.870757 -v 0.037024 -0.085890 0.173434 -vn -0.392015 4.087455 -4.644284 -v 0.037165 -0.087221 0.172507 -vn -4.393073 3.562921 -2.681644 -v 0.037024 -0.087880 0.171923 -vn -2.870703 4.300558 -3.401838 -v 0.037087 -0.087841 0.171891 -vn -0.391780 4.813608 -3.886728 -v 0.037165 -0.087824 0.171878 -vn 2.156545 4.484335 -3.683209 -v 0.037245 -0.087833 0.171885 -vn -4.363725 3.841663 -2.332705 -v 0.037024 -0.088375 0.171191 -vn -4.394207 4.414364 0.642923 -v 0.037024 -0.088962 0.167770 -vn -4.398415 4.459723 -0.002098 -v 0.037024 -0.089036 0.168650 -vn -4.392313 4.416431 -0.642975 -v 0.037024 -0.088962 0.169530 -vn -4.673640 4.068487 -1.028092 -v 0.037024 -0.088896 0.169851 -vn -4.396572 4.186031 -1.542050 -v 0.037024 -0.088739 0.170386 -vn -4.702149 3.789476 -1.727577 -v 0.037024 -0.088482 0.170988 -vn -4.202575 1.849120 4.167547 -v 0.036884 -0.085987 0.163726 -vn -4.265007 1.216100 4.335859 -v 0.036884 -0.085147 0.163438 -vn -4.122405 0.769906 4.565454 -v 0.036884 -0.084761 0.163355 -vn -4.244355 0.334361 4.513146 -v 0.036884 -0.084271 0.163291 -vn -4.169963 -0.112135 4.598325 -v 0.036884 -0.083514 0.163282 -vn -4.229490 -0.507674 4.530331 -v 0.036884 -0.083383 0.163291 -vn -4.286000 -0.971261 4.376729 -v 0.036884 -0.082507 0.163438 -vn -4.078647 -4.638744 -0.393113 -v 0.036884 -0.078486 0.169274 -vn -4.385819 -4.320811 -0.094259 -v 0.036884 -0.078450 0.168650 -vn -4.139948 -4.599326 0.459656 -v 0.036884 -0.078486 0.168026 -vn -4.263658 -4.429359 0.853513 -v 0.036884 -0.078523 0.167765 -vn -4.235975 -4.349631 1.342690 -v 0.036884 -0.078741 0.166904 -vn -4.184478 -4.261570 1.713084 -v 0.036884 -0.078774 0.166811 -vn -4.274294 -3.972866 2.088667 -v 0.036884 -0.079098 0.166091 -vn -4.120914 -3.877039 2.532185 -v 0.036884 -0.079334 0.165695 -vn -4.289774 -3.482103 2.806865 -v 0.036884 -0.079584 0.165347 -vn -4.204936 -3.247563 3.231649 -v 0.036884 -0.080137 0.164739 -vn -4.241149 -2.961400 3.450371 -v 0.036884 -0.080185 0.164694 -vn -4.246720 -2.557457 3.739987 -v 0.036884 -0.080886 0.164149 -vn -4.048654 -2.238298 4.106297 -v 0.036884 -0.081138 0.163993 -vn -4.264489 -1.798206 4.116829 -v 0.036884 -0.081667 0.163726 -vn -4.158858 -1.418058 4.380679 -v 0.036884 -0.082285 0.163499 -vn -4.341013 -4.312799 -0.901581 -v 0.036884 -0.078523 0.169535 -vn -4.310797 -4.250995 -1.332539 -v 0.036884 -0.078741 0.170396 -vn -4.223058 -4.228895 -1.682161 -v 0.036884 -0.078774 0.170489 -vn -4.316508 -3.864649 -2.133919 -v 0.036884 -0.079098 0.171209 -vn -3.953402 -4.008186 -2.490919 -v 0.036884 -0.079334 0.171605 -vn -4.375422 -3.337522 -2.786697 -v 0.036884 -0.079584 0.171953 -vn -4.201964 -3.265923 -3.212237 -v 0.036884 -0.080137 0.172561 -vn -4.260464 -2.921910 -3.451550 -v 0.036884 -0.080185 0.172606 -vn -4.293331 -2.504572 -3.701540 -v 0.036884 -0.080886 0.173151 -vn -4.154021 -2.250699 -4.010820 -v 0.036884 -0.081138 0.173307 -vn -4.309985 -1.696812 -4.095773 -v 0.036884 -0.081667 0.173574 -vn -4.115308 -1.480860 -4.382525 -v 0.036884 -0.082285 0.173801 -vn -4.343276 -0.901194 -4.311284 -v 0.036884 -0.082507 0.173862 -vn -4.260033 -0.501801 -4.491669 -v 0.036884 -0.083383 0.174009 -vn -4.204229 -0.129723 -4.566114 -v 0.036884 -0.083514 0.174018 -vn -4.252170 0.402856 -4.485651 -v 0.036884 -0.084271 0.174009 -vn -3.981986 0.704473 -4.651088 -v 0.036884 -0.084761 0.173945 -vn -4.298986 1.235579 -4.282460 -v 0.036884 -0.085147 0.173862 -vn -4.213753 1.841964 -4.153615 -v 0.036884 -0.085987 0.173574 -vn -4.244637 2.404726 -3.840250 -v 0.036884 -0.086768 0.173151 -vn -4.141315 2.795099 -3.667760 -v 0.036884 -0.087038 0.172963 -vn -4.246756 3.117003 -3.272219 -v 0.036884 -0.087469 0.172606 -vn -4.137107 3.426473 -3.090043 -v 0.036884 -0.087946 0.172106 -vn -4.266906 3.658260 -2.635245 -v 0.036884 -0.088070 0.171953 -vn -4.237291 3.928262 -2.290375 -v 0.036884 -0.088556 0.171209 -vn -4.185953 4.154876 -1.936314 -v 0.036884 -0.088632 0.171063 -vn -4.214993 4.308598 -1.471019 -v 0.036884 -0.088912 0.170396 -vn -4.004493 4.541649 -1.192265 -v 0.036884 -0.089059 0.169890 -vn -4.239712 4.492088 -0.630582 -v 0.036884 -0.089130 0.169535 -vn -4.221111 4.534934 -0.001731 -v 0.036884 -0.089204 0.168650 -vn -4.238095 4.494106 0.631515 -v 0.036884 -0.089130 0.167765 -vn -4.130453 4.486773 1.109879 -v 0.036884 -0.089059 0.167410 -vn -4.223949 4.287265 1.522672 -v 0.036884 -0.088912 0.166904 -vn -4.154151 4.185961 1.923350 -v 0.036884 -0.088632 0.166237 -vn -4.230371 3.938951 2.289647 -v 0.036884 -0.088556 0.166091 -vn -4.255883 3.661906 2.654918 -v 0.036884 -0.088070 0.165347 -vn -4.170199 3.438662 3.050614 -v 0.036884 -0.087946 0.165194 -vn -4.228549 3.084453 3.327418 -v 0.036884 -0.087469 0.164694 -vn -4.026556 2.888104 3.690910 -v 0.036884 -0.087038 0.164337 -vn -4.230980 2.410194 3.857772 -v 0.036884 -0.086768 0.164149 -vn -2.212597 5.525797 0.885007 -v 0.036689 -0.089272 0.167741 -vn -2.219845 5.278112 1.842758 -v 0.036689 -0.089048 0.166858 -vn -2.214606 4.908902 2.681847 -v 0.036689 -0.088681 0.166023 -vn -2.210417 4.437696 3.411606 -v 0.036689 -0.088183 0.165260 -vn -2.228369 3.769001 4.119515 -v 0.036689 -0.087565 0.164589 -vn -2.213639 3.036268 4.699272 -v 0.036689 -0.086846 0.164029 -vn -2.239136 2.239224 5.104910 -v 0.036689 -0.086044 0.163595 -vn -2.213741 1.408129 5.415229 -v 0.036689 -0.085182 0.163299 -vn -2.218241 0.430762 5.575239 -v 0.036689 -0.084283 0.163149 -vn -2.216763 -0.480760 5.571269 -v 0.036689 -0.083371 0.163149 -vn -2.209937 -1.339835 5.435276 -v 0.036689 -0.082472 0.163299 -vn -2.226631 -2.261537 5.106683 -v 0.036689 -0.081609 0.163595 -vn -2.212960 -3.083877 4.668673 -v 0.036689 -0.080808 0.164029 -vn -2.222360 -3.773154 4.121386 -v 0.036689 -0.080088 0.164589 -vn -2.211582 -4.399491 3.460367 -v 0.036689 -0.079471 0.165260 -vn -2.216704 -4.934506 2.633045 -v 0.036689 -0.078972 0.166023 -vn -2.220045 -5.291381 1.800548 -v 0.036689 -0.078606 0.166858 -vn -2.210144 -5.515449 0.957526 -v 0.036689 -0.078382 0.167741 -vn -2.224895 -5.586379 -0.022252 -v 0.036689 -0.078307 0.168650 -vn -2.212710 -5.514494 -0.948210 -v 0.036689 -0.078382 0.169559 -vn -2.217271 -5.295812 -1.795276 -v 0.036689 -0.078606 0.170442 -vn -2.233846 -4.902351 -2.663041 -v 0.036689 -0.078972 0.171277 -vn -2.216837 -4.396757 -3.455975 -v 0.036689 -0.079471 0.172040 -vn -2.224723 -3.775319 -4.116564 -v 0.036689 -0.080088 0.172711 -vn -2.210600 -3.092641 -4.665729 -v 0.036689 -0.080808 0.173271 -vn -2.223165 -2.222018 -5.127109 -v 0.036689 -0.081609 0.173705 -vn -2.212672 -1.347935 -5.430545 -v 0.036689 -0.082472 0.174001 -vn -2.213794 -0.488515 -5.573327 -v 0.036689 -0.083371 0.174151 -vn -2.231992 0.472439 -5.560511 -v 0.036689 -0.084283 0.174151 -vn -2.215586 1.399775 -5.415376 -v 0.036689 -0.085182 0.174001 -vn -2.239141 2.239228 -5.104906 -v 0.036689 -0.086044 0.173705 -vn -2.211463 3.030167 -4.705853 -v 0.036689 -0.086846 0.173271 -vn -2.221444 3.805240 -4.093839 -v 0.036689 -0.087565 0.172711 -vn -2.213309 4.430176 -3.416878 -v 0.036689 -0.088183 0.172040 -vn -2.211662 4.907320 -2.690466 -v 0.036689 -0.088681 0.171277 -vn -2.230200 5.284246 -1.798842 -v 0.036689 -0.089048 0.170442 -vn -2.214591 5.522398 -0.893000 -v 0.036689 -0.089272 0.169559 -vn -2.239153 5.574355 -0.000006 -v 0.036689 -0.089347 0.168650 -vn 0.607371 5.887396 -0.982424 -v 0.036449 -0.089305 0.169564 -vn 0.607377 5.645411 -1.938060 -v 0.036449 -0.089080 0.170453 -vn 0.607373 5.249403 -2.840827 -v 0.036449 -0.088712 0.171294 -vn 0.607382 4.710233 -3.666133 -v 0.036449 -0.088210 0.172062 -vn 0.607351 4.042590 -4.391429 -v 0.036449 -0.087589 0.172736 -vn 0.607331 3.264630 -4.996905 -v 0.036449 -0.086865 0.173300 -vn 0.607325 2.397657 -5.466070 -v 0.036449 -0.086058 0.173736 -vn 0.607417 1.465264 -5.786171 -v 0.036449 -0.085190 0.174034 -vn 0.607269 0.492926 -5.948442 -v 0.036449 -0.084285 0.174185 -vn 0.607268 -0.492908 -5.948448 -v 0.036449 -0.083368 0.174185 -vn 0.607413 -1.465295 -5.786165 -v 0.036449 -0.082463 0.174034 -vn 0.607331 -2.397639 -5.466076 -v 0.036449 -0.081596 0.173736 -vn 0.607393 -3.264636 -4.996910 -v 0.036449 -0.080789 0.173300 -vn 0.607356 -4.042589 -4.391430 -v 0.036449 -0.080065 0.172736 -vn 0.607372 -4.710236 -3.666130 -v 0.036449 -0.079444 0.172062 -vn 0.607372 -5.249403 -2.840829 -v 0.036449 -0.078942 0.171294 -vn 0.607378 -5.645410 -1.938061 -v 0.036449 -0.078573 0.170453 -vn 0.607380 -5.887395 -0.982420 -v 0.036449 -0.078348 0.169564 -vn 0.607347 -5.968843 -0.000003 -v 0.036449 -0.078273 0.168650 -vn 0.607345 -5.887408 0.982416 -v 0.036449 -0.078348 0.167736 -vn 0.607374 -5.645411 1.938065 -v 0.036449 -0.078573 0.166847 -vn 0.607373 -5.249403 2.840827 -v 0.036449 -0.078942 0.166006 -vn 0.607382 -4.710233 3.666133 -v 0.036449 -0.079444 0.165238 -vn 0.607355 -4.042595 4.391426 -v 0.036449 -0.080065 0.164564 -vn 0.607378 -3.264627 4.996918 -v 0.036449 -0.080789 0.164000 -vn 0.607325 -2.397657 5.466070 -v 0.036449 -0.081596 0.163564 -vn 0.607417 -1.465264 5.786171 -v 0.036449 -0.082463 0.163266 -vn 0.607269 -0.492926 5.948442 -v 0.036449 -0.083368 0.163115 -vn 0.607268 0.492908 5.948448 -v 0.036449 -0.084285 0.163115 -vn 0.607413 1.465295 5.786165 -v 0.036449 -0.085190 0.163266 -vn 0.607327 2.397643 5.466073 -v 0.036449 -0.086058 0.163564 -vn 0.607346 3.264629 4.996904 -v 0.036449 -0.086865 0.164000 -vn 0.607356 4.042589 4.391430 -v 0.036449 -0.087589 0.164564 -vn 0.607372 4.710236 3.666130 -v 0.036449 -0.088210 0.165238 -vn 0.607372 5.249403 2.840829 -v 0.036449 -0.088712 0.166006 -vn 0.607378 5.645410 1.938061 -v 0.036449 -0.089080 0.166847 -vn 0.607356 5.887406 0.982418 -v 0.036449 -0.089305 0.167736 -vn 0.607346 5.968843 0.000001 -v 0.036449 -0.089381 0.168650 -vn 3.323310 4.948545 -0.825764 -v 0.036221 -0.089224 0.169551 -vn 3.323315 4.745113 -1.628991 -v 0.036221 -0.089002 0.170427 -vn 3.323330 4.412264 -2.387799 -v 0.036221 -0.088639 0.171254 -vn 3.323292 3.959076 -3.081481 -v 0.036221 -0.088145 0.172011 -vn 3.323262 3.397860 -3.691090 -v 0.036221 -0.087533 0.172676 -vn 3.323283 2.744007 -4.200039 -v 0.036221 -0.086820 0.173231 -vn 3.323319 2.015261 -4.594376 -v 0.036221 -0.086025 0.173661 -vn 3.323326 1.231600 -4.863428 -v 0.036221 -0.085170 0.173954 -vn 3.323287 0.414313 -4.999752 -v 0.036221 -0.084279 0.174103 -vn 3.323301 -0.414313 -4.999743 -v 0.036221 -0.083375 0.174103 -vn 3.323335 -1.231598 -4.863422 -v 0.036221 -0.082484 0.173954 -vn 3.323314 -2.015268 -4.594374 -v 0.036221 -0.081629 0.173661 -vn 3.323274 -2.744003 -4.200046 -v 0.036221 -0.080834 0.173231 -vn 3.323260 -3.397860 -3.691092 -v 0.036221 -0.080121 0.172676 -vn 3.323300 -3.959071 -3.081481 -v 0.036221 -0.079509 0.172011 -vn 3.323330 -4.412268 -2.387794 -v 0.036221 -0.079014 0.171254 -vn 3.323318 -4.745110 -1.628988 -v 0.036221 -0.078651 0.170427 -vn 3.323305 -4.948546 -0.825764 -v 0.036221 -0.078430 0.169551 -vn 3.323257 -5.016950 -0.000006 -v 0.036221 -0.078355 0.168650 -vn 3.323295 -4.948534 0.825781 -v 0.036221 -0.078430 0.167749 -vn 3.323318 -4.745110 1.628997 -v 0.036221 -0.078651 0.166873 -vn 3.323330 -4.412264 2.387799 -v 0.036221 -0.079014 0.166046 -vn 3.323292 -3.959076 3.081481 -v 0.036221 -0.079509 0.165289 -vn 3.323262 -3.397860 3.691090 -v 0.036221 -0.080121 0.164624 -vn 3.323283 -2.744007 4.200039 -v 0.036221 -0.080834 0.164069 -vn 3.323319 -2.015261 4.594376 -v 0.036221 -0.081629 0.163639 -vn 3.323326 -1.231600 4.863428 -v 0.036221 -0.082484 0.163346 -vn 3.323215 -0.414334 4.999836 -v 0.036221 -0.083375 0.163197 -vn 3.323221 0.414322 4.999836 -v 0.036221 -0.084279 0.163197 -vn 3.323328 1.231613 4.863427 -v 0.036221 -0.085170 0.163346 -vn 3.323314 2.015268 4.594374 -v 0.036221 -0.086025 0.163639 -vn 3.323274 2.744003 4.200046 -v 0.036221 -0.086820 0.164069 -vn 3.323260 3.397860 3.691092 -v 0.036221 -0.087533 0.164624 -vn 3.323300 3.959071 3.081481 -v 0.036221 -0.088145 0.165289 -vn 3.323330 4.412268 2.387794 -v 0.036221 -0.088639 0.166046 -vn 3.323316 4.745111 1.628994 -v 0.036221 -0.089002 0.166873 -vn 3.323286 4.948536 0.825784 -v 0.036221 -0.089224 0.167749 -vn 3.323259 5.016949 0.000002 -v 0.036221 -0.089299 0.168650 -vn 5.311654 2.865821 -0.478226 -v 0.036059 -0.089047 0.169521 -vn 5.311690 2.747999 -0.943396 -v 0.036059 -0.088832 0.170368 -vn 5.311683 2.555249 -1.382826 -v 0.036059 -0.088481 0.171169 -vn 5.311681 2.292795 -1.784550 -v 0.036059 -0.088003 0.171900 -vn 5.311719 1.967757 -2.137571 -v 0.036059 -0.087411 0.172543 -vn 5.311667 1.589140 -2.432349 -v 0.036059 -0.086721 0.173080 -vn 5.311701 1.167086 -2.660716 -v 0.036059 -0.085953 0.173496 -vn 5.311683 0.713256 -2.816530 -v 0.036059 -0.085126 0.173780 -vn 5.311765 0.239916 -2.895425 -v 0.036059 -0.084264 0.173924 -vn 5.311759 -0.239932 -2.895430 -v 0.036059 -0.083390 0.173924 -vn 5.311678 -0.713238 -2.816539 -v 0.036059 -0.082528 0.173780 -vn 5.311700 -1.167095 -2.660711 -v 0.036059 -0.081701 0.173496 -vn 5.311668 -1.589125 -2.432359 -v 0.036059 -0.080932 0.173080 -vn 5.311720 -1.967771 -2.137559 -v 0.036059 -0.080243 0.172543 -vn 5.311679 -2.292791 -1.784557 -v 0.036059 -0.079651 0.171900 -vn 5.311684 -2.555249 -1.382824 -v 0.036059 -0.079173 0.171169 -vn 5.311687 -2.748006 -0.943393 -v 0.036059 -0.078822 0.170368 -vn 5.311653 -2.865821 -0.478237 -v 0.036059 -0.078607 0.169521 -vn 5.311696 -2.905414 0.000005 -v 0.036059 -0.078535 0.168650 -vn 5.311666 -2.865815 0.478219 -v 0.036059 -0.078607 0.167779 -vn 5.311687 -2.748013 0.943399 -v 0.036059 -0.078822 0.166932 -vn 5.311683 -2.555249 1.382829 -v 0.036059 -0.079173 0.166131 -vn 5.311681 -2.292795 1.784550 -v 0.036059 -0.079651 0.165400 -vn 5.311712 -1.967780 2.137589 -v 0.036059 -0.080243 0.164757 -vn 5.311666 -1.589138 2.432354 -v 0.036059 -0.080932 0.164220 -vn 5.311701 -1.167086 2.660716 -v 0.036059 -0.081701 0.163804 -vn 5.311682 -0.713266 2.816532 -v 0.036059 -0.082528 0.163520 -vn 5.311675 -0.239941 2.895484 -v 0.036059 -0.083390 0.163376 -vn 5.311676 0.239944 2.895478 -v 0.036059 -0.084264 0.163376 -vn 5.311687 0.713256 2.816527 -v 0.036059 -0.085126 0.163520 -vn 5.311700 1.167095 2.660711 -v 0.036059 -0.085953 0.163804 -vn 5.311668 1.589125 2.432359 -v 0.036059 -0.086721 0.164220 -vn 5.311713 1.967789 2.137581 -v 0.036059 -0.087411 0.164757 -vn 5.311678 2.292796 1.784556 -v 0.036059 -0.088003 0.165400 -vn 5.311684 2.555249 1.382824 -v 0.036059 -0.088481 0.166131 -vn 5.311686 2.748014 0.943400 -v 0.036059 -0.088832 0.166932 -vn 5.311666 2.865814 0.478225 -v 0.036059 -0.089047 0.167779 -vn 5.311696 2.905416 -0.000006 -v 0.036059 -0.089119 0.168650 -vn 6.179245 0.788865 -0.131638 -v 0.036000 -0.088815 0.169482 -vn 6.179239 0.756460 -0.259689 -v 0.036000 -0.088610 0.170292 -vn 6.179241 0.703389 -0.380655 -v 0.036000 -0.088274 0.171057 -vn 6.179240 0.631146 -0.491242 -v 0.036000 -0.087817 0.171756 -vn 6.179244 0.541673 -0.588414 -v 0.036000 -0.087252 0.172370 -vn 6.179233 0.437459 -0.669576 -v 0.036000 -0.086593 0.172883 -vn 6.179236 0.321273 -0.732439 -v 0.036000 -0.085858 0.173281 -vn 6.179236 0.196338 -0.775328 -v 0.036000 -0.085068 0.173552 -vn 6.179240 0.066043 -0.797058 -v 0.036000 -0.084244 0.173690 -vn 6.179240 -0.066045 -0.797058 -v 0.036000 -0.083409 0.173690 -vn 6.179236 -0.196338 -0.775329 -v 0.036000 -0.082585 0.173552 -vn 6.179236 -0.321274 -0.732440 -v 0.036000 -0.081795 0.173281 -vn 6.179234 -0.437453 -0.669578 -v 0.036000 -0.081061 0.172883 -vn 6.179244 -0.541676 -0.588409 -v 0.036000 -0.080402 0.172370 -vn 6.179240 -0.631145 -0.491243 -v 0.036000 -0.079836 0.171756 -vn 6.179241 -0.703390 -0.380654 -v 0.036000 -0.079379 0.171057 -vn 6.179239 -0.756457 -0.259692 -v 0.036000 -0.079044 0.170292 -vn 6.179245 -0.788864 -0.131633 -v 0.036000 -0.078839 0.169482 -vn 6.179241 -0.799784 -0.000001 -v 0.036000 -0.078770 0.168650 -vn 6.179242 -0.788873 0.131642 -v 0.036000 -0.078839 0.167818 -vn 6.179235 -0.756474 0.259697 -v 0.036000 -0.079044 0.167008 -vn 6.179242 -0.703386 0.380657 -v 0.036000 -0.079379 0.166243 -vn 6.179240 -0.631146 0.491241 -v 0.036000 -0.079836 0.165544 -vn 6.179234 -0.541700 0.588440 -v 0.036000 -0.080402 0.164929 -vn 6.179234 -0.437452 0.669577 -v 0.036000 -0.081061 0.164417 -vn 6.179236 -0.321273 0.732439 -v 0.036000 -0.081795 0.164019 -vn 6.179238 -0.196343 0.775323 -v 0.036000 -0.082585 0.163748 -vn 6.179253 -0.066040 0.797010 -v 0.036000 -0.083409 0.163610 -vn 6.179252 0.066048 0.797015 -v 0.036000 -0.084244 0.163610 -vn 6.179236 0.196338 0.775329 -v 0.036000 -0.085068 0.163748 -vn 6.179236 0.321274 0.732440 -v 0.036000 -0.085858 0.164019 -vn 6.179233 0.437452 0.669578 -v 0.036000 -0.086593 0.164417 -vn 6.179234 0.541696 0.588442 -v 0.036000 -0.087252 0.164929 -vn 6.179240 0.631146 0.491237 -v 0.036000 -0.087817 0.165544 -vn 6.179242 0.703390 0.380654 -v 0.036000 -0.088274 0.166243 -vn 6.179235 0.756471 0.259703 -v 0.036000 -0.088610 0.167008 -vn 6.179243 0.788872 0.131637 -v 0.036000 -0.088815 0.167818 -vn 6.179242 0.799784 0.000001 -v 0.036000 -0.088884 0.168650 -vn 5.508965 -1.874018 0.812800 -v 0.036000 -0.082025 0.167904 -vn 5.507341 -2.046851 0.049193 -v 0.036000 -0.081877 0.168650 -vn 5.493523 0.812214 -1.895944 -v 0.036000 -0.084573 0.170452 -vn 5.485377 0.024096 -2.072889 -v 0.036000 -0.083827 0.170600 -vn 5.480045 -0.776985 -1.929474 -v 0.036000 -0.083081 0.170452 -vn 5.476740 -1.463399 -1.484452 -v 0.036000 -0.082448 0.170029 -vn 5.507046 -1.421365 1.469657 -v 0.036000 -0.082448 0.167271 -vn 5.506260 -0.752105 1.901739 -v 0.036000 -0.083081 0.166848 -vn 5.507106 0.029794 2.043508 -v 0.036000 -0.083827 0.166700 -vn 5.510295 0.803385 1.874927 -v 0.036000 -0.084573 0.166848 -vn 5.522417 1.879018 -0.760023 -v 0.036000 -0.085628 0.169396 -vn 5.505483 1.463696 -1.431947 -v 0.036000 -0.085206 0.170029 -vn 5.474945 -1.925116 -0.805833 -v 0.036000 -0.082025 0.169396 -vn 5.516479 1.449734 1.424732 -v 0.036000 -0.085206 0.167271 -vn 5.540291 2.005962 -0.000005 -v 0.036000 -0.085777 0.168650 -vn 5.526316 1.871141 0.765155 -v 0.036000 -0.085628 0.167904 -vn 2.274156 -5.001595 2.236451 -v 0.035800 -0.082210 0.167980 -vn 1.968982 -4.769452 3.144483 -v 0.035800 -0.082411 0.167621 -vn 2.281067 -3.717655 4.017807 -v 0.035800 -0.082589 0.167413 -vn 2.044784 -3.097849 4.736275 -v 0.035800 -0.082952 0.167134 -vn 2.287857 -1.838852 5.150607 -v 0.035800 -0.083157 0.167033 -vn 2.113326 -0.949479 5.527200 -v 0.035800 -0.083644 0.166910 -vn 2.294523 0.331545 5.454090 -v 0.035800 -0.083827 0.166900 -vn 2.174280 1.319013 5.401459 -v 0.035800 -0.084368 0.166986 -vn 2.301147 2.445165 4.880898 -v 0.035800 -0.084496 0.167033 -vn 2.227185 3.336477 4.393031 -v 0.035800 -0.084998 0.167350 -vn 2.307679 4.161855 3.525149 -v 0.035800 -0.085064 0.167413 -vn 2.271521 4.778656 2.678513 -v 0.035800 -0.085425 0.167938 -vn 2.314112 5.207107 1.606190 -v 0.035800 -0.085444 0.167980 -vn 2.393616 5.474804 -0.000016 -v 0.035800 -0.085577 0.168650 -vn 2.314069 5.207165 -1.605837 -v 0.035800 -0.085444 0.169320 -vn 2.282285 4.778526 -2.660863 -v 0.035800 -0.085425 0.169362 -vn 2.315559 4.148457 -3.531113 -v 0.035800 -0.085064 0.169887 -vn 2.255382 3.349336 -4.354653 -v 0.035800 -0.084998 0.169951 -vn 2.316828 2.415730 -4.881643 -v 0.035800 -0.084496 0.170267 -vn 2.228812 1.361769 -5.346488 -v 0.035800 -0.084368 0.170314 -vn 2.317835 0.291225 -5.437895 -v 0.035800 -0.083827 0.170400 -vn 2.204777 -0.860187 -5.470840 -v 0.035800 -0.083644 0.170390 -vn 2.318646 -1.880331 -5.110022 -v 0.035800 -0.083157 0.170267 -vn 2.185094 -2.953916 -4.704217 -v 0.035800 -0.082952 0.170166 -vn 2.319225 -3.745447 -3.951411 -v 0.035800 -0.082589 0.169887 -vn 2.171192 -4.575683 -3.169938 -v 0.035800 -0.082411 0.169679 -vn 2.319570 -5.001444 -2.150388 -v 0.035800 -0.082210 0.169320 -vn 2.164023 -5.459176 -1.117561 -v 0.035800 -0.082115 0.169014 -vn 2.267168 -5.482897 0.092033 -v 0.035800 -0.082077 0.168650 -vn 1.886030 -5.679762 1.001680 -v 0.035800 -0.082115 0.168286 -vn -2.314108 5.207114 1.606183 -v 0.034700 -0.085444 0.167980 -vn -2.393613 5.474806 -0.000004 -v 0.034700 -0.085577 0.168650 -vn -2.314072 5.207162 -1.605840 -v 0.034700 -0.085444 0.169320 -vn -2.271600 4.778831 -2.678230 -v 0.034700 -0.085425 0.169362 -vn -2.307679 4.161855 -3.525150 -v 0.034700 -0.085064 0.169887 -vn -2.227185 3.336477 -4.393031 -v 0.034700 -0.084998 0.169951 -vn -2.301196 2.444925 -4.881042 -v 0.034700 -0.084496 0.170267 -vn -2.174305 1.318766 -5.401437 -v 0.034700 -0.084368 0.170314 -vn -2.294577 0.331762 -5.453977 -v 0.034700 -0.083827 0.170400 -vn -2.113394 -0.949296 -5.527224 -v 0.034700 -0.083644 0.170390 -vn -2.287884 -1.839008 -5.150566 -v 0.034700 -0.083157 0.170267 -vn -2.044867 -3.097820 -4.736172 -v 0.034700 -0.082952 0.170166 -vn -2.281092 -3.717618 -4.017836 -v 0.034700 -0.082589 0.169887 -vn -1.968948 -4.769515 -3.144444 -v 0.034700 -0.082411 0.169679 -vn -2.274173 -5.001566 -2.236431 -v 0.034700 -0.082210 0.169320 -vn -1.886042 -5.679755 -1.001707 -v 0.034700 -0.082115 0.169014 -vn -2.267168 -5.482897 -0.092033 -v 0.034700 -0.082077 0.168650 -vn -2.164010 -5.459183 1.117533 -v 0.034700 -0.082115 0.168286 -vn -2.319548 -5.001474 2.150423 -v 0.034700 -0.082210 0.167980 -vn -2.171176 -4.575665 3.169968 -v 0.034700 -0.082411 0.167621 -vn -2.319214 -3.745495 3.951356 -v 0.034700 -0.082589 0.167413 -vn -2.185080 -2.953884 4.704313 -v 0.034700 -0.082952 0.167134 -vn -2.318619 -1.880175 5.110064 -v 0.034700 -0.083157 0.167033 -vn -2.204709 -0.860369 5.470816 -v 0.034700 -0.083644 0.166910 -vn -2.317782 0.291007 5.438008 -v 0.034700 -0.083827 0.166900 -vn -2.228793 1.362018 5.346508 -v 0.034700 -0.084368 0.166986 -vn -2.316779 2.415969 4.881498 -v 0.034700 -0.084496 0.167033 -vn -2.255382 3.349336 4.354653 -v 0.034700 -0.084998 0.167350 -vn -2.315559 4.148457 3.531114 -v 0.034700 -0.085064 0.167413 -vn -2.282206 4.778351 2.661146 -v 0.034700 -0.085425 0.167938 -vn -5.505483 1.463696 1.431947 -v 0.034500 -0.085206 0.167271 -vn -5.522409 1.879024 0.760028 -v 0.034500 -0.085628 0.167904 -vn -5.493497 0.812253 1.895960 -v 0.034500 -0.084573 0.166848 -vn -5.485327 0.024069 2.072944 -v 0.034500 -0.083827 0.166700 -vn -5.480027 -0.776971 1.929502 -v 0.034500 -0.083081 0.166848 -vn -5.476731 -1.463419 1.484450 -v 0.034500 -0.082448 0.167271 -vn -5.474927 -1.925134 0.805837 -v 0.034500 -0.082025 0.167904 -vn -5.507341 -2.046851 -0.049193 -v 0.034500 -0.081877 0.168650 -vn -5.508990 -1.873986 -0.812802 -v 0.034500 -0.082025 0.169396 -vn -5.507047 -1.421366 -1.469652 -v 0.034500 -0.082448 0.170029 -vn -5.506276 -0.752113 -1.901718 -v 0.034500 -0.083081 0.170452 -vn -5.507154 0.029819 -2.043453 -v 0.034500 -0.083827 0.170600 -vn -5.510322 0.803346 -1.874911 -v 0.034500 -0.084573 0.170452 -vn -5.516479 1.449734 -1.424732 -v 0.034500 -0.085206 0.170029 -vn -5.526325 1.871134 -0.765146 -v 0.034500 -0.085628 0.169396 -vn -5.540292 2.005960 0.000002 -v 0.034500 -0.085777 0.168650 -vn -5.190921 1.389141 1.912009 -v 0.034500 -0.085473 0.166385 -vn -5.190858 1.912047 1.389181 -v 0.034500 -0.086092 0.167004 -vn -5.190856 2.247743 0.730348 -v 0.034500 -0.086490 0.167785 -vn -5.190829 2.363442 -0.000006 -v 0.034500 -0.086627 0.168650 -vn -5.190850 -1.912045 1.389192 -v 0.034500 -0.081562 0.167004 -vn -5.190920 -1.389160 1.911996 -v 0.034500 -0.082181 0.166385 -vn -5.190872 -0.730335 2.247732 -v 0.034500 -0.082962 0.165987 -vn -5.190872 -0.000001 2.363405 -v 0.034500 -0.083827 0.165850 -vn -5.190867 0.730347 2.247732 -v 0.034500 -0.084692 0.165987 -vn -5.190921 -1.389141 -1.912009 -v 0.034500 -0.082181 0.170915 -vn -5.190858 -1.912047 -1.389181 -v 0.034500 -0.081562 0.170296 -vn -5.190856 -2.247743 -0.730348 -v 0.034500 -0.081164 0.169515 -vn -5.190829 -2.363442 0.000006 -v 0.034500 -0.081027 0.168650 -vn -5.190851 -2.247746 0.730346 -v 0.034500 -0.081164 0.167785 -vn -5.190851 2.247746 -0.730346 -v 0.034500 -0.086490 0.169515 -vn -5.190850 1.912045 -1.389192 -v 0.034500 -0.086092 0.170296 -vn -5.190920 1.389160 -1.911996 -v 0.034500 -0.085473 0.170915 -vn -5.190872 0.730335 -2.247732 -v 0.034500 -0.084692 0.171313 -vn -5.190872 0.000001 -2.363405 -v 0.034500 -0.083827 0.171450 -vn -5.190867 -0.730347 -2.247732 -v 0.034500 -0.082962 0.171313 -vn -2.056948 4.903312 -1.592071 -v 0.034300 -0.086680 0.169577 -vn -2.060001 4.171529 -3.029641 -v 0.034300 -0.086254 0.170413 -vn -2.062724 3.031183 -4.170678 -v 0.034300 -0.085590 0.171077 -vn -2.065036 1.593981 -4.903553 -v 0.034300 -0.084754 0.171503 -vn -2.067004 0.000570 -5.156291 -v 0.034300 -0.083827 0.171650 -vn -2.068628 -1.593014 -4.904238 -v 0.034300 -0.082900 0.171503 -vn -2.069905 -3.030662 -4.171939 -v 0.034300 -0.082063 0.171077 -vn -2.070766 -4.171736 -3.031201 -v 0.034300 -0.081400 0.170413 -vn -2.071301 -4.904330 -1.593624 -v 0.034300 -0.080974 0.169577 -vn -2.071470 -5.156786 0.000004 -v 0.034300 -0.080827 0.168650 -vn -2.071303 -4.904327 1.593620 -v 0.034300 -0.080974 0.167723 -vn -2.070772 -4.171726 3.031203 -v 0.034300 -0.081400 0.166887 -vn -2.069906 -3.030674 4.171929 -v 0.034300 -0.082063 0.166223 -vn -2.068625 -1.593008 4.904244 -v 0.034300 -0.082900 0.165797 -vn -2.067004 0.000568 5.156291 -v 0.034300 -0.083827 0.165650 -vn -2.065040 1.593987 4.903546 -v 0.034300 -0.084754 0.165797 -vn -2.062726 3.031168 4.170689 -v 0.034300 -0.085590 0.166223 -vn -2.059998 4.171540 3.029637 -v 0.034300 -0.086254 0.166887 -vn -2.056945 4.903315 1.592075 -v 0.034300 -0.086680 0.167723 -vn -2.055217 5.155160 -0.000004 -v 0.034300 -0.086827 0.168650 -vn -2.293325 5.291950 -1.222308 -v 0.028700 -0.086694 0.169534 -vn -2.264663 5.050697 -2.052714 -v 0.028700 -0.086680 0.169577 -vn -2.289853 4.682204 -2.758496 -v 0.028700 -0.086306 0.170340 -vn -2.234545 4.204367 -3.513052 -v 0.028700 -0.086254 0.170413 -vn -2.286290 3.638336 -4.040738 -v 0.028700 -0.085697 0.170995 -vn -2.199343 2.950130 -4.653279 -v 0.028700 -0.085590 0.171077 -vn -2.282713 2.256081 -4.950672 -v 0.028700 -0.084923 0.171443 -vn -2.159359 1.401372 -5.363301 -v 0.028700 -0.084754 0.171503 -vn -2.279035 0.663605 -5.402952 -v 0.028700 -0.084051 0.171642 -vn -2.114999 -0.298396 -5.571589 -v 0.028700 -0.083827 0.171650 -vn -2.275315 -0.992228 -5.355453 -v 0.028700 -0.083159 0.171575 -vn -2.066695 -1.990869 -5.252858 -v 0.028700 -0.082900 0.171503 -vn -2.271518 -2.557971 -4.812014 -v 0.028700 -0.082327 0.171248 -vn -2.014546 -3.516235 -4.431137 -v 0.028700 -0.082063 0.171077 -vn -2.267732 -3.888661 -3.822265 -v 0.028700 -0.081628 0.170691 -vn -1.958943 -4.728193 -3.177666 -v 0.028700 -0.081400 0.170413 -vn -2.263907 -4.860636 -2.477485 -v 0.028700 -0.081124 0.169952 -vn -1.899781 -5.508146 -1.605729 -v 0.028700 -0.080974 0.169577 -vn -2.259982 -5.383614 -0.901799 -v 0.028700 -0.080860 0.169097 -vn -1.837137 -5.776632 0.140180 -v 0.028700 -0.080827 0.168650 -vn -2.256017 -5.408582 0.759140 -v 0.028700 -0.080860 0.168203 -vn -2.138117 -5.306173 1.672295 -v 0.028700 -0.080974 0.167723 -vn -2.297400 -4.863618 2.410855 -v 0.028700 -0.081124 0.167348 -vn -2.144504 -4.553540 3.187150 -v 0.028700 -0.081400 0.166887 -vn -2.297177 -3.908560 3.767237 -v 0.028700 -0.081628 0.166609 -vn -2.154974 -3.378606 4.402269 -v 0.028700 -0.082063 0.166223 -vn -2.296940 -2.588329 4.771909 -v 0.028700 -0.082327 0.166052 -vn -2.169147 -1.892631 5.203765 -v 0.028700 -0.082900 0.165797 -vn -2.296536 -1.026430 5.331071 -v 0.028700 -0.083159 0.165725 -vn -2.186477 -0.236058 5.517295 -v 0.028700 -0.083827 0.165650 -vn -2.296083 0.631609 5.392453 -v 0.028700 -0.084051 0.165658 -vn -2.206309 1.434997 5.314647 -v 0.028700 -0.084754 0.165797 -vn -2.295566 2.230747 4.950297 -v 0.028700 -0.084923 0.165857 -vn -2.227623 2.963728 4.616588 -v 0.028700 -0.085590 0.166223 -vn -2.294883 3.621998 4.045748 -v 0.028700 -0.085697 0.166304 -vn -2.249412 4.206975 3.490243 -v 0.028700 -0.086254 0.166887 -vn -2.294178 4.675148 2.763217 -v 0.028700 -0.086306 0.166960 -vn -2.270397 5.049391 2.042873 -v 0.028700 -0.086680 0.167723 -vn -2.293324 5.291953 1.222305 -v 0.028700 -0.086694 0.167766 -vn -2.357433 5.463895 0.000004 -v 0.028700 -0.086827 0.168650 -vn -5.474120 1.739193 1.161963 -v 0.028500 -0.086471 0.166847 -vn -5.487123 1.988136 0.599100 -v 0.028500 -0.086885 0.167707 -vn -5.464605 1.329559 1.629282 -v 0.028500 -0.085822 0.166148 -vn -5.457898 0.794769 1.955728 -v 0.028500 -0.084996 0.165671 -vn -5.453161 0.183030 2.108991 -v 0.028500 -0.084066 0.165459 -vn -5.449901 -0.449832 2.072810 -v 0.028500 -0.083115 0.165530 -vn -5.447729 -1.045403 1.848797 -v 0.028500 -0.082227 0.165879 -vn -5.446247 -1.548586 1.456412 -v 0.028500 -0.081481 0.166473 -vn -5.445406 -1.912489 0.930866 -v 0.028500 -0.080944 0.167262 -vn -5.474413 -2.075723 0.268722 -v 0.028500 -0.080663 0.168173 -vn -5.474451 -2.062746 -0.345566 -v 0.028500 -0.080663 0.169127 -vn -5.472483 -1.870455 -0.940413 -v 0.028500 -0.080944 0.170038 -vn -5.470832 -1.510890 -1.451604 -v 0.028500 -0.081481 0.170827 -vn -5.469661 -1.016586 -1.833323 -v 0.028500 -0.082227 0.171421 -vn -5.469248 -0.432292 -2.051476 -v 0.028500 -0.083115 0.171770 -vn -5.469745 0.189073 -2.087180 -v 0.028500 -0.084066 0.171841 -vn -5.471569 0.791451 -1.938091 -v 0.028500 -0.084996 0.171629 -vn -5.475118 1.320815 -1.618891 -v 0.028500 -0.085822 0.171152 -vn -5.480942 1.730077 -1.159681 -v 0.028500 -0.086471 0.170453 -vn -5.489537 1.983660 -0.603036 -v 0.028500 -0.086885 0.169593 -vn -5.501266 2.060428 0.000003 -v 0.028500 -0.087027 0.168650 -vn -5.259129 -1.636216 -1.636239 -v 0.028500 -0.089342 0.163135 -vn -5.259207 -1.923945 -1.285531 -v 0.028500 -0.090312 0.164317 -vn -5.259193 -2.137784 -0.885488 -v 0.028500 -0.091033 0.165665 -vn -5.259183 -2.269465 -0.451429 -v 0.028500 -0.091477 0.167128 -vn -5.259159 0.885512 -2.137808 -v 0.028500 -0.080842 0.161444 -vn -5.259192 0.451421 -2.269458 -v 0.028500 -0.082305 0.161000 -vn -5.259197 -0.000001 -2.313913 -v 0.028500 -0.083827 0.160850 -vn -5.259189 -0.451424 -2.269458 -v 0.028500 -0.085349 0.161000 -vn -5.259160 -0.885506 -2.137810 -v 0.028500 -0.086812 0.161444 -vn -5.259207 -1.285540 -1.923939 -v 0.028500 -0.088160 0.162165 -vn -5.259202 1.923942 -1.285540 -v 0.028500 -0.077341 0.164317 -vn -5.259129 1.636229 -1.636225 -v 0.028500 -0.078311 0.163135 -vn -5.259182 1.285546 -1.923962 -v 0.028500 -0.079493 0.162165 -vn -5.259197 2.313913 -0.000002 -v 0.028500 -0.076027 0.168650 -vn -5.259182 2.269465 -0.451427 -v 0.028500 -0.076177 0.167128 -vn -5.259194 2.137783 -0.885488 -v 0.028500 -0.076621 0.165665 -vn -5.259192 -0.451421 2.269458 -v 0.028500 -0.085349 0.176300 -vn -5.259198 0.000001 2.313913 -v 0.028500 -0.083827 0.176450 -vn -5.259196 -1.636185 1.636183 -v 0.028500 -0.089342 0.174165 -vn -5.259205 -1.285536 1.923943 -v 0.028500 -0.088160 0.175135 -vn -5.259158 -0.885515 2.137807 -v 0.028500 -0.086812 0.175856 -vn -5.259197 -2.313913 0.000002 -v 0.028500 -0.091627 0.168650 -vn -5.259182 -2.269465 0.451427 -v 0.028500 -0.091477 0.170172 -vn -5.259192 -2.137783 0.885494 -v 0.028500 -0.091033 0.171635 -vn -5.259156 -1.923978 1.285565 -v 0.028500 -0.090312 0.172983 -vn -5.259155 1.923973 1.285572 -v 0.028500 -0.077341 0.172983 -vn -5.259193 2.137784 0.885488 -v 0.028500 -0.076621 0.171635 -vn -5.259182 2.269465 0.451429 -v 0.028500 -0.076177 0.170172 -vn -5.259189 0.451424 2.269458 -v 0.028500 -0.082305 0.176300 -vn -5.259159 0.885506 2.137810 -v 0.028500 -0.080842 0.175856 -vn -5.259179 1.285554 1.923957 -v 0.028500 -0.079493 0.175135 -vn -5.259195 1.636191 1.636179 -v 0.028500 -0.078311 0.174165 -vn -2.134659 5.245714 -0.000001 -v 0.028700 -0.075827 0.168650 -vn -2.134648 5.144938 1.023389 -v 0.028700 -0.075981 0.170211 -vn -2.134652 4.846411 2.007450 -v 0.028700 -0.076436 0.171711 -vn -2.134628 4.361683 2.914387 -v 0.028700 -0.077175 0.173095 -vn -2.134656 3.709290 3.709279 -v 0.028700 -0.078170 0.174307 -vn -2.134643 2.914371 4.361665 -v 0.028700 -0.079382 0.175302 -vn -2.134629 2.007453 4.846445 -v 0.028700 -0.080765 0.176041 -vn -2.134653 1.023395 5.144927 -v 0.028700 -0.082266 0.176496 -vn -2.134659 0.000001 5.245713 -v 0.028700 -0.083827 0.176650 -vn -2.134651 -1.023394 5.144929 -v 0.028700 -0.085388 0.176496 -vn -2.134629 -2.007459 4.846441 -v 0.028700 -0.086888 0.176041 -vn -2.134664 -2.914357 4.361646 -v 0.028700 -0.088271 0.175302 -vn -2.134655 -3.709287 3.709284 -v 0.028700 -0.089484 0.174307 -vn -2.134629 -4.361688 2.914381 -v 0.028700 -0.090479 0.173095 -vn -2.134653 -4.846407 2.007454 -v 0.028700 -0.091218 0.171711 -vn -2.134647 -5.144938 1.023386 -v 0.028700 -0.091673 0.170211 -vn -2.134656 -5.245714 0.000001 -v 0.028700 -0.091827 0.168650 -vn -2.134647 -5.144938 -1.023388 -v 0.028700 -0.091673 0.167089 -vn -2.134655 -4.846414 -2.007444 -v 0.028700 -0.091218 0.165589 -vn -2.134658 -4.361646 -2.914360 -v 0.028700 -0.090479 0.164205 -vn -2.134609 -3.709316 -3.709333 -v 0.028700 -0.089484 0.162993 -vn -2.134663 -2.914363 -4.361645 -v 0.028700 -0.088271 0.161998 -vn -2.134632 -2.007455 -4.846444 -v 0.028700 -0.086888 0.161259 -vn -2.134656 -1.023393 -5.144928 -v 0.028700 -0.085388 0.160804 -vn -2.134659 -0.000001 -5.245713 -v 0.028700 -0.083827 0.160650 -vn -2.134654 1.023392 -5.144930 -v 0.028700 -0.082266 0.160804 -vn -2.134632 2.007460 -4.846443 -v 0.028700 -0.080765 0.161259 -vn -2.134641 2.914366 -4.361670 -v 0.028700 -0.079382 0.161998 -vn -2.134609 3.709327 -3.709323 -v 0.028700 -0.078170 0.162993 -vn -2.134660 4.361639 -2.914364 -v 0.028700 -0.077175 0.164205 -vn -2.134654 4.846415 -2.007445 -v 0.028700 -0.076436 0.165589 -vn -2.134649 5.144939 -1.023387 -v 0.028700 -0.075981 0.167089 -# 5792 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 57//57 -f 57//57 56//56 58//58 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 81//81 80//80 82//82 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 105//105 104//104 106//106 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 1//1 -f 1//1 128//128 2//2 -f 128//128 129//129 2//2 -f 2//2 129//129 130//130 -f 2//2 130//130 4//4 -f 4//4 130//130 131//131 -f 4//4 131//131 6//6 -f 6//6 131//131 132//132 -f 6//6 132//132 8//8 -f 8//8 132//132 133//133 -f 8//8 133//133 10//10 -f 10//10 133//133 134//134 -f 10//10 134//134 12//12 -f 12//12 134//134 135//135 -f 12//12 135//135 14//14 -f 14//14 135//135 136//136 -f 14//14 136//136 16//16 -f 16//16 136//136 137//137 -f 16//16 137//137 18//18 -f 18//18 137//137 138//138 -f 18//18 138//138 20//20 -f 20//20 138//138 139//139 -f 20//20 139//139 22//22 -f 22//22 139//139 140//140 -f 22//22 140//140 24//24 -f 24//24 140//140 141//141 -f 24//24 141//141 26//26 -f 26//26 141//141 142//142 -f 26//26 142//142 28//28 -f 28//28 142//142 143//143 -f 28//28 143//143 30//30 -f 30//30 143//143 144//144 -f 30//30 144//144 32//32 -f 32//32 144//144 145//145 -f 32//32 145//145 34//34 -f 34//34 145//145 146//146 -f 34//34 146//146 36//36 -f 36//36 146//146 147//147 -f 36//36 147//147 38//38 -f 38//38 147//147 148//148 -f 38//38 148//148 40//40 -f 40//40 148//148 149//149 -f 40//40 149//149 42//42 -f 42//42 149//149 150//150 -f 42//42 150//150 44//44 -f 44//44 150//150 151//151 -f 44//44 151//151 46//46 -f 46//46 151//151 152//152 -f 46//46 152//152 48//48 -f 48//48 152//152 153//153 -f 48//48 153//153 50//50 -f 50//50 153//153 154//154 -f 50//50 154//154 52//52 -f 52//52 154//154 155//155 -f 52//52 155//155 54//54 -f 54//54 155//155 156//156 -f 54//54 156//156 56//56 -f 56//56 156//156 157//157 -f 56//56 157//157 58//58 -f 58//58 157//157 158//158 -f 58//58 158//158 60//60 -f 60//60 158//158 159//159 -f 60//60 159//159 62//62 -f 62//62 159//159 160//160 -f 62//62 160//160 64//64 -f 64//64 160//160 161//161 -f 64//64 161//161 66//66 -f 66//66 161//161 162//162 -f 66//66 162//162 68//68 -f 68//68 162//162 163//163 -f 68//68 163//163 70//70 -f 70//70 163//163 164//164 -f 70//70 164//164 72//72 -f 72//72 164//164 165//165 -f 72//72 165//165 74//74 -f 74//74 165//165 166//166 -f 74//74 166//166 76//76 -f 76//76 166//166 167//167 -f 76//76 167//167 78//78 -f 78//78 167//167 168//168 -f 78//78 168//168 80//80 -f 80//80 168//168 169//169 -f 80//80 169//169 82//82 -f 82//82 169//169 170//170 -f 82//82 170//170 84//84 -f 84//84 170//170 171//171 -f 84//84 171//171 86//86 -f 86//86 171//171 172//172 -f 86//86 172//172 88//88 -f 88//88 172//172 173//173 -f 88//88 173//173 90//90 -f 90//90 173//173 174//174 -f 90//90 174//174 92//92 -f 92//92 174//174 175//175 -f 92//92 175//175 94//94 -f 94//94 175//175 176//176 -f 94//94 176//176 96//96 -f 96//96 176//176 177//177 -f 96//96 177//177 98//98 -f 98//98 177//177 178//178 -f 98//98 178//178 100//100 -f 100//100 178//178 179//179 -f 100//100 179//179 102//102 -f 102//102 179//179 180//180 -f 102//102 180//180 104//104 -f 104//104 180//180 181//181 -f 104//104 181//181 106//106 -f 106//106 181//181 182//182 -f 106//106 182//182 108//108 -f 108//108 182//182 183//183 -f 108//108 183//183 110//110 -f 110//110 183//183 184//184 -f 110//110 184//184 112//112 -f 112//112 184//184 185//185 -f 112//112 185//185 114//114 -f 114//114 185//185 186//186 -f 114//114 186//186 116//116 -f 116//116 186//186 187//187 -f 116//116 187//187 118//118 -f 118//118 187//187 188//188 -f 118//118 188//188 120//120 -f 120//120 188//188 189//189 -f 120//120 189//189 122//122 -f 122//122 189//189 190//190 -f 122//122 190//190 124//124 -f 124//124 190//190 191//191 -f 124//124 191//191 126//126 -f 126//126 191//191 192//192 -f 126//126 192//192 128//128 -f 128//128 192//192 129//129 -f 192//192 193//193 129//129 -f 129//129 193//193 194//194 -f 129//129 194//194 130//130 -f 130//130 194//194 195//195 -f 130//130 195//195 131//131 -f 131//131 195//195 196//196 -f 131//131 196//196 132//132 -f 132//132 196//196 197//197 -f 132//132 197//197 133//133 -f 133//133 197//197 198//198 -f 133//133 198//198 134//134 -f 134//134 198//198 199//199 -f 134//134 199//199 135//135 -f 135//135 199//199 200//200 -f 135//135 200//200 136//136 -f 136//136 200//200 201//201 -f 136//136 201//201 137//137 -f 137//137 201//201 202//202 -f 137//137 202//202 138//138 -f 138//138 202//202 203//203 -f 138//138 203//203 139//139 -f 139//139 203//203 204//204 -f 139//139 204//204 140//140 -f 140//140 204//204 205//205 -f 140//140 205//205 141//141 -f 141//141 205//205 206//206 -f 141//141 206//206 142//142 -f 142//142 206//206 207//207 -f 142//142 207//207 143//143 -f 143//143 207//207 208//208 -f 143//143 208//208 144//144 -f 144//144 208//208 209//209 -f 144//144 209//209 145//145 -f 145//145 209//209 210//210 -f 145//145 210//210 146//146 -f 146//146 210//210 211//211 -f 146//146 211//211 147//147 -f 147//147 211//211 212//212 -f 147//147 212//212 148//148 -f 148//148 212//212 213//213 -f 148//148 213//213 149//149 -f 149//149 213//213 214//214 -f 149//149 214//214 150//150 -f 150//150 214//214 215//215 -f 150//150 215//215 151//151 -f 151//151 215//215 216//216 -f 151//151 216//216 152//152 -f 152//152 216//216 217//217 -f 152//152 217//217 153//153 -f 153//153 217//217 218//218 -f 153//153 218//218 154//154 -f 154//154 218//218 219//219 -f 154//154 219//219 155//155 -f 155//155 219//219 220//220 -f 155//155 220//220 156//156 -f 156//156 220//220 221//221 -f 156//156 221//221 157//157 -f 157//157 221//221 222//222 -f 157//157 222//222 158//158 -f 158//158 222//222 223//223 -f 158//158 223//223 159//159 -f 159//159 223//223 224//224 -f 159//159 224//224 160//160 -f 160//160 224//224 225//225 -f 160//160 225//225 161//161 -f 161//161 225//225 226//226 -f 161//161 226//226 162//162 -f 162//162 226//226 227//227 -f 162//162 227//227 163//163 -f 163//163 227//227 228//228 -f 163//163 228//228 164//164 -f 164//164 228//228 229//229 -f 164//164 229//229 165//165 -f 165//165 229//229 230//230 -f 165//165 230//230 166//166 -f 166//166 230//230 231//231 -f 166//166 231//231 167//167 -f 167//167 231//231 232//232 -f 167//167 232//232 168//168 -f 168//168 232//232 233//233 -f 168//168 233//233 169//169 -f 169//169 233//233 234//234 -f 169//169 234//234 170//170 -f 170//170 234//234 235//235 -f 170//170 235//235 171//171 -f 171//171 235//235 236//236 -f 171//171 236//236 172//172 -f 172//172 236//236 237//237 -f 172//172 237//237 173//173 -f 173//173 237//237 238//238 -f 173//173 238//238 174//174 -f 174//174 238//238 239//239 -f 174//174 239//239 175//175 -f 175//175 239//239 240//240 -f 175//175 240//240 176//176 -f 176//176 240//240 241//241 -f 176//176 241//241 177//177 -f 177//177 241//241 242//242 -f 177//177 242//242 178//178 -f 178//178 242//242 243//243 -f 178//178 243//243 179//179 -f 179//179 243//243 244//244 -f 179//179 244//244 180//180 -f 180//180 244//244 245//245 -f 180//180 245//245 181//181 -f 181//181 245//245 246//246 -f 181//181 246//246 182//182 -f 182//182 246//246 247//247 -f 182//182 247//247 183//183 -f 183//183 247//247 248//248 -f 183//183 248//248 184//184 -f 184//184 248//248 249//249 -f 184//184 249//249 185//185 -f 185//185 249//249 250//250 -f 185//185 250//250 186//186 -f 186//186 250//250 251//251 -f 186//186 251//251 187//187 -f 187//187 251//251 252//252 -f 187//187 252//252 188//188 -f 188//188 252//252 253//253 -f 188//188 253//253 189//189 -f 189//189 253//253 254//254 -f 189//189 254//254 190//190 -f 190//190 254//254 255//255 -f 190//190 255//255 191//191 -f 191//191 255//255 256//256 -f 191//191 256//256 192//192 -f 192//192 256//256 193//193 -f 242//242 257//257 243//243 -f 243//243 257//257 258//258 -f 243//243 258//258 244//244 -f 244//244 258//258 259//259 -f 244//244 259//259 245//245 -f 245//245 259//259 260//260 -f 245//245 260//260 246//246 -f 246//246 260//260 261//261 -f 246//246 261//261 247//247 -f 247//247 261//261 262//262 -f 247//247 262//262 248//248 -f 236//236 263//263 237//237 -f 237//237 263//263 264//264 -f 237//237 264//264 238//238 -f 238//238 264//264 265//265 -f 238//238 265//265 239//239 -f 239//239 265//265 266//266 -f 239//239 266//266 240//240 -f 240//240 266//266 267//267 -f 240//240 267//267 241//241 -f 241//241 267//267 268//268 -f 241//241 268//268 242//242 -f 242//242 268//268 269//269 -f 242//242 269//269 257//257 -f 230//230 270//270 231//231 -f 231//231 270//270 271//271 -f 231//231 271//271 232//232 -f 232//232 271//271 272//272 -f 232//232 272//272 233//233 -f 233//233 272//272 273//273 -f 233//233 273//273 234//234 -f 234//234 273//273 274//274 -f 234//234 274//274 235//235 -f 235//235 274//274 275//275 -f 235//235 275//275 236//236 -f 236//236 275//275 276//276 -f 236//236 276//276 263//263 -f 216//216 277//277 217//217 -f 217//217 277//277 278//278 -f 217//217 278//278 218//218 -f 218//218 278//278 279//279 -f 218//218 279//279 219//219 -f 219//219 279//279 280//280 -f 219//219 280//280 220//220 -f 220//220 280//280 281//281 -f 220//220 281//281 221//221 -f 221//221 281//281 282//282 -f 221//221 282//282 222//222 -f 222//222 282//282 283//283 -f 222//222 283//283 223//223 -f 223//223 283//283 284//284 -f 223//223 284//284 224//224 -f 224//224 284//284 285//285 -f 224//224 285//285 225//225 -f 225//225 285//285 286//286 -f 225//225 286//286 226//226 -f 226//226 286//286 287//287 -f 226//226 287//287 227//227 -f 227//227 287//287 288//288 -f 227//227 288//288 228//228 -f 228//228 288//288 289//289 -f 228//228 289//289 229//229 -f 229//229 289//289 290//290 -f 229//229 290//290 230//230 -f 230//230 290//290 291//291 -f 230//230 291//291 270//270 -f 210//210 292//292 211//211 -f 211//211 292//292 293//293 -f 211//211 293//293 212//212 -f 212//212 293//293 294//294 -f 212//212 294//294 213//213 -f 213//213 294//294 295//295 -f 213//213 295//295 214//214 -f 214//214 295//295 296//296 -f 214//214 296//296 215//215 -f 215//215 296//296 297//297 -f 215//215 297//297 216//216 -f 216//216 297//297 298//298 -f 216//216 298//298 277//277 -f 204//204 299//299 205//205 -f 205//205 299//299 300//300 -f 205//205 300//300 206//206 -f 206//206 300//300 301//301 -f 206//206 301//301 207//207 -f 207//207 301//301 302//302 -f 207//207 302//302 208//208 -f 208//208 302//302 303//303 -f 208//208 303//303 209//209 -f 209//209 303//303 304//304 -f 209//209 304//304 210//210 -f 210//210 304//304 305//305 -f 210//210 305//305 292//292 -f 198//198 306//306 199//199 -f 199//199 306//306 307//307 -f 199//199 307//307 200//200 -f 200//200 307//307 308//308 -f 200//200 308//308 201//201 -f 201//201 308//308 309//309 -f 201//201 309//309 202//202 -f 202//202 309//309 310//310 -f 202//202 310//310 203//203 -f 203//203 310//310 311//311 -f 203//203 311//311 204//204 -f 204//204 311//311 312//312 -f 204//204 312//312 299//299 -f 262//262 313//313 248//248 -f 248//248 313//313 314//314 -f 248//248 314//314 249//249 -f 249//249 314//314 315//315 -f 249//249 315//315 250//250 -f 250//250 315//315 316//316 -f 250//250 316//316 251//251 -f 251//251 316//316 317//317 -f 251//251 317//317 252//252 -f 252//252 317//317 318//318 -f 252//252 318//318 253//253 -f 253//253 318//318 319//319 -f 253//253 319//319 254//254 -f 254//254 319//319 320//320 -f 254//254 320//320 255//255 -f 255//255 320//320 321//321 -f 255//255 321//321 256//256 -f 256//256 321//321 322//322 -f 256//256 322//322 193//193 -f 193//193 322//322 323//323 -f 193//193 323//323 194//194 -f 194//194 323//323 324//324 -f 194//194 324//324 195//195 -f 195//195 324//324 325//325 -f 195//195 325//325 196//196 -f 196//196 325//325 326//326 -f 196//196 326//326 197//197 -f 197//197 326//326 327//327 -f 197//197 327//327 198//198 -f 198//198 327//327 328//328 -f 198//198 328//328 306//306 -f 329//329 330//330 331//331 -f 332//332 333//333 334//334 -f 335//335 336//336 337//337 -f 338//338 339//339 340//340 -f 341//341 342//342 343//343 -f 344//344 345//345 346//346 -f 347//347 348//348 349//349 -f 328//328 327//327 350//350 -f 307//307 306//306 351//351 -f 308//308 307//307 352//352 -f 296//296 295//295 335//335 -f 298//298 297//297 353//353 -f 278//278 277//277 354//354 -f 279//279 278//278 355//355 -f 276//276 275//275 356//356 -f 265//265 264//264 357//357 -f 258//258 257//257 358//358 -f 261//261 260//260 359//359 -f 320//320 319//319 360//360 -f 322//322 321//321 361//361 -f 361//361 321//321 320//320 -f 317//317 316//316 347//347 -f 347//347 316//316 315//315 -f 347//347 315//315 348//348 -f 348//348 315//315 314//314 -f 348//348 314//314 313//313 -f 362//362 262//262 261//261 -f 260//260 259//259 363//363 -f 266//266 345//345 267//267 -f 267//267 345//345 344//344 -f 267//267 344//344 268//268 -f 268//268 344//344 269//269 -f 264//264 263//263 364//364 -f 364//364 263//263 276//276 -f 273//273 272//272 341//341 -f 341//341 272//272 271//271 -f 341//341 271//271 342//342 -f 342//342 271//271 270//270 -f 342//342 270//270 291//291 -f 365//365 290//290 289//289 -f 289//289 288//288 366//366 -f 366//366 288//288 287//287 -f 285//285 284//284 338//338 -f 338//338 284//284 283//283 -f 338//338 283//283 339//339 -f 339//339 283//283 282//282 -f 339//339 282//282 281//281 -f 279//279 355//355 280//280 -f 335//335 295//295 336//336 -f 336//336 295//295 294//294 -f 336//336 294//294 293//293 -f 367//367 292//292 305//305 -f 305//305 304//304 368//368 -f 368//368 304//304 303//303 -f 302//302 301//301 369//369 -f 300//300 299//299 332//332 -f 332//332 299//299 312//312 -f 332//332 312//312 333//333 -f 333//333 312//312 311//311 -f 333//333 311//311 310//310 -f 308//308 352//352 309//309 -f 326//326 325//325 329//329 -f 329//329 325//325 324//324 -f 329//329 324//324 330//330 -f 330//330 324//324 323//323 -f 370//370 371//371 360//360 -f 372//372 349//349 373//373 -f 373//373 349//349 348//348 -f 373//373 348//348 362//362 -f 362//362 348//348 313//313 -f 362//362 313//313 262//262 -f 374//374 375//375 363//363 -f 376//376 346//346 377//377 -f 377//377 346//346 345//345 -f 377//377 345//345 357//357 -f 357//357 345//345 266//266 -f 357//357 266//266 265//265 -f 378//378 379//379 356//356 -f 380//380 343//343 381//381 -f 381//381 343//343 342//342 -f 381//381 342//342 365//365 -f 365//365 342//342 291//291 -f 365//365 291//291 290//290 -f 382//382 383//383 384//384 -f 385//385 340//340 386//386 -f 386//386 340//340 339//339 -f 386//386 339//339 387//387 -f 387//387 339//339 281//281 -f 387//387 281//281 280//280 -f 388//388 389//389 354//354 -f 390//390 337//337 391//391 -f 391//391 337//337 336//336 -f 391//391 336//336 367//367 -f 367//367 336//336 293//293 -f 367//367 293//293 292//292 -f 392//392 393//393 394//394 -f 395//395 334//334 396//396 -f 396//396 334//334 333//333 -f 396//396 333//333 397//397 -f 397//397 333//333 310//310 -f 397//397 310//310 309//309 -f 398//398 399//399 351//351 -f 400//400 331//331 401//401 -f 401//401 331//331 330//330 -f 401//401 330//330 402//402 -f 402//402 330//330 323//323 -f 402//402 323//323 322//322 -f 403//403 371//371 404//404 -f 404//404 371//371 370//370 -f 404//404 370//370 405//405 -f 406//406 375//375 407//407 -f 407//407 375//375 374//374 -f 407//407 374//374 408//408 -f 409//409 379//379 410//410 -f 410//410 379//379 378//378 -f 410//410 378//378 411//411 -f 412//412 383//383 413//413 -f 413//413 383//383 382//382 -f 413//413 382//382 414//414 -f 415//415 389//389 416//416 -f 416//416 389//389 388//388 -f 416//416 388//388 417//417 -f 418//418 393//393 419//419 -f 419//419 393//393 392//392 -f 419//419 392//392 420//420 -f 421//421 399//399 422//422 -f 422//422 399//399 398//398 -f 422//422 398//398 423//423 -f 424//424 425//425 426//426 -f 322//322 361//361 402//402 -f 402//402 361//361 427//427 -f 402//402 427//427 401//401 -f 401//401 427//427 424//424 -f 401//401 424//424 400//400 -f 400//400 424//424 426//426 -f 400//400 426//426 428//428 -f 320//320 360//360 361//361 -f 361//361 360//360 371//371 -f 361//361 371//371 427//427 -f 427//427 371//371 403//403 -f 427//427 403//403 424//424 -f 424//424 403//403 429//429 -f 424//424 429//429 425//425 -f 430//430 431//431 432//432 -f 432//432 431//431 405//405 -f 432//432 405//405 433//433 -f 433//433 405//405 370//370 -f 433//433 370//370 434//434 -f 434//434 370//370 360//360 -f 434//434 360//360 318//318 -f 318//318 360//360 319//319 -f 431//431 435//435 405//405 -f 405//405 435//435 436//436 -f 405//405 436//436 404//404 -f 404//404 436//436 437//437 -f 404//404 437//437 403//403 -f 403//403 437//437 438//438 -f 403//403 438//438 429//429 -f 318//318 317//317 434//434 -f 434//434 317//317 347//347 -f 434//434 347//347 433//433 -f 433//433 347//347 349//349 -f 433//433 349//349 432//432 -f 432//432 349//349 372//372 -f 432//432 372//372 430//430 -f 430//430 372//372 439//439 -f 440//440 441//441 442//442 -f 261//261 359//359 362//362 -f 362//362 359//359 443//443 -f 362//362 443//443 373//373 -f 373//373 443//443 440//440 -f 373//373 440//440 372//372 -f 372//372 440//440 442//442 -f 372//372 442//442 439//439 -f 260//260 363//363 359//359 -f 359//359 363//363 375//375 -f 359//359 375//375 443//443 -f 443//443 375//375 406//406 -f 443//443 406//406 440//440 -f 440//440 406//406 444//444 -f 440//440 444//444 441//441 -f 445//445 446//446 447//447 -f 447//447 446//446 408//408 -f 447//447 408//408 448//448 -f 448//448 408//408 374//374 -f 448//448 374//374 358//358 -f 358//358 374//374 363//363 -f 358//358 363//363 258//258 -f 258//258 363//363 259//259 -f 446//446 449//449 408//408 -f 408//408 449//449 450//450 -f 408//408 450//450 407//407 -f 407//407 450//450 451//451 -f 407//407 451//451 406//406 -f 406//406 451//451 452//452 -f 406//406 452//452 444//444 -f 257//257 269//269 358//358 -f 358//358 269//269 344//344 -f 358//358 344//344 448//448 -f 448//448 344//344 346//346 -f 448//448 346//346 447//447 -f 447//447 346//346 376//376 -f 447//447 376//376 445//445 -f 445//445 376//376 453//453 -f 454//454 455//455 456//456 -f 264//264 364//364 357//357 -f 357//357 364//364 457//457 -f 357//357 457//457 377//377 -f 377//377 457//457 454//454 -f 377//377 454//454 376//376 -f 376//376 454//454 456//456 -f 376//376 456//456 453//453 -f 276//276 356//356 364//364 -f 364//364 356//356 379//379 -f 364//364 379//379 457//457 -f 457//457 379//379 409//409 -f 457//457 409//409 454//454 -f 454//454 409//409 458//458 -f 454//454 458//458 455//455 -f 459//459 460//460 461//461 -f 461//461 460//460 411//411 -f 461//461 411//411 462//462 -f 462//462 411//411 378//378 -f 462//462 378//378 463//463 -f 463//463 378//378 356//356 -f 463//463 356//356 274//274 -f 274//274 356//356 275//275 -f 460//460 464//464 411//411 -f 411//411 464//464 465//465 -f 411//411 465//465 410//410 -f 410//410 465//465 466//466 -f 410//410 466//466 409//409 -f 409//409 466//466 467//467 -f 409//409 467//467 458//458 -f 274//274 273//273 463//463 -f 463//463 273//273 341//341 -f 463//463 341//341 462//462 -f 462//462 341//341 343//343 -f 462//462 343//343 461//461 -f 461//461 343//343 380//380 -f 461//461 380//380 459//459 -f 459//459 380//380 468//468 -f 469//469 470//470 471//471 -f 289//289 366//366 365//365 -f 365//365 366//366 472//472 -f 365//365 472//472 381//381 -f 381//381 472//472 469//469 -f 381//381 469//469 380//380 -f 380//380 469//469 471//471 -f 380//380 471//471 468//468 -f 287//287 384//384 366//366 -f 366//366 384//384 383//383 -f 366//366 383//383 472//472 -f 472//472 383//383 412//412 -f 472//472 412//412 469//469 -f 469//469 412//412 473//473 -f 469//469 473//473 470//470 -f 474//474 475//475 476//476 -f 476//476 475//475 414//414 -f 476//476 414//414 477//477 -f 477//477 414//414 382//382 -f 477//477 382//382 478//478 -f 478//478 382//382 384//384 -f 478//478 384//384 286//286 -f 286//286 384//384 287//287 -f 475//475 479//479 414//414 -f 414//414 479//479 480//480 -f 414//414 480//480 413//413 -f 413//413 480//480 481//481 -f 413//413 481//481 412//412 -f 412//412 481//481 482//482 -f 412//412 482//482 473//473 -f 286//286 285//285 478//478 -f 478//478 285//285 338//338 -f 478//478 338//338 477//477 -f 477//477 338//338 340//340 -f 477//477 340//340 476//476 -f 476//476 340//340 385//385 -f 476//476 385//385 474//474 -f 474//474 385//385 483//483 -f 484//484 485//485 486//486 -f 280//280 355//355 387//387 -f 387//387 355//355 487//487 -f 387//387 487//487 386//386 -f 386//386 487//487 484//484 -f 386//386 484//484 385//385 -f 385//385 484//484 486//486 -f 385//385 486//486 483//483 -f 278//278 354//354 355//355 -f 355//355 354//354 389//389 -f 355//355 389//389 487//487 -f 487//487 389//389 415//415 -f 487//487 415//415 484//484 -f 484//484 415//415 488//488 -f 484//484 488//488 485//485 -f 489//489 490//490 491//491 -f 491//491 490//490 417//417 -f 491//491 417//417 492//492 -f 492//492 417//417 388//388 -f 492//492 388//388 353//353 -f 353//353 388//388 354//354 -f 353//353 354//354 298//298 -f 298//298 354//354 277//277 -f 490//490 493//493 417//417 -f 417//417 493//493 494//494 -f 417//417 494//494 416//416 -f 416//416 494//494 495//495 -f 416//416 495//495 415//415 -f 415//415 495//495 496//496 -f 415//415 496//496 488//488 -f 297//297 296//296 353//353 -f 353//353 296//296 335//335 -f 353//353 335//335 492//492 -f 492//492 335//335 337//337 -f 492//492 337//337 491//491 -f 491//491 337//337 390//390 -f 491//491 390//390 489//489 -f 489//489 390//390 497//497 -f 498//498 499//499 500//500 -f 305//305 368//368 367//367 -f 367//367 368//368 501//501 -f 367//367 501//501 391//391 -f 391//391 501//501 498//498 -f 391//391 498//498 390//390 -f 390//390 498//498 500//500 -f 390//390 500//500 497//497 -f 303//303 394//394 368//368 -f 368//368 394//394 393//393 -f 368//368 393//393 501//501 -f 501//501 393//393 418//418 -f 501//501 418//418 498//498 -f 498//498 418//418 502//502 -f 498//498 502//502 499//499 -f 503//503 504//504 505//505 -f 505//505 504//504 420//420 -f 505//505 420//420 506//506 -f 506//506 420//420 392//392 -f 506//506 392//392 369//369 -f 369//369 392//392 394//394 -f 369//369 394//394 302//302 -f 302//302 394//394 303//303 -f 504//504 507//507 420//420 -f 420//420 507//507 508//508 -f 420//420 508//508 419//419 -f 419//419 508//508 509//509 -f 419//419 509//509 418//418 -f 418//418 509//509 510//510 -f 418//418 510//510 502//502 -f 301//301 300//300 369//369 -f 369//369 300//300 332//332 -f 369//369 332//332 506//506 -f 506//506 332//332 334//334 -f 506//506 334//334 505//505 -f 505//505 334//334 395//395 -f 505//505 395//395 503//503 -f 503//503 395//395 511//511 -f 512//512 513//513 514//514 -f 309//309 352//352 397//397 -f 397//397 352//352 515//515 -f 397//397 515//515 396//396 -f 396//396 515//515 512//512 -f 396//396 512//512 395//395 -f 395//395 512//512 514//514 -f 395//395 514//514 511//511 -f 307//307 351//351 352//352 -f 352//352 351//351 399//399 -f 352//352 399//399 515//515 -f 515//515 399//399 421//421 -f 515//515 421//421 512//512 -f 512//512 421//421 516//516 -f 512//512 516//516 513//513 -f 517//517 518//518 519//519 -f 519//519 518//518 423//423 -f 519//519 423//423 520//520 -f 520//520 423//423 398//398 -f 520//520 398//398 350//350 -f 350//350 398//398 351//351 -f 350//350 351//351 328//328 -f 328//328 351//351 306//306 -f 518//518 521//521 423//423 -f 423//423 521//521 522//522 -f 423//423 522//522 422//422 -f 422//422 522//522 523//523 -f 422//422 523//523 421//421 -f 421//421 523//523 524//524 -f 421//421 524//524 516//516 -f 327//327 326//326 350//350 -f 350//350 326//326 329//329 -f 350//350 329//329 520//520 -f 520//520 329//329 331//331 -f 520//520 331//331 519//519 -f 519//519 331//331 400//400 -f 519//519 400//400 517//517 -f 517//517 400//400 428//428 -f 471//471 525//525 468//468 -f 468//468 525//525 526//526 -f 468//468 526//526 459//459 -f 459//459 526//526 527//527 -f 459//459 527//527 460//460 -f 460//460 527//527 528//528 -f 460//460 528//528 464//464 -f 464//464 528//528 529//529 -f 464//464 529//529 465//465 -f 530//530 451//451 450//450 -f 529//529 531//531 465//465 -f 465//465 531//531 532//532 -f 465//465 532//532 466//466 -f 466//466 532//532 533//533 -f 466//466 533//533 467//467 -f 467//467 533//533 534//534 -f 467//467 534//534 458//458 -f 458//458 534//534 535//535 -f 458//458 535//535 455//455 -f 455//455 535//535 536//536 -f 455//455 536//536 456//456 -f 456//456 536//536 537//537 -f 456//456 537//537 453//453 -f 453//453 537//537 538//538 -f 453//453 538//538 445//445 -f 445//445 538//538 539//539 -f 445//445 539//539 446//446 -f 446//446 539//539 540//540 -f 446//446 540//540 449//449 -f 449//449 540//540 541//541 -f 449//449 541//541 450//450 -f 450//450 541//541 542//542 -f 450//450 542//542 530//530 -f 530//530 543//543 451//451 -f 451//451 543//543 544//544 -f 451//451 544//544 452//452 -f 452//452 544//544 545//545 -f 452//452 545//545 444//444 -f 444//444 545//545 546//546 -f 444//444 546//546 441//441 -f 441//441 546//546 547//547 -f 441//441 547//547 442//442 -f 442//442 547//547 548//548 -f 442//442 548//548 439//439 -f 439//439 548//548 549//549 -f 439//439 549//549 430//430 -f 430//430 549//549 550//550 -f 430//430 550//550 431//431 -f 431//431 550//550 551//551 -f 431//431 551//551 435//435 -f 435//435 551//551 552//552 -f 435//435 552//552 436//436 -f 436//436 552//552 553//553 -f 436//436 553//553 437//437 -f 553//553 554//554 437//437 -f 437//437 554//554 555//555 -f 437//437 555//555 438//438 -f 438//438 555//555 556//556 -f 438//438 556//556 429//429 -f 429//429 556//556 557//557 -f 429//429 557//557 425//425 -f 425//425 557//557 558//558 -f 425//425 558//558 426//426 -f 426//426 558//558 559//559 -f 426//426 559//559 428//428 -f 428//428 559//559 560//560 -f 428//428 560//560 517//517 -f 517//517 560//560 561//561 -f 517//517 561//561 518//518 -f 561//561 562//562 518//518 -f 518//518 562//562 563//563 -f 518//518 563//563 521//521 -f 521//521 563//563 564//564 -f 521//521 564//564 522//522 -f 522//522 564//564 565//565 -f 522//522 565//565 523//523 -f 565//565 566//566 523//523 -f 523//523 566//566 567//567 -f 523//523 567//567 524//524 -f 524//524 567//567 568//568 -f 524//524 568//568 516//516 -f 516//516 568//568 513//513 -f 513//513 568//568 569//569 -f 513//513 569//569 514//514 -f 514//514 569//569 570//570 -f 514//514 570//570 511//511 -f 511//511 570//570 571//571 -f 511//511 571//571 503//503 -f 503//503 571//571 572//572 -f 503//503 572//572 504//504 -f 572//572 573//573 504//504 -f 504//504 573//573 574//574 -f 504//504 574//574 507//507 -f 507//507 574//574 575//575 -f 507//507 575//575 508//508 -f 508//508 575//575 576//576 -f 508//508 576//576 509//509 -f 576//576 577//577 509//509 -f 509//509 577//577 578//578 -f 509//509 578//578 510//510 -f 510//510 578//578 579//579 -f 510//510 579//579 502//502 -f 502//502 579//579 580//580 -f 502//502 580//580 499//499 -f 499//499 580//580 581//581 -f 499//499 581//581 500//500 -f 500//500 581//581 582//582 -f 500//500 582//582 497//497 -f 497//497 582//582 583//583 -f 497//497 583//583 489//489 -f 489//489 583//583 584//584 -f 489//489 584//584 490//490 -f 490//490 584//584 585//585 -f 490//490 585//585 493//493 -f 493//493 585//585 586//586 -f 493//493 586//586 494//494 -f 494//494 586//586 587//587 -f 494//494 587//587 495//495 -f 587//587 588//588 495//495 -f 495//495 588//588 589//589 -f 495//495 589//589 496//496 -f 496//496 589//589 590//590 -f 496//496 590//590 488//488 -f 488//488 590//590 591//591 -f 488//488 591//591 485//485 -f 485//485 591//591 592//592 -f 485//485 592//592 486//486 -f 486//486 592//592 593//593 -f 486//486 593//593 483//483 -f 593//593 594//594 483//483 -f 483//483 594//594 595//595 -f 483//483 595//595 474//474 -f 474//474 595//595 596//596 -f 474//474 596//596 475//475 -f 475//475 596//596 597//597 -f 475//475 597//597 479//479 -f 479//479 597//597 598//598 -f 479//479 598//598 480//480 -f 480//480 598//598 599//599 -f 480//480 599//599 481//481 -f 481//481 599//599 600//600 -f 481//481 600//600 482//482 -f 482//482 600//600 601//601 -f 482//482 601//601 473//473 -f 473//473 601//601 602//602 -f 473//473 602//602 470//470 -f 470//470 602//602 603//603 -f 470//470 603//603 471//471 -f 471//471 603//603 604//604 -f 471//471 604//604 525//525 -f 605//605 606//606 607//607 -f 608//608 609//609 610//610 -f 611//611 612//612 613//613 -f 614//614 615//615 616//616 -f 617//617 618//618 619//619 -f 620//620 621//621 622//622 -f 623//623 624//624 625//625 -f 626//626 627//627 628//628 -f 629//629 630//630 631//631 -f 621//621 632//632 633//633 -f 624//624 634//634 635//635 -f 627//627 636//636 637//637 -f 630//630 638//638 639//639 -f 570//570 569//569 640//640 -f 558//558 557//557 641//641 -f 641//641 557//557 642//642 -f 555//555 554//554 638//638 -f 554//554 553//553 638//638 -f 638//638 553//553 552//552 -f 638//638 552//552 639//639 -f 639//639 552//552 551//551 -f 639//639 551//551 643//643 -f 643//643 551//551 550//550 -f 643//643 550//550 644//644 -f 644//644 550//550 549//549 -f 644//644 549//549 645//645 -f 645//645 549//549 548//548 -f 548//548 547//547 645//645 -f 645//645 547//547 546//546 -f 645//645 546//546 646//646 -f 646//646 546//546 545//545 -f 646//646 545//545 647//647 -f 647//647 545//545 544//544 -f 647//647 544//544 648//648 -f 648//648 544//544 543//543 -f 543//543 530//530 648//648 -f 648//648 530//530 542//542 -f 648//648 542//542 649//649 -f 540//540 539//539 636//636 -f 539//539 538//538 636//636 -f 636//636 538//538 537//537 -f 636//636 537//537 637//637 -f 637//637 537//537 536//536 -f 637//637 536//536 650//650 -f 650//650 536//536 535//535 -f 650//650 535//535 651//651 -f 651//651 535//535 534//534 -f 651//651 534//534 652//652 -f 652//652 534//534 533//533 -f 533//533 532//532 652//652 -f 652//652 532//532 531//531 -f 652//652 531//531 653//653 -f 653//653 531//531 529//529 -f 653//653 529//529 654//654 -f 654//654 529//529 528//528 -f 654//654 528//528 655//655 -f 655//655 528//528 527//527 -f 527//527 526//526 655//655 -f 655//655 526//526 525//525 -f 655//655 525//525 656//656 -f 603//603 602//602 634//634 -f 602//602 601//601 634//634 -f 634//634 601//601 600//600 -f 634//634 600//600 635//635 -f 635//635 600//600 599//599 -f 635//635 599//599 657//657 -f 657//657 599//599 598//598 -f 657//657 598//598 658//658 -f 658//658 598//598 597//597 -f 658//658 597//597 659//659 -f 659//659 597//597 596//596 -f 596//596 595//595 659//659 -f 659//659 595//595 594//594 -f 659//659 594//594 660//660 -f 660//660 594//594 593//593 -f 660//660 593//593 661//661 -f 661//661 593//593 592//592 -f 661//661 592//592 662//662 -f 662//662 592//592 591//591 -f 591//591 590//590 662//662 -f 662//662 590//590 589//589 -f 662//662 589//589 663//663 -f 587//587 586//586 632//632 -f 586//586 585//585 632//632 -f 632//632 585//585 584//584 -f 632//632 584//584 633//633 -f 633//633 584//584 583//583 -f 633//633 583//583 664//664 -f 664//664 583//583 582//582 -f 664//664 582//582 665//665 -f 665//665 582//582 581//581 -f 665//665 581//581 666//666 -f 666//666 581//581 580//580 -f 580//580 579//579 666//666 -f 666//666 579//579 578//578 -f 666//666 578//578 667//667 -f 667//667 578//578 577//577 -f 667//667 577//577 668//668 -f 668//668 577//577 576//576 -f 668//668 576//576 669//669 -f 669//669 576//576 575//575 -f 575//575 574//574 669//669 -f 669//669 574//574 573//573 -f 669//669 573//573 670//670 -f 570//570 640//640 571//571 -f 564//564 671//671 565//565 -f 565//565 671//671 672//672 -f 565//565 672//672 566//566 -f 564//564 563//563 671//671 -f 671//671 563//563 562//562 -f 671//671 562//562 673//673 -f 673//673 562//562 561//561 -f 673//673 561//561 674//674 -f 674//674 561//561 560//560 -f 674//674 560//560 641//641 -f 641//641 560//560 559//559 -f 641//641 559//559 558//558 -f 642//642 675//675 676//676 -f 630//630 639//639 631//631 -f 631//631 639//639 643//643 -f 631//631 643//643 677//677 -f 677//677 643//643 644//644 -f 677//677 644//644 678//678 -f 678//678 644//644 645//645 -f 678//678 645//645 679//679 -f 679//679 645//645 646//646 -f 679//679 646//646 680//680 -f 680//680 646//646 647//647 -f 680//680 647//647 681//681 -f 681//681 647//647 648//648 -f 681//681 648//648 682//682 -f 682//682 648//648 649//649 -f 682//682 649//649 683//683 -f 627//627 637//637 628//628 -f 628//628 637//637 650//650 -f 628//628 650//650 684//684 -f 684//684 650//650 651//651 -f 684//684 651//651 685//685 -f 685//685 651//651 652//652 -f 685//685 652//652 686//686 -f 686//686 652//652 653//653 -f 686//686 653//653 687//687 -f 687//687 653//653 654//654 -f 687//687 654//654 688//688 -f 688//688 654//654 655//655 -f 688//688 655//655 689//689 -f 689//689 655//655 656//656 -f 689//689 656//656 690//690 -f 624//624 635//635 625//625 -f 625//625 635//635 657//657 -f 625//625 657//657 691//691 -f 691//691 657//657 658//658 -f 691//691 658//658 692//692 -f 692//692 658//658 659//659 -f 692//692 659//659 693//693 -f 693//693 659//659 660//660 -f 693//693 660//660 694//694 -f 694//694 660//660 661//661 -f 694//694 661//661 695//695 -f 695//695 661//661 662//662 -f 695//695 662//662 696//696 -f 696//696 662//662 663//663 -f 696//696 663//663 697//697 -f 621//621 633//633 622//622 -f 622//622 633//633 664//664 -f 622//622 664//664 698//698 -f 698//698 664//664 665//665 -f 698//698 665//665 699//699 -f 699//699 665//665 666//666 -f 699//699 666//666 700//700 -f 700//700 666//666 667//667 -f 700//700 667//667 701//701 -f 701//701 667//667 668//668 -f 701//701 668//668 702//702 -f 702//702 668//668 669//669 -f 702//702 669//669 703//703 -f 703//703 669//669 670//670 -f 703//703 670//670 704//704 -f 642//642 676//676 641//641 -f 641//641 676//676 705//705 -f 641//641 705//705 674//674 -f 674//674 705//705 706//706 -f 674//674 706//706 673//673 -f 673//673 706//706 707//707 -f 673//673 707//707 671//671 -f 671//671 707//707 708//708 -f 671//671 708//708 672//672 -f 675//675 709//709 710//710 -f 629//629 631//631 711//711 -f 711//711 631//631 677//677 -f 711//711 677//677 712//712 -f 712//712 677//677 678//678 -f 712//712 678//678 713//713 -f 713//713 678//678 679//679 -f 713//713 679//679 714//714 -f 714//714 679//679 680//680 -f 714//714 680//680 715//715 -f 715//715 680//680 681//681 -f 715//715 681//681 716//716 -f 716//716 681//681 682//682 -f 716//716 682//682 717//717 -f 717//717 682//682 683//683 -f 717//717 683//683 619//619 -f 626//626 628//628 718//718 -f 718//718 628//628 684//684 -f 718//718 684//684 719//719 -f 719//719 684//684 685//685 -f 719//719 685//685 720//720 -f 720//720 685//685 686//686 -f 720//720 686//686 721//721 -f 721//721 686//686 687//687 -f 721//721 687//687 722//722 -f 722//722 687//687 688//688 -f 722//722 688//688 723//723 -f 723//723 688//688 689//689 -f 723//723 689//689 724//724 -f 724//724 689//689 690//690 -f 724//724 690//690 616//616 -f 623//623 625//625 725//725 -f 725//725 625//625 691//691 -f 725//725 691//691 726//726 -f 726//726 691//691 692//692 -f 726//726 692//692 727//727 -f 727//727 692//692 693//693 -f 727//727 693//693 728//728 -f 728//728 693//693 694//694 -f 728//728 694//694 729//729 -f 729//729 694//694 695//695 -f 729//729 695//695 730//730 -f 730//730 695//695 696//696 -f 730//730 696//696 731//731 -f 731//731 696//696 697//697 -f 731//731 697//697 613//613 -f 620//620 622//622 732//732 -f 732//732 622//622 698//698 -f 732//732 698//698 733//733 -f 733//733 698//698 699//699 -f 733//733 699//699 734//734 -f 734//734 699//699 700//700 -f 734//734 700//700 735//735 -f 735//735 700//700 701//701 -f 735//735 701//701 736//736 -f 736//736 701//701 702//702 -f 736//736 702//702 737//737 -f 737//737 702//702 703//703 -f 737//737 703//703 738//738 -f 738//738 703//703 704//704 -f 738//738 704//704 610//610 -f 569//569 568//568 640//640 -f 640//640 568//568 739//739 -f 640//640 739//739 740//740 -f 740//740 739//739 741//741 -f 740//740 741//741 742//742 -f 742//742 741//741 607//607 -f 675//675 710//710 676//676 -f 676//676 710//710 743//743 -f 676//676 743//743 705//705 -f 705//705 743//743 744//744 -f 705//705 744//744 706//706 -f 706//706 744//744 745//745 -f 706//706 745//745 707//707 -f 707//707 745//745 746//746 -f 707//707 746//746 708//708 -f 747//747 710//710 748//748 -f 748//748 710//710 709//709 -f 748//748 709//709 749//749 -f 750//750 749//749 751//751 -f 751//751 749//749 709//709 -f 751//751 709//709 752//752 -f 752//752 709//709 675//675 -f 752//752 675//675 753//753 -f 753//753 675//675 642//642 -f 753//753 642//642 556//556 -f 556//556 642//642 557//557 -f 556//556 555//555 753//753 -f 753//753 555//555 638//638 -f 753//753 638//638 752//752 -f 752//752 638//638 630//630 -f 752//752 630//630 751//751 -f 751//751 630//630 629//629 -f 751//751 629//629 750//750 -f 750//750 629//629 754//754 -f 755//755 756//756 713//713 -f 713//713 756//756 757//757 -f 713//713 757//757 712//712 -f 712//712 757//757 758//758 -f 712//712 758//758 711//711 -f 711//711 758//758 759//759 -f 711//711 759//759 629//629 -f 629//629 759//759 760//760 -f 629//629 760//760 754//754 -f 755//755 713//713 761//761 -f 761//761 713//713 714//714 -f 761//761 714//714 762//762 -f 762//762 714//714 715//715 -f 762//762 715//715 763//763 -f 763//763 715//715 716//716 -f 763//763 716//716 764//764 -f 764//764 716//716 717//717 -f 764//764 717//717 765//765 -f 619//619 618//618 717//717 -f 717//717 618//618 766//766 -f 717//717 766//766 765//765 -f 767//767 617//617 768//768 -f 768//768 617//617 619//619 -f 768//768 619//619 769//769 -f 769//769 619//619 683//683 -f 769//769 683//683 770//770 -f 770//770 683//683 649//649 -f 770//770 649//649 541//541 -f 541//541 649//649 542//542 -f 541//541 540//540 770//770 -f 770//770 540//540 636//636 -f 770//770 636//636 769//769 -f 769//769 636//636 627//627 -f 769//769 627//627 768//768 -f 768//768 627//627 626//626 -f 768//768 626//626 767//767 -f 767//767 626//626 771//771 -f 772//772 773//773 720//720 -f 720//720 773//773 774//774 -f 720//720 774//774 719//719 -f 719//719 774//774 775//775 -f 719//719 775//775 718//718 -f 718//718 775//775 776//776 -f 718//718 776//776 626//626 -f 626//626 776//776 777//777 -f 626//626 777//777 771//771 -f 772//772 720//720 778//778 -f 778//778 720//720 721//721 -f 778//778 721//721 779//779 -f 779//779 721//721 722//722 -f 779//779 722//722 780//780 -f 780//780 722//722 723//723 -f 780//780 723//723 781//781 -f 781//781 723//723 724//724 -f 781//781 724//724 782//782 -f 616//616 615//615 724//724 -f 724//724 615//615 783//783 -f 724//724 783//783 782//782 -f 784//784 614//614 785//785 -f 785//785 614//614 616//616 -f 785//785 616//616 786//786 -f 786//786 616//616 690//690 -f 786//786 690//690 787//787 -f 787//787 690//690 656//656 -f 787//787 656//656 604//604 -f 604//604 656//656 525//525 -f 604//604 603//603 787//787 -f 787//787 603//603 634//634 -f 787//787 634//634 786//786 -f 786//786 634//634 624//624 -f 786//786 624//624 785//785 -f 785//785 624//624 623//623 -f 785//785 623//623 784//784 -f 784//784 623//623 788//788 -f 789//789 790//790 727//727 -f 727//727 790//790 791//791 -f 727//727 791//791 726//726 -f 726//726 791//791 792//792 -f 726//726 792//792 725//725 -f 725//725 792//792 793//793 -f 725//725 793//793 623//623 -f 623//623 793//793 794//794 -f 623//623 794//794 788//788 -f 789//789 727//727 795//795 -f 795//795 727//727 728//728 -f 795//795 728//728 796//796 -f 796//796 728//728 729//729 -f 796//796 729//729 797//797 -f 797//797 729//729 730//730 -f 797//797 730//730 798//798 -f 798//798 730//730 731//731 -f 798//798 731//731 799//799 -f 613//613 612//612 731//731 -f 731//731 612//612 800//800 -f 731//731 800//800 799//799 -f 801//801 611//611 802//802 -f 802//802 611//611 613//613 -f 802//802 613//613 803//803 -f 803//803 613//613 697//697 -f 803//803 697//697 804//804 -f 804//804 697//697 663//663 -f 804//804 663//663 588//588 -f 588//588 663//663 589//589 -f 588//588 587//587 804//804 -f 804//804 587//587 632//632 -f 804//804 632//632 803//803 -f 803//803 632//632 621//621 -f 803//803 621//621 802//802 -f 802//802 621//621 620//620 -f 802//802 620//620 801//801 -f 801//801 620//620 805//805 -f 806//806 807//807 734//734 -f 734//734 807//807 808//808 -f 734//734 808//808 733//733 -f 733//733 808//808 809//809 -f 733//733 809//809 732//732 -f 732//732 809//809 810//810 -f 732//732 810//810 620//620 -f 620//620 810//810 811//811 -f 620//620 811//811 805//805 -f 806//806 734//734 812//812 -f 812//812 734//734 735//735 -f 812//812 735//735 813//813 -f 813//813 735//735 736//736 -f 813//813 736//736 814//814 -f 814//814 736//736 737//737 -f 814//814 737//737 815//815 -f 815//815 737//737 738//738 -f 815//815 738//738 816//816 -f 610//610 609//609 738//738 -f 738//738 609//609 817//817 -f 738//738 817//817 816//816 -f 818//818 608//608 819//819 -f 819//819 608//608 610//610 -f 819//819 610//610 820//820 -f 820//820 610//610 704//704 -f 820//820 704//704 821//821 -f 821//821 704//704 670//670 -f 821//821 670//670 572//572 -f 572//572 670//670 573//573 -f 572//572 571//571 821//821 -f 821//821 571//571 640//640 -f 821//821 640//640 820//820 -f 820//820 640//640 740//740 -f 820//820 740//740 819//819 -f 819//819 740//740 742//742 -f 819//819 742//742 818//818 -f 818//818 742//742 822//822 -f 607//607 606//606 742//742 -f 742//742 606//606 823//823 -f 742//742 823//823 822//822 -f 824//824 605//605 825//825 -f 825//825 605//605 607//607 -f 825//825 607//607 826//826 -f 826//826 607//607 741//741 -f 826//826 741//741 827//827 -f 827//827 741//741 739//739 -f 827//827 739//739 567//567 -f 567//567 739//739 568//568 -f 567//567 566//566 827//827 -f 827//827 566//566 672//672 -f 827//827 672//672 826//826 -f 826//826 672//672 708//708 -f 826//826 708//708 825//825 -f 825//825 708//708 746//746 -f 825//825 746//746 824//824 -f 824//824 746//746 828//828 -f 747//747 829//829 710//710 -f 710//710 829//829 830//830 -f 710//710 830//830 743//743 -f 743//743 830//830 831//831 -f 743//743 831//831 744//744 -f 744//744 831//831 832//832 -f 744//744 832//832 745//745 -f 745//745 832//832 833//833 -f 745//745 833//833 746//746 -f 746//746 833//833 834//834 -f 746//746 834//834 828//828 -f 835//835 750//750 836//836 -f 836//836 750//750 754//754 -f 836//836 754//754 837//837 -f 837//837 754//754 760//760 -f 837//837 760//760 838//838 -f 838//838 760//760 759//759 -f 838//838 759//759 839//839 -f 839//839 759//759 758//758 -f 839//839 758//758 840//840 -f 771//771 841//841 842//842 -f 758//758 757//757 840//840 -f 840//840 757//757 756//756 -f 840//840 756//756 843//843 -f 843//843 756//756 755//755 -f 843//843 755//755 844//844 -f 844//844 755//755 761//761 -f 844//844 761//761 845//845 -f 845//845 761//761 762//762 -f 845//845 762//762 846//846 -f 846//846 762//762 763//763 -f 846//846 763//763 847//847 -f 847//847 763//763 764//764 -f 847//847 764//764 848//848 -f 848//848 764//764 765//765 -f 848//848 765//765 849//849 -f 849//849 765//765 766//766 -f 849//849 766//766 850//850 -f 850//850 766//766 618//618 -f 850//850 618//618 851//851 -f 851//851 618//618 617//617 -f 851//851 617//617 842//842 -f 842//842 617//617 767//767 -f 842//842 767//767 771//771 -f 771//771 777//777 841//841 -f 841//841 777//777 776//776 -f 841//841 776//776 852//852 -f 852//852 776//776 775//775 -f 852//852 775//775 853//853 -f 853//853 775//775 774//774 -f 853//853 774//774 854//854 -f 854//854 774//774 773//773 -f 854//854 773//773 855//855 -f 855//855 773//773 772//772 -f 855//855 772//772 856//856 -f 856//856 772//772 778//778 -f 856//856 778//778 857//857 -f 857//857 778//778 779//779 -f 857//857 779//779 858//858 -f 858//858 779//779 780//780 -f 858//858 780//780 859//859 -f 859//859 780//780 781//781 -f 859//859 781//781 860//860 -f 860//860 781//781 782//782 -f 860//860 782//782 861//861 -f 782//782 783//783 861//861 -f 861//861 783//783 615//615 -f 861//861 615//615 862//862 -f 862//862 615//615 614//614 -f 862//862 614//614 863//863 -f 863//863 614//614 784//784 -f 863//863 784//784 864//864 -f 864//864 784//784 788//788 -f 864//864 788//788 865//865 -f 865//865 788//788 794//794 -f 865//865 794//794 866//866 -f 866//866 794//794 793//793 -f 866//866 793//793 867//867 -f 867//867 793//793 792//792 -f 867//867 792//792 868//868 -f 792//792 791//791 868//868 -f 868//868 791//791 790//790 -f 868//868 790//790 869//869 -f 869//869 790//790 789//789 -f 869//869 789//789 870//870 -f 870//870 789//789 795//795 -f 870//870 795//795 871//871 -f 795//795 796//796 871//871 -f 871//871 796//796 797//797 -f 871//871 797//797 872//872 -f 872//872 797//797 798//798 -f 872//872 798//798 873//873 -f 873//873 798//798 874//874 -f 874//874 798//798 799//799 -f 874//874 799//799 875//875 -f 875//875 799//799 800//800 -f 875//875 800//800 876//876 -f 876//876 800//800 612//612 -f 876//876 612//612 877//877 -f 877//877 612//612 611//611 -f 877//877 611//611 878//878 -f 611//611 801//801 878//878 -f 878//878 801//801 805//805 -f 878//878 805//805 879//879 -f 879//879 805//805 811//811 -f 879//879 811//811 880//880 -f 880//880 811//811 810//810 -f 880//880 810//810 881//881 -f 810//810 809//809 881//881 -f 881//881 809//809 808//808 -f 881//881 808//808 882//882 -f 882//882 808//808 807//807 -f 882//882 807//807 883//883 -f 883//883 807//807 806//806 -f 883//883 806//806 884//884 -f 884//884 806//806 812//812 -f 884//884 812//812 885//885 -f 885//885 812//812 813//813 -f 885//885 813//813 886//886 -f 886//886 813//813 814//814 -f 886//886 814//814 887//887 -f 887//887 814//814 815//815 -f 887//887 815//815 888//888 -f 888//888 815//815 816//816 -f 888//888 816//816 889//889 -f 889//889 816//816 817//817 -f 889//889 817//817 890//890 -f 890//890 817//817 609//609 -f 890//890 609//609 891//891 -f 609//609 608//608 891//891 -f 891//891 608//608 818//818 -f 891//891 818//818 892//892 -f 892//892 818//818 822//822 -f 892//892 822//822 893//893 -f 893//893 822//822 823//823 -f 893//893 823//823 894//894 -f 894//894 823//823 606//606 -f 894//894 606//606 895//895 -f 895//895 606//606 605//605 -f 895//895 605//605 896//896 -f 605//605 824//824 896//896 -f 896//896 824//824 828//828 -f 896//896 828//828 897//897 -f 897//897 828//828 834//834 -f 897//897 834//834 898//898 -f 898//898 834//834 833//833 -f 898//898 833//833 899//899 -f 899//899 833//833 832//832 -f 899//899 832//832 900//900 -f 900//900 832//832 831//831 -f 900//900 831//831 901//901 -f 901//901 831//831 830//830 -f 901//901 830//830 902//902 -f 902//902 830//830 829//829 -f 902//902 829//829 903//903 -f 903//903 829//829 747//747 -f 903//903 747//747 904//904 -f 904//904 747//747 748//748 -f 904//904 748//748 835//835 -f 835//835 748//748 749//749 -f 835//835 749//749 750//750 -f 905//905 906//906 907//907 -f 908//908 909//909 910//910 -f 911//911 912//912 913//913 -f 914//914 915//915 916//916 -f 917//917 918//918 919//919 -f 920//920 921//921 922//922 -f 923//923 924//924 925//925 -f 897//897 898//898 905//905 -f 895//895 896//896 926//926 -f 893//893 894//894 927//927 -f 887//887 888//888 908//908 -f 885//885 886//886 928//928 -f 883//883 884//884 929//929 -f 877//877 878//878 911//911 -f 875//875 876//876 930//930 -f 873//873 874//874 931//931 -f 867//867 868//868 914//914 -f 865//865 866//866 932//932 -f 863//863 864//864 933//933 -f 857//857 858//858 917//917 -f 855//855 856//856 934//934 -f 853//853 854//854 935//935 -f 849//849 850//850 920//920 -f 847//847 848//848 936//936 -f 845//845 846//846 937//937 -f 837//837 838//838 923//923 -f 835//835 836//836 938//938 -f 903//903 904//904 939//939 -f 901//901 902//902 940//940 -f 940//940 902//902 903//903 -f 923//923 838//838 924//924 -f 924//924 838//838 839//839 -f 924//924 839//839 840//840 -f 843//843 844//844 941//941 -f 941//941 844//844 845//845 -f 920//920 850//850 921//921 -f 921//921 850//850 851//851 -f 921//921 851//851 842//842 -f 841//841 852//852 942//942 -f 942//942 852//852 853//853 -f 917//917 858//858 918//918 -f 918//918 858//858 859//859 -f 918//918 859//859 860//860 -f 861//861 862//862 943//943 -f 943//943 862//862 863//863 -f 914//914 868//868 915//915 -f 915//915 868//868 869//869 -f 915//915 869//869 870//870 -f 871//871 872//872 944//944 -f 944//944 872//872 873//873 -f 911//911 878//878 912//912 -f 912//912 878//878 879//879 -f 912//912 879//879 880//880 -f 881//881 882//882 945//945 -f 945//945 882//882 883//883 -f 908//908 888//888 909//909 -f 909//909 888//888 889//889 -f 909//909 889//889 890//890 -f 891//891 892//892 946//946 -f 946//946 892//892 893//893 -f 905//905 898//898 906//906 -f 906//906 898//898 899//899 -f 906//906 899//899 900//900 -f 947//947 948//948 939//939 -f 949//949 925//925 950//950 -f 950//950 925//925 924//924 -f 950//950 924//924 951//951 -f 951//951 924//924 840//840 -f 951//951 840//840 843//843 -f 952//952 953//953 937//937 -f 954//954 922//922 955//955 -f 955//955 922//922 921//921 -f 955//955 921//921 956//956 -f 956//956 921//921 842//842 -f 956//956 842//842 841//841 -f 957//957 958//958 935//935 -f 959//959 919//919 960//960 -f 960//960 919//919 918//918 -f 960//960 918//918 961//961 -f 961//961 918//918 860//860 -f 961//961 860//860 861//861 -f 962//962 963//963 933//933 -f 964//964 916//916 965//965 -f 965//965 916//916 915//915 -f 965//965 915//915 966//966 -f 966//966 915//915 870//870 -f 966//966 870//870 871//871 -f 967//967 968//968 931//931 -f 969//969 913//913 970//970 -f 970//970 913//913 912//912 -f 970//970 912//912 971//971 -f 971//971 912//912 880//880 -f 971//971 880//880 881//881 -f 972//972 973//973 929//929 -f 974//974 910//910 975//975 -f 975//975 910//910 909//909 -f 975//975 909//909 976//976 -f 976//976 909//909 890//890 -f 976//976 890//890 891//891 -f 977//977 978//978 927//927 -f 979//979 907//907 980//980 -f 980//980 907//907 906//906 -f 980//980 906//906 981//981 -f 981//981 906//906 900//900 -f 981//981 900//900 901//901 -f 982//982 948//948 983//983 -f 983//983 948//948 947//947 -f 983//983 947//947 984//984 -f 985//985 953//953 986//986 -f 986//986 953//953 952//952 -f 986//986 952//952 987//987 -f 988//988 958//958 989//989 -f 989//989 958//958 957//957 -f 989//989 957//957 990//990 -f 991//991 963//963 992//992 -f 992//992 963//963 962//962 -f 992//992 962//962 993//993 -f 994//994 968//968 995//995 -f 995//995 968//968 967//967 -f 995//995 967//967 996//996 -f 997//997 973//973 998//998 -f 998//998 973//973 972//972 -f 998//998 972//972 999//999 -f 1000//1000 978//978 1001//1001 -f 1001//1001 978//978 977//977 -f 1001//1001 977//977 1002//1002 -f 1003//1003 1004//1004 1005//1005 -f 901//901 940//940 981//981 -f 981//981 940//940 1006//1006 -f 981//981 1006//1006 980//980 -f 980//980 1006//1006 1003//1003 -f 980//980 1003//1003 979//979 -f 979//979 1003//1003 1005//1005 -f 979//979 1005//1005 1007//1007 -f 903//903 939//939 940//940 -f 940//940 939//939 948//948 -f 940//940 948//948 1006//1006 -f 1006//1006 948//948 982//982 -f 1006//1006 982//982 1003//1003 -f 1003//1003 982//982 1008//1008 -f 1003//1003 1008//1008 1004//1004 -f 1009//1009 1010//1010 1011//1011 -f 1011//1011 1010//1010 984//984 -f 1011//1011 984//984 1012//1012 -f 1012//1012 984//984 947//947 -f 1012//1012 947//947 938//938 -f 938//938 947//947 939//939 -f 938//938 939//939 835//835 -f 835//835 939//939 904//904 -f 1010//1010 1013//1013 984//984 -f 984//984 1013//1013 1014//1014 -f 984//984 1014//1014 983//983 -f 983//983 1014//1014 1015//1015 -f 983//983 1015//1015 982//982 -f 982//982 1015//1015 1016//1016 -f 982//982 1016//1016 1008//1008 -f 836//836 837//837 938//938 -f 938//938 837//837 923//923 -f 938//938 923//923 1012//1012 -f 1012//1012 923//923 925//925 -f 1012//1012 925//925 1011//1011 -f 1011//1011 925//925 949//949 -f 1011//1011 949//949 1009//1009 -f 1009//1009 949//949 1017//1017 -f 1018//1018 1019//1019 1020//1020 -f 843//843 941//941 951//951 -f 951//951 941//941 1021//1021 -f 951//951 1021//1021 950//950 -f 950//950 1021//1021 1018//1018 -f 950//950 1018//1018 949//949 -f 949//949 1018//1018 1020//1020 -f 949//949 1020//1020 1017//1017 -f 845//845 937//937 941//941 -f 941//941 937//937 953//953 -f 941//941 953//953 1021//1021 -f 1021//1021 953//953 985//985 -f 1021//1021 985//985 1018//1018 -f 1018//1018 985//985 1022//1022 -f 1018//1018 1022//1022 1019//1019 -f 1023//1023 1024//1024 1025//1025 -f 1025//1025 1024//1024 987//987 -f 1025//1025 987//987 1026//1026 -f 1026//1026 987//987 952//952 -f 1026//1026 952//952 936//936 -f 936//936 952//952 937//937 -f 936//936 937//937 847//847 -f 847//847 937//937 846//846 -f 1024//1024 1027//1027 987//987 -f 987//987 1027//1027 1028//1028 -f 987//987 1028//1028 986//986 -f 986//986 1028//1028 1029//1029 -f 986//986 1029//1029 985//985 -f 985//985 1029//1029 1030//1030 -f 985//985 1030//1030 1022//1022 -f 848//848 849//849 936//936 -f 936//936 849//849 920//920 -f 936//936 920//920 1026//1026 -f 1026//1026 920//920 922//922 -f 1026//1026 922//922 1025//1025 -f 1025//1025 922//922 954//954 -f 1025//1025 954//954 1023//1023 -f 1023//1023 954//954 1031//1031 -f 1032//1032 1033//1033 1034//1034 -f 841//841 942//942 956//956 -f 956//956 942//942 1035//1035 -f 956//956 1035//1035 955//955 -f 955//955 1035//1035 1032//1032 -f 955//955 1032//1032 954//954 -f 954//954 1032//1032 1034//1034 -f 954//954 1034//1034 1031//1031 -f 853//853 935//935 942//942 -f 942//942 935//935 958//958 -f 942//942 958//958 1035//1035 -f 1035//1035 958//958 988//988 -f 1035//1035 988//988 1032//1032 -f 1032//1032 988//988 1036//1036 -f 1032//1032 1036//1036 1033//1033 -f 1037//1037 1038//1038 1039//1039 -f 1039//1039 1038//1038 990//990 -f 1039//1039 990//990 1040//1040 -f 1040//1040 990//990 957//957 -f 1040//1040 957//957 934//934 -f 934//934 957//957 935//935 -f 934//934 935//935 855//855 -f 855//855 935//935 854//854 -f 1038//1038 1041//1041 990//990 -f 990//990 1041//1041 1042//1042 -f 990//990 1042//1042 989//989 -f 989//989 1042//1042 1043//1043 -f 989//989 1043//1043 988//988 -f 988//988 1043//1043 1044//1044 -f 988//988 1044//1044 1036//1036 -f 856//856 857//857 934//934 -f 934//934 857//857 917//917 -f 934//934 917//917 1040//1040 -f 1040//1040 917//917 919//919 -f 1040//1040 919//919 1039//1039 -f 1039//1039 919//919 959//959 -f 1039//1039 959//959 1037//1037 -f 1037//1037 959//959 1045//1045 -f 1046//1046 1047//1047 1048//1048 -f 861//861 943//943 961//961 -f 961//961 943//943 1049//1049 -f 961//961 1049//1049 960//960 -f 960//960 1049//1049 1046//1046 -f 960//960 1046//1046 959//959 -f 959//959 1046//1046 1048//1048 -f 959//959 1048//1048 1045//1045 -f 863//863 933//933 943//943 -f 943//943 933//933 963//963 -f 943//943 963//963 1049//1049 -f 1049//1049 963//963 991//991 -f 1049//1049 991//991 1046//1046 -f 1046//1046 991//991 1050//1050 -f 1046//1046 1050//1050 1047//1047 -f 1051//1051 1052//1052 1053//1053 -f 1053//1053 1052//1052 993//993 -f 1053//1053 993//993 1054//1054 -f 1054//1054 993//993 962//962 -f 1054//1054 962//962 932//932 -f 932//932 962//962 933//933 -f 932//932 933//933 865//865 -f 865//865 933//933 864//864 -f 1052//1052 1055//1055 993//993 -f 993//993 1055//1055 1056//1056 -f 993//993 1056//1056 992//992 -f 992//992 1056//1056 1057//1057 -f 992//992 1057//1057 991//991 -f 991//991 1057//1057 1058//1058 -f 991//991 1058//1058 1050//1050 -f 866//866 867//867 932//932 -f 932//932 867//867 914//914 -f 932//932 914//914 1054//1054 -f 1054//1054 914//914 916//916 -f 1054//1054 916//916 1053//1053 -f 1053//1053 916//916 964//964 -f 1053//1053 964//964 1051//1051 -f 1051//1051 964//964 1059//1059 -f 1060//1060 1061//1061 1062//1062 -f 871//871 944//944 966//966 -f 966//966 944//944 1063//1063 -f 966//966 1063//1063 965//965 -f 965//965 1063//1063 1060//1060 -f 965//965 1060//1060 964//964 -f 964//964 1060//1060 1062//1062 -f 964//964 1062//1062 1059//1059 -f 873//873 931//931 944//944 -f 944//944 931//931 968//968 -f 944//944 968//968 1063//1063 -f 1063//1063 968//968 994//994 -f 1063//1063 994//994 1060//1060 -f 1060//1060 994//994 1064//1064 -f 1060//1060 1064//1064 1061//1061 -f 1065//1065 1066//1066 1067//1067 -f 1067//1067 1066//1066 996//996 -f 1067//1067 996//996 1068//1068 -f 1068//1068 996//996 967//967 -f 1068//1068 967//967 930//930 -f 930//930 967//967 931//931 -f 930//930 931//931 875//875 -f 875//875 931//931 874//874 -f 1066//1066 1069//1069 996//996 -f 996//996 1069//1069 1070//1070 -f 996//996 1070//1070 995//995 -f 995//995 1070//1070 1071//1071 -f 995//995 1071//1071 994//994 -f 994//994 1071//1071 1072//1072 -f 994//994 1072//1072 1064//1064 -f 876//876 877//877 930//930 -f 930//930 877//877 911//911 -f 930//930 911//911 1068//1068 -f 1068//1068 911//911 913//913 -f 1068//1068 913//913 1067//1067 -f 1067//1067 913//913 969//969 -f 1067//1067 969//969 1065//1065 -f 1065//1065 969//969 1073//1073 -f 1074//1074 1075//1075 1076//1076 -f 881//881 945//945 971//971 -f 971//971 945//945 1077//1077 -f 971//971 1077//1077 970//970 -f 970//970 1077//1077 1074//1074 -f 970//970 1074//1074 969//969 -f 969//969 1074//1074 1076//1076 -f 969//969 1076//1076 1073//1073 -f 883//883 929//929 945//945 -f 945//945 929//929 973//973 -f 945//945 973//973 1077//1077 -f 1077//1077 973//973 997//997 -f 1077//1077 997//997 1074//1074 -f 1074//1074 997//997 1078//1078 -f 1074//1074 1078//1078 1075//1075 -f 1079//1079 1080//1080 1081//1081 -f 1081//1081 1080//1080 999//999 -f 1081//1081 999//999 1082//1082 -f 1082//1082 999//999 972//972 -f 1082//1082 972//972 928//928 -f 928//928 972//972 929//929 -f 928//928 929//929 885//885 -f 885//885 929//929 884//884 -f 1080//1080 1083//1083 999//999 -f 999//999 1083//1083 1084//1084 -f 999//999 1084//1084 998//998 -f 998//998 1084//1084 1085//1085 -f 998//998 1085//1085 997//997 -f 997//997 1085//1085 1086//1086 -f 997//997 1086//1086 1078//1078 -f 886//886 887//887 928//928 -f 928//928 887//887 908//908 -f 928//928 908//908 1082//1082 -f 1082//1082 908//908 910//910 -f 1082//1082 910//910 1081//1081 -f 1081//1081 910//910 974//974 -f 1081//1081 974//974 1079//1079 -f 1079//1079 974//974 1087//1087 -f 1088//1088 1089//1089 1090//1090 -f 891//891 946//946 976//976 -f 976//976 946//946 1091//1091 -f 976//976 1091//1091 975//975 -f 975//975 1091//1091 1088//1088 -f 975//975 1088//1088 974//974 -f 974//974 1088//1088 1090//1090 -f 974//974 1090//1090 1087//1087 -f 893//893 927//927 946//946 -f 946//946 927//927 978//978 -f 946//946 978//978 1091//1091 -f 1091//1091 978//978 1000//1000 -f 1091//1091 1000//1000 1088//1088 -f 1088//1088 1000//1000 1092//1092 -f 1088//1088 1092//1092 1089//1089 -f 1093//1093 1094//1094 1095//1095 -f 1095//1095 1094//1094 1002//1002 -f 1095//1095 1002//1002 1096//1096 -f 1096//1096 1002//1002 977//977 -f 1096//1096 977//977 926//926 -f 926//926 977//977 927//927 -f 926//926 927//927 895//895 -f 895//895 927//927 894//894 -f 1094//1094 1097//1097 1002//1002 -f 1002//1002 1097//1097 1098//1098 -f 1002//1002 1098//1098 1001//1001 -f 1001//1001 1098//1098 1099//1099 -f 1001//1001 1099//1099 1000//1000 -f 1000//1000 1099//1099 1100//1100 -f 1000//1000 1100//1100 1092//1092 -f 896//896 897//897 926//926 -f 926//926 897//897 905//905 -f 926//926 905//905 1096//1096 -f 1096//1096 905//905 907//907 -f 1096//1096 907//907 1095//1095 -f 1095//1095 907//907 979//979 -f 1095//1095 979//979 1093//1093 -f 1093//1093 979//979 1007//1007 -f 1057//1057 1101//1101 1058//1058 -f 1058//1058 1101//1101 1102//1102 -f 1058//1058 1102//1102 1050//1050 -f 1050//1050 1102//1102 1103//1103 -f 1050//1050 1103//1103 1047//1047 -f 1047//1047 1103//1103 1104//1104 -f 1047//1047 1104//1104 1048//1048 -f 1048//1048 1104//1104 1105//1105 -f 1048//1048 1105//1105 1045//1045 -f 1045//1045 1105//1105 1106//1106 -f 1045//1045 1106//1106 1037//1037 -f 1037//1037 1106//1106 1107//1107 -f 1037//1037 1107//1107 1038//1038 -f 1107//1107 1108//1108 1038//1038 -f 1038//1038 1108//1108 1109//1109 -f 1038//1038 1109//1109 1041//1041 -f 1041//1041 1109//1109 1110//1110 -f 1041//1041 1110//1110 1042//1042 -f 1042//1042 1110//1110 1111//1111 -f 1042//1042 1111//1111 1043//1043 -f 1111//1111 1112//1112 1043//1043 -f 1043//1043 1112//1112 1113//1113 -f 1043//1043 1113//1113 1044//1044 -f 1044//1044 1113//1113 1114//1114 -f 1044//1044 1114//1114 1036//1036 -f 1036//1036 1114//1114 1115//1115 -f 1036//1036 1115//1115 1033//1033 -f 1033//1033 1115//1115 1116//1116 -f 1033//1033 1116//1116 1034//1034 -f 1034//1034 1116//1116 1117//1117 -f 1034//1034 1117//1117 1031//1031 -f 1031//1031 1117//1117 1118//1118 -f 1031//1031 1118//1118 1023//1023 -f 1023//1023 1118//1118 1119//1119 -f 1023//1023 1119//1119 1024//1024 -f 1119//1119 1120//1120 1024//1024 -f 1024//1024 1120//1120 1121//1121 -f 1024//1024 1121//1121 1027//1027 -f 1027//1027 1121//1121 1122//1122 -f 1027//1027 1122//1122 1028//1028 -f 1028//1028 1122//1122 1123//1123 -f 1028//1028 1123//1123 1029//1029 -f 1123//1123 1124//1124 1029//1029 -f 1029//1029 1124//1124 1125//1125 -f 1029//1029 1125//1125 1030//1030 -f 1030//1030 1125//1125 1126//1126 -f 1030//1030 1126//1126 1022//1022 -f 1022//1022 1126//1126 1127//1127 -f 1022//1022 1127//1127 1019//1019 -f 1019//1019 1127//1127 1128//1128 -f 1019//1019 1128//1128 1020//1020 -f 1020//1020 1128//1128 1129//1129 -f 1020//1020 1129//1129 1017//1017 -f 1017//1017 1129//1129 1130//1130 -f 1017//1017 1130//1130 1009//1009 -f 1009//1009 1130//1130 1131//1131 -f 1009//1009 1131//1131 1010//1010 -f 1131//1131 1132//1132 1010//1010 -f 1010//1010 1132//1132 1133//1133 -f 1010//1010 1133//1133 1013//1013 -f 1013//1013 1133//1133 1134//1134 -f 1013//1013 1134//1134 1014//1014 -f 1014//1014 1134//1134 1135//1135 -f 1014//1014 1135//1135 1015//1015 -f 1135//1135 1136//1136 1015//1015 -f 1015//1015 1136//1136 1137//1137 -f 1015//1015 1137//1137 1016//1016 -f 1016//1016 1137//1137 1138//1138 -f 1016//1016 1138//1138 1008//1008 -f 1008//1008 1138//1138 1139//1139 -f 1008//1008 1139//1139 1004//1004 -f 1004//1004 1139//1139 1140//1140 -f 1004//1004 1140//1140 1005//1005 -f 1005//1005 1140//1140 1141//1141 -f 1005//1005 1141//1141 1007//1007 -f 1007//1007 1141//1141 1142//1142 -f 1007//1007 1142//1142 1093//1093 -f 1093//1093 1142//1142 1143//1143 -f 1093//1093 1143//1143 1094//1094 -f 1143//1143 1144//1144 1094//1094 -f 1094//1094 1144//1144 1145//1145 -f 1094//1094 1145//1145 1097//1097 -f 1097//1097 1145//1145 1146//1146 -f 1097//1097 1146//1146 1098//1098 -f 1098//1098 1146//1146 1147//1147 -f 1098//1098 1147//1147 1099//1099 -f 1147//1147 1148//1148 1099//1099 -f 1099//1099 1148//1148 1149//1149 -f 1099//1099 1149//1149 1100//1100 -f 1100//1100 1149//1149 1150//1150 -f 1100//1100 1150//1150 1092//1092 -f 1092//1092 1150//1150 1151//1151 -f 1092//1092 1151//1151 1089//1089 -f 1089//1089 1151//1151 1152//1152 -f 1089//1089 1152//1152 1090//1090 -f 1090//1090 1152//1152 1153//1153 -f 1090//1090 1153//1153 1087//1087 -f 1087//1087 1153//1153 1154//1154 -f 1087//1087 1154//1154 1079//1079 -f 1079//1079 1154//1154 1155//1155 -f 1079//1079 1155//1155 1080//1080 -f 1155//1155 1156//1156 1080//1080 -f 1080//1080 1156//1156 1157//1157 -f 1080//1080 1157//1157 1083//1083 -f 1083//1083 1157//1157 1158//1158 -f 1083//1083 1158//1158 1084//1084 -f 1084//1084 1158//1158 1159//1159 -f 1084//1084 1159//1159 1085//1085 -f 1159//1159 1160//1160 1085//1085 -f 1085//1085 1160//1160 1161//1161 -f 1085//1085 1161//1161 1086//1086 -f 1086//1086 1161//1161 1162//1162 -f 1086//1086 1162//1162 1078//1078 -f 1078//1078 1162//1162 1163//1163 -f 1078//1078 1163//1163 1075//1075 -f 1075//1075 1163//1163 1164//1164 -f 1075//1075 1164//1164 1076//1076 -f 1076//1076 1164//1164 1165//1165 -f 1076//1076 1165//1165 1073//1073 -f 1073//1073 1165//1165 1166//1166 -f 1073//1073 1166//1166 1065//1065 -f 1065//1065 1166//1166 1167//1167 -f 1065//1065 1167//1167 1066//1066 -f 1167//1167 1168//1168 1066//1066 -f 1066//1066 1168//1168 1169//1169 -f 1066//1066 1169//1169 1069//1069 -f 1069//1069 1169//1169 1170//1170 -f 1069//1069 1170//1170 1070//1070 -f 1070//1070 1170//1170 1171//1171 -f 1070//1070 1171//1171 1071//1071 -f 1171//1171 1172//1172 1071//1071 -f 1071//1071 1172//1172 1173//1173 -f 1071//1071 1173//1173 1072//1072 -f 1072//1072 1173//1173 1174//1174 -f 1072//1072 1174//1174 1064//1064 -f 1064//1064 1174//1174 1175//1175 -f 1064//1064 1175//1175 1061//1061 -f 1061//1061 1175//1175 1176//1176 -f 1061//1061 1176//1176 1062//1062 -f 1062//1062 1176//1176 1177//1177 -f 1062//1062 1177//1177 1059//1059 -f 1059//1059 1177//1177 1178//1178 -f 1059//1059 1178//1178 1051//1051 -f 1051//1051 1178//1178 1179//1179 -f 1051//1051 1179//1179 1052//1052 -f 1179//1179 1180//1180 1052//1052 -f 1052//1052 1180//1180 1181//1181 -f 1052//1052 1181//1181 1055//1055 -f 1055//1055 1181//1181 1182//1182 -f 1055//1055 1182//1182 1056//1056 -f 1056//1056 1182//1182 1183//1183 -f 1056//1056 1183//1183 1057//1057 -f 1057//1057 1183//1183 1184//1184 -f 1057//1057 1184//1184 1101//1101 -f 1141//1141 1185//1185 1186//1186 -f 1141//1141 1140//1140 1185//1185 -f 1185//1185 1140//1140 1139//1139 -f 1185//1185 1139//1139 1187//1187 -f 1187//1187 1139//1139 1138//1138 -f 1187//1187 1138//1138 1188//1188 -f 1138//1138 1137//1137 1188//1188 -f 1188//1188 1137//1137 1136//1136 -f 1188//1188 1136//1136 1189//1189 -f 1189//1189 1136//1136 1135//1135 -f 1189//1189 1135//1135 1190//1190 -f 1190//1190 1135//1135 1134//1134 -f 1129//1129 1191//1191 1192//1192 -f 1134//1134 1133//1133 1190//1190 -f 1190//1190 1133//1133 1132//1132 -f 1190//1190 1132//1132 1193//1193 -f 1193//1193 1132//1132 1131//1131 -f 1193//1193 1131//1131 1192//1192 -f 1192//1192 1131//1131 1130//1130 -f 1192//1192 1130//1130 1129//1129 -f 1129//1129 1128//1128 1191//1191 -f 1191//1191 1128//1128 1127//1127 -f 1191//1191 1127//1127 1194//1194 -f 1194//1194 1127//1127 1126//1126 -f 1194//1194 1126//1126 1195//1195 -f 1126//1126 1125//1125 1195//1195 -f 1195//1195 1125//1125 1124//1124 -f 1195//1195 1124//1124 1196//1196 -f 1196//1196 1124//1124 1123//1123 -f 1196//1196 1123//1123 1197//1197 -f 1197//1197 1123//1123 1122//1122 -f 1117//1117 1198//1198 1199//1199 -f 1122//1122 1121//1121 1197//1197 -f 1197//1197 1121//1121 1120//1120 -f 1197//1197 1120//1120 1200//1200 -f 1200//1200 1120//1120 1119//1119 -f 1200//1200 1119//1119 1199//1199 -f 1199//1199 1119//1119 1118//1118 -f 1199//1199 1118//1118 1117//1117 -f 1117//1117 1116//1116 1198//1198 -f 1198//1198 1116//1116 1115//1115 -f 1198//1198 1115//1115 1201//1201 -f 1201//1201 1115//1115 1114//1114 -f 1201//1201 1114//1114 1202//1202 -f 1114//1114 1113//1113 1202//1202 -f 1202//1202 1113//1113 1112//1112 -f 1202//1202 1112//1112 1203//1203 -f 1203//1203 1112//1112 1111//1111 -f 1203//1203 1111//1111 1204//1204 -f 1204//1204 1111//1111 1110//1110 -f 1105//1105 1205//1205 1206//1206 -f 1110//1110 1109//1109 1204//1204 -f 1204//1204 1109//1109 1108//1108 -f 1204//1204 1108//1108 1207//1207 -f 1207//1207 1108//1108 1107//1107 -f 1207//1207 1107//1107 1206//1206 -f 1206//1206 1107//1107 1106//1106 -f 1206//1206 1106//1106 1105//1105 -f 1105//1105 1104//1104 1205//1205 -f 1205//1205 1104//1104 1103//1103 -f 1205//1205 1103//1103 1208//1208 -f 1208//1208 1103//1103 1102//1102 -f 1208//1208 1102//1102 1209//1209 -f 1102//1102 1101//1101 1209//1209 -f 1209//1209 1101//1101 1184//1184 -f 1209//1209 1184//1184 1210//1210 -f 1210//1210 1184//1184 1183//1183 -f 1210//1210 1183//1183 1211//1211 -f 1211//1211 1183//1183 1182//1182 -f 1177//1177 1212//1212 1213//1213 -f 1182//1182 1181//1181 1211//1211 -f 1211//1211 1181//1181 1180//1180 -f 1211//1211 1180//1180 1214//1214 -f 1214//1214 1180//1180 1179//1179 -f 1214//1214 1179//1179 1213//1213 -f 1213//1213 1179//1179 1178//1178 -f 1213//1213 1178//1178 1177//1177 -f 1177//1177 1176//1176 1212//1212 -f 1212//1212 1176//1176 1175//1175 -f 1212//1212 1175//1175 1215//1215 -f 1215//1215 1175//1175 1174//1174 -f 1215//1215 1174//1174 1216//1216 -f 1174//1174 1173//1173 1216//1216 -f 1216//1216 1173//1173 1172//1172 -f 1216//1216 1172//1172 1217//1217 -f 1217//1217 1172//1172 1171//1171 -f 1217//1217 1171//1171 1218//1218 -f 1218//1218 1171//1171 1170//1170 -f 1165//1165 1219//1219 1220//1220 -f 1170//1170 1169//1169 1218//1218 -f 1218//1218 1169//1169 1168//1168 -f 1218//1218 1168//1168 1221//1221 -f 1221//1221 1168//1168 1167//1167 -f 1221//1221 1167//1167 1220//1220 -f 1220//1220 1167//1167 1166//1166 -f 1220//1220 1166//1166 1165//1165 -f 1165//1165 1164//1164 1219//1219 -f 1219//1219 1164//1164 1163//1163 -f 1219//1219 1163//1163 1222//1222 -f 1222//1222 1163//1163 1162//1162 -f 1222//1222 1162//1162 1223//1223 -f 1162//1162 1161//1161 1223//1223 -f 1223//1223 1161//1161 1160//1160 -f 1223//1223 1160//1160 1224//1224 -f 1224//1224 1160//1160 1159//1159 -f 1224//1224 1159//1159 1225//1225 -f 1225//1225 1159//1159 1158//1158 -f 1153//1153 1226//1226 1227//1227 -f 1158//1158 1157//1157 1225//1225 -f 1225//1225 1157//1157 1156//1156 -f 1225//1225 1156//1156 1228//1228 -f 1228//1228 1156//1156 1155//1155 -f 1228//1228 1155//1155 1227//1227 -f 1227//1227 1155//1155 1154//1154 -f 1227//1227 1154//1154 1153//1153 -f 1153//1153 1152//1152 1226//1226 -f 1226//1226 1152//1152 1151//1151 -f 1226//1226 1151//1151 1229//1229 -f 1229//1229 1151//1151 1150//1150 -f 1229//1229 1150//1150 1230//1230 -f 1150//1150 1149//1149 1230//1230 -f 1230//1230 1149//1149 1148//1148 -f 1230//1230 1148//1148 1231//1231 -f 1231//1231 1148//1148 1147//1147 -f 1231//1231 1147//1147 1232//1232 -f 1232//1232 1147//1147 1146//1146 -f 1146//1146 1145//1145 1232//1232 -f 1232//1232 1145//1145 1144//1144 -f 1232//1232 1144//1144 1233//1233 -f 1233//1233 1144//1144 1143//1143 -f 1233//1233 1143//1143 1186//1186 -f 1186//1186 1143//1143 1142//1142 -f 1186//1186 1142//1142 1141//1141 -f 1186//1186 1234//1234 1233//1233 -f 1233//1233 1234//1234 1235//1235 -f 1233//1233 1235//1235 1232//1232 -f 1232//1232 1235//1235 1236//1236 -f 1232//1232 1236//1236 1231//1231 -f 1231//1231 1236//1236 1237//1237 -f 1231//1231 1237//1237 1230//1230 -f 1230//1230 1237//1237 1238//1238 -f 1230//1230 1238//1238 1229//1229 -f 1229//1229 1238//1238 1239//1239 -f 1229//1229 1239//1239 1226//1226 -f 1226//1226 1239//1239 1240//1240 -f 1226//1226 1240//1240 1227//1227 -f 1227//1227 1240//1240 1241//1241 -f 1227//1227 1241//1241 1228//1228 -f 1228//1228 1241//1241 1242//1242 -f 1228//1228 1242//1242 1225//1225 -f 1225//1225 1242//1242 1243//1243 -f 1225//1225 1243//1243 1224//1224 -f 1224//1224 1243//1243 1244//1244 -f 1224//1224 1244//1244 1223//1223 -f 1223//1223 1244//1244 1245//1245 -f 1223//1223 1245//1245 1222//1222 -f 1222//1222 1245//1245 1246//1246 -f 1222//1222 1246//1246 1219//1219 -f 1219//1219 1246//1246 1247//1247 -f 1219//1219 1247//1247 1220//1220 -f 1220//1220 1247//1247 1248//1248 -f 1220//1220 1248//1248 1221//1221 -f 1221//1221 1248//1248 1249//1249 -f 1221//1221 1249//1249 1218//1218 -f 1218//1218 1249//1249 1250//1250 -f 1218//1218 1250//1250 1217//1217 -f 1217//1217 1250//1250 1251//1251 -f 1217//1217 1251//1251 1216//1216 -f 1216//1216 1251//1251 1252//1252 -f 1216//1216 1252//1252 1215//1215 -f 1215//1215 1252//1252 1253//1253 -f 1215//1215 1253//1253 1212//1212 -f 1212//1212 1253//1253 1254//1254 -f 1212//1212 1254//1254 1213//1213 -f 1213//1213 1254//1254 1255//1255 -f 1213//1213 1255//1255 1214//1214 -f 1214//1214 1255//1255 1256//1256 -f 1214//1214 1256//1256 1211//1211 -f 1211//1211 1256//1256 1257//1257 -f 1211//1211 1257//1257 1210//1210 -f 1210//1210 1257//1257 1258//1258 -f 1210//1210 1258//1258 1209//1209 -f 1209//1209 1258//1258 1259//1259 -f 1209//1209 1259//1259 1208//1208 -f 1208//1208 1259//1259 1260//1260 -f 1208//1208 1260//1260 1205//1205 -f 1205//1205 1260//1260 1261//1261 -f 1205//1205 1261//1261 1206//1206 -f 1206//1206 1261//1261 1262//1262 -f 1206//1206 1262//1262 1207//1207 -f 1207//1207 1262//1262 1263//1263 -f 1207//1207 1263//1263 1204//1204 -f 1204//1204 1263//1263 1264//1264 -f 1204//1204 1264//1264 1203//1203 -f 1203//1203 1264//1264 1265//1265 -f 1203//1203 1265//1265 1202//1202 -f 1202//1202 1265//1265 1266//1266 -f 1202//1202 1266//1266 1201//1201 -f 1201//1201 1266//1266 1267//1267 -f 1201//1201 1267//1267 1198//1198 -f 1198//1198 1267//1267 1268//1268 -f 1198//1198 1268//1268 1199//1199 -f 1199//1199 1268//1268 1269//1269 -f 1199//1199 1269//1269 1200//1200 -f 1200//1200 1269//1269 1270//1270 -f 1200//1200 1270//1270 1197//1197 -f 1197//1197 1270//1270 1271//1271 -f 1197//1197 1271//1271 1196//1196 -f 1196//1196 1271//1271 1272//1272 -f 1196//1196 1272//1272 1195//1195 -f 1195//1195 1272//1272 1273//1273 -f 1195//1195 1273//1273 1194//1194 -f 1194//1194 1273//1273 1274//1274 -f 1194//1194 1274//1274 1191//1191 -f 1191//1191 1274//1274 1275//1275 -f 1191//1191 1275//1275 1192//1192 -f 1192//1192 1275//1275 1276//1276 -f 1192//1192 1276//1276 1193//1193 -f 1193//1193 1276//1276 1277//1277 -f 1193//1193 1277//1277 1190//1190 -f 1190//1190 1277//1277 1278//1278 -f 1190//1190 1278//1278 1189//1189 -f 1189//1189 1278//1278 1279//1279 -f 1189//1189 1279//1279 1188//1188 -f 1188//1188 1279//1279 1280//1280 -f 1188//1188 1280//1280 1187//1187 -f 1187//1187 1280//1280 1281//1281 -f 1187//1187 1281//1281 1185//1185 -f 1185//1185 1281//1281 1282//1282 -f 1185//1185 1282//1282 1186//1186 -f 1186//1186 1282//1282 1234//1234 -f 1282//1282 1283//1283 1234//1234 -f 1234//1234 1283//1283 1284//1284 -f 1234//1234 1284//1284 1235//1235 -f 1235//1235 1284//1284 1285//1285 -f 1235//1235 1285//1285 1236//1236 -f 1236//1236 1285//1285 1286//1286 -f 1236//1236 1286//1286 1237//1237 -f 1237//1237 1286//1286 1287//1287 -f 1237//1237 1287//1287 1238//1238 -f 1238//1238 1287//1287 1288//1288 -f 1238//1238 1288//1288 1239//1239 -f 1239//1239 1288//1288 1289//1289 -f 1239//1239 1289//1289 1240//1240 -f 1240//1240 1289//1289 1290//1290 -f 1240//1240 1290//1290 1241//1241 -f 1241//1241 1290//1290 1291//1291 -f 1241//1241 1291//1291 1242//1242 -f 1242//1242 1291//1291 1292//1292 -f 1242//1242 1292//1292 1243//1243 -f 1243//1243 1292//1292 1293//1293 -f 1243//1243 1293//1293 1244//1244 -f 1244//1244 1293//1293 1294//1294 -f 1244//1244 1294//1294 1245//1245 -f 1245//1245 1294//1294 1295//1295 -f 1245//1245 1295//1295 1246//1246 -f 1246//1246 1295//1295 1296//1296 -f 1246//1246 1296//1296 1247//1247 -f 1247//1247 1296//1296 1297//1297 -f 1247//1247 1297//1297 1248//1248 -f 1248//1248 1297//1297 1298//1298 -f 1248//1248 1298//1298 1249//1249 -f 1249//1249 1298//1298 1299//1299 -f 1249//1249 1299//1299 1250//1250 -f 1250//1250 1299//1299 1300//1300 -f 1250//1250 1300//1300 1251//1251 -f 1251//1251 1300//1300 1301//1301 -f 1251//1251 1301//1301 1252//1252 -f 1252//1252 1301//1301 1302//1302 -f 1252//1252 1302//1302 1253//1253 -f 1253//1253 1302//1302 1303//1303 -f 1253//1253 1303//1303 1254//1254 -f 1254//1254 1303//1303 1304//1304 -f 1254//1254 1304//1304 1255//1255 -f 1255//1255 1304//1304 1305//1305 -f 1255//1255 1305//1305 1256//1256 -f 1256//1256 1305//1305 1306//1306 -f 1256//1256 1306//1306 1257//1257 -f 1257//1257 1306//1306 1307//1307 -f 1257//1257 1307//1307 1258//1258 -f 1258//1258 1307//1307 1308//1308 -f 1258//1258 1308//1308 1259//1259 -f 1259//1259 1308//1308 1309//1309 -f 1259//1259 1309//1309 1260//1260 -f 1260//1260 1309//1309 1310//1310 -f 1260//1260 1310//1310 1261//1261 -f 1261//1261 1310//1310 1311//1311 -f 1261//1261 1311//1311 1262//1262 -f 1262//1262 1311//1311 1312//1312 -f 1262//1262 1312//1312 1263//1263 -f 1263//1263 1312//1312 1313//1313 -f 1263//1263 1313//1313 1264//1264 -f 1264//1264 1313//1313 1314//1314 -f 1264//1264 1314//1314 1265//1265 -f 1265//1265 1314//1314 1315//1315 -f 1265//1265 1315//1315 1266//1266 -f 1266//1266 1315//1315 1316//1316 -f 1266//1266 1316//1316 1267//1267 -f 1267//1267 1316//1316 1317//1317 -f 1267//1267 1317//1317 1268//1268 -f 1268//1268 1317//1317 1318//1318 -f 1268//1268 1318//1318 1269//1269 -f 1269//1269 1318//1318 1319//1319 -f 1269//1269 1319//1319 1270//1270 -f 1270//1270 1319//1319 1320//1320 -f 1270//1270 1320//1320 1271//1271 -f 1271//1271 1320//1320 1321//1321 -f 1271//1271 1321//1321 1272//1272 -f 1272//1272 1321//1321 1322//1322 -f 1272//1272 1322//1322 1273//1273 -f 1273//1273 1322//1322 1323//1323 -f 1273//1273 1323//1323 1274//1274 -f 1274//1274 1323//1323 1324//1324 -f 1274//1274 1324//1324 1275//1275 -f 1275//1275 1324//1324 1325//1325 -f 1275//1275 1325//1325 1276//1276 -f 1276//1276 1325//1325 1326//1326 -f 1276//1276 1326//1326 1277//1277 -f 1277//1277 1326//1326 1327//1327 -f 1277//1277 1327//1327 1278//1278 -f 1278//1278 1327//1327 1328//1328 -f 1278//1278 1328//1328 1279//1279 -f 1279//1279 1328//1328 1329//1329 -f 1279//1279 1329//1329 1280//1280 -f 1280//1280 1329//1329 1330//1330 -f 1280//1280 1330//1330 1281//1281 -f 1281//1281 1330//1330 1331//1331 -f 1281//1281 1331//1331 1282//1282 -f 1282//1282 1331//1331 1283//1283 -f 1331//1331 1332//1332 1283//1283 -f 1283//1283 1332//1332 1333//1333 -f 1283//1283 1333//1333 1284//1284 -f 1284//1284 1333//1333 1334//1334 -f 1284//1284 1334//1334 1285//1285 -f 1285//1285 1334//1334 1335//1335 -f 1285//1285 1335//1335 1286//1286 -f 1286//1286 1335//1335 1336//1336 -f 1286//1286 1336//1336 1287//1287 -f 1287//1287 1336//1336 1337//1337 -f 1287//1287 1337//1337 1288//1288 -f 1288//1288 1337//1337 1338//1338 -f 1288//1288 1338//1338 1289//1289 -f 1289//1289 1338//1338 1339//1339 -f 1289//1289 1339//1339 1290//1290 -f 1290//1290 1339//1339 1340//1340 -f 1290//1290 1340//1340 1291//1291 -f 1291//1291 1340//1340 1341//1341 -f 1291//1291 1341//1341 1292//1292 -f 1292//1292 1341//1341 1342//1342 -f 1292//1292 1342//1342 1293//1293 -f 1293//1293 1342//1342 1343//1343 -f 1293//1293 1343//1343 1294//1294 -f 1294//1294 1343//1343 1344//1344 -f 1294//1294 1344//1344 1295//1295 -f 1295//1295 1344//1344 1345//1345 -f 1295//1295 1345//1345 1296//1296 -f 1296//1296 1345//1345 1346//1346 -f 1296//1296 1346//1346 1297//1297 -f 1297//1297 1346//1346 1347//1347 -f 1297//1297 1347//1347 1298//1298 -f 1298//1298 1347//1347 1348//1348 -f 1298//1298 1348//1348 1299//1299 -f 1299//1299 1348//1348 1349//1349 -f 1299//1299 1349//1349 1300//1300 -f 1300//1300 1349//1349 1350//1350 -f 1300//1300 1350//1350 1301//1301 -f 1301//1301 1350//1350 1351//1351 -f 1301//1301 1351//1351 1302//1302 -f 1302//1302 1351//1351 1352//1352 -f 1302//1302 1352//1352 1303//1303 -f 1303//1303 1352//1352 1353//1353 -f 1303//1303 1353//1353 1304//1304 -f 1304//1304 1353//1353 1354//1354 -f 1304//1304 1354//1354 1305//1305 -f 1305//1305 1354//1354 1355//1355 -f 1305//1305 1355//1355 1306//1306 -f 1306//1306 1355//1355 1356//1356 -f 1306//1306 1356//1356 1307//1307 -f 1307//1307 1356//1356 1357//1357 -f 1307//1307 1357//1357 1308//1308 -f 1308//1308 1357//1357 1358//1358 -f 1308//1308 1358//1358 1309//1309 -f 1309//1309 1358//1358 1359//1359 -f 1309//1309 1359//1359 1310//1310 -f 1310//1310 1359//1359 1360//1360 -f 1310//1310 1360//1360 1311//1311 -f 1311//1311 1360//1360 1361//1361 -f 1311//1311 1361//1361 1312//1312 -f 1312//1312 1361//1361 1362//1362 -f 1312//1312 1362//1362 1313//1313 -f 1313//1313 1362//1362 1363//1363 -f 1313//1313 1363//1363 1314//1314 -f 1314//1314 1363//1363 1364//1364 -f 1314//1314 1364//1364 1315//1315 -f 1315//1315 1364//1364 1365//1365 -f 1315//1315 1365//1365 1316//1316 -f 1316//1316 1365//1365 1366//1366 -f 1316//1316 1366//1366 1317//1317 -f 1317//1317 1366//1366 1367//1367 -f 1317//1317 1367//1367 1318//1318 -f 1318//1318 1367//1367 1368//1368 -f 1318//1318 1368//1368 1319//1319 -f 1319//1319 1368//1368 1369//1369 -f 1319//1319 1369//1369 1320//1320 -f 1320//1320 1369//1369 1370//1370 -f 1320//1320 1370//1370 1321//1321 -f 1321//1321 1370//1370 1371//1371 -f 1321//1321 1371//1371 1322//1322 -f 1322//1322 1371//1371 1372//1372 -f 1322//1322 1372//1372 1323//1323 -f 1323//1323 1372//1372 1373//1373 -f 1323//1323 1373//1373 1324//1324 -f 1324//1324 1373//1373 1374//1374 -f 1324//1324 1374//1374 1325//1325 -f 1325//1325 1374//1374 1375//1375 -f 1325//1325 1375//1375 1326//1326 -f 1326//1326 1375//1375 1376//1376 -f 1326//1326 1376//1376 1327//1327 -f 1327//1327 1376//1376 1377//1377 -f 1327//1327 1377//1377 1328//1328 -f 1328//1328 1377//1377 1378//1378 -f 1328//1328 1378//1378 1329//1329 -f 1329//1329 1378//1378 1379//1379 -f 1329//1329 1379//1379 1330//1330 -f 1330//1330 1379//1379 1380//1380 -f 1330//1330 1380//1380 1331//1331 -f 1331//1331 1380//1380 1332//1332 -f 1380//1380 1381//1381 1332//1332 -f 1332//1332 1381//1381 1382//1382 -f 1332//1332 1382//1382 1333//1333 -f 1333//1333 1382//1382 1383//1383 -f 1333//1333 1383//1383 1334//1334 -f 1334//1334 1383//1383 1384//1384 -f 1334//1334 1384//1384 1335//1335 -f 1335//1335 1384//1384 1385//1385 -f 1335//1335 1385//1385 1336//1336 -f 1336//1336 1385//1385 1386//1386 -f 1336//1336 1386//1386 1337//1337 -f 1337//1337 1386//1386 1387//1387 -f 1337//1337 1387//1387 1338//1338 -f 1338//1338 1387//1387 1388//1388 -f 1338//1338 1388//1388 1339//1339 -f 1339//1339 1388//1388 1389//1389 -f 1339//1339 1389//1389 1340//1340 -f 1340//1340 1389//1389 1390//1390 -f 1340//1340 1390//1390 1341//1341 -f 1341//1341 1390//1390 1391//1391 -f 1341//1341 1391//1391 1342//1342 -f 1342//1342 1391//1391 1392//1392 -f 1342//1342 1392//1392 1343//1343 -f 1343//1343 1392//1392 1393//1393 -f 1343//1343 1393//1393 1344//1344 -f 1344//1344 1393//1393 1394//1394 -f 1344//1344 1394//1394 1345//1345 -f 1345//1345 1394//1394 1395//1395 -f 1345//1345 1395//1395 1346//1346 -f 1346//1346 1395//1395 1396//1396 -f 1346//1346 1396//1396 1347//1347 -f 1347//1347 1396//1396 1397//1397 -f 1347//1347 1397//1397 1348//1348 -f 1348//1348 1397//1397 1398//1398 -f 1348//1348 1398//1398 1349//1349 -f 1349//1349 1398//1398 1399//1399 -f 1349//1349 1399//1399 1350//1350 -f 1350//1350 1399//1399 1400//1400 -f 1350//1350 1400//1400 1351//1351 -f 1351//1351 1400//1400 1401//1401 -f 1351//1351 1401//1401 1352//1352 -f 1352//1352 1401//1401 1402//1402 -f 1352//1352 1402//1402 1353//1353 -f 1353//1353 1402//1402 1403//1403 -f 1353//1353 1403//1403 1354//1354 -f 1354//1354 1403//1403 1404//1404 -f 1354//1354 1404//1404 1355//1355 -f 1355//1355 1404//1404 1405//1405 -f 1355//1355 1405//1405 1356//1356 -f 1356//1356 1405//1405 1406//1406 -f 1356//1356 1406//1406 1357//1357 -f 1357//1357 1406//1406 1407//1407 -f 1357//1357 1407//1407 1358//1358 -f 1358//1358 1407//1407 1408//1408 -f 1358//1358 1408//1408 1359//1359 -f 1359//1359 1408//1408 1409//1409 -f 1359//1359 1409//1409 1360//1360 -f 1360//1360 1409//1409 1410//1410 -f 1360//1360 1410//1410 1361//1361 -f 1361//1361 1410//1410 1411//1411 -f 1361//1361 1411//1411 1362//1362 -f 1362//1362 1411//1411 1412//1412 -f 1362//1362 1412//1412 1363//1363 -f 1363//1363 1412//1412 1413//1413 -f 1363//1363 1413//1413 1364//1364 -f 1364//1364 1413//1413 1414//1414 -f 1364//1364 1414//1414 1365//1365 -f 1365//1365 1414//1414 1415//1415 -f 1365//1365 1415//1415 1366//1366 -f 1366//1366 1415//1415 1416//1416 -f 1366//1366 1416//1416 1367//1367 -f 1367//1367 1416//1416 1417//1417 -f 1367//1367 1417//1417 1368//1368 -f 1368//1368 1417//1417 1418//1418 -f 1368//1368 1418//1418 1369//1369 -f 1369//1369 1418//1418 1419//1419 -f 1369//1369 1419//1419 1370//1370 -f 1370//1370 1419//1419 1420//1420 -f 1370//1370 1420//1420 1371//1371 -f 1371//1371 1420//1420 1421//1421 -f 1371//1371 1421//1421 1372//1372 -f 1372//1372 1421//1421 1422//1422 -f 1372//1372 1422//1422 1373//1373 -f 1373//1373 1422//1422 1423//1423 -f 1373//1373 1423//1423 1374//1374 -f 1374//1374 1423//1423 1424//1424 -f 1374//1374 1424//1424 1375//1375 -f 1375//1375 1424//1424 1425//1425 -f 1375//1375 1425//1425 1376//1376 -f 1376//1376 1425//1425 1426//1426 -f 1376//1376 1426//1426 1377//1377 -f 1377//1377 1426//1426 1427//1427 -f 1377//1377 1427//1427 1378//1378 -f 1378//1378 1427//1427 1428//1428 -f 1378//1378 1428//1428 1379//1379 -f 1379//1379 1428//1428 1429//1429 -f 1379//1379 1429//1429 1380//1380 -f 1380//1380 1429//1429 1381//1381 -f 1429//1429 1430//1430 1381//1381 -f 1381//1381 1430//1430 1431//1431 -f 1381//1381 1431//1431 1382//1382 -f 1382//1382 1431//1431 1432//1432 -f 1382//1382 1432//1432 1383//1383 -f 1383//1383 1432//1432 1433//1433 -f 1383//1383 1433//1433 1384//1384 -f 1384//1384 1433//1433 1434//1434 -f 1384//1384 1434//1434 1385//1385 -f 1385//1385 1434//1434 1435//1435 -f 1385//1385 1435//1435 1386//1386 -f 1386//1386 1435//1435 1436//1436 -f 1386//1386 1436//1436 1387//1387 -f 1387//1387 1436//1436 1437//1437 -f 1387//1387 1437//1437 1388//1388 -f 1388//1388 1437//1437 1438//1438 -f 1388//1388 1438//1438 1389//1389 -f 1389//1389 1438//1438 1439//1439 -f 1389//1389 1439//1439 1390//1390 -f 1390//1390 1439//1439 1440//1440 -f 1390//1390 1440//1440 1391//1391 -f 1391//1391 1440//1440 1441//1441 -f 1391//1391 1441//1441 1392//1392 -f 1392//1392 1441//1441 1442//1442 -f 1392//1392 1442//1442 1393//1393 -f 1393//1393 1442//1442 1443//1443 -f 1393//1393 1443//1443 1394//1394 -f 1394//1394 1443//1443 1444//1444 -f 1394//1394 1444//1444 1395//1395 -f 1395//1395 1444//1444 1445//1445 -f 1395//1395 1445//1445 1396//1396 -f 1396//1396 1445//1445 1446//1446 -f 1396//1396 1446//1446 1397//1397 -f 1397//1397 1446//1446 1447//1447 -f 1397//1397 1447//1447 1398//1398 -f 1398//1398 1447//1447 1448//1448 -f 1398//1398 1448//1448 1399//1399 -f 1399//1399 1448//1448 1449//1449 -f 1399//1399 1449//1449 1400//1400 -f 1400//1400 1449//1449 1450//1450 -f 1400//1400 1450//1450 1401//1401 -f 1401//1401 1450//1450 1451//1451 -f 1401//1401 1451//1451 1402//1402 -f 1402//1402 1451//1451 1452//1452 -f 1402//1402 1452//1452 1403//1403 -f 1403//1403 1452//1452 1453//1453 -f 1403//1403 1453//1453 1404//1404 -f 1404//1404 1453//1453 1454//1454 -f 1404//1404 1454//1454 1405//1405 -f 1405//1405 1454//1454 1455//1455 -f 1405//1405 1455//1455 1406//1406 -f 1406//1406 1455//1455 1456//1456 -f 1406//1406 1456//1456 1407//1407 -f 1407//1407 1456//1456 1457//1457 -f 1407//1407 1457//1457 1408//1408 -f 1408//1408 1457//1457 1458//1458 -f 1408//1408 1458//1458 1409//1409 -f 1409//1409 1458//1458 1459//1459 -f 1409//1409 1459//1459 1410//1410 -f 1410//1410 1459//1459 1460//1460 -f 1410//1410 1460//1460 1411//1411 -f 1411//1411 1460//1460 1461//1461 -f 1411//1411 1461//1461 1412//1412 -f 1412//1412 1461//1461 1462//1462 -f 1412//1412 1462//1462 1413//1413 -f 1413//1413 1462//1462 1463//1463 -f 1413//1413 1463//1463 1414//1414 -f 1414//1414 1463//1463 1464//1464 -f 1414//1414 1464//1464 1415//1415 -f 1415//1415 1464//1464 1465//1465 -f 1415//1415 1465//1465 1416//1416 -f 1416//1416 1465//1465 1466//1466 -f 1416//1416 1466//1466 1417//1417 -f 1417//1417 1466//1466 1467//1467 -f 1417//1417 1467//1467 1418//1418 -f 1418//1418 1467//1467 1468//1468 -f 1418//1418 1468//1468 1419//1419 -f 1419//1419 1468//1468 1469//1469 -f 1419//1419 1469//1469 1420//1420 -f 1420//1420 1469//1469 1470//1470 -f 1420//1420 1470//1470 1421//1421 -f 1421//1421 1470//1470 1471//1471 -f 1421//1421 1471//1471 1422//1422 -f 1422//1422 1471//1471 1472//1472 -f 1422//1422 1472//1472 1423//1423 -f 1423//1423 1472//1472 1473//1473 -f 1423//1423 1473//1473 1424//1424 -f 1424//1424 1473//1473 1474//1474 -f 1424//1424 1474//1474 1425//1425 -f 1425//1425 1474//1474 1475//1475 -f 1425//1425 1475//1475 1426//1426 -f 1426//1426 1475//1475 1476//1476 -f 1426//1426 1476//1476 1427//1427 -f 1427//1427 1476//1476 1477//1477 -f 1427//1427 1477//1477 1428//1428 -f 1428//1428 1477//1477 1478//1478 -f 1428//1428 1478//1478 1429//1429 -f 1429//1429 1478//1478 1430//1430 -f 1454//1454 1479//1479 1455//1455 -f 1455//1455 1479//1479 1480//1480 -f 1455//1455 1480//1480 1456//1456 -f 1456//1456 1480//1480 1481//1481 -f 1456//1456 1481//1481 1457//1457 -f 1457//1457 1481//1481 1482//1482 -f 1457//1457 1482//1482 1458//1458 -f 1482//1482 1483//1483 1458//1458 -f 1458//1458 1483//1483 1484//1484 -f 1458//1458 1484//1484 1459//1459 -f 1459//1459 1484//1484 1485//1485 -f 1459//1459 1485//1485 1460//1460 -f 1460//1460 1485//1485 1486//1486 -f 1460//1460 1486//1486 1461//1461 -f 1461//1461 1486//1486 1487//1487 -f 1461//1461 1487//1487 1462//1462 -f 1487//1487 1488//1488 1462//1462 -f 1462//1462 1488//1488 1489//1489 -f 1462//1462 1489//1489 1463//1463 -f 1463//1463 1489//1489 1490//1490 -f 1463//1463 1490//1490 1464//1464 -f 1464//1464 1490//1490 1491//1491 -f 1464//1464 1491//1491 1465//1465 -f 1465//1465 1491//1491 1492//1492 -f 1465//1465 1492//1492 1466//1466 -f 1466//1466 1492//1492 1493//1493 -f 1466//1466 1493//1493 1467//1467 -f 1493//1493 1494//1494 1467//1467 -f 1467//1467 1494//1494 1495//1495 -f 1467//1467 1495//1495 1468//1468 -f 1468//1468 1495//1495 1496//1496 -f 1468//1468 1496//1496 1469//1469 -f 1469//1469 1496//1496 1497//1497 -f 1469//1469 1497//1497 1470//1470 -f 1470//1470 1497//1497 1498//1498 -f 1470//1470 1498//1498 1471//1471 -f 1498//1498 1499//1499 1471//1471 -f 1471//1471 1499//1499 1500//1500 -f 1471//1471 1500//1500 1472//1472 -f 1472//1472 1500//1500 1501//1501 -f 1472//1472 1501//1501 1473//1473 -f 1473//1473 1501//1501 1502//1502 -f 1473//1473 1502//1502 1474//1474 -f 1474//1474 1502//1502 1503//1503 -f 1474//1474 1503//1503 1475//1475 -f 1475//1475 1503//1503 1504//1504 -f 1475//1475 1504//1504 1476//1476 -f 1440//1440 1505//1505 1441//1441 -f 1441//1441 1505//1505 1506//1506 -f 1441//1441 1506//1506 1442//1442 -f 1442//1442 1506//1506 1507//1507 -f 1442//1442 1507//1507 1443//1443 -f 1443//1443 1507//1507 1508//1508 -f 1443//1443 1508//1508 1444//1444 -f 1444//1444 1508//1508 1509//1509 -f 1444//1444 1509//1509 1445//1445 -f 1509//1509 1510//1510 1445//1445 -f 1445//1445 1510//1510 1511//1511 -f 1445//1445 1511//1511 1446//1446 -f 1446//1446 1511//1511 1512//1512 -f 1446//1446 1512//1512 1447//1447 -f 1447//1447 1512//1512 1513//1513 -f 1447//1447 1513//1513 1448//1448 -f 1448//1448 1513//1513 1514//1514 -f 1448//1448 1514//1514 1449//1449 -f 1514//1514 1515//1515 1449//1449 -f 1449//1449 1515//1515 1516//1516 -f 1449//1449 1516//1516 1450//1450 -f 1450//1450 1516//1516 1517//1517 -f 1450//1450 1517//1517 1451//1451 -f 1451//1451 1517//1517 1518//1518 -f 1451//1451 1518//1518 1452//1452 -f 1452//1452 1518//1518 1519//1519 -f 1452//1452 1519//1519 1453//1453 -f 1453//1453 1519//1519 1520//1520 -f 1453//1453 1520//1520 1454//1454 -f 1454//1454 1520//1520 1521//1521 -f 1454//1454 1521//1521 1479//1479 -f 1504//1504 1522//1522 1476//1476 -f 1476//1476 1522//1522 1523//1523 -f 1476//1476 1523//1523 1477//1477 -f 1477//1477 1523//1523 1524//1524 -f 1477//1477 1524//1524 1478//1478 -f 1478//1478 1524//1524 1525//1525 -f 1478//1478 1525//1525 1430//1430 -f 1430//1430 1525//1525 1526//1526 -f 1430//1430 1526//1526 1431//1431 -f 1436//1436 1527//1527 1437//1437 -f 1437//1437 1527//1527 1528//1528 -f 1437//1437 1528//1528 1438//1438 -f 1438//1438 1528//1528 1529//1529 -f 1438//1438 1529//1529 1439//1439 -f 1439//1439 1529//1529 1530//1530 -f 1439//1439 1530//1530 1440//1440 -f 1440//1440 1530//1530 1531//1531 -f 1440//1440 1531//1531 1505//1505 -f 1526//1526 1532//1532 1431//1431 -f 1431//1431 1532//1532 1533//1533 -f 1431//1431 1533//1533 1432//1432 -f 1432//1432 1533//1533 1534//1534 -f 1432//1432 1534//1534 1433//1433 -f 1433//1433 1534//1534 1535//1535 -f 1433//1433 1535//1535 1434//1434 -f 1434//1434 1535//1535 1536//1536 -f 1434//1434 1536//1536 1435//1435 -f 1435//1435 1536//1536 1537//1537 -f 1435//1435 1537//1537 1436//1436 -f 1436//1436 1537//1537 1538//1538 -f 1436//1436 1538//1538 1527//1527 -f 1525//1525 1539//1539 1526//1526 -f 1526//1526 1539//1539 1540//1540 -f 1526//1526 1540//1540 1532//1532 -f 1532//1532 1540//1540 1541//1541 -f 1532//1532 1541//1541 1533//1533 -f 1533//1533 1541//1541 1542//1542 -f 1533//1533 1542//1542 1534//1534 -f 1534//1534 1542//1542 1543//1543 -f 1534//1534 1543//1543 1535//1535 -f 1535//1535 1543//1543 1544//1544 -f 1535//1535 1544//1544 1536//1536 -f 1536//1536 1544//1544 1545//1545 -f 1536//1536 1545//1545 1537//1537 -f 1537//1537 1545//1545 1546//1546 -f 1537//1537 1546//1546 1538//1538 -f 1538//1538 1546//1546 1547//1547 -f 1538//1538 1547//1547 1527//1527 -f 1527//1527 1547//1547 1548//1548 -f 1527//1527 1548//1548 1528//1528 -f 1528//1528 1548//1548 1549//1549 -f 1528//1528 1549//1549 1529//1529 -f 1529//1529 1549//1549 1550//1550 -f 1529//1529 1550//1550 1530//1530 -f 1530//1530 1550//1550 1551//1551 -f 1530//1530 1551//1551 1531//1531 -f 1531//1531 1551//1551 1552//1552 -f 1531//1531 1552//1552 1505//1505 -f 1505//1505 1552//1552 1553//1553 -f 1505//1505 1553//1553 1506//1506 -f 1506//1506 1553//1553 1554//1554 -f 1506//1506 1554//1554 1507//1507 -f 1507//1507 1554//1554 1555//1555 -f 1507//1507 1555//1555 1508//1508 -f 1508//1508 1555//1555 1556//1556 -f 1508//1508 1556//1556 1509//1509 -f 1509//1509 1556//1556 1557//1557 -f 1509//1509 1557//1557 1510//1510 -f 1510//1510 1557//1557 1558//1558 -f 1510//1510 1558//1558 1511//1511 -f 1511//1511 1558//1558 1559//1559 -f 1511//1511 1559//1559 1512//1512 -f 1512//1512 1559//1559 1560//1560 -f 1512//1512 1560//1560 1513//1513 -f 1513//1513 1560//1560 1561//1561 -f 1513//1513 1561//1561 1514//1514 -f 1514//1514 1561//1561 1562//1562 -f 1514//1514 1562//1562 1515//1515 -f 1515//1515 1562//1562 1563//1563 -f 1515//1515 1563//1563 1516//1516 -f 1516//1516 1563//1563 1564//1564 -f 1516//1516 1564//1564 1517//1517 -f 1517//1517 1564//1564 1565//1565 -f 1517//1517 1565//1565 1518//1518 -f 1518//1518 1565//1565 1566//1566 -f 1518//1518 1566//1566 1519//1519 -f 1519//1519 1566//1566 1567//1567 -f 1519//1519 1567//1567 1520//1520 -f 1520//1520 1567//1567 1568//1568 -f 1520//1520 1568//1568 1521//1521 -f 1521//1521 1568//1568 1569//1569 -f 1521//1521 1569//1569 1479//1479 -f 1479//1479 1569//1569 1570//1570 -f 1479//1479 1570//1570 1480//1480 -f 1480//1480 1570//1570 1571//1571 -f 1480//1480 1571//1571 1481//1481 -f 1481//1481 1571//1571 1572//1572 -f 1481//1481 1572//1572 1482//1482 -f 1482//1482 1572//1572 1573//1573 -f 1482//1482 1573//1573 1483//1483 -f 1483//1483 1573//1573 1574//1574 -f 1483//1483 1574//1574 1484//1484 -f 1484//1484 1574//1574 1575//1575 -f 1484//1484 1575//1575 1485//1485 -f 1485//1485 1575//1575 1576//1576 -f 1485//1485 1576//1576 1486//1486 -f 1486//1486 1576//1576 1577//1577 -f 1486//1486 1577//1577 1487//1487 -f 1487//1487 1577//1577 1578//1578 -f 1487//1487 1578//1578 1488//1488 -f 1488//1488 1578//1578 1579//1579 -f 1488//1488 1579//1579 1489//1489 -f 1489//1489 1579//1579 1580//1580 -f 1489//1489 1580//1580 1490//1490 -f 1490//1490 1580//1580 1581//1581 -f 1490//1490 1581//1581 1491//1491 -f 1491//1491 1581//1581 1582//1582 -f 1491//1491 1582//1582 1492//1492 -f 1492//1492 1582//1582 1583//1583 -f 1492//1492 1583//1583 1493//1493 -f 1493//1493 1583//1583 1584//1584 -f 1493//1493 1584//1584 1494//1494 -f 1494//1494 1584//1584 1585//1585 -f 1494//1494 1585//1585 1495//1495 -f 1495//1495 1585//1585 1586//1586 -f 1495//1495 1586//1586 1496//1496 -f 1496//1496 1586//1586 1587//1587 -f 1496//1496 1587//1587 1497//1497 -f 1497//1497 1587//1587 1588//1588 -f 1497//1497 1588//1588 1498//1498 -f 1498//1498 1588//1588 1589//1589 -f 1498//1498 1589//1589 1499//1499 -f 1499//1499 1589//1589 1590//1590 -f 1499//1499 1590//1590 1500//1500 -f 1500//1500 1590//1590 1591//1591 -f 1500//1500 1591//1591 1501//1501 -f 1501//1501 1591//1591 1592//1592 -f 1501//1501 1592//1592 1502//1502 -f 1502//1502 1592//1592 1593//1593 -f 1502//1502 1593//1593 1503//1503 -f 1503//1503 1593//1593 1594//1594 -f 1503//1503 1594//1594 1504//1504 -f 1504//1504 1594//1594 1595//1595 -f 1504//1504 1595//1595 1522//1522 -f 1522//1522 1595//1595 1596//1596 -f 1522//1522 1596//1596 1523//1523 -f 1523//1523 1596//1596 1597//1597 -f 1523//1523 1597//1597 1524//1524 -f 1524//1524 1597//1597 1598//1598 -f 1524//1524 1598//1598 1525//1525 -f 1525//1525 1598//1598 1539//1539 -f 1598//1598 1599//1599 1539//1539 -f 1539//1539 1599//1599 1600//1600 -f 1539//1539 1600//1600 1540//1540 -f 1540//1540 1600//1600 1601//1601 -f 1540//1540 1601//1601 1541//1541 -f 1541//1541 1601//1601 1602//1602 -f 1541//1541 1602//1602 1542//1542 -f 1542//1542 1602//1602 1603//1603 -f 1542//1542 1603//1603 1543//1543 -f 1543//1543 1603//1603 1604//1604 -f 1543//1543 1604//1604 1544//1544 -f 1544//1544 1604//1604 1605//1605 -f 1544//1544 1605//1605 1545//1545 -f 1545//1545 1605//1605 1606//1606 -f 1545//1545 1606//1606 1546//1546 -f 1546//1546 1606//1606 1607//1607 -f 1546//1546 1607//1607 1547//1547 -f 1547//1547 1607//1607 1608//1608 -f 1547//1547 1608//1608 1548//1548 -f 1548//1548 1608//1608 1609//1609 -f 1548//1548 1609//1609 1549//1549 -f 1549//1549 1609//1609 1610//1610 -f 1549//1549 1610//1610 1550//1550 -f 1550//1550 1610//1610 1611//1611 -f 1550//1550 1611//1611 1551//1551 -f 1551//1551 1611//1611 1612//1612 -f 1551//1551 1612//1612 1552//1552 -f 1552//1552 1612//1612 1613//1613 -f 1552//1552 1613//1613 1553//1553 -f 1553//1553 1613//1613 1614//1614 -f 1553//1553 1614//1614 1554//1554 -f 1554//1554 1614//1614 1615//1615 -f 1554//1554 1615//1615 1555//1555 -f 1555//1555 1615//1615 1616//1616 -f 1555//1555 1616//1616 1556//1556 -f 1556//1556 1616//1616 1617//1617 -f 1556//1556 1617//1617 1557//1557 -f 1557//1557 1617//1617 1618//1618 -f 1557//1557 1618//1618 1558//1558 -f 1558//1558 1618//1618 1619//1619 -f 1558//1558 1619//1619 1559//1559 -f 1559//1559 1619//1619 1620//1620 -f 1559//1559 1620//1620 1560//1560 -f 1560//1560 1620//1620 1621//1621 -f 1560//1560 1621//1621 1561//1561 -f 1561//1561 1621//1621 1622//1622 -f 1561//1561 1622//1622 1562//1562 -f 1562//1562 1622//1622 1623//1623 -f 1562//1562 1623//1623 1563//1563 -f 1563//1563 1623//1623 1624//1624 -f 1563//1563 1624//1624 1564//1564 -f 1564//1564 1624//1624 1625//1625 -f 1564//1564 1625//1625 1565//1565 -f 1565//1565 1625//1625 1626//1626 -f 1565//1565 1626//1626 1566//1566 -f 1566//1566 1626//1626 1627//1627 -f 1566//1566 1627//1627 1567//1567 -f 1567//1567 1627//1627 1628//1628 -f 1567//1567 1628//1628 1568//1568 -f 1568//1568 1628//1628 1629//1629 -f 1568//1568 1629//1629 1569//1569 -f 1569//1569 1629//1629 1630//1630 -f 1569//1569 1630//1630 1570//1570 -f 1570//1570 1630//1630 1631//1631 -f 1570//1570 1631//1631 1571//1571 -f 1571//1571 1631//1631 1632//1632 -f 1571//1571 1632//1632 1572//1572 -f 1572//1572 1632//1632 1633//1633 -f 1572//1572 1633//1633 1573//1573 -f 1573//1573 1633//1633 1634//1634 -f 1573//1573 1634//1634 1574//1574 -f 1574//1574 1634//1634 1635//1635 -f 1574//1574 1635//1635 1575//1575 -f 1575//1575 1635//1635 1636//1636 -f 1575//1575 1636//1636 1576//1576 -f 1576//1576 1636//1636 1637//1637 -f 1576//1576 1637//1637 1577//1577 -f 1577//1577 1637//1637 1638//1638 -f 1577//1577 1638//1638 1578//1578 -f 1578//1578 1638//1638 1639//1639 -f 1578//1578 1639//1639 1579//1579 -f 1579//1579 1639//1639 1640//1640 -f 1579//1579 1640//1640 1580//1580 -f 1580//1580 1640//1640 1641//1641 -f 1580//1580 1641//1641 1581//1581 -f 1581//1581 1641//1641 1642//1642 -f 1581//1581 1642//1642 1582//1582 -f 1582//1582 1642//1642 1643//1643 -f 1582//1582 1643//1643 1583//1583 -f 1583//1583 1643//1643 1644//1644 -f 1583//1583 1644//1644 1584//1584 -f 1584//1584 1644//1644 1645//1645 -f 1584//1584 1645//1645 1585//1585 -f 1585//1585 1645//1645 1646//1646 -f 1585//1585 1646//1646 1586//1586 -f 1586//1586 1646//1646 1647//1647 -f 1586//1586 1647//1647 1587//1587 -f 1587//1587 1647//1647 1648//1648 -f 1587//1587 1648//1648 1588//1588 -f 1588//1588 1648//1648 1649//1649 -f 1588//1588 1649//1649 1589//1589 -f 1589//1589 1649//1649 1650//1650 -f 1589//1589 1650//1650 1590//1590 -f 1590//1590 1650//1650 1651//1651 -f 1590//1590 1651//1651 1591//1591 -f 1591//1591 1651//1651 1652//1652 -f 1591//1591 1652//1652 1592//1592 -f 1592//1592 1652//1652 1653//1653 -f 1592//1592 1653//1653 1593//1593 -f 1593//1593 1653//1653 1654//1654 -f 1593//1593 1654//1654 1594//1594 -f 1594//1594 1654//1654 1655//1655 -f 1594//1594 1655//1655 1595//1595 -f 1595//1595 1655//1655 1656//1656 -f 1595//1595 1656//1656 1596//1596 -f 1596//1596 1656//1656 1657//1657 -f 1596//1596 1657//1657 1597//1597 -f 1597//1597 1657//1657 1658//1658 -f 1597//1597 1658//1658 1598//1598 -f 1598//1598 1658//1658 1599//1599 -f 1659//1659 1660//1660 1629//1629 -f 1629//1629 1660//1660 1630//1630 -f 1630//1630 1660//1660 1661//1661 -f 1630//1630 1661//1661 1631//1631 -f 1631//1631 1661//1661 1662//1662 -f 1631//1631 1662//1662 1632//1632 -f 1632//1632 1662//1662 1663//1663 -f 1632//1632 1663//1663 1633//1633 -f 1633//1633 1663//1663 1664//1664 -f 1633//1633 1664//1664 1634//1634 -f 1634//1634 1664//1664 1665//1665 -f 1634//1634 1665//1665 1635//1635 -f 1635//1635 1665//1665 1666//1666 -f 1635//1635 1666//1666 1636//1636 -f 1666//1666 1667//1667 1636//1636 -f 1636//1636 1667//1667 1668//1668 -f 1636//1636 1668//1668 1637//1637 -f 1637//1637 1668//1668 1669//1669 -f 1637//1637 1669//1669 1638//1638 -f 1638//1638 1669//1669 1639//1639 -f 1639//1639 1669//1669 1670//1670 -f 1639//1639 1670//1670 1640//1640 -f 1640//1640 1670//1670 1671//1671 -f 1640//1640 1671//1671 1641//1641 -f 1641//1641 1671//1671 1672//1672 -f 1641//1641 1672//1672 1642//1642 -f 1642//1642 1672//1672 1673//1673 -f 1642//1642 1673//1673 1643//1643 -f 1643//1643 1673//1673 1674//1674 -f 1643//1643 1674//1674 1644//1644 -f 1644//1644 1674//1674 1675//1675 -f 1644//1644 1675//1675 1645//1645 -f 1645//1645 1675//1675 1676//1676 -f 1645//1645 1676//1676 1646//1646 -f 1676//1676 1677//1677 1646//1646 -f 1646//1646 1677//1677 1678//1678 -f 1646//1646 1678//1678 1647//1647 -f 1647//1647 1678//1678 1679//1679 -f 1647//1647 1679//1679 1648//1648 -f 1648//1648 1679//1679 1649//1649 -f 1649//1649 1679//1679 1680//1680 -f 1649//1649 1680//1680 1650//1650 -f 1650//1650 1680//1680 1681//1681 -f 1650//1650 1681//1681 1651//1651 -f 1651//1651 1681//1681 1682//1682 -f 1651//1651 1682//1682 1652//1652 -f 1652//1652 1682//1682 1683//1683 -f 1652//1652 1683//1683 1653//1653 -f 1653//1653 1683//1683 1684//1684 -f 1653//1653 1684//1684 1654//1654 -f 1654//1654 1684//1684 1685//1685 -f 1654//1654 1685//1685 1655//1655 -f 1655//1655 1685//1685 1686//1686 -f 1655//1655 1686//1686 1656//1656 -f 1686//1686 1687//1687 1656//1656 -f 1656//1656 1687//1687 1688//1688 -f 1656//1656 1688//1688 1657//1657 -f 1657//1657 1688//1688 1689//1689 -f 1657//1657 1689//1689 1658//1658 -f 1658//1658 1689//1689 1599//1599 -f 1599//1599 1689//1689 1690//1690 -f 1599//1599 1690//1690 1600//1600 -f 1600//1600 1690//1690 1691//1691 -f 1600//1600 1691//1691 1601//1601 -f 1601//1601 1691//1691 1692//1692 -f 1601//1601 1692//1692 1602//1602 -f 1602//1602 1692//1692 1693//1693 -f 1602//1602 1693//1693 1603//1603 -f 1603//1603 1693//1693 1694//1694 -f 1603//1603 1694//1694 1604//1604 -f 1604//1604 1694//1694 1695//1695 -f 1604//1604 1695//1695 1605//1605 -f 1605//1605 1695//1695 1696//1696 -f 1605//1605 1696//1696 1606//1606 -f 1696//1696 1697//1697 1606//1606 -f 1606//1606 1697//1697 1698//1698 -f 1606//1606 1698//1698 1607//1607 -f 1607//1607 1698//1698 1699//1699 -f 1607//1607 1699//1699 1608//1608 -f 1608//1608 1699//1699 1609//1609 -f 1609//1609 1699//1699 1700//1700 -f 1609//1609 1700//1700 1610//1610 -f 1610//1610 1700//1700 1701//1701 -f 1610//1610 1701//1701 1611//1611 -f 1611//1611 1701//1701 1702//1702 -f 1611//1611 1702//1702 1612//1612 -f 1612//1612 1702//1702 1703//1703 -f 1612//1612 1703//1703 1613//1613 -f 1613//1613 1703//1703 1704//1704 -f 1613//1613 1704//1704 1614//1614 -f 1614//1614 1704//1704 1705//1705 -f 1614//1614 1705//1705 1615//1615 -f 1615//1615 1705//1705 1706//1706 -f 1615//1615 1706//1706 1616//1616 -f 1706//1706 1707//1707 1616//1616 -f 1616//1616 1707//1707 1708//1708 -f 1616//1616 1708//1708 1617//1617 -f 1617//1617 1708//1708 1709//1709 -f 1617//1617 1709//1709 1618//1618 -f 1618//1618 1709//1709 1619//1619 -f 1619//1619 1709//1709 1710//1710 -f 1619//1619 1710//1710 1620//1620 -f 1620//1620 1710//1710 1711//1711 -f 1620//1620 1711//1711 1621//1621 -f 1621//1621 1711//1711 1712//1712 -f 1621//1621 1712//1712 1622//1622 -f 1622//1622 1712//1712 1713//1713 -f 1622//1622 1713//1713 1623//1623 -f 1623//1623 1713//1713 1714//1714 -f 1623//1623 1714//1714 1624//1624 -f 1624//1624 1714//1714 1715//1715 -f 1624//1624 1715//1715 1625//1625 -f 1625//1625 1715//1715 1716//1716 -f 1625//1625 1716//1716 1626//1626 -f 1716//1716 1717//1717 1626//1626 -f 1626//1626 1717//1717 1718//1718 -f 1626//1626 1718//1718 1627//1627 -f 1627//1627 1718//1718 1659//1659 -f 1627//1627 1659//1659 1628//1628 -f 1628//1628 1659//1659 1629//1629 -f 1719//1719 1720//1720 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1725//1725 1726//1726 1727//1727 -f 1728//1728 1729//1729 1730//1730 -f 1731//1731 1732//1732 1733//1733 -f 1734//1734 1735//1735 1736//1736 -f 1737//1737 1738//1738 1739//1739 -f 1740//1740 1741//1741 1742//1742 -f 1693//1693 1692//1692 1743//1743 -f 1695//1695 1694//1694 1744//1744 -f 1701//1701 1700//1700 1745//1745 -f 1713//1713 1712//1712 1746//1746 -f 1715//1715 1714//1714 1747//1747 -f 1661//1661 1660//1660 1748//1748 -f 1673//1673 1672//1672 1749//1749 -f 1675//1675 1674//1674 1750//1750 -f 1681//1681 1680//1680 1751//1751 -f 1752//1752 1689//1689 1688//1688 -f 1752//1752 1688//1688 1753//1753 -f 1753//1753 1688//1688 1687//1687 -f 1753//1753 1687//1687 1754//1754 -f 1684//1684 1755//1755 1685//1685 -f 1685//1685 1755//1755 1754//1754 -f 1685//1685 1754//1754 1686//1686 -f 1686//1686 1754//1754 1687//1687 -f 1684//1684 1683//1683 1756//1756 -f 1681//1681 1751//1751 1682//1682 -f 1741//1741 1678//1678 1677//1677 -f 1741//1741 1677//1677 1742//1742 -f 1742//1742 1677//1677 1676//1676 -f 1742//1742 1676//1676 1675//1675 -f 1673//1673 1749//1749 1674//1674 -f 1672//1672 1671//1671 1757//1757 -f 1757//1757 1671//1671 1670//1670 -f 1757//1757 1670//1670 1669//1669 -f 1664//1664 1739//1739 1665//1665 -f 1665//1665 1739//1739 1738//1738 -f 1665//1665 1738//1738 1666//1666 -f 1666//1666 1738//1738 1667//1667 -f 1664//1664 1663//1663 1758//1758 -f 1661//1661 1748//1748 1662//1662 -f 1735//1735 1718//1718 1717//1717 -f 1735//1735 1717//1717 1736//1736 -f 1736//1736 1717//1717 1716//1716 -f 1736//1736 1716//1716 1715//1715 -f 1713//1713 1746//1746 1714//1714 -f 1712//1712 1711//1711 1759//1759 -f 1759//1759 1711//1711 1710//1710 -f 1759//1759 1710//1710 1709//1709 -f 1704//1704 1733//1733 1705//1705 -f 1705//1705 1733//1733 1732//1732 -f 1705//1705 1732//1732 1706//1706 -f 1706//1706 1732//1732 1707//1707 -f 1704//1704 1703//1703 1760//1760 -f 1701//1701 1745//1745 1702//1702 -f 1729//1729 1698//1698 1697//1697 -f 1729//1729 1697//1697 1730//1730 -f 1730//1730 1697//1697 1696//1696 -f 1730//1730 1696//1696 1695//1695 -f 1693//1693 1743//1743 1694//1694 -f 1692//1692 1691//1691 1761//1761 -f 1761//1761 1691//1691 1690//1690 -f 1761//1761 1690//1690 1689//1689 -f 1679//1679 1678//1678 1762//1762 -f 1762//1762 1678//1678 1741//1741 -f 1762//1762 1741//1741 1763//1763 -f 1763//1763 1741//1741 1740//1740 -f 1763//1763 1740//1740 1764//1764 -f 1668//1668 1667//1667 1765//1765 -f 1765//1765 1667//1667 1738//1738 -f 1765//1765 1738//1738 1766//1766 -f 1766//1766 1738//1738 1737//1737 -f 1766//1766 1737//1737 1767//1767 -f 1659//1659 1718//1718 1768//1768 -f 1768//1768 1718//1718 1735//1735 -f 1768//1768 1735//1735 1769//1769 -f 1769//1769 1735//1735 1734//1734 -f 1769//1769 1734//1734 1770//1770 -f 1708//1708 1707//1707 1771//1771 -f 1771//1771 1707//1707 1732//1732 -f 1771//1771 1732//1732 1772//1772 -f 1772//1772 1732//1732 1731//1731 -f 1772//1772 1731//1731 1773//1773 -f 1699//1699 1698//1698 1774//1774 -f 1774//1774 1698//1698 1729//1729 -f 1774//1774 1729//1729 1775//1775 -f 1775//1775 1729//1729 1728//1728 -f 1775//1775 1728//1728 1776//1776 -f 1755//1755 1777//1777 1754//1754 -f 1754//1754 1777//1777 1778//1778 -f 1754//1754 1778//1778 1753//1753 -f 1753//1753 1778//1778 1779//1779 -f 1753//1753 1779//1779 1752//1752 -f 1752//1752 1779//1779 1780//1780 -f 1781//1781 1782//1782 1783//1783 -f 1784//1784 1785//1785 1786//1786 -f 1787//1787 1785//1785 1788//1788 -f 1788//1788 1785//1785 1784//1784 -f 1788//1788 1784//1784 1789//1789 -f 1669//1669 1668//1668 1789//1789 -f 1789//1789 1668//1668 1765//1765 -f 1789//1789 1765//1765 1788//1788 -f 1788//1788 1765//1765 1766//1766 -f 1788//1788 1766//1766 1787//1787 -f 1787//1787 1766//1766 1767//1767 -f 1790//1790 1791//1791 1792//1792 -f 1793//1793 1794//1794 1795//1795 -f 1796//1796 1794//1794 1797//1797 -f 1797//1797 1794//1794 1793//1793 -f 1797//1797 1793//1793 1798//1798 -f 1709//1709 1708//1708 1798//1798 -f 1798//1798 1708//1708 1771//1771 -f 1798//1798 1771//1771 1797//1797 -f 1797//1797 1771//1771 1772//1772 -f 1797//1797 1772//1772 1796//1796 -f 1796//1796 1772//1772 1773//1773 -f 1799//1799 1800//1800 1801//1801 -f 1777//1777 1802//1802 1778//1778 -f 1778//1778 1802//1802 1803//1803 -f 1778//1778 1803//1803 1779//1779 -f 1779//1779 1803//1803 1804//1804 -f 1779//1779 1804//1804 1780//1780 -f 1780//1780 1804//1804 1805//1805 -f 1684//1684 1756//1756 1755//1755 -f 1755//1755 1756//1756 1806//1806 -f 1755//1755 1806//1806 1777//1777 -f 1777//1777 1806//1806 1727//1727 -f 1777//1777 1727//1727 1802//1802 -f 1802//1802 1727//1727 1726//1726 -f 1802//1802 1726//1726 1807//1807 -f 1756//1756 1781//1781 1806//1806 -f 1806//1806 1781//1781 1783//1783 -f 1806//1806 1783//1783 1727//1727 -f 1727//1727 1783//1783 1808//1808 -f 1727//1727 1808//1808 1725//1725 -f 1809//1809 1810//1810 1811//1811 -f 1811//1811 1810//1810 1782//1782 -f 1811//1811 1782//1782 1812//1812 -f 1812//1812 1782//1782 1781//1781 -f 1812//1812 1781//1781 1751//1751 -f 1751//1751 1781//1781 1756//1756 -f 1751//1751 1756//1756 1682//1682 -f 1682//1682 1756//1756 1683//1683 -f 1810//1810 1813//1813 1782//1782 -f 1782//1782 1813//1813 1814//1814 -f 1782//1782 1814//1814 1783//1783 -f 1783//1783 1814//1814 1815//1815 -f 1783//1783 1815//1815 1808//1808 -f 1680//1680 1679//1679 1751//1751 -f 1751//1751 1679//1679 1762//1762 -f 1751//1751 1762//1762 1812//1812 -f 1812//1812 1762//1762 1763//1763 -f 1812//1812 1763//1763 1811//1811 -f 1811//1811 1763//1763 1764//1764 -f 1811//1811 1764//1764 1809//1809 -f 1809//1809 1764//1764 1816//1816 -f 1817//1817 1818//1818 1819//1819 -f 1675//1675 1750//1750 1742//1742 -f 1742//1742 1750//1750 1820//1820 -f 1742//1742 1820//1820 1740//1740 -f 1740//1740 1820//1820 1817//1817 -f 1740//1740 1817//1817 1764//1764 -f 1764//1764 1817//1817 1819//1819 -f 1764//1764 1819//1819 1816//1816 -f 1821//1821 1822//1822 1823//1823 -f 1674//1674 1749//1749 1750//1750 -f 1750//1750 1749//1749 1824//1824 -f 1750//1750 1824//1824 1820//1820 -f 1820//1820 1824//1824 1821//1821 -f 1820//1820 1821//1821 1817//1817 -f 1817//1817 1821//1821 1823//1823 -f 1817//1817 1823//1823 1818//1818 -f 1825//1825 1826//1826 1827//1827 -f 1672//1672 1757//1757 1749//1749 -f 1749//1749 1757//1757 1828//1828 -f 1749//1749 1828//1828 1824//1824 -f 1824//1824 1828//1828 1825//1825 -f 1824//1824 1825//1825 1821//1821 -f 1821//1821 1825//1825 1827//1827 -f 1821//1821 1827//1827 1822//1822 -f 1669//1669 1789//1789 1757//1757 -f 1757//1757 1789//1789 1784//1784 -f 1757//1757 1784//1784 1828//1828 -f 1828//1828 1784//1784 1786//1786 -f 1828//1828 1786//1786 1825//1825 -f 1825//1825 1786//1786 1829//1829 -f 1825//1825 1829//1829 1826//1826 -f 1830//1830 1831//1831 1767//1767 -f 1767//1767 1831//1831 1832//1832 -f 1767//1767 1832//1832 1787//1787 -f 1787//1787 1832//1832 1833//1833 -f 1787//1787 1833//1833 1785//1785 -f 1785//1785 1833//1833 1834//1834 -f 1785//1785 1834//1834 1786//1786 -f 1786//1786 1834//1834 1835//1835 -f 1786//1786 1835//1835 1829//1829 -f 1664//1664 1758//1758 1739//1739 -f 1739//1739 1758//1758 1836//1836 -f 1739//1739 1836//1836 1737//1737 -f 1737//1737 1836//1836 1724//1724 -f 1737//1737 1724//1724 1767//1767 -f 1767//1767 1724//1724 1723//1723 -f 1767//1767 1723//1723 1830//1830 -f 1758//1758 1790//1790 1836//1836 -f 1836//1836 1790//1790 1792//1792 -f 1836//1836 1792//1792 1724//1724 -f 1724//1724 1792//1792 1837//1837 -f 1724//1724 1837//1837 1722//1722 -f 1838//1838 1839//1839 1840//1840 -f 1840//1840 1839//1839 1791//1791 -f 1840//1840 1791//1791 1841//1841 -f 1841//1841 1791//1791 1790//1790 -f 1841//1841 1790//1790 1748//1748 -f 1748//1748 1790//1790 1758//1758 -f 1748//1748 1758//1758 1662//1662 -f 1662//1662 1758//1758 1663//1663 -f 1839//1839 1842//1842 1791//1791 -f 1791//1791 1842//1842 1843//1843 -f 1791//1791 1843//1843 1792//1792 -f 1792//1792 1843//1843 1844//1844 -f 1792//1792 1844//1844 1837//1837 -f 1660//1660 1659//1659 1748//1748 -f 1748//1748 1659//1659 1768//1768 -f 1748//1748 1768//1768 1841//1841 -f 1841//1841 1768//1768 1769//1769 -f 1841//1841 1769//1769 1840//1840 -f 1840//1840 1769//1769 1770//1770 -f 1840//1840 1770//1770 1838//1838 -f 1838//1838 1770//1770 1845//1845 -f 1846//1846 1847//1847 1848//1848 -f 1715//1715 1747//1747 1736//1736 -f 1736//1736 1747//1747 1849//1849 -f 1736//1736 1849//1849 1734//1734 -f 1734//1734 1849//1849 1846//1846 -f 1734//1734 1846//1846 1770//1770 -f 1770//1770 1846//1846 1848//1848 -f 1770//1770 1848//1848 1845//1845 -f 1850//1850 1851//1851 1852//1852 -f 1714//1714 1746//1746 1747//1747 -f 1747//1747 1746//1746 1853//1853 -f 1747//1747 1853//1853 1849//1849 -f 1849//1849 1853//1853 1850//1850 -f 1849//1849 1850//1850 1846//1846 -f 1846//1846 1850//1850 1852//1852 -f 1846//1846 1852//1852 1847//1847 -f 1854//1854 1855//1855 1856//1856 -f 1712//1712 1759//1759 1746//1746 -f 1746//1746 1759//1759 1857//1857 -f 1746//1746 1857//1857 1853//1853 -f 1853//1853 1857//1857 1854//1854 -f 1853//1853 1854//1854 1850//1850 -f 1850//1850 1854//1854 1856//1856 -f 1850//1850 1856//1856 1851//1851 -f 1709//1709 1798//1798 1759//1759 -f 1759//1759 1798//1798 1793//1793 -f 1759//1759 1793//1793 1857//1857 -f 1857//1857 1793//1793 1795//1795 -f 1857//1857 1795//1795 1854//1854 -f 1854//1854 1795//1795 1858//1858 -f 1854//1854 1858//1858 1855//1855 -f 1859//1859 1860//1860 1773//1773 -f 1773//1773 1860//1860 1861//1861 -f 1773//1773 1861//1861 1796//1796 -f 1796//1796 1861//1861 1862//1862 -f 1796//1796 1862//1862 1794//1794 -f 1794//1794 1862//1862 1863//1863 -f 1794//1794 1863//1863 1795//1795 -f 1795//1795 1863//1863 1864//1864 -f 1795//1795 1864//1864 1858//1858 -f 1704//1704 1760//1760 1733//1733 -f 1733//1733 1760//1760 1865//1865 -f 1733//1733 1865//1865 1731//1731 -f 1731//1731 1865//1865 1721//1721 -f 1731//1731 1721//1721 1773//1773 -f 1773//1773 1721//1721 1720//1720 -f 1773//1773 1720//1720 1859//1859 -f 1760//1760 1799//1799 1865//1865 -f 1865//1865 1799//1799 1801//1801 -f 1865//1865 1801//1801 1721//1721 -f 1721//1721 1801//1801 1866//1866 -f 1721//1721 1866//1866 1719//1719 -f 1867//1867 1868//1868 1869//1869 -f 1869//1869 1868//1868 1800//1800 -f 1869//1869 1800//1800 1870//1870 -f 1870//1870 1800//1800 1799//1799 -f 1870//1870 1799//1799 1745//1745 -f 1745//1745 1799//1799 1760//1760 -f 1745//1745 1760//1760 1702//1702 -f 1702//1702 1760//1760 1703//1703 -f 1868//1868 1871//1871 1800//1800 -f 1800//1800 1871//1871 1872//1872 -f 1800//1800 1872//1872 1801//1801 -f 1801//1801 1872//1872 1873//1873 -f 1801//1801 1873//1873 1866//1866 -f 1700//1700 1699//1699 1745//1745 -f 1745//1745 1699//1699 1774//1774 -f 1745//1745 1774//1774 1870//1870 -f 1870//1870 1774//1774 1775//1775 -f 1870//1870 1775//1775 1869//1869 -f 1869//1869 1775//1775 1776//1776 -f 1869//1869 1776//1776 1867//1867 -f 1867//1867 1776//1776 1874//1874 -f 1875//1875 1876//1876 1877//1877 -f 1695//1695 1744//1744 1730//1730 -f 1730//1730 1744//1744 1878//1878 -f 1730//1730 1878//1878 1728//1728 -f 1728//1728 1878//1878 1875//1875 -f 1728//1728 1875//1875 1776//1776 -f 1776//1776 1875//1875 1877//1877 -f 1776//1776 1877//1877 1874//1874 -f 1879//1879 1880//1880 1881//1881 -f 1694//1694 1743//1743 1744//1744 -f 1744//1744 1743//1743 1882//1882 -f 1744//1744 1882//1882 1878//1878 -f 1878//1878 1882//1882 1879//1879 -f 1878//1878 1879//1879 1875//1875 -f 1875//1875 1879//1879 1881//1881 -f 1875//1875 1881//1881 1876//1876 -f 1883//1883 1884//1884 1885//1885 -f 1692//1692 1761//1761 1743//1743 -f 1743//1743 1761//1761 1886//1886 -f 1743//1743 1886//1886 1882//1882 -f 1882//1882 1886//1886 1883//1883 -f 1882//1882 1883//1883 1879//1879 -f 1879//1879 1883//1883 1885//1885 -f 1879//1879 1885//1885 1880//1880 -f 1689//1689 1752//1752 1761//1761 -f 1761//1761 1752//1752 1780//1780 -f 1761//1761 1780//1780 1886//1886 -f 1886//1886 1780//1780 1805//1805 -f 1886//1886 1805//1805 1883//1883 -f 1883//1883 1805//1805 1887//1887 -f 1883//1883 1887//1887 1884//1884 -f 1807//1807 1888//1888 1802//1802 -f 1802//1802 1888//1888 1889//1889 -f 1802//1802 1889//1889 1803//1803 -f 1803//1803 1889//1889 1890//1890 -f 1803//1803 1890//1890 1804//1804 -f 1804//1804 1890//1890 1891//1891 -f 1804//1804 1891//1891 1805//1805 -f 1805//1805 1891//1891 1892//1892 -f 1805//1805 1892//1892 1887//1887 -f 1810//1810 1893//1893 1813//1813 -f 1813//1813 1893//1893 1894//1894 -f 1813//1813 1894//1894 1814//1814 -f 1814//1814 1894//1894 1895//1895 -f 1814//1814 1895//1895 1815//1815 -f 1815//1815 1895//1895 1896//1896 -f 1815//1815 1896//1896 1808//1808 -f 1827//1827 1897//1897 1822//1822 -f 1822//1822 1897//1897 1898//1898 -f 1822//1822 1898//1898 1823//1823 -f 1823//1823 1898//1898 1899//1899 -f 1823//1823 1899//1899 1818//1818 -f 1818//1818 1899//1899 1900//1900 -f 1818//1818 1900//1900 1819//1819 -f 1819//1819 1900//1900 1901//1901 -f 1819//1819 1901//1901 1816//1816 -f 1816//1816 1901//1901 1902//1902 -f 1816//1816 1902//1902 1809//1809 -f 1809//1809 1902//1902 1903//1903 -f 1809//1809 1903//1903 1810//1810 -f 1810//1810 1903//1903 1904//1904 -f 1810//1810 1904//1904 1893//1893 -f 1832//1832 1905//1905 1833//1833 -f 1833//1833 1905//1905 1906//1906 -f 1833//1833 1906//1906 1834//1834 -f 1834//1834 1906//1906 1907//1907 -f 1834//1834 1907//1907 1835//1835 -f 1835//1835 1907//1907 1908//1908 -f 1835//1835 1908//1908 1829//1829 -f 1829//1829 1908//1908 1909//1909 -f 1829//1829 1909//1909 1826//1826 -f 1826//1826 1909//1909 1910//1910 -f 1826//1826 1910//1910 1827//1827 -f 1827//1827 1910//1910 1911//1911 -f 1827//1827 1911//1911 1897//1897 -f 1831//1831 1912//1912 1832//1832 -f 1832//1832 1912//1912 1913//1913 -f 1832//1832 1913//1913 1905//1905 -f 1843//1843 1914//1914 1844//1844 -f 1844//1844 1914//1914 1915//1915 -f 1844//1844 1915//1915 1837//1837 -f 1837//1837 1915//1915 1916//1916 -f 1837//1837 1916//1916 1722//1722 -f 1722//1722 1916//1916 1917//1917 -f 1722//1722 1917//1917 1723//1723 -f 1723//1723 1917//1917 1918//1918 -f 1723//1723 1918//1918 1830//1830 -f 1830//1830 1918//1918 1919//1919 -f 1830//1830 1919//1919 1831//1831 -f 1831//1831 1919//1919 1920//1920 -f 1831//1831 1920//1920 1912//1912 -f 1845//1845 1921//1921 1838//1838 -f 1838//1838 1921//1921 1922//1922 -f 1838//1838 1922//1922 1839//1839 -f 1839//1839 1922//1922 1923//1923 -f 1839//1839 1923//1923 1842//1842 -f 1842//1842 1923//1923 1924//1924 -f 1842//1842 1924//1924 1843//1843 -f 1843//1843 1924//1924 1925//1925 -f 1843//1843 1925//1925 1914//1914 -f 1858//1858 1926//1926 1855//1855 -f 1855//1855 1926//1926 1927//1927 -f 1855//1855 1927//1927 1856//1856 -f 1856//1856 1927//1927 1928//1928 -f 1856//1856 1928//1928 1851//1851 -f 1851//1851 1928//1928 1929//1929 -f 1851//1851 1929//1929 1852//1852 -f 1852//1852 1929//1929 1930//1930 -f 1852//1852 1930//1930 1847//1847 -f 1847//1847 1930//1930 1931//1931 -f 1847//1847 1931//1931 1848//1848 -f 1848//1848 1931//1931 1932//1932 -f 1848//1848 1932//1932 1845//1845 -f 1845//1845 1932//1932 1933//1933 -f 1845//1845 1933//1933 1921//1921 -f 1861//1861 1934//1934 1862//1862 -f 1862//1862 1934//1934 1935//1935 -f 1862//1862 1935//1935 1863//1863 -f 1863//1863 1935//1935 1936//1936 -f 1863//1863 1936//1936 1864//1864 -f 1864//1864 1936//1936 1937//1937 -f 1864//1864 1937//1937 1858//1858 -f 1858//1858 1937//1937 1938//1938 -f 1858//1858 1938//1938 1926//1926 -f 1720//1720 1939//1939 1859//1859 -f 1859//1859 1939//1939 1940//1940 -f 1859//1859 1940//1940 1860//1860 -f 1860//1860 1940//1940 1941//1941 -f 1860//1860 1941//1941 1861//1861 -f 1861//1861 1941//1941 1942//1942 -f 1861//1861 1942//1942 1934//1934 -f 1872//1872 1943//1943 1873//1873 -f 1873//1873 1943//1943 1944//1944 -f 1873//1873 1944//1944 1866//1866 -f 1866//1866 1944//1944 1945//1945 -f 1866//1866 1945//1945 1719//1719 -f 1719//1719 1945//1945 1946//1946 -f 1719//1719 1946//1946 1720//1720 -f 1720//1720 1946//1946 1947//1947 -f 1720//1720 1947//1947 1939//1939 -f 1881//1881 1948//1948 1876//1876 -f 1876//1876 1948//1948 1949//1949 -f 1876//1876 1949//1949 1877//1877 -f 1877//1877 1949//1949 1950//1950 -f 1877//1877 1950//1950 1874//1874 -f 1874//1874 1950//1950 1951//1951 -f 1874//1874 1951//1951 1867//1867 -f 1867//1867 1951//1951 1952//1952 -f 1867//1867 1952//1952 1868//1868 -f 1868//1868 1952//1952 1953//1953 -f 1868//1868 1953//1953 1871//1871 -f 1871//1871 1953//1953 1954//1954 -f 1871//1871 1954//1954 1872//1872 -f 1872//1872 1954//1954 1955//1955 -f 1872//1872 1955//1955 1943//1943 -f 1891//1891 1956//1956 1892//1892 -f 1892//1892 1956//1956 1957//1957 -f 1892//1892 1957//1957 1887//1887 -f 1887//1887 1957//1957 1958//1958 -f 1887//1887 1958//1958 1884//1884 -f 1884//1884 1958//1958 1959//1959 -f 1884//1884 1959//1959 1885//1885 -f 1885//1885 1959//1959 1960//1960 -f 1885//1885 1960//1960 1880//1880 -f 1880//1880 1960//1960 1961//1961 -f 1880//1880 1961//1961 1881//1881 -f 1881//1881 1961//1961 1962//1962 -f 1881//1881 1962//1962 1948//1948 -f 1896//1896 1963//1963 1808//1808 -f 1808//1808 1963//1963 1964//1964 -f 1808//1808 1964//1964 1725//1725 -f 1725//1725 1964//1964 1965//1965 -f 1725//1725 1965//1965 1726//1726 -f 1726//1726 1965//1965 1966//1966 -f 1726//1726 1966//1966 1807//1807 -f 1807//1807 1966//1966 1967//1967 -f 1807//1807 1967//1967 1888//1888 -f 1888//1888 1967//1967 1968//1968 -f 1888//1888 1968//1968 1889//1889 -f 1889//1889 1968//1968 1969//1969 -f 1889//1889 1969//1969 1890//1890 -f 1890//1890 1969//1969 1970//1970 -f 1890//1890 1970//1970 1891//1891 -f 1891//1891 1970//1970 1971//1971 -f 1891//1891 1971//1971 1956//1956 -f 1972//1972 1973//1973 1974//1974 -f 1975//1975 1976//1976 1977//1977 -f 1977//1977 1976//1976 1978//1978 -f 1979//1979 1980//1980 1981//1981 -f 1981//1981 1980//1980 1982//1982 -f 1983//1983 1984//1984 1985//1985 -f 1986//1986 1987//1987 1988//1988 -f 1989//1989 1990//1990 1991//1991 -f 1992//1992 1993//1993 1994//1994 -f 1995//1995 1996//1996 1997//1997 -f 1998//1998 1999//1999 2000//2000 -f 2001//2001 2002//2002 2003//2003 -f 2004//2004 2005//2005 2006//2006 -f 1970//1970 1969//1969 2004//2004 -f 1957//1957 1956//1956 2007//2007 -f 1960//1960 1959//1959 1989//1989 -f 1962//1962 1961//1961 2008//2008 -f 1949//1949 1948//1948 2009//2009 -f 1950//1950 1949//1949 2010//2010 -f 1952//1952 1951//1951 2011//2011 -f 1944//1944 1943//1943 1992//1992 -f 1946//1946 1945//1945 2012//2012 -f 1939//1939 1947//1947 2013//2013 -f 1940//1940 1939//1939 2014//2014 -f 1938//1938 1937//1937 2015//2015 -f 1930//1930 1929//1929 1995//1995 -f 1932//1932 1931//1931 2016//2016 -f 1921//1921 1933//1933 2017//2017 -f 1922//1922 1921//1921 2018//2018 -f 1917//1917 1916//1916 2019//2019 -f 1913//1913 1912//1912 1998//1998 -f 1906//1906 1905//1905 2020//2020 -f 1908//1908 1907//1907 2021//2021 -f 1909//1909 1908//1908 2022//2022 -f 1911//1911 1910//1910 2023//2023 -f 1901//1901 1900//1900 2001//2001 -f 1903//1903 1902//1902 2024//2024 -f 1893//1893 1904//1904 2025//2025 -f 1894//1894 1893//1893 2026//2026 -f 1967//1967 1966//1966 2027//2027 -f 2004//2004 1969//1969 2005//2005 -f 2005//2005 1969//1969 1968//1968 -f 2005//2005 1968//1968 1967//1967 -f 2027//2027 1966//1966 2028//2028 -f 1966//1966 1965//1965 2028//2028 -f 2028//2028 1965//1965 1964//1964 -f 2028//2028 1964//1964 2029//2029 -f 2029//2029 1964//1964 1963//1963 -f 2029//2029 1963//1963 1896//1896 -f 1896//1896 1895//1895 2030//2030 -f 2030//2030 1895//1895 1894//1894 -f 2001//2001 1900//1900 2002//2002 -f 2002//2002 1900//1900 1899//1899 -f 2002//2002 1899//1899 1898//1898 -f 1898//1898 1897//1897 2031//2031 -f 2031//2031 1897//1897 1911//1911 -f 1909//1909 2022//2022 1910//1910 -f 1998//1998 1912//1912 1999//1999 -f 1999//1999 1912//1912 1920//1920 -f 1999//1999 1920//1920 1919//1919 -f 1919//1919 1918//1918 2032//2032 -f 2032//2032 1918//1918 1917//1917 -f 2019//2019 1916//1916 2033//2033 -f 1916//1916 1915//1915 2033//2033 -f 2033//2033 1915//1915 1914//1914 -f 2033//2033 1914//1914 2034//2034 -f 1923//1923 2035//2035 1924//1924 -f 1924//1924 2035//2035 2034//2034 -f 1924//1924 2034//2034 1925//1925 -f 1925//1925 2034//2034 1914//1914 -f 1922//1922 2018//2018 1923//1923 -f 1995//1995 1929//1929 1996//1996 -f 1996//1996 1929//1929 1928//1928 -f 1996//1996 1928//1928 1927//1927 -f 1927//1927 1926//1926 2036//2036 -f 2036//2036 1926//1926 1938//1938 -f 2015//2015 1937//1937 2037//2037 -f 1937//1937 1936//1936 2037//2037 -f 2037//2037 1936//1936 1935//1935 -f 2037//2037 1935//1935 2038//2038 -f 1935//1935 1934//1934 2038//2038 -f 2038//2038 1934//1934 1942//1942 -f 2038//2038 1942//1942 2039//2039 -f 2039//2039 1942//1942 1941//1941 -f 2039//2039 1941//1941 1940//1940 -f 1992//1992 1943//1943 1993//1993 -f 1993//1993 1943//1943 1955//1955 -f 1993//1993 1955//1955 1954//1954 -f 1954//1954 1953//1953 2040//2040 -f 2040//2040 1953//1953 1952//1952 -f 1950//1950 2010//2010 1951//1951 -f 1989//1989 1959//1959 1990//1990 -f 1990//1990 1959//1959 1958//1958 -f 1990//1990 1958//1958 1957//1957 -f 2029//2029 2041//2041 2028//2028 -f 2028//2028 2041//2041 2042//2042 -f 2028//2028 2042//2042 2027//2027 -f 2027//2027 2042//2042 1988//1988 -f 2043//2043 2044//2044 2025//2025 -f 1904//1904 1903//1903 2025//2025 -f 2025//2025 1903//1903 2024//2024 -f 2025//2025 2024//2024 2043//2043 -f 2043//2043 2024//2024 2045//2045 -f 2043//2043 2045//2045 2046//2046 -f 2046//2046 2045//2045 2047//2047 -f 2048//2048 2049//2049 2021//2021 -f 1907//1907 1906//1906 2021//2021 -f 2021//2021 1906//1906 2020//2020 -f 2021//2021 2020//2020 2048//2048 -f 2048//2048 2020//2020 2050//2050 -f 2048//2048 2050//2050 2051//2051 -f 2051//2051 2050//2050 2052//2052 -f 2035//2035 1981//1981 2034//2034 -f 2034//2034 1981//1981 1982//1982 -f 2034//2034 1982//1982 2033//2033 -f 2033//2033 1982//1982 2053//2053 -f 2033//2033 2053//2053 2019//2019 -f 2019//2019 2053//2053 2054//2054 -f 2055//2055 2056//2056 2017//2017 -f 1933//1933 1932//1932 2017//2017 -f 2017//2017 1932//1932 2016//2016 -f 2017//2017 2016//2016 2055//2055 -f 2055//2055 2016//2016 2057//2057 -f 2055//2055 2057//2057 2058//2058 -f 2058//2058 2057//2057 2059//2059 -f 2039//2039 1977//1977 2038//2038 -f 2038//2038 1977//1977 1978//1978 -f 2038//2038 1978//1978 2037//2037 -f 2037//2037 1978//1978 2060//2060 -f 2037//2037 2060//2060 2015//2015 -f 2015//2015 2060//2060 2061//2061 -f 2062//2062 2063//2063 2013//2013 -f 1947//1947 1946//1946 2013//2013 -f 2013//2013 1946//1946 2012//2012 -f 2013//2013 2012//2012 2062//2062 -f 2062//2062 2012//2012 2064//2064 -f 2062//2062 2064//2064 2065//2065 -f 2065//2065 2064//2064 2066//2066 -f 2067//2067 2068//2068 2009//2009 -f 2069//2069 2070//2070 2007//2007 -f 1956//1956 1971//1971 2007//2007 -f 2007//2007 1971//1971 2071//2071 -f 2007//2007 2071//2071 2069//2069 -f 2069//2069 2071//2071 2072//2072 -f 2073//2073 2074//2074 2006//2006 -f 2006//2006 2074//2074 2072//2072 -f 2006//2006 2072//2072 2004//2004 -f 2004//2004 2072//2072 2071//2071 -f 2004//2004 2071//2071 1970//1970 -f 1970//1970 2071//2071 1971//1971 -f 1967//1967 2027//2027 2005//2005 -f 2005//2005 2027//2027 1988//1988 -f 2005//2005 1988//1988 2006//2006 -f 2006//2006 1988//1988 1987//1987 -f 2006//2006 1987//1987 2073//2073 -f 1986//1986 1988//1988 2075//2075 -f 2075//2075 1988//1988 2042//2042 -f 2075//2075 2042//2042 2076//2076 -f 2076//2076 2042//2042 2041//2041 -f 2076//2076 2041//2041 2077//2077 -f 2078//2078 2079//2079 2080//2080 -f 1896//1896 2030//2030 2029//2029 -f 2029//2029 2030//2030 2078//2078 -f 2029//2029 2078//2078 2041//2041 -f 2041//2041 2078//2078 2080//2080 -f 2041//2041 2080//2080 2077//2077 -f 1894//1894 2026//2026 2030//2030 -f 2030//2030 2026//2026 2081//2081 -f 2030//2030 2081//2081 2078//2078 -f 2078//2078 2081//2081 2082//2082 -f 2078//2078 2082//2082 2079//2079 -f 1893//1893 2025//2025 2026//2026 -f 2026//2026 2025//2025 2044//2044 -f 2026//2026 2044//2044 2081//2081 -f 2081//2081 2044//2044 2083//2083 -f 2081//2081 2083//2083 2082//2082 -f 2046//2046 2084//2084 2043//2043 -f 2043//2043 2084//2084 2085//2085 -f 2043//2043 2085//2085 2044//2044 -f 2044//2044 2085//2085 2086//2086 -f 2044//2044 2086//2086 2083//2083 -f 1902//1902 1901//1901 2024//2024 -f 2024//2024 1901//1901 2001//2001 -f 2024//2024 2001//2001 2045//2045 -f 2045//2045 2001//2001 2003//2003 -f 2045//2045 2003//2003 2047//2047 -f 2047//2047 2003//2003 2087//2087 -f 2088//2088 2089//2089 2090//2090 -f 1898//1898 2031//2031 2002//2002 -f 2002//2002 2031//2031 2088//2088 -f 2002//2002 2088//2088 2003//2003 -f 2003//2003 2088//2088 2090//2090 -f 2003//2003 2090//2090 2087//2087 -f 1911//1911 2023//2023 2031//2031 -f 2031//2031 2023//2023 1985//1985 -f 2031//2031 1985//1985 2088//2088 -f 2088//2088 1985//1985 1984//1984 -f 2088//2088 1984//1984 2089//2089 -f 1910//1910 2022//2022 2023//2023 -f 2023//2023 2022//2022 2091//2091 -f 2023//2023 2091//2091 1985//1985 -f 1985//1985 2091//2091 2092//2092 -f 1985//1985 2092//2092 1983//1983 -f 1908//1908 2021//2021 2022//2022 -f 2022//2022 2021//2021 2049//2049 -f 2022//2022 2049//2049 2091//2091 -f 2091//2091 2049//2049 2093//2093 -f 2091//2091 2093//2093 2092//2092 -f 2051//2051 2094//2094 2048//2048 -f 2048//2048 2094//2094 2095//2095 -f 2048//2048 2095//2095 2049//2049 -f 2049//2049 2095//2095 2096//2096 -f 2049//2049 2096//2096 2093//2093 -f 1905//1905 1913//1913 2020//2020 -f 2020//2020 1913//1913 1998//1998 -f 2020//2020 1998//1998 2050//2050 -f 2050//2050 1998//1998 2000//2000 -f 2050//2050 2000//2000 2052//2052 -f 2052//2052 2000//2000 2097//2097 -f 2098//2098 2099//2099 2100//2100 -f 1919//1919 2032//2032 1999//1999 -f 1999//1999 2032//2032 2098//2098 -f 1999//1999 2098//2098 2000//2000 -f 2000//2000 2098//2098 2100//2100 -f 2000//2000 2100//2100 2097//2097 -f 1917//1917 2019//2019 2032//2032 -f 2032//2032 2019//2019 2054//2054 -f 2032//2032 2054//2054 2098//2098 -f 2098//2098 2054//2054 2101//2101 -f 2098//2098 2101//2101 2099//2099 -f 1980//1980 2102//2102 1982//1982 -f 1982//1982 2102//2102 2103//2103 -f 1982//1982 2103//2103 2053//2053 -f 2053//2053 2103//2103 2104//2104 -f 2053//2053 2104//2104 2054//2054 -f 2054//2054 2104//2104 2105//2105 -f 2054//2054 2105//2105 2101//2101 -f 1923//1923 2018//2018 2035//2035 -f 2035//2035 2018//2018 2106//2106 -f 2035//2035 2106//2106 1981//1981 -f 1981//1981 2106//2106 2107//2107 -f 1981//1981 2107//2107 1979//1979 -f 1921//1921 2017//2017 2018//2018 -f 2018//2018 2017//2017 2056//2056 -f 2018//2018 2056//2056 2106//2106 -f 2106//2106 2056//2056 2108//2108 -f 2106//2106 2108//2108 2107//2107 -f 2058//2058 2109//2109 2055//2055 -f 2055//2055 2109//2109 2110//2110 -f 2055//2055 2110//2110 2056//2056 -f 2056//2056 2110//2110 2111//2111 -f 2056//2056 2111//2111 2108//2108 -f 1931//1931 1930//1930 2016//2016 -f 2016//2016 1930//1930 1995//1995 -f 2016//2016 1995//1995 2057//2057 -f 2057//2057 1995//1995 1997//1997 -f 2057//2057 1997//1997 2059//2059 -f 2059//2059 1997//1997 2112//2112 -f 2113//2113 2114//2114 2115//2115 -f 1927//1927 2036//2036 1996//1996 -f 1996//1996 2036//2036 2113//2113 -f 1996//1996 2113//2113 1997//1997 -f 1997//1997 2113//2113 2115//2115 -f 1997//1997 2115//2115 2112//2112 -f 1938//1938 2015//2015 2036//2036 -f 2036//2036 2015//2015 2061//2061 -f 2036//2036 2061//2061 2113//2113 -f 2113//2113 2061//2061 2116//2116 -f 2113//2113 2116//2116 2114//2114 -f 1976//1976 2117//2117 1978//1978 -f 1978//1978 2117//2117 2118//2118 -f 1978//1978 2118//2118 2060//2060 -f 2060//2060 2118//2118 2119//2119 -f 2060//2060 2119//2119 2061//2061 -f 2061//2061 2119//2119 2120//2120 -f 2061//2061 2120//2120 2116//2116 -f 1940//1940 2014//2014 2039//2039 -f 2039//2039 2014//2014 2121//2121 -f 2039//2039 2121//2121 1977//1977 -f 1977//1977 2121//2121 2122//2122 -f 1977//1977 2122//2122 1975//1975 -f 1939//1939 2013//2013 2014//2014 -f 2014//2014 2013//2013 2063//2063 -f 2014//2014 2063//2063 2121//2121 -f 2121//2121 2063//2063 2123//2123 -f 2121//2121 2123//2123 2122//2122 -f 2065//2065 2124//2124 2062//2062 -f 2062//2062 2124//2124 2125//2125 -f 2062//2062 2125//2125 2063//2063 -f 2063//2063 2125//2125 2126//2126 -f 2063//2063 2126//2126 2123//2123 -f 1945//1945 1944//1944 2012//2012 -f 2012//2012 1944//1944 1992//1992 -f 2012//2012 1992//1992 2064//2064 -f 2064//2064 1992//1992 1994//1994 -f 2064//2064 1994//1994 2066//2066 -f 2066//2066 1994//1994 2127//2127 -f 2128//2128 2129//2129 2130//2130 -f 1954//1954 2040//2040 1993//1993 -f 1993//1993 2040//2040 2128//2128 -f 1993//1993 2128//2128 1994//1994 -f 1994//1994 2128//2128 2130//2130 -f 1994//1994 2130//2130 2127//2127 -f 1952//1952 2011//2011 2040//2040 -f 2040//2040 2011//2011 1974//1974 -f 2040//2040 1974//1974 2128//2128 -f 2128//2128 1974//1974 1973//1973 -f 2128//2128 1973//1973 2129//2129 -f 1951//1951 2010//2010 2011//2011 -f 2011//2011 2010//2010 2131//2131 -f 2011//2011 2131//2131 1974//1974 -f 1974//1974 2131//2131 2132//2132 -f 1974//1974 2132//2132 1972//1972 -f 1949//1949 2009//2009 2010//2010 -f 2010//2010 2009//2009 2068//2068 -f 2010//2010 2068//2068 2131//2131 -f 2131//2131 2068//2068 2133//2133 -f 2131//2131 2133//2133 2132//2132 -f 2134//2134 2135//2135 2136//2136 -f 2136//2136 2135//2135 2067//2067 -f 2136//2136 2067//2067 2008//2008 -f 2008//2008 2067//2067 2009//2009 -f 2008//2008 2009//2009 1962//1962 -f 1962//1962 2009//2009 1948//1948 -f 2135//2135 2137//2137 2067//2067 -f 2067//2067 2137//2137 2138//2138 -f 2067//2067 2138//2138 2068//2068 -f 2068//2068 2138//2138 2139//2139 -f 2068//2068 2139//2139 2133//2133 -f 1961//1961 1960//1960 2008//2008 -f 2008//2008 1960//1960 1989//1989 -f 2008//2008 1989//1989 2136//2136 -f 2136//2136 1989//1989 1991//1991 -f 2136//2136 1991//1991 2134//2134 -f 2134//2134 1991//1991 2140//2140 -f 1957//1957 2007//2007 1990//1990 -f 1990//1990 2007//2007 2070//2070 -f 1990//1990 2070//2070 1991//1991 -f 1991//1991 2070//2070 2141//2141 -f 1991//1991 2141//2141 2140//2140 -f 2074//2074 2142//2142 2072//2072 -f 2072//2072 2142//2142 2143//2143 -f 2072//2072 2143//2143 2069//2069 -f 2069//2069 2143//2143 2144//2144 -f 2069//2069 2144//2144 2070//2070 -f 2070//2070 2144//2144 2145//2145 -f 2070//2070 2145//2145 2141//2141 -f 2146//2146 2147//2147 2104//2104 -f 2104//2104 2147//2147 2105//2105 -f 2105//2105 2147//2147 2148//2148 -f 2105//2105 2148//2148 2101//2101 -f 2101//2101 2148//2148 2149//2149 -f 2101//2101 2149//2149 2099//2099 -f 2099//2099 2149//2149 2150//2150 -f 2099//2099 2150//2150 2100//2100 -f 2100//2100 2150//2150 2097//2097 -f 2097//2097 2150//2150 2151//2151 -f 2097//2097 2151//2151 2052//2052 -f 2151//2151 2152//2152 2052//2052 -f 2052//2052 2152//2152 2153//2153 -f 2052//2052 2153//2153 2051//2051 -f 2051//2051 2153//2153 2154//2154 -f 2155//2155 1984//1984 2156//2156 -f 2156//2156 1984//1984 1983//1983 -f 2156//2156 1983//1983 2157//2157 -f 2157//2157 1983//1983 2092//2092 -f 2157//2157 2092//2092 2158//2158 -f 2158//2158 2092//2092 2093//2093 -f 2158//2158 2093//2093 2159//2159 -f 2159//2159 2093//2093 2096//2096 -f 2159//2159 2096//2096 2160//2160 -f 2160//2160 2096//2096 2095//2095 -f 2160//2160 2095//2095 2154//2154 -f 2154//2154 2095//2095 2094//2094 -f 2154//2154 2094//2094 2051//2051 -f 2161//2161 2082//2082 2162//2162 -f 2162//2162 2082//2082 2083//2083 -f 2162//2162 2083//2083 2163//2163 -f 2163//2163 2083//2083 2086//2086 -f 2163//2163 2086//2086 2164//2164 -f 2164//2164 2086//2086 2085//2085 -f 2164//2164 2085//2085 2165//2165 -f 2165//2165 2085//2085 2084//2084 -f 2165//2165 2084//2084 2166//2166 -f 2166//2166 2084//2084 2046//2046 -f 2166//2166 2046//2046 2167//2167 -f 2167//2167 2046//2046 2047//2047 -f 2167//2167 2047//2047 2168//2168 -f 2168//2168 2047//2047 2087//2087 -f 2168//2168 2087//2087 2169//2169 -f 2169//2169 2087//2087 2090//2090 -f 2169//2169 2090//2090 2155//2155 -f 2155//2155 2090//2090 2089//2089 -f 2155//2155 2089//2089 1984//1984 -f 2170//2170 1987//1987 2171//2171 -f 2171//2171 1987//1987 1986//1986 -f 2171//2171 1986//1986 2172//2172 -f 2172//2172 1986//1986 2075//2075 -f 2172//2172 2075//2075 2173//2173 -f 2173//2173 2075//2075 2076//2076 -f 2173//2173 2076//2076 2174//2174 -f 2174//2174 2076//2076 2077//2077 -f 2174//2174 2077//2077 2175//2175 -f 2175//2175 2077//2077 2080//2080 -f 2175//2175 2080//2080 2161//2161 -f 2161//2161 2080//2080 2079//2079 -f 2161//2161 2079//2079 2082//2082 -f 2176//2176 2145//2145 2177//2177 -f 2177//2177 2145//2145 2144//2144 -f 2177//2177 2144//2144 2178//2178 -f 2178//2178 2144//2144 2143//2143 -f 2178//2178 2143//2143 2179//2179 -f 2179//2179 2143//2143 2142//2142 -f 2179//2179 2142//2142 2180//2180 -f 2180//2180 2142//2142 2074//2074 -f 2180//2180 2074//2074 2170//2170 -f 2170//2170 2074//2074 2073//2073 -f 2170//2170 2073//2073 1987//1987 -f 2181//2181 1973//1973 2182//2182 -f 2182//2182 1973//1973 1972//1972 -f 2182//2182 1972//1972 2183//2183 -f 2183//2183 1972//1972 2132//2132 -f 2183//2183 2132//2132 2184//2184 -f 2184//2184 2132//2132 2133//2133 -f 2184//2184 2133//2133 2185//2185 -f 2185//2185 2133//2133 2139//2139 -f 2185//2185 2139//2139 2186//2186 -f 2186//2186 2139//2139 2138//2138 -f 2186//2186 2138//2138 2187//2187 -f 2187//2187 2138//2138 2137//2137 -f 2187//2187 2137//2137 2188//2188 -f 2188//2188 2137//2137 2135//2135 -f 2188//2188 2135//2135 2189//2189 -f 2189//2189 2135//2135 2134//2134 -f 2189//2189 2134//2134 2190//2190 -f 2190//2190 2134//2134 2140//2140 -f 2190//2190 2140//2140 2176//2176 -f 2176//2176 2140//2140 2141//2141 -f 2176//2176 2141//2141 2145//2145 -f 2191//2191 2124//2124 2192//2192 -f 2192//2192 2124//2124 2065//2065 -f 2192//2192 2065//2065 2193//2193 -f 2193//2193 2065//2065 2066//2066 -f 2193//2193 2066//2066 2194//2194 -f 2194//2194 2066//2066 2127//2127 -f 2194//2194 2127//2127 2195//2195 -f 2195//2195 2127//2127 2130//2130 -f 2195//2195 2130//2130 2181//2181 -f 2181//2181 2130//2130 2129//2129 -f 2181//2181 2129//2129 1973//1973 -f 2196//2196 2116//2116 2197//2197 -f 2197//2197 2116//2116 2120//2120 -f 2197//2197 2120//2120 2198//2198 -f 2198//2198 2120//2120 2119//2119 -f 2198//2198 2119//2119 2199//2199 -f 2199//2199 2119//2119 2118//2118 -f 2199//2199 2118//2118 2200//2200 -f 2200//2200 2118//2118 2117//2117 -f 2200//2200 2117//2117 2201//2201 -f 2201//2201 2117//2117 1976//1976 -f 2201//2201 1976//1976 2202//2202 -f 2202//2202 1976//1976 1975//1975 -f 2202//2202 1975//1975 2203//2203 -f 2203//2203 1975//1975 2122//2122 -f 2203//2203 2122//2122 2204//2204 -f 2204//2204 2122//2122 2123//2123 -f 2204//2204 2123//2123 2205//2205 -f 2205//2205 2123//2123 2126//2126 -f 2205//2205 2126//2126 2191//2191 -f 2191//2191 2126//2126 2125//2125 -f 2191//2191 2125//2125 2124//2124 -f 2206//2206 2058//2058 2207//2207 -f 2207//2207 2058//2058 2059//2059 -f 2207//2207 2059//2059 2208//2208 -f 2208//2208 2059//2059 2112//2112 -f 2208//2208 2112//2112 2209//2209 -f 2209//2209 2112//2112 2115//2115 -f 2209//2209 2115//2115 2196//2196 -f 2196//2196 2115//2115 2114//2114 -f 2196//2196 2114//2114 2116//2116 -f 2104//2104 2103//2103 2146//2146 -f 2146//2146 2103//2103 2102//2102 -f 2146//2146 2102//2102 2210//2210 -f 2210//2210 2102//2102 1980//1980 -f 2210//2210 1980//1980 2211//2211 -f 2211//2211 1980//1980 1979//1979 -f 2211//2211 1979//1979 2212//2212 -f 2212//2212 1979//1979 2107//2107 -f 2212//2212 2107//2107 2213//2213 -f 2213//2213 2107//2107 2108//2108 -f 2213//2213 2108//2108 2214//2214 -f 2214//2214 2108//2108 2111//2111 -f 2214//2214 2111//2111 2215//2215 -f 2215//2215 2111//2111 2110//2110 -f 2215//2215 2110//2110 2206//2206 -f 2206//2206 2110//2110 2109//2109 -f 2206//2206 2109//2109 2058//2058 -f 2216//2216 2217//2217 2218//2218 -f 2219//2219 2220//2220 2221//2221 -f 2222//2222 2223//2223 2224//2224 -f 2225//2225 2226//2226 2227//2227 -f 2228//2228 2229//2229 2230//2230 -f 2231//2231 2232//2232 2233//2233 -f 2234//2234 2235//2235 2236//2236 -f 2237//2237 2238//2238 2239//2239 -f 2240//2240 2241//2241 2242//2242 -f 2243//2243 2244//2244 2245//2245 -f 2246//2246 2247//2247 2248//2248 -f 2249//2249 2250//2250 2251//2251 -f 2252//2252 2253//2253 2254//2254 -f 2242//2242 2255//2255 2256//2256 -f 2253//2253 2257//2257 2258//2258 -f 2255//2255 2259//2259 2260//2260 -f 2184//2184 2185//2185 2261//2261 -f 2182//2182 2183//2183 2262//2262 -f 2191//2191 2192//2192 2263//2263 -f 2209//2209 2196//2196 2264//2264 -f 2213//2213 2214//2214 2265//2265 -f 2211//2211 2212//2212 2266//2266 -f 2146//2146 2210//2210 2267//2267 -f 2148//2148 2147//2147 2268//2268 -f 2150//2150 2149//2149 2269//2269 -f 2165//2165 2166//2166 2270//2270 -f 2163//2163 2164//2164 2271//2271 -f 2175//2175 2161//2161 2272//2272 -f 2180//2180 2273//2273 2274//2274 -f 2170//2170 2171//2171 2275//2275 -f 2172//2172 2173//2173 2276//2276 -f 2175//2175 2272//2272 2174//2174 -f 2156//2156 2277//2277 2260//2260 -f 2167//2167 2168//2168 2259//2259 -f 2259//2259 2168//2168 2169//2169 -f 2259//2259 2169//2169 2260//2260 -f 2260//2260 2169//2169 2155//2155 -f 2260//2260 2155//2155 2156//2156 -f 2156//2156 2157//2157 2277//2277 -f 2277//2277 2157//2157 2158//2158 -f 2277//2277 2158//2158 2278//2278 -f 2278//2278 2158//2158 2159//2159 -f 2278//2278 2159//2159 2279//2279 -f 2159//2159 2160//2160 2279//2279 -f 2279//2279 2160//2160 2154//2154 -f 2279//2279 2154//2154 2280//2280 -f 2280//2280 2154//2154 2153//2153 -f 2280//2280 2153//2153 2152//2152 -f 2206//2206 2207//2207 2281//2281 -f 2209//2209 2264//2264 2208//2208 -f 2197//2197 2198//2198 2257//2257 -f 2257//2257 2198//2198 2199//2199 -f 2257//2257 2199//2199 2258//2258 -f 2258//2258 2199//2199 2200//2200 -f 2258//2258 2200//2200 2282//2282 -f 2200//2200 2201//2201 2282//2282 -f 2282//2282 2201//2201 2202//2202 -f 2282//2282 2202//2202 2283//2283 -f 2205//2205 2284//2284 2204//2204 -f 2204//2204 2284//2284 2283//2283 -f 2204//2204 2283//2283 2203//2203 -f 2203//2203 2283//2283 2202//2202 -f 2194//2194 2195//2195 2285//2285 -f 2182//2182 2262//2262 2181//2181 -f 2187//2187 2188//2188 2286//2286 -f 2286//2286 2188//2188 2189//2189 -f 2286//2286 2189//2189 2287//2287 -f 2189//2189 2190//2190 2287//2287 -f 2287//2287 2190//2190 2176//2176 -f 2287//2287 2176//2176 2288//2288 -f 2176//2176 2177//2177 2288//2288 -f 2288//2288 2177//2177 2178//2178 -f 2288//2288 2178//2178 2274//2274 -f 2274//2274 2178//2178 2179//2179 -f 2274//2274 2179//2179 2180//2180 -f 2273//2273 2289//2289 2290//2290 -f 2255//2255 2260//2260 2256//2256 -f 2256//2256 2260//2260 2277//2277 -f 2256//2256 2277//2277 2291//2291 -f 2291//2291 2277//2277 2278//2278 -f 2291//2291 2278//2278 2292//2292 -f 2292//2292 2278//2278 2279//2279 -f 2292//2292 2279//2279 2293//2293 -f 2293//2293 2279//2279 2280//2280 -f 2293//2293 2280//2280 2294//2294 -f 2253//2253 2258//2258 2254//2254 -f 2254//2254 2258//2258 2282//2282 -f 2254//2254 2282//2282 2295//2295 -f 2295//2295 2282//2282 2283//2283 -f 2295//2295 2283//2283 2296//2296 -f 2296//2296 2283//2283 2284//2284 -f 2296//2296 2284//2284 2297//2297 -f 2273//2273 2290//2290 2274//2274 -f 2274//2274 2290//2290 2298//2298 -f 2274//2274 2298//2298 2288//2288 -f 2288//2288 2298//2298 2299//2299 -f 2288//2288 2299//2299 2287//2287 -f 2287//2287 2299//2299 2300//2300 -f 2287//2287 2300//2300 2286//2286 -f 2289//2289 2301//2301 2302//2302 -f 2161//2161 2162//2162 2272//2272 -f 2272//2272 2162//2162 2303//2303 -f 2272//2272 2303//2303 2304//2304 -f 2304//2304 2303//2303 2305//2305 -f 2304//2304 2305//2305 2306//2306 -f 2306//2306 2305//2305 2248//2248 -f 2242//2242 2256//2256 2307//2307 -f 2307//2307 2256//2256 2291//2291 -f 2307//2307 2291//2291 2308//2308 -f 2308//2308 2291//2291 2292//2292 -f 2308//2308 2292//2292 2309//2309 -f 2309//2309 2292//2292 2293//2293 -f 2309//2309 2293//2293 2310//2310 -f 2310//2310 2293//2293 2294//2294 -f 2310//2310 2294//2294 2239//2239 -f 2149//2149 2148//2148 2269//2269 -f 2269//2269 2148//2148 2268//2268 -f 2269//2269 2268//2268 2311//2311 -f 2311//2311 2268//2268 2312//2312 -f 2311//2311 2312//2312 2313//2313 -f 2313//2313 2312//2312 2236//2236 -f 2214//2214 2215//2215 2265//2265 -f 2265//2265 2215//2215 2314//2314 -f 2265//2265 2314//2314 2315//2315 -f 2315//2315 2314//2314 2316//2316 -f 2315//2315 2316//2316 2317//2317 -f 2317//2317 2316//2316 2230//2230 -f 2252//2252 2254//2254 2318//2318 -f 2318//2318 2254//2254 2295//2295 -f 2318//2318 2295//2295 2319//2319 -f 2319//2319 2295//2295 2296//2296 -f 2319//2319 2296//2296 2320//2320 -f 2320//2320 2296//2296 2297//2297 -f 2320//2320 2297//2297 2321//2321 -f 2195//2195 2181//2181 2285//2285 -f 2285//2285 2181//2181 2262//2262 -f 2285//2285 2262//2262 2322//2322 -f 2322//2322 2262//2262 2323//2323 -f 2322//2322 2323//2323 2324//2324 -f 2324//2324 2323//2323 2221//2221 -f 2289//2289 2302//2302 2290//2290 -f 2290//2290 2302//2302 2325//2325 -f 2290//2290 2325//2325 2298//2298 -f 2298//2298 2325//2325 2326//2326 -f 2298//2298 2326//2326 2299//2299 -f 2299//2299 2326//2326 2327//2327 -f 2299//2299 2327//2327 2300//2300 -f 2180//2180 2170//2170 2273//2273 -f 2273//2273 2170//2170 2275//2275 -f 2273//2273 2275//2275 2289//2289 -f 2289//2289 2275//2275 2328//2328 -f 2289//2289 2328//2328 2301//2301 -f 2301//2301 2328//2328 2251//2251 -f 2301//2301 2251//2251 2329//2329 -f 2329//2329 2251//2251 2250//2250 -f 2330//2330 2249//2249 2331//2331 -f 2331//2331 2249//2249 2251//2251 -f 2331//2331 2251//2251 2332//2332 -f 2332//2332 2251//2251 2328//2328 -f 2332//2332 2328//2328 2276//2276 -f 2276//2276 2328//2328 2275//2275 -f 2276//2276 2275//2275 2172//2172 -f 2172//2172 2275//2275 2171//2171 -f 2173//2173 2174//2174 2276//2276 -f 2276//2276 2174//2174 2272//2272 -f 2276//2276 2272//2272 2332//2332 -f 2332//2332 2272//2272 2304//2304 -f 2332//2332 2304//2304 2331//2331 -f 2331//2331 2304//2304 2306//2306 -f 2331//2331 2306//2306 2330//2330 -f 2330//2330 2306//2306 2333//2333 -f 2248//2248 2247//2247 2306//2306 -f 2306//2306 2247//2247 2334//2334 -f 2306//2306 2334//2334 2333//2333 -f 2162//2162 2163//2163 2303//2303 -f 2303//2303 2163//2163 2271//2271 -f 2303//2303 2271//2271 2305//2305 -f 2305//2305 2271//2271 2335//2335 -f 2305//2305 2335//2335 2248//2248 -f 2248//2248 2335//2335 2245//2245 -f 2248//2248 2245//2245 2246//2246 -f 2246//2246 2245//2245 2244//2244 -f 2336//2336 2243//2243 2337//2337 -f 2337//2337 2243//2243 2245//2245 -f 2337//2337 2245//2245 2338//2338 -f 2338//2338 2245//2245 2335//2335 -f 2338//2338 2335//2335 2270//2270 -f 2270//2270 2335//2335 2271//2271 -f 2270//2270 2271//2271 2165//2165 -f 2165//2165 2271//2271 2164//2164 -f 2166//2166 2167//2167 2270//2270 -f 2270//2270 2167//2167 2259//2259 -f 2270//2270 2259//2259 2338//2338 -f 2338//2338 2259//2259 2255//2255 -f 2338//2338 2255//2255 2337//2337 -f 2337//2337 2255//2255 2242//2242 -f 2337//2337 2242//2242 2336//2336 -f 2336//2336 2242//2242 2241//2241 -f 2240//2240 2242//2242 2339//2339 -f 2339//2339 2242//2242 2307//2307 -f 2339//2339 2307//2307 2340//2340 -f 2340//2340 2307//2307 2308//2308 -f 2340//2340 2308//2308 2341//2341 -f 2341//2341 2308//2308 2309//2309 -f 2341//2341 2309//2309 2342//2342 -f 2342//2342 2309//2309 2310//2310 -f 2342//2342 2310//2310 2343//2343 -f 2239//2239 2238//2238 2310//2310 -f 2310//2310 2238//2238 2344//2344 -f 2310//2310 2344//2344 2343//2343 -f 2345//2345 2237//2237 2346//2346 -f 2346//2346 2237//2237 2239//2239 -f 2346//2346 2239//2239 2347//2347 -f 2347//2347 2239//2239 2294//2294 -f 2347//2347 2294//2294 2348//2348 -f 2348//2348 2294//2294 2280//2280 -f 2348//2348 2280//2280 2151//2151 -f 2151//2151 2280//2280 2152//2152 -f 2151//2151 2150//2150 2348//2348 -f 2348//2348 2150//2150 2269//2269 -f 2348//2348 2269//2269 2347//2347 -f 2347//2347 2269//2269 2311//2311 -f 2347//2347 2311//2311 2346//2346 -f 2346//2346 2311//2311 2313//2313 -f 2346//2346 2313//2313 2345//2345 -f 2345//2345 2313//2313 2349//2349 -f 2236//2236 2235//2235 2313//2313 -f 2313//2313 2235//2235 2350//2350 -f 2313//2313 2350//2350 2349//2349 -f 2147//2147 2146//2146 2268//2268 -f 2268//2268 2146//2146 2267//2267 -f 2268//2268 2267//2267 2312//2312 -f 2312//2312 2267//2267 2351//2351 -f 2312//2312 2351//2351 2236//2236 -f 2236//2236 2351//2351 2233//2233 -f 2236//2236 2233//2233 2234//2234 -f 2234//2234 2233//2233 2232//2232 -f 2352//2352 2231//2231 2353//2353 -f 2353//2353 2231//2231 2233//2233 -f 2353//2353 2233//2233 2354//2354 -f 2354//2354 2233//2233 2351//2351 -f 2354//2354 2351//2351 2266//2266 -f 2266//2266 2351//2351 2267//2267 -f 2266//2266 2267//2267 2211//2211 -f 2211//2211 2267//2267 2210//2210 -f 2212//2212 2213//2213 2266//2266 -f 2266//2266 2213//2213 2265//2265 -f 2266//2266 2265//2265 2354//2354 -f 2354//2354 2265//2265 2315//2315 -f 2354//2354 2315//2315 2353//2353 -f 2353//2353 2315//2315 2317//2317 -f 2353//2353 2317//2317 2352//2352 -f 2352//2352 2317//2317 2355//2355 -f 2230//2230 2229//2229 2317//2317 -f 2317//2317 2229//2229 2356//2356 -f 2317//2317 2356//2356 2355//2355 -f 2226//2226 2228//2228 2227//2227 -f 2227//2227 2228//2228 2230//2230 -f 2227//2227 2230//2230 2357//2357 -f 2357//2357 2230//2230 2316//2316 -f 2357//2357 2316//2316 2281//2281 -f 2281//2281 2316//2316 2314//2314 -f 2281//2281 2314//2314 2206//2206 -f 2206//2206 2314//2314 2215//2215 -f 2358//2358 2225//2225 2359//2359 -f 2359//2359 2225//2225 2227//2227 -f 2359//2359 2227//2227 2360//2360 -f 2360//2360 2227//2227 2357//2357 -f 2360//2360 2357//2357 2264//2264 -f 2264//2264 2357//2357 2281//2281 -f 2264//2264 2281//2281 2208//2208 -f 2208//2208 2281//2281 2207//2207 -f 2196//2196 2197//2197 2264//2264 -f 2264//2264 2197//2197 2257//2257 -f 2264//2264 2257//2257 2360//2360 -f 2360//2360 2257//2257 2253//2253 -f 2360//2360 2253//2253 2359//2359 -f 2359//2359 2253//2253 2252//2252 -f 2359//2359 2252//2252 2358//2358 -f 2358//2358 2252//2252 2361//2361 -f 2362//2362 2363//2363 2321//2321 -f 2321//2321 2363//2363 2364//2364 -f 2321//2321 2364//2364 2320//2320 -f 2320//2320 2364//2364 2365//2365 -f 2320//2320 2365//2365 2319//2319 -f 2319//2319 2365//2365 2366//2366 -f 2319//2319 2366//2366 2318//2318 -f 2318//2318 2366//2366 2367//2367 -f 2318//2318 2367//2367 2252//2252 -f 2252//2252 2367//2367 2368//2368 -f 2252//2252 2368//2368 2361//2361 -f 2205//2205 2191//2191 2284//2284 -f 2284//2284 2191//2191 2263//2263 -f 2284//2284 2263//2263 2297//2297 -f 2297//2297 2263//2263 2369//2369 -f 2297//2297 2369//2369 2321//2321 -f 2321//2321 2369//2369 2224//2224 -f 2321//2321 2224//2224 2362//2362 -f 2362//2362 2224//2224 2223//2223 -f 2370//2370 2222//2222 2371//2371 -f 2371//2371 2222//2222 2224//2224 -f 2371//2371 2224//2224 2372//2372 -f 2372//2372 2224//2224 2369//2369 -f 2372//2372 2369//2369 2373//2373 -f 2373//2373 2369//2369 2263//2263 -f 2373//2373 2263//2263 2193//2193 -f 2193//2193 2263//2263 2192//2192 -f 2193//2193 2194//2194 2373//2373 -f 2373//2373 2194//2194 2285//2285 -f 2373//2373 2285//2285 2372//2372 -f 2372//2372 2285//2285 2322//2322 -f 2372//2372 2322//2322 2371//2371 -f 2371//2371 2322//2322 2324//2324 -f 2371//2371 2324//2324 2370//2370 -f 2370//2370 2324//2324 2374//2374 -f 2221//2221 2220//2220 2324//2324 -f 2324//2324 2220//2220 2375//2375 -f 2324//2324 2375//2375 2374//2374 -f 2217//2217 2219//2219 2218//2218 -f 2218//2218 2219//2219 2221//2221 -f 2218//2218 2221//2221 2376//2376 -f 2376//2376 2221//2221 2323//2323 -f 2376//2376 2323//2323 2261//2261 -f 2261//2261 2323//2323 2262//2262 -f 2261//2261 2262//2262 2184//2184 -f 2184//2184 2262//2262 2183//2183 -f 2377//2377 2216//2216 2378//2378 -f 2378//2378 2216//2216 2218//2218 -f 2378//2378 2218//2218 2379//2379 -f 2379//2379 2218//2218 2376//2376 -f 2379//2379 2376//2376 2380//2380 -f 2380//2380 2376//2376 2261//2261 -f 2380//2380 2261//2261 2186//2186 -f 2186//2186 2261//2261 2185//2185 -f 2186//2186 2187//2187 2380//2380 -f 2380//2380 2187//2187 2286//2286 -f 2380//2380 2286//2286 2379//2379 -f 2379//2379 2286//2286 2300//2300 -f 2379//2379 2300//2300 2378//2378 -f 2378//2378 2300//2300 2327//2327 -f 2378//2378 2327//2327 2377//2377 -f 2377//2377 2327//2327 2381//2381 -f 2329//2329 2382//2382 2301//2301 -f 2301//2301 2382//2382 2383//2383 -f 2301//2301 2383//2383 2302//2302 -f 2302//2302 2383//2383 2384//2384 -f 2302//2302 2384//2384 2325//2325 -f 2325//2325 2384//2384 2385//2385 -f 2325//2325 2385//2385 2326//2326 -f 2326//2326 2385//2385 2386//2386 -f 2326//2326 2386//2386 2327//2327 -f 2327//2327 2386//2386 2387//2387 -f 2327//2327 2387//2387 2381//2381 -f 2388//2388 2336//2336 2389//2389 -f 2389//2389 2336//2336 2241//2241 -f 2389//2389 2241//2241 2390//2390 -f 2390//2390 2241//2241 2240//2240 -f 2390//2390 2240//2240 2391//2391 -f 2391//2391 2240//2240 2339//2339 -f 2391//2391 2339//2339 2392//2392 -f 2392//2392 2339//2339 2340//2340 -f 2392//2392 2340//2340 2393//2393 -f 2393//2393 2340//2340 2341//2341 -f 2393//2393 2341//2341 2394//2394 -f 2394//2394 2341//2341 2342//2342 -f 2395//2395 2396//2396 2352//2352 -f 2352//2352 2396//2396 2397//2397 -f 2352//2352 2397//2397 2231//2231 -f 2231//2231 2397//2397 2398//2398 -f 2231//2231 2398//2398 2232//2232 -f 2232//2232 2398//2398 2399//2399 -f 2232//2232 2399//2399 2234//2234 -f 2234//2234 2399//2399 2400//2400 -f 2234//2234 2400//2400 2235//2235 -f 2235//2235 2400//2400 2401//2401 -f 2235//2235 2401//2401 2350//2350 -f 2350//2350 2401//2401 2402//2402 -f 2350//2350 2402//2402 2349//2349 -f 2349//2349 2402//2402 2403//2403 -f 2349//2349 2403//2403 2345//2345 -f 2345//2345 2403//2403 2404//2404 -f 2345//2345 2404//2404 2237//2237 -f 2237//2237 2404//2404 2405//2405 -f 2237//2237 2405//2405 2238//2238 -f 2238//2238 2405//2405 2406//2406 -f 2238//2238 2406//2406 2344//2344 -f 2344//2344 2406//2406 2407//2407 -f 2344//2344 2407//2407 2343//2343 -f 2343//2343 2407//2407 2408//2408 -f 2343//2343 2408//2408 2342//2342 -f 2342//2342 2408//2408 2409//2409 -f 2342//2342 2409//2409 2394//2394 -f 2352//2352 2355//2355 2395//2395 -f 2395//2395 2355//2355 2356//2356 -f 2395//2395 2356//2356 2410//2410 -f 2410//2410 2356//2356 2411//2411 -f 2411//2411 2356//2356 2229//2229 -f 2411//2411 2229//2229 2412//2412 -f 2412//2412 2229//2229 2228//2228 -f 2412//2412 2228//2228 2413//2413 -f 2413//2413 2228//2228 2226//2226 -f 2413//2413 2226//2226 2414//2414 -f 2226//2226 2225//2225 2414//2414 -f 2414//2414 2225//2225 2358//2358 -f 2414//2414 2358//2358 2415//2415 -f 2415//2415 2358//2358 2416//2416 -f 2358//2358 2361//2361 2416//2416 -f 2416//2416 2361//2361 2368//2368 -f 2416//2416 2368//2368 2417//2417 -f 2417//2417 2368//2368 2418//2418 -f 2418//2418 2368//2368 2367//2367 -f 2418//2418 2367//2367 2419//2419 -f 2419//2419 2367//2367 2366//2366 -f 2419//2419 2366//2366 2420//2420 -f 2420//2420 2366//2366 2365//2365 -f 2420//2420 2365//2365 2421//2421 -f 2421//2421 2365//2365 2364//2364 -f 2421//2421 2364//2364 2422//2422 -f 2422//2422 2364//2364 2423//2423 -f 2423//2423 2364//2364 2363//2363 -f 2423//2423 2363//2363 2424//2424 -f 2424//2424 2363//2363 2362//2362 -f 2424//2424 2362//2362 2425//2425 -f 2425//2425 2362//2362 2223//2223 -f 2425//2425 2223//2223 2426//2426 -f 2426//2426 2223//2223 2222//2222 -f 2426//2426 2222//2222 2427//2427 -f 2427//2427 2222//2222 2370//2370 -f 2427//2427 2370//2370 2428//2428 -f 2370//2370 2374//2374 2428//2428 -f 2428//2428 2374//2374 2375//2375 -f 2428//2428 2375//2375 2429//2429 -f 2429//2429 2375//2375 2220//2220 -f 2429//2429 2220//2220 2430//2430 -f 2430//2430 2220//2220 2219//2219 -f 2430//2430 2219//2219 2431//2431 -f 2431//2431 2219//2219 2217//2217 -f 2431//2431 2217//2217 2432//2432 -f 2432//2432 2217//2217 2216//2216 -f 2432//2432 2216//2216 2433//2433 -f 2433//2433 2216//2216 2377//2377 -f 2433//2433 2377//2377 2434//2434 -f 2434//2434 2377//2377 2381//2381 -f 2434//2434 2381//2381 2435//2435 -f 2435//2435 2381//2381 2387//2387 -f 2435//2435 2387//2387 2436//2436 -f 2436//2436 2387//2387 2386//2386 -f 2436//2436 2386//2386 2437//2437 -f 2437//2437 2386//2386 2385//2385 -f 2437//2437 2385//2385 2438//2438 -f 2438//2438 2385//2385 2384//2384 -f 2438//2438 2384//2384 2439//2439 -f 2439//2439 2384//2384 2383//2383 -f 2439//2439 2383//2383 2440//2440 -f 2440//2440 2383//2383 2382//2382 -f 2440//2440 2382//2382 2441//2441 -f 2441//2441 2382//2382 2329//2329 -f 2441//2441 2329//2329 2442//2442 -f 2442//2442 2329//2329 2250//2250 -f 2442//2442 2250//2250 2443//2443 -f 2443//2443 2250//2250 2249//2249 -f 2443//2443 2249//2249 2444//2444 -f 2444//2444 2249//2249 2330//2330 -f 2444//2444 2330//2330 2445//2445 -f 2445//2445 2330//2330 2333//2333 -f 2445//2445 2333//2333 2446//2446 -f 2446//2446 2333//2333 2334//2334 -f 2446//2446 2334//2334 2447//2447 -f 2447//2447 2334//2334 2247//2247 -f 2447//2447 2247//2247 2448//2448 -f 2448//2448 2247//2247 2246//2246 -f 2448//2448 2246//2246 2449//2449 -f 2449//2449 2246//2246 2244//2244 -f 2449//2449 2244//2244 2388//2388 -f 2388//2388 2244//2244 2243//2243 -f 2388//2388 2243//2243 2336//2336 -f 2450//2450 2441//2441 2451//2451 -f 2451//2451 2441//2441 2442//2442 -f 2451//2451 2442//2442 2452//2452 -f 2442//2442 2443//2443 2452//2452 -f 2452//2452 2443//2443 2444//2444 -f 2452//2452 2444//2444 2453//2453 -f 2444//2444 2445//2445 2453//2453 -f 2453//2453 2445//2445 2446//2446 -f 2453//2453 2446//2446 2454//2454 -f 2454//2454 2446//2446 2447//2447 -f 2454//2454 2447//2447 2455//2455 -f 2447//2447 2448//2448 2455//2455 -f 2455//2455 2448//2448 2449//2449 -f 2455//2455 2449//2449 2456//2456 -f 2456//2456 2449//2449 2388//2388 -f 2456//2456 2388//2388 2457//2457 -f 2388//2388 2389//2389 2457//2457 -f 2457//2457 2389//2389 2390//2390 -f 2457//2457 2390//2390 2458//2458 -f 2458//2458 2390//2390 2391//2391 -f 2458//2458 2391//2391 2459//2459 -f 2391//2391 2392//2392 2459//2459 -f 2459//2459 2392//2392 2393//2393 -f 2459//2459 2393//2393 2460//2460 -f 2393//2393 2394//2394 2460//2460 -f 2460//2460 2394//2394 2409//2409 -f 2460//2460 2409//2409 2461//2461 -f 2461//2461 2409//2409 2408//2408 -f 2461//2461 2408//2408 2462//2462 -f 2408//2408 2407//2407 2462//2462 -f 2462//2462 2407//2407 2406//2406 -f 2462//2462 2406//2406 2463//2463 -f 2406//2406 2405//2405 2463//2463 -f 2463//2463 2405//2405 2404//2404 -f 2463//2463 2404//2404 2464//2464 -f 2404//2404 2403//2403 2464//2464 -f 2464//2464 2403//2403 2402//2402 -f 2464//2464 2402//2402 2465//2465 -f 2465//2465 2402//2402 2401//2401 -f 2465//2465 2401//2401 2466//2466 -f 2401//2401 2400//2400 2466//2466 -f 2466//2466 2400//2400 2399//2399 -f 2466//2466 2399//2399 2467//2467 -f 2399//2399 2398//2398 2467//2467 -f 2467//2467 2398//2398 2397//2397 -f 2467//2467 2397//2397 2468//2468 -f 2468//2468 2397//2397 2396//2396 -f 2468//2468 2396//2396 2469//2469 -f 2396//2396 2395//2395 2469//2469 -f 2469//2469 2395//2395 2410//2410 -f 2469//2469 2410//2410 2470//2470 -f 2410//2410 2411//2411 2470//2470 -f 2470//2470 2411//2411 2412//2412 -f 2470//2470 2412//2412 2471//2471 -f 2471//2471 2412//2412 2413//2413 -f 2471//2471 2413//2413 2472//2472 -f 2413//2413 2414//2414 2472//2472 -f 2472//2472 2414//2414 2415//2415 -f 2472//2472 2415//2415 2473//2473 -f 2415//2415 2416//2416 2473//2473 -f 2473//2473 2416//2416 2417//2417 -f 2473//2473 2417//2417 2474//2474 -f 2417//2417 2418//2418 2474//2474 -f 2474//2474 2418//2418 2419//2419 -f 2474//2474 2419//2419 2475//2475 -f 2475//2475 2419//2419 2420//2420 -f 2475//2475 2420//2420 2476//2476 -f 2420//2420 2421//2421 2476//2476 -f 2476//2476 2421//2421 2422//2422 -f 2476//2476 2422//2422 2477//2477 -f 2422//2422 2423//2423 2477//2477 -f 2477//2477 2423//2423 2424//2424 -f 2477//2477 2424//2424 2478//2478 -f 2478//2478 2424//2424 2425//2425 -f 2478//2478 2425//2425 2479//2479 -f 2425//2425 2426//2426 2479//2479 -f 2479//2479 2426//2426 2427//2427 -f 2479//2479 2427//2427 2480//2480 -f 2480//2480 2427//2427 2428//2428 -f 2480//2480 2428//2428 2481//2481 -f 2428//2428 2429//2429 2481//2481 -f 2481//2481 2429//2429 2430//2430 -f 2481//2481 2430//2430 2482//2482 -f 2482//2482 2430//2430 2431//2431 -f 2482//2482 2431//2431 2483//2483 -f 2431//2431 2432//2432 2483//2483 -f 2483//2483 2432//2432 2433//2433 -f 2483//2483 2433//2433 2484//2484 -f 2433//2433 2434//2434 2484//2484 -f 2484//2484 2434//2434 2435//2435 -f 2484//2484 2435//2435 2485//2485 -f 2485//2485 2435//2435 2436//2436 -f 2485//2485 2436//2436 2486//2486 -f 2436//2436 2437//2437 2486//2486 -f 2486//2486 2437//2437 2438//2438 -f 2486//2486 2438//2438 2487//2487 -f 2487//2487 2438//2438 2439//2439 -f 2487//2487 2439//2439 2450//2450 -f 2450//2450 2439//2439 2440//2440 -f 2450//2450 2440//2440 2441//2441 -f 2486//2486 2488//2488 2485//2485 -f 2485//2485 2488//2488 2489//2489 -f 2485//2485 2489//2489 2484//2484 -f 2484//2484 2489//2489 2490//2490 -f 2484//2484 2490//2490 2483//2483 -f 2483//2483 2490//2490 2491//2491 -f 2483//2483 2491//2491 2482//2482 -f 2482//2482 2491//2491 2492//2492 -f 2482//2482 2492//2492 2481//2481 -f 2481//2481 2492//2492 2493//2493 -f 2481//2481 2493//2493 2480//2480 -f 2480//2480 2493//2493 2494//2494 -f 2480//2480 2494//2494 2479//2479 -f 2479//2479 2494//2494 2495//2495 -f 2479//2479 2495//2495 2478//2478 -f 2478//2478 2495//2495 2496//2496 -f 2478//2478 2496//2496 2477//2477 -f 2477//2477 2496//2496 2497//2497 -f 2477//2477 2497//2497 2476//2476 -f 2476//2476 2497//2497 2498//2498 -f 2476//2476 2498//2498 2475//2475 -f 2475//2475 2498//2498 2499//2499 -f 2475//2475 2499//2499 2474//2474 -f 2474//2474 2499//2499 2500//2500 -f 2474//2474 2500//2500 2473//2473 -f 2473//2473 2500//2500 2501//2501 -f 2473//2473 2501//2501 2472//2472 -f 2472//2472 2501//2501 2502//2502 -f 2472//2472 2502//2502 2471//2471 -f 2471//2471 2502//2502 2503//2503 -f 2471//2471 2503//2503 2470//2470 -f 2470//2470 2503//2503 2504//2504 -f 2470//2470 2504//2504 2469//2469 -f 2469//2469 2504//2504 2505//2505 -f 2469//2469 2505//2505 2468//2468 -f 2468//2468 2505//2505 2506//2506 -f 2468//2468 2506//2506 2467//2467 -f 2467//2467 2506//2506 2507//2507 -f 2467//2467 2507//2507 2466//2466 -f 2466//2466 2507//2507 2508//2508 -f 2466//2466 2508//2508 2465//2465 -f 2465//2465 2508//2508 2509//2509 -f 2465//2465 2509//2509 2464//2464 -f 2464//2464 2509//2509 2510//2510 -f 2464//2464 2510//2510 2463//2463 -f 2463//2463 2510//2510 2511//2511 -f 2463//2463 2511//2511 2462//2462 -f 2462//2462 2511//2511 2512//2512 -f 2462//2462 2512//2512 2461//2461 -f 2461//2461 2512//2512 2513//2513 -f 2461//2461 2513//2513 2460//2460 -f 2460//2460 2513//2513 2514//2514 -f 2460//2460 2514//2514 2459//2459 -f 2459//2459 2514//2514 2515//2515 -f 2459//2459 2515//2515 2458//2458 -f 2458//2458 2515//2515 2516//2516 -f 2458//2458 2516//2516 2457//2457 -f 2457//2457 2516//2516 2517//2517 -f 2457//2457 2517//2517 2456//2456 -f 2456//2456 2517//2517 2518//2518 -f 2456//2456 2518//2518 2455//2455 -f 2455//2455 2518//2518 2519//2519 -f 2455//2455 2519//2519 2454//2454 -f 2454//2454 2519//2519 2520//2520 -f 2454//2454 2520//2520 2453//2453 -f 2453//2453 2520//2520 2521//2521 -f 2453//2453 2521//2521 2452//2452 -f 2452//2452 2521//2521 2522//2522 -f 2452//2452 2522//2522 2451//2451 -f 2451//2451 2522//2522 2523//2523 -f 2451//2451 2523//2523 2450//2450 -f 2450//2450 2523//2523 2524//2524 -f 2450//2450 2524//2524 2487//2487 -f 2487//2487 2524//2524 2525//2525 -f 2487//2487 2525//2525 2486//2486 -f 2486//2486 2525//2525 2488//2488 -f 2488//2488 2526//2526 2489//2489 -f 2489//2489 2526//2526 2527//2527 -f 2489//2489 2527//2527 2490//2490 -f 2490//2490 2527//2527 2528//2528 -f 2490//2490 2528//2528 2491//2491 -f 2491//2491 2528//2528 2529//2529 -f 2491//2491 2529//2529 2492//2492 -f 2492//2492 2529//2529 2530//2530 -f 2492//2492 2530//2530 2493//2493 -f 2493//2493 2530//2530 2531//2531 -f 2493//2493 2531//2531 2494//2494 -f 2494//2494 2531//2531 2532//2532 -f 2494//2494 2532//2532 2495//2495 -f 2495//2495 2532//2532 2533//2533 -f 2495//2495 2533//2533 2496//2496 -f 2496//2496 2533//2533 2534//2534 -f 2496//2496 2534//2534 2497//2497 -f 2497//2497 2534//2534 2535//2535 -f 2497//2497 2535//2535 2498//2498 -f 2498//2498 2535//2535 2536//2536 -f 2498//2498 2536//2536 2499//2499 -f 2499//2499 2536//2536 2537//2537 -f 2499//2499 2537//2537 2500//2500 -f 2500//2500 2537//2537 2538//2538 -f 2500//2500 2538//2538 2501//2501 -f 2501//2501 2538//2538 2539//2539 -f 2501//2501 2539//2539 2502//2502 -f 2502//2502 2539//2539 2540//2540 -f 2502//2502 2540//2540 2503//2503 -f 2503//2503 2540//2540 2541//2541 -f 2503//2503 2541//2541 2504//2504 -f 2504//2504 2541//2541 2542//2542 -f 2504//2504 2542//2542 2505//2505 -f 2505//2505 2542//2542 2543//2543 -f 2505//2505 2543//2543 2506//2506 -f 2506//2506 2543//2543 2544//2544 -f 2506//2506 2544//2544 2507//2507 -f 2507//2507 2544//2544 2545//2545 -f 2507//2507 2545//2545 2508//2508 -f 2508//2508 2545//2545 2546//2546 -f 2508//2508 2546//2546 2509//2509 -f 2509//2509 2546//2546 2547//2547 -f 2509//2509 2547//2547 2510//2510 -f 2510//2510 2547//2547 2548//2548 -f 2510//2510 2548//2548 2511//2511 -f 2511//2511 2548//2548 2549//2549 -f 2511//2511 2549//2549 2512//2512 -f 2512//2512 2549//2549 2550//2550 -f 2512//2512 2550//2550 2513//2513 -f 2513//2513 2550//2550 2551//2551 -f 2513//2513 2551//2551 2514//2514 -f 2514//2514 2551//2551 2552//2552 -f 2514//2514 2552//2552 2515//2515 -f 2515//2515 2552//2552 2553//2553 -f 2515//2515 2553//2553 2516//2516 -f 2516//2516 2553//2553 2554//2554 -f 2516//2516 2554//2554 2517//2517 -f 2517//2517 2554//2554 2555//2555 -f 2517//2517 2555//2555 2518//2518 -f 2518//2518 2555//2555 2556//2556 -f 2518//2518 2556//2556 2519//2519 -f 2519//2519 2556//2556 2557//2557 -f 2519//2519 2557//2557 2520//2520 -f 2520//2520 2557//2557 2558//2558 -f 2520//2520 2558//2558 2521//2521 -f 2521//2521 2558//2558 2559//2559 -f 2521//2521 2559//2559 2522//2522 -f 2522//2522 2559//2559 2560//2560 -f 2522//2522 2560//2560 2523//2523 -f 2523//2523 2560//2560 2561//2561 -f 2523//2523 2561//2561 2524//2524 -f 2524//2524 2561//2561 2562//2562 -f 2524//2524 2562//2562 2525//2525 -f 2525//2525 2562//2562 2563//2563 -f 2525//2525 2563//2563 2488//2488 -f 2488//2488 2563//2563 2526//2526 -f 2526//2526 2564//2564 2527//2527 -f 2527//2527 2564//2564 2565//2565 -f 2527//2527 2565//2565 2528//2528 -f 2528//2528 2565//2565 2566//2566 -f 2528//2528 2566//2566 2529//2529 -f 2529//2529 2566//2566 2567//2567 -f 2529//2529 2567//2567 2530//2530 -f 2530//2530 2567//2567 2568//2568 -f 2530//2530 2568//2568 2531//2531 -f 2531//2531 2568//2568 2569//2569 -f 2531//2531 2569//2569 2532//2532 -f 2532//2532 2569//2569 2570//2570 -f 2532//2532 2570//2570 2533//2533 -f 2533//2533 2570//2570 2571//2571 -f 2533//2533 2571//2571 2534//2534 -f 2534//2534 2571//2571 2572//2572 -f 2534//2534 2572//2572 2535//2535 -f 2535//2535 2572//2572 2573//2573 -f 2535//2535 2573//2573 2536//2536 -f 2536//2536 2573//2573 2574//2574 -f 2536//2536 2574//2574 2537//2537 -f 2537//2537 2574//2574 2575//2575 -f 2537//2537 2575//2575 2538//2538 -f 2538//2538 2575//2575 2576//2576 -f 2538//2538 2576//2576 2539//2539 -f 2539//2539 2576//2576 2577//2577 -f 2539//2539 2577//2577 2540//2540 -f 2540//2540 2577//2577 2578//2578 -f 2540//2540 2578//2578 2541//2541 -f 2541//2541 2578//2578 2579//2579 -f 2541//2541 2579//2579 2542//2542 -f 2542//2542 2579//2579 2580//2580 -f 2542//2542 2580//2580 2543//2543 -f 2543//2543 2580//2580 2581//2581 -f 2543//2543 2581//2581 2544//2544 -f 2544//2544 2581//2581 2582//2582 -f 2544//2544 2582//2582 2545//2545 -f 2545//2545 2582//2582 2583//2583 -f 2545//2545 2583//2583 2546//2546 -f 2546//2546 2583//2583 2584//2584 -f 2546//2546 2584//2584 2547//2547 -f 2547//2547 2584//2584 2585//2585 -f 2547//2547 2585//2585 2548//2548 -f 2548//2548 2585//2585 2586//2586 -f 2548//2548 2586//2586 2549//2549 -f 2549//2549 2586//2586 2587//2587 -f 2549//2549 2587//2587 2550//2550 -f 2550//2550 2587//2587 2588//2588 -f 2550//2550 2588//2588 2551//2551 -f 2551//2551 2588//2588 2589//2589 -f 2551//2551 2589//2589 2552//2552 -f 2552//2552 2589//2589 2590//2590 -f 2552//2552 2590//2590 2553//2553 -f 2553//2553 2590//2590 2591//2591 -f 2553//2553 2591//2591 2554//2554 -f 2554//2554 2591//2591 2592//2592 -f 2554//2554 2592//2592 2555//2555 -f 2555//2555 2592//2592 2593//2593 -f 2555//2555 2593//2593 2556//2556 -f 2556//2556 2593//2593 2594//2594 -f 2556//2556 2594//2594 2557//2557 -f 2557//2557 2594//2594 2595//2595 -f 2557//2557 2595//2595 2558//2558 -f 2558//2558 2595//2595 2596//2596 -f 2558//2558 2596//2596 2559//2559 -f 2559//2559 2596//2596 2597//2597 -f 2559//2559 2597//2597 2560//2560 -f 2560//2560 2597//2597 2598//2598 -f 2560//2560 2598//2598 2561//2561 -f 2561//2561 2598//2598 2599//2599 -f 2561//2561 2599//2599 2562//2562 -f 2562//2562 2599//2599 2600//2600 -f 2562//2562 2600//2600 2563//2563 -f 2563//2563 2600//2600 2601//2601 -f 2563//2563 2601//2601 2526//2526 -f 2526//2526 2601//2601 2564//2564 -f 2564//2564 2602//2602 2565//2565 -f 2565//2565 2602//2602 2603//2603 -f 2565//2565 2603//2603 2566//2566 -f 2566//2566 2603//2603 2604//2604 -f 2566//2566 2604//2604 2567//2567 -f 2567//2567 2604//2604 2605//2605 -f 2567//2567 2605//2605 2568//2568 -f 2568//2568 2605//2605 2606//2606 -f 2568//2568 2606//2606 2569//2569 -f 2569//2569 2606//2606 2607//2607 -f 2569//2569 2607//2607 2570//2570 -f 2570//2570 2607//2607 2608//2608 -f 2570//2570 2608//2608 2571//2571 -f 2571//2571 2608//2608 2609//2609 -f 2571//2571 2609//2609 2572//2572 -f 2572//2572 2609//2609 2610//2610 -f 2572//2572 2610//2610 2573//2573 -f 2573//2573 2610//2610 2611//2611 -f 2573//2573 2611//2611 2574//2574 -f 2574//2574 2611//2611 2612//2612 -f 2574//2574 2612//2612 2575//2575 -f 2575//2575 2612//2612 2613//2613 -f 2575//2575 2613//2613 2576//2576 -f 2576//2576 2613//2613 2614//2614 -f 2576//2576 2614//2614 2577//2577 -f 2577//2577 2614//2614 2615//2615 -f 2577//2577 2615//2615 2578//2578 -f 2578//2578 2615//2615 2616//2616 -f 2578//2578 2616//2616 2579//2579 -f 2579//2579 2616//2616 2617//2617 -f 2579//2579 2617//2617 2580//2580 -f 2580//2580 2617//2617 2618//2618 -f 2580//2580 2618//2618 2581//2581 -f 2581//2581 2618//2618 2619//2619 -f 2581//2581 2619//2619 2582//2582 -f 2582//2582 2619//2619 2620//2620 -f 2582//2582 2620//2620 2583//2583 -f 2583//2583 2620//2620 2621//2621 -f 2583//2583 2621//2621 2584//2584 -f 2584//2584 2621//2621 2622//2622 -f 2584//2584 2622//2622 2585//2585 -f 2585//2585 2622//2622 2623//2623 -f 2585//2585 2623//2623 2586//2586 -f 2586//2586 2623//2623 2624//2624 -f 2586//2586 2624//2624 2587//2587 -f 2587//2587 2624//2624 2625//2625 -f 2587//2587 2625//2625 2588//2588 -f 2588//2588 2625//2625 2626//2626 -f 2588//2588 2626//2626 2589//2589 -f 2589//2589 2626//2626 2627//2627 -f 2589//2589 2627//2627 2590//2590 -f 2590//2590 2627//2627 2628//2628 -f 2590//2590 2628//2628 2591//2591 -f 2591//2591 2628//2628 2629//2629 -f 2591//2591 2629//2629 2592//2592 -f 2592//2592 2629//2629 2630//2630 -f 2592//2592 2630//2630 2593//2593 -f 2593//2593 2630//2630 2631//2631 -f 2593//2593 2631//2631 2594//2594 -f 2594//2594 2631//2631 2632//2632 -f 2594//2594 2632//2632 2595//2595 -f 2595//2595 2632//2632 2633//2633 -f 2595//2595 2633//2633 2596//2596 -f 2596//2596 2633//2633 2634//2634 -f 2596//2596 2634//2634 2597//2597 -f 2597//2597 2634//2634 2635//2635 -f 2597//2597 2635//2635 2598//2598 -f 2598//2598 2635//2635 2636//2636 -f 2598//2598 2636//2636 2599//2599 -f 2599//2599 2636//2636 2637//2637 -f 2599//2599 2637//2637 2600//2600 -f 2600//2600 2637//2637 2638//2638 -f 2600//2600 2638//2638 2601//2601 -f 2601//2601 2638//2638 2639//2639 -f 2601//2601 2639//2639 2564//2564 -f 2564//2564 2639//2639 2602//2602 -f 2622//2622 2621//2621 2640//2640 -f 2640//2640 2621//2621 2641//2641 -f 2609//2609 2642//2642 2643//2643 -f 2613//2613 2644//2644 2614//2614 -f 2614//2614 2644//2644 2645//2645 -f 2614//2614 2645//2645 2615//2615 -f 2646//2646 2624//2624 2640//2640 -f 2640//2640 2624//2624 2623//2623 -f 2640//2640 2623//2623 2622//2622 -f 2647//2647 2626//2626 2646//2646 -f 2646//2646 2626//2626 2625//2625 -f 2646//2646 2625//2625 2624//2624 -f 2630//2630 2629//2629 2648//2648 -f 2648//2648 2629//2629 2628//2628 -f 2648//2648 2628//2628 2647//2647 -f 2647//2647 2628//2628 2627//2627 -f 2647//2647 2627//2627 2626//2626 -f 2630//2630 2648//2648 2631//2631 -f 2631//2631 2648//2648 2649//2649 -f 2631//2631 2649//2649 2632//2632 -f 2604//2604 2650//2650 2605//2605 -f 2605//2605 2650//2650 2651//2651 -f 2609//2609 2608//2608 2642//2642 -f 2642//2642 2608//2608 2607//2607 -f 2642//2642 2607//2607 2651//2651 -f 2651//2651 2607//2607 2606//2606 -f 2651//2651 2606//2606 2605//2605 -f 2613//2613 2612//2612 2644//2644 -f 2644//2644 2612//2612 2611//2611 -f 2644//2644 2611//2611 2643//2643 -f 2643//2643 2611//2611 2610//2610 -f 2643//2643 2610//2610 2609//2609 -f 2615//2615 2645//2645 2616//2616 -f 2616//2616 2645//2645 2652//2652 -f 2616//2616 2652//2652 2617//2617 -f 2621//2621 2620//2620 2641//2641 -f 2641//2641 2620//2620 2619//2619 -f 2641//2641 2619//2619 2652//2652 -f 2652//2652 2619//2619 2618//2618 -f 2652//2652 2618//2618 2617//2617 -f 2632//2632 2649//2649 2633//2633 -f 2633//2633 2649//2649 2653//2653 -f 2633//2633 2653//2653 2634//2634 -f 2604//2604 2603//2603 2650//2650 -f 2650//2650 2603//2603 2602//2602 -f 2650//2650 2602//2602 2654//2654 -f 2602//2602 2639//2639 2654//2654 -f 2654//2654 2639//2639 2638//2638 -f 2654//2654 2638//2638 2655//2655 -f 2638//2638 2637//2637 2655//2655 -f 2655//2655 2637//2637 2636//2636 -f 2655//2655 2636//2636 2653//2653 -f 2653//2653 2636//2636 2635//2635 -f 2653//2653 2635//2635 2634//2634 -f 2646//2646 2640//2640 2656//2656 -f 2656//2656 2657//2657 2646//2646 -f 2646//2646 2657//2657 2658//2658 -f 2646//2646 2658//2658 2647//2647 -f 2658//2658 2659//2659 2647//2647 -f 2647//2647 2659//2659 2660//2660 -f 2647//2647 2660//2660 2648//2648 -f 2660//2660 2661//2661 2648//2648 -f 2648//2648 2661//2661 2662//2662 -f 2648//2648 2662//2662 2649//2649 -f 2662//2662 2663//2663 2649//2649 -f 2649//2649 2663//2663 2664//2664 -f 2649//2649 2664//2664 2653//2653 -f 2664//2664 2665//2665 2653//2653 -f 2653//2653 2665//2665 2666//2666 -f 2653//2653 2666//2666 2655//2655 -f 2666//2666 2667//2667 2655//2655 -f 2655//2655 2667//2667 2668//2668 -f 2655//2655 2668//2668 2654//2654 -f 2654//2654 2668//2668 2669//2669 -f 2654//2654 2669//2669 2650//2650 -f 2669//2669 2670//2670 2650//2650 -f 2650//2650 2670//2670 2671//2671 -f 2650//2650 2671//2671 2651//2651 -f 2671//2671 2672//2672 2651//2651 -f 2651//2651 2672//2672 2673//2673 -f 2651//2651 2673//2673 2642//2642 -f 2673//2673 2674//2674 2642//2642 -f 2642//2642 2674//2674 2675//2675 -f 2642//2642 2675//2675 2643//2643 -f 2675//2675 2676//2676 2643//2643 -f 2643//2643 2676//2676 2677//2677 -f 2643//2643 2677//2677 2644//2644 -f 2677//2677 2678//2678 2644//2644 -f 2644//2644 2678//2678 2679//2679 -f 2644//2644 2679//2679 2645//2645 -f 2679//2679 2680//2680 2645//2645 -f 2645//2645 2680//2680 2681//2681 -f 2645//2645 2681//2681 2652//2652 -f 2681//2681 2682//2682 2652//2652 -f 2652//2652 2682//2682 2683//2683 -f 2652//2652 2683//2683 2641//2641 -f 2641//2641 2683//2683 2684//2684 -f 2641//2641 2684//2684 2640//2640 -f 2640//2640 2684//2684 2685//2685 -f 2640//2640 2685//2685 2656//2656 -f 2668//2668 2686//2686 2669//2669 -f 2669//2669 2686//2686 2687//2687 -f 2669//2669 2687//2687 2670//2670 -f 2670//2670 2687//2687 2688//2688 -f 2670//2670 2688//2688 2671//2671 -f 2671//2671 2688//2688 2689//2689 -f 2671//2671 2689//2689 2672//2672 -f 2672//2672 2689//2689 2690//2690 -f 2672//2672 2690//2690 2673//2673 -f 2673//2673 2690//2690 2691//2691 -f 2673//2673 2691//2691 2674//2674 -f 2674//2674 2691//2691 2692//2692 -f 2674//2674 2692//2692 2675//2675 -f 2675//2675 2692//2692 2693//2693 -f 2675//2675 2693//2693 2676//2676 -f 2676//2676 2693//2693 2694//2694 -f 2676//2676 2694//2694 2677//2677 -f 2677//2677 2694//2694 2695//2695 -f 2677//2677 2695//2695 2678//2678 -f 2678//2678 2695//2695 2696//2696 -f 2678//2678 2696//2696 2679//2679 -f 2679//2679 2696//2696 2697//2697 -f 2679//2679 2697//2697 2680//2680 -f 2680//2680 2697//2697 2698//2698 -f 2680//2680 2698//2698 2681//2681 -f 2681//2681 2698//2698 2699//2699 -f 2681//2681 2699//2699 2682//2682 -f 2682//2682 2699//2699 2700//2700 -f 2682//2682 2700//2700 2683//2683 -f 2683//2683 2700//2700 2701//2701 -f 2683//2683 2701//2701 2684//2684 -f 2684//2684 2701//2701 2702//2702 -f 2684//2684 2702//2702 2685//2685 -f 2685//2685 2702//2702 2703//2703 -f 2685//2685 2703//2703 2656//2656 -f 2656//2656 2703//2703 2704//2704 -f 2656//2656 2704//2704 2657//2657 -f 2657//2657 2704//2704 2705//2705 -f 2657//2657 2705//2705 2658//2658 -f 2658//2658 2705//2705 2706//2706 -f 2658//2658 2706//2706 2659//2659 -f 2659//2659 2706//2706 2707//2707 -f 2659//2659 2707//2707 2660//2660 -f 2660//2660 2707//2707 2708//2708 -f 2660//2660 2708//2708 2661//2661 -f 2661//2661 2708//2708 2709//2709 -f 2661//2661 2709//2709 2662//2662 -f 2662//2662 2709//2709 2710//2710 -f 2662//2662 2710//2710 2663//2663 -f 2663//2663 2710//2710 2711//2711 -f 2663//2663 2711//2711 2664//2664 -f 2664//2664 2711//2711 2712//2712 -f 2664//2664 2712//2712 2665//2665 -f 2665//2665 2712//2712 2713//2713 -f 2665//2665 2713//2713 2666//2666 -f 2666//2666 2713//2713 2714//2714 -f 2666//2666 2714//2714 2667//2667 -f 2667//2667 2714//2714 2715//2715 -f 2667//2667 2715//2715 2668//2668 -f 2668//2668 2715//2715 2686//2686 -f 2716//2716 2717//2717 2715//2715 -f 2715//2715 2714//2714 2716//2716 -f 2716//2716 2714//2714 2713//2713 -f 2716//2716 2713//2713 2718//2718 -f 2713//2713 2712//2712 2718//2718 -f 2718//2718 2712//2712 2711//2711 -f 2718//2718 2711//2711 2719//2719 -f 2711//2711 2710//2710 2719//2719 -f 2719//2719 2710//2710 2709//2709 -f 2719//2719 2709//2709 2720//2720 -f 2709//2709 2708//2708 2720//2720 -f 2720//2720 2708//2708 2707//2707 -f 2720//2720 2707//2707 2721//2721 -f 2707//2707 2706//2706 2721//2721 -f 2721//2721 2706//2706 2705//2705 -f 2721//2721 2705//2705 2722//2722 -f 2705//2705 2704//2704 2722//2722 -f 2722//2722 2704//2704 2703//2703 -f 2722//2722 2703//2703 2723//2723 -f 2723//2723 2703//2703 2702//2702 -f 2723//2723 2702//2702 2724//2724 -f 2702//2702 2701//2701 2724//2724 -f 2724//2724 2701//2701 2700//2700 -f 2724//2724 2700//2700 2725//2725 -f 2700//2700 2699//2699 2725//2725 -f 2725//2725 2699//2699 2698//2698 -f 2725//2725 2698//2698 2726//2726 -f 2698//2698 2697//2697 2726//2726 -f 2726//2726 2697//2697 2696//2696 -f 2726//2726 2696//2696 2727//2727 -f 2696//2696 2695//2695 2727//2727 -f 2727//2727 2695//2695 2694//2694 -f 2727//2727 2694//2694 2728//2728 -f 2694//2694 2693//2693 2728//2728 -f 2728//2728 2693//2693 2692//2692 -f 2728//2728 2692//2692 2729//2729 -f 2692//2692 2691//2691 2729//2729 -f 2729//2729 2691//2691 2690//2690 -f 2729//2729 2690//2690 2730//2730 -f 2690//2690 2689//2689 2730//2730 -f 2730//2730 2689//2689 2688//2688 -f 2730//2730 2688//2688 2731//2731 -f 2731//2731 2688//2688 2687//2687 -f 2731//2731 2687//2687 2717//2717 -f 2717//2717 2687//2687 2686//2686 -f 2717//2717 2686//2686 2715//2715 -f 2718//2718 2732//2732 2716//2716 -f 2716//2716 2732//2732 2733//2733 -f 2716//2716 2733//2733 2717//2717 -f 2717//2717 2733//2733 2734//2734 -f 2717//2717 2734//2734 2731//2731 -f 2731//2731 2734//2734 2735//2735 -f 2731//2731 2735//2735 2730//2730 -f 2722//2722 2736//2736 2721//2721 -f 2721//2721 2736//2736 2737//2737 -f 2721//2721 2737//2737 2720//2720 -f 2720//2720 2737//2737 2738//2738 -f 2720//2720 2738//2738 2719//2719 -f 2719//2719 2738//2738 2739//2739 -f 2719//2719 2739//2739 2718//2718 -f 2718//2718 2739//2739 2740//2740 -f 2718//2718 2740//2740 2732//2732 -f 2726//2726 2741//2741 2725//2725 -f 2725//2725 2741//2741 2742//2742 -f 2725//2725 2742//2742 2724//2724 -f 2724//2724 2742//2742 2743//2743 -f 2724//2724 2743//2743 2723//2723 -f 2723//2723 2743//2743 2744//2744 -f 2723//2723 2744//2744 2722//2722 -f 2722//2722 2744//2744 2745//2745 -f 2722//2722 2745//2745 2736//2736 -f 2735//2735 2746//2746 2730//2730 -f 2730//2730 2746//2746 2747//2747 -f 2730//2730 2747//2747 2729//2729 -f 2729//2729 2747//2747 2748//2748 -f 2729//2729 2748//2748 2728//2728 -f 2728//2728 2748//2748 2749//2749 -f 2728//2728 2749//2749 2727//2727 -f 2727//2727 2749//2749 2750//2750 -f 2727//2727 2750//2750 2726//2726 -f 2726//2726 2750//2750 2751//2751 -f 2726//2726 2751//2751 2741//2741 -f 2746//2746 2752//2752 2747//2747 -f 2747//2747 2752//2752 2753//2753 -f 2747//2747 2753//2753 2748//2748 -f 2748//2748 2753//2753 2754//2754 -f 2748//2748 2754//2754 2749//2749 -f 2749//2749 2754//2754 2755//2755 -f 2749//2749 2755//2755 2750//2750 -f 2750//2750 2755//2755 2756//2756 -f 2750//2750 2756//2756 2751//2751 -f 2751//2751 2756//2756 2757//2757 -f 2751//2751 2757//2757 2741//2741 -f 2741//2741 2757//2757 2758//2758 -f 2741//2741 2758//2758 2742//2742 -f 2742//2742 2758//2758 2759//2759 -f 2742//2742 2759//2759 2743//2743 -f 2743//2743 2759//2759 2760//2760 -f 2743//2743 2760//2760 2744//2744 -f 2744//2744 2760//2760 2761//2761 -f 2744//2744 2761//2761 2745//2745 -f 2745//2745 2761//2761 2762//2762 -f 2745//2745 2762//2762 2736//2736 -f 2736//2736 2762//2762 2763//2763 -f 2736//2736 2763//2763 2737//2737 -f 2737//2737 2763//2763 2764//2764 -f 2737//2737 2764//2764 2738//2738 -f 2738//2738 2764//2764 2765//2765 -f 2738//2738 2765//2765 2739//2739 -f 2739//2739 2765//2765 2766//2766 -f 2739//2739 2766//2766 2740//2740 -f 2740//2740 2766//2766 2767//2767 -f 2740//2740 2767//2767 2732//2732 -f 2732//2732 2767//2767 2768//2768 -f 2732//2732 2768//2768 2733//2733 -f 2733//2733 2768//2768 2769//2769 -f 2733//2733 2769//2769 2734//2734 -f 2734//2734 2769//2769 2770//2770 -f 2734//2734 2770//2770 2735//2735 -f 2735//2735 2770//2770 2771//2771 -f 2735//2735 2771//2771 2746//2746 -f 2746//2746 2771//2771 2752//2752 -f 2772//2772 2752//2752 2771//2771 -f 2772//2772 2773//2773 2752//2752 -f 2752//2752 2773//2773 2774//2774 -f 2752//2752 2774//2774 2753//2753 -f 2774//2774 2775//2775 2753//2753 -f 2753//2753 2775//2775 2776//2776 -f 2753//2753 2776//2776 2754//2754 -f 2776//2776 2777//2777 2754//2754 -f 2754//2754 2777//2777 2778//2778 -f 2754//2754 2778//2778 2755//2755 -f 2778//2778 2779//2779 2755//2755 -f 2755//2755 2779//2779 2780//2780 -f 2755//2755 2780//2780 2756//2756 -f 2780//2780 2781//2781 2756//2756 -f 2756//2756 2781//2781 2782//2782 -f 2756//2756 2782//2782 2757//2757 -f 2782//2782 2783//2783 2757//2757 -f 2757//2757 2783//2783 2784//2784 -f 2757//2757 2784//2784 2758//2758 -f 2784//2784 2785//2785 2758//2758 -f 2758//2758 2785//2785 2786//2786 -f 2758//2758 2786//2786 2759//2759 -f 2786//2786 2787//2787 2759//2759 -f 2759//2759 2787//2787 2788//2788 -f 2759//2759 2788//2788 2760//2760 -f 2788//2788 2789//2789 2760//2760 -f 2760//2760 2789//2789 2790//2790 -f 2760//2760 2790//2790 2761//2761 -f 2790//2790 2791//2791 2761//2761 -f 2761//2761 2791//2791 2792//2792 -f 2761//2761 2792//2792 2762//2762 -f 2792//2792 2793//2793 2762//2762 -f 2762//2762 2793//2793 2794//2794 -f 2762//2762 2794//2794 2763//2763 -f 2794//2794 2795//2795 2763//2763 -f 2763//2763 2795//2795 2796//2796 -f 2763//2763 2796//2796 2764//2764 -f 2796//2796 2797//2797 2764//2764 -f 2764//2764 2797//2797 2798//2798 -f 2764//2764 2798//2798 2765//2765 -f 2798//2798 2799//2799 2765//2765 -f 2765//2765 2799//2799 2800//2800 -f 2765//2765 2800//2800 2766//2766 -f 2800//2800 2801//2801 2766//2766 -f 2766//2766 2801//2801 2802//2802 -f 2766//2766 2802//2802 2767//2767 -f 2802//2802 2803//2803 2767//2767 -f 2767//2767 2803//2803 2804//2804 -f 2767//2767 2804//2804 2768//2768 -f 2804//2804 2805//2805 2768//2768 -f 2768//2768 2805//2805 2806//2806 -f 2768//2768 2806//2806 2769//2769 -f 2806//2806 2807//2807 2769//2769 -f 2769//2769 2807//2807 2808//2808 -f 2769//2769 2808//2808 2770//2770 -f 2808//2808 2809//2809 2770//2770 -f 2770//2770 2809//2809 2810//2810 -f 2770//2770 2810//2810 2771//2771 -f 2771//2771 2810//2810 2811//2811 -f 2771//2771 2811//2811 2772//2772 -f 2812//2812 2813//2813 2809//2809 -f 2809//2809 2808//2808 2812//2812 -f 2812//2812 2808//2808 2807//2807 -f 2812//2812 2807//2807 2814//2814 -f 2807//2807 2806//2806 2814//2814 -f 2814//2814 2806//2806 2805//2805 -f 2814//2814 2805//2805 2815//2815 -f 2805//2805 2804//2804 2815//2815 -f 2815//2815 2804//2804 2803//2803 -f 2815//2815 2803//2803 2816//2816 -f 2803//2803 2802//2802 2816//2816 -f 2816//2816 2802//2802 2801//2801 -f 2816//2816 2801//2801 2817//2817 -f 2801//2801 2800//2800 2817//2817 -f 2817//2817 2800//2800 2799//2799 -f 2817//2817 2799//2799 2818//2818 -f 2799//2799 2798//2798 2818//2818 -f 2818//2818 2798//2798 2797//2797 -f 2818//2818 2797//2797 2819//2819 -f 2797//2797 2796//2796 2819//2819 -f 2819//2819 2796//2796 2795//2795 -f 2819//2819 2795//2795 2820//2820 -f 2795//2795 2794//2794 2820//2820 -f 2820//2820 2794//2794 2793//2793 -f 2820//2820 2793//2793 2821//2821 -f 2821//2821 2793//2793 2792//2792 -f 2821//2821 2792//2792 2822//2822 -f 2792//2792 2791//2791 2822//2822 -f 2822//2822 2791//2791 2790//2790 -f 2822//2822 2790//2790 2823//2823 -f 2790//2790 2789//2789 2823//2823 -f 2823//2823 2789//2789 2788//2788 -f 2823//2823 2788//2788 2824//2824 -f 2788//2788 2787//2787 2824//2824 -f 2824//2824 2787//2787 2786//2786 -f 2824//2824 2786//2786 2825//2825 -f 2786//2786 2785//2785 2825//2825 -f 2825//2825 2785//2785 2784//2784 -f 2825//2825 2784//2784 2826//2826 -f 2784//2784 2783//2783 2826//2826 -f 2826//2826 2783//2783 2782//2782 -f 2826//2826 2782//2782 2827//2827 -f 2782//2782 2781//2781 2827//2827 -f 2827//2827 2781//2781 2780//2780 -f 2827//2827 2780//2780 2828//2828 -f 2780//2780 2779//2779 2828//2828 -f 2828//2828 2779//2779 2778//2778 -f 2828//2828 2778//2778 2829//2829 -f 2778//2778 2777//2777 2829//2829 -f 2829//2829 2777//2777 2776//2776 -f 2829//2829 2776//2776 2830//2830 -f 2776//2776 2775//2775 2830//2830 -f 2830//2830 2775//2775 2774//2774 -f 2830//2830 2774//2774 2831//2831 -f 2774//2774 2773//2773 2831//2831 -f 2831//2831 2773//2773 2772//2772 -f 2831//2831 2772//2772 2832//2832 -f 2832//2832 2772//2772 2811//2811 -f 2832//2832 2811//2811 2813//2813 -f 2813//2813 2811//2811 2810//2810 -f 2813//2813 2810//2810 2809//2809 -f 2814//2814 2833//2833 2812//2812 -f 2812//2812 2833//2833 2834//2834 -f 2812//2812 2834//2834 2813//2813 -f 2834//2834 2835//2835 2813//2813 -f 2813//2813 2835//2835 2836//2836 -f 2813//2813 2836//2836 2832//2832 -f 2818//2818 2837//2837 2817//2817 -f 2817//2817 2837//2837 2838//2838 -f 2817//2817 2838//2838 2816//2816 -f 2838//2838 2839//2839 2816//2816 -f 2816//2816 2839//2839 2840//2840 -f 2816//2816 2840//2840 2815//2815 -f 2815//2815 2840//2840 2841//2841 -f 2815//2815 2841//2841 2814//2814 -f 2814//2814 2841//2841 2842//2842 -f 2814//2814 2842//2842 2833//2833 -f 2820//2820 2843//2843 2819//2819 -f 2819//2819 2843//2843 2844//2844 -f 2819//2819 2844//2844 2818//2818 -f 2818//2818 2844//2844 2845//2845 -f 2818//2818 2845//2845 2837//2837 -f 2822//2822 2846//2846 2821//2821 -f 2821//2821 2846//2846 2847//2847 -f 2821//2821 2847//2847 2820//2820 -f 2820//2820 2847//2847 2848//2848 -f 2820//2820 2848//2848 2843//2843 -f 2828//2828 2849//2849 2827//2827 -f 2827//2827 2849//2849 2850//2850 -f 2827//2827 2850//2850 2826//2826 -f 2830//2830 2851//2851 2829//2829 -f 2829//2829 2851//2851 2852//2852 -f 2829//2829 2852//2852 2828//2828 -f 2828//2828 2852//2852 2853//2853 -f 2828//2828 2853//2853 2849//2849 -f 2836//2836 2854//2854 2832//2832 -f 2832//2832 2854//2854 2855//2855 -f 2832//2832 2855//2855 2831//2831 -f 2831//2831 2855//2855 2856//2856 -f 2831//2831 2856//2856 2830//2830 -f 2830//2830 2856//2856 2857//2857 -f 2830//2830 2857//2857 2851//2851 -f 2824//2824 2858//2858 2823//2823 -f 2823//2823 2858//2858 2859//2859 -f 2823//2823 2859//2859 2822//2822 -f 2822//2822 2859//2859 2860//2860 -f 2822//2822 2860//2860 2846//2846 -f 2850//2850 2861//2861 2826//2826 -f 2826//2826 2861//2861 2862//2862 -f 2826//2826 2862//2862 2825//2825 -f 2825//2825 2862//2862 2863//2863 -f 2825//2825 2863//2863 2824//2824 -f 2824//2824 2863//2863 2864//2864 -f 2824//2824 2864//2864 2858//2858 -f 2865//2865 2860//2860 2866//2866 -f 2866//2866 2860//2860 2859//2859 -f 2866//2866 2859//2859 2867//2867 -f 2867//2867 2859//2859 2858//2858 -f 2867//2867 2858//2858 2868//2868 -f 2868//2868 2858//2858 2864//2864 -f 2868//2868 2864//2864 2869//2869 -f 2869//2869 2864//2864 2863//2863 -f 2869//2869 2863//2863 2870//2870 -f 2870//2870 2863//2863 2862//2862 -f 2870//2870 2862//2862 2871//2871 -f 2871//2871 2862//2862 2861//2861 -f 2871//2871 2861//2861 2872//2872 -f 2872//2872 2861//2861 2850//2850 -f 2872//2872 2850//2850 2873//2873 -f 2873//2873 2850//2850 2849//2849 -f 2873//2873 2849//2849 2874//2874 -f 2874//2874 2849//2849 2853//2853 -f 2874//2874 2853//2853 2875//2875 -f 2875//2875 2853//2853 2852//2852 -f 2875//2875 2852//2852 2876//2876 -f 2876//2876 2852//2852 2851//2851 -f 2876//2876 2851//2851 2877//2877 -f 2877//2877 2851//2851 2857//2857 -f 2877//2877 2857//2857 2878//2878 -f 2878//2878 2857//2857 2856//2856 -f 2878//2878 2856//2856 2879//2879 -f 2879//2879 2856//2856 2855//2855 -f 2879//2879 2855//2855 2880//2880 -f 2880//2880 2855//2855 2854//2854 -f 2880//2880 2854//2854 2881//2881 -f 2881//2881 2854//2854 2836//2836 -f 2881//2881 2836//2836 2882//2882 -f 2882//2882 2836//2836 2835//2835 -f 2882//2882 2835//2835 2883//2883 -f 2883//2883 2835//2835 2834//2834 -f 2883//2883 2834//2834 2884//2884 -f 2884//2884 2834//2834 2833//2833 -f 2884//2884 2833//2833 2885//2885 -f 2885//2885 2833//2833 2842//2842 -f 2885//2885 2842//2842 2886//2886 -f 2886//2886 2842//2842 2841//2841 -f 2886//2886 2841//2841 2887//2887 -f 2887//2887 2841//2841 2840//2840 -f 2887//2887 2840//2840 2888//2888 -f 2888//2888 2840//2840 2839//2839 -f 2888//2888 2839//2839 2889//2889 -f 2889//2889 2839//2839 2838//2838 -f 2889//2889 2838//2838 2890//2890 -f 2890//2890 2838//2838 2837//2837 -f 2890//2890 2837//2837 2891//2891 -f 2891//2891 2837//2837 2845//2845 -f 2891//2891 2845//2845 2892//2892 -f 2892//2892 2845//2845 2844//2844 -f 2892//2892 2844//2844 2893//2893 -f 2893//2893 2844//2844 2843//2843 -f 2893//2893 2843//2843 2894//2894 -f 2894//2894 2843//2843 2848//2848 -f 2894//2894 2848//2848 2895//2895 -f 2895//2895 2848//2848 2847//2847 -f 2895//2895 2847//2847 2896//2896 -f 2896//2896 2847//2847 2846//2846 -f 2896//2896 2846//2846 2865//2865 -f 2865//2865 2846//2846 2860//2860 -f 127//127 2881//2881 2882//2882 -f 2883//2883 123//123 2882//2882 -f 2882//2882 123//123 125//125 -f 2882//2882 125//125 127//127 -f 2884//2884 119//119 2883//2883 -f 2883//2883 119//119 121//121 -f 2883//2883 121//121 123//123 -f 2885//2885 115//115 2884//2884 -f 2884//2884 115//115 117//117 -f 2884//2884 117//117 119//119 -f 2886//2886 111//111 2885//2885 -f 2885//2885 111//111 113//113 -f 2885//2885 113//113 115//115 -f 2887//2887 107//107 2886//2886 -f 2886//2886 107//107 109//109 -f 2886//2886 109//109 111//111 -f 2888//2888 103//103 2887//2887 -f 2887//2887 103//103 105//105 -f 2887//2887 105//105 107//107 -f 2889//2889 99//99 2888//2888 -f 2888//2888 99//99 101//101 -f 2888//2888 101//101 103//103 -f 2890//2890 95//95 2889//2889 -f 2889//2889 95//95 97//97 -f 2889//2889 97//97 99//99 -f 2891//2891 91//91 2890//2890 -f 2890//2890 91//91 93//93 -f 2890//2890 93//93 95//95 -f 2892//2892 87//87 2891//2891 -f 2891//2891 87//87 89//89 -f 2891//2891 89//89 91//91 -f 2893//2893 83//83 2892//2892 -f 2892//2892 83//83 85//85 -f 2892//2892 85//85 87//87 -f 2894//2894 79//79 2893//2893 -f 2893//2893 79//79 81//81 -f 2893//2893 81//81 83//83 -f 2895//2895 75//75 2894//2894 -f 2894//2894 75//75 77//77 -f 2894//2894 77//77 79//79 -f 2896//2896 71//71 2895//2895 -f 2895//2895 71//71 73//73 -f 2895//2895 73//73 75//75 -f 2865//2865 67//67 2896//2896 -f 2896//2896 67//67 69//69 -f 2896//2896 69//69 71//71 -f 2866//2866 63//63 2865//2865 -f 2865//2865 63//63 65//65 -f 2865//2865 65//65 67//67 -f 2867//2867 59//59 2866//2866 -f 2866//2866 59//59 61//61 -f 2866//2866 61//61 63//63 -f 2868//2868 55//55 2867//2867 -f 2867//2867 55//55 57//57 -f 2867//2867 57//57 59//59 -f 2869//2869 51//51 2868//2868 -f 2868//2868 51//51 53//53 -f 2868//2868 53//53 55//55 -f 2870//2870 47//47 2869//2869 -f 2869//2869 47//47 49//49 -f 2869//2869 49//49 51//51 -f 2871//2871 43//43 2870//2870 -f 2870//2870 43//43 45//45 -f 2870//2870 45//45 47//47 -f 2872//2872 39//39 2871//2871 -f 2871//2871 39//39 41//41 -f 2871//2871 41//41 43//43 -f 2873//2873 35//35 2872//2872 -f 2872//2872 35//35 37//37 -f 2872//2872 37//37 39//39 -f 2874//2874 31//31 2873//2873 -f 2873//2873 31//31 33//33 -f 2873//2873 33//33 35//35 -f 2875//2875 27//27 2874//2874 -f 2874//2874 27//27 29//29 -f 2874//2874 29//29 31//31 -f 2876//2876 23//23 2875//2875 -f 2875//2875 23//23 25//25 -f 2875//2875 25//25 27//27 -f 2877//2877 19//19 2876//2876 -f 2876//2876 19//19 21//21 -f 2876//2876 21//21 23//23 -f 2878//2878 15//15 2877//2877 -f 2877//2877 15//15 17//17 -f 2877//2877 17//17 19//19 -f 2879//2879 11//11 2878//2878 -f 2878//2878 11//11 13//13 -f 2878//2878 13//13 15//15 -f 2880//2880 7//7 2879//2879 -f 2879//2879 7//7 9//9 -f 2879//2879 9//9 11//11 -f 127//127 1//1 2881//2881 -f 2881//2881 1//1 3//3 -f 2881//2881 3//3 2880//2880 -f 2880//2880 3//3 5//5 -f 2880//2880 5//5 7//7 -f 2897//2897 2898//2898 2899//2899 -f 2899//2899 2898//2898 2900//2900 -f 2899//2899 2900//2900 2901//2901 -f 2901//2901 2900//2900 2902//2902 -f 2901//2901 2902//2902 2903//2903 -f 2903//2903 2902//2902 2904//2904 -f 2903//2903 2904//2904 2905//2905 -f 2905//2905 2904//2904 2906//2906 -f 2905//2905 2906//2906 2907//2907 -f 2907//2907 2906//2906 2908//2908 -f 2907//2907 2908//2908 2909//2909 -f 2909//2909 2908//2908 2910//2910 -f 2909//2909 2910//2910 2911//2911 -f 2911//2911 2910//2910 2912//2912 -f 2911//2911 2912//2912 2913//2913 -f 2913//2913 2912//2912 2914//2914 -f 2913//2913 2914//2914 2915//2915 -f 2915//2915 2914//2914 2916//2916 -f 2915//2915 2916//2916 2917//2917 -f 2917//2917 2916//2916 2918//2918 -f 2917//2917 2918//2918 2919//2919 -f 2919//2919 2918//2918 2920//2920 -f 2919//2919 2920//2920 2921//2921 -f 2921//2921 2920//2920 2922//2922 -f 2921//2921 2922//2922 2923//2923 -f 2923//2923 2922//2922 2924//2924 -f 2923//2923 2924//2924 2925//2925 -f 2925//2925 2924//2924 2926//2926 -f 2925//2925 2926//2926 2927//2927 -f 2927//2927 2926//2926 2928//2928 -f 2927//2927 2928//2928 2929//2929 -f 2929//2929 2928//2928 2930//2930 -f 2929//2929 2930//2930 2931//2931 -f 2931//2931 2930//2930 2932//2932 -f 2931//2931 2932//2932 2933//2933 -f 2933//2933 2932//2932 2934//2934 -f 2933//2933 2934//2934 2935//2935 -f 2935//2935 2934//2934 2936//2936 -f 2935//2935 2936//2936 2937//2937 -f 2937//2937 2936//2936 2938//2938 -f 2937//2937 2938//2938 2939//2939 -f 2939//2939 2938//2938 2940//2940 -f 2939//2939 2940//2940 2941//2941 -f 2941//2941 2940//2940 2942//2942 -f 2941//2941 2942//2942 2943//2943 -f 2943//2943 2942//2942 2944//2944 -f 2943//2943 2944//2944 2945//2945 -f 2945//2945 2944//2944 2946//2946 -f 2945//2945 2946//2946 2947//2947 -f 2947//2947 2946//2946 2948//2948 -f 2947//2947 2948//2948 2949//2949 -f 2949//2949 2948//2948 2950//2950 -f 2949//2949 2950//2950 2951//2951 -f 2951//2951 2950//2950 2952//2952 -f 2951//2951 2952//2952 2953//2953 -f 2953//2953 2952//2952 2954//2954 -f 2953//2953 2954//2954 2955//2955 -f 2955//2955 2954//2954 2956//2956 -f 2955//2955 2956//2956 2957//2957 -f 2957//2957 2956//2956 2958//2958 -f 2957//2957 2958//2958 2959//2959 -f 2959//2959 2958//2958 2960//2960 -f 2959//2959 2960//2960 2961//2961 -f 2961//2961 2960//2960 2962//2962 -f 2961//2961 2962//2962 2963//2963 -f 2963//2963 2962//2962 2964//2964 -f 2963//2963 2964//2964 2965//2965 -f 2965//2965 2964//2964 2966//2966 -f 2965//2965 2966//2966 2967//2967 -f 2967//2967 2966//2966 2968//2968 -f 2967//2967 2968//2968 2969//2969 -f 2969//2969 2968//2968 2970//2970 -f 2969//2969 2970//2970 2971//2971 -f 2971//2971 2970//2970 2972//2972 -f 2971//2971 2972//2972 2973//2973 -f 2973//2973 2972//2972 2974//2974 -f 2973//2973 2974//2974 2975//2975 -f 2975//2975 2974//2974 2976//2976 -f 2975//2975 2976//2976 2977//2977 -f 2977//2977 2976//2976 2978//2978 -f 2977//2977 2978//2978 2979//2979 -f 2979//2979 2978//2978 2980//2980 -f 2979//2979 2980//2980 2981//2981 -f 2981//2981 2980//2980 2982//2982 -f 2981//2981 2982//2982 2983//2983 -f 2983//2983 2982//2982 2984//2984 -f 2983//2983 2984//2984 2985//2985 -f 2985//2985 2984//2984 2986//2986 -f 2985//2985 2986//2986 2987//2987 -f 2987//2987 2986//2986 2988//2988 -f 2987//2987 2988//2988 2989//2989 -f 2989//2989 2988//2988 2990//2990 -f 2989//2989 2990//2990 2991//2991 -f 2991//2991 2990//2990 2992//2992 -f 2991//2991 2992//2992 2993//2993 -f 2993//2993 2992//2992 2994//2994 -f 2993//2993 2994//2994 2995//2995 -f 2995//2995 2994//2994 2996//2996 -f 2995//2995 2996//2996 2997//2997 -f 2997//2997 2996//2996 2998//2998 -f 2997//2997 2998//2998 2999//2999 -f 2999//2999 2998//2998 3000//3000 -f 2999//2999 3000//3000 3001//3001 -f 3001//3001 3000//3000 3002//3002 -f 3001//3001 3002//3002 3003//3003 -f 3003//3003 3002//3002 3004//3004 -f 3003//3003 3004//3004 3005//3005 -f 3005//3005 3004//3004 3006//3006 -f 3005//3005 3006//3006 3007//3007 -f 3007//3007 3006//3006 3008//3008 -f 3007//3007 3008//3008 3009//3009 -f 3009//3009 3008//3008 3010//3010 -f 3009//3009 3010//3010 3011//3011 -f 3011//3011 3010//3010 3012//3012 -f 3011//3011 3012//3012 3013//3013 -f 3013//3013 3012//3012 3014//3014 -f 3013//3013 3014//3014 3015//3015 -f 3015//3015 3014//3014 3016//3016 -f 3015//3015 3016//3016 3017//3017 -f 3017//3017 3016//3016 3018//3018 -f 3017//3017 3018//3018 3019//3019 -f 3019//3019 3018//3018 3020//3020 -f 3019//3019 3020//3020 3021//3021 -f 3021//3021 3020//3020 3022//3022 -f 3021//3021 3022//3022 3023//3023 -f 3023//3023 3022//3022 3024//3024 -f 3023//3023 3024//3024 2897//2897 -f 2897//2897 3024//3024 2898//2898 -f 3024//3024 3025//3025 2898//2898 -f 2898//2898 3025//3025 3026//3026 -f 2898//2898 3026//3026 2900//2900 -f 2900//2900 3026//3026 3027//3027 -f 2900//2900 3027//3027 2902//2902 -f 2902//2902 3027//3027 3028//3028 -f 2902//2902 3028//3028 2904//2904 -f 2904//2904 3028//3028 3029//3029 -f 2904//2904 3029//3029 2906//2906 -f 2906//2906 3029//3029 3030//3030 -f 2906//2906 3030//3030 2908//2908 -f 2908//2908 3030//3030 3031//3031 -f 2908//2908 3031//3031 2910//2910 -f 2910//2910 3031//3031 3032//3032 -f 2910//2910 3032//3032 2912//2912 -f 2912//2912 3032//3032 3033//3033 -f 2912//2912 3033//3033 2914//2914 -f 2914//2914 3033//3033 3034//3034 -f 2914//2914 3034//3034 2916//2916 -f 2916//2916 3034//3034 3035//3035 -f 2916//2916 3035//3035 2918//2918 -f 2918//2918 3035//3035 3036//3036 -f 2918//2918 3036//3036 2920//2920 -f 2920//2920 3036//3036 3037//3037 -f 2920//2920 3037//3037 2922//2922 -f 2922//2922 3037//3037 3038//3038 -f 2922//2922 3038//3038 2924//2924 -f 2924//2924 3038//3038 3039//3039 -f 2924//2924 3039//3039 2926//2926 -f 2926//2926 3039//3039 3040//3040 -f 2926//2926 3040//3040 2928//2928 -f 2928//2928 3040//3040 3041//3041 -f 2928//2928 3041//3041 2930//2930 -f 2930//2930 3041//3041 3042//3042 -f 2930//2930 3042//3042 2932//2932 -f 2932//2932 3042//3042 3043//3043 -f 2932//2932 3043//3043 2934//2934 -f 2934//2934 3043//3043 3044//3044 -f 2934//2934 3044//3044 2936//2936 -f 2936//2936 3044//3044 3045//3045 -f 2936//2936 3045//3045 2938//2938 -f 2938//2938 3045//3045 3046//3046 -f 2938//2938 3046//3046 2940//2940 -f 2940//2940 3046//3046 3047//3047 -f 2940//2940 3047//3047 2942//2942 -f 2942//2942 3047//3047 3048//3048 -f 2942//2942 3048//3048 2944//2944 -f 2944//2944 3048//3048 3049//3049 -f 2944//2944 3049//3049 2946//2946 -f 2946//2946 3049//3049 3050//3050 -f 2946//2946 3050//3050 2948//2948 -f 2948//2948 3050//3050 3051//3051 -f 2948//2948 3051//3051 2950//2950 -f 2950//2950 3051//3051 3052//3052 -f 2950//2950 3052//3052 2952//2952 -f 2952//2952 3052//3052 3053//3053 -f 2952//2952 3053//3053 2954//2954 -f 2954//2954 3053//3053 3054//3054 -f 2954//2954 3054//3054 2956//2956 -f 2956//2956 3054//3054 3055//3055 -f 2956//2956 3055//3055 2958//2958 -f 2958//2958 3055//3055 3056//3056 -f 2958//2958 3056//3056 2960//2960 -f 2960//2960 3056//3056 3057//3057 -f 2960//2960 3057//3057 2962//2962 -f 2962//2962 3057//3057 3058//3058 -f 2962//2962 3058//3058 2964//2964 -f 2964//2964 3058//3058 3059//3059 -f 2964//2964 3059//3059 2966//2966 -f 2966//2966 3059//3059 3060//3060 -f 2966//2966 3060//3060 2968//2968 -f 2968//2968 3060//3060 3061//3061 -f 2968//2968 3061//3061 2970//2970 -f 2970//2970 3061//3061 3062//3062 -f 2970//2970 3062//3062 2972//2972 -f 2972//2972 3062//3062 3063//3063 -f 2972//2972 3063//3063 2974//2974 -f 2974//2974 3063//3063 3064//3064 -f 2974//2974 3064//3064 2976//2976 -f 2976//2976 3064//3064 3065//3065 -f 2976//2976 3065//3065 2978//2978 -f 2978//2978 3065//3065 3066//3066 -f 2978//2978 3066//3066 2980//2980 -f 2980//2980 3066//3066 3067//3067 -f 2980//2980 3067//3067 2982//2982 -f 2982//2982 3067//3067 3068//3068 -f 2982//2982 3068//3068 2984//2984 -f 2984//2984 3068//3068 3069//3069 -f 2984//2984 3069//3069 2986//2986 -f 2986//2986 3069//3069 3070//3070 -f 2986//2986 3070//3070 2988//2988 -f 2988//2988 3070//3070 3071//3071 -f 2988//2988 3071//3071 2990//2990 -f 2990//2990 3071//3071 3072//3072 -f 2990//2990 3072//3072 2992//2992 -f 2992//2992 3072//3072 3073//3073 -f 2992//2992 3073//3073 2994//2994 -f 2994//2994 3073//3073 3074//3074 -f 2994//2994 3074//3074 2996//2996 -f 2996//2996 3074//3074 3075//3075 -f 2996//2996 3075//3075 2998//2998 -f 2998//2998 3075//3075 3076//3076 -f 2998//2998 3076//3076 3000//3000 -f 3000//3000 3076//3076 3077//3077 -f 3000//3000 3077//3077 3002//3002 -f 3002//3002 3077//3077 3078//3078 -f 3002//3002 3078//3078 3004//3004 -f 3004//3004 3078//3078 3079//3079 -f 3004//3004 3079//3079 3006//3006 -f 3006//3006 3079//3079 3080//3080 -f 3006//3006 3080//3080 3008//3008 -f 3008//3008 3080//3080 3081//3081 -f 3008//3008 3081//3081 3010//3010 -f 3010//3010 3081//3081 3082//3082 -f 3010//3010 3082//3082 3012//3012 -f 3012//3012 3082//3082 3083//3083 -f 3012//3012 3083//3083 3014//3014 -f 3014//3014 3083//3083 3084//3084 -f 3014//3014 3084//3084 3016//3016 -f 3016//3016 3084//3084 3085//3085 -f 3016//3016 3085//3085 3018//3018 -f 3018//3018 3085//3085 3086//3086 -f 3018//3018 3086//3086 3020//3020 -f 3020//3020 3086//3086 3087//3087 -f 3020//3020 3087//3087 3022//3022 -f 3022//3022 3087//3087 3088//3088 -f 3022//3022 3088//3088 3024//3024 -f 3024//3024 3088//3088 3025//3025 -f 3088//3088 3089//3089 3025//3025 -f 3025//3025 3089//3089 3090//3090 -f 3025//3025 3090//3090 3026//3026 -f 3026//3026 3090//3090 3091//3091 -f 3026//3026 3091//3091 3027//3027 -f 3027//3027 3091//3091 3092//3092 -f 3027//3027 3092//3092 3028//3028 -f 3028//3028 3092//3092 3093//3093 -f 3028//3028 3093//3093 3029//3029 -f 3029//3029 3093//3093 3094//3094 -f 3029//3029 3094//3094 3030//3030 -f 3030//3030 3094//3094 3095//3095 -f 3030//3030 3095//3095 3031//3031 -f 3031//3031 3095//3095 3096//3096 -f 3031//3031 3096//3096 3032//3032 -f 3032//3032 3096//3096 3097//3097 -f 3032//3032 3097//3097 3033//3033 -f 3033//3033 3097//3097 3098//3098 -f 3033//3033 3098//3098 3034//3034 -f 3034//3034 3098//3098 3099//3099 -f 3034//3034 3099//3099 3035//3035 -f 3035//3035 3099//3099 3100//3100 -f 3035//3035 3100//3100 3036//3036 -f 3036//3036 3100//3100 3101//3101 -f 3036//3036 3101//3101 3037//3037 -f 3037//3037 3101//3101 3102//3102 -f 3037//3037 3102//3102 3038//3038 -f 3038//3038 3102//3102 3103//3103 -f 3038//3038 3103//3103 3039//3039 -f 3039//3039 3103//3103 3104//3104 -f 3039//3039 3104//3104 3040//3040 -f 3040//3040 3104//3104 3105//3105 -f 3040//3040 3105//3105 3041//3041 -f 3041//3041 3105//3105 3106//3106 -f 3041//3041 3106//3106 3042//3042 -f 3042//3042 3106//3106 3107//3107 -f 3042//3042 3107//3107 3043//3043 -f 3043//3043 3107//3107 3108//3108 -f 3043//3043 3108//3108 3044//3044 -f 3044//3044 3108//3108 3109//3109 -f 3044//3044 3109//3109 3045//3045 -f 3045//3045 3109//3109 3110//3110 -f 3045//3045 3110//3110 3046//3046 -f 3046//3046 3110//3110 3111//3111 -f 3046//3046 3111//3111 3047//3047 -f 3047//3047 3111//3111 3112//3112 -f 3047//3047 3112//3112 3048//3048 -f 3048//3048 3112//3112 3113//3113 -f 3048//3048 3113//3113 3049//3049 -f 3049//3049 3113//3113 3114//3114 -f 3049//3049 3114//3114 3050//3050 -f 3050//3050 3114//3114 3115//3115 -f 3050//3050 3115//3115 3051//3051 -f 3051//3051 3115//3115 3116//3116 -f 3051//3051 3116//3116 3052//3052 -f 3052//3052 3116//3116 3117//3117 -f 3052//3052 3117//3117 3053//3053 -f 3053//3053 3117//3117 3118//3118 -f 3053//3053 3118//3118 3054//3054 -f 3054//3054 3118//3118 3119//3119 -f 3054//3054 3119//3119 3055//3055 -f 3055//3055 3119//3119 3120//3120 -f 3055//3055 3120//3120 3056//3056 -f 3056//3056 3120//3120 3121//3121 -f 3056//3056 3121//3121 3057//3057 -f 3057//3057 3121//3121 3122//3122 -f 3057//3057 3122//3122 3058//3058 -f 3058//3058 3122//3122 3123//3123 -f 3058//3058 3123//3123 3059//3059 -f 3059//3059 3123//3123 3124//3124 -f 3059//3059 3124//3124 3060//3060 -f 3060//3060 3124//3124 3125//3125 -f 3060//3060 3125//3125 3061//3061 -f 3061//3061 3125//3125 3126//3126 -f 3061//3061 3126//3126 3062//3062 -f 3062//3062 3126//3126 3127//3127 -f 3062//3062 3127//3127 3063//3063 -f 3063//3063 3127//3127 3128//3128 -f 3063//3063 3128//3128 3064//3064 -f 3064//3064 3128//3128 3129//3129 -f 3064//3064 3129//3129 3065//3065 -f 3065//3065 3129//3129 3130//3130 -f 3065//3065 3130//3130 3066//3066 -f 3066//3066 3130//3130 3131//3131 -f 3066//3066 3131//3131 3067//3067 -f 3067//3067 3131//3131 3132//3132 -f 3067//3067 3132//3132 3068//3068 -f 3068//3068 3132//3132 3133//3133 -f 3068//3068 3133//3133 3069//3069 -f 3069//3069 3133//3133 3134//3134 -f 3069//3069 3134//3134 3070//3070 -f 3070//3070 3134//3134 3135//3135 -f 3070//3070 3135//3135 3071//3071 -f 3071//3071 3135//3135 3136//3136 -f 3071//3071 3136//3136 3072//3072 -f 3072//3072 3136//3136 3137//3137 -f 3072//3072 3137//3137 3073//3073 -f 3073//3073 3137//3137 3138//3138 -f 3073//3073 3138//3138 3074//3074 -f 3074//3074 3138//3138 3139//3139 -f 3074//3074 3139//3139 3075//3075 -f 3075//3075 3139//3139 3140//3140 -f 3075//3075 3140//3140 3076//3076 -f 3076//3076 3140//3140 3141//3141 -f 3076//3076 3141//3141 3077//3077 -f 3077//3077 3141//3141 3142//3142 -f 3077//3077 3142//3142 3078//3078 -f 3078//3078 3142//3142 3143//3143 -f 3078//3078 3143//3143 3079//3079 -f 3079//3079 3143//3143 3144//3144 -f 3079//3079 3144//3144 3080//3080 -f 3080//3080 3144//3144 3145//3145 -f 3080//3080 3145//3145 3081//3081 -f 3081//3081 3145//3145 3146//3146 -f 3081//3081 3146//3146 3082//3082 -f 3082//3082 3146//3146 3147//3147 -f 3082//3082 3147//3147 3083//3083 -f 3083//3083 3147//3147 3148//3148 -f 3083//3083 3148//3148 3084//3084 -f 3084//3084 3148//3148 3149//3149 -f 3084//3084 3149//3149 3085//3085 -f 3085//3085 3149//3149 3150//3150 -f 3085//3085 3150//3150 3086//3086 -f 3086//3086 3150//3150 3151//3151 -f 3086//3086 3151//3151 3087//3087 -f 3087//3087 3151//3151 3152//3152 -f 3087//3087 3152//3152 3088//3088 -f 3088//3088 3152//3152 3089//3089 -f 3138//3138 3153//3153 3139//3139 -f 3139//3139 3153//3153 3154//3154 -f 3139//3139 3154//3154 3140//3140 -f 3140//3140 3154//3154 3155//3155 -f 3140//3140 3155//3155 3141//3141 -f 3141//3141 3155//3155 3156//3156 -f 3141//3141 3156//3156 3142//3142 -f 3142//3142 3156//3156 3157//3157 -f 3142//3142 3157//3157 3143//3143 -f 3143//3143 3157//3157 3158//3158 -f 3143//3143 3158//3158 3144//3144 -f 3132//3132 3159//3159 3133//3133 -f 3133//3133 3159//3159 3160//3160 -f 3133//3133 3160//3160 3134//3134 -f 3134//3134 3160//3160 3161//3161 -f 3134//3134 3161//3161 3135//3135 -f 3135//3135 3161//3161 3162//3162 -f 3135//3135 3162//3162 3136//3136 -f 3136//3136 3162//3162 3163//3163 -f 3136//3136 3163//3163 3137//3137 -f 3137//3137 3163//3163 3164//3164 -f 3137//3137 3164//3164 3138//3138 -f 3138//3138 3164//3164 3165//3165 -f 3138//3138 3165//3165 3153//3153 -f 3126//3126 3166//3166 3127//3127 -f 3127//3127 3166//3166 3167//3167 -f 3127//3127 3167//3167 3128//3128 -f 3128//3128 3167//3167 3168//3168 -f 3128//3128 3168//3168 3129//3129 -f 3129//3129 3168//3168 3169//3169 -f 3129//3129 3169//3169 3130//3130 -f 3130//3130 3169//3169 3170//3170 -f 3130//3130 3170//3170 3131//3131 -f 3131//3131 3170//3170 3171//3171 -f 3131//3131 3171//3171 3132//3132 -f 3132//3132 3171//3171 3172//3172 -f 3132//3132 3172//3172 3159//3159 -f 3112//3112 3173//3173 3113//3113 -f 3113//3113 3173//3173 3174//3174 -f 3113//3113 3174//3174 3114//3114 -f 3114//3114 3174//3174 3175//3175 -f 3114//3114 3175//3175 3115//3115 -f 3115//3115 3175//3175 3176//3176 -f 3115//3115 3176//3176 3116//3116 -f 3116//3116 3176//3176 3177//3177 -f 3116//3116 3177//3177 3117//3117 -f 3117//3117 3177//3177 3178//3178 -f 3117//3117 3178//3178 3118//3118 -f 3118//3118 3178//3178 3179//3179 -f 3118//3118 3179//3179 3119//3119 -f 3119//3119 3179//3179 3180//3180 -f 3119//3119 3180//3180 3120//3120 -f 3120//3120 3180//3180 3181//3181 -f 3120//3120 3181//3181 3121//3121 -f 3121//3121 3181//3181 3182//3182 -f 3121//3121 3182//3182 3122//3122 -f 3122//3122 3182//3182 3183//3183 -f 3122//3122 3183//3183 3123//3123 -f 3123//3123 3183//3183 3184//3184 -f 3123//3123 3184//3184 3124//3124 -f 3124//3124 3184//3184 3185//3185 -f 3124//3124 3185//3185 3125//3125 -f 3125//3125 3185//3185 3186//3186 -f 3125//3125 3186//3186 3126//3126 -f 3126//3126 3186//3186 3187//3187 -f 3126//3126 3187//3187 3166//3166 -f 3106//3106 3188//3188 3107//3107 -f 3107//3107 3188//3188 3189//3189 -f 3107//3107 3189//3189 3108//3108 -f 3108//3108 3189//3189 3190//3190 -f 3108//3108 3190//3190 3109//3109 -f 3109//3109 3190//3190 3191//3191 -f 3109//3109 3191//3191 3110//3110 -f 3110//3110 3191//3191 3192//3192 -f 3110//3110 3192//3192 3111//3111 -f 3111//3111 3192//3192 3193//3193 -f 3111//3111 3193//3193 3112//3112 -f 3112//3112 3193//3193 3194//3194 -f 3112//3112 3194//3194 3173//3173 -f 3100//3100 3195//3195 3101//3101 -f 3101//3101 3195//3195 3196//3196 -f 3101//3101 3196//3196 3102//3102 -f 3102//3102 3196//3196 3197//3197 -f 3102//3102 3197//3197 3103//3103 -f 3103//3103 3197//3197 3198//3198 -f 3103//3103 3198//3198 3104//3104 -f 3104//3104 3198//3198 3199//3199 -f 3104//3104 3199//3199 3105//3105 -f 3105//3105 3199//3199 3200//3200 -f 3105//3105 3200//3200 3106//3106 -f 3106//3106 3200//3200 3201//3201 -f 3106//3106 3201//3201 3188//3188 -f 3094//3094 3202//3202 3095//3095 -f 3095//3095 3202//3202 3203//3203 -f 3095//3095 3203//3203 3096//3096 -f 3096//3096 3203//3203 3204//3204 -f 3096//3096 3204//3204 3097//3097 -f 3097//3097 3204//3204 3205//3205 -f 3097//3097 3205//3205 3098//3098 -f 3098//3098 3205//3205 3206//3206 -f 3098//3098 3206//3206 3099//3099 -f 3099//3099 3206//3206 3207//3207 -f 3099//3099 3207//3207 3100//3100 -f 3100//3100 3207//3207 3208//3208 -f 3100//3100 3208//3208 3195//3195 -f 3158//3158 3209//3209 3144//3144 -f 3144//3144 3209//3209 3210//3210 -f 3144//3144 3210//3210 3145//3145 -f 3145//3145 3210//3210 3211//3211 -f 3145//3145 3211//3211 3146//3146 -f 3146//3146 3211//3211 3212//3212 -f 3146//3146 3212//3212 3147//3147 -f 3147//3147 3212//3212 3213//3213 -f 3147//3147 3213//3213 3148//3148 -f 3148//3148 3213//3213 3214//3214 -f 3148//3148 3214//3214 3149//3149 -f 3149//3149 3214//3214 3215//3215 -f 3149//3149 3215//3215 3150//3150 -f 3150//3150 3215//3215 3216//3216 -f 3150//3150 3216//3216 3151//3151 -f 3151//3151 3216//3216 3217//3217 -f 3151//3151 3217//3217 3152//3152 -f 3152//3152 3217//3217 3218//3218 -f 3152//3152 3218//3218 3089//3089 -f 3089//3089 3218//3218 3219//3219 -f 3089//3089 3219//3219 3090//3090 -f 3090//3090 3219//3219 3220//3220 -f 3090//3090 3220//3220 3091//3091 -f 3091//3091 3220//3220 3221//3221 -f 3091//3091 3221//3221 3092//3092 -f 3092//3092 3221//3221 3222//3222 -f 3092//3092 3222//3222 3093//3093 -f 3093//3093 3222//3222 3223//3223 -f 3093//3093 3223//3223 3094//3094 -f 3094//3094 3223//3223 3224//3224 -f 3094//3094 3224//3224 3202//3202 -f 3225//3225 3226//3226 3227//3227 -f 3228//3228 3229//3229 3230//3230 -f 3231//3231 3232//3232 3233//3233 -f 3234//3234 3235//3235 3236//3236 -f 3237//3237 3238//3238 3239//3239 -f 3240//3240 3241//3241 3242//3242 -f 3243//3243 3244//3244 3245//3245 -f 3224//3224 3223//3223 3246//3246 -f 3203//3203 3202//3202 3247//3247 -f 3204//3204 3203//3203 3248//3248 -f 3192//3192 3191//3191 3231//3231 -f 3194//3194 3193//3193 3249//3249 -f 3174//3174 3173//3173 3250//3250 -f 3175//3175 3174//3174 3251//3251 -f 3172//3172 3171//3171 3252//3252 -f 3161//3161 3160//3160 3253//3253 -f 3154//3154 3153//3153 3254//3254 -f 3157//3157 3156//3156 3255//3255 -f 3216//3216 3215//3215 3256//3256 -f 3218//3218 3217//3217 3257//3257 -f 3257//3257 3217//3217 3216//3216 -f 3213//3213 3212//3212 3243//3243 -f 3243//3243 3212//3212 3211//3211 -f 3243//3243 3211//3211 3244//3244 -f 3244//3244 3211//3211 3210//3210 -f 3244//3244 3210//3210 3209//3209 -f 3258//3258 3158//3158 3157//3157 -f 3156//3156 3155//3155 3259//3259 -f 3162//3162 3241//3241 3163//3163 -f 3163//3163 3241//3241 3240//3240 -f 3163//3163 3240//3240 3164//3164 -f 3164//3164 3240//3240 3165//3165 -f 3160//3160 3159//3159 3260//3260 -f 3260//3260 3159//3159 3172//3172 -f 3169//3169 3168//3168 3237//3237 -f 3237//3237 3168//3168 3167//3167 -f 3237//3237 3167//3167 3238//3238 -f 3238//3238 3167//3167 3166//3166 -f 3238//3238 3166//3166 3187//3187 -f 3261//3261 3186//3186 3185//3185 -f 3185//3185 3184//3184 3262//3262 -f 3262//3262 3184//3184 3183//3183 -f 3181//3181 3180//3180 3234//3234 -f 3234//3234 3180//3180 3179//3179 -f 3234//3234 3179//3179 3235//3235 -f 3235//3235 3179//3179 3178//3178 -f 3235//3235 3178//3178 3177//3177 -f 3175//3175 3251//3251 3176//3176 -f 3231//3231 3191//3191 3232//3232 -f 3232//3232 3191//3191 3190//3190 -f 3232//3232 3190//3190 3189//3189 -f 3263//3263 3188//3188 3201//3201 -f 3201//3201 3200//3200 3264//3264 -f 3264//3264 3200//3200 3199//3199 -f 3198//3198 3197//3197 3265//3265 -f 3196//3196 3195//3195 3228//3228 -f 3228//3228 3195//3195 3208//3208 -f 3228//3228 3208//3208 3229//3229 -f 3229//3229 3208//3208 3207//3207 -f 3229//3229 3207//3207 3206//3206 -f 3204//3204 3248//3248 3205//3205 -f 3222//3222 3221//3221 3225//3225 -f 3225//3225 3221//3221 3220//3220 -f 3225//3225 3220//3220 3226//3226 -f 3226//3226 3220//3220 3219//3219 -f 3266//3266 3267//3267 3256//3256 -f 3268//3268 3245//3245 3269//3269 -f 3269//3269 3245//3245 3244//3244 -f 3269//3269 3244//3244 3258//3258 -f 3258//3258 3244//3244 3209//3209 -f 3258//3258 3209//3209 3158//3158 -f 3270//3270 3271//3271 3259//3259 -f 3272//3272 3242//3242 3273//3273 -f 3273//3273 3242//3242 3241//3241 -f 3273//3273 3241//3241 3253//3253 -f 3253//3253 3241//3241 3162//3162 -f 3253//3253 3162//3162 3161//3161 -f 3274//3274 3275//3275 3252//3252 -f 3276//3276 3239//3239 3277//3277 -f 3277//3277 3239//3239 3238//3238 -f 3277//3277 3238//3238 3261//3261 -f 3261//3261 3238//3238 3187//3187 -f 3261//3261 3187//3187 3186//3186 -f 3278//3278 3279//3279 3280//3280 -f 3281//3281 3236//3236 3282//3282 -f 3282//3282 3236//3236 3235//3235 -f 3282//3282 3235//3235 3283//3283 -f 3283//3283 3235//3235 3177//3177 -f 3283//3283 3177//3177 3176//3176 -f 3284//3284 3285//3285 3250//3250 -f 3286//3286 3233//3233 3287//3287 -f 3287//3287 3233//3233 3232//3232 -f 3287//3287 3232//3232 3263//3263 -f 3263//3263 3232//3232 3189//3189 -f 3263//3263 3189//3189 3188//3188 -f 3288//3288 3289//3289 3290//3290 -f 3291//3291 3230//3230 3292//3292 -f 3292//3292 3230//3230 3229//3229 -f 3292//3292 3229//3229 3293//3293 -f 3293//3293 3229//3229 3206//3206 -f 3293//3293 3206//3206 3205//3205 -f 3294//3294 3295//3295 3247//3247 -f 3296//3296 3227//3227 3297//3297 -f 3297//3297 3227//3227 3226//3226 -f 3297//3297 3226//3226 3298//3298 -f 3298//3298 3226//3226 3219//3219 -f 3298//3298 3219//3219 3218//3218 -f 3299//3299 3267//3267 3300//3300 -f 3300//3300 3267//3267 3266//3266 -f 3300//3300 3266//3266 3301//3301 -f 3302//3302 3271//3271 3303//3303 -f 3303//3303 3271//3271 3270//3270 -f 3303//3303 3270//3270 3304//3304 -f 3305//3305 3275//3275 3306//3306 -f 3306//3306 3275//3275 3274//3274 -f 3306//3306 3274//3274 3307//3307 -f 3308//3308 3279//3279 3309//3309 -f 3309//3309 3279//3279 3278//3278 -f 3309//3309 3278//3278 3310//3310 -f 3311//3311 3285//3285 3312//3312 -f 3312//3312 3285//3285 3284//3284 -f 3312//3312 3284//3284 3313//3313 -f 3314//3314 3289//3289 3315//3315 -f 3315//3315 3289//3289 3288//3288 -f 3315//3315 3288//3288 3316//3316 -f 3317//3317 3295//3295 3318//3318 -f 3318//3318 3295//3295 3294//3294 -f 3318//3318 3294//3294 3319//3319 -f 3320//3320 3321//3321 3322//3322 -f 3218//3218 3257//3257 3298//3298 -f 3298//3298 3257//3257 3323//3323 -f 3298//3298 3323//3323 3297//3297 -f 3297//3297 3323//3323 3320//3320 -f 3297//3297 3320//3320 3296//3296 -f 3296//3296 3320//3320 3322//3322 -f 3296//3296 3322//3322 3324//3324 -f 3216//3216 3256//3256 3257//3257 -f 3257//3257 3256//3256 3267//3267 -f 3257//3257 3267//3267 3323//3323 -f 3323//3323 3267//3267 3299//3299 -f 3323//3323 3299//3299 3320//3320 -f 3320//3320 3299//3299 3325//3325 -f 3320//3320 3325//3325 3321//3321 -f 3326//3326 3327//3327 3328//3328 -f 3328//3328 3327//3327 3301//3301 -f 3328//3328 3301//3301 3329//3329 -f 3329//3329 3301//3301 3266//3266 -f 3329//3329 3266//3266 3330//3330 -f 3330//3330 3266//3266 3256//3256 -f 3330//3330 3256//3256 3214//3214 -f 3214//3214 3256//3256 3215//3215 -f 3327//3327 3331//3331 3301//3301 -f 3301//3301 3331//3331 3332//3332 -f 3301//3301 3332//3332 3300//3300 -f 3300//3300 3332//3332 3333//3333 -f 3300//3300 3333//3333 3299//3299 -f 3299//3299 3333//3333 3334//3334 -f 3299//3299 3334//3334 3325//3325 -f 3214//3214 3213//3213 3330//3330 -f 3330//3330 3213//3213 3243//3243 -f 3330//3330 3243//3243 3329//3329 -f 3329//3329 3243//3243 3245//3245 -f 3329//3329 3245//3245 3328//3328 -f 3328//3328 3245//3245 3268//3268 -f 3328//3328 3268//3268 3326//3326 -f 3326//3326 3268//3268 3335//3335 -f 3336//3336 3337//3337 3338//3338 -f 3157//3157 3255//3255 3258//3258 -f 3258//3258 3255//3255 3339//3339 -f 3258//3258 3339//3339 3269//3269 -f 3269//3269 3339//3339 3336//3336 -f 3269//3269 3336//3336 3268//3268 -f 3268//3268 3336//3336 3338//3338 -f 3268//3268 3338//3338 3335//3335 -f 3156//3156 3259//3259 3255//3255 -f 3255//3255 3259//3259 3271//3271 -f 3255//3255 3271//3271 3339//3339 -f 3339//3339 3271//3271 3302//3302 -f 3339//3339 3302//3302 3336//3336 -f 3336//3336 3302//3302 3340//3340 -f 3336//3336 3340//3340 3337//3337 -f 3341//3341 3342//3342 3343//3343 -f 3343//3343 3342//3342 3304//3304 -f 3343//3343 3304//3304 3344//3344 -f 3344//3344 3304//3304 3270//3270 -f 3344//3344 3270//3270 3254//3254 -f 3254//3254 3270//3270 3259//3259 -f 3254//3254 3259//3259 3154//3154 -f 3154//3154 3259//3259 3155//3155 -f 3342//3342 3345//3345 3304//3304 -f 3304//3304 3345//3345 3346//3346 -f 3304//3304 3346//3346 3303//3303 -f 3303//3303 3346//3346 3347//3347 -f 3303//3303 3347//3347 3302//3302 -f 3302//3302 3347//3347 3348//3348 -f 3302//3302 3348//3348 3340//3340 -f 3153//3153 3165//3165 3254//3254 -f 3254//3254 3165//3165 3240//3240 -f 3254//3254 3240//3240 3344//3344 -f 3344//3344 3240//3240 3242//3242 -f 3344//3344 3242//3242 3343//3343 -f 3343//3343 3242//3242 3272//3272 -f 3343//3343 3272//3272 3341//3341 -f 3341//3341 3272//3272 3349//3349 -f 3350//3350 3351//3351 3352//3352 -f 3160//3160 3260//3260 3253//3253 -f 3253//3253 3260//3260 3353//3353 -f 3253//3253 3353//3353 3273//3273 -f 3273//3273 3353//3353 3350//3350 -f 3273//3273 3350//3350 3272//3272 -f 3272//3272 3350//3350 3352//3352 -f 3272//3272 3352//3352 3349//3349 -f 3172//3172 3252//3252 3260//3260 -f 3260//3260 3252//3252 3275//3275 -f 3260//3260 3275//3275 3353//3353 -f 3353//3353 3275//3275 3305//3305 -f 3353//3353 3305//3305 3350//3350 -f 3350//3350 3305//3305 3354//3354 -f 3350//3350 3354//3354 3351//3351 -f 3355//3355 3356//3356 3357//3357 -f 3357//3357 3356//3356 3307//3307 -f 3357//3357 3307//3307 3358//3358 -f 3358//3358 3307//3307 3274//3274 -f 3358//3358 3274//3274 3359//3359 -f 3359//3359 3274//3274 3252//3252 -f 3359//3359 3252//3252 3170//3170 -f 3170//3170 3252//3252 3171//3171 -f 3356//3356 3360//3360 3307//3307 -f 3307//3307 3360//3360 3361//3361 -f 3307//3307 3361//3361 3306//3306 -f 3306//3306 3361//3361 3362//3362 -f 3306//3306 3362//3362 3305//3305 -f 3305//3305 3362//3362 3363//3363 -f 3305//3305 3363//3363 3354//3354 -f 3170//3170 3169//3169 3359//3359 -f 3359//3359 3169//3169 3237//3237 -f 3359//3359 3237//3237 3358//3358 -f 3358//3358 3237//3237 3239//3239 -f 3358//3358 3239//3239 3357//3357 -f 3357//3357 3239//3239 3276//3276 -f 3357//3357 3276//3276 3355//3355 -f 3355//3355 3276//3276 3364//3364 -f 3365//3365 3366//3366 3367//3367 -f 3185//3185 3262//3262 3261//3261 -f 3261//3261 3262//3262 3368//3368 -f 3261//3261 3368//3368 3277//3277 -f 3277//3277 3368//3368 3365//3365 -f 3277//3277 3365//3365 3276//3276 -f 3276//3276 3365//3365 3367//3367 -f 3276//3276 3367//3367 3364//3364 -f 3183//3183 3280//3280 3262//3262 -f 3262//3262 3280//3280 3279//3279 -f 3262//3262 3279//3279 3368//3368 -f 3368//3368 3279//3279 3308//3308 -f 3368//3368 3308//3308 3365//3365 -f 3365//3365 3308//3308 3369//3369 -f 3365//3365 3369//3369 3366//3366 -f 3370//3370 3371//3371 3372//3372 -f 3372//3372 3371//3371 3310//3310 -f 3372//3372 3310//3310 3373//3373 -f 3373//3373 3310//3310 3278//3278 -f 3373//3373 3278//3278 3374//3374 -f 3374//3374 3278//3278 3280//3280 -f 3374//3374 3280//3280 3182//3182 -f 3182//3182 3280//3280 3183//3183 -f 3371//3371 3375//3375 3310//3310 -f 3310//3310 3375//3375 3376//3376 -f 3310//3310 3376//3376 3309//3309 -f 3309//3309 3376//3376 3377//3377 -f 3309//3309 3377//3377 3308//3308 -f 3308//3308 3377//3377 3378//3378 -f 3308//3308 3378//3378 3369//3369 -f 3182//3182 3181//3181 3374//3374 -f 3374//3374 3181//3181 3234//3234 -f 3374//3374 3234//3234 3373//3373 -f 3373//3373 3234//3234 3236//3236 -f 3373//3373 3236//3236 3372//3372 -f 3372//3372 3236//3236 3281//3281 -f 3372//3372 3281//3281 3370//3370 -f 3370//3370 3281//3281 3379//3379 -f 3380//3380 3381//3381 3382//3382 -f 3176//3176 3251//3251 3283//3283 -f 3283//3283 3251//3251 3383//3383 -f 3283//3283 3383//3383 3282//3282 -f 3282//3282 3383//3383 3380//3380 -f 3282//3282 3380//3380 3281//3281 -f 3281//3281 3380//3380 3382//3382 -f 3281//3281 3382//3382 3379//3379 -f 3174//3174 3250//3250 3251//3251 -f 3251//3251 3250//3250 3285//3285 -f 3251//3251 3285//3285 3383//3383 -f 3383//3383 3285//3285 3311//3311 -f 3383//3383 3311//3311 3380//3380 -f 3380//3380 3311//3311 3384//3384 -f 3380//3380 3384//3384 3381//3381 -f 3385//3385 3386//3386 3387//3387 -f 3387//3387 3386//3386 3313//3313 -f 3387//3387 3313//3313 3388//3388 -f 3388//3388 3313//3313 3284//3284 -f 3388//3388 3284//3284 3249//3249 -f 3249//3249 3284//3284 3250//3250 -f 3249//3249 3250//3250 3194//3194 -f 3194//3194 3250//3250 3173//3173 -f 3386//3386 3389//3389 3313//3313 -f 3313//3313 3389//3389 3390//3390 -f 3313//3313 3390//3390 3312//3312 -f 3312//3312 3390//3390 3391//3391 -f 3312//3312 3391//3391 3311//3311 -f 3311//3311 3391//3391 3392//3392 -f 3311//3311 3392//3392 3384//3384 -f 3193//3193 3192//3192 3249//3249 -f 3249//3249 3192//3192 3231//3231 -f 3249//3249 3231//3231 3388//3388 -f 3388//3388 3231//3231 3233//3233 -f 3388//3388 3233//3233 3387//3387 -f 3387//3387 3233//3233 3286//3286 -f 3387//3387 3286//3286 3385//3385 -f 3385//3385 3286//3286 3393//3393 -f 3394//3394 3395//3395 3396//3396 -f 3201//3201 3264//3264 3263//3263 -f 3263//3263 3264//3264 3397//3397 -f 3263//3263 3397//3397 3287//3287 -f 3287//3287 3397//3397 3394//3394 -f 3287//3287 3394//3394 3286//3286 -f 3286//3286 3394//3394 3396//3396 -f 3286//3286 3396//3396 3393//3393 -f 3199//3199 3290//3290 3264//3264 -f 3264//3264 3290//3290 3289//3289 -f 3264//3264 3289//3289 3397//3397 -f 3397//3397 3289//3289 3314//3314 -f 3397//3397 3314//3314 3394//3394 -f 3394//3394 3314//3314 3398//3398 -f 3394//3394 3398//3398 3395//3395 -f 3399//3399 3400//3400 3401//3401 -f 3401//3401 3400//3400 3316//3316 -f 3401//3401 3316//3316 3402//3402 -f 3402//3402 3316//3316 3288//3288 -f 3402//3402 3288//3288 3265//3265 -f 3265//3265 3288//3288 3290//3290 -f 3265//3265 3290//3290 3198//3198 -f 3198//3198 3290//3290 3199//3199 -f 3400//3400 3403//3403 3316//3316 -f 3316//3316 3403//3403 3404//3404 -f 3316//3316 3404//3404 3315//3315 -f 3315//3315 3404//3404 3405//3405 -f 3315//3315 3405//3405 3314//3314 -f 3314//3314 3405//3405 3406//3406 -f 3314//3314 3406//3406 3398//3398 -f 3197//3197 3196//3196 3265//3265 -f 3265//3265 3196//3196 3228//3228 -f 3265//3265 3228//3228 3402//3402 -f 3402//3402 3228//3228 3230//3230 -f 3402//3402 3230//3230 3401//3401 -f 3401//3401 3230//3230 3291//3291 -f 3401//3401 3291//3291 3399//3399 -f 3399//3399 3291//3291 3407//3407 -f 3408//3408 3409//3409 3410//3410 -f 3205//3205 3248//3248 3293//3293 -f 3293//3293 3248//3248 3411//3411 -f 3293//3293 3411//3411 3292//3292 -f 3292//3292 3411//3411 3408//3408 -f 3292//3292 3408//3408 3291//3291 -f 3291//3291 3408//3408 3410//3410 -f 3291//3291 3410//3410 3407//3407 -f 3203//3203 3247//3247 3248//3248 -f 3248//3248 3247//3247 3295//3295 -f 3248//3248 3295//3295 3411//3411 -f 3411//3411 3295//3295 3317//3317 -f 3411//3411 3317//3317 3408//3408 -f 3408//3408 3317//3317 3412//3412 -f 3408//3408 3412//3412 3409//3409 -f 3413//3413 3414//3414 3415//3415 -f 3415//3415 3414//3414 3319//3319 -f 3415//3415 3319//3319 3416//3416 -f 3416//3416 3319//3319 3294//3294 -f 3416//3416 3294//3294 3246//3246 -f 3246//3246 3294//3294 3247//3247 -f 3246//3246 3247//3247 3224//3224 -f 3224//3224 3247//3247 3202//3202 -f 3414//3414 3417//3417 3319//3319 -f 3319//3319 3417//3417 3418//3418 -f 3319//3319 3418//3418 3318//3318 -f 3318//3318 3418//3418 3419//3419 -f 3318//3318 3419//3419 3317//3317 -f 3317//3317 3419//3419 3420//3420 -f 3317//3317 3420//3420 3412//3412 -f 3223//3223 3222//3222 3246//3246 -f 3246//3246 3222//3222 3225//3225 -f 3246//3246 3225//3225 3416//3416 -f 3416//3416 3225//3225 3227//3227 -f 3416//3416 3227//3227 3415//3415 -f 3415//3415 3227//3227 3296//3296 -f 3415//3415 3296//3296 3413//3413 -f 3413//3413 3296//3296 3324//3324 -f 3367//3367 3421//3421 3364//3364 -f 3364//3364 3421//3421 3422//3422 -f 3364//3364 3422//3422 3355//3355 -f 3355//3355 3422//3422 3423//3423 -f 3355//3355 3423//3423 3356//3356 -f 3356//3356 3423//3423 3424//3424 -f 3356//3356 3424//3424 3360//3360 -f 3360//3360 3424//3424 3425//3425 -f 3360//3360 3425//3425 3361//3361 -f 3426//3426 3347//3347 3346//3346 -f 3425//3425 3427//3427 3361//3361 -f 3361//3361 3427//3427 3428//3428 -f 3361//3361 3428//3428 3362//3362 -f 3362//3362 3428//3428 3429//3429 -f 3362//3362 3429//3429 3363//3363 -f 3363//3363 3429//3429 3430//3430 -f 3363//3363 3430//3430 3354//3354 -f 3354//3354 3430//3430 3431//3431 -f 3354//3354 3431//3431 3351//3351 -f 3351//3351 3431//3431 3432//3432 -f 3351//3351 3432//3432 3352//3352 -f 3352//3352 3432//3432 3433//3433 -f 3352//3352 3433//3433 3349//3349 -f 3349//3349 3433//3433 3434//3434 -f 3349//3349 3434//3434 3341//3341 -f 3341//3341 3434//3434 3435//3435 -f 3341//3341 3435//3435 3342//3342 -f 3342//3342 3435//3435 3436//3436 -f 3342//3342 3436//3436 3345//3345 -f 3345//3345 3436//3436 3437//3437 -f 3345//3345 3437//3437 3346//3346 -f 3346//3346 3437//3437 3438//3438 -f 3346//3346 3438//3438 3426//3426 -f 3426//3426 3439//3439 3347//3347 -f 3347//3347 3439//3439 3440//3440 -f 3347//3347 3440//3440 3348//3348 -f 3348//3348 3440//3440 3441//3441 -f 3348//3348 3441//3441 3340//3340 -f 3340//3340 3441//3441 3442//3442 -f 3340//3340 3442//3442 3337//3337 -f 3337//3337 3442//3442 3443//3443 -f 3337//3337 3443//3443 3338//3338 -f 3338//3338 3443//3443 3444//3444 -f 3338//3338 3444//3444 3335//3335 -f 3335//3335 3444//3444 3445//3445 -f 3335//3335 3445//3445 3326//3326 -f 3326//3326 3445//3445 3446//3446 -f 3326//3326 3446//3446 3327//3327 -f 3327//3327 3446//3446 3447//3447 -f 3327//3327 3447//3447 3331//3331 -f 3331//3331 3447//3447 3448//3448 -f 3331//3331 3448//3448 3332//3332 -f 3332//3332 3448//3448 3449//3449 -f 3332//3332 3449//3449 3333//3333 -f 3449//3449 3450//3450 3333//3333 -f 3333//3333 3450//3450 3451//3451 -f 3333//3333 3451//3451 3334//3334 -f 3334//3334 3451//3451 3452//3452 -f 3334//3334 3452//3452 3325//3325 -f 3325//3325 3452//3452 3453//3453 -f 3325//3325 3453//3453 3321//3321 -f 3321//3321 3453//3453 3454//3454 -f 3321//3321 3454//3454 3322//3322 -f 3322//3322 3454//3454 3455//3455 -f 3322//3322 3455//3455 3324//3324 -f 3324//3324 3455//3455 3456//3456 -f 3324//3324 3456//3456 3413//3413 -f 3413//3413 3456//3456 3457//3457 -f 3413//3413 3457//3457 3414//3414 -f 3457//3457 3458//3458 3414//3414 -f 3414//3414 3458//3458 3459//3459 -f 3414//3414 3459//3459 3417//3417 -f 3417//3417 3459//3459 3460//3460 -f 3417//3417 3460//3460 3418//3418 -f 3418//3418 3460//3460 3461//3461 -f 3418//3418 3461//3461 3419//3419 -f 3461//3461 3462//3462 3419//3419 -f 3419//3419 3462//3462 3463//3463 -f 3419//3419 3463//3463 3420//3420 -f 3420//3420 3463//3463 3464//3464 -f 3420//3420 3464//3464 3412//3412 -f 3412//3412 3464//3464 3409//3409 -f 3409//3409 3464//3464 3465//3465 -f 3409//3409 3465//3465 3410//3410 -f 3410//3410 3465//3465 3466//3466 -f 3410//3410 3466//3466 3407//3407 -f 3407//3407 3466//3466 3467//3467 -f 3407//3407 3467//3467 3399//3399 -f 3399//3399 3467//3467 3468//3468 -f 3399//3399 3468//3468 3400//3400 -f 3468//3468 3469//3469 3400//3400 -f 3400//3400 3469//3469 3470//3470 -f 3400//3400 3470//3470 3403//3403 -f 3403//3403 3470//3470 3471//3471 -f 3403//3403 3471//3471 3404//3404 -f 3404//3404 3471//3471 3472//3472 -f 3404//3404 3472//3472 3405//3405 -f 3472//3472 3473//3473 3405//3405 -f 3405//3405 3473//3473 3474//3474 -f 3405//3405 3474//3474 3406//3406 -f 3406//3406 3474//3474 3475//3475 -f 3406//3406 3475//3475 3398//3398 -f 3398//3398 3475//3475 3476//3476 -f 3398//3398 3476//3476 3395//3395 -f 3395//3395 3476//3476 3477//3477 -f 3395//3395 3477//3477 3396//3396 -f 3396//3396 3477//3477 3478//3478 -f 3396//3396 3478//3478 3393//3393 -f 3393//3393 3478//3478 3479//3479 -f 3393//3393 3479//3479 3385//3385 -f 3385//3385 3479//3479 3480//3480 -f 3385//3385 3480//3480 3386//3386 -f 3386//3386 3480//3480 3481//3481 -f 3386//3386 3481//3481 3389//3389 -f 3389//3389 3481//3481 3482//3482 -f 3389//3389 3482//3482 3390//3390 -f 3390//3390 3482//3482 3483//3483 -f 3390//3390 3483//3483 3391//3391 -f 3483//3483 3484//3484 3391//3391 -f 3391//3391 3484//3484 3485//3485 -f 3391//3391 3485//3485 3392//3392 -f 3392//3392 3485//3485 3486//3486 -f 3392//3392 3486//3486 3384//3384 -f 3384//3384 3486//3486 3487//3487 -f 3384//3384 3487//3487 3381//3381 -f 3381//3381 3487//3487 3488//3488 -f 3381//3381 3488//3488 3382//3382 -f 3382//3382 3488//3488 3489//3489 -f 3382//3382 3489//3489 3379//3379 -f 3489//3489 3490//3490 3379//3379 -f 3379//3379 3490//3490 3491//3491 -f 3379//3379 3491//3491 3370//3370 -f 3370//3370 3491//3491 3492//3492 -f 3370//3370 3492//3492 3371//3371 -f 3371//3371 3492//3492 3493//3493 -f 3371//3371 3493//3493 3375//3375 -f 3375//3375 3493//3493 3494//3494 -f 3375//3375 3494//3494 3376//3376 -f 3376//3376 3494//3494 3495//3495 -f 3376//3376 3495//3495 3377//3377 -f 3377//3377 3495//3495 3496//3496 -f 3377//3377 3496//3496 3378//3378 -f 3378//3378 3496//3496 3497//3497 -f 3378//3378 3497//3497 3369//3369 -f 3369//3369 3497//3497 3498//3498 -f 3369//3369 3498//3498 3366//3366 -f 3366//3366 3498//3498 3499//3499 -f 3366//3366 3499//3499 3367//3367 -f 3367//3367 3499//3499 3500//3500 -f 3367//3367 3500//3500 3421//3421 -f 3501//3501 3502//3502 3503//3503 -f 3504//3504 3505//3505 3506//3506 -f 3507//3507 3508//3508 3509//3509 -f 3510//3510 3511//3511 3512//3512 -f 3513//3513 3514//3514 3515//3515 -f 3516//3516 3517//3517 3518//3518 -f 3519//3519 3520//3520 3521//3521 -f 3522//3522 3523//3523 3524//3524 -f 3525//3525 3526//3526 3527//3527 -f 3517//3517 3528//3528 3529//3529 -f 3520//3520 3530//3530 3531//3531 -f 3523//3523 3532//3532 3533//3533 -f 3526//3526 3534//3534 3535//3535 -f 3466//3466 3465//3465 3536//3536 -f 3454//3454 3453//3453 3537//3537 -f 3537//3537 3453//3453 3538//3538 -f 3451//3451 3450//3450 3534//3534 -f 3450//3450 3449//3449 3534//3534 -f 3534//3534 3449//3449 3448//3448 -f 3534//3534 3448//3448 3535//3535 -f 3535//3535 3448//3448 3447//3447 -f 3535//3535 3447//3447 3539//3539 -f 3539//3539 3447//3447 3446//3446 -f 3539//3539 3446//3446 3540//3540 -f 3540//3540 3446//3446 3445//3445 -f 3540//3540 3445//3445 3541//3541 -f 3541//3541 3445//3445 3444//3444 -f 3444//3444 3443//3443 3541//3541 -f 3541//3541 3443//3443 3442//3442 -f 3541//3541 3442//3442 3542//3542 -f 3542//3542 3442//3442 3441//3441 -f 3542//3542 3441//3441 3543//3543 -f 3543//3543 3441//3441 3440//3440 -f 3543//3543 3440//3440 3544//3544 -f 3544//3544 3440//3440 3439//3439 -f 3439//3439 3426//3426 3544//3544 -f 3544//3544 3426//3426 3438//3438 -f 3544//3544 3438//3438 3545//3545 -f 3436//3436 3435//3435 3532//3532 -f 3435//3435 3434//3434 3532//3532 -f 3532//3532 3434//3434 3433//3433 -f 3532//3532 3433//3433 3533//3533 -f 3533//3533 3433//3433 3432//3432 -f 3533//3533 3432//3432 3546//3546 -f 3546//3546 3432//3432 3431//3431 -f 3546//3546 3431//3431 3547//3547 -f 3547//3547 3431//3431 3430//3430 -f 3547//3547 3430//3430 3548//3548 -f 3548//3548 3430//3430 3429//3429 -f 3429//3429 3428//3428 3548//3548 -f 3548//3548 3428//3428 3427//3427 -f 3548//3548 3427//3427 3549//3549 -f 3549//3549 3427//3427 3425//3425 -f 3549//3549 3425//3425 3550//3550 -f 3550//3550 3425//3425 3424//3424 -f 3550//3550 3424//3424 3551//3551 -f 3551//3551 3424//3424 3423//3423 -f 3423//3423 3422//3422 3551//3551 -f 3551//3551 3422//3422 3421//3421 -f 3551//3551 3421//3421 3552//3552 -f 3499//3499 3498//3498 3530//3530 -f 3498//3498 3497//3497 3530//3530 -f 3530//3530 3497//3497 3496//3496 -f 3530//3530 3496//3496 3531//3531 -f 3531//3531 3496//3496 3495//3495 -f 3531//3531 3495//3495 3553//3553 -f 3553//3553 3495//3495 3494//3494 -f 3553//3553 3494//3494 3554//3554 -f 3554//3554 3494//3494 3493//3493 -f 3554//3554 3493//3493 3555//3555 -f 3555//3555 3493//3493 3492//3492 -f 3492//3492 3491//3491 3555//3555 -f 3555//3555 3491//3491 3490//3490 -f 3555//3555 3490//3490 3556//3556 -f 3556//3556 3490//3490 3489//3489 -f 3556//3556 3489//3489 3557//3557 -f 3557//3557 3489//3489 3488//3488 -f 3557//3557 3488//3488 3558//3558 -f 3558//3558 3488//3488 3487//3487 -f 3487//3487 3486//3486 3558//3558 -f 3558//3558 3486//3486 3485//3485 -f 3558//3558 3485//3485 3559//3559 -f 3483//3483 3482//3482 3528//3528 -f 3482//3482 3481//3481 3528//3528 -f 3528//3528 3481//3481 3480//3480 -f 3528//3528 3480//3480 3529//3529 -f 3529//3529 3480//3480 3479//3479 -f 3529//3529 3479//3479 3560//3560 -f 3560//3560 3479//3479 3478//3478 -f 3560//3560 3478//3478 3561//3561 -f 3561//3561 3478//3478 3477//3477 -f 3561//3561 3477//3477 3562//3562 -f 3562//3562 3477//3477 3476//3476 -f 3476//3476 3475//3475 3562//3562 -f 3562//3562 3475//3475 3474//3474 -f 3562//3562 3474//3474 3563//3563 -f 3563//3563 3474//3474 3473//3473 -f 3563//3563 3473//3473 3564//3564 -f 3564//3564 3473//3473 3472//3472 -f 3564//3564 3472//3472 3565//3565 -f 3565//3565 3472//3472 3471//3471 -f 3471//3471 3470//3470 3565//3565 -f 3565//3565 3470//3470 3469//3469 -f 3565//3565 3469//3469 3566//3566 -f 3466//3466 3536//3536 3467//3467 -f 3460//3460 3567//3567 3461//3461 -f 3461//3461 3567//3567 3568//3568 -f 3461//3461 3568//3568 3462//3462 -f 3460//3460 3459//3459 3567//3567 -f 3567//3567 3459//3459 3458//3458 -f 3567//3567 3458//3458 3569//3569 -f 3569//3569 3458//3458 3457//3457 -f 3569//3569 3457//3457 3570//3570 -f 3570//3570 3457//3457 3456//3456 -f 3570//3570 3456//3456 3537//3537 -f 3537//3537 3456//3456 3455//3455 -f 3537//3537 3455//3455 3454//3454 -f 3538//3538 3571//3571 3572//3572 -f 3526//3526 3535//3535 3527//3527 -f 3527//3527 3535//3535 3539//3539 -f 3527//3527 3539//3539 3573//3573 -f 3573//3573 3539//3539 3540//3540 -f 3573//3573 3540//3540 3574//3574 -f 3574//3574 3540//3540 3541//3541 -f 3574//3574 3541//3541 3575//3575 -f 3575//3575 3541//3541 3542//3542 -f 3575//3575 3542//3542 3576//3576 -f 3576//3576 3542//3542 3543//3543 -f 3576//3576 3543//3543 3577//3577 -f 3577//3577 3543//3543 3544//3544 -f 3577//3577 3544//3544 3578//3578 -f 3578//3578 3544//3544 3545//3545 -f 3578//3578 3545//3545 3579//3579 -f 3523//3523 3533//3533 3524//3524 -f 3524//3524 3533//3533 3546//3546 -f 3524//3524 3546//3546 3580//3580 -f 3580//3580 3546//3546 3547//3547 -f 3580//3580 3547//3547 3581//3581 -f 3581//3581 3547//3547 3548//3548 -f 3581//3581 3548//3548 3582//3582 -f 3582//3582 3548//3548 3549//3549 -f 3582//3582 3549//3549 3583//3583 -f 3583//3583 3549//3549 3550//3550 -f 3583//3583 3550//3550 3584//3584 -f 3584//3584 3550//3550 3551//3551 -f 3584//3584 3551//3551 3585//3585 -f 3585//3585 3551//3551 3552//3552 -f 3585//3585 3552//3552 3586//3586 -f 3520//3520 3531//3531 3521//3521 -f 3521//3521 3531//3531 3553//3553 -f 3521//3521 3553//3553 3587//3587 -f 3587//3587 3553//3553 3554//3554 -f 3587//3587 3554//3554 3588//3588 -f 3588//3588 3554//3554 3555//3555 -f 3588//3588 3555//3555 3589//3589 -f 3589//3589 3555//3555 3556//3556 -f 3589//3589 3556//3556 3590//3590 -f 3590//3590 3556//3556 3557//3557 -f 3590//3590 3557//3557 3591//3591 -f 3591//3591 3557//3557 3558//3558 -f 3591//3591 3558//3558 3592//3592 -f 3592//3592 3558//3558 3559//3559 -f 3592//3592 3559//3559 3593//3593 -f 3517//3517 3529//3529 3518//3518 -f 3518//3518 3529//3529 3560//3560 -f 3518//3518 3560//3560 3594//3594 -f 3594//3594 3560//3560 3561//3561 -f 3594//3594 3561//3561 3595//3595 -f 3595//3595 3561//3561 3562//3562 -f 3595//3595 3562//3562 3596//3596 -f 3596//3596 3562//3562 3563//3563 -f 3596//3596 3563//3563 3597//3597 -f 3597//3597 3563//3563 3564//3564 -f 3597//3597 3564//3564 3598//3598 -f 3598//3598 3564//3564 3565//3565 -f 3598//3598 3565//3565 3599//3599 -f 3599//3599 3565//3565 3566//3566 -f 3599//3599 3566//3566 3600//3600 -f 3538//3538 3572//3572 3537//3537 -f 3537//3537 3572//3572 3601//3601 -f 3537//3537 3601//3601 3570//3570 -f 3570//3570 3601//3601 3602//3602 -f 3570//3570 3602//3602 3569//3569 -f 3569//3569 3602//3602 3603//3603 -f 3569//3569 3603//3603 3567//3567 -f 3567//3567 3603//3603 3604//3604 -f 3567//3567 3604//3604 3568//3568 -f 3571//3571 3605//3605 3606//3606 -f 3525//3525 3527//3527 3607//3607 -f 3607//3607 3527//3527 3573//3573 -f 3607//3607 3573//3573 3608//3608 -f 3608//3608 3573//3573 3574//3574 -f 3608//3608 3574//3574 3609//3609 -f 3609//3609 3574//3574 3575//3575 -f 3609//3609 3575//3575 3610//3610 -f 3610//3610 3575//3575 3576//3576 -f 3610//3610 3576//3576 3611//3611 -f 3611//3611 3576//3576 3577//3577 -f 3611//3611 3577//3577 3612//3612 -f 3612//3612 3577//3577 3578//3578 -f 3612//3612 3578//3578 3613//3613 -f 3613//3613 3578//3578 3579//3579 -f 3613//3613 3579//3579 3515//3515 -f 3522//3522 3524//3524 3614//3614 -f 3614//3614 3524//3524 3580//3580 -f 3614//3614 3580//3580 3615//3615 -f 3615//3615 3580//3580 3581//3581 -f 3615//3615 3581//3581 3616//3616 -f 3616//3616 3581//3581 3582//3582 -f 3616//3616 3582//3582 3617//3617 -f 3617//3617 3582//3582 3583//3583 -f 3617//3617 3583//3583 3618//3618 -f 3618//3618 3583//3583 3584//3584 -f 3618//3618 3584//3584 3619//3619 -f 3619//3619 3584//3584 3585//3585 -f 3619//3619 3585//3585 3620//3620 -f 3620//3620 3585//3585 3586//3586 -f 3620//3620 3586//3586 3512//3512 -f 3519//3519 3521//3521 3621//3621 -f 3621//3621 3521//3521 3587//3587 -f 3621//3621 3587//3587 3622//3622 -f 3622//3622 3587//3587 3588//3588 -f 3622//3622 3588//3588 3623//3623 -f 3623//3623 3588//3588 3589//3589 -f 3623//3623 3589//3589 3624//3624 -f 3624//3624 3589//3589 3590//3590 -f 3624//3624 3590//3590 3625//3625 -f 3625//3625 3590//3590 3591//3591 -f 3625//3625 3591//3591 3626//3626 -f 3626//3626 3591//3591 3592//3592 -f 3626//3626 3592//3592 3627//3627 -f 3627//3627 3592//3592 3593//3593 -f 3627//3627 3593//3593 3509//3509 -f 3516//3516 3518//3518 3628//3628 -f 3628//3628 3518//3518 3594//3594 -f 3628//3628 3594//3594 3629//3629 -f 3629//3629 3594//3594 3595//3595 -f 3629//3629 3595//3595 3630//3630 -f 3630//3630 3595//3595 3596//3596 -f 3630//3630 3596//3596 3631//3631 -f 3631//3631 3596//3596 3597//3597 -f 3631//3631 3597//3597 3632//3632 -f 3632//3632 3597//3597 3598//3598 -f 3632//3632 3598//3598 3633//3633 -f 3633//3633 3598//3598 3599//3599 -f 3633//3633 3599//3599 3634//3634 -f 3634//3634 3599//3599 3600//3600 -f 3634//3634 3600//3600 3506//3506 -f 3465//3465 3464//3464 3536//3536 -f 3536//3536 3464//3464 3635//3635 -f 3536//3536 3635//3635 3636//3636 -f 3636//3636 3635//3635 3637//3637 -f 3636//3636 3637//3637 3638//3638 -f 3638//3638 3637//3637 3503//3503 -f 3571//3571 3606//3606 3572//3572 -f 3572//3572 3606//3606 3639//3639 -f 3572//3572 3639//3639 3601//3601 -f 3601//3601 3639//3639 3640//3640 -f 3601//3601 3640//3640 3602//3602 -f 3602//3602 3640//3640 3641//3641 -f 3602//3602 3641//3641 3603//3603 -f 3603//3603 3641//3641 3642//3642 -f 3603//3603 3642//3642 3604//3604 -f 3643//3643 3606//3606 3644//3644 -f 3644//3644 3606//3606 3605//3605 -f 3644//3644 3605//3605 3645//3645 -f 3646//3646 3645//3645 3647//3647 -f 3647//3647 3645//3645 3605//3605 -f 3647//3647 3605//3605 3648//3648 -f 3648//3648 3605//3605 3571//3571 -f 3648//3648 3571//3571 3649//3649 -f 3649//3649 3571//3571 3538//3538 -f 3649//3649 3538//3538 3452//3452 -f 3452//3452 3538//3538 3453//3453 -f 3452//3452 3451//3451 3649//3649 -f 3649//3649 3451//3451 3534//3534 -f 3649//3649 3534//3534 3648//3648 -f 3648//3648 3534//3534 3526//3526 -f 3648//3648 3526//3526 3647//3647 -f 3647//3647 3526//3526 3525//3525 -f 3647//3647 3525//3525 3646//3646 -f 3646//3646 3525//3525 3650//3650 -f 3651//3651 3652//3652 3609//3609 -f 3609//3609 3652//3652 3653//3653 -f 3609//3609 3653//3653 3608//3608 -f 3608//3608 3653//3653 3654//3654 -f 3608//3608 3654//3654 3607//3607 -f 3607//3607 3654//3654 3655//3655 -f 3607//3607 3655//3655 3525//3525 -f 3525//3525 3655//3655 3656//3656 -f 3525//3525 3656//3656 3650//3650 -f 3651//3651 3609//3609 3657//3657 -f 3657//3657 3609//3609 3610//3610 -f 3657//3657 3610//3610 3658//3658 -f 3658//3658 3610//3610 3611//3611 -f 3658//3658 3611//3611 3659//3659 -f 3659//3659 3611//3611 3612//3612 -f 3659//3659 3612//3612 3660//3660 -f 3660//3660 3612//3612 3613//3613 -f 3660//3660 3613//3613 3661//3661 -f 3515//3515 3514//3514 3613//3613 -f 3613//3613 3514//3514 3662//3662 -f 3613//3613 3662//3662 3661//3661 -f 3663//3663 3513//3513 3664//3664 -f 3664//3664 3513//3513 3515//3515 -f 3664//3664 3515//3515 3665//3665 -f 3665//3665 3515//3515 3579//3579 -f 3665//3665 3579//3579 3666//3666 -f 3666//3666 3579//3579 3545//3545 -f 3666//3666 3545//3545 3437//3437 -f 3437//3437 3545//3545 3438//3438 -f 3437//3437 3436//3436 3666//3666 -f 3666//3666 3436//3436 3532//3532 -f 3666//3666 3532//3532 3665//3665 -f 3665//3665 3532//3532 3523//3523 -f 3665//3665 3523//3523 3664//3664 -f 3664//3664 3523//3523 3522//3522 -f 3664//3664 3522//3522 3663//3663 -f 3663//3663 3522//3522 3667//3667 -f 3668//3668 3669//3669 3616//3616 -f 3616//3616 3669//3669 3670//3670 -f 3616//3616 3670//3670 3615//3615 -f 3615//3615 3670//3670 3671//3671 -f 3615//3615 3671//3671 3614//3614 -f 3614//3614 3671//3671 3672//3672 -f 3614//3614 3672//3672 3522//3522 -f 3522//3522 3672//3672 3673//3673 -f 3522//3522 3673//3673 3667//3667 -f 3668//3668 3616//3616 3674//3674 -f 3674//3674 3616//3616 3617//3617 -f 3674//3674 3617//3617 3675//3675 -f 3675//3675 3617//3617 3618//3618 -f 3675//3675 3618//3618 3676//3676 -f 3676//3676 3618//3618 3619//3619 -f 3676//3676 3619//3619 3677//3677 -f 3677//3677 3619//3619 3620//3620 -f 3677//3677 3620//3620 3678//3678 -f 3512//3512 3511//3511 3620//3620 -f 3620//3620 3511//3511 3679//3679 -f 3620//3620 3679//3679 3678//3678 -f 3680//3680 3510//3510 3681//3681 -f 3681//3681 3510//3510 3512//3512 -f 3681//3681 3512//3512 3682//3682 -f 3682//3682 3512//3512 3586//3586 -f 3682//3682 3586//3586 3683//3683 -f 3683//3683 3586//3586 3552//3552 -f 3683//3683 3552//3552 3500//3500 -f 3500//3500 3552//3552 3421//3421 -f 3500//3500 3499//3499 3683//3683 -f 3683//3683 3499//3499 3530//3530 -f 3683//3683 3530//3530 3682//3682 -f 3682//3682 3530//3530 3520//3520 -f 3682//3682 3520//3520 3681//3681 -f 3681//3681 3520//3520 3519//3519 -f 3681//3681 3519//3519 3680//3680 -f 3680//3680 3519//3519 3684//3684 -f 3685//3685 3686//3686 3623//3623 -f 3623//3623 3686//3686 3687//3687 -f 3623//3623 3687//3687 3622//3622 -f 3622//3622 3687//3687 3688//3688 -f 3622//3622 3688//3688 3621//3621 -f 3621//3621 3688//3688 3689//3689 -f 3621//3621 3689//3689 3519//3519 -f 3519//3519 3689//3689 3690//3690 -f 3519//3519 3690//3690 3684//3684 -f 3685//3685 3623//3623 3691//3691 -f 3691//3691 3623//3623 3624//3624 -f 3691//3691 3624//3624 3692//3692 -f 3692//3692 3624//3624 3625//3625 -f 3692//3692 3625//3625 3693//3693 -f 3693//3693 3625//3625 3626//3626 -f 3693//3693 3626//3626 3694//3694 -f 3694//3694 3626//3626 3627//3627 -f 3694//3694 3627//3627 3695//3695 -f 3509//3509 3508//3508 3627//3627 -f 3627//3627 3508//3508 3696//3696 -f 3627//3627 3696//3696 3695//3695 -f 3697//3697 3507//3507 3698//3698 -f 3698//3698 3507//3507 3509//3509 -f 3698//3698 3509//3509 3699//3699 -f 3699//3699 3509//3509 3593//3593 -f 3699//3699 3593//3593 3700//3700 -f 3700//3700 3593//3593 3559//3559 -f 3700//3700 3559//3559 3484//3484 -f 3484//3484 3559//3559 3485//3485 -f 3484//3484 3483//3483 3700//3700 -f 3700//3700 3483//3483 3528//3528 -f 3700//3700 3528//3528 3699//3699 -f 3699//3699 3528//3528 3517//3517 -f 3699//3699 3517//3517 3698//3698 -f 3698//3698 3517//3517 3516//3516 -f 3698//3698 3516//3516 3697//3697 -f 3697//3697 3516//3516 3701//3701 -f 3702//3702 3703//3703 3630//3630 -f 3630//3630 3703//3703 3704//3704 -f 3630//3630 3704//3704 3629//3629 -f 3629//3629 3704//3704 3705//3705 -f 3629//3629 3705//3705 3628//3628 -f 3628//3628 3705//3705 3706//3706 -f 3628//3628 3706//3706 3516//3516 -f 3516//3516 3706//3706 3707//3707 -f 3516//3516 3707//3707 3701//3701 -f 3702//3702 3630//3630 3708//3708 -f 3708//3708 3630//3630 3631//3631 -f 3708//3708 3631//3631 3709//3709 -f 3709//3709 3631//3631 3632//3632 -f 3709//3709 3632//3632 3710//3710 -f 3710//3710 3632//3632 3633//3633 -f 3710//3710 3633//3633 3711//3711 -f 3711//3711 3633//3633 3634//3634 -f 3711//3711 3634//3634 3712//3712 -f 3506//3506 3505//3505 3634//3634 -f 3634//3634 3505//3505 3713//3713 -f 3634//3634 3713//3713 3712//3712 -f 3714//3714 3504//3504 3715//3715 -f 3715//3715 3504//3504 3506//3506 -f 3715//3715 3506//3506 3716//3716 -f 3716//3716 3506//3506 3600//3600 -f 3716//3716 3600//3600 3717//3717 -f 3717//3717 3600//3600 3566//3566 -f 3717//3717 3566//3566 3468//3468 -f 3468//3468 3566//3566 3469//3469 -f 3468//3468 3467//3467 3717//3717 -f 3717//3717 3467//3467 3536//3536 -f 3717//3717 3536//3536 3716//3716 -f 3716//3716 3536//3536 3636//3636 -f 3716//3716 3636//3636 3715//3715 -f 3715//3715 3636//3636 3638//3638 -f 3715//3715 3638//3638 3714//3714 -f 3714//3714 3638//3638 3718//3718 -f 3503//3503 3502//3502 3638//3638 -f 3638//3638 3502//3502 3719//3719 -f 3638//3638 3719//3719 3718//3718 -f 3720//3720 3501//3501 3721//3721 -f 3721//3721 3501//3501 3503//3503 -f 3721//3721 3503//3503 3722//3722 -f 3722//3722 3503//3503 3637//3637 -f 3722//3722 3637//3637 3723//3723 -f 3723//3723 3637//3637 3635//3635 -f 3723//3723 3635//3635 3463//3463 -f 3463//3463 3635//3635 3464//3464 -f 3463//3463 3462//3462 3723//3723 -f 3723//3723 3462//3462 3568//3568 -f 3723//3723 3568//3568 3722//3722 -f 3722//3722 3568//3568 3604//3604 -f 3722//3722 3604//3604 3721//3721 -f 3721//3721 3604//3604 3642//3642 -f 3721//3721 3642//3642 3720//3720 -f 3720//3720 3642//3642 3724//3724 -f 3643//3643 3725//3725 3606//3606 -f 3606//3606 3725//3725 3726//3726 -f 3606//3606 3726//3726 3639//3639 -f 3639//3639 3726//3726 3727//3727 -f 3639//3639 3727//3727 3640//3640 -f 3640//3640 3727//3727 3728//3728 -f 3640//3640 3728//3728 3641//3641 -f 3641//3641 3728//3728 3729//3729 -f 3641//3641 3729//3729 3642//3642 -f 3642//3642 3729//3729 3730//3730 -f 3642//3642 3730//3730 3724//3724 -f 3731//3731 3646//3646 3732//3732 -f 3732//3732 3646//3646 3650//3650 -f 3732//3732 3650//3650 3733//3733 -f 3733//3733 3650//3650 3656//3656 -f 3733//3733 3656//3656 3734//3734 -f 3734//3734 3656//3656 3655//3655 -f 3734//3734 3655//3655 3735//3735 -f 3735//3735 3655//3655 3654//3654 -f 3735//3735 3654//3654 3736//3736 -f 3667//3667 3737//3737 3738//3738 -f 3654//3654 3653//3653 3736//3736 -f 3736//3736 3653//3653 3652//3652 -f 3736//3736 3652//3652 3739//3739 -f 3739//3739 3652//3652 3651//3651 -f 3739//3739 3651//3651 3740//3740 -f 3740//3740 3651//3651 3657//3657 -f 3740//3740 3657//3657 3741//3741 -f 3741//3741 3657//3657 3658//3658 -f 3741//3741 3658//3658 3742//3742 -f 3742//3742 3658//3658 3659//3659 -f 3742//3742 3659//3659 3743//3743 -f 3743//3743 3659//3659 3660//3660 -f 3743//3743 3660//3660 3744//3744 -f 3744//3744 3660//3660 3661//3661 -f 3744//3744 3661//3661 3745//3745 -f 3745//3745 3661//3661 3662//3662 -f 3745//3745 3662//3662 3746//3746 -f 3746//3746 3662//3662 3514//3514 -f 3746//3746 3514//3514 3747//3747 -f 3747//3747 3514//3514 3513//3513 -f 3747//3747 3513//3513 3738//3738 -f 3738//3738 3513//3513 3663//3663 -f 3738//3738 3663//3663 3667//3667 -f 3667//3667 3673//3673 3737//3737 -f 3737//3737 3673//3673 3672//3672 -f 3737//3737 3672//3672 3748//3748 -f 3748//3748 3672//3672 3671//3671 -f 3748//3748 3671//3671 3749//3749 -f 3749//3749 3671//3671 3670//3670 -f 3749//3749 3670//3670 3750//3750 -f 3750//3750 3670//3670 3669//3669 -f 3750//3750 3669//3669 3751//3751 -f 3751//3751 3669//3669 3668//3668 -f 3751//3751 3668//3668 3752//3752 -f 3752//3752 3668//3668 3674//3674 -f 3752//3752 3674//3674 3753//3753 -f 3753//3753 3674//3674 3675//3675 -f 3753//3753 3675//3675 3754//3754 -f 3754//3754 3675//3675 3676//3676 -f 3754//3754 3676//3676 3755//3755 -f 3755//3755 3676//3676 3677//3677 -f 3755//3755 3677//3677 3756//3756 -f 3756//3756 3677//3677 3678//3678 -f 3756//3756 3678//3678 3757//3757 -f 3678//3678 3679//3679 3757//3757 -f 3757//3757 3679//3679 3511//3511 -f 3757//3757 3511//3511 3758//3758 -f 3758//3758 3511//3511 3510//3510 -f 3758//3758 3510//3510 3759//3759 -f 3759//3759 3510//3510 3680//3680 -f 3759//3759 3680//3680 3760//3760 -f 3760//3760 3680//3680 3684//3684 -f 3760//3760 3684//3684 3761//3761 -f 3761//3761 3684//3684 3690//3690 -f 3761//3761 3690//3690 3762//3762 -f 3762//3762 3690//3690 3689//3689 -f 3762//3762 3689//3689 3763//3763 -f 3763//3763 3689//3689 3688//3688 -f 3763//3763 3688//3688 3764//3764 -f 3688//3688 3687//3687 3764//3764 -f 3764//3764 3687//3687 3686//3686 -f 3764//3764 3686//3686 3765//3765 -f 3765//3765 3686//3686 3685//3685 -f 3765//3765 3685//3685 3766//3766 -f 3766//3766 3685//3685 3691//3691 -f 3766//3766 3691//3691 3767//3767 -f 3691//3691 3692//3692 3767//3767 -f 3767//3767 3692//3692 3693//3693 -f 3767//3767 3693//3693 3768//3768 -f 3768//3768 3693//3693 3694//3694 -f 3768//3768 3694//3694 3769//3769 -f 3769//3769 3694//3694 3770//3770 -f 3770//3770 3694//3694 3695//3695 -f 3770//3770 3695//3695 3771//3771 -f 3771//3771 3695//3695 3696//3696 -f 3771//3771 3696//3696 3772//3772 -f 3772//3772 3696//3696 3508//3508 -f 3772//3772 3508//3508 3773//3773 -f 3773//3773 3508//3508 3507//3507 -f 3773//3773 3507//3507 3774//3774 -f 3507//3507 3697//3697 3774//3774 -f 3774//3774 3697//3697 3701//3701 -f 3774//3774 3701//3701 3775//3775 -f 3775//3775 3701//3701 3707//3707 -f 3775//3775 3707//3707 3776//3776 -f 3776//3776 3707//3707 3706//3706 -f 3776//3776 3706//3706 3777//3777 -f 3706//3706 3705//3705 3777//3777 -f 3777//3777 3705//3705 3704//3704 -f 3777//3777 3704//3704 3778//3778 -f 3778//3778 3704//3704 3703//3703 -f 3778//3778 3703//3703 3779//3779 -f 3779//3779 3703//3703 3702//3702 -f 3779//3779 3702//3702 3780//3780 -f 3780//3780 3702//3702 3708//3708 -f 3780//3780 3708//3708 3781//3781 -f 3781//3781 3708//3708 3709//3709 -f 3781//3781 3709//3709 3782//3782 -f 3782//3782 3709//3709 3710//3710 -f 3782//3782 3710//3710 3783//3783 -f 3783//3783 3710//3710 3711//3711 -f 3783//3783 3711//3711 3784//3784 -f 3784//3784 3711//3711 3712//3712 -f 3784//3784 3712//3712 3785//3785 -f 3785//3785 3712//3712 3713//3713 -f 3785//3785 3713//3713 3786//3786 -f 3786//3786 3713//3713 3505//3505 -f 3786//3786 3505//3505 3787//3787 -f 3505//3505 3504//3504 3787//3787 -f 3787//3787 3504//3504 3714//3714 -f 3787//3787 3714//3714 3788//3788 -f 3788//3788 3714//3714 3718//3718 -f 3788//3788 3718//3718 3789//3789 -f 3789//3789 3718//3718 3719//3719 -f 3789//3789 3719//3719 3790//3790 -f 3790//3790 3719//3719 3502//3502 -f 3790//3790 3502//3502 3791//3791 -f 3791//3791 3502//3502 3501//3501 -f 3791//3791 3501//3501 3792//3792 -f 3501//3501 3720//3720 3792//3792 -f 3792//3792 3720//3720 3724//3724 -f 3792//3792 3724//3724 3793//3793 -f 3793//3793 3724//3724 3730//3730 -f 3793//3793 3730//3730 3794//3794 -f 3794//3794 3730//3730 3729//3729 -f 3794//3794 3729//3729 3795//3795 -f 3795//3795 3729//3729 3728//3728 -f 3795//3795 3728//3728 3796//3796 -f 3796//3796 3728//3728 3727//3727 -f 3796//3796 3727//3727 3797//3797 -f 3797//3797 3727//3727 3726//3726 -f 3797//3797 3726//3726 3798//3798 -f 3798//3798 3726//3726 3725//3725 -f 3798//3798 3725//3725 3799//3799 -f 3799//3799 3725//3725 3643//3643 -f 3799//3799 3643//3643 3800//3800 -f 3800//3800 3643//3643 3644//3644 -f 3800//3800 3644//3644 3731//3731 -f 3731//3731 3644//3644 3645//3645 -f 3731//3731 3645//3645 3646//3646 -f 3801//3801 3802//3802 3803//3803 -f 3804//3804 3805//3805 3806//3806 -f 3807//3807 3808//3808 3809//3809 -f 3810//3810 3811//3811 3812//3812 -f 3813//3813 3814//3814 3815//3815 -f 3816//3816 3817//3817 3818//3818 -f 3819//3819 3820//3820 3821//3821 -f 3793//3793 3794//3794 3801//3801 -f 3791//3791 3792//3792 3822//3822 -f 3789//3789 3790//3790 3823//3823 -f 3783//3783 3784//3784 3804//3804 -f 3781//3781 3782//3782 3824//3824 -f 3779//3779 3780//3780 3825//3825 -f 3773//3773 3774//3774 3807//3807 -f 3771//3771 3772//3772 3826//3826 -f 3769//3769 3770//3770 3827//3827 -f 3763//3763 3764//3764 3810//3810 -f 3761//3761 3762//3762 3828//3828 -f 3759//3759 3760//3760 3829//3829 -f 3753//3753 3754//3754 3813//3813 -f 3751//3751 3752//3752 3830//3830 -f 3749//3749 3750//3750 3831//3831 -f 3745//3745 3746//3746 3816//3816 -f 3743//3743 3744//3744 3832//3832 -f 3741//3741 3742//3742 3833//3833 -f 3733//3733 3734//3734 3819//3819 -f 3731//3731 3732//3732 3834//3834 -f 3799//3799 3800//3800 3835//3835 -f 3797//3797 3798//3798 3836//3836 -f 3836//3836 3798//3798 3799//3799 -f 3819//3819 3734//3734 3820//3820 -f 3820//3820 3734//3734 3735//3735 -f 3820//3820 3735//3735 3736//3736 -f 3739//3739 3740//3740 3837//3837 -f 3837//3837 3740//3740 3741//3741 -f 3816//3816 3746//3746 3817//3817 -f 3817//3817 3746//3746 3747//3747 -f 3817//3817 3747//3747 3738//3738 -f 3737//3737 3748//3748 3838//3838 -f 3838//3838 3748//3748 3749//3749 -f 3813//3813 3754//3754 3814//3814 -f 3814//3814 3754//3754 3755//3755 -f 3814//3814 3755//3755 3756//3756 -f 3757//3757 3758//3758 3839//3839 -f 3839//3839 3758//3758 3759//3759 -f 3810//3810 3764//3764 3811//3811 -f 3811//3811 3764//3764 3765//3765 -f 3811//3811 3765//3765 3766//3766 -f 3767//3767 3768//3768 3840//3840 -f 3840//3840 3768//3768 3769//3769 -f 3807//3807 3774//3774 3808//3808 -f 3808//3808 3774//3774 3775//3775 -f 3808//3808 3775//3775 3776//3776 -f 3777//3777 3778//3778 3841//3841 -f 3841//3841 3778//3778 3779//3779 -f 3804//3804 3784//3784 3805//3805 -f 3805//3805 3784//3784 3785//3785 -f 3805//3805 3785//3785 3786//3786 -f 3787//3787 3788//3788 3842//3842 -f 3842//3842 3788//3788 3789//3789 -f 3801//3801 3794//3794 3802//3802 -f 3802//3802 3794//3794 3795//3795 -f 3802//3802 3795//3795 3796//3796 -f 3843//3843 3844//3844 3835//3835 -f 3845//3845 3821//3821 3846//3846 -f 3846//3846 3821//3821 3820//3820 -f 3846//3846 3820//3820 3847//3847 -f 3847//3847 3820//3820 3736//3736 -f 3847//3847 3736//3736 3739//3739 -f 3848//3848 3849//3849 3833//3833 -f 3850//3850 3818//3818 3851//3851 -f 3851//3851 3818//3818 3817//3817 -f 3851//3851 3817//3817 3852//3852 -f 3852//3852 3817//3817 3738//3738 -f 3852//3852 3738//3738 3737//3737 -f 3853//3853 3854//3854 3831//3831 -f 3855//3855 3815//3815 3856//3856 -f 3856//3856 3815//3815 3814//3814 -f 3856//3856 3814//3814 3857//3857 -f 3857//3857 3814//3814 3756//3756 -f 3857//3857 3756//3756 3757//3757 -f 3858//3858 3859//3859 3829//3829 -f 3860//3860 3812//3812 3861//3861 -f 3861//3861 3812//3812 3811//3811 -f 3861//3861 3811//3811 3862//3862 -f 3862//3862 3811//3811 3766//3766 -f 3862//3862 3766//3766 3767//3767 -f 3863//3863 3864//3864 3827//3827 -f 3865//3865 3809//3809 3866//3866 -f 3866//3866 3809//3809 3808//3808 -f 3866//3866 3808//3808 3867//3867 -f 3867//3867 3808//3808 3776//3776 -f 3867//3867 3776//3776 3777//3777 -f 3868//3868 3869//3869 3825//3825 -f 3870//3870 3806//3806 3871//3871 -f 3871//3871 3806//3806 3805//3805 -f 3871//3871 3805//3805 3872//3872 -f 3872//3872 3805//3805 3786//3786 -f 3872//3872 3786//3786 3787//3787 -f 3873//3873 3874//3874 3823//3823 -f 3875//3875 3803//3803 3876//3876 -f 3876//3876 3803//3803 3802//3802 -f 3876//3876 3802//3802 3877//3877 -f 3877//3877 3802//3802 3796//3796 -f 3877//3877 3796//3796 3797//3797 -f 3878//3878 3844//3844 3879//3879 -f 3879//3879 3844//3844 3843//3843 -f 3879//3879 3843//3843 3880//3880 -f 3881//3881 3849//3849 3882//3882 -f 3882//3882 3849//3849 3848//3848 -f 3882//3882 3848//3848 3883//3883 -f 3884//3884 3854//3854 3885//3885 -f 3885//3885 3854//3854 3853//3853 -f 3885//3885 3853//3853 3886//3886 -f 3887//3887 3859//3859 3888//3888 -f 3888//3888 3859//3859 3858//3858 -f 3888//3888 3858//3858 3889//3889 -f 3890//3890 3864//3864 3891//3891 -f 3891//3891 3864//3864 3863//3863 -f 3891//3891 3863//3863 3892//3892 -f 3893//3893 3869//3869 3894//3894 -f 3894//3894 3869//3869 3868//3868 -f 3894//3894 3868//3868 3895//3895 -f 3896//3896 3874//3874 3897//3897 -f 3897//3897 3874//3874 3873//3873 -f 3897//3897 3873//3873 3898//3898 -f 3899//3899 3900//3900 3901//3901 -f 3797//3797 3836//3836 3877//3877 -f 3877//3877 3836//3836 3902//3902 -f 3877//3877 3902//3902 3876//3876 -f 3876//3876 3902//3902 3899//3899 -f 3876//3876 3899//3899 3875//3875 -f 3875//3875 3899//3899 3901//3901 -f 3875//3875 3901//3901 3903//3903 -f 3799//3799 3835//3835 3836//3836 -f 3836//3836 3835//3835 3844//3844 -f 3836//3836 3844//3844 3902//3902 -f 3902//3902 3844//3844 3878//3878 -f 3902//3902 3878//3878 3899//3899 -f 3899//3899 3878//3878 3904//3904 -f 3899//3899 3904//3904 3900//3900 -f 3905//3905 3906//3906 3907//3907 -f 3907//3907 3906//3906 3880//3880 -f 3907//3907 3880//3880 3908//3908 -f 3908//3908 3880//3880 3843//3843 -f 3908//3908 3843//3843 3834//3834 -f 3834//3834 3843//3843 3835//3835 -f 3834//3834 3835//3835 3731//3731 -f 3731//3731 3835//3835 3800//3800 -f 3906//3906 3909//3909 3880//3880 -f 3880//3880 3909//3909 3910//3910 -f 3880//3880 3910//3910 3879//3879 -f 3879//3879 3910//3910 3911//3911 -f 3879//3879 3911//3911 3878//3878 -f 3878//3878 3911//3911 3912//3912 -f 3878//3878 3912//3912 3904//3904 -f 3732//3732 3733//3733 3834//3834 -f 3834//3834 3733//3733 3819//3819 -f 3834//3834 3819//3819 3908//3908 -f 3908//3908 3819//3819 3821//3821 -f 3908//3908 3821//3821 3907//3907 -f 3907//3907 3821//3821 3845//3845 -f 3907//3907 3845//3845 3905//3905 -f 3905//3905 3845//3845 3913//3913 -f 3914//3914 3915//3915 3916//3916 -f 3739//3739 3837//3837 3847//3847 -f 3847//3847 3837//3837 3917//3917 -f 3847//3847 3917//3917 3846//3846 -f 3846//3846 3917//3917 3914//3914 -f 3846//3846 3914//3914 3845//3845 -f 3845//3845 3914//3914 3916//3916 -f 3845//3845 3916//3916 3913//3913 -f 3741//3741 3833//3833 3837//3837 -f 3837//3837 3833//3833 3849//3849 -f 3837//3837 3849//3849 3917//3917 -f 3917//3917 3849//3849 3881//3881 -f 3917//3917 3881//3881 3914//3914 -f 3914//3914 3881//3881 3918//3918 -f 3914//3914 3918//3918 3915//3915 -f 3919//3919 3920//3920 3921//3921 -f 3921//3921 3920//3920 3883//3883 -f 3921//3921 3883//3883 3922//3922 -f 3922//3922 3883//3883 3848//3848 -f 3922//3922 3848//3848 3832//3832 -f 3832//3832 3848//3848 3833//3833 -f 3832//3832 3833//3833 3743//3743 -f 3743//3743 3833//3833 3742//3742 -f 3920//3920 3923//3923 3883//3883 -f 3883//3883 3923//3923 3924//3924 -f 3883//3883 3924//3924 3882//3882 -f 3882//3882 3924//3924 3925//3925 -f 3882//3882 3925//3925 3881//3881 -f 3881//3881 3925//3925 3926//3926 -f 3881//3881 3926//3926 3918//3918 -f 3744//3744 3745//3745 3832//3832 -f 3832//3832 3745//3745 3816//3816 -f 3832//3832 3816//3816 3922//3922 -f 3922//3922 3816//3816 3818//3818 -f 3922//3922 3818//3818 3921//3921 -f 3921//3921 3818//3818 3850//3850 -f 3921//3921 3850//3850 3919//3919 -f 3919//3919 3850//3850 3927//3927 -f 3928//3928 3929//3929 3930//3930 -f 3737//3737 3838//3838 3852//3852 -f 3852//3852 3838//3838 3931//3931 -f 3852//3852 3931//3931 3851//3851 -f 3851//3851 3931//3931 3928//3928 -f 3851//3851 3928//3928 3850//3850 -f 3850//3850 3928//3928 3930//3930 -f 3850//3850 3930//3930 3927//3927 -f 3749//3749 3831//3831 3838//3838 -f 3838//3838 3831//3831 3854//3854 -f 3838//3838 3854//3854 3931//3931 -f 3931//3931 3854//3854 3884//3884 -f 3931//3931 3884//3884 3928//3928 -f 3928//3928 3884//3884 3932//3932 -f 3928//3928 3932//3932 3929//3929 -f 3933//3933 3934//3934 3935//3935 -f 3935//3935 3934//3934 3886//3886 -f 3935//3935 3886//3886 3936//3936 -f 3936//3936 3886//3886 3853//3853 -f 3936//3936 3853//3853 3830//3830 -f 3830//3830 3853//3853 3831//3831 -f 3830//3830 3831//3831 3751//3751 -f 3751//3751 3831//3831 3750//3750 -f 3934//3934 3937//3937 3886//3886 -f 3886//3886 3937//3937 3938//3938 -f 3886//3886 3938//3938 3885//3885 -f 3885//3885 3938//3938 3939//3939 -f 3885//3885 3939//3939 3884//3884 -f 3884//3884 3939//3939 3940//3940 -f 3884//3884 3940//3940 3932//3932 -f 3752//3752 3753//3753 3830//3830 -f 3830//3830 3753//3753 3813//3813 -f 3830//3830 3813//3813 3936//3936 -f 3936//3936 3813//3813 3815//3815 -f 3936//3936 3815//3815 3935//3935 -f 3935//3935 3815//3815 3855//3855 -f 3935//3935 3855//3855 3933//3933 -f 3933//3933 3855//3855 3941//3941 -f 3942//3942 3943//3943 3944//3944 -f 3757//3757 3839//3839 3857//3857 -f 3857//3857 3839//3839 3945//3945 -f 3857//3857 3945//3945 3856//3856 -f 3856//3856 3945//3945 3942//3942 -f 3856//3856 3942//3942 3855//3855 -f 3855//3855 3942//3942 3944//3944 -f 3855//3855 3944//3944 3941//3941 -f 3759//3759 3829//3829 3839//3839 -f 3839//3839 3829//3829 3859//3859 -f 3839//3839 3859//3859 3945//3945 -f 3945//3945 3859//3859 3887//3887 -f 3945//3945 3887//3887 3942//3942 -f 3942//3942 3887//3887 3946//3946 -f 3942//3942 3946//3946 3943//3943 -f 3947//3947 3948//3948 3949//3949 -f 3949//3949 3948//3948 3889//3889 -f 3949//3949 3889//3889 3950//3950 -f 3950//3950 3889//3889 3858//3858 -f 3950//3950 3858//3858 3828//3828 -f 3828//3828 3858//3858 3829//3829 -f 3828//3828 3829//3829 3761//3761 -f 3761//3761 3829//3829 3760//3760 -f 3948//3948 3951//3951 3889//3889 -f 3889//3889 3951//3951 3952//3952 -f 3889//3889 3952//3952 3888//3888 -f 3888//3888 3952//3952 3953//3953 -f 3888//3888 3953//3953 3887//3887 -f 3887//3887 3953//3953 3954//3954 -f 3887//3887 3954//3954 3946//3946 -f 3762//3762 3763//3763 3828//3828 -f 3828//3828 3763//3763 3810//3810 -f 3828//3828 3810//3810 3950//3950 -f 3950//3950 3810//3810 3812//3812 -f 3950//3950 3812//3812 3949//3949 -f 3949//3949 3812//3812 3860//3860 -f 3949//3949 3860//3860 3947//3947 -f 3947//3947 3860//3860 3955//3955 -f 3956//3956 3957//3957 3958//3958 -f 3767//3767 3840//3840 3862//3862 -f 3862//3862 3840//3840 3959//3959 -f 3862//3862 3959//3959 3861//3861 -f 3861//3861 3959//3959 3956//3956 -f 3861//3861 3956//3956 3860//3860 -f 3860//3860 3956//3956 3958//3958 -f 3860//3860 3958//3958 3955//3955 -f 3769//3769 3827//3827 3840//3840 -f 3840//3840 3827//3827 3864//3864 -f 3840//3840 3864//3864 3959//3959 -f 3959//3959 3864//3864 3890//3890 -f 3959//3959 3890//3890 3956//3956 -f 3956//3956 3890//3890 3960//3960 -f 3956//3956 3960//3960 3957//3957 -f 3961//3961 3962//3962 3963//3963 -f 3963//3963 3962//3962 3892//3892 -f 3963//3963 3892//3892 3964//3964 -f 3964//3964 3892//3892 3863//3863 -f 3964//3964 3863//3863 3826//3826 -f 3826//3826 3863//3863 3827//3827 -f 3826//3826 3827//3827 3771//3771 -f 3771//3771 3827//3827 3770//3770 -f 3962//3962 3965//3965 3892//3892 -f 3892//3892 3965//3965 3966//3966 -f 3892//3892 3966//3966 3891//3891 -f 3891//3891 3966//3966 3967//3967 -f 3891//3891 3967//3967 3890//3890 -f 3890//3890 3967//3967 3968//3968 -f 3890//3890 3968//3968 3960//3960 -f 3772//3772 3773//3773 3826//3826 -f 3826//3826 3773//3773 3807//3807 -f 3826//3826 3807//3807 3964//3964 -f 3964//3964 3807//3807 3809//3809 -f 3964//3964 3809//3809 3963//3963 -f 3963//3963 3809//3809 3865//3865 -f 3963//3963 3865//3865 3961//3961 -f 3961//3961 3865//3865 3969//3969 -f 3970//3970 3971//3971 3972//3972 -f 3777//3777 3841//3841 3867//3867 -f 3867//3867 3841//3841 3973//3973 -f 3867//3867 3973//3973 3866//3866 -f 3866//3866 3973//3973 3970//3970 -f 3866//3866 3970//3970 3865//3865 -f 3865//3865 3970//3970 3972//3972 -f 3865//3865 3972//3972 3969//3969 -f 3779//3779 3825//3825 3841//3841 -f 3841//3841 3825//3825 3869//3869 -f 3841//3841 3869//3869 3973//3973 -f 3973//3973 3869//3869 3893//3893 -f 3973//3973 3893//3893 3970//3970 -f 3970//3970 3893//3893 3974//3974 -f 3970//3970 3974//3974 3971//3971 -f 3975//3975 3976//3976 3977//3977 -f 3977//3977 3976//3976 3895//3895 -f 3977//3977 3895//3895 3978//3978 -f 3978//3978 3895//3895 3868//3868 -f 3978//3978 3868//3868 3824//3824 -f 3824//3824 3868//3868 3825//3825 -f 3824//3824 3825//3825 3781//3781 -f 3781//3781 3825//3825 3780//3780 -f 3976//3976 3979//3979 3895//3895 -f 3895//3895 3979//3979 3980//3980 -f 3895//3895 3980//3980 3894//3894 -f 3894//3894 3980//3980 3981//3981 -f 3894//3894 3981//3981 3893//3893 -f 3893//3893 3981//3981 3982//3982 -f 3893//3893 3982//3982 3974//3974 -f 3782//3782 3783//3783 3824//3824 -f 3824//3824 3783//3783 3804//3804 -f 3824//3824 3804//3804 3978//3978 -f 3978//3978 3804//3804 3806//3806 -f 3978//3978 3806//3806 3977//3977 -f 3977//3977 3806//3806 3870//3870 -f 3977//3977 3870//3870 3975//3975 -f 3975//3975 3870//3870 3983//3983 -f 3984//3984 3985//3985 3986//3986 -f 3787//3787 3842//3842 3872//3872 -f 3872//3872 3842//3842 3987//3987 -f 3872//3872 3987//3987 3871//3871 -f 3871//3871 3987//3987 3984//3984 -f 3871//3871 3984//3984 3870//3870 -f 3870//3870 3984//3984 3986//3986 -f 3870//3870 3986//3986 3983//3983 -f 3789//3789 3823//3823 3842//3842 -f 3842//3842 3823//3823 3874//3874 -f 3842//3842 3874//3874 3987//3987 -f 3987//3987 3874//3874 3896//3896 -f 3987//3987 3896//3896 3984//3984 -f 3984//3984 3896//3896 3988//3988 -f 3984//3984 3988//3988 3985//3985 -f 3989//3989 3990//3990 3991//3991 -f 3991//3991 3990//3990 3898//3898 -f 3991//3991 3898//3898 3992//3992 -f 3992//3992 3898//3898 3873//3873 -f 3992//3992 3873//3873 3822//3822 -f 3822//3822 3873//3873 3823//3823 -f 3822//3822 3823//3823 3791//3791 -f 3791//3791 3823//3823 3790//3790 -f 3990//3990 3993//3993 3898//3898 -f 3898//3898 3993//3993 3994//3994 -f 3898//3898 3994//3994 3897//3897 -f 3897//3897 3994//3994 3995//3995 -f 3897//3897 3995//3995 3896//3896 -f 3896//3896 3995//3995 3996//3996 -f 3896//3896 3996//3996 3988//3988 -f 3792//3792 3793//3793 3822//3822 -f 3822//3822 3793//3793 3801//3801 -f 3822//3822 3801//3801 3992//3992 -f 3992//3992 3801//3801 3803//3803 -f 3992//3992 3803//3803 3991//3991 -f 3991//3991 3803//3803 3875//3875 -f 3991//3991 3875//3875 3989//3989 -f 3989//3989 3875//3875 3903//3903 -f 3953//3953 3997//3997 3954//3954 -f 3954//3954 3997//3997 3998//3998 -f 3954//3954 3998//3998 3946//3946 -f 3946//3946 3998//3998 3999//3999 -f 3946//3946 3999//3999 3943//3943 -f 3943//3943 3999//3999 4000//4000 -f 3943//3943 4000//4000 3944//3944 -f 3944//3944 4000//4000 4001//4001 -f 3944//3944 4001//4001 3941//3941 -f 3941//3941 4001//4001 4002//4002 -f 3941//3941 4002//4002 3933//3933 -f 3933//3933 4002//4002 4003//4003 -f 3933//3933 4003//4003 3934//3934 -f 4003//4003 4004//4004 3934//3934 -f 3934//3934 4004//4004 4005//4005 -f 3934//3934 4005//4005 3937//3937 -f 3937//3937 4005//4005 4006//4006 -f 3937//3937 4006//4006 3938//3938 -f 3938//3938 4006//4006 4007//4007 -f 3938//3938 4007//4007 3939//3939 -f 4007//4007 4008//4008 3939//3939 -f 3939//3939 4008//4008 4009//4009 -f 3939//3939 4009//4009 3940//3940 -f 3940//3940 4009//4009 4010//4010 -f 3940//3940 4010//4010 3932//3932 -f 3932//3932 4010//4010 4011//4011 -f 3932//3932 4011//4011 3929//3929 -f 3929//3929 4011//4011 4012//4012 -f 3929//3929 4012//4012 3930//3930 -f 3930//3930 4012//4012 4013//4013 -f 3930//3930 4013//4013 3927//3927 -f 3927//3927 4013//4013 4014//4014 -f 3927//3927 4014//4014 3919//3919 -f 3919//3919 4014//4014 4015//4015 -f 3919//3919 4015//4015 3920//3920 -f 4015//4015 4016//4016 3920//3920 -f 3920//3920 4016//4016 4017//4017 -f 3920//3920 4017//4017 3923//3923 -f 3923//3923 4017//4017 4018//4018 -f 3923//3923 4018//4018 3924//3924 -f 3924//3924 4018//4018 4019//4019 -f 3924//3924 4019//4019 3925//3925 -f 4019//4019 4020//4020 3925//3925 -f 3925//3925 4020//4020 4021//4021 -f 3925//3925 4021//4021 3926//3926 -f 3926//3926 4021//4021 4022//4022 -f 3926//3926 4022//4022 3918//3918 -f 3918//3918 4022//4022 4023//4023 -f 3918//3918 4023//4023 3915//3915 -f 3915//3915 4023//4023 4024//4024 -f 3915//3915 4024//4024 3916//3916 -f 3916//3916 4024//4024 4025//4025 -f 3916//3916 4025//4025 3913//3913 -f 3913//3913 4025//4025 4026//4026 -f 3913//3913 4026//4026 3905//3905 -f 3905//3905 4026//4026 4027//4027 -f 3905//3905 4027//4027 3906//3906 -f 4027//4027 4028//4028 3906//3906 -f 3906//3906 4028//4028 4029//4029 -f 3906//3906 4029//4029 3909//3909 -f 3909//3909 4029//4029 4030//4030 -f 3909//3909 4030//4030 3910//3910 -f 3910//3910 4030//4030 4031//4031 -f 3910//3910 4031//4031 3911//3911 -f 4031//4031 4032//4032 3911//3911 -f 3911//3911 4032//4032 4033//4033 -f 3911//3911 4033//4033 3912//3912 -f 3912//3912 4033//4033 4034//4034 -f 3912//3912 4034//4034 3904//3904 -f 3904//3904 4034//4034 4035//4035 -f 3904//3904 4035//4035 3900//3900 -f 3900//3900 4035//4035 4036//4036 -f 3900//3900 4036//4036 3901//3901 -f 3901//3901 4036//4036 4037//4037 -f 3901//3901 4037//4037 3903//3903 -f 3903//3903 4037//4037 4038//4038 -f 3903//3903 4038//4038 3989//3989 -f 3989//3989 4038//4038 4039//4039 -f 3989//3989 4039//4039 3990//3990 -f 4039//4039 4040//4040 3990//3990 -f 3990//3990 4040//4040 4041//4041 -f 3990//3990 4041//4041 3993//3993 -f 3993//3993 4041//4041 4042//4042 -f 3993//3993 4042//4042 3994//3994 -f 3994//3994 4042//4042 4043//4043 -f 3994//3994 4043//4043 3995//3995 -f 4043//4043 4044//4044 3995//3995 -f 3995//3995 4044//4044 4045//4045 -f 3995//3995 4045//4045 3996//3996 -f 3996//3996 4045//4045 4046//4046 -f 3996//3996 4046//4046 3988//3988 -f 3988//3988 4046//4046 4047//4047 -f 3988//3988 4047//4047 3985//3985 -f 3985//3985 4047//4047 4048//4048 -f 3985//3985 4048//4048 3986//3986 -f 3986//3986 4048//4048 4049//4049 -f 3986//3986 4049//4049 3983//3983 -f 3983//3983 4049//4049 4050//4050 -f 3983//3983 4050//4050 3975//3975 -f 3975//3975 4050//4050 4051//4051 -f 3975//3975 4051//4051 3976//3976 -f 4051//4051 4052//4052 3976//3976 -f 3976//3976 4052//4052 4053//4053 -f 3976//3976 4053//4053 3979//3979 -f 3979//3979 4053//4053 4054//4054 -f 3979//3979 4054//4054 3980//3980 -f 3980//3980 4054//4054 4055//4055 -f 3980//3980 4055//4055 3981//3981 -f 4055//4055 4056//4056 3981//3981 -f 3981//3981 4056//4056 4057//4057 -f 3981//3981 4057//4057 3982//3982 -f 3982//3982 4057//4057 4058//4058 -f 3982//3982 4058//4058 3974//3974 -f 3974//3974 4058//4058 4059//4059 -f 3974//3974 4059//4059 3971//3971 -f 3971//3971 4059//4059 4060//4060 -f 3971//3971 4060//4060 3972//3972 -f 3972//3972 4060//4060 4061//4061 -f 3972//3972 4061//4061 3969//3969 -f 3969//3969 4061//4061 4062//4062 -f 3969//3969 4062//4062 3961//3961 -f 3961//3961 4062//4062 4063//4063 -f 3961//3961 4063//4063 3962//3962 -f 4063//4063 4064//4064 3962//3962 -f 3962//3962 4064//4064 4065//4065 -f 3962//3962 4065//4065 3965//3965 -f 3965//3965 4065//4065 4066//4066 -f 3965//3965 4066//4066 3966//3966 -f 3966//3966 4066//4066 4067//4067 -f 3966//3966 4067//4067 3967//3967 -f 4067//4067 4068//4068 3967//3967 -f 3967//3967 4068//4068 4069//4069 -f 3967//3967 4069//4069 3968//3968 -f 3968//3968 4069//4069 4070//4070 -f 3968//3968 4070//4070 3960//3960 -f 3960//3960 4070//4070 4071//4071 -f 3960//3960 4071//4071 3957//3957 -f 3957//3957 4071//4071 4072//4072 -f 3957//3957 4072//4072 3958//3958 -f 3958//3958 4072//4072 4073//4073 -f 3958//3958 4073//4073 3955//3955 -f 3955//3955 4073//4073 4074//4074 -f 3955//3955 4074//4074 3947//3947 -f 3947//3947 4074//4074 4075//4075 -f 3947//3947 4075//4075 3948//3948 -f 4075//4075 4076//4076 3948//3948 -f 3948//3948 4076//4076 4077//4077 -f 3948//3948 4077//4077 3951//3951 -f 3951//3951 4077//4077 4078//4078 -f 3951//3951 4078//4078 3952//3952 -f 3952//3952 4078//4078 4079//4079 -f 3952//3952 4079//4079 3953//3953 -f 3953//3953 4079//4079 4080//4080 -f 3953//3953 4080//4080 3997//3997 -f 4037//4037 4081//4081 4082//4082 -f 4037//4037 4036//4036 4081//4081 -f 4081//4081 4036//4036 4035//4035 -f 4081//4081 4035//4035 4083//4083 -f 4083//4083 4035//4035 4034//4034 -f 4083//4083 4034//4034 4084//4084 -f 4034//4034 4033//4033 4084//4084 -f 4084//4084 4033//4033 4032//4032 -f 4084//4084 4032//4032 4085//4085 -f 4085//4085 4032//4032 4031//4031 -f 4085//4085 4031//4031 4086//4086 -f 4086//4086 4031//4031 4030//4030 -f 4025//4025 4087//4087 4088//4088 -f 4030//4030 4029//4029 4086//4086 -f 4086//4086 4029//4029 4028//4028 -f 4086//4086 4028//4028 4089//4089 -f 4089//4089 4028//4028 4027//4027 -f 4089//4089 4027//4027 4088//4088 -f 4088//4088 4027//4027 4026//4026 -f 4088//4088 4026//4026 4025//4025 -f 4025//4025 4024//4024 4087//4087 -f 4087//4087 4024//4024 4023//4023 -f 4087//4087 4023//4023 4090//4090 -f 4090//4090 4023//4023 4022//4022 -f 4090//4090 4022//4022 4091//4091 -f 4022//4022 4021//4021 4091//4091 -f 4091//4091 4021//4021 4020//4020 -f 4091//4091 4020//4020 4092//4092 -f 4092//4092 4020//4020 4019//4019 -f 4092//4092 4019//4019 4093//4093 -f 4093//4093 4019//4019 4018//4018 -f 4013//4013 4094//4094 4095//4095 -f 4018//4018 4017//4017 4093//4093 -f 4093//4093 4017//4017 4016//4016 -f 4093//4093 4016//4016 4096//4096 -f 4096//4096 4016//4016 4015//4015 -f 4096//4096 4015//4015 4095//4095 -f 4095//4095 4015//4015 4014//4014 -f 4095//4095 4014//4014 4013//4013 -f 4013//4013 4012//4012 4094//4094 -f 4094//4094 4012//4012 4011//4011 -f 4094//4094 4011//4011 4097//4097 -f 4097//4097 4011//4011 4010//4010 -f 4097//4097 4010//4010 4098//4098 -f 4010//4010 4009//4009 4098//4098 -f 4098//4098 4009//4009 4008//4008 -f 4098//4098 4008//4008 4099//4099 -f 4099//4099 4008//4008 4007//4007 -f 4099//4099 4007//4007 4100//4100 -f 4100//4100 4007//4007 4006//4006 -f 4001//4001 4101//4101 4102//4102 -f 4006//4006 4005//4005 4100//4100 -f 4100//4100 4005//4005 4004//4004 -f 4100//4100 4004//4004 4103//4103 -f 4103//4103 4004//4004 4003//4003 -f 4103//4103 4003//4003 4102//4102 -f 4102//4102 4003//4003 4002//4002 -f 4102//4102 4002//4002 4001//4001 -f 4001//4001 4000//4000 4101//4101 -f 4101//4101 4000//4000 3999//3999 -f 4101//4101 3999//3999 4104//4104 -f 4104//4104 3999//3999 3998//3998 -f 4104//4104 3998//3998 4105//4105 -f 3998//3998 3997//3997 4105//4105 -f 4105//4105 3997//3997 4080//4080 -f 4105//4105 4080//4080 4106//4106 -f 4106//4106 4080//4080 4079//4079 -f 4106//4106 4079//4079 4107//4107 -f 4107//4107 4079//4079 4078//4078 -f 4073//4073 4108//4108 4109//4109 -f 4078//4078 4077//4077 4107//4107 -f 4107//4107 4077//4077 4076//4076 -f 4107//4107 4076//4076 4110//4110 -f 4110//4110 4076//4076 4075//4075 -f 4110//4110 4075//4075 4109//4109 -f 4109//4109 4075//4075 4074//4074 -f 4109//4109 4074//4074 4073//4073 -f 4073//4073 4072//4072 4108//4108 -f 4108//4108 4072//4072 4071//4071 -f 4108//4108 4071//4071 4111//4111 -f 4111//4111 4071//4071 4070//4070 -f 4111//4111 4070//4070 4112//4112 -f 4070//4070 4069//4069 4112//4112 -f 4112//4112 4069//4069 4068//4068 -f 4112//4112 4068//4068 4113//4113 -f 4113//4113 4068//4068 4067//4067 -f 4113//4113 4067//4067 4114//4114 -f 4114//4114 4067//4067 4066//4066 -f 4061//4061 4115//4115 4116//4116 -f 4066//4066 4065//4065 4114//4114 -f 4114//4114 4065//4065 4064//4064 -f 4114//4114 4064//4064 4117//4117 -f 4117//4117 4064//4064 4063//4063 -f 4117//4117 4063//4063 4116//4116 -f 4116//4116 4063//4063 4062//4062 -f 4116//4116 4062//4062 4061//4061 -f 4061//4061 4060//4060 4115//4115 -f 4115//4115 4060//4060 4059//4059 -f 4115//4115 4059//4059 4118//4118 -f 4118//4118 4059//4059 4058//4058 -f 4118//4118 4058//4058 4119//4119 -f 4058//4058 4057//4057 4119//4119 -f 4119//4119 4057//4057 4056//4056 -f 4119//4119 4056//4056 4120//4120 -f 4120//4120 4056//4056 4055//4055 -f 4120//4120 4055//4055 4121//4121 -f 4121//4121 4055//4055 4054//4054 -f 4049//4049 4122//4122 4123//4123 -f 4054//4054 4053//4053 4121//4121 -f 4121//4121 4053//4053 4052//4052 -f 4121//4121 4052//4052 4124//4124 -f 4124//4124 4052//4052 4051//4051 -f 4124//4124 4051//4051 4123//4123 -f 4123//4123 4051//4051 4050//4050 -f 4123//4123 4050//4050 4049//4049 -f 4049//4049 4048//4048 4122//4122 -f 4122//4122 4048//4048 4047//4047 -f 4122//4122 4047//4047 4125//4125 -f 4125//4125 4047//4047 4046//4046 -f 4125//4125 4046//4046 4126//4126 -f 4046//4046 4045//4045 4126//4126 -f 4126//4126 4045//4045 4044//4044 -f 4126//4126 4044//4044 4127//4127 -f 4127//4127 4044//4044 4043//4043 -f 4127//4127 4043//4043 4128//4128 -f 4128//4128 4043//4043 4042//4042 -f 4042//4042 4041//4041 4128//4128 -f 4128//4128 4041//4041 4040//4040 -f 4128//4128 4040//4040 4129//4129 -f 4129//4129 4040//4040 4039//4039 -f 4129//4129 4039//4039 4082//4082 -f 4082//4082 4039//4039 4038//4038 -f 4082//4082 4038//4038 4037//4037 -f 4082//4082 4130//4130 4129//4129 -f 4129//4129 4130//4130 4131//4131 -f 4129//4129 4131//4131 4128//4128 -f 4128//4128 4131//4131 4132//4132 -f 4128//4128 4132//4132 4127//4127 -f 4127//4127 4132//4132 4133//4133 -f 4127//4127 4133//4133 4126//4126 -f 4126//4126 4133//4133 4134//4134 -f 4126//4126 4134//4134 4125//4125 -f 4125//4125 4134//4134 4135//4135 -f 4125//4125 4135//4135 4122//4122 -f 4122//4122 4135//4135 4136//4136 -f 4122//4122 4136//4136 4123//4123 -f 4123//4123 4136//4136 4137//4137 -f 4123//4123 4137//4137 4124//4124 -f 4124//4124 4137//4137 4138//4138 -f 4124//4124 4138//4138 4121//4121 -f 4121//4121 4138//4138 4139//4139 -f 4121//4121 4139//4139 4120//4120 -f 4120//4120 4139//4139 4140//4140 -f 4120//4120 4140//4140 4119//4119 -f 4119//4119 4140//4140 4141//4141 -f 4119//4119 4141//4141 4118//4118 -f 4118//4118 4141//4141 4142//4142 -f 4118//4118 4142//4142 4115//4115 -f 4115//4115 4142//4142 4143//4143 -f 4115//4115 4143//4143 4116//4116 -f 4116//4116 4143//4143 4144//4144 -f 4116//4116 4144//4144 4117//4117 -f 4117//4117 4144//4144 4145//4145 -f 4117//4117 4145//4145 4114//4114 -f 4114//4114 4145//4145 4146//4146 -f 4114//4114 4146//4146 4113//4113 -f 4113//4113 4146//4146 4147//4147 -f 4113//4113 4147//4147 4112//4112 -f 4112//4112 4147//4147 4148//4148 -f 4112//4112 4148//4148 4111//4111 -f 4111//4111 4148//4148 4149//4149 -f 4111//4111 4149//4149 4108//4108 -f 4108//4108 4149//4149 4150//4150 -f 4108//4108 4150//4150 4109//4109 -f 4109//4109 4150//4150 4151//4151 -f 4109//4109 4151//4151 4110//4110 -f 4110//4110 4151//4151 4152//4152 -f 4110//4110 4152//4152 4107//4107 -f 4107//4107 4152//4152 4153//4153 -f 4107//4107 4153//4153 4106//4106 -f 4106//4106 4153//4153 4154//4154 -f 4106//4106 4154//4154 4105//4105 -f 4105//4105 4154//4154 4155//4155 -f 4105//4105 4155//4155 4104//4104 -f 4104//4104 4155//4155 4156//4156 -f 4104//4104 4156//4156 4101//4101 -f 4101//4101 4156//4156 4157//4157 -f 4101//4101 4157//4157 4102//4102 -f 4102//4102 4157//4157 4158//4158 -f 4102//4102 4158//4158 4103//4103 -f 4103//4103 4158//4158 4159//4159 -f 4103//4103 4159//4159 4100//4100 -f 4100//4100 4159//4159 4160//4160 -f 4100//4100 4160//4160 4099//4099 -f 4099//4099 4160//4160 4161//4161 -f 4099//4099 4161//4161 4098//4098 -f 4098//4098 4161//4161 4162//4162 -f 4098//4098 4162//4162 4097//4097 -f 4097//4097 4162//4162 4163//4163 -f 4097//4097 4163//4163 4094//4094 -f 4094//4094 4163//4163 4164//4164 -f 4094//4094 4164//4164 4095//4095 -f 4095//4095 4164//4164 4165//4165 -f 4095//4095 4165//4165 4096//4096 -f 4096//4096 4165//4165 4166//4166 -f 4096//4096 4166//4166 4093//4093 -f 4093//4093 4166//4166 4167//4167 -f 4093//4093 4167//4167 4092//4092 -f 4092//4092 4167//4167 4168//4168 -f 4092//4092 4168//4168 4091//4091 -f 4091//4091 4168//4168 4169//4169 -f 4091//4091 4169//4169 4090//4090 -f 4090//4090 4169//4169 4170//4170 -f 4090//4090 4170//4170 4087//4087 -f 4087//4087 4170//4170 4171//4171 -f 4087//4087 4171//4171 4088//4088 -f 4088//4088 4171//4171 4172//4172 -f 4088//4088 4172//4172 4089//4089 -f 4089//4089 4172//4172 4173//4173 -f 4089//4089 4173//4173 4086//4086 -f 4086//4086 4173//4173 4174//4174 -f 4086//4086 4174//4174 4085//4085 -f 4085//4085 4174//4174 4175//4175 -f 4085//4085 4175//4175 4084//4084 -f 4084//4084 4175//4175 4176//4176 -f 4084//4084 4176//4176 4083//4083 -f 4083//4083 4176//4176 4177//4177 -f 4083//4083 4177//4177 4081//4081 -f 4081//4081 4177//4177 4178//4178 -f 4081//4081 4178//4178 4082//4082 -f 4082//4082 4178//4178 4130//4130 -f 4178//4178 4179//4179 4130//4130 -f 4130//4130 4179//4179 4180//4180 -f 4130//4130 4180//4180 4131//4131 -f 4131//4131 4180//4180 4181//4181 -f 4131//4131 4181//4181 4132//4132 -f 4132//4132 4181//4181 4182//4182 -f 4132//4132 4182//4182 4133//4133 -f 4133//4133 4182//4182 4183//4183 -f 4133//4133 4183//4183 4134//4134 -f 4134//4134 4183//4183 4184//4184 -f 4134//4134 4184//4184 4135//4135 -f 4135//4135 4184//4184 4185//4185 -f 4135//4135 4185//4185 4136//4136 -f 4136//4136 4185//4185 4186//4186 -f 4136//4136 4186//4186 4137//4137 -f 4137//4137 4186//4186 4187//4187 -f 4137//4137 4187//4187 4138//4138 -f 4138//4138 4187//4187 4188//4188 -f 4138//4138 4188//4188 4139//4139 -f 4139//4139 4188//4188 4189//4189 -f 4139//4139 4189//4189 4140//4140 -f 4140//4140 4189//4189 4190//4190 -f 4140//4140 4190//4190 4141//4141 -f 4141//4141 4190//4190 4191//4191 -f 4141//4141 4191//4191 4142//4142 -f 4142//4142 4191//4191 4192//4192 -f 4142//4142 4192//4192 4143//4143 -f 4143//4143 4192//4192 4193//4193 -f 4143//4143 4193//4193 4144//4144 -f 4144//4144 4193//4193 4194//4194 -f 4144//4144 4194//4194 4145//4145 -f 4145//4145 4194//4194 4195//4195 -f 4145//4145 4195//4195 4146//4146 -f 4146//4146 4195//4195 4196//4196 -f 4146//4146 4196//4196 4147//4147 -f 4147//4147 4196//4196 4197//4197 -f 4147//4147 4197//4197 4148//4148 -f 4148//4148 4197//4197 4198//4198 -f 4148//4148 4198//4198 4149//4149 -f 4149//4149 4198//4198 4199//4199 -f 4149//4149 4199//4199 4150//4150 -f 4150//4150 4199//4199 4200//4200 -f 4150//4150 4200//4200 4151//4151 -f 4151//4151 4200//4200 4201//4201 -f 4151//4151 4201//4201 4152//4152 -f 4152//4152 4201//4201 4202//4202 -f 4152//4152 4202//4202 4153//4153 -f 4153//4153 4202//4202 4203//4203 -f 4153//4153 4203//4203 4154//4154 -f 4154//4154 4203//4203 4204//4204 -f 4154//4154 4204//4204 4155//4155 -f 4155//4155 4204//4204 4205//4205 -f 4155//4155 4205//4205 4156//4156 -f 4156//4156 4205//4205 4206//4206 -f 4156//4156 4206//4206 4157//4157 -f 4157//4157 4206//4206 4207//4207 -f 4157//4157 4207//4207 4158//4158 -f 4158//4158 4207//4207 4208//4208 -f 4158//4158 4208//4208 4159//4159 -f 4159//4159 4208//4208 4209//4209 -f 4159//4159 4209//4209 4160//4160 -f 4160//4160 4209//4209 4210//4210 -f 4160//4160 4210//4210 4161//4161 -f 4161//4161 4210//4210 4211//4211 -f 4161//4161 4211//4211 4162//4162 -f 4162//4162 4211//4211 4212//4212 -f 4162//4162 4212//4212 4163//4163 -f 4163//4163 4212//4212 4213//4213 -f 4163//4163 4213//4213 4164//4164 -f 4164//4164 4213//4213 4214//4214 -f 4164//4164 4214//4214 4165//4165 -f 4165//4165 4214//4214 4215//4215 -f 4165//4165 4215//4215 4166//4166 -f 4166//4166 4215//4215 4216//4216 -f 4166//4166 4216//4216 4167//4167 -f 4167//4167 4216//4216 4217//4217 -f 4167//4167 4217//4217 4168//4168 -f 4168//4168 4217//4217 4218//4218 -f 4168//4168 4218//4218 4169//4169 -f 4169//4169 4218//4218 4219//4219 -f 4169//4169 4219//4219 4170//4170 -f 4170//4170 4219//4219 4220//4220 -f 4170//4170 4220//4220 4171//4171 -f 4171//4171 4220//4220 4221//4221 -f 4171//4171 4221//4221 4172//4172 -f 4172//4172 4221//4221 4222//4222 -f 4172//4172 4222//4222 4173//4173 -f 4173//4173 4222//4222 4223//4223 -f 4173//4173 4223//4223 4174//4174 -f 4174//4174 4223//4223 4224//4224 -f 4174//4174 4224//4224 4175//4175 -f 4175//4175 4224//4224 4225//4225 -f 4175//4175 4225//4225 4176//4176 -f 4176//4176 4225//4225 4226//4226 -f 4176//4176 4226//4226 4177//4177 -f 4177//4177 4226//4226 4227//4227 -f 4177//4177 4227//4227 4178//4178 -f 4178//4178 4227//4227 4179//4179 -f 4227//4227 4228//4228 4179//4179 -f 4179//4179 4228//4228 4229//4229 -f 4179//4179 4229//4229 4180//4180 -f 4180//4180 4229//4229 4230//4230 -f 4180//4180 4230//4230 4181//4181 -f 4181//4181 4230//4230 4231//4231 -f 4181//4181 4231//4231 4182//4182 -f 4182//4182 4231//4231 4232//4232 -f 4182//4182 4232//4232 4183//4183 -f 4183//4183 4232//4232 4233//4233 -f 4183//4183 4233//4233 4184//4184 -f 4184//4184 4233//4233 4234//4234 -f 4184//4184 4234//4234 4185//4185 -f 4185//4185 4234//4234 4235//4235 -f 4185//4185 4235//4235 4186//4186 -f 4186//4186 4235//4235 4236//4236 -f 4186//4186 4236//4236 4187//4187 -f 4187//4187 4236//4236 4237//4237 -f 4187//4187 4237//4237 4188//4188 -f 4188//4188 4237//4237 4238//4238 -f 4188//4188 4238//4238 4189//4189 -f 4189//4189 4238//4238 4239//4239 -f 4189//4189 4239//4239 4190//4190 -f 4190//4190 4239//4239 4240//4240 -f 4190//4190 4240//4240 4191//4191 -f 4191//4191 4240//4240 4241//4241 -f 4191//4191 4241//4241 4192//4192 -f 4192//4192 4241//4241 4242//4242 -f 4192//4192 4242//4242 4193//4193 -f 4193//4193 4242//4242 4243//4243 -f 4193//4193 4243//4243 4194//4194 -f 4194//4194 4243//4243 4244//4244 -f 4194//4194 4244//4244 4195//4195 -f 4195//4195 4244//4244 4245//4245 -f 4195//4195 4245//4245 4196//4196 -f 4196//4196 4245//4245 4246//4246 -f 4196//4196 4246//4246 4197//4197 -f 4197//4197 4246//4246 4247//4247 -f 4197//4197 4247//4247 4198//4198 -f 4198//4198 4247//4247 4248//4248 -f 4198//4198 4248//4248 4199//4199 -f 4199//4199 4248//4248 4249//4249 -f 4199//4199 4249//4249 4200//4200 -f 4200//4200 4249//4249 4250//4250 -f 4200//4200 4250//4250 4201//4201 -f 4201//4201 4250//4250 4251//4251 -f 4201//4201 4251//4251 4202//4202 -f 4202//4202 4251//4251 4252//4252 -f 4202//4202 4252//4252 4203//4203 -f 4203//4203 4252//4252 4253//4253 -f 4203//4203 4253//4253 4204//4204 -f 4204//4204 4253//4253 4254//4254 -f 4204//4204 4254//4254 4205//4205 -f 4205//4205 4254//4254 4255//4255 -f 4205//4205 4255//4255 4206//4206 -f 4206//4206 4255//4255 4256//4256 -f 4206//4206 4256//4256 4207//4207 -f 4207//4207 4256//4256 4257//4257 -f 4207//4207 4257//4257 4208//4208 -f 4208//4208 4257//4257 4258//4258 -f 4208//4208 4258//4258 4209//4209 -f 4209//4209 4258//4258 4259//4259 -f 4209//4209 4259//4259 4210//4210 -f 4210//4210 4259//4259 4260//4260 -f 4210//4210 4260//4260 4211//4211 -f 4211//4211 4260//4260 4261//4261 -f 4211//4211 4261//4261 4212//4212 -f 4212//4212 4261//4261 4262//4262 -f 4212//4212 4262//4262 4213//4213 -f 4213//4213 4262//4262 4263//4263 -f 4213//4213 4263//4263 4214//4214 -f 4214//4214 4263//4263 4264//4264 -f 4214//4214 4264//4264 4215//4215 -f 4215//4215 4264//4264 4265//4265 -f 4215//4215 4265//4265 4216//4216 -f 4216//4216 4265//4265 4266//4266 -f 4216//4216 4266//4266 4217//4217 -f 4217//4217 4266//4266 4267//4267 -f 4217//4217 4267//4267 4218//4218 -f 4218//4218 4267//4267 4268//4268 -f 4218//4218 4268//4268 4219//4219 -f 4219//4219 4268//4268 4269//4269 -f 4219//4219 4269//4269 4220//4220 -f 4220//4220 4269//4269 4270//4270 -f 4220//4220 4270//4270 4221//4221 -f 4221//4221 4270//4270 4271//4271 -f 4221//4221 4271//4271 4222//4222 -f 4222//4222 4271//4271 4272//4272 -f 4222//4222 4272//4272 4223//4223 -f 4223//4223 4272//4272 4273//4273 -f 4223//4223 4273//4273 4224//4224 -f 4224//4224 4273//4273 4274//4274 -f 4224//4224 4274//4274 4225//4225 -f 4225//4225 4274//4274 4275//4275 -f 4225//4225 4275//4275 4226//4226 -f 4226//4226 4275//4275 4276//4276 -f 4226//4226 4276//4276 4227//4227 -f 4227//4227 4276//4276 4228//4228 -f 4276//4276 4277//4277 4228//4228 -f 4228//4228 4277//4277 4278//4278 -f 4228//4228 4278//4278 4229//4229 -f 4229//4229 4278//4278 4279//4279 -f 4229//4229 4279//4279 4230//4230 -f 4230//4230 4279//4279 4280//4280 -f 4230//4230 4280//4280 4231//4231 -f 4231//4231 4280//4280 4281//4281 -f 4231//4231 4281//4281 4232//4232 -f 4232//4232 4281//4281 4282//4282 -f 4232//4232 4282//4282 4233//4233 -f 4233//4233 4282//4282 4283//4283 -f 4233//4233 4283//4283 4234//4234 -f 4234//4234 4283//4283 4284//4284 -f 4234//4234 4284//4284 4235//4235 -f 4235//4235 4284//4284 4285//4285 -f 4235//4235 4285//4285 4236//4236 -f 4236//4236 4285//4285 4286//4286 -f 4236//4236 4286//4286 4237//4237 -f 4237//4237 4286//4286 4287//4287 -f 4237//4237 4287//4287 4238//4238 -f 4238//4238 4287//4287 4288//4288 -f 4238//4238 4288//4288 4239//4239 -f 4239//4239 4288//4288 4289//4289 -f 4239//4239 4289//4289 4240//4240 -f 4240//4240 4289//4289 4290//4290 -f 4240//4240 4290//4290 4241//4241 -f 4241//4241 4290//4290 4291//4291 -f 4241//4241 4291//4291 4242//4242 -f 4242//4242 4291//4291 4292//4292 -f 4242//4242 4292//4292 4243//4243 -f 4243//4243 4292//4292 4293//4293 -f 4243//4243 4293//4293 4244//4244 -f 4244//4244 4293//4293 4294//4294 -f 4244//4244 4294//4294 4245//4245 -f 4245//4245 4294//4294 4295//4295 -f 4245//4245 4295//4295 4246//4246 -f 4246//4246 4295//4295 4296//4296 -f 4246//4246 4296//4296 4247//4247 -f 4247//4247 4296//4296 4297//4297 -f 4247//4247 4297//4297 4248//4248 -f 4248//4248 4297//4297 4298//4298 -f 4248//4248 4298//4298 4249//4249 -f 4249//4249 4298//4298 4299//4299 -f 4249//4249 4299//4299 4250//4250 -f 4250//4250 4299//4299 4300//4300 -f 4250//4250 4300//4300 4251//4251 -f 4251//4251 4300//4300 4301//4301 -f 4251//4251 4301//4301 4252//4252 -f 4252//4252 4301//4301 4302//4302 -f 4252//4252 4302//4302 4253//4253 -f 4253//4253 4302//4302 4303//4303 -f 4253//4253 4303//4303 4254//4254 -f 4254//4254 4303//4303 4304//4304 -f 4254//4254 4304//4304 4255//4255 -f 4255//4255 4304//4304 4305//4305 -f 4255//4255 4305//4305 4256//4256 -f 4256//4256 4305//4305 4306//4306 -f 4256//4256 4306//4306 4257//4257 -f 4257//4257 4306//4306 4307//4307 -f 4257//4257 4307//4307 4258//4258 -f 4258//4258 4307//4307 4308//4308 -f 4258//4258 4308//4308 4259//4259 -f 4259//4259 4308//4308 4309//4309 -f 4259//4259 4309//4309 4260//4260 -f 4260//4260 4309//4309 4310//4310 -f 4260//4260 4310//4310 4261//4261 -f 4261//4261 4310//4310 4311//4311 -f 4261//4261 4311//4311 4262//4262 -f 4262//4262 4311//4311 4312//4312 -f 4262//4262 4312//4312 4263//4263 -f 4263//4263 4312//4312 4313//4313 -f 4263//4263 4313//4313 4264//4264 -f 4264//4264 4313//4313 4314//4314 -f 4264//4264 4314//4314 4265//4265 -f 4265//4265 4314//4314 4315//4315 -f 4265//4265 4315//4315 4266//4266 -f 4266//4266 4315//4315 4316//4316 -f 4266//4266 4316//4316 4267//4267 -f 4267//4267 4316//4316 4317//4317 -f 4267//4267 4317//4317 4268//4268 -f 4268//4268 4317//4317 4318//4318 -f 4268//4268 4318//4318 4269//4269 -f 4269//4269 4318//4318 4319//4319 -f 4269//4269 4319//4319 4270//4270 -f 4270//4270 4319//4319 4320//4320 -f 4270//4270 4320//4320 4271//4271 -f 4271//4271 4320//4320 4321//4321 -f 4271//4271 4321//4321 4272//4272 -f 4272//4272 4321//4321 4322//4322 -f 4272//4272 4322//4322 4273//4273 -f 4273//4273 4322//4322 4323//4323 -f 4273//4273 4323//4323 4274//4274 -f 4274//4274 4323//4323 4324//4324 -f 4274//4274 4324//4324 4275//4275 -f 4275//4275 4324//4324 4325//4325 -f 4275//4275 4325//4325 4276//4276 -f 4276//4276 4325//4325 4277//4277 -f 4325//4325 4326//4326 4277//4277 -f 4277//4277 4326//4326 4327//4327 -f 4277//4277 4327//4327 4278//4278 -f 4278//4278 4327//4327 4328//4328 -f 4278//4278 4328//4328 4279//4279 -f 4279//4279 4328//4328 4329//4329 -f 4279//4279 4329//4329 4280//4280 -f 4280//4280 4329//4329 4330//4330 -f 4280//4280 4330//4330 4281//4281 -f 4281//4281 4330//4330 4331//4331 -f 4281//4281 4331//4331 4282//4282 -f 4282//4282 4331//4331 4332//4332 -f 4282//4282 4332//4332 4283//4283 -f 4283//4283 4332//4332 4333//4333 -f 4283//4283 4333//4333 4284//4284 -f 4284//4284 4333//4333 4334//4334 -f 4284//4284 4334//4334 4285//4285 -f 4285//4285 4334//4334 4335//4335 -f 4285//4285 4335//4335 4286//4286 -f 4286//4286 4335//4335 4336//4336 -f 4286//4286 4336//4336 4287//4287 -f 4287//4287 4336//4336 4337//4337 -f 4287//4287 4337//4337 4288//4288 -f 4288//4288 4337//4337 4338//4338 -f 4288//4288 4338//4338 4289//4289 -f 4289//4289 4338//4338 4339//4339 -f 4289//4289 4339//4339 4290//4290 -f 4290//4290 4339//4339 4340//4340 -f 4290//4290 4340//4340 4291//4291 -f 4291//4291 4340//4340 4341//4341 -f 4291//4291 4341//4341 4292//4292 -f 4292//4292 4341//4341 4342//4342 -f 4292//4292 4342//4342 4293//4293 -f 4293//4293 4342//4342 4343//4343 -f 4293//4293 4343//4343 4294//4294 -f 4294//4294 4343//4343 4344//4344 -f 4294//4294 4344//4344 4295//4295 -f 4295//4295 4344//4344 4345//4345 -f 4295//4295 4345//4345 4296//4296 -f 4296//4296 4345//4345 4346//4346 -f 4296//4296 4346//4346 4297//4297 -f 4297//4297 4346//4346 4347//4347 -f 4297//4297 4347//4347 4298//4298 -f 4298//4298 4347//4347 4348//4348 -f 4298//4298 4348//4348 4299//4299 -f 4299//4299 4348//4348 4349//4349 -f 4299//4299 4349//4349 4300//4300 -f 4300//4300 4349//4349 4350//4350 -f 4300//4300 4350//4350 4301//4301 -f 4301//4301 4350//4350 4351//4351 -f 4301//4301 4351//4351 4302//4302 -f 4302//4302 4351//4351 4352//4352 -f 4302//4302 4352//4352 4303//4303 -f 4303//4303 4352//4352 4353//4353 -f 4303//4303 4353//4353 4304//4304 -f 4304//4304 4353//4353 4354//4354 -f 4304//4304 4354//4354 4305//4305 -f 4305//4305 4354//4354 4355//4355 -f 4305//4305 4355//4355 4306//4306 -f 4306//4306 4355//4355 4356//4356 -f 4306//4306 4356//4356 4307//4307 -f 4307//4307 4356//4356 4357//4357 -f 4307//4307 4357//4357 4308//4308 -f 4308//4308 4357//4357 4358//4358 -f 4308//4308 4358//4358 4309//4309 -f 4309//4309 4358//4358 4359//4359 -f 4309//4309 4359//4359 4310//4310 -f 4310//4310 4359//4359 4360//4360 -f 4310//4310 4360//4360 4311//4311 -f 4311//4311 4360//4360 4361//4361 -f 4311//4311 4361//4361 4312//4312 -f 4312//4312 4361//4361 4362//4362 -f 4312//4312 4362//4362 4313//4313 -f 4313//4313 4362//4362 4363//4363 -f 4313//4313 4363//4363 4314//4314 -f 4314//4314 4363//4363 4364//4364 -f 4314//4314 4364//4364 4315//4315 -f 4315//4315 4364//4364 4365//4365 -f 4315//4315 4365//4365 4316//4316 -f 4316//4316 4365//4365 4366//4366 -f 4316//4316 4366//4366 4317//4317 -f 4317//4317 4366//4366 4367//4367 -f 4317//4317 4367//4367 4318//4318 -f 4318//4318 4367//4367 4368//4368 -f 4318//4318 4368//4368 4319//4319 -f 4319//4319 4368//4368 4369//4369 -f 4319//4319 4369//4369 4320//4320 -f 4320//4320 4369//4369 4370//4370 -f 4320//4320 4370//4370 4321//4321 -f 4321//4321 4370//4370 4371//4371 -f 4321//4321 4371//4371 4322//4322 -f 4322//4322 4371//4371 4372//4372 -f 4322//4322 4372//4372 4323//4323 -f 4323//4323 4372//4372 4373//4373 -f 4323//4323 4373//4373 4324//4324 -f 4324//4324 4373//4373 4374//4374 -f 4324//4324 4374//4374 4325//4325 -f 4325//4325 4374//4374 4326//4326 -f 4350//4350 4375//4375 4351//4351 -f 4351//4351 4375//4375 4376//4376 -f 4351//4351 4376//4376 4352//4352 -f 4352//4352 4376//4376 4377//4377 -f 4352//4352 4377//4377 4353//4353 -f 4353//4353 4377//4377 4378//4378 -f 4353//4353 4378//4378 4354//4354 -f 4378//4378 4379//4379 4354//4354 -f 4354//4354 4379//4379 4380//4380 -f 4354//4354 4380//4380 4355//4355 -f 4355//4355 4380//4380 4381//4381 -f 4355//4355 4381//4381 4356//4356 -f 4356//4356 4381//4381 4382//4382 -f 4356//4356 4382//4382 4357//4357 -f 4357//4357 4382//4382 4383//4383 -f 4357//4357 4383//4383 4358//4358 -f 4383//4383 4384//4384 4358//4358 -f 4358//4358 4384//4384 4385//4385 -f 4358//4358 4385//4385 4359//4359 -f 4359//4359 4385//4385 4386//4386 -f 4359//4359 4386//4386 4360//4360 -f 4360//4360 4386//4386 4387//4387 -f 4360//4360 4387//4387 4361//4361 -f 4361//4361 4387//4387 4388//4388 -f 4361//4361 4388//4388 4362//4362 -f 4362//4362 4388//4388 4389//4389 -f 4362//4362 4389//4389 4363//4363 -f 4389//4389 4390//4390 4363//4363 -f 4363//4363 4390//4390 4391//4391 -f 4363//4363 4391//4391 4364//4364 -f 4364//4364 4391//4391 4392//4392 -f 4364//4364 4392//4392 4365//4365 -f 4365//4365 4392//4392 4393//4393 -f 4365//4365 4393//4393 4366//4366 -f 4366//4366 4393//4393 4394//4394 -f 4366//4366 4394//4394 4367//4367 -f 4394//4394 4395//4395 4367//4367 -f 4367//4367 4395//4395 4396//4396 -f 4367//4367 4396//4396 4368//4368 -f 4368//4368 4396//4396 4397//4397 -f 4368//4368 4397//4397 4369//4369 -f 4369//4369 4397//4397 4398//4398 -f 4369//4369 4398//4398 4370//4370 -f 4370//4370 4398//4398 4399//4399 -f 4370//4370 4399//4399 4371//4371 -f 4371//4371 4399//4399 4400//4400 -f 4371//4371 4400//4400 4372//4372 -f 4336//4336 4401//4401 4337//4337 -f 4337//4337 4401//4401 4402//4402 -f 4337//4337 4402//4402 4338//4338 -f 4338//4338 4402//4402 4403//4403 -f 4338//4338 4403//4403 4339//4339 -f 4339//4339 4403//4403 4404//4404 -f 4339//4339 4404//4404 4340//4340 -f 4340//4340 4404//4404 4405//4405 -f 4340//4340 4405//4405 4341//4341 -f 4405//4405 4406//4406 4341//4341 -f 4341//4341 4406//4406 4407//4407 -f 4341//4341 4407//4407 4342//4342 -f 4342//4342 4407//4407 4408//4408 -f 4342//4342 4408//4408 4343//4343 -f 4343//4343 4408//4408 4409//4409 -f 4343//4343 4409//4409 4344//4344 -f 4344//4344 4409//4409 4410//4410 -f 4344//4344 4410//4410 4345//4345 -f 4410//4410 4411//4411 4345//4345 -f 4345//4345 4411//4411 4412//4412 -f 4345//4345 4412//4412 4346//4346 -f 4346//4346 4412//4412 4413//4413 -f 4346//4346 4413//4413 4347//4347 -f 4347//4347 4413//4413 4414//4414 -f 4347//4347 4414//4414 4348//4348 -f 4348//4348 4414//4414 4415//4415 -f 4348//4348 4415//4415 4349//4349 -f 4349//4349 4415//4415 4416//4416 -f 4349//4349 4416//4416 4350//4350 -f 4350//4350 4416//4416 4417//4417 -f 4350//4350 4417//4417 4375//4375 -f 4400//4400 4418//4418 4372//4372 -f 4372//4372 4418//4418 4419//4419 -f 4372//4372 4419//4419 4373//4373 -f 4373//4373 4419//4419 4420//4420 -f 4373//4373 4420//4420 4374//4374 -f 4374//4374 4420//4420 4421//4421 -f 4374//4374 4421//4421 4326//4326 -f 4326//4326 4421//4421 4422//4422 -f 4326//4326 4422//4422 4327//4327 -f 4332//4332 4423//4423 4333//4333 -f 4333//4333 4423//4423 4424//4424 -f 4333//4333 4424//4424 4334//4334 -f 4334//4334 4424//4424 4425//4425 -f 4334//4334 4425//4425 4335//4335 -f 4335//4335 4425//4425 4426//4426 -f 4335//4335 4426//4426 4336//4336 -f 4336//4336 4426//4426 4427//4427 -f 4336//4336 4427//4427 4401//4401 -f 4422//4422 4428//4428 4327//4327 -f 4327//4327 4428//4428 4429//4429 -f 4327//4327 4429//4429 4328//4328 -f 4328//4328 4429//4429 4430//4430 -f 4328//4328 4430//4430 4329//4329 -f 4329//4329 4430//4430 4431//4431 -f 4329//4329 4431//4431 4330//4330 -f 4330//4330 4431//4431 4432//4432 -f 4330//4330 4432//4432 4331//4331 -f 4331//4331 4432//4432 4433//4433 -f 4331//4331 4433//4433 4332//4332 -f 4332//4332 4433//4433 4434//4434 -f 4332//4332 4434//4434 4423//4423 -f 4421//4421 4435//4435 4422//4422 -f 4422//4422 4435//4435 4436//4436 -f 4422//4422 4436//4436 4428//4428 -f 4428//4428 4436//4436 4437//4437 -f 4428//4428 4437//4437 4429//4429 -f 4429//4429 4437//4437 4438//4438 -f 4429//4429 4438//4438 4430//4430 -f 4430//4430 4438//4438 4439//4439 -f 4430//4430 4439//4439 4431//4431 -f 4431//4431 4439//4439 4440//4440 -f 4431//4431 4440//4440 4432//4432 -f 4432//4432 4440//4440 4441//4441 -f 4432//4432 4441//4441 4433//4433 -f 4433//4433 4441//4441 4442//4442 -f 4433//4433 4442//4442 4434//4434 -f 4434//4434 4442//4442 4443//4443 -f 4434//4434 4443//4443 4423//4423 -f 4423//4423 4443//4443 4444//4444 -f 4423//4423 4444//4444 4424//4424 -f 4424//4424 4444//4444 4445//4445 -f 4424//4424 4445//4445 4425//4425 -f 4425//4425 4445//4445 4446//4446 -f 4425//4425 4446//4446 4426//4426 -f 4426//4426 4446//4446 4447//4447 -f 4426//4426 4447//4447 4427//4427 -f 4427//4427 4447//4447 4448//4448 -f 4427//4427 4448//4448 4401//4401 -f 4401//4401 4448//4448 4449//4449 -f 4401//4401 4449//4449 4402//4402 -f 4402//4402 4449//4449 4450//4450 -f 4402//4402 4450//4450 4403//4403 -f 4403//4403 4450//4450 4451//4451 -f 4403//4403 4451//4451 4404//4404 -f 4404//4404 4451//4451 4452//4452 -f 4404//4404 4452//4452 4405//4405 -f 4405//4405 4452//4452 4453//4453 -f 4405//4405 4453//4453 4406//4406 -f 4406//4406 4453//4453 4454//4454 -f 4406//4406 4454//4454 4407//4407 -f 4407//4407 4454//4454 4455//4455 -f 4407//4407 4455//4455 4408//4408 -f 4408//4408 4455//4455 4456//4456 -f 4408//4408 4456//4456 4409//4409 -f 4409//4409 4456//4456 4457//4457 -f 4409//4409 4457//4457 4410//4410 -f 4410//4410 4457//4457 4458//4458 -f 4410//4410 4458//4458 4411//4411 -f 4411//4411 4458//4458 4459//4459 -f 4411//4411 4459//4459 4412//4412 -f 4412//4412 4459//4459 4460//4460 -f 4412//4412 4460//4460 4413//4413 -f 4413//4413 4460//4460 4461//4461 -f 4413//4413 4461//4461 4414//4414 -f 4414//4414 4461//4461 4462//4462 -f 4414//4414 4462//4462 4415//4415 -f 4415//4415 4462//4462 4463//4463 -f 4415//4415 4463//4463 4416//4416 -f 4416//4416 4463//4463 4464//4464 -f 4416//4416 4464//4464 4417//4417 -f 4417//4417 4464//4464 4465//4465 -f 4417//4417 4465//4465 4375//4375 -f 4375//4375 4465//4465 4466//4466 -f 4375//4375 4466//4466 4376//4376 -f 4376//4376 4466//4466 4467//4467 -f 4376//4376 4467//4467 4377//4377 -f 4377//4377 4467//4467 4468//4468 -f 4377//4377 4468//4468 4378//4378 -f 4378//4378 4468//4468 4469//4469 -f 4378//4378 4469//4469 4379//4379 -f 4379//4379 4469//4469 4470//4470 -f 4379//4379 4470//4470 4380//4380 -f 4380//4380 4470//4470 4471//4471 -f 4380//4380 4471//4471 4381//4381 -f 4381//4381 4471//4471 4472//4472 -f 4381//4381 4472//4472 4382//4382 -f 4382//4382 4472//4472 4473//4473 -f 4382//4382 4473//4473 4383//4383 -f 4383//4383 4473//4473 4474//4474 -f 4383//4383 4474//4474 4384//4384 -f 4384//4384 4474//4474 4475//4475 -f 4384//4384 4475//4475 4385//4385 -f 4385//4385 4475//4475 4476//4476 -f 4385//4385 4476//4476 4386//4386 -f 4386//4386 4476//4476 4477//4477 -f 4386//4386 4477//4477 4387//4387 -f 4387//4387 4477//4477 4478//4478 -f 4387//4387 4478//4478 4388//4388 -f 4388//4388 4478//4478 4479//4479 -f 4388//4388 4479//4479 4389//4389 -f 4389//4389 4479//4479 4480//4480 -f 4389//4389 4480//4480 4390//4390 -f 4390//4390 4480//4480 4481//4481 -f 4390//4390 4481//4481 4391//4391 -f 4391//4391 4481//4481 4482//4482 -f 4391//4391 4482//4482 4392//4392 -f 4392//4392 4482//4482 4483//4483 -f 4392//4392 4483//4483 4393//4393 -f 4393//4393 4483//4483 4484//4484 -f 4393//4393 4484//4484 4394//4394 -f 4394//4394 4484//4484 4485//4485 -f 4394//4394 4485//4485 4395//4395 -f 4395//4395 4485//4485 4486//4486 -f 4395//4395 4486//4486 4396//4396 -f 4396//4396 4486//4486 4487//4487 -f 4396//4396 4487//4487 4397//4397 -f 4397//4397 4487//4487 4488//4488 -f 4397//4397 4488//4488 4398//4398 -f 4398//4398 4488//4488 4489//4489 -f 4398//4398 4489//4489 4399//4399 -f 4399//4399 4489//4489 4490//4490 -f 4399//4399 4490//4490 4400//4400 -f 4400//4400 4490//4490 4491//4491 -f 4400//4400 4491//4491 4418//4418 -f 4418//4418 4491//4491 4492//4492 -f 4418//4418 4492//4492 4419//4419 -f 4419//4419 4492//4492 4493//4493 -f 4419//4419 4493//4493 4420//4420 -f 4420//4420 4493//4493 4494//4494 -f 4420//4420 4494//4494 4421//4421 -f 4421//4421 4494//4494 4435//4435 -f 4494//4494 4495//4495 4435//4435 -f 4435//4435 4495//4495 4496//4496 -f 4435//4435 4496//4496 4436//4436 -f 4436//4436 4496//4496 4497//4497 -f 4436//4436 4497//4497 4437//4437 -f 4437//4437 4497//4497 4498//4498 -f 4437//4437 4498//4498 4438//4438 -f 4438//4438 4498//4498 4499//4499 -f 4438//4438 4499//4499 4439//4439 -f 4439//4439 4499//4499 4500//4500 -f 4439//4439 4500//4500 4440//4440 -f 4440//4440 4500//4500 4501//4501 -f 4440//4440 4501//4501 4441//4441 -f 4441//4441 4501//4501 4502//4502 -f 4441//4441 4502//4502 4442//4442 -f 4442//4442 4502//4502 4503//4503 -f 4442//4442 4503//4503 4443//4443 -f 4443//4443 4503//4503 4504//4504 -f 4443//4443 4504//4504 4444//4444 -f 4444//4444 4504//4504 4505//4505 -f 4444//4444 4505//4505 4445//4445 -f 4445//4445 4505//4505 4506//4506 -f 4445//4445 4506//4506 4446//4446 -f 4446//4446 4506//4506 4507//4507 -f 4446//4446 4507//4507 4447//4447 -f 4447//4447 4507//4507 4508//4508 -f 4447//4447 4508//4508 4448//4448 -f 4448//4448 4508//4508 4509//4509 -f 4448//4448 4509//4509 4449//4449 -f 4449//4449 4509//4509 4510//4510 -f 4449//4449 4510//4510 4450//4450 -f 4450//4450 4510//4510 4511//4511 -f 4450//4450 4511//4511 4451//4451 -f 4451//4451 4511//4511 4512//4512 -f 4451//4451 4512//4512 4452//4452 -f 4452//4452 4512//4512 4513//4513 -f 4452//4452 4513//4513 4453//4453 -f 4453//4453 4513//4513 4514//4514 -f 4453//4453 4514//4514 4454//4454 -f 4454//4454 4514//4514 4515//4515 -f 4454//4454 4515//4515 4455//4455 -f 4455//4455 4515//4515 4516//4516 -f 4455//4455 4516//4516 4456//4456 -f 4456//4456 4516//4516 4517//4517 -f 4456//4456 4517//4517 4457//4457 -f 4457//4457 4517//4517 4518//4518 -f 4457//4457 4518//4518 4458//4458 -f 4458//4458 4518//4518 4519//4519 -f 4458//4458 4519//4519 4459//4459 -f 4459//4459 4519//4519 4520//4520 -f 4459//4459 4520//4520 4460//4460 -f 4460//4460 4520//4520 4521//4521 -f 4460//4460 4521//4521 4461//4461 -f 4461//4461 4521//4521 4522//4522 -f 4461//4461 4522//4522 4462//4462 -f 4462//4462 4522//4522 4523//4523 -f 4462//4462 4523//4523 4463//4463 -f 4463//4463 4523//4523 4524//4524 -f 4463//4463 4524//4524 4464//4464 -f 4464//4464 4524//4524 4525//4525 -f 4464//4464 4525//4525 4465//4465 -f 4465//4465 4525//4525 4526//4526 -f 4465//4465 4526//4526 4466//4466 -f 4466//4466 4526//4526 4527//4527 -f 4466//4466 4527//4527 4467//4467 -f 4467//4467 4527//4527 4528//4528 -f 4467//4467 4528//4528 4468//4468 -f 4468//4468 4528//4528 4529//4529 -f 4468//4468 4529//4529 4469//4469 -f 4469//4469 4529//4529 4530//4530 -f 4469//4469 4530//4530 4470//4470 -f 4470//4470 4530//4530 4531//4531 -f 4470//4470 4531//4531 4471//4471 -f 4471//4471 4531//4531 4532//4532 -f 4471//4471 4532//4532 4472//4472 -f 4472//4472 4532//4532 4533//4533 -f 4472//4472 4533//4533 4473//4473 -f 4473//4473 4533//4533 4534//4534 -f 4473//4473 4534//4534 4474//4474 -f 4474//4474 4534//4534 4535//4535 -f 4474//4474 4535//4535 4475//4475 -f 4475//4475 4535//4535 4536//4536 -f 4475//4475 4536//4536 4476//4476 -f 4476//4476 4536//4536 4537//4537 -f 4476//4476 4537//4537 4477//4477 -f 4477//4477 4537//4537 4538//4538 -f 4477//4477 4538//4538 4478//4478 -f 4478//4478 4538//4538 4539//4539 -f 4478//4478 4539//4539 4479//4479 -f 4479//4479 4539//4539 4540//4540 -f 4479//4479 4540//4540 4480//4480 -f 4480//4480 4540//4540 4541//4541 -f 4480//4480 4541//4541 4481//4481 -f 4481//4481 4541//4541 4542//4542 -f 4481//4481 4542//4542 4482//4482 -f 4482//4482 4542//4542 4543//4543 -f 4482//4482 4543//4543 4483//4483 -f 4483//4483 4543//4543 4544//4544 -f 4483//4483 4544//4544 4484//4484 -f 4484//4484 4544//4544 4545//4545 -f 4484//4484 4545//4545 4485//4485 -f 4485//4485 4545//4545 4546//4546 -f 4485//4485 4546//4546 4486//4486 -f 4486//4486 4546//4546 4547//4547 -f 4486//4486 4547//4547 4487//4487 -f 4487//4487 4547//4547 4548//4548 -f 4487//4487 4548//4548 4488//4488 -f 4488//4488 4548//4548 4549//4549 -f 4488//4488 4549//4549 4489//4489 -f 4489//4489 4549//4549 4550//4550 -f 4489//4489 4550//4550 4490//4490 -f 4490//4490 4550//4550 4551//4551 -f 4490//4490 4551//4551 4491//4491 -f 4491//4491 4551//4551 4552//4552 -f 4491//4491 4552//4552 4492//4492 -f 4492//4492 4552//4552 4553//4553 -f 4492//4492 4553//4553 4493//4493 -f 4493//4493 4553//4553 4554//4554 -f 4493//4493 4554//4554 4494//4494 -f 4494//4494 4554//4554 4495//4495 -f 4555//4555 4556//4556 4525//4525 -f 4525//4525 4556//4556 4526//4526 -f 4526//4526 4556//4556 4557//4557 -f 4526//4526 4557//4557 4527//4527 -f 4527//4527 4557//4557 4558//4558 -f 4527//4527 4558//4558 4528//4528 -f 4528//4528 4558//4558 4559//4559 -f 4528//4528 4559//4559 4529//4529 -f 4529//4529 4559//4559 4560//4560 -f 4529//4529 4560//4560 4530//4530 -f 4530//4530 4560//4560 4561//4561 -f 4530//4530 4561//4561 4531//4531 -f 4531//4531 4561//4561 4562//4562 -f 4531//4531 4562//4562 4532//4532 -f 4562//4562 4563//4563 4532//4532 -f 4532//4532 4563//4563 4564//4564 -f 4532//4532 4564//4564 4533//4533 -f 4533//4533 4564//4564 4565//4565 -f 4533//4533 4565//4565 4534//4534 -f 4534//4534 4565//4565 4535//4535 -f 4535//4535 4565//4565 4566//4566 -f 4535//4535 4566//4566 4536//4536 -f 4536//4536 4566//4566 4567//4567 -f 4536//4536 4567//4567 4537//4537 -f 4537//4537 4567//4567 4568//4568 -f 4537//4537 4568//4568 4538//4538 -f 4538//4538 4568//4568 4569//4569 -f 4538//4538 4569//4569 4539//4539 -f 4539//4539 4569//4569 4570//4570 -f 4539//4539 4570//4570 4540//4540 -f 4540//4540 4570//4570 4571//4571 -f 4540//4540 4571//4571 4541//4541 -f 4541//4541 4571//4571 4572//4572 -f 4541//4541 4572//4572 4542//4542 -f 4572//4572 4573//4573 4542//4542 -f 4542//4542 4573//4573 4574//4574 -f 4542//4542 4574//4574 4543//4543 -f 4543//4543 4574//4574 4575//4575 -f 4543//4543 4575//4575 4544//4544 -f 4544//4544 4575//4575 4545//4545 -f 4545//4545 4575//4575 4576//4576 -f 4545//4545 4576//4576 4546//4546 -f 4546//4546 4576//4576 4577//4577 -f 4546//4546 4577//4577 4547//4547 -f 4547//4547 4577//4577 4578//4578 -f 4547//4547 4578//4578 4548//4548 -f 4548//4548 4578//4578 4579//4579 -f 4548//4548 4579//4579 4549//4549 -f 4549//4549 4579//4579 4580//4580 -f 4549//4549 4580//4580 4550//4550 -f 4550//4550 4580//4580 4581//4581 -f 4550//4550 4581//4581 4551//4551 -f 4551//4551 4581//4581 4582//4582 -f 4551//4551 4582//4582 4552//4552 -f 4582//4582 4583//4583 4552//4552 -f 4552//4552 4583//4583 4584//4584 -f 4552//4552 4584//4584 4553//4553 -f 4553//4553 4584//4584 4585//4585 -f 4553//4553 4585//4585 4554//4554 -f 4554//4554 4585//4585 4495//4495 -f 4495//4495 4585//4585 4586//4586 -f 4495//4495 4586//4586 4496//4496 -f 4496//4496 4586//4586 4587//4587 -f 4496//4496 4587//4587 4497//4497 -f 4497//4497 4587//4587 4588//4588 -f 4497//4497 4588//4588 4498//4498 -f 4498//4498 4588//4588 4589//4589 -f 4498//4498 4589//4589 4499//4499 -f 4499//4499 4589//4589 4590//4590 -f 4499//4499 4590//4590 4500//4500 -f 4500//4500 4590//4590 4591//4591 -f 4500//4500 4591//4591 4501//4501 -f 4501//4501 4591//4591 4592//4592 -f 4501//4501 4592//4592 4502//4502 -f 4592//4592 4593//4593 4502//4502 -f 4502//4502 4593//4593 4594//4594 -f 4502//4502 4594//4594 4503//4503 -f 4503//4503 4594//4594 4595//4595 -f 4503//4503 4595//4595 4504//4504 -f 4504//4504 4595//4595 4505//4505 -f 4505//4505 4595//4595 4596//4596 -f 4505//4505 4596//4596 4506//4506 -f 4506//4506 4596//4596 4597//4597 -f 4506//4506 4597//4597 4507//4507 -f 4507//4507 4597//4597 4598//4598 -f 4507//4507 4598//4598 4508//4508 -f 4508//4508 4598//4598 4599//4599 -f 4508//4508 4599//4599 4509//4509 -f 4509//4509 4599//4599 4600//4600 -f 4509//4509 4600//4600 4510//4510 -f 4510//4510 4600//4600 4601//4601 -f 4510//4510 4601//4601 4511//4511 -f 4511//4511 4601//4601 4602//4602 -f 4511//4511 4602//4602 4512//4512 -f 4602//4602 4603//4603 4512//4512 -f 4512//4512 4603//4603 4604//4604 -f 4512//4512 4604//4604 4513//4513 -f 4513//4513 4604//4604 4605//4605 -f 4513//4513 4605//4605 4514//4514 -f 4514//4514 4605//4605 4515//4515 -f 4515//4515 4605//4605 4606//4606 -f 4515//4515 4606//4606 4516//4516 -f 4516//4516 4606//4606 4607//4607 -f 4516//4516 4607//4607 4517//4517 -f 4517//4517 4607//4607 4608//4608 -f 4517//4517 4608//4608 4518//4518 -f 4518//4518 4608//4608 4609//4609 -f 4518//4518 4609//4609 4519//4519 -f 4519//4519 4609//4609 4610//4610 -f 4519//4519 4610//4610 4520//4520 -f 4520//4520 4610//4610 4611//4611 -f 4520//4520 4611//4611 4521//4521 -f 4521//4521 4611//4611 4612//4612 -f 4521//4521 4612//4612 4522//4522 -f 4612//4612 4613//4613 4522//4522 -f 4522//4522 4613//4613 4614//4614 -f 4522//4522 4614//4614 4523//4523 -f 4523//4523 4614//4614 4555//4555 -f 4523//4523 4555//4555 4524//4524 -f 4524//4524 4555//4555 4525//4525 -f 4615//4615 4616//4616 4617//4617 -f 4618//4618 4619//4619 4620//4620 -f 4621//4621 4622//4622 4623//4623 -f 4624//4624 4625//4625 4626//4626 -f 4627//4627 4628//4628 4629//4629 -f 4630//4630 4631//4631 4632//4632 -f 4633//4633 4634//4634 4635//4635 -f 4636//4636 4637//4637 4638//4638 -f 4589//4589 4588//4588 4639//4639 -f 4591//4591 4590//4590 4640//4640 -f 4597//4597 4596//4596 4641//4641 -f 4609//4609 4608//4608 4642//4642 -f 4611//4611 4610//4610 4643//4643 -f 4557//4557 4556//4556 4644//4644 -f 4569//4569 4568//4568 4645//4645 -f 4571//4571 4570//4570 4646//4646 -f 4577//4577 4576//4576 4647//4647 -f 4648//4648 4585//4585 4584//4584 -f 4648//4648 4584//4584 4649//4649 -f 4649//4649 4584//4584 4583//4583 -f 4649//4649 4583//4583 4650//4650 -f 4580//4580 4651//4651 4581//4581 -f 4581//4581 4651//4651 4650//4650 -f 4581//4581 4650//4650 4582//4582 -f 4582//4582 4650//4650 4583//4583 -f 4580//4580 4579//4579 4652//4652 -f 4577//4577 4647//4647 4578//4578 -f 4637//4637 4574//4574 4573//4573 -f 4637//4637 4573//4573 4638//4638 -f 4638//4638 4573//4573 4572//4572 -f 4638//4638 4572//4572 4571//4571 -f 4569//4569 4645//4645 4570//4570 -f 4568//4568 4567//4567 4653//4653 -f 4653//4653 4567//4567 4566//4566 -f 4653//4653 4566//4566 4565//4565 -f 4560//4560 4635//4635 4561//4561 -f 4561//4561 4635//4635 4634//4634 -f 4561//4561 4634//4634 4562//4562 -f 4562//4562 4634//4634 4563//4563 -f 4560//4560 4559//4559 4654//4654 -f 4557//4557 4644//4644 4558//4558 -f 4631//4631 4614//4614 4613//4613 -f 4631//4631 4613//4613 4632//4632 -f 4632//4632 4613//4613 4612//4612 -f 4632//4632 4612//4612 4611//4611 -f 4609//4609 4642//4642 4610//4610 -f 4608//4608 4607//4607 4655//4655 -f 4655//4655 4607//4607 4606//4606 -f 4655//4655 4606//4606 4605//4605 -f 4600//4600 4629//4629 4601//4601 -f 4601//4601 4629//4629 4628//4628 -f 4601//4601 4628//4628 4602//4602 -f 4602//4602 4628//4628 4603//4603 -f 4600//4600 4599//4599 4656//4656 -f 4597//4597 4641//4641 4598//4598 -f 4625//4625 4594//4594 4593//4593 -f 4625//4625 4593//4593 4626//4626 -f 4626//4626 4593//4593 4592//4592 -f 4626//4626 4592//4592 4591//4591 -f 4589//4589 4639//4639 4590//4590 -f 4588//4588 4587//4587 4657//4657 -f 4657//4657 4587//4587 4586//4586 -f 4657//4657 4586//4586 4585//4585 -f 4575//4575 4574//4574 4658//4658 -f 4658//4658 4574//4574 4637//4637 -f 4658//4658 4637//4637 4659//4659 -f 4659//4659 4637//4637 4636//4636 -f 4659//4659 4636//4636 4660//4660 -f 4564//4564 4563//4563 4661//4661 -f 4661//4661 4563//4563 4634//4634 -f 4661//4661 4634//4634 4662//4662 -f 4662//4662 4634//4634 4633//4633 -f 4662//4662 4633//4633 4663//4663 -f 4555//4555 4614//4614 4664//4664 -f 4664//4664 4614//4614 4631//4631 -f 4664//4664 4631//4631 4665//4665 -f 4665//4665 4631//4631 4630//4630 -f 4665//4665 4630//4630 4666//4666 -f 4604//4604 4603//4603 4667//4667 -f 4667//4667 4603//4603 4628//4628 -f 4667//4667 4628//4628 4668//4668 -f 4668//4668 4628//4628 4627//4627 -f 4668//4668 4627//4627 4669//4669 -f 4595//4595 4594//4594 4670//4670 -f 4670//4670 4594//4594 4625//4625 -f 4670//4670 4625//4625 4671//4671 -f 4671//4671 4625//4625 4624//4624 -f 4671//4671 4624//4624 4672//4672 -f 4651//4651 4673//4673 4650//4650 -f 4650//4650 4673//4673 4674//4674 -f 4650//4650 4674//4674 4649//4649 -f 4649//4649 4674//4674 4675//4675 -f 4649//4649 4675//4675 4648//4648 -f 4648//4648 4675//4675 4676//4676 -f 4677//4677 4678//4678 4679//4679 -f 4680//4680 4681//4681 4682//4682 -f 4683//4683 4681//4681 4684//4684 -f 4684//4684 4681//4681 4680//4680 -f 4684//4684 4680//4680 4685//4685 -f 4565//4565 4564//4564 4685//4685 -f 4685//4685 4564//4564 4661//4661 -f 4685//4685 4661//4661 4684//4684 -f 4684//4684 4661//4661 4662//4662 -f 4684//4684 4662//4662 4683//4683 -f 4683//4683 4662//4662 4663//4663 -f 4686//4686 4687//4687 4688//4688 -f 4689//4689 4690//4690 4691//4691 -f 4692//4692 4690//4690 4693//4693 -f 4693//4693 4690//4690 4689//4689 -f 4693//4693 4689//4689 4694//4694 -f 4605//4605 4604//4604 4694//4694 -f 4694//4694 4604//4604 4667//4667 -f 4694//4694 4667//4667 4693//4693 -f 4693//4693 4667//4667 4668//4668 -f 4693//4693 4668//4668 4692//4692 -f 4692//4692 4668//4668 4669//4669 -f 4695//4695 4696//4696 4697//4697 -f 4673//4673 4698//4698 4674//4674 -f 4674//4674 4698//4698 4699//4699 -f 4674//4674 4699//4699 4675//4675 -f 4675//4675 4699//4699 4700//4700 -f 4675//4675 4700//4700 4676//4676 -f 4676//4676 4700//4700 4701//4701 -f 4580//4580 4652//4652 4651//4651 -f 4651//4651 4652//4652 4702//4702 -f 4651//4651 4702//4702 4673//4673 -f 4673//4673 4702//4702 4623//4623 -f 4673//4673 4623//4623 4698//4698 -f 4698//4698 4623//4623 4622//4622 -f 4698//4698 4622//4622 4703//4703 -f 4652//4652 4677//4677 4702//4702 -f 4702//4702 4677//4677 4679//4679 -f 4702//4702 4679//4679 4623//4623 -f 4623//4623 4679//4679 4704//4704 -f 4623//4623 4704//4704 4621//4621 -f 4705//4705 4706//4706 4707//4707 -f 4707//4707 4706//4706 4678//4678 -f 4707//4707 4678//4678 4708//4708 -f 4708//4708 4678//4678 4677//4677 -f 4708//4708 4677//4677 4647//4647 -f 4647//4647 4677//4677 4652//4652 -f 4647//4647 4652//4652 4578//4578 -f 4578//4578 4652//4652 4579//4579 -f 4706//4706 4709//4709 4678//4678 -f 4678//4678 4709//4709 4710//4710 -f 4678//4678 4710//4710 4679//4679 -f 4679//4679 4710//4710 4711//4711 -f 4679//4679 4711//4711 4704//4704 -f 4576//4576 4575//4575 4647//4647 -f 4647//4647 4575//4575 4658//4658 -f 4647//4647 4658//4658 4708//4708 -f 4708//4708 4658//4658 4659//4659 -f 4708//4708 4659//4659 4707//4707 -f 4707//4707 4659//4659 4660//4660 -f 4707//4707 4660//4660 4705//4705 -f 4705//4705 4660//4660 4712//4712 -f 4713//4713 4714//4714 4715//4715 -f 4571//4571 4646//4646 4638//4638 -f 4638//4638 4646//4646 4716//4716 -f 4638//4638 4716//4716 4636//4636 -f 4636//4636 4716//4716 4713//4713 -f 4636//4636 4713//4713 4660//4660 -f 4660//4660 4713//4713 4715//4715 -f 4660//4660 4715//4715 4712//4712 -f 4717//4717 4718//4718 4719//4719 -f 4570//4570 4645//4645 4646//4646 -f 4646//4646 4645//4645 4720//4720 -f 4646//4646 4720//4720 4716//4716 -f 4716//4716 4720//4720 4717//4717 -f 4716//4716 4717//4717 4713//4713 -f 4713//4713 4717//4717 4719//4719 -f 4713//4713 4719//4719 4714//4714 -f 4721//4721 4722//4722 4723//4723 -f 4568//4568 4653//4653 4645//4645 -f 4645//4645 4653//4653 4724//4724 -f 4645//4645 4724//4724 4720//4720 -f 4720//4720 4724//4724 4721//4721 -f 4720//4720 4721//4721 4717//4717 -f 4717//4717 4721//4721 4723//4723 -f 4717//4717 4723//4723 4718//4718 -f 4565//4565 4685//4685 4653//4653 -f 4653//4653 4685//4685 4680//4680 -f 4653//4653 4680//4680 4724//4724 -f 4724//4724 4680//4680 4682//4682 -f 4724//4724 4682//4682 4721//4721 -f 4721//4721 4682//4682 4725//4725 -f 4721//4721 4725//4725 4722//4722 -f 4726//4726 4727//4727 4663//4663 -f 4663//4663 4727//4727 4728//4728 -f 4663//4663 4728//4728 4683//4683 -f 4683//4683 4728//4728 4729//4729 -f 4683//4683 4729//4729 4681//4681 -f 4681//4681 4729//4729 4730//4730 -f 4681//4681 4730//4730 4682//4682 -f 4682//4682 4730//4730 4731//4731 -f 4682//4682 4731//4731 4725//4725 -f 4560//4560 4654//4654 4635//4635 -f 4635//4635 4654//4654 4732//4732 -f 4635//4635 4732//4732 4633//4633 -f 4633//4633 4732//4732 4620//4620 -f 4633//4633 4620//4620 4663//4663 -f 4663//4663 4620//4620 4619//4619 -f 4663//4663 4619//4619 4726//4726 -f 4654//4654 4686//4686 4732//4732 -f 4732//4732 4686//4686 4688//4688 -f 4732//4732 4688//4688 4620//4620 -f 4620//4620 4688//4688 4733//4733 -f 4620//4620 4733//4733 4618//4618 -f 4734//4734 4735//4735 4736//4736 -f 4736//4736 4735//4735 4687//4687 -f 4736//4736 4687//4687 4737//4737 -f 4737//4737 4687//4687 4686//4686 -f 4737//4737 4686//4686 4644//4644 -f 4644//4644 4686//4686 4654//4654 -f 4644//4644 4654//4654 4558//4558 -f 4558//4558 4654//4654 4559//4559 -f 4735//4735 4738//4738 4687//4687 -f 4687//4687 4738//4738 4739//4739 -f 4687//4687 4739//4739 4688//4688 -f 4688//4688 4739//4739 4740//4740 -f 4688//4688 4740//4740 4733//4733 -f 4556//4556 4555//4555 4644//4644 -f 4644//4644 4555//4555 4664//4664 -f 4644//4644 4664//4664 4737//4737 -f 4737//4737 4664//4664 4665//4665 -f 4737//4737 4665//4665 4736//4736 -f 4736//4736 4665//4665 4666//4666 -f 4736//4736 4666//4666 4734//4734 -f 4734//4734 4666//4666 4741//4741 -f 4742//4742 4743//4743 4744//4744 -f 4611//4611 4643//4643 4632//4632 -f 4632//4632 4643//4643 4745//4745 -f 4632//4632 4745//4745 4630//4630 -f 4630//4630 4745//4745 4742//4742 -f 4630//4630 4742//4742 4666//4666 -f 4666//4666 4742//4742 4744//4744 -f 4666//4666 4744//4744 4741//4741 -f 4746//4746 4747//4747 4748//4748 -f 4610//4610 4642//4642 4643//4643 -f 4643//4643 4642//4642 4749//4749 -f 4643//4643 4749//4749 4745//4745 -f 4745//4745 4749//4749 4746//4746 -f 4745//4745 4746//4746 4742//4742 -f 4742//4742 4746//4746 4748//4748 -f 4742//4742 4748//4748 4743//4743 -f 4750//4750 4751//4751 4752//4752 -f 4608//4608 4655//4655 4642//4642 -f 4642//4642 4655//4655 4753//4753 -f 4642//4642 4753//4753 4749//4749 -f 4749//4749 4753//4753 4750//4750 -f 4749//4749 4750//4750 4746//4746 -f 4746//4746 4750//4750 4752//4752 -f 4746//4746 4752//4752 4747//4747 -f 4605//4605 4694//4694 4655//4655 -f 4655//4655 4694//4694 4689//4689 -f 4655//4655 4689//4689 4753//4753 -f 4753//4753 4689//4689 4691//4691 -f 4753//4753 4691//4691 4750//4750 -f 4750//4750 4691//4691 4754//4754 -f 4750//4750 4754//4754 4751//4751 -f 4755//4755 4756//4756 4669//4669 -f 4669//4669 4756//4756 4757//4757 -f 4669//4669 4757//4757 4692//4692 -f 4692//4692 4757//4757 4758//4758 -f 4692//4692 4758//4758 4690//4690 -f 4690//4690 4758//4758 4759//4759 -f 4690//4690 4759//4759 4691//4691 -f 4691//4691 4759//4759 4760//4760 -f 4691//4691 4760//4760 4754//4754 -f 4600//4600 4656//4656 4629//4629 -f 4629//4629 4656//4656 4761//4761 -f 4629//4629 4761//4761 4627//4627 -f 4627//4627 4761//4761 4617//4617 -f 4627//4627 4617//4617 4669//4669 -f 4669//4669 4617//4617 4616//4616 -f 4669//4669 4616//4616 4755//4755 -f 4656//4656 4695//4695 4761//4761 -f 4761//4761 4695//4695 4697//4697 -f 4761//4761 4697//4697 4617//4617 -f 4617//4617 4697//4697 4762//4762 -f 4617//4617 4762//4762 4615//4615 -f 4763//4763 4764//4764 4765//4765 -f 4765//4765 4764//4764 4696//4696 -f 4765//4765 4696//4696 4766//4766 -f 4766//4766 4696//4696 4695//4695 -f 4766//4766 4695//4695 4641//4641 -f 4641//4641 4695//4695 4656//4656 -f 4641//4641 4656//4656 4598//4598 -f 4598//4598 4656//4656 4599//4599 -f 4764//4764 4767//4767 4696//4696 -f 4696//4696 4767//4767 4768//4768 -f 4696//4696 4768//4768 4697//4697 -f 4697//4697 4768//4768 4769//4769 -f 4697//4697 4769//4769 4762//4762 -f 4596//4596 4595//4595 4641//4641 -f 4641//4641 4595//4595 4670//4670 -f 4641//4641 4670//4670 4766//4766 -f 4766//4766 4670//4670 4671//4671 -f 4766//4766 4671//4671 4765//4765 -f 4765//4765 4671//4671 4672//4672 -f 4765//4765 4672//4672 4763//4763 -f 4763//4763 4672//4672 4770//4770 -f 4771//4771 4772//4772 4773//4773 -f 4591//4591 4640//4640 4626//4626 -f 4626//4626 4640//4640 4774//4774 -f 4626//4626 4774//4774 4624//4624 -f 4624//4624 4774//4774 4771//4771 -f 4624//4624 4771//4771 4672//4672 -f 4672//4672 4771//4771 4773//4773 -f 4672//4672 4773//4773 4770//4770 -f 4775//4775 4776//4776 4777//4777 -f 4590//4590 4639//4639 4640//4640 -f 4640//4640 4639//4639 4778//4778 -f 4640//4640 4778//4778 4774//4774 -f 4774//4774 4778//4778 4775//4775 -f 4774//4774 4775//4775 4771//4771 -f 4771//4771 4775//4775 4777//4777 -f 4771//4771 4777//4777 4772//4772 -f 4779//4779 4780//4780 4781//4781 -f 4588//4588 4657//4657 4639//4639 -f 4639//4639 4657//4657 4782//4782 -f 4639//4639 4782//4782 4778//4778 -f 4778//4778 4782//4782 4779//4779 -f 4778//4778 4779//4779 4775//4775 -f 4775//4775 4779//4779 4781//4781 -f 4775//4775 4781//4781 4776//4776 -f 4585//4585 4648//4648 4657//4657 -f 4657//4657 4648//4648 4676//4676 -f 4657//4657 4676//4676 4782//4782 -f 4782//4782 4676//4676 4701//4701 -f 4782//4782 4701//4701 4779//4779 -f 4779//4779 4701//4701 4783//4783 -f 4779//4779 4783//4783 4780//4780 -f 4703//4703 4784//4784 4698//4698 -f 4698//4698 4784//4784 4785//4785 -f 4698//4698 4785//4785 4699//4699 -f 4699//4699 4785//4785 4786//4786 -f 4699//4699 4786//4786 4700//4700 -f 4700//4700 4786//4786 4787//4787 -f 4700//4700 4787//4787 4701//4701 -f 4701//4701 4787//4787 4788//4788 -f 4701//4701 4788//4788 4783//4783 -f 4706//4706 4789//4789 4709//4709 -f 4709//4709 4789//4789 4790//4790 -f 4709//4709 4790//4790 4710//4710 -f 4710//4710 4790//4790 4791//4791 -f 4710//4710 4791//4791 4711//4711 -f 4711//4711 4791//4791 4792//4792 -f 4711//4711 4792//4792 4704//4704 -f 4723//4723 4793//4793 4718//4718 -f 4718//4718 4793//4793 4794//4794 -f 4718//4718 4794//4794 4719//4719 -f 4719//4719 4794//4794 4795//4795 -f 4719//4719 4795//4795 4714//4714 -f 4714//4714 4795//4795 4796//4796 -f 4714//4714 4796//4796 4715//4715 -f 4715//4715 4796//4796 4797//4797 -f 4715//4715 4797//4797 4712//4712 -f 4712//4712 4797//4797 4798//4798 -f 4712//4712 4798//4798 4705//4705 -f 4705//4705 4798//4798 4799//4799 -f 4705//4705 4799//4799 4706//4706 -f 4706//4706 4799//4799 4800//4800 -f 4706//4706 4800//4800 4789//4789 -f 4728//4728 4801//4801 4729//4729 -f 4729//4729 4801//4801 4802//4802 -f 4729//4729 4802//4802 4730//4730 -f 4730//4730 4802//4802 4803//4803 -f 4730//4730 4803//4803 4731//4731 -f 4731//4731 4803//4803 4804//4804 -f 4731//4731 4804//4804 4725//4725 -f 4725//4725 4804//4804 4805//4805 -f 4725//4725 4805//4805 4722//4722 -f 4722//4722 4805//4805 4806//4806 -f 4722//4722 4806//4806 4723//4723 -f 4723//4723 4806//4806 4807//4807 -f 4723//4723 4807//4807 4793//4793 -f 4727//4727 4808//4808 4728//4728 -f 4728//4728 4808//4808 4809//4809 -f 4728//4728 4809//4809 4801//4801 -f 4739//4739 4810//4810 4740//4740 -f 4740//4740 4810//4810 4811//4811 -f 4740//4740 4811//4811 4733//4733 -f 4733//4733 4811//4811 4812//4812 -f 4733//4733 4812//4812 4618//4618 -f 4618//4618 4812//4812 4813//4813 -f 4618//4618 4813//4813 4619//4619 -f 4619//4619 4813//4813 4814//4814 -f 4619//4619 4814//4814 4726//4726 -f 4726//4726 4814//4814 4815//4815 -f 4726//4726 4815//4815 4727//4727 -f 4727//4727 4815//4815 4816//4816 -f 4727//4727 4816//4816 4808//4808 -f 4741//4741 4817//4817 4734//4734 -f 4734//4734 4817//4817 4818//4818 -f 4734//4734 4818//4818 4735//4735 -f 4735//4735 4818//4818 4819//4819 -f 4735//4735 4819//4819 4738//4738 -f 4738//4738 4819//4819 4820//4820 -f 4738//4738 4820//4820 4739//4739 -f 4739//4739 4820//4820 4821//4821 -f 4739//4739 4821//4821 4810//4810 -f 4754//4754 4822//4822 4751//4751 -f 4751//4751 4822//4822 4823//4823 -f 4751//4751 4823//4823 4752//4752 -f 4752//4752 4823//4823 4824//4824 -f 4752//4752 4824//4824 4747//4747 -f 4747//4747 4824//4824 4825//4825 -f 4747//4747 4825//4825 4748//4748 -f 4748//4748 4825//4825 4826//4826 -f 4748//4748 4826//4826 4743//4743 -f 4743//4743 4826//4826 4827//4827 -f 4743//4743 4827//4827 4744//4744 -f 4744//4744 4827//4827 4828//4828 -f 4744//4744 4828//4828 4741//4741 -f 4741//4741 4828//4828 4829//4829 -f 4741//4741 4829//4829 4817//4817 -f 4757//4757 4830//4830 4758//4758 -f 4758//4758 4830//4830 4831//4831 -f 4758//4758 4831//4831 4759//4759 -f 4759//4759 4831//4831 4832//4832 -f 4759//4759 4832//4832 4760//4760 -f 4760//4760 4832//4832 4833//4833 -f 4760//4760 4833//4833 4754//4754 -f 4754//4754 4833//4833 4834//4834 -f 4754//4754 4834//4834 4822//4822 -f 4616//4616 4835//4835 4755//4755 -f 4755//4755 4835//4835 4836//4836 -f 4755//4755 4836//4836 4756//4756 -f 4756//4756 4836//4836 4837//4837 -f 4756//4756 4837//4837 4757//4757 -f 4757//4757 4837//4837 4838//4838 -f 4757//4757 4838//4838 4830//4830 -f 4768//4768 4839//4839 4769//4769 -f 4769//4769 4839//4839 4840//4840 -f 4769//4769 4840//4840 4762//4762 -f 4762//4762 4840//4840 4841//4841 -f 4762//4762 4841//4841 4615//4615 -f 4615//4615 4841//4841 4842//4842 -f 4615//4615 4842//4842 4616//4616 -f 4616//4616 4842//4842 4843//4843 -f 4616//4616 4843//4843 4835//4835 -f 4777//4777 4844//4844 4772//4772 -f 4772//4772 4844//4844 4845//4845 -f 4772//4772 4845//4845 4773//4773 -f 4773//4773 4845//4845 4846//4846 -f 4773//4773 4846//4846 4770//4770 -f 4770//4770 4846//4846 4847//4847 -f 4770//4770 4847//4847 4763//4763 -f 4763//4763 4847//4847 4848//4848 -f 4763//4763 4848//4848 4764//4764 -f 4764//4764 4848//4848 4849//4849 -f 4764//4764 4849//4849 4767//4767 -f 4767//4767 4849//4849 4850//4850 -f 4767//4767 4850//4850 4768//4768 -f 4768//4768 4850//4850 4851//4851 -f 4768//4768 4851//4851 4839//4839 -f 4787//4787 4852//4852 4788//4788 -f 4788//4788 4852//4852 4853//4853 -f 4788//4788 4853//4853 4783//4783 -f 4783//4783 4853//4853 4854//4854 -f 4783//4783 4854//4854 4780//4780 -f 4780//4780 4854//4854 4855//4855 -f 4780//4780 4855//4855 4781//4781 -f 4781//4781 4855//4855 4856//4856 -f 4781//4781 4856//4856 4776//4776 -f 4776//4776 4856//4856 4857//4857 -f 4776//4776 4857//4857 4777//4777 -f 4777//4777 4857//4857 4858//4858 -f 4777//4777 4858//4858 4844//4844 -f 4792//4792 4859//4859 4704//4704 -f 4704//4704 4859//4859 4860//4860 -f 4704//4704 4860//4860 4621//4621 -f 4621//4621 4860//4860 4861//4861 -f 4621//4621 4861//4861 4622//4622 -f 4622//4622 4861//4861 4862//4862 -f 4622//4622 4862//4862 4703//4703 -f 4703//4703 4862//4862 4863//4863 -f 4703//4703 4863//4863 4784//4784 -f 4784//4784 4863//4863 4864//4864 -f 4784//4784 4864//4864 4785//4785 -f 4785//4785 4864//4864 4865//4865 -f 4785//4785 4865//4865 4786//4786 -f 4786//4786 4865//4865 4866//4866 -f 4786//4786 4866//4866 4787//4787 -f 4787//4787 4866//4866 4867//4867 -f 4787//4787 4867//4867 4852//4852 -f 4868//4868 4869//4869 4870//4870 -f 4871//4871 4872//4872 4873//4873 -f 4873//4873 4872//4872 4874//4874 -f 4875//4875 4876//4876 4877//4877 -f 4877//4877 4876//4876 4878//4878 -f 4879//4879 4880//4880 4881//4881 -f 4882//4882 4883//4883 4884//4884 -f 4885//4885 4886//4886 4887//4887 -f 4888//4888 4889//4889 4890//4890 -f 4891//4891 4892//4892 4893//4893 -f 4894//4894 4895//4895 4896//4896 -f 4897//4897 4898//4898 4899//4899 -f 4900//4900 4901//4901 4902//4902 -f 4866//4866 4865//4865 4900//4900 -f 4853//4853 4852//4852 4903//4903 -f 4856//4856 4855//4855 4885//4885 -f 4858//4858 4857//4857 4904//4904 -f 4845//4845 4844//4844 4905//4905 -f 4846//4846 4845//4845 4906//4906 -f 4848//4848 4847//4847 4907//4907 -f 4840//4840 4839//4839 4888//4888 -f 4842//4842 4841//4841 4908//4908 -f 4835//4835 4843//4843 4909//4909 -f 4836//4836 4835//4835 4910//4910 -f 4834//4834 4833//4833 4911//4911 -f 4826//4826 4825//4825 4891//4891 -f 4828//4828 4827//4827 4912//4912 -f 4817//4817 4829//4829 4913//4913 -f 4818//4818 4817//4817 4914//4914 -f 4813//4813 4812//4812 4915//4915 -f 4809//4809 4808//4808 4894//4894 -f 4802//4802 4801//4801 4916//4916 -f 4804//4804 4803//4803 4917//4917 -f 4805//4805 4804//4804 4918//4918 -f 4807//4807 4806//4806 4919//4919 -f 4797//4797 4796//4796 4897//4897 -f 4799//4799 4798//4798 4920//4920 -f 4789//4789 4800//4800 4921//4921 -f 4790//4790 4789//4789 4922//4922 -f 4863//4863 4862//4862 4923//4923 -f 4900//4900 4865//4865 4901//4901 -f 4901//4901 4865//4865 4864//4864 -f 4901//4901 4864//4864 4863//4863 -f 4923//4923 4862//4862 4924//4924 -f 4862//4862 4861//4861 4924//4924 -f 4924//4924 4861//4861 4860//4860 -f 4924//4924 4860//4860 4925//4925 -f 4925//4925 4860//4860 4859//4859 -f 4925//4925 4859//4859 4792//4792 -f 4792//4792 4791//4791 4926//4926 -f 4926//4926 4791//4791 4790//4790 -f 4897//4897 4796//4796 4898//4898 -f 4898//4898 4796//4796 4795//4795 -f 4898//4898 4795//4795 4794//4794 -f 4794//4794 4793//4793 4927//4927 -f 4927//4927 4793//4793 4807//4807 -f 4805//4805 4918//4918 4806//4806 -f 4894//4894 4808//4808 4895//4895 -f 4895//4895 4808//4808 4816//4816 -f 4895//4895 4816//4816 4815//4815 -f 4815//4815 4814//4814 4928//4928 -f 4928//4928 4814//4814 4813//4813 -f 4915//4915 4812//4812 4929//4929 -f 4812//4812 4811//4811 4929//4929 -f 4929//4929 4811//4811 4810//4810 -f 4929//4929 4810//4810 4930//4930 -f 4819//4819 4931//4931 4820//4820 -f 4820//4820 4931//4931 4930//4930 -f 4820//4820 4930//4930 4821//4821 -f 4821//4821 4930//4930 4810//4810 -f 4818//4818 4914//4914 4819//4819 -f 4891//4891 4825//4825 4892//4892 -f 4892//4892 4825//4825 4824//4824 -f 4892//4892 4824//4824 4823//4823 -f 4823//4823 4822//4822 4932//4932 -f 4932//4932 4822//4822 4834//4834 -f 4911//4911 4833//4833 4933//4933 -f 4833//4833 4832//4832 4933//4933 -f 4933//4933 4832//4832 4831//4831 -f 4933//4933 4831//4831 4934//4934 -f 4831//4831 4830//4830 4934//4934 -f 4934//4934 4830//4830 4838//4838 -f 4934//4934 4838//4838 4935//4935 -f 4935//4935 4838//4838 4837//4837 -f 4935//4935 4837//4837 4836//4836 -f 4888//4888 4839//4839 4889//4889 -f 4889//4889 4839//4839 4851//4851 -f 4889//4889 4851//4851 4850//4850 -f 4850//4850 4849//4849 4936//4936 -f 4936//4936 4849//4849 4848//4848 -f 4846//4846 4906//4906 4847//4847 -f 4885//4885 4855//4855 4886//4886 -f 4886//4886 4855//4855 4854//4854 -f 4886//4886 4854//4854 4853//4853 -f 4925//4925 4937//4937 4924//4924 -f 4924//4924 4937//4937 4938//4938 -f 4924//4924 4938//4938 4923//4923 -f 4923//4923 4938//4938 4884//4884 -f 4939//4939 4940//4940 4921//4921 -f 4800//4800 4799//4799 4921//4921 -f 4921//4921 4799//4799 4920//4920 -f 4921//4921 4920//4920 4939//4939 -f 4939//4939 4920//4920 4941//4941 -f 4939//4939 4941//4941 4942//4942 -f 4942//4942 4941//4941 4943//4943 -f 4944//4944 4945//4945 4917//4917 -f 4803//4803 4802//4802 4917//4917 -f 4917//4917 4802//4802 4916//4916 -f 4917//4917 4916//4916 4944//4944 -f 4944//4944 4916//4916 4946//4946 -f 4944//4944 4946//4946 4947//4947 -f 4947//4947 4946//4946 4948//4948 -f 4931//4931 4877//4877 4930//4930 -f 4930//4930 4877//4877 4878//4878 -f 4930//4930 4878//4878 4929//4929 -f 4929//4929 4878//4878 4949//4949 -f 4929//4929 4949//4949 4915//4915 -f 4915//4915 4949//4949 4950//4950 -f 4951//4951 4952//4952 4913//4913 -f 4829//4829 4828//4828 4913//4913 -f 4913//4913 4828//4828 4912//4912 -f 4913//4913 4912//4912 4951//4951 -f 4951//4951 4912//4912 4953//4953 -f 4951//4951 4953//4953 4954//4954 -f 4954//4954 4953//4953 4955//4955 -f 4935//4935 4873//4873 4934//4934 -f 4934//4934 4873//4873 4874//4874 -f 4934//4934 4874//4874 4933//4933 -f 4933//4933 4874//4874 4956//4956 -f 4933//4933 4956//4956 4911//4911 -f 4911//4911 4956//4956 4957//4957 -f 4958//4958 4959//4959 4909//4909 -f 4843//4843 4842//4842 4909//4909 -f 4909//4909 4842//4842 4908//4908 -f 4909//4909 4908//4908 4958//4958 -f 4958//4958 4908//4908 4960//4960 -f 4958//4958 4960//4960 4961//4961 -f 4961//4961 4960//4960 4962//4962 -f 4963//4963 4964//4964 4905//4905 -f 4965//4965 4966//4966 4903//4903 -f 4852//4852 4867//4867 4903//4903 -f 4903//4903 4867//4867 4967//4967 -f 4903//4903 4967//4967 4965//4965 -f 4965//4965 4967//4967 4968//4968 -f 4969//4969 4970//4970 4902//4902 -f 4902//4902 4970//4970 4968//4968 -f 4902//4902 4968//4968 4900//4900 -f 4900//4900 4968//4968 4967//4967 -f 4900//4900 4967//4967 4866//4866 -f 4866//4866 4967//4967 4867//4867 -f 4863//4863 4923//4923 4901//4901 -f 4901//4901 4923//4923 4884//4884 -f 4901//4901 4884//4884 4902//4902 -f 4902//4902 4884//4884 4883//4883 -f 4902//4902 4883//4883 4969//4969 -f 4882//4882 4884//4884 4971//4971 -f 4971//4971 4884//4884 4938//4938 -f 4971//4971 4938//4938 4972//4972 -f 4972//4972 4938//4938 4937//4937 -f 4972//4972 4937//4937 4973//4973 -f 4974//4974 4975//4975 4976//4976 -f 4792//4792 4926//4926 4925//4925 -f 4925//4925 4926//4926 4974//4974 -f 4925//4925 4974//4974 4937//4937 -f 4937//4937 4974//4974 4976//4976 -f 4937//4937 4976//4976 4973//4973 -f 4790//4790 4922//4922 4926//4926 -f 4926//4926 4922//4922 4977//4977 -f 4926//4926 4977//4977 4974//4974 -f 4974//4974 4977//4977 4978//4978 -f 4974//4974 4978//4978 4975//4975 -f 4789//4789 4921//4921 4922//4922 -f 4922//4922 4921//4921 4940//4940 -f 4922//4922 4940//4940 4977//4977 -f 4977//4977 4940//4940 4979//4979 -f 4977//4977 4979//4979 4978//4978 -f 4942//4942 4980//4980 4939//4939 -f 4939//4939 4980//4980 4981//4981 -f 4939//4939 4981//4981 4940//4940 -f 4940//4940 4981//4981 4982//4982 -f 4940//4940 4982//4982 4979//4979 -f 4798//4798 4797//4797 4920//4920 -f 4920//4920 4797//4797 4897//4897 -f 4920//4920 4897//4897 4941//4941 -f 4941//4941 4897//4897 4899//4899 -f 4941//4941 4899//4899 4943//4943 -f 4943//4943 4899//4899 4983//4983 -f 4984//4984 4985//4985 4986//4986 -f 4794//4794 4927//4927 4898//4898 -f 4898//4898 4927//4927 4984//4984 -f 4898//4898 4984//4984 4899//4899 -f 4899//4899 4984//4984 4986//4986 -f 4899//4899 4986//4986 4983//4983 -f 4807//4807 4919//4919 4927//4927 -f 4927//4927 4919//4919 4881//4881 -f 4927//4927 4881//4881 4984//4984 -f 4984//4984 4881//4881 4880//4880 -f 4984//4984 4880//4880 4985//4985 -f 4806//4806 4918//4918 4919//4919 -f 4919//4919 4918//4918 4987//4987 -f 4919//4919 4987//4987 4881//4881 -f 4881//4881 4987//4987 4988//4988 -f 4881//4881 4988//4988 4879//4879 -f 4804//4804 4917//4917 4918//4918 -f 4918//4918 4917//4917 4945//4945 -f 4918//4918 4945//4945 4987//4987 -f 4987//4987 4945//4945 4989//4989 -f 4987//4987 4989//4989 4988//4988 -f 4947//4947 4990//4990 4944//4944 -f 4944//4944 4990//4990 4991//4991 -f 4944//4944 4991//4991 4945//4945 -f 4945//4945 4991//4991 4992//4992 -f 4945//4945 4992//4992 4989//4989 -f 4801//4801 4809//4809 4916//4916 -f 4916//4916 4809//4809 4894//4894 -f 4916//4916 4894//4894 4946//4946 -f 4946//4946 4894//4894 4896//4896 -f 4946//4946 4896//4896 4948//4948 -f 4948//4948 4896//4896 4993//4993 -f 4994//4994 4995//4995 4996//4996 -f 4815//4815 4928//4928 4895//4895 -f 4895//4895 4928//4928 4994//4994 -f 4895//4895 4994//4994 4896//4896 -f 4896//4896 4994//4994 4996//4996 -f 4896//4896 4996//4996 4993//4993 -f 4813//4813 4915//4915 4928//4928 -f 4928//4928 4915//4915 4950//4950 -f 4928//4928 4950//4950 4994//4994 -f 4994//4994 4950//4950 4997//4997 -f 4994//4994 4997//4997 4995//4995 -f 4876//4876 4998//4998 4878//4878 -f 4878//4878 4998//4998 4999//4999 -f 4878//4878 4999//4999 4949//4949 -f 4949//4949 4999//4999 5000//5000 -f 4949//4949 5000//5000 4950//4950 -f 4950//4950 5000//5000 5001//5001 -f 4950//4950 5001//5001 4997//4997 -f 4819//4819 4914//4914 4931//4931 -f 4931//4931 4914//4914 5002//5002 -f 4931//4931 5002//5002 4877//4877 -f 4877//4877 5002//5002 5003//5003 -f 4877//4877 5003//5003 4875//4875 -f 4817//4817 4913//4913 4914//4914 -f 4914//4914 4913//4913 4952//4952 -f 4914//4914 4952//4952 5002//5002 -f 5002//5002 4952//4952 5004//5004 -f 5002//5002 5004//5004 5003//5003 -f 4954//4954 5005//5005 4951//4951 -f 4951//4951 5005//5005 5006//5006 -f 4951//4951 5006//5006 4952//4952 -f 4952//4952 5006//5006 5007//5007 -f 4952//4952 5007//5007 5004//5004 -f 4827//4827 4826//4826 4912//4912 -f 4912//4912 4826//4826 4891//4891 -f 4912//4912 4891//4891 4953//4953 -f 4953//4953 4891//4891 4893//4893 -f 4953//4953 4893//4893 4955//4955 -f 4955//4955 4893//4893 5008//5008 -f 5009//5009 5010//5010 5011//5011 -f 4823//4823 4932//4932 4892//4892 -f 4892//4892 4932//4932 5009//5009 -f 4892//4892 5009//5009 4893//4893 -f 4893//4893 5009//5009 5011//5011 -f 4893//4893 5011//5011 5008//5008 -f 4834//4834 4911//4911 4932//4932 -f 4932//4932 4911//4911 4957//4957 -f 4932//4932 4957//4957 5009//5009 -f 5009//5009 4957//4957 5012//5012 -f 5009//5009 5012//5012 5010//5010 -f 4872//4872 5013//5013 4874//4874 -f 4874//4874 5013//5013 5014//5014 -f 4874//4874 5014//5014 4956//4956 -f 4956//4956 5014//5014 5015//5015 -f 4956//4956 5015//5015 4957//4957 -f 4957//4957 5015//5015 5016//5016 -f 4957//4957 5016//5016 5012//5012 -f 4836//4836 4910//4910 4935//4935 -f 4935//4935 4910//4910 5017//5017 -f 4935//4935 5017//5017 4873//4873 -f 4873//4873 5017//5017 5018//5018 -f 4873//4873 5018//5018 4871//4871 -f 4835//4835 4909//4909 4910//4910 -f 4910//4910 4909//4909 4959//4959 -f 4910//4910 4959//4959 5017//5017 -f 5017//5017 4959//4959 5019//5019 -f 5017//5017 5019//5019 5018//5018 -f 4961//4961 5020//5020 4958//4958 -f 4958//4958 5020//5020 5021//5021 -f 4958//4958 5021//5021 4959//4959 -f 4959//4959 5021//5021 5022//5022 -f 4959//4959 5022//5022 5019//5019 -f 4841//4841 4840//4840 4908//4908 -f 4908//4908 4840//4840 4888//4888 -f 4908//4908 4888//4888 4960//4960 -f 4960//4960 4888//4888 4890//4890 -f 4960//4960 4890//4890 4962//4962 -f 4962//4962 4890//4890 5023//5023 -f 5024//5024 5025//5025 5026//5026 -f 4850//4850 4936//4936 4889//4889 -f 4889//4889 4936//4936 5024//5024 -f 4889//4889 5024//5024 4890//4890 -f 4890//4890 5024//5024 5026//5026 -f 4890//4890 5026//5026 5023//5023 -f 4848//4848 4907//4907 4936//4936 -f 4936//4936 4907//4907 4870//4870 -f 4936//4936 4870//4870 5024//5024 -f 5024//5024 4870//4870 4869//4869 -f 5024//5024 4869//4869 5025//5025 -f 4847//4847 4906//4906 4907//4907 -f 4907//4907 4906//4906 5027//5027 -f 4907//4907 5027//5027 4870//4870 -f 4870//4870 5027//5027 5028//5028 -f 4870//4870 5028//5028 4868//4868 -f 4845//4845 4905//4905 4906//4906 -f 4906//4906 4905//4905 4964//4964 -f 4906//4906 4964//4964 5027//5027 -f 5027//5027 4964//4964 5029//5029 -f 5027//5027 5029//5029 5028//5028 -f 5030//5030 5031//5031 5032//5032 -f 5032//5032 5031//5031 4963//4963 -f 5032//5032 4963//4963 4904//4904 -f 4904//4904 4963//4963 4905//4905 -f 4904//4904 4905//4905 4858//4858 -f 4858//4858 4905//4905 4844//4844 -f 5031//5031 5033//5033 4963//4963 -f 4963//4963 5033//5033 5034//5034 -f 4963//4963 5034//5034 4964//4964 -f 4964//4964 5034//5034 5035//5035 -f 4964//4964 5035//5035 5029//5029 -f 4857//4857 4856//4856 4904//4904 -f 4904//4904 4856//4856 4885//4885 -f 4904//4904 4885//4885 5032//5032 -f 5032//5032 4885//4885 4887//4887 -f 5032//5032 4887//4887 5030//5030 -f 5030//5030 4887//4887 5036//5036 -f 4853//4853 4903//4903 4886//4886 -f 4886//4886 4903//4903 4966//4966 -f 4886//4886 4966//4966 4887//4887 -f 4887//4887 4966//4966 5037//5037 -f 4887//4887 5037//5037 5036//5036 -f 4970//4970 5038//5038 4968//4968 -f 4968//4968 5038//5038 5039//5039 -f 4968//4968 5039//5039 4965//4965 -f 4965//4965 5039//5039 5040//5040 -f 4965//4965 5040//5040 4966//4966 -f 4966//4966 5040//5040 5041//5041 -f 4966//4966 5041//5041 5037//5037 -f 5042//5042 5043//5043 5000//5000 -f 5000//5000 5043//5043 5001//5001 -f 5001//5001 5043//5043 5044//5044 -f 5001//5001 5044//5044 4997//4997 -f 4997//4997 5044//5044 5045//5045 -f 4997//4997 5045//5045 4995//4995 -f 4995//4995 5045//5045 5046//5046 -f 4995//4995 5046//5046 4996//4996 -f 4996//4996 5046//5046 4993//4993 -f 4993//4993 5046//5046 5047//5047 -f 4993//4993 5047//5047 4948//4948 -f 5047//5047 5048//5048 4948//4948 -f 4948//4948 5048//5048 5049//5049 -f 4948//4948 5049//5049 4947//4947 -f 4947//4947 5049//5049 5050//5050 -f 5051//5051 4880//4880 5052//5052 -f 5052//5052 4880//4880 4879//4879 -f 5052//5052 4879//4879 5053//5053 -f 5053//5053 4879//4879 4988//4988 -f 5053//5053 4988//4988 5054//5054 -f 5054//5054 4988//4988 4989//4989 -f 5054//5054 4989//4989 5055//5055 -f 5055//5055 4989//4989 4992//4992 -f 5055//5055 4992//4992 5056//5056 -f 5056//5056 4992//4992 4991//4991 -f 5056//5056 4991//4991 5050//5050 -f 5050//5050 4991//4991 4990//4990 -f 5050//5050 4990//4990 4947//4947 -f 5057//5057 4978//4978 5058//5058 -f 5058//5058 4978//4978 4979//4979 -f 5058//5058 4979//4979 5059//5059 -f 5059//5059 4979//4979 4982//4982 -f 5059//5059 4982//4982 5060//5060 -f 5060//5060 4982//4982 4981//4981 -f 5060//5060 4981//4981 5061//5061 -f 5061//5061 4981//4981 4980//4980 -f 5061//5061 4980//4980 5062//5062 -f 5062//5062 4980//4980 4942//4942 -f 5062//5062 4942//4942 5063//5063 -f 5063//5063 4942//4942 4943//4943 -f 5063//5063 4943//4943 5064//5064 -f 5064//5064 4943//4943 4983//4983 -f 5064//5064 4983//4983 5065//5065 -f 5065//5065 4983//4983 4986//4986 -f 5065//5065 4986//4986 5051//5051 -f 5051//5051 4986//4986 4985//4985 -f 5051//5051 4985//4985 4880//4880 -f 5066//5066 4883//4883 5067//5067 -f 5067//5067 4883//4883 4882//4882 -f 5067//5067 4882//4882 5068//5068 -f 5068//5068 4882//4882 4971//4971 -f 5068//5068 4971//4971 5069//5069 -f 5069//5069 4971//4971 4972//4972 -f 5069//5069 4972//4972 5070//5070 -f 5070//5070 4972//4972 4973//4973 -f 5070//5070 4973//4973 5071//5071 -f 5071//5071 4973//4973 4976//4976 -f 5071//5071 4976//4976 5057//5057 -f 5057//5057 4976//4976 4975//4975 -f 5057//5057 4975//4975 4978//4978 -f 5072//5072 5041//5041 5073//5073 -f 5073//5073 5041//5041 5040//5040 -f 5073//5073 5040//5040 5074//5074 -f 5074//5074 5040//5040 5039//5039 -f 5074//5074 5039//5039 5075//5075 -f 5075//5075 5039//5039 5038//5038 -f 5075//5075 5038//5038 5076//5076 -f 5076//5076 5038//5038 4970//4970 -f 5076//5076 4970//4970 5066//5066 -f 5066//5066 4970//4970 4969//4969 -f 5066//5066 4969//4969 4883//4883 -f 5077//5077 4869//4869 5078//5078 -f 5078//5078 4869//4869 4868//4868 -f 5078//5078 4868//4868 5079//5079 -f 5079//5079 4868//4868 5028//5028 -f 5079//5079 5028//5028 5080//5080 -f 5080//5080 5028//5028 5029//5029 -f 5080//5080 5029//5029 5081//5081 -f 5081//5081 5029//5029 5035//5035 -f 5081//5081 5035//5035 5082//5082 -f 5082//5082 5035//5035 5034//5034 -f 5082//5082 5034//5034 5083//5083 -f 5083//5083 5034//5034 5033//5033 -f 5083//5083 5033//5033 5084//5084 -f 5084//5084 5033//5033 5031//5031 -f 5084//5084 5031//5031 5085//5085 -f 5085//5085 5031//5031 5030//5030 -f 5085//5085 5030//5030 5086//5086 -f 5086//5086 5030//5030 5036//5036 -f 5086//5086 5036//5036 5072//5072 -f 5072//5072 5036//5036 5037//5037 -f 5072//5072 5037//5037 5041//5041 -f 5087//5087 5020//5020 5088//5088 -f 5088//5088 5020//5020 4961//4961 -f 5088//5088 4961//4961 5089//5089 -f 5089//5089 4961//4961 4962//4962 -f 5089//5089 4962//4962 5090//5090 -f 5090//5090 4962//4962 5023//5023 -f 5090//5090 5023//5023 5091//5091 -f 5091//5091 5023//5023 5026//5026 -f 5091//5091 5026//5026 5077//5077 -f 5077//5077 5026//5026 5025//5025 -f 5077//5077 5025//5025 4869//4869 -f 5092//5092 5012//5012 5093//5093 -f 5093//5093 5012//5012 5016//5016 -f 5093//5093 5016//5016 5094//5094 -f 5094//5094 5016//5016 5015//5015 -f 5094//5094 5015//5015 5095//5095 -f 5095//5095 5015//5015 5014//5014 -f 5095//5095 5014//5014 5096//5096 -f 5096//5096 5014//5014 5013//5013 -f 5096//5096 5013//5013 5097//5097 -f 5097//5097 5013//5013 4872//4872 -f 5097//5097 4872//4872 5098//5098 -f 5098//5098 4872//4872 4871//4871 -f 5098//5098 4871//4871 5099//5099 -f 5099//5099 4871//4871 5018//5018 -f 5099//5099 5018//5018 5100//5100 -f 5100//5100 5018//5018 5019//5019 -f 5100//5100 5019//5019 5101//5101 -f 5101//5101 5019//5019 5022//5022 -f 5101//5101 5022//5022 5087//5087 -f 5087//5087 5022//5022 5021//5021 -f 5087//5087 5021//5021 5020//5020 -f 5102//5102 4954//4954 5103//5103 -f 5103//5103 4954//4954 4955//4955 -f 5103//5103 4955//4955 5104//5104 -f 5104//5104 4955//4955 5008//5008 -f 5104//5104 5008//5008 5105//5105 -f 5105//5105 5008//5008 5011//5011 -f 5105//5105 5011//5011 5092//5092 -f 5092//5092 5011//5011 5010//5010 -f 5092//5092 5010//5010 5012//5012 -f 5000//5000 4999//4999 5042//5042 -f 5042//5042 4999//4999 4998//4998 -f 5042//5042 4998//4998 5106//5106 -f 5106//5106 4998//4998 4876//4876 -f 5106//5106 4876//4876 5107//5107 -f 5107//5107 4876//4876 4875//4875 -f 5107//5107 4875//4875 5108//5108 -f 5108//5108 4875//4875 5003//5003 -f 5108//5108 5003//5003 5109//5109 -f 5109//5109 5003//5003 5004//5004 -f 5109//5109 5004//5004 5110//5110 -f 5110//5110 5004//5004 5007//5007 -f 5110//5110 5007//5007 5111//5111 -f 5111//5111 5007//5007 5006//5006 -f 5111//5111 5006//5006 5102//5102 -f 5102//5102 5006//5006 5005//5005 -f 5102//5102 5005//5005 4954//4954 -f 5112//5112 5113//5113 5114//5114 -f 5115//5115 5116//5116 5117//5117 -f 5118//5118 5119//5119 5120//5120 -f 5121//5121 5122//5122 5123//5123 -f 5124//5124 5125//5125 5126//5126 -f 5127//5127 5128//5128 5129//5129 -f 5130//5130 5131//5131 5132//5132 -f 5133//5133 5134//5134 5135//5135 -f 5136//5136 5137//5137 5138//5138 -f 5139//5139 5140//5140 5141//5141 -f 5142//5142 5143//5143 5144//5144 -f 5145//5145 5146//5146 5147//5147 -f 5148//5148 5149//5149 5150//5150 -f 5138//5138 5151//5151 5152//5152 -f 5149//5149 5153//5153 5154//5154 -f 5151//5151 5155//5155 5156//5156 -f 5080//5080 5081//5081 5157//5157 -f 5078//5078 5079//5079 5158//5158 -f 5087//5087 5088//5088 5159//5159 -f 5105//5105 5092//5092 5160//5160 -f 5109//5109 5110//5110 5161//5161 -f 5107//5107 5108//5108 5162//5162 -f 5042//5042 5106//5106 5163//5163 -f 5044//5044 5043//5043 5164//5164 -f 5046//5046 5045//5045 5165//5165 -f 5061//5061 5062//5062 5166//5166 -f 5059//5059 5060//5060 5167//5167 -f 5071//5071 5057//5057 5168//5168 -f 5076//5076 5169//5169 5170//5170 -f 5066//5066 5067//5067 5171//5171 -f 5068//5068 5069//5069 5172//5172 -f 5071//5071 5168//5168 5070//5070 -f 5052//5052 5173//5173 5156//5156 -f 5063//5063 5064//5064 5155//5155 -f 5155//5155 5064//5064 5065//5065 -f 5155//5155 5065//5065 5156//5156 -f 5156//5156 5065//5065 5051//5051 -f 5156//5156 5051//5051 5052//5052 -f 5052//5052 5053//5053 5173//5173 -f 5173//5173 5053//5053 5054//5054 -f 5173//5173 5054//5054 5174//5174 -f 5174//5174 5054//5054 5055//5055 -f 5174//5174 5055//5055 5175//5175 -f 5055//5055 5056//5056 5175//5175 -f 5175//5175 5056//5056 5050//5050 -f 5175//5175 5050//5050 5176//5176 -f 5176//5176 5050//5050 5049//5049 -f 5176//5176 5049//5049 5048//5048 -f 5102//5102 5103//5103 5177//5177 -f 5105//5105 5160//5160 5104//5104 -f 5093//5093 5094//5094 5153//5153 -f 5153//5153 5094//5094 5095//5095 -f 5153//5153 5095//5095 5154//5154 -f 5154//5154 5095//5095 5096//5096 -f 5154//5154 5096//5096 5178//5178 -f 5096//5096 5097//5097 5178//5178 -f 5178//5178 5097//5097 5098//5098 -f 5178//5178 5098//5098 5179//5179 -f 5101//5101 5180//5180 5100//5100 -f 5100//5100 5180//5180 5179//5179 -f 5100//5100 5179//5179 5099//5099 -f 5099//5099 5179//5179 5098//5098 -f 5090//5090 5091//5091 5181//5181 -f 5078//5078 5158//5158 5077//5077 -f 5083//5083 5084//5084 5182//5182 -f 5182//5182 5084//5084 5085//5085 -f 5182//5182 5085//5085 5183//5183 -f 5085//5085 5086//5086 5183//5183 -f 5183//5183 5086//5086 5072//5072 -f 5183//5183 5072//5072 5184//5184 -f 5072//5072 5073//5073 5184//5184 -f 5184//5184 5073//5073 5074//5074 -f 5184//5184 5074//5074 5170//5170 -f 5170//5170 5074//5074 5075//5075 -f 5170//5170 5075//5075 5076//5076 -f 5169//5169 5185//5185 5186//5186 -f 5151//5151 5156//5156 5152//5152 -f 5152//5152 5156//5156 5173//5173 -f 5152//5152 5173//5173 5187//5187 -f 5187//5187 5173//5173 5174//5174 -f 5187//5187 5174//5174 5188//5188 -f 5188//5188 5174//5174 5175//5175 -f 5188//5188 5175//5175 5189//5189 -f 5189//5189 5175//5175 5176//5176 -f 5189//5189 5176//5176 5190//5190 -f 5149//5149 5154//5154 5150//5150 -f 5150//5150 5154//5154 5178//5178 -f 5150//5150 5178//5178 5191//5191 -f 5191//5191 5178//5178 5179//5179 -f 5191//5191 5179//5179 5192//5192 -f 5192//5192 5179//5179 5180//5180 -f 5192//5192 5180//5180 5193//5193 -f 5169//5169 5186//5186 5170//5170 -f 5170//5170 5186//5186 5194//5194 -f 5170//5170 5194//5194 5184//5184 -f 5184//5184 5194//5194 5195//5195 -f 5184//5184 5195//5195 5183//5183 -f 5183//5183 5195//5195 5196//5196 -f 5183//5183 5196//5196 5182//5182 -f 5185//5185 5197//5197 5198//5198 -f 5057//5057 5058//5058 5168//5168 -f 5168//5168 5058//5058 5199//5199 -f 5168//5168 5199//5199 5200//5200 -f 5200//5200 5199//5199 5201//5201 -f 5200//5200 5201//5201 5202//5202 -f 5202//5202 5201//5201 5144//5144 -f 5138//5138 5152//5152 5203//5203 -f 5203//5203 5152//5152 5187//5187 -f 5203//5203 5187//5187 5204//5204 -f 5204//5204 5187//5187 5188//5188 -f 5204//5204 5188//5188 5205//5205 -f 5205//5205 5188//5188 5189//5189 -f 5205//5205 5189//5189 5206//5206 -f 5206//5206 5189//5189 5190//5190 -f 5206//5206 5190//5190 5135//5135 -f 5045//5045 5044//5044 5165//5165 -f 5165//5165 5044//5044 5164//5164 -f 5165//5165 5164//5164 5207//5207 -f 5207//5207 5164//5164 5208//5208 -f 5207//5207 5208//5208 5209//5209 -f 5209//5209 5208//5208 5132//5132 -f 5110//5110 5111//5111 5161//5161 -f 5161//5161 5111//5111 5210//5210 -f 5161//5161 5210//5210 5211//5211 -f 5211//5211 5210//5210 5212//5212 -f 5211//5211 5212//5212 5213//5213 -f 5213//5213 5212//5212 5126//5126 -f 5148//5148 5150//5150 5214//5214 -f 5214//5214 5150//5150 5191//5191 -f 5214//5214 5191//5191 5215//5215 -f 5215//5215 5191//5191 5192//5192 -f 5215//5215 5192//5192 5216//5216 -f 5216//5216 5192//5192 5193//5193 -f 5216//5216 5193//5193 5217//5217 -f 5091//5091 5077//5077 5181//5181 -f 5181//5181 5077//5077 5158//5158 -f 5181//5181 5158//5158 5218//5218 -f 5218//5218 5158//5158 5219//5219 -f 5218//5218 5219//5219 5220//5220 -f 5220//5220 5219//5219 5117//5117 -f 5185//5185 5198//5198 5186//5186 -f 5186//5186 5198//5198 5221//5221 -f 5186//5186 5221//5221 5194//5194 -f 5194//5194 5221//5221 5222//5222 -f 5194//5194 5222//5222 5195//5195 -f 5195//5195 5222//5222 5223//5223 -f 5195//5195 5223//5223 5196//5196 -f 5076//5076 5066//5066 5169//5169 -f 5169//5169 5066//5066 5171//5171 -f 5169//5169 5171//5171 5185//5185 -f 5185//5185 5171//5171 5224//5224 -f 5185//5185 5224//5224 5197//5197 -f 5197//5197 5224//5224 5147//5147 -f 5197//5197 5147//5147 5225//5225 -f 5225//5225 5147//5147 5146//5146 -f 5226//5226 5145//5145 5227//5227 -f 5227//5227 5145//5145 5147//5147 -f 5227//5227 5147//5147 5228//5228 -f 5228//5228 5147//5147 5224//5224 -f 5228//5228 5224//5224 5172//5172 -f 5172//5172 5224//5224 5171//5171 -f 5172//5172 5171//5171 5068//5068 -f 5068//5068 5171//5171 5067//5067 -f 5069//5069 5070//5070 5172//5172 -f 5172//5172 5070//5070 5168//5168 -f 5172//5172 5168//5168 5228//5228 -f 5228//5228 5168//5168 5200//5200 -f 5228//5228 5200//5200 5227//5227 -f 5227//5227 5200//5200 5202//5202 -f 5227//5227 5202//5202 5226//5226 -f 5226//5226 5202//5202 5229//5229 -f 5144//5144 5143//5143 5202//5202 -f 5202//5202 5143//5143 5230//5230 -f 5202//5202 5230//5230 5229//5229 -f 5058//5058 5059//5059 5199//5199 -f 5199//5199 5059//5059 5167//5167 -f 5199//5199 5167//5167 5201//5201 -f 5201//5201 5167//5167 5231//5231 -f 5201//5201 5231//5231 5144//5144 -f 5144//5144 5231//5231 5141//5141 -f 5144//5144 5141//5141 5142//5142 -f 5142//5142 5141//5141 5140//5140 -f 5232//5232 5139//5139 5233//5233 -f 5233//5233 5139//5139 5141//5141 -f 5233//5233 5141//5141 5234//5234 -f 5234//5234 5141//5141 5231//5231 -f 5234//5234 5231//5231 5166//5166 -f 5166//5166 5231//5231 5167//5167 -f 5166//5166 5167//5167 5061//5061 -f 5061//5061 5167//5167 5060//5060 -f 5062//5062 5063//5063 5166//5166 -f 5166//5166 5063//5063 5155//5155 -f 5166//5166 5155//5155 5234//5234 -f 5234//5234 5155//5155 5151//5151 -f 5234//5234 5151//5151 5233//5233 -f 5233//5233 5151//5151 5138//5138 -f 5233//5233 5138//5138 5232//5232 -f 5232//5232 5138//5138 5137//5137 -f 5136//5136 5138//5138 5235//5235 -f 5235//5235 5138//5138 5203//5203 -f 5235//5235 5203//5203 5236//5236 -f 5236//5236 5203//5203 5204//5204 -f 5236//5236 5204//5204 5237//5237 -f 5237//5237 5204//5204 5205//5205 -f 5237//5237 5205//5205 5238//5238 -f 5238//5238 5205//5205 5206//5206 -f 5238//5238 5206//5206 5239//5239 -f 5135//5135 5134//5134 5206//5206 -f 5206//5206 5134//5134 5240//5240 -f 5206//5206 5240//5240 5239//5239 -f 5241//5241 5133//5133 5242//5242 -f 5242//5242 5133//5133 5135//5135 -f 5242//5242 5135//5135 5243//5243 -f 5243//5243 5135//5135 5190//5190 -f 5243//5243 5190//5190 5244//5244 -f 5244//5244 5190//5190 5176//5176 -f 5244//5244 5176//5176 5047//5047 -f 5047//5047 5176//5176 5048//5048 -f 5047//5047 5046//5046 5244//5244 -f 5244//5244 5046//5046 5165//5165 -f 5244//5244 5165//5165 5243//5243 -f 5243//5243 5165//5165 5207//5207 -f 5243//5243 5207//5207 5242//5242 -f 5242//5242 5207//5207 5209//5209 -f 5242//5242 5209//5209 5241//5241 -f 5241//5241 5209//5209 5245//5245 -f 5132//5132 5131//5131 5209//5209 -f 5209//5209 5131//5131 5246//5246 -f 5209//5209 5246//5246 5245//5245 -f 5043//5043 5042//5042 5164//5164 -f 5164//5164 5042//5042 5163//5163 -f 5164//5164 5163//5163 5208//5208 -f 5208//5208 5163//5163 5247//5247 -f 5208//5208 5247//5247 5132//5132 -f 5132//5132 5247//5247 5129//5129 -f 5132//5132 5129//5129 5130//5130 -f 5130//5130 5129//5129 5128//5128 -f 5248//5248 5127//5127 5249//5249 -f 5249//5249 5127//5127 5129//5129 -f 5249//5249 5129//5129 5250//5250 -f 5250//5250 5129//5129 5247//5247 -f 5250//5250 5247//5247 5162//5162 -f 5162//5162 5247//5247 5163//5163 -f 5162//5162 5163//5163 5107//5107 -f 5107//5107 5163//5163 5106//5106 -f 5108//5108 5109//5109 5162//5162 -f 5162//5162 5109//5109 5161//5161 -f 5162//5162 5161//5161 5250//5250 -f 5250//5250 5161//5161 5211//5211 -f 5250//5250 5211//5211 5249//5249 -f 5249//5249 5211//5211 5213//5213 -f 5249//5249 5213//5213 5248//5248 -f 5248//5248 5213//5213 5251//5251 -f 5126//5126 5125//5125 5213//5213 -f 5213//5213 5125//5125 5252//5252 -f 5213//5213 5252//5252 5251//5251 -f 5122//5122 5124//5124 5123//5123 -f 5123//5123 5124//5124 5126//5126 -f 5123//5123 5126//5126 5253//5253 -f 5253//5253 5126//5126 5212//5212 -f 5253//5253 5212//5212 5177//5177 -f 5177//5177 5212//5212 5210//5210 -f 5177//5177 5210//5210 5102//5102 -f 5102//5102 5210//5210 5111//5111 -f 5254//5254 5121//5121 5255//5255 -f 5255//5255 5121//5121 5123//5123 -f 5255//5255 5123//5123 5256//5256 -f 5256//5256 5123//5123 5253//5253 -f 5256//5256 5253//5253 5160//5160 -f 5160//5160 5253//5253 5177//5177 -f 5160//5160 5177//5177 5104//5104 -f 5104//5104 5177//5177 5103//5103 -f 5092//5092 5093//5093 5160//5160 -f 5160//5160 5093//5093 5153//5153 -f 5160//5160 5153//5153 5256//5256 -f 5256//5256 5153//5153 5149//5149 -f 5256//5256 5149//5149 5255//5255 -f 5255//5255 5149//5149 5148//5148 -f 5255//5255 5148//5148 5254//5254 -f 5254//5254 5148//5148 5257//5257 -f 5258//5258 5259//5259 5217//5217 -f 5217//5217 5259//5259 5260//5260 -f 5217//5217 5260//5260 5216//5216 -f 5216//5216 5260//5260 5261//5261 -f 5216//5216 5261//5261 5215//5215 -f 5215//5215 5261//5261 5262//5262 -f 5215//5215 5262//5262 5214//5214 -f 5214//5214 5262//5262 5263//5263 -f 5214//5214 5263//5263 5148//5148 -f 5148//5148 5263//5263 5264//5264 -f 5148//5148 5264//5264 5257//5257 -f 5101//5101 5087//5087 5180//5180 -f 5180//5180 5087//5087 5159//5159 -f 5180//5180 5159//5159 5193//5193 -f 5193//5193 5159//5159 5265//5265 -f 5193//5193 5265//5265 5217//5217 -f 5217//5217 5265//5265 5120//5120 -f 5217//5217 5120//5120 5258//5258 -f 5258//5258 5120//5120 5119//5119 -f 5266//5266 5118//5118 5267//5267 -f 5267//5267 5118//5118 5120//5120 -f 5267//5267 5120//5120 5268//5268 -f 5268//5268 5120//5120 5265//5265 -f 5268//5268 5265//5265 5269//5269 -f 5269//5269 5265//5265 5159//5159 -f 5269//5269 5159//5159 5089//5089 -f 5089//5089 5159//5159 5088//5088 -f 5089//5089 5090//5090 5269//5269 -f 5269//5269 5090//5090 5181//5181 -f 5269//5269 5181//5181 5268//5268 -f 5268//5268 5181//5181 5218//5218 -f 5268//5268 5218//5218 5267//5267 -f 5267//5267 5218//5218 5220//5220 -f 5267//5267 5220//5220 5266//5266 -f 5266//5266 5220//5220 5270//5270 -f 5117//5117 5116//5116 5220//5220 -f 5220//5220 5116//5116 5271//5271 -f 5220//5220 5271//5271 5270//5270 -f 5113//5113 5115//5115 5114//5114 -f 5114//5114 5115//5115 5117//5117 -f 5114//5114 5117//5117 5272//5272 -f 5272//5272 5117//5117 5219//5219 -f 5272//5272 5219//5219 5157//5157 -f 5157//5157 5219//5219 5158//5158 -f 5157//5157 5158//5158 5080//5080 -f 5080//5080 5158//5158 5079//5079 -f 5273//5273 5112//5112 5274//5274 -f 5274//5274 5112//5112 5114//5114 -f 5274//5274 5114//5114 5275//5275 -f 5275//5275 5114//5114 5272//5272 -f 5275//5275 5272//5272 5276//5276 -f 5276//5276 5272//5272 5157//5157 -f 5276//5276 5157//5157 5082//5082 -f 5082//5082 5157//5157 5081//5081 -f 5082//5082 5083//5083 5276//5276 -f 5276//5276 5083//5083 5182//5182 -f 5276//5276 5182//5182 5275//5275 -f 5275//5275 5182//5182 5196//5196 -f 5275//5275 5196//5196 5274//5274 -f 5274//5274 5196//5196 5223//5223 -f 5274//5274 5223//5223 5273//5273 -f 5273//5273 5223//5223 5277//5277 -f 5225//5225 5278//5278 5197//5197 -f 5197//5197 5278//5278 5279//5279 -f 5197//5197 5279//5279 5198//5198 -f 5198//5198 5279//5279 5280//5280 -f 5198//5198 5280//5280 5221//5221 -f 5221//5221 5280//5280 5281//5281 -f 5221//5221 5281//5281 5222//5222 -f 5222//5222 5281//5281 5282//5282 -f 5222//5222 5282//5282 5223//5223 -f 5223//5223 5282//5282 5283//5283 -f 5223//5223 5283//5283 5277//5277 -f 5284//5284 5232//5232 5285//5285 -f 5285//5285 5232//5232 5137//5137 -f 5285//5285 5137//5137 5286//5286 -f 5286//5286 5137//5137 5136//5136 -f 5286//5286 5136//5136 5287//5287 -f 5287//5287 5136//5136 5235//5235 -f 5287//5287 5235//5235 5288//5288 -f 5288//5288 5235//5235 5236//5236 -f 5288//5288 5236//5236 5289//5289 -f 5289//5289 5236//5236 5237//5237 -f 5289//5289 5237//5237 5290//5290 -f 5290//5290 5237//5237 5238//5238 -f 5291//5291 5292//5292 5248//5248 -f 5248//5248 5292//5292 5293//5293 -f 5248//5248 5293//5293 5127//5127 -f 5127//5127 5293//5293 5294//5294 -f 5127//5127 5294//5294 5128//5128 -f 5128//5128 5294//5294 5295//5295 -f 5128//5128 5295//5295 5130//5130 -f 5130//5130 5295//5295 5296//5296 -f 5130//5130 5296//5296 5131//5131 -f 5131//5131 5296//5296 5297//5297 -f 5131//5131 5297//5297 5246//5246 -f 5246//5246 5297//5297 5298//5298 -f 5246//5246 5298//5298 5245//5245 -f 5245//5245 5298//5298 5299//5299 -f 5245//5245 5299//5299 5241//5241 -f 5241//5241 5299//5299 5300//5300 -f 5241//5241 5300//5300 5133//5133 -f 5133//5133 5300//5300 5301//5301 -f 5133//5133 5301//5301 5134//5134 -f 5134//5134 5301//5301 5302//5302 -f 5134//5134 5302//5302 5240//5240 -f 5240//5240 5302//5302 5303//5303 -f 5240//5240 5303//5303 5239//5239 -f 5239//5239 5303//5303 5304//5304 -f 5239//5239 5304//5304 5238//5238 -f 5238//5238 5304//5304 5305//5305 -f 5238//5238 5305//5305 5290//5290 -f 5248//5248 5251//5251 5291//5291 -f 5291//5291 5251//5251 5252//5252 -f 5291//5291 5252//5252 5306//5306 -f 5306//5306 5252//5252 5307//5307 -f 5307//5307 5252//5252 5125//5125 -f 5307//5307 5125//5125 5308//5308 -f 5308//5308 5125//5125 5124//5124 -f 5308//5308 5124//5124 5309//5309 -f 5309//5309 5124//5124 5122//5122 -f 5309//5309 5122//5122 5310//5310 -f 5122//5122 5121//5121 5310//5310 -f 5310//5310 5121//5121 5254//5254 -f 5310//5310 5254//5254 5311//5311 -f 5311//5311 5254//5254 5312//5312 -f 5254//5254 5257//5257 5312//5312 -f 5312//5312 5257//5257 5264//5264 -f 5312//5312 5264//5264 5313//5313 -f 5313//5313 5264//5264 5314//5314 -f 5314//5314 5264//5264 5263//5263 -f 5314//5314 5263//5263 5315//5315 -f 5315//5315 5263//5263 5262//5262 -f 5315//5315 5262//5262 5316//5316 -f 5316//5316 5262//5262 5261//5261 -f 5316//5316 5261//5261 5317//5317 -f 5317//5317 5261//5261 5260//5260 -f 5317//5317 5260//5260 5318//5318 -f 5318//5318 5260//5260 5319//5319 -f 5319//5319 5260//5260 5259//5259 -f 5319//5319 5259//5259 5320//5320 -f 5320//5320 5259//5259 5258//5258 -f 5320//5320 5258//5258 5321//5321 -f 5321//5321 5258//5258 5119//5119 -f 5321//5321 5119//5119 5322//5322 -f 5322//5322 5119//5119 5118//5118 -f 5322//5322 5118//5118 5323//5323 -f 5323//5323 5118//5118 5266//5266 -f 5323//5323 5266//5266 5324//5324 -f 5266//5266 5270//5270 5324//5324 -f 5324//5324 5270//5270 5271//5271 -f 5324//5324 5271//5271 5325//5325 -f 5325//5325 5271//5271 5116//5116 -f 5325//5325 5116//5116 5326//5326 -f 5326//5326 5116//5116 5115//5115 -f 5326//5326 5115//5115 5327//5327 -f 5327//5327 5115//5115 5113//5113 -f 5327//5327 5113//5113 5328//5328 -f 5328//5328 5113//5113 5112//5112 -f 5328//5328 5112//5112 5329//5329 -f 5329//5329 5112//5112 5273//5273 -f 5329//5329 5273//5273 5330//5330 -f 5330//5330 5273//5273 5277//5277 -f 5330//5330 5277//5277 5331//5331 -f 5331//5331 5277//5277 5283//5283 -f 5331//5331 5283//5283 5332//5332 -f 5332//5332 5283//5283 5282//5282 -f 5332//5332 5282//5282 5333//5333 -f 5333//5333 5282//5282 5281//5281 -f 5333//5333 5281//5281 5334//5334 -f 5334//5334 5281//5281 5280//5280 -f 5334//5334 5280//5280 5335//5335 -f 5335//5335 5280//5280 5279//5279 -f 5335//5335 5279//5279 5336//5336 -f 5336//5336 5279//5279 5278//5278 -f 5336//5336 5278//5278 5337//5337 -f 5337//5337 5278//5278 5225//5225 -f 5337//5337 5225//5225 5338//5338 -f 5338//5338 5225//5225 5146//5146 -f 5338//5338 5146//5146 5339//5339 -f 5339//5339 5146//5146 5145//5145 -f 5339//5339 5145//5145 5340//5340 -f 5340//5340 5145//5145 5226//5226 -f 5340//5340 5226//5226 5341//5341 -f 5341//5341 5226//5226 5229//5229 -f 5341//5341 5229//5229 5342//5342 -f 5342//5342 5229//5229 5230//5230 -f 5342//5342 5230//5230 5343//5343 -f 5343//5343 5230//5230 5143//5143 -f 5343//5343 5143//5143 5344//5344 -f 5344//5344 5143//5143 5142//5142 -f 5344//5344 5142//5142 5345//5345 -f 5345//5345 5142//5142 5140//5140 -f 5345//5345 5140//5140 5284//5284 -f 5284//5284 5140//5140 5139//5139 -f 5284//5284 5139//5139 5232//5232 -f 5346//5346 5337//5337 5347//5347 -f 5347//5347 5337//5337 5338//5338 -f 5347//5347 5338//5338 5348//5348 -f 5338//5338 5339//5339 5348//5348 -f 5348//5348 5339//5339 5340//5340 -f 5348//5348 5340//5340 5349//5349 -f 5340//5340 5341//5341 5349//5349 -f 5349//5349 5341//5341 5342//5342 -f 5349//5349 5342//5342 5350//5350 -f 5350//5350 5342//5342 5343//5343 -f 5350//5350 5343//5343 5351//5351 -f 5343//5343 5344//5344 5351//5351 -f 5351//5351 5344//5344 5345//5345 -f 5351//5351 5345//5345 5352//5352 -f 5352//5352 5345//5345 5284//5284 -f 5352//5352 5284//5284 5353//5353 -f 5284//5284 5285//5285 5353//5353 -f 5353//5353 5285//5285 5286//5286 -f 5353//5353 5286//5286 5354//5354 -f 5354//5354 5286//5286 5287//5287 -f 5354//5354 5287//5287 5355//5355 -f 5287//5287 5288//5288 5355//5355 -f 5355//5355 5288//5288 5289//5289 -f 5355//5355 5289//5289 5356//5356 -f 5289//5289 5290//5290 5356//5356 -f 5356//5356 5290//5290 5305//5305 -f 5356//5356 5305//5305 5357//5357 -f 5357//5357 5305//5305 5304//5304 -f 5357//5357 5304//5304 5358//5358 -f 5304//5304 5303//5303 5358//5358 -f 5358//5358 5303//5303 5302//5302 -f 5358//5358 5302//5302 5359//5359 -f 5302//5302 5301//5301 5359//5359 -f 5359//5359 5301//5301 5300//5300 -f 5359//5359 5300//5300 5360//5360 -f 5300//5300 5299//5299 5360//5360 -f 5360//5360 5299//5299 5298//5298 -f 5360//5360 5298//5298 5361//5361 -f 5361//5361 5298//5298 5297//5297 -f 5361//5361 5297//5297 5362//5362 -f 5297//5297 5296//5296 5362//5362 -f 5362//5362 5296//5296 5295//5295 -f 5362//5362 5295//5295 5363//5363 -f 5295//5295 5294//5294 5363//5363 -f 5363//5363 5294//5294 5293//5293 -f 5363//5363 5293//5293 5364//5364 -f 5364//5364 5293//5293 5292//5292 -f 5364//5364 5292//5292 5365//5365 -f 5292//5292 5291//5291 5365//5365 -f 5365//5365 5291//5291 5306//5306 -f 5365//5365 5306//5306 5366//5366 -f 5306//5306 5307//5307 5366//5366 -f 5366//5366 5307//5307 5308//5308 -f 5366//5366 5308//5308 5367//5367 -f 5367//5367 5308//5308 5309//5309 -f 5367//5367 5309//5309 5368//5368 -f 5309//5309 5310//5310 5368//5368 -f 5368//5368 5310//5310 5311//5311 -f 5368//5368 5311//5311 5369//5369 -f 5311//5311 5312//5312 5369//5369 -f 5369//5369 5312//5312 5313//5313 -f 5369//5369 5313//5313 5370//5370 -f 5313//5313 5314//5314 5370//5370 -f 5370//5370 5314//5314 5315//5315 -f 5370//5370 5315//5315 5371//5371 -f 5371//5371 5315//5315 5316//5316 -f 5371//5371 5316//5316 5372//5372 -f 5316//5316 5317//5317 5372//5372 -f 5372//5372 5317//5317 5318//5318 -f 5372//5372 5318//5318 5373//5373 -f 5318//5318 5319//5319 5373//5373 -f 5373//5373 5319//5319 5320//5320 -f 5373//5373 5320//5320 5374//5374 -f 5374//5374 5320//5320 5321//5321 -f 5374//5374 5321//5321 5375//5375 -f 5321//5321 5322//5322 5375//5375 -f 5375//5375 5322//5322 5323//5323 -f 5375//5375 5323//5323 5376//5376 -f 5376//5376 5323//5323 5324//5324 -f 5376//5376 5324//5324 5377//5377 -f 5324//5324 5325//5325 5377//5377 -f 5377//5377 5325//5325 5326//5326 -f 5377//5377 5326//5326 5378//5378 -f 5378//5378 5326//5326 5327//5327 -f 5378//5378 5327//5327 5379//5379 -f 5327//5327 5328//5328 5379//5379 -f 5379//5379 5328//5328 5329//5329 -f 5379//5379 5329//5329 5380//5380 -f 5329//5329 5330//5330 5380//5380 -f 5380//5380 5330//5330 5331//5331 -f 5380//5380 5331//5331 5381//5381 -f 5381//5381 5331//5331 5332//5332 -f 5381//5381 5332//5332 5382//5382 -f 5332//5332 5333//5333 5382//5382 -f 5382//5382 5333//5333 5334//5334 -f 5382//5382 5334//5334 5383//5383 -f 5383//5383 5334//5334 5335//5335 -f 5383//5383 5335//5335 5346//5346 -f 5346//5346 5335//5335 5336//5336 -f 5346//5346 5336//5336 5337//5337 -f 5382//5382 5384//5384 5381//5381 -f 5381//5381 5384//5384 5385//5385 -f 5381//5381 5385//5385 5380//5380 -f 5380//5380 5385//5385 5386//5386 -f 5380//5380 5386//5386 5379//5379 -f 5379//5379 5386//5386 5387//5387 -f 5379//5379 5387//5387 5378//5378 -f 5378//5378 5387//5387 5388//5388 -f 5378//5378 5388//5388 5377//5377 -f 5377//5377 5388//5388 5389//5389 -f 5377//5377 5389//5389 5376//5376 -f 5376//5376 5389//5389 5390//5390 -f 5376//5376 5390//5390 5375//5375 -f 5375//5375 5390//5390 5391//5391 -f 5375//5375 5391//5391 5374//5374 -f 5374//5374 5391//5391 5392//5392 -f 5374//5374 5392//5392 5373//5373 -f 5373//5373 5392//5392 5393//5393 -f 5373//5373 5393//5393 5372//5372 -f 5372//5372 5393//5393 5394//5394 -f 5372//5372 5394//5394 5371//5371 -f 5371//5371 5394//5394 5395//5395 -f 5371//5371 5395//5395 5370//5370 -f 5370//5370 5395//5395 5396//5396 -f 5370//5370 5396//5396 5369//5369 -f 5369//5369 5396//5396 5397//5397 -f 5369//5369 5397//5397 5368//5368 -f 5368//5368 5397//5397 5398//5398 -f 5368//5368 5398//5398 5367//5367 -f 5367//5367 5398//5398 5399//5399 -f 5367//5367 5399//5399 5366//5366 -f 5366//5366 5399//5399 5400//5400 -f 5366//5366 5400//5400 5365//5365 -f 5365//5365 5400//5400 5401//5401 -f 5365//5365 5401//5401 5364//5364 -f 5364//5364 5401//5401 5402//5402 -f 5364//5364 5402//5402 5363//5363 -f 5363//5363 5402//5402 5403//5403 -f 5363//5363 5403//5403 5362//5362 -f 5362//5362 5403//5403 5404//5404 -f 5362//5362 5404//5404 5361//5361 -f 5361//5361 5404//5404 5405//5405 -f 5361//5361 5405//5405 5360//5360 -f 5360//5360 5405//5405 5406//5406 -f 5360//5360 5406//5406 5359//5359 -f 5359//5359 5406//5406 5407//5407 -f 5359//5359 5407//5407 5358//5358 -f 5358//5358 5407//5407 5408//5408 -f 5358//5358 5408//5408 5357//5357 -f 5357//5357 5408//5408 5409//5409 -f 5357//5357 5409//5409 5356//5356 -f 5356//5356 5409//5409 5410//5410 -f 5356//5356 5410//5410 5355//5355 -f 5355//5355 5410//5410 5411//5411 -f 5355//5355 5411//5411 5354//5354 -f 5354//5354 5411//5411 5412//5412 -f 5354//5354 5412//5412 5353//5353 -f 5353//5353 5412//5412 5413//5413 -f 5353//5353 5413//5413 5352//5352 -f 5352//5352 5413//5413 5414//5414 -f 5352//5352 5414//5414 5351//5351 -f 5351//5351 5414//5414 5415//5415 -f 5351//5351 5415//5415 5350//5350 -f 5350//5350 5415//5415 5416//5416 -f 5350//5350 5416//5416 5349//5349 -f 5349//5349 5416//5416 5417//5417 -f 5349//5349 5417//5417 5348//5348 -f 5348//5348 5417//5417 5418//5418 -f 5348//5348 5418//5418 5347//5347 -f 5347//5347 5418//5418 5419//5419 -f 5347//5347 5419//5419 5346//5346 -f 5346//5346 5419//5419 5420//5420 -f 5346//5346 5420//5420 5383//5383 -f 5383//5383 5420//5420 5421//5421 -f 5383//5383 5421//5421 5382//5382 -f 5382//5382 5421//5421 5384//5384 -f 5384//5384 5422//5422 5385//5385 -f 5385//5385 5422//5422 5423//5423 -f 5385//5385 5423//5423 5386//5386 -f 5386//5386 5423//5423 5424//5424 -f 5386//5386 5424//5424 5387//5387 -f 5387//5387 5424//5424 5425//5425 -f 5387//5387 5425//5425 5388//5388 -f 5388//5388 5425//5425 5426//5426 -f 5388//5388 5426//5426 5389//5389 -f 5389//5389 5426//5426 5427//5427 -f 5389//5389 5427//5427 5390//5390 -f 5390//5390 5427//5427 5428//5428 -f 5390//5390 5428//5428 5391//5391 -f 5391//5391 5428//5428 5429//5429 -f 5391//5391 5429//5429 5392//5392 -f 5392//5392 5429//5429 5430//5430 -f 5392//5392 5430//5430 5393//5393 -f 5393//5393 5430//5430 5431//5431 -f 5393//5393 5431//5431 5394//5394 -f 5394//5394 5431//5431 5432//5432 -f 5394//5394 5432//5432 5395//5395 -f 5395//5395 5432//5432 5433//5433 -f 5395//5395 5433//5433 5396//5396 -f 5396//5396 5433//5433 5434//5434 -f 5396//5396 5434//5434 5397//5397 -f 5397//5397 5434//5434 5435//5435 -f 5397//5397 5435//5435 5398//5398 -f 5398//5398 5435//5435 5436//5436 -f 5398//5398 5436//5436 5399//5399 -f 5399//5399 5436//5436 5437//5437 -f 5399//5399 5437//5437 5400//5400 -f 5400//5400 5437//5437 5438//5438 -f 5400//5400 5438//5438 5401//5401 -f 5401//5401 5438//5438 5439//5439 -f 5401//5401 5439//5439 5402//5402 -f 5402//5402 5439//5439 5440//5440 -f 5402//5402 5440//5440 5403//5403 -f 5403//5403 5440//5440 5441//5441 -f 5403//5403 5441//5441 5404//5404 -f 5404//5404 5441//5441 5442//5442 -f 5404//5404 5442//5442 5405//5405 -f 5405//5405 5442//5442 5443//5443 -f 5405//5405 5443//5443 5406//5406 -f 5406//5406 5443//5443 5444//5444 -f 5406//5406 5444//5444 5407//5407 -f 5407//5407 5444//5444 5445//5445 -f 5407//5407 5445//5445 5408//5408 -f 5408//5408 5445//5445 5446//5446 -f 5408//5408 5446//5446 5409//5409 -f 5409//5409 5446//5446 5447//5447 -f 5409//5409 5447//5447 5410//5410 -f 5410//5410 5447//5447 5448//5448 -f 5410//5410 5448//5448 5411//5411 -f 5411//5411 5448//5448 5449//5449 -f 5411//5411 5449//5449 5412//5412 -f 5412//5412 5449//5449 5450//5450 -f 5412//5412 5450//5450 5413//5413 -f 5413//5413 5450//5450 5451//5451 -f 5413//5413 5451//5451 5414//5414 -f 5414//5414 5451//5451 5452//5452 -f 5414//5414 5452//5452 5415//5415 -f 5415//5415 5452//5452 5453//5453 -f 5415//5415 5453//5453 5416//5416 -f 5416//5416 5453//5453 5454//5454 -f 5416//5416 5454//5454 5417//5417 -f 5417//5417 5454//5454 5455//5455 -f 5417//5417 5455//5455 5418//5418 -f 5418//5418 5455//5455 5456//5456 -f 5418//5418 5456//5456 5419//5419 -f 5419//5419 5456//5456 5457//5457 -f 5419//5419 5457//5457 5420//5420 -f 5420//5420 5457//5457 5458//5458 -f 5420//5420 5458//5458 5421//5421 -f 5421//5421 5458//5458 5459//5459 -f 5421//5421 5459//5459 5384//5384 -f 5384//5384 5459//5459 5422//5422 -f 5422//5422 5460//5460 5423//5423 -f 5423//5423 5460//5460 5461//5461 -f 5423//5423 5461//5461 5424//5424 -f 5424//5424 5461//5461 5462//5462 -f 5424//5424 5462//5462 5425//5425 -f 5425//5425 5462//5462 5463//5463 -f 5425//5425 5463//5463 5426//5426 -f 5426//5426 5463//5463 5464//5464 -f 5426//5426 5464//5464 5427//5427 -f 5427//5427 5464//5464 5465//5465 -f 5427//5427 5465//5465 5428//5428 -f 5428//5428 5465//5465 5466//5466 -f 5428//5428 5466//5466 5429//5429 -f 5429//5429 5466//5466 5467//5467 -f 5429//5429 5467//5467 5430//5430 -f 5430//5430 5467//5467 5468//5468 -f 5430//5430 5468//5468 5431//5431 -f 5431//5431 5468//5468 5469//5469 -f 5431//5431 5469//5469 5432//5432 -f 5432//5432 5469//5469 5470//5470 -f 5432//5432 5470//5470 5433//5433 -f 5433//5433 5470//5470 5471//5471 -f 5433//5433 5471//5471 5434//5434 -f 5434//5434 5471//5471 5472//5472 -f 5434//5434 5472//5472 5435//5435 -f 5435//5435 5472//5472 5473//5473 -f 5435//5435 5473//5473 5436//5436 -f 5436//5436 5473//5473 5474//5474 -f 5436//5436 5474//5474 5437//5437 -f 5437//5437 5474//5474 5475//5475 -f 5437//5437 5475//5475 5438//5438 -f 5438//5438 5475//5475 5476//5476 -f 5438//5438 5476//5476 5439//5439 -f 5439//5439 5476//5476 5477//5477 -f 5439//5439 5477//5477 5440//5440 -f 5440//5440 5477//5477 5478//5478 -f 5440//5440 5478//5478 5441//5441 -f 5441//5441 5478//5478 5479//5479 -f 5441//5441 5479//5479 5442//5442 -f 5442//5442 5479//5479 5480//5480 -f 5442//5442 5480//5480 5443//5443 -f 5443//5443 5480//5480 5481//5481 -f 5443//5443 5481//5481 5444//5444 -f 5444//5444 5481//5481 5482//5482 -f 5444//5444 5482//5482 5445//5445 -f 5445//5445 5482//5482 5483//5483 -f 5445//5445 5483//5483 5446//5446 -f 5446//5446 5483//5483 5484//5484 -f 5446//5446 5484//5484 5447//5447 -f 5447//5447 5484//5484 5485//5485 -f 5447//5447 5485//5485 5448//5448 -f 5448//5448 5485//5485 5486//5486 -f 5448//5448 5486//5486 5449//5449 -f 5449//5449 5486//5486 5487//5487 -f 5449//5449 5487//5487 5450//5450 -f 5450//5450 5487//5487 5488//5488 -f 5450//5450 5488//5488 5451//5451 -f 5451//5451 5488//5488 5489//5489 -f 5451//5451 5489//5489 5452//5452 -f 5452//5452 5489//5489 5490//5490 -f 5452//5452 5490//5490 5453//5453 -f 5453//5453 5490//5490 5491//5491 -f 5453//5453 5491//5491 5454//5454 -f 5454//5454 5491//5491 5492//5492 -f 5454//5454 5492//5492 5455//5455 -f 5455//5455 5492//5492 5493//5493 -f 5455//5455 5493//5493 5456//5456 -f 5456//5456 5493//5493 5494//5494 -f 5456//5456 5494//5494 5457//5457 -f 5457//5457 5494//5494 5495//5495 -f 5457//5457 5495//5495 5458//5458 -f 5458//5458 5495//5495 5496//5496 -f 5458//5458 5496//5496 5459//5459 -f 5459//5459 5496//5496 5497//5497 -f 5459//5459 5497//5497 5422//5422 -f 5422//5422 5497//5497 5460//5460 -f 5460//5460 5498//5498 5461//5461 -f 5461//5461 5498//5498 5499//5499 -f 5461//5461 5499//5499 5462//5462 -f 5462//5462 5499//5499 5500//5500 -f 5462//5462 5500//5500 5463//5463 -f 5463//5463 5500//5500 5501//5501 -f 5463//5463 5501//5501 5464//5464 -f 5464//5464 5501//5501 5502//5502 -f 5464//5464 5502//5502 5465//5465 -f 5465//5465 5502//5502 5503//5503 -f 5465//5465 5503//5503 5466//5466 -f 5466//5466 5503//5503 5504//5504 -f 5466//5466 5504//5504 5467//5467 -f 5467//5467 5504//5504 5505//5505 -f 5467//5467 5505//5505 5468//5468 -f 5468//5468 5505//5505 5506//5506 -f 5468//5468 5506//5506 5469//5469 -f 5469//5469 5506//5506 5507//5507 -f 5469//5469 5507//5507 5470//5470 -f 5470//5470 5507//5507 5508//5508 -f 5470//5470 5508//5508 5471//5471 -f 5471//5471 5508//5508 5509//5509 -f 5471//5471 5509//5509 5472//5472 -f 5472//5472 5509//5509 5510//5510 -f 5472//5472 5510//5510 5473//5473 -f 5473//5473 5510//5510 5511//5511 -f 5473//5473 5511//5511 5474//5474 -f 5474//5474 5511//5511 5512//5512 -f 5474//5474 5512//5512 5475//5475 -f 5475//5475 5512//5512 5513//5513 -f 5475//5475 5513//5513 5476//5476 -f 5476//5476 5513//5513 5514//5514 -f 5476//5476 5514//5514 5477//5477 -f 5477//5477 5514//5514 5515//5515 -f 5477//5477 5515//5515 5478//5478 -f 5478//5478 5515//5515 5516//5516 -f 5478//5478 5516//5516 5479//5479 -f 5479//5479 5516//5516 5517//5517 -f 5479//5479 5517//5517 5480//5480 -f 5480//5480 5517//5517 5518//5518 -f 5480//5480 5518//5518 5481//5481 -f 5481//5481 5518//5518 5519//5519 -f 5481//5481 5519//5519 5482//5482 -f 5482//5482 5519//5519 5520//5520 -f 5482//5482 5520//5520 5483//5483 -f 5483//5483 5520//5520 5521//5521 -f 5483//5483 5521//5521 5484//5484 -f 5484//5484 5521//5521 5522//5522 -f 5484//5484 5522//5522 5485//5485 -f 5485//5485 5522//5522 5523//5523 -f 5485//5485 5523//5523 5486//5486 -f 5486//5486 5523//5523 5524//5524 -f 5486//5486 5524//5524 5487//5487 -f 5487//5487 5524//5524 5525//5525 -f 5487//5487 5525//5525 5488//5488 -f 5488//5488 5525//5525 5526//5526 -f 5488//5488 5526//5526 5489//5489 -f 5489//5489 5526//5526 5527//5527 -f 5489//5489 5527//5527 5490//5490 -f 5490//5490 5527//5527 5528//5528 -f 5490//5490 5528//5528 5491//5491 -f 5491//5491 5528//5528 5529//5529 -f 5491//5491 5529//5529 5492//5492 -f 5492//5492 5529//5529 5530//5530 -f 5492//5492 5530//5530 5493//5493 -f 5493//5493 5530//5530 5531//5531 -f 5493//5493 5531//5531 5494//5494 -f 5494//5494 5531//5531 5532//5532 -f 5494//5494 5532//5532 5495//5495 -f 5495//5495 5532//5532 5533//5533 -f 5495//5495 5533//5533 5496//5496 -f 5496//5496 5533//5533 5534//5534 -f 5496//5496 5534//5534 5497//5497 -f 5497//5497 5534//5534 5535//5535 -f 5497//5497 5535//5535 5460//5460 -f 5460//5460 5535//5535 5498//5498 -f 5518//5518 5517//5517 5536//5536 -f 5536//5536 5517//5517 5537//5537 -f 5505//5505 5538//5538 5539//5539 -f 5509//5509 5540//5540 5510//5510 -f 5510//5510 5540//5540 5541//5541 -f 5510//5510 5541//5541 5511//5511 -f 5542//5542 5520//5520 5536//5536 -f 5536//5536 5520//5520 5519//5519 -f 5536//5536 5519//5519 5518//5518 -f 5543//5543 5522//5522 5542//5542 -f 5542//5542 5522//5522 5521//5521 -f 5542//5542 5521//5521 5520//5520 -f 5526//5526 5525//5525 5544//5544 -f 5544//5544 5525//5525 5524//5524 -f 5544//5544 5524//5524 5543//5543 -f 5543//5543 5524//5524 5523//5523 -f 5543//5543 5523//5523 5522//5522 -f 5526//5526 5544//5544 5527//5527 -f 5527//5527 5544//5544 5545//5545 -f 5527//5527 5545//5545 5528//5528 -f 5500//5500 5546//5546 5501//5501 -f 5501//5501 5546//5546 5547//5547 -f 5505//5505 5504//5504 5538//5538 -f 5538//5538 5504//5504 5503//5503 -f 5538//5538 5503//5503 5547//5547 -f 5547//5547 5503//5503 5502//5502 -f 5547//5547 5502//5502 5501//5501 -f 5509//5509 5508//5508 5540//5540 -f 5540//5540 5508//5508 5507//5507 -f 5540//5540 5507//5507 5539//5539 -f 5539//5539 5507//5507 5506//5506 -f 5539//5539 5506//5506 5505//5505 -f 5511//5511 5541//5541 5512//5512 -f 5512//5512 5541//5541 5548//5548 -f 5512//5512 5548//5548 5513//5513 -f 5517//5517 5516//5516 5537//5537 -f 5537//5537 5516//5516 5515//5515 -f 5537//5537 5515//5515 5548//5548 -f 5548//5548 5515//5515 5514//5514 -f 5548//5548 5514//5514 5513//5513 -f 5528//5528 5545//5545 5529//5529 -f 5529//5529 5545//5545 5549//5549 -f 5529//5529 5549//5549 5530//5530 -f 5500//5500 5499//5499 5546//5546 -f 5546//5546 5499//5499 5498//5498 -f 5546//5546 5498//5498 5550//5550 -f 5498//5498 5535//5535 5550//5550 -f 5550//5550 5535//5535 5534//5534 -f 5550//5550 5534//5534 5551//5551 -f 5534//5534 5533//5533 5551//5551 -f 5551//5551 5533//5533 5532//5532 -f 5551//5551 5532//5532 5549//5549 -f 5549//5549 5532//5532 5531//5531 -f 5549//5549 5531//5531 5530//5530 -f 5542//5542 5536//5536 5552//5552 -f 5552//5552 5553//5553 5542//5542 -f 5542//5542 5553//5553 5554//5554 -f 5542//5542 5554//5554 5543//5543 -f 5554//5554 5555//5555 5543//5543 -f 5543//5543 5555//5555 5556//5556 -f 5543//5543 5556//5556 5544//5544 -f 5556//5556 5557//5557 5544//5544 -f 5544//5544 5557//5557 5558//5558 -f 5544//5544 5558//5558 5545//5545 -f 5558//5558 5559//5559 5545//5545 -f 5545//5545 5559//5559 5560//5560 -f 5545//5545 5560//5560 5549//5549 -f 5560//5560 5561//5561 5549//5549 -f 5549//5549 5561//5561 5562//5562 -f 5549//5549 5562//5562 5551//5551 -f 5562//5562 5563//5563 5551//5551 -f 5551//5551 5563//5563 5564//5564 -f 5551//5551 5564//5564 5550//5550 -f 5550//5550 5564//5564 5565//5565 -f 5550//5550 5565//5565 5546//5546 -f 5565//5565 5566//5566 5546//5546 -f 5546//5546 5566//5566 5567//5567 -f 5546//5546 5567//5567 5547//5547 -f 5567//5567 5568//5568 5547//5547 -f 5547//5547 5568//5568 5569//5569 -f 5547//5547 5569//5569 5538//5538 -f 5569//5569 5570//5570 5538//5538 -f 5538//5538 5570//5570 5571//5571 -f 5538//5538 5571//5571 5539//5539 -f 5571//5571 5572//5572 5539//5539 -f 5539//5539 5572//5572 5573//5573 -f 5539//5539 5573//5573 5540//5540 -f 5573//5573 5574//5574 5540//5540 -f 5540//5540 5574//5574 5575//5575 -f 5540//5540 5575//5575 5541//5541 -f 5575//5575 5576//5576 5541//5541 -f 5541//5541 5576//5576 5577//5577 -f 5541//5541 5577//5577 5548//5548 -f 5577//5577 5578//5578 5548//5548 -f 5548//5548 5578//5578 5579//5579 -f 5548//5548 5579//5579 5537//5537 -f 5537//5537 5579//5579 5580//5580 -f 5537//5537 5580//5580 5536//5536 -f 5536//5536 5580//5580 5581//5581 -f 5536//5536 5581//5581 5552//5552 -f 5564//5564 5582//5582 5565//5565 -f 5565//5565 5582//5582 5583//5583 -f 5565//5565 5583//5583 5566//5566 -f 5566//5566 5583//5583 5584//5584 -f 5566//5566 5584//5584 5567//5567 -f 5567//5567 5584//5584 5585//5585 -f 5567//5567 5585//5585 5568//5568 -f 5568//5568 5585//5585 5586//5586 -f 5568//5568 5586//5586 5569//5569 -f 5569//5569 5586//5586 5587//5587 -f 5569//5569 5587//5587 5570//5570 -f 5570//5570 5587//5587 5588//5588 -f 5570//5570 5588//5588 5571//5571 -f 5571//5571 5588//5588 5589//5589 -f 5571//5571 5589//5589 5572//5572 -f 5572//5572 5589//5589 5590//5590 -f 5572//5572 5590//5590 5573//5573 -f 5573//5573 5590//5590 5591//5591 -f 5573//5573 5591//5591 5574//5574 -f 5574//5574 5591//5591 5592//5592 -f 5574//5574 5592//5592 5575//5575 -f 5575//5575 5592//5592 5593//5593 -f 5575//5575 5593//5593 5576//5576 -f 5576//5576 5593//5593 5594//5594 -f 5576//5576 5594//5594 5577//5577 -f 5577//5577 5594//5594 5595//5595 -f 5577//5577 5595//5595 5578//5578 -f 5578//5578 5595//5595 5596//5596 -f 5578//5578 5596//5596 5579//5579 -f 5579//5579 5596//5596 5597//5597 -f 5579//5579 5597//5597 5580//5580 -f 5580//5580 5597//5597 5598//5598 -f 5580//5580 5598//5598 5581//5581 -f 5581//5581 5598//5598 5599//5599 -f 5581//5581 5599//5599 5552//5552 -f 5552//5552 5599//5599 5600//5600 -f 5552//5552 5600//5600 5553//5553 -f 5553//5553 5600//5600 5601//5601 -f 5553//5553 5601//5601 5554//5554 -f 5554//5554 5601//5601 5602//5602 -f 5554//5554 5602//5602 5555//5555 -f 5555//5555 5602//5602 5603//5603 -f 5555//5555 5603//5603 5556//5556 -f 5556//5556 5603//5603 5604//5604 -f 5556//5556 5604//5604 5557//5557 -f 5557//5557 5604//5604 5605//5605 -f 5557//5557 5605//5605 5558//5558 -f 5558//5558 5605//5605 5606//5606 -f 5558//5558 5606//5606 5559//5559 -f 5559//5559 5606//5606 5607//5607 -f 5559//5559 5607//5607 5560//5560 -f 5560//5560 5607//5607 5608//5608 -f 5560//5560 5608//5608 5561//5561 -f 5561//5561 5608//5608 5609//5609 -f 5561//5561 5609//5609 5562//5562 -f 5562//5562 5609//5609 5610//5610 -f 5562//5562 5610//5610 5563//5563 -f 5563//5563 5610//5610 5611//5611 -f 5563//5563 5611//5611 5564//5564 -f 5564//5564 5611//5611 5582//5582 -f 5612//5612 5613//5613 5611//5611 -f 5611//5611 5610//5610 5612//5612 -f 5612//5612 5610//5610 5609//5609 -f 5612//5612 5609//5609 5614//5614 -f 5609//5609 5608//5608 5614//5614 -f 5614//5614 5608//5608 5607//5607 -f 5614//5614 5607//5607 5615//5615 -f 5607//5607 5606//5606 5615//5615 -f 5615//5615 5606//5606 5605//5605 -f 5615//5615 5605//5605 5616//5616 -f 5605//5605 5604//5604 5616//5616 -f 5616//5616 5604//5604 5603//5603 -f 5616//5616 5603//5603 5617//5617 -f 5603//5603 5602//5602 5617//5617 -f 5617//5617 5602//5602 5601//5601 -f 5617//5617 5601//5601 5618//5618 -f 5601//5601 5600//5600 5618//5618 -f 5618//5618 5600//5600 5599//5599 -f 5618//5618 5599//5599 5619//5619 -f 5619//5619 5599//5599 5598//5598 -f 5619//5619 5598//5598 5620//5620 -f 5598//5598 5597//5597 5620//5620 -f 5620//5620 5597//5597 5596//5596 -f 5620//5620 5596//5596 5621//5621 -f 5596//5596 5595//5595 5621//5621 -f 5621//5621 5595//5595 5594//5594 -f 5621//5621 5594//5594 5622//5622 -f 5594//5594 5593//5593 5622//5622 -f 5622//5622 5593//5593 5592//5592 -f 5622//5622 5592//5592 5623//5623 -f 5592//5592 5591//5591 5623//5623 -f 5623//5623 5591//5591 5590//5590 -f 5623//5623 5590//5590 5624//5624 -f 5590//5590 5589//5589 5624//5624 -f 5624//5624 5589//5589 5588//5588 -f 5624//5624 5588//5588 5625//5625 -f 5588//5588 5587//5587 5625//5625 -f 5625//5625 5587//5587 5586//5586 -f 5625//5625 5586//5586 5626//5626 -f 5586//5586 5585//5585 5626//5626 -f 5626//5626 5585//5585 5584//5584 -f 5626//5626 5584//5584 5627//5627 -f 5627//5627 5584//5584 5583//5583 -f 5627//5627 5583//5583 5613//5613 -f 5613//5613 5583//5583 5582//5582 -f 5613//5613 5582//5582 5611//5611 -f 5614//5614 5628//5628 5612//5612 -f 5612//5612 5628//5628 5629//5629 -f 5612//5612 5629//5629 5613//5613 -f 5613//5613 5629//5629 5630//5630 -f 5613//5613 5630//5630 5627//5627 -f 5627//5627 5630//5630 5631//5631 -f 5627//5627 5631//5631 5626//5626 -f 5618//5618 5632//5632 5617//5617 -f 5617//5617 5632//5632 5633//5633 -f 5617//5617 5633//5633 5616//5616 -f 5616//5616 5633//5633 5634//5634 -f 5616//5616 5634//5634 5615//5615 -f 5615//5615 5634//5634 5635//5635 -f 5615//5615 5635//5635 5614//5614 -f 5614//5614 5635//5635 5636//5636 -f 5614//5614 5636//5636 5628//5628 -f 5622//5622 5637//5637 5621//5621 -f 5621//5621 5637//5637 5638//5638 -f 5621//5621 5638//5638 5620//5620 -f 5620//5620 5638//5638 5639//5639 -f 5620//5620 5639//5639 5619//5619 -f 5619//5619 5639//5639 5640//5640 -f 5619//5619 5640//5640 5618//5618 -f 5618//5618 5640//5640 5641//5641 -f 5618//5618 5641//5641 5632//5632 -f 5631//5631 5642//5642 5626//5626 -f 5626//5626 5642//5642 5643//5643 -f 5626//5626 5643//5643 5625//5625 -f 5625//5625 5643//5643 5644//5644 -f 5625//5625 5644//5644 5624//5624 -f 5624//5624 5644//5644 5645//5645 -f 5624//5624 5645//5645 5623//5623 -f 5623//5623 5645//5645 5646//5646 -f 5623//5623 5646//5646 5622//5622 -f 5622//5622 5646//5646 5647//5647 -f 5622//5622 5647//5647 5637//5637 -f 5642//5642 5648//5648 5643//5643 -f 5643//5643 5648//5648 5649//5649 -f 5643//5643 5649//5649 5644//5644 -f 5644//5644 5649//5649 5650//5650 -f 5644//5644 5650//5650 5645//5645 -f 5645//5645 5650//5650 5651//5651 -f 5645//5645 5651//5651 5646//5646 -f 5646//5646 5651//5651 5652//5652 -f 5646//5646 5652//5652 5647//5647 -f 5647//5647 5652//5652 5653//5653 -f 5647//5647 5653//5653 5637//5637 -f 5637//5637 5653//5653 5654//5654 -f 5637//5637 5654//5654 5638//5638 -f 5638//5638 5654//5654 5655//5655 -f 5638//5638 5655//5655 5639//5639 -f 5639//5639 5655//5655 5656//5656 -f 5639//5639 5656//5656 5640//5640 -f 5640//5640 5656//5656 5657//5657 -f 5640//5640 5657//5657 5641//5641 -f 5641//5641 5657//5657 5658//5658 -f 5641//5641 5658//5658 5632//5632 -f 5632//5632 5658//5658 5659//5659 -f 5632//5632 5659//5659 5633//5633 -f 5633//5633 5659//5659 5660//5660 -f 5633//5633 5660//5660 5634//5634 -f 5634//5634 5660//5660 5661//5661 -f 5634//5634 5661//5661 5635//5635 -f 5635//5635 5661//5661 5662//5662 -f 5635//5635 5662//5662 5636//5636 -f 5636//5636 5662//5662 5663//5663 -f 5636//5636 5663//5663 5628//5628 -f 5628//5628 5663//5663 5664//5664 -f 5628//5628 5664//5664 5629//5629 -f 5629//5629 5664//5664 5665//5665 -f 5629//5629 5665//5665 5630//5630 -f 5630//5630 5665//5665 5666//5666 -f 5630//5630 5666//5666 5631//5631 -f 5631//5631 5666//5666 5667//5667 -f 5631//5631 5667//5667 5642//5642 -f 5642//5642 5667//5667 5648//5648 -f 5668//5668 5648//5648 5667//5667 -f 5668//5668 5669//5669 5648//5648 -f 5648//5648 5669//5669 5670//5670 -f 5648//5648 5670//5670 5649//5649 -f 5670//5670 5671//5671 5649//5649 -f 5649//5649 5671//5671 5672//5672 -f 5649//5649 5672//5672 5650//5650 -f 5672//5672 5673//5673 5650//5650 -f 5650//5650 5673//5673 5674//5674 -f 5650//5650 5674//5674 5651//5651 -f 5674//5674 5675//5675 5651//5651 -f 5651//5651 5675//5675 5676//5676 -f 5651//5651 5676//5676 5652//5652 -f 5676//5676 5677//5677 5652//5652 -f 5652//5652 5677//5677 5678//5678 -f 5652//5652 5678//5678 5653//5653 -f 5678//5678 5679//5679 5653//5653 -f 5653//5653 5679//5679 5680//5680 -f 5653//5653 5680//5680 5654//5654 -f 5680//5680 5681//5681 5654//5654 -f 5654//5654 5681//5681 5682//5682 -f 5654//5654 5682//5682 5655//5655 -f 5682//5682 5683//5683 5655//5655 -f 5655//5655 5683//5683 5684//5684 -f 5655//5655 5684//5684 5656//5656 -f 5684//5684 5685//5685 5656//5656 -f 5656//5656 5685//5685 5686//5686 -f 5656//5656 5686//5686 5657//5657 -f 5686//5686 5687//5687 5657//5657 -f 5657//5657 5687//5687 5688//5688 -f 5657//5657 5688//5688 5658//5658 -f 5688//5688 5689//5689 5658//5658 -f 5658//5658 5689//5689 5690//5690 -f 5658//5658 5690//5690 5659//5659 -f 5690//5690 5691//5691 5659//5659 -f 5659//5659 5691//5691 5692//5692 -f 5659//5659 5692//5692 5660//5660 -f 5692//5692 5693//5693 5660//5660 -f 5660//5660 5693//5693 5694//5694 -f 5660//5660 5694//5694 5661//5661 -f 5694//5694 5695//5695 5661//5661 -f 5661//5661 5695//5695 5696//5696 -f 5661//5661 5696//5696 5662//5662 -f 5696//5696 5697//5697 5662//5662 -f 5662//5662 5697//5697 5698//5698 -f 5662//5662 5698//5698 5663//5663 -f 5698//5698 5699//5699 5663//5663 -f 5663//5663 5699//5699 5700//5700 -f 5663//5663 5700//5700 5664//5664 -f 5700//5700 5701//5701 5664//5664 -f 5664//5664 5701//5701 5702//5702 -f 5664//5664 5702//5702 5665//5665 -f 5702//5702 5703//5703 5665//5665 -f 5665//5665 5703//5703 5704//5704 -f 5665//5665 5704//5704 5666//5666 -f 5704//5704 5705//5705 5666//5666 -f 5666//5666 5705//5705 5706//5706 -f 5666//5666 5706//5706 5667//5667 -f 5667//5667 5706//5706 5707//5707 -f 5667//5667 5707//5707 5668//5668 -f 5708//5708 5709//5709 5705//5705 -f 5705//5705 5704//5704 5708//5708 -f 5708//5708 5704//5704 5703//5703 -f 5708//5708 5703//5703 5710//5710 -f 5703//5703 5702//5702 5710//5710 -f 5710//5710 5702//5702 5701//5701 -f 5710//5710 5701//5701 5711//5711 -f 5701//5701 5700//5700 5711//5711 -f 5711//5711 5700//5700 5699//5699 -f 5711//5711 5699//5699 5712//5712 -f 5699//5699 5698//5698 5712//5712 -f 5712//5712 5698//5698 5697//5697 -f 5712//5712 5697//5697 5713//5713 -f 5697//5697 5696//5696 5713//5713 -f 5713//5713 5696//5696 5695//5695 -f 5713//5713 5695//5695 5714//5714 -f 5695//5695 5694//5694 5714//5714 -f 5714//5714 5694//5694 5693//5693 -f 5714//5714 5693//5693 5715//5715 -f 5693//5693 5692//5692 5715//5715 -f 5715//5715 5692//5692 5691//5691 -f 5715//5715 5691//5691 5716//5716 -f 5691//5691 5690//5690 5716//5716 -f 5716//5716 5690//5690 5689//5689 -f 5716//5716 5689//5689 5717//5717 -f 5717//5717 5689//5689 5688//5688 -f 5717//5717 5688//5688 5718//5718 -f 5688//5688 5687//5687 5718//5718 -f 5718//5718 5687//5687 5686//5686 -f 5718//5718 5686//5686 5719//5719 -f 5686//5686 5685//5685 5719//5719 -f 5719//5719 5685//5685 5684//5684 -f 5719//5719 5684//5684 5720//5720 -f 5684//5684 5683//5683 5720//5720 -f 5720//5720 5683//5683 5682//5682 -f 5720//5720 5682//5682 5721//5721 -f 5682//5682 5681//5681 5721//5721 -f 5721//5721 5681//5681 5680//5680 -f 5721//5721 5680//5680 5722//5722 -f 5680//5680 5679//5679 5722//5722 -f 5722//5722 5679//5679 5678//5678 -f 5722//5722 5678//5678 5723//5723 -f 5678//5678 5677//5677 5723//5723 -f 5723//5723 5677//5677 5676//5676 -f 5723//5723 5676//5676 5724//5724 -f 5676//5676 5675//5675 5724//5724 -f 5724//5724 5675//5675 5674//5674 -f 5724//5724 5674//5674 5725//5725 -f 5674//5674 5673//5673 5725//5725 -f 5725//5725 5673//5673 5672//5672 -f 5725//5725 5672//5672 5726//5726 -f 5672//5672 5671//5671 5726//5726 -f 5726//5726 5671//5671 5670//5670 -f 5726//5726 5670//5670 5727//5727 -f 5670//5670 5669//5669 5727//5727 -f 5727//5727 5669//5669 5668//5668 -f 5727//5727 5668//5668 5728//5728 -f 5728//5728 5668//5668 5707//5707 -f 5728//5728 5707//5707 5709//5709 -f 5709//5709 5707//5707 5706//5706 -f 5709//5709 5706//5706 5705//5705 -f 5710//5710 5729//5729 5708//5708 -f 5708//5708 5729//5729 5730//5730 -f 5708//5708 5730//5730 5709//5709 -f 5730//5730 5731//5731 5709//5709 -f 5709//5709 5731//5731 5732//5732 -f 5709//5709 5732//5732 5728//5728 -f 5714//5714 5733//5733 5713//5713 -f 5713//5713 5733//5733 5734//5734 -f 5713//5713 5734//5734 5712//5712 -f 5734//5734 5735//5735 5712//5712 -f 5712//5712 5735//5735 5736//5736 -f 5712//5712 5736//5736 5711//5711 -f 5711//5711 5736//5736 5737//5737 -f 5711//5711 5737//5737 5710//5710 -f 5710//5710 5737//5737 5738//5738 -f 5710//5710 5738//5738 5729//5729 -f 5716//5716 5739//5739 5715//5715 -f 5715//5715 5739//5739 5740//5740 -f 5715//5715 5740//5740 5714//5714 -f 5714//5714 5740//5740 5741//5741 -f 5714//5714 5741//5741 5733//5733 -f 5718//5718 5742//5742 5717//5717 -f 5717//5717 5742//5742 5743//5743 -f 5717//5717 5743//5743 5716//5716 -f 5716//5716 5743//5743 5744//5744 -f 5716//5716 5744//5744 5739//5739 -f 5724//5724 5745//5745 5723//5723 -f 5723//5723 5745//5745 5746//5746 -f 5723//5723 5746//5746 5722//5722 -f 5726//5726 5747//5747 5725//5725 -f 5725//5725 5747//5747 5748//5748 -f 5725//5725 5748//5748 5724//5724 -f 5724//5724 5748//5748 5749//5749 -f 5724//5724 5749//5749 5745//5745 -f 5732//5732 5750//5750 5728//5728 -f 5728//5728 5750//5750 5751//5751 -f 5728//5728 5751//5751 5727//5727 -f 5727//5727 5751//5751 5752//5752 -f 5727//5727 5752//5752 5726//5726 -f 5726//5726 5752//5752 5753//5753 -f 5726//5726 5753//5753 5747//5747 -f 5720//5720 5754//5754 5719//5719 -f 5719//5719 5754//5754 5755//5755 -f 5719//5719 5755//5755 5718//5718 -f 5718//5718 5755//5755 5756//5756 -f 5718//5718 5756//5756 5742//5742 -f 5746//5746 5757//5757 5722//5722 -f 5722//5722 5757//5757 5758//5758 -f 5722//5722 5758//5758 5721//5721 -f 5721//5721 5758//5758 5759//5759 -f 5721//5721 5759//5759 5720//5720 -f 5720//5720 5759//5759 5760//5760 -f 5720//5720 5760//5760 5754//5754 -f 5761//5761 5756//5756 5762//5762 -f 5762//5762 5756//5756 5755//5755 -f 5762//5762 5755//5755 5763//5763 -f 5763//5763 5755//5755 5754//5754 -f 5763//5763 5754//5754 5764//5764 -f 5764//5764 5754//5754 5760//5760 -f 5764//5764 5760//5760 5765//5765 -f 5765//5765 5760//5760 5759//5759 -f 5765//5765 5759//5759 5766//5766 -f 5766//5766 5759//5759 5758//5758 -f 5766//5766 5758//5758 5767//5767 -f 5767//5767 5758//5758 5757//5757 -f 5767//5767 5757//5757 5768//5768 -f 5768//5768 5757//5757 5746//5746 -f 5768//5768 5746//5746 5769//5769 -f 5769//5769 5746//5746 5745//5745 -f 5769//5769 5745//5745 5770//5770 -f 5770//5770 5745//5745 5749//5749 -f 5770//5770 5749//5749 5771//5771 -f 5771//5771 5749//5749 5748//5748 -f 5771//5771 5748//5748 5772//5772 -f 5772//5772 5748//5748 5747//5747 -f 5772//5772 5747//5747 5773//5773 -f 5773//5773 5747//5747 5753//5753 -f 5773//5773 5753//5753 5774//5774 -f 5774//5774 5753//5753 5752//5752 -f 5774//5774 5752//5752 5775//5775 -f 5775//5775 5752//5752 5751//5751 -f 5775//5775 5751//5751 5776//5776 -f 5776//5776 5751//5751 5750//5750 -f 5776//5776 5750//5750 5777//5777 -f 5777//5777 5750//5750 5732//5732 -f 5777//5777 5732//5732 5778//5778 -f 5778//5778 5732//5732 5731//5731 -f 5778//5778 5731//5731 5779//5779 -f 5779//5779 5731//5731 5730//5730 -f 5779//5779 5730//5730 5780//5780 -f 5780//5780 5730//5730 5729//5729 -f 5780//5780 5729//5729 5781//5781 -f 5781//5781 5729//5729 5738//5738 -f 5781//5781 5738//5738 5782//5782 -f 5782//5782 5738//5738 5737//5737 -f 5782//5782 5737//5737 5783//5783 -f 5783//5783 5737//5737 5736//5736 -f 5783//5783 5736//5736 5784//5784 -f 5784//5784 5736//5736 5735//5735 -f 5784//5784 5735//5735 5785//5785 -f 5785//5785 5735//5735 5734//5734 -f 5785//5785 5734//5734 5786//5786 -f 5786//5786 5734//5734 5733//5733 -f 5786//5786 5733//5733 5787//5787 -f 5787//5787 5733//5733 5741//5741 -f 5787//5787 5741//5741 5788//5788 -f 5788//5788 5741//5741 5740//5740 -f 5788//5788 5740//5740 5789//5789 -f 5789//5789 5740//5740 5739//5739 -f 5789//5789 5739//5739 5790//5790 -f 5790//5790 5739//5739 5744//5744 -f 5790//5790 5744//5744 5791//5791 -f 5791//5791 5744//5744 5743//5743 -f 5791//5791 5743//5743 5792//5792 -f 5792//5792 5743//5743 5742//5742 -f 5792//5792 5742//5742 5761//5761 -f 5761//5761 5742//5742 5756//5756 -f 3023//3023 5777//5777 5778//5778 -f 5779//5779 3019//3019 5778//5778 -f 5778//5778 3019//3019 3021//3021 -f 5778//5778 3021//3021 3023//3023 -f 5780//5780 3015//3015 5779//5779 -f 5779//5779 3015//3015 3017//3017 -f 5779//5779 3017//3017 3019//3019 -f 5781//5781 3011//3011 5780//5780 -f 5780//5780 3011//3011 3013//3013 -f 5780//5780 3013//3013 3015//3015 -f 5782//5782 3007//3007 5781//5781 -f 5781//5781 3007//3007 3009//3009 -f 5781//5781 3009//3009 3011//3011 -f 5783//5783 3003//3003 5782//5782 -f 5782//5782 3003//3003 3005//3005 -f 5782//5782 3005//3005 3007//3007 -f 5784//5784 2999//2999 5783//5783 -f 5783//5783 2999//2999 3001//3001 -f 5783//5783 3001//3001 3003//3003 -f 5785//5785 2995//2995 5784//5784 -f 5784//5784 2995//2995 2997//2997 -f 5784//5784 2997//2997 2999//2999 -f 5786//5786 2991//2991 5785//5785 -f 5785//5785 2991//2991 2993//2993 -f 5785//5785 2993//2993 2995//2995 -f 5787//5787 2987//2987 5786//5786 -f 5786//5786 2987//2987 2989//2989 -f 5786//5786 2989//2989 2991//2991 -f 5788//5788 2983//2983 5787//5787 -f 5787//5787 2983//2983 2985//2985 -f 5787//5787 2985//2985 2987//2987 -f 5789//5789 2979//2979 5788//5788 -f 5788//5788 2979//2979 2981//2981 -f 5788//5788 2981//2981 2983//2983 -f 5790//5790 2975//2975 5789//5789 -f 5789//5789 2975//2975 2977//2977 -f 5789//5789 2977//2977 2979//2979 -f 5791//5791 2971//2971 5790//5790 -f 5790//5790 2971//2971 2973//2973 -f 5790//5790 2973//2973 2975//2975 -f 5792//5792 2967//2967 5791//5791 -f 5791//5791 2967//2967 2969//2969 -f 5791//5791 2969//2969 2971//2971 -f 5761//5761 2963//2963 5792//5792 -f 5792//5792 2963//2963 2965//2965 -f 5792//5792 2965//2965 2967//2967 -f 5762//5762 2959//2959 5761//5761 -f 5761//5761 2959//2959 2961//2961 -f 5761//5761 2961//2961 2963//2963 -f 5763//5763 2955//2955 5762//5762 -f 5762//5762 2955//2955 2957//2957 -f 5762//5762 2957//2957 2959//2959 -f 5764//5764 2951//2951 5763//5763 -f 5763//5763 2951//2951 2953//2953 -f 5763//5763 2953//2953 2955//2955 -f 5765//5765 2947//2947 5764//5764 -f 5764//5764 2947//2947 2949//2949 -f 5764//5764 2949//2949 2951//2951 -f 5766//5766 2943//2943 5765//5765 -f 5765//5765 2943//2943 2945//2945 -f 5765//5765 2945//2945 2947//2947 -f 5767//5767 2939//2939 5766//5766 -f 5766//5766 2939//2939 2941//2941 -f 5766//5766 2941//2941 2943//2943 -f 5768//5768 2935//2935 5767//5767 -f 5767//5767 2935//2935 2937//2937 -f 5767//5767 2937//2937 2939//2939 -f 5769//5769 2931//2931 5768//5768 -f 5768//5768 2931//2931 2933//2933 -f 5768//5768 2933//2933 2935//2935 -f 5770//5770 2927//2927 5769//5769 -f 5769//5769 2927//2927 2929//2929 -f 5769//5769 2929//2929 2931//2931 -f 5771//5771 2923//2923 5770//5770 -f 5770//5770 2923//2923 2925//2925 -f 5770//5770 2925//2925 2927//2927 -f 5772//5772 2919//2919 5771//5771 -f 5771//5771 2919//2919 2921//2921 -f 5771//5771 2921//2921 2923//2923 -f 5773//5773 2915//2915 5772//5772 -f 5772//5772 2915//2915 2917//2917 -f 5772//5772 2917//2917 2919//2919 -f 5774//5774 2911//2911 5773//5773 -f 5773//5773 2911//2911 2913//2913 -f 5773//5773 2913//2913 2915//2915 -f 5775//5775 2907//2907 5774//5774 -f 5774//5774 2907//2907 2909//2909 -f 5774//5774 2909//2909 2911//2911 -f 5776//5776 2903//2903 5775//5775 -f 5775//5775 2903//2903 2905//2905 -f 5775//5775 2905//2905 2907//2907 -f 3023//3023 2897//2897 5777//5777 -f 5777//5777 2897//2897 2899//2899 -f 5777//5777 2899//2899 5776//5776 -f 5776//5776 2899//2899 2901//2901 -f 5776//5776 2901//2901 2903//2903 -# 11584 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/switch.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/switch.obj deleted file mode 100644 index 8da91e10b..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/switch.obj +++ /dev/null @@ -1,680 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object switch.obj -# -# Vertices: 164 -# Faces: 336 -# -#### -vn 0.241861 0.278062 0.929616 -v 0.006250 0.007002 0.010750 -vn 0.577350 0.577350 0.577350 -v 0.007500 0.010500 0.010750 -vn -0.241861 0.278062 0.929616 -v -0.006250 0.007002 0.010750 -vn -0.577350 0.577350 0.577350 -v -0.007500 0.010500 0.010750 -vn -0.241860 -0.278061 0.929616 -v -0.006250 -0.007002 0.010750 -vn -0.577350 -0.577350 0.577350 -v -0.007500 -0.010500 0.010750 -vn 0.241860 -0.278061 0.929616 -v 0.006250 -0.007002 0.010750 -vn 0.577350 -0.577350 0.577350 -v 0.007500 -0.010500 0.010750 -vn -0.297106 0.630263 -0.717284 -v -0.003250 -0.006250 -0.013750 -vn 0.297106 0.630263 -0.717284 -v 0.003250 -0.006250 -0.013750 -vn -0.297106 -0.630263 -0.717284 -v -0.003250 -0.007250 -0.013750 -vn 0.297106 -0.630263 -0.717284 -v 0.003250 -0.007250 -0.013750 -vn -0.297106 0.630263 -0.717284 -v -0.003250 0.000750 -0.013750 -vn 0.297106 0.630263 -0.717284 -v 0.003250 0.000750 -0.013750 -vn -0.297106 -0.630263 -0.717284 -v -0.003250 -0.000750 -0.013750 -vn 0.297106 -0.630263 -0.717284 -v 0.003250 -0.000750 -0.013750 -vn -0.653226 0.731363 0.195969 -v -0.006250 0.010500 0.006585 -vn -0.450036 0.292306 -0.843816 -v -0.006250 0.009250 0.008750 -vn 0.653226 0.731363 0.195969 -v 0.006250 0.010500 0.006585 -vn 0.450036 0.292306 -0.843816 -v 0.006250 0.009250 0.008750 -vn -0.450036 -0.292306 -0.843816 -v -0.006250 -0.009250 0.008750 -vn -0.653227 -0.731363 0.195969 -v -0.006250 -0.010500 0.006585 -vn 0.450036 -0.292306 -0.843816 -v 0.006250 -0.009250 0.008750 -vn 0.653227 -0.731363 0.195969 -v 0.006250 -0.010500 0.006585 -vn -0.653227 0.731363 -0.195969 -v -0.006250 0.010500 0.002675 -vn 0.653226 0.731363 -0.195969 -v 0.006250 0.010500 0.002675 -vn 0.653226 -0.731363 -0.195969 -v 0.006250 -0.010500 0.002675 -vn -0.653227 -0.731363 -0.195969 -v -0.006250 -0.010500 0.002675 -vn -0.297106 0.630263 -0.717284 -v -0.003250 0.007250 -0.013750 -vn 0.297106 0.630263 -0.717284 -v 0.003250 0.007250 -0.013750 -vn -0.297106 -0.630263 -0.717284 -v -0.003250 0.006250 -0.013750 -vn 0.297106 -0.630263 -0.717284 -v 0.003250 0.006250 -0.013750 -vn 0.577350 -0.577350 -0.577350 -v 0.007500 -0.010500 0.008750 -vn 0.577350 0.577350 -0.577350 -v 0.007500 0.010500 0.008750 -vn -0.577350 -0.577350 -0.577350 -v -0.007500 -0.010500 0.008750 -vn -0.577350 0.577350 -0.577350 -v -0.007500 0.010500 0.008750 -vn -0.577350 0.577350 -0.577350 -v -0.006250 0.009250 -0.006250 -vn -0.577350 -0.577350 -0.577350 -v -0.006250 -0.009250 -0.006250 -vn -0.770262 0.615997 -0.165057 -v -0.006250 0.009250 0.000510 -vn -0.770262 -0.615997 -0.165057 -v -0.006250 -0.009250 0.000510 -vn 0.770262 0.615997 -0.165057 -v 0.006250 0.009250 0.000510 -vn 0.770262 -0.615997 -0.165057 -v 0.006250 -0.009250 0.000510 -vn 0.577350 -0.577350 -0.577351 -v 0.006250 -0.009250 -0.006250 -vn 0.577350 0.577350 -0.577350 -v 0.006250 0.009250 -0.006250 -vn 0.318872 0.770269 0.552275 -v -0.000353 0.007250 -0.012242 -vn -0.000000 0.770261 0.637729 -v -0.000000 0.007250 -0.012337 -vn -0.552286 0.770265 -0.318860 -v 0.000612 0.007250 -0.008644 -vn -0.318860 0.770261 -0.552292 -v 0.000353 0.007250 -0.008385 -vn 0.301511 0.301511 -0.904534 -v 0.004250 0.007250 -0.006250 -vn -0.000000 0.770261 -0.637729 -v -0.000000 0.007250 -0.008290 -vn -0.301511 0.301512 -0.904534 -v -0.004250 0.007250 -0.006250 -vn 0.318860 0.770261 -0.552292 -v -0.000353 0.007250 -0.008385 -vn -0.318872 0.770269 0.552275 -v 0.000353 0.007250 -0.012242 -vn -0.552302 0.770255 0.318856 -v 0.000612 0.007250 -0.011984 -vn 0.717283 0.630262 -0.297111 -v 0.004250 0.007250 -0.012750 -vn -0.669352 0.737701 0.088123 -v 0.000707 0.007250 -0.011630 -vn -0.669356 0.737698 -0.088117 -v 0.000707 0.007250 -0.008997 -vn 0.552286 0.770265 -0.318860 -v -0.000612 0.007250 -0.008644 -vn 0.669355 0.737698 -0.088117 -v -0.000707 0.007250 -0.008997 -vn -0.717283 0.630262 -0.297111 -v -0.004250 0.007250 -0.012750 -vn 0.669352 0.737701 0.088123 -v -0.000707 0.007250 -0.011630 -vn 0.552302 0.770255 0.318856 -v -0.000612 0.007250 -0.011984 -vn -0.301511 0.301512 -0.904534 -v -0.004250 -0.006250 -0.006250 -vn -0.301511 -0.301512 -0.904534 -v -0.004250 -0.007250 -0.006250 -vn 0.301511 -0.301511 -0.904534 -v 0.004250 0.006250 -0.006250 -vn -0.301511 -0.301512 -0.904534 -v -0.004250 0.006250 -0.006250 -vn 0.301511 -0.301511 -0.904534 -v 0.004250 -0.007250 -0.006250 -vn 0.301511 0.301511 -0.904534 -v 0.004250 -0.006250 -0.006250 -vn -0.301511 -0.301512 -0.904534 -v -0.004250 -0.000750 -0.006250 -vn -0.301511 0.301512 -0.904534 -v -0.004250 0.000750 -0.006250 -vn 0.301511 0.301511 -0.904534 -v 0.004250 0.000750 -0.006250 -vn 0.301511 -0.301511 -0.904534 -v 0.004250 -0.000750 -0.006250 -vn 0.552302 0.770255 0.318856 -v -0.000612 0.000750 -0.011984 -vn 0.669352 0.737701 0.088123 -v -0.000707 0.000750 -0.011630 -vn -0.717283 0.630262 -0.297111 -v -0.004250 0.000750 -0.012750 -vn 0.669355 0.737698 -0.088117 -v -0.000707 0.000750 -0.008997 -vn 0.552286 0.770265 -0.318860 -v -0.000612 0.000750 -0.008644 -vn 0.318872 0.770269 0.552275 -v -0.000353 0.000750 -0.012242 -vn -0.000000 0.770261 0.637729 -v -0.000000 0.000750 -0.012337 -vn -0.318872 0.770269 0.552275 -v 0.000353 0.000750 -0.012242 -vn -0.552302 0.770255 0.318856 -v 0.000612 0.000750 -0.011984 -vn 0.717283 0.630262 -0.297111 -v 0.004250 0.000750 -0.012750 -vn -0.669352 0.737701 0.088123 -v 0.000707 0.000750 -0.011630 -vn -0.669356 0.737698 -0.088117 -v 0.000707 0.000750 -0.008997 -vn -0.552286 0.770265 -0.318860 -v 0.000612 0.000750 -0.008644 -vn -0.318860 0.770261 -0.552292 -v 0.000353 0.000750 -0.008385 -vn -0.000000 0.770261 -0.637729 -v -0.000000 0.000750 -0.008290 -vn 0.318860 0.770261 -0.552291 -v -0.000353 0.000750 -0.008385 -vn -0.552302 -0.770255 0.318856 -v 0.000612 0.006250 -0.011984 -vn -0.318872 -0.770269 0.552275 -v 0.000353 0.006250 -0.012242 -vn 0.000000 -0.770261 0.637729 -v -0.000000 0.006250 -0.012337 -vn -0.669352 -0.737701 0.088123 -v 0.000707 0.006250 -0.011630 -vn 0.717283 -0.630262 -0.297111 -v 0.004250 0.006250 -0.012750 -vn -0.669355 -0.737698 -0.088117 -v 0.000707 0.006250 -0.008997 -vn -0.552286 -0.770265 -0.318860 -v 0.000612 0.006250 -0.008644 -vn 0.552286 -0.770265 -0.318860 -v -0.000612 0.006250 -0.008644 -vn 0.318860 -0.770261 -0.552292 -v -0.000353 0.006250 -0.008385 -vn 0.000000 -0.770261 -0.637729 -v -0.000000 0.006250 -0.008290 -vn -0.318860 -0.770261 -0.552292 -v 0.000353 0.006250 -0.008385 -vn 0.318872 -0.770269 0.552275 -v -0.000353 0.006250 -0.012242 -vn 0.552302 -0.770255 0.318856 -v -0.000612 0.006250 -0.011984 -vn -0.717283 -0.630262 -0.297111 -v -0.004250 0.006250 -0.012750 -vn 0.669352 -0.737701 0.088123 -v -0.000707 0.006250 -0.011630 -vn 0.669356 -0.737698 -0.088117 -v -0.000707 0.006250 -0.008997 -vn 0.552302 0.770255 0.318856 -v -0.000612 -0.006250 -0.011984 -vn 0.669352 0.737701 0.088123 -v -0.000707 -0.006250 -0.011630 -vn -0.717283 0.630262 -0.297111 -v -0.004250 -0.006250 -0.012750 -vn 0.669355 0.737698 -0.088117 -v -0.000707 -0.006250 -0.008997 -vn 0.552286 0.770265 -0.318860 -v -0.000612 -0.006250 -0.008644 -vn 0.318872 0.770269 0.552275 -v -0.000353 -0.006250 -0.012242 -vn -0.000000 0.770261 0.637729 -v 0.000000 -0.006250 -0.012337 -vn -0.318872 0.770269 0.552275 -v 0.000353 -0.006250 -0.012242 -vn -0.552302 0.770255 0.318856 -v 0.000612 -0.006250 -0.011984 -vn 0.717283 0.630262 -0.297111 -v 0.004250 -0.006250 -0.012750 -vn -0.669352 0.737701 0.088123 -v 0.000707 -0.006250 -0.011630 -vn -0.669356 0.737698 -0.088117 -v 0.000707 -0.006250 -0.008997 -vn -0.552286 0.770265 -0.318860 -v 0.000612 -0.006250 -0.008644 -vn -0.318860 0.770261 -0.552292 -v 0.000353 -0.006250 -0.008385 -vn -0.000000 0.770261 -0.637729 -v 0.000000 -0.006250 -0.008290 -vn 0.318860 0.770261 -0.552292 -v -0.000353 -0.006250 -0.008385 -vn 0.000000 -0.770261 0.637729 -v 0.000000 -0.000750 -0.012337 -vn -0.318872 -0.770269 0.552275 -v 0.000353 -0.000750 -0.012242 -vn -0.318860 -0.770261 -0.552291 -v 0.000353 -0.000750 -0.008385 -vn 0.000000 -0.770261 -0.637729 -v 0.000000 -0.000750 -0.008290 -vn 0.318860 -0.770261 -0.552292 -v -0.000353 -0.000750 -0.008385 -vn 0.552286 -0.770265 -0.318860 -v -0.000612 -0.000750 -0.008644 -vn -0.552286 -0.770265 -0.318860 -v 0.000612 -0.000750 -0.008644 -vn -0.669355 -0.737698 -0.088117 -v 0.000707 -0.000750 -0.008997 -vn 0.717283 -0.630262 -0.297111 -v 0.004250 -0.000750 -0.012750 -vn -0.669352 -0.737701 0.088123 -v 0.000707 -0.000750 -0.011630 -vn -0.552302 -0.770255 0.318856 -v 0.000612 -0.000750 -0.011984 -vn 0.318872 -0.770269 0.552275 -v -0.000353 -0.000750 -0.012242 -vn 0.552302 -0.770255 0.318856 -v -0.000612 -0.000750 -0.011984 -vn -0.717283 -0.630262 -0.297111 -v -0.004250 -0.000750 -0.012750 -vn 0.669352 -0.737701 0.088123 -v -0.000707 -0.000750 -0.011630 -vn 0.669356 -0.737698 -0.088117 -v -0.000707 -0.000750 -0.008997 -vn -0.552302 -0.770255 0.318856 -v 0.000612 -0.007250 -0.011984 -vn -0.669352 -0.737701 0.088123 -v 0.000707 -0.007250 -0.011630 -vn 0.717283 -0.630262 -0.297111 -v 0.004250 -0.007250 -0.012750 -vn -0.669355 -0.737698 -0.088117 -v 0.000707 -0.007250 -0.008997 -vn -0.552286 -0.770265 -0.318860 -v 0.000612 -0.007250 -0.008644 -vn -0.318872 -0.770269 0.552275 -v 0.000353 -0.007250 -0.012242 -vn 0.000000 -0.770261 0.637729 -v 0.000000 -0.007250 -0.012337 -vn 0.552286 -0.770265 -0.318860 -v -0.000612 -0.007250 -0.008644 -vn 0.318860 -0.770261 -0.552292 -v -0.000353 -0.007250 -0.008385 -vn 0.000000 -0.770261 -0.637729 -v 0.000000 -0.007250 -0.008290 -vn -0.318860 -0.770261 -0.552292 -v 0.000353 -0.007250 -0.008385 -vn 0.318872 -0.770269 0.552275 -v -0.000353 -0.007250 -0.012242 -vn 0.552302 -0.770255 0.318856 -v -0.000612 -0.007250 -0.011984 -vn -0.717283 -0.630262 -0.297111 -v -0.004250 -0.007250 -0.012750 -vn 0.669352 -0.737701 0.088123 -v -0.000707 -0.007250 -0.011630 -vn 0.669356 -0.737698 -0.088117 -v -0.000707 -0.007250 -0.008997 -vn 0.578243 0.425319 0.696232 -v 0.006250 0.006250 0.013750 -vn -0.578243 0.425319 0.696232 -v -0.006250 0.006250 0.013750 -vn 0.578243 -0.425318 0.696232 -v 0.006250 -0.006250 0.013750 -vn -0.578243 -0.425318 0.696232 -v -0.006250 -0.006250 0.013750 -vn 0.720189 0.118355 0.683608 -v 0.006250 -0.003783 0.013176 -vn 0.720189 -0.118355 0.683608 -v 0.006250 0.003783 0.013176 -vn 0.720191 -0.039626 0.692643 -v 0.006250 0.001266 0.012887 -vn 0.720191 0.039626 0.692643 -v 0.006250 -0.001266 0.012887 -vn -0.720189 -0.118355 0.683608 -v -0.006250 0.003783 0.013176 -vn -0.720189 0.118354 0.683608 -v -0.006250 -0.003783 0.013176 -vn -0.720191 0.039626 0.692643 -v -0.006250 -0.001266 0.012887 -vn -0.720191 -0.039626 0.692643 -v -0.006250 0.001266 0.012887 -# 164 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 3//3 4//4 5//5 -f 5//5 4//4 6//6 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 7//7 8//8 1//1 -f 1//1 8//8 2//2 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 25//25 17//17 26//26 -f 26//26 17//17 19//19 -f 27//27 24//24 28//28 -f 28//28 24//24 22//22 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 33//33 34//34 8//8 -f 8//8 34//34 2//2 -f 6//6 4//4 35//35 -f 35//35 4//4 36//36 -f 20//20 34//34 23//23 -f 23//23 34//34 33//33 -f 23//23 33//33 21//21 -f 21//21 33//33 35//35 -f 21//21 35//35 18//18 -f 18//18 35//35 36//36 -f 18//18 36//36 20//20 -f 20//20 36//36 34//34 -f 4//4 2//2 36//36 -f 36//36 2//2 34//34 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 25//25 -f 25//25 40//40 17//17 -f 21//21 18//18 22//22 -f 22//22 18//18 17//17 -f 22//22 17//17 28//28 -f 28//28 17//17 40//40 -f 41//41 26//26 19//19 -f 42//42 43//43 44//44 -f 44//44 41//41 42//42 -f 42//42 41//41 19//19 -f 42//42 19//19 27//27 -f 27//27 19//19 20//20 -f 27//27 20//20 24//24 -f 24//24 20//20 23//23 -f 8//8 6//6 33//33 -f 33//33 6//6 35//35 -f 37//37 39//39 44//44 -f 44//44 39//39 41//41 -f 26//26 41//41 25//25 -f 25//25 41//41 39//39 -f 45//45 46//46 29//29 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 29//29 46//46 30//30 -f 46//46 53//53 30//30 -f 30//30 53//53 54//54 -f 30//30 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 49//49 -f 49//49 56//56 57//57 -f 49//49 57//57 47//47 -f 52//52 58//58 51//51 -f 51//51 58//58 59//59 -f 51//51 59//59 60//60 -f 60//60 59//59 61//61 -f 60//60 61//61 29//29 -f 29//29 61//61 62//62 -f 29//29 62//62 45//45 -f 63//63 64//64 38//38 -f 43//43 65//65 44//44 -f 44//44 65//65 49//49 -f 44//44 49//49 37//37 -f 37//37 49//49 51//51 -f 37//37 51//51 66//66 -f 38//38 64//64 43//43 -f 43//43 64//64 67//67 -f 43//43 67//67 68//68 -f 69//69 37//37 70//70 -f 70//70 37//37 66//66 -f 70//70 66//66 71//71 -f 38//38 37//37 63//63 -f 63//63 37//37 69//69 -f 63//63 69//69 68//68 -f 68//68 69//69 72//72 -f 68//68 72//72 43//43 -f 43//43 72//72 71//71 -f 43//43 71//71 65//65 -f 65//65 71//71 66//66 -f 73//73 13//13 74//74 -f 74//74 13//13 75//75 -f 74//74 75//75 76//76 -f 76//76 75//75 70//70 -f 76//76 70//70 77//77 -f 73//73 78//78 13//13 -f 13//13 78//78 79//79 -f 13//13 79//79 14//14 -f 79//79 80//80 14//14 -f 14//14 80//80 81//81 -f 14//14 81//81 82//82 -f 82//82 81//81 83//83 -f 82//82 83//83 71//71 -f 71//71 83//83 84//84 -f 71//71 84//84 85//85 -f 85//85 86//86 71//71 -f 71//71 86//86 87//87 -f 71//71 87//87 70//70 -f 70//70 87//87 88//88 -f 70//70 88//88 77//77 -f 89//89 90//90 32//32 -f 32//32 90//90 91//91 -f 32//32 91//91 31//31 -f 89//89 32//32 92//92 -f 92//92 32//32 93//93 -f 92//92 93//93 94//94 -f 94//94 93//93 65//65 -f 94//94 65//65 95//95 -f 96//96 97//97 66//66 -f 66//66 97//97 98//98 -f 66//66 98//98 65//65 -f 65//65 98//98 99//99 -f 65//65 99//99 95//95 -f 91//91 100//100 31//31 -f 31//31 100//100 101//101 -f 31//31 101//101 102//102 -f 102//102 101//101 103//103 -f 102//102 103//103 66//66 -f 66//66 103//103 104//104 -f 66//66 104//104 96//96 -f 105//105 9//9 106//106 -f 106//106 9//9 107//107 -f 106//106 107//107 108//108 -f 108//108 107//107 63//63 -f 108//108 63//63 109//109 -f 105//105 110//110 9//9 -f 9//9 110//110 111//111 -f 9//9 111//111 10//10 -f 111//111 112//112 10//10 -f 10//10 112//112 113//113 -f 10//10 113//113 114//114 -f 114//114 113//113 115//115 -f 114//114 115//115 68//68 -f 68//68 115//115 116//116 -f 68//68 116//116 117//117 -f 117//117 118//118 68//68 -f 68//68 118//118 119//119 -f 68//68 119//119 63//63 -f 63//63 119//119 120//120 -f 63//63 120//120 109//109 -f 15//15 16//16 121//121 -f 121//121 16//16 122//122 -f 123//123 72//72 124//124 -f 124//124 72//72 69//69 -f 124//124 69//69 125//125 -f 125//125 69//69 126//126 -f 123//123 127//127 72//72 -f 72//72 127//127 128//128 -f 72//72 128//128 129//129 -f 129//129 128//128 130//130 -f 129//129 130//130 16//16 -f 16//16 130//130 131//131 -f 16//16 131//131 122//122 -f 121//121 132//132 15//15 -f 15//15 132//132 133//133 -f 15//15 133//133 134//134 -f 134//134 133//133 135//135 -f 134//134 135//135 69//69 -f 69//69 135//135 136//136 -f 69//69 136//136 126//126 -f 137//137 12//12 138//138 -f 138//138 12//12 139//139 -f 138//138 139//139 140//140 -f 140//140 139//139 67//67 -f 140//140 67//67 141//141 -f 137//137 142//142 12//12 -f 12//12 142//142 143//143 -f 12//12 143//143 11//11 -f 144//144 145//145 64//64 -f 64//64 145//145 146//146 -f 64//64 146//146 67//67 -f 67//67 146//146 147//147 -f 67//67 147//147 141//141 -f 143//143 148//148 11//11 -f 11//11 148//148 149//149 -f 11//11 149//149 150//150 -f 150//150 149//149 151//151 -f 150//150 151//151 64//64 -f 64//64 151//151 152//152 -f 64//64 152//152 144//144 -f 42//42 27//27 40//40 -f 40//40 27//27 28//28 -f 43//43 42//42 38//38 -f 38//38 42//42 40//40 -f 153//153 1//1 154//154 -f 154//154 1//1 3//3 -f 7//7 155//155 5//5 -f 5//5 155//155 156//156 -f 157//157 155//155 7//7 -f 153//153 158//158 1//1 -f 1//1 158//158 159//159 -f 1//1 159//159 7//7 -f 7//7 159//159 160//160 -f 7//7 160//160 157//157 -f 161//161 154//154 3//3 -f 156//156 162//162 5//5 -f 5//5 162//162 163//163 -f 5//5 163//163 3//3 -f 3//3 163//163 164//164 -f 3//3 164//164 161//161 -f 153//153 154//154 158//158 -f 158//158 154//154 161//161 -f 158//158 161//161 159//159 -f 159//159 161//161 164//164 -f 159//159 164//164 160//160 -f 160//160 164//164 163//163 -f 160//160 163//163 157//157 -f 157//157 163//163 162//162 -f 157//157 162//162 155//155 -f 155//155 162//162 156//156 -f 139//139 114//114 67//67 -f 67//67 114//114 68//68 -f 12//12 10//10 139//139 -f 139//139 10//10 114//114 -f 150//150 107//107 11//11 -f 11//11 107//107 9//9 -f 64//64 63//63 150//150 -f 150//150 63//63 107//107 -f 129//129 82//82 72//72 -f 72//72 82//82 71//71 -f 16//16 14//14 129//129 -f 129//129 14//14 82//82 -f 134//134 75//75 15//15 -f 15//15 75//75 13//13 -f 69//69 70//70 134//134 -f 134//134 70//70 75//75 -f 93//93 55//55 65//65 -f 65//65 55//55 49//49 -f 32//32 30//30 93//93 -f 93//93 30//30 55//55 -f 66//66 51//51 102//102 -f 102//102 51//51 60//60 -f 102//102 60//60 31//31 -f 31//31 60//60 29//29 -f 151//151 106//106 152//152 -f 152//152 106//106 108//108 -f 106//106 151//151 105//105 -f 105//105 151//151 149//149 -f 105//105 149//149 110//110 -f 110//110 149//149 148//148 -f 110//110 148//148 111//111 -f 111//111 148//148 143//143 -f 111//111 143//143 112//112 -f 112//112 143//143 142//142 -f 112//112 142//142 113//113 -f 113//113 142//142 137//137 -f 113//113 137//137 115//115 -f 115//115 137//137 138//138 -f 140//140 116//116 138//138 -f 138//138 116//116 115//115 -f 116//116 140//140 117//117 -f 117//117 140//140 141//141 -f 117//117 141//141 118//118 -f 118//118 141//141 147//147 -f 118//118 147//147 119//119 -f 119//119 147//147 146//146 -f 119//119 146//146 120//120 -f 120//120 146//146 145//145 -f 120//120 145//145 109//109 -f 109//109 145//145 144//144 -f 109//109 144//144 108//108 -f 108//108 144//144 152//152 -f 135//135 74//74 136//136 -f 136//136 74//74 76//76 -f 74//74 135//135 73//73 -f 73//73 135//135 133//133 -f 73//73 133//133 78//78 -f 78//78 133//133 132//132 -f 78//78 132//132 79//79 -f 79//79 132//132 121//121 -f 79//79 121//121 80//80 -f 80//80 121//121 122//122 -f 80//80 122//122 81//81 -f 81//81 122//122 131//131 -f 81//81 131//131 83//83 -f 83//83 131//131 130//130 -f 128//128 84//84 130//130 -f 130//130 84//84 83//83 -f 84//84 128//128 85//85 -f 85//85 128//128 127//127 -f 85//85 127//127 86//86 -f 86//86 127//127 123//123 -f 86//86 123//123 87//87 -f 87//87 123//123 124//124 -f 87//87 124//124 88//88 -f 88//88 124//124 125//125 -f 88//88 125//125 77//77 -f 77//77 125//125 126//126 -f 77//77 126//126 76//76 -f 76//76 126//126 136//136 -f 57//57 94//94 47//47 -f 47//47 94//94 95//95 -f 47//47 95//95 48//48 -f 48//48 95//95 99//99 -f 48//48 99//99 50//50 -f 50//50 99//99 98//98 -f 50//50 98//98 52//52 -f 52//52 98//98 97//97 -f 52//52 97//97 58//58 -f 58//58 97//97 96//96 -f 58//58 96//96 59//59 -f 59//59 96//96 104//104 -f 94//94 57//57 92//92 -f 92//92 57//57 56//56 -f 61//61 103//103 62//62 -f 62//62 103//103 101//101 -f 62//62 101//101 45//45 -f 45//45 101//101 100//100 -f 45//45 100//100 46//46 -f 46//46 100//100 91//91 -f 46//46 91//91 53//53 -f 53//53 91//91 90//90 -f 53//53 90//90 54//54 -f 54//54 90//90 89//89 -f 54//54 89//89 56//56 -f 56//56 89//89 92//92 -f 103//103 61//61 104//104 -f 104//104 61//61 59//59 -# 336 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/zamenjivac_dodatno.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/zamenjivac_dodatno.obj deleted file mode 100644 index 5075515a5..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/zamenjivac_dodatno.obj +++ /dev/null @@ -1,4308 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object zamenjivac_dodatno.obj -# -# Vertices: 1050 -# Faces: 2192 -# -#### -vn 0.835724 -0.154358 0.527009 -v -0.013049 0.015000 0.193700 -vn 0.717284 0.630262 0.297108 -v -0.013049 0.019000 0.193700 -vn 0.527010 -0.154357 0.835724 -v -0.031639 0.015000 0.212289 -vn 0.297109 0.630262 0.717284 -v -0.031639 0.019000 0.212289 -vn 0.527010 0.154357 0.835724 -v -0.031639 -0.015000 0.212289 -vn 0.297109 -0.630262 0.717284 -v -0.031639 -0.019000 0.212289 -vn 0.835724 0.154358 0.527009 -v -0.013049 -0.015000 0.193700 -vn 0.717284 -0.630263 0.297108 -v -0.013049 -0.019000 0.193700 -vn -0.637720 0.770268 0.000000 -v -0.039299 -0.015300 0.209039 -vn -0.637720 -0.770268 0.000000 -v -0.039299 -0.019000 0.209039 -vn -0.552288 0.770259 -0.318873 -v -0.039467 -0.015300 0.209664 -vn -0.552288 -0.770259 -0.318873 -v -0.039467 -0.019000 0.209664 -vn -0.318873 0.770259 -0.552288 -v -0.039924 -0.015300 0.210122 -vn -0.318873 -0.770259 -0.552288 -v -0.039924 -0.019000 0.210122 -vn 0.000004 0.770270 -0.637718 -v -0.040549 -0.015300 0.210289 -vn 0.000004 -0.770270 -0.637718 -v -0.040549 -0.019000 0.210289 -vn 0.318877 0.770257 -0.552288 -v -0.041174 -0.015300 0.210122 -vn 0.318877 -0.770257 -0.552287 -v -0.041174 -0.019000 0.210122 -vn 0.552288 0.770259 -0.318873 -v -0.041632 -0.015300 0.209664 -vn 0.552288 -0.770259 -0.318873 -v -0.041632 -0.019000 0.209664 -vn 0.637720 0.770268 0.000000 -v -0.041799 -0.015300 0.209039 -vn 0.637720 -0.770268 0.000000 -v -0.041799 -0.019000 0.209039 -vn 0.552288 0.770259 0.318873 -v -0.041632 -0.015300 0.208414 -vn 0.552288 -0.770259 0.318873 -v -0.041632 -0.019000 0.208414 -vn 0.318847 0.770266 0.552292 -v -0.041174 -0.015300 0.207957 -vn 0.318846 -0.770268 0.552290 -v -0.041174 -0.019000 0.207957 -vn 0.000004 0.770247 0.637746 -v -0.040549 -0.015300 0.207789 -vn 0.000004 -0.770247 0.637746 -v -0.040549 -0.019000 0.207789 -vn -0.318841 0.770270 0.552290 -v -0.039924 -0.015300 0.207957 -vn -0.318841 -0.770270 0.552290 -v -0.039924 -0.019000 0.207957 -vn -0.552288 0.770259 0.318873 -v -0.039467 -0.015300 0.208414 -vn -0.552288 -0.770259 0.318873 -v -0.039467 -0.019000 0.208414 -vn -0.637716 0.770271 -0.000008 -v -0.039299 -0.015300 0.193039 -vn -0.637716 -0.770271 -0.000008 -v -0.039299 -0.019000 0.193039 -vn -0.552306 0.770247 -0.318868 -v -0.039467 -0.015300 0.193664 -vn -0.552306 -0.770247 -0.318868 -v -0.039467 -0.019000 0.193664 -vn -0.318854 0.770278 -0.552271 -v -0.039924 -0.015300 0.194122 -vn -0.318854 -0.770278 -0.552271 -v -0.039924 -0.019000 0.194122 -vn 0.000004 0.770247 -0.637746 -v -0.040549 -0.015300 0.194289 -vn 0.000004 -0.770247 -0.637746 -v -0.040549 -0.019000 0.194289 -vn 0.318858 0.770277 -0.552270 -v -0.041174 -0.015300 0.194122 -vn 0.318859 -0.770277 -0.552271 -v -0.041174 -0.019000 0.194122 -vn 0.552306 0.770247 -0.318868 -v -0.041632 -0.015300 0.193664 -vn 0.552306 -0.770247 -0.318868 -v -0.041632 -0.019000 0.193664 -vn 0.637716 0.770271 -0.000008 -v -0.041799 -0.015300 0.193039 -vn 0.637716 -0.770271 -0.000008 -v -0.041799 -0.019000 0.193039 -vn 0.552288 0.770259 0.318873 -v -0.041632 -0.015300 0.192414 -vn 0.552288 -0.770259 0.318873 -v -0.041632 -0.019000 0.192414 -vn 0.318877 0.770257 0.552288 -v -0.041174 -0.015300 0.191957 -vn 0.318877 -0.770257 0.552288 -v -0.041174 -0.019000 0.191957 -vn 0.000004 0.770270 0.637718 -v -0.040549 -0.015300 0.191789 -vn 0.000004 -0.770270 0.637718 -v -0.040549 -0.019000 0.191789 -vn -0.318873 0.770259 0.552288 -v -0.039924 -0.015300 0.191957 -vn -0.318873 -0.770259 0.552288 -v -0.039924 -0.019000 0.191957 -vn -0.552288 0.770259 0.318873 -v -0.039467 -0.015300 0.192414 -vn -0.552288 -0.770259 0.318873 -v -0.039467 -0.019000 0.192414 -vn -0.637720 0.770268 0.000000 -v -0.044549 -0.015300 0.187539 -vn -0.637720 -0.770268 0.000000 -v -0.044549 -0.019000 0.187539 -vn -0.552288 0.770259 -0.318873 -v -0.044717 -0.015300 0.188164 -vn -0.552288 -0.770259 -0.318873 -v -0.044717 -0.019000 0.188164 -vn -0.318877 0.770257 -0.552288 -v -0.045174 -0.015300 0.188622 -vn -0.318877 -0.770257 -0.552287 -v -0.045174 -0.019000 0.188622 -vn -0.000004 0.770270 -0.637718 -v -0.045799 -0.015300 0.188789 -vn -0.000004 -0.770270 -0.637718 -v -0.045799 -0.019000 0.188789 -vn 0.318873 0.770259 -0.552288 -v -0.046424 -0.015300 0.188622 -vn 0.318873 -0.770259 -0.552288 -v -0.046424 -0.019000 0.188622 -vn 0.552289 0.770264 -0.318857 -v -0.046882 -0.015300 0.188164 -vn 0.552289 -0.770264 -0.318857 -v -0.046882 -0.019000 0.188164 -vn 0.637735 0.770256 -0.000000 -v -0.047049 -0.015300 0.187539 -vn 0.637734 -0.770257 0.000000 -v -0.047049 -0.019000 0.187539 -vn 0.552289 0.770264 0.318857 -v -0.046882 -0.015300 0.186914 -vn 0.552289 -0.770264 0.318857 -v -0.046882 -0.019000 0.186914 -vn 0.318873 0.770259 0.552288 -v -0.046424 -0.015300 0.186457 -vn 0.318873 -0.770259 0.552288 -v -0.046424 -0.019000 0.186457 -vn -0.000004 0.770270 0.637718 -v -0.045799 -0.015300 0.186289 -vn -0.000004 -0.770270 0.637718 -v -0.045799 -0.019000 0.186289 -vn -0.318877 0.770257 0.552288 -v -0.045174 -0.015300 0.186457 -vn -0.318877 -0.770257 0.552287 -v -0.045174 -0.019000 0.186457 -vn -0.552288 0.770259 0.318873 -v -0.044717 -0.015300 0.186914 -vn -0.552288 -0.770259 0.318873 -v -0.044717 -0.019000 0.186914 -vn -0.637734 0.770257 0.000000 -v -0.052549 -0.015300 0.187539 -vn -0.637735 -0.770256 0.000000 -v -0.052549 -0.019000 0.187539 -vn -0.552289 0.770264 -0.318857 -v -0.052717 -0.015300 0.188164 -vn -0.552289 -0.770264 -0.318857 -v -0.052717 -0.019000 0.188164 -vn -0.318873 0.770259 -0.552286 -v -0.053174 -0.015300 0.188622 -vn -0.318873 -0.770258 -0.552288 -v -0.053174 -0.019000 0.188622 -vn 0.000004 0.770270 -0.637718 -v -0.053799 -0.015300 0.188789 -vn 0.000004 -0.770270 -0.637718 -v -0.053799 -0.019000 0.188789 -vn 0.318877 0.770257 -0.552288 -v -0.054424 -0.015300 0.188622 -vn 0.318877 -0.770257 -0.552288 -v -0.054424 -0.019000 0.188622 -vn 0.552288 0.770259 -0.318873 -v -0.054882 -0.015300 0.188164 -vn 0.552288 -0.770259 -0.318873 -v -0.054882 -0.019000 0.188164 -vn 0.637721 0.770268 0.000000 -v -0.055049 -0.015300 0.187539 -vn 0.637720 -0.770268 -0.000000 -v -0.055049 -0.019000 0.187539 -vn 0.552288 0.770259 0.318873 -v -0.054882 -0.015300 0.186914 -vn 0.552288 -0.770259 0.318873 -v -0.054882 -0.019000 0.186914 -vn 0.318877 0.770257 0.552288 -v -0.054424 -0.015300 0.186457 -vn 0.318877 -0.770257 0.552288 -v -0.054424 -0.019000 0.186457 -vn 0.000004 0.770269 0.637719 -v -0.053799 -0.015300 0.186289 -vn 0.000004 -0.770270 0.637718 -v -0.053799 -0.019000 0.186289 -vn -0.318873 0.770264 0.552280 -v -0.053174 -0.015300 0.186457 -vn -0.318873 -0.770259 0.552288 -v -0.053174 -0.019000 0.186457 -vn -0.552289 0.770264 0.318857 -v -0.052717 -0.015300 0.186914 -vn -0.552289 -0.770264 0.318857 -v -0.052717 -0.019000 0.186914 -vn -0.637734 0.770257 -0.000000 -v -0.060549 -0.015300 0.187539 -vn -0.637734 -0.770257 0.000000 -v -0.060549 -0.019000 0.187539 -vn -0.552280 0.770268 -0.318864 -v -0.060717 -0.015300 0.188164 -vn -0.552280 -0.770268 -0.318864 -v -0.060717 -0.019000 0.188164 -vn -0.318871 0.770253 -0.552297 -v -0.061174 -0.015300 0.188622 -vn -0.318871 -0.770253 -0.552297 -v -0.061174 -0.019000 0.188622 -vn -0.000004 0.770270 -0.637718 -v -0.061799 -0.015300 0.188789 -vn -0.000004 -0.770270 -0.637718 -v -0.061799 -0.019000 0.188789 -vn 0.318873 0.770259 -0.552288 -v -0.062424 -0.015300 0.188622 -vn 0.318873 -0.770259 -0.552288 -v -0.062424 -0.019000 0.188622 -vn 0.552289 0.770264 -0.318857 -v -0.062882 -0.015300 0.188164 -vn 0.552289 -0.770264 -0.318857 -v -0.062882 -0.019000 0.188164 -vn 0.637734 0.770257 0.000000 -v -0.063049 -0.015300 0.187539 -vn 0.637734 -0.770257 0.000000 -v -0.063049 -0.019000 0.187539 -vn 0.552289 0.770264 0.318857 -v -0.062882 -0.015300 0.186914 -vn 0.552289 -0.770264 0.318857 -v -0.062882 -0.019000 0.186914 -vn 0.318873 0.770259 0.552288 -v -0.062424 -0.015300 0.186457 -vn 0.318873 -0.770258 0.552288 -v -0.062424 -0.019000 0.186457 -vn -0.000004 0.770270 0.637718 -v -0.061799 -0.015300 0.186289 -vn -0.000004 -0.770270 0.637718 -v -0.061799 -0.019000 0.186289 -vn -0.318871 0.770253 0.552297 -v -0.061174 -0.015300 0.186457 -vn -0.318871 -0.770253 0.552297 -v -0.061174 -0.019000 0.186457 -vn -0.552280 0.770268 0.318864 -v -0.060717 -0.015300 0.186914 -vn -0.552279 -0.770268 0.318864 -v -0.060717 -0.019000 0.186914 -vn -0.717940 -0.630896 0.294163 -v -0.065549 0.017300 0.188078 -vn -0.717941 0.630896 0.294163 -v -0.065549 0.019000 0.188078 -vn -0.904534 -0.301511 0.301512 -v -0.065549 0.017300 0.184539 -vn -0.577350 0.577350 -0.577350 -v -0.065549 0.019000 0.182539 -vn -0.904534 0.301510 0.301511 -v -0.065549 -0.015300 0.184539 -vn -0.577350 -0.577350 -0.577350 -v -0.065549 -0.019000 0.182539 -vn -0.717940 0.630896 0.294163 -v -0.065549 -0.015300 0.188078 -vn -0.717940 -0.630896 0.294163 -v -0.065549 -0.019000 0.188078 -vn 0.707105 0.707108 0.000000 -v -0.013049 0.019000 0.190289 -vn 0.577350 -0.577350 -0.577350 -v -0.013049 -0.019000 0.188700 -vn 0.577350 0.577351 -0.577350 -v -0.013049 0.019000 0.188700 -vn 0.707106 -0.707107 -0.000000 -v -0.013049 -0.019000 0.190289 -vn 0.318866 0.552288 -0.770261 -v -0.023469 0.008551 0.188700 -vn 0.000002 0.637727 -0.770262 -v -0.022344 0.008250 0.188700 -vn 0.000003 -1.000000 0.000000 -v -0.022344 -0.008250 0.188700 -vn 0.000003 1.000000 0.000000 -v -0.022344 -0.012750 0.188700 -vn -0.318863 0.552289 -0.770262 -v -0.021219 -0.012449 0.188700 -vn 0.318866 -0.552288 -0.770261 -v -0.023469 0.012449 0.188700 -vn 0.301511 0.904534 -0.301512 -v -0.035049 0.019000 0.188700 -vn 0.000002 -0.637727 -0.770262 -v -0.022344 0.012750 0.188700 -vn -0.318863 -0.552288 -0.770262 -v -0.021219 0.012449 0.188700 -vn -0.866024 -0.500003 -0.000000 -v -0.020395 0.011625 0.188700 -vn 0.866024 -0.500003 0.000000 -v -0.024293 0.011625 0.188700 -vn 1.000000 0.000000 0.000000 -v -0.024594 0.010500 0.188700 -vn 0.301511 -0.904534 -0.301511 -v -0.035049 -0.019000 0.188700 -vn 0.552288 0.318866 -0.770261 -v -0.024293 0.009375 0.188700 -vn 0.318865 0.552288 -0.770261 -v -0.023469 -0.012449 0.188700 -vn 0.866024 0.500003 0.000000 -v -0.024293 -0.011625 0.188700 -vn -0.499999 -0.866026 -0.000000 -v -0.021219 -0.008551 0.188700 -vn 0.500002 -0.866024 0.000000 -v -0.023469 -0.008551 0.188700 -vn 0.866024 -0.500003 0.000000 -v -0.024293 -0.009375 0.188700 -vn 1.000000 -0.000000 0.000000 -v -0.024594 -0.010500 0.188700 -vn -0.866024 0.500003 0.000000 -v -0.020395 -0.011625 0.188700 -vn -1.000000 -0.000000 -0.000000 -v -0.020094 -0.010500 0.188700 -vn -0.866024 -0.500003 -0.000000 -v -0.020395 -0.009375 0.188700 -vn -0.318863 0.552288 -0.770262 -v -0.021219 0.008551 0.188700 -vn -0.552288 0.318866 -0.770261 -v -0.020395 0.009375 0.188700 -vn -1.000000 0.000000 -0.000000 -v -0.020094 0.010500 0.188700 -vn 0.577350 0.577350 -0.577350 -v -0.035049 0.019000 0.182539 -vn 0.577350 -0.577350 -0.577350 -v -0.035049 -0.019000 0.182539 -vn 0.318873 0.770259 0.552288 -v -0.062424 0.019000 0.186457 -vn -0.000004 0.770270 0.637718 -v -0.061799 0.019000 0.186289 -vn 0.318877 0.770257 -0.552288 -v -0.054424 0.019000 0.188622 -vn -0.300052 0.629631 0.716612 -v -0.063421 0.019000 0.190239 -vn 0.000004 0.770270 -0.637718 -v -0.053799 0.019000 0.188789 -vn -0.301511 0.904534 0.301511 -v -0.043549 0.019000 0.190239 -vn -0.318871 0.770253 0.552297 -v -0.061174 0.019000 0.186457 -vn 0.637721 0.770268 0.000000 -v -0.055049 0.019000 0.187539 -vn 0.552288 0.770259 0.318873 -v -0.054882 0.019000 0.186914 -vn 0.318877 0.770257 0.552287 -v -0.054424 0.019000 0.186457 -vn 0.000004 0.770270 0.637718 -v -0.053799 0.019000 0.186289 -vn -0.318877 0.770257 0.552288 -v -0.045174 0.019000 0.186457 -vn -0.552288 0.770259 0.318873 -v -0.044717 0.019000 0.186914 -vn -0.000000 0.707106 -0.707107 -v -0.043174 0.019000 0.182539 -vn -0.318873 0.770259 0.552288 -v -0.053174 0.019000 0.186457 -vn 0.637735 0.770256 0.000000 -v -0.047049 0.019000 0.187539 -vn 0.552289 0.770264 0.318857 -v -0.046882 0.019000 0.186914 -vn 0.318873 0.770259 0.552288 -v -0.046424 0.019000 0.186457 -vn -0.000004 0.770270 0.637718 -v -0.045799 0.019000 0.186289 -vn -0.637720 0.770268 -0.000000 -v -0.044549 0.019000 0.187539 -vn -0.552288 0.770259 -0.318873 -v -0.044717 0.019000 0.188164 -vn -0.552289 0.770264 0.318857 -v -0.052717 0.019000 0.186914 -vn 0.318873 0.770259 -0.552288 -v -0.046424 0.019000 0.188622 -vn 0.552289 0.770264 -0.318857 -v -0.046882 0.019000 0.188164 -vn -0.318877 0.770257 -0.552288 -v -0.045174 0.019000 0.188622 -vn -0.000004 0.770270 -0.637718 -v -0.045799 0.019000 0.188789 -vn 0.318873 0.770259 -0.552288 -v -0.062424 0.019000 0.188622 -vn -0.637734 0.770257 0.000000 -v -0.052549 0.019000 0.187539 -vn -0.552289 0.770264 -0.318857 -v -0.052717 0.019000 0.188164 -vn -0.318873 0.770259 -0.552288 -v -0.053174 0.019000 0.188622 -vn 0.552289 0.770265 -0.318857 -v -0.062882 0.019000 0.188164 -vn 0.637733 0.770257 0.000000 -v -0.063049 0.019000 0.187539 -vn 0.552289 0.770264 0.318857 -v -0.062882 0.019000 0.186914 -vn -0.552279 0.770268 0.318864 -v -0.060717 0.019000 0.186914 -vn -0.637734 0.770257 0.000000 -v -0.060549 0.019000 0.187539 -vn 0.552288 0.770259 -0.318873 -v -0.054882 0.019000 0.188164 -vn -0.552280 0.770268 -0.318864 -v -0.060717 0.019000 0.188164 -vn -0.318871 0.770253 -0.552297 -v -0.061174 0.019000 0.188622 -vn -0.000004 0.770270 -0.637718 -v -0.061799 0.019000 0.188789 -vn -0.000000 1.000000 -0.000000 -v -0.043174 0.019000 0.190289 -vn 0.318877 0.770257 0.552288 -v -0.041174 0.019000 0.191957 -vn 0.000004 0.770270 0.637718 -v -0.040549 0.019000 0.191789 -vn 0.318877 0.770257 -0.552288 -v -0.041174 0.019000 0.210122 -vn 0.552288 0.770259 -0.318873 -v -0.041632 0.019000 0.209664 -vn 0.000000 0.707107 0.707107 -v -0.043174 0.019000 0.212289 -vn 0.637720 0.770268 0.000000 -v -0.041799 0.019000 0.209039 -vn 0.552288 0.770259 0.318873 -v -0.041632 0.019000 0.208414 -vn 0.318846 0.770268 0.552290 -v -0.041174 0.019000 0.207957 -vn -0.318873 0.770258 0.552288 -v -0.039924 0.019000 0.191957 -vn -0.552288 0.770259 0.318873 -v -0.039467 0.019000 0.192414 -vn -0.637720 0.770268 -0.000000 -v -0.039299 0.019000 0.209039 -vn -0.552288 0.770259 0.318873 -v -0.039467 0.019000 0.208414 -vn -0.318842 0.770270 0.552290 -v -0.039924 0.019000 0.207957 -vn -0.552288 0.770259 -0.318873 -v -0.039467 0.019000 0.209664 -vn -0.318873 0.770259 -0.552288 -v -0.039924 0.019000 0.210122 -vn 0.000004 0.770270 -0.637718 -v -0.040549 0.019000 0.210289 -vn 0.318859 0.770277 -0.552271 -v -0.041174 0.019000 0.194122 -vn 0.000004 0.770247 -0.637746 -v -0.040549 0.019000 0.194289 -vn 0.000004 0.770247 0.637746 -v -0.040549 0.019000 0.207789 -vn -0.318854 0.770278 -0.552271 -v -0.039924 0.019000 0.194122 -vn -0.552306 0.770247 -0.318868 -v -0.039467 0.019000 0.193664 -vn -0.637716 0.770271 -0.000008 -v -0.039299 0.019000 0.193039 -vn 0.552306 0.770247 -0.318868 -v -0.041632 0.019000 0.193664 -vn 0.637716 0.770271 -0.000008 -v -0.041799 0.019000 0.193039 -vn 0.552288 0.770259 0.318873 -v -0.041632 0.019000 0.192414 -vn -0.577350 0.577350 0.577350 -v -0.043549 0.019000 0.212289 -vn -0.707107 0.707107 0.000000 -v -0.043549 0.019000 0.190289 -vn -0.301512 -0.904534 0.301511 -v -0.043549 -0.019000 0.190239 -vn -0.300052 -0.629631 0.716613 -v -0.063421 -0.019000 0.190239 -vn 0.000000 -1.000000 0.000000 -v -0.043174 -0.019000 0.190289 -vn -0.707107 -0.707107 0.000000 -v -0.043549 -0.019000 0.190289 -vn 0.000000 -0.707106 -0.707107 -v -0.043174 -0.019000 0.182539 -vn 0.000000 -0.707107 0.707107 -v -0.043174 -0.019000 0.212289 -vn -0.577350 -0.577350 0.577350 -v -0.043549 -0.019000 0.212289 -vn -0.637720 -0.770268 0.000000 -v -0.039299 0.017300 0.209039 -vn -0.552288 -0.770259 -0.318873 -v -0.039467 0.017300 0.209664 -vn -0.318873 -0.770259 -0.552288 -v -0.039924 0.017300 0.210122 -vn 0.000004 -0.770270 -0.637718 -v -0.040549 0.017300 0.210289 -vn 0.318877 -0.770257 -0.552288 -v -0.041174 0.017300 0.210122 -vn 0.552288 -0.770259 -0.318873 -v -0.041632 0.017300 0.209664 -vn 0.637720 -0.770268 0.000000 -v -0.041799 0.017300 0.209039 -vn 0.552288 -0.770259 0.318873 -v -0.041632 0.017300 0.208414 -vn 0.318846 -0.770268 0.552290 -v -0.041174 0.017300 0.207957 -vn 0.000004 -0.770247 0.637746 -v -0.040549 0.017300 0.207789 -vn -0.318841 -0.770270 0.552290 -v -0.039924 0.017300 0.207957 -vn -0.552288 -0.770259 0.318873 -v -0.039467 0.017300 0.208414 -vn -0.637716 -0.770271 -0.000008 -v -0.039299 0.017300 0.193039 -vn -0.552306 -0.770247 -0.318868 -v -0.039467 0.017300 0.193664 -vn -0.318854 -0.770278 -0.552271 -v -0.039924 0.017300 0.194122 -vn 0.000004 -0.770247 -0.637746 -v -0.040549 0.017300 0.194289 -vn 0.318859 -0.770277 -0.552271 -v -0.041174 0.017300 0.194122 -vn 0.552306 -0.770247 -0.318868 -v -0.041632 0.017300 0.193664 -vn 0.637716 -0.770271 -0.000008 -v -0.041799 0.017300 0.193039 -vn 0.552288 -0.770259 0.318873 -v -0.041632 0.017300 0.192414 -vn 0.318877 -0.770257 0.552288 -v -0.041174 0.017300 0.191957 -vn 0.000004 -0.770270 0.637718 -v -0.040549 0.017300 0.191789 -vn -0.318873 -0.770259 0.552288 -v -0.039924 0.017300 0.191957 -vn -0.552288 -0.770259 0.318873 -v -0.039467 0.017300 0.192414 -vn -0.637720 -0.770268 0.000000 -v -0.044549 0.017300 0.187539 -vn -0.552288 -0.770259 -0.318873 -v -0.044717 0.017300 0.188164 -vn -0.318877 -0.770257 -0.552287 -v -0.045174 0.017300 0.188622 -vn -0.000004 -0.770270 -0.637718 -v -0.045799 0.017300 0.188789 -vn 0.318873 -0.770259 -0.552288 -v -0.046424 0.017300 0.188622 -vn 0.552289 -0.770264 -0.318857 -v -0.046882 0.017300 0.188164 -vn 0.637734 -0.770257 0.000000 -v -0.047049 0.017300 0.187539 -vn 0.552289 -0.770264 0.318857 -v -0.046882 0.017300 0.186914 -vn 0.318873 -0.770259 0.552288 -v -0.046424 0.017300 0.186457 -vn -0.000004 -0.770270 0.637718 -v -0.045799 0.017300 0.186289 -vn -0.318877 -0.770257 0.552288 -v -0.045174 0.017300 0.186457 -vn -0.552288 -0.770259 0.318873 -v -0.044717 0.017300 0.186914 -vn -0.637735 -0.770256 0.000000 -v -0.052549 0.017300 0.187539 -vn -0.552289 -0.770264 -0.318857 -v -0.052717 0.017300 0.188164 -vn -0.318873 -0.770258 -0.552288 -v -0.053174 0.017300 0.188622 -vn 0.000004 -0.770270 -0.637718 -v -0.053799 0.017300 0.188789 -vn 0.318877 -0.770257 -0.552288 -v -0.054424 0.017300 0.188622 -vn 0.552288 -0.770259 -0.318873 -v -0.054882 0.017300 0.188164 -vn 0.637720 -0.770268 0.000000 -v -0.055049 0.017300 0.187539 -vn 0.552288 -0.770259 0.318873 -v -0.054882 0.017300 0.186914 -vn 0.318877 -0.770257 0.552288 -v -0.054424 0.017300 0.186457 -vn 0.000004 -0.770270 0.637718 -v -0.053799 0.017300 0.186289 -vn -0.318873 -0.770259 0.552288 -v -0.053174 0.017300 0.186457 -vn -0.552289 -0.770264 0.318857 -v -0.052717 0.017300 0.186914 -vn -0.637734 -0.770257 0.000000 -v -0.060549 0.017300 0.187539 -vn -0.552280 -0.770268 -0.318864 -v -0.060717 0.017300 0.188164 -vn -0.318870 -0.770253 -0.552297 -v -0.061174 0.017300 0.188622 -vn -0.000004 -0.770270 -0.637718 -v -0.061799 0.017300 0.188789 -vn 0.318873 -0.770259 -0.552288 -v -0.062424 0.017300 0.188622 -vn 0.552289 -0.770264 -0.318857 -v -0.062882 0.017300 0.188164 -vn 0.637734 -0.770257 0.000000 -v -0.063049 0.017300 0.187539 -vn 0.552289 -0.770264 0.318857 -v -0.062882 0.017300 0.186914 -vn 0.318873 -0.770258 0.552288 -v -0.062424 0.017300 0.186457 -vn -0.000004 -0.770269 0.637719 -v -0.061799 0.017300 0.186289 -vn -0.318871 -0.770253 0.552297 -v -0.061174 0.017300 0.186457 -vn -0.552280 -0.770268 0.318864 -v -0.060717 0.017300 0.186914 -vn 0.000000 -1.000000 0.000000 -v -0.043174 0.017300 0.190289 -vn -0.707107 -0.707107 0.000000 -v -0.043549 0.017300 0.190289 -vn -0.301511 -0.904534 0.301512 -v -0.043549 0.017300 0.190239 -vn -0.300052 -0.629631 0.716613 -v -0.063421 0.017300 0.190239 -vn -0.306472 -0.628261 0.715097 -v -0.042549 0.017300 0.184539 -vn 0.000000 -0.707107 0.707107 -v -0.043174 0.017300 0.184539 -vn -0.719323 -0.632288 0.287727 -v -0.037549 0.017300 0.189789 -vn -0.707107 -0.707107 0.000000 -v -0.037549 0.017300 0.190289 -vn 0.000000 -0.707107 0.707107 -v -0.043174 0.017300 0.212289 -vn -0.301511 -0.301511 0.904534 -v -0.037549 0.017300 0.212289 -vn -0.577350 -0.577350 0.577350 -v -0.043549 0.017300 0.212289 -vn -0.300052 0.629631 0.716612 -v -0.063421 -0.015300 0.190239 -vn -0.301511 0.904534 0.301511 -v -0.043549 -0.015300 0.190239 -vn -0.000000 0.707107 0.707107 -v -0.043174 -0.015300 0.184539 -vn 0.000000 1.000000 0.000000 -v -0.043174 -0.015300 0.190289 -vn -0.707107 0.707106 0.000000 -v -0.043549 -0.015300 0.190289 -vn 0.000000 0.707106 0.707108 -v -0.043174 -0.015300 0.212289 -vn -0.577350 0.577350 0.577350 -v -0.043549 -0.015300 0.212289 -vn -0.306472 0.628261 0.715097 -v -0.042549 -0.015300 0.184539 -vn -0.719323 0.632288 0.287727 -v -0.037549 -0.015300 0.189789 -vn -0.707106 0.707107 0.000000 -v -0.037549 -0.015300 0.190289 -vn -0.301511 0.301511 0.904534 -v -0.037549 -0.015300 0.212289 -vn 0.577350 0.577350 0.577351 -v -0.031639 -0.015000 0.193700 -vn 0.577350 -0.577350 0.577350 -v -0.031639 0.015000 0.193700 -vn -0.637726 -0.000000 0.770263 -v -0.020094 -0.010500 0.193700 -vn -0.552288 0.318866 0.770261 -v -0.020395 -0.011625 0.193700 -vn -0.318863 0.552289 0.770262 -v -0.021219 -0.012449 0.193700 -vn 0.000002 0.637728 0.770262 -v -0.022344 -0.012750 0.193700 -vn 0.318865 0.552288 0.770261 -v -0.023469 -0.012449 0.193700 -vn 0.552288 0.318866 0.770261 -v -0.024293 -0.011625 0.193700 -vn 0.637726 -0.000000 0.770263 -v -0.024594 -0.010500 0.193700 -vn 0.552288 -0.318866 0.770261 -v -0.024293 0.011625 0.193700 -vn 0.318866 -0.552288 0.770261 -v -0.023469 0.012449 0.193700 -vn 0.000002 -0.637727 0.770262 -v -0.022344 0.012750 0.193700 -vn -0.318863 -0.552289 0.770262 -v -0.021219 0.012449 0.193700 -vn -0.552288 -0.318866 0.770261 -v -0.020395 0.011625 0.193700 -vn 0.552288 -0.318866 0.770261 -v -0.024293 -0.009375 0.193700 -vn 0.000002 0.637727 0.770262 -v -0.022344 0.008250 0.193700 -vn 0.318866 0.552288 0.770261 -v -0.023469 0.008551 0.193700 -vn 0.552288 0.318866 0.770261 -v -0.024293 0.009375 0.193700 -vn 0.637726 0.000000 0.770263 -v -0.024594 0.010500 0.193700 -vn -0.552288 -0.318866 0.770261 -v -0.020395 -0.009375 0.193700 -vn -0.318863 -0.552289 0.770262 -v -0.021219 -0.008551 0.193700 -vn -0.637726 -0.000000 0.770263 -v -0.020094 0.010500 0.193700 -vn -0.552288 0.318866 0.770261 -v -0.020395 0.009375 0.193700 -vn -0.318863 0.552289 0.770262 -v -0.021219 0.008551 0.193700 -vn 0.000002 -0.637727 0.770262 -v -0.022344 -0.008250 0.193700 -vn 0.318866 -0.552288 0.770261 -v -0.023469 -0.008551 0.193700 -vn -0.301511 0.904534 -0.301512 -v -0.023049 0.040000 0.168800 -vn 0.904534 0.301511 -0.301511 -v -0.013049 0.040000 0.168800 -vn 0.900770 0.310542 0.303606 -v -0.013049 0.040000 0.149241 -vn -0.717100 0.696970 -0.000215 -v -0.088049 0.040000 0.146622 -vn -0.034953 0.696308 0.716891 -v -0.050981 0.040000 0.188700 -vn -0.301511 0.301511 0.904534 -v -0.023049 0.040000 0.188700 -vn -0.581070 0.576730 -0.574230 -v -0.091008 0.040000 0.146622 -vn -0.716427 0.696309 0.043437 -v -0.090978 0.040000 0.149173 -vn -0.712249 0.685853 0.149358 -v -0.090129 0.040000 0.156909 -vn -0.669847 0.685852 0.284451 -v -0.087799 0.040000 0.164335 -vn -0.401622 0.685852 0.606883 -v -0.073056 0.040000 0.182057 -vn -0.276502 0.685852 0.673167 -v -0.066179 0.040000 0.185700 -vn -0.140918 0.685853 0.713966 -v -0.058726 0.040000 0.187943 -vn -0.602086 0.685853 0.408777 -v -0.084074 0.040000 0.171168 -vn -0.511536 0.685853 0.517626 -v -0.079097 0.040000 0.177151 -vn 0.577351 0.577350 -0.577350 -v -0.084785 0.040000 0.084039 -vn -0.577350 0.577350 -0.577351 -v -0.091549 0.040000 0.084039 -vn 0.301511 0.904535 -0.301509 -v -0.084785 0.040000 0.090039 -vn -0.708422 0.705777 0.004194 -v -0.091549 0.040000 0.100883 -vn -0.171823 0.895921 -0.409636 -v -0.046007 0.040000 0.133465 -vn 0.900770 0.310542 -0.303606 -v -0.013049 0.040000 0.133241 -vn 0.706068 0.708116 -0.006369 -v -0.013049 0.040000 0.121017 -vn 0.047655 0.685231 -0.726765 -v -0.080980 0.040000 0.135613 -vn -0.000898 0.693181 -0.720763 -v -0.077340 0.040000 0.126887 -vn -0.051681 0.007354 -0.998637 -v -0.085285 0.040000 0.127399 -vn 0.195537 0.757445 -0.622930 -v -0.084451 0.040000 0.127477 -vn -0.129107 0.719839 0.682028 -v -0.057950 0.040000 0.102625 -vn -0.204513 0.719963 0.663195 -v -0.047035 0.040000 0.105331 -vn 0.037426 0.991110 -0.127672 -v -0.047812 0.040000 0.103008 -vn -0.547969 0.573151 0.609285 -v -0.091536 0.040000 0.102011 -vn 0.026275 0.719962 0.693516 -v -0.080341 0.040000 0.100955 -vn 0.577350 0.577351 -0.577351 -v -0.059785 0.040000 0.090039 -vn -0.055706 0.717686 0.694135 -v -0.069098 0.040000 0.101161 -vn 0.036103 0.998239 -0.047065 -v -0.059785 0.040000 0.100268 -vn 0.031587 0.991324 -0.127587 -v -0.053916 0.040000 0.101422 -vn 0.073174 0.991200 -0.110309 -v -0.019384 0.040000 0.116375 -vn 0.067503 0.991110 -0.114646 -v -0.024718 0.040000 0.113009 -vn -0.396922 0.905297 0.151296 -v -0.035299 0.040000 0.109772 -vn 0.060302 0.991110 -0.118596 -v -0.030248 0.040000 0.109978 -vn -0.263914 0.714228 0.648250 -v -0.036493 0.040000 0.109242 -vn 0.052868 0.991110 -0.122090 -v -0.035956 0.040000 0.107295 -vn 0.045233 0.991110 -0.125119 -v -0.041818 0.040000 0.104969 -vn 0.433614 0.757453 -0.488102 -v -0.083721 0.040000 0.127890 -vn 0.595554 0.757454 -0.267542 -v -0.083225 0.040000 0.128566 -vn 0.096836 0.691156 -0.716189 -v -0.066613 0.040000 0.127552 -vn 0.677933 0.731607 -0.071822 -v -0.083049 0.040000 0.129386 -vn 0.199338 0.691154 -0.694672 -v -0.056096 0.040000 0.129760 -vn 0.724657 0.685235 -0.072976 -v -0.083049 0.040000 0.133614 -vn 0.687582 0.664871 -0.291852 -v -0.082890 0.040000 0.134395 -vn 0.518888 0.664857 -0.537327 -v -0.082439 0.040000 0.135053 -vn 0.267688 0.664875 -0.697341 -v -0.081766 0.040000 0.135481 -vn -0.170482 -0.896463 -0.409012 -v -0.046007 -0.040000 0.133465 -vn 0.900770 -0.310542 -0.303606 -v -0.013049 -0.040000 0.133241 -vn 0.047655 -0.685231 -0.726765 -v -0.080980 -0.040000 0.135613 -vn 0.033862 -0.716405 0.696863 -v -0.080341 -0.040000 0.100955 -vn -0.547969 -0.573151 0.609285 -v -0.091536 -0.040000 0.102011 -vn -0.708422 -0.705777 0.004194 -v -0.091549 -0.040000 0.100883 -vn -0.048491 -0.022271 -0.998575 -v -0.085285 -0.040000 0.127399 -vn 0.011832 -0.692122 -0.721683 -v -0.075339 -0.040000 0.126893 -vn 0.195537 -0.757445 -0.622930 -v -0.084451 -0.040000 0.127477 -vn 0.433614 -0.757453 -0.488102 -v -0.083721 -0.040000 0.127890 -vn -0.056984 -0.717350 0.694378 -v -0.069098 -0.040000 0.101161 -vn 0.301511 -0.904534 -0.301511 -v -0.084785 -0.040000 0.090039 -vn 0.577351 -0.577350 -0.577350 -v -0.084785 -0.040000 0.084039 -vn -0.577350 -0.577350 -0.577351 -v -0.091549 -0.040000 0.084039 -vn 0.577350 -0.577348 -0.577353 -v -0.059785 -0.040000 0.090039 -vn 0.025180 -0.999152 -0.032588 -v -0.059785 -0.040000 0.100268 -vn -0.129107 -0.719839 0.682029 -v -0.057950 -0.040000 0.102625 -vn -0.204513 -0.719963 0.663195 -v -0.047035 -0.040000 0.105331 -vn 0.702007 -0.711358 -0.034007 -v -0.013049 -0.040000 0.121017 -vn 0.055745 -0.994925 -0.083767 -v -0.019887 -0.040000 0.116038 -vn 0.048448 -0.994920 -0.088243 -v -0.027386 -0.040000 0.111492 -vn -0.396922 -0.905297 0.151295 -v -0.035299 -0.040000 0.109772 -vn 0.040700 -0.994920 -0.092071 -v -0.035247 -0.040000 0.107605 -vn -0.263914 -0.714227 0.648251 -v -0.036493 -0.040000 0.109242 -vn 0.032653 -0.994920 -0.095221 -v -0.043413 -0.040000 0.104407 -vn 0.025422 -0.994999 -0.096592 -v -0.051823 -0.040000 0.101921 -vn 0.205314 -0.692122 -0.691963 -v -0.055456 -0.040000 0.129947 -vn 0.724657 -0.685235 -0.072976 -v -0.083049 -0.040000 0.133614 -vn 0.109559 -0.692122 -0.713418 -v -0.065293 -0.040000 0.127742 -vn 0.677933 -0.731607 -0.071822 -v -0.083049 -0.040000 0.129386 -vn 0.595554 -0.757454 -0.267542 -v -0.083225 -0.040000 0.128566 -vn 0.518888 -0.664857 -0.537327 -v -0.082439 -0.040000 0.135053 -vn 0.687582 -0.664871 -0.291852 -v -0.082890 -0.040000 0.134395 -vn 0.267688 -0.664875 -0.697341 -v -0.081766 -0.040000 0.135481 -vn -0.726993 0.680939 -0.088335 -v -0.088049 -0.037000 0.130393 -vn -0.301511 0.904534 -0.301511 -v -0.088049 -0.037000 0.146622 -vn -0.034953 0.696308 0.716891 -v -0.050981 -0.037000 0.188700 -vn -0.102478 0.994230 -0.031692 -v -0.019295 -0.037000 0.178825 -vn -0.102637 0.994686 -0.008107 -v -0.019049 -0.037000 0.177200 -vn 0.021156 0.994423 -0.103318 -v -0.025797 -0.037000 0.182557 -vn -0.694333 0.678884 -0.238786 -v -0.036123 -0.037000 0.111595 -vn -0.170482 0.896462 -0.409013 -v -0.046007 -0.037000 0.133465 -vn -0.047642 0.994967 0.088157 -v -0.029883 -0.037000 0.114686 -vn -0.053340 0.994989 0.084565 -v -0.023877 -0.037000 0.118212 -vn -0.000028 1.000000 -0.000059 -v -0.028549 -0.037000 0.180975 -vn 0.040237 0.996131 -0.078126 -v -0.027324 -0.037000 0.181949 -vn -0.087705 0.670658 0.736564 -v -0.028549 -0.037000 0.188700 -vn -0.038900 0.994230 -0.099972 -v -0.022555 -0.037000 0.182326 -vn -0.066699 0.994230 -0.084016 -v -0.021130 -0.037000 0.181508 -vn -0.088540 0.994230 -0.060556 -v -0.020010 -0.037000 0.180305 -vn -0.427827 0.656969 -0.620770 -v -0.086752 -0.037000 0.127922 -vn -0.667439 0.656962 -0.350609 -v -0.087705 -0.037000 0.128998 -vn -0.151909 0.674384 -0.722586 -v -0.085408 -0.037000 0.127414 -vn 0.011777 0.692122 -0.721685 -v -0.075339 -0.037000 0.126893 -vn 0.109559 0.692122 -0.713418 -v -0.065293 -0.037000 0.127742 -vn 0.205314 0.692122 -0.691963 -v -0.055456 -0.037000 0.129947 -vn -0.581070 0.576730 -0.574230 -v -0.091008 -0.037000 0.146622 -vn -0.716427 0.696309 0.043437 -v -0.090978 -0.037000 0.149173 -vn -0.712249 0.685853 0.149358 -v -0.090129 -0.037000 0.156909 -vn -0.669847 0.685852 0.284451 -v -0.087799 -0.037000 0.164335 -vn -0.401622 0.685852 0.606883 -v -0.073056 -0.037000 0.182057 -vn -0.276502 0.685852 0.673167 -v -0.066179 -0.037000 0.185700 -vn -0.140918 0.685853 0.713966 -v -0.058726 -0.037000 0.187943 -vn -0.001080 0.999999 0.000583 -v -0.019049 -0.037000 0.121488 -vn -0.007621 0.994231 -0.106990 -v -0.024159 -0.037000 0.182686 -vn -0.602086 0.685853 0.408777 -v -0.084074 -0.037000 0.171168 -vn -0.511536 0.685853 0.517626 -v -0.079097 -0.037000 0.177151 -vn -0.997440 0.038671 -0.060154 -v -0.088049 0.040000 0.130393 -vn -0.569946 0.765195 -0.299395 -v -0.087705 0.040000 0.128998 -vn -0.611622 0.584941 -0.532694 -v -0.088049 0.040000 0.127780 -vn -0.365344 0.765186 -0.530107 -v -0.086752 0.040000 0.127922 -vn -0.180790 0.029646 -0.983075 -v -0.085408 0.040000 0.127414 -vn -0.547969 -0.573151 0.609285 -v -0.091536 0.037000 0.102011 -vn -0.904168 -0.299127 0.304965 -v -0.091549 0.037000 0.100883 -vn 0.028425 -0.719823 0.693576 -v -0.080341 0.037000 0.100955 -vn -0.003038 -0.064147 0.997936 -v -0.076549 0.037000 0.100883 -vn -0.716427 -0.696309 0.043437 -v -0.090978 0.037000 0.149173 -vn -0.581070 -0.576730 -0.574230 -v -0.091008 0.037000 0.146622 -vn -0.301511 -0.904534 -0.301511 -v -0.088049 0.037000 0.146622 -vn -0.712249 -0.685853 0.149358 -v -0.090129 0.037000 0.156909 -vn -0.053340 -0.994989 0.084565 -v -0.023877 0.037000 0.118212 -vn -0.171823 -0.895922 -0.409635 -v -0.046007 0.037000 0.133465 -vn -0.047642 -0.994967 0.088157 -v -0.029883 0.037000 0.114686 -vn -0.694333 -0.678883 -0.238786 -v -0.036123 0.037000 0.111595 -vn -0.034953 -0.696308 0.716891 -v -0.050981 0.037000 0.188700 -vn 0.096836 -0.691156 -0.716189 -v -0.066613 0.037000 0.127552 -vn 0.199338 -0.691155 -0.694672 -v -0.056096 0.037000 0.129760 -vn -0.140918 -0.685853 0.713966 -v -0.058726 0.037000 0.187943 -vn -0.602871 -0.586902 -0.540456 -v -0.088049 0.037000 0.127780 -vn -0.002454 -0.693136 -0.720802 -v -0.077340 0.037000 0.126887 -vn -0.084706 -0.672964 0.734809 -v -0.028549 0.037000 0.188700 -vn -0.000028 -1.000000 -0.000059 -v -0.028549 0.037000 0.180975 -vn 0.035420 -0.994178 -0.101765 -v -0.027324 0.037000 0.181949 -vn 0.024328 -0.994230 -0.104472 -v -0.025797 0.037000 0.182557 -vn -0.001080 -0.999999 0.000583 -v -0.019049 0.037000 0.121488 -vn -0.102637 -0.994686 -0.008108 -v -0.019049 0.037000 0.177200 -vn -0.088540 -0.994230 -0.060555 -v -0.020010 0.037000 0.180305 -vn -0.066698 -0.994230 -0.084016 -v -0.021130 0.037000 0.181508 -vn -0.038898 -0.994229 -0.099975 -v -0.022555 0.037000 0.182326 -vn -0.276502 -0.685852 0.673167 -v -0.066179 0.037000 0.185700 -vn -0.401622 -0.685852 0.606883 -v -0.073056 0.037000 0.182057 -vn -0.511536 -0.685853 0.517626 -v -0.079097 0.037000 0.177151 -vn -0.102479 -0.994230 -0.031692 -v -0.019295 0.037000 0.178825 -vn -0.007625 -0.994231 -0.106991 -v -0.024159 0.037000 0.182686 -vn -0.602086 -0.685853 0.408777 -v -0.084074 0.037000 0.171168 -vn -0.669847 -0.685852 0.284451 -v -0.087799 0.037000 0.164335 -vn -0.716427 -0.696309 0.043437 -v -0.090978 -0.040000 0.149173 -vn -0.581070 -0.576730 -0.574230 -v -0.091008 -0.040000 0.146622 -vn -0.717100 -0.696970 -0.000214 -v -0.088049 -0.040000 0.146622 -vn 0.900770 -0.310542 0.303606 -v -0.013049 -0.040000 0.149241 -vn 0.904533 -0.301513 -0.301513 -v -0.013049 -0.040000 0.168800 -vn -0.301511 -0.904534 -0.301512 -v -0.023049 -0.040000 0.168800 -vn -0.712249 -0.685853 0.149358 -v -0.090129 -0.040000 0.156909 -vn -0.301511 -0.301511 0.904534 -v -0.023049 -0.040000 0.188700 -vn -0.034953 -0.696308 0.716891 -v -0.050981 -0.040000 0.188700 -vn -0.140918 -0.685853 0.713966 -v -0.058726 -0.040000 0.187943 -vn -0.276502 -0.685852 0.673167 -v -0.066179 -0.040000 0.185700 -vn -0.401622 -0.685852 0.606883 -v -0.073056 -0.040000 0.182057 -vn -0.511536 -0.685853 0.517626 -v -0.079097 -0.040000 0.177151 -vn -0.602086 -0.685853 0.408777 -v -0.084074 -0.040000 0.171168 -vn -0.669847 -0.685852 0.284451 -v -0.087799 -0.040000 0.164335 -vn 0.904536 -0.301508 0.301509 -v -0.013049 -0.025000 0.188700 -vn -0.060527 -0.997536 0.035484 -v -0.028549 -0.025000 0.188700 -vn -0.323470 -0.561612 0.761550 -v -0.026549 -0.025536 0.188700 -vn -0.669354 0.088119 0.737699 -v -0.024549 -0.033000 0.188700 -vn -0.553355 0.320377 0.768867 -v -0.025085 -0.035000 0.188700 -vn -0.088122 -0.669353 0.737700 -v -0.018049 -0.041000 0.188700 -vn -0.318864 -0.552288 0.770262 -v -0.016049 -0.041536 0.188700 -vn -0.577350 -0.577350 0.577350 -v -0.014049 -0.050000 0.188700 -vn 0.577350 -0.577350 0.577350 -v -0.013049 -0.050000 0.188700 -vn -0.669352 -0.088123 0.737701 -v -0.014049 -0.045000 0.188700 -vn -0.552289 -0.318865 0.770261 -v -0.014585 -0.043000 0.188700 -vn -0.561938 -0.324640 0.760812 -v -0.025085 -0.027000 0.188700 -vn -0.675526 -0.081640 0.732803 -v -0.024549 -0.029000 0.188700 -vn -0.577350 -0.577350 0.577350 -v -0.023049 -0.041000 0.188700 -vn -0.319266 0.554323 0.768632 -v -0.026549 -0.036464 0.188700 -vn -0.904534 0.301511 0.301511 -v -0.034549 -0.019300 0.188700 -vn 0.552288 0.318866 0.770261 -v -0.024293 0.009375 0.188700 -vn -0.904534 -0.301511 0.301512 -v -0.034549 0.019300 0.188700 -vn -0.318863 0.552289 0.770262 -v -0.021219 -0.012449 0.188700 -vn 0.904534 0.301511 0.301511 -v -0.013049 -0.019300 0.188700 -vn 0.318866 0.552289 0.770261 -v -0.023469 -0.012449 0.188700 -vn 0.318866 0.552288 0.770261 -v -0.023469 0.008551 0.188700 -vn 0.318866 -0.552288 0.770261 -v -0.023469 0.012449 0.188700 -vn 0.904534 -0.301511 0.301510 -v -0.013049 0.019300 0.188700 -vn 0.000002 -0.637727 0.770262 -v -0.022344 0.012750 0.188700 -vn -0.318863 -0.552289 0.770262 -v -0.021219 0.012449 0.188700 -vn 0.000002 0.637727 0.770262 -v -0.022344 0.008250 0.188700 -vn -0.318863 0.552289 0.770262 -v -0.021219 0.008551 0.188700 -vn -0.552288 0.318866 0.770261 -v -0.020395 0.009375 0.188700 -vn -0.552289 0.318865 0.770261 -v -0.014585 0.043000 0.188700 -vn 0.904534 0.301511 0.301512 -v -0.013049 0.025000 0.188700 -vn -0.669352 0.088123 0.737701 -v -0.014049 0.045000 0.188700 -vn 0.577350 0.577350 0.577350 -v -0.013049 0.050000 0.188700 -vn -0.577350 0.577350 0.577350 -v -0.014049 0.050000 0.188700 -vn -0.669354 0.088119 0.737699 -v -0.024549 0.029000 0.188700 -vn -0.553354 0.320378 0.768867 -v -0.025085 0.027000 0.188700 -vn -0.319005 0.554071 0.768922 -v -0.026549 0.025536 0.188700 -vn -0.064620 0.997113 0.039872 -v -0.028549 0.025000 0.188700 -vn -0.577350 0.577350 0.577350 -v -0.023049 0.041000 0.188700 -vn -0.088122 0.669353 0.737700 -v -0.018049 0.041000 0.188700 -vn -0.318864 0.552288 0.770262 -v -0.016049 0.041536 0.188700 -vn -0.320937 -0.560930 0.763123 -v -0.026549 0.036464 0.188700 -vn -0.561456 -0.324901 0.761056 -v -0.025085 0.035000 0.188700 -vn -0.675528 -0.081639 0.732801 -v -0.024549 0.033000 0.188700 -vn 0.061986 0.677288 -0.733103 -v -0.025641 0.025000 0.184620 -vn -0.469614 0.489069 -0.735034 -v -0.025641 0.026254 0.184620 -vn -0.213609 0.668601 -0.712281 -v -0.022454 0.025000 0.184401 -vn -0.590143 0.385214 -0.709466 -v -0.025085 0.027000 0.184681 -vn -0.682486 0.169000 -0.711092 -v -0.024686 0.027965 0.184699 -vn -0.730894 0.056716 -0.680130 -v -0.024549 0.029000 0.184700 -vn -0.236881 -0.115541 -0.964644 -v -0.022454 0.035000 0.184401 -vn -0.740232 -0.045748 -0.670793 -v -0.024549 0.033000 0.184700 -vn -0.692352 -0.165940 -0.702220 -v -0.024685 0.034032 0.184699 -vn -0.102228 -0.067013 -0.992501 -v -0.024016 0.035000 0.184681 -vn -0.589096 -0.440104 -0.677698 -v -0.025085 0.035000 0.184681 -vn -0.015615 0.999738 -0.016739 -v -0.028549 0.025000 0.183544 -vn 0.001008 0.925018 -0.379921 -v -0.027550 0.025127 0.184074 -vn -0.136077 0.681504 -0.719052 -v -0.026549 0.025536 0.184428 -vn -0.411237 -0.093989 -0.906670 -v -0.021830 0.035000 0.184190 -vn -0.565939 -0.094404 -0.819025 -v -0.019886 0.035000 0.183074 -vn -0.432429 0.678439 -0.593907 -v -0.019647 0.025000 0.182876 -vn -0.611037 -0.119441 -0.782539 -v -0.019282 -0.025000 0.182539 -vn -0.878716 0.320598 -0.353659 -v -0.019282 -0.012297 0.182539 -vn -0.918404 0.000145 -0.395644 -v -0.018245 -0.010500 0.181262 -vn -0.692004 0.109207 -0.713586 -v -0.019647 -0.035000 0.182876 -vn -0.432965 -0.679224 -0.592617 -v -0.019647 -0.025000 0.182876 -vn -0.818177 0.099998 -0.566204 -v -0.018359 -0.035000 0.181434 -vn -0.883374 0.157600 -0.441377 -v -0.017730 -0.035000 0.180321 -vn -0.918404 -0.000145 -0.395643 -v -0.018245 0.010500 0.181262 -vn -0.878715 -0.320599 -0.353660 -v -0.019282 0.012297 0.182539 -vn -0.611037 0.119441 -0.782539 -v -0.019282 0.025000 0.182539 -vn -0.692004 -0.109207 -0.713586 -v -0.019647 0.035000 0.182876 -vn -0.811978 -0.090411 -0.576644 -v -0.018359 0.035000 0.181434 -vn -0.895829 -0.121872 -0.427362 -v -0.017730 0.035000 0.180321 -vn -0.224834 0.133442 -0.965217 -v -0.022454 -0.035000 0.184401 -vn -0.214697 -0.669577 -0.711035 -v -0.022454 -0.025000 0.184401 -vn -0.410100 0.095629 -0.907013 -v -0.021830 -0.035000 0.184190 -vn -0.566814 0.095965 -0.818237 -v -0.019886 -0.035000 0.183074 -vn -0.739934 -0.044471 -0.671208 -v -0.024549 -0.029000 0.184700 -vn -0.731105 0.058235 -0.679775 -v -0.024549 -0.033000 0.184700 -vn -0.683611 0.150889 -0.714079 -v -0.024687 -0.034039 0.184699 -vn -0.113462 0.070634 -0.991028 -v -0.024016 -0.035000 0.184681 -vn -0.566519 0.444044 -0.694176 -v -0.025085 -0.035000 0.184681 -vn -0.408175 -0.506163 -0.759731 -v -0.025641 -0.026254 0.184620 -vn 0.072549 -0.684665 -0.725238 -v -0.025641 -0.025000 0.184620 -vn -0.609973 -0.359147 -0.706361 -v -0.025085 -0.027000 0.184681 -vn -0.690755 -0.184814 -0.699072 -v -0.024686 -0.027966 0.184699 -vn -0.154625 -0.684497 -0.712429 -v -0.026549 -0.025536 0.184428 -vn 0.005683 -0.928971 -0.370108 -v -0.027549 -0.025127 0.184074 -vn -0.015632 -0.999737 -0.016758 -v -0.028549 -0.025000 0.183544 -vn -0.878715 -0.320599 -0.353660 -v -0.019282 -0.008703 0.182539 -vn -0.878716 0.320599 -0.353659 -v -0.019282 0.008703 0.182539 -vn -0.962429 0.097288 -0.253507 -v -0.017384 -0.035000 0.179416 -vn -0.962428 -0.097286 -0.253509 -v -0.017384 0.035000 0.179416 -vn -0.992482 0.097316 -0.074221 -v -0.017049 -0.035000 0.177200 -vn -0.992481 -0.097241 -0.074332 -v -0.017049 0.035000 0.177200 -vn -0.272352 -0.471729 -0.838628 -v -0.020294 0.014050 0.182539 -vn -0.272352 -0.471729 -0.838628 -v -0.020294 -0.006950 0.182539 -vn -0.577350 0.577350 -0.577350 -v -0.034549 0.025000 0.182539 -vn 0.544705 -0.000000 -0.838628 -v -0.026443 -0.010500 0.182539 -vn 0.272352 0.471728 -0.838628 -v -0.024394 -0.014050 0.182539 -vn -0.577350 -0.577350 -0.577350 -v -0.034549 -0.025000 0.182539 -vn -0.272352 0.471729 -0.838627 -v -0.020294 -0.014050 0.182539 -vn 0.272352 -0.471728 -0.838628 -v -0.024394 0.014050 0.182539 -vn 0.544705 0.000000 -0.838628 -v -0.026443 0.010500 0.182539 -vn 0.272352 0.471728 -0.838628 -v -0.024394 0.006950 0.182539 -vn 0.272352 -0.471728 -0.838628 -v -0.024394 -0.006950 0.182539 -vn -0.272352 0.471729 -0.838627 -v -0.020294 0.006950 0.182539 -vn 0.000002 0.637727 -0.770262 -v -0.022344 -0.012750 0.185539 -vn -0.318863 0.552289 -0.770262 -v -0.021219 -0.012449 0.185539 -vn -0.552288 0.318866 -0.770261 -v -0.020395 -0.011625 0.185539 -vn -0.637726 -0.000000 -0.770263 -v -0.020094 -0.010500 0.185539 -vn -0.552288 -0.318866 -0.770261 -v -0.020395 -0.009375 0.185539 -vn -0.318863 -0.552289 -0.770262 -v -0.021219 -0.008551 0.185539 -vn 0.000002 -0.637727 -0.770262 -v -0.022344 -0.008250 0.185539 -vn 0.318866 -0.552288 -0.770261 -v -0.023469 -0.008551 0.185539 -vn 0.552288 -0.318866 -0.770261 -v -0.024293 -0.009375 0.185539 -vn 0.637726 -0.000000 -0.770263 -v -0.024594 -0.010500 0.185539 -vn 0.552288 0.318866 -0.770261 -v -0.024293 -0.011625 0.185539 -vn 0.318866 0.552289 -0.770261 -v -0.023469 -0.012449 0.185539 -vn 0.000002 0.637727 -0.770262 -v -0.022344 0.008250 0.185539 -vn -0.318863 0.552289 -0.770262 -v -0.021219 0.008551 0.185539 -vn -0.552288 0.318866 -0.770261 -v -0.020395 0.009375 0.185539 -vn -0.637726 0.000000 -0.770263 -v -0.020094 0.010500 0.185539 -vn -0.552288 -0.318866 -0.770261 -v -0.020395 0.011625 0.185539 -vn -0.318863 -0.552289 -0.770262 -v -0.021219 0.012449 0.185539 -vn 0.000002 -0.637727 -0.770262 -v -0.022344 0.012750 0.185539 -vn 0.318866 -0.552289 -0.770261 -v -0.023469 0.012449 0.185539 -vn 0.552288 -0.318866 -0.770261 -v -0.024293 0.011625 0.185539 -vn 0.637726 0.000000 -0.770263 -v -0.024594 0.010500 0.185539 -vn 0.552288 0.318866 -0.770261 -v -0.024293 0.009375 0.185539 -vn 0.318866 0.552288 -0.770261 -v -0.023469 0.008551 0.185539 -vn -0.000000 -0.637728 0.770261 -v -0.018049 -0.042750 0.178700 -vn 0.000000 -0.637728 -0.770261 -v -0.018049 -0.042750 0.168800 -vn -0.318863 -0.552289 0.770262 -v -0.016924 -0.043051 0.178700 -vn -0.318863 -0.552289 -0.770262 -v -0.016924 -0.043051 0.168800 -vn -0.552288 -0.318866 0.770261 -v -0.016101 -0.043875 0.178700 -vn -0.552288 -0.318866 -0.770261 -v -0.016101 -0.043875 0.168800 -vn -0.637726 0.000000 0.770263 -v -0.015799 -0.045000 0.178700 -vn -0.637726 0.000000 -0.770263 -v -0.015799 -0.045000 0.168800 -vn -0.552288 0.318866 0.770261 -v -0.016101 -0.046125 0.178700 -vn -0.552288 0.318866 -0.770261 -v -0.016101 -0.046125 0.168800 -vn -0.318863 0.552289 0.770262 -v -0.016924 -0.046949 0.178700 -vn -0.318863 0.552289 -0.770262 -v -0.016924 -0.046949 0.168800 -vn 0.000000 0.637728 0.770261 -v -0.018049 -0.047250 0.178700 -vn 0.000000 0.637728 -0.770261 -v -0.018049 -0.047250 0.168800 -vn 0.318863 0.552289 0.770262 -v -0.019174 -0.046949 0.178700 -vn 0.318863 0.552289 -0.770262 -v -0.019174 -0.046949 0.168800 -vn 0.552289 0.318858 0.770264 -v -0.019998 -0.046125 0.178700 -vn 0.552289 0.318858 -0.770264 -v -0.019998 -0.046125 0.168800 -vn 0.637733 0.000000 0.770257 -v -0.020299 -0.045000 0.178700 -vn 0.637733 0.000000 -0.770257 -v -0.020299 -0.045000 0.168800 -vn 0.552289 -0.318857 0.770264 -v -0.019998 -0.043875 0.178700 -vn 0.552289 -0.318857 -0.770264 -v -0.019998 -0.043875 0.168800 -vn 0.318863 -0.552289 0.770262 -v -0.019174 -0.043051 0.178700 -vn 0.318863 -0.552289 -0.770262 -v -0.019174 -0.043051 0.168800 -vn -0.452584 -0.048729 0.890389 -v -0.035299 0.035000 0.109772 -vn -0.541375 0.253420 0.801681 -v -0.068685 -0.017078 0.101192 -vn -0.042520 0.548771 0.834890 -v -0.072285 -0.019157 0.100974 -vn 0.467217 0.276588 0.839766 -v -0.075885 -0.017078 0.100885 -vn -0.014656 0.019622 0.999700 -v -0.076549 -0.037000 0.100883 -vn 0.467279 -0.276441 0.839780 -v -0.075885 -0.012922 0.100885 -vn 0.466829 -0.277366 0.839725 -v -0.075885 0.017078 0.100885 -vn -0.040288 -0.550215 0.834051 -v -0.072285 0.019157 0.100974 -vn -0.541375 -0.253420 0.801681 -v -0.068685 0.017078 0.101192 -vn -0.541353 -0.253397 0.801703 -v -0.068685 -0.012922 0.101192 -vn -0.541353 0.253397 0.801702 -v -0.068685 0.012922 0.101192 -vn -0.042969 -0.548479 0.835060 -v -0.072285 -0.010843 0.100974 -vn -0.042970 0.548479 0.835060 -v -0.072285 0.010843 0.100974 -vn 0.467279 0.276441 0.839780 -v -0.075885 0.012922 0.100885 -vn 0.039431 0.715653 0.697342 -v -0.080341 -0.037000 0.100955 -vn -0.547969 0.573151 0.609285 -v -0.091536 -0.037000 0.102011 -vn -0.452585 0.048730 0.890389 -v -0.035299 -0.035000 0.109772 -vn -0.881311 0.085263 0.464782 -v -0.017049 -0.035000 0.120473 -vn -0.881817 -0.084316 0.463993 -v -0.017049 0.035000 0.120473 -vn -0.539694 0.097864 0.836154 -v -0.022804 -0.035000 0.116525 -vn -0.538949 -0.097246 0.836706 -v -0.022804 0.035000 0.116525 -vn -0.500088 0.129571 0.856226 -v -0.026455 -0.035000 0.114311 -vn -0.500088 -0.129571 0.856226 -v -0.026455 0.035000 0.114311 -vn -0.463811 0.097854 0.880513 -v -0.028932 -0.035000 0.112927 -vn -0.463813 -0.097853 0.880513 -v -0.028932 0.035000 0.112927 -vn -0.904168 0.299127 0.304965 -v -0.091549 -0.037000 0.100883 -vn 0.757325 0.621397 -0.200810 -v -0.059785 0.039885 0.099590 -vn 0.759053 0.564630 -0.324085 -v -0.059785 0.039732 0.099255 -vn 0.778617 0.466107 -0.420119 -v -0.059785 0.039551 0.098989 -vn 0.798887 0.310773 -0.514976 -v -0.059785 0.039039 0.098536 -vn 0.807345 -0.192217 -0.557895 -v -0.059785 -0.038656 0.098353 -vn 0.797622 -0.368463 -0.477529 -v -0.059785 -0.039237 0.098675 -vn 0.774766 -0.516186 -0.365090 -v -0.059785 -0.039683 0.099173 -vn 0.798326 0.142860 -0.585035 -v -0.059785 0.038414 0.098285 -vn 0.782425 0.032284 -0.621907 -v -0.059785 0.038000 0.098241 -vn 0.792210 -0.051532 -0.608070 -v -0.059785 -0.038000 0.098241 -vn 0.753406 -0.604967 -0.257670 -v -0.059785 -0.039848 0.099493 -vn 0.745087 -0.650204 -0.148593 -v -0.059785 -0.039945 0.099798 -vn 0.503105 0.130404 -0.854330 -v -0.023703 0.038000 0.111286 -vn 0.466910 -0.098106 -0.878846 -v -0.026423 -0.038000 0.109738 -vn 0.449317 0.130393 -0.883805 -v -0.029342 0.038000 0.108196 -vn 0.419905 -0.098134 -0.902247 -v -0.034438 -0.038000 0.105776 -vn 0.393943 0.130259 -0.909858 -v -0.035161 0.038000 0.105459 -vn 0.373871 -0.113702 -0.920485 -v -0.035161 -0.038000 0.105459 -vn 0.337164 0.130294 -0.932386 -v -0.041138 0.038000 0.103088 -vn 0.331276 -0.098573 -0.938371 -v -0.042764 -0.038000 0.102515 -vn 0.278831 0.130297 -0.951460 -v -0.047250 0.038000 0.101089 -vn 0.279505 -0.149041 -0.948506 -v -0.047250 -0.038000 0.101089 -vn 0.221921 0.128304 -0.966586 -v -0.053473 0.038000 0.099472 -vn 0.230870 -0.097608 -0.968076 -v -0.051338 -0.038000 0.099980 -vn 0.879134 0.044056 -0.474533 -v -0.013049 0.038000 0.118479 -vn 0.880401 -0.033526 -0.473043 -v -0.013049 -0.038000 0.118479 -vn 0.552983 0.128640 -0.823202 -v -0.018265 0.038000 0.114718 -vn 0.554417 -0.097886 -0.826463 -v -0.018777 -0.038000 0.114374 -vn 0.509569 -0.144365 -0.848233 -v -0.023703 -0.038000 0.111286 -vn 0.678877 0.095830 0.727972 -v -0.013049 0.021000 0.194700 -vn 0.577350 -0.577350 0.577350 -v -0.013049 0.019300 0.194700 -vn 0.678874 -0.727973 0.095841 -v -0.013049 -0.025000 0.190700 -vn 0.568075 0.575537 -0.588259 -v -0.013049 0.042000 0.133241 -vn 0.568075 0.575537 0.588259 -v -0.013049 0.042000 0.149241 -vn 0.577350 0.577350 0.577350 -v -0.013049 -0.019300 0.194700 -vn 0.678877 -0.095830 0.727972 -v -0.013049 -0.021000 0.194700 -vn 0.577350 -0.577350 -0.577350 -v -0.013049 -0.050000 0.168800 -vn 0.577350 0.577350 -0.577351 -v -0.013049 0.050000 0.168800 -vn 0.568075 -0.575536 0.588260 -v -0.013049 -0.042000 0.149241 -vn 0.568075 -0.575537 -0.588259 -v -0.013049 -0.042000 0.133241 -vn 0.653224 -0.378577 0.655727 -v -0.013049 -0.023000 0.194164 -vn 0.653228 -0.655722 0.378579 -v -0.013049 -0.024464 0.192700 -vn 0.709230 0.702577 -0.058121 -v -0.013049 0.039994 0.120821 -vn 0.749530 0.640168 -0.168495 -v -0.013049 0.039816 0.119951 -vn 0.863424 0.176792 -0.472486 -v -0.013049 0.038562 0.118580 -vn 0.860015 0.283453 -0.424299 -v -0.013049 0.039001 0.118818 -vn 0.841893 0.370299 -0.392550 -v -0.013049 0.039057 0.118860 -vn 0.810530 0.480874 -0.334366 -v -0.013049 0.039477 0.119303 -vn 0.790781 0.556427 -0.255058 -v -0.013049 0.039734 0.119748 -vn 0.653224 0.378577 0.655727 -v -0.013049 0.023000 0.194164 -vn 0.653228 0.655722 0.378579 -v -0.013049 0.024464 0.192700 -vn 0.678874 0.727973 0.095841 -v -0.013049 0.025000 0.190700 -vn 0.801096 -0.495938 -0.335099 -v -0.013049 -0.039438 0.119250 -vn 0.842394 -0.320112 -0.433476 -v -0.013049 -0.038939 0.118774 -vn 0.737305 -0.652992 -0.173157 -v -0.013049 -0.039839 0.120017 -vn 0.865730 -0.143458 -0.479512 -v -0.013049 -0.038410 0.118532 -vn -0.318866 -0.552288 -0.770261 -v -0.071160 0.016949 0.090039 -vn -0.000002 -0.637727 -0.770262 -v -0.072285 0.017250 0.090039 -vn -0.318866 0.552288 -0.770261 -v -0.071160 -0.016949 0.090039 -vn -0.000002 0.637727 -0.770262 -v -0.072285 -0.017250 0.090039 -vn 0.318863 0.552289 -0.770262 -v -0.073410 -0.016949 0.090039 -vn 0.318863 -0.552289 -0.770262 -v -0.073410 0.016949 0.090039 -vn 0.552288 -0.318866 -0.770261 -v -0.074233 0.016125 0.090039 -vn 0.637726 -0.000000 -0.770264 -v -0.074535 0.015000 0.090039 -vn 0.552288 -0.318866 -0.770261 -v -0.074233 -0.013875 0.090039 -vn 0.637726 -0.000000 -0.770263 -v -0.074535 -0.015000 0.090039 -vn 0.552288 0.318866 -0.770261 -v -0.074233 -0.016125 0.090039 -vn -0.318865 0.552287 -0.770262 -v -0.071160 0.013051 0.090039 -vn -0.318866 -0.552288 -0.770261 -v -0.071160 -0.013051 0.090039 -vn -0.000002 0.637727 -0.770262 -v -0.072285 0.012750 0.090039 -vn -0.000002 -0.637728 -0.770261 -v -0.072285 -0.012750 0.090039 -vn 0.318863 0.552289 -0.770262 -v -0.073410 0.013051 0.090039 -vn -0.552288 0.318866 -0.770261 -v -0.070336 0.013875 0.090039 -vn -0.637726 -0.000000 -0.770263 -v -0.070035 0.015000 0.090039 -vn -0.552288 -0.318866 -0.770261 -v -0.070336 0.016125 0.090039 -vn 0.318863 -0.552289 -0.770262 -v -0.073410 -0.013051 0.090039 -vn 0.552288 0.318866 -0.770261 -v -0.074233 0.013875 0.090039 -vn -0.552288 0.318866 -0.770261 -v -0.070336 -0.016125 0.090039 -vn -0.637726 0.000000 -0.770263 -v -0.070035 -0.015000 0.090039 -vn -0.552288 -0.318866 -0.770261 -v -0.070336 -0.013875 0.090039 -vn -0.000002 -0.637727 0.770262 -v -0.072285 -0.012750 0.095039 -vn -0.318866 -0.552288 0.770261 -v -0.071160 -0.013051 0.095039 -vn -0.552288 -0.318866 0.770261 -v -0.070336 -0.013875 0.095039 -vn -0.637726 -0.000000 0.770263 -v -0.070035 -0.015000 0.095039 -vn -0.552288 0.318866 0.770261 -v -0.070336 -0.016125 0.095039 -vn -0.318866 0.552288 0.770261 -v -0.071160 -0.016949 0.095039 -vn -0.000002 0.637727 0.770262 -v -0.072285 -0.017250 0.095039 -vn 0.318863 0.552289 0.770262 -v -0.073410 -0.016949 0.095039 -vn 0.552288 0.318866 0.770261 -v -0.074233 -0.016125 0.095039 -vn 0.637726 0.000000 0.770263 -v -0.074535 -0.015000 0.095039 -vn 0.552288 -0.318866 0.770261 -v -0.074233 -0.013875 0.095039 -vn 0.318863 -0.552289 0.770262 -v -0.073410 -0.013051 0.095039 -vn -0.000002 -0.637727 0.770262 -v -0.072285 0.017250 0.095039 -vn -0.318866 -0.552288 0.770261 -v -0.071160 0.016949 0.095039 -vn -0.552288 -0.318866 0.770261 -v -0.070336 0.016125 0.095039 -vn -0.637726 -0.000000 0.770264 -v -0.070035 0.015000 0.095039 -vn -0.552288 0.318866 0.770261 -v -0.070336 0.013875 0.095039 -vn -0.318866 0.552288 0.770261 -v -0.071160 0.013051 0.095039 -vn -0.000002 0.637727 0.770262 -v -0.072285 0.012750 0.095039 -vn 0.318863 0.552289 0.770262 -v -0.073410 0.013051 0.095039 -vn 0.552288 0.318866 0.770261 -v -0.074233 0.013875 0.095039 -vn 0.637726 -0.000000 0.770263 -v -0.074535 0.015000 0.095039 -vn 0.552288 -0.318866 0.770261 -v -0.074233 0.016125 0.095039 -vn 0.318863 -0.552289 0.770262 -v -0.073410 0.016949 0.095039 -vn 0.000000 -0.792406 0.609994 -v -0.072285 0.019157 0.095039 -vn 0.686244 -0.396203 0.609994 -v -0.075885 0.017078 0.095039 -vn 0.686243 0.396203 0.609994 -v -0.075885 0.012922 0.095039 -vn -0.000000 0.792406 0.609994 -v -0.072285 0.010843 0.095039 -vn -0.686244 0.396203 0.609994 -v -0.068685 0.012922 0.095039 -vn -0.686244 -0.396203 0.609994 -v -0.068685 0.017078 0.095039 -vn 0.000000 -0.792406 0.609994 -v -0.072285 -0.010843 0.095039 -vn 0.686244 -0.396203 0.609994 -v -0.075885 -0.012922 0.095039 -vn 0.686243 0.396203 0.609994 -v -0.075885 -0.017078 0.095039 -vn -0.000000 0.792406 0.609994 -v -0.072285 -0.019157 0.095039 -vn -0.686244 0.396203 0.609994 -v -0.068685 -0.017078 0.095039 -vn -0.686244 -0.396203 0.609994 -v -0.068685 -0.012922 0.095039 -vn -0.577350 -0.577350 -0.577351 -v -0.023049 -0.050000 0.168800 -vn -0.904534 -0.301511 0.301511 -v -0.023049 -0.041000 0.178700 -vn -0.577350 -0.577350 0.577351 -v -0.023049 -0.050000 0.178700 -vn -0.301511 -0.904534 0.301511 -v -0.014049 -0.050000 0.178700 -vn 0.318863 -0.552289 -0.770262 -v -0.019174 0.046949 0.168800 -vn -0.577350 0.577350 -0.577351 -v -0.023049 0.050000 0.168800 -vn 0.000000 -0.637728 -0.770261 -v -0.018049 0.047250 0.168800 -vn -0.318863 -0.552289 -0.770262 -v -0.016924 0.046949 0.168800 -vn -0.318863 0.552289 -0.770262 -v -0.016924 0.043051 0.168800 -vn -0.552288 0.318866 -0.770261 -v -0.016101 0.043875 0.168800 -vn -0.637726 -0.000000 -0.770263 -v -0.015799 0.045000 0.168800 -vn -0.552288 -0.318866 -0.770261 -v -0.016101 0.046125 0.168800 -vn 0.000000 0.637728 -0.770261 -v -0.018049 0.042750 0.168800 -vn 0.318863 0.552289 -0.770262 -v -0.019174 0.043051 0.168800 -vn 0.552289 -0.318858 -0.770264 -v -0.019998 0.046125 0.168800 -vn 0.637733 -0.000000 -0.770257 -v -0.020299 0.045000 0.168800 -vn 0.552289 0.318857 -0.770264 -v -0.019998 0.043875 0.168800 -vn -0.301511 0.904534 0.301511 -v -0.014049 0.050000 0.178700 -vn -0.577350 0.577350 0.577350 -v -0.023049 0.050000 0.178700 -vn -0.904534 0.301511 0.301511 -v -0.023049 0.041000 0.178700 -vn -0.000000 -0.637728 0.770261 -v -0.018049 0.047250 0.178700 -vn -0.318863 -0.552289 0.770262 -v -0.016924 0.046949 0.178700 -vn -0.552288 -0.318866 0.770261 -v -0.016101 0.046125 0.178700 -vn -0.637726 -0.000000 0.770263 -v -0.015799 0.045000 0.178700 -vn -0.552288 0.318866 0.770261 -v -0.016101 0.043875 0.178700 -vn -0.318863 0.552289 0.770262 -v -0.016924 0.043051 0.178700 -vn 0.000000 0.637728 0.770261 -v -0.018049 0.042750 0.178700 -vn 0.318863 0.552289 0.770262 -v -0.019174 0.043051 0.178700 -vn 0.552289 0.318857 0.770264 -v -0.019998 0.043875 0.178700 -vn 0.637733 -0.000000 0.770257 -v -0.020299 0.045000 0.178700 -vn 0.552289 -0.318858 0.770264 -v -0.019998 0.046125 0.178700 -vn 0.318863 -0.552289 0.770262 -v -0.019174 0.046949 0.178700 -vn -0.727973 0.095841 0.678874 -v -0.014049 0.045000 0.178700 -vn -0.095839 0.727973 0.678874 -v -0.018049 0.041000 0.178700 -vn -0.655721 0.378582 0.653227 -v -0.014585 0.043000 0.178700 -vn -0.378581 0.655722 0.653227 -v -0.016049 0.041536 0.178700 -vn -0.095839 -0.727973 0.678874 -v -0.018049 -0.041000 0.178700 -vn -0.727973 -0.095841 0.678874 -v -0.014049 -0.045000 0.178700 -vn -0.378581 -0.655722 0.653227 -v -0.016049 -0.041536 0.178700 -vn -0.655721 -0.378582 0.653227 -v -0.014585 -0.043000 0.178700 -vn -0.678874 -0.727973 0.095841 -v -0.034549 -0.025000 0.190700 -vn -0.678874 0.727973 0.095841 -v -0.034549 0.025000 0.190700 -vn -0.678877 -0.095830 0.727972 -v -0.034549 -0.021000 0.194700 -vn -0.577350 0.577350 0.577350 -v -0.034549 -0.019300 0.194700 -vn -0.577350 -0.577350 0.577350 -v -0.034549 0.019300 0.194700 -vn -0.678877 0.095830 0.727972 -v -0.034549 0.021000 0.194700 -vn -0.653224 -0.378577 0.655727 -v -0.034549 -0.023000 0.194164 -vn -0.653228 -0.655722 0.378579 -v -0.034549 -0.024464 0.192700 -vn -0.653224 0.378577 0.655727 -v -0.034549 0.023000 0.194164 -vn -0.653228 0.655722 0.378579 -v -0.034549 0.024464 0.192700 -vn 0.792406 0.000000 -0.609994 -v -0.026443 0.010500 0.185539 -vn 0.396203 0.686244 -0.609994 -v -0.024394 0.006950 0.185539 -vn 0.396203 -0.686244 -0.609994 -v -0.024394 0.014050 0.185539 -vn -0.396203 -0.686244 -0.609994 -v -0.020294 0.014050 0.185539 -vn -0.792406 -0.000000 -0.609995 -v -0.018245 0.010500 0.185539 -vn -0.396202 0.686244 -0.609995 -v -0.020294 0.006950 0.185539 -vn 0.792406 -0.000000 -0.609994 -v -0.026443 -0.010500 0.185539 -vn 0.396203 0.686244 -0.609994 -v -0.024394 -0.014050 0.185539 -vn 0.396203 -0.686244 -0.609994 -v -0.024394 -0.006950 0.185539 -vn -0.396203 -0.686244 -0.609994 -v -0.020294 -0.006950 0.185539 -vn -0.792406 -0.000000 -0.609995 -v -0.018245 -0.010500 0.185539 -vn -0.396202 0.686244 -0.609995 -v -0.020294 -0.014050 0.185539 -vn -0.726994 -0.680939 -0.088335 -v -0.088049 -0.042000 0.130393 -vn -0.586391 -0.579208 0.566271 -v -0.088049 -0.042000 0.146622 -vn -0.009401 -0.684058 -0.729367 -v -0.085285 -0.042000 0.127399 -vn -0.174266 -0.680843 -0.711396 -v -0.085408 -0.042000 0.127414 -vn -0.794671 0.601386 -0.082661 -v -0.035808 -0.036848 0.110897 -vn -0.883466 0.456600 0.104901 -v -0.035540 -0.036414 0.110306 -vn -0.941992 0.245789 0.228559 -v -0.035362 -0.035765 0.109911 -vn -0.427827 -0.656969 -0.620770 -v -0.086752 -0.042000 0.127922 -vn -0.667439 -0.656962 -0.350608 -v -0.087705 -0.042000 0.128998 -vn 0.603762 -0.754847 -0.256274 -v -0.082890 -0.042000 0.134395 -vn 0.455612 -0.754865 -0.471802 -v -0.082439 -0.042000 0.135053 -vn 0.312932 -0.900418 0.302195 -v -0.085049 -0.042000 0.138757 -vn 0.312932 -0.900418 -0.302194 -v -0.085049 -0.042000 0.143724 -vn -0.290145 -0.908594 -0.300454 -v -0.016049 -0.042000 0.146134 -vn -0.290146 -0.908594 0.300454 -v -0.016049 -0.042000 0.136347 -vn 0.044692 -0.730375 -0.681583 -v -0.080980 -0.042000 0.135613 -vn 0.235059 -0.754842 -0.612340 -v -0.081766 -0.042000 0.135481 -vn 0.224244 -0.662849 -0.714385 -v -0.084451 -0.042000 0.127477 -vn 0.497285 -0.662843 -0.559774 -v -0.083721 -0.042000 0.127890 -vn 0.679614 -0.730370 -0.068440 -v -0.083049 -0.042000 0.133614 -vn 0.725287 -0.684145 -0.076839 -v -0.083049 -0.042000 0.129386 -vn 0.683006 -0.662842 -0.306828 -v -0.083225 -0.042000 0.128566 -vn 0.586391 -0.579208 -0.566271 -v -0.085049 -0.040000 0.143724 -vn 0.586391 -0.579208 0.566271 -v -0.085049 -0.040000 0.138757 -vn -0.568075 -0.575537 0.588259 -v -0.016049 -0.040000 0.136347 -vn -0.568075 -0.575537 -0.588258 -v -0.016049 -0.040000 0.146134 -vn -0.586391 0.579207 0.566272 -v -0.088049 0.042000 0.146622 -vn -0.726994 0.680938 -0.088335 -v -0.088049 0.042000 0.130393 -vn -0.174266 0.680843 -0.711396 -v -0.085408 0.042000 0.127414 -vn -0.009401 0.684058 -0.729367 -v -0.085285 0.042000 0.127399 -vn -0.883466 -0.456599 0.104901 -v -0.035540 0.036414 0.110306 -vn -0.941991 -0.245791 0.228559 -v -0.035362 0.035765 0.109911 -vn -0.794671 -0.601386 -0.082661 -v -0.035808 0.036848 0.110897 -vn 0.044692 0.730375 -0.681583 -v -0.080980 0.042000 0.135613 -vn 0.235059 0.754842 -0.612340 -v -0.081766 0.042000 0.135481 -vn 0.455612 0.754865 -0.471802 -v -0.082439 0.042000 0.135053 -vn 0.603762 0.754847 -0.256274 -v -0.082890 0.042000 0.134395 -vn 0.679614 0.730370 -0.068440 -v -0.083049 0.042000 0.133614 -vn 0.725287 0.684145 -0.076839 -v -0.083049 0.042000 0.129386 -vn 0.683006 0.662842 -0.306828 -v -0.083225 0.042000 0.128566 -vn 0.497285 0.662843 -0.559774 -v -0.083721 0.042000 0.127890 -vn 0.224244 0.662849 -0.714385 -v -0.084451 0.042000 0.127477 -vn -0.427827 0.656969 -0.620770 -v -0.086752 0.042000 0.127922 -vn -0.667439 0.656962 -0.350609 -v -0.087705 0.042000 0.128998 -vn 0.312932 0.900418 0.302195 -v -0.085049 0.042000 0.138757 -vn 0.312932 0.900418 -0.302195 -v -0.085049 0.042000 0.143724 -vn -0.290146 0.908594 -0.300454 -v -0.016049 0.042000 0.146134 -vn -0.290146 0.908594 0.300454 -v -0.016049 0.042000 0.136347 -vn 0.586391 0.579208 0.566272 -v -0.085049 0.040000 0.138757 -vn 0.586392 0.579209 -0.566270 -v -0.085049 0.040000 0.143724 -vn -0.568075 0.575537 -0.588259 -v -0.016049 0.040000 0.146134 -vn -0.568075 0.575537 0.588258 -v -0.016049 0.040000 0.136347 -vn -0.085736 0.995166 0.047901 -v -0.019041 -0.037000 0.121484 -vn -0.260251 0.955425 0.139402 -v -0.018405 -0.036893 0.121160 -vn -0.205050 0.922657 0.326588 -v -0.023467 -0.036848 0.117567 -vn -0.604991 0.726643 0.325540 -v -0.017637 -0.036416 0.120770 -vn -0.687310 0.626605 0.367385 -v -0.017413 -0.036149 0.120656 -vn -0.497739 0.383009 0.778177 -v -0.022886 -0.035765 0.116653 -vn -0.762975 0.505369 0.403077 -v -0.017318 -0.036002 0.120608 -vn -0.844056 0.298593 0.445434 -v -0.017145 -0.035609 0.120521 -vn -0.407854 0.886250 0.219580 -v -0.018052 -0.036733 0.120980 -vn -0.508766 0.817062 0.271233 -v -0.017833 -0.036588 0.120869 -vn -0.379136 0.704297 0.600185 -v -0.023119 -0.036414 0.117019 -vn -0.183721 0.922320 0.339960 -v -0.029519 -0.036848 0.114013 -vn -0.337222 0.704916 0.623999 -v -0.029210 -0.036414 0.113442 -vn -0.435028 0.384123 0.814371 -v -0.029004 -0.035765 0.113061 -vn -0.326872 0.944737 -0.025055 -v -0.018284 -0.036848 0.177200 -vn -0.709127 0.703044 -0.053557 -v -0.017635 -0.036414 0.177200 -vn -0.530815 0.846478 -0.041358 -v -0.018049 -0.036732 0.177200 -vn -0.848703 0.524911 -0.064587 -v -0.017317 -0.036000 0.177200 -vn -0.945176 0.318839 -0.070596 -v -0.017202 -0.035765 0.177200 -vn -0.342402 0.386301 -0.856465 -v -0.021885 -0.035765 0.184048 -vn -0.883996 0.383471 -0.267398 -v -0.017530 -0.035765 0.179371 -vn -0.028317 0.917233 -0.397343 -v -0.024104 -0.036848 0.183450 -vn -0.144450 0.917233 -0.371238 -v -0.022278 -0.036848 0.183039 -vn -0.247680 0.917235 -0.311986 -v -0.020654 -0.036848 0.182107 -vn -0.328809 0.917231 -0.224884 -v -0.019378 -0.036848 0.180737 -vn -0.087848 0.384467 -0.918950 -v -0.024027 -0.035765 0.184529 -vn -0.442328 0.699071 -0.561824 -v -0.025538 -0.035632 0.184531 -vn -0.055110 0.699900 -0.712112 -v -0.024058 -0.036414 0.184097 -vn -0.306121 0.838752 -0.450317 -v -0.026192 -0.036232 0.184082 -vn 0.102803 0.747796 -0.655921 -v -0.026118 -0.036414 0.183934 -vn -0.208756 0.894181 -0.396058 -v -0.026373 -0.036356 0.183927 -vn -0.171172 0.945783 -0.276035 -v -0.026562 -0.036471 0.183753 -vn -0.094677 0.973395 -0.208657 -v -0.027147 -0.036746 0.183132 -vn 0.071468 0.920080 -0.385155 -v -0.025970 -0.036848 0.183302 -vn -0.047206 0.994562 -0.092837 -v -0.027621 -0.036891 0.182531 -vn -0.000740 0.999999 -0.001505 -v -0.028542 -0.037000 0.180990 -vn -0.008635 0.999812 -0.017349 -v -0.028397 -0.036997 0.181280 -vn -0.376697 0.918322 -0.121589 -v -0.018564 -0.036848 0.179051 -vn -0.682209 0.697805 -0.218310 -v -0.017944 -0.036414 0.179243 -vn -0.591135 0.697927 -0.404299 -v -0.018842 -0.036414 0.181103 -vn -0.766121 0.379124 -0.518965 -v -0.018485 -0.035765 0.181348 -vn -0.567326 0.385274 -0.727808 -v -0.019981 -0.035765 0.182955 -vn -0.445289 0.697936 -0.560895 -v -0.020250 -0.036414 0.182615 -vn -0.259690 0.697939 -0.667415 -v -0.022042 -0.036414 0.183644 -vn -0.183720 -0.922320 0.339960 -v -0.029519 0.036848 0.114013 -vn -0.085736 -0.995166 0.047901 -v -0.019041 0.037000 0.121484 -vn -0.205050 -0.922657 0.326587 -v -0.023467 0.036848 0.117567 -vn -0.260299 -0.955419 0.139354 -v -0.018405 0.036893 0.121160 -vn -0.408031 -0.886222 0.219369 -v -0.018052 0.036733 0.120980 -vn -0.377754 -0.704880 0.600372 -v -0.023119 0.036414 0.117019 -vn -0.546209 -0.786005 0.289571 -v -0.017833 0.036588 0.120869 -vn -0.675007 -0.644957 0.358324 -v -0.017413 0.036149 0.120656 -vn -0.496031 -0.382829 0.779355 -v -0.022886 0.035765 0.116653 -vn -0.762933 -0.505396 0.403124 -v -0.017318 0.036002 0.120608 -vn -0.844370 -0.299449 0.444262 -v -0.017145 0.035609 0.120521 -vn -0.435028 -0.384124 0.814370 -v -0.029004 0.035765 0.113061 -vn -0.337222 -0.704915 0.624001 -v -0.029210 0.036414 0.113442 -vn -0.945156 -0.318858 -0.070784 -v -0.017202 0.035765 0.177200 -vn -0.848673 -0.524950 -0.064665 -v -0.017317 0.036000 0.177200 -vn -0.709095 -0.703082 -0.053479 -v -0.017635 0.036414 0.177200 -vn -0.530829 -0.846476 -0.041224 -v -0.018049 0.036732 0.177200 -vn -0.326906 -0.944726 -0.024998 -v -0.018284 0.036848 0.177200 -vn -0.376696 -0.918323 -0.121587 -v -0.018564 0.036848 0.179051 -vn -0.328808 -0.917230 -0.224888 -v -0.019378 0.036848 0.180737 -vn -0.247683 -0.917234 -0.311987 -v -0.020654 0.036848 0.182107 -vn -0.144449 -0.917234 -0.371236 -v -0.022278 0.036848 0.183039 -vn -0.035452 -0.997454 -0.061882 -v -0.028010 0.036963 0.181954 -vn -0.006210 -0.999893 -0.013220 -v -0.028397 0.036997 0.181280 -vn -0.000740 -0.999999 -0.001505 -v -0.028542 0.037000 0.180990 -vn 0.069915 -0.922800 -0.378883 -v -0.025970 0.036848 0.183302 -vn -0.080722 -0.985292 -0.150608 -v -0.027147 0.036746 0.183132 -vn -0.441280 -0.717281 -0.539240 -v -0.025538 0.035632 0.184531 -vn -0.322026 -0.840234 -0.436241 -v -0.026192 0.036232 0.184082 -vn 0.095802 -0.730245 -0.676435 -v -0.026118 0.036414 0.183934 -vn -0.191262 -0.932790 -0.305486 -v -0.026566 0.036474 0.183749 -vn -0.115792 -0.958937 -0.258907 -v -0.026976 0.036677 0.183326 -vn -0.054182 -0.699820 -0.712261 -v -0.024058 0.036414 0.184097 -vn -0.077236 -0.388427 -0.918237 -v -0.024027 0.035765 0.184529 -vn -0.028314 -0.917233 -0.397344 -v -0.024104 0.036848 0.183450 -vn -0.682210 -0.697804 -0.218309 -v -0.017944 0.036414 0.179243 -vn -0.591133 -0.697927 -0.404301 -v -0.018842 0.036414 0.181103 -vn -0.884654 -0.384487 -0.263738 -v -0.017530 0.035765 0.179371 -vn -0.756961 -0.387533 -0.526145 -v -0.018485 0.035765 0.181348 -vn -0.345840 -0.387643 -0.854475 -v -0.021885 0.035765 0.184048 -vn -0.259694 -0.697939 -0.667413 -v -0.022042 0.036414 0.183644 -vn -0.445290 -0.697936 -0.560894 -v -0.020250 0.036414 0.182615 -vn -0.567326 -0.385275 -0.727808 -v -0.019981 0.035765 0.182955 -vn 0.482516 0.498965 -0.719870 -v -0.018415 0.039000 0.114940 -vn 0.280798 0.863616 -0.418712 -v -0.018825 0.039732 0.115546 -vn 0.116496 0.863745 -0.490278 -v -0.053695 0.039732 0.100447 -vn 0.196788 0.497885 -0.844621 -v -0.053533 0.039000 0.099733 -vn 0.243974 0.497796 -0.832272 -v -0.047325 0.039000 0.101346 -vn 0.294868 0.497794 -0.815631 -v -0.041229 0.039000 0.103340 -vn 0.344632 0.497813 -0.795871 -v -0.035268 0.039000 0.105705 -vn 0.393089 0.497808 -0.773090 -v -0.029463 0.039000 0.108434 -vn 0.440044 0.497806 -0.747362 -v -0.023839 0.039000 0.111516 -vn 0.141718 0.863826 -0.483447 -v -0.047531 0.039732 0.102049 -vn 0.171285 0.863822 -0.473787 -v -0.041478 0.039732 0.104028 -vn 0.200190 0.863828 -0.462303 -v -0.035558 0.039732 0.106377 -vn 0.228339 0.863824 -0.449076 -v -0.029795 0.039732 0.109087 -vn 0.255615 0.863823 -0.434133 -v -0.024210 0.039732 0.112147 -vn 0.303906 -0.383694 -0.872021 -v -0.042813 -0.038765 0.102659 -vn 0.512099 -0.383557 -0.768530 -v -0.018862 -0.038765 0.114501 -vn 0.218520 -0.384501 -0.896888 -v -0.051375 -0.038765 0.100128 -vn 0.213817 -0.922159 -0.322343 -v -0.019462 -0.039848 0.115401 -vn 0.391893 -0.704637 -0.591529 -v -0.019102 -0.039414 0.114861 -vn 0.172988 -0.703620 -0.689198 -v -0.051480 -0.039414 0.100549 -vn 0.096321 -0.922032 -0.374940 -v -0.051637 -0.039848 0.101178 -vn 0.156555 -0.921988 -0.354160 -v -0.034938 -0.039848 0.106905 -vn 0.125603 -0.921988 -0.366281 -v -0.043164 -0.039848 0.103683 -vn 0.286959 -0.704451 -0.649156 -v -0.034675 -0.039414 0.106311 -vn 0.230228 -0.704440 -0.671386 -v -0.042954 -0.039414 0.103069 -vn 0.377290 -0.385164 -0.842200 -v -0.034500 -0.038765 0.105915 -vn 0.438978 -0.384741 -0.811956 -v -0.026496 -0.038765 0.109872 -vn 0.341578 -0.704448 -0.622155 -v -0.026705 -0.039414 0.110252 -vn 0.186354 -0.921988 -0.339428 -v -0.027017 -0.039848 0.110821 -# 1050 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 2//2 4//4 -f 5//5 6//6 7//7 -f 7//7 6//6 8//8 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 11//11 12//12 13//13 -f 13//13 12//12 14//14 -f 13//13 14//14 15//15 -f 15//15 14//14 16//16 -f 15//15 16//16 17//17 -f 17//17 16//16 18//18 -f 17//17 18//18 19//19 -f 19//19 18//18 20//20 -f 19//19 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 25//25 26//26 27//27 -f 27//27 26//26 28//28 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 9//9 -f 9//9 32//32 10//10 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 37//37 -f 37//37 36//36 38//38 -f 37//37 38//38 39//39 -f 39//39 38//38 40//40 -f 39//39 40//40 41//41 -f 41//41 40//40 42//42 -f 41//41 42//42 43//43 -f 43//43 42//42 44//44 -f 43//43 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 47//47 48//48 49//49 -f 49//49 48//48 50//50 -f 49//49 50//50 51//51 -f 51//51 50//50 52//52 -f 51//51 52//52 53//53 -f 53//53 52//52 54//54 -f 53//53 54//54 55//55 -f 55//55 54//54 56//56 -f 55//55 56//56 33//33 -f 33//33 56//56 34//34 -f 57//57 58//58 59//59 -f 59//59 58//58 60//60 -f 59//59 60//60 61//61 -f 61//61 60//60 62//62 -f 61//61 62//62 63//63 -f 63//63 62//62 64//64 -f 63//63 64//64 65//65 -f 65//65 64//64 66//66 -f 65//65 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 57//57 -f 57//57 80//80 58//58 -f 81//81 82//82 83//83 -f 83//83 82//82 84//84 -f 83//83 84//84 85//85 -f 85//85 84//84 86//86 -f 85//85 86//86 87//87 -f 87//87 86//86 88//88 -f 87//87 88//88 89//89 -f 89//89 88//88 90//90 -f 89//89 90//90 91//91 -f 91//91 90//90 92//92 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 96//96 -f 95//95 96//96 97//97 -f 97//97 96//96 98//98 -f 97//97 98//98 99//99 -f 99//99 98//98 100//100 -f 99//99 100//100 101//101 -f 101//101 100//100 102//102 -f 101//101 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 81//81 -f 81//81 104//104 82//82 -f 105//105 106//106 107//107 -f 107//107 106//106 108//108 -f 107//107 108//108 109//109 -f 109//109 108//108 110//110 -f 109//109 110//110 111//111 -f 111//111 110//110 112//112 -f 111//111 112//112 113//113 -f 113//113 112//112 114//114 -f 113//113 114//114 115//115 -f 115//115 114//114 116//116 -f 115//115 116//116 117//117 -f 117//117 116//116 118//118 -f 117//117 118//118 119//119 -f 119//119 118//118 120//120 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 123//123 122//122 124//124 -f 123//123 124//124 125//125 -f 125//125 124//124 126//126 -f 125//125 126//126 127//127 -f 127//127 126//126 128//128 -f 127//127 128//128 105//105 -f 105//105 128//128 106//106 -f 129//129 130//130 131//131 -f 131//131 130//130 132//132 -f 131//131 132//132 133//133 -f 133//133 132//132 134//134 -f 133//133 134//134 135//135 -f 135//135 134//134 136//136 -f 137//137 2//2 1//1 -f 138//138 139//139 140//140 -f 140//140 139//139 137//137 -f 137//137 1//1 140//140 -f 140//140 1//1 7//7 -f 140//140 7//7 8//8 -f 141//141 142//142 143//143 -f 138//138 144//144 145//145 -f 146//146 147//147 148//148 -f 148//148 147//147 139//139 -f 148//148 139//139 149//149 -f 149//149 139//139 150//150 -f 146//146 151//151 147//147 -f 147//147 151//151 152//152 -f 147//147 152//152 153//153 -f 153//153 152//152 154//154 -f 153//153 154//154 141//141 -f 144//144 138//138 155//155 -f 155//155 138//138 153//153 -f 155//155 153//153 156//156 -f 143//143 142//142 157//157 -f 143//143 158//158 141//141 -f 141//141 158//158 159//159 -f 141//141 159//159 153//153 -f 153//153 159//159 160//160 -f 153//153 160//160 156//156 -f 145//145 161//161 138//138 -f 138//138 161//161 162//162 -f 138//138 162//162 139//139 -f 139//139 162//162 163//163 -f 139//139 163//163 157//157 -f 142//142 164//164 157//157 -f 157//157 164//164 165//165 -f 157//157 165//165 139//139 -f 139//139 165//165 166//166 -f 139//139 166//166 150//150 -f 167//167 147//147 168//168 -f 168//168 147//147 153//153 -f 132//132 169//169 170//170 -f 171//171 172//172 173//173 -f 173//173 172//172 174//174 -f 175//175 176//176 170//170 -f 170//170 176//176 177//177 -f 170//170 177//177 132//132 -f 132//132 177//177 178//178 -f 132//132 178//178 179//179 -f 180//180 181//181 182//182 -f 183//183 184//184 179//179 -f 179//179 184//184 185//185 -f 179//179 185//185 132//132 -f 132//132 185//185 186//186 -f 132//132 186//186 182//182 -f 182//182 186//186 187//187 -f 182//182 187//187 180//180 -f 188//188 189//189 174//174 -f 190//190 191//191 183//183 -f 183//183 191//191 192//192 -f 183//183 192//192 184//184 -f 189//189 193//193 174//174 -f 174//174 193//193 194//194 -f 174//174 194//194 191//191 -f 130//130 172//172 195//195 -f 190//190 196//196 191//191 -f 191//191 196//196 197//197 -f 191//191 197//197 174//174 -f 174//174 197//197 198//198 -f 174//174 198//198 173//173 -f 195//195 199//199 130//130 -f 130//130 199//199 200//200 -f 130//130 200//200 132//132 -f 132//132 200//200 201//201 -f 132//132 201//201 169//169 -f 175//175 202//202 176//176 -f 176//176 202//202 203//203 -f 176//176 203//203 204//204 -f 204//204 203//203 205//205 -f 204//204 205//205 171//171 -f 171//171 205//205 206//206 -f 171//171 206//206 172//172 -f 172//172 206//206 207//207 -f 172//172 207//207 195//195 -f 137//137 139//139 147//147 -f 167//167 182//182 147//147 -f 147//147 182//182 208//208 -f 147//147 208//208 137//137 -f 208//208 209//209 210//210 -f 211//211 212//212 213//213 -f 213//213 212//212 214//214 -f 213//213 214//214 208//208 -f 208//208 214//214 215//215 -f 208//208 215//215 216//216 -f 208//208 210//210 137//137 -f 137//137 210//210 217//217 -f 137//137 217//217 218//218 -f 219//219 4//4 220//220 -f 220//220 4//4 2//2 -f 220//220 2//2 221//221 -f 221//221 2//2 137//137 -f 219//219 222//222 4//4 -f 4//4 222//222 223//223 -f 4//4 223//223 213//213 -f 213//213 223//223 224//224 -f 213//213 224//224 211//211 -f 225//225 216//216 226//226 -f 226//226 216//216 227//227 -f 226//226 227//227 228//228 -f 228//228 227//227 221//221 -f 228//228 221//221 229//229 -f 229//229 221//221 137//137 -f 229//229 137//137 230//230 -f 230//230 137//137 218//218 -f 225//225 231//231 216//216 -f 216//216 231//231 232//232 -f 216//216 232//232 208//208 -f 208//208 232//232 233//233 -f 208//208 233//233 209//209 -f 234//234 213//213 235//235 -f 235//235 213//213 208//208 -f 235//235 208//208 174//174 -f 174//174 208//208 182//182 -f 174//174 182//182 188//188 -f 188//188 182//182 181//181 -f 112//112 236//236 237//237 -f 153//153 138//138 140//140 -f 238//238 239//239 236//236 -f 168//168 238//238 240//240 -f 240//240 238//238 58//58 -f 134//134 122//122 120//120 -f 134//134 120//120 136//136 -f 120//120 118//118 136//136 -f 136//136 118//118 116//116 -f 136//136 116//116 237//237 -f 237//237 116//116 114//114 -f 237//237 114//114 112//112 -f 58//58 80//80 240//240 -f 240//240 80//80 78//78 -f 240//240 78//78 76//76 -f 98//98 106//106 100//100 -f 100//100 106//106 128//128 -f 100//100 128//128 240//240 -f 240//240 128//128 126//126 -f 240//240 126//126 134//134 -f 134//134 126//126 124//124 -f 134//134 124//124 122//122 -f 74//74 82//82 76//76 -f 76//76 82//82 104//104 -f 76//76 104//104 240//240 -f 240//240 104//104 102//102 -f 240//240 102//102 100//100 -f 98//98 96//96 106//106 -f 106//106 96//96 94//94 -f 106//106 94//94 108//108 -f 108//108 94//94 92//92 -f 108//108 92//92 110//110 -f 110//110 92//92 90//90 -f 110//110 90//90 112//112 -f 112//112 90//90 88//88 -f 112//112 88//88 236//236 -f 236//236 88//88 86//86 -f 236//236 62//62 238//238 -f 238//238 62//62 60//60 -f 238//238 60//60 58//58 -f 74//74 72//72 82//82 -f 82//82 72//72 70//70 -f 82//82 70//70 84//84 -f 84//84 70//70 68//68 -f 84//84 68//68 86//86 -f 86//86 68//68 66//66 -f 86//86 66//66 236//236 -f 236//236 66//66 64//64 -f 236//236 64//64 62//62 -f 52//52 50//50 238//238 -f 168//168 153//153 238//238 -f 238//238 153//153 140//140 -f 238//238 140//140 52//52 -f 52//52 140//140 54//54 -f 8//8 6//6 38//38 -f 238//238 26//26 24//24 -f 241//241 22//22 20//20 -f 50//50 48//48 238//238 -f 238//238 48//48 46//46 -f 238//238 46//46 26//26 -f 38//38 36//36 8//8 -f 8//8 36//36 34//34 -f 8//8 34//34 140//140 -f 140//140 34//34 56//56 -f 140//140 56//56 54//54 -f 242//242 239//239 241//241 -f 241//241 239//239 238//238 -f 241//241 238//238 22//22 -f 22//22 238//238 24//24 -f 20//20 18//18 241//241 -f 241//241 18//18 16//16 -f 241//241 16//16 6//6 -f 6//6 16//16 14//14 -f 6//6 14//14 12//12 -f 12//12 10//10 6//6 -f 6//6 10//10 32//32 -f 6//6 32//32 38//38 -f 38//38 32//32 30//30 -f 38//38 30//30 40//40 -f 40//40 30//30 28//28 -f 40//40 28//28 42//42 -f 42//42 28//28 26//26 -f 42//42 26//26 44//44 -f 44//44 26//26 46//46 -f 219//219 243//243 222//222 -f 222//222 243//243 244//244 -f 222//222 244//244 223//223 -f 223//223 244//244 245//245 -f 223//223 245//245 224//224 -f 224//224 245//245 246//246 -f 224//224 246//246 211//211 -f 211//211 246//246 247//247 -f 211//211 247//247 212//212 -f 212//212 247//247 248//248 -f 212//212 248//248 214//214 -f 214//214 248//248 249//249 -f 214//214 249//249 215//215 -f 215//215 249//249 250//250 -f 215//215 250//250 216//216 -f 216//216 250//250 251//251 -f 216//216 251//251 227//227 -f 227//227 251//251 252//252 -f 227//227 252//252 221//221 -f 221//221 252//252 253//253 -f 221//221 253//253 220//220 -f 220//220 253//253 254//254 -f 220//220 254//254 219//219 -f 219//219 254//254 243//243 -f 230//230 255//255 229//229 -f 229//229 255//255 256//256 -f 229//229 256//256 228//228 -f 228//228 256//256 257//257 -f 228//228 257//257 226//226 -f 226//226 257//257 258//258 -f 226//226 258//258 225//225 -f 225//225 258//258 259//259 -f 225//225 259//259 231//231 -f 231//231 259//259 260//260 -f 231//231 260//260 232//232 -f 232//232 260//260 261//261 -f 232//232 261//261 233//233 -f 233//233 261//261 262//262 -f 233//233 262//262 209//209 -f 209//209 262//262 263//263 -f 209//209 263//263 210//210 -f 210//210 263//263 264//264 -f 210//210 264//264 217//217 -f 217//217 264//264 265//265 -f 217//217 265//265 218//218 -f 218//218 265//265 266//266 -f 218//218 266//266 230//230 -f 230//230 266//266 255//255 -f 188//188 267//267 189//189 -f 189//189 267//267 268//268 -f 189//189 268//268 193//193 -f 193//193 268//268 269//269 -f 193//193 269//269 194//194 -f 194//194 269//269 270//270 -f 194//194 270//270 191//191 -f 191//191 270//270 271//271 -f 191//191 271//271 192//192 -f 192//192 271//271 272//272 -f 192//192 272//272 184//184 -f 184//184 272//272 273//273 -f 184//184 273//273 185//185 -f 185//185 273//273 274//274 -f 185//185 274//274 186//186 -f 186//186 274//274 275//275 -f 186//186 275//275 187//187 -f 187//187 275//275 276//276 -f 187//187 276//276 180//180 -f 180//180 276//276 277//277 -f 180//180 277//277 181//181 -f 181//181 277//277 278//278 -f 181//181 278//278 188//188 -f 188//188 278//278 267//267 -f 196//196 279//279 197//197 -f 197//197 279//279 280//280 -f 197//197 280//280 198//198 -f 198//198 280//280 281//281 -f 198//198 281//281 173//173 -f 173//173 281//281 282//282 -f 173//173 282//282 171//171 -f 171//171 282//282 283//283 -f 171//171 283//283 204//204 -f 204//204 283//283 284//284 -f 204//204 284//284 176//176 -f 176//176 284//284 285//285 -f 176//176 285//285 177//177 -f 177//177 285//285 286//286 -f 177//177 286//286 178//178 -f 178//178 286//286 287//287 -f 178//178 287//287 179//179 -f 179//179 287//287 288//288 -f 179//179 288//288 183//183 -f 183//183 288//288 289//289 -f 183//183 289//289 190//190 -f 190//190 289//289 290//290 -f 190//190 290//290 196//196 -f 196//196 290//290 279//279 -f 203//203 291//291 205//205 -f 205//205 291//291 292//292 -f 205//205 292//292 206//206 -f 206//206 292//292 293//293 -f 206//206 293//293 207//207 -f 207//207 293//293 294//294 -f 207//207 294//294 195//195 -f 195//195 294//294 295//295 -f 195//195 295//295 199//199 -f 199//199 295//295 296//296 -f 199//199 296//296 200//200 -f 200//200 296//296 297//297 -f 200//200 297//297 201//201 -f 201//201 297//297 298//298 -f 201//201 298//298 169//169 -f 169//169 298//298 299//299 -f 169//169 299//299 170//170 -f 170//170 299//299 300//300 -f 170//170 300//300 175//175 -f 175//175 300//300 301//301 -f 175//175 301//301 202//202 -f 202//202 301//301 302//302 -f 202//202 302//302 203//203 -f 203//203 302//302 291//291 -f 303//303 304//304 305//305 -f 306//306 294//294 305//305 -f 305//305 294//294 293//293 -f 307//307 303//303 308//308 -f 308//308 303//303 267//267 -f 308//308 288//288 131//131 -f 131//131 288//288 287//287 -f 131//131 287//287 300//300 -f 281//281 305//305 282//282 -f 282//282 305//305 293//293 -f 282//282 293//293 283//283 -f 283//283 293//293 292//292 -f 283//283 292//292 284//284 -f 267//267 278//278 308//308 -f 308//308 278//278 277//277 -f 308//308 277//277 276//276 -f 284//284 292//292 285//285 -f 285//285 292//292 291//291 -f 285//285 291//291 286//286 -f 286//286 291//291 302//302 -f 286//286 302//302 287//287 -f 287//287 302//302 301//301 -f 287//287 301//301 300//300 -f 300//300 299//299 131//131 -f 131//131 299//299 298//298 -f 131//131 298//298 129//129 -f 298//298 297//297 129//129 -f 129//129 297//297 296//296 -f 129//129 296//296 306//306 -f 306//306 296//296 295//295 -f 306//306 295//295 294//294 -f 275//275 279//279 276//276 -f 276//276 279//279 290//290 -f 276//276 290//290 308//308 -f 308//308 290//290 289//289 -f 308//308 289//289 288//288 -f 305//305 269//269 303//303 -f 303//303 269//269 268//268 -f 303//303 268//268 267//267 -f 275//275 274//274 279//279 -f 279//279 274//274 273//273 -f 279//279 273//273 280//280 -f 280//280 273//273 272//272 -f 280//280 272//272 281//281 -f 281//281 272//272 271//271 -f 281//281 271//271 305//305 -f 305//305 271//271 270//270 -f 305//305 270//270 269//269 -f 264//264 263//263 303//303 -f 307//307 309//309 303//303 -f 303//303 309//309 310//310 -f 303//303 310//310 264//264 -f 264//264 310//310 265//265 -f 303//303 251//251 250//250 -f 311//311 249//249 248//248 -f 263//263 262//262 303//303 -f 303//303 262//262 261//261 -f 303//303 261//261 251//251 -f 257//257 256//256 312//312 -f 312//312 256//256 255//255 -f 312//312 255//255 310//310 -f 310//310 255//255 266//266 -f 310//310 266//266 265//265 -f 313//313 304//304 311//311 -f 311//311 304//304 303//303 -f 311//311 303//303 249//249 -f 249//249 303//303 250//250 -f 248//248 247//247 311//311 -f 311//311 247//247 246//246 -f 311//311 246//246 312//312 -f 312//312 246//246 245//245 -f 312//312 245//245 244//244 -f 244//244 243//243 312//312 -f 312//312 243//243 254//254 -f 312//312 254//254 257//257 -f 257//257 254//254 253//253 -f 257//257 253//253 258//258 -f 258//258 253//253 252//252 -f 258//258 252//252 259//259 -f 259//259 252//252 251//251 -f 259//259 251//251 260//260 -f 260//260 251//251 261//261 -f 133//133 121//121 123//123 -f 89//89 314//314 87//87 -f 87//87 314//314 315//315 -f 125//125 93//93 123//123 -f 123//123 93//93 95//95 -f 123//123 95//95 133//133 -f 133//133 95//95 97//97 -f 133//133 97//97 99//99 -f 77//77 79//79 316//316 -f 101//101 69//69 99//99 -f 99//99 69//69 71//71 -f 99//99 71//71 133//133 -f 133//133 71//71 73//73 -f 133//133 73//73 316//316 -f 316//316 73//73 75//75 -f 316//316 75//75 77//77 -f 57//57 59//59 315//315 -f 103//103 65//65 101//101 -f 101//101 65//65 67//67 -f 101//101 67//67 69//69 -f 59//59 61//61 315//315 -f 315//315 61//61 63//63 -f 315//315 63//63 65//65 -f 135//135 314//314 113//113 -f 79//79 57//57 316//316 -f 316//316 57//57 315//315 -f 316//316 315//315 317//317 -f 317//317 315//315 318//318 -f 317//317 318//318 319//319 -f 319//319 318//318 320//320 -f 103//103 81//81 65//65 -f 65//65 81//81 83//83 -f 65//65 83//83 315//315 -f 315//315 83//83 85//85 -f 315//315 85//85 87//87 -f 113//113 115//115 135//135 -f 135//135 115//115 117//117 -f 135//135 117//117 133//133 -f 133//133 117//117 119//119 -f 133//133 119//119 121//121 -f 125//125 127//127 93//93 -f 93//93 127//127 105//105 -f 93//93 105//105 91//91 -f 91//91 105//105 107//107 -f 91//91 107//107 89//89 -f 89//89 107//107 109//109 -f 89//89 109//109 314//314 -f 314//314 109//109 111//111 -f 314//314 111//111 113//113 -f 25//25 33//33 35//35 -f 317//317 49//49 51//51 -f 41//41 43//43 319//319 -f 319//319 43//43 45//45 -f 319//319 45//45 317//317 -f 317//317 45//45 47//47 -f 317//317 47//47 49//49 -f 321//321 316//316 322//322 -f 322//322 316//316 317//317 -f 322//322 317//317 323//323 -f 323//323 317//317 51//51 -f 9//9 324//324 323//323 -f 51//51 53//53 323//323 -f 323//323 53//53 55//55 -f 323//323 55//55 33//33 -f 35//35 37//37 25//25 -f 25//25 37//37 39//39 -f 25//25 39//39 23//23 -f 23//23 39//39 41//41 -f 23//23 41//41 21//21 -f 21//21 41//41 319//319 -f 21//21 319//319 19//19 -f 19//19 319//319 17//17 -f 25//25 27//27 33//33 -f 33//33 27//27 29//29 -f 33//33 29//29 323//323 -f 323//323 29//29 31//31 -f 323//323 31//31 9//9 -f 9//9 11//11 324//324 -f 324//324 11//11 13//13 -f 324//324 13//13 319//319 -f 319//319 13//13 15//15 -f 319//319 15//15 17//17 -f 309//309 322//322 310//310 -f 310//310 322//322 323//323 -f 310//310 323//323 312//312 -f 312//312 323//323 324//324 -f 307//307 321//321 309//309 -f 309//309 321//321 322//322 -f 237//237 314//314 136//136 -f 136//136 314//314 135//135 -f 306//306 172//172 129//129 -f 129//129 172//172 130//130 -f 134//134 132//132 240//240 -f 240//240 132//132 182//182 -f 240//240 182//182 168//168 -f 168//168 182//182 167//167 -f 321//321 307//307 316//316 -f 316//316 307//307 308//308 -f 316//316 308//308 133//133 -f 133//133 308//308 131//131 -f 174//174 172//172 305//305 -f 305//305 172//172 306//306 -f 313//313 234//234 304//304 -f 304//304 234//234 235//235 -f 304//304 235//235 305//305 -f 305//305 235//235 174//174 -f 312//312 4//4 213//213 -f 234//234 313//313 213//213 -f 213//213 313//313 311//311 -f 213//213 311//311 312//312 -f 320//320 242//242 319//319 -f 319//319 242//242 241//241 -f 319//319 241//241 324//324 -f 241//241 6//6 324//324 -f 324//324 6//6 5//5 -f 324//324 5//5 312//312 -f 312//312 5//5 3//3 -f 312//312 3//3 4//4 -f 237//237 236//236 314//314 -f 314//314 236//236 315//315 -f 315//315 236//236 318//318 -f 318//318 236//236 239//239 -f 318//318 239//239 320//320 -f 320//320 239//239 242//242 -f 325//325 326//326 5//5 -f 5//5 326//326 3//3 -f 326//326 1//1 3//3 -f 325//325 5//5 7//7 -f 7//7 327//327 328//328 -f 328//328 329//329 7//7 -f 7//7 329//329 330//330 -f 7//7 330//330 325//325 -f 330//330 331//331 325//325 -f 325//325 331//331 332//332 -f 325//325 332//332 333//333 -f 334//334 335//335 326//326 -f 326//326 335//335 336//336 -f 326//326 336//336 1//1 -f 1//1 336//336 337//337 -f 1//1 337//337 338//338 -f 339//339 340//340 333//333 -f 333//333 340//340 341//341 -f 333//333 341//341 325//325 -f 325//325 341//341 342//342 -f 325//325 342//342 326//326 -f 326//326 342//342 343//343 -f 326//326 343//343 334//334 -f 327//327 7//7 344//344 -f 344//344 7//7 1//1 -f 344//344 1//1 345//345 -f 338//338 346//346 1//1 -f 1//1 346//346 347//347 -f 1//1 347//347 345//345 -f 345//345 347//347 348//348 -f 345//345 348//348 349//349 -f 349//349 348//348 340//340 -f 349//349 340//340 350//350 -f 350//350 340//340 339//339 -f 142//142 340//340 164//164 -f 164//164 340//340 348//348 -f 164//164 348//348 165//165 -f 165//165 348//348 347//347 -f 165//165 347//347 166//166 -f 166//166 347//347 346//346 -f 166//166 346//346 150//150 -f 150//150 346//346 338//338 -f 150//150 338//338 149//149 -f 149//149 338//338 337//337 -f 149//149 337//337 148//148 -f 148//148 337//337 336//336 -f 148//148 336//336 146//146 -f 146//146 336//336 335//335 -f 146//146 335//335 151//151 -f 151//151 335//335 334//334 -f 151//151 334//334 152//152 -f 152//152 334//334 343//343 -f 152//152 343//343 154//154 -f 154//154 343//343 342//342 -f 154//154 342//342 141//141 -f 141//141 342//342 341//341 -f 141//141 341//341 142//142 -f 142//142 341//341 340//340 -f 144//144 330//330 145//145 -f 145//145 330//330 329//329 -f 145//145 329//329 161//161 -f 161//161 329//329 328//328 -f 161//161 328//328 162//162 -f 162//162 328//328 327//327 -f 162//162 327//327 163//163 -f 163//163 327//327 344//344 -f 163//163 344//344 157//157 -f 157//157 344//344 345//345 -f 157//157 345//345 143//143 -f 143//143 345//345 349//349 -f 143//143 349//349 158//158 -f 158//158 349//349 350//350 -f 158//158 350//350 159//159 -f 159//159 350//350 339//339 -f 159//159 339//339 160//160 -f 160//160 339//339 333//333 -f 160//160 333//333 156//156 -f 156//156 333//333 332//332 -f 156//156 332//332 155//155 -f 155//155 332//332 331//331 -f 155//155 331//331 144//144 -f 144//144 331//331 330//330 -f 351//351 352//352 353//353 -f 353//353 354//354 351//351 -f 351//351 354//354 355//355 -f 351//351 355//355 356//356 -f 357//357 358//358 354//354 -f 354//354 358//358 359//359 -f 354//354 359//359 360//360 -f 361//361 362//362 354//354 -f 354//354 362//362 363//363 -f 354//354 363//363 355//355 -f 360//360 364//364 354//354 -f 354//354 364//364 365//365 -f 354//354 365//365 361//361 -f 366//366 367//367 368//368 -f 368//368 367//367 369//369 -f 370//370 371//371 372//372 -f 371//371 370//370 373//373 -f 374//374 375//375 376//376 -f 377//377 378//378 379//379 -f 369//369 380//380 368//368 -f 368//368 380//380 381//381 -f 368//368 381//381 382//382 -f 382//382 381//381 383//383 -f 382//382 383//383 384//384 -f 384//384 383//383 377//377 -f 384//384 377//377 385//385 -f 385//385 377//377 379//379 -f 372//372 386//386 370//370 -f 370//370 386//386 387//387 -f 370//370 387//387 388//388 -f 388//388 387//387 389//389 -f 388//388 389//389 390//390 -f 390//390 389//389 391//391 -f 390//390 391//391 378//378 -f 378//378 391//391 392//392 -f 378//378 392//392 379//379 -f 376//376 393//393 374//374 -f 374//374 393//393 394//394 -f 374//374 394//394 395//395 -f 395//395 394//394 396//396 -f 395//395 396//396 397//397 -f 397//397 396//396 398//398 -f 398//398 399//399 400//400 -f 370//370 397//397 373//373 -f 373//373 397//397 398//398 -f 373//373 398//398 401//401 -f 401//401 398//398 400//400 -f 402//402 403//403 404//404 -f 405//405 406//406 407//407 -f 408//408 409//409 410//410 -f 410//410 409//409 411//411 -f 412//412 405//405 413//413 -f 413//413 405//405 407//407 -f 413//413 407//407 414//414 -f 414//414 407//407 415//415 -f 413//413 416//416 412//412 -f 412//412 416//416 417//417 -f 412//412 417//417 418//418 -f 418//418 417//417 419//419 -f 420//420 403//403 421//421 -f 421//421 403//403 402//402 -f 421//421 402//402 422//422 -f 422//422 402//402 423//423 -f 422//422 423//423 424//424 -f 424//424 423//423 425//425 -f 424//424 425//425 426//426 -f 426//426 425//425 419//419 -f 426//426 419//419 427//427 -f 427//427 419//419 417//417 -f 428//428 429//429 430//430 -f 430//430 429//429 431//431 -f 430//430 431//431 409//409 -f 409//409 431//431 432//432 -f 409//409 432//432 411//411 -f 433//433 434//434 435//435 -f 435//435 434//434 429//429 -f 435//435 429//429 404//404 -f 404//404 429//429 428//428 -f 404//404 428//428 402//402 -f 436//436 437//437 438//438 -f 439//439 440//440 441//441 -f 442//442 443//443 444//444 -f 444//444 443//443 445//445 -f 446//446 447//447 443//443 -f 438//438 448//448 446//446 -f 449//449 450//450 451//451 -f 452//452 453//453 454//454 -f 454//454 453//453 436//436 -f 454//454 436//436 455//455 -f 455//455 436//436 438//438 -f 455//455 438//438 456//456 -f 456//456 438//438 446//446 -f 456//456 446//446 457//457 -f 457//457 446//446 443//443 -f 458//458 459//459 437//437 -f 437//437 459//459 460//460 -f 437//437 460//460 461//461 -f 462//462 463//463 437//437 -f 437//437 463//463 464//464 -f 437//437 464//464 438//438 -f 465//465 445//445 440//440 -f 440//440 445//445 443//443 -f 440//440 443//443 441//441 -f 441//441 443//443 447//447 -f 439//439 441//441 451//451 -f 451//451 441//441 466//466 -f 451//451 466//466 449//449 -f 461//461 467//467 437//437 -f 437//437 467//467 468//468 -f 437//437 468//468 462//462 -f 469//469 470//470 471//471 -f 471//471 470//470 472//472 -f 471//471 472//472 473//473 -f 474//474 475//475 476//476 -f 476//476 475//475 477//477 -f 478//478 479//479 480//480 -f 478//478 480//480 481//481 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 486//486 487//487 488//488 -f 480//480 486//486 489//489 -f 480//480 490//490 486//486 -f 486//486 490//490 491//491 -f 486//486 491//491 487//487 -f 492//492 486//486 493//493 -f 493//493 486//486 488//488 -f 493//493 488//488 494//494 -f 494//494 488//488 483//483 -f 494//494 483//483 495//495 -f 482//482 496//496 483//483 -f 483//483 496//496 497//497 -f 483//483 497//497 495//495 -f 498//498 499//499 500//500 -f 489//489 501//501 480//480 -f 480//480 501//501 502//502 -f 480//480 502//502 503//503 -f 497//497 504//504 495//495 -f 495//495 504//504 498//498 -f 495//495 498//498 505//505 -f 505//505 498//498 500//500 -f 503//503 506//506 480//480 -f 480//480 506//506 507//507 -f 480//480 507//507 481//481 -f 369//369 475//475 380//380 -f 380//380 475//475 474//474 -f 478//478 358//358 479//479 -f 479//479 358//358 357//357 -f 508//508 509//509 510//510 -f 511//511 512//512 510//510 -f 510//510 512//512 513//513 -f 508//508 510//510 514//514 -f 513//513 515//515 510//510 -f 510//510 515//515 516//516 -f 510//510 516//516 517//517 -f 517//517 518//518 510//510 -f 510//510 518//518 519//519 -f 510//510 519//519 520//520 -f 520//520 521//521 510//510 -f 510//510 521//521 522//522 -f 510//510 522//522 514//514 -f 508//508 459//459 509//509 -f 509//509 459//459 458//458 -f 523//523 524//524 525//525 -f 526//526 527//527 515//515 -f 528//528 529//529 523//523 -f 530//530 531//531 532//532 -f 532//532 531//531 523//523 -f 532//532 523//523 533//533 -f 533//533 523//523 529//529 -f 525//525 534//534 523//523 -f 523//523 534//534 535//535 -f 523//523 535//535 526//526 -f 526//526 515//515 523//523 -f 523//523 515//515 536//536 -f 523//523 536//536 528//528 -f 438//438 516//516 448//448 -f 448//448 516//516 515//515 -f 448//448 515//515 537//537 -f 537//537 515//515 527//527 -f 156//156 160//160 538//538 -f 539//539 152//152 540//540 -f 538//538 160//160 540//540 -f 161//161 541//541 542//542 -f 542//542 541//541 144//144 -f 542//542 144//144 538//538 -f 538//538 144//144 543//543 -f 538//538 543//543 156//156 -f 544//544 539//539 158//158 -f 158//158 539//539 540//540 -f 158//158 540//540 159//159 -f 159//159 540//540 160//160 -f 152//152 151//151 540//540 -f 540//540 151//151 545//545 -f 540//540 545//545 546//546 -f 546//546 545//545 547//547 -f 546//546 547//547 548//548 -f 544//544 158//158 549//549 -f 549//549 158//158 143//143 -f 549//549 143//143 550//550 -f 548//548 150//150 546//546 -f 546//546 150//150 166//166 -f 546//546 166//166 542//542 -f 542//542 166//166 551//551 -f 542//542 551//551 550//550 -f 143//143 157//157 550//550 -f 550//550 157//157 163//163 -f 550//550 163//163 542//542 -f 542//542 163//163 162//162 -f 542//542 162//162 161//161 -f 552//552 553//553 554//554 -f 554//554 553//553 555//555 -f 554//554 555//555 556//556 -f 557//557 558//558 553//553 -f 553//553 558//558 559//559 -f 553//553 559//559 560//560 -f 561//561 356//356 562//562 -f 562//562 356//356 553//553 -f 562//562 553//553 563//563 -f 563//563 553//553 552//552 -f 355//355 486//486 356//356 -f 356//356 486//486 492//492 -f 492//492 564//564 356//356 -f 356//356 564//564 565//565 -f 356//356 565//565 553//553 -f 553//553 565//565 566//566 -f 553//553 566//566 557//557 -f 567//567 568//568 569//569 -f 569//569 568//568 570//570 -f 570//570 571//571 569//569 -f 569//569 571//571 572//572 -f 569//569 572//572 573//573 -f 572//572 574//574 573//573 -f 573//573 574//574 575//575 -f 573//573 575//575 576//576 -f 576//576 575//575 577//577 -f 578//578 579//579 567//567 -f 567//567 579//579 580//580 -f 567//567 580//580 568//568 -f 573//573 581//581 569//569 -f 569//569 581//581 582//582 -f 569//569 582//582 583//583 -f 584//584 585//585 586//586 -f 587//587 588//588 589//589 -f 589//589 588//588 584//584 -f 589//589 584//584 590//590 -f 590//590 584//584 586//586 -f 591//591 592//592 593//593 -f 582//582 594//594 583//583 -f 583//583 594//594 595//595 -f 583//583 595//595 593//593 -f 593//593 595//595 596//596 -f 593//593 596//596 591//591 -f 597//597 598//598 599//599 -f 599//599 598//598 588//588 -f 599//599 588//588 600//600 -f 600//600 588//588 587//587 -f 601//601 598//598 602//602 -f 602//602 598//598 597//597 -f 602//602 597//597 603//603 -f 603//603 597//597 604//604 -f 603//603 604//604 605//605 -f 606//606 607//607 608//608 -f 608//608 607//607 598//598 -f 608//608 598//598 609//609 -f 609//609 598//598 601//601 -f 606//606 610//610 607//607 -f 607//607 610//610 611//611 -f 607//607 611//611 612//612 -f 613//613 614//614 586//586 -f 586//586 614//614 591//591 -f 586//586 591//591 590//590 -f 590//590 591//591 596//596 -f 590//590 596//596 615//615 -f 615//615 596//596 616//616 -f 615//615 616//616 617//617 -f 617//617 616//616 618//618 -f 593//593 592//592 619//619 -f 614//614 613//613 620//620 -f 593//593 619//619 621//621 -f 622//622 623//623 624//624 -f 624//624 623//623 584//584 -f 584//584 623//623 625//625 -f 584//584 625//625 585//585 -f 619//619 626//626 621//621 -f 621//621 626//626 627//627 -f 621//621 627//627 624//624 -f 624//624 627//627 628//628 -f 624//624 628//628 622//622 -f 622//622 628//628 629//629 -f 629//629 628//628 620//620 -f 620//620 628//628 630//630 -f 620//620 630//630 614//614 -f 631//631 144//144 632//632 -f 632//632 144//144 541//541 -f 632//632 541//541 633//633 -f 633//633 541//541 161//161 -f 633//633 161//161 634//634 -f 634//634 161//161 162//162 -f 634//634 162//162 635//635 -f 635//635 162//162 163//163 -f 635//635 163//163 636//636 -f 636//636 163//163 157//157 -f 636//636 157//157 637//637 -f 637//637 157//157 143//143 -f 637//637 143//143 638//638 -f 638//638 143//143 158//158 -f 638//638 158//158 639//639 -f 639//639 158//158 159//159 -f 639//639 159//159 640//640 -f 640//640 159//159 160//160 -f 640//640 160//160 641//641 -f 641//641 160//160 156//156 -f 641//641 156//156 642//642 -f 642//642 156//156 543//543 -f 642//642 543//543 631//631 -f 631//631 543//543 144//144 -f 643//643 549//549 644//644 -f 644//644 549//549 550//550 -f 644//644 550//550 645//645 -f 645//645 550//550 551//551 -f 645//645 551//551 646//646 -f 646//646 551//551 166//166 -f 646//646 166//166 647//647 -f 647//647 166//166 150//150 -f 647//647 150//150 648//648 -f 648//648 150//150 548//548 -f 648//648 548//548 649//649 -f 649//649 548//548 547//547 -f 649//649 547//547 650//650 -f 650//650 547//547 545//545 -f 650//650 545//545 651//651 -f 651//651 545//545 151//151 -f 651//651 151//151 652//652 -f 652//652 151//151 152//152 -f 652//652 152//152 653//653 -f 653//653 152//152 539//539 -f 653//653 539//539 654//654 -f 654//654 539//539 544//544 -f 654//654 544//544 643//643 -f 643//643 544//544 549//549 -f 526//526 535//535 602//602 -f 602//602 535//535 601//601 -f 655//655 656//656 657//657 -f 657//657 656//656 658//658 -f 657//657 658//658 659//659 -f 659//659 658//658 660//660 -f 659//659 660//660 661//661 -f 661//661 660//660 662//662 -f 661//661 662//662 663//663 -f 663//663 662//662 664//664 -f 663//663 664//664 665//665 -f 665//665 664//664 666//666 -f 665//665 666//666 667//667 -f 667//667 666//666 668//668 -f 667//667 668//668 669//669 -f 669//669 668//668 670//670 -f 669//669 670//670 671//671 -f 671//671 670//670 672//672 -f 671//671 672//672 673//673 -f 673//673 672//672 674//674 -f 673//673 674//674 675//675 -f 675//675 674//674 676//676 -f 675//675 676//676 677//677 -f 677//677 676//676 678//678 -f 677//677 678//678 655//655 -f 655//655 678//678 656//656 -f 679//679 388//388 390//390 -f 680//680 412//412 418//418 -f 681//681 682//682 683//683 -f 683//683 682//682 684//684 -f 683//683 684//684 477//477 -f 685//685 686//686 383//383 -f 383//383 686//686 687//687 -f 383//383 687//687 377//377 -f 680//680 418//418 688//688 -f 688//688 418//418 689//689 -f 688//688 689//689 690//690 -f 690//690 689//689 691//691 -f 690//690 691//691 684//684 -f 684//684 691//691 692//692 -f 684//684 692//692 477//477 -f 680//680 681//681 412//412 -f 412//412 681//681 683//683 -f 412//412 683//683 405//405 -f 405//405 683//683 693//693 -f 405//405 693//693 406//406 -f 406//406 693//693 694//694 -f 692//692 685//685 477//477 -f 477//477 685//685 383//383 -f 477//477 383//383 476//476 -f 476//476 383//383 381//381 -f 476//476 381//381 474//474 -f 474//474 381//381 380//380 -f 425//425 423//423 695//695 -f 696//696 697//697 698//698 -f 698//698 697//697 699//699 -f 698//698 699//699 700//700 -f 700//700 699//699 701//701 -f 700//700 701//701 702//702 -f 702//702 701//701 703//703 -f 702//702 703//703 695//695 -f 695//695 703//703 679//679 -f 695//695 679//679 425//425 -f 425//425 679//679 390//390 -f 425//425 390//390 419//419 -f 419//419 390//390 378//378 -f 419//419 378//378 418//418 -f 418//418 378//378 377//377 -f 418//418 377//377 689//689 -f 689//689 377//377 687//687 -f 475//475 704//704 477//477 -f 477//477 704//704 683//683 -f 369//369 367//367 475//475 -f 475//475 367//367 415//415 -f 475//475 415//415 704//704 -f 704//704 415//415 407//407 -f 414//414 415//415 366//366 -f 366//366 415//415 367//367 -f 382//382 384//384 705//705 -f 705//705 706//706 382//382 -f 382//382 706//706 707//707 -f 382//382 707//707 708//708 -f 709//709 710//710 416//416 -f 416//416 710//710 711//711 -f 708//708 712//712 382//382 -f 382//382 712//712 713//713 -f 382//382 713//713 416//416 -f 416//416 713//713 714//714 -f 416//416 714//714 709//709 -f 711//711 715//715 416//416 -f 416//416 715//715 716//716 -f 416//416 716//716 417//417 -f 717//717 718//718 719//719 -f 719//719 718//718 720//720 -f 719//719 720//720 721//721 -f 721//721 720//720 722//722 -f 721//721 722//722 723//723 -f 723//723 722//722 724//724 -f 723//723 724//724 725//725 -f 725//725 724//724 726//726 -f 725//725 726//726 727//727 -f 727//727 726//726 728//728 -f 727//727 728//728 713//713 -f 713//713 728//728 714//714 -f 729//729 730//730 731//731 -f 731//731 730//730 732//732 -f 731//731 732//732 717//717 -f 717//717 732//732 733//733 -f 717//717 733//733 718//718 -f 734//734 735//735 546//546 -f 736//736 523//523 542//542 -f 737//737 738//738 371//371 -f 371//371 738//738 353//353 -f 542//542 739//739 740//740 -f 531//531 741//741 523//523 -f 523//523 741//741 512//512 -f 352//352 742//742 555//555 -f 743//743 744//744 511//511 -f 511//511 744//744 403//403 -f 555//555 553//553 352//352 -f 352//352 553//553 546//546 -f 352//352 546//546 353//353 -f 353//353 546//546 542//542 -f 353//353 542//542 371//371 -f 371//371 542//542 523//523 -f 371//371 523//523 372//372 -f 740//740 745//745 542//542 -f 542//542 745//745 746//746 -f 542//542 746//746 736//736 -f 372//372 523//523 747//747 -f 747//747 523//523 512//512 -f 747//747 512//512 748//748 -f 729//729 749//749 512//512 -f 512//512 749//749 750//750 -f 512//512 750//750 751//751 -f 751//751 752//752 512//512 -f 512//512 752//752 753//753 -f 512//512 753//753 748//748 -f 754//754 734//734 755//755 -f 755//755 734//734 546//546 -f 755//755 546//546 756//756 -f 756//756 546//546 553//553 -f 757//757 758//758 759//759 -f 759//759 758//758 760//760 -f 759//759 760//760 420//420 -f 420//420 760//760 730//730 -f 420//420 730//730 403//403 -f 403//403 730//730 729//729 -f 403//403 729//729 511//511 -f 511//511 729//729 512//512 -f 557//557 566//566 572//572 -f 572//572 566//566 574//574 -f 617//617 618//618 696//696 -f 696//696 618//618 697//697 -f 366//366 368//368 414//414 -f 414//414 368//368 413//413 -f 761//761 762//762 382//382 -f 382//382 762//762 368//368 -f 763//763 416//416 764//764 -f 764//764 416//416 413//413 -f 764//764 413//413 765//765 -f 762//762 766//766 368//368 -f 368//368 766//766 767//767 -f 368//368 767//767 768//768 -f 368//368 769//769 770//770 -f 368//368 770//770 413//413 -f 413//413 770//770 771//771 -f 413//413 771//771 765//765 -f 772//772 773//773 774//774 -f 774//774 773//773 775//775 -f 774//774 775//775 776//776 -f 772//772 777//777 416//416 -f 416//416 777//777 778//778 -f 416//416 778//778 382//382 -f 382//382 778//778 779//779 -f 382//382 779//779 761//761 -f 769//769 368//368 780//780 -f 780//780 368//368 768//768 -f 780//780 768//768 775//775 -f 775//775 768//768 781//781 -f 775//775 781//781 776//776 -f 763//763 782//782 416//416 -f 416//416 782//782 783//783 -f 416//416 783//783 772//772 -f 772//772 783//783 784//784 -f 772//772 784//784 773//773 -f 785//785 775//775 786//786 -f 786//786 775//775 773//773 -f 786//786 773//773 787//787 -f 787//787 773//773 784//784 -f 787//787 784//784 788//788 -f 788//788 784//784 783//783 -f 788//788 783//783 789//789 -f 789//789 783//783 782//782 -f 789//789 782//782 790//790 -f 790//790 782//782 763//763 -f 790//790 763//763 791//791 -f 791//791 763//763 764//764 -f 791//791 764//764 792//792 -f 792//792 764//764 765//765 -f 792//792 765//765 793//793 -f 793//793 765//765 771//771 -f 793//793 771//771 794//794 -f 794//794 771//771 770//770 -f 794//794 770//770 795//795 -f 795//795 770//770 769//769 -f 795//795 769//769 796//796 -f 796//796 769//769 780//780 -f 796//796 780//780 785//785 -f 785//785 780//780 775//775 -f 797//797 762//762 798//798 -f 798//798 762//762 761//761 -f 798//798 761//761 799//799 -f 799//799 761//761 779//779 -f 799//799 779//779 800//800 -f 800//800 779//779 778//778 -f 800//800 778//778 801//801 -f 801//801 778//778 777//777 -f 801//801 777//777 802//802 -f 802//802 777//777 772//772 -f 802//802 772//772 803//803 -f 803//803 772//772 774//774 -f 803//803 774//774 804//804 -f 804//804 774//774 776//776 -f 804//804 776//776 805//805 -f 805//805 776//776 781//781 -f 805//805 781//781 806//806 -f 806//806 781//781 768//768 -f 806//806 768//768 807//807 -f 807//807 768//768 767//767 -f 807//807 767//767 808//808 -f 808//808 767//767 766//766 -f 808//808 766//766 797//797 -f 797//797 766//766 762//762 -f 809//809 686//686 810//810 -f 810//810 686//686 685//685 -f 810//810 685//685 811//811 -f 811//811 685//685 692//692 -f 811//811 692//692 812//812 -f 812//812 692//692 691//691 -f 812//812 691//691 813//813 -f 813//813 691//691 689//689 -f 813//813 689//689 814//814 -f 814//814 689//689 687//687 -f 814//814 687//687 809//809 -f 809//809 687//687 686//686 -f 801//801 802//802 813//813 -f 813//813 802//802 812//812 -f 802//802 803//803 812//812 -f 812//812 803//803 804//804 -f 812//812 804//804 811//811 -f 809//809 810//810 808//808 -f 804//804 805//805 811//811 -f 811//811 805//805 806//806 -f 811//811 806//806 810//810 -f 810//810 806//806 807//807 -f 810//810 807//807 808//808 -f 808//808 797//797 809//809 -f 809//809 797//797 798//798 -f 809//809 798//798 814//814 -f 814//814 798//798 799//799 -f 814//814 799//799 813//813 -f 813//813 799//799 800//800 -f 813//813 800//800 801//801 -f 815//815 690//690 816//816 -f 816//816 690//690 684//684 -f 816//816 684//684 817//817 -f 817//817 684//684 682//682 -f 817//817 682//682 818//818 -f 818//818 682//682 681//681 -f 818//818 681//681 819//819 -f 819//819 681//681 680//680 -f 819//819 680//680 820//820 -f 820//820 680//680 688//688 -f 820//820 688//688 815//815 -f 815//815 688//688 690//690 -f 787//787 788//788 820//820 -f 793//793 794//794 817//817 -f 820//820 788//788 819//819 -f 817//817 794//794 816//816 -f 788//788 789//789 819//819 -f 819//819 789//789 790//790 -f 819//819 790//790 818//818 -f 818//818 790//790 791//791 -f 818//818 791//791 817//817 -f 817//817 791//791 792//792 -f 817//817 792//792 793//793 -f 794//794 795//795 816//816 -f 816//816 795//795 796//796 -f 816//816 796//796 815//815 -f 815//815 796//796 785//785 -f 815//815 785//785 820//820 -f 820//820 785//785 786//786 -f 820//820 786//786 787//787 -f 678//678 513//513 656//656 -f 656//656 513//513 512//512 -f 656//656 512//512 658//658 -f 666//666 664//664 741//741 -f 741//741 664//664 662//662 -f 741//741 662//662 512//512 -f 512//512 662//662 660//660 -f 512//512 660//660 658//658 -f 666//666 741//741 668//668 -f 668//668 741//741 821//821 -f 668//668 821//821 670//670 -f 678//678 676//676 513//513 -f 513//513 676//676 674//674 -f 513//513 674//674 821//821 -f 821//821 674//674 672//672 -f 821//821 672//672 670//670 -f 536//536 515//515 822//822 -f 822//822 515//515 513//513 -f 822//822 513//513 823//823 -f 823//823 513//513 821//821 -f 531//531 530//530 824//824 -f 823//823 821//821 824//824 -f 824//824 821//821 741//741 -f 824//824 741//741 531//531 -f 825//825 826//826 827//827 -f 827//827 826//826 742//742 -f 827//827 742//742 828//828 -f 829//829 830//830 352//352 -f 352//352 830//830 831//831 -f 352//352 831//831 742//742 -f 742//742 831//831 832//832 -f 742//742 832//832 828//828 -f 829//829 352//352 833//833 -f 833//833 352//352 351//351 -f 833//833 351//351 834//834 -f 825//825 835//835 826//826 -f 826//826 835//835 836//836 -f 826//826 836//836 351//351 -f 351//351 836//836 837//837 -f 351//351 837//837 834//834 -f 556//556 555//555 838//838 -f 838//838 555//555 742//742 -f 838//838 742//742 839//839 -f 839//839 742//742 826//826 -f 356//356 561//561 840//840 -f 839//839 826//826 840//840 -f 840//840 826//826 351//351 -f 840//840 351//351 356//356 -f 841//841 827//827 842//842 -f 842//842 827//827 828//828 -f 842//842 828//828 843//843 -f 843//843 828//828 832//832 -f 843//843 832//832 844//844 -f 844//844 832//832 831//831 -f 844//844 831//831 845//845 -f 845//845 831//831 830//830 -f 845//845 830//830 846//846 -f 846//846 830//830 829//829 -f 846//846 829//829 847//847 -f 847//847 829//829 833//833 -f 847//847 833//833 848//848 -f 848//848 833//833 834//834 -f 848//848 834//834 849//849 -f 849//849 834//834 837//837 -f 849//849 837//837 850//850 -f 850//850 837//837 836//836 -f 850//850 836//836 851//851 -f 851//851 836//836 835//835 -f 851//851 835//835 852//852 -f 852//852 835//835 825//825 -f 852//852 825//825 841//841 -f 841//841 825//825 827//827 -f 554//554 556//556 853//853 -f 853//853 556//556 838//838 -f 854//854 840//840 562//562 -f 562//562 840//840 561//561 -f 849//849 850//850 840//840 -f 840//840 850//850 839//839 -f 850//850 851//851 839//839 -f 839//839 851//851 852//852 -f 839//839 852//852 838//838 -f 838//838 852//852 841//841 -f 841//841 842//842 838//838 -f 838//838 842//842 843//843 -f 838//838 843//843 853//853 -f 853//853 843//843 844//844 -f 853//853 844//844 855//855 -f 855//855 844//844 845//845 -f 855//855 845//845 856//856 -f 856//856 845//845 846//846 -f 856//856 846//846 854//854 -f 854//854 846//846 847//847 -f 854//854 847//847 840//840 -f 840//840 847//847 848//848 -f 840//840 848//848 849//849 -f 854//854 562//562 856//856 -f 856//856 562//562 563//563 -f 856//856 563//563 855//855 -f 855//855 563//563 552//552 -f 855//855 552//552 853//853 -f 853//853 552//552 554//554 -f 528//528 536//536 857//857 -f 857//857 536//536 822//822 -f 858//858 824//824 532//532 -f 532//532 824//824 530//530 -f 665//665 667//667 824//824 -f 824//824 667//667 823//823 -f 673//673 822//822 671//671 -f 671//671 822//822 823//823 -f 671//671 823//823 669//669 -f 669//669 823//823 667//667 -f 673//673 675//675 822//822 -f 822//822 675//675 677//677 -f 822//822 677//677 857//857 -f 857//857 677//677 655//655 -f 857//857 655//655 859//859 -f 859//859 655//655 657//657 -f 859//859 657//657 860//860 -f 860//860 657//657 659//659 -f 860//860 659//659 858//858 -f 858//858 659//659 661//661 -f 858//858 661//661 824//824 -f 824//824 661//661 663//663 -f 824//824 663//663 665//665 -f 858//858 532//532 860//860 -f 860//860 532//532 533//533 -f 860//860 533//533 859//859 -f 859//859 533//533 529//529 -f 859//859 529//529 857//857 -f 857//857 529//529 528//528 -f 523//523 736//736 524//524 -f 524//524 736//736 861//861 -f 524//524 861//861 612//612 -f 612//612 861//861 624//624 -f 598//598 607//607 588//588 -f 588//588 607//607 612//612 -f 588//588 612//612 584//584 -f 584//584 612//612 624//624 -f 756//756 553//553 862//862 -f 862//862 553//553 560//560 -f 862//862 560//560 621//621 -f 621//621 560//560 578//578 -f 621//621 578//578 593//593 -f 567//567 569//569 578//578 -f 578//578 569//569 583//583 -f 578//578 583//583 593//593 -f 863//863 864//864 538//538 -f 624//624 538//538 621//621 -f 621//621 538//538 540//540 -f 621//621 540//540 862//862 -f 540//540 865//865 866//866 -f 867//867 863//863 868//868 -f 868//868 863//863 538//538 -f 868//868 538//538 861//861 -f 861//861 538//538 624//624 -f 866//866 869//869 540//540 -f 540//540 869//869 870//870 -f 540//540 870//870 862//862 -f 871//871 872//872 627//627 -f 627//627 872//872 628//628 -f 873//873 871//871 626//626 -f 626//626 871//871 627//627 -f 874//874 873//873 619//619 -f 619//619 873//873 626//626 -f 874//874 619//619 875//875 -f 875//875 619//619 592//592 -f 875//875 592//592 591//591 -f 630//630 876//876 614//614 -f 614//614 876//876 875//875 -f 614//614 875//875 591//591 -f 872//872 876//876 628//628 -f 628//628 876//876 630//630 -f 647//647 874//874 875//875 -f 653//653 872//872 871//871 -f 647//647 648//648 874//874 -f 874//874 648//648 649//649 -f 874//874 649//649 873//873 -f 649//649 650//650 873//873 -f 873//873 650//650 651//651 -f 873//873 651//651 871//871 -f 871//871 651//651 652//652 -f 871//871 652//652 653//653 -f 653//653 654//654 872//872 -f 872//872 654//654 643//643 -f 872//872 643//643 876//876 -f 643//643 644//644 876//876 -f 876//876 644//644 645//645 -f 876//876 645//645 875//875 -f 875//875 645//645 646//646 -f 875//875 646//646 647//647 -f 877//877 878//878 622//622 -f 622//622 878//878 623//623 -f 879//879 877//877 629//629 -f 629//629 877//877 622//622 -f 880//880 879//879 620//620 -f 620//620 879//879 629//629 -f 880//880 620//620 881//881 -f 881//881 620//620 613//613 -f 881//881 613//613 586//586 -f 625//625 882//882 585//585 -f 585//585 882//882 881//881 -f 585//585 881//881 586//586 -f 878//878 882//882 623//623 -f 623//623 882//882 625//625 -f 880//880 881//881 635//635 -f 631//631 882//882 878//878 -f 635//635 636//636 880//880 -f 880//880 636//636 637//637 -f 880//880 637//637 879//879 -f 637//637 638//638 879//879 -f 879//879 638//638 639//639 -f 879//879 639//639 877//877 -f 639//639 640//640 877//877 -f 877//877 640//640 641//641 -f 877//877 641//641 878//878 -f 878//878 641//641 642//642 -f 878//878 642//642 631//631 -f 631//631 632//632 882//882 -f 882//882 632//632 633//633 -f 882//882 633//633 881//881 -f 881//881 633//633 634//634 -f 881//881 634//634 635//635 -f 735//735 865//865 546//546 -f 546//546 865//865 540//540 -f 866//866 865//865 734//734 -f 734//734 865//865 735//735 -f 864//864 739//739 538//538 -f 538//538 739//739 542//542 -f 740//740 739//739 863//863 -f 863//863 739//739 864//864 -f 683//683 704//704 693//693 -f 693//693 704//704 694//694 -f 704//704 407//407 694//694 -f 694//694 407//407 406//406 -f 459//459 508//508 514//514 -f 459//459 514//514 460//460 -f 460//460 514//514 522//522 -f 460//460 522//522 461//461 -f 461//461 522//522 521//521 -f 461//461 521//521 467//467 -f 467//467 521//521 520//520 -f 467//467 520//520 468//468 -f 468//468 520//520 519//519 -f 468//468 519//519 462//462 -f 462//462 519//519 518//518 -f 462//462 518//518 463//463 -f 463//463 518//518 517//517 -f 463//463 517//517 464//464 -f 464//464 517//517 516//516 -f 464//464 516//516 438//438 -f 458//458 437//437 509//509 -f 509//509 437//437 510//510 -f 437//437 436//436 510//510 -f 510//510 436//436 883//883 -f 510//510 883//883 884//884 -f 885//885 886//886 408//408 -f 408//408 886//886 454//454 -f 408//408 454//454 409//409 -f 454//454 455//455 409//409 -f 409//409 455//455 456//456 -f 409//409 456//456 430//430 -f 430//430 456//456 457//457 -f 430//430 457//457 428//428 -f 428//428 457//457 443//443 -f 428//428 443//443 402//402 -f 887//887 888//888 423//423 -f 423//423 888//888 889//889 -f 423//423 889//889 695//695 -f 402//402 443//443 423//423 -f 423//423 443//443 442//442 -f 423//423 442//442 887//887 -f 454//454 886//886 890//890 -f 454//454 890//890 452//452 -f 452//452 890//890 891//891 -f 452//452 891//891 453//453 -f 453//453 891//891 883//883 -f 453//453 883//883 436//436 -f 892//892 893//893 894//894 -f 883//883 894//894 884//884 -f 884//884 894//894 895//895 -f 884//884 895//895 743//743 -f 743//743 895//895 896//896 -f 743//743 896//896 744//744 -f 744//744 896//896 897//897 -f 744//744 897//897 898//898 -f 898//898 897//897 894//894 -f 898//898 894//894 899//899 -f 899//899 894//894 893//893 -f 891//891 890//890 883//883 -f 883//883 890//890 886//886 -f 886//886 885//885 883//883 -f 883//883 885//885 900//900 -f 883//883 900//900 901//901 -f 892//892 894//894 902//902 -f 902//902 894//894 883//883 -f 902//902 883//883 903//903 -f 903//903 883//883 901//901 -f 903//903 901//901 904//904 -f 885//885 408//408 410//410 -f 885//885 410//410 900//900 -f 900//900 410//410 411//411 -f 900//900 411//411 901//901 -f 901//901 411//411 432//432 -f 901//901 432//432 904//904 -f 904//904 432//432 431//431 -f 904//904 431//431 903//903 -f 902//902 903//903 429//429 -f 429//429 903//903 431//431 -f 902//902 429//429 892//892 -f 892//892 429//429 434//434 -f 892//892 434//434 893//893 -f 893//893 434//434 433//433 -f 893//893 433//433 899//899 -f 899//899 433//433 435//435 -f 899//899 435//435 898//898 -f 898//898 435//435 404//404 -f 744//744 898//898 403//403 -f 403//403 898//898 404//404 -f 884//884 743//743 510//510 -f 510//510 743//743 511//511 -f 895//895 894//894 905//905 -f 905//905 894//894 906//906 -f 894//894 897//897 906//906 -f 906//906 897//897 907//907 -f 897//897 896//896 907//907 -f 907//907 896//896 908//908 -f 896//896 895//895 908//908 -f 908//908 895//895 905//905 -f 907//907 908//908 906//906 -f 906//906 908//908 905//905 -f 486//486 355//355 363//363 -f 486//486 363//363 489//489 -f 489//489 363//363 362//362 -f 489//489 362//362 501//501 -f 501//501 362//362 361//361 -f 501//501 361//361 502//502 -f 502//502 361//361 365//365 -f 502//502 365//365 503//503 -f 503//503 365//365 364//364 -f 503//503 364//364 506//506 -f 506//506 364//364 360//360 -f 506//506 360//360 507//507 -f 507//507 360//360 359//359 -f 507//507 359//359 481//481 -f 481//481 359//359 358//358 -f 481//481 358//358 478//478 -f 480//480 479//479 354//354 -f 354//354 479//479 357//357 -f 469//469 471//471 490//490 -f 909//909 910//910 354//354 -f 354//354 910//910 469//469 -f 354//354 469//469 480//480 -f 480//480 469//469 490//490 -f 491//491 395//395 487//487 -f 487//487 395//395 397//397 -f 487//487 397//397 488//488 -f 488//488 397//397 370//370 -f 488//488 370//370 483//483 -f 911//911 912//912 473//473 -f 473//473 912//912 375//375 -f 471//471 473//473 490//490 -f 490//490 473//473 375//375 -f 490//490 375//375 491//491 -f 491//491 375//375 374//374 -f 491//491 374//374 395//395 -f 913//913 388//388 914//914 -f 914//914 388//388 679//679 -f 483//483 370//370 485//485 -f 485//485 370//370 388//388 -f 485//485 388//388 915//915 -f 915//915 388//388 913//913 -f 738//738 909//909 353//353 -f 353//353 909//909 354//354 -f 916//916 737//737 373//373 -f 373//373 737//737 371//371 -f 916//916 373//373 917//917 -f 917//917 373//373 401//401 -f 917//917 401//401 918//918 -f 918//918 401//401 400//400 -f 918//918 400//400 919//919 -f 919//919 400//400 399//399 -f 919//919 399//399 920//920 -f 920//920 399//399 398//398 -f 921//921 920//920 396//396 -f 396//396 920//920 398//398 -f 921//921 396//396 394//394 -f 921//921 394//394 922//922 -f 922//922 394//394 393//393 -f 922//922 393//393 923//923 -f 923//923 393//393 376//376 -f 923//923 376//376 924//924 -f 924//924 376//376 375//375 -f 924//924 375//375 912//912 -f 911//911 473//473 472//472 -f 911//911 472//472 925//925 -f 925//925 472//472 470//470 -f 925//925 470//470 926//926 -f 926//926 470//470 469//469 -f 926//926 469//469 910//910 -f 927//927 910//910 928//928 -f 928//928 910//910 909//909 -f 928//928 909//909 929//929 -f 929//929 909//909 738//738 -f 929//929 738//738 930//930 -f 930//930 738//738 737//737 -f 930//930 737//737 927//927 -f 927//927 737//737 916//916 -f 927//927 916//916 917//917 -f 917//917 918//918 927//927 -f 927//927 918//918 919//919 -f 927//927 919//919 910//910 -f 910//910 919//919 920//920 -f 910//910 920//920 921//921 -f 925//925 926//926 911//911 -f 911//911 926//926 910//910 -f 911//911 910//910 912//912 -f 912//912 910//910 924//924 -f 921//921 922//922 910//910 -f 910//910 922//922 923//923 -f 910//910 923//923 924//924 -f 927//927 928//928 931//931 -f 931//931 928//928 932//932 -f 928//928 929//929 932//932 -f 932//932 929//929 933//933 -f 929//929 930//930 933//933 -f 933//933 930//930 934//934 -f 930//930 927//927 934//934 -f 934//934 927//927 931//931 -f 933//933 934//934 932//932 -f 932//932 934//934 931//931 -f 935//935 936//936 937//937 -f 938//938 939//939 940//940 -f 939//939 941//941 940//940 -f 940//940 941//941 942//942 -f 940//940 942//942 696//696 -f 943//943 944//944 945//945 -f 465//465 935//935 445//445 -f 445//445 935//935 937//937 -f 445//445 937//937 444//444 -f 444//444 937//937 946//946 -f 444//444 946//946 442//442 -f 442//442 946//946 887//887 -f 936//936 943//943 937//937 -f 937//937 943//943 945//945 -f 937//937 945//945 946//946 -f 946//946 945//945 947//947 -f 946//946 947//947 887//887 -f 887//887 947//947 888//888 -f 944//944 938//938 945//945 -f 945//945 938//938 940//940 -f 945//945 940//940 947//947 -f 947//947 940//940 948//948 -f 947//947 948//948 888//888 -f 888//888 948//948 889//889 -f 696//696 698//698 940//940 -f 940//940 698//698 700//700 -f 940//940 700//700 948//948 -f 948//948 700//700 702//702 -f 948//948 702//702 889//889 -f 889//889 702//702 695//695 -f 465//465 440//440 935//935 -f 935//935 440//440 949//949 -f 950//950 944//944 951//951 -f 951//951 944//944 943//943 -f 951//951 943//943 949//949 -f 949//949 943//943 936//936 -f 949//949 936//936 935//935 -f 952//952 939//939 950//950 -f 950//950 939//939 938//938 -f 950//950 938//938 944//944 -f 617//617 696//696 953//953 -f 953//953 696//696 942//942 -f 953//953 942//942 952//952 -f 952//952 942//942 941//941 -f 952//952 941//941 939//939 -f 597//597 599//599 954//954 -f 590//590 615//615 955//955 -f 449//449 466//466 956//956 -f 450//450 449//449 957//957 -f 451//451 450//450 958//958 -f 439//439 451//451 959//959 -f 605//605 604//604 960//960 -f 605//605 960//960 961//961 -f 961//961 960//960 962//962 -f 961//961 962//962 963//963 -f 963//963 964//964 965//965 -f 965//965 964//964 966//966 -f 966//966 964//964 967//967 -f 967//967 964//964 968//968 -f 967//967 968//968 969//969 -f 447//447 446//446 970//970 -f 968//968 441//441 969//969 -f 969//969 441//441 447//447 -f 969//969 447//447 971//971 -f 971//971 447//447 970//970 -f 439//439 972//972 440//440 -f 440//440 972//972 949//949 -f 949//949 972//972 951//951 -f 951//951 972//972 973//973 -f 951//951 973//973 950//950 -f 963//963 962//962 964//964 -f 964//964 962//962 956//956 -f 964//964 956//956 968//968 -f 968//968 956//956 466//466 -f 968//968 466//466 441//441 -f 950//950 973//973 952//952 -f 952//952 973//973 955//955 -f 952//952 955//955 953//953 -f 953//953 955//955 615//615 -f 953//953 615//615 617//617 -f 439//439 959//959 972//972 -f 972//972 959//959 974//974 -f 972//972 974//974 973//973 -f 973//973 974//974 975//975 -f 973//973 975//975 955//955 -f 955//955 975//975 589//589 -f 955//955 589//589 590//590 -f 976//976 600//600 587//587 -f 451//451 958//958 959//959 -f 959//959 958//958 977//977 -f 959//959 977//977 974//974 -f 974//974 977//977 976//976 -f 974//974 976//976 975//975 -f 975//975 976//976 587//587 -f 975//975 587//587 589//589 -f 450//450 957//957 958//958 -f 958//958 957//957 978//978 -f 958//958 978//978 977//977 -f 977//977 978//978 954//954 -f 977//977 954//954 976//976 -f 976//976 954//954 599//599 -f 976//976 599//599 600//600 -f 449//449 956//956 957//957 -f 957//957 956//956 962//962 -f 957//957 962//962 978//978 -f 978//978 962//962 960//960 -f 978//978 960//960 954//954 -f 954//954 960//960 604//604 -f 954//954 604//604 597//597 -f 484//484 485//485 915//915 -f 482//482 484//484 979//979 -f 496//496 482//482 980//980 -f 980//980 482//482 981//981 -f 980//980 981//981 982//982 -f 982//982 981//981 983//983 -f 983//983 981//981 984//984 -f 983//983 984//984 985//985 -f 985//985 984//984 986//986 -f 986//986 984//984 987//987 -f 986//986 987//987 988//988 -f 988//988 987//987 989//989 -f 989//989 987//987 699//699 -f 989//989 699//699 697//697 -f 990//990 703//703 701//701 -f 482//482 979//979 981//981 -f 981//981 979//979 991//991 -f 981//981 991//991 984//984 -f 984//984 991//991 990//990 -f 984//984 990//990 987//987 -f 987//987 990//990 701//701 -f 987//987 701//701 699//699 -f 484//484 915//915 979//979 -f 979//979 915//915 913//913 -f 979//979 913//913 991//991 -f 991//991 913//913 914//914 -f 991//991 914//914 990//990 -f 990//990 914//914 679//679 -f 990//990 679//679 703//703 -f 697//697 618//618 989//989 -f 989//989 618//618 992//992 -f 989//989 992//992 988//988 -f 988//988 992//992 993//993 -f 988//988 993//993 986//986 -f 986//986 993//993 994//994 -f 986//986 994//994 985//985 -f 985//985 994//994 983//983 -f 983//983 994//994 995//995 -f 983//983 995//995 982//982 -f 982//982 995//995 996//996 -f 982//982 996//996 980//980 -f 980//980 996//996 497//497 -f 980//980 497//497 496//496 -f 504//504 497//497 996//996 -f 498//498 504//504 997//997 -f 499//499 498//498 998//998 -f 500//500 499//499 999//999 -f 505//505 500//500 1000//1000 -f 1001//1001 1002//1002 494//494 -f 494//494 1002//1002 1003//1003 -f 494//494 1003//1003 493//493 -f 495//495 1004//1004 494//494 -f 494//494 1004//1004 1005//1005 -f 494//494 1005//1005 1001//1001 -f 1006//1006 1007//1007 1008//1008 -f 1008//1008 1007//1007 1009//1009 -f 1008//1008 1009//1009 1004//1004 -f 1004//1004 1009//1009 1010//1010 -f 1004//1004 1010//1010 1005//1005 -f 1011//1011 1012//1012 1006//1006 -f 1006//1006 1012//1012 576//576 -f 1006//1006 576//576 577//577 -f 1006//1006 1008//1008 1011//1011 -f 1011//1011 1008//1008 1004//1004 -f 1011//1011 1004//1004 1013//1013 -f 1013//1013 1004//1004 495//495 -f 1013//1013 495//495 505//505 -f 504//504 996//996 997//997 -f 997//997 996//996 995//995 -f 997//997 995//995 1014//1014 -f 498//498 997//997 998//998 -f 998//998 997//997 1014//1014 -f 998//998 1014//1014 1015//1015 -f 1015//1015 1014//1014 1016//1016 -f 1015//1015 1016//1016 1017//1017 -f 995//995 994//994 1014//1014 -f 1014//1014 994//994 993//993 -f 1014//1014 993//993 1016//1016 -f 1016//1016 993//993 992//992 -f 1016//1016 992//992 618//618 -f 1018//1018 581//581 573//573 -f 505//505 1000//1000 1013//1013 -f 1013//1013 1000//1000 1019//1019 -f 1013//1013 1019//1019 1011//1011 -f 1011//1011 1019//1019 1018//1018 -f 1011//1011 1018//1018 1012//1012 -f 1012//1012 1018//1018 573//573 -f 1012//1012 573//573 576//576 -f 500//500 999//999 1000//1000 -f 1000//1000 999//999 1020//1020 -f 1000//1000 1020//1020 1019//1019 -f 1019//1019 1020//1020 1021//1021 -f 1019//1019 1021//1021 1018//1018 -f 1018//1018 1021//1021 582//582 -f 1018//1018 582//582 581//581 -f 499//499 998//998 999//999 -f 999//999 998//998 1015//1015 -f 999//999 1015//1015 1020//1020 -f 1020//1020 1015//1015 1017//1017 -f 1020//1020 1017//1017 1021//1021 -f 1021//1021 1017//1017 594//594 -f 1021//1021 594//594 582//582 -f 618//618 616//616 1016//1016 -f 1016//1016 616//616 596//596 -f 1016//1016 596//596 1017//1017 -f 1017//1017 596//596 595//595 -f 1017//1017 595//595 594//594 -f 559//559 580//580 560//560 -f 560//560 580//580 579//579 -f 560//560 579//579 578//578 -f 558//558 557//557 572//572 -f 572//572 571//571 558//558 -f 558//558 571//571 570//570 -f 558//558 570//570 559//559 -f 559//559 570//570 568//568 -f 559//559 568//568 580//580 -f 574//574 566//566 575//575 -f 575//575 566//566 565//565 -f 575//575 565//565 577//577 -f 577//577 565//565 1006//1006 -f 1006//1006 565//565 564//564 -f 1006//1006 564//564 1007//1007 -f 493//493 1003//1003 492//492 -f 492//492 1003//1003 1002//1002 -f 492//492 1002//1002 1001//1001 -f 1001//1001 1005//1005 492//492 -f 492//492 1005//1005 1010//1010 -f 492//492 1010//1010 564//564 -f 564//564 1010//1010 1009//1009 -f 564//564 1009//1009 1007//1007 -f 527//527 526//526 602//602 -f 969//969 971//971 448//448 -f 448//448 971//971 970//970 -f 448//448 970//970 446//446 -f 602//602 603//603 527//527 -f 527//527 603//603 605//605 -f 527//527 605//605 537//537 -f 537//537 605//605 961//961 -f 537//537 961//961 963//963 -f 963//963 965//965 537//537 -f 537//537 965//965 966//966 -f 537//537 966//966 448//448 -f 448//448 966//966 967//967 -f 448//448 967//967 969//969 -f 601//601 535//535 609//609 -f 609//609 535//535 534//534 -f 609//609 534//534 608//608 -f 608//608 534//534 606//606 -f 606//606 534//534 525//525 -f 606//606 525//525 610//610 -f 610//610 525//525 611//611 -f 611//611 525//525 524//524 -f 611//611 524//524 612//612 -f 866//866 734//734 754//754 -f 866//866 754//754 869//869 -f 869//869 754//754 755//755 -f 869//869 755//755 870//870 -f 870//870 755//755 756//756 -f 870//870 756//756 862//862 -f 861//861 736//736 746//746 -f 861//861 746//746 868//868 -f 868//868 746//746 745//745 -f 868//868 745//745 867//867 -f 867//867 745//745 740//740 -f 867//867 740//740 863//863 -f 705//705 384//384 385//385 -f 1022//1022 750//750 749//749 -f 753//753 752//752 1023//1023 -f 1023//1023 752//752 751//751 -f 748//748 386//386 747//747 -f 747//747 386//386 372//372 -f 707//707 706//706 1024//1024 -f 1024//1024 706//706 705//705 -f 712//712 708//708 1025//1025 -f 1025//1025 708//708 707//707 -f 727//727 713//713 712//712 -f 712//712 1025//1025 727//727 -f 727//727 1025//1025 1026//1026 -f 727//727 1026//1026 725//725 -f 725//725 1026//1026 1027//1027 -f 725//725 1027//1027 723//723 -f 723//723 1027//1027 1028//1028 -f 723//723 1028//1028 721//721 -f 721//721 1028//1028 1029//1029 -f 721//721 1029//1029 719//719 -f 719//719 1029//1029 1030//1030 -f 719//719 1030//1030 717//717 -f 717//717 1030//1030 1022//1022 -f 717//717 1022//1022 731//731 -f 731//731 1022//1022 749//749 -f 731//731 749//749 729//729 -f 707//707 1024//1024 1025//1025 -f 1025//1025 1024//1024 1031//1031 -f 1025//1025 1031//1031 1026//1026 -f 1026//1026 1031//1031 1032//1032 -f 1026//1026 1032//1032 1027//1027 -f 1027//1027 1032//1032 1033//1033 -f 1027//1027 1033//1033 1028//1028 -f 1028//1028 1033//1033 1034//1034 -f 1028//1028 1034//1034 1029//1029 -f 1029//1029 1034//1034 1035//1035 -f 1029//1029 1035//1035 1030//1030 -f 1030//1030 1035//1035 1023//1023 -f 1030//1030 1023//1023 1022//1022 -f 1022//1022 1023//1023 751//751 -f 1022//1022 751//751 750//750 -f 705//705 385//385 1024//1024 -f 1024//1024 385//385 379//379 -f 1024//1024 379//379 1031//1031 -f 1031//1031 379//379 392//392 -f 1031//1031 392//392 1032//1032 -f 1032//1032 392//392 391//391 -f 1032//1032 391//391 1033//1033 -f 1033//1033 391//391 389//389 -f 1033//1033 389//389 1034//1034 -f 1034//1034 389//389 387//387 -f 1034//1034 387//387 1035//1035 -f 1035//1035 387//387 386//386 -f 1035//1035 386//386 1023//1023 -f 1023//1023 386//386 748//748 -f 1023//1023 748//748 753//753 -f 726//726 724//724 1036//1036 -f 733//733 732//732 1037//1037 -f 714//714 728//728 1038//1038 -f 420//420 421//421 1039//1039 -f 420//420 1039//1039 759//759 -f 759//759 1039//1039 1040//1040 -f 759//759 1040//1040 757//757 -f 757//757 1040//1040 1037//1037 -f 757//757 1037//1037 758//758 -f 732//732 730//730 1037//1037 -f 1037//1037 730//730 760//760 -f 1037//1037 760//760 758//758 -f 714//714 1038//1038 709//709 -f 709//709 1038//1038 1041//1041 -f 709//709 1041//1041 710//710 -f 710//710 1041//1041 711//711 -f 711//711 1041//1041 1042//1042 -f 711//711 1042//1042 715//715 -f 715//715 1042//1042 716//716 -f 716//716 1042//1042 427//427 -f 716//716 427//427 417//417 -f 424//424 426//426 1043//1043 -f 1043//1043 426//426 1044//1044 -f 1043//1043 1044//1044 1045//1045 -f 1045//1045 1044//1044 1046//1046 -f 1045//1045 1046//1046 1047//1047 -f 1047//1047 1046//1046 1036//1036 -f 718//718 733//733 1048//1048 -f 1048//1048 733//733 1037//1037 -f 1048//1048 1037//1037 1049//1049 -f 1049//1049 1037//1037 1040//1040 -f 1049//1049 1040//1040 1050//1050 -f 1050//1050 1040//1040 1039//1039 -f 1050//1050 1039//1039 422//422 -f 422//422 1039//1039 421//421 -f 422//422 424//424 1050//1050 -f 1050//1050 424//424 1043//1043 -f 1050//1050 1043//1043 1049//1049 -f 1049//1049 1043//1043 1045//1045 -f 1049//1049 1045//1045 1048//1048 -f 1048//1048 1045//1045 1047//1047 -f 1048//1048 1047//1047 718//718 -f 718//718 1047//1047 720//720 -f 1036//1036 724//724 1047//1047 -f 1047//1047 724//724 722//722 -f 1047//1047 722//722 720//720 -f 728//728 726//726 1038//1038 -f 1038//1038 726//726 1036//1036 -f 1038//1038 1036//1036 1041//1041 -f 1041//1041 1036//1036 1046//1046 -f 1041//1041 1046//1046 1042//1042 -f 1042//1042 1046//1046 1044//1044 -f 1042//1042 1044//1044 427//427 -f 427//427 1044//1044 426//426 -# 2192 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/zamenjivac_osnovno.obj b/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/zamenjivac_osnovno.obj deleted file mode 100644 index 37ae4a851..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/RobotMemristor2/zamenjivac_osnovno.obj +++ /dev/null @@ -1,2892 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object osnovno.obj -# -# Vertices: 714 -# Faces: 1448 -# -#### -vn -0.301511 0.904534 -0.301512 -v -0.023049 0.040000 0.168800 -vn 0.904534 0.301511 -0.301511 -v -0.013049 0.040000 0.168800 -vn 0.900770 0.310542 0.303606 -v -0.013049 0.040000 0.149241 -vn -0.717100 0.696970 -0.000215 -v -0.088049 0.040000 0.146622 -vn -0.034953 0.696308 0.716891 -v -0.050981 0.040000 0.188700 -vn -0.301511 0.301511 0.904534 -v -0.023049 0.040000 0.188700 -vn -0.581070 0.576730 -0.574230 -v -0.091008 0.040000 0.146622 -vn -0.716427 0.696309 0.043437 -v -0.090978 0.040000 0.149173 -vn -0.712249 0.685853 0.149358 -v -0.090129 0.040000 0.156909 -vn -0.669847 0.685852 0.284451 -v -0.087799 0.040000 0.164335 -vn -0.401622 0.685852 0.606883 -v -0.073056 0.040000 0.182057 -vn -0.276502 0.685852 0.673167 -v -0.066179 0.040000 0.185700 -vn -0.140918 0.685853 0.713966 -v -0.058726 0.040000 0.187943 -vn -0.602086 0.685853 0.408777 -v -0.084074 0.040000 0.171168 -vn -0.511536 0.685853 0.517626 -v -0.079097 0.040000 0.177151 -vn 0.577350 0.577350 -0.577350 -v -0.084785 0.040000 0.084039 -vn -0.577350 0.577350 -0.577350 -v -0.091549 0.040000 0.084039 -vn 0.301511 0.904534 -0.301511 -v -0.084785 0.040000 0.090039 -vn -0.708422 0.705777 0.004194 -v -0.091549 0.040000 0.100883 -vn -0.171823 0.895922 -0.409635 -v -0.046007 0.040000 0.133465 -vn 0.900770 0.310542 -0.303606 -v -0.013049 0.040000 0.133241 -vn 0.706068 0.708116 -0.006369 -v -0.013049 0.040000 0.121017 -vn 0.047655 0.685231 -0.726765 -v -0.080980 0.040000 0.135613 -vn -0.000898 0.693181 -0.720763 -v -0.077340 0.040000 0.126887 -vn -0.051681 0.007354 -0.998637 -v -0.085285 0.040000 0.127399 -vn 0.195537 0.757445 -0.622930 -v -0.084451 0.040000 0.127477 -vn -0.129107 0.719839 0.682028 -v -0.057950 0.040000 0.102625 -vn -0.204513 0.719963 0.663195 -v -0.047035 0.040000 0.105331 -vn 0.037426 0.991110 -0.127672 -v -0.047812 0.040000 0.103008 -vn -0.547969 0.573151 0.609285 -v -0.091536 0.040000 0.102011 -vn 0.026275 0.719962 0.693516 -v -0.080341 0.040000 0.100955 -vn 0.577349 0.577350 -0.577352 -v -0.059785 0.040000 0.090039 -vn -0.055706 0.717686 0.694135 -v -0.069098 0.040000 0.101161 -vn 0.036103 0.998239 -0.047065 -v -0.059785 0.040000 0.100268 -vn 0.031587 0.991324 -0.127587 -v -0.053916 0.040000 0.101422 -vn 0.073174 0.991200 -0.110309 -v -0.019384 0.040000 0.116375 -vn 0.067503 0.991110 -0.114647 -v -0.024718 0.040000 0.113009 -vn -0.396922 0.905297 0.151296 -v -0.035299 0.040000 0.109772 -vn 0.060302 0.991110 -0.118596 -v -0.030248 0.040000 0.109978 -vn -0.263914 0.714228 0.648250 -v -0.036493 0.040000 0.109242 -vn 0.052868 0.991110 -0.122090 -v -0.035956 0.040000 0.107295 -vn 0.045234 0.991110 -0.125120 -v -0.041818 0.040000 0.104969 -vn 0.433614 0.757453 -0.488102 -v -0.083721 0.040000 0.127890 -vn 0.595554 0.757454 -0.267542 -v -0.083225 0.040000 0.128566 -vn 0.096836 0.691156 -0.716189 -v -0.066613 0.040000 0.127552 -vn 0.677933 0.731607 -0.071822 -v -0.083049 0.040000 0.129386 -vn 0.199338 0.691154 -0.694672 -v -0.056096 0.040000 0.129760 -vn 0.724657 0.685235 -0.072976 -v -0.083049 0.040000 0.133614 -vn 0.687582 0.664871 -0.291852 -v -0.082890 0.040000 0.134395 -vn 0.518888 0.664857 -0.537327 -v -0.082439 0.040000 0.135053 -vn 0.267688 0.664875 -0.697341 -v -0.081766 0.040000 0.135481 -vn -0.170482 -0.896462 -0.409013 -v -0.046007 -0.040000 0.133465 -vn 0.900770 -0.310542 -0.303606 -v -0.013049 -0.040000 0.133241 -vn 0.047655 -0.685231 -0.726765 -v -0.080980 -0.040000 0.135613 -vn 0.033862 -0.716405 0.696863 -v -0.080341 -0.040000 0.100955 -vn -0.547969 -0.573151 0.609285 -v -0.091536 -0.040000 0.102011 -vn -0.708422 -0.705777 0.004194 -v -0.091549 -0.040000 0.100883 -vn -0.048490 -0.022271 -0.998575 -v -0.085285 -0.040000 0.127399 -vn 0.011832 -0.692122 -0.721683 -v -0.075339 -0.040000 0.126893 -vn 0.195537 -0.757445 -0.622930 -v -0.084451 -0.040000 0.127477 -vn 0.433614 -0.757453 -0.488102 -v -0.083721 -0.040000 0.127890 -vn -0.056984 -0.717350 0.694379 -v -0.069098 -0.040000 0.101161 -vn 0.301511 -0.904534 -0.301512 -v -0.084785 -0.040000 0.090039 -vn 0.577350 -0.577350 -0.577350 -v -0.084785 -0.040000 0.084039 -vn -0.577350 -0.577350 -0.577350 -v -0.091549 -0.040000 0.084039 -vn 0.577351 -0.577350 -0.577350 -v -0.059785 -0.040000 0.090039 -vn 0.025180 -0.999152 -0.032588 -v -0.059785 -0.040000 0.100268 -vn -0.129107 -0.719839 0.682028 -v -0.057950 -0.040000 0.102625 -vn -0.204513 -0.719963 0.663195 -v -0.047035 -0.040000 0.105331 -vn 0.702007 -0.711358 -0.034007 -v -0.013049 -0.040000 0.121017 -vn 0.055745 -0.994925 -0.083767 -v -0.019887 -0.040000 0.116038 -vn 0.048448 -0.994920 -0.088243 -v -0.027386 -0.040000 0.111492 -vn -0.396922 -0.905297 0.151295 -v -0.035299 -0.040000 0.109772 -vn 0.040700 -0.994920 -0.092071 -v -0.035247 -0.040000 0.107605 -vn -0.263914 -0.714227 0.648250 -v -0.036493 -0.040000 0.109242 -vn 0.032653 -0.994920 -0.095222 -v -0.043413 -0.040000 0.104407 -vn 0.025422 -0.994999 -0.096592 -v -0.051823 -0.040000 0.101921 -vn 0.205314 -0.692122 -0.691963 -v -0.055456 -0.040000 0.129947 -vn 0.724657 -0.685235 -0.072976 -v -0.083049 -0.040000 0.133614 -vn 0.109559 -0.692122 -0.713418 -v -0.065293 -0.040000 0.127742 -vn 0.677933 -0.731607 -0.071822 -v -0.083049 -0.040000 0.129386 -vn 0.595554 -0.757454 -0.267542 -v -0.083225 -0.040000 0.128566 -vn 0.518888 -0.664857 -0.537327 -v -0.082439 -0.040000 0.135053 -vn 0.687582 -0.664871 -0.291852 -v -0.082890 -0.040000 0.134395 -vn 0.267688 -0.664875 -0.697341 -v -0.081766 -0.040000 0.135481 -vn -0.726993 0.680939 -0.088335 -v -0.088049 -0.037000 0.130393 -vn -0.301511 0.904534 -0.301511 -v -0.088049 -0.037000 0.146622 -vn -0.034953 0.696308 0.716891 -v -0.050981 -0.037000 0.188700 -vn -0.102478 0.994230 -0.031692 -v -0.019295 -0.037000 0.178825 -vn -0.102637 0.994686 -0.008107 -v -0.019049 -0.037000 0.177200 -vn 0.021156 0.994423 -0.103318 -v -0.025797 -0.037000 0.182557 -vn -0.694333 0.678884 -0.238786 -v -0.036123 -0.037000 0.111595 -vn -0.170482 0.896462 -0.409012 -v -0.046007 -0.037000 0.133465 -vn -0.047642 0.994967 0.088157 -v -0.029883 -0.037000 0.114686 -vn -0.053340 0.994989 0.084565 -v -0.023877 -0.037000 0.118212 -vn -0.000028 1.000000 -0.000059 -v -0.028549 -0.037000 0.180975 -vn 0.040236 0.996131 -0.078126 -v -0.027324 -0.037000 0.181949 -vn -0.087705 0.670658 0.736564 -v -0.028549 -0.037000 0.188700 -vn -0.038900 0.994230 -0.099972 -v -0.022555 -0.037000 0.182326 -vn -0.066699 0.994230 -0.084016 -v -0.021130 -0.037000 0.181508 -vn -0.088540 0.994230 -0.060556 -v -0.020010 -0.037000 0.180305 -vn -0.427827 0.656969 -0.620770 -v -0.086752 -0.037000 0.127922 -vn -0.667439 0.656962 -0.350609 -v -0.087705 -0.037000 0.128998 -vn -0.151909 0.674384 -0.722586 -v -0.085408 -0.037000 0.127414 -vn 0.011777 0.692122 -0.721685 -v -0.075339 -0.037000 0.126893 -vn 0.109559 0.692122 -0.713418 -v -0.065293 -0.037000 0.127742 -vn 0.205314 0.692122 -0.691963 -v -0.055456 -0.037000 0.129947 -vn -0.581070 0.576730 -0.574230 -v -0.091008 -0.037000 0.146622 -vn -0.716427 0.696309 0.043437 -v -0.090978 -0.037000 0.149173 -vn -0.712249 0.685853 0.149358 -v -0.090129 -0.037000 0.156909 -vn -0.669847 0.685852 0.284451 -v -0.087799 -0.037000 0.164335 -vn -0.401622 0.685852 0.606883 -v -0.073056 -0.037000 0.182057 -vn -0.276502 0.685852 0.673167 -v -0.066179 -0.037000 0.185700 -vn -0.140918 0.685853 0.713966 -v -0.058726 -0.037000 0.187943 -vn -0.001080 0.999999 0.000583 -v -0.019049 -0.037000 0.121488 -vn -0.007621 0.994231 -0.106990 -v -0.024159 -0.037000 0.182686 -vn -0.602086 0.685853 0.408777 -v -0.084074 -0.037000 0.171168 -vn -0.511536 0.685853 0.517626 -v -0.079097 -0.037000 0.177151 -vn -0.997440 0.038671 -0.060154 -v -0.088049 0.040000 0.130393 -vn -0.569946 0.765195 -0.299395 -v -0.087705 0.040000 0.128998 -vn -0.611622 0.584941 -0.532694 -v -0.088049 0.040000 0.127780 -vn -0.365344 0.765186 -0.530107 -v -0.086752 0.040000 0.127922 -vn -0.180790 0.029646 -0.983075 -v -0.085408 0.040000 0.127414 -vn -0.547969 -0.573151 0.609285 -v -0.091536 0.037000 0.102011 -vn -0.904169 -0.299124 0.304965 -v -0.091549 0.037000 0.100883 -vn 0.028425 -0.719823 0.693575 -v -0.080341 0.037000 0.100955 -vn -0.003038 -0.064147 0.997936 -v -0.076549 0.037000 0.100883 -vn -0.716427 -0.696309 0.043437 -v -0.090978 0.037000 0.149173 -vn -0.581070 -0.576730 -0.574230 -v -0.091008 0.037000 0.146622 -vn -0.301511 -0.904534 -0.301511 -v -0.088049 0.037000 0.146622 -vn -0.712249 -0.685853 0.149358 -v -0.090129 0.037000 0.156909 -vn -0.053340 -0.994989 0.084565 -v -0.023877 0.037000 0.118212 -vn -0.171823 -0.895922 -0.409635 -v -0.046007 0.037000 0.133465 -vn -0.047642 -0.994967 0.088157 -v -0.029883 0.037000 0.114686 -vn -0.694333 -0.678883 -0.238786 -v -0.036123 0.037000 0.111595 -vn -0.034953 -0.696308 0.716891 -v -0.050981 0.037000 0.188700 -vn 0.096836 -0.691156 -0.716189 -v -0.066613 0.037000 0.127552 -vn 0.199338 -0.691154 -0.694673 -v -0.056096 0.037000 0.129760 -vn -0.140918 -0.685853 0.713966 -v -0.058726 0.037000 0.187943 -vn -0.602870 -0.586902 -0.540457 -v -0.088049 0.037000 0.127780 -vn -0.002454 -0.693136 -0.720802 -v -0.077340 0.037000 0.126887 -vn -0.084707 -0.672964 0.734809 -v -0.028549 0.037000 0.188700 -vn -0.000028 -1.000000 -0.000059 -v -0.028549 0.037000 0.180975 -vn 0.035421 -0.994178 -0.101765 -v -0.027324 0.037000 0.181949 -vn 0.024328 -0.994230 -0.104472 -v -0.025797 0.037000 0.182557 -vn -0.001080 -0.999999 0.000583 -v -0.019049 0.037000 0.121488 -vn -0.102637 -0.994686 -0.008108 -v -0.019049 0.037000 0.177200 -vn -0.088540 -0.994230 -0.060555 -v -0.020010 0.037000 0.180305 -vn -0.066698 -0.994230 -0.084016 -v -0.021130 0.037000 0.181508 -vn -0.038898 -0.994229 -0.099975 -v -0.022555 0.037000 0.182326 -vn -0.276502 -0.685852 0.673167 -v -0.066179 0.037000 0.185700 -vn -0.401622 -0.685852 0.606883 -v -0.073056 0.037000 0.182057 -vn -0.511536 -0.685853 0.517626 -v -0.079097 0.037000 0.177151 -vn -0.102478 -0.994230 -0.031692 -v -0.019295 0.037000 0.178825 -vn -0.007625 -0.994231 -0.106990 -v -0.024159 0.037000 0.182686 -vn -0.602086 -0.685853 0.408777 -v -0.084074 0.037000 0.171168 -vn -0.669847 -0.685852 0.284451 -v -0.087799 0.037000 0.164335 -vn -0.716427 -0.696309 0.043437 -v -0.090978 -0.040000 0.149173 -vn -0.581070 -0.576730 -0.574230 -v -0.091008 -0.040000 0.146622 -vn -0.717100 -0.696970 -0.000214 -v -0.088049 -0.040000 0.146622 -vn 0.900770 -0.310542 0.303606 -v -0.013049 -0.040000 0.149241 -vn 0.904535 -0.301510 -0.301510 -v -0.013049 -0.040000 0.168800 -vn -0.301511 -0.904534 -0.301512 -v -0.023049 -0.040000 0.168800 -vn -0.712249 -0.685853 0.149358 -v -0.090129 -0.040000 0.156909 -vn -0.301511 -0.301511 0.904534 -v -0.023049 -0.040000 0.188700 -vn -0.034953 -0.696308 0.716891 -v -0.050981 -0.040000 0.188700 -vn -0.140918 -0.685853 0.713966 -v -0.058726 -0.040000 0.187943 -vn -0.276502 -0.685852 0.673167 -v -0.066179 -0.040000 0.185700 -vn -0.401622 -0.685852 0.606883 -v -0.073056 -0.040000 0.182057 -vn -0.511536 -0.685853 0.517626 -v -0.079097 -0.040000 0.177151 -vn -0.602086 -0.685853 0.408777 -v -0.084074 -0.040000 0.171168 -vn -0.669847 -0.685852 0.284451 -v -0.087799 -0.040000 0.164335 -vn 0.904533 -0.301512 0.301513 -v -0.013049 -0.025000 0.188700 -vn -0.060527 -0.997536 0.035484 -v -0.028549 -0.025000 0.188700 -vn -0.323470 -0.561612 0.761550 -v -0.026549 -0.025536 0.188700 -vn -0.669355 0.088119 0.737699 -v -0.024549 -0.033000 0.188700 -vn -0.553355 0.320377 0.768867 -v -0.025085 -0.035000 0.188700 -vn -0.088122 -0.669353 0.737700 -v -0.018049 -0.041000 0.188700 -vn -0.318864 -0.552288 0.770262 -v -0.016049 -0.041536 0.188700 -vn -0.577350 -0.577350 0.577350 -v -0.014049 -0.050000 0.188700 -vn 0.577350 -0.577350 0.577350 -v -0.013049 -0.050000 0.188700 -vn -0.669352 -0.088123 0.737701 -v -0.014049 -0.045000 0.188700 -vn -0.552289 -0.318865 0.770261 -v -0.014585 -0.043000 0.188700 -vn -0.561938 -0.324640 0.760812 -v -0.025085 -0.027000 0.188700 -vn -0.675526 -0.081640 0.732802 -v -0.024549 -0.029000 0.188700 -vn -0.577350 -0.577350 0.577350 -v -0.023049 -0.041000 0.188700 -vn -0.319266 0.554323 0.768632 -v -0.026549 -0.036464 0.188700 -vn 0.552288 0.318866 0.770261 -v -0.024293 -0.011625 0.188700 -vn 0.637726 -0.000000 0.770263 -v -0.024594 -0.010500 0.188700 -vn -0.904534 0.301511 0.301511 -v -0.034549 -0.019300 0.188700 -vn 0.552288 0.318866 0.770261 -v -0.024293 0.009375 0.188700 -vn 0.637726 0.000000 0.770263 -v -0.024594 0.010500 0.188700 -vn -0.904534 -0.301511 0.301511 -v -0.034549 0.019300 0.188700 -vn -0.552288 0.318866 0.770261 -v -0.020395 -0.011625 0.188700 -vn -0.318863 0.552289 0.770262 -v -0.021219 -0.012449 0.188700 -vn 0.904534 0.301511 0.301512 -v -0.013049 -0.019300 0.188700 -vn 0.000002 0.637727 0.770262 -v -0.022344 -0.012750 0.188700 -vn 0.318866 0.552289 0.770261 -v -0.023469 -0.012449 0.188700 -vn 0.318866 0.552288 0.770261 -v -0.023469 0.008551 0.188700 -vn 0.318866 -0.552288 0.770261 -v -0.023469 -0.008551 0.188700 -vn 0.552288 -0.318866 0.770261 -v -0.024293 -0.009375 0.188700 -vn 0.552288 -0.318866 0.770261 -v -0.024293 0.011625 0.188700 -vn 0.318866 -0.552289 0.770261 -v -0.023469 0.012449 0.188700 -vn 0.904534 -0.301511 0.301512 -v -0.013049 0.019300 0.188700 -vn 0.000002 -0.637727 0.770262 -v -0.022344 0.012750 0.188700 -vn -0.318863 -0.552289 0.770262 -v -0.021219 0.012449 0.188700 -vn 0.000002 0.637727 0.770262 -v -0.022344 0.008250 0.188700 -vn 0.000002 -0.637727 0.770262 -v -0.022344 -0.008250 0.188700 -vn -0.318863 0.552289 0.770262 -v -0.021219 0.008551 0.188700 -vn -0.552288 -0.318866 0.770261 -v -0.020395 0.011625 0.188700 -vn -0.637726 0.000000 0.770263 -v -0.020094 0.010500 0.188700 -vn -0.552288 0.318866 0.770261 -v -0.020395 0.009375 0.188700 -vn -0.318863 -0.552289 0.770262 -v -0.021219 -0.008551 0.188700 -vn -0.552288 -0.318866 0.770261 -v -0.020395 -0.009375 0.188700 -vn -0.637726 -0.000000 0.770263 -v -0.020094 -0.010500 0.188700 -vn -0.552289 0.318865 0.770261 -v -0.014585 0.043000 0.188700 -vn 0.904534 0.301511 0.301512 -v -0.013049 0.025000 0.188700 -vn -0.669352 0.088123 0.737701 -v -0.014049 0.045000 0.188700 -vn 0.577350 0.577350 0.577350 -v -0.013049 0.050000 0.188700 -vn -0.577350 0.577350 0.577350 -v -0.014049 0.050000 0.188700 -vn -0.669355 0.088119 0.737699 -v -0.024549 0.029000 0.188700 -vn -0.553354 0.320378 0.768867 -v -0.025085 0.027000 0.188700 -vn -0.319005 0.554071 0.768922 -v -0.026549 0.025536 0.188700 -vn -0.064620 0.997113 0.039873 -v -0.028549 0.025000 0.188700 -vn -0.577350 0.577350 0.577350 -v -0.023049 0.041000 0.188700 -vn -0.088122 0.669353 0.737700 -v -0.018049 0.041000 0.188700 -vn -0.318864 0.552288 0.770262 -v -0.016049 0.041536 0.188700 -vn -0.320937 -0.560930 0.763123 -v -0.026549 0.036464 0.188700 -vn -0.561456 -0.324901 0.761056 -v -0.025085 0.035000 0.188700 -vn -0.675528 -0.081639 0.732801 -v -0.024549 0.033000 0.188700 -vn 0.061986 0.677288 -0.733103 -v -0.025641 0.025000 0.184620 -vn -0.469614 0.489069 -0.735034 -v -0.025641 0.026254 0.184620 -vn -0.213609 0.668600 -0.712281 -v -0.022454 0.025000 0.184401 -vn -0.590143 0.385213 -0.709466 -v -0.025085 0.027000 0.184681 -vn -0.682486 0.169000 -0.711092 -v -0.024686 0.027965 0.184699 -vn -0.730894 0.056716 -0.680130 -v -0.024549 0.029000 0.184700 -vn -0.236881 -0.115541 -0.964644 -v -0.022454 0.035000 0.184401 -vn -0.740232 -0.045748 -0.670793 -v -0.024549 0.033000 0.184700 -vn -0.692351 -0.165940 -0.702220 -v -0.024685 0.034032 0.184699 -vn -0.102228 -0.067013 -0.992501 -v -0.024016 0.035000 0.184681 -vn -0.589096 -0.440104 -0.677698 -v -0.025085 0.035000 0.184681 -vn -0.015615 0.999738 -0.016740 -v -0.028549 0.025000 0.183544 -vn 0.001008 0.925018 -0.379921 -v -0.027550 0.025127 0.184074 -vn -0.136077 0.681504 -0.719052 -v -0.026549 0.025536 0.184428 -vn -0.411237 -0.093989 -0.906670 -v -0.021830 0.035000 0.184190 -vn -0.565939 -0.094404 -0.819025 -v -0.019886 0.035000 0.183074 -vn -0.432429 0.678440 -0.593906 -v -0.019647 0.025000 0.182876 -vn -0.611037 -0.119441 -0.782539 -v -0.019282 -0.025000 0.182539 -vn -0.878716 0.320598 -0.353659 -v -0.019282 -0.012297 0.182539 -vn -0.918404 0.000145 -0.395643 -v -0.018245 -0.010500 0.181262 -vn -0.692004 0.109206 -0.713586 -v -0.019647 -0.035000 0.182876 -vn -0.432965 -0.679225 -0.592617 -v -0.019647 -0.025000 0.182876 -vn -0.818177 0.099998 -0.566204 -v -0.018359 -0.035000 0.181434 -vn -0.883373 0.157600 -0.441377 -v -0.017730 -0.035000 0.180321 -vn -0.918404 -0.000145 -0.395643 -v -0.018245 0.010500 0.181262 -vn -0.878715 -0.320599 -0.353660 -v -0.019282 0.012297 0.182539 -vn -0.611037 0.119441 -0.782539 -v -0.019282 0.025000 0.182539 -vn -0.692004 -0.109207 -0.713586 -v -0.019647 0.035000 0.182876 -vn -0.811978 -0.090411 -0.576644 -v -0.018359 0.035000 0.181434 -vn -0.895829 -0.121872 -0.427361 -v -0.017730 0.035000 0.180321 -vn -0.224834 0.133442 -0.965217 -v -0.022454 -0.035000 0.184401 -vn -0.214697 -0.669578 -0.711035 -v -0.022454 -0.025000 0.184401 -vn -0.410100 0.095629 -0.907013 -v -0.021830 -0.035000 0.184190 -vn -0.566814 0.095965 -0.818237 -v -0.019886 -0.035000 0.183074 -vn -0.739934 -0.044471 -0.671208 -v -0.024549 -0.029000 0.184700 -vn -0.731105 0.058235 -0.679775 -v -0.024549 -0.033000 0.184700 -vn -0.683611 0.150889 -0.714079 -v -0.024687 -0.034039 0.184699 -vn -0.113462 0.070634 -0.991028 -v -0.024016 -0.035000 0.184681 -vn -0.566519 0.444044 -0.694176 -v -0.025085 -0.035000 0.184681 -vn -0.408175 -0.506163 -0.759732 -v -0.025641 -0.026254 0.184620 -vn 0.072549 -0.684666 -0.725238 -v -0.025641 -0.025000 0.184620 -vn -0.609973 -0.359147 -0.706361 -v -0.025085 -0.027000 0.184681 -vn -0.690755 -0.184814 -0.699072 -v -0.024686 -0.027966 0.184699 -vn -0.154625 -0.684497 -0.712429 -v -0.026549 -0.025536 0.184428 -vn 0.005683 -0.928971 -0.370108 -v -0.027549 -0.025127 0.184074 -vn -0.015632 -0.999737 -0.016758 -v -0.028549 -0.025000 0.183544 -vn -0.878715 -0.320599 -0.353660 -v -0.019282 -0.008703 0.182539 -vn -0.878716 0.320598 -0.353659 -v -0.019282 0.008703 0.182539 -vn -0.962429 0.097288 -0.253507 -v -0.017384 -0.035000 0.179416 -vn -0.962428 -0.097286 -0.253509 -v -0.017384 0.035000 0.179416 -vn -0.992482 0.097316 -0.074221 -v -0.017049 -0.035000 0.177200 -vn -0.992481 -0.097241 -0.074332 -v -0.017049 0.035000 0.177200 -vn -0.272352 -0.471729 -0.838628 -v -0.020294 0.014050 0.182539 -vn -0.272352 -0.471729 -0.838628 -v -0.020294 -0.006950 0.182539 -vn -0.577350 0.577350 -0.577350 -v -0.034549 0.025000 0.182539 -vn 0.544705 -0.000000 -0.838628 -v -0.026443 -0.010500 0.182539 -vn 0.272352 0.471728 -0.838628 -v -0.024394 -0.014050 0.182539 -vn -0.577350 -0.577350 -0.577350 -v -0.034549 -0.025000 0.182539 -vn -0.272352 0.471729 -0.838627 -v -0.020294 -0.014050 0.182539 -vn 0.272352 -0.471728 -0.838628 -v -0.024394 0.014050 0.182539 -vn 0.544705 0.000000 -0.838628 -v -0.026443 0.010500 0.182539 -vn 0.272352 0.471728 -0.838628 -v -0.024394 0.006950 0.182539 -vn 0.272352 -0.471728 -0.838628 -v -0.024394 -0.006950 0.182539 -vn -0.272352 0.471729 -0.838628 -v -0.020294 0.006950 0.182539 -vn 0.000002 0.637727 -0.770262 -v -0.022344 -0.012750 0.185539 -vn -0.318863 0.552289 -0.770262 -v -0.021219 -0.012449 0.185539 -vn -0.552288 0.318866 -0.770261 -v -0.020395 -0.011625 0.185539 -vn -0.637726 -0.000000 -0.770263 -v -0.020094 -0.010500 0.185539 -vn -0.552288 -0.318866 -0.770261 -v -0.020395 -0.009375 0.185539 -vn -0.318863 -0.552289 -0.770262 -v -0.021219 -0.008551 0.185539 -vn 0.000002 -0.637727 -0.770262 -v -0.022344 -0.008250 0.185539 -vn 0.318866 -0.552288 -0.770261 -v -0.023469 -0.008551 0.185539 -vn 0.552288 -0.318866 -0.770261 -v -0.024293 -0.009375 0.185539 -vn 0.637726 -0.000000 -0.770263 -v -0.024594 -0.010500 0.185539 -vn 0.552288 0.318866 -0.770261 -v -0.024293 -0.011625 0.185539 -vn 0.318866 0.552289 -0.770261 -v -0.023469 -0.012449 0.185539 -vn 0.000002 0.637727 -0.770262 -v -0.022344 0.008250 0.185539 -vn -0.318863 0.552289 -0.770262 -v -0.021219 0.008551 0.185539 -vn -0.552288 0.318866 -0.770261 -v -0.020395 0.009375 0.185539 -vn -0.637726 0.000000 -0.770263 -v -0.020094 0.010500 0.185539 -vn -0.552288 -0.318866 -0.770261 -v -0.020395 0.011625 0.185539 -vn -0.318863 -0.552289 -0.770262 -v -0.021219 0.012449 0.185539 -vn 0.000002 -0.637727 -0.770262 -v -0.022344 0.012750 0.185539 -vn 0.318866 -0.552289 -0.770261 -v -0.023469 0.012449 0.185539 -vn 0.552288 -0.318866 -0.770261 -v -0.024293 0.011625 0.185539 -vn 0.637726 0.000000 -0.770263 -v -0.024594 0.010500 0.185539 -vn 0.552288 0.318866 -0.770261 -v -0.024293 0.009375 0.185539 -vn 0.318866 0.552288 -0.770261 -v -0.023469 0.008551 0.185539 -vn -0.000000 -0.637728 0.770261 -v -0.018049 -0.042750 0.178700 -vn 0.000000 -0.637728 -0.770261 -v -0.018049 -0.042750 0.168800 -vn -0.318863 -0.552289 0.770262 -v -0.016924 -0.043051 0.178700 -vn -0.318863 -0.552289 -0.770262 -v -0.016924 -0.043051 0.168800 -vn -0.552288 -0.318866 0.770261 -v -0.016101 -0.043875 0.178700 -vn -0.552288 -0.318866 -0.770261 -v -0.016101 -0.043875 0.168800 -vn -0.637726 0.000000 0.770263 -v -0.015799 -0.045000 0.178700 -vn -0.637726 0.000000 -0.770264 -v -0.015799 -0.045000 0.168800 -vn -0.552288 0.318866 0.770261 -v -0.016101 -0.046125 0.178700 -vn -0.552288 0.318866 -0.770261 -v -0.016101 -0.046125 0.168800 -vn -0.318863 0.552289 0.770262 -v -0.016924 -0.046949 0.178700 -vn -0.318863 0.552289 -0.770262 -v -0.016924 -0.046949 0.168800 -vn -0.000000 0.637728 0.770261 -v -0.018049 -0.047250 0.178700 -vn 0.000000 0.637728 -0.770261 -v -0.018049 -0.047250 0.168800 -vn 0.318863 0.552289 0.770262 -v -0.019174 -0.046949 0.178700 -vn 0.318863 0.552289 -0.770262 -v -0.019174 -0.046949 0.168800 -vn 0.552289 0.318858 0.770264 -v -0.019998 -0.046125 0.178700 -vn 0.552289 0.318858 -0.770264 -v -0.019998 -0.046125 0.168800 -vn 0.637733 0.000000 0.770257 -v -0.020299 -0.045000 0.178700 -vn 0.637734 0.000000 -0.770257 -v -0.020299 -0.045000 0.168800 -vn 0.552289 -0.318857 0.770264 -v -0.019998 -0.043875 0.178700 -vn 0.552289 -0.318857 -0.770264 -v -0.019998 -0.043875 0.168800 -vn 0.318863 -0.552289 0.770262 -v -0.019174 -0.043051 0.178700 -vn 0.318863 -0.552289 -0.770262 -v -0.019174 -0.043051 0.168800 -vn -0.452584 -0.048729 0.890389 -v -0.035299 0.035000 0.109772 -vn -0.541375 0.253420 0.801681 -v -0.068685 -0.017078 0.101192 -vn -0.042520 0.548771 0.834890 -v -0.072285 -0.019157 0.100974 -vn 0.467217 0.276588 0.839766 -v -0.075885 -0.017078 0.100885 -vn -0.014656 0.019622 0.999700 -v -0.076549 -0.037000 0.100883 -vn 0.467279 -0.276441 0.839780 -v -0.075885 -0.012922 0.100885 -vn 0.466829 -0.277366 0.839725 -v -0.075885 0.017078 0.100885 -vn -0.040288 -0.550215 0.834051 -v -0.072285 0.019157 0.100974 -vn -0.541375 -0.253420 0.801681 -v -0.068685 0.017078 0.101192 -vn -0.541353 -0.253397 0.801702 -v -0.068685 -0.012922 0.101192 -vn -0.541353 0.253397 0.801702 -v -0.068685 0.012922 0.101192 -vn -0.042970 -0.548479 0.835060 -v -0.072285 -0.010843 0.100974 -vn -0.042970 0.548479 0.835060 -v -0.072285 0.010843 0.100974 -vn 0.467279 0.276441 0.839780 -v -0.075885 0.012922 0.100885 -vn 0.039431 0.715654 0.697341 -v -0.080341 -0.037000 0.100955 -vn -0.547969 0.573151 0.609285 -v -0.091536 -0.037000 0.102011 -vn -0.452585 0.048730 0.890389 -v -0.035299 -0.035000 0.109772 -vn -0.881311 0.085263 0.464781 -v -0.017049 -0.035000 0.120473 -vn -0.881817 -0.084316 0.463993 -v -0.017049 0.035000 0.120473 -vn -0.539694 0.097864 0.836153 -v -0.022804 -0.035000 0.116525 -vn -0.538949 -0.097246 0.836706 -v -0.022804 0.035000 0.116525 -vn -0.500088 0.129571 0.856226 -v -0.026455 -0.035000 0.114311 -vn -0.500088 -0.129571 0.856226 -v -0.026455 0.035000 0.114311 -vn -0.463811 0.097854 0.880513 -v -0.028932 -0.035000 0.112927 -vn -0.463813 -0.097854 0.880513 -v -0.028932 0.035000 0.112927 -vn -0.904169 0.299124 0.304965 -v -0.091549 -0.037000 0.100883 -vn 0.757325 0.621397 -0.200810 -v -0.059785 0.039885 0.099590 -vn 0.759053 0.564630 -0.324085 -v -0.059785 0.039732 0.099255 -vn 0.778617 0.466107 -0.420119 -v -0.059785 0.039551 0.098989 -vn 0.798887 0.310773 -0.514976 -v -0.059785 0.039039 0.098536 -vn 0.807345 -0.192217 -0.557895 -v -0.059785 -0.038656 0.098353 -vn 0.797622 -0.368463 -0.477529 -v -0.059785 -0.039237 0.098675 -vn 0.774766 -0.516186 -0.365090 -v -0.059785 -0.039683 0.099173 -vn 0.798326 0.142860 -0.585035 -v -0.059785 0.038414 0.098285 -vn 0.782425 0.032284 -0.621907 -v -0.059785 0.038000 0.098241 -vn 0.792210 -0.051532 -0.608069 -v -0.059785 -0.038000 0.098241 -vn 0.753406 -0.604967 -0.257670 -v -0.059785 -0.039848 0.099493 -vn 0.745087 -0.650204 -0.148593 -v -0.059785 -0.039945 0.099798 -vn 0.503105 0.130404 -0.854330 -v -0.023703 0.038000 0.111286 -vn 0.466910 -0.098106 -0.878846 -v -0.026423 -0.038000 0.109738 -vn 0.449317 0.130393 -0.883805 -v -0.029342 0.038000 0.108196 -vn 0.419905 -0.098133 -0.902247 -v -0.034438 -0.038000 0.105776 -vn 0.393943 0.130259 -0.909858 -v -0.035161 0.038000 0.105459 -vn 0.373871 -0.113702 -0.920485 -v -0.035161 -0.038000 0.105459 -vn 0.337164 0.130293 -0.932386 -v -0.041138 0.038000 0.103088 -vn 0.331276 -0.098572 -0.938371 -v -0.042764 -0.038000 0.102515 -vn 0.278831 0.130297 -0.951460 -v -0.047250 0.038000 0.101089 -vn 0.279505 -0.149041 -0.948506 -v -0.047250 -0.038000 0.101089 -vn 0.221921 0.128304 -0.966586 -v -0.053473 0.038000 0.099472 -vn 0.230870 -0.097608 -0.968076 -v -0.051338 -0.038000 0.099980 -vn 0.879134 0.044056 -0.474533 -v -0.013049 0.038000 0.118479 -vn 0.880401 -0.033526 -0.473043 -v -0.013049 -0.038000 0.118479 -vn 0.552983 0.128640 -0.823202 -v -0.018265 0.038000 0.114718 -vn 0.554417 -0.097886 -0.826462 -v -0.018777 -0.038000 0.114374 -vn 0.509569 -0.144365 -0.848233 -v -0.023703 -0.038000 0.111286 -vn 0.678877 0.095830 0.727972 -v -0.013049 0.021000 0.194700 -vn 0.577350 -0.577350 0.577350 -v -0.013049 0.019300 0.194700 -vn 0.678874 -0.727973 0.095841 -v -0.013049 -0.025000 0.190700 -vn 0.568075 0.575537 -0.588259 -v -0.013049 0.042000 0.133241 -vn 0.568075 0.575537 0.588259 -v -0.013049 0.042000 0.149241 -vn 0.577350 0.577350 0.577350 -v -0.013049 -0.019300 0.194700 -vn 0.678877 -0.095830 0.727972 -v -0.013049 -0.021000 0.194700 -vn 0.577350 -0.577350 -0.577350 -v -0.013049 -0.050000 0.168800 -vn 0.577350 0.577350 -0.577350 -v -0.013049 0.050000 0.168800 -vn 0.568075 -0.575536 0.588260 -v -0.013049 -0.042000 0.149241 -vn 0.568075 -0.575537 -0.588259 -v -0.013049 -0.042000 0.133241 -vn 0.653224 -0.378577 0.655727 -v -0.013049 -0.023000 0.194164 -vn 0.653228 -0.655722 0.378579 -v -0.013049 -0.024464 0.192700 -vn 0.709230 0.702577 -0.058121 -v -0.013049 0.039994 0.120821 -vn 0.749530 0.640168 -0.168495 -v -0.013049 0.039816 0.119951 -vn 0.863424 0.176792 -0.472486 -v -0.013049 0.038562 0.118580 -vn 0.860015 0.283453 -0.424298 -v -0.013049 0.039001 0.118818 -vn 0.841893 0.370299 -0.392550 -v -0.013049 0.039057 0.118860 -vn 0.810530 0.480874 -0.334366 -v -0.013049 0.039477 0.119303 -vn 0.790781 0.556427 -0.255058 -v -0.013049 0.039734 0.119748 -vn 0.653224 0.378577 0.655727 -v -0.013049 0.023000 0.194164 -vn 0.653228 0.655722 0.378579 -v -0.013049 0.024464 0.192700 -vn 0.678874 0.727973 0.095841 -v -0.013049 0.025000 0.190700 -vn 0.801096 -0.495938 -0.335099 -v -0.013049 -0.039438 0.119250 -vn 0.842394 -0.320112 -0.433476 -v -0.013049 -0.038939 0.118774 -vn 0.737305 -0.652992 -0.173157 -v -0.013049 -0.039839 0.120017 -vn 0.865730 -0.143458 -0.479512 -v -0.013049 -0.038410 0.118532 -vn -0.318866 -0.552288 -0.770261 -v -0.071160 0.016949 0.090039 -vn -0.000002 -0.637727 -0.770262 -v -0.072285 0.017250 0.090039 -vn -0.318866 0.552288 -0.770261 -v -0.071160 -0.016949 0.090039 -vn -0.000002 0.637727 -0.770262 -v -0.072285 -0.017250 0.090039 -vn 0.318863 0.552289 -0.770262 -v -0.073410 -0.016949 0.090039 -vn 0.318863 -0.552288 -0.770262 -v -0.073410 0.016949 0.090039 -vn 0.552288 -0.318866 -0.770261 -v -0.074233 0.016125 0.090039 -vn 0.637726 0.000000 -0.770263 -v -0.074535 0.015000 0.090039 -vn 0.552288 -0.318866 -0.770261 -v -0.074233 -0.013875 0.090039 -vn 0.637726 0.000000 -0.770263 -v -0.074535 -0.015000 0.090039 -vn 0.552288 0.318866 -0.770261 -v -0.074233 -0.016125 0.090039 -vn -0.318865 0.552287 -0.770262 -v -0.071160 0.013051 0.090039 -vn -0.318866 -0.552288 -0.770261 -v -0.071160 -0.013051 0.090039 -vn -0.000002 0.637727 -0.770262 -v -0.072285 0.012750 0.090039 -vn -0.000002 -0.637729 -0.770261 -v -0.072285 -0.012750 0.090039 -vn 0.318863 0.552289 -0.770262 -v -0.073410 0.013051 0.090039 -vn -0.552288 0.318866 -0.770261 -v -0.070336 0.013875 0.090039 -vn -0.637726 -0.000000 -0.770263 -v -0.070035 0.015000 0.090039 -vn -0.552288 -0.318866 -0.770261 -v -0.070336 0.016125 0.090039 -vn 0.318863 -0.552288 -0.770262 -v -0.073410 -0.013051 0.090039 -vn 0.552288 0.318866 -0.770261 -v -0.074233 0.013875 0.090039 -vn -0.552288 0.318866 -0.770261 -v -0.070336 -0.016125 0.090039 -vn -0.637726 -0.000000 -0.770263 -v -0.070035 -0.015000 0.090039 -vn -0.552288 -0.318866 -0.770261 -v -0.070336 -0.013875 0.090039 -vn -0.000002 -0.637727 0.770262 -v -0.072285 -0.012750 0.095039 -vn -0.318866 -0.552288 0.770261 -v -0.071160 -0.013051 0.095039 -vn -0.552288 -0.318866 0.770261 -v -0.070336 -0.013875 0.095039 -vn -0.637726 -0.000000 0.770263 -v -0.070035 -0.015000 0.095039 -vn -0.552288 0.318866 0.770261 -v -0.070336 -0.016125 0.095039 -vn -0.318866 0.552288 0.770261 -v -0.071160 -0.016949 0.095039 -vn -0.000002 0.637727 0.770262 -v -0.072285 -0.017250 0.095039 -vn 0.318863 0.552288 0.770262 -v -0.073410 -0.016949 0.095039 -vn 0.552288 0.318866 0.770261 -v -0.074233 -0.016125 0.095039 -vn 0.637726 0.000000 0.770263 -v -0.074535 -0.015000 0.095039 -vn 0.552288 -0.318866 0.770261 -v -0.074233 -0.013875 0.095039 -vn 0.318863 -0.552289 0.770262 -v -0.073410 -0.013051 0.095039 -vn -0.000002 -0.637727 0.770262 -v -0.072285 0.017250 0.095039 -vn -0.318866 -0.552288 0.770261 -v -0.071160 0.016949 0.095039 -vn -0.552288 -0.318866 0.770261 -v -0.070336 0.016125 0.095039 -vn -0.637726 -0.000000 0.770263 -v -0.070035 0.015000 0.095039 -vn -0.552288 0.318866 0.770261 -v -0.070336 0.013875 0.095039 -vn -0.318866 0.552288 0.770261 -v -0.071160 0.013051 0.095039 -vn -0.000002 0.637727 0.770262 -v -0.072285 0.012750 0.095039 -vn 0.318863 0.552288 0.770262 -v -0.073410 0.013051 0.095039 -vn 0.552288 0.318866 0.770261 -v -0.074233 0.013875 0.095039 -vn 0.637726 0.000000 0.770263 -v -0.074535 0.015000 0.095039 -vn 0.552288 -0.318866 0.770261 -v -0.074233 0.016125 0.095039 -vn 0.318863 -0.552289 0.770262 -v -0.073410 0.016949 0.095039 -vn 0.000000 -0.792406 0.609994 -v -0.072285 0.019157 0.095039 -vn 0.686244 -0.396203 0.609994 -v -0.075885 0.017078 0.095039 -vn 0.686244 0.396203 0.609994 -v -0.075885 0.012922 0.095039 -vn -0.000000 0.792406 0.609994 -v -0.072285 0.010843 0.095039 -vn -0.686244 0.396203 0.609994 -v -0.068685 0.012922 0.095039 -vn -0.686244 -0.396203 0.609994 -v -0.068685 0.017078 0.095039 -vn 0.000000 -0.792406 0.609994 -v -0.072285 -0.010843 0.095039 -vn 0.686244 -0.396203 0.609994 -v -0.075885 -0.012922 0.095039 -vn 0.686243 0.396203 0.609994 -v -0.075885 -0.017078 0.095039 -vn -0.000000 0.792406 0.609994 -v -0.072285 -0.019157 0.095039 -vn -0.686244 0.396203 0.609994 -v -0.068685 -0.017078 0.095039 -vn -0.686244 -0.396203 0.609994 -v -0.068685 -0.012922 0.095039 -vn -0.577350 -0.577350 -0.577351 -v -0.023049 -0.050000 0.168800 -vn -0.904534 -0.301511 0.301511 -v -0.023049 -0.041000 0.178700 -vn -0.577350 -0.577350 0.577351 -v -0.023049 -0.050000 0.178700 -vn -0.301511 -0.904534 0.301511 -v -0.014049 -0.050000 0.178700 -vn 0.318863 -0.552289 -0.770262 -v -0.019174 0.046949 0.168800 -vn -0.577350 0.577350 -0.577351 -v -0.023049 0.050000 0.168800 -vn 0.000000 -0.637728 -0.770261 -v -0.018049 0.047250 0.168800 -vn -0.318863 -0.552289 -0.770262 -v -0.016924 0.046949 0.168800 -vn -0.318863 0.552289 -0.770262 -v -0.016924 0.043051 0.168800 -vn -0.552288 0.318866 -0.770261 -v -0.016101 0.043875 0.168800 -vn -0.637726 -0.000000 -0.770264 -v -0.015799 0.045000 0.168800 -vn -0.552288 -0.318866 -0.770261 -v -0.016101 0.046125 0.168800 -vn 0.000000 0.637728 -0.770261 -v -0.018049 0.042750 0.168800 -vn 0.318863 0.552289 -0.770262 -v -0.019174 0.043051 0.168800 -vn 0.552289 -0.318858 -0.770264 -v -0.019998 0.046125 0.168800 -vn 0.637733 -0.000000 -0.770257 -v -0.020299 0.045000 0.168800 -vn 0.552289 0.318857 -0.770264 -v -0.019998 0.043875 0.168800 -vn -0.301511 0.904534 0.301511 -v -0.014049 0.050000 0.178700 -vn -0.577350 0.577350 0.577350 -v -0.023049 0.050000 0.178700 -vn -0.904534 0.301511 0.301511 -v -0.023049 0.041000 0.178700 -vn -0.000000 -0.637728 0.770261 -v -0.018049 0.047250 0.178700 -vn -0.318863 -0.552289 0.770262 -v -0.016924 0.046949 0.178700 -vn -0.552288 -0.318866 0.770261 -v -0.016101 0.046125 0.178700 -vn -0.637726 -0.000000 0.770263 -v -0.015799 0.045000 0.178700 -vn -0.552288 0.318866 0.770261 -v -0.016101 0.043875 0.178700 -vn -0.318863 0.552289 0.770262 -v -0.016924 0.043051 0.178700 -vn -0.000000 0.637728 0.770261 -v -0.018049 0.042750 0.178700 -vn 0.318863 0.552289 0.770262 -v -0.019174 0.043051 0.178700 -vn 0.552289 0.318857 0.770264 -v -0.019998 0.043875 0.178700 -vn 0.637733 -0.000000 0.770257 -v -0.020299 0.045000 0.178700 -vn 0.552289 -0.318858 0.770264 -v -0.019998 0.046125 0.178700 -vn 0.318863 -0.552289 0.770262 -v -0.019174 0.046949 0.178700 -vn -0.727973 0.095841 0.678874 -v -0.014049 0.045000 0.178700 -vn -0.095839 0.727973 0.678874 -v -0.018049 0.041000 0.178700 -vn -0.655721 0.378582 0.653227 -v -0.014585 0.043000 0.178700 -vn -0.378581 0.655722 0.653227 -v -0.016049 0.041536 0.178700 -vn -0.095839 -0.727973 0.678874 -v -0.018049 -0.041000 0.178700 -vn -0.727973 -0.095841 0.678874 -v -0.014049 -0.045000 0.178700 -vn -0.378581 -0.655722 0.653227 -v -0.016049 -0.041536 0.178700 -vn -0.655721 -0.378582 0.653227 -v -0.014585 -0.043000 0.178700 -vn -0.678874 -0.727973 0.095841 -v -0.034549 -0.025000 0.190700 -vn -0.678874 0.727973 0.095841 -v -0.034549 0.025000 0.190700 -vn -0.678877 -0.095830 0.727972 -v -0.034549 -0.021000 0.194700 -vn -0.577350 0.577350 0.577350 -v -0.034549 -0.019300 0.194700 -vn -0.577350 -0.577350 0.577350 -v -0.034549 0.019300 0.194700 -vn -0.678877 0.095830 0.727971 -v -0.034549 0.021000 0.194700 -vn -0.653224 -0.378577 0.655727 -v -0.034549 -0.023000 0.194164 -vn -0.653228 -0.655722 0.378579 -v -0.034549 -0.024464 0.192700 -vn -0.653224 0.378577 0.655727 -v -0.034549 0.023000 0.194164 -vn -0.653228 0.655722 0.378579 -v -0.034549 0.024464 0.192700 -vn 0.792406 0.000000 -0.609994 -v -0.026443 0.010500 0.185539 -vn 0.396203 0.686244 -0.609994 -v -0.024394 0.006950 0.185539 -vn 0.396203 -0.686244 -0.609994 -v -0.024394 0.014050 0.185539 -vn -0.396203 -0.686244 -0.609994 -v -0.020294 0.014050 0.185539 -vn -0.792406 -0.000000 -0.609995 -v -0.018245 0.010500 0.185539 -vn -0.396202 0.686244 -0.609995 -v -0.020294 0.006950 0.185539 -vn 0.792406 -0.000000 -0.609994 -v -0.026443 -0.010500 0.185539 -vn 0.396203 0.686244 -0.609994 -v -0.024394 -0.014050 0.185539 -vn 0.396203 -0.686244 -0.609994 -v -0.024394 -0.006950 0.185539 -vn -0.396203 -0.686244 -0.609994 -v -0.020294 -0.006950 0.185539 -vn -0.792406 -0.000000 -0.609995 -v -0.018245 -0.010500 0.185539 -vn -0.396202 0.686244 -0.609995 -v -0.020294 -0.014050 0.185539 -vn -0.726994 -0.680939 -0.088335 -v -0.088049 -0.042000 0.130393 -vn -0.586391 -0.579208 0.566271 -v -0.088049 -0.042000 0.146622 -vn -0.009401 -0.684058 -0.729367 -v -0.085285 -0.042000 0.127399 -vn -0.174266 -0.680843 -0.711396 -v -0.085408 -0.042000 0.127414 -vn -0.794671 0.601386 -0.082661 -v -0.035808 -0.036848 0.110897 -vn -0.883466 0.456600 0.104901 -v -0.035540 -0.036414 0.110306 -vn -0.941992 0.245789 0.228559 -v -0.035362 -0.035765 0.109911 -vn -0.427827 -0.656969 -0.620770 -v -0.086752 -0.042000 0.127922 -vn -0.667439 -0.656962 -0.350609 -v -0.087705 -0.042000 0.128998 -vn 0.603763 -0.754847 -0.256274 -v -0.082890 -0.042000 0.134395 -vn 0.455612 -0.754865 -0.471802 -v -0.082439 -0.042000 0.135053 -vn 0.312932 -0.900418 0.302195 -v -0.085049 -0.042000 0.138757 -vn 0.312932 -0.900418 -0.302194 -v -0.085049 -0.042000 0.143724 -vn -0.290145 -0.908594 -0.300454 -v -0.016049 -0.042000 0.146134 -vn -0.290146 -0.908594 0.300454 -v -0.016049 -0.042000 0.136347 -vn 0.044692 -0.730375 -0.681583 -v -0.080980 -0.042000 0.135613 -vn 0.235059 -0.754842 -0.612340 -v -0.081766 -0.042000 0.135481 -vn 0.224244 -0.662849 -0.714385 -v -0.084451 -0.042000 0.127477 -vn 0.497286 -0.662843 -0.559774 -v -0.083721 -0.042000 0.127890 -vn 0.679614 -0.730370 -0.068440 -v -0.083049 -0.042000 0.133614 -vn 0.725287 -0.684145 -0.076839 -v -0.083049 -0.042000 0.129386 -vn 0.683006 -0.662842 -0.306828 -v -0.083225 -0.042000 0.128566 -vn 0.586392 -0.579208 -0.566271 -v -0.085049 -0.040000 0.143724 -vn 0.586391 -0.579208 0.566271 -v -0.085049 -0.040000 0.138757 -vn -0.568075 -0.575537 0.588259 -v -0.016049 -0.040000 0.136347 -vn -0.568075 -0.575537 -0.588258 -v -0.016049 -0.040000 0.146134 -vn -0.586391 0.579207 0.566272 -v -0.088049 0.042000 0.146622 -vn -0.726994 0.680938 -0.088335 -v -0.088049 0.042000 0.130393 -vn -0.174266 0.680843 -0.711396 -v -0.085408 0.042000 0.127414 -vn -0.009401 0.684058 -0.729367 -v -0.085285 0.042000 0.127399 -vn -0.883466 -0.456600 0.104901 -v -0.035540 0.036414 0.110306 -vn -0.941991 -0.245790 0.228559 -v -0.035362 0.035765 0.109911 -vn -0.794671 -0.601386 -0.082661 -v -0.035808 0.036848 0.110897 -vn 0.044692 0.730375 -0.681583 -v -0.080980 0.042000 0.135613 -vn 0.235059 0.754842 -0.612340 -v -0.081766 0.042000 0.135481 -vn 0.455612 0.754865 -0.471802 -v -0.082439 0.042000 0.135053 -vn 0.603762 0.754847 -0.256274 -v -0.082890 0.042000 0.134395 -vn 0.679614 0.730370 -0.068440 -v -0.083049 0.042000 0.133614 -vn 0.725287 0.684145 -0.076839 -v -0.083049 0.042000 0.129386 -vn 0.683006 0.662842 -0.306828 -v -0.083225 0.042000 0.128566 -vn 0.497285 0.662843 -0.559774 -v -0.083721 0.042000 0.127890 -vn 0.224244 0.662849 -0.714385 -v -0.084451 0.042000 0.127477 -vn -0.427827 0.656969 -0.620770 -v -0.086752 0.042000 0.127922 -vn -0.667439 0.656962 -0.350609 -v -0.087705 0.042000 0.128998 -vn 0.312932 0.900418 0.302195 -v -0.085049 0.042000 0.138757 -vn 0.312932 0.900418 -0.302195 -v -0.085049 0.042000 0.143724 -vn -0.290146 0.908594 -0.300454 -v -0.016049 0.042000 0.146134 -vn -0.290146 0.908594 0.300455 -v -0.016049 0.042000 0.136347 -vn 0.586391 0.579208 0.566272 -v -0.085049 0.040000 0.138757 -vn 0.586392 0.579208 -0.566270 -v -0.085049 0.040000 0.143724 -vn -0.568075 0.575537 -0.588259 -v -0.016049 0.040000 0.146134 -vn -0.568075 0.575537 0.588258 -v -0.016049 0.040000 0.136347 -vn -0.085736 0.995166 0.047901 -v -0.019041 -0.037000 0.121484 -vn -0.260251 0.955425 0.139402 -v -0.018405 -0.036893 0.121160 -vn -0.205050 0.922657 0.326588 -v -0.023467 -0.036848 0.117567 -vn -0.604991 0.726643 0.325540 -v -0.017637 -0.036416 0.120770 -vn -0.687310 0.626605 0.367385 -v -0.017413 -0.036149 0.120656 -vn -0.497739 0.383009 0.778177 -v -0.022886 -0.035765 0.116653 -vn -0.762975 0.505369 0.403077 -v -0.017318 -0.036002 0.120608 -vn -0.844055 0.298592 0.445436 -v -0.017145 -0.035609 0.120521 -vn -0.407854 0.886250 0.219580 -v -0.018052 -0.036733 0.120980 -vn -0.508766 0.817062 0.271233 -v -0.017833 -0.036588 0.120869 -vn -0.379136 0.704297 0.600185 -v -0.023119 -0.036414 0.117019 -vn -0.183722 0.922320 0.339960 -v -0.029519 -0.036848 0.114013 -vn -0.337222 0.704916 0.623999 -v -0.029210 -0.036414 0.113442 -vn -0.435028 0.384123 0.814371 -v -0.029004 -0.035765 0.113061 -vn -0.326872 0.944737 -0.025055 -v -0.018284 -0.036848 0.177200 -vn -0.709127 0.703044 -0.053557 -v -0.017635 -0.036414 0.177200 -vn -0.530815 0.846478 -0.041358 -v -0.018049 -0.036732 0.177200 -vn -0.848703 0.524911 -0.064587 -v -0.017317 -0.036000 0.177200 -vn -0.945176 0.318839 -0.070596 -v -0.017202 -0.035765 0.177200 -vn -0.342402 0.386301 -0.856465 -v -0.021885 -0.035765 0.184048 -vn -0.883996 0.383471 -0.267398 -v -0.017530 -0.035765 0.179371 -vn -0.028317 0.917233 -0.397343 -v -0.024104 -0.036848 0.183450 -vn -0.144450 0.917233 -0.371238 -v -0.022278 -0.036848 0.183039 -vn -0.247680 0.917235 -0.311986 -v -0.020654 -0.036848 0.182107 -vn -0.328809 0.917230 -0.224884 -v -0.019378 -0.036848 0.180737 -vn -0.087847 0.384467 -0.918950 -v -0.024027 -0.035765 0.184529 -vn -0.442328 0.699071 -0.561823 -v -0.025538 -0.035632 0.184531 -vn -0.055110 0.699900 -0.712112 -v -0.024058 -0.036414 0.184097 -vn -0.306121 0.838752 -0.450317 -v -0.026192 -0.036232 0.184082 -vn 0.102803 0.747796 -0.655921 -v -0.026118 -0.036414 0.183934 -vn -0.208756 0.894181 -0.396058 -v -0.026373 -0.036356 0.183927 -vn -0.171172 0.945783 -0.276035 -v -0.026562 -0.036471 0.183753 -vn -0.094677 0.973395 -0.208657 -v -0.027147 -0.036746 0.183132 -vn 0.071468 0.920080 -0.385155 -v -0.025970 -0.036848 0.183302 -vn -0.047206 0.994562 -0.092837 -v -0.027621 -0.036891 0.182531 -vn -0.000740 0.999999 -0.001505 -v -0.028542 -0.037000 0.180990 -vn -0.008635 0.999812 -0.017349 -v -0.028397 -0.036997 0.181280 -vn -0.376697 0.918322 -0.121589 -v -0.018564 -0.036848 0.179051 -vn -0.682209 0.697805 -0.218310 -v -0.017944 -0.036414 0.179243 -vn -0.591135 0.697927 -0.404299 -v -0.018842 -0.036414 0.181103 -vn -0.766121 0.379124 -0.518965 -v -0.018485 -0.035765 0.181348 -vn -0.567326 0.385274 -0.727808 -v -0.019981 -0.035765 0.182955 -vn -0.445289 0.697936 -0.560895 -v -0.020250 -0.036414 0.182615 -vn -0.259690 0.697939 -0.667415 -v -0.022042 -0.036414 0.183644 -vn -0.183720 -0.922320 0.339960 -v -0.029519 0.036848 0.114013 -vn -0.085736 -0.995166 0.047901 -v -0.019041 0.037000 0.121484 -vn -0.205050 -0.922657 0.326587 -v -0.023467 0.036848 0.117567 -vn -0.260299 -0.955419 0.139354 -v -0.018405 0.036893 0.121160 -vn -0.408030 -0.886222 0.219369 -v -0.018052 0.036733 0.120980 -vn -0.377754 -0.704880 0.600372 -v -0.023119 0.036414 0.117019 -vn -0.546209 -0.786005 0.289571 -v -0.017833 0.036588 0.120869 -vn -0.675007 -0.644957 0.358324 -v -0.017413 0.036149 0.120656 -vn -0.496031 -0.382829 0.779355 -v -0.022886 0.035765 0.116653 -vn -0.762932 -0.505396 0.403125 -v -0.017318 0.036002 0.120608 -vn -0.844370 -0.299450 0.444263 -v -0.017145 0.035609 0.120521 -vn -0.435028 -0.384124 0.814370 -v -0.029004 0.035765 0.113061 -vn -0.337222 -0.704915 0.624001 -v -0.029210 0.036414 0.113442 -vn -0.945156 -0.318858 -0.070784 -v -0.017202 0.035765 0.177200 -vn -0.848673 -0.524950 -0.064664 -v -0.017317 0.036000 0.177200 -vn -0.709095 -0.703082 -0.053479 -v -0.017635 0.036414 0.177200 -vn -0.530829 -0.846476 -0.041224 -v -0.018049 0.036732 0.177200 -vn -0.326906 -0.944726 -0.024998 -v -0.018284 0.036848 0.177200 -vn -0.376696 -0.918323 -0.121587 -v -0.018564 0.036848 0.179051 -vn -0.328808 -0.917230 -0.224888 -v -0.019378 0.036848 0.180737 -vn -0.247683 -0.917234 -0.311987 -v -0.020654 0.036848 0.182107 -vn -0.144449 -0.917234 -0.371236 -v -0.022278 0.036848 0.183039 -vn -0.035452 -0.997454 -0.061882 -v -0.028010 0.036963 0.181954 -vn -0.006210 -0.999893 -0.013220 -v -0.028397 0.036997 0.181280 -vn -0.000740 -0.999999 -0.001505 -v -0.028542 0.037000 0.180990 -vn 0.069915 -0.922800 -0.378883 -v -0.025970 0.036848 0.183302 -vn -0.080722 -0.985292 -0.150608 -v -0.027147 0.036746 0.183132 -vn -0.441280 -0.717281 -0.539240 -v -0.025538 0.035632 0.184531 -vn -0.322026 -0.840234 -0.436241 -v -0.026192 0.036232 0.184082 -vn 0.095802 -0.730245 -0.676435 -v -0.026118 0.036414 0.183934 -vn -0.191262 -0.932790 -0.305486 -v -0.026566 0.036474 0.183749 -vn -0.115792 -0.958937 -0.258907 -v -0.026976 0.036677 0.183326 -vn -0.054182 -0.699820 -0.712261 -v -0.024058 0.036414 0.184097 -vn -0.077236 -0.388427 -0.918237 -v -0.024027 0.035765 0.184529 -vn -0.028314 -0.917233 -0.397344 -v -0.024104 0.036848 0.183450 -vn -0.682210 -0.697804 -0.218309 -v -0.017944 0.036414 0.179243 -vn -0.591133 -0.697927 -0.404301 -v -0.018842 0.036414 0.181103 -vn -0.884654 -0.384487 -0.263738 -v -0.017530 0.035765 0.179371 -vn -0.756961 -0.387533 -0.526145 -v -0.018485 0.035765 0.181348 -vn -0.345840 -0.387643 -0.854475 -v -0.021885 0.035765 0.184048 -vn -0.259694 -0.697939 -0.667413 -v -0.022042 0.036414 0.183644 -vn -0.445290 -0.697936 -0.560894 -v -0.020250 0.036414 0.182615 -vn -0.567326 -0.385275 -0.727808 -v -0.019981 0.035765 0.182955 -vn 0.482516 0.498965 -0.719870 -v -0.018415 0.039000 0.114940 -vn 0.280798 0.863616 -0.418712 -v -0.018825 0.039732 0.115546 -vn 0.116496 0.863745 -0.490278 -v -0.053695 0.039732 0.100447 -vn 0.196788 0.497885 -0.844621 -v -0.053533 0.039000 0.099733 -vn 0.243974 0.497796 -0.832272 -v -0.047325 0.039000 0.101346 -vn 0.294868 0.497794 -0.815631 -v -0.041229 0.039000 0.103340 -vn 0.344632 0.497813 -0.795871 -v -0.035268 0.039000 0.105705 -vn 0.393089 0.497808 -0.773090 -v -0.029463 0.039000 0.108434 -vn 0.440044 0.497806 -0.747362 -v -0.023839 0.039000 0.111516 -vn 0.141718 0.863826 -0.483447 -v -0.047531 0.039732 0.102049 -vn 0.171285 0.863822 -0.473786 -v -0.041478 0.039732 0.104028 -vn 0.200190 0.863828 -0.462304 -v -0.035558 0.039732 0.106377 -vn 0.228339 0.863824 -0.449076 -v -0.029795 0.039732 0.109087 -vn 0.255615 0.863823 -0.434133 -v -0.024210 0.039732 0.112147 -vn 0.303906 -0.383694 -0.872021 -v -0.042813 -0.038765 0.102659 -vn 0.512099 -0.383557 -0.768530 -v -0.018862 -0.038765 0.114501 -vn 0.218520 -0.384501 -0.896888 -v -0.051375 -0.038765 0.100128 -vn 0.213817 -0.922159 -0.322343 -v -0.019462 -0.039848 0.115401 -vn 0.391893 -0.704637 -0.591529 -v -0.019102 -0.039414 0.114861 -vn 0.172989 -0.703620 -0.689198 -v -0.051480 -0.039414 0.100549 -vn 0.096321 -0.922032 -0.374940 -v -0.051637 -0.039848 0.101178 -vn 0.156555 -0.921988 -0.354160 -v -0.034938 -0.039848 0.106905 -vn 0.125603 -0.921988 -0.366281 -v -0.043164 -0.039848 0.103683 -vn 0.286959 -0.704451 -0.649156 -v -0.034675 -0.039414 0.106311 -vn 0.230227 -0.704440 -0.671386 -v -0.042954 -0.039414 0.103069 -vn 0.377290 -0.385164 -0.842200 -v -0.034500 -0.038765 0.105915 -vn 0.438978 -0.384741 -0.811956 -v -0.026496 -0.038765 0.109872 -vn 0.341578 -0.704448 -0.622155 -v -0.026705 -0.039414 0.110252 -vn 0.186354 -0.921988 -0.339428 -v -0.027017 -0.039848 0.110821 -# 714 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 3//3 4//4 1//1 -f 1//1 4//4 5//5 -f 1//1 5//5 6//6 -f 7//7 8//8 4//4 -f 4//4 8//8 9//9 -f 4//4 9//9 10//10 -f 11//11 12//12 4//4 -f 4//4 12//12 13//13 -f 4//4 13//13 5//5 -f 10//10 14//14 4//4 -f 4//4 14//14 15//15 -f 4//4 15//15 11//11 -f 16//16 17//17 18//18 -f 18//18 17//17 19//19 -f 20//20 21//21 22//22 -f 21//21 20//20 23//23 -f 24//24 25//25 26//26 -f 27//27 28//28 29//29 -f 19//19 30//30 18//18 -f 18//18 30//30 31//31 -f 18//18 31//31 32//32 -f 32//32 31//31 33//33 -f 32//32 33//33 34//34 -f 34//34 33//33 27//27 -f 34//34 27//27 35//35 -f 35//35 27//27 29//29 -f 22//22 36//36 20//20 -f 20//20 36//36 37//37 -f 20//20 37//37 38//38 -f 38//38 37//37 39//39 -f 38//38 39//39 40//40 -f 40//40 39//39 41//41 -f 40//40 41//41 28//28 -f 28//28 41//41 42//42 -f 28//28 42//42 29//29 -f 26//26 43//43 24//24 -f 24//24 43//43 44//44 -f 24//24 44//44 45//45 -f 45//45 44//44 46//46 -f 45//45 46//46 47//47 -f 47//47 46//46 48//48 -f 48//48 49//49 50//50 -f 20//20 47//47 23//23 -f 23//23 47//47 48//48 -f 23//23 48//48 51//51 -f 51//51 48//48 50//50 -f 52//52 53//53 54//54 -f 55//55 56//56 57//57 -f 58//58 59//59 60//60 -f 60//60 59//59 61//61 -f 62//62 55//55 63//63 -f 63//63 55//55 57//57 -f 63//63 57//57 64//64 -f 64//64 57//57 65//65 -f 63//63 66//66 62//62 -f 62//62 66//66 67//67 -f 62//62 67//67 68//68 -f 68//68 67//67 69//69 -f 70//70 53//53 71//71 -f 71//71 53//53 52//52 -f 71//71 52//52 72//72 -f 72//72 52//52 73//73 -f 72//72 73//73 74//74 -f 74//74 73//73 75//75 -f 74//74 75//75 76//76 -f 76//76 75//75 69//69 -f 76//76 69//69 77//77 -f 77//77 69//69 67//67 -f 78//78 79//79 80//80 -f 80//80 79//79 81//81 -f 80//80 81//81 59//59 -f 59//59 81//81 82//82 -f 59//59 82//82 61//61 -f 83//83 84//84 85//85 -f 85//85 84//84 79//79 -f 85//85 79//79 54//54 -f 54//54 79//79 78//78 -f 54//54 78//78 52//52 -f 86//86 87//87 88//88 -f 89//89 90//90 91//91 -f 92//92 93//93 94//94 -f 94//94 93//93 95//95 -f 96//96 97//97 93//93 -f 88//88 98//98 96//96 -f 99//99 100//100 101//101 -f 102//102 103//103 104//104 -f 104//104 103//103 86//86 -f 104//104 86//86 105//105 -f 105//105 86//86 88//88 -f 105//105 88//88 106//106 -f 106//106 88//88 96//96 -f 106//106 96//96 107//107 -f 107//107 96//96 93//93 -f 108//108 109//109 87//87 -f 87//87 109//109 110//110 -f 87//87 110//110 111//111 -f 112//112 113//113 87//87 -f 87//87 113//113 114//114 -f 87//87 114//114 88//88 -f 115//115 95//95 90//90 -f 90//90 95//95 93//93 -f 90//90 93//93 91//91 -f 91//91 93//93 97//97 -f 89//89 91//91 101//101 -f 101//101 91//91 116//116 -f 101//101 116//116 99//99 -f 111//111 117//117 87//87 -f 87//87 117//117 118//118 -f 87//87 118//118 112//112 -f 119//119 120//120 121//121 -f 121//121 120//120 122//122 -f 121//121 122//122 123//123 -f 124//124 125//125 126//126 -f 126//126 125//125 127//127 -f 128//128 129//129 130//130 -f 128//128 130//130 131//131 -f 132//132 133//133 134//134 -f 134//134 133//133 135//135 -f 136//136 137//137 138//138 -f 130//130 136//136 139//139 -f 130//130 140//140 136//136 -f 136//136 140//140 141//141 -f 136//136 141//141 137//137 -f 142//142 136//136 143//143 -f 143//143 136//136 138//138 -f 143//143 138//138 144//144 -f 144//144 138//138 133//133 -f 144//144 133//133 145//145 -f 132//132 146//146 133//133 -f 133//133 146//146 147//147 -f 133//133 147//147 145//145 -f 148//148 149//149 150//150 -f 139//139 151//151 130//130 -f 130//130 151//151 152//152 -f 130//130 152//152 153//153 -f 147//147 154//154 145//145 -f 145//145 154//154 148//148 -f 145//145 148//148 155//155 -f 155//155 148//148 150//150 -f 153//153 156//156 130//130 -f 130//130 156//156 157//157 -f 130//130 157//157 131//131 -f 19//19 125//125 30//30 -f 30//30 125//125 124//124 -f 128//128 8//8 129//129 -f 129//129 8//8 7//7 -f 158//158 159//159 160//160 -f 161//161 162//162 160//160 -f 160//160 162//162 163//163 -f 158//158 160//160 164//164 -f 163//163 165//165 160//160 -f 160//160 165//165 166//166 -f 160//160 166//166 167//167 -f 167//167 168//168 160//160 -f 160//160 168//168 169//169 -f 160//160 169//169 170//170 -f 170//170 171//171 160//160 -f 160//160 171//171 172//172 -f 160//160 172//172 164//164 -f 158//158 109//109 159//159 -f 159//159 109//109 108//108 -f 173//173 174//174 175//175 -f 176//176 177//177 165//165 -f 178//178 179//179 173//173 -f 180//180 181//181 182//182 -f 182//182 181//181 173//173 -f 182//182 173//173 183//183 -f 183//183 173//173 179//179 -f 175//175 184//184 173//173 -f 173//173 184//184 185//185 -f 173//173 185//185 176//176 -f 176//176 165//165 173//173 -f 173//173 165//165 186//186 -f 173//173 186//186 178//178 -f 88//88 166//166 98//98 -f 98//98 166//166 165//165 -f 98//98 165//165 187//187 -f 187//187 165//165 177//177 -f 188//188 189//189 190//190 -f 191//191 192//192 193//193 -f 190//190 189//189 193//193 -f 194//194 195//195 196//196 -f 196//196 195//195 197//197 -f 196//196 197//197 190//190 -f 190//190 197//197 198//198 -f 190//190 198//198 188//188 -f 199//199 191//191 200//200 -f 200//200 191//191 193//193 -f 200//200 193//193 201//201 -f 201//201 193//193 189//189 -f 192//192 202//202 193//193 -f 193//193 202//202 203//203 -f 193//193 203//203 204//204 -f 204//204 203//203 205//205 -f 204//204 205//205 206//206 -f 199//199 200//200 207//207 -f 207//207 200//200 208//208 -f 207//207 208//208 209//209 -f 206//206 210//210 204//204 -f 204//204 210//210 211//211 -f 204//204 211//211 196//196 -f 196//196 211//211 212//212 -f 196//196 212//212 209//209 -f 208//208 213//213 209//209 -f 209//209 213//213 214//214 -f 209//209 214//214 196//196 -f 196//196 214//214 215//215 -f 196//196 215//215 194//194 -f 216//216 217//217 218//218 -f 218//218 217//217 219//219 -f 218//218 219//219 220//220 -f 221//221 222//222 217//217 -f 217//217 222//222 223//223 -f 217//217 223//223 224//224 -f 225//225 6//6 226//226 -f 226//226 6//6 217//217 -f 226//226 217//217 227//227 -f 227//227 217//217 216//216 -f 5//5 136//136 6//6 -f 6//6 136//136 142//142 -f 142//142 228//228 6//6 -f 6//6 228//228 229//229 -f 6//6 229//229 217//217 -f 217//217 229//229 230//230 -f 217//217 230//230 221//221 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 234//234 235//235 233//233 -f 233//233 235//235 236//236 -f 233//233 236//236 237//237 -f 236//236 238//238 237//237 -f 237//237 238//238 239//239 -f 237//237 239//239 240//240 -f 240//240 239//239 241//241 -f 242//242 243//243 231//231 -f 231//231 243//243 244//244 -f 231//231 244//244 232//232 -f 237//237 245//245 233//233 -f 233//233 245//245 246//246 -f 233//233 246//246 247//247 -f 248//248 249//249 250//250 -f 251//251 252//252 253//253 -f 253//253 252//252 248//248 -f 253//253 248//248 254//254 -f 254//254 248//248 250//250 -f 255//255 256//256 257//257 -f 246//246 258//258 247//247 -f 247//247 258//258 259//259 -f 247//247 259//259 257//257 -f 257//257 259//259 260//260 -f 257//257 260//260 255//255 -f 261//261 262//262 263//263 -f 263//263 262//262 252//252 -f 263//263 252//252 264//264 -f 264//264 252//252 251//251 -f 265//265 262//262 266//266 -f 266//266 262//262 261//261 -f 266//266 261//261 267//267 -f 267//267 261//261 268//268 -f 267//267 268//268 269//269 -f 270//270 271//271 272//272 -f 272//272 271//271 262//262 -f 272//272 262//262 273//273 -f 273//273 262//262 265//265 -f 270//270 274//274 271//271 -f 271//271 274//274 275//275 -f 271//271 275//275 276//276 -f 277//277 278//278 250//250 -f 250//250 278//278 255//255 -f 250//250 255//255 254//254 -f 254//254 255//255 260//260 -f 254//254 260//260 279//279 -f 279//279 260//260 280//280 -f 279//279 280//280 281//281 -f 281//281 280//280 282//282 -f 257//257 256//256 283//283 -f 278//278 277//277 284//284 -f 257//257 283//283 285//285 -f 286//286 287//287 288//288 -f 288//288 287//287 248//248 -f 248//248 287//287 289//289 -f 248//248 289//289 249//249 -f 283//283 290//290 285//285 -f 285//285 290//290 291//291 -f 285//285 291//291 288//288 -f 288//288 291//291 292//292 -f 288//288 292//292 286//286 -f 286//286 292//292 293//293 -f 293//293 292//292 284//284 -f 284//284 292//292 294//294 -f 284//284 294//294 278//278 -f 295//295 197//197 296//296 -f 296//296 197//197 195//195 -f 296//296 195//195 297//297 -f 297//297 195//195 194//194 -f 297//297 194//194 298//298 -f 298//298 194//194 215//215 -f 298//298 215//215 299//299 -f 299//299 215//215 214//214 -f 299//299 214//214 300//300 -f 300//300 214//214 213//213 -f 300//300 213//213 301//301 -f 301//301 213//213 208//208 -f 301//301 208//208 302//302 -f 302//302 208//208 200//200 -f 302//302 200//200 303//303 -f 303//303 200//200 201//201 -f 303//303 201//201 304//304 -f 304//304 201//201 189//189 -f 304//304 189//189 305//305 -f 305//305 189//189 188//188 -f 305//305 188//188 306//306 -f 306//306 188//188 198//198 -f 306//306 198//198 295//295 -f 295//295 198//198 197//197 -f 307//307 207//207 308//308 -f 308//308 207//207 209//209 -f 308//308 209//209 309//309 -f 309//309 209//209 212//212 -f 309//309 212//212 310//310 -f 310//310 212//212 211//211 -f 310//310 211//211 311//311 -f 311//311 211//211 210//210 -f 311//311 210//210 312//312 -f 312//312 210//210 206//206 -f 312//312 206//206 313//313 -f 313//313 206//206 205//205 -f 313//313 205//205 314//314 -f 314//314 205//205 203//203 -f 314//314 203//203 315//315 -f 315//315 203//203 202//202 -f 315//315 202//202 316//316 -f 316//316 202//202 192//192 -f 316//316 192//192 317//317 -f 317//317 192//192 191//191 -f 317//317 191//191 318//318 -f 318//318 191//191 199//199 -f 318//318 199//199 307//307 -f 307//307 199//199 207//207 -f 176//176 185//185 266//266 -f 266//266 185//185 265//265 -f 319//319 320//320 321//321 -f 321//321 320//320 322//322 -f 321//321 322//322 323//323 -f 323//323 322//322 324//324 -f 323//323 324//324 325//325 -f 325//325 324//324 326//326 -f 325//325 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 331//331 -f 331//331 330//330 332//332 -f 331//331 332//332 333//333 -f 333//333 332//332 334//334 -f 333//333 334//334 335//335 -f 335//335 334//334 336//336 -f 335//335 336//336 337//337 -f 337//337 336//336 338//338 -f 337//337 338//338 339//339 -f 339//339 338//338 340//340 -f 339//339 340//340 341//341 -f 341//341 340//340 342//342 -f 341//341 342//342 319//319 -f 319//319 342//342 320//320 -f 343//343 38//38 40//40 -f 344//344 62//62 68//68 -f 345//345 346//346 347//347 -f 347//347 346//346 348//348 -f 347//347 348//348 127//127 -f 349//349 350//350 33//33 -f 33//33 350//350 351//351 -f 33//33 351//351 27//27 -f 344//344 68//68 352//352 -f 352//352 68//68 353//353 -f 352//352 353//353 354//354 -f 354//354 353//353 355//355 -f 354//354 355//355 348//348 -f 348//348 355//355 356//356 -f 348//348 356//356 127//127 -f 344//344 345//345 62//62 -f 62//62 345//345 347//347 -f 62//62 347//347 55//55 -f 55//55 347//347 357//357 -f 55//55 357//357 56//56 -f 56//56 357//357 358//358 -f 356//356 349//349 127//127 -f 127//127 349//349 33//33 -f 127//127 33//33 126//126 -f 126//126 33//33 31//31 -f 126//126 31//31 124//124 -f 124//124 31//31 30//30 -f 75//75 73//73 359//359 -f 360//360 361//361 362//362 -f 362//362 361//361 363//363 -f 362//362 363//363 364//364 -f 364//364 363//363 365//365 -f 364//364 365//365 366//366 -f 366//366 365//365 367//367 -f 366//366 367//367 359//359 -f 359//359 367//367 343//343 -f 359//359 343//343 75//75 -f 75//75 343//343 40//40 -f 75//75 40//40 69//69 -f 69//69 40//40 28//28 -f 69//69 28//28 68//68 -f 68//68 28//28 27//27 -f 68//68 27//27 353//353 -f 353//353 27//27 351//351 -f 125//125 368//368 127//127 -f 127//127 368//368 347//347 -f 19//19 17//17 125//125 -f 125//125 17//17 65//65 -f 125//125 65//65 368//368 -f 368//368 65//65 57//57 -f 64//64 65//65 16//16 -f 16//16 65//65 17//17 -f 32//32 34//34 369//369 -f 369//369 370//370 32//32 -f 32//32 370//370 371//371 -f 32//32 371//371 372//372 -f 373//373 374//374 66//66 -f 66//66 374//374 375//375 -f 372//372 376//376 32//32 -f 32//32 376//376 377//377 -f 32//32 377//377 66//66 -f 66//66 377//377 378//378 -f 66//66 378//378 373//373 -f 375//375 379//379 66//66 -f 66//66 379//379 380//380 -f 66//66 380//380 67//67 -f 381//381 382//382 383//383 -f 383//383 382//382 384//384 -f 383//383 384//384 385//385 -f 385//385 384//384 386//386 -f 385//385 386//386 387//387 -f 387//387 386//386 388//388 -f 387//387 388//388 389//389 -f 389//389 388//388 390//390 -f 389//389 390//390 391//391 -f 391//391 390//390 392//392 -f 391//391 392//392 377//377 -f 377//377 392//392 378//378 -f 393//393 394//394 395//395 -f 395//395 394//394 396//396 -f 395//395 396//396 381//381 -f 381//381 396//396 397//397 -f 381//381 397//397 382//382 -f 398//398 399//399 204//204 -f 400//400 173//173 196//196 -f 401//401 402//402 21//21 -f 21//21 402//402 3//3 -f 196//196 403//403 404//404 -f 181//181 405//405 173//173 -f 173//173 405//405 162//162 -f 2//2 406//406 219//219 -f 407//407 408//408 161//161 -f 161//161 408//408 53//53 -f 219//219 217//217 2//2 -f 2//2 217//217 204//204 -f 2//2 204//204 3//3 -f 3//3 204//204 196//196 -f 3//3 196//196 21//21 -f 21//21 196//196 173//173 -f 21//21 173//173 22//22 -f 404//404 409//409 196//196 -f 196//196 409//409 410//410 -f 196//196 410//410 400//400 -f 22//22 173//173 411//411 -f 411//411 173//173 162//162 -f 411//411 162//162 412//412 -f 393//393 413//413 162//162 -f 162//162 413//413 414//414 -f 162//162 414//414 415//415 -f 415//415 416//416 162//162 -f 162//162 416//416 417//417 -f 162//162 417//417 412//412 -f 418//418 398//398 419//419 -f 419//419 398//398 204//204 -f 419//419 204//204 420//420 -f 420//420 204//204 217//217 -f 421//421 422//422 423//423 -f 423//423 422//422 424//424 -f 423//423 424//424 70//70 -f 70//70 424//424 394//394 -f 70//70 394//394 53//53 -f 53//53 394//394 393//393 -f 53//53 393//393 161//161 -f 161//161 393//393 162//162 -f 221//221 230//230 236//236 -f 236//236 230//230 238//238 -f 281//281 282//282 360//360 -f 360//360 282//282 361//361 -f 16//16 18//18 64//64 -f 64//64 18//18 63//63 -f 425//425 426//426 32//32 -f 32//32 426//426 18//18 -f 427//427 66//66 428//428 -f 428//428 66//66 63//63 -f 428//428 63//63 429//429 -f 426//426 430//430 18//18 -f 18//18 430//430 431//431 -f 18//18 431//431 432//432 -f 18//18 433//433 434//434 -f 18//18 434//434 63//63 -f 63//63 434//434 435//435 -f 63//63 435//435 429//429 -f 436//436 437//437 438//438 -f 438//438 437//437 439//439 -f 438//438 439//439 440//440 -f 436//436 441//441 66//66 -f 66//66 441//441 442//442 -f 66//66 442//442 32//32 -f 32//32 442//442 443//443 -f 32//32 443//443 425//425 -f 433//433 18//18 444//444 -f 444//444 18//18 432//432 -f 444//444 432//432 439//439 -f 439//439 432//432 445//445 -f 439//439 445//445 440//440 -f 427//427 446//446 66//66 -f 66//66 446//446 447//447 -f 66//66 447//447 436//436 -f 436//436 447//447 448//448 -f 436//436 448//448 437//437 -f 449//449 439//439 450//450 -f 450//450 439//439 437//437 -f 450//450 437//437 451//451 -f 451//451 437//437 448//448 -f 451//451 448//448 452//452 -f 452//452 448//448 447//447 -f 452//452 447//447 453//453 -f 453//453 447//447 446//446 -f 453//453 446//446 454//454 -f 454//454 446//446 427//427 -f 454//454 427//427 455//455 -f 455//455 427//427 428//428 -f 455//455 428//428 456//456 -f 456//456 428//428 429//429 -f 456//456 429//429 457//457 -f 457//457 429//429 435//435 -f 457//457 435//435 458//458 -f 458//458 435//435 434//434 -f 458//458 434//434 459//459 -f 459//459 434//434 433//433 -f 459//459 433//433 460//460 -f 460//460 433//433 444//444 -f 460//460 444//444 449//449 -f 449//449 444//444 439//439 -f 461//461 426//426 462//462 -f 462//462 426//426 425//425 -f 462//462 425//425 463//463 -f 463//463 425//425 443//443 -f 463//463 443//443 464//464 -f 464//464 443//443 442//442 -f 464//464 442//442 465//465 -f 465//465 442//442 441//441 -f 465//465 441//441 466//466 -f 466//466 441//441 436//436 -f 466//466 436//436 467//467 -f 467//467 436//436 438//438 -f 467//467 438//438 468//468 -f 468//468 438//438 440//440 -f 468//468 440//440 469//469 -f 469//469 440//440 445//445 -f 469//469 445//445 470//470 -f 470//470 445//445 432//432 -f 470//470 432//432 471//471 -f 471//471 432//432 431//431 -f 471//471 431//431 472//472 -f 472//472 431//431 430//430 -f 472//472 430//430 461//461 -f 461//461 430//430 426//426 -f 473//473 350//350 474//474 -f 474//474 350//350 349//349 -f 474//474 349//349 475//475 -f 475//475 349//349 356//356 -f 475//475 356//356 476//476 -f 476//476 356//356 355//355 -f 476//476 355//355 477//477 -f 477//477 355//355 353//353 -f 477//477 353//353 478//478 -f 478//478 353//353 351//351 -f 478//478 351//351 473//473 -f 473//473 351//351 350//350 -f 465//465 466//466 477//477 -f 477//477 466//466 476//476 -f 466//466 467//467 476//476 -f 476//476 467//467 468//468 -f 476//476 468//468 475//475 -f 473//473 474//474 472//472 -f 468//468 469//469 475//475 -f 475//475 469//469 470//470 -f 475//475 470//470 474//474 -f 474//474 470//470 471//471 -f 474//474 471//471 472//472 -f 472//472 461//461 473//473 -f 473//473 461//461 462//462 -f 473//473 462//462 478//478 -f 478//478 462//462 463//463 -f 478//478 463//463 477//477 -f 477//477 463//463 464//464 -f 477//477 464//464 465//465 -f 479//479 354//354 480//480 -f 480//480 354//354 348//348 -f 480//480 348//348 481//481 -f 481//481 348//348 346//346 -f 481//481 346//346 482//482 -f 482//482 346//346 345//345 -f 482//482 345//345 483//483 -f 483//483 345//345 344//344 -f 483//483 344//344 484//484 -f 484//484 344//344 352//352 -f 484//484 352//352 479//479 -f 479//479 352//352 354//354 -f 451//451 452//452 484//484 -f 457//457 458//458 481//481 -f 484//484 452//452 483//483 -f 481//481 458//458 480//480 -f 452//452 453//453 483//483 -f 483//483 453//453 454//454 -f 483//483 454//454 482//482 -f 482//482 454//454 455//455 -f 482//482 455//455 481//481 -f 481//481 455//455 456//456 -f 481//481 456//456 457//457 -f 458//458 459//459 480//480 -f 480//480 459//459 460//460 -f 480//480 460//460 479//479 -f 479//479 460//460 449//449 -f 479//479 449//449 484//484 -f 484//484 449//449 450//450 -f 484//484 450//450 451//451 -f 342//342 163//163 320//320 -f 320//320 163//163 162//162 -f 320//320 162//162 322//322 -f 330//330 328//328 405//405 -f 405//405 328//328 326//326 -f 405//405 326//326 162//162 -f 162//162 326//326 324//324 -f 162//162 324//324 322//322 -f 330//330 405//405 332//332 -f 332//332 405//405 485//485 -f 332//332 485//485 334//334 -f 342//342 340//340 163//163 -f 163//163 340//340 338//338 -f 163//163 338//338 485//485 -f 485//485 338//338 336//336 -f 485//485 336//336 334//334 -f 186//186 165//165 486//486 -f 486//486 165//165 163//163 -f 486//486 163//163 487//487 -f 487//487 163//163 485//485 -f 181//181 180//180 488//488 -f 487//487 485//485 488//488 -f 488//488 485//485 405//405 -f 488//488 405//405 181//181 -f 489//489 490//490 491//491 -f 491//491 490//490 406//406 -f 491//491 406//406 492//492 -f 493//493 494//494 2//2 -f 2//2 494//494 495//495 -f 2//2 495//495 406//406 -f 406//406 495//495 496//496 -f 406//406 496//496 492//492 -f 493//493 2//2 497//497 -f 497//497 2//2 1//1 -f 497//497 1//1 498//498 -f 489//489 499//499 490//490 -f 490//490 499//499 500//500 -f 490//490 500//500 1//1 -f 1//1 500//500 501//501 -f 1//1 501//501 498//498 -f 220//220 219//219 502//502 -f 502//502 219//219 406//406 -f 502//502 406//406 503//503 -f 503//503 406//406 490//490 -f 6//6 225//225 504//504 -f 503//503 490//490 504//504 -f 504//504 490//490 1//1 -f 504//504 1//1 6//6 -f 505//505 491//491 506//506 -f 506//506 491//491 492//492 -f 506//506 492//492 507//507 -f 507//507 492//492 496//496 -f 507//507 496//496 508//508 -f 508//508 496//496 495//495 -f 508//508 495//495 509//509 -f 509//509 495//495 494//494 -f 509//509 494//494 510//510 -f 510//510 494//494 493//493 -f 510//510 493//493 511//511 -f 511//511 493//493 497//497 -f 511//511 497//497 512//512 -f 512//512 497//497 498//498 -f 512//512 498//498 513//513 -f 513//513 498//498 501//501 -f 513//513 501//501 514//514 -f 514//514 501//501 500//500 -f 514//514 500//500 515//515 -f 515//515 500//500 499//499 -f 515//515 499//499 516//516 -f 516//516 499//499 489//489 -f 516//516 489//489 505//505 -f 505//505 489//489 491//491 -f 218//218 220//220 517//517 -f 517//517 220//220 502//502 -f 518//518 504//504 226//226 -f 226//226 504//504 225//225 -f 513//513 514//514 504//504 -f 504//504 514//514 503//503 -f 514//514 515//515 503//503 -f 503//503 515//515 516//516 -f 503//503 516//516 502//502 -f 502//502 516//516 505//505 -f 505//505 506//506 502//502 -f 502//502 506//506 507//507 -f 502//502 507//507 517//517 -f 517//517 507//507 508//508 -f 517//517 508//508 519//519 -f 519//519 508//508 509//509 -f 519//519 509//509 520//520 -f 520//520 509//509 510//510 -f 520//520 510//510 518//518 -f 518//518 510//510 511//511 -f 518//518 511//511 504//504 -f 504//504 511//511 512//512 -f 504//504 512//512 513//513 -f 518//518 226//226 520//520 -f 520//520 226//226 227//227 -f 520//520 227//227 519//519 -f 519//519 227//227 216//216 -f 519//519 216//216 517//517 -f 517//517 216//216 218//218 -f 178//178 186//186 521//521 -f 521//521 186//186 486//486 -f 522//522 488//488 182//182 -f 182//182 488//488 180//180 -f 329//329 331//331 488//488 -f 488//488 331//331 487//487 -f 337//337 486//486 335//335 -f 335//335 486//486 487//487 -f 335//335 487//487 333//333 -f 333//333 487//487 331//331 -f 337//337 339//339 486//486 -f 486//486 339//339 341//341 -f 486//486 341//341 521//521 -f 521//521 341//341 319//319 -f 521//521 319//319 523//523 -f 523//523 319//319 321//321 -f 523//523 321//321 524//524 -f 524//524 321//321 323//323 -f 524//524 323//323 522//522 -f 522//522 323//323 325//325 -f 522//522 325//325 488//488 -f 488//488 325//325 327//327 -f 488//488 327//327 329//329 -f 522//522 182//182 524//524 -f 524//524 182//182 183//183 -f 524//524 183//183 523//523 -f 523//523 183//183 179//179 -f 523//523 179//179 521//521 -f 521//521 179//179 178//178 -f 173//173 400//400 174//174 -f 174//174 400//400 525//525 -f 174//174 525//525 276//276 -f 276//276 525//525 288//288 -f 262//262 271//271 252//252 -f 252//252 271//271 276//276 -f 252//252 276//276 248//248 -f 248//248 276//276 288//288 -f 420//420 217//217 526//526 -f 526//526 217//217 224//224 -f 526//526 224//224 285//285 -f 285//285 224//224 242//242 -f 285//285 242//242 257//257 -f 231//231 233//233 242//242 -f 242//242 233//233 247//247 -f 242//242 247//247 257//257 -f 527//527 528//528 190//190 -f 288//288 190//190 285//285 -f 285//285 190//190 193//193 -f 285//285 193//193 526//526 -f 193//193 529//529 530//530 -f 531//531 527//527 532//532 -f 532//532 527//527 190//190 -f 532//532 190//190 525//525 -f 525//525 190//190 288//288 -f 530//530 533//533 193//193 -f 193//193 533//533 534//534 -f 193//193 534//534 526//526 -f 535//535 536//536 291//291 -f 291//291 536//536 292//292 -f 537//537 535//535 290//290 -f 290//290 535//535 291//291 -f 538//538 537//537 283//283 -f 283//283 537//537 290//290 -f 538//538 283//283 539//539 -f 539//539 283//283 256//256 -f 539//539 256//256 255//255 -f 294//294 540//540 278//278 -f 278//278 540//540 539//539 -f 278//278 539//539 255//255 -f 536//536 540//540 292//292 -f 292//292 540//540 294//294 -f 311//311 538//538 539//539 -f 317//317 536//536 535//535 -f 311//311 312//312 538//538 -f 538//538 312//312 313//313 -f 538//538 313//313 537//537 -f 313//313 314//314 537//537 -f 537//537 314//314 315//315 -f 537//537 315//315 535//535 -f 535//535 315//315 316//316 -f 535//535 316//316 317//317 -f 317//317 318//318 536//536 -f 536//536 318//318 307//307 -f 536//536 307//307 540//540 -f 307//307 308//308 540//540 -f 540//540 308//308 309//309 -f 540//540 309//309 539//539 -f 539//539 309//309 310//310 -f 539//539 310//310 311//311 -f 541//541 542//542 286//286 -f 286//286 542//542 287//287 -f 543//543 541//541 293//293 -f 293//293 541//541 286//286 -f 544//544 543//543 284//284 -f 284//284 543//543 293//293 -f 544//544 284//284 545//545 -f 545//545 284//284 277//277 -f 545//545 277//277 250//250 -f 289//289 546//546 249//249 -f 249//249 546//546 545//545 -f 249//249 545//545 250//250 -f 542//542 546//546 287//287 -f 287//287 546//546 289//289 -f 544//544 545//545 299//299 -f 295//295 546//546 542//542 -f 299//299 300//300 544//544 -f 544//544 300//300 301//301 -f 544//544 301//301 543//543 -f 301//301 302//302 543//543 -f 543//543 302//302 303//303 -f 543//543 303//303 541//541 -f 303//303 304//304 541//541 -f 541//541 304//304 305//305 -f 541//541 305//305 542//542 -f 542//542 305//305 306//306 -f 542//542 306//306 295//295 -f 295//295 296//296 546//546 -f 546//546 296//296 297//297 -f 546//546 297//297 545//545 -f 545//545 297//297 298//298 -f 545//545 298//298 299//299 -f 399//399 529//529 204//204 -f 204//204 529//529 193//193 -f 530//530 529//529 398//398 -f 398//398 529//529 399//399 -f 528//528 403//403 190//190 -f 190//190 403//403 196//196 -f 404//404 403//403 527//527 -f 527//527 403//403 528//528 -f 347//347 368//368 357//357 -f 357//357 368//368 358//358 -f 368//368 57//57 358//358 -f 358//358 57//57 56//56 -f 109//109 158//158 164//164 -f 109//109 164//164 110//110 -f 110//110 164//164 172//172 -f 110//110 172//172 111//111 -f 111//111 172//172 171//171 -f 111//111 171//171 117//117 -f 117//117 171//171 170//170 -f 117//117 170//170 118//118 -f 118//118 170//170 169//169 -f 118//118 169//169 112//112 -f 112//112 169//169 168//168 -f 112//112 168//168 113//113 -f 113//113 168//168 167//167 -f 113//113 167//167 114//114 -f 114//114 167//167 166//166 -f 114//114 166//166 88//88 -f 108//108 87//87 159//159 -f 159//159 87//87 160//160 -f 87//87 86//86 160//160 -f 160//160 86//86 547//547 -f 160//160 547//547 548//548 -f 549//549 550//550 58//58 -f 58//58 550//550 104//104 -f 58//58 104//104 59//59 -f 104//104 105//105 59//59 -f 59//59 105//105 106//106 -f 59//59 106//106 80//80 -f 80//80 106//106 107//107 -f 80//80 107//107 78//78 -f 78//78 107//107 93//93 -f 78//78 93//93 52//52 -f 551//551 552//552 73//73 -f 73//73 552//552 553//553 -f 73//73 553//553 359//359 -f 52//52 93//93 73//73 -f 73//73 93//93 92//92 -f 73//73 92//92 551//551 -f 104//104 550//550 554//554 -f 104//104 554//554 102//102 -f 102//102 554//554 555//555 -f 102//102 555//555 103//103 -f 103//103 555//555 547//547 -f 103//103 547//547 86//86 -f 556//556 557//557 558//558 -f 547//547 558//558 548//548 -f 548//548 558//558 559//559 -f 548//548 559//559 407//407 -f 407//407 559//559 560//560 -f 407//407 560//560 408//408 -f 408//408 560//560 561//561 -f 408//408 561//561 562//562 -f 562//562 561//561 558//558 -f 562//562 558//558 563//563 -f 563//563 558//558 557//557 -f 555//555 554//554 547//547 -f 547//547 554//554 550//550 -f 550//550 549//549 547//547 -f 547//547 549//549 564//564 -f 547//547 564//564 565//565 -f 556//556 558//558 566//566 -f 566//566 558//558 547//547 -f 566//566 547//547 567//567 -f 567//567 547//547 565//565 -f 567//567 565//565 568//568 -f 549//549 58//58 60//60 -f 549//549 60//60 564//564 -f 564//564 60//60 61//61 -f 564//564 61//61 565//565 -f 565//565 61//61 82//82 -f 565//565 82//82 568//568 -f 568//568 82//82 81//81 -f 568//568 81//81 567//567 -f 566//566 567//567 79//79 -f 79//79 567//567 81//81 -f 566//566 79//79 556//556 -f 556//556 79//79 84//84 -f 556//556 84//84 557//557 -f 557//557 84//84 83//83 -f 557//557 83//83 563//563 -f 563//563 83//83 85//85 -f 563//563 85//85 562//562 -f 562//562 85//85 54//54 -f 408//408 562//562 53//53 -f 53//53 562//562 54//54 -f 548//548 407//407 160//160 -f 160//160 407//407 161//161 -f 559//559 558//558 569//569 -f 569//569 558//558 570//570 -f 558//558 561//561 570//570 -f 570//570 561//561 571//571 -f 561//561 560//560 571//571 -f 571//571 560//560 572//572 -f 560//560 559//559 572//572 -f 572//572 559//559 569//569 -f 571//571 572//572 570//570 -f 570//570 572//572 569//569 -f 136//136 5//5 13//13 -f 136//136 13//13 139//139 -f 139//139 13//13 12//12 -f 139//139 12//12 151//151 -f 151//151 12//12 11//11 -f 151//151 11//11 152//152 -f 152//152 11//11 15//15 -f 152//152 15//15 153//153 -f 153//153 15//15 14//14 -f 153//153 14//14 156//156 -f 156//156 14//14 10//10 -f 156//156 10//10 157//157 -f 157//157 10//10 9//9 -f 157//157 9//9 131//131 -f 131//131 9//9 8//8 -f 131//131 8//8 128//128 -f 130//130 129//129 4//4 -f 4//4 129//129 7//7 -f 119//119 121//121 140//140 -f 573//573 574//574 4//4 -f 4//4 574//574 119//119 -f 4//4 119//119 130//130 -f 130//130 119//119 140//140 -f 141//141 45//45 137//137 -f 137//137 45//45 47//47 -f 137//137 47//47 138//138 -f 138//138 47//47 20//20 -f 138//138 20//20 133//133 -f 575//575 576//576 123//123 -f 123//123 576//576 25//25 -f 121//121 123//123 140//140 -f 140//140 123//123 25//25 -f 140//140 25//25 141//141 -f 141//141 25//25 24//24 -f 141//141 24//24 45//45 -f 577//577 38//38 578//578 -f 578//578 38//38 343//343 -f 133//133 20//20 135//135 -f 135//135 20//20 38//38 -f 135//135 38//38 579//579 -f 579//579 38//38 577//577 -f 402//402 573//573 3//3 -f 3//3 573//573 4//4 -f 580//580 401//401 23//23 -f 23//23 401//401 21//21 -f 580//580 23//23 581//581 -f 581//581 23//23 51//51 -f 581//581 51//51 582//582 -f 582//582 51//51 50//50 -f 582//582 50//50 583//583 -f 583//583 50//50 49//49 -f 583//583 49//49 584//584 -f 584//584 49//49 48//48 -f 585//585 584//584 46//46 -f 46//46 584//584 48//48 -f 585//585 46//46 44//44 -f 585//585 44//44 586//586 -f 586//586 44//44 43//43 -f 586//586 43//43 587//587 -f 587//587 43//43 26//26 -f 587//587 26//26 588//588 -f 588//588 26//26 25//25 -f 588//588 25//25 576//576 -f 575//575 123//123 122//122 -f 575//575 122//122 589//589 -f 589//589 122//122 120//120 -f 589//589 120//120 590//590 -f 590//590 120//120 119//119 -f 590//590 119//119 574//574 -f 591//591 574//574 592//592 -f 592//592 574//574 573//573 -f 592//592 573//573 593//593 -f 593//593 573//573 402//402 -f 593//593 402//402 594//594 -f 594//594 402//402 401//401 -f 594//594 401//401 591//591 -f 591//591 401//401 580//580 -f 591//591 580//580 581//581 -f 581//581 582//582 591//591 -f 591//591 582//582 583//583 -f 591//591 583//583 574//574 -f 574//574 583//583 584//584 -f 574//574 584//584 585//585 -f 589//589 590//590 575//575 -f 575//575 590//590 574//574 -f 575//575 574//574 576//576 -f 576//576 574//574 588//588 -f 585//585 586//586 574//574 -f 574//574 586//586 587//587 -f 574//574 587//587 588//588 -f 591//591 592//592 595//595 -f 595//595 592//592 596//596 -f 592//592 593//593 596//596 -f 596//596 593//593 597//597 -f 593//593 594//594 597//597 -f 597//597 594//594 598//598 -f 594//594 591//591 598//598 -f 598//598 591//591 595//595 -f 597//597 598//598 596//596 -f 596//596 598//598 595//595 -f 599//599 600//600 601//601 -f 602//602 603//603 604//604 -f 603//603 605//605 604//604 -f 604//604 605//605 606//606 -f 604//604 606//606 360//360 -f 607//607 608//608 609//609 -f 115//115 599//599 95//95 -f 95//95 599//599 601//601 -f 95//95 601//601 94//94 -f 94//94 601//601 610//610 -f 94//94 610//610 92//92 -f 92//92 610//610 551//551 -f 600//600 607//607 601//601 -f 601//601 607//607 609//609 -f 601//601 609//609 610//610 -f 610//610 609//609 611//611 -f 610//610 611//611 551//551 -f 551//551 611//611 552//552 -f 608//608 602//602 609//609 -f 609//609 602//602 604//604 -f 609//609 604//604 611//611 -f 611//611 604//604 612//612 -f 611//611 612//612 552//552 -f 552//552 612//612 553//553 -f 360//360 362//362 604//604 -f 604//604 362//362 364//364 -f 604//604 364//364 612//612 -f 612//612 364//364 366//366 -f 612//612 366//366 553//553 -f 553//553 366//366 359//359 -f 115//115 90//90 599//599 -f 599//599 90//90 613//613 -f 614//614 608//608 615//615 -f 615//615 608//608 607//607 -f 615//615 607//607 613//613 -f 613//613 607//607 600//600 -f 613//613 600//600 599//599 -f 616//616 603//603 614//614 -f 614//614 603//603 602//602 -f 614//614 602//602 608//608 -f 281//281 360//360 617//617 -f 617//617 360//360 606//606 -f 617//617 606//606 616//616 -f 616//616 606//606 605//605 -f 616//616 605//605 603//603 -f 261//261 263//263 618//618 -f 254//254 279//279 619//619 -f 99//99 116//116 620//620 -f 100//100 99//99 621//621 -f 101//101 100//100 622//622 -f 89//89 101//101 623//623 -f 269//269 268//268 624//624 -f 269//269 624//624 625//625 -f 625//625 624//624 626//626 -f 625//625 626//626 627//627 -f 627//627 628//628 629//629 -f 629//629 628//628 630//630 -f 630//630 628//628 631//631 -f 631//631 628//628 632//632 -f 631//631 632//632 633//633 -f 97//97 96//96 634//634 -f 632//632 91//91 633//633 -f 633//633 91//91 97//97 -f 633//633 97//97 635//635 -f 635//635 97//97 634//634 -f 89//89 636//636 90//90 -f 90//90 636//636 613//613 -f 613//613 636//636 615//615 -f 615//615 636//636 637//637 -f 615//615 637//637 614//614 -f 627//627 626//626 628//628 -f 628//628 626//626 620//620 -f 628//628 620//620 632//632 -f 632//632 620//620 116//116 -f 632//632 116//116 91//91 -f 614//614 637//637 616//616 -f 616//616 637//637 619//619 -f 616//616 619//619 617//617 -f 617//617 619//619 279//279 -f 617//617 279//279 281//281 -f 89//89 623//623 636//636 -f 636//636 623//623 638//638 -f 636//636 638//638 637//637 -f 637//637 638//638 639//639 -f 637//637 639//639 619//619 -f 619//619 639//639 253//253 -f 619//619 253//253 254//254 -f 640//640 264//264 251//251 -f 101//101 622//622 623//623 -f 623//623 622//622 641//641 -f 623//623 641//641 638//638 -f 638//638 641//641 640//640 -f 638//638 640//640 639//639 -f 639//639 640//640 251//251 -f 639//639 251//251 253//253 -f 100//100 621//621 622//622 -f 622//622 621//621 642//642 -f 622//622 642//642 641//641 -f 641//641 642//642 618//618 -f 641//641 618//618 640//640 -f 640//640 618//618 263//263 -f 640//640 263//263 264//264 -f 99//99 620//620 621//621 -f 621//621 620//620 626//626 -f 621//621 626//626 642//642 -f 642//642 626//626 624//624 -f 642//642 624//624 618//618 -f 618//618 624//624 268//268 -f 618//618 268//268 261//261 -f 134//134 135//135 579//579 -f 132//132 134//134 643//643 -f 146//146 132//132 644//644 -f 644//644 132//132 645//645 -f 644//644 645//645 646//646 -f 646//646 645//645 647//647 -f 647//647 645//645 648//648 -f 647//647 648//648 649//649 -f 649//649 648//648 650//650 -f 650//650 648//648 651//651 -f 650//650 651//651 652//652 -f 652//652 651//651 653//653 -f 653//653 651//651 363//363 -f 653//653 363//363 361//361 -f 654//654 367//367 365//365 -f 132//132 643//643 645//645 -f 645//645 643//643 655//655 -f 645//645 655//655 648//648 -f 648//648 655//655 654//654 -f 648//648 654//654 651//651 -f 651//651 654//654 365//365 -f 651//651 365//365 363//363 -f 134//134 579//579 643//643 -f 643//643 579//579 577//577 -f 643//643 577//577 655//655 -f 655//655 577//577 578//578 -f 655//655 578//578 654//654 -f 654//654 578//578 343//343 -f 654//654 343//343 367//367 -f 361//361 282//282 653//653 -f 653//653 282//282 656//656 -f 653//653 656//656 652//652 -f 652//652 656//656 657//657 -f 652//652 657//657 650//650 -f 650//650 657//657 658//658 -f 650//650 658//658 649//649 -f 649//649 658//658 647//647 -f 647//647 658//658 659//659 -f 647//647 659//659 646//646 -f 646//646 659//659 660//660 -f 646//646 660//660 644//644 -f 644//644 660//660 147//147 -f 644//644 147//147 146//146 -f 154//154 147//147 660//660 -f 148//148 154//154 661//661 -f 149//149 148//148 662//662 -f 150//150 149//149 663//663 -f 155//155 150//150 664//664 -f 665//665 666//666 144//144 -f 144//144 666//666 667//667 -f 144//144 667//667 143//143 -f 145//145 668//668 144//144 -f 144//144 668//668 669//669 -f 144//144 669//669 665//665 -f 670//670 671//671 672//672 -f 672//672 671//671 673//673 -f 672//672 673//673 668//668 -f 668//668 673//673 674//674 -f 668//668 674//674 669//669 -f 675//675 676//676 670//670 -f 670//670 676//676 240//240 -f 670//670 240//240 241//241 -f 670//670 672//672 675//675 -f 675//675 672//672 668//668 -f 675//675 668//668 677//677 -f 677//677 668//668 145//145 -f 677//677 145//145 155//155 -f 154//154 660//660 661//661 -f 661//661 660//660 659//659 -f 661//661 659//659 678//678 -f 148//148 661//661 662//662 -f 662//662 661//661 678//678 -f 662//662 678//678 679//679 -f 679//679 678//678 680//680 -f 679//679 680//680 681//681 -f 659//659 658//658 678//678 -f 678//678 658//658 657//657 -f 678//678 657//657 680//680 -f 680//680 657//657 656//656 -f 680//680 656//656 282//282 -f 682//682 245//245 237//237 -f 155//155 664//664 677//677 -f 677//677 664//664 683//683 -f 677//677 683//683 675//675 -f 675//675 683//683 682//682 -f 675//675 682//682 676//676 -f 676//676 682//682 237//237 -f 676//676 237//237 240//240 -f 150//150 663//663 664//664 -f 664//664 663//663 684//684 -f 664//664 684//684 683//683 -f 683//683 684//684 685//685 -f 683//683 685//685 682//682 -f 682//682 685//685 246//246 -f 682//682 246//246 245//245 -f 149//149 662//662 663//663 -f 663//663 662//662 679//679 -f 663//663 679//679 684//684 -f 684//684 679//679 681//681 -f 684//684 681//681 685//685 -f 685//685 681//681 258//258 -f 685//685 258//258 246//246 -f 282//282 280//280 680//680 -f 680//680 280//280 260//260 -f 680//680 260//260 681//681 -f 681//681 260//260 259//259 -f 681//681 259//259 258//258 -f 223//223 244//244 224//224 -f 224//224 244//244 243//243 -f 224//224 243//243 242//242 -f 222//222 221//221 236//236 -f 236//236 235//235 222//222 -f 222//222 235//235 234//234 -f 222//222 234//234 223//223 -f 223//223 234//234 232//232 -f 223//223 232//232 244//244 -f 238//238 230//230 239//239 -f 239//239 230//230 229//229 -f 239//239 229//229 241//241 -f 241//241 229//229 670//670 -f 670//670 229//229 228//228 -f 670//670 228//228 671//671 -f 143//143 667//667 142//142 -f 142//142 667//667 666//666 -f 142//142 666//666 665//665 -f 665//665 669//669 142//142 -f 142//142 669//669 674//674 -f 142//142 674//674 228//228 -f 228//228 674//674 673//673 -f 228//228 673//673 671//671 -f 177//177 176//176 266//266 -f 633//633 635//635 98//98 -f 98//98 635//635 634//634 -f 98//98 634//634 96//96 -f 266//266 267//267 177//177 -f 177//177 267//267 269//269 -f 177//177 269//269 187//187 -f 187//187 269//269 625//625 -f 187//187 625//625 627//627 -f 627//627 629//629 187//187 -f 187//187 629//629 630//630 -f 187//187 630//630 98//98 -f 98//98 630//630 631//631 -f 98//98 631//631 633//633 -f 265//265 185//185 273//273 -f 273//273 185//185 184//184 -f 273//273 184//184 272//272 -f 272//272 184//184 270//270 -f 270//270 184//184 175//175 -f 270//270 175//175 274//274 -f 274//274 175//175 275//275 -f 275//275 175//175 174//174 -f 275//275 174//174 276//276 -f 530//530 398//398 418//418 -f 530//530 418//418 533//533 -f 533//533 418//418 419//419 -f 533//533 419//419 534//534 -f 534//534 419//419 420//420 -f 534//534 420//420 526//526 -f 525//525 400//400 410//410 -f 525//525 410//410 532//532 -f 532//532 410//410 409//409 -f 532//532 409//409 531//531 -f 531//531 409//409 404//404 -f 531//531 404//404 527//527 -f 369//369 34//34 35//35 -f 686//686 414//414 413//413 -f 417//417 416//416 687//687 -f 687//687 416//416 415//415 -f 412//412 36//36 411//411 -f 411//411 36//36 22//22 -f 371//371 370//370 688//688 -f 688//688 370//370 369//369 -f 376//376 372//372 689//689 -f 689//689 372//372 371//371 -f 391//391 377//377 376//376 -f 376//376 689//689 391//391 -f 391//391 689//689 690//690 -f 391//391 690//690 389//389 -f 389//389 690//690 691//691 -f 389//389 691//691 387//387 -f 387//387 691//691 692//692 -f 387//387 692//692 385//385 -f 385//385 692//692 693//693 -f 385//385 693//693 383//383 -f 383//383 693//693 694//694 -f 383//383 694//694 381//381 -f 381//381 694//694 686//686 -f 381//381 686//686 395//395 -f 395//395 686//686 413//413 -f 395//395 413//413 393//393 -f 371//371 688//688 689//689 -f 689//689 688//688 695//695 -f 689//689 695//695 690//690 -f 690//690 695//695 696//696 -f 690//690 696//696 691//691 -f 691//691 696//696 697//697 -f 691//691 697//697 692//692 -f 692//692 697//697 698//698 -f 692//692 698//698 693//693 -f 693//693 698//698 699//699 -f 693//693 699//699 694//694 -f 694//694 699//699 687//687 -f 694//694 687//687 686//686 -f 686//686 687//687 415//415 -f 686//686 415//415 414//414 -f 369//369 35//35 688//688 -f 688//688 35//35 29//29 -f 688//688 29//29 695//695 -f 695//695 29//29 42//42 -f 695//695 42//42 696//696 -f 696//696 42//42 41//41 -f 696//696 41//41 697//697 -f 697//697 41//41 39//39 -f 697//697 39//39 698//698 -f 698//698 39//39 37//37 -f 698//698 37//37 699//699 -f 699//699 37//37 36//36 -f 699//699 36//36 687//687 -f 687//687 36//36 412//412 -f 687//687 412//412 417//417 -f 390//390 388//388 700//700 -f 397//397 396//396 701//701 -f 378//378 392//392 702//702 -f 70//70 71//71 703//703 -f 70//70 703//703 423//423 -f 423//423 703//703 704//704 -f 423//423 704//704 421//421 -f 421//421 704//704 701//701 -f 421//421 701//701 422//422 -f 396//396 394//394 701//701 -f 701//701 394//394 424//424 -f 701//701 424//424 422//422 -f 378//378 702//702 373//373 -f 373//373 702//702 705//705 -f 373//373 705//705 374//374 -f 374//374 705//705 375//375 -f 375//375 705//705 706//706 -f 375//375 706//706 379//379 -f 379//379 706//706 380//380 -f 380//380 706//706 77//77 -f 380//380 77//77 67//67 -f 74//74 76//76 707//707 -f 707//707 76//76 708//708 -f 707//707 708//708 709//709 -f 709//709 708//708 710//710 -f 709//709 710//710 711//711 -f 711//711 710//710 700//700 -f 382//382 397//397 712//712 -f 712//712 397//397 701//701 -f 712//712 701//701 713//713 -f 713//713 701//701 704//704 -f 713//713 704//704 714//714 -f 714//714 704//704 703//703 -f 714//714 703//703 72//72 -f 72//72 703//703 71//71 -f 72//72 74//74 714//714 -f 714//714 74//74 707//707 -f 714//714 707//707 713//713 -f 713//713 707//707 709//709 -f 713//713 709//709 712//712 -f 712//712 709//709 711//711 -f 712//712 711//711 382//382 -f 382//382 711//711 384//384 -f 700//700 388//388 711//711 -f 711//711 388//388 386//386 -f 711//711 386//386 384//384 -f 392//392 390//390 702//702 -f 702//702 390//390 700//700 -f 702//702 700//700 705//705 -f 705//705 700//700 710//710 -f 705//705 710//710 706//706 -f 706//706 710//710 708//708 -f 706//706 708//708 77//77 -f 77//77 708//708 76//76 -# 1448 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/meshes/statuette.obj b/mep3_simulation/webots_data/worlds/assets/meshes/statuette.obj deleted file mode 100644 index 5aca5820e..000000000 --- a/mep3_simulation/webots_data/worlds/assets/meshes/statuette.obj +++ /dev/null @@ -1,28748 +0,0 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object statuette.obj -# -# Vertices: 7174 -# Faces: 14384 -# -#### -vn 0.715134 0.698955 0.006824 -v -0.014142 -0.014142 0.022774 -vn 0.678012 0.734364 0.031761 -v -0.013926 -0.014355 0.022872 -vn 0.668498 0.743391 -0.021919 -v -0.013788 -0.014488 0.020682 -vn 0.662656 0.518902 -0.540025 -v -0.011036 -0.016679 0.016679 -vn 0.684682 0.520915 -0.509763 -v -0.011094 -0.016641 0.016641 -vn 0.556317 0.830754 -0.018975 -v -0.011648 -0.016258 0.017472 -vn -0.770679 0.450736 -0.450434 -v 0.013057 -0.015150 0.015150 -vn -0.650830 0.757914 0.044577 -v 0.013057 -0.015150 0.023238 -vn -0.794486 0.429390 -0.429436 -v 0.013349 -0.014893 0.014893 -vn -0.707191 0.706989 0.006846 -v 0.014142 -0.014142 0.022774 -vn -0.587795 0.578855 -0.565176 -v 0.014142 -0.014142 0.014142 -vn -0.423224 0.810159 -0.405616 -v 0.014364 -0.013917 0.014364 -vn -0.737120 0.477664 -0.478007 -v 0.012070 -0.015947 0.015947 -vn -0.698597 0.503771 -0.508111 -v 0.011039 -0.016677 0.016677 -vn -0.616114 0.786616 0.040490 -v 0.012957 -0.015235 0.023277 -vn -0.559909 0.827563 0.040508 -v 0.010955 -0.016733 0.023966 -vn -0.662523 0.529917 -0.529387 -v 0.010677 -0.016911 0.016911 -vn -0.504892 0.862845 0.024131 -v 0.010679 -0.016910 0.024048 -vn -0.617730 0.556134 -0.555990 -v 0.009602 -0.017544 0.017544 -vn -0.570731 0.579568 -0.581693 -v 0.008494 -0.018107 0.018107 -vn -0.445326 0.894463 0.040246 -v 0.008785 -0.017967 0.024534 -vn -0.511671 0.607345 -0.607720 -v 0.008064 -0.018302 0.018302 -vn -0.386624 0.922180 0.010277 -v 0.008066 -0.018301 0.024687 -vn -0.427916 0.638967 -0.639226 -v 0.005762 -0.019152 0.019152 -vn -0.322952 0.945566 0.040076 -v 0.006481 -0.018921 0.024973 -vn -0.340326 0.664552 -0.665243 -v 0.005274 -0.019292 0.019292 -vn 0.180401 0.694852 -0.696158 -v -0.002912 -0.019787 0.019787 -vn 0.069464 0.996890 0.037223 -v -0.000880 -0.019981 0.025460 -vn 0.071937 0.704827 -0.705722 -v -0.000588 -0.019991 0.019991 -vn 0.000218 0.999755 0.022120 -v -0.000588 -0.019991 0.025465 -vn -0.029650 0.706456 -0.707135 -v 0.000000 -0.020000 0.020000 -vn -0.060221 0.997547 0.035681 -v 0.001611 -0.019935 0.025439 -vn -0.140304 0.700280 -0.699945 -v 0.002369 -0.019859 0.019859 -vn -0.140610 0.990037 -0.007502 -v 0.002370 -0.019859 0.025404 -vn -0.237996 0.687115 -0.686463 -v 0.002912 -0.019787 0.019787 -vn -0.190250 0.981140 0.034202 -v 0.004077 -0.019580 0.025276 -vn -0.263519 0.964649 0.003115 -v 0.005276 -0.019291 0.025143 -vn 0.617812 0.554084 -0.557943 -v -0.009127 -0.017796 0.017796 -vn 0.609524 0.792499 -0.020643 -v -0.012398 -0.015694 0.018597 -vn 0.619470 0.783995 0.040122 -v -0.012409 -0.015685 0.023484 -vn 0.569742 0.821494 -0.023284 -v -0.011656 -0.016252 0.023745 -vn 0.515001 0.856421 0.036279 -v -0.010349 -0.017114 0.024141 -vn 0.459229 0.888300 0.005585 -v -0.009130 -0.017795 0.024454 -vn 0.542517 0.594124 -0.593879 -v -0.008489 -0.018109 0.018109 -vn 0.389481 0.920280 0.037269 -v -0.008131 -0.018273 0.024674 -vn 0.461426 0.627998 -0.626662 -v -0.006400 -0.018948 0.018948 -vn 0.335429 0.941950 0.014760 -v -0.006402 -0.018948 0.024985 -vn 0.375035 0.655115 -0.655876 -v -0.005762 -0.019152 0.019152 -vn 0.263413 0.963987 0.036639 -v -0.005789 -0.019144 0.025075 -vn 0.278365 0.678219 -0.680097 -v -0.003533 -0.019685 0.019685 -vn 0.201997 0.978850 0.032404 -v -0.003533 -0.019685 0.025324 -vn 0.137234 0.989879 0.036135 -v -0.003359 -0.019716 0.025338 -vn 0.752658 0.657180 0.040270 -v -0.014912 -0.013328 0.023128 -vn 0.730947 0.682170 -0.018997 -v -0.015052 -0.013169 0.022578 -vn 0.776212 0.630449 0.005506 -v -0.015643 -0.012462 0.023465 -vn -0.444618 0.777308 -0.445093 -v 0.015150 -0.013057 0.015150 -vn -0.753181 0.657664 0.013994 -v 0.015148 -0.013059 0.023237 -vn -0.483895 0.728588 -0.484774 -v 0.016167 -0.011775 0.016167 -vn -0.801221 0.597179 0.037714 -v 0.015685 -0.012409 0.023484 -vn -0.521334 0.673798 -0.523648 -v 0.016911 -0.010677 0.016911 -vn -0.836161 0.547739 0.028567 -v 0.016910 -0.010679 0.024048 -vn -0.559578 0.609341 -0.561762 -v 0.017651 -0.009404 0.017651 -vn -0.873045 0.486180 0.037696 -v 0.017114 -0.010350 0.024141 -vn -0.592977 0.541191 -0.596230 -v 0.018302 -0.008064 0.018302 -vn -0.904187 0.425212 0.040504 -v 0.018273 -0.008131 0.024674 -vn -0.928934 0.368940 0.031051 -v 0.018302 -0.008065 0.024688 -vn -0.627060 0.462144 -0.627071 -v 0.018790 -0.006850 0.018790 -vn -0.951439 0.305552 0.037450 -v 0.019144 -0.005789 0.025075 -vn -0.657579 0.374425 -0.653755 -v 0.019292 -0.005274 0.019292 -vn -0.971527 0.236888 0.004319 -v 0.019292 -0.005276 0.025143 -vn -0.678328 0.283784 -0.677745 -v 0.019562 -0.004162 0.019562 -vn -0.983251 0.178805 0.035302 -v 0.019716 -0.003359 0.025338 -vn -0.697592 0.183533 -0.692590 -v 0.019859 -0.002369 0.019859 -vn -0.994412 0.101602 -0.028657 -v 0.019859 -0.002370 0.025404 -vn -0.707119 0.079454 -0.702616 -v 0.019951 -0.001392 0.019951 -vn -0.998250 0.048788 0.033430 -v 0.019981 -0.000880 0.025460 -vn -0.712371 -0.017112 -0.701595 -v 0.019991 0.000588 0.019991 -vn -0.999752 -0.022026 0.003289 -v 0.019991 0.000589 0.025465 -vn -0.703372 -0.127658 -0.699265 -v 0.019951 0.001404 0.019951 -vn -0.995223 -0.090046 0.037729 -v 0.019935 0.001611 0.025439 -vn -0.692361 -0.222407 -0.686419 -v 0.019686 0.003533 0.019685 -vn -0.987928 -0.154197 0.014896 -v 0.019685 0.003534 0.025324 -vn -0.974442 -0.221330 0.038410 -v 0.019580 0.004077 0.025276 -vn -0.670332 -0.324077 -0.667555 -v 0.019560 0.004174 0.019560 -vn -0.957669 -0.285959 0.033118 -v 0.018948 0.006400 0.024985 -vn -0.646271 -0.409913 -0.643665 -v 0.018948 0.006400 0.018948 -vn -0.937782 -0.345078 0.038550 -v 0.018921 0.006481 0.024973 -vn -0.615754 -0.495446 -0.612683 -v 0.018786 0.006861 0.018786 -vn -0.912483 -0.407587 0.035315 -v 0.017967 0.008785 0.024534 -vn -0.577367 -0.571988 -0.582646 -v 0.017796 0.009127 0.017796 -vn -0.825021 -0.564892 -0.015429 -v 0.016255 0.011652 0.017477 -vn -0.529030 -0.670476 -0.520181 -v 0.016641 0.011094 0.016641 -vn -0.803365 -0.595478 0.003252 -v 0.016252 0.011656 0.023745 -vn -0.547789 -0.627238 -0.553624 -v 0.017643 0.009420 0.017643 -vn -0.850241 -0.524866 0.040076 -v 0.016733 0.010955 0.023966 -vn -0.879503 -0.475285 0.024070 -v 0.017795 0.009128 0.024455 -vn -0.725770 -0.687937 -0.000814 -v 0.014363 0.013918 0.020877 -vn -0.763294 -0.645687 -0.021711 -v 0.014905 0.013336 0.020004 -vn -0.775879 -0.629762 0.037567 -v 0.015235 0.012957 0.023277 -vn -0.809102 -0.587304 -0.020670 -v 0.016053 0.011929 0.017894 -vn -0.728456 -0.684367 0.031503 -v 0.014355 0.013926 0.022872 -vn -0.701602 -0.712561 0.003343 -v 0.014142 0.014142 0.022774 -vn -0.697752 -0.715978 -0.022761 -v 0.013646 0.014621 0.021932 -vn -0.652906 -0.756267 0.042116 -v 0.013328 0.014912 0.023128 -vn -0.637494 -0.770383 0.010558 -v 0.012462 0.015643 0.023465 -vn -0.726702 -0.656842 -0.201154 -v 0.022500 -0.002535 0.009267 -vn -0.724202 -0.683034 -0.094844 -v 0.022500 -0.002478 0.009001 -vn 0.390014 -0.913335 -0.117085 -v 0.028200 -0.002478 0.009001 -vn -0.716788 -0.697134 -0.014797 -v 0.022500 -0.002465 0.008798 -vn 0.390011 -0.919975 0.039209 -v 0.028200 -0.002466 0.008730 -vn -0.719242 -0.692843 0.051570 -v 0.022500 -0.002466 0.008730 -vn 0.390185 -0.900071 0.193980 -v 0.028200 -0.002501 0.008461 -vn -0.726703 -0.671533 0.144726 -v 0.022500 -0.002501 0.008461 -vn 0.390184 -0.854342 0.343302 -v 0.028200 -0.002580 0.008202 -vn -0.726702 -0.637416 0.256134 -v 0.022500 -0.002580 0.008202 -vn 0.390185 -0.784034 0.482749 -v 0.028200 -0.002703 0.007959 -vn -0.726704 -0.584958 0.360174 -v 0.022500 -0.002703 0.007959 -vn 0.390184 -0.691171 0.608308 -v 0.028200 -0.002864 0.007741 -vn -0.726702 -0.515676 0.453853 -v 0.022500 -0.002864 0.007741 -vn 0.390185 -0.578425 0.716366 -v 0.028200 -0.003060 0.007553 -vn -0.726704 -0.431556 0.534472 -v 0.022500 -0.003060 0.007553 -vn 0.390185 -0.449037 0.803817 -v 0.028200 -0.003285 0.007401 -vn -0.726702 -0.335022 0.599720 -v 0.022500 -0.003285 0.007401 -vn 0.390185 -0.306733 0.868142 -v 0.028200 -0.003532 0.007289 -vn -0.726703 -0.228850 0.647712 -v 0.022500 -0.003532 0.007289 -vn 0.390184 -0.155606 0.907493 -v 0.028200 -0.003795 0.007221 -vn -0.726702 -0.116096 0.677072 -v 0.022500 -0.003795 0.007221 -vn 0.390185 -0.000000 0.920736 -v 0.028200 -0.004065 0.007198 -vn -0.726704 -0.000000 0.686951 -v 0.022500 -0.004065 0.007198 -vn 0.390184 0.155606 0.907493 -v 0.028200 -0.004335 0.007221 -vn -0.726702 0.116096 0.677072 -v 0.022500 -0.004335 0.007221 -vn 0.390185 0.306733 0.868142 -v 0.028200 -0.004598 0.007289 -vn -0.726704 0.228850 0.647711 -v 0.022500 -0.004598 0.007289 -vn 0.390185 0.449039 0.803816 -v 0.028200 -0.004845 0.007401 -vn -0.726702 0.335023 0.599720 -v 0.022500 -0.004845 0.007401 -vn 0.390185 0.578425 0.716366 -v 0.028200 -0.005070 0.007553 -vn -0.726704 0.431557 0.534472 -v 0.022500 -0.005070 0.007553 -vn 0.390184 0.691171 0.608308 -v 0.028200 -0.005266 0.007741 -vn -0.726700 0.515678 0.453854 -v 0.022500 -0.005266 0.007741 -vn 0.390186 0.784033 0.482750 -v 0.028200 -0.005427 0.007959 -vn -0.726704 0.584958 0.360174 -v 0.022500 -0.005427 0.007959 -vn 0.390185 0.854342 0.343301 -v 0.028200 -0.005550 0.008202 -vn -0.726702 0.637417 0.256134 -v 0.022500 -0.005550 0.008202 -vn 0.390184 0.900070 0.193983 -v 0.028200 -0.005629 0.008461 -vn -0.726702 0.671534 0.144729 -v 0.022500 -0.005629 0.008461 -vn 0.390185 0.919907 0.039078 -v 0.028200 -0.005664 0.008730 -vn -0.726703 0.686333 0.029156 -v 0.022500 -0.005664 0.008730 -vn 0.390185 0.913279 -0.116952 -v 0.028200 -0.005652 0.009001 -vn -0.726703 0.681388 -0.087257 -v 0.022500 -0.005652 0.009001 -vn 0.390185 0.880378 -0.269611 -v 0.028200 -0.005595 0.009267 -vn -0.726702 0.656842 -0.201154 -v 0.022500 -0.005595 0.009267 -vn 0.390186 0.822149 -0.414520 -v 0.028200 -0.005494 0.009518 -vn -0.726705 0.613395 -0.309269 -v 0.022500 -0.005494 0.009518 -vn 0.390184 0.740269 -0.547502 -v 0.028200 -0.005351 0.009749 -vn -0.726701 0.552308 -0.408487 -v 0.022500 -0.005351 0.009749 -vn 0.390185 0.637097 -0.664728 -v 0.028200 -0.005172 0.009953 -vn -0.726703 0.475331 -0.495947 -v 0.022500 -0.005172 0.009953 -vn 0.390185 0.515589 -0.762839 -v 0.028200 -0.004961 0.010124 -vn -0.726704 0.384674 -0.569146 -v 0.022500 -0.004961 0.010124 -vn 0.390184 0.379252 -0.839002 -v 0.028200 -0.004724 0.010256 -vn -0.726701 0.282956 -0.625972 -v 0.022500 -0.004724 0.010256 -vn 0.390185 0.232006 -0.891027 -v 0.028200 -0.004468 0.010346 -vn -0.726704 0.173097 -0.664785 -v 0.022500 -0.004468 0.010346 -vn 0.390185 0.078082 -0.917420 -v 0.028200 -0.004201 0.010392 -vn -0.726702 0.058256 -0.684478 -v 0.022500 -0.004201 0.010392 -vn 0.390184 -0.078082 -0.917420 -v 0.028200 -0.003929 0.010392 -vn -0.726702 -0.058256 -0.684478 -v 0.022500 -0.003929 0.010392 -vn 0.390185 -0.232006 -0.891027 -v 0.028200 -0.003662 0.010346 -vn -0.726704 -0.173097 -0.664785 -v 0.022500 -0.003662 0.010346 -vn 0.390184 -0.379254 -0.839001 -v 0.028200 -0.003406 0.010256 -vn -0.726702 -0.282957 -0.625971 -v 0.022500 -0.003406 0.010256 -vn 0.390185 -0.515588 -0.762840 -v 0.028200 -0.003169 0.010124 -vn -0.726703 -0.384675 -0.569147 -v 0.022500 -0.003169 0.010124 -vn 0.390185 -0.637095 -0.664730 -v 0.028200 -0.002958 0.009953 -vn -0.726703 -0.475330 -0.495948 -v 0.022500 -0.002958 0.009953 -vn 0.390184 -0.740269 -0.547502 -v 0.028200 -0.002779 0.009749 -vn -0.726701 -0.552308 -0.408487 -v 0.022500 -0.002779 0.009749 -vn 0.390185 -0.822149 -0.414521 -v 0.028200 -0.002636 0.009518 -vn -0.726705 -0.613395 -0.309269 -v 0.022500 -0.002636 0.009518 -vn 0.390184 -0.880378 -0.269611 -v 0.028200 -0.002535 0.009267 -vn -0.726702 -0.656842 -0.201154 -v 0.022500 0.005595 0.009267 -vn -0.724202 -0.683034 -0.094844 -v 0.022500 0.005652 0.009001 -vn 0.390014 -0.913335 -0.117085 -v 0.028200 0.005652 0.009001 -vn -0.716790 -0.697132 -0.014797 -v 0.022500 0.005665 0.008798 -vn 0.390011 -0.919975 0.039209 -v 0.028200 0.005664 0.008730 -vn -0.719242 -0.692843 0.051570 -v 0.022500 0.005664 0.008730 -vn 0.390185 -0.900072 0.193977 -v 0.028200 0.005629 0.008461 -vn -0.726702 -0.671535 0.144724 -v 0.022500 0.005629 0.008461 -vn 0.390185 -0.854342 0.343301 -v 0.028200 0.005550 0.008202 -vn -0.726704 -0.637415 0.256133 -v 0.022500 0.005550 0.008202 -vn 0.390185 -0.784034 0.482750 -v 0.028200 0.005427 0.007959 -vn -0.726703 -0.584959 0.360175 -v 0.022500 0.005427 0.007959 -vn 0.390184 -0.691173 0.608306 -v 0.028200 0.005266 0.007741 -vn -0.726702 -0.515677 0.453851 -v 0.022500 0.005266 0.007741 -vn 0.390185 -0.578424 0.716367 -v 0.028200 0.005070 0.007553 -vn -0.726704 -0.431555 0.534473 -v 0.022500 0.005070 0.007553 -vn 0.390184 -0.449037 0.803817 -v 0.028200 0.004845 0.007401 -vn -0.726701 -0.335022 0.599721 -v 0.022500 0.004845 0.007401 -vn 0.390185 -0.306733 0.868142 -v 0.028200 0.004598 0.007289 -vn -0.726704 -0.228850 0.647711 -v 0.022500 0.004598 0.007289 -vn 0.390184 -0.155606 0.907493 -v 0.028200 0.004335 0.007221 -vn -0.726702 -0.116096 0.677072 -v 0.022500 0.004335 0.007221 -vn 0.390185 -0.000000 0.920736 -v 0.028200 0.004065 0.007198 -vn -0.726704 -0.000000 0.686951 -v 0.022500 0.004065 0.007198 -vn 0.390184 0.155606 0.907493 -v 0.028200 0.003795 0.007221 -vn -0.726702 0.116096 0.677072 -v 0.022500 0.003795 0.007221 -vn 0.390185 0.306733 0.868142 -v 0.028200 0.003532 0.007289 -vn -0.726704 0.228850 0.647711 -v 0.022500 0.003532 0.007289 -vn 0.390184 0.449037 0.803817 -v 0.028200 0.003285 0.007401 -vn -0.726706 0.335020 0.599717 -v 0.022500 0.003285 0.007401 -vn 0.390186 0.578424 0.716367 -v 0.028200 0.003060 0.007553 -vn -0.726704 0.431555 0.534473 -v 0.022500 0.003060 0.007553 -vn 0.390185 0.691173 0.608306 -v 0.028200 0.002864 0.007741 -vn -0.726702 0.515677 0.453851 -v 0.022500 0.002864 0.007741 -vn 0.390185 0.784033 0.482750 -v 0.028200 0.002703 0.007959 -vn -0.726703 0.584959 0.360175 -v 0.022500 0.002703 0.007959 -vn 0.390186 0.854342 0.343301 -v 0.028200 0.002580 0.008202 -vn -0.726703 0.637415 0.256133 -v 0.022500 0.002580 0.008202 -vn 0.390184 0.900071 0.193983 -v 0.028200 0.002501 0.008461 -vn -0.726701 0.671535 0.144729 -v 0.022500 0.002501 0.008461 -vn 0.390186 0.919906 0.039078 -v 0.028200 0.002466 0.008730 -vn -0.726705 0.686330 0.029156 -v 0.022500 0.002466 0.008730 -vn 0.390185 0.913278 -0.116955 -v 0.028200 0.002478 0.009001 -vn -0.726702 0.681389 -0.087259 -v 0.022500 0.002478 0.009001 -vn 0.390185 0.880378 -0.269611 -v 0.028200 0.002535 0.009267 -vn -0.726702 0.656842 -0.201154 -v 0.022500 0.002535 0.009267 -vn 0.390186 0.822150 -0.414518 -v 0.028200 0.002636 0.009518 -vn -0.726704 0.613397 -0.309267 -v 0.022500 0.002636 0.009518 -vn 0.390185 0.740269 -0.547502 -v 0.028200 0.002779 0.009749 -vn -0.726702 0.552307 -0.408486 -v 0.022500 0.002779 0.009749 -vn 0.390184 0.637096 -0.664729 -v 0.028200 0.002958 0.009953 -vn -0.726702 0.475332 -0.495948 -v 0.022500 0.002958 0.009953 -vn 0.390185 0.515590 -0.762838 -v 0.028200 0.003169 0.010124 -vn -0.726705 0.384675 -0.569144 -v 0.022500 0.003169 0.010124 -vn 0.390184 0.379251 -0.839003 -v 0.028200 0.003406 0.010256 -vn -0.726702 0.282956 -0.625972 -v 0.022500 0.003406 0.010256 -vn 0.390185 0.232005 -0.891027 -v 0.028200 0.003662 0.010346 -vn -0.726703 0.173096 -0.664786 -v 0.022500 0.003662 0.010346 -vn 0.390185 0.078082 -0.917420 -v 0.028200 0.003929 0.010392 -vn -0.726702 0.058256 -0.684478 -v 0.022500 0.003929 0.010392 -vn 0.390184 -0.078082 -0.917420 -v 0.028200 0.004201 0.010392 -vn -0.726702 -0.058256 -0.684478 -v 0.022500 0.004201 0.010392 -vn 0.390185 -0.232005 -0.891027 -v 0.028200 0.004468 0.010346 -vn -0.726703 -0.173096 -0.664786 -v 0.022500 0.004468 0.010346 -vn 0.390184 -0.379254 -0.839001 -v 0.028200 0.004724 0.010256 -vn -0.726702 -0.282957 -0.625971 -v 0.022500 0.004724 0.010256 -vn 0.390184 -0.515589 -0.762839 -v 0.028200 0.004961 0.010124 -vn -0.726703 -0.384676 -0.569146 -v 0.022500 0.004961 0.010124 -vn 0.390185 -0.637094 -0.664731 -v 0.028200 0.005172 0.009953 -vn -0.726703 -0.475329 -0.495949 -v 0.022500 0.005172 0.009953 -vn 0.390184 -0.740269 -0.547502 -v 0.028200 0.005351 0.009749 -vn -0.726702 -0.552307 -0.408486 -v 0.022500 0.005351 0.009749 -vn 0.390185 -0.822150 -0.414518 -v 0.028200 0.005494 0.009518 -vn -0.726704 -0.613397 -0.309267 -v 0.022500 0.005494 0.009518 -vn 0.390184 -0.880378 -0.269611 -v 0.028200 0.005595 0.009267 -vn 0.828486 -0.022516 -0.559557 -v -0.016120 0.017758 0.011839 -vn 0.530992 -0.530889 -0.660458 -v -0.016641 0.016641 0.011094 -vn 0.551412 -0.551528 -0.625908 -v -0.017676 0.017676 0.009357 -vn 0.253626 -0.253636 0.933457 -v -0.009840 0.009840 -0.017412 -vn 0.213761 -0.215636 0.952789 -v -0.008535 0.008535 -0.018087 -vn 0.396690 0.026250 0.917577 -v -0.008536 0.024589 -0.018087 -vn -0.819704 -0.002850 -0.572780 -v 0.016114 0.023681 0.011847 -vn -0.484657 0.094299 -0.869606 -v 0.017095 0.024133 0.010380 -vn -0.486825 0.142247 -0.861840 -v 0.017116 0.023967 0.010346 -vn -0.487094 0.194478 -0.851421 -v 0.017140 0.023837 0.010307 -vn -0.488720 0.243576 -0.837749 -v 0.017170 0.023711 0.010256 -vn -0.497548 0.281051 -0.820644 -v 0.017207 0.023589 0.010194 -vn -0.518592 0.332344 -0.787788 -v 0.017249 0.023474 0.010124 -vn -0.830122 -0.018769 -0.557266 -v 0.016116 0.017765 0.011843 -vn -0.534007 0.401938 -0.743829 -v 0.017347 0.023263 0.009953 -vn -0.549806 0.477784 -0.685154 -v 0.017463 0.023084 0.009749 -vn -0.523034 -0.524227 -0.672028 -v 0.016641 0.016641 0.011094 -vn -0.503174 -0.528761 -0.683540 -v 0.017348 0.017348 0.009952 -vn -0.558216 -0.474326 -0.680742 -v 0.017463 0.017526 0.009749 -vn -0.573188 0.545460 -0.611498 -v 0.017590 0.022941 0.009518 -vn -0.573188 -0.545460 -0.611498 -v 0.017590 0.017669 0.009518 -vn -0.600003 0.626767 -0.497152 -v 0.017724 0.022840 0.009267 -vn -0.625317 0.659733 -0.416811 -v 0.017860 0.022783 0.009001 -vn -0.583612 -0.597217 -0.550209 -v 0.017676 0.017739 0.009358 -vn -0.583618 0.597113 -0.550315 -v 0.017676 0.022871 0.009358 -vn -0.706668 0.705665 -0.051553 -v 0.018241 0.022885 0.008202 -vn -0.626561 -0.620430 -0.471685 -v 0.018855 0.018855 0.006670 -vn -0.680835 0.710815 -0.176650 -v 0.018122 0.022806 0.008461 -vn -0.605244 -0.600451 -0.522627 -v 0.018374 0.018374 0.007899 -vn -0.652787 0.694221 -0.303195 -v 0.017994 0.022771 0.008730 -vn -0.570455 -0.654087 -0.496741 -v 0.017812 0.017812 0.009096 -vn -0.595534 -0.626405 -0.502948 -v 0.017724 0.017770 0.009267 -vn -0.737499 0.670993 0.076574 -v 0.018348 0.023008 0.007959 -vn -0.765795 0.611158 0.200112 -v 0.018441 0.023169 0.007741 -vn -0.784354 0.539209 0.306662 -v 0.018519 0.023365 0.007553 -vn -0.826873 0.075666 0.557275 -v 0.018658 0.024234 0.007204 -vn -0.828450 0.000630 0.560063 -v 0.018660 0.024370 0.007198 -vn -0.942630 0.007580 -0.333754 -v 0.018856 0.024943 0.006668 -vn -0.794759 0.476030 0.376502 -v 0.018552 0.023474 0.007472 -vn -0.804029 0.419399 0.421475 -v 0.018580 0.023590 0.007401 -vn -0.812075 0.356752 0.461803 -v 0.018604 0.023710 0.007340 -vn -0.818944 0.291211 0.494496 -v 0.018624 0.023837 0.007289 -vn -0.821802 0.219117 0.525955 -v 0.018640 0.023967 0.007250 -vn -0.822902 0.151289 0.547671 -v 0.018651 0.024100 0.007221 -vn -0.827735 -0.075107 0.556070 -v 0.018658 0.024506 0.007204 -vn -0.826908 -0.158929 0.539412 -v 0.018651 0.024640 0.007221 -vn -0.821526 -0.235295 0.519357 -v 0.018632 0.024840 0.007269 -vn -0.977252 0.021074 -0.211032 -v 0.019629 0.025298 0.003835 -vn -0.676622 -0.677134 -0.289260 -v 0.019629 0.019629 0.003835 -vn -0.961852 0.037975 -0.270922 -v 0.019144 0.025075 0.005789 -vn -0.661512 -0.660111 -0.355887 -v 0.019330 0.019330 0.005133 -vn -0.641407 -0.641857 -0.420258 -v 0.018945 0.018945 0.006409 -vn -0.964076 -0.010656 0.265414 -v 0.019387 0.025187 -0.004912 -vn -0.692646 -0.678237 0.245431 -v 0.019678 0.019678 -0.003575 -vn -0.982373 0.035806 0.183471 -v 0.019580 0.025276 -0.004077 -vn -0.698136 -0.691288 0.186349 -v 0.019876 0.019876 -0.002224 -vn -0.991697 0.016844 0.127488 -v 0.019898 0.025422 -0.002018 -vn -0.702504 -0.700933 0.123212 -v 0.019898 0.019898 -0.002018 -vn -0.997887 0.035768 0.054236 -v 0.019935 0.025439 -0.001611 -vn -0.717375 -0.695624 0.038483 -v 0.019989 0.019989 -0.000666 -vn -0.999257 0.035872 -0.014080 -v 0.019981 0.025460 0.000880 -vn -0.710312 -0.703564 -0.021326 -v 0.019988 0.019988 0.000689 -vn -0.996474 0.036513 -0.075541 -v 0.019979 0.025459 0.000918 -vn -0.703250 -0.705348 -0.089014 -v 0.019979 0.019979 0.000918 -vn -0.989193 0.038562 -0.141460 -v 0.019716 0.025338 0.003359 -vn -0.698364 -0.698039 -0.158207 -v 0.019872 0.019872 0.002258 -vn -0.687239 -0.687757 -0.233863 -v 0.019676 0.019676 0.003587 -vn -0.867263 0.012298 0.497699 -v 0.017132 0.024150 -0.010319 -vn -0.594820 -0.592808 0.542925 -v 0.018396 0.018396 -0.007848 -vn -0.898409 0.041402 0.437204 -v 0.017967 0.024534 -0.008785 -vn -0.612612 -0.614631 0.496925 -v 0.018459 0.018459 -0.007698 -vn -0.924128 0.004223 0.382060 -v 0.018459 0.024760 -0.007699 -vn -0.641937 -0.632241 0.433806 -v 0.018946 0.018946 -0.006408 -vn -0.950153 0.034026 0.309921 -v 0.018921 0.024973 -0.006481 -vn -0.659358 -0.650572 0.376835 -v 0.019341 0.019341 -0.005090 -vn -0.669835 -0.669229 0.321642 -v 0.019388 0.019388 -0.004911 -vn -0.794184 0.025748 0.607132 -v 0.015437 0.023370 -0.012716 -vn -0.521617 -0.519944 0.676442 -v 0.017060 0.017060 -0.010439 -vn -0.832852 0.041611 0.551929 -v 0.016733 0.023966 -0.010955 -vn -0.542926 -0.543748 0.639976 -v 0.017133 0.017133 -0.010318 -vn -0.572758 -0.570099 0.589012 -v 0.017808 0.017808 -0.009104 -vn -0.711919 0.006815 0.702229 -v 0.014142 0.022774 -0.014142 -vn -0.414675 -0.411763 0.811478 -v 0.014421 0.014421 -0.013858 -vn -0.446490 -0.440242 0.778996 -v 0.015361 0.015361 -0.012808 -vn -0.760267 0.041428 0.648289 -v 0.015235 0.023277 -0.012957 -vn -0.465666 -0.465670 0.752533 -v 0.015437 0.015437 -0.012716 -vn -0.495208 -0.494004 0.714653 -v 0.016289 0.016289 -0.011605 -vn -0.306147 -0.306049 0.901448 -v 0.011092 0.011092 -0.016643 -vn -0.333395 -0.332909 0.882054 -v 0.012245 0.012245 -0.015813 -vn -0.562289 0.012441 0.826847 -v 0.011095 0.023923 -0.016640 -vn -0.363685 -0.362316 0.858173 -v 0.013336 0.013336 -0.014905 -vn -0.385611 -0.385391 0.838319 -v 0.013409 0.013409 -0.014839 -vn -0.657241 0.014557 0.753540 -v 0.013412 0.023094 -0.014836 -vn -0.608096 0.039157 0.792897 -v 0.012409 0.023484 -0.015685 -vn -0.228226 -0.228285 0.946467 -v 0.008535 0.008535 -0.018087 -vn -0.254282 -0.253947 0.933194 -v 0.009806 0.009806 -0.017431 -vn -0.444151 0.023965 0.895631 -v 0.008537 0.024589 -0.018086 -vn -0.285002 -0.283876 0.915526 -v 0.011027 0.011027 -0.016685 -vn -0.494076 0.038187 0.868580 -v 0.010349 0.024141 -0.017114 -vn -0.152289 -0.152467 0.976505 -v 0.005794 0.005794 -0.019142 -vn -0.177284 -0.177100 0.968094 -v 0.007158 0.007158 -0.018675 -vn -0.282694 0.038707 0.958429 -v 0.005789 0.025075 -0.019144 -vn -0.208015 -0.207158 0.955937 -v 0.008485 0.008485 -0.018111 -vn -0.375205 0.037039 0.926202 -v 0.008131 0.024674 -0.018273 -vn -0.065869 -0.061721 0.995918 -v 0.002916 0.002916 -0.019786 -vn -0.102036 -0.101927 0.989545 -v 0.004357 0.004357 -0.019520 -vn -0.118630 0.014599 0.992831 -v 0.002929 0.025370 -0.019784 -vn -0.132846 -0.132165 0.982285 -v 0.005761 0.005761 -0.019152 -vn -0.187408 0.041089 0.981422 -v 0.003360 0.025338 -0.019716 -vn -0.028162 -0.027698 0.999220 -v 0.001466 0.001466 -0.019946 -vn -0.059853 0.036007 0.997558 -v 0.000880 0.025460 -0.019981 -vn 0.020517 -0.017381 0.999638 -v 0.000000 0.025469 -0.020000 -vn 0.333939 0.039443 0.941769 -v -0.006481 0.024973 -0.018921 -vn 0.176812 -0.176991 0.968200 -v -0.007184 0.007184 -0.018665 -vn 0.272356 0.010155 0.962143 -v -0.005796 0.025074 -0.019142 -vn 0.138603 -0.139160 0.980522 -v -0.005795 0.005795 -0.019142 -vn 0.206500 0.038140 0.977703 -v -0.004077 0.025276 -0.019580 -vn 0.101602 -0.101632 0.989620 -v -0.004374 0.004374 -0.019516 -vn 0.143592 0.002606 0.989634 -v -0.002930 0.025370 -0.019784 -vn 0.064576 -0.064396 0.995833 -v -0.002929 0.002929 -0.019784 -vn 0.070576 0.034034 0.996926 -v -0.001611 0.025439 -0.019935 -vn 0.027589 -0.027567 0.999239 -v -0.001468 0.001468 -0.019946 -vn -0.000060 0.000205 1.000000 -v 0.000000 0.000000 -0.020000 -vn 0.454394 0.040251 0.889891 -v -0.008785 0.024534 -0.017967 -vn 0.514068 0.034674 0.857048 -v -0.010955 0.023966 -0.016733 -vn 0.293067 -0.292713 0.910182 -v -0.011092 0.011092 -0.016642 -vn 0.569583 0.035660 0.821160 -v -0.011093 0.023924 -0.016642 -vn 0.332525 -0.332508 0.882533 -v -0.012284 0.012284 -0.015783 -vn 0.620881 0.035725 0.783091 -v -0.012957 0.023277 -0.015235 -vn 0.373150 -0.372329 0.849782 -v -0.013410 0.013410 -0.014838 -vn 0.665313 0.036347 0.745680 -v -0.013411 0.023094 -0.014837 -vn 0.412728 -0.414104 0.811279 -v -0.014463 0.014463 -0.013814 -vn 0.713905 0.006697 0.700210 -v -0.014142 0.022774 -0.014142 -vn 0.452166 -0.454624 0.767374 -v -0.015438 0.015438 -0.012715 -vn 0.763666 0.030295 0.644901 -v -0.015437 0.023370 -0.012716 -vn 0.493448 -0.495150 0.715078 -v -0.016330 0.016330 -0.011547 -vn 0.806614 0.037631 0.589880 -v -0.015685 0.023484 -0.012409 -vn 0.529020 -0.535058 0.658673 -v -0.017134 0.017134 -0.010317 -vn 0.845436 0.041275 0.532480 -v -0.017114 0.024141 -0.010349 -vn 0.876144 0.032270 0.480968 -v -0.017134 0.024150 -0.010317 -vn 0.570003 -0.570253 0.591531 -v -0.017845 0.017845 -0.009031 -vn 0.906443 0.038343 0.420584 -v -0.018273 0.024674 -0.008131 -vn 0.605783 -0.605410 0.516241 -v -0.018460 0.018460 -0.007696 -vn 0.934129 0.008194 0.356841 -v -0.018459 0.024760 -0.007698 -vn 0.637120 -0.636693 0.434396 -v -0.018975 0.018975 -0.006320 -vn 0.953516 0.036078 0.299174 -v -0.019144 0.025075 -0.005789 -vn 0.664336 -0.663406 0.344311 -v -0.019388 0.019388 -0.004910 -vn 0.973534 -0.022463 0.227436 -v -0.019388 0.025187 -0.004912 -vn 0.684981 -0.685497 0.246770 -v -0.019696 0.019696 -0.003473 -vn 0.984394 0.034248 0.172614 -v -0.019716 0.025338 -0.003359 -vn 0.699419 -0.699759 0.145431 -v -0.019898 0.019898 -0.002018 -vn 0.994600 0.003033 0.103736 -v -0.019898 0.025422 -0.002019 -vn 0.706108 -0.707041 0.038800 -v -0.019992 0.019992 -0.000551 -vn 0.998653 0.038052 0.035275 -v -0.019981 0.025460 -0.000880 -vn 0.707089 -0.703884 -0.067619 -v -0.019979 0.019979 0.000918 -vn 0.999546 0.010529 -0.028243 -v -0.019979 0.025459 0.000918 -vn 0.994603 0.036947 -0.096953 -v -0.019935 0.025439 0.001611 -vn 0.698886 -0.694980 -0.169000 -v -0.019858 0.019858 0.002382 -vn 0.986393 0.026005 -0.162334 -v -0.019629 0.025298 0.003834 -vn 0.681491 -0.679134 -0.272669 -v -0.019629 0.019629 0.003834 -vn 0.973424 0.037247 -0.225959 -v -0.019580 0.025276 0.004077 -vn 0.658377 -0.657475 -0.366423 -v -0.019295 0.019295 0.005265 -vn 0.955564 0.036559 -0.292509 -v -0.018921 0.024973 0.006481 -vn 0.934661 0.033921 -0.353919 -v -0.018856 0.024943 0.006668 -vn 0.627401 -0.630368 -0.457170 -v -0.018856 0.018856 0.006667 -vn 0.910324 0.036921 -0.412246 -v -0.017967 0.024534 0.008785 -vn 0.596747 -0.598249 -0.534782 -v -0.018316 0.018316 0.008033 -vn 0.874234 0.009853 -0.485405 -v -0.017675 0.024399 0.009359 -vn 0.848760 0.035813 -0.527564 -v -0.016733 0.023966 0.010955 -vn 0.794883 -0.016651 -0.606534 -v -0.016113 0.023681 0.011847 -vn 0.794452 -0.020061 -0.606996 -v -0.015694 0.018597 0.012398 -vn 0.772113 0.034175 -0.634565 -v -0.015235 0.023277 0.012957 -vn 0.743200 -0.022027 -0.668707 -v -0.014488 0.020682 0.013788 -vn 0.724286 0.020112 -0.689207 -v -0.014207 0.022804 0.014077 -vn 0.697336 0.006777 -0.716712 -v -0.014142 0.022774 0.014142 -vn 0.681792 -0.022728 -0.731193 -v -0.013169 0.022578 0.015052 -vn 0.658549 0.038651 -0.751544 -v -0.013328 0.023128 0.014912 -vn 0.631683 0.005704 -0.775206 -v -0.012462 0.023465 0.015643 -vn -0.803984 -0.021580 -0.594259 -v 0.016053 0.017894 0.011929 -vn -0.769207 -0.018251 -0.638739 -v 0.014905 0.020004 0.013336 -vn -0.636847 0.010887 -0.770913 -v 0.012462 0.023465 0.015643 -vn -0.651597 0.043841 -0.757297 -v 0.013328 0.023128 0.014912 -vn -0.696693 -0.023883 -0.716972 -v 0.013646 0.021932 0.014621 -vn -0.699882 0.002460 -0.714254 -v 0.014142 0.022774 0.014142 -vn -0.725167 -0.018899 -0.688313 -v 0.014215 0.021104 0.014069 -vn -0.729362 0.019494 -0.683850 -v 0.014207 0.022804 0.014077 -vn -0.783425 0.045479 -0.619820 -v 0.015685 0.023484 0.012409 -vn 0.564707 0.562615 -0.603796 -v -0.017676 -0.017676 0.009357 -vn 0.530926 0.534338 -0.657724 -v -0.017067 -0.017067 0.010426 -vn 0.842876 -0.039767 -0.536636 -v -0.017072 -0.024122 0.010419 -vn 0.805853 -0.036528 -0.590988 -v -0.015685 -0.023484 0.012409 -vn -0.559143 -0.014053 -0.828952 -v 0.011038 -0.023941 0.016678 -vn -0.063914 0.063910 0.995907 -v 0.002899 -0.002899 -0.019789 -vn -0.107060 -0.038013 0.993526 -v 0.001611 -0.025439 -0.019935 -vn -0.173009 -0.036143 0.984257 -v 0.004077 -0.025276 -0.019580 -vn -0.101062 0.100632 0.989778 -v 0.004349 -0.004349 -0.019522 -vn -0.242441 -0.026240 0.969811 -v 0.004349 -0.025249 -0.019521 -vn -0.137865 0.137823 0.980815 -v 0.005745 -0.005745 -0.019157 -vn -0.298955 -0.035475 0.953608 -v 0.006481 -0.024973 -0.018921 -vn -0.175891 0.175139 0.968705 -v 0.007145 -0.007145 -0.018680 -vn -0.377606 -0.001669 0.925965 -v 0.007147 -0.024861 -0.018679 -vn -0.213311 0.213259 0.953425 -v 0.008469 -0.008469 -0.018118 -vn -0.420836 -0.034568 0.906478 -v 0.008785 -0.024534 -0.017967 -vn -0.252244 0.251562 0.934393 -v 0.009788 -0.009788 -0.017441 -vn -0.505425 0.023714 0.862545 -v 0.009791 -0.024291 -0.017439 -vn -0.290719 0.290736 0.911568 -v 0.011013 -0.011013 -0.016695 -vn -0.535655 -0.034175 0.843745 -v 0.010955 -0.023966 -0.016733 -vn -0.330289 0.330196 0.884240 -v 0.012223 -0.012223 -0.015830 -vn -0.601050 -0.008752 0.799164 -v 0.012226 -0.023550 -0.015828 -vn -0.370079 0.370349 0.851988 -v 0.013323 -0.013323 -0.014916 -vn -0.641794 -0.041172 0.765771 -v 0.012957 -0.023277 -0.015235 -vn -0.409471 0.410592 0.814707 -v 0.014398 -0.014398 -0.013881 -vn -0.696660 -0.005916 0.717378 -v 0.014142 -0.022774 -0.014142 -vn -0.736103 -0.032177 0.676104 -v 0.014397 -0.022891 -0.013883 -vn -0.450233 0.450133 0.771149 -v 0.015350 -0.015350 -0.012821 -vn -0.784535 -0.039439 0.618829 -v 0.015685 -0.023484 -0.012409 -vn -0.491388 0.489563 0.720324 -v 0.016266 -0.016266 -0.011637 -vn -0.821517 0.024829 0.569643 -v 0.016264 -0.023750 -0.011640 -vn -0.529090 0.529024 0.663475 -v 0.017051 -0.017051 -0.010453 -vn -0.856387 -0.035539 0.515110 -v 0.017114 -0.024141 -0.010349 -vn -0.567738 0.566039 0.597724 -v 0.017787 -0.017787 -0.009145 -vn -0.888376 -0.006047 0.459076 -v 0.017785 -0.024450 -0.009148 -vn -0.601688 0.602078 0.524856 -v 0.018389 -0.018389 -0.007864 -vn -0.919741 -0.037676 0.390714 -v 0.018273 -0.024674 -0.008131 -vn -0.634393 0.632904 0.443821 -v 0.018929 -0.018929 -0.006458 -vn -0.941709 -0.013799 0.336147 -v 0.018928 -0.024976 -0.006460 -vn -0.660431 0.662212 0.353986 -v 0.019337 -0.019337 -0.005107 -vn -0.963267 -0.037516 0.265911 -v 0.019144 -0.025075 -0.005789 -vn -0.683380 0.681927 0.260706 -v 0.019667 -0.019667 -0.003633 -vn -0.978370 -0.029475 0.204752 -v 0.019667 -0.025316 -0.003633 -vn -0.697914 0.698263 0.159200 -v 0.019874 -0.019874 -0.002241 -vn -0.989491 -0.037245 0.139714 -v 0.019716 -0.025338 -0.003359 -vn -0.996833 -0.036419 0.070696 -v 0.019981 -0.025460 -0.000880 -vn -0.708694 0.703409 0.054481 -v 0.019987 -0.019987 -0.000730 -vn -0.999540 -0.029652 0.006427 -v 0.019987 -0.025463 -0.000730 -vn -0.709599 0.702310 -0.056840 -v 0.019989 -0.019989 0.000672 -vn -0.997727 -0.035448 -0.057306 -v 0.019935 -0.025439 0.001611 -vn -0.707677 0.691001 -0.147348 -v 0.019880 -0.019880 0.002187 -vn -0.990975 -0.005346 -0.133942 -v 0.019880 -0.025414 0.002188 -vn -0.686855 0.678183 -0.261341 -v 0.019679 -0.019679 0.003570 -vn -0.981883 -0.034308 -0.186358 -v 0.019580 -0.025276 0.004077 -vn -0.664348 0.660217 -0.350364 -v 0.019350 -0.019350 0.005059 -vn -0.961113 0.019061 -0.275498 -v 0.019349 -0.025170 0.005061 -vn -0.820574 0.233357 0.521731 -v 0.018633 -0.024840 0.007267 -vn -0.819943 0.149705 0.552523 -v 0.018651 -0.024645 0.007221 -vn -0.951127 -0.122749 -0.283356 -v 0.018921 -0.024973 0.006481 -vn -0.815708 0.075884 0.573465 -v 0.018658 -0.024511 0.007204 -vn -0.816143 -0.000148 0.577850 -v 0.018660 -0.024375 0.007198 -vn -0.814307 -0.077217 0.575276 -v 0.018658 -0.024239 0.007204 -vn -0.810443 -0.153520 0.565343 -v 0.018651 -0.024105 0.007221 -vn -0.810395 -0.219024 0.543404 -v 0.018640 -0.023971 0.007250 -vn -0.809492 -0.293856 0.508302 -v 0.018624 -0.023842 0.007289 -vn -0.803083 -0.360608 0.474362 -v 0.018604 -0.023716 0.007340 -vn -0.795132 -0.423708 0.433863 -v 0.018580 -0.023595 0.007401 -vn -0.785569 -0.481917 0.388121 -v 0.018551 -0.023478 0.007473 -vn -0.775050 -0.546088 0.317940 -v 0.018519 -0.023370 0.007553 -vn -0.762915 -0.599815 0.241213 -v 0.018441 -0.023174 0.007741 -vn -0.635663 0.633909 -0.440558 -v 0.018951 -0.018951 0.006393 -vn -0.608855 0.601090 -0.517674 -v 0.018407 -0.018407 0.007822 -vn -0.750374 -0.641811 0.158171 -v 0.018408 -0.023109 0.007819 -vn -0.735969 -0.673685 0.067066 -v 0.018348 -0.023013 0.007959 -vn -0.508641 0.517648 -0.687986 -v 0.017342 -0.017342 0.009963 -vn -0.539856 0.426108 -0.725939 -v 0.017347 -0.017352 0.009953 -vn -0.557486 -0.474568 -0.681171 -v 0.017463 -0.023089 0.009749 -vn -0.558132 0.474223 -0.680883 -v 0.017463 -0.017531 0.009749 -vn -0.577455 0.546977 -0.606104 -v 0.017590 -0.017674 0.009518 -vn -0.577455 -0.546830 -0.606237 -v 0.017590 -0.022946 0.009518 -vn -0.711496 -0.700562 -0.054654 -v 0.018241 -0.022890 0.008202 -vn -0.681702 -0.708667 -0.181861 -v 0.018122 -0.022811 0.008461 -vn -0.570621 0.656019 -0.493995 -v 0.017820 -0.017820 0.009080 -vn -0.652708 -0.694014 -0.303838 -v 0.017994 -0.022776 0.008730 -vn -0.596079 0.609605 -0.522562 -v 0.017724 -0.017775 0.009267 -vn -0.625121 -0.659970 -0.416729 -v 0.017860 -0.022788 0.009001 -vn -0.599964 -0.609841 -0.517820 -v 0.017724 -0.022845 0.009267 -vn -0.525276 0.517000 -0.675867 -v 0.017072 -0.017072 0.010419 -vn -0.542087 -0.394948 -0.741726 -v 0.017347 -0.023268 0.009953 -vn -0.526668 -0.326775 -0.784754 -v 0.017249 -0.023479 0.010124 -vn -0.507395 -0.186044 -0.841391 -v 0.017140 -0.023841 0.010306 -vn -0.505620 -0.136729 -0.851853 -v 0.017116 -0.023972 0.010346 -vn -0.515621 -0.276977 -0.810814 -v 0.017207 -0.023594 0.010195 -vn -0.511316 -0.231818 -0.827536 -v 0.017170 -0.023716 0.010256 -vn -0.608979 -0.036506 -0.792346 -v 0.012409 -0.023484 0.015685 -vn -0.655458 -0.011072 -0.755151 -v 0.013349 -0.023120 0.014893 -vn -0.711074 -0.006693 -0.703085 -v 0.014142 -0.022774 0.014142 -vn -0.759478 -0.041368 -0.649216 -v 0.015235 -0.023277 0.012957 -vn -0.448138 0.440222 -0.778060 -v 0.015366 -0.015366 0.012802 -vn -0.791582 -0.027693 -0.610435 -v 0.015372 -0.023340 0.012794 -vn -0.482987 0.472091 -0.737464 -v 0.015782 -0.015783 0.012285 -vn -0.833000 -0.038196 -0.551953 -v 0.016733 -0.023966 0.010955 -vn -0.850348 -0.008141 -0.526158 -v 0.017072 -0.024122 0.010419 -vn -0.506128 -0.093374 -0.857389 -v 0.017096 -0.024133 0.010380 -vn -0.494231 -0.037777 -0.868510 -v 0.010349 -0.024141 0.017114 -vn -0.442084 -0.025355 -0.896615 -v 0.008491 -0.024599 0.018108 -vn -0.374974 -0.036549 -0.926315 -v 0.008131 -0.024674 0.018273 -vn -0.283336 -0.037400 -0.958291 -v 0.005789 -0.025075 0.019144 -vn -0.188290 -0.037932 -0.981381 -v 0.003360 -0.025338 0.019716 -vn -0.117271 -0.010859 -0.993041 -v 0.002913 -0.025371 0.019787 -vn -0.059498 -0.035577 -0.997594 -v 0.000880 -0.025460 0.019981 -vn 0.020267 0.018179 -0.999629 -v 0.000000 -0.025469 0.020000 -vn 0.070783 -0.033867 -0.996917 -v -0.001611 -0.025439 0.019935 -vn 0.143018 -0.002090 -0.989718 -v -0.002913 -0.025371 0.019787 -vn 0.206276 -0.037851 -0.977762 -v -0.004077 -0.025276 0.019580 -vn 0.271630 -0.008934 -0.962360 -v -0.005764 -0.025079 0.019152 -vn 0.333362 -0.039153 -0.941986 -v -0.006481 -0.024973 0.018921 -vn 0.395190 -0.023766 -0.918292 -v -0.008490 -0.024599 0.018108 -vn 0.454374 -0.039247 -0.889946 -v -0.008785 -0.024534 0.017967 -vn 0.514750 -0.039144 -0.856446 -v -0.010955 -0.023966 0.016733 -vn 0.563213 -0.042636 -0.825211 -v -0.011036 -0.023942 0.016680 -vn 0.619662 -0.037368 -0.783979 -v -0.012957 -0.023277 0.015235 -vn 0.628179 0.523372 -0.575737 -v -0.013346 -0.015644 0.014896 -vn 0.642381 0.527729 -0.555742 -v -0.012774 -0.015797 0.015389 -vn 0.662452 -0.037637 -0.748158 -v -0.013347 -0.023120 0.014895 -vn 0.660599 0.525110 -0.536534 -v -0.012155 -0.016042 0.015883 -vn 0.678047 0.523518 -0.515928 -v -0.011635 -0.016308 0.016267 -vn 0.624366 0.521359 -0.581680 -v -0.013379 -0.015638 0.014866 -vn 0.712840 -0.005882 -0.701302 -v -0.014142 -0.022774 0.014142 -vn 0.616512 0.526953 -0.585008 -v -0.013562 -0.015606 0.014699 -vn 0.760855 -0.025964 -0.648402 -v -0.015372 -0.023340 0.012795 -vn 0.556918 0.526943 -0.642008 -v -0.015374 -0.015791 0.012792 -vn 0.563702 0.523565 -0.638842 -v -0.015262 -0.015749 0.012925 -vn 0.571153 0.526830 -0.629471 -v -0.015188 -0.015724 0.013013 -vn 0.579087 0.532909 -0.616982 -v -0.014667 -0.015601 0.013597 -vn 0.599656 0.530995 -0.598713 -v -0.014125 -0.015562 0.014159 -vn 0.514045 0.519713 -0.682390 -v -0.016641 -0.016641 0.011094 -vn 0.525236 0.519745 -0.673789 -v -0.016214 -0.016267 0.011709 -vn 0.543984 0.523325 -0.655906 -v -0.015755 -0.015969 0.012320 -vn 0.874113 -0.035832 -0.484400 -v -0.017114 -0.024141 0.010350 -vn 0.906073 -0.039049 -0.421315 -v -0.018273 -0.024674 0.008131 -vn 0.602000 0.598857 -0.528173 -v -0.018407 -0.018407 0.007822 -vn 0.932653 -0.016823 -0.360383 -v -0.018406 -0.024736 0.007823 -vn 0.632930 0.628806 -0.451666 -v -0.018856 -0.018856 0.006667 -vn 0.952734 -0.036516 -0.301603 -v -0.019144 -0.025075 0.005789 -vn 0.660361 0.659157 -0.359772 -v -0.019350 -0.019350 0.005059 -vn 0.972838 0.011401 -0.231208 -v -0.019349 -0.025170 0.005060 -vn 0.681758 0.681772 -0.265316 -v -0.019629 -0.019629 0.003834 -vn 0.983890 -0.034576 -0.175397 -v -0.019716 -0.025338 0.003359 -vn 0.697939 0.697150 -0.163901 -v -0.019880 -0.019880 0.002187 -vn 0.994419 0.042480 -0.096570 -v -0.019880 -0.025414 0.002188 -vn 0.705768 0.705990 -0.058910 -v -0.019979 -0.019979 0.000918 -vn 0.998387 -0.033063 -0.046164 -v -0.019981 -0.025460 0.000880 -vn 0.706587 0.706123 0.046110 -v -0.019987 -0.019987 -0.000730 -vn 0.999667 -0.006278 0.025032 -v -0.019987 -0.025463 -0.000731 -vn 0.697862 0.699995 0.151640 -v -0.019898 -0.019898 -0.002018 -vn 0.994974 -0.038363 0.092489 -v -0.019935 -0.025439 -0.001611 -vn 0.684079 0.684523 0.251922 -v -0.019667 -0.019667 -0.003633 -vn 0.580396 -0.024092 0.813978 -v -0.012224 -0.023550 -0.015829 -vn 0.331434 0.331494 0.883325 -v -0.012223 -0.012223 -0.015830 -vn 0.371172 0.372216 0.850698 -v -0.013410 -0.013410 -0.014838 -vn 0.987528 -0.018693 0.156328 -v -0.019667 -0.025316 -0.003633 -vn 0.973994 -0.037252 0.223492 -v -0.019580 -0.025276 -0.004077 -vn 0.662017 0.663476 0.348616 -v -0.019388 -0.019388 -0.004910 -vn 0.947455 -0.036491 0.317801 -v -0.018921 -0.024973 -0.006481 -vn 0.631876 0.637207 0.441249 -v -0.018929 -0.018929 -0.006458 -vn 0.912214 -0.037431 0.408000 -v -0.017967 -0.024534 -0.008785 -vn 0.602896 0.606849 0.517929 -v -0.018460 -0.018460 -0.007696 -vn 0.879762 -0.024799 0.474767 -v -0.017786 -0.024450 -0.009146 -vn 0.566711 0.569538 0.595371 -v -0.017787 -0.017787 -0.009145 -vn 0.851071 -0.036506 0.523781 -v -0.016733 -0.023966 -0.010955 -vn 0.532599 0.529197 0.660521 -v -0.017134 -0.017134 -0.010317 -vn 0.802645 -0.001140 0.596456 -v -0.016264 -0.023750 -0.011640 -vn 0.492861 0.492458 0.717338 -v -0.016266 -0.016266 -0.011637 -vn 0.775316 -0.035486 0.630575 -v -0.015235 -0.023277 -0.012957 -vn 0.452690 0.451552 0.768878 -v -0.015438 -0.015438 -0.012715 -vn 0.730424 -0.033947 0.682150 -v -0.014397 -0.022892 -0.013882 -vn 0.412648 0.411604 0.812591 -v -0.014398 -0.014398 -0.013881 -vn 0.692146 -0.004716 0.721743 -v -0.014142 -0.022774 -0.014142 -vn 0.627827 -0.042517 0.777191 -v -0.012409 -0.023484 -0.015685 -vn 0.466753 0.002818 0.884383 -v -0.009791 -0.024291 -0.017440 -vn 0.252838 0.252818 0.933893 -v -0.009788 -0.009788 -0.017441 -vn 0.291858 0.292245 0.910721 -v -0.011092 -0.011092 -0.016642 -vn 0.525496 -0.039534 0.849877 -v -0.010349 -0.024141 -0.017114 -vn 0.345083 0.033777 0.937964 -v -0.007147 -0.024861 -0.018679 -vn 0.176421 0.176220 0.968412 -v -0.007145 -0.007145 -0.018680 -vn 0.214984 0.213214 0.953059 -v -0.008535 -0.008535 -0.018087 -vn 0.411018 -0.036628 0.910891 -v -0.008131 -0.024674 -0.018273 -vn 0.224168 -0.004847 0.974538 -v -0.004350 -0.025249 -0.019521 -vn 0.101297 0.101253 0.989690 -v -0.004349 -0.004349 -0.019522 -vn 0.138758 0.138245 0.980630 -v -0.005795 -0.005795 -0.019142 -vn 0.289320 -0.034094 0.956625 -v -0.005789 -0.025075 -0.019144 -vn -0.042792 -0.032083 0.998569 -v 0.001460 -0.025444 -0.019947 -vn -0.026404 0.028082 0.999257 -v 0.001460 -0.001460 -0.019947 -vn 0.021590 -0.037722 0.999055 -v -0.000880 -0.025460 -0.019981 -vn 0.092605 -0.014949 0.995591 -v -0.001461 -0.025444 -0.019947 -vn 0.027457 0.027475 0.999245 -v -0.001460 -0.001460 -0.019947 -vn 0.064231 0.064425 0.995853 -v -0.002929 -0.002929 -0.019784 -vn 0.153481 -0.037296 0.987448 -v -0.003359 -0.025338 -0.019716 -vn -0.040347 -0.965330 -0.257897 -v 0.022500 0.017812 0.009096 -vn 0.389860 -0.880487 -0.269725 -v 0.028200 0.017770 0.009267 -vn 0.390069 -0.822153 -0.414621 -v 0.028200 0.017669 0.009518 -vn 0.390184 -0.740272 -0.547498 -v 0.028200 0.017526 0.009749 -vn -0.049896 -0.744200 -0.666091 -v 0.022500 0.017347 0.009953 -vn 0.390186 -0.637094 -0.664731 -v 0.028200 0.017347 0.009953 -vn -0.726702 -0.384674 -0.569149 -v 0.022500 0.017136 0.010124 -vn 0.390184 -0.515586 -0.762842 -v 0.028200 0.017136 0.010124 -vn -0.726702 -0.282957 -0.625970 -v 0.022500 0.016899 0.010256 -vn 0.390184 -0.379254 -0.839001 -v 0.028200 0.016899 0.010256 -vn -0.726703 -0.173096 -0.664786 -v 0.022500 0.016643 0.010346 -vn 0.390185 -0.232005 -0.891027 -v 0.028200 0.016643 0.010346 -vn -0.726702 -0.058256 -0.684478 -v 0.022500 0.016376 0.010392 -vn 0.390184 -0.078082 -0.917420 -v 0.028200 0.016376 0.010392 -vn -0.726702 0.058256 -0.684478 -v 0.022500 0.016104 0.010392 -vn 0.390185 0.078082 -0.917420 -v 0.028200 0.016104 0.010392 -vn -0.726703 0.173096 -0.664786 -v 0.022500 0.015837 0.010346 -vn 0.390185 0.232005 -0.891027 -v 0.028200 0.015837 0.010346 -vn -0.726702 0.282957 -0.625970 -v 0.022500 0.015581 0.010256 -vn 0.390184 0.379254 -0.839001 -v 0.028200 0.015581 0.010256 -vn -0.726703 0.384676 -0.569146 -v 0.022500 0.015344 0.010124 -vn 0.390185 0.515589 -0.762839 -v 0.028200 0.015344 0.010124 -vn -0.726703 0.475329 -0.495949 -v 0.022500 0.015133 0.009953 -vn 0.390185 0.637093 -0.664732 -v 0.028200 0.015133 0.009953 -vn -0.726702 0.552307 -0.408486 -v 0.022500 0.014954 0.009749 -vn 0.390184 0.740269 -0.547502 -v 0.028200 0.014954 0.009749 -vn -0.726702 0.613398 -0.309268 -v 0.022500 0.014811 0.009518 -vn 0.390185 0.822150 -0.414518 -v 0.028200 0.014811 0.009518 -vn -0.726702 0.656842 -0.201154 -v 0.022500 0.014710 0.009267 -vn 0.390184 0.880378 -0.269611 -v 0.028200 0.014710 0.009267 -vn -0.726704 0.681387 -0.087254 -v 0.022500 0.014653 0.009001 -vn 0.390185 0.913279 -0.116949 -v 0.028200 0.014653 0.009001 -vn -0.726702 0.686334 0.029156 -v 0.022500 0.014641 0.008730 -vn 0.390185 0.919907 0.039078 -v 0.028200 0.014641 0.008730 -vn -0.726702 0.671534 0.144724 -v 0.022500 0.014676 0.008461 -vn 0.390185 0.900071 0.193977 -v 0.028200 0.014676 0.008461 -vn -0.726703 0.637415 0.256133 -v 0.022500 0.014755 0.008202 -vn 0.390185 0.854342 0.343302 -v 0.028200 0.014755 0.008202 -vn -0.726703 0.584959 0.360175 -v 0.022500 0.014878 0.007959 -vn 0.390185 0.784033 0.482750 -v 0.028200 0.014878 0.007959 -vn -0.726702 0.515677 0.453851 -v 0.022500 0.015039 0.007741 -vn 0.390185 0.691173 0.608306 -v 0.028200 0.015039 0.007741 -vn -0.726704 0.431555 0.534473 -v 0.022500 0.015235 0.007553 -vn 0.390185 0.578424 0.716367 -v 0.028200 0.015235 0.007553 -vn -0.726701 0.335022 0.599721 -v 0.022500 0.015460 0.007401 -vn 0.390184 0.449037 0.803817 -v 0.028200 0.015460 0.007401 -vn -0.726704 0.228850 0.647711 -v 0.022500 0.015707 0.007289 -vn 0.390185 0.306733 0.868142 -v 0.028200 0.015707 0.007289 -vn -0.726702 0.116096 0.677072 -v 0.022500 0.015970 0.007221 -vn 0.390184 0.155606 0.907493 -v 0.028200 0.015970 0.007221 -vn -0.726705 -0.000000 0.686950 -v 0.022500 0.016240 0.007198 -vn 0.390185 -0.000000 0.920736 -v 0.028200 0.016240 0.007198 -vn -0.726702 -0.116096 0.677072 -v 0.022500 0.016510 0.007221 -vn 0.390184 -0.155606 0.907493 -v 0.028200 0.016510 0.007221 -vn -0.726704 -0.228850 0.647711 -v 0.022500 0.016773 0.007289 -vn 0.390185 -0.306733 0.868142 -v 0.028200 0.016773 0.007289 -vn -0.726702 -0.335024 0.599719 -v 0.022500 0.017020 0.007401 -vn 0.390185 -0.449040 0.803815 -v 0.028200 0.017020 0.007401 -vn -0.726702 -0.431556 0.534475 -v 0.022500 0.017245 0.007553 -vn 0.390185 -0.578423 0.716367 -v 0.028200 0.017245 0.007553 -vn -0.726702 -0.515673 0.453857 -v 0.022500 0.017441 0.007741 -vn 0.390185 -0.691166 0.608313 -v 0.028200 0.017441 0.007741 -vn -0.726705 -0.584957 0.360173 -v 0.022500 0.017602 0.007959 -vn 0.390186 -0.784034 0.482749 -v 0.028200 0.017602 0.007959 -vn -0.726702 -0.637418 0.256130 -v 0.022500 0.017725 0.008202 -vn 0.390184 -0.854344 0.343296 -v 0.028200 0.017725 0.008202 -vn -0.726701 -0.671535 0.144729 -v 0.022500 0.017804 0.008461 -vn 0.390184 -0.900070 0.193984 -v 0.028200 0.017804 0.008461 -vn -0.726704 -0.686332 0.029160 -v 0.022500 0.017839 0.008730 -vn 0.390185 -0.919906 0.039084 -v 0.028200 0.017839 0.008730 -vn -0.720247 -0.690263 -0.069143 -v 0.022500 0.017827 0.009001 -vn 0.389974 -0.913388 -0.116806 -v 0.028200 0.017827 0.009001 -vn -0.048717 0.711769 -0.700722 -v 0.022500 -0.017342 0.009963 -vn -0.041283 0.966540 -0.253174 -v 0.022500 -0.017820 0.009080 -vn 0.390179 0.880380 -0.269613 -v 0.028200 -0.017775 0.009267 -vn -0.720156 0.690464 -0.068082 -v 0.022500 -0.017832 0.009001 -vn 0.390185 0.913279 -0.116947 -v 0.028200 -0.017832 0.009001 -vn -0.726702 0.686334 0.029155 -v 0.022500 -0.017844 0.008730 -vn 0.390184 0.919907 0.039076 -v 0.028200 -0.017844 0.008730 -vn -0.726704 0.671533 0.144725 -v 0.022500 -0.017809 0.008461 -vn 0.390185 0.900071 0.193979 -v 0.028200 -0.017809 0.008461 -vn -0.726702 0.637416 0.256135 -v 0.022500 -0.017730 0.008202 -vn 0.390185 0.854341 0.343303 -v 0.028200 -0.017730 0.008202 -vn -0.726703 0.584959 0.360174 -v 0.022500 -0.017607 0.007959 -vn 0.390185 0.784033 0.482750 -v 0.028200 -0.017607 0.007959 -vn -0.726702 0.515675 0.453853 -v 0.022500 -0.017446 0.007741 -vn 0.390185 0.691170 0.608309 -v 0.028200 -0.017446 0.007741 -vn -0.726703 0.431556 0.534474 -v 0.022500 -0.017250 0.007553 -vn 0.390185 0.578424 0.716367 -v 0.028200 -0.017250 0.007553 -vn -0.726702 0.335023 0.599719 -v 0.022500 -0.017025 0.007401 -vn 0.390185 0.449038 0.803816 -v 0.028200 -0.017025 0.007401 -vn -0.726703 0.228850 0.647712 -v 0.022500 -0.016778 0.007289 -vn 0.390185 0.306733 0.868142 -v 0.028200 -0.016778 0.007289 -vn -0.726702 0.116096 0.677072 -v 0.022500 -0.016515 0.007221 -vn 0.390184 0.155606 0.907493 -v 0.028200 -0.016515 0.007221 -vn -0.726701 -0.000000 0.686954 -v 0.022500 -0.016245 0.007198 -vn 0.390185 -0.000000 0.920736 -v 0.028200 -0.016245 0.007198 -vn -0.726701 -0.116096 0.677073 -v 0.022500 -0.015975 0.007221 -vn 0.390184 -0.155606 0.907493 -v 0.028200 -0.015975 0.007221 -vn -0.726704 -0.228850 0.647711 -v 0.022500 -0.015712 0.007289 -vn 0.390185 -0.306733 0.868142 -v 0.028200 -0.015712 0.007289 -vn -0.726702 -0.335023 0.599720 -v 0.022500 -0.015465 0.007401 -vn 0.390184 -0.449038 0.803816 -v 0.028200 -0.015465 0.007401 -vn -0.726704 -0.431556 0.534472 -v 0.022500 -0.015240 0.007553 -vn 0.390185 -0.578425 0.716366 -v 0.028200 -0.015240 0.007553 -vn -0.726702 -0.515676 0.453853 -v 0.022500 -0.015044 0.007741 -vn 0.390184 -0.691171 0.608308 -v 0.028200 -0.015044 0.007741 -vn -0.726704 -0.584958 0.360174 -v 0.022500 -0.014883 0.007959 -vn 0.390185 -0.784034 0.482749 -v 0.028200 -0.014883 0.007959 -vn -0.726702 -0.637416 0.256134 -v 0.022500 -0.014760 0.008202 -vn 0.390184 -0.854342 0.343302 -v 0.028200 -0.014760 0.008202 -vn -0.726703 -0.671533 0.144726 -v 0.022500 -0.014681 0.008461 -vn 0.390185 -0.900071 0.193980 -v 0.028200 -0.014681 0.008461 -vn -0.726702 -0.686333 0.029156 -v 0.022500 -0.014646 0.008730 -vn 0.390184 -0.919907 0.039078 -v 0.028200 -0.014646 0.008730 -vn -0.726704 -0.681387 -0.087254 -v 0.022500 -0.014658 0.009001 -vn 0.390185 -0.913279 -0.116949 -v 0.028200 -0.014658 0.009001 -vn -0.726702 -0.656842 -0.201154 -v 0.022500 -0.014715 0.009267 -vn 0.390184 -0.880378 -0.269611 -v 0.028200 -0.014715 0.009267 -vn -0.726705 -0.613395 -0.309269 -v 0.022500 -0.014816 0.009518 -vn 0.390185 -0.822149 -0.414521 -v 0.028200 -0.014816 0.009518 -vn -0.726701 -0.552308 -0.408487 -v 0.022500 -0.014959 0.009749 -vn 0.390184 -0.740269 -0.547502 -v 0.028200 -0.014959 0.009749 -vn -0.726703 -0.475330 -0.495948 -v 0.022500 -0.015138 0.009953 -vn 0.390185 -0.637095 -0.664730 -v 0.028200 -0.015138 0.009953 -vn -0.726703 -0.384675 -0.569147 -v 0.022500 -0.015349 0.010124 -vn 0.390185 -0.515588 -0.762840 -v 0.028200 -0.015349 0.010124 -vn -0.726701 -0.282958 -0.625971 -v 0.022500 -0.015586 0.010256 -vn 0.390184 -0.379255 -0.839001 -v 0.028200 -0.015586 0.010256 -vn -0.726704 -0.173097 -0.664785 -v 0.022500 -0.015842 0.010346 -vn 0.390185 -0.232006 -0.891027 -v 0.028200 -0.015842 0.010346 -vn -0.726702 -0.058256 -0.684478 -v 0.022500 -0.016109 0.010392 -vn 0.390184 -0.078082 -0.917420 -v 0.028200 -0.016109 0.010392 -vn -0.726702 0.058256 -0.684478 -v 0.022500 -0.016381 0.010392 -vn 0.390185 0.078082 -0.917420 -v 0.028200 -0.016381 0.010392 -vn -0.726704 0.173097 -0.664785 -v 0.022500 -0.016648 0.010346 -vn 0.390185 0.232006 -0.891027 -v 0.028200 -0.016648 0.010346 -vn -0.726702 0.282957 -0.625971 -v 0.022500 -0.016904 0.010256 -vn 0.390184 0.379252 -0.839002 -v 0.028200 -0.016904 0.010256 -vn -0.726183 0.383725 -0.570450 -v 0.022500 -0.017141 0.010124 -vn 0.390140 0.515571 -0.762874 -v 0.028200 -0.017141 0.010124 -vn 0.390139 0.637133 -0.664720 -v 0.028200 -0.017352 0.009953 -vn 0.390184 0.740270 -0.547501 -v 0.028200 -0.017531 0.009749 -vn 0.390185 0.822148 -0.414522 -v 0.028200 -0.017674 0.009518 -vn 0.756259 -0.652915 0.042116 -v -0.014912 0.013328 0.023128 -vn 0.770381 -0.637497 0.010533 -v -0.015643 0.012462 0.023465 -vn 0.717410 -0.696228 -0.024289 -v -0.014621 0.013646 0.021932 -vn 0.705998 -0.708205 0.003454 -v -0.014142 0.014142 0.022774 -vn 0.709034 -0.705167 -0.003083 -v -0.014142 0.014142 0.021213 -vn 0.656582 -0.753270 0.038528 -v -0.013328 0.014912 0.023128 -vn 0.678921 -0.733905 -0.021186 -v -0.013169 0.015052 0.022578 -vn 0.630444 -0.776215 0.005510 -v -0.012462 0.015643 0.023465 -vn 0.560614 -0.000928 -0.828076 -v 0.032500 -0.028098 -0.032500 -vn 0.560625 0.000000 -0.828070 -v 0.032500 -0.020310 -0.032500 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.020310 0.005349 -vn 0.769189 -0.125335 -0.626610 -v 0.032500 -0.029464 -0.032360 -vn 0.754667 -0.092130 -0.649607 -v 0.032500 -0.029104 -0.032425 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.030088 0.005349 -vn 0.735414 -0.058752 -0.675066 -v 0.032500 -0.028772 -0.032467 -vn 0.866839 -0.308796 -0.391453 -v 0.032500 -0.031485 -0.031440 -vn 0.861829 -0.290987 -0.415424 -v 0.032500 -0.031244 -0.031622 -vn 0.560631 -0.828065 -0.000711 -v 0.032500 -0.032500 -0.029500 -vn 0.560628 -0.828068 -0.000000 -v 0.032500 -0.032500 0.005349 -vn 0.850625 -0.271925 -0.449993 -v 0.032500 -0.031162 -0.031677 -vn 0.823616 -0.229808 -0.518503 -v 0.032500 -0.030642 -0.031968 -vn 0.798819 -0.176481 -0.575102 -v 0.032500 -0.030088 -0.032191 -vn 0.879979 -0.324680 -0.346727 -v 0.032500 -0.031686 -0.031261 -vn 0.909829 -0.413735 -0.032157 -v 0.032500 -0.032486 -0.029740 -vn 0.916163 -0.390045 -0.092247 -v 0.032500 -0.032449 -0.029963 -vn 0.908991 -0.395141 -0.132663 -v 0.032500 -0.032393 -0.030169 -vn 0.911207 -0.376214 -0.167822 -v 0.032500 -0.032299 -0.030412 -vn 0.888813 -0.341064 -0.306083 -v 0.032500 -0.031867 -0.031072 -vn 0.905747 -0.370071 -0.206566 -v 0.032500 -0.032239 -0.030535 -vn 0.897342 -0.357488 -0.258804 -v 0.032500 -0.032057 -0.030833 -vn 0.845399 -0.262261 0.465318 -v 0.032500 -0.030965 0.031799 -vn 0.857102 -0.285270 0.428949 -v 0.032500 -0.031243 0.031623 -vn 0.560618 -0.828074 0.001212 -v 0.032500 -0.032500 0.029500 -vn 0.861479 -0.304862 0.406095 -v 0.032500 -0.031366 0.031534 -vn 0.878140 -0.319695 0.355901 -v 0.032500 -0.031688 0.031260 -vn 0.883874 -0.335466 0.325929 -v 0.032500 -0.031731 0.031218 -vn 0.895346 -0.352497 0.272214 -v 0.032500 -0.032043 0.030852 -vn 0.902465 -0.371494 0.218060 -v 0.032500 -0.032175 0.030649 -vn 0.907901 -0.376650 0.183985 -v 0.032500 -0.032288 0.030436 -vn 0.905638 -0.403320 0.130968 -v 0.032500 -0.032378 0.030213 -vn 0.909407 -0.401980 0.106724 -v 0.032500 -0.032445 0.029980 -vn 0.818597 -0.573223 0.036249 -v 0.032500 -0.032486 0.029741 -vn 0.735440 -0.058723 0.675041 -v 0.032500 -0.028772 0.032467 -vn 0.749860 -0.103633 0.653430 -v 0.032500 -0.029109 0.032425 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.030088 0.022299 -vn 0.769138 -0.122061 0.627318 -v 0.032500 -0.029464 0.032360 -vn 0.797515 -0.176777 0.576818 -v 0.032500 -0.030088 0.032191 -vn 0.789759 -0.228257 0.569368 -v 0.032500 -0.030536 0.032017 -vn 0.830275 0.231346 0.507072 -v 0.032500 0.030715 0.031933 -vn 0.815865 0.205491 0.540497 -v 0.032500 0.030254 0.032132 -vn 0.560628 0.828068 0.000000 -v 0.032500 0.032500 0.022299 -vn 0.908929 0.393921 0.136656 -v 0.032500 0.032375 0.030224 -vn 0.917458 0.386624 0.093775 -v 0.032500 0.032453 0.029947 -vn 0.560635 0.828062 0.001090 -v 0.032500 0.032500 0.029500 -vn 0.914051 0.400434 0.064521 -v 0.032500 0.032468 0.029866 -vn 0.801008 0.173667 0.572911 -v 0.032500 0.030121 0.032179 -vn 0.782767 0.142799 0.605709 -v 0.032500 0.029549 0.032341 -vn 0.769837 0.116395 0.627538 -v 0.032500 0.029470 0.032359 -vn 0.911121 0.374941 0.171110 -v 0.032500 0.032299 0.030412 -vn 0.904986 0.369522 0.210840 -v 0.032500 0.032226 0.030560 -vn 0.893954 0.355903 0.272358 -v 0.032500 0.032028 0.030873 -vn 0.886039 0.337941 0.317380 -v 0.032500 0.031792 0.031155 -vn 0.881314 0.323362 0.344561 -v 0.032500 0.031688 0.031260 -vn 0.868226 0.309903 0.387485 -v 0.032500 0.031525 0.031407 -vn 0.854808 0.286746 0.432528 -v 0.032500 0.031231 0.031631 -vn 0.844719 0.262117 0.466630 -v 0.032500 0.030919 0.031825 -vn 0.928894 -0.319329 -0.187575 -v 0.032500 0.013705 -0.001569 -vn 0.929329 -0.341854 -0.139584 -v 0.032500 0.014520 -0.003205 -vn 0.560630 0.828066 0.000000 -v 0.032500 0.032500 0.005349 -vn 0.927510 -0.358207 -0.106835 -v 0.032500 0.014826 -0.004106 -vn 0.926728 -0.366819 -0.081360 -v 0.032500 0.014973 -0.004688 -vn 0.927154 -0.370632 -0.054931 -v 0.032500 0.015082 -0.005261 -vn 0.926692 -0.360971 0.104606 -v 0.032500 0.014825 -0.009397 -vn 0.927304 -0.351158 0.129594 -v 0.032500 0.014617 -0.010037 -vn 0.560620 0.828071 -0.001847 -v 0.032500 0.032500 -0.029500 -vn 0.928368 -0.334679 0.161628 -v 0.032500 0.014255 -0.010910 -vn 0.926795 -0.319723 0.197047 -v 0.032500 0.013497 -0.012259 -vn 0.926818 -0.272144 -0.258740 -v 0.032500 0.012273 0.000314 -vn 0.925811 -0.253704 -0.280195 -v 0.032500 0.011271 0.001280 -vn 0.926610 -0.235983 -0.292756 -v 0.032500 0.011188 0.001352 -vn 0.926642 -0.288823 -0.240657 -v 0.032500 0.012694 -0.000164 -vn 0.927086 -0.303182 -0.220436 -v 0.032500 0.013156 -0.000751 -vn 0.929156 -0.369501 -0.011752 -v 0.032500 0.015190 -0.006321 -vn 0.930570 -0.363845 0.040702 -v 0.032500 0.015133 -0.007875 -vn 0.928202 -0.364462 0.074890 -v 0.032500 0.014973 -0.008815 -vn 0.926520 -0.215617 -0.308336 -v 0.032500 0.009790 0.002402 -vn 1.000000 0.000000 0.000000 -v 0.032500 0.010153 0.005349 -vn 0.926551 -0.196687 -0.320652 -v 0.032500 0.009669 0.002481 -vn 0.926240 -0.275811 0.256921 -v 0.032500 0.012317 -0.013766 -vn 0.855279 0.286131 -0.432004 -v 0.032500 0.031226 -0.031634 -vn 0.867953 0.309496 -0.388419 -v 0.032500 0.031521 -0.031411 -vn 0.927083 -0.290408 0.237025 -v 0.032500 0.012678 -0.013356 -vn 0.881562 0.323011 -0.344257 -v 0.032500 0.031688 -0.031260 -vn 0.886159 0.336942 -0.318107 -v 0.032500 0.031790 -0.031158 -vn 0.770193 0.113080 -0.627707 -v 0.032500 0.029470 -0.032359 -vn 0.739486 0.071277 -0.669387 -v 0.032500 0.028830 -0.032461 -vn 0.926748 -0.257167 0.273867 -v 0.032500 0.011663 -0.014426 -vn 0.560618 0.000982 -0.828074 -v 0.032500 0.028098 -0.032500 -vn 0.782297 0.144134 -0.606001 -v 0.032500 0.029546 -0.032342 -vn 0.799739 0.172319 -0.575085 -v 0.032500 0.030121 -0.032179 -vn 0.815598 0.205345 -0.540956 -v 0.032500 0.030244 -0.032135 -vn 0.914762 0.390909 -0.101986 -v 0.032500 0.032453 -0.029947 -vn 0.905669 0.403458 -0.130328 -v 0.032500 0.032374 -0.030227 -vn 0.911427 0.374842 -0.169689 -v 0.032500 0.032299 -0.030412 -vn 0.926438 -0.307039 0.217807 -v 0.032500 0.013429 -0.012361 -vn 0.895990 0.441639 -0.046449 -v 0.032500 0.032468 -0.029868 -vn 0.828173 0.230468 -0.510895 -v 0.032500 0.030715 -0.031933 -vn 0.844740 0.261495 -0.466942 -v 0.032500 0.030914 -0.031828 -vn 0.895068 0.355342 -0.269417 -v 0.032500 0.032026 -0.030876 -vn 0.904571 0.369314 -0.212977 -v 0.032500 0.032224 -0.030563 -vn 0.927320 0.373398 -0.025523 -v 0.032500 -0.015184 -0.006201 -vn 0.928818 0.364670 -0.065669 -v 0.032500 -0.015070 -0.005187 -vn 0.925648 0.378373 -0.003155 -v 0.032500 -0.015200 -0.006750 -vn 0.927597 0.277280 0.250360 -v 0.032500 -0.012518 -0.013542 -vn 0.926373 0.296912 0.231683 -v 0.032500 -0.012941 -0.013031 -vn 0.927132 0.309982 0.210565 -v 0.032500 -0.013358 -0.012466 -vn 0.929175 0.324660 0.176720 -v 0.032500 -0.013899 -0.011599 -vn 0.929706 0.349827 -0.115184 -v 0.032500 -0.014689 -0.003669 -vn 0.928029 0.340726 -0.150561 -v 0.032500 -0.014283 -0.002650 -vn 0.926367 0.332684 -0.176539 -v 0.032500 -0.014048 -0.002175 -vn 0.927996 0.343417 0.144527 -v 0.032500 -0.014544 -0.010233 -vn 0.926468 0.356905 0.119481 -v 0.032500 -0.014648 -0.009951 -vn 0.927243 0.362483 0.093948 -v 0.032500 -0.014908 -0.009090 -vn 0.927162 0.318383 -0.197493 -v 0.032500 -0.013688 -0.001541 -vn 0.926408 0.305869 -0.219571 -v 0.032500 -0.013143 -0.000734 -vn 0.927534 0.287879 -0.238341 -v 0.032500 -0.012919 -0.000440 -vn 0.926486 0.369986 0.068804 -v 0.032500 -0.015043 -0.008466 -vn 0.928557 0.369034 0.039943 -v 0.032500 -0.015127 -0.007923 -vn 0.927510 0.373362 0.018058 -v 0.032500 -0.015197 -0.006981 -vn 0.928137 0.122098 0.351645 -v 0.032500 -0.006121 -0.017693 -vn 0.928677 0.166871 0.331229 -v 0.032500 -0.008246 -0.016796 -vn 0.560628 0.000000 -0.828068 -v 0.032500 -0.010155 -0.032500 -vn 0.926676 0.092600 0.364276 -v 0.032500 -0.004401 -0.018191 -vn 0.926761 0.197559 0.319506 -v 0.032500 -0.009627 -0.016008 -vn 0.927420 0.219864 0.302577 -v 0.032500 -0.010092 -0.015697 -vn 0.928521 0.251148 0.273446 -v 0.032500 -0.011580 -0.014504 -vn 0.560629 0.000000 -0.828067 -v 0.032500 0.000000 -0.032500 -vn 0.926969 0.022186 0.374482 -v 0.032500 -0.001463 -0.018645 -vn 0.926395 0.049810 0.373243 -v 0.032500 -0.002426 -0.018548 -vn 0.926652 0.070765 0.369200 -v 0.032500 -0.003822 -0.018318 -vn 0.560629 0.000000 -0.828067 -v 0.032500 0.010153 -0.032500 -vn 0.928288 -0.062220 0.366620 -v 0.032500 0.003241 -0.018427 -vn 0.928849 -0.017623 0.370039 -v 0.032500 0.000937 -0.018677 -vn 0.927619 -0.234273 0.290927 -v 0.032500 0.010964 -0.015039 -vn 0.926292 -0.209656 0.313093 -v 0.032500 0.009663 -0.015984 -vn 0.927097 -0.152314 0.342479 -v 0.032500 0.007480 -0.017160 -vn 0.926206 -0.126033 0.355327 -v 0.032500 0.006113 -0.017696 -vn 0.926789 -0.101485 0.361613 -v 0.032500 0.005445 -0.017911 -vn 0.926013 -0.194111 0.323761 -v 0.032500 0.009293 -0.016216 -vn 0.927139 -0.180812 0.328207 -v 0.032500 0.008869 -0.016464 -vn 0.926528 -0.111380 -0.359361 -v 0.032500 0.005515 0.004390 -vn 0.926981 -0.131802 -0.351190 -v 0.032500 0.006542 0.004042 -vn 0.926318 -0.154625 -0.343550 -v 0.032500 0.007708 0.003557 -vn 0.926906 -0.175295 -0.331839 -v 0.032500 0.008274 0.003282 -vn 0.925968 -0.047652 -0.374583 -v 0.032500 0.002713 0.005009 -vn 0.926543 -0.067649 -0.370057 -v 0.032500 0.003197 0.004934 -vn 0.926650 -0.089160 -0.365199 -v 0.032500 0.004673 0.004624 -vn 0.925624 -0.023009 -0.377744 -v 0.032500 0.000827 0.005182 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.000000 0.005349 -vn 0.924932 -0.009406 -0.380017 -v 0.032500 0.000643 0.005189 -vn 0.928887 0.262065 -0.261708 -v 0.032500 -0.011962 0.000636 -vn 0.929123 0.222940 -0.295005 -v 0.032500 -0.010540 0.001872 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.010155 0.005349 -vn 0.926809 0.199736 -0.318009 -v 0.032500 -0.009265 0.002733 -vn 0.927097 0.177486 -0.330136 -v 0.032500 -0.008798 0.003004 -vn 0.926592 0.157052 -0.341705 -v 0.032500 -0.007499 0.003651 -vn 0.926979 0.135387 -0.349828 -v 0.032500 -0.006916 0.003897 -vn 0.926529 0.114409 -0.358406 -v 0.032500 -0.005586 0.004368 -vn 0.926729 0.092127 -0.364261 -v 0.032500 -0.004831 0.004583 -vn 0.926698 0.071709 -0.368903 -v 0.032500 -0.003546 0.004872 -vn 0.926186 0.050044 -0.373731 -v 0.032500 -0.002598 0.005025 -vn 0.926428 0.028035 -0.375426 -v 0.032500 -0.001465 0.005145 -vn 0.926260 0.006950 -0.376821 -v 0.032500 -0.000264 0.005198 -vn 0.931110 0.121509 0.343904 -v 0.032500 0.015141 0.005687 -vn 0.931111 0.061640 0.359490 -v 0.032500 0.015682 0.005546 -vn 0.931113 0.000001 0.364732 -v 0.032500 0.016240 0.005498 -vn 0.931111 0.325681 -0.164205 -v 0.032500 0.013293 0.010284 -vn 0.931112 0.293244 -0.216883 -v 0.032500 0.013587 0.010760 -vn 1.000000 0.000000 0.000000 -v 0.032500 0.010153 0.022299 -vn 0.931111 0.252374 -0.263323 -v 0.032500 0.013957 0.011181 -vn 0.931111 0.204243 -0.302188 -v 0.032500 0.014392 0.011532 -vn 0.931110 0.150236 -0.332360 -v 0.032500 0.014881 0.011805 -vn 0.931110 -0.121509 0.343904 -v 0.032500 0.025469 0.005687 -vn 0.931110 -0.061642 0.359491 -v 0.032500 0.024928 0.005546 -vn 0.931113 0.000001 0.364732 -v 0.032500 0.024370 0.005498 -vn 0.931111 0.061640 0.359490 -v 0.032500 0.023812 0.005546 -vn 0.931110 0.121509 0.343904 -v 0.032500 0.023271 0.005687 -vn 0.931112 0.177880 0.318418 -v 0.032500 0.022761 0.005917 -vn 0.931110 -0.061642 0.359491 -v 0.032500 0.016798 0.005546 -vn 0.931110 0.229135 0.283779 -v 0.032500 0.022297 0.006231 -vn 0.931110 -0.121510 0.343904 -v 0.032500 0.017339 0.005687 -vn 0.931110 0.030933 -0.363424 -v 0.032500 0.024090 0.012086 -vn 0.931111 0.091905 -0.352966 -v 0.032500 0.023538 0.011992 -vn 0.931110 -0.030932 -0.363424 -v 0.032500 0.024650 0.012086 -vn 0.931111 -0.091907 -0.352966 -v 0.032500 0.025202 0.011992 -vn 0.931110 -0.150236 -0.332360 -v 0.032500 0.025729 0.011805 -vn 0.931112 0.177880 0.318417 -v 0.032500 0.014631 0.005917 -vn 0.931109 0.229136 0.283782 -v 0.032500 0.014167 0.006231 -vn 0.931111 0.273797 0.240971 -v 0.032500 0.013763 0.006618 -vn 0.931110 0.310584 0.191235 -v 0.032500 0.013430 0.007068 -vn 0.931111 0.338434 0.135994 -v 0.032500 0.013178 0.007568 -vn 0.931110 0.356551 0.076843 -v 0.032500 0.013014 0.008103 -vn 0.931112 0.364406 0.015479 -v 0.032500 0.012943 0.008658 -vn 0.931111 0.361783 -0.046328 -v 0.032500 0.012967 0.009217 -vn 0.931111 0.348748 -0.106803 -v 0.032500 0.013085 0.009764 -vn 0.931112 0.293244 -0.216883 -v 0.032500 0.021717 0.010760 -vn 0.931110 0.252377 -0.263324 -v 0.032500 0.022087 0.011181 -vn 0.931111 -0.325682 -0.164205 -v 0.032500 0.019187 0.010284 -vn 0.931111 -0.204243 -0.302188 -v 0.032500 0.026218 0.011532 -vn 0.931110 -0.252376 -0.263325 -v 0.032500 0.026653 0.011181 -vn 0.931112 -0.293245 -0.216883 -v 0.032500 0.027023 0.010760 -vn 0.931112 -0.364405 0.015481 -v 0.032500 0.027667 0.008658 -vn 0.931109 -0.356556 0.076842 -v 0.032500 0.027596 0.008103 -vn 0.931111 -0.338433 0.135995 -v 0.032500 0.027432 0.007568 -vn 0.931109 -0.310589 0.191236 -v 0.032500 0.027180 0.007068 -vn 0.931111 -0.273796 0.240972 -v 0.032500 0.026847 0.006618 -vn 0.931111 0.091905 -0.352966 -v 0.032500 0.015408 0.011992 -vn 0.931110 0.030932 -0.363424 -v 0.032500 0.015960 0.012086 -vn 0.931110 -0.030932 -0.363424 -v 0.032500 0.016520 0.012086 -vn 0.931111 -0.091907 -0.352966 -v 0.032500 0.017072 0.011992 -vn 0.931110 -0.150236 -0.332360 -v 0.032500 0.017599 0.011805 -vn 0.931110 -0.204244 -0.302190 -v 0.032500 0.018088 0.011532 -vn 0.931111 -0.325681 -0.164205 -v 0.032500 0.027317 0.010284 -vn 0.931111 -0.348748 -0.106802 -v 0.032500 0.027525 0.009764 -vn 0.931110 -0.361783 -0.046329 -v 0.032500 0.027643 0.009217 -vn 0.931109 -0.229138 0.283781 -v 0.032500 0.026443 0.006231 -vn 0.931111 -0.177879 0.318419 -v 0.032500 0.025979 0.005917 -vn 0.931111 0.325682 -0.164206 -v 0.032500 0.021423 0.010284 -vn 0.931111 -0.273797 0.240972 -v 0.032500 0.018717 0.006618 -vn 0.931110 -0.229136 0.283779 -v 0.032500 0.018313 0.006231 -vn 0.931111 -0.177879 0.318419 -v 0.032500 0.017849 0.005917 -vn 0.931110 -0.252377 -0.263325 -v 0.032500 0.018523 0.011181 -vn 0.931111 -0.293247 -0.216885 -v 0.032500 0.018893 0.010760 -vn 0.931111 0.150235 -0.332359 -v 0.032500 0.023011 0.011805 -vn 0.931111 0.204243 -0.302187 -v 0.032500 0.022522 0.011532 -vn 0.931111 0.273797 0.240971 -v 0.032500 0.021893 0.006618 -vn 0.931111 -0.338434 0.135995 -v 0.032500 0.019302 0.007568 -vn 0.931110 -0.310585 0.191234 -v 0.032500 0.019050 0.007068 -vn 0.931110 0.310584 0.191235 -v 0.032500 0.021560 0.007068 -vn 0.931111 0.338434 0.135994 -v 0.032500 0.021308 0.007568 -vn 0.931110 0.356551 0.076843 -v 0.032500 0.021144 0.008103 -vn 0.931110 0.348752 -0.106804 -v 0.032500 0.021215 0.009764 -vn 0.931110 -0.348751 -0.106805 -v 0.032500 0.019395 0.009764 -vn 0.931111 0.361782 -0.046328 -v 0.032500 0.021097 0.009217 -vn 0.931112 -0.361779 -0.046327 -v 0.032500 0.019513 0.009217 -vn 0.931111 0.364407 0.015480 -v 0.032500 0.021073 0.008658 -vn 0.931112 -0.364406 0.015480 -v 0.032500 0.019537 0.008658 -vn 0.931111 -0.356551 0.076842 -v 0.032500 0.019466 0.008103 -vn 0.931112 -0.177878 0.318418 -v 0.032500 0.005674 0.005917 -vn 0.931110 -0.121510 0.343903 -v 0.032500 0.005164 0.005687 -vn 0.931110 -0.061642 0.359491 -v 0.032500 0.004623 0.005546 -vn 0.931112 0.000001 0.364732 -v 0.032500 0.004065 0.005498 -vn 0.931111 0.061640 0.359489 -v 0.032500 0.003507 0.005546 -vn 0.931110 0.121509 0.343904 -v 0.032500 0.002966 0.005687 -vn 0.931111 0.177880 0.318419 -v 0.032500 0.002456 0.005917 -vn 0.931110 0.229135 0.283779 -v 0.032500 0.001992 0.006231 -vn 0.931111 0.273797 0.240971 -v 0.032500 0.001588 0.006618 -vn 0.931111 0.325682 -0.164206 -v 0.032500 0.001118 0.010284 -vn 0.931112 0.293244 -0.216883 -v 0.032500 0.001412 0.010760 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.000000 0.022299 -vn 0.931110 0.310584 0.191235 -v 0.032500 0.001255 0.007068 -vn 0.931111 0.338434 0.135994 -v 0.032500 0.001003 0.007568 -vn 0.931110 0.356551 0.076843 -v 0.032500 0.000839 0.008103 -vn 0.931111 0.364407 0.015480 -v 0.032500 0.000768 0.008658 -vn 0.931113 0.361778 -0.046328 -v 0.032500 0.000792 0.009217 -vn 0.931110 0.348751 -0.106803 -v 0.032500 0.000910 0.009764 -vn 0.931111 0.252376 -0.263324 -v 0.032500 0.001782 0.011181 -vn 0.931110 0.204245 -0.302190 -v 0.032500 0.002217 0.011532 -vn 0.931111 0.150235 -0.332359 -v 0.032500 0.002706 0.011805 -vn 0.931111 0.091905 -0.352966 -v 0.032500 0.003233 0.011992 -vn 0.931110 0.030933 -0.363424 -v 0.032500 0.003785 0.012086 -vn 0.931110 -0.030932 -0.363425 -v 0.032500 0.004345 0.012086 -vn 0.931111 -0.091907 -0.352966 -v 0.032500 0.004897 0.011992 -vn 0.931112 -0.364406 0.015480 -v 0.032500 0.007362 0.008658 -vn 0.931111 -0.356551 0.076842 -v 0.032500 0.007291 0.008103 -vn 0.931111 -0.338434 0.135995 -v 0.032500 0.007127 0.007568 -vn 0.931110 -0.310585 0.191234 -v 0.032500 0.006875 0.007068 -vn 0.931111 -0.273796 0.240972 -v 0.032500 0.006542 0.006618 -vn 0.931109 -0.229138 0.283781 -v 0.032500 0.006138 0.006231 -vn 0.931110 -0.252376 -0.263325 -v 0.032500 0.006348 0.011181 -vn 0.931112 -0.293245 -0.216883 -v 0.032500 0.006718 0.010760 -vn 0.931110 -0.150236 -0.332360 -v 0.032500 0.005424 0.011805 -vn 0.931111 -0.204243 -0.302188 -v 0.032500 0.005913 0.011532 -vn 0.931111 -0.325681 -0.164205 -v 0.032500 0.007012 0.010284 -vn 0.931111 -0.348748 -0.106802 -v 0.032500 0.007220 0.009764 -vn 0.931110 -0.361783 -0.046329 -v 0.032500 0.007338 0.009217 -vn 0.931111 -0.356551 0.076842 -v 0.032500 -0.000839 0.008103 -vn 0.931111 -0.338434 0.135995 -v 0.032500 -0.001003 0.007568 -vn 0.931111 0.061640 0.359490 -v 0.032500 -0.004623 0.005546 -vn 0.931110 0.121509 0.343904 -v 0.032500 -0.005164 0.005687 -vn 0.931112 0.325679 -0.164205 -v 0.032500 -0.007012 0.010284 -vn 0.931111 0.293246 -0.216884 -v 0.032500 -0.006718 0.010760 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.010155 0.022299 -vn 0.931111 -0.252375 -0.263323 -v 0.032500 -0.001782 0.011181 -vn 0.931111 -0.293246 -0.216884 -v 0.032500 -0.001412 0.010760 -vn 0.931111 -0.325682 -0.164205 -v 0.032500 -0.001118 0.010284 -vn 0.931110 -0.310586 0.191235 -v 0.032500 -0.001255 0.007068 -vn 0.931111 -0.273798 0.240973 -v 0.032500 -0.001588 0.006618 -vn 0.931110 -0.229137 0.283780 -v 0.032500 -0.001992 0.006231 -vn 0.931112 0.000001 0.364732 -v 0.032500 -0.004065 0.005498 -vn 0.931110 -0.061642 0.359491 -v 0.032500 -0.003507 0.005546 -vn 0.931111 0.177880 0.318419 -v 0.032500 -0.005674 0.005917 -vn 0.931110 0.229135 0.283779 -v 0.032500 -0.006138 0.006231 -vn 0.931111 0.273798 0.240972 -v 0.032500 -0.006542 0.006618 -vn 0.931111 -0.091906 -0.352966 -v 0.032500 -0.003233 0.011992 -vn 0.931111 -0.150235 -0.332358 -v 0.032500 -0.002706 0.011805 -vn 0.931111 -0.204243 -0.302188 -v 0.032500 -0.002217 0.011532 -vn 0.931110 -0.348750 -0.106804 -v 0.032500 -0.000910 0.009764 -vn 0.931112 -0.361779 -0.046327 -v 0.032500 -0.000792 0.009217 -vn 0.931112 -0.364406 0.015480 -v 0.032500 -0.000768 0.008658 -vn 0.931112 -0.177878 0.318419 -v 0.032500 -0.002456 0.005917 -vn 0.931110 -0.121510 0.343904 -v 0.032500 -0.002966 0.005687 -vn 0.931110 0.310586 0.191236 -v 0.032500 -0.006875 0.007068 -vn 0.931111 0.338435 0.135994 -v 0.032500 -0.007127 0.007568 -vn 0.931110 0.356551 0.076843 -v 0.032500 -0.007291 0.008103 -vn 0.931111 0.364408 0.015480 -v 0.032500 -0.007362 0.008658 -vn 0.931112 0.361780 -0.046328 -v 0.032500 -0.007338 0.009217 -vn 0.931111 0.348749 -0.106803 -v 0.032500 -0.007220 0.009764 -vn 0.931111 0.252375 -0.263323 -v 0.032500 -0.006348 0.011181 -vn 0.931110 0.204244 -0.302189 -v 0.032500 -0.005913 0.011532 -vn 0.931110 0.150236 -0.332360 -v 0.032500 -0.005424 0.011805 -vn 0.931111 0.091905 -0.352966 -v 0.032500 -0.004897 0.011992 -vn 0.931110 0.030933 -0.363424 -v 0.032500 -0.004345 0.012086 -vn 0.931110 -0.030932 -0.363425 -v 0.032500 -0.003785 0.012086 -vn 0.931111 -0.338434 0.135995 -v 0.032500 -0.013183 0.007568 -vn 0.931111 -0.356551 0.076842 -v 0.032500 -0.013019 0.008103 -vn 0.931111 -0.364408 0.015480 -v 0.032500 -0.012948 0.008658 -vn 0.931112 0.000001 0.364732 -v 0.032500 -0.016245 0.005498 -vn 0.931111 0.061640 0.359490 -v 0.032500 -0.016803 0.005546 -vn 0.931111 -0.252376 -0.263324 -v 0.032500 -0.013962 0.011181 -vn 0.931112 -0.293245 -0.216883 -v 0.032500 -0.013592 0.010760 -vn 0.931110 -0.310586 0.191235 -v 0.032500 -0.013435 0.007068 -vn 0.931110 -0.273798 0.240973 -v 0.032500 -0.013768 0.006618 -vn 0.931110 -0.229136 0.283779 -v 0.032500 -0.014172 0.006231 -vn 0.931110 -0.061642 0.359491 -v 0.032500 -0.015687 0.005546 -vn 0.931110 0.121509 0.343904 -v 0.032500 -0.017344 0.005687 -vn 0.931111 0.177880 0.318420 -v 0.032500 -0.017854 0.005917 -vn 0.931110 0.229135 0.283780 -v 0.032500 -0.018318 0.006231 -vn 0.931111 -0.325681 -0.164205 -v 0.032500 -0.013298 0.010284 -vn 0.931111 -0.348748 -0.106803 -v 0.032500 -0.013090 0.009764 -vn 0.931112 -0.361780 -0.046328 -v 0.032500 -0.012972 0.009217 -vn 0.931111 0.273797 0.240971 -v 0.032500 -0.018722 0.006618 -vn 0.931110 0.310586 0.191235 -v 0.032500 -0.019055 0.007068 -vn 0.931111 0.338435 0.135995 -v 0.032500 -0.019307 0.007568 -vn 0.931110 0.356551 0.076843 -v 0.032500 -0.019471 0.008103 -vn 0.931112 0.364406 0.015479 -v 0.032500 -0.019542 0.008658 -vn 0.931110 0.361784 -0.046328 -v 0.032500 -0.019518 0.009217 -vn 0.931112 -0.177878 0.318419 -v 0.032500 -0.014636 0.005917 -vn 0.931110 -0.121510 0.343904 -v 0.032500 -0.015146 0.005687 -vn 0.931111 0.348749 -0.106803 -v 0.032500 -0.019400 0.009764 -vn 1.000000 0.000000 0.000000 -v 0.032500 -0.020310 0.022299 -vn 0.931112 0.325680 -0.164205 -v 0.032500 -0.019192 0.010284 -vn 0.931112 0.293245 -0.216883 -v 0.032500 -0.018898 0.010760 -vn 0.931111 0.252376 -0.263324 -v 0.032500 -0.018528 0.011181 -vn 0.931111 0.204243 -0.302188 -v 0.032500 -0.018093 0.011532 -vn 0.931111 0.150235 -0.332359 -v 0.032500 -0.017604 0.011805 -vn 0.931111 -0.091906 -0.352967 -v 0.032500 -0.015413 0.011992 -vn 0.931111 -0.150235 -0.332358 -v 0.032500 -0.014886 0.011805 -vn 0.931110 -0.204243 -0.302189 -v 0.032500 -0.014397 0.011532 -vn 0.931111 0.091905 -0.352966 -v 0.032500 -0.017077 0.011992 -vn 0.931110 0.030933 -0.363424 -v 0.032500 -0.016525 0.012086 -vn 0.931110 -0.030932 -0.363425 -v 0.032500 -0.015965 0.012086 -vn 0.740667 0.065493 0.668673 -v 0.032500 0.028829 0.032461 -vn 0.560623 0.000995 0.828071 -v 0.032500 0.028098 0.032500 -vn 0.560629 -0.000000 0.828067 -v 0.032500 0.010153 0.032500 -vn 0.560629 -0.000000 0.828067 -v 0.032500 -0.000000 0.032500 -vn 0.560629 -0.000000 0.828067 -v 0.032500 -0.010155 0.032500 -vn 0.560629 -0.000000 0.828067 -v 0.032500 -0.020310 0.032500 -vn 0.560617 -0.000906 0.828075 -v 0.032500 -0.028098 0.032500 -vn 0.931111 0.325681 -0.164206 -v 0.032500 -0.027322 0.010284 -vn 0.931111 0.293246 -0.216884 -v 0.032500 -0.027028 0.010760 -vn 0.931110 -0.348750 -0.106805 -v 0.032500 -0.021220 0.009764 -vn 0.931111 -0.361781 -0.046327 -v 0.032500 -0.021102 0.009217 -vn 0.931111 0.061640 0.359490 -v 0.032500 -0.024933 0.005546 -vn 0.931110 0.121509 0.343904 -v 0.032500 -0.025474 0.005687 -vn 0.931111 0.177880 0.318419 -v 0.032500 -0.025984 0.005917 -vn 0.931110 0.229135 0.283779 -v 0.032500 -0.026448 0.006231 -vn 0.931111 0.338435 0.135995 -v 0.032500 -0.027437 0.007568 -vn 0.931111 0.356549 0.076842 -v 0.032500 -0.027601 0.008103 -vn 0.931113 0.000001 0.364732 -v 0.032500 -0.024375 0.005498 -vn 0.931110 0.364409 0.015480 -v 0.032500 -0.027672 0.008658 -vn 0.931111 0.361781 -0.046328 -v 0.032500 -0.027648 0.009217 -vn 0.931110 0.348750 -0.106803 -v 0.032500 -0.027530 0.009764 -vn 0.931111 -0.364408 0.015480 -v 0.032500 -0.021078 0.008658 -vn 0.931111 0.252374 -0.263323 -v 0.032500 -0.026658 0.011181 -vn 0.931111 0.204243 -0.302188 -v 0.032500 -0.026223 0.011532 -vn 0.931110 0.150236 -0.332360 -v 0.032500 -0.025734 0.011805 -vn 0.931111 -0.356551 0.076842 -v 0.032500 -0.021149 0.008103 -vn 0.931111 -0.338435 0.135995 -v 0.032500 -0.021313 0.007568 -vn 0.931110 -0.310585 0.191234 -v 0.032500 -0.021565 0.007068 -vn 0.931111 0.273797 0.240972 -v 0.032500 -0.026852 0.006618 -vn 0.931111 0.310585 0.191234 -v 0.032500 -0.027185 0.007068 -vn 0.931111 0.091905 -0.352967 -v 0.032500 -0.025207 0.011992 -vn 0.931110 0.030933 -0.363424 -v 0.032500 -0.024655 0.012086 -vn 0.931110 -0.030932 -0.363425 -v 0.032500 -0.024095 0.012086 -vn 0.931111 -0.091907 -0.352966 -v 0.032500 -0.023543 0.011992 -vn 0.931110 -0.150236 -0.332360 -v 0.032500 -0.023016 0.011805 -vn 0.931111 -0.204243 -0.302188 -v 0.032500 -0.022527 0.011532 -vn 0.931111 -0.252375 -0.263322 -v 0.032500 -0.022092 0.011181 -vn 0.931111 -0.293247 -0.216885 -v 0.032500 -0.021722 0.010760 -vn 0.931111 -0.325682 -0.164205 -v 0.032500 -0.021428 0.010284 -vn 0.931111 -0.273797 0.240972 -v 0.032500 -0.021898 0.006618 -vn 0.931110 -0.229136 0.283779 -v 0.032500 -0.022302 0.006231 -vn 0.931111 -0.177879 0.318419 -v 0.032500 -0.022766 0.005917 -vn 0.931110 -0.121510 0.343903 -v 0.032500 -0.023276 0.005687 -vn 0.931110 -0.061642 0.359491 -v 0.032500 -0.023817 0.005546 -vn 0.560629 -0.828067 -0.000000 -v 0.032500 -0.032500 0.022299 -vn -0.404128 -0.914697 -0.003087 -v 0.021811 -0.028224 0.001853 -vn -0.404201 -0.914669 0.001679 -v 0.021864 -0.028245 -0.001012 -vn -0.403854 -0.914801 0.006437 -v 0.021559 -0.028124 -0.003863 -vn -0.403083 -0.915095 0.011156 -v 0.020901 -0.027861 -0.006657 -vn -0.401893 -0.915550 0.015817 -v 0.019899 -0.027460 -0.009351 -vn -0.399108 -0.916644 -0.021828 -v 0.018128 -0.026751 0.012599 -vn -0.401400 -0.915743 -0.017113 -v 0.019548 -0.027319 0.010103 -vn -0.402738 -0.915230 -0.012516 -v 0.020645 -0.027758 0.007453 -vn -0.403628 -0.914890 -0.007828 -v 0.021403 -0.028061 0.004689 -vn 0.214828 -0.972417 0.090848 -v 0.032467 -0.032487 0.029941 -vn 0.211133 -0.961036 0.178417 -v 0.032371 -0.032448 0.030367 -vn -0.356134 -0.933957 -0.029880 -v 0.016567 -0.026127 0.014710 -vn 0.189395 -0.964489 0.184095 -v 0.032350 -0.032440 0.030432 -vn 0.200010 -0.956540 0.212194 -v 0.032335 -0.032434 0.030478 -vn 0.197241 -0.958878 -0.204082 -v 0.032335 -0.032434 -0.030478 -vn 0.193563 -0.964826 -0.177890 -v 0.032357 -0.032443 -0.030411 -vn -0.356001 -0.933999 0.030137 -v 0.016567 -0.026127 -0.014710 -vn 0.215687 -0.969577 -0.115760 -v 0.032448 -0.032479 -0.030055 -vn -0.400280 -0.916166 0.020371 -v 0.018567 -0.026927 -0.011902 -vn -0.396400 -0.917731 0.025258 -v 0.016924 -0.026269 -0.014270 -vn 0.222213 -0.973021 -0.062053 -v 0.032488 -0.032495 -0.029764 -vn 0.208797 -0.973890 -0.089114 -v 0.032466 -0.032486 -0.029947 -vn -0.001678 -0.914673 -0.404192 -v 0.001012 -0.028245 0.021864 -vn 0.001145 -0.707106 0.707107 -v 0.028098 -0.032500 0.032500 -vn 0.003087 -0.914701 -0.404120 -v -0.001853 -0.028224 0.021811 -vn -0.001182 -0.707105 0.707108 -v -0.028098 -0.032500 0.032500 -vn 0.007828 -0.914887 -0.403635 -v -0.004689 -0.028061 0.021403 -vn -0.006436 -0.914804 -0.403846 -v 0.003863 -0.028124 0.021559 -vn -0.011158 -0.915097 -0.403079 -v 0.006657 -0.027861 0.020901 -vn -0.015813 -0.915551 -0.401890 -v 0.009351 -0.027460 0.019899 -vn 0.021820 -0.916649 -0.399098 -v -0.012599 -0.026751 0.018128 -vn 0.017119 -0.915737 -0.401413 -v -0.010103 -0.027319 0.019548 -vn 0.012515 -0.915232 -0.402734 -v -0.007453 -0.027758 0.020645 -vn -0.136950 -0.874785 0.464754 -v -0.029534 -0.032443 0.032358 -vn -0.167216 -0.882571 0.439439 -v -0.029662 -0.032433 0.032332 -vn 0.029838 -0.933975 -0.356090 -v -0.014710 -0.026127 0.016567 -vn -0.184110 -0.884784 0.428089 -v -0.029834 -0.032417 0.032293 -vn -0.203372 -0.890585 0.406816 -v -0.030308 -0.032366 0.032164 -vn -0.020362 -0.916171 -0.400270 -v 0.011902 -0.026927 0.018567 -vn -0.025251 -0.917728 -0.396405 -v 0.014270 -0.026269 0.016924 -vn 0.079824 -0.853746 0.514535 -v 0.028845 -0.032485 0.032461 -vn -0.030081 -0.934015 -0.355966 -v 0.014710 -0.026127 0.016567 -vn 0.147478 -0.872649 0.465547 -v 0.029538 -0.032443 0.032357 -vn 0.196545 -0.890720 0.409863 -v 0.030307 -0.032366 0.032164 -vn -0.097341 -0.852512 0.513564 -v -0.028878 -0.032483 0.032458 -vn 0.001677 -0.914673 0.404191 -v -0.001012 -0.028245 -0.021864 -vn -0.001160 -0.707099 -0.707113 -v -0.028098 -0.032500 -0.032500 -vn -0.003087 -0.914700 0.404122 -v 0.001853 -0.028224 -0.021811 -vn 0.001179 -0.707104 -0.707108 -v 0.028098 -0.032500 -0.032500 -vn -0.007828 -0.914886 0.403636 -v 0.004689 -0.028061 -0.021403 -vn 0.006436 -0.914805 0.403845 -v -0.003863 -0.028124 -0.021559 -vn 0.011159 -0.915096 0.403081 -v -0.006657 -0.027861 -0.020901 -vn 0.015812 -0.915551 0.401890 -v -0.009351 -0.027460 -0.019899 -vn -0.021820 -0.916649 0.399097 -v 0.012599 -0.026751 -0.018128 -vn -0.017118 -0.915738 0.401411 -v 0.010103 -0.027319 -0.019548 -vn -0.012515 -0.915232 0.402732 -v 0.007453 -0.027758 -0.020645 -vn 0.136943 -0.874798 -0.464732 -v 0.029534 -0.032443 -0.032358 -vn 0.167198 -0.882529 -0.439530 -v 0.029662 -0.032433 -0.032332 -vn -0.029838 -0.933974 0.356093 -v 0.014710 -0.026127 -0.016567 -vn 0.184160 -0.884806 -0.428023 -v 0.029834 -0.032417 -0.032293 -vn 0.203337 -0.890603 -0.406792 -v 0.030307 -0.032366 -0.032164 -vn 0.020363 -0.916170 0.400273 -v -0.011902 -0.026927 -0.018567 -vn 0.025253 -0.917728 0.396405 -v -0.014270 -0.026269 -0.016924 -vn -0.079819 -0.853741 -0.514543 -v -0.028845 -0.032484 -0.032461 -vn 0.030084 -0.934014 0.355967 -v -0.014710 -0.026127 -0.016567 -vn -0.147474 -0.872635 -0.465575 -v -0.029539 -0.032443 -0.032357 -vn -0.196573 -0.890706 -0.409881 -v -0.030308 -0.032366 -0.032164 -vn 0.097345 -0.852498 -0.513586 -v 0.028878 -0.032483 -0.032458 -vn 0.404164 -0.914685 -0.001674 -v -0.021864 -0.028245 0.001012 -vn -0.707091 -0.707121 0.001136 -v -0.032500 -0.032500 0.029500 -vn 0.404139 -0.914692 0.003086 -v -0.021811 -0.028224 -0.001853 -vn -0.707116 -0.707096 -0.001101 -v -0.032500 -0.032500 -0.029500 -vn 0.403652 -0.914879 0.007834 -v -0.021403 -0.028061 -0.004689 -vn 0.403818 -0.914817 -0.006428 -v -0.021559 -0.028124 0.003863 -vn 0.403089 -0.915093 -0.011167 -v -0.020901 -0.027861 0.006657 -vn 0.401904 -0.915545 -0.015821 -v -0.019899 -0.027460 0.009351 -vn 0.399080 -0.916657 0.021806 -v -0.018128 -0.026751 -0.012599 -vn 0.401423 -0.915733 0.017122 -v -0.019548 -0.027319 -0.010103 -vn 0.402747 -0.915226 0.012524 -v -0.020645 -0.027758 -0.007453 -vn -0.184419 -0.964609 -0.188464 -v -0.032350 -0.032440 -0.030432 -vn -0.196977 -0.958102 -0.207944 -v -0.032335 -0.032434 -0.030478 -vn 0.356074 -0.933982 0.029810 -v -0.016567 -0.026127 -0.014710 -vn -0.201998 -0.965734 -0.162957 -v -0.032371 -0.032448 -0.030367 -vn -0.197397 -0.958153 0.207311 -v -0.032335 -0.032434 0.030478 -vn -0.191083 -0.965668 0.175988 -v -0.032357 -0.032443 0.030411 -vn 0.355946 -0.934023 -0.030052 -v -0.016567 -0.026127 0.014710 -vn -0.255766 -0.957821 0.131008 -v -0.032448 -0.032479 0.030055 -vn 0.400271 -0.916171 -0.020361 -v -0.018567 -0.026927 0.011902 -vn 0.396401 -0.917730 -0.025239 -v -0.016924 -0.026269 0.014270 -vn -0.452018 -0.891168 0.038722 -v -0.032488 -0.032495 0.029764 -vn -0.204031 -0.974905 0.089061 -v -0.032466 -0.032486 0.029947 -vn -0.204443 -0.974847 -0.088752 -v -0.032467 -0.032487 -0.029941 -vn -0.914652 0.404239 0.001672 -v -0.028245 -0.021864 -0.001012 -vn -0.914700 0.404121 -0.003092 -v -0.028224 -0.021811 0.001853 -vn -0.914888 0.403632 -0.007817 -v -0.028061 -0.021403 0.004689 -vn -0.914830 0.403788 0.006419 -v -0.028124 -0.021559 -0.003863 -vn -0.915106 0.403058 0.011155 -v -0.027861 -0.020901 -0.006657 -vn -0.915546 0.401903 0.015820 -v -0.027460 -0.019899 -0.009351 -vn -0.916643 0.399111 -0.021827 -v -0.026751 -0.018128 0.012599 -vn -0.915733 0.401422 -0.017121 -v -0.027319 -0.019548 0.010103 -vn -0.915248 0.402697 -0.012499 -v -0.027758 -0.020645 0.007453 -vn -0.964553 -0.184550 0.188626 -v -0.032440 -0.032350 0.030432 -vn -0.958160 -0.196799 0.207843 -v -0.032434 -0.032335 0.030478 -vn -0.934007 0.356012 -0.029770 -v -0.026127 -0.016567 0.014710 -vn -0.965719 -0.202045 0.162990 -v -0.032448 -0.032371 0.030367 -vn -0.958209 -0.197182 -0.207256 -v -0.032434 -0.032335 -0.030478 -vn -0.965650 -0.191276 -0.175878 -v -0.032443 -0.032357 -0.030411 -vn -0.934052 0.355871 0.030031 -v -0.026127 -0.016567 -0.014710 -vn -0.957723 -0.256109 -0.131052 -v -0.032479 -0.032448 -0.030055 -vn -0.916169 0.400274 0.020358 -v -0.026927 -0.018567 -0.011902 -vn -0.917731 0.396397 0.025271 -v -0.026269 -0.016924 -0.014270 -vn -0.891388 -0.451587 -0.038696 -v -0.032495 -0.032488 -0.029764 -vn -0.974695 -0.204952 -0.089248 -v -0.032487 -0.032466 -0.029947 -vn -0.974647 -0.205386 0.088772 -v -0.032487 -0.032467 0.029941 -vn -0.912953 0.002972 -0.408054 -v -0.028749 -0.001032 0.023122 -vn -0.707071 -0.001112 0.707142 -v -0.032500 -0.028098 0.032500 -vn -0.912879 0.000037 -0.408230 -v -0.028763 -0.000008 0.023157 -vn -0.707100 0.001193 0.707113 -v -0.032500 0.028098 0.032500 -vn -0.912938 -0.002884 -0.408089 -v -0.028749 0.001020 0.023123 -vn -0.913800 -0.010707 -0.406023 -v -0.028550 0.004039 0.022624 -vn -0.913413 -0.008281 -0.406950 -v -0.028645 0.003003 0.022862 -vn -0.913122 -0.005695 -0.407647 -v -0.028707 0.002057 0.023018 -vn -0.913157 0.005733 -0.407567 -v -0.028707 -0.002057 0.023018 -vn -0.913273 0.007885 -0.407273 -v -0.028638 -0.003088 0.022845 -vn -0.913458 0.009540 -0.406821 -v -0.028619 -0.003309 0.022799 -vn -0.914089 0.011573 -0.405349 -v -0.028506 -0.004438 0.022514 -vn -0.914658 0.013806 -0.403992 -v -0.028359 -0.005574 0.022146 -vn -0.915320 0.015716 -0.402420 -v -0.028177 -0.006724 0.021692 -vn -0.916264 -0.017843 -0.400178 -v -0.027863 0.008364 0.020907 -vn -0.915512 -0.016480 -0.401953 -v -0.028104 0.007137 0.021509 -vn -0.917028 -0.018828 -0.398379 -v -0.027598 0.009546 0.020246 -vn -0.914862 -0.014813 -0.403496 -v -0.028279 0.006104 0.021947 -vn -0.914283 -0.012905 -0.404871 -v -0.028428 0.005072 0.022319 -vn -0.916064 0.017231 -0.400662 -v -0.027959 -0.007895 0.021148 -vn -0.916824 0.018398 -0.398868 -v -0.027715 -0.009041 0.020538 -vn -0.917705 0.019145 -0.396801 -v -0.027378 -0.010441 0.019695 -vn -0.919225 -0.019516 -0.393250 -v -0.026628 0.013117 0.017820 -vn -0.918535 -0.019632 -0.394852 -v -0.026980 0.011917 0.018700 -vn -0.917770 -0.019421 -0.396637 -v -0.027304 0.010728 0.019509 -vn -0.918662 0.019364 -0.394569 -v -0.026982 -0.011911 0.018704 -vn -0.919552 0.019002 -0.392509 -v -0.026515 -0.013487 0.017537 -vn -0.853763 -0.079847 0.514502 -v -0.032485 -0.028845 0.032461 -vn -0.920059 0.019322 -0.391304 -v -0.026250 -0.014331 0.016875 -vn -0.872656 -0.147498 0.465527 -v -0.032443 -0.029538 0.032357 -vn -0.934053 0.030037 -0.355870 -v -0.026127 -0.014710 0.016567 -vn -0.890725 -0.196581 0.409836 -v -0.032366 -0.030307 0.032164 -vn -0.916748 -0.024733 -0.398700 -v -0.026250 0.014331 0.016875 -vn -0.852532 0.097322 0.513534 -v -0.032483 0.028878 0.032458 -vn -0.917207 -0.027306 -0.397473 -v -0.025914 0.015327 0.016034 -vn -0.874781 0.136925 0.464769 -v -0.032443 0.029534 0.032358 -vn -0.882555 0.167249 0.439460 -v -0.032433 0.029662 0.032332 -vn -0.884889 0.183492 0.428139 -v -0.032417 0.029834 0.032293 -vn -0.892728 0.211285 0.397990 -v -0.032371 0.030261 0.032179 -vn -0.897907 0.254024 0.359493 -v -0.032331 0.030574 0.032077 -vn -0.877338 0.242233 0.414247 -v -0.032146 0.031616 0.031616 -vn -0.950329 -0.220446 -0.219722 -v -0.025779 0.015697 0.015697 -vn -0.910901 0.297279 0.286156 -v -0.032217 0.031271 0.031792 -vn -0.902278 0.269197 0.336790 -v -0.032273 0.030956 0.031931 -vn -0.914653 -0.001671 0.404236 -v -0.028245 0.001012 -0.021864 -vn -0.707063 0.001127 -0.707150 -v -0.032500 0.028098 -0.032500 -vn -0.914700 0.003092 0.404121 -v -0.028224 -0.001853 -0.021811 -vn -0.707096 -0.001189 -0.707116 -v -0.032500 -0.028098 -0.032500 -vn -0.914888 0.007817 0.403632 -v -0.028061 -0.004689 -0.021403 -vn -0.914830 -0.006419 0.403789 -v -0.028124 0.003863 -0.021559 -vn -0.915106 -0.011155 0.403059 -v -0.027861 0.006657 -0.020901 -vn -0.915546 -0.015820 0.401903 -v -0.027460 0.009351 -0.019899 -vn -0.916643 0.021827 0.399111 -v -0.026751 -0.012599 -0.018128 -vn -0.915734 0.017121 0.401421 -v -0.027319 -0.010103 -0.019548 -vn -0.915248 0.012499 0.402697 -v -0.027758 -0.007453 -0.020645 -vn -0.874780 -0.136928 -0.464770 -v -0.032443 -0.029534 -0.032358 -vn -0.882544 -0.167248 -0.439482 -v -0.032433 -0.029662 -0.032332 -vn -0.934006 0.029771 0.356014 -v -0.026127 -0.014710 -0.016567 -vn -0.884794 -0.184179 -0.428040 -v -0.032417 -0.029834 -0.032293 -vn -0.890590 -0.203319 -0.406829 -v -0.032366 -0.030307 -0.032164 -vn -0.916169 -0.020358 0.400274 -v -0.026927 0.011902 -0.018567 -vn -0.916806 -0.024709 0.398568 -v -0.026269 0.014270 -0.016924 -vn -0.853835 0.078302 -0.514621 -v -0.032485 0.028845 -0.032461 -vn -0.960609 -0.196489 0.196527 -v -0.025779 0.015697 -0.015697 -vn -0.867989 0.126330 -0.480245 -v -0.032461 0.029286 -0.032403 -vn -0.852520 -0.097327 -0.513554 -v -0.032483 -0.028878 -0.032458 -vn -0.891393 0.274159 -0.360909 -v -0.032296 0.030813 -0.031989 -vn -0.901099 0.274702 -0.335498 -v -0.032275 0.030941 -0.031938 -vn -0.869692 0.235379 -0.433858 -v -0.032146 0.031616 -0.031616 -vn -0.888839 0.195220 -0.414554 -v -0.032394 0.030061 -0.032236 -vn -0.876155 0.153261 -0.457016 -v -0.032443 0.029534 -0.032358 -vn -0.914652 -0.404238 -0.001672 -v -0.028245 0.021864 0.001012 -vn -0.707116 0.707097 0.001106 -v -0.032500 0.032500 0.029500 -vn -0.914701 -0.404120 0.003092 -v -0.028224 0.021811 -0.001853 -vn -0.707088 0.707125 -0.001143 -v -0.032500 0.032500 -0.029500 -vn -0.914889 -0.403630 0.007817 -v -0.028061 0.021403 -0.004689 -vn -0.914830 -0.403787 -0.006419 -v -0.028124 0.021559 0.003863 -vn -0.915106 -0.403059 -0.011156 -v -0.027861 0.020901 0.006657 -vn -0.915545 -0.401904 -0.015820 -v -0.027460 0.019899 0.009351 -vn -0.916403 -0.399673 0.021611 -v -0.026751 0.018128 -0.012599 -vn -0.915733 -0.401423 0.017121 -v -0.027319 0.019548 -0.010103 -vn -0.915248 -0.402698 0.012500 -v -0.027758 0.020645 -0.007453 -vn -0.917376 -0.397171 0.026009 -v -0.026063 0.016406 -0.014901 -vn -0.974640 0.205417 -0.088771 -v -0.032487 0.032467 -0.029941 -vn -0.965716 0.202053 -0.162996 -v -0.032448 0.032371 -0.030367 -vn -0.960658 0.185164 -0.207002 -v -0.032440 0.032350 -0.030432 -vn -0.951818 0.183144 0.245971 -v -0.032392 0.032231 0.030735 -vn -0.961763 0.186836 0.200262 -v -0.032443 0.032357 0.030411 -vn -0.916169 -0.400274 -0.020358 -v -0.026927 0.018567 0.011902 -vn -0.916804 -0.398575 -0.024655 -v -0.026269 0.016924 0.014270 -vn -0.891327 0.451739 0.038313 -v -0.032495 0.032488 0.029764 -vn -0.971523 0.225958 0.071316 -v -0.032490 0.032474 0.029892 -vn -0.965991 0.210573 0.150069 -v -0.032454 0.032385 0.030318 -vn -0.971011 0.210461 0.113335 -v -0.032486 0.032466 0.029947 -vn -0.940544 0.172495 -0.292612 -v -0.032369 0.032174 -0.030854 -vn -0.914528 0.137530 -0.380427 -v -0.032270 0.031924 -0.031259 -vn -0.915061 0.133857 0.380454 -v -0.032268 0.031919 0.031265 -vn -0.940327 0.160899 0.299826 -v -0.032364 0.032159 0.030882 -vn -0.403626 0.914891 0.007827 -v 0.021403 0.028061 -0.004689 -vn -0.404128 0.914697 0.003087 -v 0.021811 0.028224 -0.001853 -vn -0.404199 0.914669 -0.001677 -v 0.021864 0.028245 0.001012 -vn -0.403856 0.914800 -0.006437 -v 0.021559 0.028124 0.003863 -vn -0.403079 0.915097 -0.011155 -v 0.020901 0.027861 0.006657 -vn -0.399108 0.916644 0.021828 -v 0.018128 0.026751 -0.012599 -vn -0.401399 0.915744 0.017112 -v 0.019548 0.027319 -0.010103 -vn -0.402736 0.915231 0.012516 -v 0.020645 0.027758 -0.007453 -vn 0.188571 0.964448 -0.185153 -v 0.032350 0.032440 -0.030432 -vn 0.195360 0.959123 -0.204739 -v 0.032335 0.032434 -0.030478 -vn -0.356135 0.933957 0.029879 -v 0.016567 0.026127 -0.014710 -vn 0.207627 0.962228 -0.176092 -v 0.032371 0.032448 -0.030367 -vn 0.198040 0.958904 0.203185 -v 0.032335 0.032434 0.030478 -vn 0.192727 0.964704 0.179452 -v 0.032357 0.032443 0.030411 -vn -0.356002 0.933999 -0.030136 -v 0.016567 0.026127 0.014710 -vn 0.227064 0.966989 0.115650 -v 0.032448 0.032479 0.030055 -vn -0.401892 0.915551 -0.015817 -v 0.019899 0.027460 0.009351 -vn -0.400280 0.916167 -0.020370 -v 0.018567 0.026927 0.011902 -vn -0.396399 0.917731 -0.025256 -v 0.016924 0.026269 0.014270 -vn 0.302281 0.952570 0.035162 -v 0.032488 0.032495 0.029764 -vn 0.205482 0.973749 0.097927 -v 0.032466 0.032486 0.029947 -vn 0.207324 0.972866 -0.102710 -v 0.032467 0.032487 -0.029941 -vn 0.002930 0.912952 -0.408058 -v -0.001032 0.028749 0.023122 -vn -0.001146 0.707108 0.707104 -v -0.028098 0.032500 0.032500 -vn 0.000031 0.912877 -0.408234 -v -0.000008 0.028763 0.023157 -vn 0.001184 0.707103 0.707109 -v 0.028098 0.032500 0.032500 -vn -0.002885 0.912936 -0.408093 -v 0.001020 0.028749 0.023123 -vn -0.010700 0.913800 -0.406024 -v 0.004039 0.028550 0.022624 -vn -0.008273 0.913386 -0.407010 -v 0.003003 0.028645 0.022862 -vn -0.005683 0.913103 -0.407689 -v 0.002057 0.028707 0.023018 -vn 0.005751 0.913154 -0.407575 -v -0.002057 0.028707 0.023018 -vn 0.007937 0.913280 -0.407256 -v -0.003088 0.028638 0.022845 -vn 0.009606 0.913483 -0.406763 -v -0.003309 0.028620 0.022799 -vn 0.011542 0.914077 -0.405376 -v -0.004438 0.028506 0.022514 -vn 0.013818 0.914661 -0.403986 -v -0.005574 0.028359 0.022146 -vn 0.015727 0.915327 -0.402405 -v -0.006724 0.028177 0.021692 -vn -0.017836 0.916264 -0.400179 -v 0.008364 0.027863 0.020907 -vn -0.016484 0.915501 -0.401977 -v 0.007137 0.028104 0.021509 -vn -0.018842 0.917020 -0.398397 -v 0.009546 0.027598 0.020246 -vn -0.014837 0.914854 -0.403513 -v 0.006104 0.028279 0.021947 -vn -0.012920 0.914292 -0.404850 -v 0.005072 0.028428 0.022319 -vn 0.017243 0.916045 -0.400705 -v -0.007895 0.027959 0.021148 -vn 0.018411 0.916813 -0.398893 -v -0.009041 0.027715 0.020538 -vn 0.019128 0.917715 -0.396779 -v -0.010441 0.027378 0.019695 -vn -0.019456 0.919261 -0.393167 -v 0.013117 0.026628 0.017820 -vn -0.019621 0.918529 -0.394866 -v 0.011917 0.026980 0.018700 -vn -0.019421 0.917780 -0.396613 -v 0.010728 0.027304 0.019509 -vn 0.019411 0.918640 -0.394619 -v -0.011911 0.026982 0.018704 -vn 0.018641 0.918695 -0.394527 -v -0.013487 0.026515 0.017537 -vn -0.079828 0.853745 0.514536 -v -0.028845 0.032485 0.032461 -vn 0.026712 0.917952 -0.395792 -v -0.014331 0.026250 0.016875 -vn -0.147470 0.872638 0.465571 -v -0.029538 0.032443 0.032357 -vn 0.030089 0.934014 -0.355966 -v -0.014710 0.026127 0.016567 -vn -0.196573 0.890705 0.409883 -v -0.030308 0.032366 0.032164 -vn 0.203339 0.890603 0.406792 -v 0.030307 0.032366 0.032164 -vn -0.030067 0.933981 -0.356055 -v 0.014710 0.026127 0.016567 -vn 0.184147 0.884797 0.428046 -v 0.029834 0.032417 0.032293 -vn 0.167200 0.882540 0.439509 -v 0.029662 0.032433 0.032332 -vn -0.019503 0.920923 -0.389256 -v 0.014331 0.026250 0.016875 -vn 0.097337 0.852510 0.513568 -v 0.028878 0.032483 0.032458 -vn 0.136939 0.874797 0.464734 -v 0.029534 0.032443 0.032358 -vn 0.404163 0.914685 0.001673 -v -0.021864 0.028245 -0.001012 -vn 0.404140 0.914692 -0.003086 -v -0.021811 0.028224 0.001853 -vn 0.403651 0.914879 -0.007834 -v -0.021403 0.028061 0.004689 -vn 0.403820 0.914816 0.006429 -v -0.021559 0.028124 -0.003863 -vn 0.403088 0.915093 0.011166 -v -0.020901 0.027861 -0.006657 -vn 0.401903 0.915545 0.015821 -v -0.019899 0.027460 -0.009351 -vn 0.399080 0.916657 -0.021806 -v -0.018128 0.026751 0.012599 -vn 0.401423 0.915733 -0.017122 -v -0.019548 0.027319 0.010103 -vn 0.402747 0.915226 -0.012524 -v -0.020645 0.027758 0.007453 -vn -0.184359 0.964619 0.188472 -v -0.032350 0.032440 0.030432 -vn -0.208787 0.953040 0.219371 -v -0.032335 0.032434 0.030478 -vn 0.356075 0.933982 -0.029809 -v -0.016567 0.026127 0.014710 -vn -0.193619 0.967099 0.165018 -v -0.032371 0.032448 0.030367 -vn -0.202867 0.955767 -0.212965 -v -0.032335 0.032434 -0.030478 -vn -0.190881 0.965767 -0.175668 -v -0.032357 0.032443 -0.030411 -vn 0.355947 0.934023 0.030051 -v -0.016567 0.026127 -0.014710 -vn -0.255753 0.957825 -0.131003 -v -0.032448 0.032479 -0.030055 -vn 0.400271 0.916171 0.020361 -v -0.018567 0.026927 -0.011902 -vn 0.396400 0.917731 0.025237 -v -0.016924 0.026269 -0.014270 -vn -0.451998 0.891178 -0.038719 -v -0.032488 0.032495 -0.029764 -vn -0.204003 0.974912 -0.089048 -v -0.032466 0.032486 -0.029947 -vn -0.203921 0.973351 0.104904 -v -0.032467 0.032487 0.029941 -vn -0.001677 0.914674 0.404190 -v 0.001012 0.028245 -0.021864 -vn 0.001160 0.707097 -0.707116 -v 0.028098 0.032500 -0.032500 -vn 0.003087 0.914700 0.404122 -v -0.001853 0.028224 -0.021811 -vn -0.001180 0.707105 -0.707107 -v -0.028098 0.032500 -0.032500 -vn 0.007828 0.914887 0.403634 -v -0.004689 0.028061 -0.021403 -vn -0.006437 0.914804 0.403848 -v 0.003863 0.028124 -0.021559 -vn -0.011157 0.915098 0.403078 -v 0.006657 0.027861 -0.020901 -vn -0.015812 0.915552 0.401889 -v 0.009351 0.027460 -0.019899 -vn 0.021820 0.916649 0.399097 -v -0.012599 0.026751 -0.018128 -vn 0.017118 0.915738 0.401412 -v -0.010103 0.027319 -0.019548 -vn 0.012515 0.915232 0.402733 -v -0.007453 0.027758 -0.020645 -vn -0.136952 0.874785 -0.464753 -v -0.029534 0.032443 -0.032358 -vn -0.167212 0.882560 -0.439464 -v -0.029662 0.032433 -0.032332 -vn 0.029839 0.933974 0.356092 -v -0.014710 0.026127 -0.016567 -vn -0.184120 0.884793 -0.428068 -v -0.029834 0.032417 -0.032293 -vn -0.203369 0.890584 -0.406819 -v -0.030308 0.032366 -0.032164 -vn -0.020361 0.916171 0.400270 -v 0.011902 0.026927 -0.018567 -vn -0.025250 0.917729 0.396404 -v 0.014270 0.026269 -0.016924 -vn 0.079821 0.853745 -0.514537 -v 0.028845 0.032484 -0.032461 -vn -0.030082 0.934013 0.355970 -v 0.014710 0.026127 -0.016567 -vn 0.147480 0.872646 -0.465552 -v 0.029538 0.032443 -0.032357 -vn 0.196541 0.890721 -0.409864 -v 0.030307 0.032366 -0.032164 -vn -0.097345 0.852500 -0.513584 -v -0.028878 0.032483 -0.032458 -vn 0.001678 0.404193 0.914672 -v -0.001012 -0.021864 0.028245 -vn -0.003087 0.404121 0.914700 -v 0.001853 -0.021811 0.028224 -vn -0.007828 0.403636 0.914886 -v 0.004689 -0.021403 0.028061 -vn 0.006436 0.403846 0.914804 -v -0.003863 -0.021559 0.028124 -vn 0.011158 0.403080 0.915097 -v -0.006657 -0.020901 0.027861 -vn 0.015813 0.401891 0.915551 -v -0.009351 -0.019899 0.027460 -vn -0.021819 0.399097 0.916649 -v 0.012599 -0.018128 0.026751 -vn -0.017119 0.401412 0.915738 -v 0.010103 -0.019548 0.027319 -vn -0.012515 0.402732 0.915232 -v 0.007453 -0.020645 0.027758 -vn 0.135828 0.039372 0.989950 -v 0.030023 -0.032088 0.032335 -vn 0.133104 0.022387 0.990849 -v 0.030174 -0.032031 0.032313 -vn -0.029829 0.356082 0.933978 -v 0.014710 -0.016567 0.026127 -vn 0.056974 0.125282 0.990484 -v 0.028886 -0.032413 0.032465 -vn 0.085153 0.074674 0.993566 -v 0.029231 -0.032335 0.032434 -vn 0.112702 0.070598 0.991118 -v 0.029866 -0.032143 0.032357 -vn -0.138499 0.029051 0.989936 -v -0.030174 -0.032031 0.032313 -vn -0.118360 0.066501 0.990741 -v -0.029862 -0.032144 0.032358 -vn 0.030074 0.355958 0.934018 -v -0.014710 -0.016567 0.026127 -vn -0.099314 0.080634 0.991784 -v -0.029643 -0.032216 0.032387 -vn -0.078218 0.043980 0.995966 -v -0.029064 -0.032375 0.032450 -vn 0.032387 -0.068349 0.997136 -v 0.028524 -0.032472 0.032489 -vn 0.020363 0.400273 0.916170 -v -0.011902 -0.018567 0.026927 -vn 0.025253 0.396406 0.917728 -v -0.014270 -0.016924 0.026269 -vn -0.033865 -0.102555 0.994151 -v -0.028514 -0.032473 0.032489 -vn -0.064542 0.119286 0.990760 -v -0.028879 -0.032415 0.032466 -vn -0.404127 -0.003087 0.914698 -v 0.021811 0.001853 0.028224 -vn -0.404202 0.001678 0.914668 -v 0.021864 -0.001012 0.028245 -vn -0.403629 -0.007828 0.914889 -v 0.021403 0.004689 0.028061 -vn -0.402737 -0.012516 0.915230 -v 0.020645 0.007453 0.027758 -vn -0.403855 0.006437 0.914800 -v 0.021559 -0.003863 0.028124 -vn -0.403081 0.011156 0.915096 -v 0.020901 -0.006657 0.027861 -vn -0.045840 0.132630 0.990105 -v 0.032088 0.030023 0.032335 -vn -0.029004 0.131928 0.990835 -v 0.032031 0.030174 0.032313 -vn -0.356126 -0.029871 0.933960 -v 0.016567 0.014710 0.026127 -vn -0.401400 -0.017113 0.915743 -v 0.019548 0.010103 0.027319 -vn -0.399108 -0.021828 0.916644 -v 0.018128 0.012599 0.026751 -vn -0.124804 0.057419 0.990519 -v 0.032413 0.028886 0.032465 -vn -0.081782 0.084316 0.993077 -v 0.032335 0.029231 0.032434 -vn -0.071229 0.112414 0.991105 -v 0.032143 0.029866 0.032357 -vn -0.027642 -0.135132 0.990442 -v 0.032031 -0.030174 0.032313 -vn -0.049999 -0.128115 0.990498 -v 0.032144 -0.029862 0.032358 -vn -0.355994 0.030127 0.934002 -v 0.016567 -0.014710 0.026127 -vn -0.080937 -0.099896 0.991701 -v 0.032216 -0.029643 0.032387 -vn -0.106660 -0.075116 0.991454 -v 0.032375 -0.029064 0.032450 -vn 0.004478 0.028625 0.999580 -v 0.032472 0.028524 0.032489 -vn -0.401893 0.015818 0.915550 -v 0.019899 -0.009351 0.027460 -vn -0.400281 0.020371 0.916166 -v 0.018567 -0.011902 0.026927 -vn -0.396401 0.025258 0.917730 -v 0.016924 -0.014270 0.026269 -vn -0.017353 -0.026680 0.999493 -v 0.032473 -0.028514 0.032489 -vn -0.117933 -0.060451 0.991180 -v 0.032415 -0.028879 0.032466 -vn 0.408063 -0.002912 0.912949 -v -0.023122 0.001032 0.028749 -vn 0.408262 -0.000042 0.912865 -v -0.023157 0.000008 0.028763 -vn 0.408125 0.002871 0.912922 -v -0.023123 -0.001020 0.028749 -vn 0.406043 0.010694 0.913791 -v -0.022624 -0.004039 0.028550 -vn 0.407012 0.008281 0.913385 -v -0.022862 -0.003003 0.028645 -vn 0.407685 0.005696 0.913105 -v -0.023018 -0.002057 0.028707 -vn 0.407566 -0.005747 0.913158 -v -0.023018 0.002057 0.028707 -vn 0.407228 -0.007964 0.913292 -v -0.022845 0.003088 0.028638 -vn 0.406709 -0.009669 0.913507 -v -0.022799 0.003309 0.028620 -vn 0.405400 -0.011545 0.914067 -v -0.022514 0.004438 0.028506 -vn 0.403987 -0.013815 0.914661 -v -0.022146 0.005574 0.028359 -vn 0.402413 -0.015740 0.915323 -v -0.021692 0.006724 0.028177 -vn 0.400187 0.017836 0.916260 -v -0.020907 -0.008364 0.027863 -vn 0.401988 0.016489 0.915497 -v -0.021509 -0.007137 0.028104 -vn 0.398409 0.018843 0.917014 -v -0.020246 -0.009546 0.027598 -vn 0.403515 0.014836 0.914853 -v -0.021947 -0.006104 0.028279 -vn 0.404845 0.012929 0.914294 -v -0.022319 -0.005072 0.028428 -vn 0.400704 -0.017238 0.916045 -v -0.021148 0.007895 0.027959 -vn 0.398885 -0.018405 0.916816 -v -0.020538 0.009041 0.027715 -vn 0.396789 -0.019138 0.917710 -v -0.019695 0.010441 0.027378 -vn 0.393160 0.019448 0.919265 -v -0.017820 -0.013117 0.026628 -vn 0.394868 0.019626 0.918528 -v -0.018700 -0.011917 0.026980 -vn 0.396611 0.019428 0.917781 -v -0.019509 -0.010728 0.027304 -vn 0.355941 -0.030046 0.934025 -v -0.016567 0.014710 0.026127 -vn 0.030397 0.137967 0.989970 -v -0.032031 0.030174 0.032313 -vn 0.066558 0.118347 0.990739 -v -0.032144 0.029862 0.032358 -vn 0.394636 -0.019425 0.918632 -v -0.018704 0.011911 0.026982 -vn 0.392569 -0.019065 0.919525 -v -0.017537 0.013487 0.026515 -vn -0.102810 0.033869 0.994124 -v -0.032473 0.028514 0.032489 -vn 0.391326 -0.019314 0.920049 -v -0.016875 0.014331 0.026250 -vn 0.074649 -0.085164 0.993567 -v -0.032335 -0.029231 0.032434 -vn 0.070581 -0.112700 0.991119 -v -0.032143 -0.029866 0.032357 -vn 0.356035 0.030025 0.933990 -v -0.016567 -0.014710 0.026127 -vn 0.039331 -0.135836 0.989950 -v -0.032088 -0.030023 0.032335 -vn 0.022392 -0.133111 0.990848 -v -0.032031 -0.030174 0.032313 -vn 0.080614 0.099323 0.991784 -v -0.032216 0.029643 0.032387 -vn 0.043896 0.078219 0.995969 -v -0.032375 0.029064 0.032450 -vn 0.119247 0.064552 0.990764 -v -0.032415 0.028879 0.032466 -vn 0.389251 0.019501 0.920925 -v -0.016875 -0.014331 0.026250 -vn -0.068467 -0.032375 0.997128 -v -0.032472 -0.028524 0.032489 -vn 0.125280 -0.056982 0.990484 -v -0.032413 -0.028886 0.032465 -vn -0.002931 -0.408057 0.912952 -v 0.001032 0.023122 0.028749 -vn -0.000031 -0.408233 0.912878 -v 0.000008 0.023157 0.028763 -vn 0.002885 -0.408092 0.912936 -v -0.001020 0.023123 0.028749 -vn 0.010700 -0.406026 0.913799 -v -0.004039 0.022624 0.028550 -vn 0.008273 -0.407010 0.913386 -v -0.003003 0.022862 0.028645 -vn 0.005684 -0.407687 0.913104 -v -0.002057 0.023018 0.028707 -vn -0.005751 -0.407575 0.913154 -v 0.002057 0.023018 0.028707 -vn -0.007938 -0.407256 0.913280 -v 0.003088 0.022845 0.028638 -vn -0.009613 -0.406757 0.913486 -v 0.003309 0.022799 0.028620 -vn -0.011542 -0.405379 0.914076 -v 0.004438 0.022514 0.028506 -vn -0.013817 -0.403987 0.914660 -v 0.005574 0.022146 0.028359 -vn -0.015726 -0.402405 0.915327 -v 0.006724 0.021692 0.028177 -vn 0.017834 -0.400177 0.916264 -v -0.008364 0.020907 0.027863 -vn 0.016484 -0.401978 0.915501 -v -0.007137 0.021509 0.028104 -vn 0.018842 -0.398395 0.917020 -v -0.009546 0.020246 0.027598 -vn 0.014837 -0.403516 0.914852 -v -0.006104 0.021947 0.028279 -vn 0.012922 -0.404850 0.914292 -v -0.005072 0.022319 0.028428 -vn -0.017244 -0.400705 0.916045 -v 0.007895 0.021148 0.027959 -vn -0.018407 -0.398889 0.916814 -v 0.009041 0.020538 0.027715 -vn -0.019130 -0.396780 0.917714 -v 0.010441 0.019695 0.027378 -vn 0.019456 -0.393170 0.919260 -v -0.013117 0.017820 0.026628 -vn 0.019622 -0.394866 0.918529 -v -0.011917 0.018700 0.026980 -vn 0.019425 -0.396617 0.917779 -v -0.010728 0.019509 0.027304 -vn -0.030084 -0.355960 0.934017 -v 0.014710 0.016567 0.026127 -vn 0.138495 -0.029031 0.989938 -v 0.030174 0.032031 0.032313 -vn 0.118364 -0.066499 0.990741 -v 0.029862 0.032144 0.032358 -vn -0.019409 -0.394618 0.918640 -v 0.011911 0.018704 0.026982 -vn -0.019060 -0.392561 0.919529 -v 0.013487 0.017537 0.026515 -vn 0.033862 0.102536 0.994153 -v 0.028514 0.032473 0.032489 -vn -0.019315 -0.391319 0.920052 -v 0.014331 0.016875 0.026250 -vn -0.085150 -0.074711 0.993563 -v -0.029231 0.032335 0.032434 -vn -0.112630 -0.070690 0.991119 -v -0.029866 0.032143 0.032357 -vn 0.030066 -0.356046 0.933985 -v -0.014710 0.016567 0.026127 -vn -0.135827 -0.039379 0.989950 -v -0.030023 0.032088 0.032335 -vn -0.133105 -0.022419 0.990848 -v -0.030174 0.032031 0.032313 -vn 0.099350 -0.080592 0.991783 -v 0.029643 0.032216 0.032387 -vn 0.078219 -0.043924 0.995968 -v 0.029064 0.032375 0.032450 -vn 0.064540 -0.119282 0.990761 -v 0.028879 0.032415 0.032466 -vn 0.025518 -0.395451 0.918133 -v -0.014331 0.016875 0.026250 -vn -0.032387 0.068318 0.997138 -v -0.028524 0.032472 0.032489 -vn -0.056983 -0.125271 0.990485 -v -0.028886 0.032413 0.032465 -vn -0.135824 0.039379 -0.989950 -v -0.030023 -0.032088 -0.032335 -vn -0.133097 0.022321 -0.990852 -v -0.030174 -0.032031 -0.032313 -vn 0.003500 0.189995 -0.981779 -v -0.005643 -0.007500 -0.022500 -vn -0.003500 0.189993 -0.981779 -v 0.005643 -0.007500 -0.022500 -vn 0.138495 0.029027 -0.989938 -v 0.030174 -0.032031 -0.032313 -vn 0.118367 0.066494 -0.990741 -v 0.029862 -0.032144 -0.032358 -vn 0.099348 0.080592 -0.991784 -v 0.029643 -0.032216 -0.032387 -vn 0.078221 0.043907 -0.995969 -v 0.029064 -0.032375 -0.032450 -vn 0.064542 0.119301 -0.990758 -v 0.028879 -0.032415 -0.032466 -vn -0.032392 -0.068194 -0.997146 -v -0.028524 -0.032472 -0.032489 -vn -0.056968 0.125279 -0.990485 -v -0.028886 -0.032413 -0.032465 -vn -0.085147 0.074704 -0.993564 -v -0.029231 -0.032335 -0.032434 -vn -0.112617 0.070721 -0.991119 -v -0.029866 -0.032143 -0.032357 -vn 0.033866 -0.102543 -0.994152 -v 0.028514 -0.032473 -0.032489 -vn 0.052951 0.127335 -0.990445 -v -0.032088 0.030023 -0.032335 -vn 0.037553 0.128877 -0.990949 -v -0.032031 0.030174 -0.032313 -vn 0.189992 -0.003496 -0.981779 -v -0.007500 0.005643 -0.022500 -vn 0.189994 0.003496 -0.981779 -v -0.007500 -0.005643 -0.022500 -vn 0.029001 -0.138522 -0.989935 -v -0.032031 -0.030174 -0.032313 -vn 0.066552 -0.118350 -0.990739 -v -0.032144 -0.029862 -0.032358 -vn 0.080621 -0.099320 -0.991784 -v -0.032216 -0.029643 -0.032387 -vn 0.043882 -0.078219 -0.995970 -v -0.032375 -0.029064 -0.032450 -vn 0.119267 -0.064554 -0.990761 -v -0.032415 -0.028879 -0.032466 -vn -0.068367 0.032381 -0.997135 -v -0.032472 0.028524 -0.032489 -vn 0.125288 0.056967 -0.990484 -v -0.032413 0.028886 -0.032465 -vn 0.098768 0.080081 -0.991883 -v -0.032335 0.029231 -0.032434 -vn 0.070665 0.113100 -0.991068 -v -0.032143 0.029866 -0.032357 -vn -0.102840 -0.033874 -0.994121 -v -0.032473 -0.028514 -0.032489 -vn -0.189993 -0.003500 -0.981779 -v 0.007500 0.005643 -0.022500 -vn -0.026105 0.134905 -0.990515 -v 0.032031 0.030174 -0.032313 -vn -0.050491 0.130031 -0.990224 -v 0.032144 0.029862 -0.032358 -vn -0.189993 0.003500 -0.981779 -v 0.007500 -0.005643 -0.022500 -vn -0.095816 -0.087112 -0.991580 -v 0.032335 -0.029231 -0.032434 -vn -0.069861 -0.113037 -0.991132 -v 0.032143 -0.029866 -0.032357 -vn -0.046537 -0.130712 -0.990328 -v 0.032088 -0.030023 -0.032335 -vn -0.030965 -0.131282 -0.990861 -v 0.032031 -0.030174 -0.032313 -vn -0.080771 0.099857 -0.991718 -v 0.032216 0.029643 -0.032387 -vn -0.061018 0.075375 -0.995287 -v 0.032375 0.029064 -0.032450 -vn -0.112222 0.070047 -0.991211 -v 0.032415 0.028879 -0.032466 -vn 0.011896 0.028513 -0.999523 -v 0.032473 0.028514 -0.032489 -vn -0.024102 -0.026822 -0.999350 -v 0.032472 -0.028524 -0.032489 -vn -0.118145 -0.060950 -0.991124 -v 0.032413 -0.028886 -0.032465 -vn 0.135820 -0.039374 -0.989951 -v 0.030023 0.032088 -0.032335 -vn 0.133095 -0.022291 -0.990853 -v 0.030174 0.032031 -0.032313 -vn -0.003500 -0.189997 -0.981779 -v 0.005643 0.007500 -0.022500 -vn 0.003500 -0.189995 -0.981779 -v -0.005643 0.007500 -0.022500 -vn -0.138497 -0.029050 -0.989937 -v -0.030174 0.032031 -0.032313 -vn -0.118364 -0.066493 -0.990742 -v -0.029862 0.032144 -0.032358 -vn -0.099310 -0.080645 -0.991783 -v -0.029643 0.032216 -0.032387 -vn -0.078219 -0.043964 -0.995966 -v -0.029064 0.032375 -0.032450 -vn -0.064544 -0.119304 -0.990758 -v -0.028879 0.032415 -0.032466 -vn 0.032392 0.068273 -0.997141 -v 0.028524 0.032472 -0.032489 -vn 0.056959 -0.125284 -0.990485 -v 0.028886 0.032413 -0.032465 -vn 0.085151 -0.074668 -0.993566 -v 0.029231 0.032335 -0.032434 -vn 0.112697 -0.070604 -0.991118 -v 0.029866 0.032143 -0.032357 -vn -0.033869 0.102611 -0.994145 -v -0.028514 0.032473 -0.032489 -vn 0.389945 -0.155649 0.907588 -v 0.028200 0.024640 0.007221 -vn 0.389948 -0.306744 0.868244 -v 0.028200 0.024903 0.007289 -vn 0.389912 -0.449095 0.803917 -v 0.028200 0.025150 0.007401 -vn -0.821067 -0.305673 0.482092 -v 0.018610 0.025046 0.007348 -vn -0.819488 -0.278792 0.500714 -v 0.018625 0.024903 0.007289 -vn -0.831572 -0.394676 0.390792 -v 0.018579 0.025375 0.007553 -vn -0.826242 -0.376466 0.419044 -v 0.018587 0.025287 0.007487 -vn 0.389912 -0.578497 0.716457 -v 0.028200 0.025375 0.007553 -vn -0.824377 -0.354408 0.441359 -v 0.018589 0.025267 0.007473 -vn -0.821434 -0.335798 0.460962 -v 0.018600 0.025150 0.007401 -vn -0.833833 -0.423880 0.353621 -v 0.018569 0.025484 0.007649 -vn 0.389912 -0.691256 0.608386 -v 0.028200 0.025571 0.007741 -vn -0.835159 -0.453828 0.310725 -v 0.018559 0.025571 0.007741 -vn 0.389915 -0.784132 0.482807 -v 0.028200 0.025732 0.007959 -vn -0.843988 -0.470081 0.258278 -v 0.018547 0.025656 0.007846 -vn -0.843112 -0.533148 0.070110 -v 0.018496 0.025855 0.008202 -vn -0.835435 -0.537288 0.115626 -v 0.018512 0.025812 0.008105 -vn 0.389916 -0.854447 0.343346 -v 0.028200 0.025855 0.008202 -vn -0.838191 -0.523053 0.154439 -v 0.018520 0.025789 0.008059 -vn -0.843097 -0.499505 0.199206 -v 0.018533 0.025733 0.007959 -vn -0.859434 -0.509808 -0.038330 -v 0.018471 0.025899 0.008326 -vn 0.389913 -0.900183 0.194007 -v 0.028200 0.025934 0.008461 -vn -0.842228 -0.530163 -0.097870 -v 0.018440 0.025934 0.008461 -vn 0.389930 -0.920015 0.039071 -v 0.028200 0.025969 0.008730 -vn -0.798263 -0.547426 -0.251200 -v 0.018360 0.025969 0.008731 -vn -0.821097 -0.537464 -0.192177 -v 0.018404 0.025957 0.008592 -vn -0.830507 -0.537513 -0.146074 -v 0.018415 0.025952 0.008557 -vn -0.811468 -0.481242 -0.331551 -v 0.018328 0.025970 0.008823 -vn 0.389944 -0.913380 -0.116968 -v 0.028200 0.025957 0.009001 -vn -0.789756 -0.464543 -0.400605 -v 0.018254 0.025957 0.009002 -vn 0.389958 -0.880467 -0.269649 -v 0.028200 0.025900 0.009267 -vn -0.724032 -0.424861 -0.543388 -v 0.018122 0.025900 0.009267 -vn -0.762159 -0.434936 -0.479525 -v 0.018212 0.025942 0.009095 -vn -0.774659 -0.456942 -0.437158 -v 0.018229 0.025949 0.009057 -vn -0.697131 -0.412735 -0.586224 -v 0.018080 0.025875 0.009340 -vn 0.389953 -0.822241 -0.414556 -v 0.028200 0.025799 0.009518 -vn -0.680335 -0.363951 -0.636148 -v 0.017967 0.025798 0.009519 -vn 0.389933 -0.740355 -0.547564 -v 0.028200 0.025656 0.009749 -vn -0.621592 -0.295612 -0.725422 -v 0.017797 0.025656 0.009750 -vn -0.654584 -0.307454 -0.690646 -v 0.017898 0.025744 0.009617 -vn -0.666266 -0.339717 -0.663839 -v 0.017924 0.025766 0.009581 -vn -0.606915 -0.247191 -0.755348 -v 0.017710 0.025571 0.009855 -vn 0.389941 -0.637164 -0.664807 -v 0.028200 0.025477 0.009953 -vn -0.593826 -0.199388 -0.779497 -v 0.017622 0.025477 0.009953 -vn -0.581859 -0.159019 -0.797592 -v 0.017519 0.025353 0.010060 -vn 0.389946 -0.515647 -0.762922 -v 0.028200 0.025266 0.010124 -vn -0.569950 -0.119563 -0.812934 -v 0.017454 0.025267 0.010123 -vn -0.550736 -0.101067 -0.828538 -v 0.017368 0.025137 0.010202 -vn 0.389944 -0.379296 -0.839094 -v 0.028200 0.025029 0.010256 -vn -0.543158 -0.071347 -0.836594 -v 0.017306 0.025030 0.010255 -vn -0.543077 -0.040925 -0.838685 -v 0.017240 0.024898 0.010308 -vn 0.389995 -0.231988 -0.891115 -v 0.028200 0.024773 0.010346 -vn -0.542375 -0.018753 -0.839927 -v 0.017189 0.024774 0.010346 -vn -0.535564 0.008100 -0.844456 -v 0.017172 0.024727 0.010358 -vn 0.390059 -0.078078 -0.917474 -v 0.028200 0.024506 0.010392 -vn -0.520384 0.009910 -0.853875 -v 0.017119 0.024530 0.010390 -vn -0.480151 0.069976 -0.874390 -v 0.017090 0.024234 0.010392 -vn -0.490404 0.063099 -0.869208 -v 0.017091 0.024300 0.010397 -vn 0.390016 0.078049 -0.917494 -v 0.028200 0.024234 0.010392 -vn -0.554899 0.034157 -0.831216 -v 0.017108 0.024468 0.010395 -vn -0.517695 0.022710 -0.855264 -v 0.017114 0.024506 0.010392 -vn 0.389954 0.232025 -0.891123 -v 0.028200 0.023967 0.010346 -vn 0.389945 0.379292 -0.839095 -v 0.028200 0.023711 0.010256 -vn 0.390065 0.515692 -0.762831 -v 0.028200 0.023474 0.010124 -vn 0.390184 0.637096 -0.664729 -v 0.028200 0.023263 0.009953 -vn 0.390184 0.740269 -0.547502 -v 0.028200 0.023084 0.009749 -vn 0.390070 0.822153 -0.414621 -v 0.028200 0.022941 0.009518 -vn 0.390070 0.880450 -0.269544 -v 0.028200 0.022840 0.009267 -vn 0.390184 0.913280 -0.116943 -v 0.028200 0.022783 0.009001 -vn 0.390185 0.919907 0.039078 -v 0.028200 0.022771 0.008730 -vn 0.390185 0.900071 0.193977 -v 0.028200 0.022806 0.008461 -vn 0.390185 0.854342 0.343302 -v 0.028200 0.022885 0.008202 -vn 0.390184 0.784034 0.482750 -v 0.028200 0.023008 0.007959 -vn 0.390184 0.691173 0.608306 -v 0.028200 0.023169 0.007741 -vn 0.390183 0.578424 0.716368 -v 0.028200 0.023365 0.007553 -vn 0.390182 0.449038 0.803818 -v 0.028200 0.023590 0.007401 -vn 0.390183 0.306733 0.868143 -v 0.028200 0.023837 0.007289 -vn 0.390182 0.155606 0.907494 -v 0.028200 0.024100 0.007221 -vn 0.390047 0.000102 0.920795 -v 0.028200 0.024370 0.007198 -vn -0.830639 0.371261 0.414975 -v 0.018586 -0.025321 0.007507 -vn -0.838554 0.392445 0.377907 -v 0.018580 -0.025380 0.007553 -vn 0.390053 0.578535 0.716349 -v 0.028200 -0.025380 0.007553 -vn -0.845871 0.480990 0.230545 -v 0.018544 -0.025695 0.007893 -vn -0.849911 0.494842 0.181059 -v 0.018535 -0.025738 0.007959 -vn 0.390181 0.784035 0.482751 -v 0.028200 -0.025737 0.007959 -vn -0.640940 0.324959 -0.695412 -v 0.017892 -0.025742 0.009630 -vn -0.609760 0.329330 -0.720926 -v 0.017800 -0.025661 0.009750 -vn 0.390182 0.740268 -0.547505 -v 0.028200 -0.025661 0.009749 -vn 0.389952 -0.232026 -0.891124 -v 0.028200 -0.023972 0.010346 -vn 0.390069 -0.078002 -0.917476 -v 0.028200 -0.024239 0.010392 -vn 0.390074 0.078001 -0.917474 -v 0.028200 -0.024511 0.010392 -vn -0.505355 -0.024021 -0.862577 -v 0.017115 -0.024511 0.010392 -vn -0.500823 -0.033531 -0.864900 -v 0.017102 -0.024432 0.010397 -vn -0.505884 -0.046461 -0.861349 -v 0.017099 -0.024408 0.010398 -vn -0.508741 -0.067520 -0.858268 -v 0.017090 -0.024246 0.010393 -vn 0.390005 0.232058 -0.891092 -v 0.028200 -0.024778 0.010346 -vn -0.516082 -0.006840 -0.856512 -v 0.017139 -0.024617 0.010380 -vn -0.503274 -0.009405 -0.864076 -v 0.017135 -0.024604 0.010382 -vn 0.390112 0.379312 -0.839008 -v 0.028200 -0.025034 0.010256 -vn -0.531182 0.056279 -0.845386 -v 0.017285 -0.024993 0.010274 -vn -0.533408 0.015983 -0.845707 -v 0.017191 -0.024782 0.010346 -vn 0.390184 0.515590 -0.762839 -v 0.028200 -0.025271 0.010124 -vn -0.566307 0.146610 -0.811050 -v 0.017456 -0.025271 0.010123 -vn -0.555527 0.135049 -0.820458 -v 0.017425 -0.025227 0.010153 -vn -0.552835 0.122174 -0.824286 -v 0.017405 -0.025198 0.010170 -vn -0.547767 0.094755 -0.831248 -v 0.017372 -0.025146 0.010200 -vn -0.532101 0.089288 -0.841960 -v 0.017307 -0.025035 0.010256 -vn 0.390184 0.637095 -0.664731 -v 0.028200 -0.025482 0.009953 -vn -0.601027 0.283798 -0.747145 -v 0.017783 -0.025646 0.009770 -vn -0.588777 0.231370 -0.774474 -v 0.017624 -0.025482 0.009953 -vn -0.576400 0.187867 -0.795280 -v 0.017596 -0.025449 0.009984 -vn 0.390181 0.822151 -0.414520 -v 0.028200 -0.025804 0.009518 -vn -0.708676 0.312165 -0.632717 -v 0.017970 -0.025803 0.009519 -vn -0.660685 0.314749 -0.681490 -v 0.017919 -0.025764 0.009592 -vn -0.771308 0.433955 -0.465582 -v 0.018200 -0.025942 0.009124 -vn 0.390181 0.880380 -0.269611 -v 0.028200 -0.025905 0.009267 -vn -0.789843 0.449248 -0.417522 -v 0.018257 -0.025962 0.009002 -vn 0.390178 0.913282 -0.116951 -v 0.028200 -0.025962 0.009001 -vn -0.805873 0.470985 -0.358806 -v 0.018312 -0.025973 0.008871 -vn -0.757827 0.417297 -0.501559 -v 0.018180 -0.025933 0.009163 -vn -0.744648 0.394979 -0.538044 -v 0.018125 -0.025905 0.009267 -vn -0.727935 0.358584 -0.584404 -v 0.018089 -0.025884 0.009330 -vn -0.823162 0.547084 -0.152000 -v 0.018408 -0.025961 0.008590 -vn 0.390180 0.919909 0.039076 -v 0.028200 -0.025974 0.008730 -vn -0.815595 0.570660 -0.095668 -v 0.018442 -0.025939 0.008461 -vn 0.390182 0.900072 0.193982 -v 0.028200 -0.025939 0.008461 -vn -0.824900 0.563778 -0.041162 -v 0.018463 -0.025919 0.008377 -vn -0.812211 0.548726 -0.198021 -v 0.018401 -0.025964 0.008611 -vn -0.826398 0.508674 -0.241491 -v 0.018363 -0.025974 0.008731 -vn -0.817869 0.479456 -0.318138 -v 0.018322 -0.025974 0.008844 -vn 0.390182 0.854343 0.343303 -v 0.028200 -0.025860 0.008202 -vn -0.847745 0.516465 0.120796 -v 0.018514 -0.025817 0.008105 -vn -0.841425 0.537365 0.056952 -v 0.018498 -0.025860 0.008202 -vn -0.833782 0.552085 0.002971 -v 0.018474 -0.025903 0.008325 -vn 0.390182 0.691171 0.608309 -v 0.028200 -0.025576 0.007741 -vn -0.840341 0.420432 0.342146 -v 0.018568 -0.025513 0.007674 -vn -0.840977 0.450043 0.300366 -v 0.018561 -0.025576 0.007741 -vn -0.840574 0.474265 0.261741 -v 0.018547 -0.025674 0.007864 -vn -0.826988 0.360056 0.431799 -v 0.018588 -0.025292 0.007487 -vn 0.389930 0.449084 0.803914 -v 0.028200 -0.025155 0.007401 -vn -0.827012 0.334317 0.451977 -v 0.018600 -0.025155 0.007401 -vn -0.827635 0.304868 0.471250 -v 0.018608 -0.025076 0.007360 -vn 0.390063 0.306666 0.868221 -v 0.028200 -0.024908 0.007289 -vn -0.824873 0.269471 0.496960 -v 0.018625 -0.024908 0.007289 -vn 0.390182 0.155606 0.907494 -v 0.028200 -0.024645 0.007221 -vn 0.389908 -0.155626 0.907608 -v 0.028200 -0.024105 0.007221 -vn 0.390047 0.000102 0.920795 -v 0.028200 -0.024375 0.007198 -vn 0.389910 -0.306772 0.868252 -v 0.028200 -0.023842 0.007289 -vn 0.389911 -0.449095 0.803918 -v 0.028200 -0.023595 0.007401 -vn 0.390058 -0.691150 0.608413 -v 0.028200 -0.023174 0.007741 -vn 0.390048 -0.578539 0.716348 -v 0.028200 -0.023370 0.007553 -vn 0.390065 -0.515691 -0.762832 -v 0.028200 -0.023479 0.010124 -vn 0.390184 -0.637095 -0.664730 -v 0.028200 -0.023268 0.009953 -vn 0.390184 -0.740268 -0.547503 -v 0.028200 -0.023089 0.009749 -vn 0.390185 -0.822149 -0.414520 -v 0.028200 -0.022946 0.009518 -vn 0.390184 -0.880378 -0.269612 -v 0.028200 -0.022845 0.009267 -vn 0.390185 -0.913279 -0.116951 -v 0.028200 -0.022788 0.009001 -vn 0.390184 -0.919907 0.039078 -v 0.028200 -0.022776 0.008730 -vn 0.390185 -0.900070 0.193981 -v 0.028200 -0.022811 0.008461 -vn 0.390184 -0.854341 0.343304 -v 0.028200 -0.022890 0.008202 -vn 0.390059 -0.784128 0.482698 -v 0.028200 -0.023013 0.007959 -vn 0.389945 -0.379294 -0.839094 -v 0.028200 -0.023716 0.010256 -vn 0.688510 -0.000000 0.725227 -v 0.029400 -0.016245 0.005698 -vn 0.390213 0.000001 0.920725 -v 0.032300 -0.016245 0.005698 -vn 0.688507 -0.122562 0.714799 -v 0.029400 -0.015721 0.005743 -vn 0.390210 -0.155602 0.907482 -v 0.032300 -0.015721 0.005743 -vn 0.688508 -0.241604 0.683802 -v 0.029400 -0.015212 0.005875 -vn 0.390207 -0.306733 0.868132 -v 0.032300 -0.015212 0.005875 -vn 0.688508 -0.353690 0.633135 -v 0.029400 -0.014733 0.006092 -vn 0.390210 -0.449032 0.803807 -v 0.032300 -0.014733 0.006092 -vn 0.688507 -0.455603 0.564255 -v 0.029400 -0.014298 0.006386 -vn 0.390209 -0.578418 0.716359 -v 0.032300 -0.014298 0.006386 -vn 0.688508 -0.544409 0.479141 -v 0.029400 -0.013918 0.006750 -vn 0.390208 -0.691164 0.608301 -v 0.032300 -0.013918 0.006750 -vn 0.688507 -0.617554 0.380242 -v 0.029400 -0.013605 0.007173 -vn 0.390207 -0.784027 0.482743 -v 0.032300 -0.013605 0.007173 -vn 0.688508 -0.672932 0.270405 -v 0.029400 -0.013369 0.007642 -vn 0.390209 -0.854332 0.343298 -v 0.032300 -0.013369 0.007642 -vn 0.688508 -0.708951 0.152791 -v 0.029400 -0.013215 0.008145 -vn 0.390209 -0.900061 0.193978 -v 0.032300 -0.013215 0.008145 -vn 0.688508 -0.724576 0.030779 -v 0.029400 -0.013148 0.008667 -vn 0.390209 -0.919897 0.039076 -v 0.032300 -0.013148 0.008667 -vn 0.688508 -0.719355 -0.092118 -v 0.029400 -0.013170 0.009192 -vn 0.390211 -0.913268 -0.116949 -v 0.032300 -0.013170 0.009192 -vn 0.688508 -0.693440 -0.212363 -v 0.029400 -0.013281 0.009706 -vn 0.390211 -0.880367 -0.269609 -v 0.032300 -0.013281 0.009706 -vn 0.688507 -0.647576 -0.326501 -v 0.029400 -0.013477 0.010194 -vn 0.390211 -0.822140 -0.414514 -v 0.032300 -0.013477 0.010194 -vn 0.688508 -0.583082 -0.431245 -v 0.029400 -0.013753 0.010641 -vn 0.390212 -0.740261 -0.547493 -v 0.032300 -0.013753 0.010641 -vn 0.688508 -0.501815 -0.523582 -v 0.029400 -0.014100 0.011036 -vn 0.390210 -0.637088 -0.664722 -v 0.032300 -0.014100 0.011036 -vn 0.688507 -0.406110 -0.600860 -v 0.029400 -0.014509 0.011366 -vn 0.390208 -0.515583 -0.762832 -v 0.032300 -0.014509 0.011366 -vn 0.688509 -0.298721 -0.660850 -v 0.029400 -0.014968 0.011623 -vn 0.390209 -0.379246 -0.838993 -v 0.032300 -0.014968 0.011623 -vn 0.688508 -0.182744 -0.701827 -v 0.029400 -0.015464 0.011798 -vn 0.390210 -0.232006 -0.891016 -v 0.032300 -0.015464 0.011798 -vn 0.688507 -0.061506 -0.722617 -v 0.029400 -0.015982 0.011887 -vn 0.390208 -0.078085 -0.917410 -v 0.032300 -0.015982 0.011887 -vn 0.688507 0.061506 -0.722617 -v 0.029400 -0.016508 0.011887 -vn 0.390207 0.078086 -0.917410 -v 0.032300 -0.016508 0.011887 -vn 0.688508 0.182743 -0.701827 -v 0.029400 -0.017026 0.011798 -vn 0.390210 0.232004 -0.891016 -v 0.032300 -0.017026 0.011798 -vn 0.688508 0.298721 -0.660850 -v 0.029400 -0.017522 0.011623 -vn 0.390209 0.379246 -0.838993 -v 0.032300 -0.017522 0.011623 -vn 0.688507 0.406110 -0.600860 -v 0.029400 -0.017981 0.011366 -vn 0.390209 0.515583 -0.762831 -v 0.032300 -0.017981 0.011366 -vn 0.688508 0.501815 -0.523582 -v 0.029400 -0.018390 0.011036 -vn 0.390209 0.637088 -0.664723 -v 0.032300 -0.018390 0.011036 -vn 0.688508 0.583083 -0.431244 -v 0.029400 -0.018737 0.010641 -vn 0.390211 0.740261 -0.547493 -v 0.032300 -0.018737 0.010641 -vn 0.688508 0.647575 -0.326501 -v 0.029400 -0.019013 0.010194 -vn 0.390212 0.822139 -0.414515 -v 0.032300 -0.019013 0.010194 -vn 0.688508 0.693440 -0.212365 -v 0.029400 -0.019209 0.009706 -vn 0.390210 0.880367 -0.269611 -v 0.032300 -0.019209 0.009706 -vn 0.688507 0.719355 -0.092116 -v 0.029400 -0.019320 0.009192 -vn 0.390208 0.913269 -0.116947 -v 0.032300 -0.019320 0.009192 -vn 0.688508 0.724575 0.030780 -v 0.029400 -0.019342 0.008667 -vn 0.390211 0.919896 0.039076 -v 0.032300 -0.019342 0.008667 -vn 0.688508 0.708952 0.152790 -v 0.029400 -0.019275 0.008145 -vn 0.390209 0.900061 0.193977 -v 0.032300 -0.019275 0.008145 -vn 0.688508 0.672932 0.270406 -v 0.029400 -0.019121 0.007642 -vn 0.390209 0.854332 0.343298 -v 0.032300 -0.019121 0.007642 -vn 0.688508 0.617554 0.380243 -v 0.029400 -0.018885 0.007173 -vn 0.390207 0.784026 0.482744 -v 0.032300 -0.018885 0.007173 -vn 0.688508 0.544409 0.479141 -v 0.029400 -0.018572 0.006750 -vn 0.390209 0.691163 0.608301 -v 0.032300 -0.018572 0.006750 -vn 0.688508 0.455603 0.564254 -v 0.029400 -0.018192 0.006386 -vn 0.390208 0.578418 0.716359 -v 0.032300 -0.018192 0.006386 -vn 0.688508 0.353690 0.633135 -v 0.029400 -0.017757 0.006092 -vn 0.390209 0.449034 0.803807 -v 0.032300 -0.017757 0.006092 -vn 0.688508 0.241603 0.683802 -v 0.029400 -0.017278 0.005875 -vn 0.390208 0.306731 0.868132 -v 0.032300 -0.017278 0.005875 -vn 0.688507 0.122562 0.714799 -v 0.029400 -0.016769 0.005743 -vn 0.390209 0.155601 0.907483 -v 0.032300 -0.016769 0.005743 -vn 0.931102 0.356573 0.076847 -v 0.029400 -0.018982 0.008208 -vn 0.931102 0.338455 0.136003 -v 0.029400 -0.018843 0.007754 -vn 0.931102 0.310603 0.191247 -v 0.029400 -0.018629 0.007330 -vn 0.931102 0.273814 0.240987 -v 0.029400 -0.018347 0.006948 -vn 0.931102 0.229149 0.283796 -v 0.029400 -0.018004 0.006620 -vn 0.931102 0.177891 0.318440 -v 0.029400 -0.017611 0.006354 -vn 0.931102 0.121515 0.343924 -v 0.029400 -0.017178 0.006158 -vn 0.931102 0.061645 0.359513 -v 0.029400 -0.016718 0.006038 -vn 0.931102 -0.000000 0.364758 -v 0.029400 -0.016245 0.005998 -vn 0.931102 -0.061645 0.359513 -v 0.029400 -0.015772 0.006038 -vn 0.931102 -0.121515 0.343924 -v 0.029400 -0.015312 0.006158 -vn 0.931102 -0.177891 0.318440 -v 0.029400 -0.014879 0.006354 -vn 0.931102 -0.229150 0.283796 -v 0.029400 -0.014486 0.006620 -vn 0.931102 -0.273815 0.240988 -v 0.029400 -0.014143 0.006948 -vn 0.931102 -0.310603 0.191246 -v 0.029400 -0.013861 0.007330 -vn 0.931102 -0.338457 0.136003 -v 0.029400 -0.013647 0.007754 -vn 0.931102 -0.356572 0.076847 -v 0.029400 -0.013508 0.008208 -vn 0.931102 -0.364431 0.015481 -v 0.029400 -0.013448 0.008679 -vn 0.931102 -0.361804 -0.046331 -v 0.029400 -0.013468 0.009154 -vn 0.931102 -0.348771 -0.106811 -v 0.029400 -0.013568 0.009618 -vn 0.931102 -0.325703 -0.164217 -v 0.029400 -0.013745 0.010059 -vn 0.931102 -0.293266 -0.216898 -v 0.029400 -0.013994 0.010463 -vn 0.931102 -0.252391 -0.263340 -v 0.029400 -0.014308 0.010820 -vn 0.931102 -0.204256 -0.302208 -v 0.029400 -0.014677 0.011118 -vn 0.931102 -0.150245 -0.332379 -v 0.029400 -0.015092 0.011350 -vn 0.931102 -0.091912 -0.352990 -v 0.029400 -0.015539 0.011508 -vn 0.931102 -0.030934 -0.363445 -v 0.029400 -0.016008 0.011588 -vn 0.931102 0.030934 -0.363445 -v 0.029400 -0.016482 0.011588 -vn 0.931102 0.091912 -0.352990 -v 0.029400 -0.016951 0.011508 -vn 0.931102 0.150245 -0.332379 -v 0.029400 -0.017398 0.011350 -vn 0.931102 0.204256 -0.302207 -v 0.029400 -0.017813 0.011118 -vn 0.931102 0.252391 -0.263340 -v 0.029400 -0.018182 0.010820 -vn 0.931102 0.293266 -0.216899 -v 0.029400 -0.018496 0.010463 -vn 0.931102 0.325702 -0.164216 -v 0.029400 -0.018745 0.010059 -vn 0.931102 0.348771 -0.106810 -v 0.029400 -0.018922 0.009618 -vn 0.931102 0.361805 -0.046331 -v 0.029400 -0.019022 0.009154 -vn 0.931102 0.364431 0.015480 -v 0.029400 -0.019042 0.008679 -vn 0.688510 -0.000000 0.725227 -v 0.029400 0.024370 0.005698 -vn 0.390213 0.000001 0.920725 -v 0.032300 0.024370 0.005698 -vn 0.688507 -0.122562 0.714799 -v 0.029400 0.024894 0.005743 -vn 0.390209 -0.155602 0.907483 -v 0.032300 0.024894 0.005743 -vn 0.688508 -0.241604 0.683802 -v 0.029400 0.025403 0.005875 -vn 0.390207 -0.306732 0.868132 -v 0.032300 0.025403 0.005875 -vn 0.688508 -0.353690 0.633135 -v 0.029400 0.025882 0.006092 -vn 0.390209 -0.449033 0.803807 -v 0.032300 0.025882 0.006092 -vn 0.688507 -0.455604 0.564254 -v 0.029400 0.026317 0.006386 -vn 0.390206 -0.578421 0.716358 -v 0.032300 0.026317 0.006386 -vn 0.688508 -0.544410 0.479140 -v 0.029400 0.026697 0.006750 -vn 0.390209 -0.691164 0.608301 -v 0.032300 0.026697 0.006750 -vn 0.688508 -0.617553 0.380243 -v 0.029400 0.027010 0.007173 -vn 0.390205 -0.784027 0.482744 -v 0.032300 0.027010 0.007173 -vn 0.688508 -0.672932 0.270407 -v 0.029400 0.027246 0.007642 -vn 0.390209 -0.854331 0.343300 -v 0.032300 0.027246 0.007642 -vn 0.688507 -0.708952 0.152790 -v 0.029400 0.027400 0.008145 -vn 0.390205 -0.900063 0.193976 -v 0.032300 0.027400 0.008145 -vn 0.688508 -0.724575 0.030778 -v 0.029400 0.027467 0.008667 -vn 0.390210 -0.919896 0.039076 -v 0.032300 0.027467 0.008667 -vn 0.688508 -0.719355 -0.092118 -v 0.029400 0.027445 0.009192 -vn 0.390209 -0.913269 -0.116950 -v 0.032300 0.027445 0.009192 -vn 0.688508 -0.693440 -0.212363 -v 0.029400 0.027334 0.009706 -vn 0.390210 -0.880368 -0.269609 -v 0.032300 0.027334 0.009706 -vn 0.688507 -0.647576 -0.326501 -v 0.029400 0.027138 0.010194 -vn 0.390211 -0.822140 -0.414514 -v 0.032300 0.027138 0.010194 -vn 0.688508 -0.583082 -0.431244 -v 0.029400 0.026862 0.010641 -vn 0.390212 -0.740261 -0.547492 -v 0.032300 0.026862 0.010641 -vn 0.688507 -0.501815 -0.523583 -v 0.029400 0.026515 0.011036 -vn 0.390209 -0.637087 -0.664723 -v 0.032300 0.026515 0.011036 -vn 0.688507 -0.406109 -0.600860 -v 0.029400 0.026106 0.011366 -vn 0.390209 -0.515583 -0.762831 -v 0.032300 0.026106 0.011366 -vn 0.688508 -0.298721 -0.660850 -v 0.029400 0.025647 0.011623 -vn 0.390208 -0.379247 -0.838993 -v 0.032300 0.025647 0.011623 -vn 0.688509 -0.182743 -0.701827 -v 0.029400 0.025151 0.011798 -vn 0.390210 -0.232006 -0.891016 -v 0.032300 0.025151 0.011798 -vn 0.688507 -0.061506 -0.722617 -v 0.029400 0.024633 0.011887 -vn 0.390208 -0.078085 -0.917410 -v 0.032300 0.024633 0.011887 -vn 0.688507 0.061506 -0.722617 -v 0.029400 0.024107 0.011887 -vn 0.390208 0.078086 -0.917410 -v 0.032300 0.024107 0.011887 -vn 0.688508 0.182743 -0.701827 -v 0.029400 0.023589 0.011798 -vn 0.390210 0.232004 -0.891016 -v 0.032300 0.023589 0.011798 -vn 0.688508 0.298720 -0.660850 -v 0.029400 0.023093 0.011623 -vn 0.390210 0.379245 -0.838993 -v 0.032300 0.023093 0.011623 -vn 0.688507 0.406110 -0.600860 -v 0.029400 0.022634 0.011366 -vn 0.390209 0.515583 -0.762831 -v 0.032300 0.022634 0.011366 -vn 0.688508 0.501816 -0.523581 -v 0.029400 0.022225 0.011036 -vn 0.390208 0.637089 -0.664721 -v 0.032300 0.022225 0.011036 -vn 0.688508 0.583082 -0.431244 -v 0.029400 0.021878 0.010641 -vn 0.390211 0.740261 -0.547493 -v 0.032300 0.021878 0.010641 -vn 0.688508 0.647574 -0.326503 -v 0.029400 0.021602 0.010194 -vn 0.390211 0.822139 -0.414516 -v 0.032300 0.021602 0.010194 -vn 0.688507 0.693440 -0.212366 -v 0.029400 0.021406 0.009706 -vn 0.390207 0.880368 -0.269612 -v 0.032300 0.021406 0.009706 -vn 0.688507 0.719356 -0.092115 -v 0.029400 0.021295 0.009192 -vn 0.390209 0.913269 -0.116947 -v 0.032300 0.021295 0.009192 -vn 0.688509 0.724575 0.030781 -v 0.029400 0.021273 0.008667 -vn 0.390210 0.919896 0.039077 -v 0.032300 0.021273 0.008667 -vn 0.688507 0.708952 0.152790 -v 0.029400 0.021340 0.008145 -vn 0.390209 0.900061 0.193977 -v 0.032300 0.021340 0.008145 -vn 0.688508 0.672932 0.270407 -v 0.029400 0.021494 0.007642 -vn 0.390210 0.854331 0.343299 -v 0.032300 0.021494 0.007642 -vn 0.688508 0.617553 0.380243 -v 0.029400 0.021730 0.007173 -vn 0.390209 0.784025 0.482745 -v 0.032300 0.021730 0.007173 -vn 0.688508 0.544409 0.479140 -v 0.029400 0.022043 0.006750 -vn 0.390210 0.691164 0.608300 -v 0.032300 0.022043 0.006750 -vn 0.688507 0.455603 0.564255 -v 0.029400 0.022423 0.006386 -vn 0.390209 0.578417 0.716359 -v 0.032300 0.022423 0.006386 -vn 0.688509 0.353690 0.633135 -v 0.029400 0.022858 0.006092 -vn 0.390211 0.449033 0.803806 -v 0.032300 0.022858 0.006092 -vn 0.688507 0.241605 0.683802 -v 0.029400 0.023337 0.005875 -vn 0.390208 0.306732 0.868132 -v 0.032300 0.023337 0.005875 -vn 0.688507 0.122562 0.714799 -v 0.029400 0.023846 0.005743 -vn 0.390208 0.155601 0.907483 -v 0.032300 0.023846 0.005743 -vn 0.931102 0.356571 0.076848 -v 0.029400 0.021633 0.008208 -vn 0.931101 0.338457 0.136004 -v 0.029400 0.021772 0.007754 -vn 0.931102 0.310603 0.191246 -v 0.029400 0.021986 0.007330 -vn 0.931102 0.273814 0.240987 -v 0.029400 0.022268 0.006948 -vn 0.931102 0.229150 0.283796 -v 0.029400 0.022611 0.006620 -vn 0.931102 0.177891 0.318439 -v 0.029400 0.023004 0.006354 -vn 0.931102 0.121515 0.343924 -v 0.029400 0.023437 0.006158 -vn 0.931102 0.061645 0.359513 -v 0.029400 0.023897 0.006038 -vn 0.931102 -0.000000 0.364758 -v 0.029400 0.024370 0.005998 -vn 0.931102 -0.061645 0.359513 -v 0.029400 0.024843 0.006038 -vn 0.931102 -0.121515 0.343924 -v 0.029400 0.025303 0.006158 -vn 0.931102 -0.177891 0.318439 -v 0.029400 0.025736 0.006354 -vn 0.931102 -0.229150 0.283796 -v 0.029400 0.026129 0.006620 -vn 0.931102 -0.273814 0.240987 -v 0.029400 0.026472 0.006948 -vn 0.931102 -0.310603 0.191247 -v 0.029400 0.026754 0.007330 -vn 0.931102 -0.338455 0.136003 -v 0.029400 0.026968 0.007754 -vn 0.931102 -0.356573 0.076847 -v 0.029400 0.027107 0.008208 -vn 0.931102 -0.364431 0.015480 -v 0.029400 0.027167 0.008679 -vn 0.931102 -0.361805 -0.046332 -v 0.029400 0.027147 0.009154 -vn 0.931102 -0.348771 -0.106811 -v 0.029400 0.027047 0.009618 -vn 0.931102 -0.325703 -0.164217 -v 0.029400 0.026870 0.010059 -vn 0.931102 -0.293266 -0.216898 -v 0.029400 0.026621 0.010463 -vn 0.931102 -0.252391 -0.263340 -v 0.029400 0.026307 0.010820 -vn 0.931101 -0.204256 -0.302208 -v 0.029400 0.025938 0.011118 -vn 0.931102 -0.150245 -0.332379 -v 0.029400 0.025523 0.011350 -vn 0.931102 -0.091912 -0.352990 -v 0.029400 0.025076 0.011508 -vn 0.931102 -0.030934 -0.363445 -v 0.029400 0.024607 0.011588 -vn 0.931102 0.030934 -0.363445 -v 0.029400 0.024133 0.011588 -vn 0.931102 0.091912 -0.352990 -v 0.029400 0.023664 0.011508 -vn 0.931102 0.150245 -0.332380 -v 0.029400 0.023217 0.011350 -vn 0.931102 0.204256 -0.302206 -v 0.029400 0.022802 0.011118 -vn 0.931102 0.252392 -0.263340 -v 0.029400 0.022433 0.010820 -vn 0.931102 0.293266 -0.216898 -v 0.029400 0.022119 0.010463 -vn 0.931101 0.325703 -0.164218 -v 0.029400 0.021870 0.010059 -vn 0.931103 0.348769 -0.106810 -v 0.029400 0.021693 0.009618 -vn 0.931102 0.361806 -0.046330 -v 0.029400 0.021593 0.009154 -vn 0.931102 0.364430 0.015480 -v 0.029400 0.021573 0.008679 -vn 0.688510 -0.000000 0.725227 -v 0.029400 0.004065 0.005698 -vn 0.390213 0.000001 0.920725 -v 0.032300 0.004065 0.005698 -vn 0.688507 -0.122562 0.714799 -v 0.029400 0.004589 0.005743 -vn 0.390209 -0.155602 0.907483 -v 0.032300 0.004589 0.005743 -vn 0.688507 -0.241605 0.683802 -v 0.029400 0.005098 0.005875 -vn 0.390207 -0.306734 0.868132 -v 0.032300 0.005098 0.005875 -vn 0.688509 -0.353690 0.633135 -v 0.029400 0.005577 0.006092 -vn 0.390211 -0.449032 0.803807 -v 0.032300 0.005577 0.006092 -vn 0.688507 -0.455603 0.564255 -v 0.029400 0.006012 0.006386 -vn 0.390206 -0.578420 0.716359 -v 0.032300 0.006012 0.006386 -vn 0.688508 -0.544410 0.479140 -v 0.029400 0.006392 0.006750 -vn 0.390209 -0.691164 0.608301 -v 0.032300 0.006392 0.006750 -vn 0.688508 -0.617553 0.380243 -v 0.029400 0.006705 0.007173 -vn 0.390209 -0.784025 0.482744 -v 0.032300 0.006705 0.007173 -vn 0.688508 -0.672932 0.270407 -v 0.029400 0.006941 0.007642 -vn 0.390209 -0.854332 0.343299 -v 0.032300 0.006941 0.007642 -vn 0.688507 -0.708952 0.152790 -v 0.029400 0.007095 0.008145 -vn 0.390209 -0.900061 0.193976 -v 0.032300 0.007095 0.008145 -vn 0.688508 -0.724575 0.030778 -v 0.029400 0.007162 0.008667 -vn 0.390211 -0.919896 0.039075 -v 0.032300 0.007162 0.008667 -vn 0.688508 -0.719355 -0.092118 -v 0.029400 0.007140 0.009192 -vn 0.390209 -0.913269 -0.116950 -v 0.032300 0.007140 0.009192 -vn 0.688508 -0.693440 -0.212363 -v 0.029400 0.007029 0.009706 -vn 0.390210 -0.880368 -0.269609 -v 0.032300 0.007029 0.009706 -vn 0.688507 -0.647576 -0.326501 -v 0.029400 0.006833 0.010194 -vn 0.390211 -0.822140 -0.414514 -v 0.032300 0.006833 0.010194 -vn 0.688508 -0.583082 -0.431244 -v 0.029400 0.006557 0.010641 -vn 0.390212 -0.740261 -0.547492 -v 0.032300 0.006557 0.010641 -vn 0.688507 -0.501815 -0.523583 -v 0.029400 0.006210 0.011036 -vn 0.390209 -0.637087 -0.664723 -v 0.032300 0.006210 0.011036 -vn 0.688507 -0.406109 -0.600860 -v 0.029400 0.005801 0.011366 -vn 0.390209 -0.515583 -0.762831 -v 0.032300 0.005801 0.011366 -vn 0.688508 -0.298721 -0.660850 -v 0.029400 0.005342 0.011623 -vn 0.390208 -0.379247 -0.838993 -v 0.032300 0.005342 0.011623 -vn 0.688509 -0.182743 -0.701827 -v 0.029400 0.004846 0.011798 -vn 0.390210 -0.232006 -0.891016 -v 0.032300 0.004846 0.011798 -vn 0.688507 -0.061506 -0.722617 -v 0.029400 0.004328 0.011887 -vn 0.390208 -0.078085 -0.917410 -v 0.032300 0.004328 0.011887 -vn 0.688507 0.061506 -0.722617 -v 0.029400 0.003802 0.011887 -vn 0.390208 0.078086 -0.917410 -v 0.032300 0.003802 0.011887 -vn 0.688508 0.182743 -0.701827 -v 0.029400 0.003284 0.011798 -vn 0.390210 0.232004 -0.891016 -v 0.032300 0.003284 0.011798 -vn 0.688508 0.298720 -0.660850 -v 0.029400 0.002788 0.011623 -vn 0.390210 0.379245 -0.838993 -v 0.032300 0.002788 0.011623 -vn 0.688507 0.406110 -0.600860 -v 0.029400 0.002329 0.011366 -vn 0.390207 0.515584 -0.762831 -v 0.032300 0.002329 0.011366 -vn 0.688508 0.501816 -0.523581 -v 0.029400 0.001920 0.011036 -vn 0.390208 0.637089 -0.664722 -v 0.032300 0.001920 0.011036 -vn 0.688508 0.583082 -0.431244 -v 0.029400 0.001573 0.010641 -vn 0.390211 0.740261 -0.547493 -v 0.032300 0.001573 0.010641 -vn 0.688508 0.647574 -0.326503 -v 0.029400 0.001297 0.010194 -vn 0.390211 0.822139 -0.414516 -v 0.032300 0.001297 0.010194 -vn 0.688507 0.693441 -0.212363 -v 0.029400 0.001101 0.009706 -vn 0.390208 0.880369 -0.269608 -v 0.032300 0.001101 0.009706 -vn 0.688509 0.719354 -0.092115 -v 0.029400 0.000990 0.009192 -vn 0.390212 0.913268 -0.116947 -v 0.032300 0.000990 0.009192 -vn 0.688508 0.724575 0.030778 -v 0.029400 0.000968 0.008667 -vn 0.390211 0.919896 0.039075 -v 0.032300 0.000968 0.008667 -vn 0.688508 0.708952 0.152790 -v 0.029400 0.001035 0.008145 -vn 0.390209 0.900061 0.193977 -v 0.032300 0.001035 0.008145 -vn 0.688508 0.672932 0.270407 -v 0.029400 0.001189 0.007642 -vn 0.390210 0.854331 0.343299 -v 0.032300 0.001189 0.007642 -vn 0.688508 0.617553 0.380243 -v 0.029400 0.001425 0.007173 -vn 0.390209 0.784025 0.482745 -v 0.032300 0.001425 0.007173 -vn 0.688508 0.544409 0.479140 -v 0.029400 0.001738 0.006750 -vn 0.390210 0.691164 0.608300 -v 0.032300 0.001738 0.006750 -vn 0.688507 0.455604 0.564254 -v 0.029400 0.002118 0.006386 -vn 0.390208 0.578419 0.716358 -v 0.032300 0.002118 0.006386 -vn 0.688508 0.353690 0.633135 -v 0.029400 0.002553 0.006092 -vn 0.390210 0.449034 0.803807 -v 0.032300 0.002553 0.006092 -vn 0.688508 0.241604 0.683802 -v 0.029400 0.003032 0.005875 -vn 0.390207 0.306731 0.868133 -v 0.032300 0.003032 0.005875 -vn 0.688507 0.122562 0.714799 -v 0.029400 0.003541 0.005743 -vn 0.390209 0.155601 0.907483 -v 0.032300 0.003541 0.005743 -vn 0.931102 0.091912 -0.352990 -v 0.029400 0.003359 0.011508 -vn 0.931102 0.150245 -0.332379 -v 0.029400 0.002912 0.011350 -vn 0.931101 0.204257 -0.302208 -v 0.029400 0.002497 0.011118 -vn 0.931102 0.252390 -0.263341 -v 0.029400 0.002128 0.010820 -vn 0.931102 0.293265 -0.216898 -v 0.029400 0.001814 0.010463 -vn 0.931102 0.325703 -0.164216 -v 0.029400 0.001565 0.010059 -vn 0.931102 0.348770 -0.106809 -v 0.029400 0.001388 0.009618 -vn 0.931102 0.361806 -0.046331 -v 0.029400 0.001288 0.009154 -vn 0.931102 0.364431 0.015480 -v 0.029400 0.001268 0.008679 -vn 0.931102 0.356572 0.076846 -v 0.029400 0.001328 0.008208 -vn 0.931102 0.338455 0.136003 -v 0.029400 0.001467 0.007754 -vn 0.931102 0.310603 0.191247 -v 0.029400 0.001681 0.007330 -vn 0.931102 0.273815 0.240987 -v 0.029400 0.001963 0.006948 -vn 0.931102 0.229149 0.283795 -v 0.029400 0.002306 0.006620 -vn 0.931102 0.177891 0.318440 -v 0.029400 0.002699 0.006354 -vn 0.931102 0.121515 0.343924 -v 0.029400 0.003132 0.006158 -vn 0.931102 0.061645 0.359513 -v 0.029400 0.003592 0.006038 -vn 0.931102 -0.000000 0.364758 -v 0.029400 0.004065 0.005998 -vn 0.931102 -0.061645 0.359513 -v 0.029400 0.004538 0.006038 -vn 0.931102 -0.121515 0.343924 -v 0.029400 0.004998 0.006158 -vn 0.931102 -0.177891 0.318439 -v 0.029400 0.005431 0.006354 -vn 0.931102 -0.229150 0.283796 -v 0.029400 0.005824 0.006620 -vn 0.931102 -0.273814 0.240987 -v 0.029400 0.006167 0.006948 -vn 0.931102 -0.310604 0.191246 -v 0.029400 0.006449 0.007330 -vn 0.931101 -0.338457 0.136004 -v 0.029400 0.006663 0.007754 -vn 0.931102 -0.356571 0.076848 -v 0.029400 0.006802 0.008208 -vn 0.931102 -0.364431 0.015480 -v 0.029400 0.006862 0.008679 -vn 0.931102 -0.361805 -0.046332 -v 0.029400 0.006842 0.009154 -vn 0.931102 -0.348771 -0.106811 -v 0.029400 0.006742 0.009618 -vn 0.931102 -0.325703 -0.164217 -v 0.029400 0.006565 0.010059 -vn 0.931102 -0.293266 -0.216898 -v 0.029400 0.006316 0.010463 -vn 0.931102 -0.252391 -0.263340 -v 0.029400 0.006002 0.010820 -vn 0.931101 -0.204256 -0.302208 -v 0.029400 0.005633 0.011118 -vn 0.931102 -0.150245 -0.332379 -v 0.029400 0.005218 0.011350 -vn 0.931102 -0.091912 -0.352990 -v 0.029400 0.004771 0.011508 -vn 0.931102 -0.030934 -0.363445 -v 0.029400 0.004302 0.011588 -vn 0.931102 0.030934 -0.363445 -v 0.029400 0.003828 0.011588 -vn 0.688510 -0.000000 0.725227 -v 0.029400 0.016240 0.005698 -vn 0.390213 0.000001 0.920725 -v 0.032300 0.016240 0.005698 -vn 0.688507 -0.122562 0.714799 -v 0.029400 0.016764 0.005743 -vn 0.390210 -0.155601 0.907482 -v 0.032300 0.016764 0.005743 -vn 0.688508 -0.241604 0.683802 -v 0.029400 0.017273 0.005875 -vn 0.390207 -0.306732 0.868132 -v 0.032300 0.017273 0.005875 -vn 0.688508 -0.353690 0.633135 -v 0.029400 0.017752 0.006092 -vn 0.390209 -0.449033 0.803807 -v 0.032300 0.017752 0.006092 -vn 0.688507 -0.455604 0.564254 -v 0.029400 0.018187 0.006386 -vn 0.390208 -0.578419 0.716358 -v 0.032300 0.018187 0.006386 -vn 0.688508 -0.544410 0.479140 -v 0.029400 0.018567 0.006750 -vn 0.390209 -0.691164 0.608300 -v 0.032300 0.018567 0.006750 -vn 0.688508 -0.617553 0.380243 -v 0.029400 0.018880 0.007173 -vn 0.390209 -0.784025 0.482744 -v 0.032300 0.018880 0.007173 -vn 0.688508 -0.672932 0.270407 -v 0.029400 0.019116 0.007642 -vn 0.390209 -0.854332 0.343299 -v 0.032300 0.019116 0.007642 -vn 0.688507 -0.708952 0.152790 -v 0.029400 0.019270 0.008145 -vn 0.390209 -0.900061 0.193976 -v 0.032300 0.019270 0.008145 -vn 0.688508 -0.724575 0.030778 -v 0.029400 0.019337 0.008667 -vn 0.390211 -0.919896 0.039075 -v 0.032300 0.019337 0.008667 -vn 0.688509 -0.719354 -0.092115 -v 0.029400 0.019315 0.009192 -vn 0.390213 -0.913268 -0.116945 -v 0.032300 0.019315 0.009192 -vn 0.688506 -0.693441 -0.212363 -v 0.029400 0.019204 0.009706 -vn 0.390208 -0.880368 -0.269611 -v 0.032300 0.019204 0.009706 -vn 0.688509 -0.647575 -0.326500 -v 0.029400 0.019008 0.010194 -vn 0.390210 -0.822141 -0.414513 -v 0.032300 0.019008 0.010194 -vn 0.688507 -0.583083 -0.431244 -v 0.029400 0.018732 0.010641 -vn 0.390209 -0.740262 -0.547493 -v 0.032300 0.018732 0.010641 -vn 0.688508 -0.501815 -0.523582 -v 0.029400 0.018385 0.011036 -vn 0.390208 -0.637088 -0.664723 -v 0.032300 0.018385 0.011036 -vn 0.688507 -0.406110 -0.600860 -v 0.029400 0.017976 0.011366 -vn 0.390207 -0.515583 -0.762832 -v 0.032300 0.017976 0.011366 -vn 0.688508 -0.298720 -0.660850 -v 0.029400 0.017517 0.011623 -vn 0.390207 -0.379246 -0.838994 -v 0.032300 0.017517 0.011623 -vn 0.688509 -0.182743 -0.701827 -v 0.029400 0.017021 0.011798 -vn 0.390210 -0.232006 -0.891016 -v 0.032300 0.017021 0.011798 -vn 0.688507 -0.061506 -0.722617 -v 0.029400 0.016503 0.011887 -vn 0.390208 -0.078085 -0.917410 -v 0.032300 0.016503 0.011887 -vn 0.688507 0.061506 -0.722617 -v 0.029400 0.015977 0.011887 -vn 0.390207 0.078086 -0.917410 -v 0.032300 0.015977 0.011887 -vn 0.688508 0.182743 -0.701827 -v 0.029400 0.015459 0.011798 -vn 0.390210 0.232004 -0.891016 -v 0.032300 0.015459 0.011798 -vn 0.688508 0.298721 -0.660850 -v 0.029400 0.014963 0.011623 -vn 0.390208 0.379248 -0.838993 -v 0.032300 0.014963 0.011623 -vn 0.688507 0.406111 -0.600859 -v 0.029400 0.014504 0.011366 -vn 0.390209 0.515584 -0.762830 -v 0.032300 0.014504 0.011366 -vn 0.688509 0.501814 -0.523582 -v 0.029400 0.014095 0.011036 -vn 0.390211 0.637086 -0.664723 -v 0.032300 0.014095 0.011036 -vn 0.688508 0.583081 -0.431246 -v 0.029400 0.013748 0.010641 -vn 0.390212 0.740260 -0.547495 -v 0.032300 0.013748 0.010641 -vn 0.688508 0.647576 -0.326501 -v 0.029400 0.013472 0.010194 -vn 0.390211 0.822140 -0.414513 -v 0.032300 0.013472 0.010194 -vn 0.688508 0.693440 -0.212363 -v 0.029400 0.013276 0.009706 -vn 0.390211 0.880367 -0.269609 -v 0.032300 0.013276 0.009706 -vn 0.688508 0.719355 -0.092118 -v 0.029400 0.013165 0.009192 -vn 0.390209 0.913269 -0.116949 -v 0.032300 0.013165 0.009192 -vn 0.688508 0.724575 0.030778 -v 0.029400 0.013143 0.008667 -vn 0.390211 0.919896 0.039074 -v 0.032300 0.013143 0.008667 -vn 0.688507 0.708952 0.152790 -v 0.029400 0.013210 0.008145 -vn 0.390209 0.900061 0.193977 -v 0.032300 0.013210 0.008145 -vn 0.688508 0.672932 0.270407 -v 0.029400 0.013364 0.007642 -vn 0.390210 0.854331 0.343299 -v 0.032300 0.013364 0.007642 -vn 0.688508 0.617553 0.380243 -v 0.029400 0.013600 0.007173 -vn 0.390209 0.784025 0.482745 -v 0.032300 0.013600 0.007173 -vn 0.688508 0.544409 0.479140 -v 0.029400 0.013913 0.006750 -vn 0.390210 0.691164 0.608300 -v 0.032300 0.013913 0.006750 -vn 0.688507 0.455603 0.564255 -v 0.029400 0.014293 0.006386 -vn 0.390206 0.578417 0.716361 -v 0.032300 0.014293 0.006386 -vn 0.688509 0.353690 0.633135 -v 0.029400 0.014728 0.006092 -vn 0.390211 0.449034 0.803806 -v 0.032300 0.014728 0.006092 -vn 0.688507 0.241605 0.683802 -v 0.029400 0.015207 0.005875 -vn 0.390208 0.306732 0.868132 -v 0.032300 0.015207 0.005875 -vn 0.688507 0.122562 0.714799 -v 0.029400 0.015716 0.005743 -vn 0.390208 0.155601 0.907483 -v 0.032300 0.015716 0.005743 -vn 0.931102 0.177891 0.318440 -v 0.029400 0.014874 0.006354 -vn 0.931102 0.121515 0.343923 -v 0.029400 0.015307 0.006158 -vn 0.931102 0.061645 0.359513 -v 0.029400 0.015767 0.006038 -vn 0.931102 -0.000000 0.364758 -v 0.029400 0.016240 0.005998 -vn 0.931102 -0.061645 0.359513 -v 0.029400 0.016713 0.006038 -vn 0.931102 -0.121515 0.343924 -v 0.029400 0.017173 0.006158 -vn 0.931102 -0.177891 0.318440 -v 0.029400 0.017606 0.006354 -vn 0.931102 -0.229149 0.283795 -v 0.029400 0.017999 0.006620 -vn 0.931102 -0.273815 0.240987 -v 0.029400 0.018342 0.006948 -vn 0.931101 -0.310604 0.191247 -v 0.029400 0.018624 0.007330 -vn 0.931102 -0.338455 0.136003 -v 0.029400 0.018838 0.007754 -vn 0.931102 -0.356573 0.076847 -v 0.029400 0.018977 0.008208 -vn 0.931102 -0.364431 0.015480 -v 0.029400 0.019037 0.008679 -vn 0.931102 -0.361805 -0.046332 -v 0.029400 0.019017 0.009154 -vn 0.931102 -0.348771 -0.106811 -v 0.029400 0.018917 0.009618 -vn 0.931101 -0.325704 -0.164216 -v 0.029400 0.018740 0.010059 -vn 0.931102 -0.293266 -0.216896 -v 0.029400 0.018491 0.010463 -vn 0.931102 -0.252390 -0.263340 -v 0.029400 0.018177 0.010820 -vn 0.931101 -0.204256 -0.302209 -v 0.029400 0.017808 0.011118 -vn 0.931102 -0.150245 -0.332379 -v 0.029400 0.017393 0.011350 -vn 0.931102 -0.091912 -0.352990 -v 0.029400 0.016946 0.011508 -vn 0.931102 -0.030934 -0.363445 -v 0.029400 0.016477 0.011588 -vn 0.931102 0.030934 -0.363445 -v 0.029400 0.016003 0.011588 -vn 0.931102 0.091912 -0.352990 -v 0.029400 0.015534 0.011508 -vn 0.931102 0.150245 -0.332379 -v 0.029400 0.015087 0.011350 -vn 0.931102 0.204256 -0.302207 -v 0.029400 0.014672 0.011118 -vn 0.931102 0.252391 -0.263340 -v 0.029400 0.014303 0.010820 -vn 0.931102 0.293266 -0.216898 -v 0.029400 0.013989 0.010463 -vn 0.931102 0.325703 -0.164217 -v 0.029400 0.013740 0.010059 -vn 0.931102 0.348770 -0.106811 -v 0.029400 0.013563 0.009618 -vn 0.931102 0.361805 -0.046332 -v 0.029400 0.013463 0.009154 -vn 0.931102 0.364430 0.015480 -v 0.029400 0.013443 0.008679 -vn 0.931102 0.356571 0.076848 -v 0.029400 0.013503 0.008208 -vn 0.931101 0.338457 0.136004 -v 0.029400 0.013642 0.007754 -vn 0.931102 0.310603 0.191246 -v 0.029400 0.013856 0.007330 -vn 0.931102 0.273814 0.240987 -v 0.029400 0.014138 0.006948 -vn 0.931102 0.229149 0.283797 -v 0.029400 0.014481 0.006620 -vn 0.688510 -0.000000 0.725227 -v 0.029400 -0.004065 0.005698 -vn 0.390213 0.000002 0.920725 -v 0.032300 -0.004065 0.005698 -vn 0.688507 -0.122562 0.714799 -v 0.029400 -0.003541 0.005743 -vn 0.390210 -0.155602 0.907482 -v 0.032300 -0.003541 0.005743 -vn 0.688508 -0.241604 0.683802 -v 0.029400 -0.003032 0.005875 -vn 0.390207 -0.306733 0.868132 -v 0.032300 -0.003032 0.005875 -vn 0.688508 -0.353690 0.633135 -v 0.029400 -0.002553 0.006092 -vn 0.390210 -0.449032 0.803807 -v 0.032300 -0.002553 0.006092 -vn 0.688507 -0.455603 0.564255 -v 0.029400 -0.002118 0.006386 -vn 0.390207 -0.578419 0.716359 -v 0.032300 -0.002118 0.006386 -vn 0.688508 -0.544409 0.479141 -v 0.029400 -0.001738 0.006750 -vn 0.390208 -0.691164 0.608301 -v 0.032300 -0.001738 0.006750 -vn 0.688507 -0.617554 0.380242 -v 0.029400 -0.001425 0.007173 -vn 0.390207 -0.784027 0.482743 -v 0.032300 -0.001425 0.007173 -vn 0.688508 -0.672932 0.270405 -v 0.029400 -0.001189 0.007642 -vn 0.390209 -0.854332 0.343298 -v 0.032300 -0.001189 0.007642 -vn 0.688507 -0.708952 0.152790 -v 0.029400 -0.001035 0.008145 -vn 0.390209 -0.900061 0.193976 -v 0.032300 -0.001035 0.008145 -vn 0.688508 -0.724575 0.030778 -v 0.029400 -0.000968 0.008667 -vn 0.390211 -0.919896 0.039075 -v 0.032300 -0.000968 0.008667 -vn 0.688508 -0.719355 -0.092116 -v 0.029400 -0.000990 0.009192 -vn 0.390213 -0.913267 -0.116947 -v 0.032300 -0.000990 0.009192 -vn 0.688507 -0.693440 -0.212363 -v 0.029400 -0.001101 0.009706 -vn 0.390209 -0.880368 -0.269610 -v 0.032300 -0.001101 0.009706 -vn 0.688508 -0.647575 -0.326500 -v 0.029400 -0.001297 0.010194 -vn 0.390210 -0.822140 -0.414513 -v 0.032300 -0.001297 0.010194 -vn 0.688508 -0.583083 -0.431244 -v 0.029400 -0.001573 0.010641 -vn 0.390210 -0.740262 -0.547493 -v 0.032300 -0.001573 0.010641 -vn 0.688508 -0.501815 -0.523583 -v 0.029400 -0.001920 0.011036 -vn 0.390210 -0.637087 -0.664723 -v 0.032300 -0.001920 0.011036 -vn 0.688507 -0.406110 -0.600860 -v 0.029400 -0.002329 0.011366 -vn 0.390209 -0.515582 -0.762832 -v 0.032300 -0.002329 0.011366 -vn 0.688508 -0.298721 -0.660850 -v 0.029400 -0.002788 0.011623 -vn 0.390209 -0.379246 -0.838993 -v 0.032300 -0.002788 0.011623 -vn 0.688509 -0.182744 -0.701827 -v 0.029400 -0.003284 0.011798 -vn 0.390210 -0.232006 -0.891016 -v 0.032300 -0.003284 0.011798 -vn 0.688507 -0.061506 -0.722617 -v 0.029400 -0.003802 0.011887 -vn 0.390208 -0.078085 -0.917410 -v 0.032300 -0.003802 0.011887 -vn 0.688507 0.061506 -0.722617 -v 0.029400 -0.004328 0.011887 -vn 0.390207 0.078086 -0.917410 -v 0.032300 -0.004328 0.011887 -vn 0.688508 0.182743 -0.701827 -v 0.029400 -0.004846 0.011798 -vn 0.390210 0.232004 -0.891016 -v 0.032300 -0.004846 0.011798 -vn 0.688508 0.298721 -0.660850 -v 0.029400 -0.005342 0.011623 -vn 0.390209 0.379247 -0.838993 -v 0.032300 -0.005342 0.011623 -vn 0.688507 0.406110 -0.600860 -v 0.029400 -0.005801 0.011366 -vn 0.390208 0.515584 -0.762831 -v 0.032300 -0.005801 0.011366 -vn 0.688508 0.501815 -0.523582 -v 0.029400 -0.006210 0.011036 -vn 0.390209 0.637088 -0.664723 -v 0.032300 -0.006210 0.011036 -vn 0.688508 0.583083 -0.431244 -v 0.029400 -0.006557 0.010641 -vn 0.390210 0.740262 -0.547493 -v 0.032300 -0.006557 0.010641 -vn 0.688509 0.647575 -0.326501 -v 0.029400 -0.006833 0.010194 -vn 0.390212 0.822138 -0.414515 -v 0.032300 -0.006833 0.010194 -vn 0.688507 0.693440 -0.212365 -v 0.029400 -0.007029 0.009706 -vn 0.390210 0.880368 -0.269610 -v 0.032300 -0.007029 0.009706 -vn 0.688508 0.719355 -0.092116 -v 0.029400 -0.007140 0.009192 -vn 0.390211 0.913268 -0.116948 -v 0.032300 -0.007140 0.009192 -vn 0.688508 0.724576 0.030779 -v 0.029400 -0.007162 0.008667 -vn 0.390209 0.919897 0.039077 -v 0.032300 -0.007162 0.008667 -vn 0.688508 0.708951 0.152791 -v 0.029400 -0.007095 0.008145 -vn 0.390209 0.900061 0.193978 -v 0.032300 -0.007095 0.008145 -vn 0.688508 0.672932 0.270405 -v 0.029400 -0.006941 0.007642 -vn 0.390210 0.854332 0.343297 -v 0.032300 -0.006941 0.007642 -vn 0.688508 0.617554 0.380242 -v 0.029400 -0.006705 0.007173 -vn 0.390207 0.784026 0.482744 -v 0.032300 -0.006705 0.007173 -vn 0.688508 0.544409 0.479141 -v 0.029400 -0.006392 0.006750 -vn 0.390208 0.691164 0.608301 -v 0.032300 -0.006392 0.006750 -vn 0.688508 0.455603 0.564255 -v 0.029400 -0.006012 0.006386 -vn 0.390208 0.578418 0.716359 -v 0.032300 -0.006012 0.006386 -vn 0.688508 0.353690 0.633135 -v 0.029400 -0.005577 0.006092 -vn 0.390210 0.449034 0.803807 -v 0.032300 -0.005577 0.006092 -vn 0.688508 0.241604 0.683802 -v 0.029400 -0.005098 0.005875 -vn 0.390207 0.306731 0.868133 -v 0.032300 -0.005098 0.005875 -vn 0.688507 0.122562 0.714799 -v 0.029400 -0.004589 0.005743 -vn 0.390209 0.155601 0.907483 -v 0.032300 -0.004589 0.005743 -vn 0.931102 -0.310603 0.191246 -v 0.029400 -0.001681 0.007330 -vn 0.931102 -0.338457 0.136003 -v 0.029400 -0.001467 0.007754 -vn 0.931102 -0.356572 0.076847 -v 0.029400 -0.001328 0.008208 -vn 0.931102 -0.364431 0.015481 -v 0.029400 -0.001268 0.008679 -vn 0.931102 -0.361804 -0.046331 -v 0.029400 -0.001288 0.009154 -vn 0.931102 -0.348771 -0.106811 -v 0.029400 -0.001388 0.009618 -vn 0.931102 -0.325703 -0.164217 -v 0.029400 -0.001565 0.010059 -vn 0.931102 -0.293266 -0.216898 -v 0.029400 -0.001814 0.010463 -vn 0.931102 -0.252391 -0.263340 -v 0.029400 -0.002128 0.010820 -vn 0.931102 -0.204256 -0.302208 -v 0.029400 -0.002497 0.011118 -vn 0.931102 -0.150245 -0.332379 -v 0.029400 -0.002912 0.011350 -vn 0.931102 -0.091912 -0.352990 -v 0.029400 -0.003359 0.011508 -vn 0.931102 -0.030934 -0.363445 -v 0.029400 -0.003828 0.011588 -vn 0.931102 0.030934 -0.363445 -v 0.029400 -0.004302 0.011588 -vn 0.931102 0.091912 -0.352990 -v 0.029400 -0.004771 0.011508 -vn 0.931102 0.150245 -0.332379 -v 0.029400 -0.005218 0.011350 -vn 0.931102 0.204256 -0.302208 -v 0.029400 -0.005633 0.011118 -vn 0.931102 0.252390 -0.263340 -v 0.029400 -0.006002 0.010820 -vn 0.931102 0.293265 -0.216898 -v 0.029400 -0.006316 0.010463 -vn 0.931101 0.325704 -0.164217 -v 0.029400 -0.006565 0.010059 -vn 0.931102 0.348769 -0.106810 -v 0.029400 -0.006742 0.009618 -vn 0.931102 0.361805 -0.046330 -v 0.029400 -0.006842 0.009154 -vn 0.931102 0.364431 0.015481 -v 0.029400 -0.006862 0.008679 -vn 0.931102 0.356572 0.076847 -v 0.029400 -0.006802 0.008208 -vn 0.931102 0.338456 0.136003 -v 0.029400 -0.006663 0.007754 -vn 0.931102 0.310603 0.191247 -v 0.029400 -0.006449 0.007330 -vn 0.931102 0.273815 0.240988 -v 0.029400 -0.006167 0.006948 -vn 0.931102 0.229149 0.283795 -v 0.029400 -0.005824 0.006620 -vn 0.931102 0.177891 0.318440 -v 0.029400 -0.005431 0.006354 -vn 0.931102 0.121515 0.343924 -v 0.029400 -0.004998 0.006158 -vn 0.931102 0.061645 0.359513 -v 0.029400 -0.004538 0.006038 -vn 0.931102 -0.000000 0.364758 -v 0.029400 -0.004065 0.005998 -vn 0.931102 -0.061645 0.359513 -v 0.029400 -0.003592 0.006038 -vn 0.931102 -0.121515 0.343924 -v 0.029400 -0.003132 0.006158 -vn 0.931102 -0.177891 0.318440 -v 0.029400 -0.002699 0.006354 -vn 0.931102 -0.229150 0.283796 -v 0.029400 -0.002306 0.006620 -vn 0.931102 -0.273815 0.240988 -v 0.029400 -0.001963 0.006948 -vn 0.688510 -0.000000 0.725227 -v 0.029400 -0.024375 0.005698 -vn 0.390213 0.000001 0.920725 -v 0.032300 -0.024375 0.005698 -vn 0.688507 -0.122562 0.714799 -v 0.029400 -0.023851 0.005743 -vn 0.390210 -0.155602 0.907482 -v 0.032300 -0.023851 0.005743 -vn 0.688508 -0.241604 0.683802 -v 0.029400 -0.023342 0.005875 -vn 0.390207 -0.306733 0.868132 -v 0.032300 -0.023342 0.005875 -vn 0.688508 -0.353690 0.633135 -v 0.029400 -0.022863 0.006092 -vn 0.390210 -0.449033 0.803807 -v 0.032300 -0.022863 0.006092 -vn 0.688507 -0.455603 0.564255 -v 0.029400 -0.022428 0.006386 -vn 0.390208 -0.578419 0.716358 -v 0.032300 -0.022428 0.006386 -vn 0.688508 -0.544409 0.479140 -v 0.029400 -0.022048 0.006750 -vn 0.390210 -0.691163 0.608301 -v 0.032300 -0.022048 0.006750 -vn 0.688508 -0.617554 0.380243 -v 0.029400 -0.021735 0.007173 -vn 0.390209 -0.784026 0.482743 -v 0.032300 -0.021735 0.007173 -vn 0.688508 -0.672932 0.270407 -v 0.029400 -0.021499 0.007642 -vn 0.390209 -0.854332 0.343299 -v 0.032300 -0.021499 0.007642 -vn 0.688507 -0.708952 0.152791 -v 0.029400 -0.021345 0.008145 -vn 0.390209 -0.900061 0.193978 -v 0.032300 -0.021345 0.008145 -vn 0.688508 -0.724576 0.030779 -v 0.029400 -0.021278 0.008667 -vn 0.390209 -0.919897 0.039076 -v 0.032300 -0.021278 0.008667 -vn 0.688508 -0.719355 -0.092116 -v 0.029400 -0.021300 0.009192 -vn 0.390210 -0.913269 -0.116947 -v 0.032300 -0.021300 0.009192 -vn 0.688507 -0.693440 -0.212364 -v 0.029400 -0.021411 0.009706 -vn 0.390208 -0.880368 -0.269611 -v 0.032300 -0.021411 0.009706 -vn 0.688508 -0.647575 -0.326501 -v 0.029400 -0.021607 0.010194 -vn 0.390210 -0.822140 -0.414514 -v 0.032300 -0.021607 0.010194 -vn 0.688507 -0.583083 -0.431245 -v 0.029400 -0.021883 0.010641 -vn 0.390210 -0.740261 -0.547494 -v 0.032300 -0.021883 0.010641 -vn 0.688508 -0.501814 -0.523583 -v 0.029400 -0.022230 0.011036 -vn 0.390211 -0.637087 -0.664723 -v 0.032300 -0.022230 0.011036 -vn 0.688507 -0.406110 -0.600860 -v 0.029400 -0.022639 0.011366 -vn 0.390209 -0.515583 -0.762831 -v 0.032300 -0.022639 0.011366 -vn 0.688508 -0.298721 -0.660850 -v 0.029400 -0.023098 0.011623 -vn 0.390208 -0.379247 -0.838993 -v 0.032300 -0.023098 0.011623 -vn 0.688509 -0.182743 -0.701827 -v 0.029400 -0.023594 0.011798 -vn 0.390210 -0.232006 -0.891016 -v 0.032300 -0.023594 0.011798 -vn 0.688507 -0.061506 -0.722617 -v 0.029400 -0.024112 0.011887 -vn 0.390208 -0.078085 -0.917410 -v 0.032300 -0.024112 0.011887 -vn 0.688507 0.061506 -0.722617 -v 0.029400 -0.024638 0.011887 -vn 0.390207 0.078086 -0.917410 -v 0.032300 -0.024638 0.011887 -vn 0.688508 0.182743 -0.701827 -v 0.029400 -0.025156 0.011798 -vn 0.390210 0.232005 -0.891016 -v 0.032300 -0.025156 0.011798 -vn 0.688508 0.298721 -0.660850 -v 0.029400 -0.025652 0.011623 -vn 0.390208 0.379247 -0.838993 -v 0.032300 -0.025652 0.011623 -vn 0.688507 0.406110 -0.600860 -v 0.029400 -0.026111 0.011366 -vn 0.390209 0.515584 -0.762831 -v 0.032300 -0.026111 0.011366 -vn 0.688508 0.501814 -0.523583 -v 0.029400 -0.026520 0.011036 -vn 0.390210 0.637086 -0.664723 -v 0.032300 -0.026520 0.011036 -vn 0.688508 0.583082 -0.431245 -v 0.029400 -0.026867 0.010641 -vn 0.390210 0.740261 -0.547494 -v 0.032300 -0.026867 0.010641 -vn 0.688508 0.647575 -0.326501 -v 0.029400 -0.027143 0.010194 -vn 0.390210 0.822140 -0.414515 -v 0.032300 -0.027143 0.010194 -vn 0.688507 0.693440 -0.212364 -v 0.029400 -0.027339 0.009706 -vn 0.390209 0.880368 -0.269609 -v 0.032300 -0.027339 0.009706 -vn 0.688508 0.719355 -0.092117 -v 0.029400 -0.027450 0.009192 -vn 0.390210 0.913268 -0.116949 -v 0.032300 -0.027450 0.009192 -vn 0.688507 0.724576 0.030780 -v 0.029400 -0.027472 0.008667 -vn 0.390209 0.919897 0.039077 -v 0.032300 -0.027472 0.008667 -vn 0.688508 0.708951 0.152791 -v 0.029400 -0.027405 0.008145 -vn 0.390210 0.900060 0.193978 -v 0.032300 -0.027405 0.008145 -vn 0.688508 0.672932 0.270406 -v 0.029400 -0.027251 0.007642 -vn 0.390209 0.854332 0.343298 -v 0.032300 -0.027251 0.007642 -vn 0.688508 0.617554 0.380243 -v 0.029400 -0.027015 0.007173 -vn 0.390209 0.784025 0.482744 -v 0.032300 -0.027015 0.007173 -vn 0.688508 0.544410 0.479140 -v 0.029400 -0.026702 0.006750 -vn 0.390209 0.691164 0.608300 -v 0.032300 -0.026702 0.006750 -vn 0.688507 0.455603 0.564255 -v 0.029400 -0.026322 0.006386 -vn 0.390208 0.578418 0.716359 -v 0.032300 -0.026322 0.006386 -vn 0.688508 0.353690 0.633135 -v 0.029400 -0.025887 0.006092 -vn 0.390210 0.449034 0.803806 -v 0.032300 -0.025887 0.006092 -vn 0.688508 0.241604 0.683802 -v 0.029400 -0.025408 0.005875 -vn 0.390208 0.306732 0.868132 -v 0.032300 -0.025408 0.005875 -vn 0.688507 0.122562 0.714799 -v 0.029400 -0.024899 0.005743 -vn 0.390209 0.155601 0.907483 -v 0.032300 -0.024899 0.005743 -vn 0.931102 0.356573 0.076847 -v 0.029400 -0.027112 0.008208 -vn 0.931102 0.338456 0.136003 -v 0.029400 -0.026973 0.007754 -vn 0.931102 0.310603 0.191246 -v 0.029400 -0.026759 0.007330 -vn 0.931102 0.273815 0.240988 -v 0.029400 -0.026477 0.006948 -vn 0.931102 0.229149 0.283796 -v 0.029400 -0.026134 0.006620 -vn 0.931102 0.177891 0.318440 -v 0.029400 -0.025741 0.006354 -vn 0.931102 0.121515 0.343924 -v 0.029400 -0.025308 0.006158 -vn 0.931102 0.061645 0.359513 -v 0.029400 -0.024848 0.006038 -vn 0.931102 -0.000000 0.364758 -v 0.029400 -0.024375 0.005998 -vn 0.931102 -0.061645 0.359513 -v 0.029400 -0.023902 0.006038 -vn 0.931102 -0.121515 0.343924 -v 0.029400 -0.023442 0.006158 -vn 0.931102 -0.177891 0.318440 -v 0.029400 -0.023009 0.006354 -vn 0.931102 -0.229149 0.283796 -v 0.029400 -0.022616 0.006620 -vn 0.931102 -0.273815 0.240987 -v 0.029400 -0.022273 0.006948 -vn 0.931102 -0.310603 0.191246 -v 0.029400 -0.021991 0.007330 -vn 0.931102 -0.338456 0.136003 -v 0.029400 -0.021777 0.007754 -vn 0.931102 -0.356573 0.076847 -v 0.029400 -0.021638 0.008208 -vn 0.931102 -0.364430 0.015481 -v 0.029400 -0.021578 0.008679 -vn 0.931102 -0.361805 -0.046331 -v 0.029400 -0.021598 0.009154 -vn 0.931102 -0.348771 -0.106810 -v 0.029400 -0.021698 0.009618 -vn 0.931102 -0.325703 -0.164217 -v 0.029400 -0.021875 0.010059 -vn 0.931102 -0.293266 -0.216898 -v 0.029400 -0.022124 0.010463 -vn 0.931102 -0.252391 -0.263340 -v 0.029400 -0.022438 0.010820 -vn 0.931102 -0.204256 -0.302208 -v 0.029400 -0.022807 0.011118 -vn 0.931102 -0.150245 -0.332379 -v 0.029400 -0.023222 0.011350 -vn 0.931102 -0.091912 -0.352990 -v 0.029400 -0.023669 0.011508 -vn 0.931102 -0.030934 -0.363445 -v 0.029400 -0.024138 0.011588 -vn 0.931102 0.030934 -0.363445 -v 0.029400 -0.024612 0.011588 -vn 0.931102 0.091912 -0.352990 -v 0.029400 -0.025081 0.011508 -vn 0.931102 0.150245 -0.332379 -v 0.029400 -0.025528 0.011350 -vn 0.931102 0.204256 -0.302208 -v 0.029400 -0.025943 0.011118 -vn 0.931102 0.252390 -0.263340 -v 0.029400 -0.026312 0.010820 -vn 0.931102 0.293266 -0.216898 -v 0.029400 -0.026626 0.010463 -vn 0.931102 0.325703 -0.164216 -v 0.029400 -0.026875 0.010059 -vn 0.931102 0.348770 -0.106810 -v 0.029400 -0.027052 0.009618 -vn 0.931102 0.361805 -0.046332 -v 0.029400 -0.027152 0.009154 -vn 0.931102 0.364430 0.015481 -v 0.029400 -0.027172 0.008679 -vn -0.018783 -0.179188 -0.983636 -v 0.006070 0.007470 -0.022500 -vn -0.035921 -0.161875 -0.986157 -v 0.006264 0.007433 -0.022500 -vn -0.179191 0.018796 -0.983635 -v 0.007470 -0.006070 -0.022500 -vn -0.161842 0.035934 -0.986162 -v 0.007433 -0.006264 -0.022500 -vn -0.018712 0.179153 -0.983643 -v 0.006070 -0.007470 -0.022500 -vn -0.035913 0.161634 -0.986197 -v 0.006264 -0.007433 -0.022500 -vn 0.018781 0.179186 -0.983636 -v -0.006070 -0.007470 -0.022500 -vn 0.035916 0.161883 -0.986156 -v -0.006264 -0.007433 -0.022500 -vn 0.179201 -0.018779 -0.983633 -v -0.007470 0.006070 -0.022500 -vn 0.035909 -0.161642 -0.986196 -v -0.006264 0.007433 -0.022500 -vn 0.018711 -0.179152 -0.983644 -v -0.006070 0.007470 -0.022500 -vn 0.161863 -0.035912 -0.986160 -v -0.007433 0.006264 -0.022500 -vn 0.150061 -0.048924 -0.987466 -v -0.007381 0.006445 -0.022500 -vn 0.048955 -0.149952 -0.987481 -v -0.006445 0.007381 -0.022500 -vn -0.138061 -0.062031 -0.988479 -v 0.007315 0.006611 -0.022500 -vn -0.149969 -0.048938 -0.987479 -v 0.007381 0.006445 -0.022500 -vn -0.048945 -0.150027 -0.987470 -v 0.006445 0.007381 -0.022500 -vn -0.161601 -0.035927 -0.986202 -v 0.007433 0.006264 -0.022500 -vn -0.179155 -0.018724 -0.983643 -v 0.007470 0.006070 -0.022500 -vn -0.075153 0.125989 -0.989181 -v 0.006764 -0.007234 -0.022500 -vn -0.062029 0.138061 -0.988479 -v 0.006611 -0.007315 -0.022500 -vn -0.125986 0.075141 -0.989182 -v 0.007234 -0.006764 -0.022500 -vn -0.048947 0.149954 -0.987481 -v 0.006445 -0.007381 -0.022500 -vn -0.150041 0.048935 -0.987468 -v 0.007381 -0.006445 -0.022500 -vn -0.138061 0.062031 -0.988479 -v 0.007315 -0.006611 -0.022500 -vn 0.125981 0.075183 -0.989180 -v -0.007234 -0.006764 -0.022500 -vn 0.138061 0.062031 -0.988479 -v -0.007315 -0.006611 -0.022500 -vn 0.062035 0.138046 -0.988481 -v -0.006611 -0.007315 -0.022500 -vn 0.149989 0.048927 -0.987476 -v -0.007381 -0.006445 -0.022500 -vn 0.048951 0.150027 -0.987469 -v -0.006445 -0.007381 -0.022500 -vn 0.161621 0.035904 -0.986200 -v -0.007433 -0.006264 -0.022500 -vn 0.179166 0.018708 -0.983641 -v -0.007470 -0.006070 -0.022500 -vn -0.088068 0.113648 -0.989610 -v 0.006903 -0.007138 -0.022500 -vn -0.113663 0.088073 -0.989608 -v 0.007138 -0.006903 -0.022500 -vn -0.100881 0.100896 -0.989769 -v 0.007027 -0.007027 -0.022500 -vn -0.062029 -0.138058 -0.988480 -v 0.006611 0.007315 -0.022500 -vn -0.075152 -0.125990 -0.989181 -v 0.006764 0.007234 -0.022500 -vn -0.125986 -0.075141 -0.989182 -v 0.007234 0.006764 -0.022500 -vn -0.088070 -0.113648 -0.989610 -v 0.006903 0.007138 -0.022500 -vn -0.113663 -0.088075 -0.989608 -v 0.007138 0.006903 -0.022500 -vn -0.100881 -0.100896 -0.989769 -v 0.007027 0.007027 -0.022500 -vn 0.062036 -0.138044 -0.988481 -v -0.006611 0.007315 -0.022500 -vn 0.138061 -0.062031 -0.988479 -v -0.007315 0.006611 -0.022500 -vn 0.075131 -0.125992 -0.989182 -v -0.006764 0.007234 -0.022500 -vn 0.125981 -0.075182 -0.989180 -v -0.007234 0.006764 -0.022500 -vn 0.088061 -0.113676 -0.989608 -v -0.006903 0.007138 -0.022500 -vn 0.113617 -0.088050 -0.989615 -v -0.007138 0.006903 -0.022500 -vn 0.100926 -0.100883 -0.989766 -v -0.007028 0.007027 -0.022500 -vn 0.075131 0.125990 -0.989182 -v -0.006764 -0.007234 -0.022500 -vn 0.088058 0.113675 -0.989608 -v -0.006903 -0.007138 -0.022500 -vn 0.113616 0.088051 -0.989615 -v -0.007138 -0.006903 -0.022500 -vn 0.100926 0.100885 -0.989766 -v -0.007028 -0.007027 -0.022500 -vn -0.208550 0.922715 -0.324199 -v -0.031547 0.032308 -0.031547 -vn -0.208152 0.916945 -0.340418 -v -0.031445 0.032304 -0.031623 -vn 0.002299 0.129145 -0.991623 -v -0.031892 0.030485 -0.032268 -vn -0.341986 0.322938 -0.882472 -v -0.032092 0.030559 -0.032178 -vn -0.126792 0.001929 -0.991928 -v -0.030487 0.031891 -0.032268 -vn -0.321983 0.330606 -0.887145 -v -0.030559 0.032092 -0.032178 -vn -0.113614 0.025566 -0.993196 -v -0.030780 0.031717 -0.032234 -vn -0.104608 0.060013 -0.992701 -v -0.031047 0.031518 -0.032214 -vn -0.110489 0.110461 -0.987720 -v -0.031294 0.031294 -0.032207 -vn -0.060041 0.104561 -0.992705 -v -0.031517 0.031048 -0.032213 -vn -0.025693 0.113732 -0.993179 -v -0.031717 0.030780 -0.032234 -vn -0.206057 0.896292 -0.392684 -v -0.030969 0.032310 -0.031905 -vn -0.212819 0.909707 -0.356568 -v -0.031266 0.032302 -0.031741 -vn -0.230796 0.889336 -0.394734 -v -0.030644 0.032331 -0.032048 -vn -0.202287 0.944552 -0.258654 -v -0.032162 0.032382 -0.030853 -vn -0.215948 0.937251 -0.273728 -v -0.032013 0.032353 -0.031077 -vn -0.206251 0.931301 -0.300230 -v -0.031860 0.032332 -0.031260 -vn -0.215544 0.926330 -0.308955 -v -0.031795 0.032325 -0.031327 -vn -0.205383 0.951097 -0.230721 -v -0.032197 0.032390 -0.030790 -vn 0.206493 0.946802 -0.246834 -v 0.032162 0.032382 -0.030853 -vn 0.405021 0.395962 -0.824119 -v 0.032386 0.030839 -0.031930 -vn 0.001939 0.126795 -0.991927 -v 0.031891 0.030487 -0.032268 -vn 0.337455 0.323267 -0.884094 -v 0.032092 0.030559 -0.032178 -vn 0.210303 0.910109 -0.357035 -v 0.031266 0.032302 -0.031742 -vn 0.208141 0.919023 -0.334775 -v 0.031445 0.032304 -0.031623 -vn 0.209879 0.921663 -0.326325 -v 0.031547 0.032308 -0.031547 -vn 0.207758 0.927482 -0.310827 -v 0.031795 0.032325 -0.031328 -vn 0.204633 0.934845 -0.290156 -v 0.031860 0.032332 -0.031260 -vn 0.208144 0.938220 -0.276442 -v 0.032013 0.032353 -0.031077 -vn 0.214298 0.944680 -0.248305 -v 0.032197 0.032390 -0.030790 -vn 0.230828 0.889313 -0.394768 -v 0.030644 0.032331 -0.032048 -vn 0.325612 0.331057 -0.885651 -v 0.030559 0.032092 -0.032178 -vn 0.206251 0.896259 -0.392659 -v 0.030969 0.032310 -0.031905 -vn 0.104591 0.060054 -0.992701 -v 0.031048 0.031517 -0.032213 -vn 0.113702 0.025646 -0.993184 -v 0.030780 0.031717 -0.032234 -vn 0.127756 -0.000325 -0.991806 -v 0.030485 0.031891 -0.032268 -vn 0.025598 0.113651 -0.993191 -v 0.031717 0.030780 -0.032234 -vn 0.059941 0.104534 -0.992713 -v 0.031518 0.031047 -0.032214 -vn 0.110304 0.110336 -0.987755 -v 0.031294 0.031294 -0.032207 -vn 0.200387 -0.951546 -0.233248 -v 0.032197 -0.032390 -0.030790 -vn 0.200928 -0.946900 -0.251016 -v 0.032162 -0.032382 -0.030853 -vn 0.207770 -0.938336 -0.276328 -v 0.032013 -0.032353 -0.031077 -vn 0.205323 -0.934188 -0.291778 -v 0.031860 -0.032332 -0.031260 -vn 0.208822 -0.927445 -0.310224 -v 0.031795 -0.032325 -0.031327 -vn 0.426499 -0.405592 -0.808451 -v 0.032386 -0.030839 -0.031930 -vn 0.338594 -0.326712 -0.882391 -v 0.032092 -0.030559 -0.032178 -vn -0.001570 -0.128570 -0.991699 -v 0.031891 -0.030485 -0.032268 -vn 0.126762 -0.001885 -0.991931 -v 0.030487 -0.031891 -0.032268 -vn 0.321973 -0.330612 -0.887147 -v 0.030559 -0.032092 -0.032178 -vn 0.113648 -0.025596 -0.993191 -v 0.030780 -0.031717 -0.032234 -vn 0.104647 -0.060044 -0.992695 -v 0.031047 -0.031518 -0.032214 -vn 0.110324 -0.110294 -0.987757 -v 0.031294 -0.031294 -0.032207 -vn 0.060082 -0.104620 -0.992696 -v 0.031517 -0.031048 -0.032213 -vn 0.025623 -0.113673 -0.993188 -v 0.031717 -0.030780 -0.032234 -vn 0.206251 -0.896255 -0.392667 -v 0.030969 -0.032310 -0.031905 -vn 0.230822 -0.889316 -0.394763 -v 0.030644 -0.032331 -0.032048 -vn 0.209628 -0.921747 -0.326248 -v 0.031547 -0.032308 -0.031547 -vn 0.208028 -0.919137 -0.334531 -v 0.031445 -0.032304 -0.031623 -vn 0.210286 -0.910102 -0.357064 -v 0.031266 -0.032302 -0.031741 -vn -0.113626 -0.025589 -0.993194 -v -0.030780 -0.031717 -0.032234 -vn -0.127779 0.000318 -0.991803 -v -0.030485 -0.031891 -0.032268 -vn -0.323978 -0.330787 -0.886351 -v -0.030559 -0.032092 -0.032178 -vn -0.951771 -0.200465 -0.232264 -v -0.032390 -0.032197 -0.030790 -vn -0.947199 -0.200078 -0.250564 -v -0.032382 -0.032162 -0.030853 -vn -0.200645 -0.951737 -0.232248 -v -0.032197 -0.032390 -0.030790 -vn -0.910369 -0.209773 -0.356685 -v -0.032302 -0.031266 -0.031741 -vn -0.209750 -0.910614 -0.356071 -v -0.031266 -0.032302 -0.031742 -vn -0.919493 -0.207518 -0.333870 -v -0.032304 -0.031445 -0.031623 -vn -0.207467 -0.919470 -0.333964 -v -0.031445 -0.032304 -0.031623 -vn -0.922494 -0.207837 -0.325283 -v -0.032308 -0.031547 -0.031547 -vn -0.207784 -0.922519 -0.325245 -v -0.031547 -0.032308 -0.031547 -vn -0.928792 -0.206357 -0.307835 -v -0.032325 -0.031795 -0.031327 -vn -0.206498 -0.928806 -0.307699 -v -0.031795 -0.032325 -0.031328 -vn -0.935345 -0.203547 -0.289307 -v -0.032332 -0.031860 -0.031260 -vn -0.203790 -0.935253 -0.289433 -v -0.031860 -0.032332 -0.031260 -vn -0.938752 -0.206937 -0.275540 -v -0.032353 -0.032013 -0.031077 -vn -0.207330 -0.938651 -0.275589 -v -0.032013 -0.032353 -0.031077 -vn -0.200027 -0.947234 -0.250474 -v -0.032162 -0.032382 -0.030853 -vn -0.907662 -0.211063 -0.362770 -v -0.032310 -0.030969 -0.031905 -vn -0.209614 -0.899505 -0.383343 -v -0.030916 -0.032312 -0.031931 -vn -0.211949 -0.905279 -0.368169 -v -0.030969 -0.032310 -0.031905 -vn -0.899758 -0.208354 -0.383437 -v -0.032312 -0.030916 -0.031931 -vn -0.330351 -0.320331 -0.887838 -v -0.032092 -0.030559 -0.032178 -vn -0.229493 -0.890755 -0.392285 -v -0.030644 -0.032331 -0.032048 -vn -0.001935 -0.126795 -0.991927 -v -0.031891 -0.030487 -0.032268 -vn -0.025614 -0.113658 -0.993190 -v -0.031717 -0.030780 -0.032234 -vn -0.060123 -0.104722 -0.992683 -v -0.031518 -0.031047 -0.032214 -vn -0.110445 -0.110476 -0.987723 -v -0.031294 -0.031294 -0.032207 -vn -0.104777 -0.060235 -0.992670 -v -0.031048 -0.031517 -0.032213 -vn -0.890731 -0.229600 -0.392279 -v -0.032331 -0.030644 -0.032048 -vn 0.200659 0.951330 0.233897 -v 0.032197 0.032390 0.030790 -vn 0.201874 0.946128 0.253156 -v 0.032162 0.032382 0.030853 -vn 0.209573 0.938104 0.275755 -v 0.032013 0.032353 0.031077 -vn 0.205022 0.934493 0.291012 -v 0.031860 0.032332 0.031260 -vn 0.208418 0.927406 0.310613 -v 0.031795 0.032325 0.031327 -vn -0.001247 0.128312 0.991733 -v 0.031891 0.030485 0.032268 -vn 0.337341 0.327362 0.882630 -v 0.032092 0.030559 0.032178 -vn 0.405034 0.397598 0.823324 -v 0.032386 0.030839 0.031930 -vn 0.126769 0.001915 0.991930 -v 0.030487 0.031891 0.032268 -vn 0.321975 0.330616 0.887145 -v 0.030559 0.032092 0.032178 -vn 0.113634 0.025509 0.993195 -v 0.030780 0.031717 0.032234 -vn 0.104596 0.060045 0.992701 -v 0.031047 0.031518 0.032214 -vn 0.110362 0.110324 0.987749 -v 0.031294 0.031294 0.032207 -vn 0.060024 0.104499 0.992712 -v 0.031517 0.031048 0.032213 -vn 0.025548 0.113669 0.993190 -v 0.031717 0.030780 0.032234 -vn 0.206253 0.896255 0.392666 -v 0.030969 0.032310 0.031905 -vn 0.230821 0.889320 0.394755 -v 0.030644 0.032331 0.032048 -vn 0.209819 0.921687 0.326297 -v 0.031547 0.032308 0.031547 -vn 0.208503 0.918274 0.336599 -v 0.031445 0.032304 0.031623 -vn 0.210999 0.909979 0.356956 -v 0.031266 0.032302 0.031741 -vn -0.001966 0.126801 0.991926 -v -0.031891 0.030487 0.032268 -vn -0.329212 0.320992 0.888022 -v -0.032092 0.030559 0.032178 -vn -0.207344 0.927924 0.309782 -v -0.031795 0.032325 0.031328 -vn -0.203522 0.935424 0.289069 -v -0.031860 0.032332 0.031260 -vn -0.209609 0.937993 0.276102 -v -0.032013 0.032353 0.031077 -vn -0.200863 0.951751 0.232000 -v -0.032197 0.032390 0.030790 -vn -0.199702 0.947700 0.248965 -v -0.032162 0.032382 0.030853 -vn -0.209525 0.910490 0.356521 -v -0.031266 0.032302 0.031742 -vn -0.206911 0.919837 0.333299 -v -0.031445 0.032304 0.031623 -vn -0.208542 0.922717 0.324197 -v -0.031547 0.032308 0.031547 -vn -0.230799 0.889336 0.394733 -v -0.030644 0.032331 0.032048 -vn -0.325641 0.331046 0.885645 -v -0.030559 0.032092 0.032178 -vn -0.206008 0.896304 0.392683 -v -0.030969 0.032310 0.031905 -vn -0.104653 0.060172 0.992687 -v -0.031048 0.031517 0.032213 -vn -0.113614 0.025504 0.993198 -v -0.030780 0.031717 0.032234 -vn -0.127729 -0.000340 0.991809 -v -0.030485 0.031891 0.032268 -vn -0.025536 0.113653 0.993192 -v -0.031717 0.030780 0.032234 -vn -0.060114 0.104657 0.992690 -v -0.031518 0.031047 0.032214 -vn -0.110476 0.110514 0.987715 -v -0.031294 0.031294 0.032207 -vn -0.025611 -0.113723 0.993182 -v -0.031717 -0.030780 0.032234 -vn 0.000294 -0.127756 0.991806 -v -0.031892 -0.030485 0.032268 -vn -0.330821 -0.324003 0.886329 -v -0.032092 -0.030559 0.032178 -vn -0.200553 -0.951748 0.232279 -v -0.032197 -0.032390 0.030790 -vn -0.200038 -0.947225 0.250500 -v -0.032162 -0.032382 0.030853 -vn -0.951754 -0.200446 0.232350 -v -0.032390 -0.032197 0.030790 -vn -0.320315 -0.330347 0.887845 -v -0.030559 -0.032092 0.032178 -vn -0.899498 -0.209625 0.383355 -v -0.032312 -0.030916 0.031931 -vn -0.209808 -0.910354 0.356703 -v -0.031266 -0.032302 0.031741 -vn -0.211156 -0.907683 0.362663 -v -0.030969 -0.032310 0.031905 -vn -0.208309 -0.899751 0.383479 -v -0.030916 -0.032312 0.031931 -vn -0.229477 -0.890768 0.392266 -v -0.030644 -0.032331 0.032048 -vn -0.905323 -0.211897 0.368090 -v -0.032310 -0.030969 0.031905 -vn -0.910607 -0.209720 0.356107 -v -0.032302 -0.031266 0.031742 -vn -0.207474 -0.919486 0.333915 -v -0.031445 -0.032304 0.031623 -vn -0.919493 -0.207519 0.333869 -v -0.032304 -0.031445 0.031623 -vn -0.207782 -0.922516 0.325256 -v -0.031547 -0.032308 0.031547 -vn -0.922490 -0.207831 0.325298 -v -0.032308 -0.031547 0.031547 -vn -0.206478 -0.928828 0.307646 -v -0.031795 -0.032325 0.031327 -vn -0.928796 -0.206369 0.307814 -v -0.032325 -0.031795 0.031328 -vn -0.203748 -0.935349 0.289152 -v -0.031860 -0.032332 0.031260 -vn -0.935224 -0.203610 0.289652 -v -0.032332 -0.031860 0.031260 -vn -0.206951 -0.938739 0.275573 -v -0.032013 -0.032353 0.031077 -vn -0.938667 -0.207326 0.275537 -v -0.032353 -0.032013 0.031077 -vn -0.947177 -0.200057 0.250665 -v -0.032382 -0.032162 0.030853 -vn -0.890736 -0.229550 0.392295 -v -0.032331 -0.030644 0.032048 -vn -0.126799 -0.001961 0.991926 -v -0.030487 -0.031891 0.032268 -vn -0.113615 -0.025494 0.993198 -v -0.030780 -0.031717 0.032234 -vn -0.104545 -0.060006 0.992708 -v -0.031047 -0.031518 0.032214 -vn -0.110510 -0.110474 0.987716 -v -0.031294 -0.031294 0.032207 -vn -0.059990 -0.104449 0.992719 -v -0.031517 -0.031048 0.032213 -vn 0.416995 -0.393159 0.819476 -v 0.032386 -0.030839 0.031930 -vn 0.340974 -0.322331 0.883085 -v 0.032092 -0.030559 0.032178 -vn 0.001971 -0.126802 0.991926 -v 0.031891 -0.030487 0.032268 -vn 0.210336 -0.910103 0.357031 -v 0.031266 -0.032302 0.031742 -vn 0.208125 -0.918971 0.334926 -v 0.031445 -0.032304 0.031623 -vn 0.209642 -0.921745 0.326246 -v 0.031547 -0.032308 0.031547 -vn 0.207851 -0.927572 0.310495 -v 0.031795 -0.032325 0.031328 -vn 0.204623 -0.934848 0.290152 -v 0.031860 -0.032332 0.031260 -vn 0.209173 -0.938010 0.276375 -v 0.032013 -0.032353 0.031077 -vn 0.200891 -0.946933 0.250919 -v 0.032162 -0.032382 0.030853 -vn 0.200543 -0.951714 0.232430 -v 0.032197 -0.032390 0.030790 -vn 0.230826 -0.889316 0.394762 -v 0.030644 -0.032331 0.032048 -vn 0.325612 -0.331059 0.885650 -v 0.030559 -0.032092 0.032178 -vn 0.206250 -0.896259 0.392658 -v 0.030969 -0.032310 0.031905 -vn 0.104482 -0.060007 0.992715 -v 0.031048 -0.031517 0.032213 -vn 0.113697 -0.025569 0.993186 -v 0.030780 -0.031717 0.032234 -vn 0.127708 0.000344 0.991812 -v 0.030485 -0.031891 0.032268 -vn 0.025516 -0.113642 0.993194 -v 0.031717 -0.030780 0.032234 -vn 0.059946 -0.104486 0.992718 -v 0.031518 -0.031047 0.032214 -vn 0.110316 -0.110357 0.987751 -v 0.031294 -0.031294 0.032207 -vn -0.035734 -0.611654 0.790318 -v -0.023484 0.012409 -0.015685 -vn -0.011515 -0.561249 0.827567 -v -0.023924 0.011095 -0.016640 -vn -0.036826 -0.495389 0.867890 -v -0.024141 0.010350 -0.017114 -vn -0.023571 -0.443165 0.896130 -v -0.024589 0.008537 -0.018086 -vn -0.036502 -0.376175 0.925829 -v -0.024674 0.008131 -0.018273 -vn -0.037555 -0.282567 0.958512 -v -0.025075 0.005789 -0.019144 -vn -0.038606 -0.188487 0.981317 -v -0.025338 0.003359 -0.019716 -vn -0.013090 -0.117606 0.992974 -v -0.025370 0.002929 -0.019784 -vn -0.036010 -0.059852 0.997558 -v -0.025460 0.000880 -0.019981 -vn 0.017382 0.020514 0.999638 -v -0.025469 0.000000 -0.020000 -vn -0.026210 0.396662 0.917590 -v -0.024589 -0.008536 -0.018087 -vn -0.039408 0.333967 0.941761 -v -0.024972 -0.006481 -0.018921 -vn -0.010130 0.272341 0.962147 -v -0.025074 -0.005796 -0.019142 -vn -0.038140 0.206505 0.977702 -v -0.025276 -0.004077 -0.019580 -vn -0.002596 0.143586 0.989635 -v -0.025370 -0.002930 -0.019784 -vn -0.034029 0.070581 0.996925 -v -0.025439 -0.001611 -0.019935 -vn 0.009560 -0.660208 0.751022 -v -0.023094 0.013412 -0.014836 -vn -0.000505 -0.712155 0.702022 -v -0.022774 0.014142 -0.014142 -vn -0.040144 -0.759559 0.649199 -v -0.023277 0.015235 -0.012957 -vn -0.023906 -0.792940 0.608830 -v -0.023370 0.015437 -0.012716 -vn -0.039663 -0.833463 0.551150 -v -0.023966 0.016733 -0.010955 -vn -0.010067 -0.865996 0.499949 -v -0.024150 0.017132 -0.010319 -vn -0.038429 -0.899125 0.436002 -v -0.024534 0.017967 -0.008785 -vn -0.004334 -0.924174 0.381948 -v -0.024760 0.018459 -0.007699 -vn -0.034396 -0.950191 0.309765 -v -0.024972 0.018921 -0.006481 -vn 0.011116 -0.963881 0.266101 -v -0.025187 0.019387 -0.004912 -vn -0.034684 -0.982419 0.183440 -v -0.025276 0.019580 -0.004077 -vn -0.016480 -0.991740 0.127205 -v -0.025422 0.019898 -0.002018 -vn -0.035754 -0.997884 0.054298 -v -0.025439 0.019935 -0.001611 -vn -0.035827 -0.999262 -0.013880 -v -0.025460 0.019981 0.000880 -vn -0.036465 -0.996488 -0.075374 -v -0.025459 0.019979 0.000918 -vn 0.016150 -0.832622 -0.553606 -v -0.017765 0.016116 0.011843 -vn -0.038158 -0.989238 -0.141250 -v -0.025338 0.019716 0.003359 -vn -0.020843 -0.977206 -0.211268 -v -0.025298 0.019629 0.003835 -vn -0.037695 -0.961904 -0.270777 -v -0.025075 0.019144 0.005789 -vn -0.007986 -0.939973 -0.341156 -v -0.024942 0.018855 0.006669 -vn -0.034305 -0.914531 -0.403059 -v -0.024674 0.018273 0.008131 -vn 0.038625 -0.887400 -0.459379 -v -0.024399 0.017675 0.009359 -vn -0.037434 -0.854036 -0.518866 -v -0.024141 0.017114 0.010350 -vn 0.004387 -0.819117 -0.573610 -v -0.023681 0.016114 0.011847 -vn 0.021572 -0.803999 -0.594239 -v -0.017894 0.016053 0.011929 -vn 0.018256 -0.769207 -0.638739 -v -0.020004 0.014905 0.013336 -vn -0.010894 -0.636861 -0.770902 -v -0.023465 0.012462 0.015643 -vn -0.043117 -0.652250 -0.756777 -v -0.023128 0.013328 0.014912 -vn 0.023882 -0.696694 -0.716971 -v -0.021932 0.013646 0.014621 -vn 0.000310 -0.699079 -0.715044 -v -0.022774 0.014142 0.014142 -vn 0.018905 -0.725175 -0.688305 -v -0.021104 0.014215 0.014069 -vn -0.029980 -0.733384 -0.679153 -v -0.022804 0.014207 0.014077 -vn -0.045284 -0.783152 -0.620179 -v -0.023484 0.015685 0.012409 -vn -0.040190 0.454458 0.889861 -v -0.024534 -0.008785 -0.017967 -vn -0.034693 0.514028 0.857071 -v -0.023966 -0.010955 -0.016733 -vn -0.035651 0.569547 0.821185 -v -0.023924 -0.011093 -0.016642 -vn -0.035722 0.620892 0.783082 -v -0.023277 -0.012957 -0.015235 -vn -0.036250 0.665274 0.745719 -v -0.023094 -0.013411 -0.014837 -vn -0.006760 0.713999 0.700114 -v -0.022774 -0.014142 -0.014142 -vn -0.030083 0.763517 0.645087 -v -0.023370 -0.015437 -0.012716 -vn -0.037419 0.806654 0.589838 -v -0.023484 -0.015685 -0.012409 -vn -0.041351 0.845268 0.532740 -v -0.024141 -0.017114 -0.010349 -vn -0.032262 0.875999 0.481233 -v -0.024150 -0.017134 -0.010317 -vn -0.038404 0.906450 0.420563 -v -0.024674 -0.018273 -0.008131 -vn -0.008142 0.934098 0.356923 -v -0.024760 -0.018459 -0.007698 -vn -0.036078 0.953539 0.299103 -v -0.025075 -0.019144 -0.005789 -vn 0.022537 0.973496 0.227592 -v -0.025187 -0.019388 -0.004912 -vn -0.034113 0.984420 0.172494 -v -0.025338 -0.019716 -0.003359 -vn -0.002770 0.994578 0.103952 -v -0.025422 -0.019898 -0.002019 -vn -0.037718 0.998672 0.035081 -v -0.025460 -0.019981 -0.000880 -vn -0.010513 0.999546 -0.028245 -v -0.025459 -0.019979 0.000918 -vn -0.037029 0.994589 -0.097062 -v -0.025439 -0.019935 0.001611 -vn -0.026188 0.986416 -0.162168 -v -0.025298 -0.019629 0.003834 -vn -0.037207 0.973432 -0.225934 -v -0.025276 -0.019580 0.004077 -vn -0.034607 0.955893 -0.291671 -v -0.024972 -0.018921 0.006481 -vn 0.000360 0.813735 -0.581236 -v -0.017758 -0.016120 0.011839 -vn 0.015827 0.795421 -0.605851 -v -0.023681 -0.016113 0.011847 -vn -0.035942 0.848528 -0.527928 -v -0.023966 -0.016733 0.010955 -vn -0.010394 0.874469 -0.484970 -v -0.024400 -0.017675 0.009359 -vn -0.037488 0.910191 -0.412489 -v -0.024534 -0.017967 0.008785 -vn -0.032084 0.934128 -0.355493 -v -0.024943 -0.018856 0.006668 -vn 0.020067 0.794434 -0.607019 -v -0.018597 -0.015694 0.012398 -vn -0.034199 0.772113 -0.634564 -v -0.023277 -0.015235 0.012957 -vn 0.022019 0.743189 -0.668719 -v -0.020682 -0.014488 0.013788 -vn -0.020168 0.724380 -0.689106 -v -0.022804 -0.014207 0.014077 -vn -0.007008 0.697386 -0.716662 -v -0.022774 -0.014142 0.014142 -vn 0.022709 0.681794 -0.731192 -v -0.022578 -0.013169 0.015052 -vn -0.038683 0.658539 -0.751552 -v -0.023128 -0.013328 0.014912 -vn -0.005707 0.631692 -0.775198 -v -0.023465 -0.012462 0.015643 -vn -0.691990 0.569571 -0.443553 -v 0.022500 -0.015783 0.012285 -vn -0.694140 -0.681077 -0.233032 -v 0.022500 0.018945 0.006409 -vn -0.692396 0.683303 -0.231701 -v 0.022500 -0.018951 0.006393 -vn -0.927640 0.027900 -0.372432 -v 0.022500 -0.001463 0.005145 -vn -0.928950 -0.234673 -0.286321 -v 0.022500 0.010964 0.001539 -vn -0.695813 -0.706456 -0.129475 -v 0.022500 0.019676 0.003587 -vn -0.693607 -0.720060 -0.020574 -v 0.022500 0.019988 0.000689 -vn -0.692845 -0.716425 0.081864 -v 0.022500 0.019876 -0.002224 -vn -0.692641 -0.697171 0.184936 -v 0.022500 0.019341 -0.005090 -vn -0.692684 0.709381 -0.130262 -v 0.022500 -0.019679 0.003570 -vn -0.693610 0.719782 -0.028607 -v 0.022500 -0.019989 0.000672 -vn -0.695878 0.713595 0.080851 -v 0.022500 -0.019874 -0.002241 -vn -0.695378 0.694643 0.184175 -v 0.022500 -0.019337 -0.005107 -vn -0.694688 0.661097 0.283479 -v 0.022500 -0.018389 -0.007864 -vn -0.926274 -0.340101 -0.162322 -v 0.022500 0.014255 -0.002590 -vn -0.927014 -0.326338 -0.184792 -v 0.022500 0.013900 -0.001902 -vn -0.926691 -0.313925 -0.206628 -v 0.022500 0.013429 -0.001139 -vn -0.927047 -0.298970 -0.226275 -v 0.022500 0.013194 -0.000803 -vn -0.928490 -0.272541 -0.252247 -v 0.022500 0.012317 0.000266 -vn -0.693998 0.613501 0.376807 -v 0.022500 -0.017051 -0.010453 -vn -0.693414 0.552734 0.462237 -v 0.022500 -0.015350 -0.012821 -vn -0.927202 -0.348158 -0.138137 -v 0.022500 0.014445 -0.003021 -vn -0.929818 -0.354939 -0.097245 -v 0.022500 0.014825 -0.004103 -vn -0.926967 0.315676 -0.202683 -v 0.022500 -0.013658 -0.001493 -vn -0.926256 0.329682 -0.182649 -v 0.022500 -0.013899 -0.001901 -vn -0.928385 0.338314 -0.153766 -v 0.022500 -0.014261 -0.002603 -vn -0.929683 0.348190 -0.120218 -v 0.022500 -0.014648 -0.003549 -vn -0.930280 0.361088 -0.064766 -v 0.022500 -0.015043 -0.005034 -vn -0.692243 -0.663433 0.284002 -v 0.022500 0.018396 -0.007848 -vn -0.691846 -0.615645 0.377268 -v 0.022500 0.017060 -0.010439 -vn -0.929919 -0.358708 0.081119 -v 0.022500 0.014973 -0.008812 -vn -0.693896 -0.568074 -0.442494 -v 0.022500 0.015790 0.012275 -vn -0.927842 -0.017525 -0.372561 -v 0.022500 0.000937 0.005177 -vn -0.927259 -0.212608 -0.308201 -v 0.022500 0.009845 0.002365 -vn -0.926793 -0.192365 -0.322568 -v 0.022500 0.009293 0.002716 -vn -0.926615 -0.172801 -0.333953 -v 0.022500 0.008336 0.003251 -vn -0.927015 -0.147761 -0.344687 -v 0.022500 0.007480 0.003660 -vn -0.926638 -0.113958 -0.358268 -v 0.022500 0.005445 0.004411 -vn -0.693585 -0.501547 -0.517098 -v 0.022500 0.013923 0.014358 -vn -0.927847 -0.370484 0.042923 -v 0.022500 0.015157 -0.007654 -vn -0.926810 -0.375255 0.014351 -v 0.022500 0.015190 -0.007179 -vn -0.927597 -0.373398 -0.011762 -v 0.022500 0.015196 -0.006479 -vn -0.929431 -0.365515 -0.050559 -v 0.022500 0.015133 -0.005625 -vn -0.927256 0.269303 -0.260141 -v 0.022500 -0.011913 0.000685 -vn -0.695605 0.149636 -0.702668 -v 0.022500 -0.004162 0.019562 -vn -0.695209 0.246701 -0.675147 -v 0.022500 -0.006850 0.018790 -vn -0.694635 0.338781 -0.634594 -v 0.022500 -0.009404 0.017651 -vn -0.928820 0.290245 -0.230327 -v 0.022500 -0.012941 -0.000469 -vn -0.926436 -0.089802 -0.365585 -v 0.022500 0.004752 0.004604 -vn -0.926650 -0.068734 -0.369588 -v 0.022500 0.003241 0.004927 -vn -0.926415 -0.047739 -0.373465 -v 0.022500 0.002779 0.005000 -vn -0.926463 -0.158997 0.341155 -v 0.022500 0.007708 -0.017057 -vn -0.926608 -0.182171 0.328956 -v 0.022500 0.008768 -0.016520 -vn -0.691190 -0.306550 0.654433 -v 0.022500 0.008485 -0.018111 -vn -0.691367 -0.481675 0.538518 -v 0.022500 0.013336 -0.014905 -vn -0.928983 -0.281846 0.239903 -v 0.022500 0.012694 -0.013336 -vn -0.691552 -0.554632 0.462751 -v 0.022500 0.015361 -0.012808 -vn -0.927248 -0.307466 0.213717 -v 0.022500 0.013447 -0.012334 -vn -0.926594 -0.322664 0.193162 -v 0.022500 0.013705 -0.011931 -vn -0.927573 -0.333601 0.168284 -v 0.022500 0.014100 -0.011225 -vn -0.928795 -0.346486 0.131482 -v 0.022500 0.014520 -0.010295 -vn -0.693025 -0.338126 -0.636701 -v 0.022500 0.009415 0.017645 -vn -0.692968 0.502584 -0.516918 -v 0.022500 -0.013915 0.014366 -vn -0.926397 0.252227 -0.279588 -v 0.022500 -0.011580 0.001004 -vn -0.927288 0.231556 -0.294141 -v 0.022500 -0.010732 0.001724 -vn -0.927090 0.126331 -0.352909 -v 0.022500 -0.006121 0.004193 -vn -0.926853 0.148355 -0.344868 -v 0.022500 -0.007436 0.003679 -vn -0.926406 0.370791 0.065466 -v 0.022500 -0.015070 -0.008313 -vn -0.927229 0.363159 0.091444 -v 0.022500 -0.014909 -0.009084 -vn -0.693772 -0.424633 -0.581693 -v 0.022500 0.011784 0.016160 -vn -0.927093 0.170503 -0.333806 -v 0.022500 -0.008246 0.003296 -vn -0.926875 0.192226 -0.322416 -v 0.022500 -0.009197 0.002774 -vn -0.927399 0.213734 -0.307000 -v 0.022500 -0.010092 0.002197 -vn -0.930088 0.366914 -0.017611 -v 0.022500 -0.015197 -0.006519 -vn -0.928380 0.371586 0.005911 -v 0.022500 -0.015200 -0.006750 -vn -0.927394 0.372070 0.038790 -v 0.022500 -0.015127 -0.007925 -vn -0.691149 -0.208179 0.692080 -v 0.022500 0.005761 -0.019152 -vn -0.691125 -0.105366 0.715013 -v 0.022500 0.002916 -0.019786 -vn -0.928018 -0.059181 0.367804 -v 0.022500 0.003197 -0.018434 -vn -0.691256 -0.398375 0.602879 -v 0.022500 0.011027 -0.016685 -vn -0.692386 -0.247923 -0.677596 -v 0.022500 0.006861 0.018786 -vn -0.692821 -0.151280 -0.705063 -v 0.022500 0.004174 0.019560 -vn -0.693093 -0.051715 -0.718991 -v 0.022500 0.001404 0.019951 -vn -0.694039 0.046425 -0.718439 -v 0.022500 -0.001392 0.019951 -vn -0.928483 0.074464 -0.363832 -v 0.022500 -0.003822 0.004818 -vn -0.926673 0.103559 -0.361320 -v 0.022500 -0.005503 0.004393 -vn -0.926475 0.357733 0.116924 -v 0.022500 -0.014689 -0.009831 -vn -0.927608 0.345837 0.141208 -v 0.022500 -0.014549 -0.010219 -vn -0.928687 0.328948 0.171271 -v 0.022500 -0.014048 -0.011325 -vn -0.926546 -0.027886 0.375148 -v 0.022500 0.000858 -0.018681 -vn -0.691545 -0.000885 0.722333 -v 0.022500 0.000009 -0.020000 -vn -0.925121 -0.011012 0.379513 -v 0.022500 0.000827 -0.018682 -vn -0.927131 -0.202331 0.315421 -v 0.022500 0.009669 -0.015981 -vn -0.926781 -0.223083 0.302178 -v 0.022500 0.010340 -0.015520 -vn -0.928491 -0.246974 0.277323 -v 0.022500 0.011271 -0.014780 -vn -0.694035 0.424258 -0.581654 -v 0.022500 -0.011775 0.016167 -vn -0.926437 -0.093175 0.364737 -v 0.022500 0.004993 -0.018040 -vn -0.926044 -0.114230 0.359713 -v 0.022500 0.005515 -0.017890 -vn -0.926465 -0.138156 0.350109 -v 0.022500 0.006963 -0.017378 -vn -0.926802 0.283278 0.246561 -v 0.022500 -0.012523 -0.013536 -vn -0.692956 0.480047 0.537928 -v 0.022500 -0.013323 -0.014916 -vn -0.926324 0.300501 0.227205 -v 0.022500 -0.013143 -0.012766 -vn -0.926681 0.313434 0.207416 -v 0.022500 -0.013367 -0.012453 -vn -0.926694 0.267013 0.264468 -v 0.022500 -0.011962 -0.014136 -vn -0.926492 0.250576 0.280757 -v 0.022500 -0.011490 -0.014586 -vn -0.692610 0.397001 0.602230 -v 0.022500 -0.011013 -0.016695 -vn -0.926962 0.226480 0.299080 -v 0.022500 -0.010540 -0.015372 -vn -0.926651 0.203129 0.316317 -v 0.022500 -0.009570 -0.016045 -vn -0.692350 0.305394 0.653748 -v 0.022500 -0.008469 -0.018118 -vn -0.926337 0.182716 0.329414 -v 0.022500 -0.008798 -0.016504 -vn -0.926505 0.121302 0.356193 -v 0.022500 -0.006232 -0.017654 -vn -0.692153 0.207206 0.691368 -v 0.022500 -0.005745 -0.019157 -vn -0.926241 0.142385 0.349005 -v 0.022500 -0.006916 -0.017397 -vn -0.926605 0.162454 0.339134 -v 0.022500 -0.007971 -0.016932 -vn -0.926574 0.100431 0.362455 -v 0.022500 -0.004831 -0.018083 -vn -0.926565 0.079018 0.367742 -v 0.022500 -0.004333 -0.018207 -vn -0.692002 0.104547 0.714285 -v 0.022500 -0.002899 -0.019789 -vn -0.927912 0.049792 0.369460 -v 0.022500 -0.002598 -0.018525 -vn -0.927038 0.009336 0.374852 -v 0.022500 -0.000264 -0.018698 -vn -0.519452 -0.519433 -0.678498 -v 0.016308 0.016267 0.011635 -vn -0.520421 -0.533343 -0.666864 -v 0.016242 0.016181 0.011755 -vn -0.534973 -0.596420 -0.598403 -v 0.015562 0.014159 0.014125 -vn -0.535264 -0.578644 -0.615357 -v 0.015606 0.014699 0.013562 -vn -0.538690 -0.566548 -0.623567 -v 0.015638 0.014866 0.013379 -vn -0.545322 -0.549212 -0.633238 -v 0.015797 0.015389 0.012774 -vn -0.527285 -0.535474 -0.659726 -v 0.016042 0.015883 0.012155 -vn -0.525078 -0.676184 -0.516787 -v 0.016267 0.011709 0.016214 -vn -0.531643 -0.656097 -0.535624 -v 0.015969 0.012320 0.015755 -vn -0.531475 -0.638705 -0.556409 -v 0.015749 0.012925 0.015262 -vn -0.529792 -0.629916 -0.567914 -v 0.015724 0.013013 0.015188 -vn -0.534358 -0.616925 -0.577810 -v 0.015601 0.013597 0.014667 -vn -0.530279 -0.605730 -0.593208 -v 0.015568 0.013923 0.014358 -vn 0.803483 -0.364778 -0.470481 -v -0.020847 0.004501 0.024150 -vn 0.768836 -0.409470 -0.491148 -v -0.020572 0.005244 0.024012 -vn 0.820336 -0.431347 -0.375486 -v -0.020407 0.005470 0.024100 -vn 0.807510 0.488626 -0.330413 -v -0.019640 -0.006886 0.024007 -vn 0.795915 0.520030 -0.309982 -v -0.019110 -0.007749 0.023939 -vn 0.728459 0.548198 -0.410885 -v -0.019716 -0.007557 0.022941 -vn 0.701504 0.705991 -0.097312 -v -0.015561 -0.012706 0.021539 -vn 0.076555 0.819387 -0.568106 -v -0.017805 -0.015349 0.012917 -vn 0.258001 0.561738 -0.786057 -v -0.023887 -0.008362 0.018708 -vn 0.306991 0.531122 -0.789725 -v -0.023939 -0.007751 0.019109 -vn 0.410886 0.546427 -0.729788 -v -0.022941 -0.007557 0.019716 -vn 0.317503 0.509689 -0.799631 -v -0.023961 -0.007483 0.019278 -vn 0.352508 0.477982 -0.804532 -v -0.024036 -0.006476 0.019876 -vn 0.456901 0.464882 -0.758371 -v -0.023686 -0.006046 0.020313 -vn 0.453355 0.394868 -0.799092 -v -0.024131 -0.004897 0.020676 -vn 0.472799 0.365655 -0.801722 -v -0.024148 -0.004558 0.020823 -vn 0.595225 0.368692 -0.713984 -v -0.022912 -0.004466 0.021737 -vn 0.730960 -0.674263 -0.105200 -v -0.014194 0.014194 0.019602 -vn 0.725355 -0.681658 -0.095932 -v -0.014188 0.014188 0.019694 -vn 0.680144 -0.726768 -0.095977 -v -0.015138 0.013200 0.020937 -vn 0.733548 -0.677295 -0.056380 -v -0.014174 0.014175 0.019942 -vn 0.703983 -0.709672 -0.027832 -v -0.014142 0.014142 0.021195 -vn 0.616253 -0.762858 -0.195650 -v -0.015753 0.012859 0.019957 -vn 0.563614 -0.801557 -0.199614 -v -0.014458 0.014219 0.018268 -vn 0.707820 -0.686966 -0.164525 -v -0.014289 0.014289 0.018503 -vn 0.491626 -0.831067 -0.260063 -v -0.015122 0.014019 0.017426 -vn 0.682304 -0.682085 -0.263100 -v -0.014545 0.014545 0.016755 -vn 0.681847 -0.697373 -0.220808 -v -0.014444 0.014444 0.017343 -vn 0.665352 -0.658021 -0.352582 -v -0.014823 0.014823 0.015474 -vn 0.670318 -0.665764 -0.327769 -v -0.014809 0.014809 0.015529 -vn 0.418846 -0.841423 -0.341432 -v -0.015844 0.013919 0.016615 -vn 0.670622 -0.680686 -0.294843 -v -0.014652 0.014652 0.016218 -vn 0.679358 -0.640056 -0.358889 -v -0.014912 0.014912 0.015129 -vn 0.341565 -0.842072 -0.417430 -v -0.016615 0.013919 0.015844 -vn 0.259576 -0.833512 -0.487728 -v -0.017426 0.014019 0.015122 -vn 0.231869 -0.865294 -0.444413 -v -0.015662 0.015320 0.013617 -vn 0.645114 -0.636916 -0.422097 -v -0.015110 0.015110 0.014444 -vn 0.530407 -0.524783 -0.665787 -v -0.016574 0.016574 0.011196 -vn 0.555373 -0.555614 -0.618752 -v -0.016148 0.016147 0.011919 -vn 0.084293 -0.830643 -0.550388 -v -0.017141 0.015730 0.012443 -vn 0.581432 -0.601143 -0.548236 -v -0.015762 0.015762 0.012704 -vn 0.094126 -0.724431 -0.682891 -v -0.020937 0.013200 0.015138 -vn 0.110977 -0.665213 -0.738360 -v -0.022548 0.011804 0.016267 -vn 0.133756 -0.622120 -0.771411 -v -0.023664 0.010654 0.017056 -vn 0.053391 -0.611541 -0.789409 -v -0.023598 0.011265 0.016586 -vn 0.022899 -0.617110 -0.786544 -v -0.023493 0.012215 0.015839 -vn 0.153825 -0.595799 -0.788265 -v -0.023720 0.010116 0.017462 -vn 0.151256 -0.604373 -0.782211 -v -0.023705 0.010260 0.017354 -vn 0.246019 -0.630061 -0.736545 -v -0.022744 0.009956 0.017851 -vn 0.216596 -0.702753 -0.677661 -v -0.021450 0.011430 0.016884 -vn 0.182576 -0.572535 -0.799293 -v -0.023828 0.009008 0.018265 -vn 0.347064 -0.561866 -0.750902 -v -0.023838 0.008459 0.018657 -vn 0.289512 -0.535614 -0.793285 -v -0.023924 0.007933 0.018991 -vn 0.339575 -0.493151 -0.800932 -v -0.024007 0.006886 0.019641 -vn 0.435799 -0.499062 -0.749010 -v -0.023382 0.006706 0.020070 -vn 0.392262 -0.585650 -0.709327 -v -0.022574 0.008193 0.019419 -vn 0.478647 -0.344198 -0.807728 -v -0.024169 0.004084 0.021013 -vn 0.376068 -0.381892 -0.844234 -v -0.024128 0.004945 0.020654 -vn 0.472190 -0.420118 -0.774943 -v -0.024012 0.005244 0.020572 -vn 0.410502 -0.423676 -0.807457 -v -0.024112 0.005258 0.020509 -vn 0.359238 -0.437683 -0.824246 -v -0.024079 0.005822 0.020229 -vn 0.613368 -0.312322 -0.725420 -v -0.023113 0.003723 0.021922 -vn 0.501808 -0.301227 -0.810834 -v -0.024181 0.003788 0.021123 -vn 0.582045 -0.418519 -0.697184 -v -0.022699 0.005132 0.021542 -vn 0.639913 -0.204850 -0.740640 -v -0.023389 0.002350 0.022173 -vn 0.653793 -0.090919 -0.751192 -v -0.023539 0.001004 0.022309 -vn 0.550648 -0.102519 -0.828418 -v -0.024248 0.001015 0.021765 -vn 0.533078 -0.138343 -0.834679 -v -0.024240 0.001637 0.021684 -vn 0.527653 -0.209121 -0.823317 -v -0.024225 0.002396 0.021535 -vn 0.507016 -0.261490 -0.821315 -v -0.024201 0.003236 0.021307 -vn 0.547135 0.083641 -0.832855 -v -0.024250 -0.000819 0.021783 -vn 0.560611 0.032624 -0.827436 -v -0.024253 -0.000336 0.021810 -vn 0.654316 0.030257 -0.755616 -v -0.023568 -0.000333 0.022336 -vn 0.554951 -0.011751 -0.831800 -v -0.024253 -0.000006 0.021816 -vn 0.553990 -0.056021 -0.830636 -v -0.024250 0.000810 0.021784 -vn 0.545996 0.137759 -0.826384 -v -0.024240 -0.001636 0.021684 -vn 0.647108 0.144850 -0.748512 -v -0.023479 -0.001679 0.022255 -vn 0.529653 0.198066 -0.824765 -v -0.024223 -0.002464 0.021518 -vn 0.624688 0.261168 -0.735905 -v -0.023264 -0.003052 0.022059 -vn 0.524313 0.227238 -0.820645 -v -0.024219 -0.002643 0.021474 -vn 0.479148 0.340934 -0.808815 -v -0.024150 -0.004501 0.020847 -vn 0.499014 0.304103 -0.811484 -v -0.024190 -0.003563 0.021201 -vn 0.520834 0.255814 -0.814427 -v -0.024205 -0.003098 0.021349 -vn 0.562166 0.472554 -0.678721 -v -0.022407 -0.005925 0.021273 -vn 0.377655 0.423912 -0.823210 -v -0.024100 -0.005470 0.020407 -vn 0.158176 0.845191 -0.510522 -v -0.017021 -0.015086 0.013494 -vn 0.237456 0.860745 -0.450258 -v -0.016253 -0.014910 0.014122 -vn 0.311237 0.869072 -0.384506 -v -0.015509 -0.014822 0.014796 -vn 0.383106 0.869260 -0.312436 -v -0.014796 -0.014822 0.015509 -vn 0.450730 0.860339 -0.238032 -v -0.014122 -0.014910 0.016253 -vn 0.572439 0.815787 -0.082496 -v -0.012917 -0.015349 0.017805 -vn 0.513892 0.842608 -0.161016 -v -0.013494 -0.015086 0.017021 -vn 0.699580 0.677335 -0.227609 -v -0.017272 -0.010872 0.021966 -vn 0.785612 0.602100 -0.142442 -v -0.017462 -0.010116 0.023720 -vn 0.757476 0.640955 -0.124122 -v -0.016657 -0.011255 0.023108 -vn 0.787639 0.613147 -0.060632 -v -0.016586 -0.011265 0.023598 -vn 0.781661 0.620879 -0.059288 -v -0.016444 -0.011448 0.023578 -vn 0.679396 0.631645 -0.373423 -v -0.018953 -0.009086 0.022004 -vn 0.785615 0.552928 -0.277631 -v -0.018991 -0.007933 0.023924 -vn 0.751555 0.605435 -0.261941 -v -0.018196 -0.009353 0.023209 -vn 0.798501 0.569226 -0.195903 -v -0.018265 -0.009008 0.023829 -vn 0.781619 0.589411 -0.204126 -v -0.017897 -0.009523 0.023779 -vn 0.797543 0.471747 -0.376006 -v -0.020081 -0.006103 0.024061 -vn 0.840609 0.401961 -0.363049 -v -0.020654 -0.004945 0.024128 -vn 0.817017 0.432998 -0.380783 -v -0.020229 -0.005822 0.024079 -vn 0.756255 0.471137 -0.453992 -v -0.020313 -0.006046 0.023686 -vn 0.714106 0.367714 -0.595684 -v -0.021737 -0.004466 0.022912 -vn 0.794159 0.360402 -0.489307 -v -0.020823 -0.004559 0.024148 -vn 0.802856 0.389345 -0.451478 -v -0.020666 -0.004920 0.024130 -vn 0.677935 0.473448 -0.562361 -v -0.021273 -0.005925 0.022407 -vn 0.829179 0.198875 -0.522408 -v -0.021535 -0.002396 0.024225 -vn 0.817593 0.245307 -0.520929 -v -0.021349 -0.003097 0.024206 -vn 0.733689 0.260867 -0.627415 -v -0.022059 -0.003052 0.023264 -vn 0.814933 0.284929 -0.504678 -v -0.021307 -0.003236 0.024201 -vn 0.813419 0.322414 -0.484147 -v -0.021013 -0.004084 0.024169 -vn 0.828288 0.144258 -0.541413 -v -0.021684 -0.001637 0.024240 -vn 0.746012 0.150548 -0.648692 -v -0.022255 -0.001679 0.023479 -vn 0.829500 0.075986 -0.553314 -v -0.021784 -0.000810 0.024250 -vn 0.755950 0.028611 -0.654004 -v -0.022336 -0.000333 0.023568 -vn 0.823843 0.035738 -0.565690 -v -0.021810 -0.000336 0.024253 -vn 0.753568 -0.087016 -0.651585 -v -0.022309 0.001004 0.023539 -vn 0.831024 -0.055546 -0.553457 -v -0.021783 0.000819 0.024250 -vn 0.832478 -0.013856 -0.553885 -v -0.021816 0.000006 0.024253 -vn 0.817313 -0.238887 -0.524340 -v -0.021474 0.002643 0.024219 -vn 0.821907 -0.195486 -0.535027 -v -0.021518 0.002464 0.024223 -vn 0.743297 -0.203745 -0.637179 -v -0.022174 0.002350 0.023389 -vn 0.826693 -0.146378 -0.543280 -v -0.021684 0.001636 0.024240 -vn 0.826075 -0.096985 -0.555152 -v -0.021765 0.001015 0.024248 -vn 0.815989 -0.278567 -0.506520 -v -0.021201 0.003563 0.024190 -vn 0.726671 -0.312345 -0.611874 -v -0.021922 0.003723 0.023113 -vn 0.807859 -0.314775 -0.498278 -v -0.021123 0.003788 0.024181 -vn 0.810910 -0.462919 -0.357955 -v -0.019876 0.006476 0.024036 -vn 0.748903 -0.499398 -0.435599 -v -0.020070 0.006706 0.023382 -vn 0.798488 -0.491310 -0.347896 -v -0.019683 0.006813 0.024012 -vn 0.782197 -0.604337 -0.151479 -v -0.017354 0.010261 0.023705 -vn 0.791163 -0.590718 -0.158475 -v -0.017466 0.010110 0.023720 -vn 0.734547 -0.631126 -0.249241 -v -0.017852 0.009956 0.022744 -vn 0.799849 -0.566545 -0.198161 -v -0.018448 0.008745 0.023853 -vn 0.754833 -0.554283 -0.350709 -v -0.018657 0.008459 0.023838 -vn 0.792073 -0.527855 -0.306576 -v -0.019278 0.007483 0.023961 -vn 0.777995 -0.616864 -0.119178 -v -0.017066 0.010642 0.023665 -vn 0.738776 -0.664254 -0.113913 -v -0.016267 0.011804 0.022548 -vn 0.787559 -0.615162 -0.036421 -v -0.016304 0.011627 0.023559 -vn 0.783177 -0.621682 -0.012090 -v -0.015841 0.012213 0.023493 -vn 0.080954 -0.784990 -0.614196 -v -0.019131 0.014515 0.013861 -vn 0.678655 -0.701097 -0.218836 -v -0.016884 0.011430 0.021450 -vn 0.197191 -0.761413 -0.617549 -v -0.019957 0.012859 0.015753 -vn 0.173330 -0.814057 -0.554317 -v -0.018268 0.014219 0.014458 -vn 0.160132 -0.849270 -0.503088 -v -0.016394 0.015485 0.013007 -vn 0.612550 -0.628828 -0.478914 -v -0.015417 0.015417 0.013546 -vn 0.710006 -0.583744 -0.393872 -v -0.019419 0.008193 0.022574 -vn 0.659455 -0.659936 -0.360005 -v -0.018605 0.009690 0.021580 -vn 0.604990 -0.726450 -0.325972 -v -0.017619 0.011177 0.020391 -vn 0.547738 -0.784315 -0.291263 -v -0.016458 0.012629 0.019005 -vn 0.361300 -0.660357 -0.658324 -v -0.021580 0.009690 0.018605 -vn 0.327273 -0.726763 -0.603910 -v -0.020391 0.011177 0.017619 -vn 0.292539 -0.784517 -0.546766 -v -0.019005 0.012629 0.016458 -vn 0.698573 -0.418921 -0.580088 -v -0.021542 0.005132 0.022699 -vn 0.660737 -0.512965 -0.547991 -v -0.021020 0.006579 0.022133 -vn 0.617842 -0.598169 -0.510357 -v -0.020340 0.008059 0.021400 -vn 0.570821 -0.673602 -0.469493 -v -0.019489 0.009556 0.020488 -vn 0.520911 -0.739409 -0.426528 -v -0.018458 0.011049 0.019388 -vn 0.469105 -0.796053 -0.382414 -v -0.017243 0.012513 0.018096 -vn 0.549154 -0.513165 -0.659615 -v -0.022133 0.006579 0.021020 -vn 0.511610 -0.598343 -0.616637 -v -0.021400 0.008059 0.020340 -vn 0.470770 -0.673743 -0.569601 -v -0.020488 0.009556 0.019489 -vn 0.427800 -0.739517 -0.519713 -v -0.019388 0.011049 0.018458 -vn 0.383633 -0.796120 -0.467995 -v -0.018096 0.012513 0.017243 -vn 0.635540 0.563213 -0.528091 -v -0.020650 -0.007425 0.021734 -vn 0.526868 0.563024 -0.636721 -v -0.021734 -0.007425 0.020650 -vn 0.588987 0.644487 -0.487577 -v -0.019854 -0.008951 0.020878 -vn 0.486286 0.644327 -0.590228 -v -0.020878 -0.008951 0.019854 -vn 0.371494 0.631317 -0.680757 -v -0.022004 -0.009086 0.018953 -vn 0.267870 0.609998 -0.745753 -v -0.023209 -0.009353 0.018196 -vn 0.201753 0.570708 -0.795982 -v -0.023853 -0.008745 0.018448 -vn 0.145605 0.603340 -0.784079 -v -0.023720 -0.010110 0.017466 -vn 0.625031 0.702483 -0.340373 -v -0.018015 -0.010613 0.020867 -vn 0.538995 0.715549 -0.444380 -v -0.018873 -0.010482 0.019829 -vn 0.443088 0.715437 -0.540206 -v -0.019829 -0.010482 0.018873 -vn 0.339062 0.702139 -0.626129 -v -0.020867 -0.010613 0.018015 -vn 0.229782 0.675560 -0.700584 -v -0.021966 -0.010872 0.017272 -vn 0.129806 0.639603 -0.757667 -v -0.023108 -0.011255 0.016657 -vn 0.051377 0.614788 -0.787017 -v -0.023559 -0.011627 0.016304 -vn 0.639605 0.740639 -0.205814 -v -0.016179 -0.012351 0.020517 -vn 0.567611 0.764678 -0.305099 -v -0.016896 -0.012112 0.019526 -vn 0.486782 0.776747 -0.399633 -v -0.017702 -0.011992 0.018583 -vn 0.398389 0.776668 -0.487928 -v -0.018583 -0.011992 0.017702 -vn 0.303806 0.764441 -0.568623 -v -0.019526 -0.012112 0.016896 -vn 0.204517 0.740256 -0.640464 -v -0.020517 -0.012351 0.016179 -vn 0.100495 0.704507 -0.702546 -v -0.021539 -0.012706 0.015561 -vn 0.089710 0.765178 -0.637538 -v -0.019768 -0.014077 0.014312 -vn 0.180145 0.796691 -0.576915 -v -0.018865 -0.013765 0.014917 -vn 0.268304 0.817944 -0.508901 -v -0.017985 -0.013554 0.015596 -vn 0.353065 0.828668 -0.434344 -v -0.017140 -0.013448 0.016341 -vn 0.433305 0.828711 -0.354240 -v -0.016341 -0.013448 0.017140 -vn 0.508003 0.818081 -0.269587 -v -0.015596 -0.013554 0.017985 -vn 0.576220 0.796899 -0.181445 -v -0.014917 -0.013765 0.018865 -vn 0.637033 0.765444 -0.091015 -v -0.014312 -0.014077 0.019768 -vn -0.364796 -0.803479 -0.470474 -v 0.004501 0.020847 0.024150 -vn -0.409435 -0.768774 -0.491274 -v 0.005244 0.020572 0.024012 -vn -0.431270 -0.820298 -0.375657 -v 0.005469 0.020407 0.024100 -vn 0.488626 -0.807494 -0.330451 -v -0.006886 0.019641 0.024007 -vn 0.519993 -0.795923 -0.310022 -v -0.007749 0.019110 0.023939 -vn 0.548198 -0.728461 -0.410881 -v -0.007557 0.019716 0.022941 -vn 0.827595 -0.435464 -0.354200 -v -0.013448 0.016341 0.017140 -vn 0.561728 -0.258043 -0.786051 -v -0.008362 0.023887 0.018708 -vn 0.531151 -0.307005 -0.789700 -v -0.007751 0.023939 0.019109 -vn 0.546442 -0.410881 -0.729779 -v -0.007557 0.022941 0.019716 -vn 0.509746 -0.317519 -0.799588 -v -0.007483 0.023961 0.019278 -vn 0.477960 -0.352550 -0.804527 -v -0.006476 0.024036 0.019876 -vn 0.464878 -0.456924 -0.758360 -v -0.006046 0.023686 0.020313 -vn 0.394851 -0.453388 -0.799082 -v -0.004897 0.024131 0.020676 -vn 0.365536 -0.472837 -0.801754 -v -0.004558 0.024148 0.020823 -vn 0.368696 -0.595222 -0.713985 -v -0.004466 0.022912 0.021737 -vn -0.856403 -0.492896 -0.153709 -v 0.015485 0.013007 0.016394 -vn -0.871931 -0.433220 -0.228161 -v 0.015320 0.013617 0.015662 -vn -0.880187 -0.368578 -0.299033 -v 0.015237 0.014267 0.014951 -vn -0.854428 -0.160198 -0.494256 -v 0.015485 0.016394 0.013007 -vn -0.829476 -0.080886 -0.552655 -v 0.015730 0.017141 0.012443 -vn -0.724426 -0.094128 -0.682896 -v 0.013200 0.020937 0.015138 -vn -0.665216 -0.110976 -0.738358 -v 0.011804 0.022548 0.016267 -vn -0.622117 -0.133753 -0.771415 -v 0.010654 0.023664 0.017056 -vn -0.611543 -0.053399 -0.789407 -v 0.011265 0.023598 0.016586 -vn -0.617099 -0.022902 -0.786552 -v 0.012215 0.023493 0.015839 -vn -0.595846 -0.153830 -0.788228 -v 0.010116 0.023720 0.017462 -vn -0.604409 -0.151258 -0.782183 -v 0.010260 0.023705 0.017354 -vn -0.630066 -0.246017 -0.736541 -v 0.009956 0.022744 0.017851 -vn -0.702755 -0.216608 -0.677655 -v 0.011430 0.021450 0.016884 -vn -0.572534 -0.182553 -0.799299 -v 0.009008 0.023829 0.018265 -vn -0.561888 -0.346919 -0.750952 -v 0.008459 0.023838 0.018657 -vn -0.535612 -0.289520 -0.793283 -v 0.007933 0.023924 0.018991 -vn -0.493151 -0.339570 -0.800933 -v 0.006885 0.024007 0.019641 -vn -0.499056 -0.435812 -0.749007 -v 0.006706 0.023382 0.020070 -vn -0.585654 -0.392268 -0.709320 -v 0.008193 0.022574 0.019419 -vn -0.344215 -0.478632 -0.807730 -v 0.004084 0.024169 0.021013 -vn -0.381874 -0.376201 -0.844183 -v 0.004945 0.024128 0.020654 -vn -0.420110 -0.472299 -0.774881 -v 0.005244 0.024012 0.020572 -vn -0.423668 -0.410569 -0.807427 -v 0.005258 0.024112 0.020509 -vn -0.437683 -0.359262 -0.824236 -v 0.005822 0.024079 0.020229 -vn -0.312331 -0.613363 -0.725421 -v 0.003723 0.023113 0.021922 -vn -0.301247 -0.501796 -0.810834 -v 0.003788 0.024181 0.021123 -vn -0.418511 -0.582050 -0.697185 -v 0.005132 0.022699 0.021542 -vn -0.204857 -0.639904 -0.740646 -v 0.002350 0.023389 0.022173 -vn -0.090920 -0.653791 -0.751193 -v 0.001004 0.023539 0.022309 -vn -0.102577 -0.550678 -0.828391 -v 0.001015 0.024248 0.021765 -vn -0.138319 -0.533087 -0.834677 -v 0.001637 0.024240 0.021684 -vn -0.209113 -0.527677 -0.823304 -v 0.002396 0.024225 0.021535 -vn -0.261503 -0.507005 -0.821317 -v 0.003236 0.024201 0.021307 -vn 0.083653 -0.547128 -0.832859 -v -0.000819 0.024250 0.021783 -vn 0.032614 -0.560617 -0.827433 -v -0.000336 0.024253 0.021810 -vn 0.030261 -0.654311 -0.755620 -v -0.000333 0.023568 0.022336 -vn -0.011743 -0.554964 -0.831791 -v -0.000006 0.024253 0.021816 -vn -0.056087 -0.554023 -0.830610 -v 0.000810 0.024250 0.021784 -vn 0.137776 -0.545999 -0.826380 -v -0.001636 0.024240 0.021684 -vn 0.144847 -0.647116 -0.748505 -v -0.001679 0.023479 0.022255 -vn 0.198076 -0.529648 -0.824766 -v -0.002464 0.024223 0.021518 -vn 0.261169 -0.624690 -0.735903 -v -0.003052 0.023264 0.022059 -vn 0.227208 -0.524301 -0.820661 -v -0.002643 0.024219 0.021474 -vn 0.340839 -0.479184 -0.808834 -v -0.004501 0.024150 0.020847 -vn 0.304112 -0.499028 -0.811472 -v -0.003563 0.024190 0.021201 -vn 0.255790 -0.520835 -0.814434 -v -0.003098 0.024206 0.021349 -vn 0.472540 -0.562161 -0.678735 -v -0.005925 0.022407 0.021273 -vn 0.423930 -0.377724 -0.823170 -v -0.005470 0.024100 0.020407 -vn 0.866623 -0.313371 -0.388282 -v -0.014822 0.015509 0.014796 -vn 0.860160 -0.238406 -0.450875 -v -0.014910 0.016253 0.014122 -vn 0.844934 -0.158326 -0.510900 -v -0.015086 0.017021 0.013494 -vn 0.817559 -0.078277 -0.570500 -v -0.015349 0.017805 0.012917 -vn 0.828655 -0.353110 -0.434332 -v -0.013448 0.017140 0.016341 -vn 0.814781 -0.511518 -0.272911 -v -0.013554 0.015596 0.017985 -vn 0.790557 -0.583391 -0.186211 -v -0.013765 0.014917 0.018865 -vn 0.761581 -0.638844 -0.108957 -v -0.014077 0.014312 0.019768 -vn 0.703975 -0.703511 -0.097428 -v -0.012706 0.015561 0.021539 -vn 0.677337 -0.699574 -0.227622 -v -0.010872 0.017272 0.021966 -vn 0.602091 -0.785625 -0.142408 -v -0.010116 0.017462 0.023720 -vn 0.640948 -0.757483 -0.124118 -v -0.011255 0.016657 0.023108 -vn 0.613135 -0.787647 -0.060648 -v -0.011265 0.016586 0.023598 -vn 0.620888 -0.781653 -0.059296 -v -0.011448 0.016444 0.023578 -vn 0.631645 -0.679399 -0.373420 -v -0.009086 0.018953 0.022004 -vn 0.552894 -0.785621 -0.277683 -v -0.007933 0.018991 0.023924 -vn 0.605451 -0.751535 -0.261962 -v -0.009353 0.018196 0.023209 -vn 0.569260 -0.798460 -0.195969 -v -0.009008 0.018265 0.023829 -vn 0.589430 -0.781594 -0.204164 -v -0.009523 0.017897 0.023779 -vn 0.471741 -0.797533 -0.376035 -v -0.006103 0.020081 0.024061 -vn 0.403111 -0.838941 -0.365622 -v -0.004945 0.020654 0.024128 -vn 0.432969 -0.817013 -0.380824 -v -0.005822 0.020229 0.024079 -vn 0.471138 -0.756243 -0.454011 -v -0.006046 0.020313 0.023686 -vn 0.367714 -0.714109 -0.595680 -v -0.004466 0.021737 0.022912 -vn 0.360387 -0.794200 -0.489252 -v -0.004559 0.020823 0.024148 -vn 0.389864 -0.802492 -0.451678 -v -0.004920 0.020666 0.024130 -vn 0.473442 -0.677943 -0.562358 -v -0.005925 0.021273 0.022407 -vn 0.198838 -0.829177 -0.522426 -v -0.002396 0.021535 0.024225 -vn 0.245395 -0.817572 -0.520919 -v -0.003098 0.021349 0.024206 -vn 0.260871 -0.733684 -0.627419 -v -0.003052 0.022059 0.023264 -vn 0.285020 -0.814924 -0.504642 -v -0.003236 0.021307 0.024201 -vn 0.322420 -0.813436 -0.484115 -v -0.004084 0.021013 0.024169 -vn 0.144281 -0.828282 -0.541416 -v -0.001637 0.021684 0.024240 -vn 0.150558 -0.746000 -0.648704 -v -0.001679 0.022255 0.023479 -vn 0.075977 -0.829492 -0.553327 -v -0.000810 0.021784 0.024250 -vn 0.028601 -0.755948 -0.654007 -v -0.000333 0.022336 0.023568 -vn 0.035680 -0.823850 -0.565684 -v -0.000336 0.021810 0.024253 -vn -0.087014 -0.753563 -0.651591 -v 0.001004 0.022309 0.023539 -vn -0.055529 -0.831027 -0.553453 -v 0.000819 0.021783 0.024250 -vn -0.013872 -0.832477 -0.553886 -v 0.000006 0.021816 0.024253 -vn -0.238887 -0.817319 -0.524331 -v 0.002643 0.021474 0.024219 -vn -0.195517 -0.821892 -0.535039 -v 0.002464 0.021518 0.024223 -vn -0.203754 -0.743297 -0.637176 -v 0.002350 0.022173 0.023389 -vn -0.146371 -0.826694 -0.543279 -v 0.001636 0.021684 0.024240 -vn -0.096947 -0.826082 -0.555149 -v 0.001015 0.021765 0.024248 -vn -0.278530 -0.816016 -0.506497 -v 0.003563 0.021201 0.024190 -vn -0.312343 -0.726671 -0.611875 -v 0.003723 0.021922 0.023113 -vn -0.314774 -0.807868 -0.498264 -v 0.003788 0.021123 0.024181 -vn -0.462928 -0.810896 -0.357974 -v 0.006476 0.019876 0.024036 -vn -0.499395 -0.748912 -0.435586 -v 0.006706 0.020070 0.023382 -vn -0.491320 -0.798476 -0.347908 -v 0.006813 0.019683 0.024012 -vn -0.527865 -0.792071 -0.306566 -v 0.007483 0.019278 0.023961 -vn -0.554325 -0.754906 -0.350485 -v 0.008459 0.018657 0.023838 -vn -0.566536 -0.799869 -0.198108 -v 0.008745 0.018448 0.023853 -vn -0.631130 -0.734548 -0.249228 -v 0.009956 0.017851 0.022744 -vn -0.590729 -0.791153 -0.158481 -v 0.010110 0.017466 0.023720 -vn -0.616860 -0.777993 -0.119213 -v 0.010642 0.017066 0.023665 -vn -0.664261 -0.738774 -0.113886 -v 0.011804 0.016267 0.022548 -vn -0.615166 -0.787554 -0.036467 -v 0.011627 0.016304 0.023559 -vn -0.621705 -0.783159 -0.012044 -v 0.012213 0.015840 0.023493 -vn -0.728939 -0.677752 -0.096439 -v 0.013200 0.015138 0.020937 -vn -0.831993 -0.549394 -0.077161 -v 0.015730 0.012443 0.017141 -vn -0.783284 -0.615135 -0.089861 -v 0.014515 0.013861 0.019131 -vn -0.784989 -0.080955 -0.614197 -v 0.014515 0.019131 0.013861 -vn -0.813894 -0.554959 -0.172039 -v 0.014219 0.014458 0.018268 -vn -0.761084 -0.618360 -0.195911 -v 0.012859 0.015753 0.019957 -vn -0.701101 -0.678647 -0.218849 -v 0.011430 0.016884 0.021450 -vn -0.604333 -0.782197 -0.151492 -v 0.010261 0.017354 0.023705 -vn -0.761416 -0.197202 -0.617541 -v 0.012859 0.019957 0.015753 -vn -0.814060 -0.173335 -0.554311 -v 0.014219 0.018268 0.014458 -vn -0.583751 -0.709998 -0.393876 -v 0.008193 0.019419 0.022574 -vn -0.659940 -0.659449 -0.360008 -v 0.009690 0.018605 0.021580 -vn -0.726449 -0.604986 -0.325982 -v 0.011177 0.017619 0.020391 -vn -0.784314 -0.547734 -0.291272 -v 0.012629 0.016458 0.019005 -vn -0.834024 -0.488508 -0.256444 -v 0.014019 0.015122 0.017426 -vn -0.660363 -0.361301 -0.658318 -v 0.009690 0.021580 0.018605 -vn -0.726763 -0.327276 -0.603909 -v 0.011177 0.020391 0.017619 -vn -0.784519 -0.292547 -0.546760 -v 0.012629 0.019005 0.016458 -vn -0.834133 -0.257688 -0.487666 -v 0.014019 0.017426 0.015122 -vn -0.863961 -0.232595 -0.446622 -v 0.015320 0.015662 0.013617 -vn -0.418912 -0.698573 -0.580094 -v 0.005132 0.021542 0.022699 -vn -0.512963 -0.660734 -0.547995 -v 0.006579 0.021020 0.022133 -vn -0.598175 -0.617837 -0.510357 -v 0.008059 0.020340 0.021400 -vn -0.673608 -0.570819 -0.469487 -v 0.009556 0.019489 0.020488 -vn -0.739404 -0.520917 -0.426528 -v 0.011049 0.018458 0.019388 -vn -0.796050 -0.469111 -0.382412 -v 0.012513 0.017243 0.018096 -vn -0.844173 -0.416228 -0.337827 -v 0.013919 0.015844 0.016615 -vn -0.513155 -0.549159 -0.659618 -v 0.006579 0.022133 0.021020 -vn -0.598349 -0.511601 -0.616639 -v 0.008059 0.021400 0.020340 -vn -0.673747 -0.470765 -0.569601 -v 0.009556 0.020488 0.019489 -vn -0.739514 -0.427791 -0.519725 -v 0.011049 0.019388 0.018458 -vn -0.796117 -0.383634 -0.467998 -v 0.012513 0.018096 0.017243 -vn -0.844211 -0.338970 -0.415220 -v 0.013919 0.016615 0.015844 -vn -0.879176 -0.301188 -0.369237 -v 0.015237 0.014951 0.014267 -vn 0.563213 -0.635538 -0.528093 -v -0.007425 0.020650 0.021734 -vn 0.563035 -0.526864 -0.636715 -v -0.007425 0.021734 0.020650 -vn 0.644495 -0.588994 -0.487557 -v -0.008951 0.019854 0.020878 -vn 0.644338 -0.486283 -0.590218 -v -0.008951 0.020878 0.019854 -vn 0.631313 -0.371482 -0.680768 -v -0.009086 0.022004 0.018953 -vn 0.609998 -0.267893 -0.745745 -v -0.009353 0.023209 0.018196 -vn 0.570734 -0.201793 -0.795954 -v -0.008745 0.023853 0.018448 -vn 0.603341 -0.145596 -0.784080 -v -0.010110 0.023720 0.017466 -vn 0.702484 -0.625040 -0.340355 -v -0.010613 0.018015 0.020867 -vn 0.715547 -0.539009 -0.444367 -v -0.010482 0.018873 0.019829 -vn 0.715428 -0.443085 -0.540221 -v -0.010482 0.019829 0.018873 -vn 0.702133 -0.339053 -0.626141 -v -0.010613 0.020867 0.018015 -vn 0.675564 -0.229794 -0.700577 -v -0.010872 0.021966 0.017272 -vn 0.639599 -0.129815 -0.757668 -v -0.011255 0.023108 0.016657 -vn 0.614780 -0.051382 -0.787023 -v -0.011627 0.023559 0.016304 -vn 0.740642 -0.639604 -0.205808 -v -0.012351 0.016179 0.020517 -vn 0.764677 -0.567613 -0.305097 -v -0.012112 0.016896 0.019526 -vn 0.776746 -0.486784 -0.399633 -v -0.011992 0.017702 0.018583 -vn 0.776668 -0.398386 -0.487930 -v -0.011992 0.018583 0.017702 -vn 0.764441 -0.303799 -0.568627 -v -0.012112 0.019526 0.016896 -vn 0.740261 -0.204517 -0.640458 -v -0.012351 0.020517 0.016179 -vn 0.704496 -0.100491 -0.702558 -v -0.012706 0.021539 0.015561 -vn 0.765174 -0.089703 -0.637544 -v -0.014077 0.019768 0.014312 -vn 0.796687 -0.180139 -0.576923 -v -0.013765 0.018865 0.014917 -vn 0.817945 -0.268311 -0.508896 -v -0.013554 0.017985 0.015596 -vn 0.799129 0.599872 0.039327 -v -0.016527 -0.011329 0.023957 -vn 0.790604 -0.590231 0.163011 -v -0.015601 0.012575 0.023927 -vn 0.790863 -0.567742 0.228483 -v -0.015602 0.012642 0.024134 -vn 0.807497 -0.562863 0.176449 -v -0.016235 0.011790 0.024261 -vn 0.786081 -0.543907 0.293669 -v -0.015620 0.012734 0.024378 -vn 0.778946 -0.519191 0.351688 -v -0.015630 0.012767 0.024457 -vn 0.801241 -0.523073 0.290529 -v -0.016253 0.011910 0.024603 -vn 0.754908 -0.460927 0.466542 -v -0.015699 0.012933 0.024805 -vn 0.736553 -0.425949 0.525412 -v -0.015779 0.013078 0.025060 -vn 0.753611 -0.421348 0.504516 -v -0.016395 0.012216 0.025243 -vn 0.715949 -0.389165 0.579628 -v -0.015836 0.013167 0.025199 -vn 0.692967 -0.352510 0.628915 -v -0.015899 0.013260 0.025331 -vn 0.713064 -0.360932 0.601055 -v -0.016515 0.012398 0.025533 -vn 0.661726 -0.313677 0.680974 -v -0.016027 0.013431 0.025548 -vn 0.634800 -0.278663 0.720678 -v -0.016047 0.013457 0.025577 -vn 0.662120 -0.295122 0.688840 -v -0.016667 0.012596 0.025796 -vn 0.481897 -0.110109 0.869282 -v -0.016554 0.014021 0.026081 -vn 0.438436 -0.062418 0.896592 -v -0.016638 0.014105 0.026134 -vn 0.454468 -0.076466 0.887475 -v -0.017286 0.013256 0.026391 -vn 0.522951 -0.153300 0.838464 -v -0.016419 0.013882 0.025981 -vn 0.601350 -0.225731 0.766436 -v -0.016848 0.012807 0.026029 -vn 0.599233 -0.234940 0.765325 -v -0.016221 0.013665 0.025795 -vn 0.565370 -0.197101 0.800942 -v -0.016269 0.013718 0.025844 -vn 0.783245 -0.475709 0.400285 -v -0.016307 0.012052 0.024932 -vn 0.766993 -0.488889 0.415583 -v -0.015689 0.012913 0.024768 -vn 0.785838 -0.610979 0.095722 -v -0.015607 0.012540 0.023802 -vn 0.813298 -0.580770 -0.035386 -v -0.017385 0.010159 0.024097 -vn 0.801707 -0.595293 0.053780 -v -0.016252 0.011695 0.023911 -vn 0.833313 -0.519367 -0.189334 -v -0.019142 0.007497 0.024368 -vn 0.824136 -0.554618 -0.114887 -v -0.018338 0.008776 0.024247 -vn 0.868704 -0.364069 -0.335869 -v -0.020648 0.004491 0.024572 -vn 0.859857 -0.419695 -0.290694 -v -0.020227 0.005464 0.024519 -vn 0.849425 -0.467830 -0.244158 -v -0.019718 0.006480 0.024450 -vn 0.895362 -0.145650 -0.420848 -v -0.021443 0.001627 0.024664 -vn 0.893279 -0.198143 -0.403475 -v -0.021287 0.002452 0.024647 -vn 0.886188 -0.242126 -0.395026 -v -0.021245 0.002630 0.024643 -vn 0.880749 -0.292680 -0.372316 -v -0.020986 0.003549 0.024613 -vn 0.900431 -0.001806 -0.434995 -v -0.021568 0.000006 0.024677 -vn 0.898952 -0.070667 -0.432310 -v -0.021536 0.000814 0.024674 -vn 0.900076 0.070953 -0.429917 -v -0.021537 -0.000805 0.024674 -vn 0.896632 0.141173 -0.419668 -v -0.021443 -0.001627 0.024664 -vn 0.891283 0.208191 -0.402829 -v -0.021302 -0.002384 0.024649 -vn 0.875316 0.334210 -0.349464 -v -0.020807 -0.004072 0.024592 -vn 0.883940 0.271322 -0.380833 -v -0.021086 -0.003222 0.024625 -vn 0.867268 0.386468 -0.313830 -v -0.020464 -0.004937 0.024549 -vn 0.854263 0.442394 -0.272988 -v -0.020056 -0.005820 0.024496 -vn 0.820086 0.563870 -0.097515 -v -0.018160 -0.009042 0.024220 -vn 0.832583 0.529456 -0.162734 -v -0.018864 -0.007953 0.024327 -vn 0.845210 0.489048 -0.215526 -v -0.019491 -0.006893 0.024418 -vn 0.462841 -0.077926 0.883009 -v -0.018427 0.011676 0.026844 -vn 0.471333 -0.076844 0.878601 -v -0.019392 0.010209 0.027226 -vn 0.479583 -0.073957 0.874374 -v -0.020209 0.008818 0.027551 -vn 0.486677 -0.069272 0.870831 -v -0.020798 0.007685 0.027784 -vn 0.493406 -0.063211 0.867499 -v -0.021322 0.006532 0.027991 -vn 0.499653 -0.055542 0.864443 -v -0.021757 0.005406 0.028164 -vn 0.505212 -0.046431 0.861745 -v -0.022108 0.004298 0.028303 -vn 0.509897 -0.038490 0.859374 -v -0.022379 0.003200 0.028410 -vn 0.511793 -0.031761 0.858522 -v -0.022422 0.002986 0.028427 -vn 0.513701 -0.023093 0.857658 -v -0.022587 0.001987 0.028492 -vn 0.515620 -0.011788 0.856736 -v -0.022685 0.000996 0.028531 -vn 0.516315 -0.000147 0.856399 -v -0.022718 0.000008 0.028544 -vn 0.515702 0.011581 0.856690 -v -0.022685 -0.000985 0.028531 -vn 0.513951 0.022819 0.857516 -v -0.022587 -0.001988 0.028492 -vn 0.511248 0.033176 0.858793 -v -0.022438 -0.002904 0.028433 -vn 0.507320 0.042909 0.860689 -v -0.022213 -0.003909 0.028344 -vn 0.502645 0.051787 0.862940 -v -0.021922 -0.004915 0.028229 -vn 0.497311 0.059416 0.865536 -v -0.021566 -0.005925 0.028088 -vn 0.491329 0.066021 0.868468 -v -0.021146 -0.006939 0.027922 -vn 0.484242 0.071400 0.872016 -v -0.020566 -0.008149 0.027692 -vn 0.477147 0.075337 0.875589 -v -0.019927 -0.009319 0.027438 -vn 0.470129 0.077600 0.879180 -v -0.019212 -0.010495 0.027155 -vn 0.463286 0.078336 0.882740 -v -0.018423 -0.011682 0.026842 -vn 0.455675 0.077921 0.886729 -v -0.017563 -0.012884 0.026501 -vn 0.623107 -0.229369 0.747748 -v -0.017947 0.011221 0.026438 -vn 0.688201 -0.299955 0.660611 -v -0.017753 0.011009 0.026176 -vn 0.645446 -0.225803 0.729666 -v -0.018870 0.009762 0.026779 -vn 0.715133 -0.294634 0.633857 -v -0.018662 0.009556 0.026491 -vn 0.667063 -0.216825 0.712751 -v -0.019647 0.008391 0.027065 -vn 0.741168 -0.282294 0.609082 -v -0.019425 0.008196 0.026753 -vn 0.685803 -0.202726 0.698982 -v -0.020202 0.007285 0.027268 -vn 0.763906 -0.263558 0.589055 -v -0.019969 0.007102 0.026938 -vn 0.703748 -0.184794 0.685996 -v -0.020692 0.006168 0.027446 -vn 0.785654 -0.239878 0.570268 -v -0.020447 0.006003 0.027099 -vn 0.720444 -0.162202 0.674278 -v -0.021096 0.005086 0.027592 -vn 0.805953 -0.210322 0.553358 -v -0.020840 0.004942 0.027229 -vn 0.735255 -0.135443 0.664120 -v -0.021419 0.004031 0.027709 -vn 0.823946 -0.175437 0.538828 -v -0.021154 0.003911 0.027333 -vn 0.746424 -0.112095 0.655962 -v -0.021667 0.002994 0.027797 -vn 0.837159 -0.144900 0.527417 -v -0.021394 0.002901 0.027411 -vn 0.751589 -0.092335 0.653137 -v -0.021707 0.002792 0.027812 -vn 0.843636 -0.119297 0.523495 -v -0.021432 0.002705 0.027423 -vn 0.757878 -0.067290 0.648917 -v -0.021856 0.001855 0.027865 -vn 0.851358 -0.086982 0.517323 -v -0.021576 0.001796 0.027470 -vn 0.762861 -0.034287 0.645653 -v -0.021944 0.000929 0.027896 -vn 0.857479 -0.044335 0.512605 -v -0.021662 0.000899 0.027497 -vn 0.764583 -0.000384 0.644525 -v -0.021974 0.000007 0.027907 -vn 0.859608 -0.000506 0.510954 -v -0.021690 0.000007 0.027507 -vn 0.762940 0.033685 0.645591 -v -0.021945 -0.000919 0.027897 -vn 0.857587 0.043530 0.512493 -v -0.021662 -0.000889 0.027498 -vn 0.758133 0.066297 0.648721 -v -0.021856 -0.001855 0.027865 -vn 0.851673 0.085698 0.517019 -v -0.021576 -0.001796 0.027470 -vn 0.750667 0.096514 0.653593 -v -0.021721 -0.002715 0.027817 -vn 0.842538 0.124831 0.523973 -v -0.021446 -0.002630 0.027428 -vn 0.740272 0.124910 0.660602 -v -0.021515 -0.003663 0.027743 -vn 0.829952 0.161664 0.533896 -v -0.021247 -0.003552 0.027363 -vn 0.727638 0.150807 0.669179 -v -0.021248 -0.004618 0.027647 -vn 0.814565 0.195361 0.546184 -v -0.020988 -0.004484 0.027278 -vn 0.713351 0.173174 0.679074 -v -0.020919 -0.005583 0.027528 -vn 0.797166 0.224576 0.560439 -v -0.020669 -0.005429 0.027172 -vn 0.697404 0.192656 0.690298 -v -0.020528 -0.006560 0.027386 -vn 0.777868 0.250147 0.576497 -v -0.020287 -0.006389 0.027045 -vn 0.678754 0.208686 0.704090 -v -0.019984 -0.007736 0.027188 -vn 0.755304 0.271407 0.596535 -v -0.019755 -0.007548 0.026865 -vn 0.659944 0.220473 0.718238 -v -0.019379 -0.008883 0.026966 -vn 0.732478 0.287179 0.617256 -v -0.019162 -0.008683 0.026663 -vn 0.641401 0.227349 0.732747 -v -0.018698 -0.010045 0.026716 -vn 0.710156 0.296682 0.638481 -v -0.018493 -0.009837 0.026433 -vn 0.623368 0.229772 0.747407 -v -0.017943 -0.011227 0.026436 -vn 0.688370 0.300383 0.660240 -v -0.017749 -0.011015 0.026175 -vn 0.605936 0.227993 0.762142 -v -0.017116 -0.012433 0.026128 -vn 0.666969 0.298801 0.682546 -v -0.016932 -0.012221 0.025889 -vn 0.741728 -0.365485 0.562370 -v -0.017593 0.010812 0.025881 -vn 0.782809 -0.424899 0.454610 -v -0.017470 0.010634 0.025558 -vn 0.771413 -0.357943 0.526116 -v -0.018494 0.009366 0.026168 -vn 0.813215 -0.414541 0.408458 -v -0.018369 0.009196 0.025816 -vn 0.800096 -0.342014 0.492821 -v -0.019248 0.008017 0.026404 -vn 0.842600 -0.394730 0.366351 -v -0.019121 0.007860 0.026025 -vn 0.825308 -0.318640 0.466192 -v -0.019785 0.006937 0.026569 -vn 0.868642 -0.366734 0.333117 -v -0.019656 0.006793 0.026170 -vn 0.849408 -0.289458 0.441271 -v -0.020257 0.005854 0.026712 -vn 0.893494 -0.332322 0.302044 -v -0.020125 0.005726 0.026295 -vn 0.871901 -0.253312 0.419072 -v -0.020643 0.004813 0.026827 -vn 0.916741 -0.290193 0.274543 -v -0.020509 0.004703 0.026393 -vn 0.891896 -0.211007 0.399998 -v -0.020951 0.003805 0.026916 -vn 0.937424 -0.241311 0.251009 -v -0.020815 0.003714 0.026470 -vn 0.906257 -0.174157 0.385185 -v -0.021186 0.002819 0.026984 -vn 0.951954 -0.198723 0.233008 -v -0.021048 0.002750 0.026527 -vn 0.913735 -0.143278 0.380210 -v -0.021223 0.002628 0.026994 -vn 0.960099 -0.163338 0.227003 -v -0.021085 0.002564 0.026535 -vn 0.922365 -0.104420 0.371939 -v -0.021364 0.001744 0.027034 -vn 0.968961 -0.119126 0.216618 -v -0.021225 0.001700 0.026569 -vn 0.929168 -0.053240 0.365804 -v -0.021447 0.000873 0.027057 -vn 0.975989 -0.060703 0.209189 -v -0.021308 0.000850 0.026588 -vn 0.931523 -0.000620 0.363682 -v -0.021475 0.000007 0.027065 -vn 0.978425 -0.000733 0.206600 -v -0.021335 0.000006 0.026594 -vn 0.929283 0.052213 0.365660 -v -0.021448 -0.000863 0.027057 -vn 0.976088 0.059503 0.209072 -v -0.021308 -0.000841 0.026588 -vn 0.922678 0.102856 0.371599 -v -0.021364 -0.001744 0.027034 -vn 0.969276 0.117233 0.216240 -v -0.021225 -0.001701 0.026569 -vn 0.912521 0.149878 0.380581 -v -0.021237 -0.002556 0.026998 -vn 0.958678 0.171040 0.227337 -v -0.021099 -0.002492 0.026539 -vn 0.898516 0.194311 0.393588 -v -0.021042 -0.003454 0.026943 -vn 0.944207 0.222018 0.243270 -v -0.020906 -0.003371 0.026492 -vn 0.881392 0.235115 0.409719 -v -0.020788 -0.004365 0.026869 -vn 0.926485 0.269074 0.263106 -v -0.020654 -0.004263 0.026430 -vn 0.862075 0.270641 0.428463 -v -0.020474 -0.005290 0.026777 -vn 0.906537 0.310286 0.286206 -v -0.020342 -0.005172 0.026351 -vn 0.840646 0.301929 0.449615 -v -0.020099 -0.006234 0.026665 -vn 0.884319 0.346866 0.312513 -v -0.019968 -0.006100 0.026253 -vn 0.815699 0.328339 0.476266 -v -0.019574 -0.007377 0.026505 -vn 0.858675 0.378249 0.345839 -v -0.019446 -0.007227 0.026114 -vn 0.790474 0.348183 0.503904 -v -0.018989 -0.008500 0.026324 -vn 0.832721 0.402251 0.380486 -v -0.018862 -0.008337 0.025954 -vn 0.765774 0.360517 0.532558 -v -0.018326 -0.009646 0.026115 -vn 0.807306 0.417747 0.416826 -v -0.018202 -0.009474 0.025768 -vn 0.741779 0.365913 0.562024 -v -0.017589 -0.010818 0.025880 -vn 0.782753 0.425325 0.454309 -v -0.017466 -0.010640 0.025557 -vn 0.717111 0.365953 0.593153 -v -0.016778 -0.012022 0.025618 -vn 0.756761 0.427969 0.494121 -v -0.016657 -0.011841 0.025321 -vn 0.824993 -0.521355 0.218118 -v -0.017345 0.010344 0.024850 -vn 0.825400 -0.556777 0.093346 -v -0.017344 0.010238 0.024476 -vn 0.850478 -0.503415 0.152514 -v -0.018258 0.008929 0.025049 -vn 0.845249 -0.534033 0.019027 -v -0.018274 0.008837 0.024649 -vn 0.875096 -0.474782 0.093752 -v -0.019024 0.007621 0.025208 -vn 0.864427 -0.500562 -0.046945 -v -0.019056 0.007544 0.024787 -vn 0.897684 -0.438011 0.048066 -v -0.019570 0.006579 0.025316 -vn 0.882762 -0.459575 -0.097579 -v -0.019615 0.006514 0.024880 -vn 0.919025 -0.394155 0.005978 -v -0.020049 0.005541 0.025407 -vn 0.899885 -0.411675 -0.143983 -v -0.020107 0.005488 0.024958 -vn 0.939145 -0.342132 -0.030874 -v -0.020443 0.004547 0.025478 -vn 0.916139 -0.355942 -0.184374 -v -0.020512 0.004506 0.025019 -vn 0.957098 -0.283047 -0.062032 -v -0.020757 0.003589 0.025532 -vn 0.930742 -0.293446 -0.218196 -v -0.020836 0.003558 0.025064 -vn 0.968892 -0.232289 -0.085384 -v -0.020997 0.002657 0.025571 -vn 0.939722 -0.240253 -0.243314 -v -0.021084 0.002635 0.025097 -vn 0.977246 -0.190607 -0.093057 -v -0.021035 0.002476 0.025577 -vn 0.947598 -0.196931 -0.251549 -v -0.021124 0.002456 0.025102 -vn 0.984532 -0.138739 -0.106994 -v -0.021179 0.001641 0.025599 -vn 0.953103 -0.143126 -0.266664 -v -0.021273 0.001628 0.025121 -vn 0.990675 -0.070585 -0.116540 -v -0.021264 0.000821 0.025612 -vn 0.958115 -0.072751 -0.276988 -v -0.021362 0.000815 0.025132 -vn 0.992797 -0.000880 -0.119807 -v -0.021293 0.000006 0.025616 -vn 0.959838 -0.000988 -0.280552 -v -0.021392 0.000006 0.025135 -vn 0.990755 0.069022 -0.116795 -v -0.021265 -0.000812 0.025612 -vn 0.958175 0.071086 -0.277215 -v -0.021363 -0.000806 0.025132 -vn 0.984823 0.136442 -0.107276 -v -0.021179 -0.001642 0.025599 -vn 0.953368 0.140699 -0.267008 -v -0.021273 -0.001629 0.025121 -vn 0.975481 0.199483 -0.092965 -v -0.021049 -0.002407 0.025579 -vn 0.945644 0.206051 -0.251596 -v -0.021139 -0.002388 0.025104 -vn 0.962948 0.259894 -0.072015 -v -0.020850 -0.003257 0.025547 -vn 0.935483 0.269084 -0.229052 -v -0.020932 -0.003229 0.025077 -vn 0.947545 0.316314 -0.045865 -v -0.020591 -0.004121 0.025504 -vn 0.922963 0.328472 -0.200613 -v -0.020665 -0.004084 0.025041 -vn 0.930227 0.366674 -0.015071 -v -0.020271 -0.005002 0.025448 -vn 0.908918 0.382057 -0.167035 -v -0.020335 -0.004956 0.024993 -vn 0.910849 0.412246 0.020209 -v -0.019889 -0.005904 0.025377 -vn 0.893099 0.431150 -0.128390 -v -0.019942 -0.005848 0.024932 -vn 0.889128 0.452938 0.065567 -v -0.019355 -0.007002 0.025274 -vn 0.875901 0.476116 -0.078168 -v -0.019395 -0.006933 0.024844 -vn 0.866870 0.485415 0.113619 -v -0.018760 -0.008088 0.025154 -vn 0.858117 0.512864 -0.024613 -v -0.018787 -0.008005 0.024740 -vn 0.845348 0.508226 0.164600 -v -0.018088 -0.009202 0.025012 -vn 0.841148 0.539820 0.032627 -v -0.018101 -0.009107 0.024617 -vn 0.824748 0.521808 0.217960 -v -0.017341 -0.010350 0.024849 -vn 0.825091 0.557262 0.093193 -v -0.017340 -0.010244 0.024475 -vn 0.804277 0.526995 0.274617 -v -0.016519 -0.011537 0.024664 -vn 0.807562 0.568005 0.158789 -v -0.016505 -0.011421 0.024314 -vn 0.813727 0.580414 -0.031117 -v -0.017380 -0.010165 0.024097 -vn 0.437838 0.065717 0.896649 -v -0.016638 -0.014105 0.026134 -vn 0.483039 0.108574 0.868841 -v -0.016554 -0.014021 0.026081 -vn 0.531353 -0.151997 0.833403 -v -0.017056 0.013028 0.026228 -vn 0.547559 -0.154939 0.822298 -v -0.018173 0.011444 0.026661 -vn 0.563674 -0.152751 0.811751 -v -0.019115 0.009981 0.027025 -vn 0.579285 -0.146921 0.801775 -v -0.019910 0.008600 0.027332 -vn 0.592705 -0.137480 0.793600 -v -0.020481 0.007480 0.027552 -vn 0.605575 -0.125446 0.785839 -v -0.020986 0.006346 0.027746 -vn 0.617518 -0.110205 0.778798 -v -0.021404 0.005242 0.027906 -vn 0.628091 -0.092072 0.772674 -v -0.021740 0.004161 0.028035 -vn 0.636366 -0.076265 0.767608 -v -0.021998 0.003094 0.028133 -vn 0.640002 -0.062884 0.765796 -v -0.022040 0.002886 0.028149 -vn 0.644306 -0.045791 0.763396 -v -0.022196 0.001919 0.028209 -vn 0.647893 -0.023372 0.761373 -v -0.022289 0.000962 0.028244 -vn 0.649099 -0.000261 0.760704 -v -0.022320 0.000007 0.028256 -vn 0.647945 0.022943 0.761341 -v -0.022289 -0.000951 0.028244 -vn 0.644528 0.045157 0.763246 -v -0.022195 -0.001920 0.028209 -vn 0.639257 0.065688 0.766182 -v -0.022055 -0.002807 0.028155 -vn 0.631802 0.084982 0.770457 -v -0.021840 -0.003782 0.028073 -vn 0.622799 0.102553 0.775631 -v -0.021562 -0.004763 0.027967 -vn 0.612596 0.117681 0.781586 -v -0.021221 -0.005750 0.027836 -vn 0.601178 0.130811 0.788336 -v -0.020817 -0.006745 0.027681 -vn 0.587746 0.141541 0.796568 -v -0.020256 -0.007938 0.027465 -vn 0.574251 0.149378 0.804936 -v -0.019636 -0.009096 0.027226 -vn 0.560900 0.153867 0.813459 -v -0.018940 -0.010266 0.026958 -vn 0.547923 0.155351 0.821977 -v -0.018169 -0.011450 0.026660 -vn 0.535241 0.154954 0.830365 -v -0.017327 -0.012655 0.026333 -vn 0.527125 0.152866 0.835925 -v -0.016419 -0.013882 0.025981 -vn 0.563484 0.194879 0.802812 -v -0.016269 -0.013718 0.025844 -vn 0.599199 0.236597 0.764841 -v -0.016221 -0.013665 0.025795 -vn 0.641282 0.274152 0.716658 -v -0.016047 -0.013457 0.025577 -vn 0.663793 0.308493 0.681330 -v -0.016027 -0.013431 0.025548 -vn 0.692681 0.351218 0.629952 -v -0.015899 -0.013260 0.025331 -vn 0.716712 0.388194 0.579336 -v -0.015836 -0.013167 0.025199 -vn 0.737281 0.425015 0.525147 -v -0.015779 -0.013078 0.025060 -vn 0.755665 0.459999 0.466230 -v -0.015699 -0.012933 0.024805 -vn 0.810729 -0.477172 0.339153 -v -0.017387 0.010477 0.025213 -vn 0.839739 -0.463356 0.283090 -v -0.018290 0.009050 0.025440 -vn 0.867761 -0.439249 0.232489 -v -0.019046 0.007727 0.025624 -vn 0.892944 -0.406819 0.192744 -v -0.019583 0.006672 0.025750 -vn 0.916880 -0.367491 0.155824 -v -0.020056 0.005621 0.025856 -vn 0.939341 -0.320056 0.123295 -v -0.020442 0.004613 0.025940 -vn 0.959344 -0.265509 0.095733 -v -0.020750 0.003642 0.026005 -vn 0.973004 -0.218330 0.074800 -v -0.020984 0.002696 0.026052 -vn 0.981445 -0.179336 0.067858 -v -0.021022 0.002512 0.026059 -vn 0.989867 -0.130663 0.055585 -v -0.021163 0.001665 0.026086 -vn 0.996676 -0.066550 0.046982 -v -0.021246 0.000833 0.026102 -vn 0.999030 -0.000802 0.044031 -v -0.021274 0.000006 0.026107 -vn 0.996776 0.065154 0.046832 -v -0.021247 -0.000824 0.026102 -vn 0.990164 0.128541 0.055255 -v -0.021163 -0.001666 0.026086 -vn 0.979854 0.187733 0.068134 -v -0.021036 -0.002443 0.026062 -vn 0.965878 0.244046 0.086722 -v -0.020841 -0.003305 0.026023 -vn 0.948722 0.296362 0.109981 -v -0.020587 -0.004181 0.025971 -vn 0.929434 0.342548 0.137160 -v -0.020273 -0.005075 0.025904 -vn 0.907891 0.383935 0.168307 -v -0.019898 -0.005989 0.025821 -vn 0.883340 0.420081 0.207947 -v -0.019372 -0.007101 0.025701 -vn 0.858345 0.448292 0.249555 -v -0.018786 -0.008199 0.025561 -vn 0.834007 0.467290 0.293380 -v -0.018122 -0.009325 0.025398 -vn 0.810558 0.477590 0.338974 -v -0.017383 -0.010483 0.025212 -vn 0.787395 0.481424 0.385019 -v -0.016570 -0.011678 0.025001 -vn 0.767614 0.490053 0.413057 -v -0.015689 -0.012913 0.024768 -vn 0.777992 0.518695 0.354518 -v -0.015630 -0.012767 0.024457 -vn 0.785788 0.544977 0.292467 -v -0.015620 -0.012734 0.024378 -vn 0.792034 0.566474 0.227573 -v -0.015602 -0.012642 0.024134 -vn 0.792476 0.587555 0.163588 -v -0.015601 -0.012575 0.023927 -vn 0.788403 0.607372 0.097567 -v -0.015607 -0.012540 0.023802 -vn 0.731563 -0.677056 0.080075 -v -0.014273 0.014026 0.023098 -vn 0.743263 -0.654096 0.140420 -v -0.014400 0.013937 0.023388 -vn 0.765075 -0.625101 0.154623 -v -0.014858 0.013447 0.023594 -vn 0.369712 -0.044783 0.928067 -v -0.016496 0.014635 0.026096 -vn 0.585319 -0.274019 0.763096 -v -0.015830 0.014065 0.025615 -vn 0.556403 -0.238813 0.795855 -v -0.015926 0.014132 0.025706 -vn 0.529603 -0.207184 0.822554 -v -0.015992 0.014182 0.025765 -vn 0.493153 -0.166950 0.853773 -v -0.016154 0.014313 0.025893 -vn 0.459935 -0.133602 0.877844 -v -0.016247 0.014395 0.025957 -vn 0.425613 -0.101447 0.899201 -v -0.016315 0.014458 0.026001 -vn 0.391145 -0.072029 0.917506 -v -0.016476 0.014616 0.026087 -vn 0.615093 -0.310007 0.724952 -v -0.015661 0.013963 0.025437 -vn 0.637269 -0.339364 0.691896 -v -0.015606 0.013933 0.025375 -vn 0.660337 -0.373142 0.651705 -v -0.015501 0.013884 0.025249 -vn 0.681860 -0.404314 0.609588 -v -0.015343 0.013824 0.025043 -vn 0.697960 -0.430288 0.572454 -v -0.015291 0.013809 0.024971 -vn 0.728424 -0.489117 0.479753 -v -0.015028 0.013767 0.024573 -vn 0.714300 -0.461681 0.525953 -v -0.015185 0.013785 0.024817 -vn 0.739403 -0.507590 0.442308 -v -0.014982 0.013766 0.024499 -vn 0.741019 -0.536912 0.403257 -v -0.014908 0.013769 0.024375 -vn 0.764745 -0.571564 0.297454 -v -0.014864 0.013614 0.024047 -vn 0.747978 -0.586564 0.310598 -v -0.014697 0.013805 0.023994 -vn 0.744076 -0.575974 0.338533 -v -0.014723 0.013799 0.024042 -vn 0.723786 -0.578008 0.376883 -v -0.014874 0.013772 0.024315 -vn 0.744494 -0.642962 0.179804 -v -0.014408 0.013932 0.023405 -vn 0.745550 -0.625778 0.229255 -v -0.014549 0.013858 0.023704 -vn 0.749059 -0.596874 0.287492 -v -0.014683 0.013809 0.023968 -vn 0.717763 -0.695789 0.026331 -v -0.014146 0.014139 0.022783 -vn 0.737756 0.513249 0.438511 -v -0.014982 -0.013766 0.024499 -vn 0.743310 0.645712 0.174776 -v -0.014408 -0.013932 0.023405 -vn 0.738338 0.661381 0.132036 -v -0.014400 -0.013937 0.023388 -vn 0.766307 0.623658 0.154351 -v -0.014858 -0.013447 0.023594 -vn 0.716711 0.697002 0.022646 -v -0.014146 -0.014139 0.022783 -vn 0.729953 0.678623 0.081477 -v -0.014273 -0.014026 0.023098 -vn 0.742660 0.580294 0.334237 -v -0.014723 -0.013799 0.024042 -vn 0.747580 0.587592 0.309611 -v -0.014697 -0.013805 0.023994 -vn 0.766874 0.571068 0.292893 -v -0.014864 -0.013614 0.024047 -vn 0.745195 0.606636 0.276907 -v -0.014683 -0.013809 0.023968 -vn 0.742107 0.628821 0.232080 -v -0.014549 -0.013858 0.023704 -vn 0.744760 0.532670 0.401989 -v -0.014908 -0.013769 0.024375 -vn 0.724279 0.571398 0.385907 -v -0.014874 -0.013772 0.024315 -vn 0.697920 0.430483 0.572356 -v -0.015291 -0.013809 0.024971 -vn 0.712761 0.462727 0.527120 -v -0.015185 -0.013785 0.024817 -vn 0.727839 0.492912 0.476748 -v -0.015028 -0.013767 0.024573 -vn 0.556477 0.238289 0.795960 -v -0.015926 -0.014132 0.025706 -vn 0.584534 0.275295 0.763238 -v -0.015830 -0.014065 0.025615 -vn 0.614172 0.312347 0.724729 -v -0.015661 -0.013963 0.025437 -vn 0.636890 0.342424 0.690737 -v -0.015606 -0.013933 0.025375 -vn 0.657574 0.374707 0.653599 -v -0.015501 -0.013884 0.025249 -vn 0.681562 0.407230 0.607978 -v -0.015343 -0.013824 0.025043 -vn 0.369742 0.044681 0.928060 -v -0.016496 -0.014635 0.026096 -vn 0.391831 0.066748 0.917613 -v -0.016476 -0.014616 0.026087 -vn 0.429026 0.100838 0.897646 -v -0.016315 -0.014458 0.026001 -vn 0.460138 0.134914 0.877537 -v -0.016247 -0.014395 0.025957 -vn 0.491422 0.170700 0.854029 -v -0.016154 -0.014313 0.025893 -vn 0.526691 0.209110 0.823935 -v -0.015992 -0.014182 0.025765 -vn 0.489968 -0.767551 0.413275 -v -0.012913 0.015689 0.024768 -vn 0.459884 -0.755566 0.466504 -v -0.012933 0.015699 0.024805 -vn 0.513301 -0.737767 0.438430 -v -0.013767 0.014982 0.024499 -vn 0.646051 -0.743337 0.173404 -v -0.013932 0.014408 0.023405 -vn 0.661565 -0.738374 0.130904 -v -0.013937 0.014400 0.023388 -vn 0.623650 -0.766313 0.154356 -v -0.013447 0.014858 0.023594 -vn 0.690139 -0.723157 0.027432 -v -0.014139 0.014146 0.022783 -vn 0.678660 -0.729920 0.081470 -v -0.014026 0.014273 0.023098 -vn 0.580368 -0.742584 0.334278 -v -0.013799 0.014723 0.024042 -vn 0.588045 -0.747709 0.308438 -v -0.013805 0.014697 0.023994 -vn 0.571112 -0.766834 0.292909 -v -0.013614 0.014864 0.024047 -vn 0.606898 -0.745326 0.275978 -v -0.013809 0.014683 0.023968 -vn 0.628817 -0.742092 0.232140 -v -0.013858 0.014549 0.023704 -vn 0.544929 -0.785785 0.292565 -v -0.012734 0.015620 0.024378 -vn 0.518676 -0.777990 0.354552 -v -0.012767 0.015630 0.024457 -vn 0.532681 -0.744852 0.401804 -v -0.013769 0.014908 0.024375 -vn 0.571343 -0.724376 0.385805 -v -0.013772 0.014874 0.024315 -vn 0.308411 -0.663670 0.681487 -v -0.013431 0.016027 0.025548 -vn 0.342419 -0.636868 0.690759 -v -0.013933 0.015606 0.025375 -vn 0.351195 -0.692666 0.629981 -v -0.013260 0.015899 0.025331 -vn 0.374671 -0.657527 0.653667 -v -0.013884 0.015501 0.025249 -vn 0.388240 -0.716760 0.579245 -v -0.013167 0.015836 0.025199 -vn 0.407347 -0.681661 0.607789 -v -0.013824 0.015343 0.025043 -vn 0.430503 -0.697922 0.572339 -v -0.013809 0.015291 0.024971 -vn 0.425044 -0.737297 0.525101 -v -0.013078 0.015779 0.025060 -vn 0.462684 -0.712698 0.527243 -v -0.013785 0.015185 0.024817 -vn 0.492935 -0.727831 0.476736 -v -0.013767 0.015028 0.024573 -vn 0.093140 -0.464950 0.880424 -v -0.014021 0.016554 0.026081 -vn 0.134936 -0.460171 0.877516 -v -0.014395 0.016247 0.025957 -vn 0.152860 -0.527121 0.835929 -v -0.013882 0.016419 0.025981 -vn 0.170687 -0.491439 0.854022 -v -0.014313 0.016154 0.025893 -vn 0.213395 -0.579380 0.786626 -v -0.013718 0.016269 0.025844 -vn 0.209071 -0.526689 0.823947 -v -0.014182 0.015992 0.025765 -vn 0.247025 -0.556110 0.793549 -v -0.014132 0.015925 0.025706 -vn 0.269852 -0.637146 0.721959 -v -0.013457 0.016047 0.025577 -vn 0.279954 -0.576924 0.767323 -v -0.014065 0.015830 0.025615 -vn 0.312419 -0.614228 0.724651 -v -0.013963 0.015661 0.025437 -vn 0.044881 -0.369873 0.927998 -v -0.014635 0.016496 0.026096 -vn 0.070750 -0.391271 0.917552 -v -0.014616 0.016477 0.026087 -vn 0.102209 -0.425290 0.899267 -v -0.014458 0.016315 0.026001 -vn 0.607372 -0.788398 0.097609 -v -0.012540 0.015607 0.023802 -vn 0.587552 -0.792481 0.163575 -v -0.012575 0.015601 0.023927 -vn 0.566474 -0.792052 0.227509 -v -0.012642 0.015602 0.024134 -vn 0.610103 0.756287 0.236230 -v -0.013858 -0.014549 0.023704 -vn 0.584073 0.756983 0.292975 -v -0.013809 -0.014683 0.023968 -vn 0.523339 0.795810 0.304635 -v -0.012680 -0.015663 0.024397 -vn -0.098762 0.429315 0.897739 -v 0.014458 -0.016315 0.026001 -vn -0.132925 0.462076 0.876822 -v 0.014395 -0.016247 0.025957 -vn -0.088665 0.483414 0.870890 -v 0.012329 -0.017786 0.026575 -vn -0.415651 0.675093 0.609495 -v 0.013824 -0.015343 0.025043 -vn -0.449196 0.694773 0.561706 -v 0.013809 -0.015291 0.024971 -vn -0.401721 0.719236 0.566851 -v 0.013687 -0.015398 0.025016 -vn -0.689142 0.724034 0.029306 -v 0.014139 -0.014146 0.022783 -vn -0.620874 0.748093 0.234249 -v 0.013858 -0.014549 0.023704 -vn -0.640337 0.747347 0.177318 -v 0.013932 -0.014408 0.023405 -vn -0.595728 0.788898 0.150823 -v 0.013074 -0.015187 0.023741 -vn -0.655997 0.742524 0.135374 -v 0.013937 -0.014400 0.023388 -vn -0.674038 0.733908 0.083974 -v 0.014026 -0.014273 0.023098 -vn -0.553135 0.736139 0.390053 -v 0.013772 -0.014874 0.024315 -vn -0.574008 0.746803 0.335857 -v 0.013799 -0.014723 0.024042 -vn -0.540941 0.784850 0.302312 -v 0.013237 -0.015198 0.024193 -vn -0.582409 0.750746 0.311737 -v 0.013805 -0.014697 0.023994 -vn -0.598985 0.748969 0.283306 -v 0.013809 -0.014683 0.023968 -vn -0.528697 0.732270 0.429255 -v 0.013766 -0.014982 0.024499 -vn -0.474830 0.760213 0.443411 -v 0.013444 -0.015269 0.024622 -vn -0.499291 0.724179 0.475682 -v 0.013767 -0.015028 0.024573 -vn -0.482125 0.697349 0.530339 -v 0.013785 -0.015185 0.024817 -vn -0.266686 0.586812 0.764546 -v 0.014065 -0.015830 0.025615 -vn -0.302281 0.619979 0.724053 -v 0.013963 -0.015661 0.025437 -vn -0.259487 0.673302 0.692337 -v 0.011815 -0.017217 0.026036 -vn -0.324949 0.642192 0.694261 -v 0.013933 -0.015606 0.025375 -vn -0.355249 0.659495 0.662468 -v 0.013901 -0.015540 0.025296 -vn -0.234790 0.559835 0.794644 -v 0.014132 -0.015925 0.025706 -vn -0.175558 0.585921 0.791123 -v 0.012065 -0.017480 0.026334 -vn -0.202367 0.531851 0.822303 -v 0.014182 -0.015992 0.025765 -vn -0.165365 0.492707 0.854339 -v 0.014313 -0.016154 0.025893 -vn -0.065669 0.394036 0.916746 -v 0.014616 -0.016477 0.026087 -vn -0.043041 0.370543 0.927818 -v 0.014635 -0.016496 0.026096 -vn 0.044722 0.369912 0.927990 -v -0.014635 -0.016496 0.026096 -vn 0.071204 0.391625 0.917366 -v -0.014616 -0.016477 0.026087 -vn 0.208167 0.526014 0.824607 -v -0.014182 -0.015992 0.025765 -vn 0.173397 0.492024 0.853139 -v -0.014313 -0.016154 0.025893 -vn 0.102549 0.477138 0.872825 -v -0.013961 -0.016601 0.026099 -vn 0.133429 0.460336 0.877660 -v -0.014395 -0.016247 0.025957 -vn 0.102042 0.424801 0.899517 -v -0.014458 -0.016315 0.026001 -vn 0.275443 0.584856 0.762939 -v -0.014065 -0.015830 0.025615 -vn 0.238503 0.556514 0.795869 -v -0.014132 -0.015925 0.025706 -vn 0.199902 0.574497 0.793721 -v -0.013660 -0.016315 0.025863 -vn 0.373333 0.659945 0.651994 -v -0.013884 -0.015501 0.025249 -vn 0.338943 0.637443 0.691942 -v -0.013933 -0.015606 0.025375 -vn 0.293213 0.657433 0.694124 -v -0.013375 -0.016073 0.025567 -vn 0.310065 0.614688 0.725272 -v -0.013963 -0.015661 0.025437 -vn 0.461448 0.714146 0.526366 -v -0.013785 -0.015185 0.024817 -vn 0.429737 0.698223 0.572547 -v -0.013809 -0.015291 0.024971 -vn 0.379118 0.723164 0.577325 -v -0.013112 -0.015880 0.025217 -vn 0.403899 0.682252 0.609424 -v -0.013824 -0.015343 0.025043 -vn 0.539590 0.746477 0.389377 -v -0.013772 -0.014874 0.024315 -vn 0.511015 0.738363 0.440095 -v -0.013767 -0.014982 0.024499 -vn 0.456333 0.769753 0.446363 -v -0.012879 -0.015743 0.024824 -vn 0.488482 0.728738 0.479923 -v -0.013767 -0.015028 0.024573 -vn 0.574170 0.755622 0.315221 -v -0.013805 -0.014697 0.023994 -vn 0.561851 0.752570 0.343455 -v -0.013799 -0.014723 0.024042 -vn 0.629765 0.754069 0.186484 -v -0.013932 -0.014408 0.023405 -vn 0.582593 0.798656 0.150778 -v -0.012523 -0.015644 0.023946 -vn 0.654554 0.745984 0.122746 -v -0.013937 -0.014400 0.023388 -vn 0.698713 0.715057 0.022228 -v -0.014139 -0.014146 0.022783 -vn 0.701829 0.708367 0.075183 -v -0.014026 -0.014273 0.023098 -vn -0.518660 0.841783 0.149643 -v 0.011059 -0.016709 0.024424 -vn -0.415576 0.897826 0.145622 -v 0.008872 -0.017964 0.024987 -vn -0.304387 0.941662 0.143601 -v 0.006547 -0.018935 0.025421 -vn -0.184541 0.972084 0.144908 -v 0.004120 -0.019605 0.025722 -vn -0.069427 0.987149 0.143936 -v 0.001628 -0.019967 0.025884 -vn 0.044629 0.988437 0.144914 -v -0.000890 -0.020013 0.025905 -vn 0.153331 0.977322 0.146051 -v -0.003395 -0.019744 0.025784 -vn 0.264518 0.953586 0.143892 -v -0.005848 -0.019162 0.025523 -vn 0.377354 0.914702 0.144651 -v -0.008212 -0.018275 0.025126 -vn 0.488745 0.859123 0.151777 -v -0.010449 -0.017096 0.024598 -vn 0.438298 0.846565 0.302030 -v -0.010584 -0.017141 0.025043 -vn 0.342569 0.890591 0.299155 -v -0.008320 -0.018341 0.025567 -vn 0.242921 0.923437 0.297076 -v -0.005926 -0.019244 0.025961 -vn 0.140546 0.944869 0.295751 -v -0.003440 -0.019837 0.026220 -vn 0.036661 0.954749 0.295146 -v -0.000902 -0.020112 0.026340 -vn -0.067594 0.953015 0.295284 -v 0.001650 -0.020064 0.026319 -vn -0.171039 0.939702 0.296153 -v 0.004175 -0.019696 0.026158 -vn -0.272525 0.914921 0.297742 -v 0.006634 -0.019013 0.025860 -vn -0.370885 0.878855 0.300097 -v 0.008988 -0.018025 0.025429 -vn -0.464961 0.831783 0.303231 -v 0.011201 -0.016747 0.024870 -vn 0.382470 0.810651 0.443354 -v -0.010751 -0.017248 0.025466 -vn 0.298385 0.847272 0.439428 -v -0.008452 -0.018470 0.025987 -vn 0.211311 0.874521 0.436532 -v -0.006021 -0.019390 0.026379 -vn 0.122161 0.892255 0.434692 -v -0.003495 -0.019994 0.026636 -vn 0.031855 0.900422 0.433849 -v -0.000916 -0.020273 0.026755 -vn -0.058714 0.898986 0.434024 -v 0.001677 -0.020225 0.026735 -vn -0.148668 0.887970 0.435208 -v 0.004242 -0.019850 0.026575 -vn -0.237122 0.867443 0.437397 -v 0.006740 -0.019154 0.026278 -vn -0.323183 0.837499 0.440623 -v 0.009131 -0.018148 0.025850 -vn -0.405941 0.798302 0.444888 -v 0.011377 -0.016846 0.025295 -vn 0.317324 0.754996 0.573835 -v -0.010946 -0.017414 0.025857 -vn 0.247209 0.784074 0.569311 -v -0.008606 -0.018658 0.026376 -vn 0.174882 0.805653 0.565985 -v -0.006130 -0.019595 0.026767 -vn 0.101035 0.819681 0.563839 -v -0.003559 -0.020210 0.027023 -vn 0.026339 0.826121 0.562877 -v -0.000932 -0.020495 0.027142 -vn -0.048538 0.824984 0.563067 -v 0.001707 -0.020446 0.027122 -vn -0.122963 0.816282 0.564415 -v 0.004319 -0.020064 0.026962 -vn -0.196278 0.800033 0.566941 -v 0.006862 -0.019355 0.026667 -vn -0.267828 0.776301 0.570635 -v 0.009296 -0.018330 0.026239 -vn -0.337455 0.745009 0.575401 -v 0.011584 -0.017004 0.025686 -vn 0.244472 0.680981 0.690288 -v -0.011164 -0.017634 0.026207 -vn 0.190244 0.702501 0.685784 -v -0.008776 -0.018901 0.026726 -vn 0.134473 0.718442 0.682465 -v -0.006251 -0.019855 0.027116 -vn 0.077647 0.728783 0.680328 -v -0.003629 -0.020481 0.027373 -vn 0.020242 0.733524 0.679362 -v -0.000951 -0.020771 0.027492 -vn -0.037291 0.732684 0.679546 -v 0.001740 -0.020721 0.027471 -vn -0.094502 0.726267 0.680886 -v 0.004404 -0.020333 0.027312 -vn -0.150945 0.714272 0.683397 -v 0.006997 -0.019611 0.027016 -vn -0.206152 0.696723 0.687080 -v 0.009481 -0.018567 0.026589 -vn -0.425014 0.625562 0.654245 -v 0.013884 -0.015501 0.025249 -vn 0.165704 0.590443 0.789886 -v -0.011400 -0.017905 0.026506 -vn 0.128845 0.604503 0.786114 -v -0.008960 -0.019194 0.027027 -vn 0.091016 0.614894 0.783340 -v -0.006381 -0.020164 0.027420 -vn 0.052533 0.621623 0.781553 -v -0.003704 -0.020801 0.027677 -vn 0.013695 0.624707 0.780739 -v -0.000971 -0.021097 0.027797 -vn -0.025218 0.624153 0.780895 -v 0.001777 -0.021046 0.027776 -vn -0.063931 0.619966 0.782020 -v 0.004495 -0.020650 0.027616 -vn -0.102164 0.612152 0.784113 -v 0.007143 -0.019916 0.027319 -vn -0.139622 0.600695 0.787192 -v 0.009680 -0.018854 0.026890 -vn 0.082940 0.485595 0.870240 -v -0.011648 -0.018218 0.026748 -vn 0.064448 0.492389 0.867986 -v -0.009153 -0.019529 0.027274 -vn 0.045501 0.497394 0.866331 -v -0.006518 -0.020516 0.027670 -vn 0.026253 0.500629 0.865264 -v -0.003783 -0.021163 0.027929 -vn 0.006842 0.502106 0.864779 -v -0.000991 -0.021463 0.028050 -vn -0.012600 0.501825 0.864877 -v 0.001814 -0.021412 0.028029 -vn -0.031944 0.499803 0.865550 -v 0.004591 -0.021010 0.027868 -vn -0.051062 0.496028 0.866804 -v 0.007296 -0.020263 0.027568 -vn -0.069818 0.490494 0.868644 -v 0.009889 -0.019184 0.027135 -vn 0.599868 -0.799133 0.039300 -v -0.011329 0.016527 0.023957 -vn -0.590184 -0.790615 0.163126 -v 0.012575 0.015601 0.023927 -vn -0.567752 -0.790869 0.228437 -v 0.012642 0.015602 0.024134 -vn -0.562847 -0.807503 0.176474 -v 0.011790 0.016235 0.024261 -vn -0.543971 -0.786104 0.293489 -v 0.012734 0.015620 0.024378 -vn -0.519260 -0.778974 0.351525 -v 0.012767 0.015630 0.024457 -vn -0.523056 -0.801239 0.290566 -v 0.011910 0.016253 0.024603 -vn -0.460801 -0.754815 0.466815 -v 0.012933 0.015699 0.024805 -vn -0.425997 -0.736560 0.525362 -v 0.013078 0.015779 0.025060 -vn -0.421356 -0.753615 0.504503 -v 0.012216 0.016395 0.025243 -vn -0.389248 -0.715984 0.579529 -v 0.013167 0.015836 0.025199 -vn -0.352504 -0.692962 0.628923 -v 0.013260 0.015899 0.025331 -vn -0.360948 -0.713075 0.601033 -v 0.012398 0.016515 0.025533 -vn -0.313632 -0.661698 0.681022 -v 0.013431 0.016027 0.025548 -vn -0.278657 -0.634801 0.720679 -v 0.013457 0.016047 0.025577 -vn -0.295140 -0.662132 0.688821 -v 0.012596 0.016667 0.025796 -vn -0.197123 -0.565392 0.800921 -v 0.013718 0.016269 0.025844 -vn -0.153289 -0.522956 0.838463 -v 0.013882 0.016419 0.025981 -vn -0.151999 -0.531346 0.833407 -v 0.013028 0.017056 0.026228 -vn -0.110058 -0.481860 0.869309 -v 0.014021 0.016554 0.026081 -vn -0.062387 -0.438397 0.896614 -v 0.014105 0.016638 0.026134 -vn -0.076468 -0.454464 0.887477 -v 0.013256 0.017286 0.026391 -vn -0.225735 -0.601352 0.766433 -v 0.012807 0.016848 0.026029 -vn -0.234990 -0.599267 0.765283 -v 0.013665 0.016221 0.025795 -vn -0.475709 -0.783234 0.400307 -v 0.012052 0.016307 0.024932 -vn -0.488792 -0.766919 0.415833 -v 0.012913 0.015689 0.024768 -vn -0.610931 -0.785858 0.095870 -v 0.012540 0.015607 0.023802 -vn -0.580769 -0.813299 -0.035390 -v 0.010159 0.017385 0.024097 -vn -0.595292 -0.801712 0.053713 -v 0.011695 0.016252 0.023911 -vn -0.519370 -0.833303 -0.189371 -v 0.007497 0.019142 0.024368 -vn -0.554623 -0.824128 -0.114915 -v 0.008775 0.018338 0.024247 -vn -0.364067 -0.868722 -0.335824 -v 0.004491 0.020648 0.024572 -vn -0.419681 -0.859867 -0.290683 -v 0.005464 0.020227 0.024519 -vn -0.467828 -0.849407 -0.244223 -v 0.006480 0.019718 0.024450 -vn -0.145658 -0.895347 -0.420877 -v 0.001627 0.021443 0.024664 -vn -0.198039 -0.893298 -0.403484 -v 0.002452 0.021287 0.024647 -vn -0.241999 -0.886220 -0.395033 -v 0.002630 0.021245 0.024643 -vn -0.292687 -0.880734 -0.372346 -v 0.003549 0.020986 0.024613 -vn -0.001811 -0.900450 -0.434956 -v 0.000006 0.021568 0.024677 -vn -0.070658 -0.898966 -0.432281 -v 0.000814 0.021536 0.024674 -vn 0.070943 -0.900061 -0.429950 -v -0.000805 0.021537 0.024674 -vn 0.141194 -0.896641 -0.419641 -v -0.001627 0.021443 0.024664 -vn 0.208180 -0.891291 -0.402818 -v -0.002384 0.021302 0.024649 -vn 0.334206 -0.875317 -0.349465 -v -0.004072 0.020807 0.024592 -vn 0.271308 -0.883946 -0.380830 -v -0.003222 0.021086 0.024625 -vn 0.386509 -0.867256 -0.313811 -v -0.004937 0.020464 0.024549 -vn 0.442387 -0.854267 -0.272986 -v -0.005820 0.020056 0.024496 -vn 0.563895 -0.820076 -0.097455 -v -0.009042 0.018160 0.024220 -vn 0.529449 -0.832581 -0.162765 -v -0.007953 0.018864 0.024327 -vn 0.489058 -0.845195 -0.215564 -v -0.006893 0.019491 0.024418 -vn -0.077906 -0.462820 0.883022 -v 0.011676 0.018427 0.026844 -vn -0.076835 -0.471317 0.878611 -v 0.010209 0.019392 0.027226 -vn -0.073949 -0.479569 0.874383 -v 0.008818 0.020209 0.027551 -vn -0.069260 -0.486663 0.870840 -v 0.007685 0.020798 0.027784 -vn -0.063205 -0.493399 0.867504 -v 0.006532 0.021322 0.027991 -vn -0.055543 -0.499661 0.864438 -v 0.005406 0.021757 0.028164 -vn -0.046423 -0.505194 0.861756 -v 0.004298 0.022108 0.028303 -vn -0.038500 -0.509896 0.859374 -v 0.003200 0.022379 0.028410 -vn -0.031760 -0.511798 0.858519 -v 0.002986 0.022422 0.028427 -vn -0.023109 -0.513729 0.857641 -v 0.001987 0.022587 0.028492 -vn -0.011783 -0.515618 0.856738 -v 0.000996 0.022685 0.028531 -vn -0.000128 -0.516286 0.856416 -v 0.000008 0.022718 0.028544 -vn 0.011584 -0.515694 0.856695 -v -0.000985 0.022685 0.028531 -vn 0.022801 -0.513966 0.857508 -v -0.001988 0.022586 0.028492 -vn 0.033178 -0.511225 0.858806 -v -0.002904 0.022438 0.028433 -vn 0.042907 -0.507330 0.860683 -v -0.003909 0.022213 0.028344 -vn 0.051778 -0.502635 0.862947 -v -0.004915 0.021922 0.028229 -vn 0.059414 -0.497309 0.865537 -v -0.005925 0.021566 0.028088 -vn 0.066011 -0.491295 0.868488 -v -0.006939 0.021146 0.027922 -vn 0.071395 -0.484231 0.872022 -v -0.008149 0.020566 0.027692 -vn 0.075347 -0.477160 0.875580 -v -0.009319 0.019927 0.027438 -vn 0.077599 -0.470136 0.879176 -v -0.010495 0.019212 0.027155 -vn 0.078323 -0.463273 0.882748 -v -0.011682 0.018423 0.026842 -vn 0.077725 -0.455787 0.886689 -v -0.012884 0.017563 0.026501 -vn -0.154944 -0.547564 0.822293 -v 0.011444 0.018173 0.026661 -vn -0.152746 -0.563667 0.811756 -v 0.009981 0.019115 0.027025 -vn -0.146899 -0.579259 0.801798 -v 0.008600 0.019910 0.027332 -vn -0.137492 -0.592708 0.793595 -v 0.007480 0.020481 0.027552 -vn -0.125438 -0.605563 0.785849 -v 0.006346 0.020986 0.027746 -vn -0.110199 -0.617523 0.778795 -v 0.005242 0.021404 0.027906 -vn -0.092084 -0.628108 0.772659 -v 0.004161 0.021740 0.028035 -vn -0.076226 -0.636372 0.767607 -v 0.003094 0.021998 0.028133 -vn -0.062833 -0.640000 0.765801 -v 0.002886 0.022040 0.028149 -vn -0.045799 -0.644296 0.763404 -v 0.001919 0.022196 0.028209 -vn -0.023352 -0.647885 0.761380 -v 0.000962 0.022289 0.028244 -vn -0.000254 -0.649134 0.760674 -v 0.000007 0.022320 0.028256 -vn 0.022945 -0.647973 0.761317 -v -0.000951 0.022289 0.028244 -vn 0.045147 -0.644556 0.763223 -v -0.001920 0.022195 0.028209 -vn 0.065700 -0.639256 0.766182 -v -0.002807 0.022055 0.028155 -vn 0.084983 -0.631821 0.770442 -v -0.003782 0.021840 0.028073 -vn 0.102551 -0.622802 0.775629 -v -0.004763 0.021562 0.027967 -vn 0.117687 -0.612589 0.781591 -v -0.005750 0.021221 0.027836 -vn 0.130816 -0.601177 0.788336 -v -0.006745 0.020817 0.027681 -vn 0.141543 -0.587765 0.796554 -v -0.007938 0.020256 0.027465 -vn 0.149389 -0.574260 0.804928 -v -0.009096 0.019636 0.027226 -vn 0.153892 -0.560939 0.813428 -v -0.010266 0.018940 0.026958 -vn 0.155356 -0.547919 0.821979 -v -0.011450 0.018169 0.026660 -vn 0.154954 -0.535239 0.830366 -v -0.012655 0.017327 0.026333 -vn -0.229375 -0.623113 0.747741 -v 0.011221 0.017947 0.026438 -vn -0.225815 -0.645465 0.729646 -v 0.009762 0.018870 0.026779 -vn -0.216831 -0.667065 0.712747 -v 0.008391 0.019647 0.027065 -vn -0.202739 -0.685813 0.698968 -v 0.007285 0.020202 0.027268 -vn -0.184791 -0.703747 0.685998 -v 0.006168 0.020692 0.027446 -vn -0.162206 -0.720449 0.674272 -v 0.005086 0.021096 0.027592 -vn -0.135449 -0.735258 0.664115 -v 0.004031 0.021419 0.027709 -vn -0.111995 -0.746411 0.655994 -v 0.002994 0.021667 0.027797 -vn -0.092266 -0.751585 0.653152 -v 0.002792 0.021707 0.027812 -vn -0.067294 -0.757851 0.648948 -v 0.001855 0.021856 0.027865 -vn -0.034302 -0.762868 0.645644 -v 0.000929 0.021944 0.027896 -vn -0.000380 -0.764608 0.644496 -v 0.000007 0.021974 0.027907 -vn 0.033691 -0.762968 0.645557 -v -0.000919 0.021945 0.027897 -vn 0.066301 -0.758136 0.648717 -v -0.001855 0.021856 0.027865 -vn 0.096522 -0.750669 0.653590 -v -0.002715 0.021721 0.027817 -vn 0.124911 -0.740281 0.660591 -v -0.003663 0.021515 0.027743 -vn 0.150809 -0.727643 0.669173 -v -0.004618 0.021248 0.027647 -vn 0.173181 -0.713340 0.679084 -v -0.005583 0.020919 0.027528 -vn 0.192663 -0.697436 0.690264 -v -0.006560 0.020528 0.027386 -vn 0.208688 -0.678761 0.704083 -v -0.007736 0.019984 0.027188 -vn 0.220476 -0.659955 0.718227 -v -0.008883 0.019379 0.026966 -vn 0.227369 -0.641433 0.732712 -v -0.010045 0.018699 0.026716 -vn 0.229796 -0.623377 0.747392 -v -0.011227 0.017943 0.026436 -vn 0.227411 -0.607293 0.761236 -v -0.012433 0.017116 0.026128 -vn -0.299960 -0.688206 0.660603 -v 0.011009 0.017753 0.026176 -vn -0.294645 -0.715150 0.633834 -v 0.009556 0.018662 0.026491 -vn -0.282326 -0.741191 0.609039 -v 0.008196 0.019425 0.026753 -vn -0.263567 -0.763921 0.589031 -v 0.007102 0.019969 0.026938 -vn -0.239887 -0.785670 0.570243 -v 0.006003 0.020447 0.027099 -vn -0.210302 -0.805944 0.553378 -v 0.004942 0.020840 0.027229 -vn -0.175427 -0.823941 0.538839 -v 0.003911 0.021154 0.027333 -vn -0.144884 -0.837160 0.527420 -v 0.002901 0.021394 0.027411 -vn -0.119300 -0.843636 0.523494 -v 0.002705 0.021432 0.027423 -vn -0.087018 -0.851374 0.517291 -v 0.001796 0.021576 0.027470 -vn -0.044351 -0.857477 0.512607 -v 0.000899 0.021662 0.027497 -vn -0.000505 -0.859590 0.510984 -v 0.000007 0.021690 0.027507 -vn 0.043530 -0.857588 0.512492 -v -0.000889 0.021662 0.027498 -vn 0.085709 -0.851672 0.517019 -v -0.001796 0.021576 0.027470 -vn 0.124836 -0.842552 0.523949 -v -0.002630 0.021446 0.027428 -vn 0.161667 -0.829949 0.533899 -v -0.003552 0.021247 0.027363 -vn 0.195365 -0.814558 0.546194 -v -0.004484 0.020988 0.027278 -vn 0.224574 -0.797182 0.560417 -v -0.005429 0.020669 0.027172 -vn 0.250141 -0.777859 0.576511 -v -0.006389 0.020287 0.027045 -vn 0.271396 -0.755292 0.596555 -v -0.007548 0.019755 0.026865 -vn 0.287184 -0.732519 0.617205 -v -0.008683 0.019162 0.026663 -vn 0.296663 -0.710111 0.638541 -v -0.009837 0.018493 0.026433 -vn 0.300375 -0.688366 0.660248 -v -0.011015 0.017749 0.026175 -vn 0.297549 -0.667166 0.682901 -v -0.012221 0.016932 0.025889 -vn -0.365508 -0.741743 0.562335 -v 0.010812 0.017593 0.025881 -vn -0.424897 -0.782810 0.454610 -v 0.010634 0.017470 0.025558 -vn -0.357943 -0.771418 0.526110 -v 0.009366 0.018494 0.026168 -vn -0.414537 -0.813215 0.408460 -v 0.009196 0.018369 0.025816 -vn -0.342030 -0.800102 0.492801 -v 0.008017 0.019248 0.026404 -vn -0.394708 -0.842583 0.366413 -v 0.007860 0.019121 0.026025 -vn -0.318635 -0.825314 0.466186 -v 0.006937 0.019785 0.026569 -vn -0.366733 -0.868641 0.333122 -v 0.006793 0.019656 0.026170 -vn -0.289438 -0.849409 0.441283 -v 0.005854 0.020257 0.026712 -vn -0.332311 -0.893495 0.302052 -v 0.005726 0.020125 0.026295 -vn -0.253321 -0.871915 0.419039 -v 0.004813 0.020643 0.026827 -vn -0.290205 -0.916744 0.274522 -v 0.004703 0.020509 0.026393 -vn -0.211002 -0.891907 0.399974 -v 0.003805 0.020951 0.026916 -vn -0.241285 -0.937428 0.251017 -v 0.003714 0.020815 0.026470 -vn -0.174067 -0.906276 0.385182 -v 0.002819 0.021186 0.026984 -vn -0.198749 -0.951952 0.232993 -v 0.002750 0.021048 0.026527 -vn -0.143238 -0.913751 0.380186 -v 0.002628 0.021223 0.026994 -vn -0.163419 -0.960092 0.226976 -v 0.002564 0.021085 0.026535 -vn -0.104451 -0.922379 0.371897 -v 0.001744 0.021364 0.027034 -vn -0.119129 -0.968960 0.216622 -v 0.001700 0.021225 0.026569 -vn -0.053219 -0.929163 0.365819 -v 0.000873 0.021447 0.027057 -vn -0.060674 -0.975989 0.209201 -v 0.000850 0.021308 0.026588 -vn -0.000620 -0.931511 0.363713 -v 0.000007 0.021475 0.027065 -vn -0.000727 -0.978417 0.206641 -v 0.000006 0.021335 0.026594 -vn 0.052209 -0.929275 0.365680 -v -0.000863 0.021448 0.027057 -vn 0.059476 -0.976095 0.209047 -v -0.000841 0.021308 0.026588 -vn 0.102847 -0.922678 0.371602 -v -0.001744 0.021364 0.027034 -vn 0.117253 -0.969263 0.216291 -v -0.001700 0.021225 0.026569 -vn 0.149889 -0.912507 0.380610 -v -0.002556 0.021237 0.026998 -vn 0.171034 -0.958682 0.227322 -v -0.002492 0.021099 0.026539 -vn 0.194318 -0.898508 0.393603 -v -0.003454 0.021042 0.026943 -vn 0.222021 -0.944207 0.243270 -v -0.003371 0.020906 0.026492 -vn 0.235110 -0.881397 0.409711 -v -0.004365 0.020788 0.026869 -vn 0.269056 -0.926491 0.263104 -v -0.004263 0.020654 0.026430 -vn 0.270647 -0.862089 0.428431 -v -0.005291 0.020474 0.026777 -vn 0.310286 -0.906529 0.286231 -v -0.005171 0.020342 0.026351 -vn 0.301943 -0.840636 0.449624 -v -0.006234 0.020099 0.026665 -vn 0.346881 -0.884315 0.312506 -v -0.006100 0.019968 0.026253 -vn 0.328318 -0.815703 0.476274 -v -0.007377 0.019574 0.026505 -vn 0.378237 -0.858692 0.345811 -v -0.007227 0.019446 0.026114 -vn 0.348177 -0.790474 0.503908 -v -0.008500 0.018989 0.026324 -vn 0.402242 -0.832697 0.380549 -v -0.008337 0.018862 0.025954 -vn 0.360515 -0.765748 0.532597 -v -0.009646 0.018326 0.026115 -vn 0.417745 -0.807304 0.416833 -v -0.009474 0.018202 0.025768 -vn 0.365907 -0.741783 0.562023 -v -0.010818 0.017589 0.025880 -vn 0.425316 -0.782756 0.454312 -v -0.010640 0.017466 0.025557 -vn 0.365951 -0.717100 0.593167 -v -0.012022 0.016778 0.025618 -vn 0.428004 -0.756791 0.494044 -v -0.011840 0.016657 0.025321 -vn -0.521357 -0.824992 0.218117 -v 0.010344 0.017345 0.024850 -vn -0.556774 -0.825401 0.093360 -v 0.010238 0.017344 0.024476 -vn -0.503413 -0.850477 0.152525 -v 0.008929 0.018258 0.025049 -vn -0.534040 -0.845246 0.019006 -v 0.008837 0.018274 0.024649 -vn -0.474799 -0.875088 0.093740 -v 0.007621 0.019024 0.025208 -vn -0.500561 -0.864428 -0.046937 -v 0.007544 0.019056 0.024787 -vn -0.437983 -0.897694 0.048119 -v 0.006579 0.019570 0.025316 -vn -0.459565 -0.882768 -0.097575 -v 0.006514 0.019615 0.024880 -vn -0.394150 -0.919027 0.005982 -v 0.005541 0.020049 0.025407 -vn -0.411692 -0.899869 -0.144033 -v 0.005488 0.020107 0.024958 -vn -0.342144 -0.939140 -0.030883 -v 0.004547 0.020443 0.025478 -vn -0.355932 -0.916144 -0.184369 -v 0.004506 0.020512 0.025019 -vn -0.283041 -0.957100 -0.062024 -v 0.003589 0.020757 0.025532 -vn -0.293441 -0.930744 -0.218194 -v 0.003558 0.020836 0.025064 -vn -0.232274 -0.968896 -0.085382 -v 0.002657 0.020997 0.025571 -vn -0.240227 -0.939720 -0.243345 -v 0.002635 0.021084 0.025097 -vn -0.190621 -0.977244 -0.093048 -v 0.002476 0.021035 0.025577 -vn -0.196897 -0.947607 -0.251542 -v 0.002456 0.021124 0.025102 -vn -0.138739 -0.984538 -0.106944 -v 0.001641 0.021179 0.025599 -vn -0.143147 -0.953105 -0.266645 -v 0.001628 0.021273 0.025121 -vn -0.070580 -0.990672 -0.116564 -v 0.000821 0.021264 0.025612 -vn -0.072772 -0.958118 -0.276975 -v 0.000815 0.021362 0.025132 -vn -0.000917 -0.992789 -0.119871 -v 0.000006 0.021293 0.025616 -vn -0.000987 -0.959849 -0.280516 -v 0.000006 0.021392 0.025135 -vn 0.069058 -0.990757 -0.116756 -v -0.000812 0.021265 0.025612 -vn 0.071106 -0.958184 -0.277177 -v -0.000806 0.021363 0.025132 -vn 0.136438 -0.984822 -0.107287 -v -0.001642 0.021179 0.025599 -vn 0.140687 -0.953369 -0.267012 -v -0.001629 0.021273 0.025121 -vn 0.199484 -0.975484 -0.092940 -v -0.002407 0.021049 0.025579 -vn 0.206040 -0.945650 -0.251584 -v -0.002388 0.021139 0.025104 -vn 0.259885 -0.962947 -0.072059 -v -0.003257 0.020850 0.025547 -vn 0.269074 -0.935486 -0.229053 -v -0.003229 0.020932 0.025077 -vn 0.316322 -0.947541 -0.045889 -v -0.004121 0.020591 0.025504 -vn 0.328472 -0.922956 -0.200647 -v -0.004084 0.020665 0.025041 -vn 0.366680 -0.930225 -0.015083 -v -0.005002 0.020271 0.025448 -vn 0.382064 -0.908912 -0.167050 -v -0.004956 0.020335 0.024993 -vn 0.412236 -0.910854 0.020177 -v -0.005904 0.019889 0.025377 -vn 0.431151 -0.893100 -0.128380 -v -0.005848 0.019942 0.024932 -vn 0.452942 -0.889125 0.065582 -v -0.007002 0.019355 0.025274 -vn 0.476124 -0.875899 -0.078143 -v -0.006933 0.019395 0.024844 -vn 0.485417 -0.866869 0.113617 -v -0.008088 0.018760 0.025154 -vn 0.512852 -0.858125 -0.024600 -v -0.008005 0.018787 0.024740 -vn 0.508235 -0.845360 0.164511 -v -0.009202 0.018088 0.025012 -vn 0.539818 -0.841146 0.032706 -v -0.009107 0.018101 0.024617 -vn 0.521806 -0.824751 0.217956 -v -0.010350 0.017341 0.024849 -vn 0.557261 -0.825091 0.093197 -v -0.010244 0.017340 0.024475 -vn 0.526981 -0.804260 0.274694 -v -0.011537 0.016519 0.024664 -vn 0.567997 -0.807559 0.158834 -v -0.011421 0.016505 0.024314 -vn 0.580396 -0.813742 -0.031064 -v -0.010165 0.017380 0.024097 -vn -0.477149 -0.810721 0.339206 -v 0.010477 0.017387 0.025213 -vn -0.463338 -0.839735 0.283130 -v 0.009050 0.018290 0.025440 -vn -0.439271 -0.867755 0.232468 -v 0.007727 0.019046 0.025624 -vn -0.406812 -0.892947 0.192743 -v 0.006672 0.019583 0.025750 -vn -0.367491 -0.916878 0.155839 -v 0.005621 0.020055 0.025856 -vn -0.320045 -0.939339 0.123343 -v 0.004613 0.020442 0.025940 -vn -0.265502 -0.959348 0.095709 -v 0.003642 0.020750 0.026005 -vn -0.218331 -0.973006 0.074776 -v 0.002696 0.020984 0.026052 -vn -0.179368 -0.981440 0.067850 -v 0.002512 0.021022 0.026059 -vn -0.130659 -0.989868 0.055584 -v 0.001665 0.021163 0.026086 -vn -0.066512 -0.996680 0.046961 -v 0.000833 0.021246 0.026102 -vn -0.000829 -0.999032 0.043988 -v 0.000006 0.021274 0.026107 -vn 0.065141 -0.996779 0.046778 -v -0.000824 0.021247 0.026102 -vn 0.128557 -0.990162 0.055245 -v -0.001666 0.021163 0.026086 -vn 0.187717 -0.979860 0.068096 -v -0.002443 0.021036 0.026062 -vn 0.244070 -0.965872 0.086726 -v -0.003305 0.020841 0.026023 -vn 0.296352 -0.948727 0.109963 -v -0.004181 0.020587 0.025971 -vn 0.342556 -0.929426 0.137198 -v -0.005075 0.020273 0.025904 -vn 0.383931 -0.907896 0.168292 -v -0.005989 0.019898 0.025821 -vn 0.420078 -0.883347 0.207924 -v -0.007101 0.019372 0.025701 -vn 0.448301 -0.858334 0.249578 -v -0.008199 0.018786 0.025561 -vn 0.467292 -0.834015 0.293356 -v -0.009325 0.018122 0.025398 -vn 0.477571 -0.810565 0.338983 -v -0.010483 0.017383 0.025212 -vn 0.481429 -0.787391 0.385021 -v -0.011678 0.016570 0.025001 -vn -0.429295 -0.098742 0.897750 -v 0.016315 0.014458 0.026001 -vn -0.462084 -0.132929 0.876817 -v 0.016247 0.014395 0.025957 -vn -0.483420 -0.088671 0.870886 -v 0.017786 0.012329 0.026575 -vn -0.675222 -0.415631 0.609365 -v 0.015343 0.013824 0.025043 -vn -0.694854 -0.449176 0.561621 -v 0.015291 0.013809 0.024971 -vn -0.719320 -0.401649 0.566796 -v 0.015398 0.013687 0.025016 -vn -0.756268 0.610151 0.236164 -v 0.014549 -0.013858 0.023704 -vn -0.756852 0.583820 0.293820 -v 0.014683 -0.013809 0.023968 -vn -0.795808 0.523336 0.304646 -v 0.015663 -0.012680 0.024397 -vn -0.369962 0.044782 0.927967 -v 0.016496 -0.014635 0.026096 -vn -0.391627 0.071213 0.917364 -v 0.016477 -0.014616 0.026087 -vn -0.526004 0.208155 0.824616 -v 0.015992 -0.014182 0.025765 -vn -0.492056 0.173449 0.853110 -v 0.016154 -0.014313 0.025893 -vn -0.477132 0.102547 0.872828 -v 0.016601 -0.013961 0.026099 -vn -0.460333 0.133448 0.877659 -v 0.016247 -0.014395 0.025957 -vn -0.424748 0.102013 0.899546 -v 0.016315 -0.014458 0.026001 -vn -0.584868 0.275434 0.762932 -v 0.015830 -0.014065 0.025615 -vn -0.556486 0.238459 0.795903 -v 0.015925 -0.014132 0.025706 -vn -0.574505 0.199913 0.793712 -v 0.016315 -0.013660 0.025863 -vn -0.659904 0.373271 0.652070 -v 0.015501 -0.013884 0.025249 -vn -0.637405 0.338896 0.692000 -v 0.015606 -0.013933 0.025375 -vn -0.657424 0.293219 0.694130 -v 0.016073 -0.013375 0.025567 -vn -0.614733 0.310114 0.725213 -v 0.015661 -0.013963 0.025437 -vn -0.714155 0.461480 0.526326 -v 0.015185 -0.013785 0.024817 -vn -0.698282 0.429801 0.572428 -v 0.015291 -0.013809 0.024971 -vn -0.723159 0.379120 0.577330 -v 0.015880 -0.013112 0.025217 -vn -0.682328 0.403978 0.609287 -v 0.015343 -0.013824 0.025043 -vn -0.746446 0.539642 0.389366 -v 0.014874 -0.013772 0.024315 -vn -0.738304 0.510947 0.440273 -v 0.014982 -0.013766 0.024499 -vn -0.769752 0.456318 0.446381 -v 0.015743 -0.012879 0.024824 -vn -0.728678 0.488390 0.480108 -v 0.015028 -0.013767 0.024573 -vn -0.755498 0.573829 0.316138 -v 0.014697 -0.013805 0.023994 -vn -0.752589 0.561936 0.343276 -v 0.014723 -0.013799 0.024042 -vn -0.754039 0.629842 0.186343 -v 0.014408 -0.013932 0.023405 -vn -0.803089 0.576956 0.148895 -v 0.015644 -0.012522 0.023946 -vn -0.726963 0.685852 0.033646 -v 0.014146 -0.014139 0.022783 -vn -0.737076 0.670900 0.081318 -v 0.014273 -0.014026 0.023098 -vn -0.753416 0.640710 0.147837 -v 0.014400 -0.013937 0.023388 -vn -0.714569 -0.699208 0.022327 -v 0.014146 0.014139 0.022783 -vn -0.740932 -0.660581 0.121051 -v 0.014400 0.013937 0.023388 -vn -0.787508 -0.597197 0.152270 -v 0.015187 0.013074 0.023741 -vn -0.747319 -0.640576 0.176568 -v 0.014408 0.013932 0.023405 -vn -0.748060 -0.620941 0.234177 -v 0.014549 0.013858 0.023704 -vn -0.736107 -0.553158 0.390081 -v 0.014874 0.013772 0.024315 -vn -0.746790 -0.573974 0.335945 -v 0.014723 0.013799 0.024042 -vn -0.784842 -0.540953 0.302311 -v 0.015198 0.013237 0.024193 -vn -0.750746 -0.582384 0.311786 -v 0.014697 0.013805 0.023994 -vn -0.748986 -0.598997 0.283236 -v 0.014683 0.013809 0.023968 -vn -0.732221 -0.528675 0.429367 -v 0.014982 0.013766 0.024499 -vn -0.760229 -0.474832 0.443381 -v 0.015269 0.013444 0.024622 -vn -0.724160 -0.499276 0.475727 -v 0.015028 0.013767 0.024573 -vn -0.697293 -0.482149 0.530392 -v 0.015185 0.013785 0.024817 -vn -0.586803 -0.266668 0.764559 -v 0.015830 0.014065 0.025615 -vn -0.620050 -0.302357 0.723961 -v 0.015661 0.013963 0.025437 -vn -0.673307 -0.259489 0.692332 -v 0.017217 0.011815 0.026036 -vn -0.642181 -0.324975 0.694259 -v 0.015606 0.013933 0.025375 -vn -0.659304 -0.355235 0.662666 -v 0.015540 0.013901 0.025296 -vn -0.559822 -0.234774 0.794657 -v 0.015925 0.014132 0.025706 -vn -0.585915 -0.175554 0.791129 -v 0.017480 0.012065 0.026334 -vn -0.531875 -0.202379 0.822284 -v 0.015992 0.014182 0.025765 -vn -0.492744 -0.165382 0.854314 -v 0.016154 0.014313 0.025893 -vn -0.394019 -0.065625 0.916757 -v 0.016477 0.014616 0.026087 -vn -0.370558 -0.043071 0.927810 -v 0.016496 0.014635 0.026096 -vn -0.847664 -0.509922 0.146440 -v 0.016709 0.011059 0.024424 -vn -0.708411 -0.701787 0.075161 -v 0.014273 0.014026 0.023098 -vn -0.901909 -0.406582 0.145779 -v 0.017964 0.008872 0.024987 -vn -0.940938 -0.304073 0.148913 -v 0.018935 0.006547 0.025421 -vn -0.969997 -0.195893 0.143984 -v 0.019605 0.004120 0.025722 -vn -0.986651 -0.078686 0.142576 -v 0.019967 0.001628 0.025884 -vn -0.988185 0.045774 0.146268 -v 0.020013 -0.000890 0.025905 -vn -0.975981 0.161876 0.145797 -v 0.019744 -0.003395 0.025784 -vn -0.950209 0.275101 0.146364 -v 0.019162 -0.005848 0.025523 -vn -0.912888 0.379457 0.150491 -v 0.018275 -0.008212 0.025126 -vn -0.864365 0.480876 0.147079 -v 0.017096 -0.010449 0.024598 -vn -0.846561 0.438292 0.302050 -v 0.017141 -0.010584 0.025043 -vn -0.890592 0.342569 0.299153 -v 0.018341 -0.008320 0.025567 -vn -0.923442 0.242918 0.297061 -v 0.019244 -0.005926 0.025961 -vn -0.944878 0.140553 0.295721 -v 0.019837 -0.003440 0.026220 -vn -0.954757 0.036661 0.295119 -v 0.020112 -0.000902 0.026340 -vn -0.953019 -0.067593 0.295273 -v 0.020064 0.001650 0.026319 -vn -0.939705 -0.171037 0.296142 -v 0.019696 0.004175 0.026158 -vn -0.914917 -0.272520 0.297759 -v 0.019013 0.006634 0.025860 -vn -0.878843 -0.370883 0.300134 -v 0.018025 0.008988 0.025429 -vn -0.831786 -0.464963 0.303218 -v 0.016747 0.011201 0.024870 -vn -0.810652 0.382476 0.443345 -v 0.017248 -0.010751 0.025466 -vn -0.847266 0.298371 0.439449 -v 0.018470 -0.008452 0.025987 -vn -0.874522 0.211310 0.436531 -v 0.019390 -0.006021 0.026379 -vn -0.892253 0.122157 0.434698 -v 0.019994 -0.003495 0.026636 -vn -0.900416 0.031856 0.433862 -v 0.020273 -0.000916 0.026755 -vn -0.898981 -0.058713 0.434035 -v 0.020225 0.001677 0.026735 -vn -0.887970 -0.148663 0.435211 -v 0.019850 0.004242 0.026575 -vn -0.867445 -0.237119 0.437395 -v 0.019154 0.006740 0.026278 -vn -0.837500 -0.323187 0.440617 -v 0.018148 0.009131 0.025850 -vn -0.798296 -0.405944 0.444897 -v 0.016846 0.011377 0.025295 -vn -0.755005 0.317339 0.573815 -v 0.017413 -0.010946 0.025857 -vn -0.784082 0.247213 0.569299 -v 0.018658 -0.008606 0.026376 -vn -0.805651 0.174875 0.565991 -v 0.019595 -0.006130 0.026767 -vn -0.819672 0.101034 0.563852 -v 0.020210 -0.003559 0.027023 -vn -0.826103 0.026342 0.562903 -v 0.020495 -0.000933 0.027142 -vn -0.824966 -0.048538 0.563094 -v 0.020446 0.001707 0.027122 -vn -0.816283 -0.122961 0.564414 -v 0.020064 0.004319 0.026962 -vn -0.800049 -0.196285 0.566916 -v 0.019355 0.006862 0.026667 -vn -0.776314 -0.267843 0.570611 -v 0.018330 0.009296 0.026239 -vn -0.745003 -0.337454 0.575409 -v 0.017004 0.011584 0.025686 -vn -0.680979 0.244463 0.690294 -v 0.017634 -0.011164 0.026207 -vn -0.702519 0.190257 0.685762 -v 0.018901 -0.008776 0.026726 -vn -0.718451 0.134479 0.682455 -v 0.019855 -0.006251 0.027116 -vn -0.728773 0.077648 0.680339 -v 0.020481 -0.003629 0.027373 -vn -0.733528 0.020245 0.679358 -v 0.020771 -0.000951 0.027492 -vn -0.732687 -0.037291 0.679543 -v 0.020721 0.001740 0.027471 -vn -0.726253 -0.094503 0.680901 -v 0.020333 0.004404 0.027312 -vn -0.714284 -0.150948 0.683383 -v 0.019611 0.006997 0.027016 -vn -0.696721 -0.206152 0.687081 -v 0.018567 0.009481 0.026589 -vn -0.625164 -0.425297 0.654441 -v 0.015501 0.013884 0.025249 -vn -0.590445 0.165704 0.789884 -v 0.017905 -0.011400 0.026506 -vn -0.604488 0.128832 0.786128 -v 0.019194 -0.008960 0.027027 -vn -0.614878 0.091009 0.783353 -v 0.020164 -0.006381 0.027420 -vn -0.621621 0.052535 0.781554 -v 0.020801 -0.003704 0.027677 -vn -0.624705 0.013694 0.780741 -v 0.021097 -0.000971 0.027797 -vn -0.624160 -0.025221 0.780889 -v 0.021046 0.001777 0.027776 -vn -0.619970 -0.063935 0.782016 -v 0.020650 0.004495 0.027616 -vn -0.612147 -0.102164 0.784116 -v 0.019916 0.007143 0.027319 -vn -0.600692 -0.139619 0.787195 -v 0.018854 0.009680 0.026890 -vn -0.485612 0.082957 0.870229 -v 0.018218 -0.011648 0.026748 -vn -0.492378 0.064443 0.867992 -v 0.019529 -0.009153 0.027274 -vn -0.497378 0.045492 0.866340 -v 0.020516 -0.006518 0.027670 -vn -0.500638 0.026256 0.865258 -v 0.021163 -0.003783 0.027929 -vn -0.502105 0.006842 0.864779 -v 0.021463 -0.000991 0.028050 -vn -0.501834 -0.012600 0.864872 -v 0.021412 0.001814 0.028029 -vn -0.499806 -0.031946 0.865548 -v 0.021010 0.004591 0.027868 -vn -0.496031 -0.051064 0.866802 -v 0.020263 0.007296 0.027568 -vn -0.490506 -0.069825 0.868636 -v 0.019184 0.009889 0.027135 -vn -0.677087 -0.731535 0.080059 -v 0.014026 0.014273 0.023098 -vn -0.654173 -0.743308 0.139825 -v 0.013937 0.014400 0.023388 -vn -0.625106 -0.765071 0.154626 -v 0.013447 0.014858 0.023594 -vn -0.045005 -0.369894 0.927983 -v 0.014635 0.016496 0.026096 -vn -0.274023 -0.585368 0.763057 -v 0.014065 0.015830 0.025615 -vn -0.238730 -0.556363 0.795907 -v 0.014132 0.015925 0.025706 -vn -0.207126 -0.529569 0.822591 -v 0.014182 0.015992 0.025765 -vn -0.166961 -0.493175 0.853758 -v 0.014313 0.016154 0.025893 -vn -0.133624 -0.459956 0.877830 -v 0.014395 0.016247 0.025957 -vn -0.101445 -0.425593 0.899211 -v 0.014458 0.016315 0.026001 -vn -0.072152 -0.391230 0.917460 -v 0.014616 0.016477 0.026087 -vn -0.310032 -0.615125 0.724915 -v 0.013963 0.015661 0.025437 -vn -0.339321 -0.637238 0.691946 -v 0.013933 0.015606 0.025375 -vn -0.373110 -0.660304 0.651757 -v 0.013884 0.015501 0.025249 -vn -0.404421 -0.681954 0.609411 -v 0.013824 0.015343 0.025043 -vn -0.430320 -0.698013 0.572365 -v 0.013809 0.015291 0.024971 -vn -0.489064 -0.728381 0.479873 -v 0.013767 0.015028 0.024573 -vn -0.461682 -0.714259 0.526007 -v 0.013785 0.015185 0.024817 -vn -0.507581 -0.739406 0.442313 -v 0.013766 0.014982 0.024499 -vn -0.536911 -0.741126 0.403063 -v 0.013769 0.014908 0.024375 -vn -0.571569 -0.764737 0.297467 -v 0.013614 0.014864 0.024047 -vn -0.586670 -0.748011 0.310318 -v 0.013805 0.014697 0.023994 -vn -0.576099 -0.744065 0.338344 -v 0.013799 0.014723 0.024042 -vn -0.577899 -0.724006 0.376628 -v 0.013772 0.014874 0.024315 -vn -0.643140 -0.744517 0.179070 -v 0.013932 0.014408 0.023405 -vn -0.625775 -0.745536 0.229308 -v 0.013858 0.014549 0.023704 -vn -0.596880 -0.749054 0.287494 -v 0.013809 0.014683 0.023968 -vn -0.692316 -0.721007 0.029106 -v 0.014139 0.014146 0.022783 -vn 0.429353 0.897718 -0.098790 -v -0.016315 0.026001 0.014458 -vn 0.462055 0.876836 -0.132909 -v -0.016247 0.025957 0.014395 -vn 0.483406 0.870895 -0.088657 -v -0.017786 0.026575 0.012329 -vn 0.675028 0.609643 -0.415539 -v -0.015343 0.025043 0.013824 -vn 0.694717 0.561811 -0.449151 -v -0.015291 0.024971 0.013809 -vn 0.719227 0.566869 -0.401711 -v -0.015398 0.025016 0.013687 -vn 0.756319 0.236156 0.610092 -v -0.014549 0.023704 -0.013858 -vn 0.756842 0.293873 0.583806 -v -0.014683 0.023968 -0.013809 -vn 0.795803 0.304645 0.523345 -v -0.015663 0.024397 -0.012680 -vn 0.369774 0.928054 0.044537 -v -0.016496 0.026096 -0.014635 -vn 0.391546 0.917406 0.071116 -v -0.016476 0.026087 -0.014616 -vn 0.526046 0.824579 0.208193 -v -0.015992 0.025765 -0.014182 -vn 0.492020 0.853146 0.173372 -v -0.016154 0.025893 -0.014313 -vn 0.477140 0.872826 0.102527 -v -0.016601 0.026099 -0.013961 -vn 0.460324 0.877672 0.133395 -v -0.016247 0.025957 -0.014395 -vn 0.424797 0.899520 0.102033 -v -0.016315 0.026001 -0.014458 -vn 0.584825 0.762960 0.275447 -v -0.015830 0.025615 -0.014065 -vn 0.556558 0.795822 0.238560 -v -0.015926 0.025705 -0.014132 -vn 0.574519 0.793704 0.199905 -v -0.016315 0.025863 -0.013660 -vn 0.659978 0.651930 0.373386 -v -0.015501 0.025249 -0.013884 -vn 0.637463 0.691909 0.338974 -v -0.015606 0.025375 -0.013933 -vn 0.657455 0.694095 0.293233 -v -0.016073 0.025567 -0.013375 -vn 0.614626 0.725345 0.310016 -v -0.015661 0.025437 -0.013963 -vn 0.714183 0.526263 0.461509 -v -0.015185 0.024817 -0.013785 -vn 0.698208 0.572535 0.429778 -v -0.015291 0.024971 -0.013809 -vn 0.723166 0.577321 0.379119 -v -0.015880 0.025217 -0.013112 -vn 0.682149 0.609608 0.403796 -v -0.015343 0.025043 -0.013824 -vn 0.746500 0.389389 0.539550 -v -0.014874 0.024315 -0.013772 -vn 0.738361 0.440214 0.510916 -v -0.014982 0.024499 -0.013766 -vn 0.769742 0.446407 0.456310 -v -0.015743 0.024824 -0.012879 -vn 0.728744 0.479919 0.488477 -v -0.015028 0.024573 -0.013767 -vn 0.755441 0.316323 0.573802 -v -0.014697 0.023994 -0.013805 -vn 0.752581 0.343445 0.561843 -v -0.014723 0.024042 -0.013799 -vn 0.740352 0.085592 0.666748 -v -0.014273 0.023098 -0.014026 -vn 0.753338 0.149026 0.640526 -v -0.014400 0.023388 -0.013937 -vn 0.803179 0.149459 0.576685 -v -0.015644 0.023946 -0.012522 -vn 0.754030 0.187884 0.629396 -v -0.014408 0.023405 -0.013932 -vn 0.725924 0.032866 0.686990 -v -0.014146 0.022783 -0.014139 -vn 0.705786 0.014365 -0.708279 -v -0.014146 0.022783 0.014139 -vn 0.734087 0.079957 -0.674332 -v -0.014273 0.023098 0.014026 -vn 0.743418 0.137548 -0.654530 -v -0.014400 0.023388 0.013937 -vn 0.787510 0.152249 -0.597200 -v -0.015187 0.023741 0.013074 -vn 0.748111 0.234208 -0.620868 -v -0.014549 0.023704 0.013858 -vn 0.747329 0.177999 -0.640168 -v -0.014408 0.023405 0.013932 -vn 0.736121 0.390166 -0.553079 -v -0.014874 0.024315 0.013772 -vn 0.746789 0.336032 -0.573924 -v -0.014723 0.024042 0.013799 -vn 0.784837 0.302367 -0.540929 -v -0.015198 0.024193 0.013237 -vn 0.750705 0.311984 -0.582329 -v -0.014697 0.023994 0.013805 -vn 0.748977 0.283301 -0.598977 -v -0.014683 0.023968 0.013809 -vn 0.732258 0.429251 -0.528717 -v -0.014982 0.024499 0.013766 -vn 0.760209 0.443410 -0.474836 -v -0.015269 0.024622 0.013444 -vn 0.724208 0.475541 -0.499383 -v -0.015028 0.024573 0.013767 -vn 0.697390 0.530273 -0.482138 -v -0.015185 0.024817 0.013785 -vn 0.586784 0.764569 -0.266680 -v -0.015830 0.025615 0.014065 -vn 0.619937 0.724118 -0.302210 -v -0.015661 0.025437 0.013963 -vn 0.673327 0.692306 -0.259507 -v -0.017217 0.026036 0.011815 -vn 0.642240 0.694195 -0.324995 -v -0.015606 0.025375 0.013933 -vn 0.659574 0.662385 -0.355259 -v -0.015540 0.025296 0.013901 -vn 0.559890 0.794580 -0.234874 -v -0.015926 0.025705 0.014132 -vn 0.585944 0.791104 -0.175567 -v -0.017480 0.026334 0.012065 -vn 0.531899 0.822258 -0.202423 -v -0.015992 0.025765 0.014182 -vn 0.492682 0.854358 -0.165340 -v -0.016154 0.025893 0.014313 -vn 0.393907 0.916813 -0.065513 -v -0.016476 0.026087 0.014616 -vn 0.370354 0.927902 -0.042850 -v -0.016496 0.026096 0.014635 -vn 0.847488 0.147083 -0.510029 -v -0.016709 0.024424 0.011059 -vn 0.902076 0.144860 -0.406540 -v -0.017964 0.024987 0.008872 -vn 0.942865 0.146417 -0.299277 -v -0.018935 0.025421 0.006547 -vn 0.970037 0.145671 -0.194445 -v -0.019606 0.025722 0.004120 -vn 0.986456 0.142919 -0.080489 -v -0.019967 0.025884 0.001628 -vn 0.989070 0.142378 0.038320 -v -0.020013 0.025905 -0.000889 -vn 0.975875 0.146783 0.161624 -v -0.019744 0.025784 -0.003395 -vn 0.950072 0.146847 0.275318 -v -0.019161 0.025523 -0.005848 -vn 0.911173 0.148013 0.384521 -v -0.018275 0.025126 -0.008212 -vn 0.861986 0.152837 0.483343 -v -0.017096 0.024598 -0.010449 -vn 0.846565 0.302026 0.438301 -v -0.017141 0.025043 -0.010584 -vn 0.890586 0.299186 0.342555 -v -0.018341 0.025567 -0.008320 -vn 0.923421 0.297146 0.242895 -v -0.019244 0.025961 -0.005926 -vn 0.944869 0.295751 0.140552 -v -0.019837 0.026220 -0.003440 -vn 0.954755 0.295124 0.036658 -v -0.020112 0.026340 -0.000902 -vn 0.953029 0.295243 -0.067590 -v -0.020064 0.026319 0.001650 -vn 0.939716 0.296108 -0.171041 -v -0.019696 0.026158 0.004175 -vn 0.914927 0.297707 -0.272541 -v -0.019013 0.025860 0.006634 -vn 0.878856 0.300082 -0.370896 -v -0.018025 0.025429 0.008988 -vn 0.831789 0.303214 -0.464961 -v -0.016747 0.024870 0.011201 -vn 0.810660 0.443322 0.382486 -v -0.017248 0.025466 -0.010751 -vn 0.847281 0.439400 0.298401 -v -0.018470 0.025987 -0.008452 -vn 0.874502 0.436580 0.211292 -v -0.019390 0.026379 -0.006021 -vn 0.892253 0.434700 0.122151 -v -0.019994 0.026636 -0.003495 -vn 0.900429 0.433835 0.031857 -v -0.020273 0.026755 -0.000916 -vn 0.898967 0.434063 -0.058708 -v -0.020225 0.026735 0.001677 -vn 0.887956 0.435240 -0.148663 -v -0.019850 0.026575 0.004242 -vn 0.867454 0.437372 -0.237129 -v -0.019154 0.026278 0.006740 -vn 0.837485 0.440663 -0.323165 -v -0.018148 0.025850 0.009131 -vn 0.798293 0.444920 -0.405924 -v -0.016846 0.025295 0.011377 -vn 0.754989 0.573853 0.317309 -v -0.017413 0.025857 -0.010946 -vn 0.784066 0.569323 0.247209 -v -0.018658 0.026376 -0.008606 -vn 0.805654 0.565985 0.174880 -v -0.019595 0.026767 -0.006130 -vn 0.819691 0.563826 0.101027 -v -0.020210 0.027023 -0.003559 -vn 0.826132 0.562860 0.026345 -v -0.020495 0.027142 -0.000933 -vn 0.824971 0.563088 -0.048530 -v -0.020446 0.027122 0.001707 -vn 0.816281 0.564418 -0.122958 -v -0.020064 0.026962 0.004319 -vn 0.800006 0.566982 -0.196272 -v -0.019355 0.026667 0.006862 -vn 0.776296 0.570647 -0.267818 -v -0.018330 0.026239 0.009296 -vn 0.745005 0.575409 -0.337449 -v -0.017004 0.025686 0.011584 -vn 0.680979 0.690293 0.244466 -v -0.017634 0.026207 -0.011164 -vn 0.702493 0.685794 0.190239 -v -0.018901 0.026726 -0.008776 -vn 0.718445 0.682461 0.134475 -v -0.019855 0.027116 -0.006251 -vn 0.728773 0.680340 0.077639 -v -0.020481 0.027373 -0.003629 -vn 0.733499 0.679389 0.020242 -v -0.020771 0.027492 -0.000951 -vn 0.732672 0.679560 -0.037284 -v -0.020721 0.027471 0.001740 -vn 0.726287 0.680864 -0.094502 -v -0.020333 0.027312 0.004404 -vn 0.714243 0.683429 -0.150937 -v -0.019611 0.027016 0.006997 -vn 0.696747 0.687052 -0.206166 -v -0.018567 0.026589 0.009481 -vn 0.625691 0.654206 -0.424882 -v -0.015501 0.025249 0.013884 -vn 0.590455 0.789874 0.165719 -v -0.017905 0.026506 -0.011400 -vn 0.604503 0.786115 0.128843 -v -0.019194 0.027027 -0.008960 -vn 0.614909 0.783327 0.091022 -v -0.020164 0.027420 -0.006381 -vn 0.621621 0.781555 0.052528 -v -0.020801 0.027677 -0.003704 -vn 0.624699 0.780745 0.013698 -v -0.021097 0.027797 -0.000971 -vn 0.624125 0.780918 -0.025216 -v -0.021046 0.027776 0.001777 -vn 0.619943 0.782038 -0.063928 -v -0.020650 0.027616 0.004495 -vn 0.612158 0.784107 -0.102169 -v -0.019916 0.027319 0.007143 -vn 0.600694 0.787192 -0.139631 -v -0.018854 0.026890 0.009680 -vn 0.485605 0.870234 0.082950 -v -0.018218 0.026748 -0.011648 -vn 0.492402 0.867978 0.064457 -v -0.019529 0.027274 -0.009153 -vn 0.497404 0.866325 0.045503 -v -0.020516 0.027670 -0.006518 -vn 0.500631 0.865263 0.026251 -v -0.021163 0.027929 -0.003783 -vn 0.502113 0.864775 0.006847 -v -0.021463 0.028050 -0.000991 -vn 0.501837 0.864870 -0.012596 -v -0.021412 0.028029 0.001814 -vn 0.499801 0.865551 -0.031947 -v -0.021010 0.027868 0.004591 -vn 0.496056 0.866787 -0.051075 -v -0.020263 0.027568 0.007296 -vn 0.490484 0.868649 -0.069817 -v -0.019184 0.027135 0.009889 -vn 0.677091 0.080081 -0.731529 -v -0.014026 0.023098 0.014273 -vn 0.654251 0.139358 -0.743327 -v -0.013937 0.023388 0.014400 -vn 0.625097 0.154630 -0.765077 -v -0.013447 0.023594 0.014858 -vn 0.044949 0.928011 -0.369831 -v -0.014635 0.026096 0.016496 -vn 0.094506 0.881288 -0.463034 -v -0.014021 0.026081 0.016554 -vn 0.133551 0.877679 -0.460265 -v -0.014395 0.025957 0.016247 -vn 0.102346 0.899782 -0.424167 -v -0.014458 0.026001 0.016315 -vn 0.072073 0.917485 -0.391187 -v -0.014616 0.026087 0.016477 -vn 0.166947 0.853762 -0.493173 -v -0.014313 0.025893 0.016154 -vn 0.153297 0.838465 -0.522950 -v -0.013882 0.025981 0.016419 -vn 0.207148 0.822568 -0.529595 -v -0.014182 0.025765 0.015992 -vn 0.197120 0.800924 -0.565389 -v -0.013718 0.025844 0.016269 -vn 0.238759 0.795882 -0.556386 -v -0.014132 0.025705 0.015926 -vn 0.275267 0.762716 -0.585229 -v -0.014065 0.025615 0.015830 -vn 0.298173 0.700325 -0.648566 -v -0.013431 0.025548 0.016027 -vn 0.310489 0.725361 -0.614369 -v -0.013963 0.025437 0.015661 -vn 0.339328 0.691932 -0.637249 -v -0.013933 0.025375 0.015606 -vn 0.237160 0.763255 -0.600997 -v -0.013665 0.025795 0.016221 -vn 0.373098 0.651764 -0.660304 -v -0.013884 0.025249 0.015501 -vn 0.389239 0.579561 -0.715963 -v -0.013167 0.025199 0.015836 -vn 0.404425 0.609404 -0.681958 -v -0.013824 0.025043 0.015343 -vn 0.430263 0.572455 -0.697975 -v -0.013809 0.024971 0.015291 -vn 0.352504 0.628940 -0.692947 -v -0.013260 0.025331 0.015899 -vn 0.461631 0.526052 -0.714259 -v -0.013785 0.024817 0.015185 -vn 0.472843 0.443948 -0.761137 -v -0.012933 0.024805 0.015699 -vn 0.489119 0.479771 -0.728411 -v -0.013767 0.024573 0.015028 -vn 0.507768 0.442165 -0.739365 -v -0.013767 0.024499 0.014982 -vn 0.426009 0.525366 -0.736550 -v -0.013078 0.025060 0.015779 -vn 0.537048 0.403132 -0.740989 -v -0.013769 0.024375 0.014908 -vn 0.517859 0.354586 -0.778519 -v -0.012767 0.024457 0.015630 -vn 0.571596 0.297462 -0.764719 -v -0.013614 0.024047 0.014864 -vn 0.587006 0.309424 -0.748118 -v -0.013805 0.023994 0.014697 -vn 0.576083 0.338508 -0.744004 -v -0.013799 0.024042 0.014723 -vn 0.577983 0.376760 -0.723870 -v -0.013772 0.024315 0.014874 -vn 0.643319 0.178427 -0.744516 -v -0.013932 0.023405 0.014408 -vn 0.625779 0.229332 -0.745525 -v -0.013858 0.023704 0.014549 -vn 0.597157 0.286559 -0.749191 -v -0.013809 0.023968 0.014683 -vn 0.689691 0.028898 -0.723527 -v -0.014139 0.022783 0.014146 -vn 0.608027 0.097743 -0.787877 -v -0.012540 0.023802 0.015607 -vn 0.543861 0.293759 -0.786079 -v -0.012734 0.024378 0.015620 -vn 0.567754 0.228443 -0.790866 -v -0.012642 0.024134 0.015602 -vn 0.590239 0.162988 -0.790603 -v -0.012575 0.023927 0.015601 -vn -0.610084 0.236215 0.756306 -v 0.013858 0.023704 -0.014549 -vn -0.583803 0.293875 0.756843 -v 0.013809 0.023968 -0.014683 -vn -0.523327 0.304672 0.795804 -v 0.012680 0.024397 -0.015663 -vn 0.098769 0.897723 0.429347 -v -0.014458 0.026001 -0.016315 -vn 0.132934 0.876816 0.462085 -v -0.014395 0.025957 -0.016247 -vn 0.088670 0.870884 0.483423 -v -0.012328 0.026575 -0.017786 -vn 0.415673 0.609475 0.675097 -v -0.013824 0.025043 -0.015343 -vn 0.449210 0.561752 0.694727 -v -0.013809 0.024971 -0.015291 -vn 0.401732 0.566825 0.719250 -v -0.013687 0.025016 -0.015398 -vn 0.691409 0.026328 0.721984 -v -0.014139 0.022783 -0.014146 -vn 0.680201 0.080739 0.728565 -v -0.014026 0.023098 -0.014273 -vn 0.660960 0.128250 0.739381 -v -0.013937 0.023388 -0.014400 -vn 0.596023 0.149278 0.788969 -v -0.013074 0.023741 -0.015187 -vn 0.640522 0.176653 0.747345 -v -0.013932 0.023405 -0.014408 -vn 0.620895 0.234259 0.748073 -v -0.013858 0.023704 -0.014549 -vn 0.553111 0.390113 0.736125 -v -0.013772 0.024315 -0.014874 -vn 0.573910 0.336102 0.746768 -v -0.013799 0.024042 -0.014723 -vn 0.540943 0.302322 0.784845 -v -0.013237 0.024193 -0.015198 -vn 0.582749 0.310803 0.750869 -v -0.013805 0.023994 -0.014697 -vn 0.599267 0.282329 0.749112 -v -0.013809 0.023968 -0.014683 -vn 0.528762 0.429185 0.732264 -v -0.013767 0.024499 -0.014982 -vn 0.474855 0.443410 0.760197 -v -0.013444 0.024622 -0.015269 -vn 0.499407 0.475537 0.724194 -v -0.013767 0.024573 -0.015028 -vn 0.482165 0.530423 0.697258 -v -0.013785 0.024817 -0.015185 -vn 0.266687 0.764548 0.586809 -v -0.014065 0.025615 -0.015830 -vn 0.302290 0.724038 0.619992 -v -0.013963 0.025437 -0.015661 -vn 0.259480 0.692350 0.673291 -v -0.011815 0.026036 -0.017217 -vn 0.324938 0.694300 0.642154 -v -0.013933 0.025375 -0.015606 -vn 0.355210 0.662471 0.659514 -v -0.013901 0.025296 -0.015540 -vn 0.234819 0.794617 0.559861 -v -0.014132 0.025705 -0.015925 -vn 0.175561 0.791118 0.585927 -v -0.012065 0.026334 -0.017480 -vn 0.202389 0.822278 0.531881 -v -0.014182 0.025765 -0.015992 -vn 0.165343 0.854347 0.492700 -v -0.014313 0.025893 -0.016154 -vn 0.065605 0.916764 0.394004 -v -0.014616 0.026087 -0.016477 -vn 0.043018 0.927836 0.370499 -v -0.014635 0.026096 -0.016496 -vn -0.044750 0.927969 0.369962 -v 0.014635 0.026096 -0.016496 -vn -0.071237 0.917358 0.391636 -v 0.014616 0.026087 -0.016477 -vn -0.208144 0.824629 0.525988 -v 0.014182 0.025765 -0.015992 -vn -0.173417 0.853132 0.492029 -v 0.014313 0.025893 -0.016154 -vn -0.102541 0.872827 0.477136 -v 0.013961 0.026099 -0.016601 -vn -0.133432 0.877658 0.460339 -v 0.014395 0.025957 -0.016247 -vn -0.102024 0.899534 0.424771 -v 0.014458 0.026001 -0.016315 -vn -0.275454 0.762921 0.584873 -v 0.014065 0.025615 -0.015830 -vn -0.238490 0.795878 0.556508 -v 0.014132 0.025705 -0.015925 -vn -0.199899 0.793717 0.574503 -v 0.013660 0.025863 -0.016315 -vn -0.373348 0.651983 0.659946 -v 0.013884 0.025249 -0.015501 -vn -0.338922 0.691964 0.637431 -v 0.013933 0.025375 -0.015606 -vn -0.293226 0.694104 0.657448 -v 0.013375 0.025567 -0.016073 -vn -0.310035 0.725309 0.614659 -v 0.013963 0.025437 -0.015661 -vn -0.461510 0.526310 0.714147 -v 0.013785 0.024817 -0.015185 -vn -0.429802 0.572454 0.698260 -v 0.013809 0.024971 -0.015291 -vn -0.379131 0.577305 0.723173 -v 0.013112 0.025217 -0.015880 -vn -0.403893 0.609441 0.682241 -v 0.013824 0.025043 -0.015343 -vn -0.539639 0.389304 0.746480 -v 0.013772 0.024315 -0.014874 -vn -0.510984 0.440154 0.738349 -v 0.013766 0.024499 -0.014982 -vn -0.456330 0.446369 0.769751 -v 0.012879 0.024824 -0.015743 -vn -0.488427 0.480042 0.728697 -v 0.013767 0.024573 -0.015028 -vn -0.573902 0.316059 0.755475 -v 0.013805 0.023994 -0.014697 -vn -0.561949 0.343267 0.752583 -v 0.013799 0.024042 -0.014723 -vn -0.581002 0.152435 0.799500 -v 0.012522 0.023946 -0.015644 -vn -0.629597 0.187059 0.754067 -v 0.013932 0.023405 -0.014408 -vn -0.657147 0.127528 0.742896 -v 0.013937 0.023388 -0.014400 -vn -0.693605 0.027990 0.719812 -v 0.014139 0.022783 -0.014146 -vn 0.510987 0.149335 0.846517 -v -0.011059 0.024424 -0.016709 -vn 0.415451 0.147982 0.897497 -v -0.008872 0.024987 -0.017964 -vn 0.307592 0.144367 0.940503 -v -0.006547 0.025421 -0.018935 -vn 0.192549 0.142791 0.970843 -v -0.004120 0.025722 -0.019605 -vn 0.069682 0.145319 0.986928 -v -0.001628 0.025884 -0.019967 -vn -0.046613 0.144662 0.988383 -v 0.000889 0.025905 -0.020013 -vn -0.160981 0.144897 0.976263 -v 0.003395 0.025784 -0.019744 -vn -0.268971 0.150794 0.951271 -v 0.005848 0.025523 -0.019162 -vn -0.375103 0.145348 0.915517 -v 0.008212 0.025126 -0.018275 -vn -0.481321 0.146088 0.864285 -v 0.010449 0.024598 -0.017096 -vn -0.680203 0.080685 0.728569 -v 0.014026 0.023098 -0.014273 -vn -0.438294 0.302042 0.846563 -v 0.010584 0.025043 -0.017141 -vn -0.342566 0.299179 0.890584 -v 0.008320 0.025567 -0.018341 -vn -0.242918 0.297079 0.923436 -v 0.005926 0.025961 -0.019244 -vn -0.140546 0.295751 0.944869 -v 0.003440 0.026220 -0.019837 -vn -0.036659 0.295147 0.954748 -v 0.000902 0.026340 -0.020112 -vn 0.067590 0.295285 0.953015 -v -0.001650 0.026319 -0.020064 -vn 0.171037 0.296152 0.939702 -v -0.004175 0.026158 -0.019696 -vn 0.272519 0.297759 0.914917 -v -0.006634 0.025860 -0.019013 -vn 0.370885 0.300122 0.878846 -v -0.008988 0.025429 -0.018025 -vn 0.464962 0.303218 0.831787 -v -0.011201 0.024870 -0.016747 -vn -0.382456 0.443375 0.810645 -v 0.010751 0.025466 -0.017248 -vn -0.298387 0.439421 0.847275 -v 0.008452 0.025987 -0.018470 -vn -0.211302 0.436544 0.874517 -v 0.006021 0.026379 -0.019390 -vn -0.122162 0.434690 0.892256 -v 0.003495 0.026636 -0.019994 -vn -0.031857 0.433850 0.900422 -v 0.000916 0.026755 -0.020273 -vn 0.058717 0.434029 0.898983 -v -0.001677 0.026735 -0.020225 -vn 0.148666 0.435211 0.887969 -v -0.004242 0.026575 -0.019850 -vn 0.237119 0.437405 0.867440 -v -0.006740 0.026278 -0.019154 -vn 0.323183 0.440624 0.837498 -v -0.009131 0.025850 -0.018148 -vn 0.405944 0.444876 0.798308 -v -0.011377 0.025295 -0.016846 -vn -0.317323 0.573834 0.754997 -v 0.010946 0.025857 -0.017414 -vn -0.247212 0.569307 0.784077 -v 0.008606 0.026376 -0.018658 -vn -0.174884 0.565984 0.805653 -v 0.006130 0.026767 -0.019595 -vn -0.101032 0.563842 0.819679 -v 0.003559 0.027023 -0.020210 -vn -0.026341 0.562877 0.826121 -v 0.000933 0.027142 -0.020495 -vn 0.048538 0.563068 0.824984 -v -0.001707 0.027122 -0.020446 -vn 0.122963 0.564415 0.816282 -v -0.004319 0.026962 -0.020064 -vn 0.196279 0.566934 0.800038 -v -0.006862 0.026667 -0.019355 -vn 0.267834 0.570635 0.776299 -v -0.009296 0.026239 -0.018330 -vn 0.337447 0.575415 0.745001 -v -0.011584 0.025686 -0.017004 -vn -0.244477 0.690281 0.680987 -v 0.011164 0.026207 -0.017634 -vn -0.190248 0.685774 0.702510 -v 0.008776 0.026726 -0.018901 -vn -0.134475 0.682460 0.718446 -v 0.006251 0.027116 -0.019855 -vn -0.077647 0.680332 0.728779 -v 0.003629 0.027373 -0.020481 -vn -0.020241 0.679361 0.733525 -v 0.000951 0.027492 -0.020771 -vn 0.037291 0.679547 0.732684 -v -0.001741 0.027471 -0.020721 -vn 0.094500 0.680889 0.726265 -v -0.004404 0.027312 -0.020333 -vn 0.150944 0.683396 0.714273 -v -0.006997 0.027016 -0.019611 -vn 0.206154 0.687069 0.696733 -v -0.009481 0.026589 -0.018567 -vn 0.424902 0.654146 0.625741 -v -0.013884 0.025249 -0.015501 -vn -0.165707 0.789883 0.590445 -v 0.011400 0.026506 -0.017905 -vn -0.128846 0.786112 0.604505 -v 0.008960 0.027027 -0.019194 -vn -0.091016 0.783340 0.614893 -v 0.006381 0.027420 -0.020164 -vn -0.052532 0.781554 0.621621 -v 0.003704 0.027677 -0.020801 -vn -0.013694 0.780737 0.624709 -v 0.000971 0.027797 -0.021097 -vn 0.025219 0.780893 0.624155 -v -0.001777 0.027776 -0.021046 -vn 0.063933 0.782020 0.619966 -v -0.004495 0.027616 -0.020650 -vn 0.102164 0.784114 0.612150 -v -0.007143 0.027319 -0.019916 -vn 0.139619 0.787198 0.600687 -v -0.009680 0.026890 -0.018854 -vn -0.082941 0.870239 0.485597 -v 0.011648 0.026748 -0.018218 -vn -0.064448 0.867986 0.492389 -v 0.009153 0.027274 -0.019529 -vn -0.045501 0.866330 0.497396 -v 0.006518 0.027670 -0.020516 -vn -0.026254 0.865262 0.500632 -v 0.003783 0.027929 -0.021163 -vn -0.006842 0.864781 0.502102 -v 0.000991 0.028050 -0.021463 -vn 0.012599 0.864875 0.501829 -v -0.001814 0.028029 -0.021412 -vn 0.031944 0.865548 0.499806 -v -0.004591 0.027868 -0.021010 -vn 0.051062 0.866803 0.496030 -v -0.007296 0.027568 -0.020263 -vn 0.069818 0.868646 0.490489 -v -0.009889 0.027135 -0.019184 -vn 0.562838 0.176513 -0.807500 -v -0.011790 0.024261 0.016235 -vn 0.523054 0.290575 -0.801237 -v -0.011910 0.024603 0.016253 -vn 0.360940 0.601045 -0.713069 -v -0.012398 0.025533 0.016515 -vn 0.073645 0.887468 -0.454948 -v -0.013256 0.026391 0.017286 -vn 0.225585 0.766149 -0.601770 -v -0.012807 0.026029 0.016848 -vn 0.421360 0.504500 -0.753615 -v -0.012216 0.025243 0.016395 -vn 0.594208 0.059756 -0.802088 -v -0.011695 0.023911 0.016252 -vn 0.582829 -0.033029 -0.811924 -v -0.010159 0.024097 0.017385 -vn 0.558935 -0.118363 -0.820720 -v -0.008775 0.024247 0.018338 -vn 0.423070 -0.293651 -0.857194 -v -0.005464 0.024519 0.020227 -vn 0.471068 -0.241124 -0.848501 -v -0.006480 0.024450 0.019718 -vn 0.512332 -0.190401 -0.837415 -v -0.007497 0.024368 0.019142 -vn 0.357544 -0.336638 -0.871113 -v -0.004491 0.024572 0.020648 -vn 0.299643 -0.371838 -0.878607 -v -0.003549 0.024613 0.020986 -vn 0.075047 -0.431776 -0.898853 -v -0.000814 0.024674 0.021536 -vn 0.143760 -0.419292 -0.896397 -v -0.001627 0.024664 0.021443 -vn 0.198036 -0.403473 -0.893304 -v -0.002452 0.024647 0.021287 -vn 0.238840 -0.397705 -0.885882 -v -0.002630 0.024643 0.021245 -vn -0.069744 -0.431820 -0.899259 -v 0.000805 0.024674 0.021537 -vn -0.001189 -0.435759 -0.900063 -v -0.000006 0.024677 0.021568 -vn -0.271801 -0.379811 -0.884233 -v 0.003222 0.024625 0.021086 -vn -0.207199 -0.403634 -0.891150 -v 0.002384 0.024649 0.021302 -vn -0.142313 -0.420621 -0.896005 -v 0.001627 0.024664 0.021443 -vn -0.390451 -0.313864 -0.865470 -v 0.004937 0.024549 0.020464 -vn -0.333163 -0.351657 -0.874837 -v 0.004072 0.024592 0.020807 -vn -0.437871 -0.272159 -0.856854 -v 0.005820 0.024496 0.020056 -vn -0.489114 -0.220226 -0.843960 -v 0.006893 0.024418 0.019491 -vn -0.530056 -0.162368 -0.832273 -v 0.007953 0.024327 0.018864 -vn -0.561457 -0.099841 -0.821461 -v 0.009042 0.024220 0.018160 -vn -0.585727 -0.030647 -0.809929 -v 0.010165 0.024097 0.017380 -vn 0.077910 0.883020 -0.462824 -v -0.011676 0.026844 0.018427 -vn 0.076835 0.878611 -0.471316 -v -0.010209 0.027226 0.019392 -vn 0.073948 0.874384 -0.479566 -v -0.008818 0.027551 0.020209 -vn 0.069256 0.870842 -0.486660 -v -0.007685 0.027784 0.020798 -vn 0.063205 0.867503 -0.493400 -v -0.006532 0.027991 0.021322 -vn 0.055543 0.864439 -0.499660 -v -0.005406 0.028164 0.021757 -vn 0.046422 0.861759 -0.505190 -v -0.004298 0.028303 0.022108 -vn 0.038497 0.859378 -0.509890 -v -0.003200 0.028410 0.022379 -vn 0.031761 0.858520 -0.511795 -v -0.002986 0.028427 0.022422 -vn 0.023108 0.857643 -0.513726 -v -0.001987 0.028492 0.022587 -vn 0.011783 0.856738 -0.515617 -v -0.000996 0.028531 0.022685 -vn 0.000127 0.856417 -0.516286 -v -0.000008 0.028544 0.022718 -vn -0.011584 0.856693 -0.515696 -v 0.000985 0.028531 0.022685 -vn -0.022799 0.857507 -0.513967 -v 0.001988 0.028492 0.022586 -vn -0.033179 0.858809 -0.511221 -v 0.002904 0.028433 0.022438 -vn -0.042907 0.860682 -0.507332 -v 0.003909 0.028344 0.022213 -vn -0.051778 0.862947 -0.502635 -v 0.004915 0.028229 0.021922 -vn -0.059415 0.865539 -0.497305 -v 0.005925 0.028088 0.021566 -vn -0.066013 0.868484 -0.491303 -v 0.006939 0.027922 0.021146 -vn -0.071395 0.872024 -0.484228 -v 0.008149 0.027692 0.020566 -vn -0.075347 0.875580 -0.477161 -v 0.009319 0.027438 0.019927 -vn -0.077600 0.879173 -0.470142 -v 0.010495 0.027155 0.019212 -vn -0.078319 0.882751 -0.463267 -v 0.011682 0.026842 0.018423 -vn -0.077913 0.886736 -0.455664 -v 0.012884 0.026501 0.017563 -vn 0.294610 0.688916 -0.662269 -v -0.012596 0.025796 0.016667 -vn 0.229379 0.747735 -0.623120 -v -0.011221 0.026438 0.017947 -vn 0.299963 0.660601 -0.688207 -v -0.011009 0.026176 0.017753 -vn 0.225824 0.729632 -0.645477 -v -0.009762 0.026779 0.018870 -vn 0.294644 0.633828 -0.715156 -v -0.009556 0.026491 0.018662 -vn 0.216828 0.712752 -0.667061 -v -0.008391 0.027065 0.019647 -vn 0.282343 0.609010 -0.741208 -v -0.008195 0.026753 0.019425 -vn 0.202745 0.698972 -0.685808 -v -0.007285 0.027268 0.020202 -vn 0.263565 0.589040 -0.763915 -v -0.007102 0.026938 0.019969 -vn 0.184792 0.685992 -0.703752 -v -0.006168 0.027446 0.020692 -vn 0.239887 0.570243 -0.785670 -v -0.006003 0.027099 0.020447 -vn 0.162203 0.674268 -0.720453 -v -0.005086 0.027592 0.021096 -vn 0.210297 0.553381 -0.805943 -v -0.004942 0.027229 0.020840 -vn 0.135446 0.664116 -0.735258 -v -0.004031 0.027709 0.021419 -vn 0.175423 0.538843 -0.823939 -v -0.003911 0.027333 0.021154 -vn 0.112007 0.655991 -0.746411 -v -0.002994 0.027797 0.021667 -vn 0.144910 0.527414 -0.837159 -v -0.002901 0.027411 0.021394 -vn 0.092281 0.653149 -0.751585 -v -0.002792 0.027812 0.021707 -vn 0.119319 0.523494 -0.843633 -v -0.002705 0.027423 0.021432 -vn 0.067293 0.648949 -0.757850 -v -0.001855 0.027865 0.021856 -vn 0.087016 0.517294 -0.851372 -v -0.001796 0.027470 0.021576 -vn 0.034303 0.645644 -0.762868 -v -0.000929 0.027896 0.021944 -vn 0.044353 0.512604 -0.857479 -v -0.000899 0.027497 0.021662 -vn 0.000382 0.644495 -0.764608 -v -0.000007 0.027907 0.021974 -vn 0.000503 0.510982 -0.859591 -v -0.000007 0.027507 0.021690 -vn -0.033692 0.645558 -0.762968 -v 0.000919 0.027897 0.021945 -vn -0.043532 0.512492 -0.857588 -v 0.000889 0.027498 0.021662 -vn -0.066303 0.648719 -0.758135 -v 0.001855 0.027865 0.021856 -vn -0.085711 0.517016 -0.851674 -v 0.001796 0.027470 0.021576 -vn -0.096519 0.653589 -0.750670 -v 0.002715 0.027817 0.021721 -vn -0.124832 0.523945 -0.842555 -v 0.002630 0.027428 0.021446 -vn -0.124909 0.660592 -0.740281 -v 0.003663 0.027743 0.021515 -vn -0.161664 0.533907 -0.829945 -v 0.003552 0.027363 0.021247 -vn -0.150814 0.669171 -0.727644 -v 0.004618 0.027647 0.021248 -vn -0.195370 0.546188 -0.814561 -v 0.004484 0.027278 0.020988 -vn -0.173183 0.679084 -0.713339 -v 0.005583 0.027528 0.020919 -vn -0.224582 0.560416 -0.797181 -v 0.005429 0.027172 0.020669 -vn -0.192662 0.690269 -0.697431 -v 0.006560 0.027386 0.020528 -vn -0.250142 0.576492 -0.777873 -v 0.006389 0.027045 0.020287 -vn -0.208692 0.704066 -0.678778 -v 0.007736 0.027188 0.019984 -vn -0.271399 0.596549 -0.755296 -v 0.007548 0.026865 0.019755 -vn -0.220475 0.718229 -0.659953 -v 0.008883 0.026966 0.019379 -vn -0.287183 0.617220 -0.732506 -v 0.008683 0.026663 0.019162 -vn -0.227363 0.732725 -0.641420 -v 0.010045 0.026716 0.018699 -vn -0.296668 0.638524 -0.710123 -v 0.009837 0.026433 0.018493 -vn -0.229793 0.747391 -0.623380 -v 0.011227 0.026436 0.017943 -vn -0.300374 0.660255 -0.688360 -v 0.011015 0.026175 0.017749 -vn -0.228019 0.762116 -0.605959 -v 0.012433 0.026128 0.017116 -vn -0.298779 0.682583 -0.666942 -v 0.012221 0.025889 0.016932 -vn 0.365516 0.562325 -0.741747 -v -0.010812 0.025881 0.017593 -vn 0.424899 0.454612 -0.782808 -v -0.010634 0.025558 0.017470 -vn 0.357937 0.526115 -0.771417 -v -0.009366 0.026168 0.018494 -vn 0.414528 0.408478 -0.813211 -v -0.009196 0.025816 0.018369 -vn 0.342036 0.492788 -0.800107 -v -0.008017 0.026404 0.019248 -vn 0.394703 0.366409 -0.842588 -v -0.007860 0.026025 0.019121 -vn 0.318629 0.466198 -0.825309 -v -0.006937 0.026569 0.019785 -vn 0.366733 0.333118 -0.868642 -v -0.006793 0.026170 0.019656 -vn 0.289437 0.441289 -0.849406 -v -0.005854 0.026712 0.020257 -vn 0.332305 0.302069 -0.893492 -v -0.005726 0.026295 0.020125 -vn 0.253310 0.419045 -0.871915 -v -0.004813 0.026827 0.020643 -vn 0.290205 0.274505 -0.916749 -v -0.004703 0.026393 0.020509 -vn 0.211007 0.399970 -0.891908 -v -0.003805 0.026916 0.020951 -vn 0.241290 0.251003 -0.937431 -v -0.003714 0.026470 0.020815 -vn 0.174072 0.385179 -0.906276 -v -0.002819 0.026984 0.021186 -vn 0.198746 0.233001 -0.951951 -v -0.002750 0.026527 0.021048 -vn 0.143229 0.380189 -0.913751 -v -0.002628 0.026994 0.021223 -vn 0.163415 0.226983 -0.960091 -v -0.002564 0.026535 0.021085 -vn 0.104450 0.371895 -0.922380 -v -0.001744 0.027034 0.021364 -vn 0.119134 0.216624 -0.968959 -v -0.001700 0.026569 0.021225 -vn 0.053221 0.365816 -0.929164 -v -0.000873 0.027057 0.021447 -vn 0.060675 0.209206 -0.975987 -v -0.000850 0.026588 0.021308 -vn 0.000621 0.363714 -0.931511 -v -0.000007 0.027065 0.021475 -vn 0.000727 0.206641 -0.978417 -v -0.000006 0.026594 0.021335 -vn -0.052210 0.365684 -0.929274 -v 0.000863 0.027057 0.021448 -vn -0.059476 0.209046 -0.976095 -v 0.000841 0.026588 0.021308 -vn -0.102850 0.371598 -0.922679 -v 0.001744 0.027034 0.021364 -vn -0.117258 0.216299 -0.969260 -v 0.001701 0.026569 0.021225 -vn -0.149890 0.380612 -0.912506 -v 0.002555 0.026998 0.021237 -vn -0.171039 0.227320 -0.958682 -v 0.002492 0.026539 0.021099 -vn -0.194312 0.393620 -0.898502 -v 0.003454 0.026943 0.021042 -vn -0.222018 0.243266 -0.944209 -v 0.003371 0.026492 0.020906 -vn -0.235108 0.409728 -0.881389 -v 0.004365 0.026869 0.020788 -vn -0.269052 0.263116 -0.926489 -v 0.004263 0.026430 0.020654 -vn -0.270647 0.428430 -0.862089 -v 0.005290 0.026777 0.020474 -vn -0.310282 0.286214 -0.906535 -v 0.005171 0.026351 0.020342 -vn -0.301938 0.449628 -0.840635 -v 0.006234 0.026665 0.020099 -vn -0.346879 0.312523 -0.884310 -v 0.006100 0.026253 0.019968 -vn -0.328319 0.476287 -0.815695 -v 0.007377 0.026505 0.019574 -vn -0.378235 0.345809 -0.858693 -v 0.007227 0.026114 0.019446 -vn -0.348179 0.503897 -0.790481 -v 0.008500 0.026324 0.018989 -vn -0.402240 0.380550 -0.832697 -v 0.008337 0.025954 0.018862 -vn -0.360520 0.532588 -0.765752 -v 0.009646 0.026115 0.018326 -vn -0.417745 0.416831 -0.807305 -v 0.009474 0.025768 0.018202 -vn -0.365918 0.562015 -0.741784 -v 0.010818 0.025880 0.017589 -vn -0.425319 0.454312 -0.782755 -v 0.010640 0.025557 0.017466 -vn -0.365969 0.593130 -0.717122 -v 0.012022 0.025618 0.016778 -vn -0.428004 0.494035 -0.756797 -v 0.011841 0.025321 0.016657 -vn 0.521351 0.218118 -0.824996 -v -0.010344 0.024850 0.017345 -vn 0.556779 0.093336 -0.825400 -v -0.010238 0.024476 0.017344 -vn 0.503420 0.152513 -0.850475 -v -0.008929 0.025049 0.018258 -vn 0.534043 0.018987 -0.845244 -v -0.008837 0.024649 0.018274 -vn 0.474795 0.093761 -0.875088 -v -0.007621 0.025208 0.019024 -vn 0.500561 -0.046917 -0.864429 -v -0.007544 0.024787 0.019056 -vn 0.437989 0.048100 -0.897693 -v -0.006579 0.025316 0.019570 -vn 0.459565 -0.097567 -0.882769 -v -0.006514 0.024880 0.019615 -vn 0.394152 0.005985 -0.919026 -v -0.005541 0.025407 0.020049 -vn 0.411687 -0.144012 -0.899875 -v -0.005488 0.024958 0.020107 -vn 0.342142 -0.030877 -0.939141 -v -0.004547 0.025478 0.020443 -vn 0.355937 -0.184352 -0.916146 -v -0.004506 0.025019 0.020512 -vn 0.283030 -0.062029 -0.957103 -v -0.003589 0.025532 0.020757 -vn 0.293445 -0.218207 -0.930739 -v -0.003558 0.025064 0.020836 -vn 0.232270 -0.085396 -0.968895 -v -0.002657 0.025571 0.020997 -vn 0.240227 -0.243360 -0.939716 -v -0.002635 0.025097 0.021084 -vn 0.190618 -0.093061 -0.977243 -v -0.002476 0.025577 0.021035 -vn 0.196894 -0.251553 -0.947604 -v -0.002456 0.025102 0.021124 -vn 0.138742 -0.106948 -0.984537 -v -0.001641 0.025599 0.021179 -vn 0.143142 -0.266647 -0.953105 -v -0.001628 0.025121 0.021273 -vn 0.070585 -0.116562 -0.990672 -v -0.000821 0.025612 0.021264 -vn 0.072769 -0.276968 -0.958120 -v -0.000815 0.025132 0.021362 -vn 0.000913 -0.119869 -0.992789 -v -0.000006 0.025616 0.021293 -vn 0.000986 -0.280514 -0.959849 -v -0.000006 0.025135 0.021392 -vn -0.069059 -0.116753 -0.990757 -v 0.000812 0.025612 0.021265 -vn -0.071106 -0.277173 -0.958185 -v 0.000806 0.025132 0.021363 -vn -0.136434 -0.107294 -0.984822 -v 0.001642 0.025599 0.021179 -vn -0.140685 -0.267005 -0.953371 -v 0.001629 0.025121 0.021273 -vn -0.199486 -0.092944 -0.975483 -v 0.002407 0.025579 0.021049 -vn -0.206041 -0.251573 -0.945652 -v 0.002388 0.025104 0.021139 -vn -0.259892 -0.072070 -0.962945 -v 0.003257 0.025547 0.020850 -vn -0.269079 -0.229039 -0.935488 -v 0.003229 0.025077 0.020932 -vn -0.316324 -0.045903 -0.947540 -v 0.004121 0.025504 0.020591 -vn -0.328481 -0.200640 -0.922954 -v 0.004084 0.025041 0.020665 -vn -0.366687 -0.015063 -0.930223 -v 0.005002 0.025448 0.020271 -vn -0.382059 -0.167071 -0.908911 -v 0.004956 0.024993 0.020335 -vn -0.412229 0.020148 -0.910858 -v 0.005904 0.025377 0.019889 -vn -0.431152 -0.128382 -0.893099 -v 0.005848 0.024932 0.019942 -vn -0.452941 0.065585 -0.889125 -v 0.007002 0.025274 0.019355 -vn -0.476126 -0.078134 -0.875899 -v 0.006933 0.024844 0.019395 -vn -0.485420 0.113627 -0.866866 -v 0.008088 0.025154 0.018760 -vn -0.512857 -0.024587 -0.858122 -v 0.008005 0.024740 0.018787 -vn -0.508232 0.164544 -0.845356 -v 0.009202 0.025012 0.018088 -vn -0.539809 0.032625 -0.841155 -v 0.009107 0.024617 0.018101 -vn -0.521806 0.217910 -0.824763 -v 0.010350 0.024849 0.017341 -vn -0.557263 0.093238 -0.825084 -v 0.010244 0.024475 0.017340 -vn -0.526984 0.274696 -0.804257 -v 0.011537 0.024664 0.016519 -vn -0.567990 0.158861 -0.807558 -v 0.011421 0.024314 0.016505 -vn -0.065681 0.896673 -0.437794 -v 0.014105 0.026134 0.016638 -vn -0.108544 0.868869 -0.482996 -v 0.014021 0.026081 0.016554 -vn 0.151993 0.833409 -0.531345 -v -0.013028 0.026228 0.017056 -vn 0.154940 0.822297 -0.547560 -v -0.011444 0.026661 0.018173 -vn 0.152748 0.811756 -0.563667 -v -0.009981 0.027025 0.019115 -vn 0.146886 0.801810 -0.579245 -v -0.008600 0.027332 0.019910 -vn 0.137496 0.793592 -0.592711 -v -0.007480 0.027552 0.020481 -vn 0.125443 0.785842 -0.605572 -v -0.006346 0.027746 0.020986 -vn 0.110196 0.778799 -0.617518 -v -0.005242 0.027906 0.021404 -vn 0.092082 0.772661 -0.628105 -v -0.004161 0.028035 0.021740 -vn 0.076229 0.767608 -0.636370 -v -0.003094 0.028133 0.021998 -vn 0.062841 0.765800 -0.640001 -v -0.002886 0.028149 0.022040 -vn 0.045798 0.763405 -0.644294 -v -0.001919 0.028209 0.022196 -vn 0.023352 0.761380 -0.647885 -v -0.000962 0.028244 0.022289 -vn 0.000254 0.760675 -0.649132 -v -0.000007 0.028256 0.022320 -vn -0.022943 0.761317 -0.647974 -v 0.000951 0.028244 0.022289 -vn -0.045147 0.763224 -0.644555 -v 0.001920 0.028209 0.022195 -vn -0.065699 0.766186 -0.639252 -v 0.002807 0.028155 0.022055 -vn -0.084980 0.770439 -0.631825 -v 0.003782 0.028073 0.021840 -vn -0.102554 0.775633 -0.622797 -v 0.004763 0.027967 0.021562 -vn -0.117688 0.781591 -0.612589 -v 0.005750 0.027836 0.021221 -vn -0.130815 0.788337 -0.601175 -v 0.006745 0.027681 0.020817 -vn -0.141543 0.796557 -0.587761 -v 0.007938 0.027465 0.020256 -vn -0.149392 0.804917 -0.574274 -v 0.009096 0.027226 0.019636 -vn -0.153890 0.813432 -0.560934 -v 0.010266 0.026958 0.018940 -vn -0.155356 0.821977 -0.547921 -v 0.011450 0.026660 0.018169 -vn -0.154956 0.830365 -0.535240 -v 0.012655 0.026333 0.017327 -vn -0.152860 0.835925 -0.527128 -v 0.013882 0.025981 0.016419 -vn -0.194905 0.802786 -0.563512 -v 0.013718 0.025844 0.016269 -vn -0.236645 0.764802 -0.599231 -v 0.013665 0.025795 0.016221 -vn -0.274156 0.716712 -0.641220 -v 0.013457 0.025577 0.016047 -vn -0.308456 0.681393 -0.663746 -v 0.013431 0.025548 0.016027 -vn -0.351199 0.629963 -0.692680 -v 0.013260 0.025331 0.015899 -vn -0.388252 0.579227 -0.716769 -v 0.013167 0.025199 0.015836 -vn -0.425049 0.525093 -0.737300 -v 0.013078 0.025060 0.015779 -vn -0.459871 0.466526 -0.755561 -v 0.012933 0.024805 0.015699 -vn 0.475611 0.400258 -0.783318 -v -0.012052 0.024932 0.016307 -vn 0.477132 0.339240 -0.810717 -v -0.010477 0.025213 0.017387 -vn 0.463332 0.283158 -0.839729 -v -0.009050 0.025440 0.018290 -vn 0.439271 0.232472 -0.867754 -v -0.007727 0.025624 0.019046 -vn 0.406812 0.192724 -0.892951 -v -0.006672 0.025750 0.019583 -vn 0.367490 0.155834 -0.916879 -v -0.005621 0.025856 0.020055 -vn 0.320053 0.123325 -0.939339 -v -0.004613 0.025940 0.020442 -vn 0.265499 0.095713 -0.959348 -v -0.003642 0.026005 0.020750 -vn 0.218327 0.074790 -0.973006 -v -0.002695 0.026052 0.020984 -vn 0.179368 0.067861 -0.981439 -v -0.002512 0.026059 0.021022 -vn 0.130659 0.055590 -0.989868 -v -0.001665 0.026086 0.021163 -vn 0.066513 0.046957 -0.996680 -v -0.000833 0.026102 0.021246 -vn 0.000830 0.043985 -0.999032 -v -0.000006 0.026107 0.021274 -vn -0.065146 0.046781 -0.996779 -v 0.000824 0.026102 0.021247 -vn -0.128555 0.055245 -0.990162 -v 0.001666 0.026086 0.021163 -vn -0.187720 0.068086 -0.979860 -v 0.002443 0.026062 0.021036 -vn -0.244073 0.086702 -0.965873 -v 0.003305 0.026023 0.020841 -vn -0.296349 0.109956 -0.948729 -v 0.004181 0.025971 0.020587 -vn -0.342559 0.137200 -0.929424 -v 0.005075 0.025904 0.020273 -vn -0.383934 0.168294 -0.907894 -v 0.005989 0.025821 0.019898 -vn -0.420077 0.207922 -0.883348 -v 0.007101 0.025701 0.019372 -vn -0.448299 0.249559 -0.858340 -v 0.008199 0.025561 0.018786 -vn -0.467289 0.293391 -0.834004 -v 0.009325 0.025398 0.018122 -vn -0.477573 0.338969 -0.810570 -v 0.010483 0.025212 0.017383 -vn -0.481420 0.385036 -0.787389 -v 0.011678 0.025001 0.016570 -vn -0.489950 0.413332 -0.767532 -v 0.012913 0.024768 0.015689 -vn -0.518769 0.354360 -0.778015 -v 0.012767 0.024457 0.015630 -vn -0.545040 0.292305 -0.785805 -v 0.012734 0.024378 0.015620 -vn -0.566476 0.227512 -0.792050 -v 0.012642 0.024134 0.015602 -vn -0.587525 0.163693 -0.792477 -v 0.012575 0.023927 0.015601 -vn -0.596831 0.041611 -0.801287 -v 0.011329 0.023957 0.016527 -vn -0.609478 0.095901 -0.786981 -v 0.012540 0.023802 0.015607 -vn -0.429300 0.897748 0.098742 -v 0.016315 0.026001 -0.014458 -vn -0.462091 0.876813 0.132935 -v 0.016247 0.025957 -0.014395 -vn -0.483422 0.870885 0.088672 -v 0.017786 0.026575 -0.012329 -vn -0.675222 0.609362 0.415636 -v 0.015343 0.025043 -0.013824 -vn -0.694858 0.561613 0.449180 -v 0.015291 0.024971 -0.013809 -vn -0.719318 0.566797 0.401651 -v 0.015398 0.025016 -0.013687 -vn -0.954406 0.145473 -0.260665 -v 0.019162 0.025523 0.005848 -vn -0.843166 0.457159 -0.282979 -v 0.018470 0.025987 0.008452 -vn -0.797750 0.151706 -0.583593 -v 0.015644 0.023946 0.012522 -vn -0.851880 0.169926 -0.495405 -v 0.017096 0.024598 0.010449 -vn -0.839722 0.306397 -0.448317 -v 0.017141 0.025043 0.010584 -vn -0.805505 0.444628 -0.391750 -v 0.017248 0.025466 0.010751 -vn -0.787299 0.565831 -0.244940 -v 0.018658 0.026376 0.008606 -vn -0.754429 0.572280 -0.321455 -v 0.017414 0.025857 0.010946 -vn -0.875637 0.434973 -0.209900 -v 0.019390 0.026379 0.006021 -vn -0.925512 0.295263 -0.237165 -v 0.019244 0.025961 0.005926 -vn -0.743469 0.136396 0.654713 -v 0.014400 0.023388 -0.013937 -vn -0.735301 0.084931 0.672398 -v 0.014273 0.023098 -0.014026 -vn -0.728064 0.033069 0.684711 -v 0.014146 0.022783 -0.014139 -vn -0.784520 0.148665 0.602019 -v 0.015187 0.023741 -0.013074 -vn -0.747315 0.176566 0.640582 -v 0.014408 0.023405 -0.013932 -vn -0.748061 0.234178 0.620940 -v 0.014549 0.023704 -0.013858 -vn -0.736106 0.390082 0.553158 -v 0.014874 0.024315 -0.013772 -vn -0.746792 0.335930 0.573980 -v 0.014723 0.024042 -0.013799 -vn -0.784842 0.302312 0.540954 -v 0.015198 0.024193 -0.013237 -vn -0.750748 0.311757 0.582396 -v 0.014697 0.023994 -0.013805 -vn -0.748987 0.283224 0.599001 -v 0.014683 0.023968 -0.013809 -vn -0.732219 0.429374 0.528672 -v 0.014982 0.024499 -0.013766 -vn -0.760229 0.443382 0.474831 -v 0.015269 0.024622 -0.013444 -vn -0.724157 0.475738 0.499270 -v 0.015028 0.024573 -0.013767 -vn -0.697295 0.530391 0.482147 -v 0.015185 0.024817 -0.013785 -vn -0.586806 0.764556 0.266671 -v 0.015830 0.025615 -0.014065 -vn -0.620045 0.723967 0.302351 -v 0.015661 0.025437 -0.013963 -vn -0.673306 0.692333 0.259489 -v 0.017217 0.026036 -0.011815 -vn -0.642180 0.694259 0.324975 -v 0.015606 0.025375 -0.013933 -vn -0.659308 0.662661 0.355236 -v 0.015540 0.025296 -0.013901 -vn -0.559830 0.794650 0.234782 -v 0.015925 0.025705 -0.014132 -vn -0.585915 0.791128 0.175554 -v 0.017480 0.026334 -0.012065 -vn -0.531879 0.822281 0.202383 -v 0.015992 0.025765 -0.014182 -vn -0.492743 0.854315 0.165381 -v 0.016154 0.025893 -0.014313 -vn -0.394000 0.916766 0.065604 -v 0.016477 0.026087 -0.014616 -vn -0.370551 0.927813 0.043061 -v 0.016496 0.026096 -0.014635 -vn -0.369955 0.927970 -0.044771 -v 0.016496 0.026096 0.014635 -vn -0.391611 0.917373 -0.071192 -v 0.016477 0.026087 0.014616 -vn -0.526008 0.824612 -0.208158 -v 0.015992 0.025765 0.014182 -vn -0.492056 0.853110 -0.173447 -v 0.016154 0.025893 0.014313 -vn -0.477131 0.872829 -0.102546 -v 0.016601 0.026099 0.013961 -vn -0.460339 0.877655 -0.133451 -v 0.016247 0.025957 0.014395 -vn -0.424752 0.899544 -0.102014 -v 0.016315 0.026001 0.014458 -vn -0.584871 0.762929 -0.275436 -v 0.015830 0.025615 0.014065 -vn -0.556493 0.795895 -0.238466 -v 0.015925 0.025705 0.014132 -vn -0.574506 0.793711 -0.199913 -v 0.016315 0.025863 0.013660 -vn -0.659906 0.652067 -0.373272 -v 0.015501 0.025249 0.013884 -vn -0.637402 0.692004 -0.338893 -v 0.015606 0.025375 0.013933 -vn -0.657425 0.694129 -0.293218 -v 0.016073 0.025567 0.013375 -vn -0.614724 0.725224 -0.310105 -v 0.015661 0.025437 0.013963 -vn -0.723159 0.577329 -0.379120 -v 0.015880 0.025217 0.013112 -vn -0.682327 0.609290 -0.403976 -v 0.015343 0.025043 0.013824 -vn -0.698283 0.572425 -0.429803 -v 0.015291 0.024971 0.013809 -vn -0.714154 0.526326 -0.461481 -v 0.015185 0.024817 0.013785 -vn -0.769751 0.446382 -0.456318 -v 0.015743 0.024824 0.012879 -vn -0.728680 0.480101 -0.488394 -v 0.015028 0.024573 0.013767 -vn -0.755495 0.316152 -0.573825 -v 0.014697 0.023994 0.013805 -vn -0.752587 0.343282 -0.561934 -v 0.014723 0.024042 0.013799 -vn -0.795808 0.304647 -0.523336 -v 0.015663 0.024397 0.012680 -vn -0.746445 0.389366 -0.539643 -v 0.014874 0.024315 0.013772 -vn -0.738306 0.440266 -0.510951 -v 0.014982 0.024499 0.013766 -vn -0.756269 0.236167 -0.610149 -v 0.014549 0.023704 0.013858 -vn -0.756851 0.293828 -0.583816 -v 0.014683 0.023968 0.013809 -vn -0.741383 0.081981 -0.666056 -v 0.014273 0.023098 0.014026 -vn -0.753419 0.147737 -0.640728 -v 0.014400 0.023388 0.013937 -vn -0.754043 0.186221 -0.629873 -v 0.014408 0.023405 0.013932 -vn -0.712538 0.022320 -0.701279 -v 0.014146 0.022783 0.014139 -vn -0.842386 0.147337 0.518341 -v 0.016709 0.024424 -0.011059 -vn -0.899054 0.144860 0.413179 -v 0.017964 0.024987 -0.008872 -vn -0.943567 0.145520 0.297497 -v 0.018935 0.025421 -0.006547 -vn -0.972192 0.144015 0.184667 -v 0.019605 0.025722 -0.004120 -vn -0.987070 0.144045 0.070318 -v 0.019967 0.025884 -0.001628 -vn -0.988055 0.148793 -0.040092 -v 0.020013 0.025905 0.000890 -vn -0.978095 0.143718 -0.150582 -v 0.019744 0.025784 0.003395 -vn -0.944878 0.295722 -0.140553 -v 0.019837 0.026220 0.003440 -vn -0.954757 0.295119 -0.036661 -v 0.020112 0.026340 0.000902 -vn -0.953019 0.295274 0.067593 -v 0.020064 0.026319 -0.001650 -vn -0.939706 0.296141 0.171037 -v 0.019696 0.026158 -0.004175 -vn -0.914916 0.297760 0.272520 -v 0.019013 0.025860 -0.006634 -vn -0.878843 0.300133 0.370883 -v 0.018025 0.025429 -0.008988 -vn -0.831787 0.303216 0.464964 -v 0.016747 0.024870 -0.011201 -vn -0.892253 0.434698 -0.122157 -v 0.019994 0.026636 0.003495 -vn -0.900416 0.433863 -0.031856 -v 0.020273 0.026755 0.000916 -vn -0.898981 0.434034 0.058713 -v 0.020225 0.026735 -0.001677 -vn -0.887969 0.435212 0.148663 -v 0.019850 0.026575 -0.004242 -vn -0.867445 0.437395 0.237119 -v 0.019154 0.026278 -0.006740 -vn -0.837499 0.440619 0.323187 -v 0.018148 0.025850 -0.009131 -vn -0.798296 0.444898 0.405943 -v 0.016846 0.025295 -0.011377 -vn -0.805652 0.565988 -0.174876 -v 0.019595 0.026767 0.006130 -vn -0.819674 0.563850 -0.101035 -v 0.020210 0.027023 0.003559 -vn -0.826103 0.562904 -0.026342 -v 0.020495 0.027142 0.000933 -vn -0.824967 0.563092 0.048538 -v 0.020446 0.027122 -0.001707 -vn -0.816283 0.564413 0.122962 -v 0.020064 0.026962 -0.004319 -vn -0.800049 0.566916 0.196285 -v 0.019355 0.026667 -0.006862 -vn -0.776314 0.570612 0.267842 -v 0.018330 0.026239 -0.009296 -vn -0.745003 0.575410 0.337454 -v 0.017004 0.025686 -0.011584 -vn -0.680979 0.690293 -0.244464 -v 0.017634 0.026207 0.011164 -vn -0.702519 0.685762 -0.190257 -v 0.018901 0.026726 0.008776 -vn -0.718449 0.682456 -0.134478 -v 0.019855 0.027116 0.006251 -vn -0.728773 0.680339 -0.077648 -v 0.020481 0.027373 0.003629 -vn -0.733528 0.679358 -0.020246 -v 0.020771 0.027492 0.000951 -vn -0.732686 0.679544 0.037290 -v 0.020721 0.027471 -0.001740 -vn -0.726253 0.680900 0.094504 -v 0.020333 0.027312 -0.004404 -vn -0.714285 0.683382 0.150949 -v 0.019611 0.027016 -0.006997 -vn -0.696723 0.687080 0.206153 -v 0.018567 0.026589 -0.009481 -vn -0.625171 0.654438 0.425290 -v 0.015501 0.025249 -0.013884 -vn -0.590445 0.789884 -0.165705 -v 0.017905 0.026506 0.011400 -vn -0.604489 0.786126 -0.128833 -v 0.019194 0.027027 0.008960 -vn -0.614879 0.783352 -0.091009 -v 0.020164 0.027420 0.006381 -vn -0.621620 0.781556 -0.052534 -v 0.020801 0.027677 0.003704 -vn -0.624706 0.780740 -0.013694 -v 0.021097 0.027797 0.000971 -vn -0.624161 0.780889 0.025221 -v 0.021046 0.027776 -0.001777 -vn -0.619971 0.782015 0.063936 -v 0.020650 0.027616 -0.004495 -vn -0.612147 0.784116 0.102164 -v 0.019916 0.027319 -0.007143 -vn -0.600693 0.787194 0.139619 -v 0.018854 0.026890 -0.009680 -vn -0.485613 0.870229 -0.082958 -v 0.018218 0.026748 0.011648 -vn -0.492378 0.867992 -0.064443 -v 0.019529 0.027274 0.009153 -vn -0.497379 0.866340 -0.045492 -v 0.020516 0.027670 0.006518 -vn -0.500639 0.865258 -0.026257 -v 0.021163 0.027929 0.003783 -vn -0.502103 0.864781 -0.006842 -v 0.021463 0.028050 0.000991 -vn -0.501836 0.864871 0.012600 -v 0.021412 0.028029 -0.001814 -vn -0.499806 0.865548 0.031946 -v 0.021010 0.027868 -0.004591 -vn -0.496031 0.866802 0.051064 -v 0.020263 0.027568 -0.007296 -vn -0.490503 0.868638 0.069824 -v 0.019184 0.027135 -0.009889 -vn -0.513221 0.438535 -0.737761 -v 0.013766 0.024499 0.014982 -vn -0.645877 0.174032 -0.743341 -v 0.013932 0.023405 0.014408 -vn -0.661452 0.131409 -0.738385 -v 0.013937 0.023388 0.014400 -vn -0.623662 0.154365 -0.766301 -v 0.013447 0.023594 0.014858 -vn -0.693086 0.026385 -0.720372 -v 0.014139 0.022783 0.014146 -vn -0.678649 0.081454 -0.729932 -v 0.014026 0.023098 0.014273 -vn -0.580386 0.334088 -0.742656 -v 0.013799 0.024042 0.014723 -vn -0.587675 0.309371 -0.747615 -v 0.013805 0.023994 0.014697 -vn -0.571076 0.292907 -0.766862 -v 0.013614 0.024047 0.014864 -vn -0.606634 0.276923 -0.745191 -v 0.013809 0.023968 0.014683 -vn -0.628808 0.232132 -0.742102 -v 0.013858 0.023704 0.014549 -vn -0.532588 0.401752 -0.744947 -v 0.013769 0.024375 0.014908 -vn -0.571178 0.385736 -0.724544 -v 0.013772 0.024315 0.014874 -vn -0.430545 0.572259 -0.697962 -v 0.013809 0.024971 0.015291 -vn -0.462733 0.527169 -0.712720 -v 0.013785 0.024817 0.015185 -vn -0.492840 0.476889 -0.727795 -v 0.013767 0.024573 0.015028 -vn -0.238222 0.796004 -0.556442 -v 0.014132 0.025705 0.015926 -vn -0.275308 0.763210 -0.584565 -v 0.014065 0.025615 0.015830 -vn -0.312397 0.724684 -0.614200 -v 0.013963 0.025437 0.015661 -vn -0.342394 0.690782 -0.636857 -v 0.013933 0.025375 0.015606 -vn -0.374677 0.653654 -0.657536 -v 0.013884 0.025249 0.015501 -vn -0.407326 0.607815 -0.681650 -v 0.013824 0.025043 0.015343 -vn -0.044884 0.927985 -0.369905 -v 0.014635 0.026096 0.016496 -vn -0.066866 0.917573 -0.391904 -v 0.014616 0.026087 0.016477 -vn -0.100806 0.897666 -0.428991 -v 0.014458 0.026001 0.016315 -vn -0.134930 0.877518 -0.460170 -v 0.014395 0.025957 0.016247 -vn -0.170710 0.854008 -0.491456 -v 0.014313 0.025893 0.016154 -vn -0.209050 0.823970 -0.526660 -v 0.014182 0.025765 0.015992 -vn -0.034121 -0.712023 0.701327 -v -0.022788 0.014142 -0.014142 -vn -0.847392 -0.379471 -0.371388 -v -0.025389 0.015104 0.015104 -vn -0.905253 -0.302848 -0.297994 -v -0.025616 0.015388 0.015388 -vn -0.872732 -0.477829 -0.100087 -v -0.026099 0.016601 0.013961 -vn -0.707864 -0.504438 -0.494440 -v -0.025042 0.014804 0.014804 -vn -0.791571 -0.435784 -0.428378 -v -0.025351 0.015064 0.015064 -vn -0.793669 -0.574623 -0.199746 -v -0.025863 0.016315 0.013660 -vn -0.821278 -0.406812 -0.400008 -v -0.025362 0.015076 0.015076 -vn -0.551347 -0.597865 -0.581871 -v -0.024653 0.014567 0.014567 -vn -0.618238 -0.562056 -0.549432 -v -0.024673 0.014578 0.014578 -vn -0.578730 -0.720688 -0.381681 -v -0.025217 0.015880 0.013112 -vn -0.416599 -0.658084 -0.627193 -v -0.024224 0.014383 0.014383 -vn -0.477028 -0.636022 -0.606565 -v -0.024247 0.014392 0.014392 -vn -0.447662 -0.766866 -0.459908 -v -0.024824 0.015743 0.012879 -vn -0.265245 -0.696717 -0.666507 -v -0.023745 0.014247 0.014247 -vn -0.330655 -0.682297 -0.652027 -v -0.023781 0.014255 0.014255 -vn -0.305327 -0.793305 -0.526728 -v -0.024397 0.015663 0.012680 -vn -0.151549 -0.796300 -0.585610 -v -0.023946 0.015644 0.012522 -vn -0.177414 -0.711311 -0.680119 -v -0.023285 0.014171 0.014171 -vn -0.107118 -0.716161 -0.689666 -v -0.023243 0.014166 0.014166 -vn -0.108125 -0.702192 0.703730 -v -0.023285 0.014171 -0.014171 -vn -0.149081 -0.781952 0.605248 -v -0.023741 0.015187 -0.013074 -vn -0.188544 -0.688566 0.700234 -v -0.023302 0.014172 -0.014172 -vn -0.264774 -0.672936 0.690690 -v -0.023745 0.014247 -0.014247 -vn -0.578354 -0.713556 0.395403 -v -0.025016 0.015398 -0.013687 -vn -0.578552 -0.572128 0.581332 -v -0.024653 0.014567 -0.014567 -vn -0.478315 -0.611583 0.630223 -v -0.024247 0.014392 -0.014392 -vn -0.794120 -0.571165 0.207714 -v -0.025661 0.015815 -0.014261 -vn -0.813124 -0.409509 0.413681 -v -0.025351 0.015064 -0.015064 -vn -0.734109 -0.472455 0.487720 -v -0.025048 0.014808 -0.014808 -vn -0.873219 -0.475804 0.105353 -v -0.025895 0.016092 -0.014577 -vn -0.916229 -0.282938 0.283672 -v -0.025608 0.015375 -0.015375 -vn -0.879555 -0.335619 0.337259 -v -0.025589 0.015348 -0.015348 -vn -0.945758 -0.229775 0.229663 -v -0.025758 0.015647 -0.015647 -vn -0.147341 -0.842385 0.518342 -v -0.024424 0.016709 -0.011059 -vn -0.144829 -0.899054 0.413190 -v -0.024987 0.017964 -0.008872 -vn -0.145507 -0.943571 0.297491 -v -0.025421 0.018935 -0.006547 -vn -0.144047 -0.972188 0.184666 -v -0.025722 0.019605 -0.004120 -vn -0.144049 -0.987069 0.070320 -v -0.025884 0.019967 -0.001628 -vn -0.148796 -0.988055 -0.040090 -v -0.025905 0.020013 0.000890 -vn -0.143748 -0.978092 -0.150573 -v -0.025784 0.019744 0.003395 -vn -0.143459 -0.953209 -0.266104 -v -0.025523 0.019162 0.005848 -vn -0.150263 -0.911249 -0.383467 -v -0.025126 0.018275 0.008212 -vn -0.151073 -0.859151 -0.488913 -v -0.024598 0.017096 0.010449 -vn -0.032784 -0.696367 -0.716937 -v -0.022788 0.014142 0.014142 -vn -0.302037 -0.846563 -0.438297 -v -0.025043 0.017141 0.010584 -vn -0.299176 -0.890587 -0.342563 -v -0.025567 0.018341 0.008320 -vn -0.297101 -0.923431 -0.242910 -v -0.025961 0.019244 0.005926 -vn -0.295759 -0.944867 -0.140548 -v -0.026220 0.019837 0.003440 -vn -0.295152 -0.954747 -0.036657 -v -0.026340 0.020112 0.000902 -vn -0.295270 -0.953020 0.067591 -v -0.026319 0.020064 -0.001650 -vn -0.296146 -0.939704 0.171039 -v -0.026158 0.019696 -0.004175 -vn -0.297736 -0.914922 0.272528 -v -0.025860 0.019013 -0.006634 -vn -0.300095 -0.878852 0.370893 -v -0.025429 0.018025 -0.008988 -vn -0.303226 -0.831785 0.464961 -v -0.024870 0.016747 -0.011201 -vn -0.303980 -0.781712 0.544538 -v -0.024193 0.015198 -0.013237 -vn -0.331626 -0.657416 0.676630 -v -0.023781 0.014255 -0.014255 -vn -0.443357 -0.810648 -0.382471 -v -0.025466 0.017248 0.010751 -vn -0.439447 -0.847265 -0.298377 -v -0.025987 0.018470 0.008452 -vn -0.436539 -0.874518 -0.211311 -v -0.026379 0.019390 0.006021 -vn -0.434699 -0.892252 -0.122158 -v -0.026636 0.019994 0.003495 -vn -0.433880 -0.900408 -0.031849 -v -0.026755 0.020273 0.000916 -vn -0.434029 -0.898984 0.058713 -v -0.026735 0.020225 -0.001677 -vn -0.435202 -0.887974 0.148666 -v -0.026575 0.019850 -0.004242 -vn -0.437398 -0.867443 0.237121 -v -0.026278 0.019154 -0.006740 -vn -0.440634 -0.837494 0.323181 -v -0.025850 0.018148 -0.009131 -vn -0.444892 -0.798302 0.405937 -v -0.025295 0.016846 -0.011377 -vn -0.447141 -0.757602 0.475503 -v -0.024622 0.015269 -0.013444 -vn -0.573824 -0.755001 -0.317332 -v -0.025857 0.017414 0.010946 -vn -0.569300 -0.784080 -0.247216 -v -0.026376 0.018658 0.008606 -vn -0.565977 -0.805660 -0.174879 -v -0.026767 0.019595 0.006130 -vn -0.563792 -0.819712 -0.101047 -v -0.027023 0.020210 0.003559 -vn -0.562848 -0.826140 -0.026343 -v -0.027142 0.020495 0.000933 -vn -0.563078 -0.824977 0.048537 -v -0.027122 0.020446 -0.001707 -vn -0.564440 -0.816265 0.122957 -v -0.026962 0.020064 -0.004319 -vn -0.566925 -0.800044 0.196282 -v -0.026667 0.019355 -0.006862 -vn -0.570638 -0.776298 0.267831 -v -0.026239 0.018330 -0.009296 -vn -0.575558 -0.745131 0.336916 -v -0.025686 0.017004 -0.011584 -vn -0.412525 -0.635426 0.652730 -v -0.024211 0.014379 -0.014379 -vn -0.695131 -0.656144 -0.293714 -v -0.025567 0.016073 0.013375 -vn -0.690296 -0.680975 -0.244467 -v -0.026207 0.017634 0.011164 -vn -0.685776 -0.702506 -0.190251 -v -0.026726 0.018901 0.008776 -vn -0.682473 -0.718436 -0.134466 -v -0.027116 0.019855 0.006251 -vn -0.680338 -0.728774 -0.077644 -v -0.027373 0.020481 0.003629 -vn -0.679363 -0.733523 -0.020244 -v -0.027492 0.020771 0.000951 -vn -0.679529 -0.732701 0.037286 -v -0.027471 0.020721 -0.001740 -vn -0.680876 -0.726275 0.094506 -v -0.027312 0.020333 -0.004404 -vn -0.683383 -0.714284 0.150949 -v -0.027016 0.019611 -0.006997 -vn -0.687083 -0.696720 0.206150 -v -0.026589 0.018567 -0.009481 -vn -0.691933 -0.673654 0.259652 -v -0.026036 0.017217 -0.011815 -vn -0.695415 -0.650769 0.304791 -v -0.025365 0.015582 -0.013962 -vn -0.789900 -0.590426 -0.165696 -v -0.026506 0.017905 0.011400 -vn -0.786118 -0.604498 -0.128840 -v -0.027027 0.019194 0.008960 -vn -0.783328 -0.614909 -0.091018 -v -0.027420 0.020164 0.006381 -vn -0.781556 -0.621619 -0.052536 -v -0.027677 0.020801 0.003704 -vn -0.780785 -0.624650 -0.013682 -v -0.027796 0.021097 0.000971 -vn -0.780874 -0.624179 0.025223 -v -0.027776 0.021046 -0.001777 -vn -0.781984 -0.620010 0.063941 -v -0.027616 0.020650 -0.004495 -vn -0.784111 -0.612154 0.102163 -v -0.027319 0.019916 -0.007143 -vn -0.787201 -0.600686 0.139614 -v -0.026890 0.018854 -0.009680 -vn -0.791285 -0.585574 0.175988 -v -0.026334 0.017480 -0.012065 -vn -0.679841 -0.510409 0.526592 -v -0.025019 0.014788 -0.014788 -vn -0.870246 -0.485587 -0.082932 -v -0.026748 0.018218 0.011648 -vn -0.867975 -0.492407 -0.064458 -v -0.027274 0.019529 0.009153 -vn -0.866334 -0.497388 -0.045494 -v -0.027670 0.020516 0.006518 -vn -0.865279 -0.500602 -0.026250 -v -0.027929 0.021163 0.003783 -vn -0.864774 -0.502115 -0.006841 -v -0.028050 0.021463 0.000991 -vn -0.864872 -0.501835 0.012608 -v -0.028029 0.021412 -0.001814 -vn -0.865551 -0.499801 0.031937 -v -0.027868 0.021010 -0.004591 -vn -0.866820 -0.496000 0.051050 -v -0.027568 0.020263 -0.007296 -vn -0.868618 -0.490537 0.069831 -v -0.027135 0.019184 -0.009889 -vn -0.871098 -0.483152 0.088047 -v -0.026575 0.017786 -0.012329 -vn -0.523683 -0.425771 -0.737886 -v -0.025060 0.013078 0.015779 -vn -0.579129 -0.392340 -0.714618 -v -0.025199 0.013167 0.015836 -vn -0.579487 -0.412869 -0.702662 -v -0.024871 0.014076 0.015052 -vn -0.305637 -0.567592 -0.764477 -v -0.024047 0.013614 0.014864 -vn -0.155577 -0.624757 -0.765163 -v -0.023594 0.013447 0.014858 -vn -0.796393 -0.216813 -0.564580 -v -0.025516 0.014668 0.015456 -vn -0.697216 -0.317999 -0.642469 -v -0.025221 0.014359 0.015229 -vn -0.095828 -0.609501 -0.786973 -v -0.023802 0.012540 0.015607 -vn -0.163625 -0.587544 -0.792476 -v -0.023927 0.012575 0.015601 -vn -0.227484 -0.566486 -0.792051 -v -0.024134 0.012642 0.015602 -vn -0.292459 -0.544975 -0.785793 -v -0.024378 0.012734 0.015620 -vn -0.354302 -0.518713 -0.778079 -v -0.024458 0.012767 0.015630 -vn -0.449933 -0.495825 -0.742777 -v -0.024477 0.013826 0.014929 -vn -0.413499 -0.490511 -0.767084 -v -0.024768 0.012913 0.015689 -vn -0.467206 -0.458790 -0.755798 -v -0.024805 0.012933 0.015699 -vn -0.632311 -0.354182 -0.689012 -v -0.025331 0.013260 0.015899 -vn -0.680366 -0.316552 -0.660982 -v -0.025548 0.013431 0.016027 -vn -0.727239 -0.275396 -0.628713 -v -0.025577 0.013457 0.016047 -vn -0.787499 -0.213260 -0.578243 -v -0.025844 0.013718 0.016269 -vn -0.873073 -0.109748 -0.475078 -v -0.025749 0.014993 0.015727 -vn -0.835892 -0.153693 -0.526938 -v -0.025981 0.013882 0.016419 -vn -0.881049 -0.089867 -0.464409 -v -0.026081 0.014021 0.016554 -vn -0.897769 0.098758 0.429252 -v -0.026000 -0.014458 -0.016315 -vn -0.876837 0.132929 0.462046 -v -0.025957 -0.014395 -0.016247 -vn -0.870912 0.088643 0.483379 -v -0.026575 -0.012329 -0.017786 -vn -0.609456 0.415683 0.675108 -v -0.025043 -0.013824 -0.015343 -vn -0.561686 0.449218 0.694774 -v -0.024971 -0.013809 -0.015291 -vn -0.566812 0.401748 0.719251 -v -0.025016 -0.013687 -0.015398 -vn -0.872446 -0.099907 0.478390 -v -0.026099 0.013961 -0.016601 -vn -0.695198 -0.294405 0.655763 -v -0.025567 0.013375 -0.016073 -vn -0.578652 -0.381936 0.720616 -v -0.025217 0.013112 -0.015880 -vn -0.447746 -0.459952 0.766791 -v -0.024824 0.012879 -0.015743 -vn -0.305290 -0.526834 0.793249 -v -0.024397 0.012680 -0.015663 -vn -0.153401 -0.583701 0.797346 -v -0.023946 0.012522 -0.015644 -vn -0.024368 0.694678 0.718908 -v -0.022783 -0.014139 -0.014146 -vn -0.080689 0.680211 0.728562 -v -0.023098 -0.014026 -0.014273 -vn -0.129000 0.660805 0.739389 -v -0.023388 -0.013937 -0.014400 -vn -0.149279 0.596025 0.788968 -v -0.023741 -0.013074 -0.015187 -vn -0.177563 0.640272 0.747344 -v -0.023405 -0.013932 -0.014408 -vn -0.234229 0.620894 0.748082 -v -0.023704 -0.013858 -0.014549 -vn -0.390001 0.553124 0.736175 -v -0.024315 -0.013772 -0.014874 -vn -0.335894 0.573989 0.746801 -v -0.024042 -0.013799 -0.014723 -vn -0.302322 0.540942 0.784846 -v -0.024193 -0.013237 -0.015198 -vn -0.311719 0.582423 0.750743 -v -0.023994 -0.013805 -0.014697 -vn -0.283226 0.599021 0.748971 -v -0.023968 -0.013809 -0.014683 -vn -0.429534 0.528612 0.732168 -v -0.024499 -0.013766 -0.014982 -vn -0.443444 0.474830 0.760193 -v -0.024622 -0.013444 -0.015269 -vn -0.475980 0.499202 0.724044 -v -0.024573 -0.013767 -0.015028 -vn -0.530294 0.482158 0.697361 -v -0.024817 -0.013785 -0.015185 -vn -0.764610 0.266628 0.586755 -v -0.025615 -0.014065 -0.015830 -vn -0.724014 0.302292 0.620019 -v -0.025437 -0.013963 -0.015661 -vn -0.692326 0.259495 0.673310 -v -0.026036 -0.011815 -0.017217 -vn -0.694252 0.324955 0.642198 -v -0.025375 -0.013933 -0.015606 -vn -0.662479 0.355233 0.659493 -v -0.025296 -0.013901 -0.015540 -vn -0.794718 0.234716 0.559760 -v -0.025705 -0.014132 -0.015925 -vn -0.791140 0.175545 0.585903 -v -0.026334 -0.012065 -0.017480 -vn -0.822319 0.202325 0.531842 -v -0.025765 -0.014182 -0.015992 -vn -0.854307 0.165397 0.492751 -v -0.025893 -0.014313 -0.016154 -vn -0.916452 0.066265 0.394619 -v -0.026087 -0.014616 -0.016477 -vn -0.927593 0.043561 0.371043 -v -0.026096 -0.014635 -0.016496 -vn -0.149322 0.510992 0.846517 -v -0.024424 -0.011059 -0.016709 -vn -0.147981 0.415456 0.897495 -v -0.024987 -0.008872 -0.017964 -vn -0.144383 0.307592 0.940500 -v -0.025421 -0.006547 -0.018935 -vn -0.142803 0.192547 0.970841 -v -0.025722 -0.004120 -0.019605 -vn -0.145318 0.069679 0.986928 -v -0.025884 -0.001628 -0.019967 -vn -0.144652 -0.046616 0.988384 -v -0.025905 0.000890 -0.020013 -vn -0.144898 -0.160984 0.976263 -v -0.025784 0.003395 -0.019744 -vn -0.150790 -0.268974 0.951270 -v -0.025523 0.005848 -0.019162 -vn -0.145336 -0.375110 0.915516 -v -0.025126 0.008212 -0.018275 -vn -0.146078 -0.481325 0.864285 -v -0.024598 0.010449 -0.017096 -vn -0.302035 -0.438298 0.846563 -v -0.025043 0.010584 -0.017141 -vn -0.299176 -0.342563 0.890587 -v -0.025567 0.008320 -0.018341 -vn -0.297101 -0.242911 0.923431 -v -0.025961 0.005926 -0.019244 -vn -0.295759 -0.140548 0.944867 -v -0.026220 0.003440 -0.019837 -vn -0.295149 -0.036657 0.954748 -v -0.026340 0.000902 -0.020112 -vn -0.295270 0.067590 0.953020 -v -0.026319 -0.001650 -0.020064 -vn -0.296146 0.171038 0.939704 -v -0.026158 -0.004175 -0.019696 -vn -0.297735 0.272528 0.914922 -v -0.025860 -0.006634 -0.019013 -vn -0.300094 0.370893 0.878853 -v -0.025429 -0.008988 -0.018025 -vn -0.303223 0.464961 0.831785 -v -0.024870 -0.011201 -0.016747 -vn -0.443357 -0.382472 0.810648 -v -0.025466 0.010751 -0.017248 -vn -0.439451 -0.298375 0.847263 -v -0.025987 0.008452 -0.018470 -vn -0.436542 -0.211310 0.874517 -v -0.026379 0.006021 -0.019390 -vn -0.434699 -0.122158 0.892252 -v -0.026636 0.003495 -0.019994 -vn -0.433876 -0.031849 0.900409 -v -0.026755 0.000916 -0.020273 -vn -0.434032 0.058713 0.898982 -v -0.026735 -0.001677 -0.020225 -vn -0.435202 0.148665 0.887974 -v -0.026575 -0.004242 -0.019850 -vn -0.437399 0.237121 0.867442 -v -0.026278 -0.006740 -0.019154 -vn -0.440634 0.323181 0.837494 -v -0.025850 -0.009131 -0.018148 -vn -0.444893 0.405937 0.798302 -v -0.025295 -0.011377 -0.016846 -vn -0.573826 -0.317331 0.755000 -v -0.025857 0.010946 -0.017414 -vn -0.569301 -0.247216 0.784080 -v -0.026376 0.008606 -0.018658 -vn -0.565976 -0.174878 0.805660 -v -0.026767 0.006130 -0.019595 -vn -0.563792 -0.101046 0.819712 -v -0.027023 0.003559 -0.020210 -vn -0.562851 -0.026343 0.826139 -v -0.027142 0.000933 -0.020495 -vn -0.563081 0.048537 0.824975 -v -0.027122 -0.001707 -0.020446 -vn -0.564440 0.122957 0.816265 -v -0.026962 -0.004319 -0.020064 -vn -0.566924 0.196282 0.800044 -v -0.026667 -0.006862 -0.019355 -vn -0.570638 0.267831 0.776298 -v -0.026239 -0.009296 -0.018330 -vn -0.575428 0.337442 0.744994 -v -0.025686 -0.011584 -0.017004 -vn -0.690297 -0.244467 0.680975 -v -0.026207 0.011164 -0.017634 -vn -0.685777 -0.190251 0.702506 -v -0.026726 0.008776 -0.018901 -vn -0.682472 -0.134465 0.718436 -v -0.027116 0.006251 -0.019855 -vn -0.680338 -0.077644 0.728774 -v -0.027373 0.003629 -0.020481 -vn -0.679365 -0.020243 0.733521 -v -0.027492 0.000951 -0.020771 -vn -0.679529 0.037286 0.732701 -v -0.027471 -0.001740 -0.020721 -vn -0.680876 0.094506 0.726275 -v -0.027312 -0.004404 -0.020333 -vn -0.683383 0.150949 0.714284 -v -0.027016 -0.006997 -0.019611 -vn -0.687083 0.206150 0.696720 -v -0.026589 -0.009481 -0.018567 -vn -0.654223 0.425071 0.625545 -v -0.025249 -0.013884 -0.015501 -vn -0.794030 -0.199045 0.574368 -v -0.025863 0.013660 -0.016315 -vn -0.789900 -0.165696 0.590427 -v -0.026506 0.011400 -0.017905 -vn -0.786117 -0.128841 0.604500 -v -0.027027 0.008960 -0.019194 -vn -0.783329 -0.091018 0.614908 -v -0.027420 0.006381 -0.020164 -vn -0.781556 -0.052536 0.621619 -v -0.027677 0.003704 -0.020801 -vn -0.780784 -0.013683 0.624652 -v -0.027796 0.000971 -0.021097 -vn -0.780874 0.025223 0.624179 -v -0.027776 -0.001777 -0.021046 -vn -0.781984 0.063941 0.620010 -v -0.027616 -0.004495 -0.020650 -vn -0.784110 0.102164 0.612156 -v -0.027319 -0.007143 -0.019916 -vn -0.787199 0.139615 0.600687 -v -0.026890 -0.009680 -0.018854 -vn -0.870246 -0.082932 0.485587 -v -0.026748 0.011648 -0.018218 -vn -0.867975 -0.064458 0.492407 -v -0.027274 0.009153 -0.019529 -vn -0.866334 -0.045494 0.497388 -v -0.027670 0.006518 -0.020516 -vn -0.865278 -0.026251 0.500604 -v -0.027929 0.003783 -0.021163 -vn -0.864773 -0.006841 0.502116 -v -0.028050 0.000991 -0.021463 -vn -0.864870 0.012608 0.501837 -v -0.028029 -0.001814 -0.021412 -vn -0.865550 0.031938 0.499803 -v -0.027868 -0.004591 -0.021010 -vn -0.866820 0.051051 0.496001 -v -0.027568 -0.007296 -0.020263 -vn -0.868618 0.069831 0.490537 -v -0.027135 -0.009889 -0.019184 -vn -0.163049 0.590220 -0.790605 -v -0.023927 -0.012575 0.015601 -vn -0.228416 0.567766 -0.790866 -v -0.024134 -0.012642 0.015602 -vn -0.176477 0.562848 -0.807501 -v -0.024261 -0.011790 0.016235 -vn -0.293639 0.543910 -0.786090 -v -0.024378 -0.012734 0.015620 -vn -0.351661 0.519202 -0.778950 -v -0.024458 -0.012767 0.015630 -vn -0.290559 0.523061 -0.801238 -v -0.024603 -0.011910 0.016253 -vn -0.466812 0.460800 -0.754818 -v -0.024805 -0.012933 0.015699 -vn -0.525354 0.425994 -0.736568 -v -0.025060 -0.013078 0.015779 -vn -0.504516 0.421346 -0.753612 -v -0.025243 -0.012216 0.016395 -vn -0.579594 0.389220 -0.715945 -v -0.025199 -0.013167 0.015836 -vn -0.628969 0.352505 -0.692920 -v -0.025331 -0.013260 0.015899 -vn -0.601057 0.360927 -0.713066 -v -0.025533 -0.012398 0.016515 -vn -0.680894 0.313744 -0.661777 -v -0.025548 -0.013431 0.016027 -vn -0.720607 0.278723 -0.634854 -v -0.025577 -0.013457 0.016047 -vn -0.688799 0.295162 -0.662144 -v -0.025796 -0.012596 0.016667 -vn -0.800928 0.197103 -0.565388 -v -0.025844 -0.013718 0.016269 -vn -0.838452 0.153273 -0.522978 -v -0.025981 -0.013882 0.016419 -vn -0.833391 0.152015 -0.531367 -v -0.026228 -0.013028 0.017056 -vn -0.869310 0.110017 -0.481868 -v -0.026081 -0.014021 0.016554 -vn -0.896644 0.062290 -0.438349 -v -0.026134 -0.014105 0.016638 -vn -0.887495 0.076420 -0.454436 -v -0.026391 -0.013256 0.017286 -vn -0.766432 0.225745 -0.601350 -v -0.026029 -0.012807 0.016848 -vn -0.765274 0.235011 -0.599271 -v -0.025795 -0.013665 0.016221 -vn -0.400280 0.475723 -0.783239 -v -0.024932 -0.012052 0.016307 -vn -0.415818 0.488807 -0.766918 -v -0.024768 -0.012913 0.015689 -vn -0.097803 0.608012 -0.787881 -v -0.023802 -0.012540 0.015607 -vn -0.059745 0.594218 -0.802082 -v -0.023911 -0.011695 0.016252 -vn 0.033051 0.582827 -0.811924 -v -0.024097 -0.010159 0.017385 -vn 0.118379 0.558931 -0.820721 -v -0.024248 -0.008776 0.018338 -vn 0.293649 0.423075 -0.857192 -v -0.024519 -0.005464 0.020227 -vn 0.241126 0.471076 -0.848496 -v -0.024450 -0.006480 0.019718 -vn 0.190383 0.512314 -0.837430 -v -0.024368 -0.007497 0.019142 -vn 0.336626 0.357549 -0.871115 -v -0.024572 -0.004491 0.020648 -vn 0.371834 0.299635 -0.878612 -v -0.024613 -0.003549 0.020986 -vn 0.431760 0.075047 -0.898861 -v -0.024674 -0.000814 0.021536 -vn 0.419295 0.143758 -0.896396 -v -0.024664 -0.001627 0.021443 -vn 0.403493 0.198056 -0.893290 -v -0.024647 -0.002452 0.021287 -vn 0.397727 0.238860 -0.885866 -v -0.024643 -0.002630 0.021245 -vn 0.431804 -0.069739 -0.899267 -v -0.024674 0.000805 0.021537 -vn 0.435747 -0.001179 -0.900069 -v -0.024677 -0.000006 0.021568 -vn 0.379808 -0.271806 -0.884233 -v -0.024625 0.003222 0.021086 -vn 0.403600 -0.207212 -0.891162 -v -0.024649 0.002384 0.021302 -vn 0.420603 -0.142320 -0.896012 -v -0.024664 0.001627 0.021443 -vn 0.313869 -0.390452 -0.865467 -v -0.024549 0.004937 0.020464 -vn 0.351661 -0.333156 -0.874838 -v -0.024592 0.004072 0.020807 -vn 0.272178 -0.437854 -0.856856 -v -0.024496 0.005820 0.020056 -vn 0.220225 -0.489120 -0.843956 -v -0.024418 0.006893 0.019491 -vn 0.162349 -0.530061 -0.832273 -v -0.024327 0.007953 0.018864 -vn 0.099846 -0.561455 -0.821462 -v -0.024220 0.009042 0.018160 -vn 0.030663 -0.585716 -0.809936 -v -0.024097 0.010165 0.017380 -vn -0.883033 0.077901 -0.462801 -v -0.026844 -0.011676 0.018427 -vn -0.878606 0.076840 -0.471325 -v -0.027226 -0.010209 0.019392 -vn -0.874379 0.073948 -0.479576 -v -0.027551 -0.008818 0.020209 -vn -0.870848 0.069270 -0.486648 -v -0.027784 -0.007685 0.020798 -vn -0.867505 0.063196 -0.493398 -v -0.027991 -0.006532 0.021322 -vn -0.864438 0.055528 -0.499664 -v -0.028164 -0.005406 0.021757 -vn -0.861746 0.046457 -0.505209 -v -0.028303 -0.004298 0.022108 -vn -0.859403 0.038444 -0.509851 -v -0.028410 -0.003200 0.022379 -vn -0.858526 0.031738 -0.511788 -v -0.028427 -0.002986 0.022422 -vn -0.857643 0.023110 -0.513727 -v -0.028492 -0.001987 0.022587 -vn -0.856730 0.011810 -0.515629 -v -0.028531 -0.000996 0.022685 -vn -0.856418 0.000131 -0.516283 -v -0.028544 -0.000008 0.022718 -vn -0.856707 -0.011599 -0.515673 -v -0.028531 0.000985 0.022685 -vn -0.857520 -0.022820 -0.513945 -v -0.028492 0.001988 0.022586 -vn -0.858810 -0.033185 -0.511219 -v -0.028433 0.002904 0.022438 -vn -0.860647 -0.042906 -0.507392 -v -0.028344 0.003909 0.022213 -vn -0.862941 -0.051782 -0.502645 -v -0.028229 0.004915 0.021922 -vn -0.865531 -0.059409 -0.497319 -v -0.028088 0.005925 0.021566 -vn -0.868485 -0.066018 -0.491299 -v -0.027922 0.006939 0.021146 -vn -0.872017 -0.071407 -0.484238 -v -0.027692 0.008149 0.020566 -vn -0.875567 -0.075353 -0.477184 -v -0.027439 0.009319 0.019927 -vn -0.879170 -0.077595 -0.470148 -v -0.027155 0.010495 0.019212 -vn -0.882753 -0.078321 -0.463263 -v -0.026842 0.011682 0.018423 -vn -0.886654 -0.077775 -0.455847 -v -0.026501 0.012884 0.017563 -vn -0.822259 0.154997 -0.547601 -v -0.026661 -0.011444 0.018173 -vn -0.811758 0.152737 -0.563668 -v -0.027025 -0.009981 0.019115 -vn -0.801794 0.146898 -0.579265 -v -0.027332 -0.008600 0.019910 -vn -0.793581 0.137520 -0.592721 -v -0.027552 -0.007480 0.020481 -vn -0.785865 0.125409 -0.605549 -v -0.027746 -0.006346 0.020986 -vn -0.778790 0.110204 -0.617528 -v -0.027906 -0.005242 0.021404 -vn -0.772654 0.092088 -0.628113 -v -0.028035 -0.004161 0.021740 -vn -0.767617 0.076327 -0.636347 -v -0.028133 -0.003094 0.021998 -vn -0.765781 0.062960 -0.640012 -v -0.028149 -0.002886 0.022040 -vn -0.763397 0.045796 -0.644304 -v -0.028209 -0.001919 0.022196 -vn -0.761412 0.023355 -0.647847 -v -0.028244 -0.000962 0.022289 -vn -0.760684 0.000266 -0.649122 -v -0.028256 -0.000007 0.022320 -vn -0.761347 -0.022961 -0.647938 -v -0.028244 0.000951 0.022289 -vn -0.763203 -0.045147 -0.644580 -v -0.028209 0.001920 0.022195 -vn -0.766146 -0.065698 -0.639300 -v -0.028155 0.002807 0.022055 -vn -0.770441 -0.084987 -0.631821 -v -0.028073 0.003782 0.021840 -vn -0.775622 -0.102552 -0.622811 -v -0.027967 0.004763 0.021562 -vn -0.781558 -0.117695 -0.612629 -v -0.027836 0.005750 0.021221 -vn -0.788322 -0.130837 -0.601191 -v -0.027681 0.006745 0.020817 -vn -0.796552 -0.141551 -0.587766 -v -0.027465 0.007938 0.020256 -vn -0.804907 -0.149397 -0.574287 -v -0.027226 0.009096 0.019636 -vn -0.813435 -0.153886 -0.560929 -v -0.026958 0.010266 0.018940 -vn -0.821978 -0.155349 -0.547922 -v -0.026660 0.011450 0.018169 -vn -0.830386 -0.154944 -0.535212 -v -0.026333 0.012655 0.017327 -vn -0.747717 0.229403 -0.623132 -v -0.026437 -0.011221 0.017947 -vn -0.729656 0.225795 -0.645460 -v -0.026779 -0.009762 0.018870 -vn -0.712746 0.216836 -0.667065 -v -0.027065 -0.008391 0.019647 -vn -0.698990 0.202729 -0.685794 -v -0.027268 -0.007285 0.020202 -vn -0.685998 0.184785 -0.703748 -v -0.027446 -0.006168 0.020692 -vn -0.674268 0.162211 -0.720452 -v -0.027592 -0.005086 0.021096 -vn -0.664114 0.135447 -0.735260 -v -0.027709 -0.004031 0.021419 -vn -0.655999 0.112055 -0.746398 -v -0.027797 -0.002994 0.021667 -vn -0.653165 0.092309 -0.751568 -v -0.027812 -0.002792 0.021707 -vn -0.648934 0.067283 -0.757864 -v -0.027865 -0.001855 0.021856 -vn -0.645657 0.034301 -0.762857 -v -0.027897 -0.000929 0.021944 -vn -0.644514 0.000381 -0.764592 -v -0.027907 -0.000007 0.021974 -vn -0.645566 -0.033685 -0.762962 -v -0.027897 0.000919 0.021945 -vn -0.648694 -0.066286 -0.758157 -v -0.027865 0.001855 0.021856 -vn -0.653590 -0.096532 -0.750667 -v -0.027817 0.002715 0.021721 -vn -0.660590 -0.124912 -0.740283 -v -0.027743 0.003663 0.021515 -vn -0.669178 -0.150798 -0.727640 -v -0.027647 0.004618 0.021248 -vn -0.679091 -0.173169 -0.713336 -v -0.027528 0.005583 0.020919 -vn -0.690269 -0.192671 -0.697428 -v -0.027386 0.006560 0.020528 -vn -0.704086 -0.208689 -0.678757 -v -0.027188 0.007736 0.019984 -vn -0.718256 -0.220457 -0.659929 -v -0.026966 0.008883 0.019379 -vn -0.732713 -0.227363 -0.641434 -v -0.026716 0.010045 0.018699 -vn -0.747404 -0.229787 -0.623366 -v -0.026436 0.011227 0.017943 -vn -0.761254 -0.227404 -0.607272 -v -0.026128 0.012433 0.017116 -vn -0.660623 0.299944 -0.688194 -v -0.026176 -0.011009 0.017753 -vn -0.633843 0.294631 -0.715147 -v -0.026491 -0.009556 0.018662 -vn -0.609008 0.282346 -0.741209 -v -0.026753 -0.008196 0.019425 -vn -0.589047 0.263553 -0.763913 -v -0.026938 -0.007102 0.019969 -vn -0.570221 0.239902 -0.785681 -v -0.027099 -0.006003 0.020447 -vn -0.553356 0.210310 -0.805957 -v -0.027229 -0.004942 0.020840 -vn -0.538819 0.175429 -0.823953 -v -0.027333 -0.003911 0.021154 -vn -0.527439 0.144929 -0.837140 -v -0.027411 -0.002901 0.021394 -vn -0.523497 0.119367 -0.843624 -v -0.027423 -0.002705 0.021432 -vn -0.517286 0.087004 -0.851379 -v -0.027470 -0.001796 0.021576 -vn -0.512599 0.044350 -0.857482 -v -0.027497 -0.000899 0.021662 -vn -0.510990 0.000502 -0.859587 -v -0.027507 -0.000007 0.021690 -vn -0.512487 -0.043516 -0.857592 -v -0.027498 0.000889 0.021662 -vn -0.517018 -0.085702 -0.851673 -v -0.027470 0.001796 0.021576 -vn -0.523945 -0.124839 -0.842554 -v -0.027428 0.002630 0.021446 -vn -0.533903 -0.161672 -0.829946 -v -0.027363 0.003552 0.021247 -vn -0.546205 -0.195363 -0.814551 -v -0.027278 0.004484 0.020988 -vn -0.560435 -0.224567 -0.797171 -v -0.027172 0.005429 0.020669 -vn -0.576514 -0.250144 -0.777856 -v -0.027045 0.006389 0.020287 -vn -0.596554 -0.271402 -0.755291 -v -0.026865 0.007548 0.019755 -vn -0.617212 -0.287180 -0.732515 -v -0.026663 0.008683 0.019162 -vn -0.638546 -0.296656 -0.710109 -v -0.026433 0.009837 0.018493 -vn -0.660287 -0.300354 -0.688337 -v -0.026175 0.011015 0.017749 -vn -0.682940 -0.297525 -0.667137 -v -0.025889 0.012221 0.016932 -vn -0.562343 0.365503 -0.741740 -v -0.025881 -0.010812 0.017593 -vn -0.454587 0.424913 -0.782815 -v -0.025558 -0.010634 0.017470 -vn -0.526093 0.357954 -0.771424 -v -0.026168 -0.009366 0.018494 -vn -0.408484 0.414527 -0.813208 -v -0.025816 -0.009196 0.018369 -vn -0.492778 0.342034 -0.800114 -v -0.026404 -0.008017 0.019248 -vn -0.366409 0.394710 -0.842585 -v -0.026025 -0.007860 0.019121 -vn -0.466160 0.318648 -0.825323 -v -0.026569 -0.006937 0.019785 -vn -0.333119 0.366734 -0.868641 -v -0.026170 -0.006793 0.019656 -vn -0.441272 0.289444 -0.849412 -v -0.026712 -0.005854 0.020257 -vn -0.302086 0.332302 -0.893487 -v -0.026295 -0.005726 0.020125 -vn -0.419027 0.253325 -0.871919 -v -0.026827 -0.004813 0.020643 -vn -0.274537 0.290195 -0.916742 -v -0.026393 -0.004703 0.020509 -vn -0.399987 0.210986 -0.891906 -v -0.026916 -0.003805 0.020951 -vn -0.251031 0.241277 -0.937427 -v -0.026470 -0.003714 0.020815 -vn -0.385184 0.174129 -0.906263 -v -0.026984 -0.002819 0.021186 -vn -0.232984 0.198739 -0.951957 -v -0.026526 -0.002750 0.021048 -vn -0.380183 0.143291 -0.913744 -v -0.026994 -0.002628 0.021223 -vn -0.227004 0.163389 -0.960090 -v -0.026536 -0.002564 0.021085 -vn -0.371912 0.104440 -0.922374 -v -0.027034 -0.001744 0.021364 -vn -0.216620 0.119134 -0.968960 -v -0.026569 -0.001700 0.021225 -vn -0.365805 0.053221 -0.929169 -v -0.027057 -0.000873 0.021447 -vn -0.209188 0.060674 -0.975991 -v -0.026588 -0.000850 0.021308 -vn -0.363728 0.000614 -0.931505 -v -0.027065 -0.000007 0.021475 -vn -0.206626 0.000727 -0.978420 -v -0.026594 -0.000006 0.021335 -vn -0.365686 -0.052192 -0.929274 -v -0.027057 0.000863 0.021448 -vn -0.209040 -0.059477 -0.976097 -v -0.026588 0.000841 0.021308 -vn -0.371618 -0.102845 -0.922672 -v -0.027034 0.001744 0.021364 -vn -0.216311 -0.117260 -0.969257 -v -0.026569 0.001701 0.021225 -vn -0.380629 -0.149891 -0.912499 -v -0.026998 0.002556 0.021237 -vn -0.227333 -0.171035 -0.958680 -v -0.026539 0.002492 0.021099 -vn -0.393630 -0.194317 -0.898497 -v -0.026943 0.003454 0.021042 -vn -0.243256 -0.222017 -0.944211 -v -0.026492 0.003371 0.020906 -vn -0.409712 -0.235103 -0.881398 -v -0.026869 0.004365 0.020788 -vn -0.263107 -0.269054 -0.926491 -v -0.026430 0.004263 0.020654 -vn -0.428431 -0.270641 -0.862091 -v -0.026777 0.005290 0.020474 -vn -0.286237 -0.310289 -0.906526 -v -0.026351 0.005172 0.020342 -vn -0.449649 -0.301941 -0.840623 -v -0.026665 0.006234 0.020099 -vn -0.312531 -0.346880 -0.884307 -v -0.026254 0.006100 0.019968 -vn -0.476274 -0.328320 -0.815702 -v -0.026505 0.007377 0.019574 -vn -0.345816 -0.378233 -0.858692 -v -0.026114 0.007227 0.019446 -vn -0.503902 -0.348178 -0.790477 -v -0.026324 0.008500 0.018989 -vn -0.380539 -0.402239 -0.832703 -v -0.025954 0.008337 0.018862 -vn -0.532581 -0.360524 -0.765754 -v -0.026115 0.009646 0.018326 -vn -0.416806 -0.417752 -0.807314 -v -0.025768 0.009474 0.018202 -vn -0.562017 -0.365919 -0.741782 -v -0.025880 0.010818 0.017589 -vn -0.454289 -0.425330 -0.782762 -v -0.025557 0.010640 0.017466 -vn -0.593136 -0.365964 -0.717119 -v -0.025618 0.012022 0.016778 -vn -0.494020 -0.428012 -0.756803 -v -0.025321 0.011841 0.016657 -vn -0.218119 0.521349 -0.824997 -v -0.024850 -0.010344 0.017345 -vn -0.093318 0.556781 -0.825401 -v -0.024476 -0.010238 0.017344 -vn -0.152499 0.503422 -0.850477 -v -0.025049 -0.008929 0.018258 -vn -0.018985 0.534041 -0.845245 -v -0.024649 -0.008837 0.018274 -vn -0.093742 0.474799 -0.875088 -v -0.025208 -0.007621 0.019024 -vn 0.046923 0.500557 -0.864431 -v -0.024787 -0.007544 0.019056 -vn -0.048107 0.437988 -0.897693 -v -0.025316 -0.006579 0.019570 -vn 0.097565 0.459562 -0.882770 -v -0.024880 -0.006514 0.019615 -vn -0.005972 0.394157 -0.919024 -v -0.025407 -0.005541 0.020049 -vn 0.144032 0.411694 -0.899868 -v -0.024958 -0.005488 0.020107 -vn 0.030887 0.342140 -0.939141 -v -0.025478 -0.004547 0.020443 -vn 0.184368 0.355933 -0.916144 -v -0.025019 -0.004506 0.020512 -vn 0.062029 0.283036 -0.957101 -v -0.025532 -0.003589 0.020757 -vn 0.218215 0.293442 -0.930739 -v -0.025064 -0.003558 0.020836 -vn 0.085388 0.232275 -0.968895 -v -0.025571 -0.002657 0.020997 -vn 0.243340 0.240229 -0.939721 -v -0.025097 -0.002635 0.021084 -vn 0.093047 0.190614 -0.977245 -v -0.025577 -0.002476 0.021035 -vn 0.251536 0.196897 -0.947608 -v -0.025102 -0.002456 0.021124 -vn 0.106945 0.138737 -0.984538 -v -0.025599 -0.001641 0.021179 -vn 0.266647 0.143144 -0.953105 -v -0.025121 -0.001628 0.021273 -vn 0.116563 0.070581 -0.990672 -v -0.025612 -0.000821 0.021264 -vn 0.276967 0.072768 -0.958120 -v -0.025132 -0.000815 0.021362 -vn 0.119879 0.000915 -0.992788 -v -0.025616 -0.000006 0.021293 -vn 0.280521 0.000988 -0.959847 -v -0.025135 -0.000006 0.021392 -vn 0.116751 -0.069058 -0.990757 -v -0.025612 0.000812 0.021265 -vn 0.277188 -0.071103 -0.958181 -v -0.025132 0.000806 0.021363 -vn 0.107299 -0.136435 -0.984821 -v -0.025599 0.001642 0.021179 -vn 0.267006 -0.140685 -0.953371 -v -0.025121 0.001629 0.021273 -vn 0.092946 -0.199490 -0.975482 -v -0.025579 0.002407 0.021049 -vn 0.251574 -0.206045 -0.945651 -v -0.025104 0.002388 0.021139 -vn 0.072078 -0.259892 -0.962944 -v -0.025547 0.003257 0.020850 -vn 0.229042 -0.269084 -0.935486 -v -0.025077 0.003229 0.020932 -vn 0.045901 -0.316322 -0.947541 -v -0.025504 0.004121 0.020591 -vn 0.200640 -0.328472 -0.922957 -v -0.025041 0.004084 0.020665 -vn 0.015079 -0.366675 -0.930227 -v -0.025448 0.005002 0.020271 -vn 0.167037 -0.382066 -0.908914 -v -0.024993 0.004956 0.020335 -vn -0.020178 -0.412235 -0.910854 -v -0.025377 0.005904 0.019889 -vn 0.128396 -0.431148 -0.893099 -v -0.024932 0.005848 0.019942 -vn -0.065597 -0.452944 -0.889122 -v -0.025274 0.007002 0.019355 -vn 0.078141 -0.476125 -0.875899 -v -0.024844 0.006933 0.019395 -vn -0.113628 -0.485416 -0.866868 -v -0.025154 0.008088 0.018760 -vn 0.024600 -0.512855 -0.858123 -v -0.024740 0.008005 0.018787 -vn -0.164538 -0.508228 -0.845359 -v -0.025012 0.009202 0.018088 -vn -0.032643 -0.539813 -0.841152 -v -0.024617 0.009107 0.018101 -vn -0.217930 -0.521806 -0.824757 -v -0.024849 0.010350 0.017341 -vn -0.093232 -0.557261 -0.825087 -v -0.024475 0.010244 0.017340 -vn -0.274673 -0.526990 -0.804261 -v -0.024664 0.011537 0.016519 -vn -0.158840 -0.567995 -0.807559 -v -0.024314 0.011421 0.016505 -vn -0.339238 0.477134 -0.810716 -v -0.025213 -0.010477 0.017387 -vn -0.283161 0.463329 -0.839730 -v -0.025440 -0.009050 0.018290 -vn -0.232489 0.439267 -0.867752 -v -0.025624 -0.007727 0.019046 -vn -0.192749 0.406808 -0.892947 -v -0.025750 -0.006672 0.019583 -vn -0.155840 0.367487 -0.916879 -v -0.025856 -0.005621 0.020055 -vn -0.123321 0.320049 -0.939341 -v -0.025940 -0.004613 0.020442 -vn -0.095714 0.265499 -0.959348 -v -0.026005 -0.003642 0.020750 -vn -0.074777 0.218329 -0.973006 -v -0.026052 -0.002696 0.020984 -vn -0.067845 0.179364 -0.981441 -v -0.026059 -0.002512 0.021022 -vn -0.055585 0.130662 -0.989868 -v -0.026086 -0.001665 0.021163 -vn -0.046959 0.066514 -0.996680 -v -0.026102 -0.000833 0.021246 -vn -0.043978 0.000827 -0.999032 -v -0.026107 -0.000006 0.021274 -vn -0.046780 -0.065147 -0.996779 -v -0.026102 0.000824 0.021247 -vn -0.055245 -0.128557 -0.990162 -v -0.026086 0.001666 0.021163 -vn -0.068091 -0.187714 -0.979861 -v -0.026062 0.002443 0.021036 -vn -0.086711 -0.244066 -0.965874 -v -0.026023 0.003305 0.020841 -vn -0.109976 -0.296351 -0.948726 -v -0.025971 0.004181 0.020587 -vn -0.137204 -0.342557 -0.929424 -v -0.025904 0.005075 0.020273 -vn -0.168264 -0.383931 -0.907901 -v -0.025821 0.005989 0.019898 -vn -0.207933 -0.420079 -0.883345 -v -0.025701 0.007101 0.019372 -vn -0.249561 -0.448295 -0.858342 -v -0.025561 0.008199 0.018786 -vn -0.293405 -0.467286 -0.834001 -v -0.025398 0.009325 0.018122 -vn -0.338971 -0.477574 -0.810569 -v -0.025212 0.010483 0.017383 -vn -0.385054 -0.481415 -0.787384 -v -0.025001 0.011678 0.016570 -vn -0.041625 -0.596829 -0.801288 -v -0.023957 0.011329 0.016527 -vn -0.897767 0.429255 -0.098761 -v -0.026000 -0.016315 0.014458 -vn -0.876837 0.462046 -0.132929 -v -0.025957 -0.016247 0.014395 -vn -0.870911 0.483380 -0.088643 -v -0.026575 -0.017786 0.012329 -vn -0.609456 0.675107 -0.415685 -v -0.025043 -0.015343 0.013824 -vn -0.561686 0.694773 -0.449220 -v -0.024971 -0.015291 0.013809 -vn -0.566811 0.719252 -0.401749 -v -0.025016 -0.015398 0.013687 -vn -0.236198 0.756297 0.610103 -v -0.023704 -0.014549 -0.013858 -vn -0.293857 0.756836 0.583821 -v -0.023968 -0.014683 -0.013809 -vn -0.304652 0.795808 0.523332 -v -0.024397 -0.015663 -0.012680 -vn -0.927757 0.370416 0.045386 -v -0.026096 -0.016496 -0.014635 -vn -0.917098 0.392131 0.071866 -v -0.026087 -0.016477 -0.014616 -vn -0.824638 0.525986 0.208115 -v -0.025765 -0.015992 -0.014182 -vn -0.853117 0.492040 0.173458 -v -0.025893 -0.016154 -0.014313 -vn -0.872842 0.477115 0.102511 -v -0.026099 -0.016601 -0.013961 -vn -0.877675 0.460300 0.133454 -v -0.025957 -0.016247 -0.014395 -vn -0.899565 0.424707 0.102015 -v -0.026000 -0.016315 -0.014458 -vn -0.762992 0.584819 0.275372 -v -0.025615 -0.015830 -0.014065 -vn -0.795965 0.556434 0.238371 -v -0.025705 -0.015925 -0.014132 -vn -0.793746 0.574476 0.199860 -v -0.025863 -0.016315 -0.013660 -vn -0.651976 0.659967 0.373324 -v -0.025249 -0.015501 -0.013884 -vn -0.691934 0.637462 0.338924 -v -0.025375 -0.015606 -0.013933 -vn -0.694098 0.657450 0.293236 -v -0.025567 -0.016073 -0.013375 -vn -0.725248 0.614716 0.310063 -v -0.025437 -0.015661 -0.013963 -vn -0.526262 0.714172 0.461526 -v -0.024817 -0.015185 -0.013785 -vn -0.572429 0.698267 0.429823 -v -0.024971 -0.015291 -0.013809 -vn -0.577307 0.723175 0.379124 -v -0.025217 -0.015880 -0.013112 -vn -0.609411 0.682264 0.403900 -v -0.025043 -0.015343 -0.013824 -vn -0.389262 0.746511 0.539627 -v -0.024315 -0.014874 -0.013772 -vn -0.440409 0.738262 0.510891 -v -0.024499 -0.014982 -0.013766 -vn -0.446389 0.769752 0.456310 -v -0.024824 -0.015743 -0.012879 -vn -0.480374 0.728581 0.488274 -v -0.024573 -0.015028 -0.013767 -vn -0.316109 0.755481 0.573868 -v -0.023994 -0.014697 -0.013805 -vn -0.343266 0.752599 0.561929 -v -0.024042 -0.014723 -0.013799 -vn -0.085561 0.740321 0.666787 -v -0.023098 -0.014273 -0.014026 -vn -0.148607 0.753383 0.640570 -v -0.023388 -0.014400 -0.013937 -vn -0.149461 0.803176 0.576688 -v -0.023946 -0.015644 -0.012522 -vn -0.187330 0.754049 0.629537 -v -0.023405 -0.014408 -0.013932 -vn -0.034494 0.728979 0.683667 -v -0.022783 -0.014146 -0.014139 -vn -0.017086 0.709306 -0.704694 -v -0.022783 -0.014146 0.014139 -vn -0.079939 0.734064 -0.674359 -v -0.023098 -0.014273 0.014026 -vn -0.137135 0.743455 -0.654576 -v -0.023388 -0.014400 0.013937 -vn -0.152258 0.787512 -0.597196 -v -0.023741 -0.015187 0.013074 -vn -0.234233 0.748085 -0.620890 -v -0.023704 -0.014549 0.013858 -vn -0.177482 0.747342 -0.640297 -v -0.023405 -0.014408 0.013932 -vn -0.390004 0.736173 -0.553124 -v -0.024315 -0.014874 0.013772 -vn -0.335878 0.746803 -0.573996 -v -0.024042 -0.014723 0.013799 -vn -0.302323 0.784845 -0.540943 -v -0.024193 -0.015198 0.013237 -vn -0.311758 0.750738 -0.582408 -v -0.023994 -0.014697 0.013805 -vn -0.283271 0.748964 -0.599008 -v -0.023968 -0.014683 0.013809 -vn -0.429525 0.732170 -0.528617 -v -0.024499 -0.014982 0.013766 -vn -0.443443 0.760193 -0.474831 -v -0.024622 -0.015269 0.013444 -vn -0.475969 0.724048 -0.499208 -v -0.024573 -0.015028 0.013767 -vn -0.530294 0.697359 -0.482160 -v -0.024817 -0.015185 0.013785 -vn -0.764614 0.586752 -0.266623 -v -0.025615 -0.015830 0.014065 -vn -0.724014 0.620019 -0.302293 -v -0.025437 -0.015661 0.013963 -vn -0.692327 0.673310 -0.259495 -v -0.026036 -0.017217 0.011815 -vn -0.694254 0.642196 -0.324953 -v -0.025375 -0.015606 0.013933 -vn -0.662473 0.659499 -0.355233 -v -0.025296 -0.015540 0.013901 -vn -0.794720 0.559759 -0.234713 -v -0.025705 -0.015925 0.014132 -vn -0.791140 0.585903 -0.175544 -v -0.026334 -0.017480 0.012065 -vn -0.822316 0.531846 -0.202328 -v -0.025765 -0.015992 0.014182 -vn -0.854309 0.492748 -0.165394 -v -0.025893 -0.016154 0.014313 -vn -0.916456 0.394612 -0.066259 -v -0.026087 -0.016477 0.014616 -vn -0.927597 0.371035 -0.043551 -v -0.026096 -0.016496 0.014635 -vn -0.147057 0.847491 -0.510033 -v -0.024424 -0.016709 0.011059 -vn -0.144919 0.902070 -0.406533 -v -0.024987 -0.017964 0.008872 -vn -0.146433 0.942862 -0.299279 -v -0.025421 -0.018935 0.006547 -vn -0.145686 0.970036 -0.194438 -v -0.025722 -0.019605 0.004120 -vn -0.142951 0.986451 -0.080496 -v -0.025884 -0.019967 0.001628 -vn -0.142338 0.989076 0.038324 -v -0.025905 -0.020013 -0.000889 -vn -0.146753 0.975880 0.161620 -v -0.025784 -0.019744 -0.003395 -vn -0.146883 0.950070 0.275306 -v -0.025523 -0.019162 -0.005848 -vn -0.148034 0.911169 0.384522 -v -0.025126 -0.018275 -0.008212 -vn -0.152804 0.861983 0.483359 -v -0.024598 -0.017096 -0.010449 -vn -0.302035 0.846563 0.438299 -v -0.025043 -0.017141 -0.010584 -vn -0.299176 0.890587 0.342563 -v -0.025567 -0.018341 -0.008320 -vn -0.297101 0.923431 0.242910 -v -0.025961 -0.019244 -0.005926 -vn -0.295759 0.944866 0.140549 -v -0.026220 -0.019837 -0.003440 -vn -0.295150 0.954747 0.036658 -v -0.026340 -0.020112 -0.000902 -vn -0.295269 0.953020 -0.067590 -v -0.026319 -0.020064 0.001650 -vn -0.296147 0.939704 -0.171039 -v -0.026158 -0.019696 0.004175 -vn -0.297733 0.914923 -0.272528 -v -0.025860 -0.019013 0.006634 -vn -0.300097 0.878852 -0.370893 -v -0.025429 -0.018025 0.008988 -vn -0.303225 0.831785 -0.464961 -v -0.024870 -0.016747 0.011201 -vn -0.443356 0.810648 0.382472 -v -0.025466 -0.017248 -0.010751 -vn -0.439450 0.847264 0.298376 -v -0.025987 -0.018470 -0.008452 -vn -0.436541 0.874517 0.211310 -v -0.026379 -0.019390 -0.006021 -vn -0.434700 0.892252 0.122157 -v -0.026636 -0.019994 -0.003495 -vn -0.433877 0.900409 0.031849 -v -0.026755 -0.020273 -0.000916 -vn -0.434030 0.898983 -0.058713 -v -0.026735 -0.020225 0.001677 -vn -0.435201 0.887975 -0.148666 -v -0.026575 -0.019850 0.004242 -vn -0.437400 0.867442 -0.237120 -v -0.026278 -0.019154 0.006740 -vn -0.440634 0.837494 -0.323181 -v -0.025850 -0.018148 0.009131 -vn -0.444892 0.798302 -0.405937 -v -0.025295 -0.016846 0.011377 -vn -0.573826 0.755000 0.317331 -v -0.025857 -0.017414 -0.010946 -vn -0.569302 0.784079 0.247215 -v -0.026376 -0.018658 -0.008606 -vn -0.565977 0.805660 0.174878 -v -0.026767 -0.019595 -0.006130 -vn -0.563792 0.819712 0.101047 -v -0.027023 -0.020210 -0.003559 -vn -0.562849 0.826140 0.026343 -v -0.027142 -0.020495 -0.000933 -vn -0.563079 0.824977 -0.048537 -v -0.027122 -0.020446 0.001707 -vn -0.564439 0.816266 -0.122957 -v -0.026962 -0.020064 0.004319 -vn -0.566925 0.800043 -0.196282 -v -0.026667 -0.019355 0.006862 -vn -0.570637 0.776299 -0.267831 -v -0.026239 -0.018330 0.009296 -vn -0.575428 0.744994 -0.337442 -v -0.025686 -0.017004 0.011584 -vn -0.690298 0.680974 0.244466 -v -0.026207 -0.017634 -0.011164 -vn -0.685777 0.702506 0.190251 -v -0.026726 -0.018901 -0.008776 -vn -0.682471 0.718437 0.134466 -v -0.027116 -0.019855 -0.006251 -vn -0.680338 0.728774 0.077645 -v -0.027373 -0.020481 -0.003629 -vn -0.679364 0.733522 0.020243 -v -0.027492 -0.020771 -0.000951 -vn -0.679529 0.732701 -0.037286 -v -0.027471 -0.020721 0.001740 -vn -0.680877 0.726275 -0.094506 -v -0.027312 -0.020333 0.004404 -vn -0.683382 0.714285 -0.150949 -v -0.027016 -0.019611 0.006997 -vn -0.687083 0.696721 -0.206150 -v -0.026589 -0.018567 0.009481 -vn -0.654213 0.625568 -0.425053 -v -0.025249 -0.015501 0.013884 -vn -0.789899 0.590427 0.165697 -v -0.026506 -0.017905 -0.011400 -vn -0.786117 0.604500 0.128841 -v -0.027027 -0.019194 -0.008960 -vn -0.783327 0.614910 0.091018 -v -0.027420 -0.020164 -0.006381 -vn -0.781556 0.621619 0.052536 -v -0.027677 -0.020801 -0.003704 -vn -0.780785 0.624650 0.013682 -v -0.027796 -0.021097 -0.000971 -vn -0.780875 0.624178 -0.025223 -v -0.027776 -0.021046 0.001777 -vn -0.781984 0.620010 -0.063941 -v -0.027616 -0.020650 0.004495 -vn -0.784111 0.612154 -0.102163 -v -0.027319 -0.019916 0.007143 -vn -0.787200 0.600686 -0.139614 -v -0.026890 -0.018854 0.009680 -vn -0.870246 0.485587 0.082932 -v -0.026748 -0.018218 -0.011648 -vn -0.867975 0.492407 0.064458 -v -0.027274 -0.019529 -0.009153 -vn -0.866335 0.497387 0.045494 -v -0.027670 -0.020516 -0.006518 -vn -0.865279 0.500602 0.026251 -v -0.027929 -0.021163 -0.003783 -vn -0.864773 0.502116 0.006841 -v -0.028050 -0.021463 -0.000991 -vn -0.864871 0.501836 -0.012608 -v -0.028029 -0.021412 0.001814 -vn -0.865551 0.499802 -0.031938 -v -0.027868 -0.021010 0.004591 -vn -0.866820 0.496000 -0.051050 -v -0.027568 -0.020263 0.007296 -vn -0.868618 0.490537 -0.069831 -v -0.027135 -0.019184 0.009889 -vn -0.080022 0.677108 -0.731520 -v -0.023098 -0.014026 0.014273 -vn -0.140085 0.654116 -0.743309 -v -0.023388 -0.013937 0.014400 -vn -0.154618 0.625107 -0.765071 -v -0.023594 -0.013447 0.014858 -vn -0.927776 0.045647 -0.370336 -v -0.026096 -0.014635 0.016496 -vn -0.763119 0.273951 -0.585321 -v -0.025615 -0.014065 0.015830 -vn -0.795986 0.238617 -0.556298 -v -0.025705 -0.014132 0.015926 -vn -0.822602 0.207089 -0.529567 -v -0.025765 -0.014182 0.015992 -vn -0.853731 0.166993 -0.493210 -v -0.025893 -0.014313 0.016154 -vn -0.877837 0.133616 -0.459944 -v -0.025957 -0.014395 0.016247 -vn -0.899244 0.101397 -0.425534 -v -0.026000 -0.014458 0.016315 -vn -0.917213 0.072757 -0.391697 -v -0.026087 -0.014616 0.016477 -vn -0.724864 0.310055 -0.615173 -v -0.025437 -0.013963 0.015661 -vn -0.691924 0.339319 -0.637263 -v -0.025375 -0.013933 0.015606 -vn -0.651753 0.373086 -0.660322 -v -0.025249 -0.013884 0.015501 -vn -0.609392 0.404416 -0.681974 -v -0.025043 -0.013824 0.015343 -vn -0.572342 0.430337 -0.698022 -v -0.024971 -0.013809 0.015291 -vn -0.480218 0.488914 -0.728254 -v -0.024573 -0.013767 0.015028 -vn -0.525945 0.461708 -0.714288 -v -0.024817 -0.013785 0.015185 -vn -0.442536 0.507513 -0.739319 -v -0.024499 -0.013766 0.014982 -vn -0.402999 0.536923 -0.741151 -v -0.024375 -0.013769 0.014908 -vn -0.297466 0.571565 -0.764740 -v -0.024047 -0.013614 0.014864 -vn -0.310347 0.586655 -0.748011 -v -0.023994 -0.013805 0.014697 -vn -0.338351 0.576081 -0.744076 -v -0.024042 -0.013799 0.014723 -vn -0.376641 0.577893 -0.724004 -v -0.024315 -0.013772 0.014874 -vn -0.179359 0.643058 -0.744518 -v -0.023405 -0.013932 0.014408 -vn -0.229302 0.625780 -0.745533 -v -0.023704 -0.013858 0.014549 -vn -0.287460 0.596907 -0.749045 -v -0.023968 -0.013809 0.014683 -vn -0.027860 0.692711 -0.720677 -v -0.022783 -0.014139 0.014146 -vn 0.610107 -0.236230 0.756284 -v -0.013858 -0.023704 -0.014549 -vn 0.584082 -0.292948 0.756988 -v -0.013809 -0.023968 -0.014683 -vn 0.523338 -0.304637 0.795810 -v -0.012680 -0.024397 -0.015663 -vn -0.098757 -0.897742 0.429309 -v 0.014458 -0.026001 -0.016315 -vn -0.132925 -0.876823 0.462075 -v 0.014395 -0.025957 -0.016247 -vn -0.088665 -0.870889 0.483415 -v 0.012329 -0.026575 -0.017786 -vn -0.415653 -0.609496 0.675090 -v 0.013824 -0.025043 -0.015343 -vn -0.449197 -0.561707 0.694771 -v 0.013809 -0.024971 -0.015291 -vn -0.401724 -0.566853 0.719232 -v 0.013687 -0.025016 -0.015398 -vn -0.654606 -0.136947 0.743463 -v 0.013937 -0.023388 -0.014400 -vn -0.672444 -0.084921 0.735260 -v 0.014026 -0.023098 -0.014273 -vn -0.687706 -0.030367 0.725354 -v 0.014139 -0.022783 -0.014146 -vn -0.602860 -0.149186 0.783775 -v 0.013074 -0.023741 -0.015187 -vn -0.640345 -0.177276 0.747350 -v 0.013932 -0.023405 -0.014408 -vn -0.620876 -0.234247 0.748091 -v 0.013858 -0.023704 -0.014549 -vn -0.553135 -0.390050 0.736140 -v 0.013772 -0.024315 -0.014874 -vn -0.574002 -0.335873 0.746801 -v 0.013799 -0.024042 -0.014723 -vn -0.540941 -0.302311 0.784851 -v 0.013237 -0.024193 -0.015198 -vn -0.582416 -0.311721 0.750747 -v 0.013805 -0.023994 -0.014697 -vn -0.598992 -0.283279 0.748974 -v 0.013809 -0.023968 -0.014683 -vn -0.528694 -0.429261 0.732268 -v 0.013766 -0.024499 -0.014982 -vn -0.474829 -0.443412 0.760213 -v 0.013444 -0.024622 -0.015269 -vn -0.499286 -0.475691 0.724176 -v 0.013767 -0.024573 -0.015028 -vn -0.482123 -0.530339 0.697351 -v 0.013785 -0.024817 -0.015185 -vn -0.266692 -0.764540 0.586817 -v 0.014065 -0.025615 -0.015830 -vn -0.302278 -0.724056 0.619977 -v 0.013963 -0.025437 -0.015661 -vn -0.259487 -0.692337 0.673302 -v 0.011815 -0.026036 -0.017217 -vn -0.324949 -0.694261 0.642192 -v 0.013933 -0.025375 -0.015606 -vn -0.355250 -0.662469 0.659494 -v 0.013901 -0.025296 -0.015540 -vn -0.234794 -0.794641 0.559837 -v 0.014132 -0.025705 -0.015925 -vn -0.175558 -0.791123 0.585921 -v 0.012065 -0.026334 -0.017480 -vn -0.202367 -0.822306 0.531847 -v 0.014182 -0.025765 -0.015992 -vn -0.165370 -0.854336 0.492710 -v 0.014313 -0.025893 -0.016154 -vn -0.065670 -0.916746 0.394037 -v 0.014616 -0.026087 -0.016477 -vn -0.043053 -0.927812 0.370555 -v 0.014635 -0.026096 -0.016496 -vn 0.044734 -0.927985 0.369923 -v -0.014635 -0.026096 -0.016496 -vn 0.071203 -0.917366 0.391625 -v -0.014616 -0.026087 -0.016477 -vn 0.208164 -0.824609 0.526011 -v -0.014182 -0.025765 -0.015992 -vn 0.173403 -0.853136 0.492027 -v -0.014313 -0.025893 -0.016154 -vn 0.102547 -0.872826 0.477137 -v -0.013961 -0.026099 -0.016601 -vn 0.133430 -0.877661 0.460335 -v -0.014395 -0.025957 -0.016247 -vn 0.102037 -0.899520 0.424796 -v -0.014458 -0.026001 -0.016315 -vn 0.275448 -0.762934 0.584859 -v -0.014065 -0.025615 -0.015830 -vn 0.238508 -0.795866 0.556517 -v -0.014132 -0.025705 -0.015925 -vn 0.199900 -0.793720 0.574498 -v -0.013660 -0.025863 -0.016315 -vn 0.373332 -0.651995 0.659944 -v -0.013884 -0.025249 -0.015501 -vn 0.338941 -0.691943 0.637443 -v -0.013933 -0.025375 -0.015606 -vn 0.293212 -0.694123 0.657435 -v -0.013375 -0.025567 -0.016073 -vn 0.310063 -0.725274 0.614686 -v -0.013963 -0.025437 -0.015661 -vn 0.461448 -0.526365 0.714147 -v -0.013785 -0.024817 -0.015185 -vn 0.429737 -0.572547 0.698224 -v -0.013809 -0.024971 -0.015291 -vn 0.379119 -0.577323 0.723164 -v -0.013112 -0.025217 -0.015880 -vn 0.403898 -0.609425 0.682251 -v -0.013824 -0.025043 -0.015343 -vn 0.539590 -0.389375 0.746478 -v -0.013772 -0.024315 -0.014874 -vn 0.511014 -0.440101 0.738361 -v -0.013767 -0.024499 -0.014982 -vn 0.456332 -0.446367 0.769752 -v -0.012879 -0.024824 -0.015743 -vn 0.488477 -0.479933 0.728735 -v -0.013767 -0.024573 -0.015028 -vn 0.574176 -0.315204 0.755624 -v -0.013805 -0.023994 -0.014697 -vn 0.561844 -0.343471 0.752569 -v -0.013799 -0.024042 -0.014723 -vn 0.629776 -0.186435 0.754072 -v -0.013932 -0.023405 -0.014408 -vn 0.581300 -0.152409 0.799288 -v -0.012523 -0.023946 -0.015644 -vn 0.676416 -0.038645 0.735506 -v -0.014139 -0.022783 -0.014146 -vn 0.663055 -0.089320 0.743223 -v -0.014026 -0.023098 -0.014273 -vn 0.640720 -0.147876 0.753400 -v -0.013937 -0.023388 -0.014400 -vn -0.510314 -0.148546 0.847062 -v 0.011059 -0.024424 -0.016709 -vn -0.406633 -0.145960 0.901857 -v 0.008872 -0.024987 -0.017964 -vn -0.297529 -0.144132 0.943770 -v 0.006547 -0.025421 -0.018935 -vn -0.186176 -0.144952 0.971765 -v 0.004120 -0.025722 -0.019605 -vn -0.077988 -0.146298 0.986162 -v 0.001628 -0.025884 -0.019967 -vn 0.035217 -0.143047 0.989089 -v -0.000890 -0.025905 -0.020013 -vn 0.153070 -0.142669 0.977863 -v -0.003395 -0.025784 -0.019744 -vn 0.274264 -0.148428 0.950131 -v -0.005848 -0.025523 -0.019162 -vn 0.384624 -0.148884 0.910987 -v -0.008212 -0.025126 -0.018275 -vn 0.489515 -0.150118 0.858976 -v -0.010449 -0.024598 -0.017096 -vn 0.438298 -0.302029 0.846565 -v -0.010584 -0.025043 -0.017141 -vn 0.342568 -0.299156 0.890591 -v -0.008320 -0.025567 -0.018341 -vn 0.242921 -0.297077 0.923436 -v -0.005926 -0.025961 -0.019244 -vn 0.140545 -0.295752 0.944869 -v -0.003440 -0.026220 -0.019837 -vn 0.036661 -0.295145 0.954749 -v -0.000902 -0.026340 -0.020112 -vn -0.067594 -0.295285 0.953015 -v 0.001650 -0.026319 -0.020064 -vn -0.171038 -0.296152 0.939702 -v 0.004175 -0.026158 -0.019696 -vn -0.272525 -0.297744 0.914920 -v 0.006634 -0.025860 -0.019013 -vn -0.370885 -0.300097 0.878855 -v 0.008988 -0.025429 -0.018025 -vn -0.464962 -0.303229 0.831783 -v 0.011201 -0.024870 -0.016747 -vn 0.382470 -0.443354 0.810650 -v -0.010751 -0.025466 -0.017248 -vn 0.298385 -0.439429 0.847271 -v -0.008452 -0.025987 -0.018470 -vn 0.211310 -0.436534 0.874520 -v -0.006021 -0.026379 -0.019390 -vn 0.122161 -0.434691 0.892256 -v -0.003495 -0.026636 -0.019994 -vn 0.031854 -0.433849 0.900422 -v -0.000916 -0.026755 -0.020273 -vn -0.058714 -0.434026 0.898985 -v 0.001677 -0.026735 -0.020225 -vn -0.148668 -0.435210 0.887970 -v 0.004242 -0.026575 -0.019850 -vn -0.237122 -0.437397 0.867443 -v 0.006740 -0.026278 -0.019154 -vn -0.323183 -0.440624 0.837498 -v 0.009131 -0.025850 -0.018148 -vn -0.405941 -0.444889 0.798302 -v 0.011377 -0.025295 -0.016846 -vn 0.317323 -0.573835 0.754997 -v -0.010946 -0.025857 -0.017414 -vn 0.247209 -0.569311 0.784075 -v -0.008606 -0.026376 -0.018658 -vn 0.174882 -0.565984 0.805654 -v -0.006130 -0.026767 -0.019595 -vn 0.101035 -0.563838 0.819682 -v -0.003559 -0.027023 -0.020210 -vn 0.026339 -0.562877 0.826121 -v -0.000932 -0.027142 -0.020495 -vn -0.048537 -0.563068 0.824984 -v 0.001707 -0.027122 -0.020446 -vn -0.122963 -0.564416 0.816281 -v 0.004319 -0.026962 -0.020064 -vn -0.196278 -0.566940 0.800033 -v 0.006862 -0.026667 -0.019355 -vn -0.267828 -0.570637 0.776300 -v 0.009296 -0.026239 -0.018330 -vn -0.337455 -0.575401 0.745009 -v 0.011584 -0.025686 -0.017004 -vn 0.244473 -0.690288 0.680982 -v -0.011164 -0.026207 -0.017634 -vn 0.190245 -0.685783 0.702502 -v -0.008776 -0.026726 -0.018901 -vn 0.134473 -0.682466 0.718441 -v -0.006251 -0.027116 -0.019855 -vn 0.077647 -0.680329 0.728782 -v -0.003629 -0.027373 -0.020481 -vn 0.020242 -0.679363 0.733523 -v -0.000951 -0.027492 -0.020771 -vn -0.037291 -0.679547 0.732684 -v 0.001740 -0.027471 -0.020721 -vn -0.094502 -0.680884 0.726268 -v 0.004404 -0.027312 -0.020333 -vn -0.150945 -0.683397 0.714272 -v 0.006997 -0.027016 -0.019611 -vn -0.206153 -0.687078 0.696724 -v 0.009481 -0.026589 -0.018567 -vn -0.425018 -0.654247 0.625556 -v 0.013884 -0.025249 -0.015501 -vn 0.165704 -0.789886 0.590443 -v -0.011400 -0.026506 -0.017905 -vn 0.128846 -0.786113 0.604504 -v -0.008960 -0.027027 -0.019194 -vn 0.091015 -0.783341 0.614893 -v -0.006381 -0.027420 -0.020164 -vn 0.052533 -0.781553 0.621624 -v -0.003704 -0.027677 -0.020801 -vn 0.013695 -0.780738 0.624709 -v -0.000971 -0.027797 -0.021097 -vn -0.025219 -0.780894 0.624154 -v 0.001777 -0.027776 -0.021046 -vn -0.063931 -0.782019 0.619967 -v 0.004495 -0.027616 -0.020650 -vn -0.102165 -0.784111 0.612153 -v 0.007143 -0.027319 -0.019916 -vn -0.139623 -0.787190 0.600697 -v 0.009680 -0.026890 -0.018854 -vn 0.082941 -0.870239 0.485597 -v -0.011648 -0.026748 -0.018218 -vn 0.064448 -0.867986 0.492389 -v -0.009153 -0.027274 -0.019529 -vn 0.045502 -0.866329 0.497397 -v -0.006518 -0.027670 -0.020516 -vn 0.026252 -0.865263 0.500630 -v -0.003783 -0.027929 -0.021163 -vn 0.006842 -0.864780 0.502105 -v -0.000991 -0.028050 -0.021463 -vn -0.012600 -0.864876 0.501828 -v 0.001814 -0.028029 -0.021412 -vn -0.031944 -0.865550 0.499802 -v 0.004591 -0.027868 -0.021010 -vn -0.051062 -0.866803 0.496029 -v 0.007296 -0.027568 -0.020263 -vn -0.069818 -0.868645 0.490492 -v 0.009889 -0.027135 -0.019184 -vn -0.836096 -0.156358 -0.525829 -v 0.016709 -0.024424 0.011059 -vn -0.756267 -0.236162 0.610153 -v 0.014549 -0.023704 -0.013858 -vn -0.756852 -0.293815 0.583822 -v 0.014683 -0.023968 -0.013809 -vn -0.795808 -0.304647 0.523336 -v 0.015663 -0.024397 -0.012680 -vn -0.429293 -0.897752 -0.098740 -v 0.016315 -0.026001 0.014458 -vn -0.462082 -0.876818 -0.132929 -v 0.016247 -0.025957 0.014395 -vn -0.483421 -0.870885 -0.088671 -v 0.017786 -0.026575 0.012329 -vn -0.747319 -0.176481 -0.640600 -v 0.014408 -0.023405 0.013932 -vn -0.743473 -0.136331 -0.654722 -v 0.014400 -0.023388 0.013937 -vn -0.785235 -0.149186 -0.600957 -v 0.015187 -0.023741 0.013074 -vn -0.728055 -0.032984 -0.684725 -v 0.014146 -0.022783 0.014139 -vn -0.946483 -0.148070 -0.286783 -v 0.018935 -0.025421 0.006547 -vn -0.919273 -0.294913 -0.260699 -v 0.019013 -0.025860 0.006634 -vn -0.870560 -0.434848 -0.230288 -v 0.019154 -0.026278 0.006740 -vn -0.778040 -0.567816 -0.268773 -v 0.018330 -0.026239 0.009296 -vn -0.801627 -0.565218 -0.194738 -v 0.019355 -0.026667 0.006862 -vn -0.794848 -0.444279 -0.413320 -v 0.016846 -0.025295 0.011377 -vn -0.744575 -0.574702 -0.339597 -v 0.017004 -0.025686 0.011584 -vn -0.824059 -0.304916 -0.477444 -v 0.016747 -0.024870 0.011201 -vn -0.735296 -0.084928 -0.672404 -v 0.014273 -0.023098 0.014026 -vn -0.746792 -0.335922 -0.573984 -v 0.014723 -0.024042 0.013799 -vn -0.750744 -0.311786 -0.582386 -v 0.014697 -0.023994 0.013805 -vn -0.784842 -0.302312 -0.540954 -v 0.015198 -0.024193 0.013237 -vn -0.748982 -0.283256 -0.598993 -v 0.014683 -0.023968 0.013809 -vn -0.748062 -0.234180 -0.620937 -v 0.014549 -0.023704 0.013858 -vn -0.697293 -0.530390 -0.482150 -v 0.015185 -0.024817 0.013785 -vn -0.760228 -0.443381 -0.474833 -v 0.015269 -0.024622 0.013444 -vn -0.694856 -0.561616 -0.449180 -v 0.015291 -0.024971 0.013809 -vn -0.719318 -0.566796 -0.401652 -v 0.015398 -0.025016 0.013687 -vn -0.675221 -0.609364 -0.415635 -v 0.015343 -0.025043 0.013824 -vn -0.724158 -0.475731 -0.499275 -v 0.015028 -0.024573 0.013767 -vn -0.732220 -0.429368 -0.528675 -v 0.014982 -0.024499 0.013766 -vn -0.736106 -0.390081 -0.553158 -v 0.014874 -0.024315 0.013772 -vn -0.586805 -0.764556 -0.266670 -v 0.015830 -0.025615 0.014065 -vn -0.620046 -0.723965 -0.302353 -v 0.015661 -0.025437 0.013963 -vn -0.673306 -0.692333 -0.259489 -v 0.017217 -0.026036 0.011815 -vn -0.642181 -0.694259 -0.324975 -v 0.015606 -0.025375 0.013933 -vn -0.659307 -0.662662 -0.355236 -v 0.015540 -0.025296 0.013901 -vn -0.559823 -0.794657 -0.234774 -v 0.015925 -0.025705 0.014132 -vn -0.585915 -0.791128 -0.175554 -v 0.017480 -0.026334 0.012065 -vn -0.531874 -0.822285 -0.202380 -v 0.015992 -0.025765 0.014182 -vn -0.492745 -0.854313 -0.165383 -v 0.016154 -0.025893 0.014313 -vn -0.394013 -0.916760 -0.065619 -v 0.016477 -0.026087 0.014616 -vn -0.370562 -0.927808 -0.043073 -v 0.016496 -0.026096 0.014635 -vn -0.369964 -0.927966 0.044783 -v 0.016496 -0.026096 -0.014635 -vn -0.391621 -0.917367 0.071205 -v 0.016477 -0.026087 -0.014616 -vn -0.526007 -0.824613 0.208158 -v 0.015992 -0.025765 -0.014182 -vn -0.492057 -0.853109 0.173450 -v 0.016154 -0.025893 -0.014313 -vn -0.477131 -0.872829 0.102546 -v 0.016601 -0.026099 -0.013961 -vn -0.460334 -0.877659 0.133448 -v 0.016247 -0.025957 -0.014395 -vn -0.424748 -0.899546 0.102012 -v 0.016315 -0.026001 -0.014458 -vn -0.584869 -0.762932 0.275433 -v 0.015830 -0.025615 -0.014065 -vn -0.556488 -0.795900 0.238461 -v 0.015925 -0.025705 -0.014132 -vn -0.574506 -0.793712 0.199912 -v 0.016315 -0.025863 -0.013660 -vn -0.659903 -0.652072 0.373269 -v 0.015501 -0.025249 -0.013884 -vn -0.637409 -0.691996 0.338898 -v 0.015606 -0.025375 -0.013933 -vn -0.657426 -0.694129 0.293219 -v 0.016073 -0.025567 -0.013375 -vn -0.614736 -0.725209 0.310116 -v 0.015661 -0.025437 -0.013963 -vn -0.714154 -0.526327 0.461480 -v 0.015185 -0.024817 -0.013785 -vn -0.698283 -0.572426 0.429801 -v 0.015291 -0.024971 -0.013809 -vn -0.723159 -0.577329 0.379120 -v 0.015880 -0.025217 -0.013112 -vn -0.682330 -0.609284 0.403979 -v 0.015343 -0.025043 -0.013824 -vn -0.746446 -0.389366 0.539641 -v 0.014874 -0.024315 -0.013772 -vn -0.738302 -0.440280 0.510944 -v 0.014982 -0.024499 -0.013766 -vn -0.769751 -0.446382 0.456318 -v 0.015743 -0.024824 -0.012879 -vn -0.728676 -0.480114 0.488387 -v 0.015028 -0.024573 -0.013767 -vn -0.755498 -0.316138 0.573828 -v 0.014697 -0.023994 -0.013805 -vn -0.752590 -0.343276 0.561934 -v 0.014723 -0.024042 -0.013799 -vn -0.754038 -0.186304 0.629856 -v 0.014408 -0.023405 -0.013932 -vn -0.798677 -0.150796 0.582560 -v 0.015644 -0.023946 -0.012522 -vn -0.745365 -0.121825 0.655430 -v 0.014400 -0.023388 -0.013937 -vn -0.715655 -0.024586 0.698021 -v 0.014146 -0.022783 -0.014139 -vn -0.713222 -0.076675 0.696732 -v 0.014273 -0.023098 -0.014026 -vn -0.972106 -0.144404 -0.184816 -v 0.019605 -0.025722 0.004120 -vn -0.987157 -0.143767 -0.069658 -v 0.019967 -0.025884 0.001628 -vn -0.988277 -0.146504 0.042951 -v 0.020013 -0.025905 -0.000889 -vn -0.977711 -0.144733 0.152095 -v 0.019744 -0.025784 -0.003395 -vn -0.953494 -0.143629 0.264991 -v 0.019162 -0.025523 -0.005848 -vn -0.914581 -0.144535 0.377693 -v 0.018275 -0.025126 -0.008212 -vn -0.859082 -0.151743 0.488827 -v 0.017096 -0.024598 -0.010449 -vn -0.846561 -0.302051 0.438292 -v 0.017141 -0.025043 -0.010584 -vn -0.890592 -0.299154 0.342569 -v 0.018341 -0.025567 -0.008320 -vn -0.923443 -0.297060 0.242918 -v 0.019244 -0.025961 -0.005926 -vn -0.944877 -0.295723 0.140553 -v 0.019837 -0.026220 -0.003440 -vn -0.954757 -0.295120 0.036662 -v 0.020112 -0.026340 -0.000902 -vn -0.953019 -0.295273 -0.067593 -v 0.020064 -0.026319 0.001650 -vn -0.939706 -0.296142 -0.171037 -v 0.019696 -0.026158 0.004175 -vn -0.810652 -0.443345 0.382476 -v 0.017248 -0.025466 -0.010751 -vn -0.847266 -0.439450 0.298371 -v 0.018470 -0.025987 -0.008452 -vn -0.874522 -0.436531 0.211310 -v 0.019390 -0.026379 -0.006021 -vn -0.892253 -0.434698 0.122157 -v 0.019994 -0.026636 -0.003495 -vn -0.900415 -0.433863 0.031856 -v 0.020273 -0.026755 -0.000916 -vn -0.898981 -0.434034 -0.058713 -v 0.020225 -0.026735 0.001677 -vn -0.887970 -0.435211 -0.148663 -v 0.019850 -0.026575 0.004242 -vn -0.755005 -0.573814 0.317339 -v 0.017413 -0.025857 -0.010946 -vn -0.784082 -0.569299 0.247212 -v 0.018658 -0.026376 -0.008606 -vn -0.805652 -0.565990 0.174875 -v 0.019595 -0.026767 -0.006130 -vn -0.819674 -0.563850 0.101035 -v 0.020210 -0.027023 -0.003559 -vn -0.826104 -0.562902 0.026342 -v 0.020495 -0.027142 -0.000933 -vn -0.824967 -0.563093 -0.048538 -v 0.020446 -0.027122 0.001707 -vn -0.816283 -0.564414 -0.122961 -v 0.020064 -0.026962 0.004319 -vn -0.680978 -0.690295 0.244463 -v 0.017634 -0.026207 -0.011164 -vn -0.702520 -0.685761 0.190258 -v 0.018901 -0.026726 -0.008776 -vn -0.718450 -0.682455 0.134479 -v 0.019855 -0.027116 -0.006251 -vn -0.728773 -0.680339 0.077648 -v 0.020481 -0.027373 -0.003629 -vn -0.733527 -0.679358 0.020245 -v 0.020771 -0.027492 -0.000951 -vn -0.732686 -0.679544 -0.037291 -v 0.020721 -0.027471 0.001740 -vn -0.726254 -0.680900 -0.094504 -v 0.020333 -0.027312 0.004404 -vn -0.714285 -0.683382 -0.150949 -v 0.019611 -0.027016 0.006997 -vn -0.696722 -0.687081 -0.206152 -v 0.018567 -0.026589 0.009481 -vn -0.625170 -0.654438 -0.425292 -v 0.015501 -0.025249 0.013884 -vn -0.590445 -0.789884 0.165705 -v 0.017905 -0.026506 -0.011400 -vn -0.604489 -0.786127 0.128833 -v 0.019194 -0.027027 -0.008960 -vn -0.614879 -0.783353 0.091009 -v 0.020164 -0.027420 -0.006381 -vn -0.621622 -0.781554 0.052535 -v 0.020801 -0.027677 -0.003704 -vn -0.624705 -0.780740 0.013694 -v 0.021097 -0.027797 -0.000971 -vn -0.624161 -0.780889 -0.025221 -v 0.021046 -0.027776 0.001777 -vn -0.619971 -0.782016 -0.063936 -v 0.020650 -0.027616 0.004495 -vn -0.612147 -0.784116 -0.102164 -v 0.019916 -0.027319 0.007143 -vn -0.600693 -0.787194 -0.139619 -v 0.018854 -0.026890 0.009680 -vn -0.485614 -0.870228 0.082958 -v 0.018218 -0.026748 -0.011648 -vn -0.492379 -0.867992 0.064443 -v 0.019529 -0.027274 -0.009153 -vn -0.497379 -0.866340 0.045492 -v 0.020516 -0.027670 -0.006518 -vn -0.500638 -0.865259 0.026256 -v 0.021163 -0.027929 -0.003783 -vn -0.502105 -0.864780 0.006842 -v 0.021463 -0.028050 -0.000991 -vn -0.501836 -0.864871 -0.012600 -v 0.021412 -0.028029 0.001814 -vn -0.499805 -0.865549 -0.031946 -v 0.021010 -0.027868 0.004591 -vn -0.496031 -0.866802 -0.051064 -v 0.020263 -0.027568 0.007296 -vn -0.490504 -0.868637 -0.069824 -v 0.019184 -0.027135 0.009889 -vn 0.756321 -0.236159 -0.610088 -v -0.014549 -0.023704 0.013858 -vn 0.756837 -0.293907 -0.583795 -v -0.014683 -0.023968 0.013809 -vn 0.795803 -0.304644 -0.523345 -v -0.015663 -0.024397 0.012680 -vn 0.429349 -0.897719 0.098789 -v -0.016315 -0.026001 -0.014458 -vn 0.462049 -0.876839 0.132905 -v -0.016247 -0.025957 -0.014395 -vn 0.483404 -0.870897 0.088656 -v -0.017786 -0.026575 -0.012329 -vn 0.675032 -0.609639 0.415539 -v -0.015343 -0.025043 -0.013824 -vn 0.694717 -0.561811 0.449151 -v -0.015291 -0.024971 -0.013809 -vn 0.719228 -0.566869 0.401710 -v -0.015398 -0.025016 -0.013687 -vn 0.739914 -0.121590 0.661621 -v -0.014400 -0.023388 -0.013937 -vn 0.713254 -0.076728 0.696694 -v -0.014273 -0.023098 -0.014026 -vn 0.708956 -0.016607 0.705058 -v -0.014146 -0.022783 -0.014139 -vn 0.787879 -0.151588 0.596882 -v -0.015187 -0.023741 -0.013074 -vn 0.747325 -0.178082 0.640150 -v -0.014408 -0.023405 -0.013932 -vn 0.748109 -0.234204 0.620872 -v -0.014549 -0.023704 -0.013858 -vn 0.736122 -0.390166 0.553077 -v -0.014874 -0.024315 -0.013772 -vn 0.746791 -0.336026 0.573925 -v -0.014723 -0.024042 -0.013799 -vn 0.784837 -0.302367 0.540929 -v -0.015198 -0.024193 -0.013237 -vn 0.750708 -0.311968 0.582335 -v -0.014697 -0.023994 -0.013805 -vn 0.748979 -0.283288 0.598981 -v -0.014683 -0.023968 -0.013809 -vn 0.732254 -0.429265 0.528711 -v -0.014982 -0.024499 -0.013766 -vn 0.760209 -0.443411 0.474836 -v -0.015269 -0.024622 -0.013444 -vn 0.724204 -0.475553 0.499377 -v -0.015028 -0.024573 -0.013767 -vn 0.697388 -0.530276 0.482139 -v -0.015185 -0.024817 -0.013785 -vn 0.586781 -0.764573 0.266676 -v -0.015830 -0.025615 -0.014065 -vn 0.619950 -0.724104 0.302219 -v -0.015661 -0.025437 -0.013963 -vn 0.673327 -0.692306 0.259506 -v -0.017217 -0.026036 -0.011815 -vn 0.642247 -0.694185 0.325003 -v -0.015606 -0.025375 -0.013933 -vn 0.659564 -0.662395 0.355257 -v -0.015540 -0.025296 -0.013901 -vn 0.559884 -0.794585 0.234870 -v -0.015926 -0.025705 -0.014132 -vn 0.585943 -0.791105 0.175567 -v -0.017480 -0.026334 -0.012065 -vn 0.531899 -0.822258 0.202423 -v -0.015992 -0.025765 -0.014182 -vn 0.492683 -0.854357 0.165341 -v -0.016154 -0.025893 -0.014313 -vn 0.393918 -0.916807 0.065525 -v -0.016476 -0.026087 -0.014616 -vn 0.370362 -0.927898 0.042860 -v -0.016496 -0.026096 -0.014635 -vn 0.369785 -0.928049 -0.044550 -v -0.016496 -0.026096 0.014635 -vn 0.391558 -0.917400 -0.071132 -v -0.016476 -0.026087 0.014616 -vn 0.526040 -0.824584 -0.208189 -v -0.015992 -0.025765 0.014182 -vn 0.492022 -0.853144 -0.173377 -v -0.016154 -0.025893 0.014313 -vn 0.477141 -0.872826 -0.102526 -v -0.016601 -0.026099 0.013961 -vn 0.460315 -0.877677 -0.133389 -v -0.016247 -0.025957 0.014395 -vn 0.424790 -0.899524 -0.102030 -v -0.016315 -0.026001 0.014458 -vn 0.584825 -0.762960 -0.275447 -v -0.015830 -0.025615 0.014065 -vn 0.556551 -0.795830 -0.238551 -v -0.015926 -0.025705 0.014132 -vn 0.574518 -0.793705 -0.199904 -v -0.016315 -0.025863 0.013660 -vn 0.659978 -0.651929 -0.373387 -v -0.015501 -0.025249 0.013884 -vn 0.637463 -0.691909 -0.338973 -v -0.015606 -0.025375 0.013933 -vn 0.657455 -0.694094 -0.293234 -v -0.016073 -0.025567 0.013375 -vn 0.614627 -0.725343 -0.310018 -v -0.015661 -0.025437 0.013963 -vn 0.714182 -0.526264 -0.461509 -v -0.015185 -0.024817 0.013785 -vn 0.698205 -0.572539 -0.429777 -v -0.015291 -0.024971 0.013809 -vn 0.723165 -0.577322 -0.379119 -v -0.015880 -0.025217 0.013112 -vn 0.682147 -0.609611 -0.403795 -v -0.015343 -0.025043 0.013824 -vn 0.746500 -0.389389 -0.539550 -v -0.014874 -0.024315 0.013772 -vn 0.738362 -0.440209 -0.510918 -v -0.014982 -0.024499 0.013766 -vn 0.769741 -0.446409 -0.456309 -v -0.015743 -0.024824 0.012879 -vn 0.728746 -0.479914 -0.488479 -v -0.015028 -0.024573 0.013767 -vn 0.755437 -0.316352 -0.573791 -v -0.014697 -0.023994 0.013805 -vn 0.752582 -0.343438 -0.561846 -v -0.014723 -0.024042 0.013799 -vn 0.754035 -0.187800 -0.629414 -v -0.014408 -0.023405 0.013932 -vn 0.803831 -0.149407 -0.575789 -v -0.015644 -0.023946 0.012522 -vn 0.724886 -0.031948 -0.688128 -v -0.014146 -0.022783 0.014139 -vn 0.739592 -0.084618 -0.667715 -v -0.014273 -0.023098 0.014026 -vn 0.753343 -0.148961 -0.640535 -v -0.014400 -0.023388 0.013937 -vn 0.847668 -0.146421 0.509921 -v -0.016709 -0.024424 -0.011059 -vn 0.901970 -0.145615 0.406505 -v -0.017964 -0.024987 -0.008872 -vn 0.941342 -0.151226 0.301671 -v -0.018935 -0.025421 -0.006547 -vn 0.969803 -0.144772 0.196273 -v -0.019606 -0.025722 -0.004120 -vn 0.986598 -0.142530 0.079435 -v -0.019967 -0.025884 -0.001628 -vn 0.988131 -0.146817 -0.045184 -v -0.020013 -0.025905 0.000890 -vn 0.975972 -0.146363 -0.161421 -v -0.019744 -0.025784 0.003395 -vn 0.950083 -0.146541 -0.275440 -v -0.019161 -0.025523 0.005848 -vn 0.911868 -0.147649 -0.383010 -v -0.018275 -0.025126 0.008212 -vn 0.862209 -0.151604 -0.483334 -v -0.017096 -0.024598 0.010449 -vn 0.846565 -0.302026 -0.438301 -v -0.017141 -0.025043 0.010584 -vn 0.890586 -0.299185 -0.342556 -v -0.018341 -0.025567 0.008320 -vn 0.923421 -0.297146 -0.242895 -v -0.019244 -0.025961 0.005926 -vn 0.944869 -0.295751 -0.140552 -v -0.019837 -0.026220 0.003440 -vn 0.954755 -0.295125 -0.036657 -v -0.020112 -0.026340 0.000902 -vn 0.953029 -0.295242 0.067590 -v -0.020064 -0.026319 -0.001650 -vn 0.939716 -0.296108 0.171041 -v -0.019696 -0.026158 -0.004175 -vn 0.914927 -0.297708 0.272541 -v -0.019013 -0.025860 -0.006634 -vn 0.878856 -0.300081 0.370896 -v -0.018025 -0.025429 -0.008988 -vn 0.831789 -0.303214 0.464961 -v -0.016747 -0.024870 -0.011201 -vn 0.810660 -0.443323 -0.382486 -v -0.017248 -0.025466 0.010751 -vn 0.847281 -0.439400 -0.298401 -v -0.018470 -0.025987 0.008452 -vn 0.874502 -0.436580 -0.211292 -v -0.019390 -0.026379 0.006021 -vn 0.892252 -0.434701 -0.122151 -v -0.019994 -0.026636 0.003495 -vn 0.900429 -0.433836 -0.031857 -v -0.020273 -0.026755 0.000916 -vn 0.898968 -0.434063 0.058708 -v -0.020225 -0.026735 -0.001677 -vn 0.887956 -0.435239 0.148663 -v -0.019850 -0.026575 -0.004242 -vn 0.867454 -0.437371 0.237130 -v -0.019154 -0.026278 -0.006740 -vn 0.837485 -0.440662 0.323165 -v -0.018148 -0.025849 -0.009131 -vn 0.798294 -0.444918 0.405925 -v -0.016846 -0.025295 -0.011377 -vn 0.754989 -0.573853 -0.317309 -v -0.017414 -0.025857 0.010946 -vn 0.784066 -0.569322 -0.247210 -v -0.018658 -0.026376 0.008606 -vn 0.805653 -0.565986 -0.174880 -v -0.019595 -0.026767 0.006130 -vn 0.819691 -0.563827 -0.101027 -v -0.020210 -0.027023 0.003559 -vn 0.826133 -0.562859 -0.026345 -v -0.020495 -0.027142 0.000933 -vn 0.824970 -0.563089 0.048530 -v -0.020446 -0.027122 -0.001707 -vn 0.816280 -0.564419 0.122958 -v -0.020064 -0.026962 -0.004319 -vn 0.800006 -0.566982 0.196271 -v -0.019355 -0.026667 -0.006862 -vn 0.776296 -0.570647 0.267818 -v -0.018330 -0.026239 -0.009296 -vn 0.745005 -0.575410 0.337449 -v -0.017004 -0.025686 -0.011584 -vn 0.680979 -0.690292 -0.244466 -v -0.017634 -0.026207 0.011164 -vn 0.702493 -0.685793 -0.190240 -v -0.018901 -0.026726 0.008776 -vn 0.718446 -0.682460 -0.134475 -v -0.019855 -0.027116 0.006251 -vn 0.728773 -0.680340 -0.077639 -v -0.020481 -0.027373 0.003629 -vn 0.733498 -0.679390 -0.020242 -v -0.020771 -0.027492 0.000951 -vn 0.732672 -0.679560 0.037284 -v -0.020721 -0.027471 -0.001740 -vn 0.726288 -0.680864 0.094502 -v -0.020333 -0.027312 -0.004404 -vn 0.714242 -0.683430 0.150937 -v -0.019611 -0.027016 -0.006997 -vn 0.696746 -0.687053 0.206165 -v -0.018567 -0.026589 -0.009481 -vn 0.625666 -0.654217 0.424902 -v -0.015501 -0.025249 -0.013884 -vn 0.590454 -0.789874 -0.165718 -v -0.017905 -0.026506 0.011400 -vn 0.604502 -0.786115 -0.128843 -v -0.019194 -0.027027 0.008960 -vn 0.614909 -0.783328 -0.091021 -v -0.020164 -0.027420 0.006381 -vn 0.621623 -0.781553 -0.052529 -v -0.020802 -0.027677 0.003704 -vn 0.624698 -0.780746 -0.013698 -v -0.021097 -0.027797 0.000971 -vn 0.624125 -0.780918 0.025216 -v -0.021046 -0.027776 -0.001777 -vn 0.619942 -0.782039 0.063927 -v -0.020650 -0.027616 -0.004495 -vn 0.612158 -0.784108 0.102169 -v -0.019916 -0.027319 -0.007143 -vn 0.600693 -0.787192 0.139631 -v -0.018854 -0.026890 -0.009680 -vn 0.485605 -0.870234 -0.082950 -v -0.018218 -0.026748 0.011648 -vn 0.492402 -0.867978 -0.064458 -v -0.019529 -0.027274 0.009153 -vn 0.497403 -0.866325 -0.045503 -v -0.020516 -0.027670 0.006518 -vn 0.500629 -0.865264 -0.026250 -v -0.021163 -0.027929 0.003783 -vn 0.502115 -0.864774 -0.006847 -v -0.021463 -0.028050 0.000991 -vn 0.501837 -0.864870 0.012596 -v -0.021412 -0.028029 -0.001814 -vn 0.499800 -0.865552 0.031947 -v -0.021010 -0.027868 -0.004591 -vn 0.496056 -0.866787 0.051075 -v -0.020263 -0.027568 -0.007296 -vn 0.490485 -0.868648 0.069817 -v -0.019184 -0.027135 -0.009889 -vn 0.098769 -0.897725 -0.429343 -v -0.014458 -0.026001 0.016315 -vn 0.132927 -0.876822 -0.462076 -v -0.014395 -0.025957 0.016247 -vn 0.088670 -0.870885 -0.483422 -v -0.012328 -0.026575 0.017786 -vn 0.415670 -0.609475 -0.675099 -v -0.013824 -0.025043 0.015343 -vn 0.449210 -0.561756 -0.694724 -v -0.013809 -0.024971 0.015291 -vn 0.401731 -0.566822 -0.719253 -v -0.013687 -0.025016 0.015398 -vn -0.610080 -0.236212 -0.756311 -v 0.013858 -0.023704 0.014549 -vn -0.583791 -0.293912 -0.756838 -v 0.013809 -0.023968 0.014683 -vn -0.523328 -0.304671 -0.795804 -v 0.012680 -0.024397 0.015663 -vn -0.044751 -0.927969 -0.369962 -v 0.014635 -0.026096 0.016496 -vn -0.071245 -0.917355 -0.391642 -v 0.014616 -0.026087 0.016477 -vn -0.208145 -0.824628 -0.525989 -v 0.014182 -0.025765 0.015992 -vn -0.173420 -0.853131 -0.492030 -v 0.014313 -0.025893 0.016154 -vn -0.102541 -0.872827 -0.477136 -v 0.013961 -0.026099 0.016601 -vn -0.133425 -0.877664 -0.460331 -v 0.014395 -0.025957 0.016247 -vn -0.102022 -0.899536 -0.424766 -v 0.014458 -0.026001 0.016315 -vn -0.275449 -0.762926 -0.584869 -v 0.014065 -0.025615 0.015830 -vn -0.238483 -0.795883 -0.556503 -v 0.014132 -0.025705 0.015926 -vn -0.199898 -0.793717 -0.574504 -v 0.013660 -0.025863 0.016315 -vn -0.373347 -0.651984 -0.659946 -v 0.013884 -0.025249 0.015501 -vn -0.338925 -0.691958 -0.637436 -v 0.013933 -0.025375 0.015606 -vn -0.293228 -0.694103 -0.657448 -v 0.013375 -0.025567 0.016073 -vn -0.310044 -0.725297 -0.614668 -v 0.013963 -0.025437 0.015661 -vn -0.461513 -0.526308 -0.714147 -v 0.013785 -0.024817 0.015185 -vn -0.429802 -0.572459 -0.698256 -v 0.013809 -0.024971 0.015291 -vn -0.379131 -0.577305 -0.723172 -v 0.013112 -0.025217 0.015880 -vn -0.403893 -0.609442 -0.682239 -v 0.013824 -0.025043 0.015343 -vn -0.539635 -0.389309 -0.746480 -v 0.013772 -0.024315 0.014874 -vn -0.510981 -0.440161 -0.738347 -v 0.013766 -0.024499 0.014982 -vn -0.456330 -0.446369 -0.769752 -v 0.012879 -0.024824 0.015743 -vn -0.488426 -0.480045 -0.728696 -v 0.013767 -0.024573 0.015028 -vn -0.573890 -0.316084 -0.755474 -v 0.013805 -0.023994 0.014697 -vn -0.561956 -0.343247 -0.752587 -v 0.013799 -0.024042 0.014723 -vn -0.580692 -0.152598 -0.799694 -v 0.012522 -0.023946 0.015644 -vn -0.629568 -0.187158 -0.754066 -v 0.013932 -0.023405 0.014408 -vn -0.656551 -0.128842 -0.743196 -v 0.013937 -0.023388 0.014400 -vn -0.692666 -0.028685 -0.720688 -v 0.014139 -0.022783 0.014146 -vn 0.690462 -0.027030 -0.722863 -v -0.014139 -0.022783 0.014146 -vn 0.679013 -0.081296 -0.729612 -v -0.014026 -0.023098 0.014273 -vn 0.660127 -0.129633 -0.739883 -v -0.013937 -0.023388 0.014400 -vn 0.596035 -0.149134 -0.788988 -v -0.013074 -0.023741 0.015187 -vn 0.640497 -0.176746 -0.747345 -v -0.013932 -0.023405 0.014408 -vn 0.620891 -0.234258 -0.748076 -v -0.013858 -0.023704 0.014549 -vn 0.553108 -0.390119 -0.736124 -v -0.013772 -0.024315 0.014874 -vn 0.573916 -0.336083 -0.746772 -v -0.013799 -0.024042 0.014723 -vn 0.540944 -0.302325 -0.784844 -v -0.013237 -0.024193 0.015198 -vn 0.582738 -0.310828 -0.750868 -v -0.013805 -0.023994 0.014697 -vn 0.599256 -0.282365 -0.749107 -v -0.013809 -0.023968 0.014683 -vn 0.528761 -0.429191 -0.732262 -v -0.013767 -0.024499 0.014982 -vn 0.474856 -0.443410 -0.760197 -v -0.013444 -0.024622 0.015269 -vn 0.499407 -0.475540 -0.724192 -v -0.013767 -0.024573 0.015028 -vn 0.482169 -0.530420 -0.697257 -v -0.013785 -0.024817 0.015185 -vn 0.266682 -0.764554 -0.586804 -v -0.014065 -0.025615 0.015830 -vn 0.302299 -0.724026 -0.620001 -v -0.013963 -0.025437 0.015661 -vn 0.259479 -0.692352 -0.673290 -v -0.011815 -0.026036 0.017217 -vn 0.324943 -0.694295 -0.642158 -v -0.013933 -0.025375 0.015606 -vn 0.355208 -0.662480 -0.659506 -v -0.013901 -0.025296 0.015540 -vn 0.234813 -0.794622 -0.559855 -v -0.014132 -0.025705 0.015926 -vn 0.175561 -0.791118 -0.585927 -v -0.012065 -0.026334 0.017480 -vn 0.202390 -0.822277 -0.531883 -v -0.014182 -0.025765 0.015992 -vn 0.165344 -0.854346 -0.492701 -v -0.014313 -0.025893 0.016154 -vn 0.065610 -0.916762 -0.394008 -v -0.014616 -0.026087 0.016477 -vn 0.043018 -0.927836 -0.370500 -v -0.014635 -0.026096 0.016496 -vn 0.511389 -0.150606 -0.846049 -v -0.011059 -0.024424 0.016709 -vn 0.415970 -0.147738 -0.897297 -v -0.008872 -0.024987 0.017964 -vn 0.307386 -0.144219 -0.940593 -v -0.006547 -0.025421 0.018935 -vn 0.192357 -0.142711 -0.970893 -v -0.004120 -0.025722 0.019605 -vn 0.069623 -0.145263 -0.986940 -v -0.001628 -0.025884 0.019967 -vn -0.046614 -0.144662 -0.988383 -v 0.000889 -0.025905 0.020013 -vn -0.161074 -0.144862 -0.976253 -v 0.003395 -0.025784 0.019744 -vn -0.268971 -0.150794 -0.951271 -v 0.005848 -0.025523 0.019162 -vn -0.375384 -0.145568 -0.915367 -v 0.008212 -0.025126 0.018275 -vn -0.481060 -0.146071 -0.864433 -v 0.010449 -0.024598 0.017096 -vn -0.679019 -0.081240 -0.729612 -v 0.014026 -0.023098 0.014273 -vn -0.438292 -0.302044 -0.846563 -v 0.010584 -0.025043 0.017141 -vn -0.342567 -0.299176 -0.890585 -v 0.008320 -0.025567 0.018341 -vn -0.242919 -0.297077 -0.923437 -v 0.005926 -0.025961 0.019244 -vn -0.140546 -0.295752 -0.944869 -v 0.003440 -0.026220 0.019837 -vn -0.036659 -0.295151 -0.954747 -v 0.000902 -0.026340 0.020112 -vn 0.067590 -0.295284 -0.953016 -v -0.001650 -0.026319 0.020064 -vn 0.171037 -0.296150 -0.939703 -v -0.004175 -0.026158 0.019696 -vn 0.272520 -0.297758 -0.914917 -v -0.006634 -0.025860 0.019013 -vn 0.370886 -0.300121 -0.878847 -v -0.008988 -0.025429 0.018025 -vn 0.464962 -0.303219 -0.831786 -v -0.011201 -0.024870 0.016747 -vn -0.382457 -0.443374 -0.810645 -v 0.010751 -0.025466 0.017248 -vn -0.298387 -0.439421 -0.847275 -v 0.008452 -0.025987 0.018470 -vn -0.211303 -0.436542 -0.874518 -v 0.006021 -0.026379 0.019390 -vn -0.122162 -0.434690 -0.892256 -v 0.003495 -0.026636 0.019994 -vn -0.031857 -0.433852 -0.900421 -v 0.000916 -0.026755 0.020273 -vn 0.058717 -0.434027 -0.898984 -v -0.001677 -0.026735 0.020225 -vn 0.148667 -0.435207 -0.887971 -v -0.004242 -0.026575 0.019850 -vn 0.237119 -0.437404 -0.867440 -v -0.006740 -0.026278 0.019154 -vn 0.323183 -0.440625 -0.837498 -v -0.009131 -0.025850 0.018148 -vn 0.405945 -0.444873 -0.798309 -v -0.011377 -0.025295 0.016846 -vn -0.317324 -0.573834 -0.754997 -v 0.010946 -0.025857 0.017414 -vn -0.247212 -0.569308 -0.784076 -v 0.008606 -0.026376 0.018658 -vn -0.174883 -0.565988 -0.805651 -v 0.006130 -0.026767 0.019595 -vn -0.101032 -0.563843 -0.819679 -v 0.003559 -0.027023 0.020210 -vn -0.026341 -0.562874 -0.826123 -v 0.000933 -0.027142 0.020495 -vn 0.048539 -0.563065 -0.824986 -v -0.001707 -0.027122 0.020446 -vn 0.122963 -0.564415 -0.816282 -v -0.004319 -0.026962 0.020064 -vn 0.196279 -0.566933 -0.800039 -v -0.006862 -0.026667 0.019355 -vn 0.267834 -0.570634 -0.776300 -v -0.009296 -0.026239 0.018330 -vn 0.337446 -0.575417 -0.745000 -v -0.011584 -0.025686 0.017004 -vn -0.244476 -0.690281 -0.680987 -v 0.011164 -0.026207 0.017634 -vn -0.190249 -0.685772 -0.702511 -v 0.008776 -0.026726 0.018901 -vn -0.134475 -0.682459 -0.718447 -v 0.006251 -0.027116 0.019855 -vn -0.077647 -0.680332 -0.728779 -v 0.003629 -0.027373 0.020481 -vn -0.020241 -0.679363 -0.733524 -v 0.000951 -0.027492 0.020771 -vn 0.037291 -0.679547 -0.732683 -v -0.001741 -0.027471 0.020721 -vn 0.094500 -0.680889 -0.726265 -v -0.004404 -0.027312 0.020333 -vn 0.150944 -0.683395 -0.714274 -v -0.006997 -0.027016 0.019611 -vn 0.206154 -0.687070 -0.696732 -v -0.009481 -0.026589 0.018567 -vn 0.424916 -0.654149 -0.625728 -v -0.013884 -0.025249 0.015501 -vn -0.165708 -0.789883 -0.590446 -v 0.011400 -0.026506 0.017905 -vn -0.128845 -0.786113 -0.604504 -v 0.008960 -0.027027 0.019194 -vn -0.091017 -0.783340 -0.614894 -v 0.006381 -0.027420 0.020164 -vn -0.052533 -0.781554 -0.621622 -v 0.003704 -0.027677 0.020801 -vn -0.013694 -0.780739 -0.624707 -v 0.000971 -0.027797 0.021097 -vn 0.025219 -0.780894 -0.624154 -v -0.001777 -0.027776 0.021046 -vn 0.063932 -0.782021 -0.619965 -v -0.004495 -0.027616 0.020650 -vn 0.102162 -0.784116 -0.612148 -v -0.007143 -0.027319 0.019916 -vn 0.139618 -0.787199 -0.600687 -v -0.009680 -0.026890 0.018854 -vn -0.082941 -0.870240 -0.485596 -v 0.011648 -0.026748 0.018218 -vn -0.064447 -0.867987 -0.492388 -v 0.009153 -0.027274 0.019529 -vn -0.045501 -0.866330 -0.497395 -v 0.006518 -0.027670 0.020516 -vn -0.026253 -0.865264 -0.500629 -v 0.003783 -0.027929 0.021163 -vn -0.006843 -0.864779 -0.502106 -v 0.000991 -0.028050 0.021463 -vn 0.012599 -0.864876 -0.501828 -v -0.001814 -0.028029 0.021412 -vn 0.031943 -0.865550 -0.499803 -v -0.004591 -0.027868 0.021010 -vn 0.051062 -0.866803 -0.496029 -v -0.007296 -0.027568 0.020263 -vn 0.069818 -0.868645 -0.490491 -v -0.009889 -0.027135 0.019184 -vn -0.951307 0.290397 -0.103364 -v -0.026000 -0.016132 0.015195 -vn -0.959721 0.198695 -0.198637 -v -0.025958 -0.015672 0.015672 -vn -0.951347 0.103143 -0.290345 -v -0.026000 -0.015195 0.016132 -vn -0.020196 0.708285 -0.705638 -v -0.022783 -0.014144 0.014140 -vn -0.020981 0.706685 -0.707217 -v -0.022783 -0.014142 0.014142 -vn -0.020345 0.706766 -0.707155 -v -0.022783 -0.014140 0.014144 -vn -0.079927 0.691084 -0.718341 -v -0.023097 -0.014089 0.014213 -vn -0.160452 0.723834 -0.671058 -v -0.023403 -0.014295 0.014057 -vn -0.233930 0.651916 -0.721306 -v -0.023700 -0.014043 0.014389 -vn -0.474479 0.557312 -0.681376 -v -0.024545 -0.014119 0.014751 -vn -0.541662 0.520463 -0.660092 -v -0.024777 -0.014177 0.014881 -vn -0.944946 0.117500 -0.305402 -v -0.025971 -0.015125 0.016063 -vn -0.944973 0.305330 -0.117475 -v -0.025971 -0.016063 0.015125 -vn -0.933832 0.328876 -0.140710 -v -0.025962 -0.016045 0.015107 -vn -0.910539 0.371276 -0.181862 -v -0.025880 -0.015892 0.014955 -vn -0.933817 0.140839 -0.328862 -v -0.025962 -0.015107 0.016045 -vn -0.910625 0.181919 -0.371035 -v -0.025880 -0.014955 0.015892 -vn -0.874179 0.236978 -0.423855 -v -0.025779 -0.014812 0.015741 -vn -0.832982 0.472798 -0.287408 -v -0.025660 -0.015591 0.014678 -vn -0.874297 0.424201 -0.235920 -v -0.025779 -0.015741 0.014812 -vn -0.833390 0.287964 -0.471738 -v -0.025660 -0.014678 0.015591 -vn -0.783895 0.340783 -0.519014 -v -0.025521 -0.014554 0.015443 -vn -0.729525 0.562114 -0.389643 -v -0.025357 -0.015292 0.014437 -vn -0.784444 0.519742 -0.338403 -v -0.025521 -0.015443 0.014554 -vn -0.731354 0.388727 -0.560368 -v -0.025357 -0.014437 0.015292 -vn -0.670765 0.436884 -0.599339 -v -0.025182 -0.014337 0.015151 -vn -0.673198 0.598627 -0.434109 -v -0.025182 -0.015151 0.014337 -vn -0.610342 0.633164 -0.476011 -v -0.024989 -0.015014 0.014250 -vn -0.611447 0.477943 -0.630637 -v -0.024989 -0.014250 0.015014 -vn -0.474670 0.684726 -0.553028 -v -0.024545 -0.014751 0.014119 -vn -0.544151 0.661652 -0.515864 -v -0.024777 -0.014881 0.014177 -vn -0.399389 0.591952 -0.700058 -v -0.024296 -0.014076 0.014629 -vn -0.953733 0.212558 -0.212633 -v -0.025929 -0.015604 0.015604 -vn -0.942556 0.236189 -0.236227 -v -0.025920 -0.015586 0.015586 -vn -0.918570 0.279396 -0.279585 -v -0.025839 -0.015436 0.015436 -vn -0.882321 0.332555 -0.333043 -v -0.025741 -0.015291 0.015291 -vn -0.839905 0.383386 -0.384154 -v -0.025624 -0.015151 0.015151 -vn -0.790947 0.432109 -0.433227 -v -0.025490 -0.015016 0.015016 -vn -0.735805 0.478125 -0.479571 -v -0.025330 -0.014882 0.014882 -vn -0.676449 0.519930 -0.521622 -v -0.025160 -0.014762 0.014762 -vn -0.613438 0.557437 -0.559426 -v -0.024971 -0.014649 0.014649 -vn -0.546335 0.591117 -0.593380 -v -0.024763 -0.014544 0.014544 -vn -0.475687 0.620751 -0.623209 -v -0.024535 -0.014447 0.014447 -vn -0.402531 0.646018 -0.648560 -v -0.024290 -0.014362 0.014362 -vn -0.343762 0.663163 -0.664863 -v -0.024028 -0.014289 0.014289 -vn -0.402210 0.702892 -0.586660 -v -0.024296 -0.014629 0.014076 -vn -0.342943 0.711274 -0.613579 -v -0.024032 -0.014514 0.014051 -vn -0.300289 0.718566 -0.627287 -v -0.023984 -0.014495 0.014048 -vn -0.237733 0.723046 -0.648604 -v -0.023700 -0.014389 0.014043 -vn -0.299075 0.673998 -0.675486 -v -0.023981 -0.014278 0.014278 -vn -0.342987 0.617066 -0.708230 -v -0.024032 -0.014051 0.014514 -vn -0.236962 0.685861 -0.688072 -v -0.023698 -0.014220 0.014220 -vn -0.300973 0.628366 -0.717336 -v -0.023984 -0.014048 0.014495 -vn -0.081057 0.718775 -0.690502 -v -0.023097 -0.014213 0.014089 -vn -0.158998 0.697272 -0.698950 -v -0.023403 -0.014178 0.014178 -vn -0.161189 0.673395 -0.721497 -v -0.023403 -0.014057 0.014295 -vn -0.080744 0.704334 -0.705262 -v -0.023097 -0.014151 0.014151 -vn -0.951345 0.290349 0.103153 -v -0.026000 -0.016132 -0.015195 -vn -0.959750 0.198623 0.198566 -v -0.025958 -0.015672 -0.015672 -vn -0.951332 0.103227 0.290365 -v -0.026000 -0.015195 -0.016132 -vn -0.020132 0.705641 0.708283 -v -0.022783 -0.014140 -0.014144 -vn -0.021055 0.707021 0.706879 -v -0.022783 -0.014142 -0.014142 -vn -0.020496 0.707346 0.706570 -v -0.022783 -0.014144 -0.014140 -vn -0.079925 0.718339 0.691087 -v -0.023097 -0.014213 -0.014089 -vn -0.160461 0.671056 0.723834 -v -0.023403 -0.014057 -0.014295 -vn -0.233931 0.721305 0.651916 -v -0.023700 -0.014389 -0.014043 -vn -0.944950 0.305394 0.117492 -v -0.025971 -0.016063 -0.015125 -vn -0.944978 0.117463 0.305318 -v -0.025971 -0.015125 -0.016063 -vn -0.933836 0.140702 0.328867 -v -0.025962 -0.015107 -0.016045 -vn -0.910539 0.181862 0.371275 -v -0.025880 -0.014955 -0.015892 -vn -0.933820 0.328855 0.140833 -v -0.025962 -0.016045 -0.015107 -vn -0.910624 0.371037 0.181921 -v -0.025880 -0.015892 -0.014955 -vn -0.874179 0.423855 0.236978 -v -0.025779 -0.015741 -0.014812 -vn -0.832983 0.287407 0.472797 -v -0.025660 -0.014678 -0.015591 -vn -0.874299 0.235917 0.424199 -v -0.025779 -0.014812 -0.015741 -vn -0.833391 0.471738 0.287964 -v -0.025660 -0.015591 -0.014678 -vn -0.783893 0.519015 0.340785 -v -0.025521 -0.015443 -0.014554 -vn -0.729526 0.389644 0.562112 -v -0.025357 -0.014437 -0.015292 -vn -0.784440 0.338407 0.519745 -v -0.025521 -0.014554 -0.015443 -vn -0.731353 0.560369 0.388728 -v -0.025357 -0.015292 -0.014437 -vn -0.670765 0.599339 0.436884 -v -0.025182 -0.015151 -0.014337 -vn -0.673197 0.434110 0.598627 -v -0.025182 -0.014337 -0.015151 -vn -0.610337 0.476013 0.633167 -v -0.024989 -0.014250 -0.015014 -vn -0.611451 0.630634 0.477941 -v -0.024989 -0.015014 -0.014250 -vn -0.541663 0.660092 0.520461 -v -0.024777 -0.014881 -0.014177 -vn -0.474672 0.553025 0.684726 -v -0.024545 -0.014119 -0.014751 -vn -0.544154 0.515863 0.661651 -v -0.024777 -0.014177 -0.014881 -vn -0.398565 0.700968 0.591430 -v -0.024296 -0.014629 -0.014076 -vn -0.475922 0.681751 0.555620 -v -0.024545 -0.014751 -0.014119 -vn -0.953731 0.212639 0.212562 -v -0.025929 -0.015604 -0.015604 -vn -0.942553 0.236231 0.236195 -v -0.025920 -0.015586 -0.015586 -vn -0.918569 0.279587 0.279396 -v -0.025839 -0.015436 -0.015436 -vn -0.882320 0.333043 0.332557 -v -0.025741 -0.015291 -0.015291 -vn -0.839907 0.384152 0.383384 -v -0.025624 -0.015151 -0.015151 -vn -0.790947 0.433226 0.432110 -v -0.025490 -0.015016 -0.015016 -vn -0.735804 0.479571 0.478126 -v -0.025330 -0.014882 -0.014882 -vn -0.676449 0.521620 0.519931 -v -0.025160 -0.014762 -0.014762 -vn -0.613438 0.559426 0.557437 -v -0.024971 -0.014649 -0.014649 -vn -0.546331 0.593382 0.591118 -v -0.024763 -0.014544 -0.014544 -vn -0.475688 0.623209 0.620751 -v -0.024535 -0.014447 -0.014447 -vn -0.402534 0.648561 0.646015 -v -0.024290 -0.014362 -0.014362 -vn -0.343750 0.664866 0.663166 -v -0.024028 -0.014289 -0.014289 -vn -0.402209 0.586660 0.702893 -v -0.024296 -0.014076 -0.014629 -vn -0.342966 0.613574 0.711268 -v -0.024032 -0.014051 -0.014514 -vn -0.300310 0.627283 0.718561 -v -0.023984 -0.014048 -0.014495 -vn -0.237724 0.648608 0.723046 -v -0.023700 -0.014043 -0.014389 -vn -0.299063 0.675488 0.674001 -v -0.023981 -0.014278 -0.014278 -vn -0.342986 0.708231 0.617065 -v -0.024032 -0.014514 -0.014051 -vn -0.236962 0.688072 0.685861 -v -0.023698 -0.014220 -0.014220 -vn -0.300972 0.717337 0.628365 -v -0.023984 -0.014495 -0.014048 -vn -0.081057 0.690507 0.718770 -v -0.023097 -0.014089 -0.014213 -vn -0.159005 0.698961 0.697260 -v -0.023403 -0.014178 -0.014178 -vn -0.161186 0.721495 0.673397 -v -0.023403 -0.014295 -0.014057 -vn -0.080740 0.705253 0.704343 -v -0.023097 -0.014151 -0.014151 -vn 0.290465 0.951273 -0.103487 -v -0.016132 0.026000 0.015195 -vn 0.198692 0.959722 -0.198635 -v -0.015672 0.025958 0.015672 -vn 0.103231 0.951317 -0.290411 -v -0.015195 0.026000 0.016132 -vn 0.707613 0.017594 -0.706381 -v -0.014144 0.022783 0.014140 -vn 0.712110 0.020182 -0.701778 -v -0.014142 0.022783 0.014142 -vn 0.706417 0.021272 -0.707476 -v -0.014140 0.022783 0.014144 -vn 0.691213 0.079898 -0.718220 -v -0.014089 0.023097 0.014213 -vn 0.723812 0.160460 -0.671081 -v -0.014295 0.023403 0.014057 -vn 0.651948 0.233918 -0.721281 -v -0.014043 0.023700 0.014389 -vn 0.557308 0.474467 -0.681387 -v -0.014119 0.024545 0.014751 -vn 0.520417 0.541703 -0.660094 -v -0.014177 0.024777 0.014881 -vn 0.117216 0.945067 -0.305138 -v -0.015125 0.025971 0.016063 -vn 0.304939 0.945142 -0.117130 -v -0.016063 0.025971 0.015125 -vn 0.328457 0.934043 -0.140286 -v -0.016045 0.025962 0.015107 -vn 0.371276 0.910542 -0.181844 -v -0.015892 0.025880 0.014955 -vn 0.140509 0.933975 -0.328556 -v -0.015107 0.025962 0.016045 -vn 0.181922 0.910612 -0.371067 -v -0.014955 0.025880 0.015892 -vn 0.236894 0.874243 -0.423770 -v -0.014812 0.025779 0.015741 -vn 0.472786 0.832987 -0.287411 -v -0.015591 0.025660 0.014678 -vn 0.424102 0.874375 -0.235809 -v -0.015741 0.025779 0.014812 -vn 0.287972 0.833385 -0.471744 -v -0.014678 0.025660 0.015591 -vn 0.340806 0.783868 -0.519040 -v -0.014554 0.025521 0.015443 -vn 0.562104 0.729538 -0.389632 -v -0.015292 0.025357 0.014437 -vn 0.519795 0.784373 -0.338484 -v -0.015443 0.025521 0.014554 -vn 0.388677 0.731408 -0.560332 -v -0.014437 0.025357 0.015292 -vn 0.436872 0.670768 -0.599345 -v -0.014337 0.025182 0.015151 -vn 0.598627 0.673195 -0.434113 -v -0.015151 0.025182 0.014337 -vn 0.633193 0.610314 -0.476008 -v -0.015014 0.024989 0.014250 -vn 0.477951 0.611425 -0.630652 -v -0.014250 0.024989 0.015014 -vn 0.684702 0.474694 -0.553036 -v -0.014751 0.024545 0.014119 -vn 0.661677 0.544145 -0.515839 -v -0.014881 0.024777 0.014177 -vn 0.591973 0.399369 -0.700052 -v -0.014076 0.024296 0.014629 -vn 0.213077 0.953502 -0.213147 -v -0.015604 0.025929 0.015604 -vn 0.236705 0.942309 -0.236696 -v -0.015586 0.025920 0.015586 -vn 0.279365 0.918587 -0.279559 -v -0.015436 0.025839 0.015436 -vn 0.332505 0.882366 -0.332973 -v -0.015291 0.025741 0.015291 -vn 0.383446 0.839864 -0.384185 -v -0.015151 0.025624 0.015151 -vn 0.432201 0.790873 -0.433270 -v -0.015016 0.025490 0.015016 -vn 0.478110 0.735824 -0.479557 -v -0.014882 0.025330 0.014882 -vn 0.519910 0.676464 -0.521622 -v -0.014762 0.025159 0.014762 -vn 0.557412 0.613457 -0.559430 -v -0.014649 0.024971 0.014649 -vn 0.591088 0.546347 -0.593397 -v -0.014544 0.024763 0.014544 -vn 0.620707 0.475731 -0.623220 -v -0.014447 0.024535 0.014447 -vn 0.646006 0.402526 -0.648575 -v -0.014362 0.024290 0.014362 -vn 0.663252 0.343455 -0.664933 -v -0.014289 0.024028 0.014289 -vn 0.702876 0.402252 -0.586650 -v -0.014629 0.024296 0.014076 -vn 0.711251 0.342992 -0.613579 -v -0.014514 0.024032 0.014051 -vn 0.718565 0.300327 -0.627271 -v -0.014495 0.023984 0.014048 -vn 0.723060 0.237761 -0.648578 -v -0.014389 0.023700 0.014043 -vn 0.674074 0.298782 -0.675539 -v -0.014278 0.023981 0.014278 -vn 0.617007 0.343083 -0.708234 -v -0.014051 0.024032 0.014514 -vn 0.685855 0.236980 -0.688073 -v -0.014220 0.023698 0.014220 -vn 0.628320 0.301039 -0.717349 -v -0.014048 0.023984 0.014495 -vn 0.718678 0.081115 -0.690595 -v -0.014213 0.023097 0.014089 -vn 0.697255 0.159022 -0.698962 -v -0.014178 0.023403 0.014178 -vn 0.673436 0.161205 -0.721454 -v -0.014057 0.023403 0.014295 -vn 0.704294 0.080725 -0.705304 -v -0.014151 0.023097 0.014151 -vn -0.198619 0.959751 -0.198566 -v 0.015672 0.025958 0.015672 -vn -0.290443 0.951305 -0.103258 -v 0.016132 0.026000 0.015195 -vn -0.103309 0.951308 -0.290415 -v 0.015195 0.026000 0.016132 -vn -0.708314 0.020602 -0.705596 -v 0.014140 0.022783 0.014144 -vn -0.704245 0.019686 -0.709684 -v 0.014142 0.022783 0.014142 -vn -0.703606 0.021216 -0.710274 -v 0.014144 0.022783 0.014140 -vn -0.718379 0.079944 -0.691043 -v 0.014213 0.023097 0.014089 -vn -0.671028 0.160421 -0.723870 -v 0.014057 0.023403 0.014295 -vn -0.721315 0.233950 -0.651899 -v 0.014389 0.023700 0.014043 -vn -0.700968 0.398660 -0.591367 -v 0.014629 0.024296 0.014076 -vn -0.476006 0.610337 -0.633173 -v 0.014250 0.024989 0.015014 -vn -0.660102 0.541640 -0.520473 -v 0.014881 0.024777 0.014177 -vn -0.387433 0.730590 -0.562257 -v 0.014437 0.025357 0.015292 -vn -0.599335 0.670784 -0.436860 -v 0.015151 0.025182 0.014337 -vn -0.287408 0.832964 -0.472829 -v 0.014678 0.025660 0.015591 -vn -0.519037 0.783864 -0.340820 -v 0.015443 0.025521 0.014554 -vn -0.181840 0.910540 -0.371283 -v 0.014955 0.025880 0.015892 -vn -0.423810 0.874223 -0.236895 -v 0.015741 0.025779 0.014812 -vn -0.305152 0.945059 -0.117242 -v 0.016063 0.025971 0.015125 -vn -0.117171 0.945123 -0.304980 -v 0.015125 0.025971 0.016063 -vn -0.140361 0.934004 -0.328535 -v 0.015107 0.025962 0.016045 -vn -0.212969 0.953578 -0.212918 -v 0.015604 0.025929 0.015604 -vn -0.236541 0.942392 -0.236528 -v 0.015586 0.025920 0.015586 -vn -0.235828 0.874351 -0.424140 -v 0.014812 0.025779 0.015741 -vn -0.279579 0.918574 -0.279389 -v 0.015436 0.025839 0.015436 -vn -0.328562 0.933977 -0.140477 -v 0.016045 0.025962 0.015107 -vn -0.333000 0.882347 -0.332528 -v 0.015291 0.025741 0.015291 -vn -0.371074 0.910610 -0.181918 -v 0.015892 0.025880 0.014955 -vn -0.338432 0.784411 -0.519773 -v 0.014554 0.025521 0.015443 -vn -0.384147 0.839914 -0.383373 -v 0.015151 0.025624 0.015151 -vn -0.433246 0.790918 -0.432143 -v 0.015016 0.025490 0.015016 -vn -0.471753 0.833377 -0.287979 -v 0.015591 0.025660 0.014678 -vn -0.433297 0.672096 -0.600450 -v 0.014337 0.025182 0.015151 -vn -0.479565 0.735789 -0.478155 -v 0.014882 0.025330 0.014882 -vn -0.521619 0.676464 -0.519914 -v 0.014762 0.025159 0.014762 -vn -0.560313 0.731417 -0.388688 -v 0.015292 0.025357 0.014437 -vn -0.515869 0.544132 -0.661665 -v 0.014177 0.024777 0.014881 -vn -0.559416 0.613487 -0.557394 -v 0.014649 0.024971 0.014649 -vn -0.630642 0.611424 -0.477966 -v 0.015014 0.024989 0.014250 -vn -0.593387 0.546339 -0.591106 -v 0.014544 0.024763 0.014544 -vn -0.555856 0.472052 -0.684245 -v 0.014119 0.024545 0.014751 -vn -0.681743 0.475925 -0.555628 -v 0.014751 0.024545 0.014119 -vn -0.623210 0.475645 -0.620783 -v 0.014447 0.024535 0.014447 -vn -0.648567 0.402506 -0.646026 -v 0.014362 0.024290 0.014362 -vn -0.588179 0.404020 -0.700581 -v 0.014076 0.024296 0.014629 -vn -0.613614 0.342720 -0.711352 -v 0.014051 0.024032 0.014514 -vn -0.664840 0.344011 -0.663056 -v 0.014289 0.024028 0.014289 -vn -0.627331 0.300102 -0.718606 -v 0.014048 0.023984 0.014495 -vn -0.648587 0.237745 -0.723058 -v 0.014043 0.023700 0.014389 -vn -0.675457 0.299285 -0.673934 -v 0.014278 0.023981 0.014278 -vn -0.708304 0.342826 -0.617070 -v 0.014514 0.024032 0.014051 -vn -0.688072 0.236919 -0.685877 -v 0.014220 0.023698 0.014220 -vn -0.717389 0.300836 -0.628371 -v 0.014495 0.023984 0.014048 -vn -0.690521 0.081078 -0.718754 -v 0.014089 0.023097 0.014213 -vn -0.698989 0.158981 -0.697237 -v 0.014178 0.023403 0.014178 -vn -0.721545 0.161167 -0.673348 -v 0.014295 0.023403 0.014057 -vn -0.705326 0.080777 -0.704266 -v 0.014151 0.023097 0.014151 -vn -0.290482 0.951270 0.103471 -v 0.016132 0.026000 -0.015195 -vn -0.198703 0.959722 0.198621 -v 0.015672 0.025958 -0.015672 -vn -0.103216 0.951323 0.290398 -v 0.015195 0.026000 -0.016132 -vn -0.704879 0.022831 0.708960 -v 0.014144 0.022783 -0.014140 -vn -0.702710 0.020375 0.711184 -v 0.014142 0.022783 -0.014142 -vn -0.709309 0.020241 0.704607 -v 0.014140 0.022783 -0.014144 -vn -0.691130 0.079933 0.718296 -v 0.014089 0.023097 -0.014213 -vn -0.723868 0.160409 0.671032 -v 0.014295 0.023403 -0.014057 -vn -0.651881 0.233953 0.721330 -v 0.014043 0.023700 -0.014389 -vn -0.117148 0.945101 0.305057 -v 0.015125 0.025971 -0.016063 -vn -0.305056 0.945089 0.117253 -v 0.016063 0.025971 -0.015125 -vn -0.328576 0.933986 0.140385 -v 0.016045 0.025962 -0.015107 -vn -0.371292 0.910534 0.181850 -v 0.015892 0.025880 -0.014955 -vn -0.140435 0.934005 0.328500 -v 0.015107 0.025962 -0.016045 -vn -0.181911 0.910612 0.371072 -v 0.014955 0.025880 -0.015892 -vn -0.236887 0.874234 0.423792 -v 0.014812 0.025779 -0.015741 -vn -0.472838 0.832957 0.287414 -v 0.015591 0.025660 -0.014678 -vn -0.424155 0.874345 0.235825 -v 0.015741 0.025779 -0.014812 -vn -0.287971 0.833381 0.471751 -v 0.014678 0.025660 -0.015591 -vn -0.340828 0.783852 0.519050 -v 0.014554 0.025521 -0.015443 -vn -0.562060 0.729587 0.389603 -v 0.015292 0.025357 -0.014437 -vn -0.519761 0.784428 0.338410 -v 0.015443 0.025521 -0.014554 -vn -0.388693 0.731392 0.560342 -v 0.014437 0.025357 -0.015292 -vn -0.436866 0.670772 0.599344 -v 0.014337 0.025182 -0.015151 -vn -0.598644 0.673192 0.434094 -v 0.015151 0.025182 -0.014337 -vn -0.633174 0.610325 0.476019 -v 0.015014 0.024989 -0.014250 -vn -0.477953 0.611425 0.630650 -v 0.014250 0.024989 -0.015014 -vn -0.520446 0.541667 0.660101 -v 0.014177 0.024777 -0.014881 -vn -0.684689 0.474716 0.553033 -v 0.014751 0.024545 -0.014119 -vn -0.661673 0.544115 0.515876 -v 0.014881 0.024777 -0.014177 -vn -0.591389 0.398624 0.700969 -v 0.014076 0.024296 -0.014629 -vn -0.555624 0.475905 0.681760 -v 0.014119 0.024545 -0.014751 -vn -0.212946 0.953574 0.212956 -v 0.015604 0.025929 -0.015604 -vn -0.236518 0.942390 0.236559 -v 0.015586 0.025920 -0.015586 -vn -0.279387 0.918572 0.279585 -v 0.015436 0.025839 -0.015436 -vn -0.332526 0.882348 0.333000 -v 0.015291 0.025741 -0.015291 -vn -0.383369 0.839914 0.384152 -v 0.015151 0.025624 -0.015151 -vn -0.432126 0.790922 0.433254 -v 0.015016 0.025490 -0.015016 -vn -0.478151 0.735785 0.479575 -v 0.014882 0.025330 -0.014882 -vn -0.519922 0.676466 0.521608 -v 0.014762 0.025159 -0.014762 -vn -0.557408 0.613484 0.559405 -v 0.014649 0.024971 -0.014649 -vn -0.591112 0.546332 0.593387 -v 0.014544 0.024763 -0.014544 -vn -0.620775 0.475660 0.623206 -v 0.014447 0.024535 -0.014447 -vn -0.646063 0.402491 0.648539 -v 0.014362 0.024290 -0.014362 -vn -0.663076 0.344012 0.664821 -v 0.014289 0.024028 -0.014289 -vn -0.702874 0.402217 0.586676 -v 0.014629 0.024296 -0.014076 -vn -0.711343 0.342822 0.613567 -v 0.014514 0.024032 -0.014051 -vn -0.718618 0.300212 0.627265 -v 0.014495 0.023984 -0.014048 -vn -0.723030 0.237724 0.648626 -v 0.014389 0.023700 -0.014043 -vn -0.673944 0.299269 0.675454 -v 0.014278 0.023981 -0.014278 -vn -0.617108 0.342782 0.708292 -v 0.014051 0.024032 -0.014514 -vn -0.685899 0.236930 0.688046 -v 0.014220 0.023698 -0.014220 -vn -0.628435 0.300735 0.717376 -v 0.014048 0.023984 -0.014495 -vn -0.718834 0.081053 0.690441 -v 0.014213 0.023097 -0.014089 -vn -0.697319 0.158974 0.698909 -v 0.014178 0.023403 -0.014178 -vn -0.673366 0.161175 0.721527 -v 0.014057 0.023403 -0.014295 -vn -0.704364 0.080751 0.705231 -v 0.014151 0.023097 -0.014151 -vn 0.198606 0.959751 0.198579 -v -0.015672 0.025958 -0.015672 -vn 0.290431 0.951307 0.103267 -v -0.016132 0.026000 -0.015195 -vn 0.103317 0.951305 0.290420 -v -0.015195 0.026000 -0.016132 -vn 0.705280 0.022041 0.708586 -v -0.014140 0.022783 -0.014144 -vn 0.712423 0.021180 0.701431 -v -0.014142 0.022783 -0.014142 -vn 0.706647 0.018921 0.707313 -v -0.014144 0.022783 -0.014140 -vn 0.718222 0.079894 0.691212 -v -0.014213 0.023097 -0.014089 -vn 0.671099 0.160453 0.723797 -v -0.014057 0.023403 -0.014295 -vn 0.721308 0.233914 0.651919 -v -0.014389 0.023700 -0.014043 -vn 0.305046 0.945109 0.117115 -v -0.016063 0.025971 -0.015125 -vn 0.117207 0.945105 0.305023 -v -0.015125 0.025971 -0.016063 -vn 0.140418 0.933986 0.328561 -v -0.015107 0.025962 -0.016045 -vn 0.181852 0.910537 0.371286 -v -0.014955 0.025880 -0.015892 -vn 0.328438 0.934036 0.140373 -v -0.016045 0.025962 -0.015107 -vn 0.371044 0.910622 0.181916 -v -0.015892 0.025880 -0.014955 -vn 0.423759 0.874252 0.236881 -v -0.015741 0.025779 -0.014812 -vn 0.287415 0.832972 0.472812 -v -0.014678 0.025660 -0.015591 -vn 0.235820 0.874366 0.424114 -v -0.014812 0.025779 -0.015741 -vn 0.471722 0.833400 0.287963 -v -0.015591 0.025660 -0.014678 -vn 0.519065 0.783840 0.340831 -v -0.015443 0.025521 -0.014554 -vn 0.389602 0.729577 0.562074 -v -0.014437 0.025357 -0.015292 -vn 0.338434 0.784415 0.519765 -v -0.014554 0.025521 -0.015443 -vn 0.560381 0.731357 0.388704 -v -0.015292 0.025357 -0.014437 -vn 0.599346 0.670771 0.436865 -v -0.015151 0.025182 -0.014337 -vn 0.434113 0.673185 0.598638 -v -0.014337 0.025182 -0.015151 -vn 0.476010 0.610330 0.633176 -v -0.014250 0.024989 -0.015014 -vn 0.630663 0.611413 0.477952 -v -0.015014 0.024989 -0.014250 -vn 0.660116 0.541656 0.520439 -v -0.014881 0.024777 -0.014177 -vn 0.553031 0.474636 0.684746 -v -0.014119 0.024545 -0.014751 -vn 0.515816 0.544197 0.661652 -v -0.014177 0.024777 -0.014881 -vn 0.700947 0.398598 0.591432 -v -0.014629 0.024296 -0.014076 -vn 0.681732 0.475940 0.555627 -v -0.014751 0.024545 -0.014119 -vn 0.213107 0.953499 0.213130 -v -0.015604 0.025929 -0.015604 -vn 0.236728 0.942307 0.236682 -v -0.015586 0.025920 -0.015586 -vn 0.279564 0.918588 0.279358 -v -0.015436 0.025839 -0.015436 -vn 0.332980 0.882364 0.332502 -v -0.015291 0.025741 -0.015291 -vn 0.384194 0.839864 0.383436 -v -0.015151 0.025624 -0.015151 -vn 0.433297 0.790882 0.432157 -v -0.015016 0.025490 -0.015016 -vn 0.479553 0.735816 0.478126 -v -0.014882 0.025330 -0.014882 -vn 0.521607 0.676464 0.519926 -v -0.014762 0.025159 -0.014762 -vn 0.559415 0.613464 0.557419 -v -0.014649 0.024971 -0.014649 -vn 0.593356 0.546340 0.591136 -v -0.014544 0.024763 -0.014544 -vn 0.623175 0.475719 0.620761 -v -0.014447 0.024535 -0.014447 -vn 0.648555 0.402543 0.646015 -v -0.014362 0.024290 -0.014362 -vn 0.664916 0.343443 0.663276 -v -0.014289 0.024028 -0.014289 -vn 0.586687 0.402193 0.702880 -v -0.014076 0.024296 -0.014629 -vn 0.613542 0.343083 0.711239 -v -0.014051 0.024032 -0.014514 -vn 0.627266 0.300337 0.718565 -v -0.014048 0.023984 -0.014495 -vn 0.648624 0.237742 0.723025 -v -0.014043 0.023700 -0.014389 -vn 0.675541 0.298763 0.674081 -v -0.014278 0.023981 -0.014278 -vn 0.708222 0.343031 0.617050 -v -0.014514 0.024032 -0.014051 -vn 0.688079 0.236990 0.685845 -v -0.014220 0.023698 -0.014220 -vn 0.717351 0.301040 0.628317 -v -0.014495 0.023984 -0.014048 -vn 0.690615 0.081040 0.718668 -v -0.014089 0.023097 -0.014213 -vn 0.698956 0.159027 0.697259 -v -0.014178 0.023403 -0.014178 -vn 0.721448 0.161228 0.673438 -v -0.014295 0.023403 -0.014057 -vn 0.705256 0.080685 0.704347 -v -0.014151 0.023097 -0.014151 -vn 0.290431 -0.951307 -0.103267 -v -0.016132 -0.026000 0.015195 -vn 0.198613 -0.959748 -0.198586 -v -0.015672 -0.025958 0.015672 -vn 0.103322 -0.951303 -0.290425 -v -0.015195 -0.026000 0.016132 -vn 0.705458 -0.022011 -0.708410 -v -0.014140 -0.022783 0.014144 -vn 0.712617 -0.021107 -0.701236 -v -0.014142 -0.022783 0.014142 -vn 0.706648 -0.018846 -0.707315 -v -0.014144 -0.022783 0.014140 -vn 0.718222 -0.079895 -0.691211 -v -0.014213 -0.023097 0.014089 -vn 0.671097 -0.160454 -0.723798 -v -0.014057 -0.023403 0.014295 -vn 0.721310 -0.233916 -0.651917 -v -0.014389 -0.023700 0.014043 -vn 0.305051 -0.945107 -0.117117 -v -0.016063 -0.025971 0.015125 -vn 0.117226 -0.945096 -0.305042 -v -0.015125 -0.025971 0.016063 -vn 0.140426 -0.933980 -0.328575 -v -0.015107 -0.025962 0.016045 -vn 0.181851 -0.910537 -0.371285 -v -0.014955 -0.025880 0.015892 -vn 0.328439 -0.934035 -0.140376 -v -0.016045 -0.025962 0.015107 -vn 0.371042 -0.910623 -0.181917 -v -0.015892 -0.025880 0.014955 -vn 0.423760 -0.874250 -0.236884 -v -0.015741 -0.025779 0.014812 -vn 0.287416 -0.832972 -0.472811 -v -0.014678 -0.025660 0.015591 -vn 0.235824 -0.874364 -0.424117 -v -0.014812 -0.025779 0.015741 -vn 0.471722 -0.833399 -0.287966 -v -0.015591 -0.025660 0.014678 -vn 0.519064 -0.783841 -0.340831 -v -0.015443 -0.025521 0.014554 -vn 0.389600 -0.729579 -0.562072 -v -0.014437 -0.025357 0.015292 -vn 0.338432 -0.784417 -0.519763 -v -0.014554 -0.025521 0.015443 -vn 0.560380 -0.731358 -0.388703 -v -0.015292 -0.025357 0.014437 -vn 0.599345 -0.670771 -0.436865 -v -0.015151 -0.025182 0.014337 -vn 0.434113 -0.673185 -0.598639 -v -0.014337 -0.025182 0.015151 -vn 0.476010 -0.610329 -0.633177 -v -0.014250 -0.024989 0.015014 -vn 0.630663 -0.611415 -0.477950 -v -0.015014 -0.024989 0.014250 -vn 0.660115 -0.541656 -0.520439 -v -0.014881 -0.024777 0.014177 -vn 0.553035 -0.474631 -0.684746 -v -0.014119 -0.024545 0.014751 -vn 0.515817 -0.544195 -0.661653 -v -0.014177 -0.024777 0.014881 -vn 0.700948 -0.398597 -0.591433 -v -0.014629 -0.024296 0.014076 -vn 0.681733 -0.475937 -0.555629 -v -0.014751 -0.024545 0.014119 -vn 0.213098 -0.953503 -0.213121 -v -0.015604 -0.025929 0.015604 -vn 0.236711 -0.942316 -0.236661 -v -0.015586 -0.025920 0.015586 -vn 0.279562 -0.918589 -0.279355 -v -0.015436 -0.025839 0.015436 -vn 0.332980 -0.882365 -0.332500 -v -0.015291 -0.025741 0.015291 -vn 0.384195 -0.839863 -0.383437 -v -0.015151 -0.025624 0.015151 -vn 0.433297 -0.790881 -0.432159 -v -0.015016 -0.025490 0.015016 -vn 0.479552 -0.735817 -0.478125 -v -0.014882 -0.025330 0.014882 -vn 0.521607 -0.676462 -0.519928 -v -0.014762 -0.025159 0.014762 -vn 0.559414 -0.613465 -0.557419 -v -0.014649 -0.024971 0.014649 -vn 0.593354 -0.546344 -0.591134 -v -0.014544 -0.024763 0.014544 -vn 0.623177 -0.475716 -0.620761 -v -0.014447 -0.024535 0.014447 -vn 0.648556 -0.402540 -0.646016 -v -0.014362 -0.024290 0.014362 -vn 0.664914 -0.343457 -0.663270 -v -0.014289 -0.024028 0.014289 -vn 0.586686 -0.402193 -0.702880 -v -0.014076 -0.024296 0.014629 -vn 0.613543 -0.343074 -0.711242 -v -0.014051 -0.024032 0.014514 -vn 0.627267 -0.300326 -0.718568 -v -0.014048 -0.023984 0.014495 -vn 0.648621 -0.237745 -0.723027 -v -0.014043 -0.023700 0.014389 -vn 0.675540 -0.298774 -0.674077 -v -0.014278 -0.023981 0.014278 -vn 0.708223 -0.343022 -0.617055 -v -0.014514 -0.024032 0.014051 -vn 0.688080 -0.236989 -0.685844 -v -0.014220 -0.023698 0.014220 -vn 0.717351 -0.301031 -0.628322 -v -0.014495 -0.023984 0.014048 -vn 0.690611 -0.081038 -0.718672 -v -0.014089 -0.023097 0.014213 -vn 0.698954 -0.159024 -0.697262 -v -0.014178 -0.023403 0.014178 -vn 0.721449 -0.161224 -0.673438 -v -0.014295 -0.023403 0.014057 -vn 0.705255 -0.080687 -0.704348 -v -0.014151 -0.023097 0.014151 -vn 0.290469 -0.951272 0.103489 -v -0.016132 -0.026000 -0.015195 -vn 0.198699 -0.959719 0.198642 -v -0.015672 -0.025958 -0.015672 -vn 0.103228 -0.951318 0.290409 -v -0.015195 -0.026000 -0.016132 -vn 0.707612 -0.017667 0.706380 -v -0.014144 -0.022783 -0.014140 -vn 0.711933 -0.020286 0.701954 -v -0.014142 -0.022783 -0.014142 -vn 0.706222 -0.021348 0.707668 -v -0.014140 -0.022783 -0.014144 -vn 0.691220 -0.079898 0.718214 -v -0.014089 -0.023097 -0.014213 -vn 0.723812 -0.160461 0.671080 -v -0.014295 -0.023403 -0.014057 -vn 0.651948 -0.233918 0.721281 -v -0.014043 -0.023700 -0.014389 -vn 0.117199 -0.945074 0.305123 -v -0.015125 -0.025971 -0.016063 -vn 0.304938 -0.945142 0.117130 -v -0.016063 -0.025971 -0.015125 -vn 0.328454 -0.934045 0.140280 -v -0.016045 -0.025962 -0.015107 -vn 0.371277 -0.910542 0.181845 -v -0.015892 -0.025880 -0.014955 -vn 0.140498 -0.933982 0.328540 -v -0.015107 -0.025962 -0.016045 -vn 0.181925 -0.910611 0.371068 -v -0.014955 -0.025880 -0.015892 -vn 0.236894 -0.874243 0.423770 -v -0.014812 -0.025779 -0.015741 -vn 0.472785 -0.832988 0.287411 -v -0.015591 -0.025660 -0.014678 -vn 0.424102 -0.874375 0.235810 -v -0.015741 -0.025779 -0.014812 -vn 0.287973 -0.833385 0.471743 -v -0.014678 -0.025660 -0.015591 -vn 0.340810 -0.783864 0.519043 -v -0.014554 -0.025521 -0.015443 -vn 0.562102 -0.729540 0.389632 -v -0.015292 -0.025357 -0.014437 -vn 0.519797 -0.784371 0.338486 -v -0.015443 -0.025521 -0.014554 -vn 0.388678 -0.731408 0.560332 -v -0.014437 -0.025357 -0.015292 -vn 0.436871 -0.670769 0.599344 -v -0.014337 -0.025182 -0.015151 -vn 0.598627 -0.673195 0.434114 -v -0.015151 -0.025182 -0.014337 -vn 0.633192 -0.610313 0.476010 -v -0.015014 -0.024989 -0.014250 -vn 0.477953 -0.611424 0.630652 -v -0.014250 -0.024989 -0.015014 -vn 0.520415 -0.541705 0.660094 -v -0.014177 -0.024777 -0.014881 -vn 0.684704 -0.474692 0.553035 -v -0.014751 -0.024545 -0.014119 -vn 0.661676 -0.544145 0.515840 -v -0.014881 -0.024777 -0.014177 -vn 0.591458 -0.398549 0.700954 -v -0.014076 -0.024296 -0.014629 -vn 0.555629 -0.475901 0.681758 -v -0.014119 -0.024545 -0.014751 -vn 0.213078 -0.953502 0.213148 -v -0.015604 -0.025929 -0.015604 -vn 0.236695 -0.942313 0.236689 -v -0.015586 -0.025920 -0.015586 -vn 0.279363 -0.918588 0.279559 -v -0.015436 -0.025839 -0.015436 -vn 0.332505 -0.882365 0.332974 -v -0.015291 -0.025741 -0.015291 -vn 0.383443 -0.839866 0.384183 -v -0.015151 -0.025624 -0.015151 -vn 0.432201 -0.790873 0.433270 -v -0.015016 -0.025490 -0.015016 -vn 0.478111 -0.735823 0.479557 -v -0.014882 -0.025330 -0.014882 -vn 0.519911 -0.676465 0.521621 -v -0.014762 -0.025159 -0.014762 -vn 0.557412 -0.613457 0.559430 -v -0.014649 -0.024971 -0.014649 -vn 0.591091 -0.546343 0.593397 -v -0.014544 -0.024763 -0.014544 -vn 0.620705 -0.475732 0.623221 -v -0.014447 -0.024535 -0.014447 -vn 0.646003 -0.402530 0.648575 -v -0.014362 -0.024290 -0.014362 -vn 0.663256 -0.343444 0.664935 -v -0.014289 -0.024028 -0.014289 -vn 0.702877 -0.402256 0.586647 -v -0.014629 -0.024296 -0.014076 -vn 0.711248 -0.343004 0.613575 -v -0.014514 -0.024032 -0.014051 -vn 0.718564 -0.300335 0.627268 -v -0.014495 -0.023984 -0.014048 -vn 0.723060 -0.237760 0.648579 -v -0.014389 -0.023700 -0.014043 -vn 0.674078 -0.298770 0.675541 -v -0.014278 -0.023981 -0.014278 -vn 0.617006 -0.343093 0.708231 -v -0.014051 -0.024032 -0.014514 -vn 0.685853 -0.236981 0.688074 -v -0.014220 -0.023698 -0.014220 -vn 0.628317 -0.301051 0.717346 -v -0.014048 -0.023984 -0.014495 -vn 0.718678 -0.081117 0.690595 -v -0.014213 -0.023097 -0.014089 -vn 0.697256 -0.159024 0.698960 -v -0.014178 -0.023403 -0.014178 -vn 0.673438 -0.161201 0.721454 -v -0.014057 -0.023403 -0.014295 -vn 0.704293 -0.080725 0.705305 -v -0.014151 -0.023097 -0.014151 -vn -0.198627 -0.959748 0.198572 -v 0.015672 -0.025958 -0.015672 -vn -0.290447 -0.951303 0.103260 -v 0.016132 -0.026000 -0.015195 -vn -0.103305 -0.951308 0.290415 -v 0.015195 -0.026000 -0.016132 -vn -0.708138 -0.020632 0.705773 -v 0.014140 -0.022783 -0.014144 -vn -0.704049 -0.019760 0.709877 -v 0.014142 -0.022783 -0.014142 -vn -0.703604 -0.021291 0.710273 -v 0.014144 -0.022783 -0.014140 -vn -0.718377 -0.079943 0.691045 -v 0.014213 -0.023097 -0.014089 -vn -0.671029 -0.160419 0.723869 -v 0.014057 -0.023403 -0.014295 -vn -0.721315 -0.233948 0.651900 -v 0.014389 -0.023700 -0.014043 -vn -0.305151 -0.945059 0.117243 -v 0.016063 -0.025971 -0.015125 -vn -0.117151 -0.945131 0.304965 -v 0.015125 -0.025971 -0.016063 -vn -0.140349 -0.934011 0.328522 -v 0.015107 -0.025962 -0.016045 -vn -0.181842 -0.910539 0.371284 -v 0.014955 -0.025880 -0.015892 -vn -0.328559 -0.933979 0.140473 -v 0.016045 -0.025962 -0.015107 -vn -0.371074 -0.910609 0.181920 -v 0.015892 -0.025880 -0.014955 -vn -0.423811 -0.874222 0.236897 -v 0.015741 -0.025779 -0.014812 -vn -0.287409 -0.832964 0.472829 -v 0.014678 -0.025660 -0.015591 -vn -0.235827 -0.874352 0.424140 -v 0.014812 -0.025779 -0.015741 -vn -0.471752 -0.833378 0.287979 -v 0.015591 -0.025660 -0.014678 -vn -0.519039 -0.783862 0.340821 -v 0.015443 -0.025521 -0.014554 -vn -0.389624 -0.729563 0.562077 -v 0.014437 -0.025357 -0.015292 -vn -0.338435 -0.784407 0.519776 -v 0.014554 -0.025521 -0.015443 -vn -0.560313 -0.731417 0.388689 -v 0.015292 -0.025357 -0.014437 -vn -0.599334 -0.670785 0.436859 -v 0.015151 -0.025182 -0.014337 -vn -0.434119 -0.673182 0.598637 -v 0.014337 -0.025182 -0.015151 -vn -0.476007 -0.610336 0.633172 -v 0.014250 -0.024989 -0.015014 -vn -0.630643 -0.611420 0.477969 -v 0.015014 -0.024989 -0.014250 -vn -0.660102 -0.541640 0.520473 -v 0.014881 -0.024777 -0.014177 -vn -0.553036 -0.474688 0.684706 -v 0.014119 -0.024545 -0.014751 -vn -0.515868 -0.544134 0.661664 -v 0.014177 -0.024777 -0.014881 -vn -0.700968 -0.398662 0.591365 -v 0.014629 -0.024296 -0.014076 -vn -0.681744 -0.475924 0.555627 -v 0.014751 -0.024545 -0.014119 -vn -0.212972 -0.953577 0.212917 -v 0.015604 -0.025929 -0.015604 -vn -0.236533 -0.942396 0.236521 -v 0.015586 -0.025920 -0.015586 -vn -0.279578 -0.918574 0.279388 -v 0.015436 -0.025839 -0.015436 -vn -0.333000 -0.882346 0.332530 -v 0.015291 -0.025741 -0.015291 -vn -0.384145 -0.839916 0.383371 -v 0.015151 -0.025624 -0.015151 -vn -0.433247 -0.790918 0.432141 -v 0.015016 -0.025490 -0.015016 -vn -0.479566 -0.735787 0.478156 -v 0.014882 -0.025330 -0.014882 -vn -0.521619 -0.676465 0.519912 -v 0.014762 -0.025159 -0.014762 -vn -0.559417 -0.613487 0.557393 -v 0.014649 -0.024971 -0.014649 -vn -0.593389 -0.546335 0.591108 -v 0.014544 -0.024763 -0.014544 -vn -0.623210 -0.475644 0.620784 -v 0.014447 -0.024535 -0.014447 -vn -0.648565 -0.402510 0.646026 -v 0.014362 -0.024290 -0.014362 -vn -0.664842 -0.344000 0.663061 -v 0.014289 -0.024028 -0.014289 -vn -0.586656 -0.402229 0.702884 -v 0.014076 -0.024296 -0.014629 -vn -0.613612 -0.342731 0.711348 -v 0.014051 -0.024032 -0.014514 -vn -0.627330 -0.300112 0.718602 -v 0.014048 -0.023984 -0.014495 -vn -0.648589 -0.237740 0.723057 -v 0.014043 -0.023700 -0.014389 -vn -0.675457 -0.299274 0.673938 -v 0.014278 -0.023981 -0.014278 -vn -0.708302 -0.342837 0.617066 -v 0.014514 -0.024032 -0.014051 -vn -0.688071 -0.236918 0.685878 -v 0.014220 -0.023698 -0.014220 -vn -0.717389 -0.300846 0.628367 -v 0.014495 -0.023984 -0.014048 -vn -0.690527 -0.081081 0.718748 -v 0.014089 -0.023097 -0.014213 -vn -0.698992 -0.158985 0.697233 -v 0.014178 -0.023403 -0.014178 -vn -0.721545 -0.161170 0.673348 -v 0.014295 -0.023403 -0.014057 -vn -0.705327 -0.080776 0.704265 -v 0.014151 -0.023097 -0.014151 -vn -0.290483 -0.951269 -0.103471 -v 0.016132 -0.026000 0.015195 -vn -0.198710 -0.959719 -0.198630 -v 0.015672 -0.025958 0.015672 -vn -0.103220 -0.951321 -0.290402 -v 0.015195 -0.026000 0.016132 -vn -0.704881 -0.022758 -0.708961 -v 0.014144 -0.022783 0.014140 -vn -0.702889 -0.020269 -0.711010 -v 0.014142 -0.022783 0.014142 -vn -0.709504 -0.020165 -0.704413 -v 0.014140 -0.022783 0.014144 -vn -0.691125 -0.079934 -0.718301 -v 0.014089 -0.023097 0.014213 -vn -0.723868 -0.160407 -0.671033 -v 0.014295 -0.023403 0.014057 -vn -0.651880 -0.233953 -0.721331 -v 0.014043 -0.023700 0.014389 -vn -0.117168 -0.945092 -0.305077 -v 0.015125 -0.025971 0.016063 -vn -0.305062 -0.945087 -0.117253 -v 0.016063 -0.025971 0.015125 -vn -0.328579 -0.933985 -0.140387 -v 0.016045 -0.025962 0.015107 -vn -0.371292 -0.910535 -0.181850 -v 0.015892 -0.025880 0.014955 -vn -0.140446 -0.933999 -0.328514 -v 0.015107 -0.025962 0.016045 -vn -0.181910 -0.910613 -0.371069 -v 0.014955 -0.025880 0.015892 -vn -0.236892 -0.874231 -0.423795 -v 0.014812 -0.025779 0.015741 -vn -0.472838 -0.832956 -0.287416 -v 0.015591 -0.025660 0.014678 -vn -0.424158 -0.874343 -0.235828 -v 0.015741 -0.025779 0.014812 -vn -0.287973 -0.833380 -0.471751 -v 0.014678 -0.025660 0.015591 -vn -0.340824 -0.783855 -0.519048 -v 0.014554 -0.025521 0.015443 -vn -0.562060 -0.729588 -0.389602 -v 0.015292 -0.025357 0.014437 -vn -0.519760 -0.784429 -0.338409 -v 0.015443 -0.025521 0.014554 -vn -0.388692 -0.731394 -0.560341 -v 0.014437 -0.025357 0.015292 -vn -0.436866 -0.670772 -0.599344 -v 0.014337 -0.025182 0.015151 -vn -0.598644 -0.673192 -0.434094 -v 0.015151 -0.025182 0.014337 -vn -0.633174 -0.610325 -0.476018 -v 0.015014 -0.024989 0.014250 -vn -0.477954 -0.611425 -0.630650 -v 0.014250 -0.024989 0.015014 -vn -0.520448 -0.541666 -0.660100 -v 0.014177 -0.024777 0.014881 -vn -0.684690 -0.474713 -0.553035 -v 0.014751 -0.024545 0.014119 -vn -0.661673 -0.544115 -0.515875 -v 0.014881 -0.024777 0.014177 -vn -0.591388 -0.398625 -0.700970 -v 0.014076 -0.024296 0.014629 -vn -0.555629 -0.475898 -0.681761 -v 0.014119 -0.024545 0.014751 -vn -0.212936 -0.953578 -0.212949 -v 0.015604 -0.025929 0.015604 -vn -0.236501 -0.942399 -0.236540 -v 0.015586 -0.025920 0.015586 -vn -0.279384 -0.918574 -0.279583 -v 0.015436 -0.025839 0.015436 -vn -0.332526 -0.882348 -0.333000 -v 0.015291 -0.025741 0.015291 -vn -0.383372 -0.839912 -0.384153 -v 0.015151 -0.025624 0.015151 -vn -0.432127 -0.790922 -0.433255 -v 0.015016 -0.025490 0.015016 -vn -0.478151 -0.735786 -0.479574 -v 0.014882 -0.025330 0.014882 -vn -0.519922 -0.676465 -0.521610 -v 0.014762 -0.025159 0.014762 -vn -0.557407 -0.613484 -0.559405 -v 0.014649 -0.024971 0.014649 -vn -0.591108 -0.546337 -0.593386 -v 0.014544 -0.024763 0.014544 -vn -0.620778 -0.475655 -0.623207 -v 0.014447 -0.024535 0.014447 -vn -0.646066 -0.402488 -0.648539 -v 0.014362 -0.024290 0.014362 -vn -0.663071 -0.344026 -0.664818 -v 0.014289 -0.024028 0.014289 -vn -0.702875 -0.402215 -0.586677 -v 0.014629 -0.024296 0.014076 -vn -0.711345 -0.342812 -0.613571 -v 0.014514 -0.024032 0.014051 -vn -0.718618 -0.300205 -0.627268 -v 0.014495 -0.023984 0.014048 -vn -0.723031 -0.237724 -0.648625 -v 0.014389 -0.023700 0.014043 -vn -0.673941 -0.299279 -0.675452 -v 0.014278 -0.023981 0.014278 -vn -0.617111 -0.342773 -0.708294 -v 0.014051 -0.024032 0.014514 -vn -0.685901 -0.236926 -0.688045 -v 0.014220 -0.023698 0.014220 -vn -0.628439 -0.300723 -0.717378 -v 0.014048 -0.023984 0.014495 -vn -0.718833 -0.081051 -0.690442 -v 0.014213 -0.023097 0.014089 -vn -0.697318 -0.158972 -0.698910 -v 0.014178 -0.023403 0.014178 -vn -0.673365 -0.161179 -0.721527 -v 0.014057 -0.023403 0.014295 -vn -0.704365 -0.080753 -0.705230 -v 0.014151 -0.023097 0.014151 -vn 0.103223 0.290402 0.951321 -v -0.015195 -0.016132 0.026000 -vn 0.198565 0.198618 0.959751 -v -0.015672 -0.015672 0.025958 -vn 0.290429 0.103346 0.951299 -v -0.016132 -0.015195 0.026000 -vn 0.707612 0.706384 0.017530 -v -0.014144 -0.014140 0.022783 -vn 0.712126 0.701759 0.020286 -v -0.014142 -0.014142 0.022783 -vn 0.706222 0.707668 0.021348 -v -0.014140 -0.014144 0.022783 -vn 0.691215 0.718219 0.079898 -v -0.014089 -0.014213 0.023097 -vn 0.723812 0.671079 0.160466 -v -0.014295 -0.014057 0.023403 -vn 0.651945 0.721283 0.233921 -v -0.014043 -0.014389 0.023700 -vn 0.591457 0.700954 0.398551 -v -0.014076 -0.014629 0.024296 -vn 0.633195 0.476011 0.610309 -v -0.015014 -0.014250 0.024989 -vn 0.520417 0.660094 0.541703 -v -0.014177 -0.014881 0.024777 -vn 0.562284 0.387433 0.730570 -v -0.015292 -0.014437 0.025357 -vn 0.436871 0.599344 0.670769 -v -0.014337 -0.015151 0.025182 -vn 0.472784 0.287409 0.832989 -v -0.015591 -0.014678 0.025660 -vn 0.340807 0.519041 0.783867 -v -0.014554 -0.015443 0.025521 -vn 0.371279 0.181846 0.910540 -v -0.015892 -0.014955 0.025880 -vn 0.236896 0.423772 0.874241 -v -0.014812 -0.015741 0.025779 -vn 0.117219 0.305142 0.945065 -v -0.015125 -0.016063 0.025971 -vn 0.304948 0.117138 0.945138 -v -0.016063 -0.015125 0.025971 -vn 0.328474 0.140299 0.934035 -v -0.016045 -0.015107 0.025962 -vn 0.213090 0.213162 0.953496 -v -0.015604 -0.015604 0.025929 -vn 0.236709 0.236701 0.942306 -v -0.015586 -0.015586 0.025920 -vn 0.424102 0.235810 0.874375 -v -0.015741 -0.014812 0.025779 -vn 0.279360 0.279558 0.918589 -v -0.015436 -0.015436 0.025839 -vn 0.140522 0.328567 0.933969 -v -0.015107 -0.016045 0.025962 -vn 0.332505 0.332974 0.882366 -v -0.015291 -0.015291 0.025741 -vn 0.181928 0.371070 0.910609 -v -0.014955 -0.015892 0.025880 -vn 0.519795 0.338483 0.784374 -v -0.015443 -0.014554 0.025521 -vn 0.383442 0.384181 0.839867 -v -0.015151 -0.015151 0.025624 -vn 0.432201 0.433269 0.790873 -v -0.015016 -0.015016 0.025490 -vn 0.287971 0.471742 0.833386 -v -0.014678 -0.015591 0.025660 -vn 0.600447 0.433288 0.672106 -v -0.015151 -0.014337 0.025182 -vn 0.478112 0.479558 0.735821 -v -0.014882 -0.014882 0.025330 -vn 0.519910 0.521619 0.676467 -v -0.014762 -0.014762 0.025159 -vn 0.388676 0.560332 0.731409 -v -0.014437 -0.015292 0.025357 -vn 0.661676 0.515840 0.544145 -v -0.014881 -0.014177 0.024777 -vn 0.557412 0.559430 0.613457 -v -0.014649 -0.014649 0.024971 -vn 0.477952 0.630651 0.611426 -v -0.014250 -0.015014 0.024989 -vn 0.591089 0.593398 0.546346 -v -0.014544 -0.014544 0.024763 -vn 0.684248 0.555825 0.472084 -v -0.014751 -0.014119 0.024545 -vn 0.555632 0.681759 0.475897 -v -0.014119 -0.014751 0.024545 -vn 0.620708 0.623221 0.475728 -v -0.014447 -0.014447 0.024535 -vn 0.646004 0.648575 0.402529 -v -0.014362 -0.014362 0.024290 -vn 0.700598 0.588154 0.404025 -v -0.014629 -0.014076 0.024296 -vn 0.711248 0.613578 0.342998 -v -0.014514 -0.014051 0.024032 -vn 0.663253 0.664936 0.343446 -v -0.014289 -0.014289 0.024028 -vn 0.718563 0.627271 0.300332 -v -0.014495 -0.014048 0.023984 -vn 0.723063 0.648577 0.237758 -v -0.014389 -0.014043 0.023700 -vn 0.674079 0.675541 0.298768 -v -0.014278 -0.014278 0.023981 -vn 0.617012 0.708234 0.343076 -v -0.014051 -0.014514 0.024032 -vn 0.685855 0.688073 0.236979 -v -0.014220 -0.014220 0.023698 -vn 0.628322 0.717350 0.301033 -v -0.014048 -0.014495 0.023984 -vn 0.718678 0.690596 0.081116 -v -0.014213 -0.014089 0.023097 -vn 0.697249 0.698967 0.159027 -v -0.014178 -0.014178 0.023403 -vn 0.673439 0.721453 0.161202 -v -0.014057 -0.014295 0.023403 -vn 0.704299 0.705299 0.080722 -v -0.014151 -0.014151 0.023097 -vn 0.290419 -0.103249 0.951313 -v -0.016132 0.015195 0.026000 -vn 0.198605 -0.198584 0.959750 -v -0.015672 0.015672 0.025958 -vn 0.103310 -0.290415 0.951308 -v -0.015195 0.016132 0.026000 -vn 0.705633 -0.708232 0.022130 -v -0.014140 0.014144 0.022783 -vn 0.712809 -0.701039 0.021182 -v -0.014142 0.014142 0.022783 -vn 0.706647 -0.707313 0.018921 -v -0.014144 0.014140 0.022783 -vn 0.718224 -0.691209 0.079896 -v -0.014213 0.014089 0.023097 -vn 0.671099 -0.723796 0.160453 -v -0.014057 0.014295 0.023403 -vn 0.721309 -0.651917 0.233918 -v -0.014389 0.014043 0.023700 -vn 0.700046 -0.591948 0.399415 -v -0.014629 0.014076 0.024296 -vn 0.476012 -0.633177 0.610327 -v -0.014250 0.015014 0.024989 -vn 0.660115 -0.520440 0.541655 -v -0.014881 0.014177 0.024777 -vn 0.387416 -0.562252 0.730604 -v -0.014437 0.015292 0.025357 -vn 0.599345 -0.436865 0.670772 -v -0.015151 0.014337 0.025182 -vn 0.287416 -0.472810 0.832972 -v -0.014678 0.015591 0.025660 -vn 0.519065 -0.340831 0.783840 -v -0.015443 0.014554 0.025521 -vn 0.181857 -0.371291 0.910533 -v -0.014955 0.015892 0.025880 -vn 0.423758 -0.236883 0.874251 -v -0.015741 0.014812 0.025779 -vn 0.305058 -0.117126 0.945104 -v -0.016063 0.015125 0.025971 -vn 0.117217 -0.305037 0.945099 -v -0.015125 0.016063 0.025971 -vn 0.140434 -0.328580 0.933977 -v -0.015107 0.016045 0.025962 -vn 0.213112 -0.213136 0.953497 -v -0.015604 0.015604 0.025929 -vn 0.236725 -0.236675 0.942309 -v -0.015586 0.015586 0.025920 -vn 0.235823 -0.424116 0.874365 -v -0.014812 0.015741 0.025779 -vn 0.279561 -0.279354 0.918590 -v -0.015436 0.015436 0.025839 -vn 0.328457 -0.140391 0.934027 -v -0.016045 0.015107 0.025962 -vn 0.332979 -0.332498 0.882366 -v -0.015291 0.015291 0.025741 -vn 0.371044 -0.181919 0.910622 -v -0.015892 0.014955 0.025880 -vn 0.338430 -0.519762 0.784419 -v -0.014554 0.015443 0.025521 -vn 0.384193 -0.383433 0.839866 -v -0.015151 0.015151 0.025624 -vn 0.433299 -0.432158 0.790880 -v -0.015016 0.015016 0.025490 -vn 0.471720 -0.287962 0.833401 -v -0.015591 0.014678 0.025660 -vn 0.433292 -0.600447 0.672102 -v -0.014337 0.015151 0.025182 -vn 0.479553 -0.478128 0.735814 -v -0.014882 0.014882 0.025330 -vn 0.521607 -0.519924 0.676465 -v -0.014762 0.014762 0.025159 -vn 0.560380 -0.388702 0.731358 -v -0.015292 0.014437 0.025357 -vn 0.515819 -0.661653 0.544194 -v -0.014177 0.014881 0.024777 -vn 0.559415 -0.557419 0.613464 -v -0.014649 0.014649 0.024971 -vn 0.630664 -0.477953 0.611412 -v -0.015014 0.014250 0.024989 -vn 0.593356 -0.591134 0.546342 -v -0.014544 0.014544 0.024763 -vn 0.555832 -0.684290 0.472016 -v -0.014119 0.014751 0.024545 -vn 0.681364 -0.557299 0.474511 -v -0.014751 0.014119 0.024545 -vn 0.623177 -0.620763 0.475714 -v -0.014447 0.014447 0.024535 -vn 0.648555 -0.646015 0.402544 -v -0.014362 0.014362 0.024290 -vn 0.588195 -0.700594 0.403974 -v -0.014076 0.014629 0.024296 -vn 0.613542 -0.711240 0.343080 -v -0.014051 0.014514 0.024032 -vn 0.664914 -0.663275 0.343447 -v -0.014289 0.014289 0.024028 -vn 0.627267 -0.718565 0.300332 -v -0.014048 0.014495 0.023984 -vn 0.648624 -0.723026 0.237741 -v -0.014043 0.014389 0.023700 -vn 0.675538 -0.674084 0.298762 -v -0.014278 0.014278 0.023981 -vn 0.708221 -0.617055 0.343024 -v -0.014514 0.014051 0.024032 -vn 0.688078 -0.685846 0.236990 -v -0.014220 0.014220 0.023698 -vn 0.717351 -0.628318 0.301038 -v -0.014495 0.014048 0.023984 -vn 0.690607 -0.718676 0.081036 -v -0.014089 0.014213 0.023097 -vn 0.698952 -0.697265 0.159023 -v -0.014178 0.014178 0.023403 -vn 0.721450 -0.673436 0.161225 -v -0.014295 0.014057 0.023403 -vn 0.705253 -0.704349 0.080688 -v -0.014151 0.014151 0.023097 -vn -0.103210 -0.290390 0.951326 -v 0.015195 0.016132 0.026000 -vn -0.198579 -0.198606 0.959751 -v 0.015672 0.015672 0.025958 -vn -0.290445 -0.103330 0.951296 -v 0.016132 0.015195 0.026000 -vn -0.704879 -0.708960 0.022834 -v 0.014144 0.014140 0.022783 -vn -0.703067 -0.710834 0.020314 -v 0.014142 0.014142 0.022783 -vn -0.709696 -0.704218 0.020238 -v 0.014140 0.014144 0.022783 -vn -0.691120 -0.718306 0.079935 -v 0.014089 0.014213 0.023097 -vn -0.723869 -0.671031 0.160413 -v 0.014295 0.014057 0.023403 -vn -0.651881 -0.721330 0.233952 -v 0.014043 0.014389 0.023700 -vn -0.557310 -0.681389 0.474463 -v 0.014119 0.014751 0.024545 -vn -0.520449 -0.660101 0.541665 -v 0.014177 0.014881 0.024777 -vn -0.117160 -0.305070 0.945096 -v 0.015125 0.016063 0.025971 -vn -0.305069 -0.117261 0.945083 -v 0.016063 0.015125 0.025971 -vn -0.328597 -0.140402 0.933976 -v 0.016045 0.015107 0.025962 -vn -0.371294 -0.181852 0.910533 -v 0.015892 0.014955 0.025880 -vn -0.140453 -0.328519 0.933996 -v 0.015107 0.016045 0.025962 -vn -0.181917 -0.371074 0.910610 -v 0.014955 0.015892 0.025880 -vn -0.236892 -0.423794 0.874232 -v 0.014812 0.015741 0.025779 -vn -0.472836 -0.287414 0.832958 -v 0.015591 0.014678 0.025660 -vn -0.424155 -0.235826 0.874345 -v 0.015741 0.014812 0.025779 -vn -0.287971 -0.471749 0.833382 -v 0.014678 0.015591 0.025660 -vn -0.340825 -0.519048 0.783854 -v 0.014554 0.015443 0.025521 -vn -0.562060 -0.389602 0.729588 -v 0.015292 0.014437 0.025357 -vn -0.519760 -0.338408 0.784429 -v 0.015443 0.014554 0.025521 -vn -0.388689 -0.560339 0.731396 -v 0.014437 0.015292 0.025357 -vn -0.436866 -0.599344 0.670772 -v 0.014337 0.015151 0.025182 -vn -0.598644 -0.434093 0.673193 -v 0.015151 0.014337 0.025182 -vn -0.633176 -0.476020 0.610323 -v 0.015014 0.014250 0.024989 -vn -0.477956 -0.630650 0.611423 -v 0.014250 0.015014 0.024989 -vn -0.684690 -0.553035 0.474713 -v 0.014751 0.014119 0.024545 -vn -0.661673 -0.515875 0.544116 -v 0.014881 0.014177 0.024777 -vn -0.591905 -0.700061 0.399454 -v 0.014076 0.014629 0.024296 -vn -0.212949 -0.212966 0.953571 -v 0.015604 0.015604 0.025929 -vn -0.236515 -0.236553 0.942392 -v 0.015586 0.015586 0.025920 -vn -0.279381 -0.279583 0.918575 -v 0.015436 0.015436 0.025839 -vn -0.332524 -0.332998 0.882349 -v 0.015291 0.015291 0.025741 -vn -0.383368 -0.384149 0.839916 -v 0.015151 0.015151 0.025624 -vn -0.432129 -0.433254 0.790921 -v 0.015016 0.015016 0.025490 -vn -0.478152 -0.479575 0.735784 -v 0.014882 0.014882 0.025330 -vn -0.519921 -0.521607 0.676467 -v 0.014762 0.014762 0.025159 -vn -0.557407 -0.559406 0.613484 -v 0.014649 0.014649 0.024971 -vn -0.591110 -0.593386 0.546335 -v 0.014544 0.014544 0.024763 -vn -0.620780 -0.623207 0.475652 -v 0.014447 0.014447 0.024535 -vn -0.646063 -0.648539 0.402492 -v 0.014362 0.014362 0.024290 -vn -0.663071 -0.664823 0.344017 -v 0.014289 0.014289 0.024028 -vn -0.702876 -0.586677 0.402213 -v 0.014629 0.014076 0.024296 -vn -0.711342 -0.613571 0.342816 -v 0.014514 0.014051 0.024032 -vn -0.718616 -0.627267 0.300212 -v 0.014495 0.014048 0.023984 -vn -0.723031 -0.648626 0.237721 -v 0.014389 0.014043 0.023700 -vn -0.673942 -0.675456 0.299268 -v 0.014278 0.014278 0.023981 -vn -0.617111 -0.708292 0.342778 -v 0.014051 0.014514 0.024032 -vn -0.685899 -0.688047 0.236927 -v 0.014220 0.014220 0.023698 -vn -0.628437 -0.717376 0.300730 -v 0.014048 0.014495 0.023984 -vn -0.718833 -0.690442 0.081048 -v 0.014213 0.014089 0.023097 -vn -0.697315 -0.698913 0.158972 -v 0.014178 0.014178 0.023403 -vn -0.673367 -0.721526 0.161175 -v 0.014057 0.014295 0.023403 -vn -0.704366 -0.705229 0.080754 -v 0.014151 0.014151 0.023097 -vn -0.290433 0.103241 0.951310 -v 0.016132 -0.015195 0.026000 -vn -0.198615 0.198569 0.959751 -v 0.015672 -0.015672 0.025958 -vn -0.103300 0.290408 0.951311 -v 0.015195 -0.016132 0.026000 -vn -0.708137 0.705773 0.020632 -v 0.014140 -0.014144 0.022783 -vn -0.704227 0.709699 0.019790 -v 0.014142 -0.014142 0.022783 -vn -0.703605 0.710275 0.021215 -v 0.014144 -0.014140 0.022783 -vn -0.718379 0.691043 0.079944 -v 0.014213 -0.014089 0.023097 -vn -0.671029 0.723869 0.160417 -v 0.014057 -0.014295 0.023403 -vn -0.721317 0.651896 0.233950 -v 0.014389 -0.014043 0.023700 -vn -0.305161 0.117252 0.945055 -v 0.016063 -0.015125 0.025971 -vn -0.117171 0.304985 0.945122 -v 0.015125 -0.016063 0.025971 -vn -0.140372 0.328548 0.933998 -v 0.015107 -0.016045 0.025962 -vn -0.181845 0.371288 0.910537 -v 0.014955 -0.015892 0.025880 -vn -0.328579 0.140491 0.933969 -v 0.016045 -0.015107 0.025962 -vn -0.371076 0.181922 0.910608 -v 0.015892 -0.014955 0.025880 -vn -0.423811 0.236897 0.874222 -v 0.015741 -0.014812 0.025779 -vn -0.287407 0.472828 0.832965 -v 0.014678 -0.015591 0.025660 -vn -0.235829 0.424141 0.874351 -v 0.014812 -0.015741 0.025779 -vn -0.471750 0.287977 0.833380 -v 0.015591 -0.014678 0.025660 -vn -0.519038 0.340820 0.783863 -v 0.015443 -0.014554 0.025521 -vn -0.389623 0.562079 0.729563 -v 0.014437 -0.015292 0.025357 -vn -0.338430 0.519773 0.784412 -v 0.014554 -0.015443 0.025521 -vn -0.560313 0.388687 0.731418 -v 0.015292 -0.014437 0.025357 -vn -0.599334 0.436859 0.670785 -v 0.015151 -0.014337 0.025182 -vn -0.434118 0.598637 0.673183 -v 0.014337 -0.015151 0.025182 -vn -0.476007 0.633171 0.610338 -v 0.014250 -0.015014 0.024989 -vn -0.630644 0.477970 0.611418 -v 0.015014 -0.014250 0.024989 -vn -0.660101 0.520474 0.541639 -v 0.014881 -0.014177 0.024777 -vn -0.553038 0.684705 0.474687 -v 0.014119 -0.014751 0.024545 -vn -0.515869 0.661664 0.544132 -v 0.014177 -0.014881 0.024777 -vn -0.700968 0.591366 0.398660 -v 0.014629 -0.014076 0.024296 -vn -0.681743 0.555628 0.475925 -v 0.014751 -0.014119 0.024545 -vn -0.212985 0.212931 0.953571 -v 0.015604 -0.015604 0.025929 -vn -0.236547 0.236533 0.942389 -v 0.015586 -0.015586 0.025920 -vn -0.279577 0.279386 0.918575 -v 0.015436 -0.015436 0.025839 -vn -0.333000 0.332528 0.882347 -v 0.015291 -0.015291 0.025741 -vn -0.384144 0.383370 0.839917 -v 0.015151 -0.015151 0.025624 -vn -0.433246 0.432141 0.790919 -v 0.015016 -0.015016 0.025490 -vn -0.479567 0.478158 0.735786 -v 0.014882 -0.014882 0.025330 -vn -0.521618 0.519910 0.676467 -v 0.014762 -0.014762 0.025159 -vn -0.559416 0.557393 0.613487 -v 0.014649 -0.014649 0.024971 -vn -0.593388 0.591107 0.546336 -v 0.014544 -0.014544 0.024763 -vn -0.623210 0.620785 0.475642 -v 0.014447 -0.014447 0.024535 -vn -0.648565 0.646026 0.402508 -v 0.014362 -0.014362 0.024290 -vn -0.664842 0.663060 0.344002 -v 0.014289 -0.014289 0.024028 -vn -0.586656 0.702884 0.402230 -v 0.014076 -0.014629 0.024296 -vn -0.613617 0.711352 0.342713 -v 0.014051 -0.014514 0.024032 -vn -0.627334 0.718606 0.300096 -v 0.014048 -0.014495 0.023984 -vn -0.648585 0.723059 0.237746 -v 0.014043 -0.014389 0.023700 -vn -0.675458 0.673939 0.299271 -v 0.014278 -0.014278 0.023981 -vn -0.708302 0.617070 0.342830 -v 0.014514 -0.014051 0.024032 -vn -0.688070 0.685878 0.236920 -v 0.014220 -0.014220 0.023698 -vn -0.717389 0.628369 0.300841 -v 0.014495 -0.014048 0.023984 -vn -0.690522 0.718753 0.081082 -v 0.014089 -0.014213 0.023097 -vn -0.698986 0.697240 0.158982 -v 0.014178 -0.014178 0.023403 -vn -0.721545 0.673348 0.161169 -v 0.014295 -0.014057 0.023403 -vn -0.705330 0.704261 0.080776 -v 0.014151 -0.014151 0.023097 -vn 0.389395 0.876279 -0.283738 -v 0.031300 -0.013619 -0.004260 -vn -0.389784 0.875605 -0.285279 -v 0.023700 -0.013619 -0.004260 -vn -0.390884 0.827413 -0.403234 -v 0.023700 -0.013020 -0.002800 -vn 0.389382 0.910593 0.138573 -v 0.031300 -0.013873 -0.008192 -vn -0.386691 0.917078 0.097149 -v 0.023700 -0.013936 -0.007777 -vn 0.391658 0.920047 0.010853 -v 0.031300 -0.014000 -0.006750 -vn -0.388188 0.921580 -0.000446 -v 0.023700 -0.014000 -0.006750 -vn -0.376454 0.920123 -0.107963 -v 0.023700 -0.013934 -0.005708 -vn 0.388064 0.807562 0.444128 -v 0.031300 -0.012799 -0.011107 -vn -0.386625 0.825699 0.410783 -v 0.023700 -0.012973 -0.010792 -vn 0.389968 0.859544 0.330317 -v 0.031300 -0.013483 -0.009643 -vn -0.389286 0.862450 0.323477 -v 0.023700 -0.013483 -0.009643 -vn 0.386996 0.892351 0.232257 -v 0.031300 -0.013744 -0.008796 -vn -0.387151 0.892481 0.231499 -v 0.023700 -0.013745 -0.008791 -vn -0.385424 0.907787 0.165440 -v 0.023700 -0.013873 -0.008192 -vn 0.386833 0.634526 0.669132 -v 0.031300 -0.010684 -0.013697 -vn -0.387159 0.679901 0.622770 -v 0.023700 -0.011620 -0.012746 -vn 0.389609 0.699018 0.599649 -v 0.031300 -0.011769 -0.012572 -vn -0.385741 0.717073 0.580526 -v 0.023700 -0.011769 -0.012572 -vn 0.387004 0.757552 0.525683 -v 0.031300 -0.012370 -0.011784 -vn -0.387498 0.757560 0.525308 -v 0.023700 -0.012378 -0.011773 -vn -0.384371 0.794514 0.470113 -v 0.023700 -0.012799 -0.011107 -vn 0.386952 -0.555650 0.735882 -v 0.031300 0.009688 -0.014511 -vn -0.386725 -0.522059 0.760196 -v 0.023700 0.009633 -0.014550 -vn 0.387161 -0.493299 0.778950 -v 0.031300 0.009012 -0.014976 -vn -0.387165 -0.462233 0.797774 -v 0.023700 0.008186 -0.015471 -vn 0.387362 -0.422362 0.819488 -v 0.031300 0.007755 -0.015700 -vn -0.385975 -0.409086 0.826844 -v 0.023700 0.007755 -0.015700 -vn 0.386508 -0.353229 0.851963 -v 0.031300 0.006617 -0.016224 -vn -0.386948 -0.349574 0.853270 -v 0.023700 0.006514 -0.016265 -vn 0.385895 -0.296190 0.873703 -v 0.031300 0.005581 -0.016609 -vn -0.384990 -0.293795 0.874910 -v 0.023700 0.005581 -0.016609 -vn 0.384398 -0.238004 0.891960 -v 0.031300 0.004803 -0.016848 -vn -0.386249 -0.234967 0.891965 -v 0.023700 0.004678 -0.016882 -vn 0.383872 -0.182739 0.905124 -v 0.031300 0.003231 -0.017210 -vn -0.384597 -0.178969 0.905569 -v 0.023700 0.003231 -0.017210 -vn 0.385147 -0.124911 0.914363 -v 0.031300 0.002882 -0.017270 -vn -0.384037 -0.120370 0.915438 -v 0.023700 0.002762 -0.017289 -vn 0.383921 -0.048434 0.922095 -v 0.031300 0.000781 -0.017483 -vn -0.385843 -0.052592 0.921064 -v 0.023700 0.000781 -0.017483 -vn 0.377279 0.014976 0.925979 -v 0.031300 -0.000327 -0.017497 -vn -0.385671 0.018151 0.922458 -v 0.023700 -0.000257 -0.017498 -vn 0.385752 0.076709 0.919408 -v 0.031300 -0.001694 -0.017421 -vn -0.382282 0.074378 0.921048 -v 0.023700 -0.001694 -0.017421 -vn 0.386996 0.131224 0.912696 -v 0.031300 -0.002276 -0.017357 -vn -0.386198 0.129263 0.913314 -v 0.023700 -0.002199 -0.017367 -vn 0.389662 0.213110 0.895962 -v 0.031300 -0.004116 -0.017025 -vn -0.389716 0.209916 0.896692 -v 0.023700 -0.004116 -0.017025 -vn 0.386254 0.293380 0.874492 -v 0.031300 -0.005887 -0.016503 -vn -0.386908 0.291863 0.874710 -v 0.023700 -0.005833 -0.016522 -vn 0.381724 0.349583 0.855616 -v 0.031300 -0.006409 -0.016307 -vn -0.385353 0.346548 0.855224 -v 0.023700 -0.006409 -0.016307 -vn 0.383882 0.405623 0.829521 -v 0.031300 -0.007514 -0.015821 -vn -0.386965 0.401585 0.830053 -v 0.023700 -0.007450 -0.015852 -vn 0.380985 0.458209 0.803054 -v 0.031300 -0.008502 -0.015291 -vn -0.387916 0.467772 0.794173 -v 0.023700 -0.008502 -0.015291 -vn 0.387495 0.512568 0.766238 -v 0.031300 -0.008979 -0.014998 -vn -0.387433 0.534738 0.750967 -v 0.023700 -0.009561 -0.014602 -vn 0.384972 0.578508 0.719114 -v 0.031300 -0.010328 -0.014007 -vn -0.385223 0.586867 0.712173 -v 0.023700 -0.010328 -0.014007 -vn -0.387547 0.630971 0.672074 -v 0.023700 -0.010684 -0.013697 -vn 0.385182 -0.920014 0.072172 -v 0.031300 0.013983 -0.007276 -vn -0.386133 -0.915433 0.113507 -v 0.023700 0.013962 -0.007540 -vn 0.390824 -0.897756 0.203204 -v 0.031300 0.013763 -0.008720 -vn -0.387322 -0.896965 0.213155 -v 0.023700 0.013763 -0.008720 -vn 0.386622 -0.869901 0.306262 -v 0.031300 0.013489 -0.009629 -vn -0.385235 -0.870243 0.307036 -v 0.023700 0.013464 -0.009695 -vn 0.384108 -0.847403 0.366564 -v 0.031300 0.013270 -0.010176 -vn -0.383319 -0.845119 0.372614 -v 0.023700 0.013270 -0.010176 -vn 0.386070 -0.816913 0.428489 -v 0.031300 0.013065 -0.010613 -vn -0.386381 -0.816291 0.429394 -v 0.023700 0.013031 -0.010679 -vn 0.388373 -0.768022 0.509224 -v 0.031300 0.012466 -0.011642 -vn -0.389224 -0.765210 0.512795 -v 0.023700 0.012466 -0.011642 -vn 0.386992 -0.712826 0.584907 -v 0.031300 0.011760 -0.012583 -vn -0.386267 -0.710293 0.588457 -v 0.023700 0.011705 -0.012648 -vn 0.385403 -0.668507 0.636053 -v 0.031300 0.011295 -0.013102 -vn -0.378423 -0.666141 0.642691 -v 0.023700 0.011295 -0.013102 -vn 0.387986 -0.620976 0.681069 -v 0.031300 0.010842 -0.013551 -vn -0.383647 -0.621654 0.682907 -v 0.023700 0.010772 -0.013616 -vn -0.386082 -0.565386 0.728889 -v 0.023700 0.009688 -0.014511 -vn 0.385102 -0.917940 -0.095300 -v 0.031300 0.013949 -0.005834 -vn -0.388232 -0.913327 -0.122918 -v 0.023700 0.013949 -0.005834 -vn 0.384154 -0.922969 -0.023555 -v 0.031300 0.013995 -0.006472 -vn -0.386207 -0.922092 -0.024289 -v 0.023700 0.013997 -0.006514 -vn -0.385093 -0.921775 0.045113 -v 0.023700 0.013983 -0.007276 -vn 0.388785 -0.907095 -0.161322 -v 0.031300 0.013897 -0.005449 -vn 0.387667 -0.892918 -0.228938 -v 0.031300 0.013672 -0.004437 -vn -0.389086 -0.887905 -0.245433 -v 0.023700 0.013658 -0.004387 -vn 0.384783 -0.878246 -0.283947 -v 0.031300 0.013658 -0.004387 -vn -0.386829 -0.855315 -0.344673 -v 0.023700 0.013337 -0.003482 -vn 0.385500 -0.854672 -0.347744 -v 0.031300 0.013322 -0.003445 -vn -0.385494 -0.828018 -0.407163 -v 0.023700 0.013085 -0.002928 -vn 0.376290 -0.829054 -0.413613 -v 0.031300 0.013085 -0.002928 -vn -0.387715 -0.795904 -0.464989 -v 0.023700 0.012854 -0.002490 -vn 0.383055 -0.798482 -0.464431 -v 0.031300 0.012832 -0.002451 -vn -0.389173 -0.742252 -0.545534 -v 0.023700 0.012188 -0.001461 -vn 0.390122 -0.741855 -0.545395 -v 0.031300 0.012188 -0.001461 -vn -0.386454 -0.684870 -0.617743 -v 0.023700 0.011424 -0.000536 -vn 0.387880 -0.682296 -0.619695 -v 0.031300 0.011394 -0.000504 -vn -0.382172 -0.639251 -0.667310 -v 0.023700 0.010906 -0.000009 -vn 0.384450 -0.638009 -0.667190 -v 0.031300 0.010906 -0.000009 -vn -0.385649 -0.590258 -0.709134 -v 0.023700 0.010454 0.000400 -vn 0.386665 -0.587049 -0.711241 -v 0.031300 0.010409 0.000439 -vn -0.389483 -0.513898 -0.764338 -v 0.023700 0.009189 0.001361 -vn 0.388592 -0.511799 -0.766197 -v 0.031300 0.009189 0.001361 -vn -0.387119 -0.433705 -0.813658 -v 0.023700 0.007788 0.002183 -vn 0.386556 -0.433096 -0.814250 -v 0.031300 0.007730 0.002213 -vn -0.384951 -0.380788 -0.840722 -v 0.023700 0.007184 0.002477 -vn 0.384981 -0.377910 -0.842006 -v 0.031300 0.007184 0.002477 -vn -0.384203 -0.324534 -0.864330 -v 0.023700 0.006202 0.002888 -vn 0.385767 -0.322119 -0.864536 -v 0.031300 0.006122 0.002918 -vn -0.385428 -0.267767 -0.883032 -v 0.023700 0.004955 0.003304 -vn 0.384700 -0.265716 -0.883969 -v 0.031300 0.004955 0.003304 -vn -0.386689 -0.213356 -0.897191 -v 0.023700 0.004453 0.003442 -vn 0.386316 -0.211556 -0.897777 -v 0.031300 0.004379 0.003461 -vn -0.389330 -0.130479 -0.911810 -v 0.023700 0.002570 0.003817 -vn 0.388969 -0.150870 -0.908813 -v 0.031300 0.002570 0.003817 -vn -0.385906 -0.050297 -0.921166 -v 0.023700 0.000678 0.003987 -vn 0.388524 -0.118531 -0.913783 -v 0.031300 0.002544 0.003821 -vn 0.385325 -0.081538 -0.919172 -v 0.031300 0.001579 0.003931 -vn 0.384756 -0.036331 -0.922303 -v 0.031300 0.000603 0.003990 -vn -0.381996 0.005493 -0.924148 -v 0.023700 0.000105 0.004000 -vn 0.385771 0.006271 -0.922573 -v 0.031300 0.000105 0.004000 -vn -0.385483 0.061297 -0.920677 -v 0.023700 -0.001301 0.003953 -vn 0.386270 0.064352 -0.920138 -v 0.031300 -0.001374 0.003948 -vn -0.381601 0.119526 -0.916566 -v 0.023700 -0.002363 0.003846 -vn 0.385128 0.119959 -0.915034 -v 0.031300 -0.002363 0.003846 -vn -0.383996 0.175083 -0.906583 -v 0.023700 -0.003249 0.003707 -vn 0.385803 0.177116 -0.905420 -v 0.031300 -0.003325 0.003693 -vn -0.382110 0.230626 -0.894876 -v 0.023700 -0.004757 0.003360 -vn 0.384953 0.234624 -0.892616 -v 0.031300 -0.004757 0.003360 -vn -0.387729 0.287462 -0.875804 -v 0.023700 -0.005154 0.003245 -vn 0.386823 0.289807 -0.875431 -v 0.031300 -0.005232 0.003221 -vn -0.391385 0.371761 -0.841791 -v 0.023700 -0.007002 0.002559 -vn 0.391183 0.374196 -0.840805 -v 0.031300 -0.007002 0.002559 -vn -0.386793 0.457722 -0.800551 -v 0.023700 -0.008583 0.001743 -vn 0.387952 0.458506 -0.799541 -v 0.031300 -0.008645 0.001706 -vn -0.383840 0.510676 -0.769336 -v 0.023700 -0.009029 0.001466 -vn 0.381679 0.516120 -0.766773 -v 0.031300 -0.009029 0.001466 -vn -0.386385 0.566771 -0.727652 -v 0.023700 -0.009993 0.000779 -vn 0.384026 0.569101 -0.727082 -v 0.031300 -0.010043 0.000739 -vn -0.385193 0.618339 -0.685042 -v 0.023700 -0.010772 0.000116 -vn 0.382696 0.619797 -0.685125 -v 0.031300 -0.010772 0.000116 -vn -0.386830 0.665462 -0.638375 -v 0.023700 -0.011068 -0.000167 -vn 0.386396 0.667686 -0.636312 -v 0.031300 -0.011109 -0.000208 -vn -0.388425 0.727342 -0.565774 -v 0.023700 -0.012092 -0.001333 -vn 0.388987 0.727798 -0.564801 -v 0.031300 -0.012092 -0.001333 -vn -0.387144 0.781118 -0.489872 -v 0.023700 -0.012638 -0.002125 -vn 0.387093 0.782887 -0.487080 -v 0.031300 -0.012665 -0.002168 -vn 0.390730 0.827703 -0.402788 -v 0.031300 -0.013020 -0.002800 -vn -0.382107 0.906189 -0.181149 -v 0.023700 -0.013850 -0.005179 -vn 0.385093 0.904125 -0.185096 -v 0.031300 -0.013855 -0.005208 -vn 0.388043 0.915992 -0.101885 -v 0.031300 -0.013934 -0.005708 -# 7174 vertices, 0 vertices normals - -f 1//1 2//2 3//3 -f 4//4 5//5 6//6 -f 7//7 8//8 9//9 -f 9//9 8//8 10//10 -f 9//9 10//10 11//11 -f 11//11 10//10 12//12 -f 7//7 13//13 8//8 -f 8//8 13//13 14//14 -f 8//8 14//14 15//15 -f 15//15 14//14 16//16 -f 16//16 14//14 17//17 -f 16//16 17//17 18//18 -f 17//17 19//19 18//18 -f 18//18 19//19 20//20 -f 18//18 20//20 21//21 -f 21//21 20//20 22//22 -f 21//21 22//22 23//23 -f 23//23 22//22 24//24 -f 23//23 24//24 25//25 -f 25//25 24//24 26//26 -f 27//27 28//28 29//29 -f 29//29 28//28 30//30 -f 29//29 30//30 31//31 -f 31//31 30//30 32//32 -f 31//31 32//32 33//33 -f 33//33 32//32 34//34 -f 33//33 34//34 35//35 -f 35//35 34//34 36//36 -f 35//35 36//36 26//26 -f 26//26 36//36 37//37 -f 26//26 37//37 25//25 -f 4//4 6//6 38//38 -f 3//3 2//2 39//39 -f 2//2 40//40 39//39 -f 39//39 40//40 41//41 -f 39//39 41//41 6//6 -f 6//6 41//41 42//42 -f 6//6 42//42 38//38 -f 38//38 42//42 43//43 -f 38//38 43//43 44//44 -f 44//44 43//43 45//45 -f 44//44 45//45 46//46 -f 46//46 45//45 47//47 -f 46//46 47//47 48//48 -f 48//48 47//47 49//49 -f 48//48 49//49 50//50 -f 50//50 49//49 51//51 -f 50//50 51//51 27//27 -f 27//27 51//51 52//52 -f 27//27 52//52 28//28 -f 1//1 3//3 53//53 -f 53//53 3//3 54//54 -f 53//53 54//54 55//55 -f 12//12 10//10 56//56 -f 56//56 10//10 57//57 -f 56//56 57//57 58//58 -f 58//58 57//57 59//59 -f 58//58 59//59 60//60 -f 60//60 59//59 61//61 -f 60//60 61//61 62//62 -f 62//62 61//61 63//63 -f 62//62 63//63 64//64 -f 63//63 65//65 64//64 -f 64//64 65//65 66//66 -f 64//64 66//66 67//67 -f 67//67 66//66 68//68 -f 67//67 68//68 69//69 -f 69//69 68//68 70//70 -f 69//69 70//70 71//71 -f 71//71 70//70 72//72 -f 71//71 72//72 73//73 -f 73//73 72//72 74//74 -f 73//73 74//74 75//75 -f 75//75 74//74 76//76 -f 75//75 76//76 77//77 -f 77//77 76//76 78//78 -f 77//77 78//78 79//79 -f 79//79 78//78 80//80 -f 79//79 80//80 81//81 -f 80//80 82//82 81//81 -f 81//81 82//82 83//83 -f 81//81 83//83 84//84 -f 84//84 83//83 85//85 -f 84//84 85//85 86//86 -f 86//86 85//85 87//87 -f 86//86 87//87 88//88 -f 88//88 87//87 89//89 -f 88//88 89//89 90//90 -f 91//91 92//92 93//93 -f 93//93 92//92 94//94 -f 93//93 94//94 95//95 -f 95//95 94//94 90//90 -f 95//95 90//90 96//96 -f 96//96 90//90 89//89 -f 97//97 98//98 99//99 -f 99//99 98//98 93//93 -f 93//93 98//98 100//100 -f 93//93 100//100 91//91 -f 99//99 101//101 97//97 -f 97//97 101//101 102//102 -f 97//97 102//102 103//103 -f 103//103 102//102 104//104 -f 103//103 104//104 105//105 -f 106//106 107//107 108//108 -f 108//108 107//107 109//109 -f 108//108 109//109 110//110 -f 110//110 109//109 111//111 -f 110//110 111//111 112//112 -f 112//112 111//111 113//113 -f 112//112 113//113 114//114 -f 114//114 113//113 115//115 -f 114//114 115//115 116//116 -f 116//116 115//115 117//117 -f 116//116 117//117 118//118 -f 118//118 117//117 119//119 -f 118//118 119//119 120//120 -f 120//120 119//119 121//121 -f 120//120 121//121 122//122 -f 122//122 121//121 123//123 -f 122//122 123//123 124//124 -f 124//124 123//123 125//125 -f 124//124 125//125 126//126 -f 126//126 125//125 127//127 -f 126//126 127//127 128//128 -f 128//128 127//127 129//129 -f 128//128 129//129 130//130 -f 130//130 129//129 131//131 -f 130//130 131//131 132//132 -f 132//132 131//131 133//133 -f 132//132 133//133 134//134 -f 134//134 133//133 135//135 -f 134//134 135//135 136//136 -f 136//136 135//135 137//137 -f 136//136 137//137 138//138 -f 138//138 137//137 139//139 -f 138//138 139//139 140//140 -f 140//140 139//139 141//141 -f 140//140 141//141 142//142 -f 142//142 141//141 143//143 -f 142//142 143//143 144//144 -f 144//144 143//143 145//145 -f 144//144 145//145 146//146 -f 146//146 145//145 147//147 -f 146//146 147//147 148//148 -f 148//148 147//147 149//149 -f 148//148 149//149 150//150 -f 150//150 149//149 151//151 -f 150//150 151//151 152//152 -f 152//152 151//151 153//153 -f 152//152 153//153 154//154 -f 154//154 153//153 155//155 -f 154//154 155//155 156//156 -f 156//156 155//155 157//157 -f 156//156 157//157 158//158 -f 158//158 157//157 159//159 -f 158//158 159//159 160//160 -f 160//160 159//159 161//161 -f 160//160 161//161 162//162 -f 162//162 161//161 163//163 -f 162//162 163//163 164//164 -f 164//164 163//163 165//165 -f 164//164 165//165 166//166 -f 166//166 165//165 167//167 -f 166//166 167//167 168//168 -f 168//168 167//167 169//169 -f 168//168 169//169 170//170 -f 170//170 169//169 171//171 -f 170//170 171//171 172//172 -f 172//172 171//171 173//173 -f 172//172 173//173 174//174 -f 174//174 173//173 175//175 -f 174//174 175//175 176//176 -f 176//176 175//175 177//177 -f 176//176 177//177 178//178 -f 178//178 177//177 179//179 -f 178//178 179//179 180//180 -f 180//180 179//179 106//106 -f 180//180 106//106 108//108 -f 181//181 182//182 183//183 -f 183//183 182//182 184//184 -f 183//183 184//184 185//185 -f 185//185 184//184 186//186 -f 185//185 186//186 187//187 -f 187//187 186//186 188//188 -f 187//187 188//188 189//189 -f 189//189 188//188 190//190 -f 189//189 190//190 191//191 -f 191//191 190//190 192//192 -f 191//191 192//192 193//193 -f 193//193 192//192 194//194 -f 193//193 194//194 195//195 -f 195//195 194//194 196//196 -f 195//195 196//196 197//197 -f 197//197 196//196 198//198 -f 197//197 198//198 199//199 -f 199//199 198//198 200//200 -f 199//199 200//200 201//201 -f 201//201 200//200 202//202 -f 201//201 202//202 203//203 -f 203//203 202//202 204//204 -f 203//203 204//204 205//205 -f 205//205 204//204 206//206 -f 205//205 206//206 207//207 -f 207//207 206//206 208//208 -f 207//207 208//208 209//209 -f 209//209 208//208 210//210 -f 209//209 210//210 211//211 -f 211//211 210//210 212//212 -f 211//211 212//212 213//213 -f 213//213 212//212 214//214 -f 213//213 214//214 215//215 -f 215//215 214//214 216//216 -f 215//215 216//216 217//217 -f 217//217 216//216 218//218 -f 217//217 218//218 219//219 -f 219//219 218//218 220//220 -f 219//219 220//220 221//221 -f 221//221 220//220 222//222 -f 221//221 222//222 223//223 -f 223//223 222//222 224//224 -f 223//223 224//224 225//225 -f 225//225 224//224 226//226 -f 225//225 226//226 227//227 -f 227//227 226//226 228//228 -f 227//227 228//228 229//229 -f 229//229 228//228 230//230 -f 229//229 230//230 231//231 -f 231//231 230//230 232//232 -f 231//231 232//232 233//233 -f 233//233 232//232 234//234 -f 233//233 234//234 235//235 -f 235//235 234//234 236//236 -f 235//235 236//236 237//237 -f 237//237 236//236 238//238 -f 237//237 238//238 239//239 -f 239//239 238//238 240//240 -f 239//239 240//240 241//241 -f 241//241 240//240 242//242 -f 241//241 242//242 243//243 -f 243//243 242//242 244//244 -f 243//243 244//244 245//245 -f 245//245 244//244 246//246 -f 245//245 246//246 247//247 -f 247//247 246//246 248//248 -f 247//247 248//248 249//249 -f 249//249 248//248 250//250 -f 249//249 250//250 251//251 -f 251//251 250//250 252//252 -f 251//251 252//252 253//253 -f 253//253 252//252 254//254 -f 253//253 254//254 255//255 -f 255//255 254//254 181//181 -f 255//255 181//181 183//183 -f 256//256 257//257 258//258 -f 259//259 260//260 261//261 -f 262//262 263//263 264//264 -f 264//264 265//265 262//262 -f 262//262 265//265 266//266 -f 262//262 266//266 267//267 -f 267//267 268//268 269//269 -f 269//269 268//268 270//270 -f 269//269 270//270 271//271 -f 272//272 269//269 273//273 -f 273//273 269//269 271//271 -f 273//273 271//271 274//274 -f 274//274 271//271 275//275 -f 274//274 275//275 276//276 -f 277//277 278//278 279//279 -f 276//276 275//275 279//279 -f 279//279 275//275 280//280 -f 279//279 280//280 277//277 -f 281//281 282//282 283//283 -f 283//283 282//282 284//284 -f 283//283 284//284 285//285 -f 285//285 284//284 286//286 -f 285//285 286//286 278//278 -f 278//278 286//286 287//287 -f 278//278 287//287 279//279 -f 281//281 288//288 282//282 -f 282//282 288//288 289//289 -f 282//282 289//289 290//290 -f 291//291 292//292 293//293 -f 290//290 294//294 282//282 -f 282//282 294//294 295//295 -f 282//282 295//295 296//296 -f 296//296 297//297 282//282 -f 282//282 297//297 298//298 -f 282//282 298//298 293//293 -f 293//293 298//298 299//299 -f 293//293 299//299 291//291 -f 292//292 300//300 293//293 -f 293//293 300//300 301//301 -f 293//293 301//301 302//302 -f 303//303 304//304 305//305 -f 305//305 304//304 306//306 -f 305//305 306//306 293//293 -f 293//293 306//306 307//307 -f 293//293 307//307 282//282 -f 308//308 309//309 310//310 -f 310//310 309//309 311//311 -f 310//310 311//311 312//312 -f 312//312 311//311 313//313 -f 312//312 313//313 314//314 -f 314//314 313//313 315//315 -f 314//314 315//315 316//316 -f 316//316 315//315 317//317 -f 316//316 317//317 318//318 -f 318//318 317//317 319//319 -f 318//318 319//319 320//320 -f 320//320 319//319 321//321 -f 320//320 321//321 303//303 -f 303//303 321//321 322//322 -f 303//303 322//322 304//304 -f 323//323 324//324 325//325 -f 325//325 324//324 326//326 -f 325//325 326//326 327//327 -f 327//327 326//326 328//328 -f 327//327 328//328 329//329 -f 329//329 328//328 330//330 -f 329//329 330//330 308//308 -f 308//308 330//330 331//331 -f 308//308 331//331 309//309 -f 332//332 333//333 334//334 -f 334//334 333//333 335//335 -f 334//334 335//335 323//323 -f 323//323 335//335 336//336 -f 323//323 336//336 324//324 -f 337//337 338//338 339//339 -f 337//337 339//339 340//340 -f 340//340 339//339 341//341 -f 340//340 341//341 332//332 -f 332//332 341//341 342//342 -f 332//332 342//342 333//333 -f 343//343 344//344 345//345 -f 345//345 344//344 346//346 -f 338//338 337//337 347//347 -f 347//347 337//337 348//348 -f 347//347 348//348 346//346 -f 346//346 348//348 349//349 -f 346//346 349//349 345//345 -f 350//350 351//351 352//352 -f 352//352 351//351 353//353 -f 343//343 345//345 353//353 -f 353//353 345//345 354//354 -f 353//353 354//354 352//352 -f 355//355 356//356 357//357 -f 357//357 356//356 358//358 -f 350//350 352//352 358//358 -f 358//358 352//352 359//359 -f 358//358 359//359 357//357 -f 360//360 361//361 362//362 -f 362//362 361//361 363//363 -f 355//355 357//357 363//363 -f 363//363 357//357 364//364 -f 363//363 364//364 362//362 -f 360//360 362//362 365//365 -f 365//365 362//362 366//366 -f 365//365 366//366 367//367 -f 261//261 260//260 368//368 -f 368//368 260//260 369//369 -f 368//368 369//369 370//370 -f 370//370 369//369 371//371 -f 370//370 371//371 372//372 -f 372//372 371//371 373//373 -f 372//372 373//373 374//374 -f 374//374 373//373 375//375 -f 374//374 375//375 376//376 -f 376//376 375//375 377//377 -f 376//376 377//377 367//367 -f 367//367 377//377 378//378 -f 367//367 378//378 365//365 -f 261//261 379//379 259//259 -f 259//259 379//379 380//380 -f 259//259 380//380 381//381 -f 381//381 380//380 382//382 -f 381//381 382//382 383//383 -f 383//383 382//382 384//384 -f 383//383 384//384 385//385 -f 385//385 384//384 386//386 -f 385//385 386//386 387//387 -f 387//387 386//386 388//388 -f 387//387 388//388 389//389 -f 389//389 388//388 390//390 -f 389//389 390//390 391//391 -f 391//391 390//390 392//392 -f 391//391 392//392 393//393 -f 392//392 394//394 393//393 -f 393//393 394//394 395//395 -f 393//393 395//395 396//396 -f 396//396 395//395 397//397 -f 396//396 397//397 398//398 -f 398//398 397//397 399//399 -f 398//398 399//399 400//400 -f 400//400 399//399 401//401 -f 400//400 401//401 402//402 -f 402//402 401//401 403//403 -f 402//402 403//403 404//404 -f 404//404 403//403 405//405 -f 404//404 405//405 406//406 -f 406//406 405//405 407//407 -f 406//406 407//407 408//408 -f 408//408 407//407 409//409 -f 408//408 409//409 410//410 -f 409//409 411//411 410//410 -f 410//410 411//411 412//412 -f 410//410 412//412 413//413 -f 413//413 412//412 414//414 -f 413//413 414//414 415//415 -f 415//415 414//414 416//416 -f 415//415 416//416 417//417 -f 416//416 418//418 417//417 -f 417//417 418//418 419//419 -f 417//417 419//419 420//420 -f 420//420 419//419 421//421 -f 420//420 421//421 422//422 -f 422//422 421//421 423//423 -f 422//422 423//423 258//258 -f 258//258 423//423 424//424 -f 258//258 424//424 256//256 -f 256//256 424//424 425//425 -f 256//256 425//425 426//426 -f 426//426 425//425 427//427 -f 426//426 427//427 428//428 -f 427//427 429//429 428//428 -f 428//428 429//429 430//430 -f 428//428 430//430 431//431 -f 431//431 430//430 432//432 -f 431//431 432//432 433//433 -f 267//267 269//269 262//262 -f 262//262 269//269 434//434 -f 262//262 434//434 435//435 -f 436//436 437//437 438//438 -f 438//438 437//437 439//439 -f 438//438 439//439 440//440 -f 440//440 439//439 441//441 -f 440//440 441//441 435//435 -f 435//435 441//441 442//442 -f 435//435 442//442 262//262 -f 443//443 444//444 445//445 -f 445//445 444//444 446//446 -f 17//17 14//14 447//447 -f 448//448 449//449 450//450 -f 448//448 450//450 451//451 -f 451//451 450//450 452//452 -f 451//451 452//452 453//453 -f 453//453 452//452 454//454 -f 453//453 454//454 455//455 -f 455//455 454//454 456//456 -f 455//455 456//456 457//457 -f 457//457 456//456 458//458 -f 457//457 458//458 459//459 -f 459//459 458//458 460//460 -f 459//459 460//460 461//461 -f 461//461 460//460 462//462 -f 461//461 462//462 463//463 -f 463//463 462//462 464//464 -f 463//463 464//464 465//465 -f 465//465 464//464 466//466 -f 465//465 466//466 467//467 -f 466//466 468//468 467//467 -f 467//467 468//468 469//469 -f 467//467 469//469 470//470 -f 470//470 469//469 471//471 -f 470//470 471//471 472//472 -f 472//472 471//471 473//473 -f 472//472 473//473 474//474 -f 474//474 473//473 475//475 -f 474//474 475//475 476//476 -f 476//476 475//475 477//477 -f 476//476 477//477 478//478 -f 478//478 477//477 479//479 -f 478//478 479//479 480//480 -f 480//480 479//479 481//481 -f 480//480 481//481 482//482 -f 482//482 481//481 483//483 -f 482//482 483//483 484//484 -f 484//484 483//483 485//485 -f 484//484 485//485 486//486 -f 485//485 487//487 486//486 -f 486//486 487//487 488//488 -f 486//486 488//488 489//489 -f 489//489 488//488 490//490 -f 489//489 490//490 491//491 -f 491//491 490//490 492//492 -f 491//491 492//492 493//493 -f 493//493 492//492 494//494 -f 493//493 494//494 495//495 -f 495//495 494//494 496//496 -f 495//495 496//496 497//497 -f 497//497 496//496 498//498 -f 499//499 500//500 501//501 -f 501//501 500//500 498//498 -f 500//500 502//502 498//498 -f 498//498 502//502 503//503 -f 498//498 503//503 504//504 -f 504//504 505//505 498//498 -f 498//498 505//505 506//506 -f 498//498 506//506 497//497 -f 497//497 506//506 507//507 -f 507//507 508//508 497//497 -f 497//497 508//508 509//509 -f 497//497 509//509 510//510 -f 510//510 511//511 497//497 -f 497//497 511//511 512//512 -f 497//497 512//512 513//513 -f 513//513 512//512 514//514 -f 514//514 512//512 515//515 -f 514//514 515//515 516//516 -f 517//517 518//518 519//519 -f 518//518 520//520 519//519 -f 519//519 520//520 521//521 -f 519//519 521//521 522//522 -f 516//516 523//523 514//514 -f 514//514 523//523 524//524 -f 514//514 524//524 525//525 -f 525//525 524//524 526//526 -f 525//525 526//526 527//527 -f 527//527 526//526 528//528 -f 527//527 528//528 521//521 -f 521//521 528//528 529//529 -f 521//521 529//529 522//522 -f 517//517 519//519 530//530 -f 530//530 519//519 531//531 -f 530//530 531//531 532//532 -f 533//533 534//534 530//530 -f 532//532 535//535 530//530 -f 530//530 535//535 536//536 -f 530//530 536//536 533//533 -f 447//447 14//14 537//537 -f 537//537 14//14 13//13 -f 537//537 13//13 538//538 -f 13//13 7//7 538//538 -f 538//538 7//7 9//9 -f 538//538 9//9 539//539 -f 539//539 9//9 11//11 -f 539//539 11//11 540//540 -f 540//540 11//11 541//541 -f 540//540 541//541 542//542 -f 542//542 541//541 543//543 -f 542//542 543//543 544//544 -f 544//544 543//543 530//530 -f 544//544 530//530 545//545 -f 545//545 530//530 534//534 -f 545//545 534//534 546//546 -f 17//17 447//447 19//19 -f 19//19 447//447 547//547 -f 19//19 547//547 20//20 -f 20//20 547//547 548//548 -f 20//20 548//548 22//22 -f 22//22 548//548 549//549 -f 22//22 549//549 24//24 -f 24//24 549//549 550//550 -f 24//24 550//550 26//26 -f 26//26 550//550 551//551 -f 26//26 551//551 35//35 -f 35//35 551//551 552//552 -f 35//35 552//552 33//33 -f 33//33 552//552 553//553 -f 33//33 553//553 31//31 -f 31//31 553//553 554//554 -f 31//31 554//554 29//29 -f 29//29 554//554 555//555 -f 29//29 555//555 27//27 -f 27//27 555//555 556//556 -f 27//27 556//556 50//50 -f 50//50 556//556 557//557 -f 50//50 557//557 48//48 -f 557//557 558//558 48//48 -f 48//48 558//558 559//559 -f 48//48 559//559 46//46 -f 46//46 559//559 560//560 -f 46//46 560//560 44//44 -f 44//44 560//560 561//561 -f 44//44 561//561 38//38 -f 38//38 561//561 562//562 -f 38//38 562//562 563//563 -f 564//564 5//5 563//563 -f 563//563 5//5 4//4 -f 563//563 4//4 38//38 -f 565//565 566//566 567//567 -f 567//567 566//566 568//568 -f 567//567 568//568 564//564 -f 564//564 568//568 569//569 -f 564//564 569//569 5//5 -f 565//565 567//567 570//570 -f 570//570 567//567 571//571 -f 570//570 571//571 572//572 -f 573//573 574//574 571//571 -f 571//571 574//574 575//575 -f 571//571 575//575 576//576 -f 576//576 577//577 571//571 -f 571//571 577//577 578//578 -f 571//571 578//578 572//572 -f 444//444 579//579 446//446 -f 446//446 579//579 580//580 -f 446//446 580//580 573//573 -f 573//573 580//580 581//581 -f 573//573 581//581 574//574 -f 445//445 582//582 443//443 -f 443//443 582//582 583//583 -f 443//443 583//583 584//584 -f 584//584 583//583 585//585 -f 584//584 585//585 586//586 -f 586//586 585//585 587//587 -f 586//586 587//587 588//588 -f 588//588 587//587 589//589 -f 588//588 589//589 590//590 -f 590//590 589//589 591//591 -f 590//590 591//591 592//592 -f 592//592 591//591 593//593 -f 592//592 593//593 594//594 -f 594//594 593//593 595//595 -f 594//594 595//595 596//596 -f 596//596 595//595 597//597 -f 596//596 597//597 598//598 -f 598//598 597//597 599//599 -f 598//598 599//599 600//600 -f 601//601 602//602 603//603 -f 599//599 604//604 600//600 -f 600//600 604//604 605//605 -f 600//600 605//605 606//606 -f 606//606 605//605 607//607 -f 606//606 607//607 608//608 -f 608//608 607//607 609//609 -f 608//608 609//609 610//610 -f 610//610 609//609 611//611 -f 610//610 611//611 612//612 -f 612//612 611//611 613//613 -f 612//612 613//613 614//614 -f 614//614 613//613 615//615 -f 614//614 615//615 616//616 -f 616//616 615//615 617//617 -f 616//616 617//617 618//618 -f 618//618 617//617 619//619 -f 618//618 619//619 620//620 -f 620//620 619//619 621//621 -f 620//620 621//621 603//603 -f 603//603 621//621 622//622 -f 603//603 622//622 601//601 -f 623//623 624//624 625//625 -f 602//602 601//601 625//625 -f 625//625 601//601 626//626 -f 625//625 626//626 623//623 -f 627//627 628//628 629//629 -f 624//624 623//623 629//629 -f 629//629 623//623 630//630 -f 629//629 630//630 627//627 -f 631//631 632//632 633//633 -f 628//628 627//627 633//633 -f 633//633 627//627 634//634 -f 633//633 634//634 631//631 -f 449//449 448//448 635//635 -f 635//635 448//448 636//636 -f 635//635 636//636 637//637 -f 637//637 636//636 378//378 -f 637//637 378//378 638//638 -f 638//638 378//378 639//639 -f 638//638 639//639 640//640 -f 632//632 631//631 640//640 -f 640//640 631//631 641//641 -f 640//640 641//641 638//638 -f 287//287 286//286 642//642 -f 643//643 644//644 279//279 -f 279//279 644//644 276//276 -f 276//276 644//644 645//645 -f 276//276 645//645 274//274 -f 273//273 274//274 646//646 -f 646//646 274//274 645//645 -f 646//646 645//645 647//647 -f 646//646 647//647 648//648 -f 648//648 647//647 649//649 -f 648//648 649//649 650//650 -f 650//650 649//649 651//651 -f 650//650 651//651 652//652 -f 652//652 651//651 653//653 -f 652//652 653//653 654//654 -f 654//654 653//653 655//655 -f 654//654 655//655 656//656 -f 656//656 655//655 657//657 -f 656//656 657//657 658//658 -f 658//658 657//657 659//659 -f 658//658 659//659 660//660 -f 660//660 659//659 661//661 -f 660//660 661//661 662//662 -f 662//662 661//661 663//663 -f 662//662 663//663 664//664 -f 664//664 663//663 665//665 -f 664//664 665//665 666//666 -f 666//666 665//665 667//667 -f 666//666 667//667 668//668 -f 668//668 667//667 669//669 -f 668//668 669//669 670//670 -f 670//670 669//669 671//671 -f 670//670 671//671 672//672 -f 672//672 671//671 673//673 -f 672//672 673//673 674//674 -f 674//674 673//673 675//675 -f 674//674 675//675 676//676 -f 676//676 675//675 677//677 -f 676//676 677//677 678//678 -f 678//678 677//677 679//679 -f 678//678 679//679 680//680 -f 680//680 679//679 681//681 -f 680//680 681//681 682//682 -f 682//682 681//681 683//683 -f 682//682 683//683 684//684 -f 684//684 683//683 685//685 -f 684//684 685//685 686//686 -f 686//686 685//685 687//687 -f 686//686 687//687 688//688 -f 688//688 687//687 689//689 -f 688//688 689//689 690//690 -f 690//690 689//689 691//691 -f 690//690 691//691 692//692 -f 692//692 691//691 693//693 -f 692//692 693//693 694//694 -f 694//694 693//693 695//695 -f 694//694 695//695 696//696 -f 696//696 695//695 697//697 -f 696//696 697//697 698//698 -f 698//698 697//697 699//699 -f 698//698 699//699 700//700 -f 700//700 699//699 701//701 -f 700//700 701//701 702//702 -f 702//702 701//701 703//703 -f 702//702 703//703 704//704 -f 704//704 703//703 705//705 -f 704//704 705//705 706//706 -f 706//706 705//705 707//707 -f 706//706 707//707 708//708 -f 708//708 707//707 709//709 -f 708//708 709//709 710//710 -f 710//710 709//709 711//711 -f 710//710 711//711 712//712 -f 712//712 711//711 713//713 -f 712//712 713//713 642//642 -f 642//642 713//713 643//643 -f 642//642 643//643 287//287 -f 287//287 643//643 279//279 -f 518//518 517//517 714//714 -f 525//525 527//527 715//715 -f 715//715 527//527 716//716 -f 715//715 716//716 717//717 -f 717//717 716//716 718//718 -f 717//717 718//718 719//719 -f 719//719 718//718 720//720 -f 719//719 720//720 721//721 -f 721//721 720//720 722//722 -f 721//721 722//722 723//723 -f 723//723 722//722 724//724 -f 723//723 724//724 725//725 -f 725//725 724//724 726//726 -f 725//725 726//726 727//727 -f 727//727 726//726 728//728 -f 727//727 728//728 729//729 -f 729//729 728//728 730//730 -f 729//729 730//730 731//731 -f 731//731 730//730 732//732 -f 731//731 732//732 733//733 -f 733//733 732//732 734//734 -f 733//733 734//734 735//735 -f 735//735 734//734 736//736 -f 735//735 736//736 737//737 -f 737//737 736//736 738//738 -f 737//737 738//738 739//739 -f 739//739 738//738 740//740 -f 739//739 740//740 741//741 -f 741//741 740//740 742//742 -f 741//741 742//742 743//743 -f 743//743 742//742 744//744 -f 743//743 744//744 745//745 -f 745//745 744//744 746//746 -f 745//745 746//746 747//747 -f 747//747 746//746 748//748 -f 747//747 748//748 749//749 -f 749//749 748//748 750//750 -f 749//749 750//750 751//751 -f 751//751 750//750 752//752 -f 751//751 752//752 753//753 -f 753//753 752//752 754//754 -f 753//753 754//754 755//755 -f 755//755 754//754 756//756 -f 755//755 756//756 757//757 -f 757//757 756//756 758//758 -f 757//757 758//758 759//759 -f 759//759 758//758 760//760 -f 759//759 760//760 761//761 -f 761//761 760//760 762//762 -f 761//761 762//762 763//763 -f 763//763 762//762 764//764 -f 763//763 764//764 765//765 -f 765//765 764//764 766//766 -f 765//765 766//766 767//767 -f 767//767 766//766 768//768 -f 767//767 768//768 769//769 -f 769//769 768//768 770//770 -f 769//769 770//770 771//771 -f 771//771 770//770 772//772 -f 771//771 772//772 773//773 -f 773//773 772//772 774//774 -f 773//773 774//774 775//775 -f 775//775 774//774 776//776 -f 775//775 776//776 777//777 -f 777//777 776//776 778//778 -f 777//777 778//778 779//779 -f 779//779 778//778 780//780 -f 779//779 780//780 781//781 -f 781//781 780//780 782//782 -f 781//781 782//782 714//714 -f 714//714 782//782 783//783 -f 714//714 783//783 518//518 -f 518//518 783//783 784//784 -f 518//518 784//784 520//520 -f 520//520 784//784 785//785 -f 520//520 785//785 521//521 -f 521//521 785//785 716//716 -f 521//521 716//716 527//527 -f 786//786 787//787 788//788 -f 786//786 788//788 789//789 -f 789//789 788//788 790//790 -f 789//789 790//790 791//791 -f 791//791 790//790 792//792 -f 791//791 792//792 793//793 -f 794//794 795//795 796//796 -f 797//797 798//798 799//799 -f 799//799 798//798 800//800 -f 799//799 800//800 794//794 -f 801//801 802//802 803//803 -f 803//803 802//802 804//804 -f 805//805 806//806 799//799 -f 799//799 806//806 807//807 -f 799//799 807//807 797//797 -f 801//801 803//803 808//808 -f 808//808 803//803 809//809 -f 808//808 809//809 810//810 -f 810//810 811//811 808//808 -f 808//808 811//811 812//812 -f 808//808 812//812 813//813 -f 813//813 812//812 814//814 -f 813//813 814//814 815//815 -f 816//816 817//817 818//818 -f 817//817 819//819 818//818 -f 818//818 819//819 820//820 -f 818//818 820//820 821//821 -f 821//821 822//822 818//818 -f 818//818 822//822 823//823 -f 818//818 823//823 824//824 -f 824//824 825//825 818//818 -f 818//818 825//825 826//826 -f 818//818 826//826 827//827 -f 828//828 829//829 830//830 -f 829//829 831//831 830//830 -f 830//830 831//831 832//832 -f 830//830 832//832 818//818 -f 818//818 832//832 833//833 -f 818//818 833//833 816//816 -f 834//834 835//835 836//836 -f 837//837 836//836 838//838 -f 838//838 836//836 839//839 -f 838//838 839//839 840//840 -f 835//835 841//841 836//836 -f 836//836 841//841 842//842 -f 836//836 842//842 843//843 -f 837//837 844//844 836//836 -f 836//836 844//844 845//845 -f 836//836 845//845 846//846 -f 846//846 847//847 836//836 -f 836//836 847//847 848//848 -f 836//836 848//848 849//849 -f 849//849 850//850 836//836 -f 836//836 850//850 851//851 -f 836//836 851//851 834//834 -f 852//852 853//853 854//854 -f 853//853 855//855 854//854 -f 854//854 855//855 856//856 -f 854//854 856//856 857//857 -f 858//858 859//859 860//860 -f 860//860 859//859 861//861 -f 860//860 861//861 862//862 -f 863//863 854//854 864//864 -f 864//864 854//854 865//865 -f 863//863 866//866 854//854 -f 854//854 866//866 867//867 -f 854//854 867//867 852//852 -f 857//857 868//868 854//854 -f 854//854 868//868 869//869 -f 854//854 869//869 860//860 -f 860//860 869//869 870//870 -f 860//860 870//870 858//858 -f 865//865 854//854 871//871 -f 871//871 854//854 872//872 -f 871//871 872//872 873//873 -f 874//874 875//875 876//876 -f 874//874 876//876 877//877 -f 877//877 876//876 878//878 -f 877//877 878//878 879//879 -f 880//880 874//874 881//881 -f 881//881 874//874 882//882 -f 881//881 882//882 883//883 -f 880//880 884//884 874//874 -f 874//874 884//884 885//885 -f 874//874 885//885 886//886 -f 887//887 877//877 888//888 -f 888//888 877//877 889//889 -f 862//862 890//890 860//860 -f 860//860 890//890 877//877 -f 860//860 877//877 891//891 -f 891//891 877//877 887//887 -f 886//886 892//892 874//874 -f 874//874 892//892 893//893 -f 874//874 893//893 875//875 -f 879//879 894//894 877//877 -f 877//877 894//894 895//895 -f 877//877 895//895 889//889 -f 896//896 897//897 796//796 -f 896//896 796//796 898//898 -f 899//899 900//900 795//795 -f 795//795 900//900 901//901 -f 795//795 901//901 902//902 -f 897//897 903//903 796//796 -f 796//796 903//903 904//904 -f 796//796 904//904 905//905 -f 902//902 906//906 795//795 -f 795//795 906//906 907//907 -f 795//795 907//907 908//908 -f 905//905 909//909 796//796 -f 796//796 909//909 910//910 -f 796//796 910//910 911//911 -f 908//908 912//912 795//795 -f 795//795 912//912 913//913 -f 795//795 913//913 796//796 -f 796//796 913//913 914//914 -f 796//796 914//914 898//898 -f 915//915 916//916 917//917 -f 915//915 917//917 918//918 -f 916//916 919//919 917//917 -f 917//917 919//919 920//920 -f 917//917 920//920 795//795 -f 795//795 920//920 921//921 -f 795//795 921//921 899//899 -f 922//922 923//923 924//924 -f 922//922 924//924 917//917 -f 917//917 924//924 925//925 -f 917//917 925//925 918//918 -f 926//926 927//927 922//922 -f 922//922 927//927 928//928 -f 922//922 928//928 923//923 -f 883//883 882//882 926//926 -f 926//926 882//882 929//929 -f 926//926 929//929 930//930 -f 931//931 932//932 926//926 -f 926//926 932//932 933//933 -f 926//926 933//933 927//927 -f 930//930 934//934 926//926 -f 926//926 934//934 935//935 -f 926//926 935//935 931//931 -f 936//936 937//937 872//872 -f 937//937 938//938 872//872 -f 872//872 938//938 939//939 -f 872//872 939//939 873//873 -f 940//940 941//941 872//872 -f 872//872 941//941 942//942 -f 872//872 942//942 936//936 -f 940//940 872//872 943//943 -f 943//943 872//872 944//944 -f 943//943 944//944 945//945 -f 946//946 947//947 948//948 -f 948//948 947//947 949//949 -f 949//949 950//950 948//948 -f 948//948 950//950 951//951 -f 948//948 951//951 952//952 -f 952//952 953//953 948//948 -f 948//948 953//953 954//954 -f 948//948 954//954 955//955 -f 955//955 956//956 948//948 -f 948//948 956//956 957//957 -f 948//948 957//957 944//944 -f 944//944 957//957 958//958 -f 944//944 958//958 945//945 -f 959//959 872//872 960//960 -f 960//960 872//872 961//961 -f 962//962 963//963 964//964 -f 963//963 965//965 964//964 -f 964//964 965//965 966//966 -f 964//964 966//966 967//967 -f 968//968 969//969 854//854 -f 854//854 969//969 970//970 -f 854//854 970//970 872//872 -f 872//872 970//970 971//971 -f 872//872 971//971 961//961 -f 971//971 972//972 961//961 -f 961//961 972//972 973//973 -f 961//961 973//973 974//974 -f 974//974 973//973 975//975 -f 974//974 975//975 976//976 -f 977//977 836//836 978//978 -f 978//978 836//836 964//964 -f 977//977 979//979 836//836 -f 836//836 979//979 980//980 -f 836//836 980//980 981//981 -f 959//959 982//982 872//872 -f 872//872 982//982 983//983 -f 872//872 983//983 984//984 -f 984//984 985//985 872//872 -f 872//872 985//985 986//986 -f 872//872 986//986 987//987 -f 987//987 988//988 872//872 -f 872//872 988//988 989//989 -f 872//872 989//989 964//964 -f 964//964 989//989 990//990 -f 964//964 990//990 962//962 -f 991//991 992//992 993//993 -f 981//981 994//994 836//836 -f 836//836 994//994 995//995 -f 836//836 995//995 996//996 -f 854//854 997//997 998//998 -f 998//998 999//999 854//854 -f 854//854 999//999 1000//1000 -f 854//854 1000//1000 1001//1001 -f 967//967 1002//1002 964//964 -f 964//964 1002//1002 1003//1003 -f 964//964 1003//1003 1004//1004 -f 1004//1004 1005//1005 964//964 -f 964//964 1005//1005 1006//1006 -f 964//964 1006//1006 978//978 -f 978//978 1006//1006 1007//1007 -f 996//996 1008//1008 836//836 -f 836//836 1008//1008 1009//1009 -f 836//836 1009//1009 854//854 -f 854//854 1009//1009 1010//1010 -f 854//854 1010//1010 997//997 -f 1001//1001 1011//1011 854//854 -f 854//854 1011//1011 1012//1012 -f 854//854 1012//1012 968//968 -f 991//991 993//993 1013//1013 -f 1014//1014 1015//1015 975//975 -f 975//975 1015//1015 1016//1016 -f 975//975 1016//1016 976//976 -f 1007//1007 1017//1017 978//978 -f 978//978 1017//1017 1018//1018 -f 978//978 1018//1018 1019//1019 -f 1019//1019 1018//1018 993//993 -f 1019//1019 993//993 1020//1020 -f 1020//1020 993//993 992//992 -f 1021//1021 1022//1022 975//975 -f 975//975 1022//1022 1023//1023 -f 975//975 1023//1023 1014//1014 -f 1021//1021 1024//1024 1022//1022 -f 1022//1022 1024//1024 1025//1025 -f 1022//1022 1025//1025 1026//1026 -f 1013//1013 993//993 1027//1027 -f 1027//1027 993//993 1028//1028 -f 1027//1027 1028//1028 1029//1029 -f 1029//1029 1028//1028 1030//1030 -f 1029//1029 1030//1030 1031//1031 -f 1031//1031 1030//1030 1032//1032 -f 1031//1031 1032//1032 1026//1026 -f 1026//1026 1032//1032 1033//1033 -f 1026//1026 1033//1033 1022//1022 -f 1034//1034 1035//1035 872//872 -f 1035//1035 1036//1036 872//872 -f 872//872 1036//1036 1037//1037 -f 872//872 1037//1037 944//944 -f 944//944 1037//1037 1038//1038 -f 944//944 1038//1038 1039//1039 -f 1039//1039 1040//1040 944//944 -f 944//944 1040//1040 1041//1041 -f 944//944 1041//1041 1042//1042 -f 1043//1043 1044//1044 1045//1045 -f 1042//1042 1046//1046 944//944 -f 944//944 1046//1046 1047//1047 -f 944//944 1047//1047 1048//1048 -f 1048//1048 1049//1049 944//944 -f 944//944 1049//1049 1050//1050 -f 944//944 1050//1050 1045//1045 -f 1045//1045 1050//1050 1051//1051 -f 1045//1045 1051//1051 1043//1043 -f 1044//1044 1052//1052 1045//1045 -f 1045//1045 1052//1052 1053//1053 -f 1045//1045 1053//1053 1054//1054 -f 1054//1054 1055//1055 1045//1045 -f 1045//1045 1055//1055 1056//1056 -f 1045//1045 1056//1056 964//964 -f 964//964 1056//1056 1057//1057 -f 964//964 1057//1057 1058//1058 -f 1059//1059 1060//1060 872//872 -f 872//872 1060//1060 1061//1061 -f 872//872 1061//1061 1062//1062 -f 1062//1062 1063//1063 872//872 -f 872//872 1063//1063 1064//1064 -f 872//872 1064//1064 1034//1034 -f 964//964 1065//1065 1066//1066 -f 1058//1058 1067//1067 964//964 -f 964//964 1067//1067 1068//1068 -f 964//964 1068//1068 1065//1065 -f 1066//1066 1069//1069 964//964 -f 964//964 1069//1069 1070//1070 -f 964//964 1070//1070 872//872 -f 872//872 1070//1070 1071//1071 -f 872//872 1071//1071 1059//1059 -f 1072//1072 1073//1073 944//944 -f 1074//1074 1075//1075 948//948 -f 1076//1076 1077//1077 1078//1078 -f 1079//1079 1080//1080 1045//1045 -f 1045//1045 1080//1080 1081//1081 -f 1073//1073 1082//1082 944//944 -f 944//944 1082//1082 1083//1083 -f 944//944 1083//1083 1084//1084 -f 1074//1074 948//948 1085//1085 -f 1085//1085 948//948 944//944 -f 1085//1085 944//944 1086//1086 -f 1075//1075 1087//1087 948//948 -f 948//948 1087//1087 1088//1088 -f 948//948 1088//1088 1089//1089 -f 1090//1090 1091//1091 1045//1045 -f 1045//1045 1091//1091 1092//1092 -f 1045//1045 1092//1092 1079//1079 -f 1081//1081 1093//1093 1045//1045 -f 1045//1045 1093//1093 1094//1094 -f 1045//1045 1094//1094 944//944 -f 944//944 1094//1094 1095//1095 -f 944//944 1095//1095 1072//1072 -f 1084//1084 1096//1096 944//944 -f 944//944 1096//1096 1097//1097 -f 944//944 1097//1097 1086//1086 -f 1089//1089 1098//1098 948//948 -f 948//948 1098//1098 1099//1099 -f 948//948 1099//1099 1100//1100 -f 1100//1100 1101//1101 948//948 -f 948//948 1101//1101 1102//1102 -f 948//948 1102//1102 1078//1078 -f 1078//1078 1102//1102 1103//1103 -f 1078//1078 1103//1103 1076//1076 -f 1077//1077 1104//1104 1078//1078 -f 1078//1078 1104//1104 1105//1105 -f 1078//1078 1105//1105 1106//1106 -f 1106//1106 1107//1107 1078//1078 -f 1078//1078 1107//1107 1108//1108 -f 1078//1078 1108//1108 1045//1045 -f 1045//1045 1108//1108 1109//1109 -f 1045//1045 1109//1109 1090//1090 -f 1110//1110 948//948 1111//1111 -f 1111//1111 948//948 1112//1112 -f 796//796 1113//1113 1114//1114 -f 1078//1078 1115//1115 1116//1116 -f 1110//1110 1117//1117 948//948 -f 948//948 1117//1117 1118//1118 -f 948//948 1118//1118 1119//1119 -f 911//911 946//946 796//796 -f 796//796 946//946 948//948 -f 796//796 948//948 1113//1113 -f 1113//1113 948//948 1120//1120 -f 1114//1114 1121//1121 796//796 -f 796//796 1121//1121 1122//1122 -f 796//796 1122//1122 1123//1123 -f 1116//1116 1124//1124 1078//1078 -f 1078//1078 1124//1124 1125//1125 -f 1078//1078 1125//1125 948//948 -f 948//948 1125//1125 1126//1126 -f 948//948 1126//1126 1112//1112 -f 1123//1123 1127//1127 796//796 -f 796//796 1127//1127 1128//1128 -f 796//796 1128//1128 1129//1129 -f 1129//1129 1130//1130 796//796 -f 796//796 1130//1130 1131//1131 -f 796//796 1131//1131 1132//1132 -f 1119//1119 1133//1133 948//948 -f 948//948 1133//1133 1134//1134 -f 948//948 1134//1134 1120//1120 -f 1132//1132 1135//1135 1136//1136 -f 1136//1136 1135//1135 1137//1137 -f 1136//1136 1137//1137 1138//1138 -f 1138//1138 1139//1139 1136//1136 -f 1136//1136 1139//1139 1140//1140 -f 1136//1136 1140//1140 1141//1141 -f 1142//1142 1143//1143 1078//1078 -f 1078//1078 1143//1143 1144//1144 -f 1078//1078 1144//1144 1115//1115 -f 1141//1141 1145//1145 1136//1136 -f 1136//1136 1145//1145 1146//1146 -f 1136//1136 1146//1146 1078//1078 -f 1078//1078 1146//1146 1147//1147 -f 1078//1078 1147//1147 1142//1142 -f 843//843 1148//1148 836//836 -f 836//836 1148//1148 1149//1149 -f 836//836 1149//1149 964//964 -f 964//964 1149//1149 1150//1150 -f 964//964 1150//1150 1045//1045 -f 1045//1045 1150//1150 1151//1151 -f 1045//1045 1151//1151 1078//1078 -f 1078//1078 1151//1151 1152//1152 -f 1078//1078 1152//1152 1136//1136 -f 1136//1136 1152//1152 1153//1153 -f 1136//1136 1153//1153 830//830 -f 830//830 1153//1153 1154//1154 -f 830//830 1154//1154 828//828 -f 1155//1155 1156//1156 830//830 -f 1157//1157 1158//1158 1136//1136 -f 1159//1159 1160//1160 799//799 -f 799//799 1160//1160 1161//1161 -f 799//799 1161//1161 1162//1162 -f 1163//1163 1164//1164 799//799 -f 794//794 796//796 799//799 -f 799//799 796//796 1165//1165 -f 799//799 1165//1165 1159//1159 -f 1164//1164 1166//1166 799//799 -f 799//799 1166//1166 1167//1167 -f 799//799 1167//1167 830//830 -f 830//830 1167//1167 1168//1168 -f 830//830 1168//1168 1155//1155 -f 1132//1132 1136//1136 796//796 -f 796//796 1136//1136 1158//1158 -f 796//796 1158//1158 1169//1169 -f 1156//1156 1170//1170 830//830 -f 830//830 1170//1170 1171//1171 -f 830//830 1171//1171 1172//1172 -f 1169//1169 1173//1173 796//796 -f 796//796 1173//1173 1174//1174 -f 796//796 1174//1174 1175//1175 -f 1162//1162 1176//1176 799//799 -f 799//799 1176//1176 1177//1177 -f 799//799 1177//1177 1163//1163 -f 1172//1172 1178//1178 830//830 -f 830//830 1178//1178 1179//1179 -f 830//830 1179//1179 1136//1136 -f 1136//1136 1179//1179 1180//1180 -f 1136//1136 1180//1180 1181//1181 -f 1181//1181 1182//1182 1136//1136 -f 1136//1136 1182//1182 1183//1183 -f 1136//1136 1183//1183 1184//1184 -f 1184//1184 1185//1185 1136//1136 -f 1136//1136 1185//1185 1186//1186 -f 1136//1136 1186//1186 1157//1157 -f 1175//1175 1187//1187 796//796 -f 796//796 1187//1187 1188//1188 -f 796//796 1188//1188 1189//1189 -f 1189//1189 1190//1190 796//796 -f 796//796 1190//1190 1191//1191 -f 796//796 1191//1191 1165//1165 -f 818//818 1192//1192 830//830 -f 830//830 1192//1192 804//804 -f 830//830 804//804 799//799 -f 799//799 804//804 802//802 -f 799//799 802//802 805//805 -f 1193//1193 1194//1194 804//804 -f 804//804 1194//1194 1195//1195 -f 804//804 1195//1195 803//803 -f 803//803 1195//1195 1196//1196 -f 803//803 1196//1196 1197//1197 -f 1198//1198 1199//1199 1192//1192 -f 1192//1192 1199//1199 1200//1200 -f 1192//1192 1200//1200 804//804 -f 804//804 1200//1200 1201//1201 -f 804//804 1201//1201 1193//1193 -f 1202//1202 1203//1203 1204//1204 -f 1204//1204 1203//1203 1205//1205 -f 1204//1204 1205//1205 1206//1206 -f 1207//1207 1208//1208 1209//1209 -f 1209//1209 1208//1208 1210//1210 -f 1197//1197 1211//1211 803//803 -f 803//803 1211//1211 1212//1212 -f 803//803 1212//1212 1213//1213 -f 1213//1213 1212//1212 1209//1209 -f 1213//1213 1209//1209 1214//1214 -f 1214//1214 1209//1209 1210//1210 -f 1198//1198 1192//1192 1204//1204 -f 1204//1204 1192//1192 818//818 -f 1204//1204 818//818 1202//1202 -f 1215//1215 1216//1216 1217//1217 -f 1217//1217 1216//1216 1218//1218 -f 1217//1217 1218//1218 1219//1219 -f 1215//1215 1220//1220 1216//1216 -f 1216//1216 1220//1220 1221//1221 -f 1216//1216 1221//1221 1222//1222 -f 1223//1223 1224//1224 1218//1218 -f 1218//1218 1224//1224 1225//1225 -f 1218//1218 1225//1225 1219//1219 -f 1226//1226 1227//1227 1228//1228 -f 1228//1228 1227//1227 1229//1229 -f 1228//1228 1229//1229 1230//1230 -f 1222//1222 1231//1231 1216//1216 -f 1216//1216 1231//1231 1232//1232 -f 1216//1216 1232//1232 1233//1233 -f 1233//1233 1232//1232 1234//1234 -f 1233//1233 1234//1234 1235//1235 -f 1235//1235 1234//1234 1236//1236 -f 1223//1223 1218//1218 1228//1228 -f 1228//1228 1218//1218 1237//1237 -f 1228//1228 1237//1237 1226//1226 -f 1238//1238 1239//1239 1240//1240 -f 1240//1240 1239//1239 1241//1241 -f 1240//1240 1241//1241 1242//1242 -f 1238//1238 1243//1243 1239//1239 -f 1239//1239 1243//1243 1244//1244 -f 1239//1239 1244//1244 1245//1245 -f 1246//1246 1247//1247 1241//1241 -f 1241//1241 1247//1247 1248//1248 -f 1241//1241 1248//1248 1242//1242 -f 1249//1249 1250//1250 1251//1251 -f 1251//1251 1250//1250 1252//1252 -f 1251//1251 1252//1252 1253//1253 -f 1245//1245 1254//1254 1239//1239 -f 1239//1239 1254//1254 1255//1255 -f 1239//1239 1255//1255 1256//1256 -f 1256//1256 1255//1255 1257//1257 -f 1256//1256 1257//1257 1258//1258 -f 1258//1258 1257//1257 1259//1259 -f 1246//1246 1241//1241 1251//1251 -f 1251//1251 1241//1241 1260//1260 -f 1251//1251 1260//1260 1249//1249 -f 1261//1261 1262//1262 1263//1263 -f 1263//1263 1262//1262 1264//1264 -f 1263//1263 1264//1264 1265//1265 -f 1261//1261 1266//1266 1262//1262 -f 1262//1262 1266//1266 1267//1267 -f 1262//1262 1267//1267 1268//1268 -f 1269//1269 1270//1270 1264//1264 -f 1264//1264 1270//1270 1271//1271 -f 1264//1264 1271//1271 1265//1265 -f 1272//1272 1273//1273 1274//1274 -f 1272//1272 1274//1274 1275//1275 -f 1276//1276 1277//1277 1278//1278 -f 1278//1278 1277//1277 1279//1279 -f 1268//1268 1280//1280 1262//1262 -f 1262//1262 1280//1280 1281//1281 -f 1262//1262 1281//1281 1282//1282 -f 1282//1282 1281//1281 1278//1278 -f 1282//1282 1278//1278 1283//1283 -f 1283//1283 1278//1278 1279//1279 -f 1269//1269 1264//1264 1274//1274 -f 1274//1274 1264//1264 1284//1284 -f 1274//1274 1284//1284 1275//1275 -f 1285//1285 1264//1264 1286//1286 -f 1286//1286 1264//1264 1262//1262 -f 1286//1286 1262//1262 1287//1287 -f 1285//1285 1288//1288 1264//1264 -f 1264//1264 1288//1288 1289//1289 -f 1264//1264 1289//1289 1290//1290 -f 1291//1291 1292//1292 1262//1262 -f 1262//1262 1292//1292 1293//1293 -f 1262//1262 1293//1293 1287//1287 -f 1294//1294 1295//1295 1296//1296 -f 1294//1294 1296//1296 1297//1297 -f 1298//1298 1299//1299 1300//1300 -f 1300//1300 1299//1299 1301//1301 -f 1290//1290 1302//1302 1264//1264 -f 1264//1264 1302//1302 1303//1303 -f 1264//1264 1303//1303 1304//1304 -f 1304//1304 1303//1303 1300//1300 -f 1304//1304 1300//1300 1305//1305 -f 1305//1305 1300//1300 1301//1301 -f 1291//1291 1262//1262 1296//1296 -f 1296//1296 1262//1262 1306//1306 -f 1296//1296 1306//1306 1297//1297 -f 1307//1307 1308//1308 1309//1309 -f 1309//1309 1308//1308 1310//1310 -f 1309//1309 1310//1310 1311//1311 -f 1312//1312 1313//1313 1310//1310 -f 1310//1310 1313//1313 1314//1314 -f 1310//1310 1314//1314 1311//1311 -f 1307//1307 1315//1315 1308//1308 -f 1308//1308 1315//1315 1316//1316 -f 1308//1308 1316//1316 1317//1317 -f 1317//1317 1318//1318 1308//1308 -f 1308//1308 1318//1318 1319//1319 -f 1308//1308 1319//1319 1320//1320 -f 1321//1321 1322//1322 1310//1310 -f 1321//1321 1310//1310 1323//1323 -f 1322//1322 1324//1324 1310//1310 -f 1310//1310 1324//1324 1325//1325 -f 1310//1310 1325//1325 1312//1312 -f 1320//1320 1326//1326 1308//1308 -f 1308//1308 1326//1326 1327//1327 -f 1308//1308 1327//1327 1328//1328 -f 1329//1329 1330//1330 1310//1310 -f 1310//1310 1330//1330 1331//1331 -f 1310//1310 1331//1331 1323//1323 -f 1328//1328 1332//1332 1308//1308 -f 1308//1308 1332//1332 1333//1333 -f 1308//1308 1333//1333 1334//1334 -f 1334//1334 1333//1333 1335//1335 -f 1334//1334 1335//1335 1336//1336 -f 1336//1336 1335//1335 1337//1337 -f 1336//1336 1337//1337 1338//1338 -f 1329//1329 1310//1310 1339//1339 -f 1339//1339 1310//1310 1340//1340 -f 1339//1339 1340//1340 1341//1341 -f 1341//1341 1340//1340 1342//1342 -f 1341//1341 1342//1342 1343//1343 -f 1343//1343 1344//1344 1341//1341 -f 1341//1341 1344//1344 1345//1345 -f 1341//1341 1345//1345 1346//1346 -f 1347//1347 1348//1348 1349//1349 -f 1349//1349 1348//1348 1341//1341 -f 1349//1349 1341//1341 1350//1350 -f 1350//1350 1341//1341 1346//1346 -f 1351//1351 1352//1352 1353//1353 -f 1353//1353 1352//1352 1354//1354 -f 1353//1353 1354//1354 1355//1355 -f 1351//1351 1356//1356 1352//1352 -f 1352//1352 1356//1356 1357//1357 -f 1352//1352 1357//1357 1358//1358 -f 1359//1359 1360//1360 1354//1354 -f 1354//1354 1360//1360 1361//1361 -f 1354//1354 1361//1361 1355//1355 -f 1362//1362 1363//1363 1364//1364 -f 1364//1364 1363//1363 1365//1365 -f 1364//1364 1365//1365 1366//1366 -f 1358//1358 1367//1367 1352//1352 -f 1352//1352 1367//1367 1368//1368 -f 1352//1352 1368//1368 1369//1369 -f 1369//1369 1368//1368 1370//1370 -f 1369//1369 1370//1370 1371//1371 -f 1359//1359 1354//1354 1364//1364 -f 1364//1364 1354//1354 1372//1372 -f 1364//1364 1372//1372 1362//1362 -f 1373//1373 1370//1370 1374//1374 -f 1374//1374 1370//1370 1375//1375 -f 1373//1373 1376//1376 1370//1370 -f 1370//1370 1376//1376 1377//1377 -f 1370//1370 1377//1377 1371//1371 -f 1378//1378 1379//1379 1380//1380 -f 1380//1380 1379//1379 1381//1381 -f 1380//1380 1381//1381 1382//1382 -f 1378//1378 1383//1383 1379//1379 -f 1379//1379 1383//1383 1384//1384 -f 1379//1379 1384//1384 1385//1385 -f 1386//1386 1387//1387 1381//1381 -f 1381//1381 1387//1387 1388//1388 -f 1381//1381 1388//1388 1382//1382 -f 1386//1386 1381//1381 1389//1389 -f 1389//1389 1381//1381 1390//1390 -f 1389//1389 1390//1390 1370//1370 -f 1370//1370 1390//1390 1391//1391 -f 1370//1370 1391//1391 1392//1392 -f 1393//1393 1394//1394 1348//1348 -f 1385//1385 1395//1395 1379//1379 -f 1379//1379 1395//1395 1396//1396 -f 1379//1379 1396//1396 1397//1397 -f 1397//1397 1396//1396 1348//1348 -f 1397//1397 1348//1348 1398//1398 -f 1394//1394 1399//1399 1348//1348 -f 1348//1348 1399//1399 1400//1400 -f 1348//1348 1400//1400 1398//1398 -f 1392//1392 1401//1401 1370//1370 -f 1370//1370 1401//1401 1402//1402 -f 1370//1370 1402//1402 1375//1375 -f 1347//1347 1403//1403 1348//1348 -f 1348//1348 1403//1403 1404//1404 -f 1348//1348 1404//1404 1393//1393 -f 860//860 1405//1405 854//854 -f 854//854 1405//1405 1406//1406 -f 854//854 1406//1406 1407//1407 -f 1407//1407 1408//1408 854//854 -f 854//854 1408//1408 1409//1409 -f 854//854 1409//1409 836//836 -f 1410//1410 1411//1411 860//860 -f 860//860 1411//1411 1412//1412 -f 860//860 1412//1412 1405//1405 -f 1413//1413 1414//1414 1415//1415 -f 1413//1413 1415//1415 1416//1416 -f 1417//1417 1418//1418 1419//1419 -f 1419//1419 1418//1418 1420//1420 -f 1409//1409 1421//1421 836//836 -f 836//836 1421//1421 1422//1422 -f 836//836 1422//1422 839//839 -f 839//839 1422//1422 1423//1423 -f 839//839 1423//1423 1424//1424 -f 1424//1424 1423//1423 1419//1419 -f 1424//1424 1419//1419 1425//1425 -f 1425//1425 1419//1419 1420//1420 -f 1410//1410 860//860 1415//1415 -f 1415//1415 860//860 1426//1426 -f 1415//1415 1426//1426 1416//1416 -f 1427//1427 1428//1428 1429//1429 -f 1429//1429 1428//1428 1430//1430 -f 1429//1429 1430//1430 1431//1431 -f 1432//1432 1433//1433 1430//1430 -f 1430//1430 1433//1433 1434//1434 -f 1430//1430 1434//1434 1431//1431 -f 1427//1427 1435//1435 1428//1428 -f 1428//1428 1435//1435 1436//1436 -f 1428//1428 1436//1436 1437//1437 -f 1437//1437 1438//1438 1428//1428 -f 1428//1428 1438//1438 1439//1439 -f 1428//1428 1439//1439 1440//1440 -f 1441//1441 1442//1442 1430//1430 -f 1441//1441 1430//1430 1443//1443 -f 1442//1442 1444//1444 1430//1430 -f 1430//1430 1444//1444 1445//1445 -f 1430//1430 1445//1445 1432//1432 -f 1440//1440 1446//1446 1428//1428 -f 1428//1428 1446//1446 1447//1447 -f 1428//1428 1447//1447 1448//1448 -f 1449//1449 1450//1450 1430//1430 -f 1430//1430 1450//1450 1451//1451 -f 1430//1430 1451//1451 1443//1443 -f 1448//1448 1452//1452 1428//1428 -f 1428//1428 1452//1452 1453//1453 -f 1428//1428 1453//1453 1454//1454 -f 1454//1454 1453//1453 1455//1455 -f 1454//1454 1455//1455 1456//1456 -f 1456//1456 1455//1455 1457//1457 -f 1456//1456 1457//1457 1458//1458 -f 1459//1459 1460//1460 1461//1461 -f 1461//1461 1460//1460 1462//1462 -f 1449//1449 1430//1430 1463//1463 -f 1463//1463 1430//1430 1464//1464 -f 1463//1463 1464//1464 1460//1460 -f 1460//1460 1464//1464 1465//1465 -f 1460//1460 1465//1465 1462//1462 -f 1466//1466 1381//1381 1467//1467 -f 1467//1467 1381//1381 1379//1379 -f 1467//1467 1379//1379 1468//1468 -f 1466//1466 1469//1469 1381//1381 -f 1381//1381 1469//1469 1470//1470 -f 1381//1381 1470//1470 1471//1471 -f 1472//1472 1473//1473 1379//1379 -f 1379//1379 1473//1473 1474//1474 -f 1379//1379 1474//1474 1468//1468 -f 1475//1475 1476//1476 1477//1477 -f 1475//1475 1477//1477 1478//1478 -f 1479//1479 1480//1480 1481//1481 -f 1481//1481 1480//1480 1482//1482 -f 1471//1471 1483//1483 1381//1381 -f 1381//1381 1483//1483 1484//1484 -f 1381//1381 1484//1484 1485//1485 -f 1485//1485 1484//1484 1481//1481 -f 1485//1485 1481//1481 1486//1486 -f 1486//1486 1481//1481 1482//1482 -f 1472//1472 1379//1379 1477//1477 -f 1477//1477 1379//1379 1487//1487 -f 1477//1477 1487//1487 1478//1478 -f 1488//1488 1489//1489 1490//1490 -f 1490//1490 1489//1489 1491//1491 -f 1490//1490 1491//1491 1492//1492 -f 1488//1488 1493//1493 1489//1489 -f 1489//1489 1493//1493 1494//1494 -f 1489//1489 1494//1494 1495//1495 -f 1496//1496 1497//1497 1491//1491 -f 1491//1491 1497//1497 1498//1498 -f 1491//1491 1498//1498 1492//1492 -f 1499//1499 1500//1500 1501//1501 -f 1501//1501 1500//1500 1502//1502 -f 1501//1501 1502//1502 1503//1503 -f 1495//1495 1504//1504 1489//1489 -f 1489//1489 1504//1504 1505//1505 -f 1489//1489 1505//1505 1506//1506 -f 1506//1506 1505//1505 1507//1507 -f 1506//1506 1507//1507 1508//1508 -f 1508//1508 1507//1507 1509//1509 -f 1496//1496 1491//1491 1501//1501 -f 1501//1501 1491//1491 1510//1510 -f 1501//1501 1510//1510 1499//1499 -f 1511//1511 1218//1218 1512//1512 -f 1512//1512 1218//1218 1216//1216 -f 1512//1512 1216//1216 1513//1513 -f 1511//1511 1514//1514 1218//1218 -f 1218//1218 1514//1514 1515//1515 -f 1218//1218 1515//1515 1516//1516 -f 1517//1517 1518//1518 1216//1216 -f 1216//1216 1518//1518 1519//1519 -f 1216//1216 1519//1519 1513//1513 -f 1520//1520 1521//1521 1522//1522 -f 1523//1523 1524//1524 1522//1522 -f 1522//1522 1524//1524 1525//1525 -f 1522//1522 1525//1525 1520//1520 -f 1526//1526 1527//1527 1528//1528 -f 1528//1528 1527//1527 1529//1529 -f 1528//1528 1529//1529 1530//1530 -f 1517//1517 1216//1216 1522//1522 -f 1522//1522 1216//1216 1531//1531 -f 1522//1522 1531//1531 1523//1523 -f 1516//1516 1532//1532 1218//1218 -f 1218//1218 1532//1532 1533//1533 -f 1218//1218 1533//1533 1534//1534 -f 1534//1534 1533//1533 1528//1528 -f 1534//1534 1528//1528 1535//1535 -f 1535//1535 1528//1528 1530//1530 -f 1536//1536 1537//1537 1151//1151 -f 1151//1151 1537//1537 1152//1152 -f 1536//1536 1151//1151 1538//1538 -f 1538//1538 1151//1151 1150//1150 -f 1538//1538 1150//1150 1539//1539 -f 1537//1537 1540//1540 1152//1152 -f 1152//1152 1540//1540 1541//1541 -f 1152//1152 1541//1541 1153//1153 -f 1542//1542 1543//1543 1544//1544 -f 1539//1539 1150//1150 1545//1545 -f 1545//1545 1150//1150 1149//1149 -f 1545//1545 1149//1149 1546//1546 -f 1547//1547 1548//1548 1544//1544 -f 1544//1544 1548//1548 1549//1549 -f 1544//1544 1549//1549 1542//1542 -f 1550//1550 1551//1551 1552//1552 -f 1552//1552 1551//1551 1553//1553 -f 1552//1552 1553//1553 1554//1554 -f 1546//1546 1149//1149 1544//1544 -f 1544//1544 1149//1149 1555//1555 -f 1544//1544 1555//1555 1547//1547 -f 1541//1541 1556//1556 1153//1153 -f 1153//1153 1556//1556 1557//1557 -f 1153//1153 1557//1557 1154//1154 -f 1154//1154 1557//1557 1558//1558 -f 1154//1154 1558//1558 1559//1559 -f 1559//1559 1558//1558 1552//1552 -f 1559//1559 1552//1552 1560//1560 -f 1560//1560 1552//1552 1554//1554 -f 1561//1561 1310//1310 1562//1562 -f 1562//1562 1310//1310 1308//1308 -f 1562//1562 1308//1308 1563//1563 -f 1564//1564 1565//1565 1308//1308 -f 1308//1308 1565//1565 1566//1566 -f 1308//1308 1566//1566 1563//1563 -f 1561//1561 1567//1567 1310//1310 -f 1310//1310 1567//1567 1568//1568 -f 1310//1310 1568//1568 1569//1569 -f 1569//1569 1570//1570 1310//1310 -f 1310//1310 1570//1570 1571//1571 -f 1310//1310 1571//1571 1572//1572 -f 1573//1573 1574//1574 1308//1308 -f 1573//1573 1308//1308 1575//1575 -f 1574//1574 1576//1576 1308//1308 -f 1308//1308 1576//1576 1577//1577 -f 1308//1308 1577//1577 1564//1564 -f 1572//1572 1578//1578 1310//1310 -f 1310//1310 1578//1578 1579//1579 -f 1310//1310 1579//1579 1580//1580 -f 1581//1581 1582//1582 1308//1308 -f 1308//1308 1582//1582 1583//1583 -f 1308//1308 1583//1583 1575//1575 -f 1584//1584 1585//1585 1586//1586 -f 1580//1580 1587//1587 1310//1310 -f 1310//1310 1587//1587 1588//1588 -f 1310//1310 1588//1588 1589//1589 -f 1589//1589 1588//1588 1590//1590 -f 1591//1591 1592//1592 1593//1593 -f 1593//1593 1592//1592 1594//1594 -f 1593//1593 1594//1594 1595//1595 -f 1586//1586 1596//1596 1584//1584 -f 1584//1584 1596//1596 1597//1597 -f 1584//1584 1597//1597 1590//1590 -f 1590//1590 1597//1597 1598//1598 -f 1590//1590 1598//1598 1589//1589 -f 1581//1581 1308//1308 1599//1599 -f 1599//1599 1308//1308 1600//1600 -f 1599//1599 1600//1600 1593//1593 -f 1593//1593 1600//1600 1601//1601 -f 1593//1593 1601//1601 1591//1591 -f 1602//1602 1430//1430 1603//1603 -f 1603//1603 1430//1430 1428//1428 -f 1603//1603 1428//1428 1604//1604 -f 1605//1605 1606//1606 1428//1428 -f 1428//1428 1606//1606 1607//1607 -f 1428//1428 1607//1607 1604//1604 -f 1602//1602 1608//1608 1430//1430 -f 1430//1430 1608//1608 1609//1609 -f 1430//1430 1609//1609 1610//1610 -f 1610//1610 1611//1611 1430//1430 -f 1430//1430 1611//1611 1612//1612 -f 1430//1430 1612//1612 1613//1613 -f 1614//1614 1615//1615 1428//1428 -f 1614//1614 1428//1428 1616//1616 -f 1615//1615 1617//1617 1428//1428 -f 1428//1428 1617//1617 1618//1618 -f 1428//1428 1618//1618 1605//1605 -f 1613//1613 1619//1619 1430//1430 -f 1430//1430 1619//1619 1620//1620 -f 1430//1430 1620//1620 1621//1621 -f 1622//1622 1623//1623 1428//1428 -f 1428//1428 1623//1623 1624//1624 -f 1428//1428 1624//1624 1616//1616 -f 1625//1625 1626//1626 1627//1627 -f 1621//1621 1628//1628 1430//1430 -f 1430//1430 1628//1628 1629//1629 -f 1430//1430 1629//1629 1630//1630 -f 1630//1630 1629//1629 1631//1631 -f 1632//1632 1633//1633 1634//1634 -f 1634//1634 1633//1633 1635//1635 -f 1634//1634 1635//1635 1636//1636 -f 1627//1627 1637//1637 1625//1625 -f 1625//1625 1637//1637 1638//1638 -f 1625//1625 1638//1638 1631//1631 -f 1631//1631 1638//1638 1639//1639 -f 1631//1631 1639//1639 1630//1630 -f 1622//1622 1428//1428 1640//1640 -f 1640//1640 1428//1428 1641//1641 -f 1640//1640 1641//1641 1634//1634 -f 1634//1634 1641//1641 1642//1642 -f 1634//1634 1642//1642 1632//1632 -f 1643//1643 1644//1644 1645//1645 -f 1646//1646 1647//1647 1648//1648 -f 1648//1648 1649//1649 1646//1646 -f 1646//1646 1649//1649 1650//1650 -f 1646//1646 1650//1650 1651//1651 -f 1652//1652 1653//1653 1645//1645 -f 1653//1653 1654//1654 1645//1645 -f 1645//1645 1654//1654 1655//1655 -f 1645//1645 1655//1655 1643//1643 -f 1651//1651 1656//1656 1646//1646 -f 1646//1646 1656//1656 1241//1241 -f 1646//1646 1241//1241 1645//1645 -f 1645//1645 1241//1241 1239//1239 -f 1645//1645 1239//1239 1652//1652 -f 1657//1657 1658//1658 1659//1659 -f 1660//1660 1661//1661 1662//1662 -f 1662//1662 1663//1663 1660//1660 -f 1660//1660 1663//1663 1664//1664 -f 1660//1660 1664//1664 1665//1665 -f 1666//1666 1667//1667 1659//1659 -f 1667//1667 1668//1668 1659//1659 -f 1659//1659 1668//1668 1669//1669 -f 1659//1659 1669//1669 1657//1657 -f 1665//1665 1670//1670 1660//1660 -f 1660//1660 1670//1670 1354//1354 -f 1660//1660 1354//1354 1659//1659 -f 1659//1659 1354//1354 1352//1352 -f 1659//1659 1352//1352 1666//1666 -f 1671//1671 1672//1672 1673//1673 -f 1671//1671 926//926 1674//1674 -f 1674//1674 926//926 922//922 -f 1675//1675 1676//1676 1674//1674 -f 1674//1674 1676//1676 1677//1677 -f 1674//1674 1677//1677 1678//1678 -f 1673//1673 1679//1679 1671//1671 -f 1671//1671 1679//1679 1680//1680 -f 1671//1671 1680//1680 1681//1681 -f 1681//1681 1682//1682 1671//1671 -f 1671//1671 1682//1682 883//883 -f 1671//1671 883//883 926//926 -f 922//922 917//917 1674//1674 -f 1674//1674 917//917 795//795 -f 1674//1674 795//795 794//794 -f 794//794 1683//1683 1674//1674 -f 1674//1674 1683//1683 1684//1684 -f 1674//1674 1684//1684 1675//1675 -f 1685//1685 1686//1686 1687//1687 -f 1688//1688 1689//1689 1690//1690 -f 1690//1690 1691//1691 1688//1688 -f 1688//1688 1691//1691 1692//1692 -f 1688//1688 1692//1692 1693//1693 -f 1694//1694 1695//1695 1687//1687 -f 1695//1695 1696//1696 1687//1687 -f 1687//1687 1696//1696 1697//1697 -f 1687//1687 1697//1697 1685//1685 -f 1693//1693 1698//1698 1688//1688 -f 1688//1688 1698//1698 1491//1491 -f 1688//1688 1491//1491 1687//1687 -f 1687//1687 1491//1491 1489//1489 -f 1687//1687 1489//1489 1694//1694 -f 1699//1699 1700//1700 302//302 -f 1701//1701 1702//1702 1700//1700 -f 1700//1700 1702//1702 1703//1703 -f 1700//1700 1703//1703 302//302 -f 1704//1704 1705//1705 1706//1706 -f 1706//1706 1705//1705 1707//1707 -f 1706//1706 1707//1707 1701//1701 -f 1701//1701 1707//1707 1708//1708 -f 1701//1701 1708//1708 1702//1702 -f 1704//1704 1706//1706 1709//1709 -f 1709//1709 1706//1706 1710//1710 -f 1709//1709 1710//1710 1711//1711 -f 1712//1712 1713//1713 1710//1710 -f 1710//1710 1713//1713 1711//1711 -f 1714//1714 1715//1715 1716//1716 -f 1716//1716 1715//1715 1717//1717 -f 1716//1716 1717//1717 1712//1712 -f 1712//1712 1717//1717 1718//1718 -f 1712//1712 1718//1718 1713//1713 -f 1714//1714 1716//1716 1719//1719 -f 1719//1719 1716//1716 1720//1720 -f 1719//1719 1720//1720 1721//1721 -f 1722//1722 1723//1723 1724//1724 -f 1722//1722 1724//1724 1720//1720 -f 1720//1720 1724//1724 1725//1725 -f 1720//1720 1725//1725 1721//1721 -f 1723//1723 1722//1722 1726//1726 -f 1726//1726 1722//1722 1727//1727 -f 1726//1726 1727//1727 1728//1728 -f 1729//1729 1730//1730 1731//1731 -f 1729//1729 1731//1731 1727//1727 -f 1727//1727 1731//1731 1732//1732 -f 1727//1727 1732//1732 1728//1728 -f 1730//1730 1729//1729 1733//1733 -f 1733//1733 1729//1729 1734//1734 -f 1733//1733 1734//1734 1735//1735 -f 1736//1736 1737//1737 1738//1738 -f 1736//1736 1738//1738 1734//1734 -f 1734//1734 1738//1738 1739//1739 -f 1734//1734 1739//1739 1735//1735 -f 1737//1737 1736//1736 1740//1740 -f 1740//1740 1736//1736 1741//1741 -f 1740//1740 1741//1741 1742//1742 -f 1742//1742 1741//1741 1743//1743 -f 1743//1743 1741//1741 1744//1744 -f 1743//1743 1744//1744 1745//1745 -f 1745//1745 1744//1744 1746//1746 -f 1746//1746 1744//1744 1747//1747 -f 1746//1746 1747//1747 1748//1748 -f 1748//1748 1747//1747 1749//1749 -f 1749//1749 1747//1747 1750//1750 -f 1749//1749 1750//1750 1751//1751 -f 1751//1751 1750//1750 1752//1752 -f 1752//1752 1750//1750 1753//1753 -f 1752//1752 1753//1753 1754//1754 -f 1755//1755 1756//1756 1757//1757 -f 1757//1757 1756//1756 1758//1758 -f 1757//1757 1758//1758 1753//1753 -f 1753//1753 1758//1758 1759//1759 -f 1753//1753 1759//1759 1754//1754 -f 1755//1755 1757//1757 263//263 -f 263//263 1757//1757 1760//1760 -f 263//263 1760//1760 264//264 -f 264//264 1760//1760 265//265 -f 265//265 1760//1760 1761//1761 -f 265//265 1761//1761 266//266 -f 266//266 1761//1761 267//267 -f 267//267 1761//1761 1762//1762 -f 267//267 1762//1762 268//268 -f 268//268 1762//1762 1763//1763 -f 268//268 1763//1763 270//270 -f 270//270 1763//1763 1764//1764 -f 270//270 1764//1764 271//271 -f 271//271 1764//1764 1765//1765 -f 271//271 1765//1765 275//275 -f 275//275 1765//1765 280//280 -f 280//280 1765//1765 1766//1766 -f 280//280 1766//1766 277//277 -f 277//277 1766//1766 1767//1767 -f 277//277 1767//1767 278//278 -f 278//278 1767//1767 1768//1768 -f 278//278 1768//1768 285//285 -f 285//285 1768//1768 1769//1769 -f 285//285 1769//1769 283//283 -f 283//283 1769//1769 1770//1770 -f 283//283 1770//1770 281//281 -f 281//281 1770//1770 1771//1771 -f 281//281 1771//1771 288//288 -f 288//288 1771//1771 1772//1772 -f 288//288 1772//1772 289//289 -f 289//289 1772//1772 1773//1773 -f 289//289 1773//1773 290//290 -f 1774//1774 295//295 1773//1773 -f 1773//1773 295//295 294//294 -f 1773//1773 294//294 290//290 -f 1775//1775 1776//1776 299//299 -f 299//299 298//298 1775//1775 -f 1775//1775 298//298 297//297 -f 1775//1775 297//297 1774//1774 -f 1774//1774 297//297 296//296 -f 1774//1774 296//296 295//295 -f 302//302 301//301 1699//1699 -f 1699//1699 301//301 300//300 -f 1699//1699 300//300 1777//1777 -f 1777//1777 300//300 292//292 -f 1777//1777 292//292 1776//1776 -f 1776//1776 292//292 291//291 -f 1776//1776 291//291 299//299 -f 1778//1778 1779//1779 1780//1780 -f 1781//1781 1782//1782 1783//1783 -f 1784//1784 1785//1785 1786//1786 -f 1787//1787 1788//1788 546//546 -f 1789//1789 1790//1790 1788//1788 -f 1788//1788 1790//1790 1791//1791 -f 1791//1791 1792//1792 1788//1788 -f 1788//1788 1792//1792 1793//1793 -f 1788//1788 1793//1793 546//546 -f 1794//1794 1795//1795 1789//1789 -f 1789//1789 1795//1795 1796//1796 -f 1789//1789 1796//1796 1790//1790 -f 1797//1797 1798//1798 1794//1794 -f 1794//1794 1798//1798 1799//1799 -f 1794//1794 1799//1799 1795//1795 -f 1800//1800 1801//1801 1797//1797 -f 1797//1797 1801//1801 1802//1802 -f 1797//1797 1802//1802 1803//1803 -f 1803//1803 1804//1804 1797//1797 -f 1797//1797 1804//1804 1805//1805 -f 1797//1797 1805//1805 1798//1798 -f 1786//1786 1785//1785 1806//1806 -f 1785//1785 1807//1807 1806//1806 -f 1806//1806 1807//1807 1808//1808 -f 1806//1806 1808//1808 1800//1800 -f 1800//1800 1808//1808 1809//1809 -f 1800//1800 1809//1809 1801//1801 -f 1810//1810 1811//1811 1786//1786 -f 1786//1786 1811//1811 1812//1812 -f 1786//1786 1812//1812 1784//1784 -f 1813//1813 1814//1814 1815//1815 -f 1815//1815 1814//1814 1816//1816 -f 1815//1815 1816//1816 1817//1817 -f 1813//1813 1818//1818 1814//1814 -f 1814//1814 1818//1818 1819//1819 -f 1814//1814 1819//1819 1810//1810 -f 1810//1810 1819//1819 1820//1820 -f 1810//1810 1820//1820 1811//1811 -f 1821//1821 1822//1822 1823//1823 -f 1823//1823 1822//1822 1824//1824 -f 1823//1823 1824//1824 1825//1825 -f 1821//1821 1826//1826 1822//1822 -f 1822//1822 1826//1826 1827//1827 -f 1822//1822 1827//1827 1816//1816 -f 1816//1816 1827//1827 1828//1828 -f 1816//1816 1828//1828 1817//1817 -f 1783//1783 1782//1782 1829//1829 -f 1782//1782 1830//1830 1829//1829 -f 1829//1829 1830//1830 1831//1831 -f 1829//1829 1831//1831 1824//1824 -f 1824//1824 1831//1831 1832//1832 -f 1824//1824 1832//1832 1825//1825 -f 1780//1780 1779//1779 1833//1833 -f 1779//1779 1834//1834 1833//1833 -f 1833//1833 1834//1834 1835//1835 -f 1833//1833 1835//1835 1783//1783 -f 1783//1783 1835//1835 1836//1836 -f 1783//1783 1836//1836 1781//1781 -f 1778//1778 1780//1780 1837//1837 -f 1837//1837 1780//1780 1838//1838 -f 1837//1837 1838//1838 1839//1839 -f 1839//1839 1838//1838 1840//1840 -f 1840//1840 1838//1838 1841//1841 -f 1840//1840 1841//1841 1842//1842 -f 1843//1843 500//500 1841//1841 -f 1841//1841 500//500 499//499 -f 1841//1841 499//499 1842//1842 -f 1844//1844 504//504 1845//1845 -f 1845//1845 504//504 503//503 -f 1845//1845 503//503 1843//1843 -f 1843//1843 503//503 502//502 -f 1843//1843 502//502 500//500 -f 1846//1846 506//506 1844//1844 -f 1844//1844 506//506 505//505 -f 1844//1844 505//505 504//504 -f 1847//1847 508//508 1846//1846 -f 1846//1846 508//508 507//507 -f 1846//1846 507//507 506//506 -f 1848//1848 511//511 1849//1849 -f 1849//1849 511//511 510//510 -f 1849//1849 510//510 1847//1847 -f 1847//1847 510//510 509//509 -f 1847//1847 509//509 508//508 -f 1850//1850 531//531 1851//1851 -f 1851//1851 531//531 519//519 -f 1851//1851 519//519 1852//1852 -f 1852//1852 519//519 522//522 -f 1852//1852 522//522 1853//1853 -f 1853//1853 522//522 529//529 -f 1853//1853 529//529 1854//1854 -f 1854//1854 529//529 528//528 -f 1854//1854 528//528 1855//1855 -f 1855//1855 528//528 526//526 -f 1855//1855 526//526 1856//1856 -f 1856//1856 526//526 524//524 -f 1856//1856 524//524 1857//1857 -f 1857//1857 524//524 523//523 -f 1857//1857 523//523 1858//1858 -f 1858//1858 523//523 516//516 -f 1858//1858 516//516 1859//1859 -f 1859//1859 516//516 515//515 -f 1859//1859 515//515 1848//1848 -f 1848//1848 515//515 512//512 -f 1848//1848 512//512 511//511 -f 1860//1860 535//535 1850//1850 -f 1850//1850 535//535 532//532 -f 1850//1850 532//532 531//531 -f 546//546 534//534 1787//1787 -f 1787//1787 534//534 533//533 -f 1787//1787 533//533 1860//1860 -f 1860//1860 533//533 536//536 -f 1860//1860 536//536 535//535 -f 1861//1861 1862//1862 1863//1863 -f 1863//1863 1862//1862 1864//1864 -f 1863//1863 1864//1864 1865//1865 -f 1865//1865 1864//1864 1866//1866 -f 1865//1865 1866//1866 1867//1867 -f 1867//1867 1866//1866 1868//1868 -f 1867//1867 1868//1868 1869//1869 -f 1869//1869 1868//1868 1870//1870 -f 1869//1869 1870//1870 1871//1871 -f 1871//1871 1870//1870 1872//1872 -f 1871//1871 1872//1872 1873//1873 -f 1873//1873 1872//1872 1874//1874 -f 1873//1873 1874//1874 1875//1875 -f 1875//1875 1874//1874 1876//1876 -f 1875//1875 1876//1876 1877//1877 -f 1877//1877 1876//1876 1878//1878 -f 1877//1877 1878//1878 1879//1879 -f 1879//1879 1878//1878 1880//1880 -f 1879//1879 1880//1880 1881//1881 -f 1881//1881 1880//1880 1882//1882 -f 1881//1881 1882//1882 1883//1883 -f 1883//1883 1882//1882 1884//1884 -f 1883//1883 1884//1884 1885//1885 -f 1885//1885 1884//1884 1886//1886 -f 1885//1885 1886//1886 1887//1887 -f 1887//1887 1886//1886 1888//1888 -f 1887//1887 1888//1888 1889//1889 -f 1889//1889 1888//1888 1890//1890 -f 1889//1889 1890//1890 1891//1891 -f 1891//1891 1890//1890 1892//1892 -f 1891//1891 1892//1892 1893//1893 -f 1893//1893 1892//1892 1894//1894 -f 1893//1893 1894//1894 1895//1895 -f 1895//1895 1894//1894 1896//1896 -f 1895//1895 1896//1896 1897//1897 -f 1897//1897 1896//1896 1898//1898 -f 1897//1897 1898//1898 1899//1899 -f 1899//1899 1898//1898 1900//1900 -f 1899//1899 1900//1900 1901//1901 -f 1901//1901 1900//1900 1902//1902 -f 1901//1901 1902//1902 1903//1903 -f 1903//1903 1902//1902 1904//1904 -f 1903//1903 1904//1904 1905//1905 -f 1905//1905 1904//1904 1906//1906 -f 1905//1905 1906//1906 1907//1907 -f 1907//1907 1906//1906 1908//1908 -f 1907//1907 1908//1908 1909//1909 -f 1909//1909 1908//1908 1910//1910 -f 1909//1909 1910//1910 1911//1911 -f 1911//1911 1910//1910 1912//1912 -f 1911//1911 1912//1912 1913//1913 -f 1913//1913 1912//1912 1914//1914 -f 1913//1913 1914//1914 1915//1915 -f 1915//1915 1914//1914 1916//1916 -f 1915//1915 1916//1916 1917//1917 -f 1917//1917 1916//1916 1918//1918 -f 1917//1917 1918//1918 1919//1919 -f 1919//1919 1918//1918 1920//1920 -f 1919//1919 1920//1920 1921//1921 -f 1921//1921 1920//1920 1922//1922 -f 1921//1921 1922//1922 1923//1923 -f 1923//1923 1922//1922 1924//1924 -f 1923//1923 1924//1924 1925//1925 -f 1925//1925 1924//1924 1926//1926 -f 1925//1925 1926//1926 1927//1927 -f 1927//1927 1926//1926 1928//1928 -f 1927//1927 1928//1928 1929//1929 -f 1929//1929 1928//1928 1930//1930 -f 1929//1929 1930//1930 1931//1931 -f 1931//1931 1930//1930 1932//1932 -f 1931//1931 1932//1932 1933//1933 -f 1933//1933 1932//1932 1934//1934 -f 1933//1933 1934//1934 1861//1861 -f 1861//1861 1934//1934 1862//1862 -f 1935//1935 1919//1919 1936//1936 -f 1936//1936 1919//1919 1921//1921 -f 1936//1936 1921//1921 1937//1937 -f 1937//1937 1921//1921 1923//1923 -f 1937//1937 1923//1923 1938//1938 -f 1938//1938 1923//1923 1925//1925 -f 1938//1938 1925//1925 1939//1939 -f 1939//1939 1925//1925 1927//1927 -f 1939//1939 1927//1927 1940//1940 -f 1940//1940 1927//1927 1929//1929 -f 1940//1940 1929//1929 1941//1941 -f 1941//1941 1929//1929 1931//1931 -f 1941//1941 1931//1931 1942//1942 -f 1942//1942 1931//1931 1933//1933 -f 1942//1942 1933//1933 1943//1943 -f 1943//1943 1933//1933 1861//1861 -f 1943//1943 1861//1861 1944//1944 -f 1944//1944 1861//1861 1863//1863 -f 1944//1944 1863//1863 1945//1945 -f 1945//1945 1863//1863 1865//1865 -f 1945//1945 1865//1865 1946//1946 -f 1946//1946 1865//1865 1867//1867 -f 1946//1946 1867//1867 1947//1947 -f 1947//1947 1867//1867 1869//1869 -f 1947//1947 1869//1869 1948//1948 -f 1948//1948 1869//1869 1871//1871 -f 1948//1948 1871//1871 1949//1949 -f 1949//1949 1871//1871 1873//1873 -f 1949//1949 1873//1873 1950//1950 -f 1950//1950 1873//1873 1875//1875 -f 1950//1950 1875//1875 1951//1951 -f 1951//1951 1875//1875 1877//1877 -f 1951//1951 1877//1877 1952//1952 -f 1952//1952 1877//1877 1879//1879 -f 1952//1952 1879//1879 1953//1953 -f 1953//1953 1879//1879 1881//1881 -f 1953//1953 1881//1881 1954//1954 -f 1954//1954 1881//1881 1883//1883 -f 1954//1954 1883//1883 1955//1955 -f 1955//1955 1883//1883 1885//1885 -f 1955//1955 1885//1885 1956//1956 -f 1956//1956 1885//1885 1887//1887 -f 1956//1956 1887//1887 1957//1957 -f 1957//1957 1887//1887 1889//1889 -f 1957//1957 1889//1889 1958//1958 -f 1958//1958 1889//1889 1891//1891 -f 1958//1958 1891//1891 1959//1959 -f 1959//1959 1891//1891 1893//1893 -f 1959//1959 1893//1893 1960//1960 -f 1960//1960 1893//1893 1895//1895 -f 1960//1960 1895//1895 1961//1961 -f 1961//1961 1895//1895 1897//1897 -f 1961//1961 1897//1897 1962//1962 -f 1962//1962 1897//1897 1899//1899 -f 1962//1962 1899//1899 1963//1963 -f 1963//1963 1899//1899 1901//1901 -f 1963//1963 1901//1901 1964//1964 -f 1964//1964 1901//1901 1903//1903 -f 1964//1964 1903//1903 1965//1965 -f 1965//1965 1903//1903 1905//1905 -f 1965//1965 1905//1905 1966//1966 -f 1966//1966 1905//1905 1907//1907 -f 1966//1966 1907//1907 1967//1967 -f 1967//1967 1907//1907 1909//1909 -f 1967//1967 1909//1909 1968//1968 -f 1968//1968 1909//1909 1911//1911 -f 1968//1968 1911//1911 1969//1969 -f 1969//1969 1911//1911 1913//1913 -f 1969//1969 1913//1913 1970//1970 -f 1970//1970 1913//1913 1915//1915 -f 1970//1970 1915//1915 1971//1971 -f 1971//1971 1915//1915 1917//1917 -f 1971//1971 1917//1917 1935//1935 -f 1935//1935 1917//1917 1919//1919 -f 1972//1972 1973//1973 1974//1974 -f 1974//1974 1973//1973 1975//1975 -f 1974//1974 1975//1975 1976//1976 -f 1976//1976 1975//1975 1977//1977 -f 1976//1976 1977//1977 1978//1978 -f 1978//1978 1977//1977 1979//1979 -f 1978//1978 1979//1979 1980//1980 -f 1980//1980 1979//1979 1981//1981 -f 1980//1980 1981//1981 1982//1982 -f 1982//1982 1981//1981 1983//1983 -f 1982//1982 1983//1983 1984//1984 -f 1984//1984 1983//1983 1985//1985 -f 1984//1984 1985//1985 1986//1986 -f 1986//1986 1985//1985 1987//1987 -f 1986//1986 1987//1987 1988//1988 -f 1988//1988 1987//1987 1989//1989 -f 1988//1988 1989//1989 1990//1990 -f 1990//1990 1989//1989 1991//1991 -f 1990//1990 1991//1991 1992//1992 -f 1992//1992 1991//1991 1993//1993 -f 1992//1992 1993//1993 1994//1994 -f 1994//1994 1993//1993 1995//1995 -f 1994//1994 1995//1995 1996//1996 -f 1996//1996 1995//1995 1997//1997 -f 1996//1996 1997//1997 1998//1998 -f 1998//1998 1997//1997 1999//1999 -f 1998//1998 1999//1999 2000//2000 -f 2000//2000 1999//1999 2001//2001 -f 2000//2000 2001//2001 2002//2002 -f 2002//2002 2001//2001 2003//2003 -f 2002//2002 2003//2003 2004//2004 -f 2004//2004 2003//2003 2005//2005 -f 2004//2004 2005//2005 2006//2006 -f 2006//2006 2005//2005 2007//2007 -f 2006//2006 2007//2007 2008//2008 -f 2008//2008 2007//2007 2009//2009 -f 2008//2008 2009//2009 2010//2010 -f 2010//2010 2009//2009 2011//2011 -f 2010//2010 2011//2011 2012//2012 -f 2012//2012 2011//2011 2013//2013 -f 2012//2012 2013//2013 2014//2014 -f 2014//2014 2013//2013 2015//2015 -f 2014//2014 2015//2015 2016//2016 -f 2016//2016 2015//2015 2017//2017 -f 2016//2016 2017//2017 2018//2018 -f 2018//2018 2017//2017 2019//2019 -f 2018//2018 2019//2019 2020//2020 -f 2020//2020 2019//2019 2021//2021 -f 2020//2020 2021//2021 2022//2022 -f 2022//2022 2021//2021 2023//2023 -f 2022//2022 2023//2023 2024//2024 -f 2024//2024 2023//2023 2025//2025 -f 2024//2024 2025//2025 2026//2026 -f 2026//2026 2025//2025 2027//2027 -f 2026//2026 2027//2027 2028//2028 -f 2028//2028 2027//2027 2029//2029 -f 2028//2028 2029//2029 2030//2030 -f 2030//2030 2029//2029 2031//2031 -f 2030//2030 2031//2031 2032//2032 -f 2032//2032 2031//2031 2033//2033 -f 2032//2032 2033//2033 2034//2034 -f 2034//2034 2033//2033 2035//2035 -f 2034//2034 2035//2035 2036//2036 -f 2036//2036 2035//2035 2037//2037 -f 2036//2036 2037//2037 2038//2038 -f 2038//2038 2037//2037 2039//2039 -f 2038//2038 2039//2039 2040//2040 -f 2040//2040 2039//2039 2041//2041 -f 2040//2040 2041//2041 2042//2042 -f 2042//2042 2041//2041 2043//2043 -f 2042//2042 2043//2043 2044//2044 -f 2044//2044 2043//2043 2045//2045 -f 2044//2044 2045//2045 1972//1972 -f 1972//1972 2045//2045 1973//1973 -f 2046//2046 2030//2030 2047//2047 -f 2047//2047 2030//2030 2032//2032 -f 2047//2047 2032//2032 2048//2048 -f 2048//2048 2032//2032 2034//2034 -f 2048//2048 2034//2034 2049//2049 -f 2049//2049 2034//2034 2036//2036 -f 2049//2049 2036//2036 2050//2050 -f 2050//2050 2036//2036 2038//2038 -f 2050//2050 2038//2038 2051//2051 -f 2051//2051 2038//2038 2040//2040 -f 2051//2051 2040//2040 2052//2052 -f 2052//2052 2040//2040 2042//2042 -f 2052//2052 2042//2042 2053//2053 -f 2053//2053 2042//2042 2044//2044 -f 2053//2053 2044//2044 2054//2054 -f 2054//2054 2044//2044 1972//1972 -f 2054//2054 1972//1972 2055//2055 -f 2055//2055 1972//1972 1974//1974 -f 2055//2055 1974//1974 2056//2056 -f 2056//2056 1974//1974 1976//1976 -f 2056//2056 1976//1976 2057//2057 -f 2057//2057 1976//1976 1978//1978 -f 2057//2057 1978//1978 2058//2058 -f 2058//2058 1978//1978 1980//1980 -f 2058//2058 1980//1980 2059//2059 -f 2059//2059 1980//1980 1982//1982 -f 2059//2059 1982//1982 2060//2060 -f 2060//2060 1982//1982 1984//1984 -f 2060//2060 1984//1984 2061//2061 -f 2061//2061 1984//1984 1986//1986 -f 2061//2061 1986//1986 2062//2062 -f 2062//2062 1986//1986 1988//1988 -f 2062//2062 1988//1988 2063//2063 -f 2063//2063 1988//1988 1990//1990 -f 2063//2063 1990//1990 2064//2064 -f 2064//2064 1990//1990 1992//1992 -f 2064//2064 1992//1992 2065//2065 -f 2065//2065 1992//1992 1994//1994 -f 2065//2065 1994//1994 2066//2066 -f 2066//2066 1994//1994 1996//1996 -f 2066//2066 1996//1996 2067//2067 -f 2067//2067 1996//1996 1998//1998 -f 2067//2067 1998//1998 2068//2068 -f 2068//2068 1998//1998 2000//2000 -f 2068//2068 2000//2000 2069//2069 -f 2069//2069 2000//2000 2002//2002 -f 2069//2069 2002//2002 2070//2070 -f 2070//2070 2002//2002 2004//2004 -f 2070//2070 2004//2004 2071//2071 -f 2071//2071 2004//2004 2006//2006 -f 2071//2071 2006//2006 2072//2072 -f 2072//2072 2006//2006 2008//2008 -f 2072//2072 2008//2008 2073//2073 -f 2073//2073 2008//2008 2010//2010 -f 2073//2073 2010//2010 2074//2074 -f 2074//2074 2010//2010 2012//2012 -f 2074//2074 2012//2012 2075//2075 -f 2075//2075 2012//2012 2014//2014 -f 2075//2075 2014//2014 2076//2076 -f 2076//2076 2014//2014 2016//2016 -f 2076//2076 2016//2016 2077//2077 -f 2077//2077 2016//2016 2018//2018 -f 2077//2077 2018//2018 2078//2078 -f 2078//2078 2018//2018 2020//2020 -f 2078//2078 2020//2020 2079//2079 -f 2079//2079 2020//2020 2022//2022 -f 2079//2079 2022//2022 2080//2080 -f 2080//2080 2022//2022 2024//2024 -f 2080//2080 2024//2024 2081//2081 -f 2081//2081 2024//2024 2026//2026 -f 2081//2081 2026//2026 2082//2082 -f 2082//2082 2026//2026 2028//2028 -f 2082//2082 2028//2028 2046//2046 -f 2046//2046 2028//2028 2030//2030 -f 2083//2083 2084//2084 2085//2085 -f 2085//2085 2084//2084 2086//2086 -f 2085//2085 2086//2086 2087//2087 -f 2087//2087 2086//2086 2088//2088 -f 2087//2087 2088//2088 2089//2089 -f 2089//2089 2088//2088 2090//2090 -f 2089//2089 2090//2090 2091//2091 -f 2091//2091 2090//2090 2092//2092 -f 2091//2091 2092//2092 2093//2093 -f 2093//2093 2092//2092 2094//2094 -f 2093//2093 2094//2094 2095//2095 -f 2095//2095 2094//2094 2096//2096 -f 2095//2095 2096//2096 2097//2097 -f 2097//2097 2096//2096 2098//2098 -f 2097//2097 2098//2098 2099//2099 -f 2099//2099 2098//2098 2100//2100 -f 2099//2099 2100//2100 2101//2101 -f 2101//2101 2100//2100 2102//2102 -f 2101//2101 2102//2102 2103//2103 -f 2103//2103 2102//2102 2104//2104 -f 2103//2103 2104//2104 2105//2105 -f 2105//2105 2104//2104 2106//2106 -f 2105//2105 2106//2106 2107//2107 -f 2107//2107 2106//2106 2108//2108 -f 2107//2107 2108//2108 2109//2109 -f 2109//2109 2108//2108 2110//2110 -f 2109//2109 2110//2110 2111//2111 -f 2111//2111 2110//2110 2112//2112 -f 2111//2111 2112//2112 2113//2113 -f 2113//2113 2112//2112 2114//2114 -f 2113//2113 2114//2114 2115//2115 -f 2115//2115 2114//2114 2116//2116 -f 2115//2115 2116//2116 2117//2117 -f 2117//2117 2116//2116 2118//2118 -f 2117//2117 2118//2118 2119//2119 -f 2119//2119 2118//2118 2120//2120 -f 2119//2119 2120//2120 2121//2121 -f 2121//2121 2120//2120 2122//2122 -f 2121//2121 2122//2122 2123//2123 -f 2123//2123 2122//2122 2124//2124 -f 2123//2123 2124//2124 2125//2125 -f 2125//2125 2124//2124 2126//2126 -f 2125//2125 2126//2126 2127//2127 -f 2127//2127 2126//2126 2128//2128 -f 2127//2127 2128//2128 2129//2129 -f 2129//2129 2128//2128 2130//2130 -f 2129//2129 2130//2130 2131//2131 -f 2131//2131 2130//2130 2132//2132 -f 2131//2131 2132//2132 2133//2133 -f 2133//2133 2132//2132 2134//2134 -f 2133//2133 2134//2134 2135//2135 -f 2135//2135 2134//2134 2136//2136 -f 2135//2135 2136//2136 2137//2137 -f 2137//2137 2136//2136 2138//2138 -f 2137//2137 2138//2138 2139//2139 -f 2139//2139 2138//2138 2140//2140 -f 2139//2139 2140//2140 2141//2141 -f 2141//2141 2140//2140 2142//2142 -f 2141//2141 2142//2142 2143//2143 -f 2143//2143 2142//2142 2144//2144 -f 2143//2143 2144//2144 2145//2145 -f 2145//2145 2144//2144 2146//2146 -f 2145//2145 2146//2146 2147//2147 -f 2147//2147 2146//2146 2148//2148 -f 2147//2147 2148//2148 2149//2149 -f 2149//2149 2148//2148 2150//2150 -f 2149//2149 2150//2150 2151//2151 -f 2151//2151 2150//2150 2152//2152 -f 2151//2151 2152//2152 2153//2153 -f 2153//2153 2152//2152 2154//2154 -f 2153//2153 2154//2154 2155//2155 -f 2155//2155 2154//2154 2156//2156 -f 2155//2155 2156//2156 2083//2083 -f 2083//2083 2156//2156 2084//2084 -f 2157//2157 2123//2123 2158//2158 -f 2158//2158 2123//2123 2125//2125 -f 2158//2158 2125//2125 2159//2159 -f 2159//2159 2125//2125 2127//2127 -f 2159//2159 2127//2127 2160//2160 -f 2160//2160 2127//2127 2129//2129 -f 2160//2160 2129//2129 2161//2161 -f 2161//2161 2129//2129 2131//2131 -f 2161//2161 2131//2131 2162//2162 -f 2162//2162 2131//2131 2133//2133 -f 2162//2162 2133//2133 2163//2163 -f 2163//2163 2133//2133 2135//2135 -f 2163//2163 2135//2135 2164//2164 -f 2164//2164 2135//2135 2137//2137 -f 2164//2164 2137//2137 2165//2165 -f 2165//2165 2137//2137 2139//2139 -f 2165//2165 2139//2139 2166//2166 -f 2166//2166 2139//2139 2141//2141 -f 2166//2166 2141//2141 2167//2167 -f 2167//2167 2141//2141 2143//2143 -f 2167//2167 2143//2143 2168//2168 -f 2168//2168 2143//2143 2145//2145 -f 2168//2168 2145//2145 2169//2169 -f 2169//2169 2145//2145 2147//2147 -f 2169//2169 2147//2147 2170//2170 -f 2170//2170 2147//2147 2149//2149 -f 2170//2170 2149//2149 2171//2171 -f 2171//2171 2149//2149 2151//2151 -f 2171//2171 2151//2151 2172//2172 -f 2172//2172 2151//2151 2153//2153 -f 2172//2172 2153//2153 2173//2173 -f 2173//2173 2153//2153 2155//2155 -f 2173//2173 2155//2155 2174//2174 -f 2174//2174 2155//2155 2083//2083 -f 2174//2174 2083//2083 2175//2175 -f 2175//2175 2083//2083 2085//2085 -f 2175//2175 2085//2085 2176//2176 -f 2176//2176 2085//2085 2087//2087 -f 2176//2176 2087//2087 2177//2177 -f 2177//2177 2087//2087 2089//2089 -f 2177//2177 2089//2089 2178//2178 -f 2178//2178 2089//2089 2091//2091 -f 2178//2178 2091//2091 2179//2179 -f 2179//2179 2091//2091 2093//2093 -f 2179//2179 2093//2093 2180//2180 -f 2180//2180 2093//2093 2095//2095 -f 2180//2180 2095//2095 2181//2181 -f 2181//2181 2095//2095 2097//2097 -f 2181//2181 2097//2097 2182//2182 -f 2182//2182 2097//2097 2099//2099 -f 2182//2182 2099//2099 2183//2183 -f 2183//2183 2099//2099 2101//2101 -f 2183//2183 2101//2101 2184//2184 -f 2184//2184 2101//2101 2103//2103 -f 2184//2184 2103//2103 2185//2185 -f 2185//2185 2103//2103 2105//2105 -f 2185//2185 2105//2105 2186//2186 -f 2186//2186 2105//2105 2107//2107 -f 2186//2186 2107//2107 2187//2187 -f 2187//2187 2107//2107 2109//2109 -f 2187//2187 2109//2109 2188//2188 -f 2188//2188 2109//2109 2111//2111 -f 2188//2188 2111//2111 2189//2189 -f 2189//2189 2111//2111 2113//2113 -f 2189//2189 2113//2113 2190//2190 -f 2190//2190 2113//2113 2115//2115 -f 2190//2190 2115//2115 2191//2191 -f 2191//2191 2115//2115 2117//2117 -f 2191//2191 2117//2117 2192//2192 -f 2192//2192 2117//2117 2119//2119 -f 2192//2192 2119//2119 2193//2193 -f 2193//2193 2119//2119 2121//2121 -f 2193//2193 2121//2121 2157//2157 -f 2157//2157 2121//2121 2123//2123 -f 2194//2194 2195//2195 2196//2196 -f 2196//2196 2195//2195 2197//2197 -f 2196//2196 2197//2197 2198//2198 -f 2198//2198 2197//2197 2199//2199 -f 2198//2198 2199//2199 2200//2200 -f 2200//2200 2199//2199 2201//2201 -f 2200//2200 2201//2201 2202//2202 -f 2202//2202 2201//2201 2203//2203 -f 2202//2202 2203//2203 2204//2204 -f 2204//2204 2203//2203 2205//2205 -f 2204//2204 2205//2205 2206//2206 -f 2206//2206 2205//2205 2207//2207 -f 2206//2206 2207//2207 2208//2208 -f 2208//2208 2207//2207 2209//2209 -f 2208//2208 2209//2209 2210//2210 -f 2210//2210 2209//2209 2211//2211 -f 2210//2210 2211//2211 2212//2212 -f 2212//2212 2211//2211 2213//2213 -f 2212//2212 2213//2213 2214//2214 -f 2214//2214 2213//2213 2215//2215 -f 2214//2214 2215//2215 2216//2216 -f 2216//2216 2215//2215 2217//2217 -f 2216//2216 2217//2217 2218//2218 -f 2218//2218 2217//2217 2219//2219 -f 2218//2218 2219//2219 2220//2220 -f 2220//2220 2219//2219 2221//2221 -f 2220//2220 2221//2221 2222//2222 -f 2222//2222 2221//2221 2223//2223 -f 2222//2222 2223//2223 2224//2224 -f 2224//2224 2223//2223 2225//2225 -f 2224//2224 2225//2225 2226//2226 -f 2226//2226 2225//2225 2227//2227 -f 2226//2226 2227//2227 2228//2228 -f 2228//2228 2227//2227 2229//2229 -f 2228//2228 2229//2229 2230//2230 -f 2230//2230 2229//2229 2231//2231 -f 2230//2230 2231//2231 2232//2232 -f 2232//2232 2231//2231 2233//2233 -f 2232//2232 2233//2233 2234//2234 -f 2234//2234 2233//2233 2235//2235 -f 2234//2234 2235//2235 2236//2236 -f 2236//2236 2235//2235 2237//2237 -f 2236//2236 2237//2237 2238//2238 -f 2238//2238 2237//2237 2239//2239 -f 2238//2238 2239//2239 2240//2240 -f 2240//2240 2239//2239 2241//2241 -f 2240//2240 2241//2241 2242//2242 -f 2242//2242 2241//2241 2243//2243 -f 2242//2242 2243//2243 2244//2244 -f 2244//2244 2243//2243 2245//2245 -f 2244//2244 2245//2245 2246//2246 -f 2246//2246 2245//2245 2247//2247 -f 2246//2246 2247//2247 2248//2248 -f 2248//2248 2247//2247 2249//2249 -f 2248//2248 2249//2249 2250//2250 -f 2250//2250 2249//2249 2251//2251 -f 2250//2250 2251//2251 2252//2252 -f 2252//2252 2251//2251 2253//2253 -f 2252//2252 2253//2253 2254//2254 -f 2254//2254 2253//2253 2255//2255 -f 2254//2254 2255//2255 2256//2256 -f 2256//2256 2255//2255 2257//2257 -f 2256//2256 2257//2257 2258//2258 -f 2258//2258 2257//2257 2259//2259 -f 2258//2258 2259//2259 2260//2260 -f 2260//2260 2259//2259 2261//2261 -f 2260//2260 2261//2261 2262//2262 -f 2262//2262 2261//2261 2263//2263 -f 2262//2262 2263//2263 2264//2264 -f 2264//2264 2263//2263 2265//2265 -f 2264//2264 2265//2265 2266//2266 -f 2266//2266 2265//2265 2267//2267 -f 2266//2266 2267//2267 2194//2194 -f 2194//2194 2267//2267 2195//2195 -f 2268//2268 2262//2262 2269//2269 -f 2269//2269 2262//2262 2264//2264 -f 2269//2269 2264//2264 2270//2270 -f 2270//2270 2264//2264 2266//2266 -f 2270//2270 2266//2266 2271//2271 -f 2271//2271 2266//2266 2194//2194 -f 2271//2271 2194//2194 2272//2272 -f 2272//2272 2194//2194 2196//2196 -f 2272//2272 2196//2196 2273//2273 -f 2273//2273 2196//2196 2198//2198 -f 2273//2273 2198//2198 2274//2274 -f 2274//2274 2198//2198 2200//2200 -f 2274//2274 2200//2200 2275//2275 -f 2275//2275 2200//2200 2202//2202 -f 2275//2275 2202//2202 2276//2276 -f 2276//2276 2202//2202 2204//2204 -f 2276//2276 2204//2204 2277//2277 -f 2277//2277 2204//2204 2206//2206 -f 2277//2277 2206//2206 2278//2278 -f 2278//2278 2206//2206 2208//2208 -f 2278//2278 2208//2208 2279//2279 -f 2279//2279 2208//2208 2210//2210 -f 2279//2279 2210//2210 2280//2280 -f 2280//2280 2210//2210 2212//2212 -f 2280//2280 2212//2212 2281//2281 -f 2281//2281 2212//2212 2214//2214 -f 2281//2281 2214//2214 2282//2282 -f 2282//2282 2214//2214 2216//2216 -f 2282//2282 2216//2216 2283//2283 -f 2283//2283 2216//2216 2218//2218 -f 2283//2283 2218//2218 2284//2284 -f 2284//2284 2218//2218 2220//2220 -f 2284//2284 2220//2220 2285//2285 -f 2285//2285 2220//2220 2222//2222 -f 2285//2285 2222//2222 2286//2286 -f 2286//2286 2222//2222 2224//2224 -f 2286//2286 2224//2224 2287//2287 -f 2287//2287 2224//2224 2226//2226 -f 2287//2287 2226//2226 2288//2288 -f 2288//2288 2226//2226 2228//2228 -f 2288//2288 2228//2228 2289//2289 -f 2289//2289 2228//2228 2230//2230 -f 2289//2289 2230//2230 2290//2290 -f 2290//2290 2230//2230 2232//2232 -f 2290//2290 2232//2232 2291//2291 -f 2291//2291 2232//2232 2234//2234 -f 2291//2291 2234//2234 2292//2292 -f 2292//2292 2234//2234 2236//2236 -f 2292//2292 2236//2236 2293//2293 -f 2293//2293 2236//2236 2238//2238 -f 2293//2293 2238//2238 2294//2294 -f 2294//2294 2238//2238 2240//2240 -f 2294//2294 2240//2240 2295//2295 -f 2295//2295 2240//2240 2242//2242 -f 2295//2295 2242//2242 2296//2296 -f 2296//2296 2242//2242 2244//2244 -f 2296//2296 2244//2244 2297//2297 -f 2297//2297 2244//2244 2246//2246 -f 2297//2297 2246//2246 2298//2298 -f 2298//2298 2246//2246 2248//2248 -f 2298//2298 2248//2248 2299//2299 -f 2299//2299 2248//2248 2250//2250 -f 2299//2299 2250//2250 2300//2300 -f 2300//2300 2250//2250 2252//2252 -f 2300//2300 2252//2252 2301//2301 -f 2301//2301 2252//2252 2254//2254 -f 2301//2301 2254//2254 2302//2302 -f 2302//2302 2254//2254 2256//2256 -f 2302//2302 2256//2256 2303//2303 -f 2303//2303 2256//2256 2258//2258 -f 2303//2303 2258//2258 2304//2304 -f 2304//2304 2258//2258 2260//2260 -f 2304//2304 2260//2260 2268//2268 -f 2268//2268 2260//2260 2262//2262 -f 2305//2305 2306//2306 2307//2307 -f 2307//2307 2306//2306 2308//2308 -f 2307//2307 2308//2308 2309//2309 -f 2309//2309 2308//2308 2310//2310 -f 2309//2309 2310//2310 2311//2311 -f 2311//2311 2310//2310 2312//2312 -f 2311//2311 2312//2312 2313//2313 -f 2313//2313 2312//2312 2314//2314 -f 2313//2313 2314//2314 2315//2315 -f 2315//2315 2314//2314 2316//2316 -f 2315//2315 2316//2316 2317//2317 -f 2317//2317 2316//2316 2318//2318 -f 2317//2317 2318//2318 2319//2319 -f 2319//2319 2318//2318 2320//2320 -f 2319//2319 2320//2320 2321//2321 -f 2321//2321 2320//2320 2322//2322 -f 2321//2321 2322//2322 2323//2323 -f 2323//2323 2322//2322 2324//2324 -f 2323//2323 2324//2324 2325//2325 -f 2325//2325 2324//2324 2326//2326 -f 2325//2325 2326//2326 2327//2327 -f 2327//2327 2326//2326 2328//2328 -f 2327//2327 2328//2328 2329//2329 -f 2329//2329 2328//2328 2330//2330 -f 2329//2329 2330//2330 2331//2331 -f 2331//2331 2330//2330 2332//2332 -f 2331//2331 2332//2332 2333//2333 -f 2333//2333 2332//2332 2334//2334 -f 2333//2333 2334//2334 2335//2335 -f 2335//2335 2334//2334 2336//2336 -f 2335//2335 2336//2336 2337//2337 -f 2337//2337 2336//2336 2338//2338 -f 2337//2337 2338//2338 2339//2339 -f 2339//2339 2338//2338 2340//2340 -f 2339//2339 2340//2340 2341//2341 -f 2341//2341 2340//2340 2342//2342 -f 2341//2341 2342//2342 2343//2343 -f 2343//2343 2342//2342 2344//2344 -f 2343//2343 2344//2344 2345//2345 -f 2345//2345 2344//2344 2346//2346 -f 2345//2345 2346//2346 2347//2347 -f 2347//2347 2346//2346 2348//2348 -f 2347//2347 2348//2348 2349//2349 -f 2349//2349 2348//2348 2350//2350 -f 2349//2349 2350//2350 2351//2351 -f 2351//2351 2350//2350 2352//2352 -f 2351//2351 2352//2352 2353//2353 -f 2353//2353 2352//2352 2354//2354 -f 2353//2353 2354//2354 2355//2355 -f 2355//2355 2354//2354 2356//2356 -f 2355//2355 2356//2356 2357//2357 -f 2357//2357 2356//2356 2358//2358 -f 2357//2357 2358//2358 2359//2359 -f 2359//2359 2358//2358 2360//2360 -f 2359//2359 2360//2360 2361//2361 -f 2361//2361 2360//2360 2362//2362 -f 2361//2361 2362//2362 2363//2363 -f 2363//2363 2362//2362 2364//2364 -f 2363//2363 2364//2364 2365//2365 -f 2365//2365 2364//2364 2366//2366 -f 2365//2365 2366//2366 2367//2367 -f 2367//2367 2366//2366 2368//2368 -f 2367//2367 2368//2368 2369//2369 -f 2369//2369 2368//2368 2370//2370 -f 2369//2369 2370//2370 2371//2371 -f 2371//2371 2370//2370 2372//2372 -f 2371//2371 2372//2372 2373//2373 -f 2373//2373 2372//2372 2374//2374 -f 2373//2373 2374//2374 2375//2375 -f 2375//2375 2374//2374 2376//2376 -f 2375//2375 2376//2376 2377//2377 -f 2377//2377 2376//2376 2378//2378 -f 2377//2377 2378//2378 2305//2305 -f 2305//2305 2378//2378 2306//2306 -f 2379//2379 2317//2317 2380//2380 -f 2380//2380 2317//2317 2319//2319 -f 2380//2380 2319//2319 2381//2381 -f 2381//2381 2319//2319 2321//2321 -f 2381//2381 2321//2321 2382//2382 -f 2382//2382 2321//2321 2323//2323 -f 2382//2382 2323//2323 2383//2383 -f 2383//2383 2323//2323 2325//2325 -f 2383//2383 2325//2325 2384//2384 -f 2384//2384 2325//2325 2327//2327 -f 2384//2384 2327//2327 2385//2385 -f 2385//2385 2327//2327 2329//2329 -f 2385//2385 2329//2329 2386//2386 -f 2386//2386 2329//2329 2331//2331 -f 2386//2386 2331//2331 2387//2387 -f 2387//2387 2331//2331 2333//2333 -f 2387//2387 2333//2333 2388//2388 -f 2388//2388 2333//2333 2335//2335 -f 2388//2388 2335//2335 2389//2389 -f 2389//2389 2335//2335 2337//2337 -f 2389//2389 2337//2337 2390//2390 -f 2390//2390 2337//2337 2339//2339 -f 2390//2390 2339//2339 2391//2391 -f 2391//2391 2339//2339 2341//2341 -f 2391//2391 2341//2341 2392//2392 -f 2392//2392 2341//2341 2343//2343 -f 2392//2392 2343//2343 2393//2393 -f 2393//2393 2343//2343 2345//2345 -f 2393//2393 2345//2345 2394//2394 -f 2394//2394 2345//2345 2347//2347 -f 2394//2394 2347//2347 2395//2395 -f 2395//2395 2347//2347 2349//2349 -f 2395//2395 2349//2349 2396//2396 -f 2396//2396 2349//2349 2351//2351 -f 2396//2396 2351//2351 2397//2397 -f 2397//2397 2351//2351 2353//2353 -f 2397//2397 2353//2353 2398//2398 -f 2398//2398 2353//2353 2355//2355 -f 2398//2398 2355//2355 2399//2399 -f 2399//2399 2355//2355 2357//2357 -f 2399//2399 2357//2357 2400//2400 -f 2400//2400 2357//2357 2359//2359 -f 2400//2400 2359//2359 2401//2401 -f 2401//2401 2359//2359 2361//2361 -f 2401//2401 2361//2361 2402//2402 -f 2402//2402 2361//2361 2363//2363 -f 2402//2402 2363//2363 2403//2403 -f 2403//2403 2363//2363 2365//2365 -f 2403//2403 2365//2365 2404//2404 -f 2404//2404 2365//2365 2367//2367 -f 2404//2404 2367//2367 2405//2405 -f 2405//2405 2367//2367 2369//2369 -f 2405//2405 2369//2369 2406//2406 -f 2406//2406 2369//2369 2371//2371 -f 2406//2406 2371//2371 2407//2407 -f 2407//2407 2371//2371 2373//2373 -f 2407//2407 2373//2373 2408//2408 -f 2408//2408 2373//2373 2375//2375 -f 2408//2408 2375//2375 2409//2409 -f 2409//2409 2375//2375 2377//2377 -f 2409//2409 2377//2377 2410//2410 -f 2410//2410 2377//2377 2305//2305 -f 2410//2410 2305//2305 2411//2411 -f 2411//2411 2305//2305 2307//2307 -f 2411//2411 2307//2307 2412//2412 -f 2412//2412 2307//2307 2309//2309 -f 2412//2412 2309//2309 2413//2413 -f 2413//2413 2309//2309 2311//2311 -f 2413//2413 2311//2311 2414//2414 -f 2414//2414 2311//2311 2313//2313 -f 2414//2414 2313//2313 2415//2415 -f 2415//2415 2313//2313 2315//2315 -f 2415//2415 2315//2315 2379//2379 -f 2379//2379 2315//2315 2317//2317 -f 2416//2416 2417//2417 2418//2418 -f 2418//2418 2417//2417 2419//2419 -f 2418//2418 2419//2419 2420//2420 -f 2420//2420 2419//2419 2421//2421 -f 2420//2420 2421//2421 2422//2422 -f 2422//2422 2421//2421 2423//2423 -f 2422//2422 2423//2423 2424//2424 -f 2424//2424 2423//2423 2425//2425 -f 2424//2424 2425//2425 2426//2426 -f 2426//2426 2425//2425 2427//2427 -f 2426//2426 2427//2427 2428//2428 -f 2428//2428 2427//2427 2429//2429 -f 2428//2428 2429//2429 2430//2430 -f 2430//2430 2429//2429 2431//2431 -f 2430//2430 2431//2431 2432//2432 -f 2432//2432 2431//2431 2433//2433 -f 2432//2432 2433//2433 2434//2434 -f 2434//2434 2433//2433 2435//2435 -f 2434//2434 2435//2435 2436//2436 -f 2436//2436 2435//2435 2437//2437 -f 2436//2436 2437//2437 2438//2438 -f 2438//2438 2437//2437 2439//2439 -f 2438//2438 2439//2439 2440//2440 -f 2440//2440 2439//2439 2441//2441 -f 2440//2440 2441//2441 2442//2442 -f 2442//2442 2441//2441 2443//2443 -f 2442//2442 2443//2443 2444//2444 -f 2444//2444 2443//2443 2445//2445 -f 2444//2444 2445//2445 2446//2446 -f 2446//2446 2445//2445 2447//2447 -f 2446//2446 2447//2447 2448//2448 -f 2448//2448 2447//2447 2449//2449 -f 2448//2448 2449//2449 2450//2450 -f 2450//2450 2449//2449 2451//2451 -f 2450//2450 2451//2451 2452//2452 -f 2452//2452 2451//2451 2453//2453 -f 2452//2452 2453//2453 2454//2454 -f 2454//2454 2453//2453 2455//2455 -f 2454//2454 2455//2455 2456//2456 -f 2456//2456 2455//2455 2457//2457 -f 2456//2456 2457//2457 2458//2458 -f 2458//2458 2457//2457 2459//2459 -f 2458//2458 2459//2459 2460//2460 -f 2460//2460 2459//2459 2461//2461 -f 2460//2460 2461//2461 2462//2462 -f 2462//2462 2461//2461 2463//2463 -f 2462//2462 2463//2463 2464//2464 -f 2464//2464 2463//2463 2465//2465 -f 2464//2464 2465//2465 2466//2466 -f 2466//2466 2465//2465 2467//2467 -f 2466//2466 2467//2467 2468//2468 -f 2468//2468 2467//2467 2469//2469 -f 2468//2468 2469//2469 2470//2470 -f 2470//2470 2469//2469 2471//2471 -f 2470//2470 2471//2471 2472//2472 -f 2472//2472 2471//2471 2473//2473 -f 2472//2472 2473//2473 2474//2474 -f 2474//2474 2473//2473 2475//2475 -f 2474//2474 2475//2475 2476//2476 -f 2476//2476 2475//2475 2477//2477 -f 2476//2476 2477//2477 2478//2478 -f 2478//2478 2477//2477 2479//2479 -f 2478//2478 2479//2479 2480//2480 -f 2480//2480 2479//2479 2481//2481 -f 2480//2480 2481//2481 2482//2482 -f 2482//2482 2481//2481 2483//2483 -f 2482//2482 2483//2483 2484//2484 -f 2484//2484 2483//2483 2485//2485 -f 2484//2484 2485//2485 2486//2486 -f 2486//2486 2485//2485 2487//2487 -f 2486//2486 2487//2487 2488//2488 -f 2488//2488 2487//2487 2489//2489 -f 2488//2488 2489//2489 2416//2416 -f 2416//2416 2489//2489 2417//2417 -f 2490//2490 2474//2474 2491//2491 -f 2491//2491 2474//2474 2476//2476 -f 2491//2491 2476//2476 2492//2492 -f 2492//2492 2476//2476 2478//2478 -f 2492//2492 2478//2478 2493//2493 -f 2493//2493 2478//2478 2480//2480 -f 2493//2493 2480//2480 2494//2494 -f 2494//2494 2480//2480 2482//2482 -f 2494//2494 2482//2482 2495//2495 -f 2495//2495 2482//2482 2484//2484 -f 2495//2495 2484//2484 2496//2496 -f 2496//2496 2484//2484 2486//2486 -f 2496//2496 2486//2486 2497//2497 -f 2497//2497 2486//2486 2488//2488 -f 2497//2497 2488//2488 2498//2498 -f 2498//2498 2488//2488 2416//2416 -f 2498//2498 2416//2416 2499//2499 -f 2499//2499 2416//2416 2418//2418 -f 2499//2499 2418//2418 2500//2500 -f 2500//2500 2418//2418 2420//2420 -f 2500//2500 2420//2420 2501//2501 -f 2501//2501 2420//2420 2422//2422 -f 2501//2501 2422//2422 2502//2502 -f 2502//2502 2422//2422 2424//2424 -f 2502//2502 2424//2424 2503//2503 -f 2503//2503 2424//2424 2426//2426 -f 2503//2503 2426//2426 2504//2504 -f 2504//2504 2426//2426 2428//2428 -f 2504//2504 2428//2428 2505//2505 -f 2505//2505 2428//2428 2430//2430 -f 2505//2505 2430//2430 2506//2506 -f 2506//2506 2430//2430 2432//2432 -f 2506//2506 2432//2432 2507//2507 -f 2507//2507 2432//2432 2434//2434 -f 2507//2507 2434//2434 2508//2508 -f 2508//2508 2434//2434 2436//2436 -f 2508//2508 2436//2436 2509//2509 -f 2509//2509 2436//2436 2438//2438 -f 2509//2509 2438//2438 2510//2510 -f 2510//2510 2438//2438 2440//2440 -f 2510//2510 2440//2440 2511//2511 -f 2511//2511 2440//2440 2442//2442 -f 2511//2511 2442//2442 2512//2512 -f 2512//2512 2442//2442 2444//2444 -f 2512//2512 2444//2444 2513//2513 -f 2513//2513 2444//2444 2446//2446 -f 2513//2513 2446//2446 2514//2514 -f 2514//2514 2446//2446 2448//2448 -f 2514//2514 2448//2448 2515//2515 -f 2515//2515 2448//2448 2450//2450 -f 2515//2515 2450//2450 2516//2516 -f 2516//2516 2450//2450 2452//2452 -f 2516//2516 2452//2452 2517//2517 -f 2517//2517 2452//2452 2454//2454 -f 2517//2517 2454//2454 2518//2518 -f 2518//2518 2454//2454 2456//2456 -f 2518//2518 2456//2456 2519//2519 -f 2519//2519 2456//2456 2458//2458 -f 2519//2519 2458//2458 2520//2520 -f 2520//2520 2458//2458 2460//2460 -f 2520//2520 2460//2460 2521//2521 -f 2521//2521 2460//2460 2462//2462 -f 2521//2521 2462//2462 2522//2522 -f 2522//2522 2462//2462 2464//2464 -f 2522//2522 2464//2464 2523//2523 -f 2523//2523 2464//2464 2466//2466 -f 2523//2523 2466//2466 2524//2524 -f 2524//2524 2466//2466 2468//2468 -f 2524//2524 2468//2468 2525//2525 -f 2525//2525 2468//2468 2470//2470 -f 2525//2525 2470//2470 2526//2526 -f 2526//2526 2470//2470 2472//2472 -f 2526//2526 2472//2472 2490//2490 -f 2490//2490 2472//2472 2474//2474 -f 1671//1671 1674//1674 1646//1646 -f 1660//1660 1659//1659 1688//1688 -f 2527//2527 2528//2528 1671//1671 -f 1674//1674 2529//2529 1646//1646 -f 1646//1646 2529//2529 2530//2530 -f 1646//1646 2530//2530 2531//2531 -f 2531//2531 2530//2530 2532//2532 -f 2527//2527 1671//1671 1687//1687 -f 1687//1687 1671//1671 1646//1646 -f 1687//1687 1646//1646 1688//1688 -f 1688//1688 1646//1646 1645//1645 -f 1688//1688 1645//1645 1660//1660 -f 1660//1660 1645//1645 2533//2533 -f 1660//1660 2533//2533 2534//2534 -f 2535//2535 2536//2536 1659//1659 -f 1659//1659 2536//2536 2537//2537 -f 1659//1659 2537//2537 1688//1688 -f 2535//2535 2538//2538 2536//2536 -f 2536//2536 2538//2538 2539//2539 -f 2536//2536 2539//2539 2540//2540 -f 2541//2541 2542//2542 2543//2543 -f 2543//2543 2542//2542 2544//2544 -f 2543//2543 2544//2544 2528//2528 -f 2528//2528 2544//2544 2545//2545 -f 2528//2528 2545//2545 1671//1671 -f 2546//2546 2547//2547 2548//2548 -f 2532//2532 2530//2530 2549//2549 -f 2549//2549 2530//2530 2550//2550 -f 2549//2549 2550//2550 2547//2547 -f 2547//2547 2550//2550 2551//2551 -f 2547//2547 2551//2551 2548//2548 -f 2552//2552 2553//2553 2554//2554 -f 2554//2554 2553//2553 2555//2555 -f 2554//2554 2555//2555 2556//2556 -f 2556//2556 2555//2555 2557//2557 -f 2556//2556 2557//2557 2534//2534 -f 2534//2534 2557//2557 2558//2558 -f 2534//2534 2558//2558 1660//1660 -f 2546//2546 2548//2548 2559//2559 -f 2559//2559 2548//2548 2560//2560 -f 2559//2559 2560//2560 2561//2561 -f 2543//2543 2562//2562 2541//2541 -f 2541//2541 2562//2562 2563//2563 -f 2541//2541 2563//2563 2564//2564 -f 2564//2564 2563//2563 2565//2565 -f 2564//2564 2565//2565 2566//2566 -f 2566//2566 2565//2565 2567//2567 -f 2540//2540 2539//2539 2568//2568 -f 2568//2568 2539//2539 2569//2569 -f 2568//2568 2569//2569 2570//2570 -f 2570//2570 2569//2569 2571//2571 -f 2570//2570 2571//2571 2572//2572 -f 2572//2572 2571//2571 2573//2573 -f 2572//2572 2573//2573 2574//2574 -f 2554//2554 2575//2575 2552//2552 -f 2552//2552 2575//2575 2576//2576 -f 2552//2552 2576//2576 2577//2577 -f 2577//2577 2576//2576 2578//2578 -f 1691//1691 1690//1690 1499//1499 -f 2579//2579 2580//2580 1375//1375 -f 1375//1375 2580//2580 1374//1374 -f 2581//2581 1376//1376 2582//2582 -f 2582//2582 1376//1376 1373//1373 -f 2582//2582 1373//1373 1374//1374 -f 1666//1666 1352//1352 1369//1369 -f 2581//2581 1658//1658 1376//1376 -f 1376//1376 1658//1658 1657//1657 -f 1376//1376 1657//1657 1377//1377 -f 1377//1377 1657//1657 1669//1669 -f 1377//1377 1669//1669 1371//1371 -f 1371//1371 1669//1669 1668//1668 -f 1371//1371 1668//1668 1369//1369 -f 1369//1369 1668//1668 1667//1667 -f 1369//1369 1667//1667 1666//1666 -f 1689//1689 2583//2583 2584//2584 -f 2584//2584 2583//2583 2585//2585 -f 2584//2584 2585//2585 2586//2586 -f 2587//2587 2588//2588 2582//2582 -f 2582//2582 2588//2588 2589//2589 -f 2582//2582 2589//2589 2581//2581 -f 2586//2586 2587//2587 2584//2584 -f 2584//2584 2587//2587 2582//2582 -f 2584//2584 2582//2582 2590//2590 -f 2590//2590 2582//2582 1374//1374 -f 2590//2590 1374//1374 2591//2591 -f 2591//2591 1374//1374 2580//2580 -f 2590//2590 2592//2592 2584//2584 -f 2584//2584 2592//2592 1503//1503 -f 2584//2584 1503//1503 1689//1689 -f 1689//1689 1503//1503 1502//1502 -f 1689//1689 1502//1502 1690//1690 -f 1690//1690 1502//1502 1500//1500 -f 1690//1690 1500//1500 1499//1499 -f 1491//1491 1698//1698 1510//1510 -f 1510//1510 1698//1698 1693//1693 -f 1510//1510 1693//1693 1499//1499 -f 1499//1499 1693//1693 1692//1692 -f 1499//1499 1692//1692 1691//1691 -f 1402//1402 1401//1401 2593//2593 -f 2593//2593 2594//2594 1402//1402 -f 1402//1402 2594//2594 2595//2595 -f 1402//1402 2595//2595 1375//1375 -f 1375//1375 2595//2595 2596//2596 -f 1375//1375 2596//2596 2579//2579 -f 1390//1390 1482//1482 1391//1391 -f 1391//1391 1482//1482 1480//1480 -f 1391//1391 1480//1480 1392//1392 -f 1392//1392 1480//1480 1479//1479 -f 1392//1392 1479//1479 1401//1401 -f 1401//1401 1479//1479 2597//2597 -f 1401//1401 2597//2597 2593//2593 -f 1381//1381 1485//1485 1390//1390 -f 1390//1390 1485//1485 1486//1486 -f 1390//1390 1486//1486 1482//1482 -f 895//895 894//894 2598//2598 -f 892//892 2599//2599 893//893 -f 1679//1679 1673//1673 880//880 -f 883//883 1682//1682 881//881 -f 881//881 1682//1682 1681//1681 -f 881//881 1681//1681 880//880 -f 880//880 1681//1681 1680//1680 -f 880//880 1680//1680 1679//1679 -f 2600//2600 2601//2601 1672//1672 -f 1672//1672 2601//2601 885//885 -f 1672//1672 885//885 1673//1673 -f 1673//1673 885//885 884//884 -f 1673//1673 884//884 880//880 -f 2599//2599 892//892 2601//2601 -f 2601//2601 892//892 886//886 -f 2601//2601 886//886 885//885 -f 2602//2602 2603//2603 875//875 -f 2603//2603 2604//2604 875//875 -f 875//875 2604//2604 2605//2605 -f 875//875 2605//2605 876//876 -f 876//876 2605//2605 878//878 -f 878//878 2605//2605 2606//2606 -f 878//878 2606//2606 2607//2607 -f 2598//2598 894//894 2607//2607 -f 2607//2607 894//894 879//879 -f 2607//2607 879//879 878//878 -f 2598//2598 2608//2608 895//895 -f 895//895 2608//2608 1414//1414 -f 895//895 1414//1414 889//889 -f 889//889 1414//1414 1413//1413 -f 889//889 1413//1413 888//888 -f 888//888 1413//1413 1416//1416 -f 888//888 1416//1416 887//887 -f 887//887 1416//1416 1426//1426 -f 887//887 1426//1426 891//891 -f 891//891 1426//1426 860//860 -f 1509//1509 2609//2609 2610//2610 -f 2610//2610 2609//2609 2611//2611 -f 1508//1508 1509//1509 1685//1685 -f 1694//1694 1489//1489 1506//1506 -f 1685//1685 1697//1697 1508//1508 -f 1508//1508 1697//1697 1696//1696 -f 1508//1508 1696//1696 1506//1506 -f 1506//1506 1696//1696 1695//1695 -f 1506//1506 1695//1695 1694//1694 -f 2612//2612 2613//2613 2610//2610 -f 2610//2610 2613//2613 2614//2614 -f 2610//2610 2614//2614 1509//1509 -f 1509//1509 2614//2614 1686//1686 -f 1509//1509 1686//1686 1685//1685 -f 2600//2600 2615//2615 2601//2601 -f 2601//2601 2615//2615 2616//2616 -f 2601//2601 2616//2616 2617//2617 -f 875//875 893//893 2602//2602 -f 2602//2602 893//893 2599//2599 -f 2602//2602 2599//2599 2611//2611 -f 2611//2611 2599//2599 2601//2601 -f 2611//2611 2601//2601 2610//2610 -f 2610//2610 2601//2601 2617//2617 -f 2610//2610 2617//2617 2612//2612 -f 1649//1649 1648//1648 1249//1249 -f 1683//1683 794//794 800//800 -f 798//798 797//797 1675//1675 -f 809//809 803//803 1213//1213 -f 809//809 1213//1213 810//810 -f 810//810 1213//1213 1214//1214 -f 810//810 1214//1214 811//811 -f 1214//1214 1210//1210 811//811 -f 811//811 1210//1210 1208//1208 -f 811//811 1208//1208 812//812 -f 812//812 1208//1208 814//814 -f 1208//1208 1207//1207 814//814 -f 814//814 1207//1207 2618//2618 -f 814//814 2618//2618 815//815 -f 815//815 2618//2618 2619//2619 -f 815//815 2619//2619 813//813 -f 813//813 2619//2619 2620//2620 -f 813//813 2620//2620 808//808 -f 808//808 2620//2620 2621//2621 -f 808//808 2621//2621 801//801 -f 801//801 2621//2621 2622//2622 -f 801//801 2622//2622 802//802 -f 805//805 2623//2623 806//806 -f 806//806 2623//2623 2624//2624 -f 806//806 2624//2624 807//807 -f 807//807 2624//2624 2625//2625 -f 2625//2625 1678//1678 807//807 -f 807//807 1678//1678 1677//1677 -f 807//807 1677//1677 797//797 -f 797//797 1677//1677 1676//1676 -f 797//797 1676//1676 1675//1675 -f 798//798 1675//1675 800//800 -f 800//800 1675//1675 1684//1684 -f 800//800 1684//1684 1683//1683 -f 1647//1647 2626//2626 2627//2627 -f 2627//2627 2626//2626 2628//2628 -f 2627//2627 2628//2628 2629//2629 -f 2630//2630 2631//2631 2624//2624 -f 2624//2624 2631//2631 2632//2632 -f 2624//2624 2632//2632 2625//2625 -f 2633//2633 2634//2634 2627//2627 -f 2627//2627 2634//2634 1253//1253 -f 2627//2627 1253//1253 1647//1647 -f 1647//1647 1253//1253 1252//1252 -f 1647//1647 1252//1252 1648//1648 -f 1648//1648 1252//1252 1250//1250 -f 1648//1648 1250//1250 1249//1249 -f 1241//1241 1656//1656 1260//1260 -f 1260//1260 1656//1656 1651//1651 -f 1260//1260 1651//1651 1249//1249 -f 1249//1249 1651//1651 1650//1650 -f 1249//1249 1650//1650 1649//1649 -f 2622//2622 2635//2635 802//802 -f 802//802 2635//2635 2636//2636 -f 802//802 2636//2636 805//805 -f 805//805 2636//2636 2637//2637 -f 805//805 2637//2637 2623//2623 -f 2623//2623 2637//2637 2633//2633 -f 2623//2623 2633//2633 2624//2624 -f 2624//2624 2633//2633 2627//2627 -f 2624//2624 2627//2627 2630//2630 -f 2630//2630 2627//2627 2629//2629 -f 1663//1663 1662//1662 1362//1362 -f 2638//2638 2639//2639 2640//2640 -f 2641//2641 2642//2642 2643//2643 -f 2641//2641 2643//2643 1298//1298 -f 1298//1298 2643//2643 1273//1273 -f 1298//1298 1273//1273 1299//1299 -f 2644//2644 2645//2645 2646//2646 -f 2646//2646 2645//2645 2647//2647 -f 2646//2646 2647//2647 2648//2648 -f 2648//2648 2647//2647 2649//2649 -f 2648//2648 2649//2649 2650//2650 -f 2650//2650 2649//2649 2651//2651 -f 2650//2650 2651//2651 2652//2652 -f 2652//2652 2651//2651 2653//2653 -f 2652//2652 2653//2653 2654//2654 -f 2654//2654 2653//2653 2655//2655 -f 2654//2654 2655//2655 2642//2642 -f 2642//2642 2655//2655 2656//2656 -f 2642//2642 2656//2656 2643//2643 -f 2657//2657 2658//2658 2644//2644 -f 2644//2644 2658//2658 2659//2659 -f 2644//2644 2659//2659 2645//2645 -f 2657//2657 2660//2660 2658//2658 -f 2658//2658 2660//2660 2661//2661 -f 2658//2658 2661//2661 2640//2640 -f 2639//2639 1259//1259 2640//2640 -f 2640//2640 1259//1259 2662//2662 -f 2640//2640 2662//2662 2658//2658 -f 2639//2639 1644//1644 1259//1259 -f 1259//1259 1644//1644 1643//1643 -f 1259//1259 1643//1643 1258//1258 -f 1652//1652 1239//1239 1256//1256 -f 1643//1643 1655//1655 1258//1258 -f 1258//1258 1655//1655 1654//1654 -f 1258//1258 1654//1654 1256//1256 -f 1256//1256 1654//1654 1653//1653 -f 1256//1256 1653//1653 1652//1652 -f 1661//1661 2663//2663 2661//2661 -f 2661//2661 2663//2663 2664//2664 -f 2664//2664 2665//2665 2661//2661 -f 2661//2661 2665//2665 2666//2666 -f 2661//2661 2666//2666 2640//2640 -f 2640//2640 2666//2666 2667//2667 -f 2640//2640 2667//2667 2638//2638 -f 2660//2660 2668//2668 2661//2661 -f 2661//2661 2668//2668 1366//1366 -f 2661//2661 1366//1366 1661//1661 -f 1661//1661 1366//1366 1365//1365 -f 1661//1661 1365//1365 1662//1662 -f 1662//1662 1365//1365 1363//1363 -f 1662//1662 1363//1363 1362//1362 -f 1354//1354 1670//1670 1372//1372 -f 1372//1372 1670//1670 1665//1665 -f 1372//1372 1665//1665 1362//1362 -f 1362//1362 1665//1665 1664//1664 -f 1362//1362 1664//1664 1663//1663 -f 1273//1273 1272//1272 1299//1299 -f 1299//1299 1272//1272 1275//1275 -f 1299//1299 1275//1275 1301//1301 -f 1301//1301 1275//1275 1284//1284 -f 1264//1264 1304//1304 1284//1284 -f 1284//1284 1304//1304 1305//1305 -f 1284//1284 1305//1305 1301//1301 -f 1637//1637 1627//1627 1465//1465 -f 1555//1555 1149//1149 1148//1148 -f 839//839 1424//1424 840//840 -f 840//840 1424//1424 1425//1425 -f 840//840 1425//1425 838//838 -f 838//838 1425//1425 837//837 -f 1425//1425 1420//1420 837//837 -f 837//837 1420//1420 1418//1418 -f 837//837 1418//1418 844//844 -f 844//844 1418//1418 845//845 -f 1418//1418 1417//1417 845//845 -f 845//845 1417//1417 2669//2669 -f 845//845 2669//2669 846//846 -f 846//846 2669//2669 2670//2670 -f 846//846 2670//2670 847//847 -f 847//847 2670//2670 2671//2671 -f 847//847 2671//2671 848//848 -f 848//848 2671//2671 2672//2672 -f 848//848 2672//2672 849//849 -f 849//849 2672//2672 2673//2673 -f 849//849 2673//2673 850//850 -f 2674//2674 841//841 2675//2675 -f 2675//2675 841//841 835//835 -f 2675//2675 835//835 2676//2676 -f 2676//2676 835//835 834//834 -f 2676//2676 834//834 851//851 -f 2674//2674 1543//1543 841//841 -f 841//841 1543//1543 1542//1542 -f 841//841 1542//1542 842//842 -f 842//842 1542//1542 1549//1549 -f 842//842 1549//1549 843//843 -f 843//843 1549//1549 1548//1548 -f 843//843 1548//1548 1148//1148 -f 1148//1148 1548//1548 1547//1547 -f 1148//1148 1547//1547 1555//1555 -f 1626//1626 2677//2677 2678//2678 -f 2678//2678 2677//2677 2679//2679 -f 2678//2678 2679//2679 2680//2680 -f 2681//2681 2682//2682 2675//2675 -f 2675//2675 2682//2682 2683//2683 -f 2675//2675 2683//2683 2674//2674 -f 2684//2684 2685//2685 2678//2678 -f 2678//2678 2685//2685 1459//1459 -f 2678//2678 1459//1459 1626//1626 -f 1626//1626 1459//1459 1461//1461 -f 1626//1626 1461//1461 1627//1627 -f 1627//1627 1461//1461 1462//1462 -f 1627//1627 1462//1462 1465//1465 -f 1430//1430 1630//1630 1464//1464 -f 1464//1464 1630//1630 1639//1639 -f 1464//1464 1639//1639 1465//1465 -f 1465//1465 1639//1639 1638//1638 -f 1465//1465 1638//1638 1637//1637 -f 2673//2673 2686//2686 850//850 -f 850//850 2686//2686 2687//2687 -f 850//850 2687//2687 851//851 -f 851//851 2687//2687 2688//2688 -f 851//851 2688//2688 2676//2676 -f 2676//2676 2688//2688 2684//2684 -f 2676//2676 2684//2684 2675//2675 -f 2675//2675 2684//2684 2678//2678 -f 2675//2675 2678//2678 2681//2681 -f 2681//2681 2678//2678 2680//2680 -f 1596//1596 1586//1586 1342//1342 -f 1585//1585 2689//2689 2690//2690 -f 1403//1403 1347//1347 2691//2691 -f 2691//2691 2692//2692 1403//1403 -f 1403//1403 2692//2692 2693//2693 -f 1403//1403 2693//2693 1404//1404 -f 2694//2694 1476//1476 1394//1394 -f 2693//2693 2695//2695 1404//1404 -f 1404//1404 2695//2695 2694//2694 -f 1404//1404 2694//2694 1393//1393 -f 1393//1393 2694//2694 1394//1394 -f 1478//1478 1487//1487 1400//1400 -f 1476//1476 1475//1475 1394//1394 -f 1394//1394 1475//1475 1478//1478 -f 1394//1394 1478//1478 1399//1399 -f 1399//1399 1478//1478 1400//1400 -f 1379//1379 1397//1397 1487//1487 -f 1487//1487 1397//1397 1398//1398 -f 1487//1487 1398//1398 1400//1400 -f 2696//2696 2697//2697 1347//1347 -f 1347//1347 2697//2697 2698//2698 -f 1347//1347 2698//2698 2691//2691 -f 1458//1458 2699//2699 2700//2700 -f 2700//2700 2699//2699 2701//2701 -f 1456//1456 1458//1458 1635//1635 -f 1641//1641 1428//1428 1454//1454 -f 1635//1635 1633//1633 1456//1456 -f 1456//1456 1633//1633 1632//1632 -f 1456//1456 1632//1632 1454//1454 -f 1454//1454 1632//1632 1642//1642 -f 1454//1454 1642//1642 1641//1641 -f 2702//2702 2703//2703 2700//2700 -f 2700//2700 2703//2703 2704//2704 -f 2700//2700 2704//2704 1458//1458 -f 1458//1458 2704//2704 1636//1636 -f 1458//1458 1636//1636 1635//1635 -f 2689//2689 2705//2705 2690//2690 -f 2690//2690 2705//2705 2706//2706 -f 2690//2690 2706//2706 2707//2707 -f 1347//1347 1349//1349 2696//2696 -f 2696//2696 1349//1349 1350//1350 -f 2696//2696 1350//1350 2701//2701 -f 2701//2701 1350//1350 2690//2690 -f 2701//2701 2690//2690 2700//2700 -f 2700//2700 2690//2690 2707//2707 -f 2700//2700 2707//2707 2702//2702 -f 1350//1350 1346//1346 2690//2690 -f 2690//2690 1346//1346 1345//1345 -f 2690//2690 1345//1345 1585//1585 -f 1585//1585 1345//1345 1344//1344 -f 1585//1585 1344//1344 1586//1586 -f 1586//1586 1344//1344 1343//1343 -f 1586//1586 1343//1343 1342//1342 -f 1310//1310 1589//1589 1340//1340 -f 1340//1340 1589//1589 1598//1598 -f 1340//1340 1598//1598 1342//1342 -f 1342//1342 1598//1598 1597//1597 -f 1342//1342 1597//1597 1596//1596 -f 2708//2708 2709//2709 2710//2710 -f 2711//2711 2712//2712 2713//2713 -f 1218//1218 1534//1534 1237//1237 -f 1237//1237 1534//1534 1535//1535 -f 1237//1237 1535//1535 1226//1226 -f 1226//1226 1535//1535 1530//1530 -f 1530//1530 1529//1529 1226//1226 -f 1226//1226 1529//1529 1527//1527 -f 1226//1226 1527//1527 1227//1227 -f 1227//1227 1527//1527 1229//1229 -f 1229//1229 1527//1527 1526//1526 -f 1229//1229 1526//1526 1230//1230 -f 2714//2714 2710//2710 2715//2715 -f 2716//2716 2717//2717 2715//2715 -f 2715//2715 2717//2717 2718//2718 -f 2715//2715 2718//2718 2714//2714 -f 2714//2714 2718//2718 2719//2719 -f 2714//2714 2719//2719 1230//1230 -f 2715//2715 2720//2720 2716//2716 -f 2716//2716 2720//2720 2721//2721 -f 2716//2716 2721//2721 2722//2722 -f 2722//2722 2721//2721 2723//2723 -f 2722//2722 2723//2723 2724//2724 -f 2724//2724 2723//2723 2725//2725 -f 2724//2724 2725//2725 2726//2726 -f 2726//2726 2725//2725 2727//2727 -f 2726//2726 2727//2727 2728//2728 -f 2728//2728 2727//2727 2729//2729 -f 2728//2728 2729//2729 2730//2730 -f 2730//2730 2729//2729 2731//2731 -f 2730//2730 2731//2731 2712//2712 -f 2712//2712 2731//2731 2732//2732 -f 2712//2712 2732//2732 2713//2713 -f 2711//2711 2713//2713 1276//1276 -f 1276//1276 2713//2713 1295//1295 -f 1276//1276 1295//1295 1277//1277 -f 1295//1295 1294//1294 1277//1277 -f 1277//1277 1294//1294 1297//1297 -f 1277//1277 1297//1297 1279//1279 -f 1279//1279 1297//1297 1306//1306 -f 1262//1262 1282//1282 1306//1306 -f 1306//1306 1282//1282 1283//1283 -f 1306//1306 1283//1283 1279//1279 -f 2709//2709 1338//1338 2710//2710 -f 2710//2710 1338//1338 2733//2733 -f 2710//2710 2733//2733 2715//2715 -f 2709//2709 1595//1595 1338//1338 -f 1338//1338 1595//1595 1594//1594 -f 1338//1338 1594//1594 1336//1336 -f 1600//1600 1308//1308 1334//1334 -f 1594//1594 1592//1592 1336//1336 -f 1336//1336 1592//1592 1591//1591 -f 1336//1336 1591//1591 1334//1334 -f 1334//1334 1591//1591 1601//1601 -f 1334//1334 1601//1601 1600//1600 -f 1230//1230 1526//1526 2714//2714 -f 2714//2714 1526//1526 2734//2734 -f 2714//2714 2734//2734 2735//2735 -f 2735//2735 2736//2736 2714//2714 -f 2714//2714 2736//2736 2737//2737 -f 2714//2714 2737//2737 2710//2710 -f 2710//2710 2737//2737 2738//2738 -f 2710//2710 2738//2738 2708//2708 -f 1154//1154 1559//1559 828//828 -f 828//828 1559//1559 1560//1560 -f 828//828 1560//1560 829//829 -f 829//829 1560//1560 1554//1554 -f 829//829 1554//1554 831//831 -f 1554//1554 1553//1553 831//831 -f 831//831 1553//1553 1551//1551 -f 831//831 1551//1551 832//832 -f 832//832 1551//1551 1550//1550 -f 816//816 833//833 2739//2739 -f 2739//2739 833//833 832//832 -f 2739//2739 832//832 2740//2740 -f 2740//2740 832//832 1550//1550 -f 2740//2740 1550//1550 2741//2741 -f 2742//2742 2743//2743 817//817 -f 2743//2743 2744//2744 817//817 -f 817//817 2744//2744 2745//2745 -f 817//817 2745//2745 819//819 -f 819//819 2745//2745 820//820 -f 2745//2745 2746//2746 820//820 -f 820//820 2746//2746 2747//2747 -f 820//820 2747//2747 821//821 -f 821//821 2747//2747 822//822 -f 2747//2747 2748//2748 822//822 -f 822//822 2748//2748 2749//2749 -f 822//822 2749//2749 823//823 -f 823//823 2749//2749 824//824 -f 2749//2749 1206//1206 824//824 -f 824//824 1206//1206 1205//1205 -f 824//824 1205//1205 825//825 -f 825//825 1205//1205 1203//1203 -f 825//825 1203//1203 826//826 -f 826//826 1203//1203 1202//1202 -f 826//826 1202//1202 827//827 -f 827//827 1202//1202 818//818 -f 1236//1236 2750//2750 2751//2751 -f 2751//2751 2750//2750 2752//2752 -f 1235//1235 1236//1236 1520//1520 -f 1531//1531 1216//1216 1233//1233 -f 1520//1520 1525//1525 1235//1235 -f 1235//1235 1525//1525 1524//1524 -f 1235//1235 1524//1524 1233//1233 -f 1233//1233 1524//1524 1523//1523 -f 1233//1233 1523//1523 1531//1531 -f 2753//2753 2754//2754 2751//2751 -f 2751//2751 2754//2754 2755//2755 -f 2751//2751 2755//2755 1236//1236 -f 1236//1236 2755//2755 1521//1521 -f 1236//1236 1521//1521 1520//1520 -f 2741//2741 2756//2756 2740//2740 -f 2740//2740 2756//2756 2757//2757 -f 2740//2740 2757//2757 2758//2758 -f 817//817 816//816 2742//2742 -f 2742//2742 816//816 2739//2739 -f 2742//2742 2739//2739 2752//2752 -f 2752//2752 2739//2739 2740//2740 -f 2752//2752 2740//2740 2751//2751 -f 2751//2751 2740//2740 2758//2758 -f 2751//2751 2758//2758 2753//2753 -f 2759//2759 2760//2760 383//383 -f 2761//2761 2762//2762 259//259 -f 2763//2763 2764//2764 369//369 -f 2765//2765 2766//2766 373//373 -f 2767//2767 2768//2768 377//377 -f 624//624 629//629 2769//2769 -f 2769//2769 629//629 2770//2770 -f 2770//2770 629//629 628//628 -f 2770//2770 628//628 2771//2771 -f 2771//2771 628//628 633//633 -f 2771//2771 633//633 2772//2772 -f 2772//2772 633//633 632//632 -f 2772//2772 632//632 2773//2773 -f 2773//2773 632//632 640//640 -f 2773//2773 640//640 2774//2774 -f 2774//2774 640//640 639//639 -f 2774//2774 639//639 2768//2768 -f 2768//2768 639//639 378//378 -f 2768//2768 378//378 377//377 -f 2767//2767 377//377 2766//2766 -f 2766//2766 377//377 375//375 -f 2766//2766 375//375 373//373 -f 2765//2765 373//373 2764//2764 -f 2764//2764 373//373 371//371 -f 2764//2764 371//371 369//369 -f 2763//2763 369//369 2762//2762 -f 2762//2762 369//369 260//260 -f 2762//2762 260//260 259//259 -f 2761//2761 259//259 2760//2760 -f 2760//2760 259//259 381//381 -f 2760//2760 381//381 383//383 -f 2759//2759 383//383 2775//2775 -f 2775//2775 383//383 385//385 -f 2775//2775 385//385 2776//2776 -f 2776//2776 385//385 387//387 -f 2776//2776 387//387 2777//2777 -f 2777//2777 387//387 389//389 -f 2777//2777 389//389 2778//2778 -f 2778//2778 389//389 391//391 -f 2778//2778 391//391 2779//2779 -f 2779//2779 391//391 393//393 -f 2779//2779 393//393 2780//2780 -f 2780//2780 393//393 396//396 -f 2780//2780 396//396 2781//2781 -f 2781//2781 396//396 398//398 -f 2781//2781 398//398 2782//2782 -f 2782//2782 398//398 400//400 -f 2782//2782 400//400 2783//2783 -f 2783//2783 400//400 402//402 -f 2783//2783 402//402 2784//2784 -f 2784//2784 402//402 2785//2785 -f 2785//2785 402//402 404//404 -f 2785//2785 404//404 2786//2786 -f 2786//2786 404//404 406//406 -f 2786//2786 406//406 2787//2787 -f 2787//2787 406//406 408//408 -f 2787//2787 408//408 2788//2788 -f 2788//2788 408//408 410//410 -f 2788//2788 410//410 2789//2789 -f 258//258 257//257 2790//2790 -f 2789//2789 410//410 2791//2791 -f 2791//2791 410//410 413//413 -f 2791//2791 413//413 2792//2792 -f 2792//2792 413//413 415//415 -f 2792//2792 415//415 2793//2793 -f 2793//2793 415//415 417//417 -f 2793//2793 417//417 2794//2794 -f 2794//2794 417//417 420//420 -f 2794//2794 420//420 2795//2795 -f 2795//2795 420//420 422//422 -f 2795//2795 422//422 2796//2796 -f 2796//2796 422//422 258//258 -f 2796//2796 258//258 2797//2797 -f 2797//2797 258//258 2790//2790 -f 2797//2797 2790//2790 2798//2798 -f 2798//2798 2790//2790 2799//2799 -f 2798//2798 2799//2799 2800//2800 -f 2801//2801 2802//2802 2803//2803 -f 2803//2803 2802//2802 2804//2804 -f 2803//2803 2804//2804 2805//2805 -f 2805//2805 2804//2804 2806//2806 -f 2805//2805 2806//2806 2800//2800 -f 2800//2800 2806//2806 2807//2807 -f 2800//2800 2807//2807 2798//2798 -f 2769//2769 2808//2808 624//624 -f 624//624 2808//2808 2809//2809 -f 624//624 2809//2809 625//625 -f 625//625 2809//2809 2810//2810 -f 625//625 2810//2810 602//602 -f 602//602 2810//2810 2811//2811 -f 602//602 2811//2811 603//603 -f 603//603 2811//2811 2812//2812 -f 603//603 2812//2812 620//620 -f 620//620 2812//2812 2813//2813 -f 620//620 2813//2813 618//618 -f 618//618 2813//2813 2814//2814 -f 618//618 2814//2814 616//616 -f 616//616 2814//2814 2815//2815 -f 616//616 2815//2815 614//614 -f 2815//2815 2816//2816 614//614 -f 614//614 2816//2816 2817//2817 -f 614//614 2817//2817 612//612 -f 612//612 2817//2817 2818//2818 -f 612//612 2818//2818 610//610 -f 610//610 2818//2818 2819//2819 -f 610//610 2819//2819 608//608 -f 608//608 2819//2819 2820//2820 -f 608//608 2820//2820 606//606 -f 606//606 2820//2820 2821//2821 -f 606//606 2821//2821 600//600 -f 600//600 2821//2821 2822//2822 -f 600//600 2822//2822 598//598 -f 598//598 2822//2822 2823//2823 -f 598//598 2823//2823 596//596 -f 596//596 2823//2823 2824//2824 -f 596//596 2824//2824 594//594 -f 2824//2824 2825//2825 594//594 -f 594//594 2825//2825 2826//2826 -f 594//594 2826//2826 592//592 -f 592//592 2826//2826 2827//2827 -f 592//592 2827//2827 590//590 -f 590//590 2827//2827 2828//2828 -f 590//590 2828//2828 588//588 -f 588//588 2828//2828 2829//2829 -f 588//588 2829//2829 586//586 -f 2830//2830 579//579 2831//2831 -f 2831//2831 579//579 444//444 -f 2831//2831 444//444 2832//2832 -f 2832//2832 444//444 443//443 -f 2832//2832 443//443 2833//2833 -f 2833//2833 443//443 584//584 -f 2833//2833 584//584 2834//2834 -f 2834//2834 584//584 586//586 -f 2834//2834 586//586 2835//2835 -f 2835//2835 586//586 2829//2829 -f 2830//2830 2831//2831 2836//2836 -f 2836//2836 2831//2831 2837//2837 -f 2836//2836 2837//2837 2838//2838 -f 2837//2837 2839//2839 2838//2838 -f 2838//2838 2839//2839 2840//2840 -f 2838//2838 2840//2840 2841//2841 -f 2841//2841 2840//2840 2842//2842 -f 2841//2841 2842//2842 2843//2843 -f 781//781 714//714 2844//2844 -f 702//702 704//704 2845//2845 -f 2845//2845 704//704 706//706 -f 2845//2845 706//706 708//708 -f 708//708 710//710 2845//2845 -f 2845//2845 710//710 712//712 -f 2845//2845 712//712 642//642 -f 2846//2846 715//715 717//717 -f 717//717 719//719 2846//2846 -f 2846//2846 719//719 721//721 -f 2846//2846 721//721 723//723 -f 133//133 131//131 2847//2847 -f 2847//2847 131//131 129//129 -f 2847//2847 129//129 127//127 -f 119//119 236//236 121//121 -f 121//121 236//236 123//123 -f 208//208 206//206 2848//2848 -f 2848//2848 206//206 204//204 -f 204//204 202//202 2848//2848 -f 2848//2848 202//202 200//200 -f 2848//2848 200//200 198//198 -f 702//702 2845//2845 700//700 -f 700//700 2845//2845 2849//2849 -f 700//700 2849//2849 698//698 -f 698//698 2849//2849 2850//2850 -f 698//698 2850//2850 696//696 -f 696//696 2850//2850 2851//2851 -f 696//696 2851//2851 694//694 -f 694//694 2851//2851 2852//2852 -f 694//694 2852//2852 692//692 -f 723//723 725//725 2846//2846 -f 2846//2846 725//725 727//727 -f 2846//2846 727//727 2853//2853 -f 2853//2853 727//727 729//729 -f 2853//2853 729//729 2854//2854 -f 2854//2854 729//729 731//731 -f 2854//2854 731//731 2855//2855 -f 2855//2855 731//731 733//733 -f 2855//2855 733//733 2856//2856 -f 2856//2856 733//733 735//735 -f 2856//2856 735//735 2857//2857 -f 119//119 117//117 236//236 -f 236//236 117//117 115//115 -f 236//236 115//115 113//113 -f 198//198 196//196 2848//2848 -f 2848//2848 196//196 194//194 -f 2848//2848 194//194 192//192 -f 192//192 676//676 678//678 -f 2858//2858 2859//2859 690//690 -f 690//690 2859//2859 2860//2860 -f 690//690 2860//2860 688//688 -f 688//688 2860//2860 2861//2861 -f 688//688 2861//2861 686//686 -f 686//686 2861//2861 2862//2862 -f 686//686 2862//2862 684//684 -f 684//684 2862//2862 2848//2848 -f 684//684 2848//2848 682//682 -f 2857//2857 735//735 2863//2863 -f 2863//2863 735//735 737//737 -f 2863//2863 737//737 2864//2864 -f 236//236 234//234 123//123 -f 123//123 234//234 232//232 -f 123//123 232//232 230//230 -f 127//127 125//125 2847//2847 -f 2847//2847 125//125 123//123 -f 2847//2847 123//123 218//218 -f 2858//2858 690//690 2865//2865 -f 2865//2865 690//690 692//692 -f 2865//2865 692//692 2866//2866 -f 2867//2867 2868//2868 739//739 -f 739//739 2868//2868 2869//2869 -f 739//739 2869//2869 737//737 -f 737//737 2869//2869 2870//2870 -f 737//737 2870//2870 2871//2871 -f 2872//2872 2873//2873 2874//2874 -f 646//646 648//648 2875//2875 -f 2875//2875 648//648 650//650 -f 2875//2875 650//650 652//652 -f 248//248 246//246 668//668 -f 230//230 228//228 123//123 -f 123//123 228//228 226//226 -f 123//123 226//226 224//224 -f 212//212 2876//2876 214//214 -f 214//214 2876//2876 2847//2847 -f 214//214 2847//2847 216//216 -f 216//216 2847//2847 218//218 -f 208//208 2848//2848 210//210 -f 210//210 2848//2848 2877//2877 -f 210//210 2877//2877 2878//2878 -f 2878//2878 2879//2879 210//210 -f 210//210 2879//2879 2880//2880 -f 210//210 2880//2880 2881//2881 -f 192//192 678//678 2848//2848 -f 2848//2848 678//678 680//680 -f 2848//2848 680//680 682//682 -f 652//652 654//654 2875//2875 -f 2875//2875 654//654 656//656 -f 2875//2875 656//656 2882//2882 -f 224//224 222//222 123//123 -f 123//123 222//222 220//220 -f 123//123 220//220 218//218 -f 2874//2874 2883//2883 2872//2872 -f 2872//2872 2883//2883 2884//2884 -f 2872//2872 2884//2884 2852//2852 -f 2852//2852 2884//2884 2885//2885 -f 2852//2852 2885//2885 692//692 -f 692//692 2885//2885 2886//2886 -f 692//692 2886//2886 2866//2866 -f 181//181 254//254 670//670 -f 745//745 747//747 2887//2887 -f 775//775 777//777 2844//2844 -f 2844//2844 777//777 779//779 -f 2844//2844 779//779 781//781 -f 113//113 111//111 236//236 -f 236//236 111//111 109//109 -f 236//236 109//109 238//238 -f 238//238 109//109 107//107 -f 2888//2888 165//165 2889//2889 -f 2889//2889 165//165 163//163 -f 2889//2889 163//163 2890//2890 -f 2867//2867 739//739 2891//2891 -f 2891//2891 739//739 741//741 -f 2891//2891 741//741 2887//2887 -f 2887//2887 741//741 743//743 -f 2887//2887 743//743 745//745 -f 2881//2881 2892//2892 210//210 -f 210//210 2892//2892 2893//2893 -f 210//210 2893//2893 212//212 -f 212//212 2893//2893 2894//2894 -f 212//212 2894//2894 2876//2876 -f 2895//2895 2896//2896 2897//2897 -f 2898//2898 2899//2899 2900//2900 -f 2900//2900 2899//2899 2901//2901 -f 2901//2901 2902//2902 2900//2900 -f 2900//2900 2902//2902 2903//2903 -f 2900//2900 2903//2903 2873//2873 -f 2873//2873 2903//2903 2904//2904 -f 2873//2873 2904//2904 2874//2874 -f 248//248 668//668 250//250 -f 244//244 2905//2905 246//246 -f 246//246 2905//2905 666//666 -f 246//246 666//666 668//668 -f 767//767 769//769 2906//2906 -f 2906//2906 769//769 771//771 -f 2906//2906 771//771 2844//2844 -f 2844//2844 771//771 773//773 -f 2844//2844 773//773 775//775 -f 2887//2887 139//139 2907//2907 -f 2907//2907 139//139 2908//2908 -f 2909//2909 2910//2910 137//137 -f 2911//2911 2912//2912 2864//2864 -f 656//656 658//658 2882//2882 -f 2882//2882 658//658 660//660 -f 2882//2882 660//660 2913//2913 -f 2913//2913 660//660 662//662 -f 2913//2913 662//662 2905//2905 -f 2905//2905 662//662 664//664 -f 2905//2905 664//664 666//666 -f 670//670 254//254 668//668 -f 668//668 254//254 252//252 -f 668//668 252//252 250//250 -f 244//244 242//242 2905//2905 -f 2905//2905 242//242 240//240 -f 2905//2905 240//240 238//238 -f 2910//2910 2914//2914 137//137 -f 137//137 2914//2914 2915//2915 -f 137//137 2915//2915 139//139 -f 139//139 2915//2915 2916//2916 -f 139//139 2916//2916 2908//2908 -f 2871//2871 2917//2917 737//737 -f 737//737 2917//2917 2918//2918 -f 737//737 2918//2918 2864//2864 -f 2864//2864 2918//2918 2919//2919 -f 2864//2864 2919//2919 2911//2911 -f 2920//2920 2921//2921 2922//2922 -f 2897//2897 2896//2896 2923//2923 -f 192//192 190//190 676//676 -f 676//676 190//190 188//188 -f 676//676 188//188 674//674 -f 674//674 188//188 186//186 -f 674//674 186//186 672//672 -f 672//672 186//186 184//184 -f 672//672 184//184 670//670 -f 670//670 184//184 182//182 -f 670//670 182//182 181//181 -f 107//107 106//106 238//238 -f 238//238 106//106 179//179 -f 238//238 179//179 2905//2905 -f 2905//2905 179//179 177//177 -f 2905//2905 177//177 2924//2924 -f 2924//2924 177//177 175//175 -f 2924//2924 175//175 2925//2925 -f 2925//2925 175//175 173//173 -f 2925//2925 173//173 2926//2926 -f 2926//2926 173//173 171//171 -f 2926//2926 171//171 2927//2927 -f 2927//2927 171//171 169//169 -f 2927//2927 169//169 2888//2888 -f 2888//2888 169//169 167//167 -f 2888//2888 167//167 165//165 -f 133//133 2847//2847 135//135 -f 135//135 2847//2847 2928//2928 -f 135//135 2928//2928 137//137 -f 137//137 2928//2928 2929//2929 -f 137//137 2929//2929 2909//2909 -f 2912//2912 2930//2930 2864//2864 -f 2864//2864 2930//2930 2931//2931 -f 2864//2864 2931//2931 2932//2932 -f 2922//2922 2921//2921 2933//2933 -f 2933//2933 2921//2921 2934//2934 -f 2933//2933 2934//2934 2935//2935 -f 2896//2896 2936//2936 2923//2923 -f 2923//2923 2936//2936 2937//2937 -f 2923//2923 2937//2937 2898//2898 -f 2898//2898 2937//2937 2938//2938 -f 2898//2898 2938//2938 2899//2899 -f 163//163 161//161 2890//2890 -f 2890//2890 161//161 159//159 -f 2890//2890 159//159 2939//2939 -f 2939//2939 159//159 157//157 -f 2939//2939 157//157 2906//2906 -f 2906//2906 157//157 155//155 -f 2906//2906 155//155 153//153 -f 153//153 757//757 759//759 -f 747//747 749//749 143//143 -f 143//143 749//749 751//751 -f 747//747 143//143 2887//2887 -f 2887//2887 143//143 141//141 -f 2887//2887 141//141 139//139 -f 2922//2922 2940//2940 2920//2920 -f 2920//2920 2940//2940 2941//2941 -f 2920//2920 2941//2941 2897//2897 -f 2897//2897 2941//2941 2942//2942 -f 2897//2897 2942//2942 2895//2895 -f 2943//2943 2944//2944 2945//2945 -f 2945//2945 2944//2944 2864//2864 -f 2945//2945 2864//2864 2946//2946 -f 2946//2946 2864//2864 2932//2932 -f 2943//2943 2947//2947 2944//2944 -f 2944//2944 2947//2947 2948//2948 -f 2944//2944 2948//2948 2949//2949 -f 2948//2948 2950//2950 2949//2949 -f 2949//2949 2950//2950 2951//2951 -f 2949//2949 2951//2951 2952//2952 -f 2952//2952 2951//2951 2953//2953 -f 153//153 151//151 757//757 -f 757//757 151//151 149//149 -f 757//757 149//149 755//755 -f 755//755 149//149 147//147 -f 755//755 147//147 753//753 -f 759//759 761//761 153//153 -f 153//153 761//761 763//763 -f 153//153 763//763 2906//2906 -f 2906//2906 763//763 765//765 -f 2906//2906 765//765 767//767 -f 753//753 147//147 751//751 -f 751//751 147//147 145//145 -f 751//751 145//145 143//143 -f 2954//2954 2955//2955 2956//2956 -f 2956//2956 2955//2955 2952//2952 -f 2956//2956 2952//2952 2957//2957 -f 2957//2957 2952//2952 2953//2953 -f 2954//2954 2958//2958 2955//2955 -f 2955//2955 2958//2958 2959//2959 -f 2955//2955 2959//2959 2960//2960 -f 2960//2960 2959//2959 2961//2961 -f 2960//2960 2961//2961 2934//2934 -f 2934//2934 2961//2961 2962//2962 -f 2934//2934 2962//2962 2935//2935 -f 77//77 79//79 2926//2926 -f 2844//2844 714//714 517//517 -f 541//541 2906//2906 543//543 -f 543//543 2906//2906 2844//2844 -f 543//543 2844//2844 530//530 -f 530//530 2844//2844 517//517 -f 273//273 646//646 272//272 -f 272//272 646//646 2875//2875 -f 272//272 2875//2875 2963//2963 -f 2963//2963 2875//2875 2964//2964 -f 2965//2965 2966//2966 2882//2882 -f 2966//2966 2967//2967 2882//2882 -f 2882//2882 2967//2967 2968//2968 -f 2882//2882 2968//2968 2875//2875 -f 2875//2875 2968//2968 2969//2969 -f 2875//2875 2969//2969 2964//2964 -f 2913//2913 2970//2970 2971//2971 -f 2913//2913 2971//2971 2882//2882 -f 2882//2882 2971//2971 2972//2972 -f 2882//2882 2972//2972 2973//2973 -f 2973//2973 2974//2974 2882//2882 -f 2882//2882 2974//2974 2975//2975 -f 2882//2882 2975//2975 2965//2965 -f 2970//2970 2913//2913 92//92 -f 92//92 2913//2913 2905//2905 -f 92//92 2905//2905 94//94 -f 2924//2924 88//88 2905//2905 -f 2905//2905 88//88 90//90 -f 2905//2905 90//90 94//94 -f 2926//2926 79//79 2925//2925 -f 79//79 81//81 2925//2925 -f 2925//2925 81//81 84//84 -f 2925//2925 84//84 2924//2924 -f 2924//2924 84//84 86//86 -f 2924//2924 86//86 88//88 -f 77//77 2926//2926 75//75 -f 75//75 2926//2926 2927//2927 -f 75//75 2927//2927 73//73 -f 73//73 2927//2927 2888//2888 -f 73//73 2888//2888 71//71 -f 71//71 2888//2888 69//69 -f 69//69 2888//2888 2889//2889 -f 69//69 2889//2889 67//67 -f 67//67 2889//2889 64//64 -f 64//64 2889//2889 2890//2890 -f 64//64 2890//2890 62//62 -f 62//62 2890//2890 60//60 -f 60//60 2890//2890 2939//2939 -f 60//60 2939//2939 58//58 -f 58//58 2939//2939 56//56 -f 56//56 2939//2939 2906//2906 -f 56//56 2906//2906 12//12 -f 12//12 2906//2906 541//541 -f 12//12 541//541 11//11 -f 355//355 363//363 2920//2920 -f 493//493 495//495 2853//2853 -f 2853//2853 495//495 2846//2846 -f 495//495 497//497 2846//2846 -f 2846//2846 497//497 513//513 -f 2846//2846 513//513 715//715 -f 715//715 513//513 514//514 -f 715//715 514//514 525//525 -f 493//493 2853//2853 491//491 -f 491//491 2853//2853 2854//2854 -f 491//491 2854//2854 489//489 -f 489//489 2854//2854 2855//2855 -f 489//489 2855//2855 486//486 -f 486//486 2855//2855 484//484 -f 484//484 2855//2855 2856//2856 -f 484//484 2856//2856 482//482 -f 482//482 2856//2856 480//480 -f 480//480 2856//2856 2857//2857 -f 480//480 2857//2857 478//478 -f 478//478 2857//2857 476//476 -f 476//476 2857//2857 2863//2863 -f 476//476 2863//2863 474//474 -f 474//474 2863//2863 472//472 -f 472//472 2863//2863 2864//2864 -f 472//472 2864//2864 470//470 -f 470//470 2864//2864 467//467 -f 467//467 2864//2864 2944//2944 -f 467//467 2944//2944 465//465 -f 465//465 2944//2944 463//463 -f 463//463 2944//2944 2949//2949 -f 463//463 2949//2949 461//461 -f 461//461 2949//2949 459//459 -f 459//459 2949//2949 2952//2952 -f 459//459 2952//2952 457//457 -f 457//457 2952//2952 455//455 -f 455//455 2952//2952 2955//2955 -f 455//455 2955//2955 453//453 -f 453//453 2955//2955 451//451 -f 451//451 2955//2955 2960//2960 -f 451//451 2960//2960 448//448 -f 448//448 2960//2960 636//636 -f 636//636 2960//2960 2934//2934 -f 636//636 2934//2934 378//378 -f 2920//2920 363//363 2921//2921 -f 363//363 361//361 2921//2921 -f 2921//2921 361//361 360//360 -f 2921//2921 360//360 2934//2934 -f 2934//2934 360//360 365//365 -f 2934//2934 365//365 378//378 -f 351//351 2897//2897 353//353 -f 353//353 2897//2897 2923//2923 -f 353//353 2923//2923 343//343 -f 351//351 350//350 2897//2897 -f 2897//2897 350//350 358//358 -f 2897//2897 358//358 2920//2920 -f 2920//2920 358//358 356//356 -f 2920//2920 356//356 355//355 -f 338//338 2898//2898 339//339 -f 339//339 2898//2898 2900//2900 -f 339//339 2900//2900 341//341 -f 338//338 347//347 2898//2898 -f 2898//2898 347//347 346//346 -f 2898//2898 346//346 2923//2923 -f 2923//2923 346//346 344//344 -f 2923//2923 344//344 343//343 -f 336//336 2873//2873 324//324 -f 324//324 2873//2873 2872//2872 -f 324//324 2872//2872 326//326 -f 336//336 335//335 2873//2873 -f 2873//2873 335//335 333//333 -f 2873//2873 333//333 2900//2900 -f 2900//2900 333//333 342//342 -f 2900//2900 342//342 341//341 -f 309//309 2852//2852 311//311 -f 311//311 2852//2852 2851//2851 -f 311//311 2851//2851 313//313 -f 309//309 331//331 2852//2852 -f 2852//2852 331//331 330//330 -f 2852//2852 330//330 2872//2872 -f 2872//2872 330//330 328//328 -f 2872//2872 328//328 326//326 -f 2849//2849 322//322 321//321 -f 2849//2849 321//321 2850//2850 -f 321//321 319//319 2850//2850 -f 2850//2850 319//319 317//317 -f 2850//2850 317//317 2851//2851 -f 2851//2851 317//317 315//315 -f 2851//2851 315//315 313//313 -f 2845//2845 306//306 2849//2849 -f 2849//2849 306//306 304//304 -f 2849//2849 304//304 322//322 -f 286//286 284//284 642//642 -f 642//642 284//284 282//282 -f 642//642 282//282 2845//2845 -f 2845//2845 282//282 307//307 -f 2845//2845 307//307 306//306 -f 2976//2976 2977//2977 2978//2978 -f 2979//2979 2980//2980 2981//2981 -f 55//55 54//54 2982//2982 -f 2830//2830 2836//2836 2983//2983 -f 2984//2984 2985//2985 2986//2986 -f 2987//2987 2988//2988 2989//2989 -f 2990//2990 2991//2991 2992//2992 -f 2993//2993 2994//2994 2995//2995 -f 2995//2995 2994//2994 2996//2996 -f 2995//2995 2996//2996 2997//2997 -f 2998//2998 2999//2999 3000//3000 -f 3001//3001 3002//3002 3003//3003 -f 3004//3004 3005//3005 3006//3006 -f 3006//3006 3005//3005 3007//3007 -f 3008//3008 3004//3004 3009//3009 -f 3010//3010 3011//3011 3012//3012 -f 3013//3013 3014//3014 3015//3015 -f 3015//3015 3014//3014 3016//3016 -f 3017//3017 3018//3018 2801//2801 -f 3019//3019 3020//3020 3018//3018 -f 3018//3018 3020//3020 3021//3021 -f 3018//3018 3021//3021 2801//2801 -f 3022//3022 3023//3023 3024//3024 -f 3024//3024 3023//3023 3019//3019 -f 3024//3024 3019//3019 3025//3025 -f 3022//3022 3024//3024 3026//3026 -f 3026//3026 3024//3024 3027//3027 -f 3026//3026 3027//3027 3028//3028 -f 3029//3029 3028//3028 3030//3030 -f 3030//3030 3028//3028 3031//3031 -f 3032//3032 3033//3033 3034//3034 -f 3034//3034 3033//3033 3035//3035 -f 3034//3034 3035//3035 3030//3030 -f 3030//3030 3035//3035 3036//3036 -f 3030//3030 3036//3036 3029//3029 -f 3037//3037 3038//3038 3032//3032 -f 3037//3037 3032//3032 3039//3039 -f 3040//3040 3041//3041 3042//3042 -f 3042//3042 3043//3043 3040//3040 -f 3040//3040 3043//3043 3044//3044 -f 3040//3040 3044//3044 3037//3037 -f 3037//3037 3044//3044 3045//3045 -f 3037//3037 3045//3045 3038//3038 -f 3046//3046 3047//3047 3048//3048 -f 3048//3048 3047//3047 3049//3049 -f 3048//3048 3049//3049 3041//3041 -f 3041//3041 3049//3049 3050//3050 -f 3041//3041 3050//3050 3042//3042 -f 3046//3046 3048//3048 3051//3051 -f 3051//3051 3048//3048 3052//3052 -f 3051//3051 3052//3052 3053//3053 -f 3053//3053 3052//3052 3054//3054 -f 3053//3053 3054//3054 3055//3055 -f 2991//2991 3056//3056 2992//2992 -f 2992//2992 3056//3056 3057//3057 -f 2992//2992 3057//3057 3054//3054 -f 3054//3054 3057//3057 3058//3058 -f 3054//3054 3058//3058 3055//3055 -f 2992//2992 3059//3059 2990//2990 -f 2990//2990 3059//3059 2989//2989 -f 2990//2990 2989//2989 3060//3060 -f 3060//3060 2989//2989 2988//2988 -f 574//574 581//581 3061//3061 -f 3061//3061 581//581 580//580 -f 3061//3061 580//580 2983//2983 -f 2983//2983 580//580 579//579 -f 2983//2983 579//579 2830//2830 -f 574//574 3061//3061 575//575 -f 575//575 3061//3061 3062//3062 -f 575//575 3062//3062 576//576 -f 576//576 3062//3062 3063//3063 -f 576//576 3063//3063 577//577 -f 577//577 3063//3063 578//578 -f 578//578 3063//3063 3064//3064 -f 578//578 3064//3064 572//572 -f 572//572 3064//3064 570//570 -f 570//570 3064//3064 3065//3065 -f 570//570 3065//3065 565//565 -f 3066//3066 39//39 6//6 -f 565//565 3065//3065 566//566 -f 566//566 3065//3065 3067//3067 -f 566//566 3067//3067 568//568 -f 568//568 3067//3067 3066//3066 -f 568//568 3066//3066 569//569 -f 569//569 3066//3066 6//6 -f 569//569 6//6 5//5 -f 3068//3068 3069//3069 3070//3070 -f 3070//3070 3069//3069 3071//3071 -f 3070//3070 3071//3071 3072//3072 -f 3073//3073 3074//3074 3075//3075 -f 3075//3075 3074//3074 3076//3076 -f 3075//3075 3076//3076 3077//3077 -f 2979//2979 2981//2981 3078//3078 -f 3079//3079 3080//3080 3081//3081 -f 3082//3082 3083//3083 3084//3084 -f 3079//3079 3081//3081 3084//3084 -f 3084//3084 3081//3081 3085//3085 -f 3084//3084 3085//3085 3082//3082 -f 3086//3086 3087//3087 3088//3088 -f 3088//3088 3087//3087 3089//3089 -f 3088//3088 3089//3089 3082//3082 -f 3082//3082 3089//3089 3090//3090 -f 3082//3082 3090//3090 3083//3083 -f 3086//3086 3088//3088 3091//3091 -f 3091//3091 3088//3088 3092//3092 -f 3091//3091 3092//3092 3093//3093 -f 3093//3093 3092//3092 3094//3094 -f 3093//3093 3094//3094 3095//3095 -f 3096//3096 3097//3097 3094//3094 -f 3094//3094 3097//3097 3098//3098 -f 3094//3094 3098//3098 3095//3095 -f 3099//3099 3100//3100 3101//3101 -f 3101//3101 3100//3100 3102//3102 -f 3101//3101 3102//3102 3096//3096 -f 3096//3096 3102//3102 3103//3103 -f 3096//3096 3103//3103 3097//3097 -f 3099//3099 3101//3101 3104//3104 -f 3104//3104 3101//3101 3105//3105 -f 3104//3104 3105//3105 3106//3106 -f 2978//2978 2977//2977 3107//3107 -f 3107//3107 2977//2977 3108//3108 -f 3107//3107 3108//3108 3109//3109 -f 3110//3110 3111//3111 3112//3112 -f 3112//3112 3111//3111 3113//3113 -f 3112//3112 3113//3113 3114//3114 -f 3114//3114 3113//3113 3115//3115 -f 3116//3116 3117//3117 3118//3118 -f 3118//3118 3117//3117 3119//3119 -f 3119//3119 3117//3117 787//787 -f 787//787 3117//3117 2995//2995 -f 787//787 2995//2995 788//788 -f 788//788 2995//2995 2997//2997 -f 788//788 2997//2997 790//790 -f 257//257 3013//3013 2790//2790 -f 2790//2790 3013//3013 3015//3015 -f 2790//2790 3015//3015 2799//2799 -f 2799//2799 3015//3015 3120//3120 -f 2801//2801 2803//2803 3017//3017 -f 3017//3017 2803//2803 2805//2805 -f 3017//3017 2805//2805 3120//3120 -f 3120//3120 2805//2805 2800//2800 -f 3120//3120 2800//2800 2799//2799 -f 3110//3110 3112//3112 3116//3116 -f 3116//3116 3112//3112 3121//3121 -f 3116//3116 3121//3121 3117//3117 -f 3117//3117 3121//3121 2998//2998 -f 3117//3117 2998//2998 2995//2995 -f 2995//2995 2998//2998 3000//3000 -f 2995//2995 3000//3000 2993//2993 -f 3019//3019 3018//3018 3025//3025 -f 3025//3025 3018//3018 3017//3017 -f 3025//3025 3017//3017 3122//3122 -f 3122//3122 3017//3017 3120//3120 -f 3122//3122 3120//3120 3123//3123 -f 3123//3123 3120//3120 3015//3015 -f 3123//3123 3015//3015 3124//3124 -f 3124//3124 3015//3015 3016//3016 -f 3124//3124 3016//3016 3125//3125 -f 3109//3109 3108//3108 3115//3115 -f 3115//3115 3108//3108 3126//3126 -f 3115//3115 3126//3126 3114//3114 -f 3114//3114 3126//3126 3127//3127 -f 3114//3114 3127//3127 3112//3112 -f 3112//3112 3127//3127 3128//3128 -f 3112//3112 3128//3128 3121//3121 -f 3121//3121 3128//3128 3129//3129 -f 3121//3121 3129//3129 2998//2998 -f 2998//2998 3129//3129 3001//3001 -f 2998//2998 3001//3001 2999//2999 -f 2999//2999 3001//3001 3003//3003 -f 2999//2999 3003//3003 3000//3000 -f 3028//3028 3027//3027 3031//3031 -f 3031//3031 3027//3027 3024//3024 -f 3031//3031 3024//3024 3130//3130 -f 3130//3130 3024//3024 3025//3025 -f 3130//3130 3025//3025 3131//3131 -f 3131//3131 3025//3025 3122//3122 -f 3131//3131 3122//3122 3132//3132 -f 3132//3132 3122//3122 3123//3123 -f 3132//3132 3123//3123 3010//3010 -f 3010//3010 3123//3123 3124//3124 -f 3010//3010 3124//3124 3011//3011 -f 3011//3011 3124//3124 3125//3125 -f 3011//3011 3125//3125 3012//3012 -f 3106//3106 3105//3105 2976//2976 -f 2976//2976 3105//3105 3133//3133 -f 2976//2976 3133//3133 2977//2977 -f 2977//2977 3133//3133 3134//3134 -f 2977//2977 3134//3134 3108//3108 -f 3108//3108 3134//3134 3135//3135 -f 3108//3108 3135//3135 3126//3126 -f 3126//3126 3135//3135 3136//3136 -f 3126//3126 3136//3136 3127//3127 -f 3127//3127 3136//3136 3137//3137 -f 3127//3127 3137//3137 3128//3128 -f 3128//3128 3137//3137 3138//3138 -f 3128//3128 3138//3138 3129//3129 -f 3129//3129 3138//3138 3006//3006 -f 3129//3129 3006//3006 3001//3001 -f 3001//3001 3006//3006 3007//3007 -f 3001//3001 3007//3007 3002//3002 -f 3032//3032 3034//3034 3039//3039 -f 3039//3039 3034//3034 3030//3030 -f 3039//3039 3030//3030 3139//3139 -f 3139//3139 3030//3030 3031//3031 -f 3139//3139 3031//3031 3140//3140 -f 3140//3140 3031//3031 3130//3130 -f 3140//3140 3130//3130 3141//3141 -f 3141//3141 3130//3130 3131//3131 -f 3141//3141 3131//3131 3142//3142 -f 3142//3142 3131//3131 3132//3132 -f 3142//3142 3132//3132 3143//3143 -f 3143//3143 3132//3132 3010//3010 -f 3143//3143 3010//3010 3009//3009 -f 3009//3009 3010//3010 3012//3012 -f 3009//3009 3012//3012 3008//3008 -f 3004//3004 3006//3006 3009//3009 -f 3009//3009 3006//3006 3138//3138 -f 3009//3009 3138//3138 3143//3143 -f 3143//3143 3138//3138 3137//3137 -f 3143//3143 3137//3137 3142//3142 -f 3142//3142 3137//3137 3136//3136 -f 3142//3142 3136//3136 3141//3141 -f 3141//3141 3136//3136 3135//3135 -f 3141//3141 3135//3135 3140//3140 -f 3140//3140 3135//3135 3134//3134 -f 3140//3140 3134//3134 3139//3139 -f 3139//3139 3134//3134 3133//3133 -f 3139//3139 3133//3133 3039//3039 -f 3039//3039 3133//3133 3105//3105 -f 3039//3039 3105//3105 3037//3037 -f 3037//3037 3105//3105 3101//3101 -f 3037//3037 3101//3101 3040//3040 -f 3040//3040 3101//3101 3096//3096 -f 3040//3040 3096//3096 3041//3041 -f 3041//3041 3096//3096 3094//3094 -f 3041//3041 3094//3094 3048//3048 -f 3048//3048 3094//3094 3092//3092 -f 3048//3048 3092//3092 3052//3052 -f 3052//3052 3092//3092 3088//3088 -f 3052//3052 3088//3088 3054//3054 -f 3054//3054 3088//3088 3082//3082 -f 3054//3054 3082//3082 2992//2992 -f 2992//2992 3082//3082 3085//3085 -f 2992//2992 3085//3085 3059//3059 -f 3080//3080 3078//3078 3081//3081 -f 3081//3081 3078//3078 2981//2981 -f 3081//3081 2981//2981 3085//3085 -f 3085//3085 2981//2981 3144//3144 -f 3085//3085 3144//3144 3059//3059 -f 3059//3059 3144//3144 3145//3145 -f 3059//3059 3145//3145 2989//2989 -f 2989//2989 3145//3145 2986//2986 -f 2989//2989 2986//2986 2987//2987 -f 2987//2987 2986//2986 2985//2985 -f 2980//2980 3074//3074 2981//2981 -f 2981//2981 3074//3074 3073//3073 -f 2981//2981 3073//3073 3144//3144 -f 3144//3144 3073//3073 3146//3146 -f 3144//3144 3146//3146 3145//3145 -f 3145//3145 3146//3146 3147//3147 -f 3145//3145 3147//3147 2986//2986 -f 2986//2986 3147//3147 3148//3148 -f 2986//2986 3148//3148 2984//2984 -f 2984//2984 3148//3148 3149//3149 -f 2984//2984 3149//3149 3150//3150 -f 3150//3150 3149//3149 3151//3151 -f 3077//3077 3069//3069 3075//3075 -f 3075//3075 3069//3069 3068//3068 -f 3075//3075 3068//3068 3073//3073 -f 3073//3073 3068//3068 3152//3152 -f 3073//3073 3152//3152 3146//3146 -f 3146//3146 3152//3152 3153//3153 -f 3146//3146 3153//3153 3147//3147 -f 3147//3147 3153//3153 3154//3154 -f 3147//3147 3154//3154 3148//3148 -f 3148//3148 3154//3154 3155//3155 -f 3148//3148 3155//3155 3149//3149 -f 3149//3149 3155//3155 3156//3156 -f 3149//3149 3156//3156 3151//3151 -f 3151//3151 3156//3156 3157//3157 -f 3151//3151 3157//3157 3158//3158 -f 3158//3158 3157//3157 2843//2843 -f 3072//3072 55//55 3070//3070 -f 3070//3070 55//55 2982//2982 -f 3070//3070 2982//2982 3068//3068 -f 3068//3068 2982//2982 3159//3159 -f 3068//3068 3159//3159 3152//3152 -f 3152//3152 3159//3159 3160//3160 -f 3152//3152 3160//3160 3153//3153 -f 3153//3153 3160//3160 3161//3161 -f 3153//3153 3161//3161 3154//3154 -f 3154//3154 3161//3161 3162//3162 -f 3154//3154 3162//3162 3155//3155 -f 3155//3155 3162//3162 3163//3163 -f 3155//3155 3163//3163 3156//3156 -f 3156//3156 3163//3163 3164//3164 -f 3156//3156 3164//3164 3157//3157 -f 3157//3157 3164//3164 3165//3165 -f 3157//3157 3165//3165 2843//2843 -f 2843//2843 3165//3165 2841//2841 -f 2838//2838 2841//2841 3166//3166 -f 3166//3166 2841//2841 3165//3165 -f 3166//3166 3165//3165 3167//3167 -f 3167//3167 3165//3165 3164//3164 -f 3167//3167 3164//3164 3168//3168 -f 3168//3168 3164//3164 3163//3163 -f 3168//3168 3163//3163 3169//3169 -f 3169//3169 3163//3163 3162//3162 -f 3169//3169 3162//3162 3170//3170 -f 3170//3170 3162//3162 3161//3161 -f 3170//3170 3161//3161 3171//3171 -f 3171//3171 3161//3161 3160//3160 -f 3171//3171 3160//3160 3172//3172 -f 3172//3172 3160//3160 3159//3159 -f 3172//3172 3159//3159 3173//3173 -f 3173//3173 3159//3159 2982//2982 -f 3173//3173 2982//2982 3//3 -f 3//3 2982//2982 54//54 -f 2836//2836 2838//2838 2983//2983 -f 2983//2983 2838//2838 3166//3166 -f 2983//2983 3166//3166 3061//3061 -f 3061//3061 3166//3166 3167//3167 -f 3061//3061 3167//3167 3062//3062 -f 3062//3062 3167//3167 3168//3168 -f 3062//3062 3168//3168 3063//3063 -f 3063//3063 3168//3168 3169//3169 -f 3063//3063 3169//3169 3064//3064 -f 3064//3064 3169//3169 3170//3170 -f 3064//3064 3170//3170 3065//3065 -f 3065//3065 3170//3170 3171//3171 -f 3065//3065 3171//3171 3067//3067 -f 3067//3067 3171//3171 3172//3172 -f 3067//3067 3172//3172 3066//3066 -f 3066//3066 3172//3172 3173//3173 -f 3066//3066 3173//3173 39//39 -f 39//39 3173//3173 3//3 -f 3174//3174 3175//3175 3176//3176 -f 3177//3177 3178//3178 3179//3179 -f 3007//3007 3005//3005 3180//3180 -f 3181//3181 3182//3182 3183//3183 -f 3184//3184 3185//3185 3186//3186 -f 3187//3187 3188//3188 3189//3189 -f 3190//3190 2971//2971 2970//2970 -f 3191//3191 2973//2973 2972//2972 -f 2965//2965 2975//2975 3192//3192 -f 3192//3192 2975//2975 2974//2974 -f 3193//3193 2968//2968 2967//2967 -f 2963//2963 2964//2964 3194//3194 -f 3194//3194 2964//2964 2969//2969 -f 3195//3195 3196//3196 436//436 -f 3197//3197 3198//3198 3196//3196 -f 3196//3196 3198//3198 3199//3199 -f 3196//3196 3199//3199 436//436 -f 3200//3200 3201//3201 3202//3202 -f 3202//3202 3201//3201 3197//3197 -f 3202//3202 3197//3197 3203//3203 -f 3200//3200 3202//3202 3204//3204 -f 3204//3204 3202//3202 3205//3205 -f 3204//3204 3205//3205 3206//3206 -f 3207//3207 3206//3206 3208//3208 -f 3208//3208 3206//3206 3209//3209 -f 3210//3210 3211//3211 3212//3212 -f 3212//3212 3211//3211 3213//3213 -f 3212//3212 3213//3213 3208//3208 -f 3208//3208 3213//3213 3214//3214 -f 3208//3208 3214//3214 3207//3207 -f 3215//3215 3216//3216 3210//3210 -f 3215//3215 3210//3210 3217//3217 -f 3218//3218 3219//3219 3220//3220 -f 3220//3220 3221//3221 3218//3218 -f 3218//3218 3221//3221 3222//3222 -f 3218//3218 3222//3222 3215//3215 -f 3215//3215 3222//3222 3223//3223 -f 3215//3215 3223//3223 3216//3216 -f 3224//3224 3225//3225 3226//3226 -f 3226//3226 3225//3225 3227//3227 -f 3226//3226 3227//3227 3219//3219 -f 3219//3219 3227//3227 3228//3228 -f 3219//3219 3228//3228 3220//3220 -f 3224//3224 3226//3226 3229//3229 -f 3229//3229 3226//3226 3230//3230 -f 3229//3229 3230//3230 3231//3231 -f 3231//3231 3230//3230 3232//3232 -f 3231//3231 3232//3232 3233//3233 -f 3188//3188 3234//3234 3189//3189 -f 3189//3189 3234//3234 3235//3235 -f 3189//3189 3235//3235 3232//3232 -f 3232//3232 3235//3235 3236//3236 -f 3232//3232 3236//3236 3233//3233 -f 3189//3189 3237//3237 3187//3187 -f 3187//3187 3237//3237 3186//3186 -f 3187//3187 3186//3186 3238//3238 -f 3238//3238 3186//3186 3185//3185 -f 3013//3013 257//257 256//256 -f 3013//3013 256//256 3014//3014 -f 3239//3239 3125//3125 3240//3240 -f 3240//3240 3125//3125 3016//3016 -f 3240//3240 3016//3016 3241//3241 -f 3241//3241 3016//3016 3014//3014 -f 3241//3241 3014//3014 3242//3242 -f 3242//3242 3014//3014 256//256 -f 3242//3242 256//256 426//426 -f 3004//3004 3008//3008 3239//3239 -f 3239//3239 3008//3008 3012//3012 -f 3239//3239 3012//3012 3125//3125 -f 3180//3180 3005//3005 3243//3243 -f 3007//3007 3180//3180 3002//3002 -f 3002//3002 3180//3180 3244//3244 -f 3002//3002 3244//3244 3003//3003 -f 3003//3003 3244//3244 3245//3245 -f 3003//3003 3245//3245 3000//3000 -f 2997//2997 2996//2996 3246//3246 -f 3246//3246 2996//2996 2994//2994 -f 3246//3246 2994//2994 3245//3245 -f 3245//3245 2994//2994 2993//2993 -f 3245//3245 2993//2993 3000//3000 -f 793//793 792//792 3247//3247 -f 3247//3247 792//792 790//790 -f 3248//3248 3249//3249 3250//3250 -f 3250//3250 3249//3249 3251//3251 -f 3250//3250 3251//3251 3252//3252 -f 3253//3253 3254//3254 3255//3255 -f 3255//3255 3254//3254 3256//3256 -f 3255//3255 3256//3256 3257//3257 -f 3177//3177 3179//3179 3258//3258 -f 3259//3259 3260//3260 3261//3261 -f 3262//3262 3263//3263 3264//3264 -f 3259//3259 3261//3261 3264//3264 -f 3264//3264 3261//3261 3265//3265 -f 3264//3264 3265//3265 3262//3262 -f 3266//3266 3267//3267 3268//3268 -f 3268//3268 3267//3267 3269//3269 -f 3268//3268 3269//3269 3262//3262 -f 3262//3262 3269//3269 3270//3270 -f 3262//3262 3270//3270 3263//3263 -f 3266//3266 3268//3268 3271//3271 -f 3271//3271 3268//3268 3272//3272 -f 3271//3271 3272//3272 3273//3273 -f 3273//3273 3272//3272 3274//3274 -f 3273//3273 3274//3274 3275//3275 -f 3276//3276 3277//3277 3274//3274 -f 3274//3274 3277//3277 3278//3278 -f 3274//3274 3278//3278 3275//3275 -f 3279//3279 3280//3280 3281//3281 -f 3281//3281 3280//3280 3282//3282 -f 3281//3281 3282//3282 3276//3276 -f 3276//3276 3282//3282 3283//3283 -f 3276//3276 3283//3283 3277//3277 -f 3279//3279 3281//3281 3284//3284 -f 3284//3284 3281//3281 3285//3285 -f 3284//3284 3285//3285 3286//3286 -f 3176//3176 3175//3175 3287//3287 -f 3287//3287 3175//3175 3288//3288 -f 3287//3287 3288//3288 3289//3289 -f 3290//3290 3291//3291 3292//3292 -f 3292//3292 3291//3291 3293//3293 -f 3292//3292 3293//3293 3294//3294 -f 3295//3295 3296//3296 3297//3297 -f 3297//3297 3296//3296 3298//3298 -f 3298//3298 3296//3296 105//105 -f 105//105 3296//3296 3299//3299 -f 105//105 3299//3299 103//103 -f 91//91 100//100 3300//3300 -f 3300//3300 100//100 98//98 -f 3300//3300 98//98 3301//3301 -f 272//272 2963//2963 269//269 -f 269//269 2963//2963 3194//3194 -f 269//269 3194//3194 434//434 -f 434//434 3194//3194 3302//3302 -f 3301//3301 98//98 3299//3299 -f 3299//3299 98//98 97//97 -f 3299//3299 97//97 103//103 -f 436//436 438//438 3195//3195 -f 3195//3195 438//438 440//440 -f 3195//3195 440//440 3302//3302 -f 3302//3302 440//440 435//435 -f 3302//3302 435//435 434//434 -f 92//92 91//91 2970//2970 -f 2970//2970 91//91 3300//3300 -f 2970//2970 3300//3300 3190//3190 -f 3190//3190 3300//3300 3301//3301 -f 3190//3190 3301//3301 3303//3303 -f 3303//3303 3301//3301 3299//3299 -f 3303//3303 3299//3299 3304//3304 -f 3304//3304 3299//3299 3296//3296 -f 3304//3304 3296//3296 3305//3305 -f 3305//3305 3296//3296 3295//3295 -f 3305//3305 3295//3295 3293//3293 -f 3293//3293 3295//3295 3306//3306 -f 3293//3293 3306//3306 3294//3294 -f 3197//3197 3196//3196 3203//3203 -f 3203//3203 3196//3196 3195//3195 -f 3203//3203 3195//3195 3307//3307 -f 3307//3307 3195//3195 3302//3302 -f 3307//3307 3302//3302 3308//3308 -f 3308//3308 3302//3302 3194//3194 -f 3308//3308 3194//3194 3193//3193 -f 3193//3193 3194//3194 2969//2969 -f 3193//3193 2969//2969 2968//2968 -f 3289//3289 3288//3288 3290//3290 -f 3290//3290 3288//3288 3309//3309 -f 3290//3290 3309//3309 3291//3291 -f 3291//3291 3309//3309 3310//3310 -f 3291//3291 3310//3310 3293//3293 -f 3293//3293 3310//3310 3311//3311 -f 3293//3293 3311//3311 3305//3305 -f 3305//3305 3311//3311 3312//3312 -f 3305//3305 3312//3312 3304//3304 -f 3304//3304 3312//3312 3313//3313 -f 3304//3304 3313//3313 3303//3303 -f 3303//3303 3313//3313 3191//3191 -f 3303//3303 3191//3191 3190//3190 -f 3190//3190 3191//3191 2972//2972 -f 3190//3190 2972//2972 2971//2971 -f 3206//3206 3205//3205 3209//3209 -f 3209//3209 3205//3205 3202//3202 -f 3209//3209 3202//3202 3314//3314 -f 3314//3314 3202//3202 3203//3203 -f 3314//3314 3203//3203 3315//3315 -f 3315//3315 3203//3203 3307//3307 -f 3315//3315 3307//3307 3316//3316 -f 3316//3316 3307//3307 3308//3308 -f 3316//3316 3308//3308 3317//3317 -f 3317//3317 3308//3308 3193//3193 -f 3317//3317 3193//3193 3318//3318 -f 3318//3318 3193//3193 2967//2967 -f 3318//3318 2967//2967 2966//2966 -f 3286//3286 3285//3285 3174//3174 -f 3174//3174 3285//3285 3319//3319 -f 3174//3174 3319//3319 3175//3175 -f 3175//3175 3319//3319 3320//3320 -f 3175//3175 3320//3320 3288//3288 -f 3288//3288 3320//3320 3321//3321 -f 3288//3288 3321//3321 3309//3309 -f 3309//3309 3321//3321 3322//3322 -f 3309//3309 3322//3322 3310//3310 -f 3310//3310 3322//3322 3323//3323 -f 3310//3310 3323//3323 3311//3311 -f 3311//3311 3323//3323 3324//3324 -f 3311//3311 3324//3324 3312//3312 -f 3312//3312 3324//3324 3325//3325 -f 3312//3312 3325//3325 3313//3313 -f 3313//3313 3325//3325 3192//3192 -f 3313//3313 3192//3192 3191//3191 -f 3191//3191 3192//3192 2974//2974 -f 3191//3191 2974//2974 2973//2973 -f 3210//3210 3212//3212 3217//3217 -f 3217//3217 3212//3212 3208//3208 -f 3217//3217 3208//3208 3326//3326 -f 3326//3326 3208//3208 3209//3209 -f 3326//3326 3209//3209 3327//3327 -f 3327//3327 3209//3209 3314//3314 -f 3327//3327 3314//3314 3328//3328 -f 3328//3328 3314//3314 3315//3315 -f 3328//3328 3315//3315 3329//3329 -f 3329//3329 3315//3315 3316//3316 -f 3329//3329 3316//3316 3330//3330 -f 3330//3330 3316//3316 3317//3317 -f 3330//3330 3317//3317 3331//3331 -f 3331//3331 3317//3317 3318//3318 -f 3331//3331 3318//3318 3332//3332 -f 3332//3332 3318//3318 2966//2966 -f 3332//3332 2966//2966 2965//2965 -f 2965//2965 3192//3192 3332//3332 -f 3332//3332 3192//3192 3325//3325 -f 3332//3332 3325//3325 3331//3331 -f 3331//3331 3325//3325 3324//3324 -f 3331//3331 3324//3324 3330//3330 -f 3330//3330 3324//3324 3323//3323 -f 3330//3330 3323//3323 3329//3329 -f 3329//3329 3323//3323 3322//3322 -f 3329//3329 3322//3322 3328//3328 -f 3328//3328 3322//3322 3321//3321 -f 3328//3328 3321//3321 3327//3327 -f 3327//3327 3321//3321 3320//3320 -f 3327//3327 3320//3320 3326//3326 -f 3326//3326 3320//3320 3319//3319 -f 3326//3326 3319//3319 3217//3217 -f 3217//3217 3319//3319 3285//3285 -f 3217//3217 3285//3285 3215//3215 -f 3215//3215 3285//3285 3281//3281 -f 3215//3215 3281//3281 3218//3218 -f 3218//3218 3281//3281 3276//3276 -f 3218//3218 3276//3276 3219//3219 -f 3219//3219 3276//3276 3274//3274 -f 3219//3219 3274//3274 3226//3226 -f 3226//3226 3274//3274 3272//3272 -f 3226//3226 3272//3272 3230//3230 -f 3230//3230 3272//3272 3268//3268 -f 3230//3230 3268//3268 3232//3232 -f 3232//3232 3268//3268 3262//3262 -f 3232//3232 3262//3262 3189//3189 -f 3189//3189 3262//3262 3265//3265 -f 3189//3189 3265//3265 3237//3237 -f 3260//3260 3258//3258 3261//3261 -f 3261//3261 3258//3258 3179//3179 -f 3261//3261 3179//3179 3265//3265 -f 3265//3265 3179//3179 3333//3333 -f 3265//3265 3333//3333 3237//3237 -f 3237//3237 3333//3333 3334//3334 -f 3237//3237 3334//3334 3186//3186 -f 3186//3186 3334//3334 3183//3183 -f 3186//3186 3183//3183 3184//3184 -f 3184//3184 3183//3183 3182//3182 -f 3178//3178 3254//3254 3179//3179 -f 3179//3179 3254//3254 3253//3253 -f 3179//3179 3253//3253 3333//3333 -f 3333//3333 3253//3253 3335//3335 -f 3333//3333 3335//3335 3334//3334 -f 3334//3334 3335//3335 3336//3336 -f 3334//3334 3336//3336 3183//3183 -f 3183//3183 3336//3336 3337//3337 -f 3183//3183 3337//3337 3181//3181 -f 3181//3181 3337//3337 3338//3338 -f 3181//3181 3338//3338 3339//3339 -f 3339//3339 3338//3338 3340//3340 -f 3257//3257 3249//3249 3255//3255 -f 3255//3255 3249//3249 3248//3248 -f 3255//3255 3248//3248 3253//3253 -f 3253//3253 3248//3248 3341//3341 -f 3253//3253 3341//3341 3335//3335 -f 3335//3335 3341//3341 3342//3342 -f 3335//3335 3342//3342 3336//3336 -f 3336//3336 3342//3342 3343//3343 -f 3336//3336 3343//3343 3337//3337 -f 3337//3337 3343//3343 3344//3344 -f 3337//3337 3344//3344 3338//3338 -f 3338//3338 3344//3344 3345//3345 -f 3338//3338 3345//3345 3340//3340 -f 3340//3340 3345//3345 3346//3346 -f 3340//3340 3346//3346 3347//3347 -f 3347//3347 3346//3346 433//433 -f 3252//3252 793//793 3250//3250 -f 3250//3250 793//793 3247//3247 -f 3250//3250 3247//3247 3248//3248 -f 3248//3248 3247//3247 3348//3348 -f 3248//3248 3348//3348 3341//3341 -f 3341//3341 3348//3348 3349//3349 -f 3341//3341 3349//3349 3342//3342 -f 3342//3342 3349//3349 3350//3350 -f 3342//3342 3350//3350 3343//3343 -f 3343//3343 3350//3350 3351//3351 -f 3343//3343 3351//3351 3344//3344 -f 3344//3344 3351//3351 3352//3352 -f 3344//3344 3352//3352 3345//3345 -f 3345//3345 3352//3352 3353//3353 -f 3345//3345 3353//3353 3346//3346 -f 3346//3346 3353//3353 3354//3354 -f 3346//3346 3354//3354 433//433 -f 433//433 3354//3354 431//431 -f 428//428 431//431 3355//3355 -f 3355//3355 431//431 3354//3354 -f 3355//3355 3354//3354 3356//3356 -f 3356//3356 3354//3354 3353//3353 -f 3356//3356 3353//3353 3357//3357 -f 3357//3357 3353//3353 3352//3352 -f 3357//3357 3352//3352 3243//3243 -f 3243//3243 3352//3352 3351//3351 -f 3243//3243 3351//3351 3180//3180 -f 3180//3180 3351//3351 3350//3350 -f 3180//3180 3350//3350 3244//3244 -f 3244//3244 3350//3350 3349//3349 -f 3244//3244 3349//3349 3245//3245 -f 3245//3245 3349//3349 3348//3348 -f 3245//3245 3348//3348 3246//3246 -f 3246//3246 3348//3348 3247//3247 -f 3246//3246 3247//3247 2997//2997 -f 2997//2997 3247//3247 790//790 -f 426//426 428//428 3242//3242 -f 3242//3242 428//428 3355//3355 -f 3242//3242 3355//3355 3241//3241 -f 3241//3241 3355//3355 3356//3356 -f 3241//3241 3356//3356 3240//3240 -f 3240//3240 3356//3356 3357//3357 -f 3240//3240 3357//3357 3239//3239 -f 3239//3239 3357//3357 3243//3243 -f 3239//3239 3243//3243 3004//3004 -f 3004//3004 3243//3243 3005//3005 -f 3358//3358 3071//3071 3069//3069 -f 3359//3359 3360//3360 3361//3361 -f 3362//3362 3363//3363 3364//3364 -f 3365//3365 3366//3366 3367//3367 -f 3368//3368 3369//3369 3370//3370 -f 3371//3371 3372//3372 3373//3373 -f 3374//3374 3375//3375 3376//3376 -f 3375//3375 1590//1590 1588//1588 -f 3374//3374 3376//3376 3377//3377 -f 3378//3378 3379//3379 3380//3380 -f 3379//3379 3378//3378 3372//3372 -f 3368//3368 3370//3370 3366//3366 -f 3381//3381 3382//3382 3365//3365 -f 3362//3362 3364//3364 3360//3360 -f 3359//3359 3361//3361 3383//3383 -f 3384//3384 3116//3116 3385//3385 -f 3385//3385 3116//3116 3118//3118 -f 3385//3385 3118//3118 3383//3383 -f 3383//3383 3118//3118 3119//3119 -f 3383//3383 3119//3119 787//787 -f 3386//3386 3113//3113 3387//3387 -f 3387//3387 3113//3113 3111//3111 -f 3387//3387 3111//3111 3384//3384 -f 3384//3384 3111//3111 3110//3110 -f 3384//3384 3110//3110 3116//3116 -f 3388//3388 2978//2978 3389//3389 -f 3389//3389 2978//2978 3107//3107 -f 3389//3389 3107//3107 3390//3390 -f 3390//3390 3107//3107 3109//3109 -f 3390//3390 3109//3109 3386//3386 -f 3386//3386 3109//3109 3115//3115 -f 3386//3386 3115//3115 3113//3113 -f 3391//3391 3100//3100 3392//3392 -f 3392//3392 3100//3100 3099//3099 -f 3392//3392 3099//3099 3393//3393 -f 3393//3393 3099//3099 3104//3104 -f 3393//3393 3104//3104 3394//3394 -f 3394//3394 3104//3104 3106//3106 -f 3394//3394 3106//3106 3388//3388 -f 3388//3388 3106//3106 2976//2976 -f 3388//3388 2976//2976 2978//2978 -f 3395//3395 3097//3097 3396//3396 -f 3396//3396 3097//3097 3103//3103 -f 3396//3396 3103//3103 3391//3391 -f 3391//3391 3103//3103 3102//3102 -f 3391//3391 3102//3102 3100//3100 -f 3093//3093 3095//3095 3395//3395 -f 3395//3395 3095//3095 3098//3098 -f 3395//3395 3098//3098 3097//3097 -f 3395//3395 3397//3397 3093//3093 -f 3093//3093 3397//3397 3398//3398 -f 3093//3093 3398//3398 3091//3091 -f 3091//3091 3398//3398 3399//3399 -f 3083//3083 3090//3090 3400//3400 -f 3400//3400 3090//3090 3089//3089 -f 3400//3400 3089//3089 3401//3401 -f 3401//3401 3089//3089 3087//3087 -f 3401//3401 3087//3087 3399//3399 -f 3399//3399 3087//3087 3086//3086 -f 3399//3399 3086//3086 3091//3091 -f 3083//3083 3400//3400 3084//3084 -f 3084//3084 3400//3400 3402//3402 -f 3084//3084 3402//3402 3079//3079 -f 3079//3079 3402//3402 3403//3403 -f 3079//3079 3403//3403 3080//3080 -f 3077//3077 3076//3076 3404//3404 -f 3404//3404 3076//3076 3074//3074 -f 3404//3404 3074//3074 3405//3405 -f 3405//3405 3074//3074 2980//2980 -f 3405//3405 2980//2980 3406//3406 -f 3406//3406 2980//2980 2979//2979 -f 3406//3406 2979//2979 3403//3403 -f 3403//3403 2979//2979 3078//3078 -f 3403//3403 3078//3078 3080//3080 -f 3375//3375 1588//1588 3376//3376 -f 3376//3376 1588//1588 1587//1587 -f 3376//3376 1587//1587 3407//3407 -f 3407//3407 1587//1587 1580//1580 -f 3407//3407 1580//1580 3408//3408 -f 3408//3408 1580//1580 1579//1579 -f 3408//3408 1579//1579 3409//3409 -f 3409//3409 1579//1579 1578//1578 -f 3409//3409 1578//1578 3410//3410 -f 3410//3410 1578//1578 1572//1572 -f 3410//3410 1572//1572 3411//3411 -f 3411//3411 1572//1572 1571//1571 -f 3411//3411 1571//1571 3412//3412 -f 3412//3412 1571//1571 1570//1570 -f 3412//3412 1570//1570 3413//3413 -f 3413//3413 1570//1570 1569//1569 -f 3413//3413 1569//1569 3414//3414 -f 3414//3414 1569//1569 1568//1568 -f 3414//3414 1568//1568 3415//3415 -f 3415//3415 1568//1568 1567//1567 -f 3415//3415 1567//1567 3416//3416 -f 3416//3416 1567//1567 1561//1561 -f 3416//3416 1561//1561 3417//3417 -f 3417//3417 1561//1561 1562//1562 -f 3417//3417 1562//1562 3418//3418 -f 3418//3418 1562//1562 1563//1563 -f 3418//3418 1563//1563 3419//3419 -f 3419//3419 1563//1563 1566//1566 -f 3419//3419 1566//1566 3420//3420 -f 3420//3420 1566//1566 1565//1565 -f 3420//3420 1565//1565 3421//3421 -f 3421//3421 1565//1565 1564//1564 -f 3421//3421 1564//1564 3422//3422 -f 3422//3422 1564//1564 1577//1577 -f 3422//3422 1577//1577 3423//3423 -f 3423//3423 1577//1577 1576//1576 -f 3423//3423 1576//1576 3424//3424 -f 3424//3424 1576//1576 1574//1574 -f 3424//3424 1574//1574 3425//3425 -f 3425//3425 1574//1574 1573//1573 -f 3425//3425 1573//1573 3426//3426 -f 3426//3426 1573//1573 1575//1575 -f 3426//3426 1575//1575 3427//3427 -f 3427//3427 1575//1575 1583//1583 -f 3427//3427 1583//1583 3428//3428 -f 3428//3428 1583//1583 1582//1582 -f 3428//3428 1582//1582 3429//3429 -f 3429//3429 1582//1582 1581//1581 -f 3429//3429 1581//1581 3430//3430 -f 3372//3372 3378//3378 3373//3373 -f 3373//3373 3378//3378 3431//3431 -f 3373//3373 3431//3431 3432//3432 -f 3432//3432 3431//3431 3433//3433 -f 3432//3432 3433//3433 3434//3434 -f 3434//3434 3433//3433 3435//3435 -f 3434//3434 3435//3435 3436//3436 -f 3436//3436 3435//3435 3437//3437 -f 3436//3436 3437//3437 3438//3438 -f 3438//3438 3437//3437 3439//3439 -f 3438//3438 3439//3439 3440//3440 -f 3440//3440 3439//3439 3441//3441 -f 3440//3440 3441//3441 3442//3442 -f 3442//3442 3441//3441 3443//3443 -f 3442//3442 3443//3443 3444//3444 -f 3444//3444 3443//3443 3445//3445 -f 3444//3444 3445//3445 3446//3446 -f 3446//3446 3445//3445 3447//3447 -f 3446//3446 3447//3447 3448//3448 -f 3448//3448 3447//3447 3449//3449 -f 3448//3448 3449//3449 3450//3450 -f 3450//3450 3449//3449 3451//3451 -f 3450//3450 3451//3451 3452//3452 -f 3452//3452 3451//3451 3453//3453 -f 3452//3452 3453//3453 3454//3454 -f 3454//3454 3453//3453 3455//3455 -f 3454//3454 3455//3455 3456//3456 -f 3456//3456 3455//3455 3457//3457 -f 3456//3456 3457//3457 3458//3458 -f 3458//3458 3457//3457 3459//3459 -f 3458//3458 3459//3459 3460//3460 -f 3460//3460 3459//3459 3461//3461 -f 3460//3460 3461//3461 3462//3462 -f 3462//3462 3461//3461 3463//3463 -f 3462//3462 3463//3463 3464//3464 -f 3464//3464 3463//3463 3465//3465 -f 3464//3464 3465//3465 3466//3466 -f 3466//3466 3465//3465 3467//3467 -f 3466//3466 3467//3467 3468//3468 -f 3468//3468 3467//3467 3469//3469 -f 3468//3468 3469//3469 3470//3470 -f 3470//3470 3469//3469 3471//3471 -f 3470//3470 3471//3471 3472//3472 -f 3472//3472 3471//3471 3473//3473 -f 3472//3472 3473//3473 3474//3474 -f 3474//3474 3473//3473 3475//3475 -f 3474//3474 3475//3475 3476//3476 -f 3476//3476 3475//3475 3477//3477 -f 3476//3476 3477//3477 3478//3478 -f 3366//3366 3370//3370 3367//3367 -f 3367//3367 3370//3370 3479//3479 -f 3367//3367 3479//3479 3480//3480 -f 3480//3480 3479//3479 3481//3481 -f 3480//3480 3481//3481 3482//3482 -f 3482//3482 3481//3481 3483//3483 -f 3482//3482 3483//3483 3484//3484 -f 3484//3484 3483//3483 3485//3485 -f 3484//3484 3485//3485 3486//3486 -f 3486//3486 3485//3485 3487//3487 -f 3486//3486 3487//3487 3488//3488 -f 3488//3488 3487//3487 3489//3489 -f 3488//3488 3489//3489 3490//3490 -f 3490//3490 3489//3489 3491//3491 -f 3490//3490 3491//3491 3492//3492 -f 3492//3492 3491//3491 3493//3493 -f 3492//3492 3493//3493 3494//3494 -f 3494//3494 3493//3493 3495//3495 -f 3494//3494 3495//3495 3496//3496 -f 3496//3496 3495//3495 3497//3497 -f 3496//3496 3497//3497 3498//3498 -f 3498//3498 3497//3497 3499//3499 -f 3498//3498 3499//3499 3500//3500 -f 3500//3500 3499//3499 3501//3501 -f 3500//3500 3501//3501 3502//3502 -f 3502//3502 3501//3501 3503//3503 -f 3502//3502 3503//3503 3504//3504 -f 3504//3504 3503//3503 3505//3505 -f 3504//3504 3505//3505 3506//3506 -f 3506//3506 3505//3505 3507//3507 -f 3506//3506 3507//3507 3508//3508 -f 3508//3508 3507//3507 3509//3509 -f 3508//3508 3509//3509 3510//3510 -f 3510//3510 3509//3509 3511//3511 -f 3510//3510 3511//3511 3512//3512 -f 3512//3512 3511//3511 3513//3513 -f 3512//3512 3513//3513 3514//3514 -f 3514//3514 3513//3513 3515//3515 -f 3514//3514 3515//3515 3516//3516 -f 3516//3516 3515//3515 3517//3517 -f 3516//3516 3517//3517 3518//3518 -f 3518//3518 3517//3517 3519//3519 -f 3518//3518 3519//3519 3520//3520 -f 3520//3520 3519//3519 3521//3521 -f 3520//3520 3521//3521 3522//3522 -f 3522//3522 3521//3521 3523//3523 -f 3522//3522 3523//3523 3524//3524 -f 3524//3524 3523//3523 3525//3525 -f 3524//3524 3525//3525 3526//3526 -f 3360//3360 3364//3364 3361//3361 -f 3361//3361 3364//3364 3527//3527 -f 3361//3361 3527//3527 3528//3528 -f 3528//3528 3527//3527 3529//3529 -f 3528//3528 3529//3529 3530//3530 -f 3530//3530 3529//3529 3531//3531 -f 3530//3530 3531//3531 3532//3532 -f 3532//3532 3531//3531 3533//3533 -f 3532//3532 3533//3533 3534//3534 -f 3534//3534 3533//3533 3535//3535 -f 3534//3534 3535//3535 3536//3536 -f 3536//3536 3535//3535 3537//3537 -f 3536//3536 3537//3537 3538//3538 -f 3538//3538 3537//3537 3539//3539 -f 3538//3538 3539//3539 3540//3540 -f 3540//3540 3539//3539 3541//3541 -f 3540//3540 3541//3541 3542//3542 -f 3542//3542 3541//3541 3543//3543 -f 3542//3542 3543//3543 3544//3544 -f 3544//3544 3543//3543 3545//3545 -f 3544//3544 3545//3545 3546//3546 -f 3546//3546 3545//3545 3547//3547 -f 3546//3546 3547//3547 3548//3548 -f 3548//3548 3547//3547 3549//3549 -f 3548//3548 3549//3549 3550//3550 -f 3550//3550 3549//3549 3551//3551 -f 3550//3550 3551//3551 3552//3552 -f 3552//3552 3551//3551 3553//3553 -f 3552//3552 3553//3553 3554//3554 -f 3554//3554 3553//3553 3555//3555 -f 3554//3554 3555//3555 3556//3556 -f 3556//3556 3555//3555 3557//3557 -f 3556//3556 3557//3557 3558//3558 -f 3558//3558 3557//3557 3559//3559 -f 3558//3558 3559//3559 3560//3560 -f 3560//3560 3559//3559 3561//3561 -f 3560//3560 3561//3561 3562//3562 -f 3562//3562 3561//3561 3563//3563 -f 3562//3562 3563//3563 3564//3564 -f 3564//3564 3563//3563 3565//3565 -f 3564//3564 3565//3565 3566//3566 -f 3566//3566 3565//3565 3567//3567 -f 3566//3566 3567//3567 3568//3568 -f 3568//3568 3567//3567 3569//3569 -f 3568//3568 3569//3569 3570//3570 -f 3570//3570 3569//3569 3571//3571 -f 3570//3570 3571//3571 3572//3572 -f 3572//3572 3571//3571 3573//3573 -f 3572//3572 3573//3573 3574//3574 -f 3077//3077 3404//3404 3069//3069 -f 3069//3069 3404//3404 3575//3575 -f 3069//3069 3575//3575 3358//3358 -f 1581//1581 1599//1599 3430//3430 -f 3430//3430 1599//1599 3576//3576 -f 3430//3430 3576//3576 3577//3577 -f 3377//3377 3376//3376 3578//3578 -f 3578//3578 3376//3376 3407//3407 -f 3578//3578 3407//3407 3579//3579 -f 3579//3579 3407//3407 3408//3408 -f 3579//3579 3408//3408 3580//3580 -f 3580//3580 3408//3408 3409//3409 -f 3580//3580 3409//3409 3581//3581 -f 3581//3581 3409//3409 3410//3410 -f 3581//3581 3410//3410 3582//3582 -f 3582//3582 3410//3410 3411//3411 -f 3582//3582 3411//3411 3583//3583 -f 3583//3583 3411//3411 3412//3412 -f 3583//3583 3412//3412 3584//3584 -f 3584//3584 3412//3412 3413//3413 -f 3584//3584 3413//3413 3585//3585 -f 3585//3585 3413//3413 3414//3414 -f 3585//3585 3414//3414 3586//3586 -f 3586//3586 3414//3414 3415//3415 -f 3586//3586 3415//3415 3587//3587 -f 3587//3587 3415//3415 3416//3416 -f 3587//3587 3416//3416 3588//3588 -f 3588//3588 3416//3416 3417//3417 -f 3588//3588 3417//3417 3589//3589 -f 3589//3589 3417//3417 3418//3418 -f 3589//3589 3418//3418 3590//3590 -f 3590//3590 3418//3418 3419//3419 -f 3590//3590 3419//3419 3591//3591 -f 3591//3591 3419//3419 3420//3420 -f 3591//3591 3420//3420 3592//3592 -f 3592//3592 3420//3420 3421//3421 -f 3592//3592 3421//3421 3593//3593 -f 3593//3593 3421//3421 3422//3422 -f 3593//3593 3422//3422 3594//3594 -f 3594//3594 3422//3422 3423//3423 -f 3594//3594 3423//3423 3595//3595 -f 3595//3595 3423//3423 3424//3424 -f 3595//3595 3424//3424 3596//3596 -f 3596//3596 3424//3424 3425//3425 -f 3596//3596 3425//3425 3597//3597 -f 3597//3597 3425//3425 3426//3426 -f 3597//3597 3426//3426 3598//3598 -f 3598//3598 3426//3426 3427//3427 -f 3598//3598 3427//3427 3599//3599 -f 3599//3599 3427//3427 3428//3428 -f 3599//3599 3428//3428 3600//3600 -f 3600//3600 3428//3428 3429//3429 -f 3600//3600 3429//3429 3601//3601 -f 3601//3601 3429//3429 3430//3430 -f 3601//3601 3430//3430 3602//3602 -f 3602//3602 3430//3430 3577//3577 -f 3602//3602 3577//3577 3603//3603 -f 3603//3603 3477//3477 3602//3602 -f 3602//3602 3477//3477 3475//3475 -f 3602//3602 3475//3475 3601//3601 -f 3601//3601 3475//3475 3473//3473 -f 3601//3601 3473//3473 3600//3600 -f 3600//3600 3473//3473 3471//3471 -f 3600//3600 3471//3471 3599//3599 -f 3599//3599 3471//3471 3469//3469 -f 3599//3599 3469//3469 3598//3598 -f 3598//3598 3469//3469 3467//3467 -f 3598//3598 3467//3467 3597//3597 -f 3597//3597 3467//3467 3465//3465 -f 3597//3597 3465//3465 3596//3596 -f 3596//3596 3465//3465 3463//3463 -f 3596//3596 3463//3463 3595//3595 -f 3595//3595 3463//3463 3461//3461 -f 3595//3595 3461//3461 3594//3594 -f 3594//3594 3461//3461 3459//3459 -f 3594//3594 3459//3459 3593//3593 -f 3593//3593 3459//3459 3457//3457 -f 3593//3593 3457//3457 3592//3592 -f 3592//3592 3457//3457 3455//3455 -f 3592//3592 3455//3455 3591//3591 -f 3591//3591 3455//3455 3453//3453 -f 3591//3591 3453//3453 3590//3590 -f 3590//3590 3453//3453 3451//3451 -f 3590//3590 3451//3451 3589//3589 -f 3589//3589 3451//3451 3449//3449 -f 3589//3589 3449//3449 3588//3588 -f 3588//3588 3449//3449 3447//3447 -f 3588//3588 3447//3447 3587//3587 -f 3587//3587 3447//3447 3445//3445 -f 3587//3587 3445//3445 3586//3586 -f 3586//3586 3445//3445 3443//3443 -f 3586//3586 3443//3443 3585//3585 -f 3585//3585 3443//3443 3441//3441 -f 3585//3585 3441//3441 3584//3584 -f 3584//3584 3441//3441 3439//3439 -f 3584//3584 3439//3439 3583//3583 -f 3583//3583 3439//3439 3437//3437 -f 3583//3583 3437//3437 3582//3582 -f 3582//3582 3437//3437 3435//3435 -f 3582//3582 3435//3435 3581//3581 -f 3581//3581 3435//3435 3433//3433 -f 3581//3581 3433//3433 3580//3580 -f 3580//3580 3433//3433 3431//3431 -f 3580//3580 3431//3431 3579//3579 -f 3579//3579 3431//3431 3378//3378 -f 3579//3579 3378//3378 3578//3578 -f 3578//3578 3378//3378 3380//3380 -f 3578//3578 3380//3380 3377//3377 -f 3603//3603 3604//3604 3477//3477 -f 3477//3477 3604//3604 3605//3605 -f 3477//3477 3605//3605 3478//3478 -f 3478//3478 3605//3605 3606//3606 -f 3478//3478 3606//3606 3607//3607 -f 3607//3607 3525//3525 3478//3478 -f 3478//3478 3525//3525 3523//3523 -f 3478//3478 3523//3523 3476//3476 -f 3476//3476 3523//3523 3521//3521 -f 3476//3476 3521//3521 3474//3474 -f 3474//3474 3521//3521 3519//3519 -f 3474//3474 3519//3519 3472//3472 -f 3472//3472 3519//3519 3517//3517 -f 3472//3472 3517//3517 3470//3470 -f 3470//3470 3517//3517 3515//3515 -f 3470//3470 3515//3515 3468//3468 -f 3468//3468 3515//3515 3513//3513 -f 3468//3468 3513//3513 3466//3466 -f 3466//3466 3513//3513 3511//3511 -f 3466//3466 3511//3511 3464//3464 -f 3464//3464 3511//3511 3509//3509 -f 3464//3464 3509//3509 3462//3462 -f 3462//3462 3509//3509 3507//3507 -f 3462//3462 3507//3507 3460//3460 -f 3460//3460 3507//3507 3505//3505 -f 3460//3460 3505//3505 3458//3458 -f 3458//3458 3505//3505 3503//3503 -f 3458//3458 3503//3503 3456//3456 -f 3456//3456 3503//3503 3501//3501 -f 3456//3456 3501//3501 3454//3454 -f 3454//3454 3501//3501 3499//3499 -f 3454//3454 3499//3499 3452//3452 -f 3452//3452 3499//3499 3497//3497 -f 3452//3452 3497//3497 3450//3450 -f 3450//3450 3497//3497 3495//3495 -f 3450//3450 3495//3495 3448//3448 -f 3448//3448 3495//3495 3493//3493 -f 3448//3448 3493//3493 3446//3446 -f 3446//3446 3493//3493 3491//3491 -f 3446//3446 3491//3491 3444//3444 -f 3444//3444 3491//3491 3489//3489 -f 3444//3444 3489//3489 3442//3442 -f 3442//3442 3489//3489 3487//3487 -f 3442//3442 3487//3487 3440//3440 -f 3440//3440 3487//3487 3485//3485 -f 3440//3440 3485//3485 3438//3438 -f 3438//3438 3485//3485 3483//3483 -f 3438//3438 3483//3483 3436//3436 -f 3436//3436 3483//3483 3481//3481 -f 3436//3436 3481//3481 3434//3434 -f 3434//3434 3481//3481 3479//3479 -f 3434//3434 3479//3479 3432//3432 -f 3432//3432 3479//3479 3370//3370 -f 3432//3432 3370//3370 3373//3373 -f 3373//3373 3370//3370 3369//3369 -f 3373//3373 3369//3369 3371//3371 -f 3607//3607 3608//3608 3525//3525 -f 3525//3525 3608//3608 3609//3609 -f 3525//3525 3609//3609 3526//3526 -f 3526//3526 3609//3609 3610//3610 -f 3526//3526 3610//3610 3611//3611 -f 3365//3365 3367//3367 3381//3381 -f 3381//3381 3367//3367 3480//3480 -f 3381//3381 3480//3480 3612//3612 -f 3612//3612 3480//3480 3482//3482 -f 3612//3612 3482//3482 3613//3613 -f 3613//3613 3482//3482 3484//3484 -f 3613//3613 3484//3484 3614//3614 -f 3614//3614 3484//3484 3486//3486 -f 3614//3614 3486//3486 3615//3615 -f 3615//3615 3486//3486 3488//3488 -f 3615//3615 3488//3488 3616//3616 -f 3616//3616 3488//3488 3490//3490 -f 3616//3616 3490//3490 3617//3617 -f 3617//3617 3490//3490 3492//3492 -f 3617//3617 3492//3492 3618//3618 -f 3618//3618 3492//3492 3494//3494 -f 3618//3618 3494//3494 3619//3619 -f 3619//3619 3494//3494 3496//3496 -f 3619//3619 3496//3496 3620//3620 -f 3620//3620 3496//3496 3498//3498 -f 3620//3620 3498//3498 3621//3621 -f 3621//3621 3498//3498 3500//3500 -f 3621//3621 3500//3500 3622//3622 -f 3622//3622 3500//3500 3502//3502 -f 3622//3622 3502//3502 3623//3623 -f 3623//3623 3502//3502 3504//3504 -f 3623//3623 3504//3504 3624//3624 -f 3624//3624 3504//3504 3506//3506 -f 3624//3624 3506//3506 3625//3625 -f 3625//3625 3506//3506 3508//3508 -f 3625//3625 3508//3508 3626//3626 -f 3626//3626 3508//3508 3510//3510 -f 3626//3626 3510//3510 3627//3627 -f 3627//3627 3510//3510 3512//3512 -f 3627//3627 3512//3512 3628//3628 -f 3628//3628 3512//3512 3514//3514 -f 3628//3628 3514//3514 3629//3629 -f 3629//3629 3514//3514 3516//3516 -f 3629//3629 3516//3516 3630//3630 -f 3630//3630 3516//3516 3518//3518 -f 3630//3630 3518//3518 3631//3631 -f 3631//3631 3518//3518 3520//3520 -f 3631//3631 3520//3520 3632//3632 -f 3632//3632 3520//3520 3522//3522 -f 3632//3632 3522//3522 3633//3633 -f 3633//3633 3522//3522 3524//3524 -f 3633//3633 3524//3524 3634//3634 -f 3634//3634 3524//3524 3526//3526 -f 3634//3634 3526//3526 3635//3635 -f 3635//3635 3526//3526 3611//3611 -f 3635//3635 3611//3611 3636//3636 -f 3636//3636 3573//3573 3635//3635 -f 3635//3635 3573//3573 3571//3571 -f 3635//3635 3571//3571 3634//3634 -f 3634//3634 3571//3571 3569//3569 -f 3634//3634 3569//3569 3633//3633 -f 3633//3633 3569//3569 3567//3567 -f 3633//3633 3567//3567 3632//3632 -f 3632//3632 3567//3567 3565//3565 -f 3632//3632 3565//3565 3631//3631 -f 3631//3631 3565//3565 3563//3563 -f 3631//3631 3563//3563 3630//3630 -f 3630//3630 3563//3563 3561//3561 -f 3630//3630 3561//3561 3629//3629 -f 3629//3629 3561//3561 3559//3559 -f 3629//3629 3559//3559 3628//3628 -f 3628//3628 3559//3559 3557//3557 -f 3628//3628 3557//3557 3627//3627 -f 3627//3627 3557//3557 3555//3555 -f 3627//3627 3555//3555 3626//3626 -f 3626//3626 3555//3555 3553//3553 -f 3626//3626 3553//3553 3625//3625 -f 3625//3625 3553//3553 3551//3551 -f 3625//3625 3551//3551 3624//3624 -f 3624//3624 3551//3551 3549//3549 -f 3624//3624 3549//3549 3623//3623 -f 3623//3623 3549//3549 3547//3547 -f 3623//3623 3547//3547 3622//3622 -f 3622//3622 3547//3547 3545//3545 -f 3622//3622 3545//3545 3621//3621 -f 3621//3621 3545//3545 3543//3543 -f 3621//3621 3543//3543 3620//3620 -f 3620//3620 3543//3543 3541//3541 -f 3620//3620 3541//3541 3619//3619 -f 3619//3619 3541//3541 3539//3539 -f 3619//3619 3539//3539 3618//3618 -f 3618//3618 3539//3539 3537//3537 -f 3618//3618 3537//3537 3617//3617 -f 3617//3617 3537//3537 3535//3535 -f 3617//3617 3535//3535 3616//3616 -f 3616//3616 3535//3535 3533//3533 -f 3616//3616 3533//3533 3615//3615 -f 3615//3615 3533//3533 3531//3531 -f 3615//3615 3531//3531 3614//3614 -f 3614//3614 3531//3531 3529//3529 -f 3614//3614 3529//3529 3613//3613 -f 3613//3613 3529//3529 3527//3527 -f 3613//3613 3527//3527 3612//3612 -f 3612//3612 3527//3527 3364//3364 -f 3612//3612 3364//3364 3381//3381 -f 3381//3381 3364//3364 3363//3363 -f 3381//3381 3363//3363 3382//3382 -f 3636//3636 3637//3637 3573//3573 -f 3573//3573 3637//3637 3638//3638 -f 3573//3573 3638//3638 3574//3574 -f 3574//3574 3638//3638 3639//3639 -f 3574//3574 3639//3639 3640//3640 -f 3383//3383 3361//3361 3385//3385 -f 3385//3385 3361//3361 3528//3528 -f 3385//3385 3528//3528 3384//3384 -f 3384//3384 3528//3528 3530//3530 -f 3384//3384 3530//3530 3387//3387 -f 3387//3387 3530//3530 3532//3532 -f 3387//3387 3532//3532 3386//3386 -f 3386//3386 3532//3532 3534//3534 -f 3386//3386 3534//3534 3390//3390 -f 3390//3390 3534//3534 3536//3536 -f 3390//3390 3536//3536 3389//3389 -f 3389//3389 3536//3536 3538//3538 -f 3389//3389 3538//3538 3388//3388 -f 3388//3388 3538//3538 3540//3540 -f 3388//3388 3540//3540 3394//3394 -f 3394//3394 3540//3540 3542//3542 -f 3394//3394 3542//3542 3393//3393 -f 3393//3393 3542//3542 3544//3544 -f 3393//3393 3544//3544 3392//3392 -f 3392//3392 3544//3544 3546//3546 -f 3392//3392 3546//3546 3391//3391 -f 3391//3391 3546//3546 3548//3548 -f 3391//3391 3548//3548 3396//3396 -f 3396//3396 3548//3548 3550//3550 -f 3396//3396 3550//3550 3395//3395 -f 3395//3395 3550//3550 3552//3552 -f 3395//3395 3552//3552 3397//3397 -f 3397//3397 3552//3552 3554//3554 -f 3397//3397 3554//3554 3398//3398 -f 3398//3398 3554//3554 3556//3556 -f 3398//3398 3556//3556 3399//3399 -f 3399//3399 3556//3556 3558//3558 -f 3399//3399 3558//3558 3401//3401 -f 3401//3401 3558//3558 3560//3560 -f 3401//3401 3560//3560 3400//3400 -f 3400//3400 3560//3560 3562//3562 -f 3400//3400 3562//3562 3402//3402 -f 3402//3402 3562//3562 3564//3564 -f 3402//3402 3564//3564 3403//3403 -f 3403//3403 3564//3564 3566//3566 -f 3403//3403 3566//3566 3406//3406 -f 3406//3406 3566//3566 3568//3568 -f 3406//3406 3568//3568 3405//3405 -f 3405//3405 3568//3568 3570//3570 -f 3405//3405 3570//3570 3404//3404 -f 3404//3404 3570//3570 3572//3572 -f 3404//3404 3572//3572 3575//3575 -f 3575//3575 3572//3572 3574//3574 -f 3575//3575 3574//3574 3358//3358 -f 3358//3358 3574//3574 3640//3640 -f 3358//3358 3640//3640 3641//3641 -f 3641//3641 55//55 3358//3358 -f 3358//3358 55//55 3072//3072 -f 3358//3358 3072//3072 3071//3071 -f 3642//3642 3643//3643 3644//3644 -f 3645//3645 1584//1584 1590//1590 -f 3646//3646 3647//3647 3380//3380 -f 3380//3380 3647//3647 3648//3648 -f 3380//3380 3648//3648 3377//3377 -f 3377//3377 3648//3648 3649//3649 -f 3377//3377 3649//3649 3374//3374 -f 3374//3374 3649//3649 3650//3650 -f 3374//3374 3650//3650 3375//3375 -f 3375//3375 3650//3650 3651//3651 -f 3375//3375 3651//3651 1590//1590 -f 1590//1590 3651//3651 3652//3652 -f 1590//1590 3652//3652 3645//3645 -f 3380//3380 3379//3379 3646//3646 -f 3646//3646 3379//3379 3372//3372 -f 3646//3646 3372//3372 3653//3653 -f 3653//3653 3372//3372 3371//3371 -f 3653//3653 3371//3371 3654//3654 -f 3655//3655 3368//3368 3656//3656 -f 3656//3656 3368//3368 3657//3657 -f 3654//3654 3371//3371 3655//3655 -f 3655//3655 3371//3371 3369//3369 -f 3655//3655 3369//3369 3368//3368 -f 3658//3658 3659//3659 3365//3365 -f 3657//3657 3368//3368 3659//3659 -f 3659//3659 3368//3368 3366//3366 -f 3659//3659 3366//3366 3365//3365 -f 3658//3658 3365//3365 3660//3660 -f 3660//3660 3365//3365 3382//3382 -f 3660//3660 3382//3382 3661//3661 -f 3661//3661 3382//3382 3363//3363 -f 3661//3661 3363//3363 3662//3662 -f 3663//3663 3664//3664 3662//3662 -f 3662//3662 3664//3664 3665//3665 -f 3662//3662 3665//3665 3661//3661 -f 3643//3643 3666//3666 3644//3644 -f 3644//3644 3666//3666 3667//3667 -f 3644//3644 3667//3667 3662//3662 -f 3662//3662 3667//3667 3668//3668 -f 3662//3662 3668//3668 3663//3663 -f 3642//3642 786//786 3669//3669 -f 3669//3669 786//786 789//789 -f 3642//3642 3644//3644 786//786 -f 786//786 3644//3644 3383//3383 -f 786//786 3383//3383 787//787 -f 3363//3363 3362//3362 3662//3662 -f 3662//3662 3362//3362 3360//3360 -f 3662//3662 3360//3360 3644//3644 -f 3644//3644 3360//3360 3359//3359 -f 3644//3644 3359//3359 3383//3383 -f 3636//3636 3611//3611 3670//3670 -f 3671//3671 3672//3672 3673//3673 -f 1//1 53//53 3674//3674 -f 3674//3674 53//53 3675//3675 -f 3676//3676 3677//3677 3678//3678 -f 3678//3678 3677//3677 3679//3679 -f 3678//3678 3679//3679 3673//3673 -f 3673//3673 3679//3679 3680//3680 -f 3673//3673 3680//3680 3671//3671 -f 3678//3678 3638//3638 3637//3637 -f 3636//3636 3670//3670 3637//3637 -f 3637//3637 3670//3670 3681//3681 -f 3637//3637 3681//3681 3678//3678 -f 3678//3678 3681//3681 3682//3682 -f 3678//3678 3682//3682 3676//3676 -f 3609//3609 3683//3683 3610//3610 -f 3610//3610 3683//3683 3684//3684 -f 3610//3610 3684//3684 3611//3611 -f 3611//3611 3684//3684 3685//3685 -f 3611//3611 3685//3685 3670//3670 -f 3604//3604 3686//3686 3605//3605 -f 3605//3605 3686//3686 3687//3687 -f 3605//3605 3687//3687 3606//3606 -f 3606//3606 3687//3687 3607//3607 -f 3687//3687 3688//3688 3607//3607 -f 3607//3607 3688//3688 3689//3689 -f 3607//3607 3689//3689 3608//3608 -f 3608//3608 3689//3689 3690//3690 -f 3608//3608 3690//3690 3609//3609 -f 3609//3609 3690//3690 3691//3691 -f 3609//3609 3691//3691 3683//3683 -f 1593//1593 3692//3692 1599//1599 -f 1599//1599 3692//3692 3693//3693 -f 1599//1599 3693//3693 3576//3576 -f 3576//3576 3693//3693 3694//3694 -f 3576//3576 3694//3694 3577//3577 -f 3577//3577 3694//3694 3695//3695 -f 3577//3577 3695//3695 3603//3603 -f 3603//3603 3695//3695 3696//3696 -f 3603//3603 3696//3696 3604//3604 -f 3604//3604 3696//3696 3697//3697 -f 3604//3604 3697//3697 3686//3686 -f 55//55 3673//3673 53//53 -f 53//53 3673//3673 3672//3672 -f 53//53 3672//3672 3675//3675 -f 55//55 3641//3641 3673//3673 -f 3673//3673 3641//3641 3640//3640 -f 3673//3673 3640//3640 3678//3678 -f 3678//3678 3640//3640 3639//3639 -f 3678//3678 3639//3639 3638//3638 -f 3698//3698 3699//3699 3700//3700 -f 3701//3701 3702//3702 3703//3703 -f 789//789 791//791 3704//3704 -f 3704//3704 791//791 3705//3705 -f 3706//3706 3707//3707 3708//3708 -f 3708//3708 3707//3707 3709//3709 -f 3708//3708 3709//3709 3703//3703 -f 3703//3703 3709//3709 3710//3710 -f 3703//3703 3710//3710 3701//3701 -f 3708//3708 3711//3711 3712//3712 -f 3698//3698 3700//3700 3712//3712 -f 3712//3712 3700//3700 3713//3713 -f 3712//3712 3713//3713 3708//3708 -f 3708//3708 3713//3713 3714//3714 -f 3708//3708 3714//3714 3706//3706 -f 3715//3715 3716//3716 3717//3717 -f 3717//3717 3716//3716 3718//3718 -f 3717//3717 3718//3718 3719//3719 -f 3718//3718 3720//3720 3719//3719 -f 3719//3719 3720//3720 3721//3721 -f 3719//3719 3721//3721 3722//3722 -f 3722//3722 3721//3721 3723//3723 -f 3722//3722 3723//3723 3699//3699 -f 3699//3699 3723//3723 3724//3724 -f 3699//3699 3724//3724 3700//3700 -f 3725//3725 3726//3726 3727//3727 -f 3727//3727 3726//3726 3728//3728 -f 3727//3727 3728//3728 3729//3729 -f 3728//3728 3730//3730 3729//3729 -f 3729//3729 3730//3730 3731//3731 -f 3729//3729 3731//3731 3732//3732 -f 3732//3732 3731//3731 3733//3733 -f 3732//3732 3733//3733 3715//3715 -f 3715//3715 3733//3733 3734//3734 -f 3715//3715 3734//3734 3716//3716 -f 1634//1634 3735//3735 1640//1640 -f 1640//1640 3735//3735 3736//3736 -f 1640//1640 3736//3736 3725//3725 -f 3725//3725 3736//3736 3737//3737 -f 3725//3725 3737//3737 3726//3726 -f 793//793 3703//3703 791//791 -f 791//791 3703//3703 3702//3702 -f 791//791 3702//3702 3705//3705 -f 793//793 3738//3738 3703//3703 -f 3703//3703 3738//3738 3739//3739 -f 3703//3703 3739//3739 3708//3708 -f 3708//3708 3739//3739 3740//3740 -f 3708//3708 3740//3740 3711//3711 -f 3741//3741 3742//3742 3743//3743 -f 3744//3744 3745//3745 3746//3746 -f 3747//3747 3748//3748 3749//3749 -f 3750//3750 10//10 8//8 -f 3751//3751 3752//3752 3753//3753 -f 3753//3753 3752//3752 3754//3754 -f 3753//3753 3754//3754 8//8 -f 8//8 3754//3754 3755//3755 -f 8//8 3755//3755 3750//3750 -f 3756//3756 3757//3757 3758//3758 -f 3758//3758 3757//3757 3759//3759 -f 3758//3758 3759//3759 3760//3760 -f 3761//3761 3762//3762 3763//3763 -f 3763//3763 3762//3762 3764//3764 -f 3765//3765 3766//3766 3767//3767 -f 3767//3767 3766//3766 3768//3768 -f 3767//3767 3768//3768 3769//3769 -f 3770//3770 3771//3771 3772//3772 -f 3772//3772 3771//3771 3773//3773 -f 3744//3744 3746//3746 3774//3774 -f 3774//3774 1517//1517 3775//3775 -f 3775//3775 1517//1517 1522//1522 -f 1528//1528 1533//1533 3776//3776 -f 3776//3776 1533//1533 3777//3777 -f 3778//3778 3779//3779 3780//3780 -f 3780//3780 3779//3779 3781//3781 -f 3780//3780 3781//3781 3782//3782 -f 3783//3783 3784//3784 3785//3785 -f 3785//3785 3784//3784 3778//3778 -f 3786//3786 3787//3787 3788//3788 -f 3788//3788 3787//3787 3789//3789 -f 3788//3788 3789//3789 3783//3783 -f 3790//3790 3791//3791 3792//3792 -f 3792//3792 3791//3791 3793//3793 -f 3792//3792 3793//3793 3786//3786 -f 3794//3794 3795//3795 3796//3796 -f 3796//3796 3795//3795 3797//3797 -f 3796//3796 3797//3797 3790//3790 -f 3742//3742 3798//3798 3743//3743 -f 3743//3743 3798//3798 3799//3799 -f 3743//3743 3799//3799 3794//3794 -f 3800//3800 3741//3741 3801//3801 -f 3800//3800 3801//3801 3802//3802 -f 3802//3802 3801//3801 40//40 -f 3802//3802 40//40 2//2 -f 1//1 3803//3803 2//2 -f 2//2 3803//3803 3804//3804 -f 2//2 3804//3804 3802//3802 -f 8//8 15//15 3753//3753 -f 3753//3753 15//15 16//16 -f 3753//3753 16//16 3805//3805 -f 3805//3805 16//16 18//18 -f 3805//3805 18//18 3806//3806 -f 18//18 21//21 3806//3806 -f 3806//3806 21//21 23//23 -f 3806//3806 23//23 3807//3807 -f 23//23 25//25 3807//3807 -f 3807//3807 25//25 37//37 -f 3807//3807 37//37 3808//3808 -f 3808//3808 37//37 36//36 -f 3808//3808 36//36 3809//3809 -f 36//36 34//34 3809//3809 -f 3809//3809 34//34 32//32 -f 3809//3809 32//32 3810//3810 -f 3810//3810 32//32 30//30 -f 30//30 28//28 3810//3810 -f 3810//3810 28//28 52//52 -f 3810//3810 52//52 3811//3811 -f 3811//3811 52//52 51//51 -f 3811//3811 51//51 3812//3812 -f 51//51 49//49 3812//3812 -f 3812//3812 49//49 47//47 -f 3812//3812 47//47 3813//3813 -f 47//47 45//45 3813//3813 -f 3813//3813 45//45 43//43 -f 3813//3813 43//43 3814//3814 -f 3814//3814 43//43 42//42 -f 3814//3814 42//42 3801//3801 -f 3801//3801 42//42 41//41 -f 3801//3801 41//41 40//40 -f 3741//3741 3743//3743 3801//3801 -f 3801//3801 3743//3743 3815//3815 -f 3801//3801 3815//3815 3814//3814 -f 3814//3814 3815//3815 3816//3816 -f 3814//3814 3816//3816 3813//3813 -f 3813//3813 3816//3816 3817//3817 -f 3813//3813 3817//3817 3812//3812 -f 3812//3812 3817//3817 3818//3818 -f 3812//3812 3818//3818 3811//3811 -f 3811//3811 3818//3818 3819//3819 -f 3811//3811 3819//3819 3810//3810 -f 3810//3810 3819//3819 3820//3820 -f 3810//3810 3820//3820 3809//3809 -f 3809//3809 3820//3820 3821//3821 -f 3809//3809 3821//3821 3808//3808 -f 3808//3808 3821//3821 3822//3822 -f 3808//3808 3822//3822 3807//3807 -f 3807//3807 3822//3822 3823//3823 -f 3807//3807 3823//3823 3806//3806 -f 3806//3806 3823//3823 3824//3824 -f 3806//3806 3824//3824 3805//3805 -f 3805//3805 3824//3824 3758//3758 -f 3805//3805 3758//3758 3753//3753 -f 3753//3753 3758//3758 3760//3760 -f 3753//3753 3760//3760 3751//3751 -f 3794//3794 3796//3796 3743//3743 -f 3743//3743 3796//3796 3825//3825 -f 3743//3743 3825//3825 3815//3815 -f 3815//3815 3825//3825 3826//3826 -f 3815//3815 3826//3826 3816//3816 -f 3816//3816 3826//3826 3827//3827 -f 3816//3816 3827//3827 3817//3817 -f 3817//3817 3827//3827 3828//3828 -f 3817//3817 3828//3828 3818//3818 -f 3818//3818 3828//3828 3829//3829 -f 3818//3818 3829//3829 3819//3819 -f 3819//3819 3829//3829 3830//3830 -f 3819//3819 3830//3830 3820//3820 -f 3820//3820 3830//3830 3831//3831 -f 3820//3820 3831//3831 3821//3821 -f 3821//3821 3831//3831 3832//3832 -f 3821//3821 3832//3832 3822//3822 -f 3822//3822 3832//3832 3833//3833 -f 3822//3822 3833//3833 3823//3823 -f 3823//3823 3833//3833 3834//3834 -f 3823//3823 3834//3834 3824//3824 -f 3824//3824 3834//3834 3762//3762 -f 3824//3824 3762//3762 3758//3758 -f 3758//3758 3762//3762 3761//3761 -f 3758//3758 3761//3761 3756//3756 -f 3790//3790 3792//3792 3796//3796 -f 3796//3796 3792//3792 3835//3835 -f 3796//3796 3835//3835 3825//3825 -f 3825//3825 3835//3835 3836//3836 -f 3825//3825 3836//3836 3826//3826 -f 3826//3826 3836//3836 3837//3837 -f 3826//3826 3837//3837 3827//3827 -f 3827//3827 3837//3837 3838//3838 -f 3827//3827 3838//3838 3828//3828 -f 3828//3828 3838//3838 3839//3839 -f 3828//3828 3839//3839 3829//3829 -f 3829//3829 3839//3839 3840//3840 -f 3829//3829 3840//3840 3830//3830 -f 3830//3830 3840//3840 3841//3841 -f 3830//3830 3841//3841 3831//3831 -f 3831//3831 3841//3841 3842//3842 -f 3831//3831 3842//3842 3832//3832 -f 3832//3832 3842//3842 3843//3843 -f 3832//3832 3843//3843 3833//3833 -f 3833//3833 3843//3843 3844//3844 -f 3833//3833 3844//3844 3834//3834 -f 3834//3834 3844//3844 3749//3749 -f 3834//3834 3749//3749 3762//3762 -f 3762//3762 3749//3749 3748//3748 -f 3762//3762 3748//3748 3764//3764 -f 3786//3786 3788//3788 3792//3792 -f 3792//3792 3788//3788 3845//3845 -f 3792//3792 3845//3845 3835//3835 -f 3835//3835 3845//3845 3846//3846 -f 3835//3835 3846//3846 3836//3836 -f 3836//3836 3846//3846 3847//3847 -f 3836//3836 3847//3847 3837//3837 -f 3837//3837 3847//3847 3848//3848 -f 3837//3837 3848//3848 3838//3838 -f 3838//3838 3848//3848 3849//3849 -f 3838//3838 3849//3849 3839//3839 -f 3839//3839 3849//3849 3850//3850 -f 3839//3839 3850//3850 3840//3840 -f 3840//3840 3850//3850 3851//3851 -f 3840//3840 3851//3851 3841//3841 -f 3841//3841 3851//3851 3852//3852 -f 3841//3841 3852//3852 3842//3842 -f 3842//3842 3852//3852 3853//3853 -f 3842//3842 3853//3853 3843//3843 -f 3843//3843 3853//3853 3767//3767 -f 3843//3843 3767//3767 3844//3844 -f 3844//3844 3767//3767 3769//3769 -f 3844//3844 3769//3769 3749//3749 -f 3749//3749 3769//3769 3854//3854 -f 3749//3749 3854//3854 3747//3747 -f 3783//3783 3785//3785 3788//3788 -f 3788//3788 3785//3785 3855//3855 -f 3788//3788 3855//3855 3845//3845 -f 3845//3845 3855//3855 3856//3856 -f 3845//3845 3856//3856 3846//3846 -f 3846//3846 3856//3856 3857//3857 -f 3846//3846 3857//3857 3847//3847 -f 3847//3847 3857//3857 3858//3858 -f 3847//3847 3858//3858 3848//3848 -f 3848//3848 3858//3858 3859//3859 -f 3848//3848 3859//3859 3849//3849 -f 3849//3849 3859//3859 3860//3860 -f 3849//3849 3860//3860 3850//3850 -f 3850//3850 3860//3860 3861//3861 -f 3850//3850 3861//3861 3851//3851 -f 3851//3851 3861//3861 3862//3862 -f 3851//3851 3862//3862 3852//3852 -f 3852//3852 3862//3862 3863//3863 -f 3852//3852 3863//3863 3853//3853 -f 3853//3853 3863//3863 3771//3771 -f 3853//3853 3771//3771 3767//3767 -f 3767//3767 3771//3771 3770//3770 -f 3767//3767 3770//3770 3765//3765 -f 3778//3778 3780//3780 3785//3785 -f 3785//3785 3780//3780 3864//3864 -f 3785//3785 3864//3864 3855//3855 -f 3855//3855 3864//3864 3865//3865 -f 3855//3855 3865//3865 3856//3856 -f 3856//3856 3865//3865 3866//3866 -f 3856//3856 3866//3866 3857//3857 -f 3857//3857 3866//3866 3867//3867 -f 3857//3857 3867//3867 3858//3858 -f 3858//3858 3867//3867 3868//3868 -f 3858//3858 3868//3868 3859//3859 -f 3859//3859 3868//3868 3869//3869 -f 3859//3859 3869//3869 3860//3860 -f 3860//3860 3869//3869 3870//3870 -f 3860//3860 3870//3870 3861//3861 -f 3861//3861 3870//3870 3871//3871 -f 3861//3861 3871//3871 3862//3862 -f 3862//3862 3871//3871 3872//3872 -f 3862//3862 3872//3872 3863//3863 -f 3863//3863 3872//3872 3746//3746 -f 3863//3863 3746//3746 3771//3771 -f 3771//3771 3746//3746 3745//3745 -f 3771//3771 3745//3745 3773//3773 -f 3774//3774 3746//3746 1517//1517 -f 1517//1517 3746//3746 3872//3872 -f 1517//1517 3872//3872 1518//1518 -f 1518//1518 3872//3872 3871//3871 -f 1518//1518 3871//3871 1519//1519 -f 1519//1519 3871//3871 3870//3870 -f 1519//1519 3870//3870 1513//1513 -f 1513//1513 3870//3870 3869//3869 -f 1513//1513 3869//3869 1512//1512 -f 1512//1512 3869//3869 3868//3868 -f 1512//1512 3868//3868 1511//1511 -f 1511//1511 3868//3868 3867//3867 -f 1511//1511 3867//3867 1514//1514 -f 1514//1514 3867//3867 3866//3866 -f 1514//1514 3866//3866 1515//1515 -f 1515//1515 3866//3866 3865//3865 -f 1515//1515 3865//3865 1516//1516 -f 1516//1516 3865//3865 3864//3864 -f 1516//1516 3864//3864 1532//1532 -f 1532//1532 3864//3864 3780//3780 -f 1532//1532 3780//3780 1533//1533 -f 1533//1533 3780//3780 3782//3782 -f 1533//1533 3782//3782 3777//3777 -f 3873//3873 3251//3251 3249//3249 -f 3874//3874 3875//3875 3876//3876 -f 3877//3877 3878//3878 3879//3879 -f 3880//3880 3881//3881 3882//3882 -f 3883//3883 3884//3884 3885//3885 -f 3886//3886 3887//3887 3888//3888 -f 3889//3889 3890//3890 3891//3891 -f 3892//3892 3893//3893 3894//3894 -f 3893//3893 1631//1631 1629//1629 -f 3892//3892 3894//3894 3890//3890 -f 3895//3895 3896//3896 3889//3889 -f 3896//3896 3895//3895 3887//3887 -f 3883//3883 3885//3885 3881//3881 -f 3897//3897 3898//3898 3880//3880 -f 3877//3877 3879//3879 3875//3875 -f 3874//3874 3876//3876 3899//3899 -f 3900//3900 3295//3295 3901//3901 -f 3901//3901 3295//3295 3297//3297 -f 3901//3901 3297//3297 3899//3899 -f 3899//3899 3297//3297 3298//3298 -f 3899//3899 3298//3298 105//105 -f 3902//3902 3292//3292 3903//3903 -f 3903//3903 3292//3292 3294//3294 -f 3903//3903 3294//3294 3900//3900 -f 3900//3900 3294//3294 3306//3306 -f 3900//3900 3306//3306 3295//3295 -f 3904//3904 3176//3176 3905//3905 -f 3905//3905 3176//3176 3287//3287 -f 3905//3905 3287//3287 3906//3906 -f 3906//3906 3287//3287 3289//3289 -f 3906//3906 3289//3289 3902//3902 -f 3902//3902 3289//3289 3290//3290 -f 3902//3902 3290//3290 3292//3292 -f 3907//3907 3280//3280 3908//3908 -f 3908//3908 3280//3280 3279//3279 -f 3908//3908 3279//3279 3909//3909 -f 3909//3909 3279//3279 3284//3284 -f 3909//3909 3284//3284 3910//3910 -f 3910//3910 3284//3284 3286//3286 -f 3910//3910 3286//3286 3904//3904 -f 3904//3904 3286//3286 3174//3174 -f 3904//3904 3174//3174 3176//3176 -f 3911//3911 3277//3277 3912//3912 -f 3912//3912 3277//3277 3283//3283 -f 3912//3912 3283//3283 3907//3907 -f 3907//3907 3283//3283 3282//3282 -f 3907//3907 3282//3282 3280//3280 -f 3273//3273 3275//3275 3911//3911 -f 3911//3911 3275//3275 3278//3278 -f 3911//3911 3278//3278 3277//3277 -f 3911//3911 3913//3913 3273//3273 -f 3273//3273 3913//3913 3914//3914 -f 3273//3273 3914//3914 3271//3271 -f 3271//3271 3914//3914 3915//3915 -f 3263//3263 3270//3270 3916//3916 -f 3916//3916 3270//3270 3269//3269 -f 3916//3916 3269//3269 3917//3917 -f 3917//3917 3269//3269 3267//3267 -f 3917//3917 3267//3267 3915//3915 -f 3915//3915 3267//3267 3266//3266 -f 3915//3915 3266//3266 3271//3271 -f 3263//3263 3916//3916 3264//3264 -f 3264//3264 3916//3916 3918//3918 -f 3264//3264 3918//3918 3259//3259 -f 3259//3259 3918//3918 3919//3919 -f 3259//3259 3919//3919 3260//3260 -f 3257//3257 3256//3256 3920//3920 -f 3920//3920 3256//3256 3254//3254 -f 3920//3920 3254//3254 3921//3921 -f 3921//3921 3254//3254 3178//3178 -f 3921//3921 3178//3178 3922//3922 -f 3922//3922 3178//3178 3177//3177 -f 3922//3922 3177//3177 3919//3919 -f 3919//3919 3177//3177 3258//3258 -f 3919//3919 3258//3258 3260//3260 -f 3893//3893 1629//1629 3894//3894 -f 3894//3894 1629//1629 1628//1628 -f 3894//3894 1628//1628 3923//3923 -f 3923//3923 1628//1628 1621//1621 -f 3923//3923 1621//1621 3924//3924 -f 3924//3924 1621//1621 1620//1620 -f 3924//3924 1620//1620 3925//3925 -f 3925//3925 1620//1620 1619//1619 -f 3925//3925 1619//1619 3926//3926 -f 3926//3926 1619//1619 1613//1613 -f 3926//3926 1613//1613 3927//3927 -f 3927//3927 1613//1613 1612//1612 -f 3927//3927 1612//1612 3928//3928 -f 3928//3928 1612//1612 1611//1611 -f 3928//3928 1611//1611 3929//3929 -f 3929//3929 1611//1611 1610//1610 -f 3929//3929 1610//1610 3930//3930 -f 3930//3930 1610//1610 1609//1609 -f 3930//3930 1609//1609 3931//3931 -f 3931//3931 1609//1609 1608//1608 -f 3931//3931 1608//1608 3932//3932 -f 3932//3932 1608//1608 1602//1602 -f 3932//3932 1602//1602 3933//3933 -f 3933//3933 1602//1602 1603//1603 -f 3933//3933 1603//1603 3934//3934 -f 3934//3934 1603//1603 1604//1604 -f 3934//3934 1604//1604 3935//3935 -f 3935//3935 1604//1604 1607//1607 -f 3935//3935 1607//1607 3936//3936 -f 3936//3936 1607//1607 1606//1606 -f 3936//3936 1606//1606 3937//3937 -f 3937//3937 1606//1606 1605//1605 -f 3937//3937 1605//1605 3938//3938 -f 3938//3938 1605//1605 1618//1618 -f 3938//3938 1618//1618 3939//3939 -f 3939//3939 1618//1618 1617//1617 -f 3939//3939 1617//1617 3940//3940 -f 3940//3940 1617//1617 1615//1615 -f 3940//3940 1615//1615 3941//3941 -f 3941//3941 1615//1615 1614//1614 -f 3941//3941 1614//1614 3942//3942 -f 3942//3942 1614//1614 1616//1616 -f 3942//3942 1616//1616 3943//3943 -f 3943//3943 1616//1616 1624//1624 -f 3943//3943 1624//1624 3944//3944 -f 3944//3944 1624//1624 1623//1623 -f 3944//3944 1623//1623 3945//3945 -f 3945//3945 1623//1623 1622//1622 -f 3945//3945 1622//1622 3946//3946 -f 3890//3890 3894//3894 3891//3891 -f 3891//3891 3894//3894 3923//3923 -f 3891//3891 3923//3923 3947//3947 -f 3947//3947 3923//3923 3924//3924 -f 3947//3947 3924//3924 3948//3948 -f 3948//3948 3924//3924 3925//3925 -f 3948//3948 3925//3925 3949//3949 -f 3949//3949 3925//3925 3926//3926 -f 3949//3949 3926//3926 3950//3950 -f 3950//3950 3926//3926 3927//3927 -f 3950//3950 3927//3927 3951//3951 -f 3951//3951 3927//3927 3928//3928 -f 3951//3951 3928//3928 3952//3952 -f 3952//3952 3928//3928 3929//3929 -f 3952//3952 3929//3929 3953//3953 -f 3953//3953 3929//3929 3930//3930 -f 3953//3953 3930//3930 3954//3954 -f 3954//3954 3930//3930 3931//3931 -f 3954//3954 3931//3931 3955//3955 -f 3955//3955 3931//3931 3932//3932 -f 3955//3955 3932//3932 3956//3956 -f 3956//3956 3932//3932 3933//3933 -f 3956//3956 3933//3933 3957//3957 -f 3957//3957 3933//3933 3934//3934 -f 3957//3957 3934//3934 3958//3958 -f 3958//3958 3934//3934 3935//3935 -f 3958//3958 3935//3935 3959//3959 -f 3959//3959 3935//3935 3936//3936 -f 3959//3959 3936//3936 3960//3960 -f 3960//3960 3936//3936 3937//3937 -f 3960//3960 3937//3937 3961//3961 -f 3961//3961 3937//3937 3938//3938 -f 3961//3961 3938//3938 3962//3962 -f 3962//3962 3938//3938 3939//3939 -f 3962//3962 3939//3939 3963//3963 -f 3963//3963 3939//3939 3940//3940 -f 3963//3963 3940//3940 3964//3964 -f 3964//3964 3940//3940 3941//3941 -f 3964//3964 3941//3941 3965//3965 -f 3965//3965 3941//3941 3942//3942 -f 3965//3965 3942//3942 3966//3966 -f 3966//3966 3942//3942 3943//3943 -f 3966//3966 3943//3943 3967//3967 -f 3967//3967 3943//3943 3944//3944 -f 3967//3967 3944//3944 3968//3968 -f 3968//3968 3944//3944 3945//3945 -f 3968//3968 3945//3945 3969//3969 -f 3969//3969 3945//3945 3946//3946 -f 3969//3969 3946//3946 3970//3970 -f 3889//3889 3891//3891 3895//3895 -f 3895//3895 3891//3891 3947//3947 -f 3895//3895 3947//3947 3971//3971 -f 3971//3971 3947//3947 3948//3948 -f 3971//3971 3948//3948 3972//3972 -f 3972//3972 3948//3948 3949//3949 -f 3972//3972 3949//3949 3973//3973 -f 3973//3973 3949//3949 3950//3950 -f 3973//3973 3950//3950 3974//3974 -f 3974//3974 3950//3950 3951//3951 -f 3974//3974 3951//3951 3975//3975 -f 3975//3975 3951//3951 3952//3952 -f 3975//3975 3952//3952 3976//3976 -f 3976//3976 3952//3952 3953//3953 -f 3976//3976 3953//3953 3977//3977 -f 3977//3977 3953//3953 3954//3954 -f 3977//3977 3954//3954 3978//3978 -f 3978//3978 3954//3954 3955//3955 -f 3978//3978 3955//3955 3979//3979 -f 3979//3979 3955//3955 3956//3956 -f 3979//3979 3956//3956 3980//3980 -f 3980//3980 3956//3956 3957//3957 -f 3980//3980 3957//3957 3981//3981 -f 3981//3981 3957//3957 3958//3958 -f 3981//3981 3958//3958 3982//3982 -f 3982//3982 3958//3958 3959//3959 -f 3982//3982 3959//3959 3983//3983 -f 3983//3983 3959//3959 3960//3960 -f 3983//3983 3960//3960 3984//3984 -f 3984//3984 3960//3960 3961//3961 -f 3984//3984 3961//3961 3985//3985 -f 3985//3985 3961//3961 3962//3962 -f 3985//3985 3962//3962 3986//3986 -f 3986//3986 3962//3962 3963//3963 -f 3986//3986 3963//3963 3987//3987 -f 3987//3987 3963//3963 3964//3964 -f 3987//3987 3964//3964 3988//3988 -f 3988//3988 3964//3964 3965//3965 -f 3988//3988 3965//3965 3989//3989 -f 3989//3989 3965//3965 3966//3966 -f 3989//3989 3966//3966 3990//3990 -f 3990//3990 3966//3966 3967//3967 -f 3990//3990 3967//3967 3991//3991 -f 3991//3991 3967//3967 3968//3968 -f 3991//3991 3968//3968 3992//3992 -f 3992//3992 3968//3968 3969//3969 -f 3992//3992 3969//3969 3993//3993 -f 3993//3993 3969//3969 3970//3970 -f 3993//3993 3970//3970 3994//3994 -f 3887//3887 3895//3895 3888//3888 -f 3888//3888 3895//3895 3971//3971 -f 3888//3888 3971//3971 3995//3995 -f 3995//3995 3971//3971 3972//3972 -f 3995//3995 3972//3972 3996//3996 -f 3996//3996 3972//3972 3973//3973 -f 3996//3996 3973//3973 3997//3997 -f 3997//3997 3973//3973 3974//3974 -f 3997//3997 3974//3974 3998//3998 -f 3998//3998 3974//3974 3975//3975 -f 3998//3998 3975//3975 3999//3999 -f 3999//3999 3975//3975 3976//3976 -f 3999//3999 3976//3976 4000//4000 -f 4000//4000 3976//3976 3977//3977 -f 4000//4000 3977//3977 4001//4001 -f 4001//4001 3977//3977 3978//3978 -f 4001//4001 3978//3978 4002//4002 -f 4002//4002 3978//3978 3979//3979 -f 4002//4002 3979//3979 4003//4003 -f 4003//4003 3979//3979 3980//3980 -f 4003//4003 3980//3980 4004//4004 -f 4004//4004 3980//3980 3981//3981 -f 4004//4004 3981//3981 4005//4005 -f 4005//4005 3981//3981 3982//3982 -f 4005//4005 3982//3982 4006//4006 -f 4006//4006 3982//3982 3983//3983 -f 4006//4006 3983//3983 4007//4007 -f 4007//4007 3983//3983 3984//3984 -f 4007//4007 3984//3984 4008//4008 -f 4008//4008 3984//3984 3985//3985 -f 4008//4008 3985//3985 4009//4009 -f 4009//4009 3985//3985 3986//3986 -f 4009//4009 3986//3986 4010//4010 -f 4010//4010 3986//3986 3987//3987 -f 4010//4010 3987//3987 4011//4011 -f 4011//4011 3987//3987 3988//3988 -f 4011//4011 3988//3988 4012//4012 -f 4012//4012 3988//3988 3989//3989 -f 4012//4012 3989//3989 4013//4013 -f 4013//4013 3989//3989 3990//3990 -f 4013//4013 3990//3990 4014//4014 -f 4014//4014 3990//3990 3991//3991 -f 4014//4014 3991//3991 4015//4015 -f 4015//4015 3991//3991 3992//3992 -f 4015//4015 3992//3992 4016//4016 -f 4016//4016 3992//3992 3993//3993 -f 4016//4016 3993//3993 4017//4017 -f 4017//4017 3993//3993 3994//3994 -f 4017//4017 3994//3994 4018//4018 -f 3881//3881 3885//3885 3882//3882 -f 3882//3882 3885//3885 4019//4019 -f 3882//3882 4019//4019 4020//4020 -f 4020//4020 4019//4019 4021//4021 -f 4020//4020 4021//4021 4022//4022 -f 4022//4022 4021//4021 4023//4023 -f 4022//4022 4023//4023 4024//4024 -f 4024//4024 4023//4023 4025//4025 -f 4024//4024 4025//4025 4026//4026 -f 4026//4026 4025//4025 4027//4027 -f 4026//4026 4027//4027 4028//4028 -f 4028//4028 4027//4027 4029//4029 -f 4028//4028 4029//4029 4030//4030 -f 4030//4030 4029//4029 4031//4031 -f 4030//4030 4031//4031 4032//4032 -f 4032//4032 4031//4031 4033//4033 -f 4032//4032 4033//4033 4034//4034 -f 4034//4034 4033//4033 4035//4035 -f 4034//4034 4035//4035 4036//4036 -f 4036//4036 4035//4035 4037//4037 -f 4036//4036 4037//4037 4038//4038 -f 4038//4038 4037//4037 4039//4039 -f 4038//4038 4039//4039 4040//4040 -f 4040//4040 4039//4039 4041//4041 -f 4040//4040 4041//4041 4042//4042 -f 4042//4042 4041//4041 4043//4043 -f 4042//4042 4043//4043 4044//4044 -f 4044//4044 4043//4043 4045//4045 -f 4044//4044 4045//4045 4046//4046 -f 4046//4046 4045//4045 4047//4047 -f 4046//4046 4047//4047 4048//4048 -f 4048//4048 4047//4047 4049//4049 -f 4048//4048 4049//4049 4050//4050 -f 4050//4050 4049//4049 4051//4051 -f 4050//4050 4051//4051 4052//4052 -f 4052//4052 4051//4051 4053//4053 -f 4052//4052 4053//4053 4054//4054 -f 4054//4054 4053//4053 4055//4055 -f 4054//4054 4055//4055 4056//4056 -f 4056//4056 4055//4055 4057//4057 -f 4056//4056 4057//4057 4058//4058 -f 4058//4058 4057//4057 4059//4059 -f 4058//4058 4059//4059 4060//4060 -f 4060//4060 4059//4059 4061//4061 -f 4060//4060 4061//4061 4062//4062 -f 4062//4062 4061//4061 4063//4063 -f 4062//4062 4063//4063 4064//4064 -f 4064//4064 4063//4063 4065//4065 -f 4064//4064 4065//4065 4066//4066 -f 3875//3875 3879//3879 3876//3876 -f 3876//3876 3879//3879 4067//4067 -f 3876//3876 4067//4067 4068//4068 -f 4068//4068 4067//4067 4069//4069 -f 4068//4068 4069//4069 4070//4070 -f 4070//4070 4069//4069 4071//4071 -f 4070//4070 4071//4071 4072//4072 -f 4072//4072 4071//4071 4073//4073 -f 4072//4072 4073//4073 4074//4074 -f 4074//4074 4073//4073 4075//4075 -f 4074//4074 4075//4075 4076//4076 -f 4076//4076 4075//4075 4077//4077 -f 4076//4076 4077//4077 4078//4078 -f 4078//4078 4077//4077 4079//4079 -f 4078//4078 4079//4079 4080//4080 -f 4080//4080 4079//4079 4081//4081 -f 4080//4080 4081//4081 4082//4082 -f 4082//4082 4081//4081 4083//4083 -f 4082//4082 4083//4083 4084//4084 -f 4084//4084 4083//4083 4085//4085 -f 4084//4084 4085//4085 4086//4086 -f 4086//4086 4085//4085 4087//4087 -f 4086//4086 4087//4087 4088//4088 -f 4088//4088 4087//4087 4089//4089 -f 4088//4088 4089//4089 4090//4090 -f 4090//4090 4089//4089 4091//4091 -f 4090//4090 4091//4091 4092//4092 -f 4092//4092 4091//4091 4093//4093 -f 4092//4092 4093//4093 4094//4094 -f 4094//4094 4093//4093 4095//4095 -f 4094//4094 4095//4095 4096//4096 -f 4096//4096 4095//4095 4097//4097 -f 4096//4096 4097//4097 4098//4098 -f 4098//4098 4097//4097 4099//4099 -f 4098//4098 4099//4099 4100//4100 -f 4100//4100 4099//4099 4101//4101 -f 4100//4100 4101//4101 4102//4102 -f 4102//4102 4101//4101 4103//4103 -f 4102//4102 4103//4103 4104//4104 -f 4104//4104 4103//4103 4105//4105 -f 4104//4104 4105//4105 4106//4106 -f 4106//4106 4105//4105 4107//4107 -f 4106//4106 4107//4107 4108//4108 -f 4108//4108 4107//4107 4109//4109 -f 4108//4108 4109//4109 4110//4110 -f 4110//4110 4109//4109 4111//4111 -f 4110//4110 4111//4111 4112//4112 -f 4112//4112 4111//4111 4113//4113 -f 4112//4112 4113//4113 4114//4114 -f 3257//3257 3920//3920 3249//3249 -f 3249//3249 3920//3920 4115//4115 -f 3249//3249 4115//4115 3873//3873 -f 1622//1622 1640//1640 3946//3946 -f 3946//3946 1640//1640 3725//3725 -f 3946//3946 3725//3725 3970//3970 -f 3970//3970 3725//3725 3727//3727 -f 3970//3970 3727//3727 3994//3994 -f 3994//3994 3727//3727 3729//3729 -f 3994//3994 3729//3729 4018//4018 -f 4018//4018 3729//3729 3732//3732 -f 4018//4018 3732//3732 3715//3715 -f 3715//3715 4065//4065 4018//4018 -f 4018//4018 4065//4065 4063//4063 -f 4018//4018 4063//4063 4017//4017 -f 4017//4017 4063//4063 4061//4061 -f 4017//4017 4061//4061 4016//4016 -f 4016//4016 4061//4061 4059//4059 -f 4016//4016 4059//4059 4015//4015 -f 4015//4015 4059//4059 4057//4057 -f 4015//4015 4057//4057 4014//4014 -f 4014//4014 4057//4057 4055//4055 -f 4014//4014 4055//4055 4013//4013 -f 4013//4013 4055//4055 4053//4053 -f 4013//4013 4053//4053 4012//4012 -f 4012//4012 4053//4053 4051//4051 -f 4012//4012 4051//4051 4011//4011 -f 4011//4011 4051//4051 4049//4049 -f 4011//4011 4049//4049 4010//4010 -f 4010//4010 4049//4049 4047//4047 -f 4010//4010 4047//4047 4009//4009 -f 4009//4009 4047//4047 4045//4045 -f 4009//4009 4045//4045 4008//4008 -f 4008//4008 4045//4045 4043//4043 -f 4008//4008 4043//4043 4007//4007 -f 4007//4007 4043//4043 4041//4041 -f 4007//4007 4041//4041 4006//4006 -f 4006//4006 4041//4041 4039//4039 -f 4006//4006 4039//4039 4005//4005 -f 4005//4005 4039//4039 4037//4037 -f 4005//4005 4037//4037 4004//4004 -f 4004//4004 4037//4037 4035//4035 -f 4004//4004 4035//4035 4003//4003 -f 4003//4003 4035//4035 4033//4033 -f 4003//4003 4033//4033 4002//4002 -f 4002//4002 4033//4033 4031//4031 -f 4002//4002 4031//4031 4001//4001 -f 4001//4001 4031//4031 4029//4029 -f 4001//4001 4029//4029 4000//4000 -f 4000//4000 4029//4029 4027//4027 -f 4000//4000 4027//4027 3999//3999 -f 3999//3999 4027//4027 4025//4025 -f 3999//3999 4025//4025 3998//3998 -f 3998//3998 4025//4025 4023//4023 -f 3998//3998 4023//4023 3997//3997 -f 3997//3997 4023//4023 4021//4021 -f 3997//3997 4021//4021 3996//3996 -f 3996//3996 4021//4021 4019//4019 -f 3996//3996 4019//4019 3995//3995 -f 3995//3995 4019//4019 3885//3885 -f 3995//3995 3885//3885 3888//3888 -f 3888//3888 3885//3885 3884//3884 -f 3888//3888 3884//3884 3886//3886 -f 3715//3715 3717//3717 4065//4065 -f 4065//4065 3717//3717 3719//3719 -f 4065//4065 3719//3719 4066//4066 -f 4066//4066 3719//3719 3722//3722 -f 4066//4066 3722//3722 3699//3699 -f 3880//3880 3882//3882 3897//3897 -f 3897//3897 3882//3882 4020//4020 -f 3897//3897 4020//4020 4116//4116 -f 4116//4116 4020//4020 4022//4022 -f 4116//4116 4022//4022 4117//4117 -f 4117//4117 4022//4022 4024//4024 -f 4117//4117 4024//4024 4118//4118 -f 4118//4118 4024//4024 4026//4026 -f 4118//4118 4026//4026 4119//4119 -f 4119//4119 4026//4026 4028//4028 -f 4119//4119 4028//4028 4120//4120 -f 4120//4120 4028//4028 4030//4030 -f 4120//4120 4030//4030 4121//4121 -f 4121//4121 4030//4030 4032//4032 -f 4121//4121 4032//4032 4122//4122 -f 4122//4122 4032//4032 4034//4034 -f 4122//4122 4034//4034 4123//4123 -f 4123//4123 4034//4034 4036//4036 -f 4123//4123 4036//4036 4124//4124 -f 4124//4124 4036//4036 4038//4038 -f 4124//4124 4038//4038 4125//4125 -f 4125//4125 4038//4038 4040//4040 -f 4125//4125 4040//4040 4126//4126 -f 4126//4126 4040//4040 4042//4042 -f 4126//4126 4042//4042 4127//4127 -f 4127//4127 4042//4042 4044//4044 -f 4127//4127 4044//4044 4128//4128 -f 4128//4128 4044//4044 4046//4046 -f 4128//4128 4046//4046 4129//4129 -f 4129//4129 4046//4046 4048//4048 -f 4129//4129 4048//4048 4130//4130 -f 4130//4130 4048//4048 4050//4050 -f 4130//4130 4050//4050 4131//4131 -f 4131//4131 4050//4050 4052//4052 -f 4131//4131 4052//4052 4132//4132 -f 4132//4132 4052//4052 4054//4054 -f 4132//4132 4054//4054 4133//4133 -f 4133//4133 4054//4054 4056//4056 -f 4133//4133 4056//4056 4134//4134 -f 4134//4134 4056//4056 4058//4058 -f 4134//4134 4058//4058 4135//4135 -f 4135//4135 4058//4058 4060//4060 -f 4135//4135 4060//4060 4136//4136 -f 4136//4136 4060//4060 4062//4062 -f 4136//4136 4062//4062 4137//4137 -f 4137//4137 4062//4062 4064//4064 -f 4137//4137 4064//4064 4138//4138 -f 4138//4138 4064//4064 4066//4066 -f 4138//4138 4066//4066 4139//4139 -f 4139//4139 4066//4066 3699//3699 -f 4139//4139 3699//3699 3698//3698 -f 3698//3698 4113//4113 4139//4139 -f 4139//4139 4113//4113 4111//4111 -f 4139//4139 4111//4111 4138//4138 -f 4138//4138 4111//4111 4109//4109 -f 4138//4138 4109//4109 4137//4137 -f 4137//4137 4109//4109 4107//4107 -f 4137//4137 4107//4107 4136//4136 -f 4136//4136 4107//4107 4105//4105 -f 4136//4136 4105//4105 4135//4135 -f 4135//4135 4105//4105 4103//4103 -f 4135//4135 4103//4103 4134//4134 -f 4134//4134 4103//4103 4101//4101 -f 4134//4134 4101//4101 4133//4133 -f 4133//4133 4101//4101 4099//4099 -f 4133//4133 4099//4099 4132//4132 -f 4132//4132 4099//4099 4097//4097 -f 4132//4132 4097//4097 4131//4131 -f 4131//4131 4097//4097 4095//4095 -f 4131//4131 4095//4095 4130//4130 -f 4130//4130 4095//4095 4093//4093 -f 4130//4130 4093//4093 4129//4129 -f 4129//4129 4093//4093 4091//4091 -f 4129//4129 4091//4091 4128//4128 -f 4128//4128 4091//4091 4089//4089 -f 4128//4128 4089//4089 4127//4127 -f 4127//4127 4089//4089 4087//4087 -f 4127//4127 4087//4087 4126//4126 -f 4126//4126 4087//4087 4085//4085 -f 4126//4126 4085//4085 4125//4125 -f 4125//4125 4085//4085 4083//4083 -f 4125//4125 4083//4083 4124//4124 -f 4124//4124 4083//4083 4081//4081 -f 4124//4124 4081//4081 4123//4123 -f 4123//4123 4081//4081 4079//4079 -f 4123//4123 4079//4079 4122//4122 -f 4122//4122 4079//4079 4077//4077 -f 4122//4122 4077//4077 4121//4121 -f 4121//4121 4077//4077 4075//4075 -f 4121//4121 4075//4075 4120//4120 -f 4120//4120 4075//4075 4073//4073 -f 4120//4120 4073//4073 4119//4119 -f 4119//4119 4073//4073 4071//4071 -f 4119//4119 4071//4071 4118//4118 -f 4118//4118 4071//4071 4069//4069 -f 4118//4118 4069//4069 4117//4117 -f 4117//4117 4069//4069 4067//4067 -f 4117//4117 4067//4067 4116//4116 -f 4116//4116 4067//4067 3879//3879 -f 4116//4116 3879//3879 3897//3897 -f 3897//3897 3879//3879 3878//3878 -f 3897//3897 3878//3878 3898//3898 -f 3698//3698 3712//3712 4113//4113 -f 4113//4113 3712//3712 3711//3711 -f 4113//4113 3711//3711 4114//4114 -f 4114//4114 3711//3711 3740//3740 -f 4114//4114 3740//3740 3739//3739 -f 3899//3899 3876//3876 3901//3901 -f 3901//3901 3876//3876 4068//4068 -f 3901//3901 4068//4068 3900//3900 -f 3900//3900 4068//4068 4070//4070 -f 3900//3900 4070//4070 3903//3903 -f 3903//3903 4070//4070 4072//4072 -f 3903//3903 4072//4072 3902//3902 -f 3902//3902 4072//4072 4074//4074 -f 3902//3902 4074//4074 3906//3906 -f 3906//3906 4074//4074 4076//4076 -f 3906//3906 4076//4076 3905//3905 -f 3905//3905 4076//4076 4078//4078 -f 3905//3905 4078//4078 3904//3904 -f 3904//3904 4078//4078 4080//4080 -f 3904//3904 4080//4080 3910//3910 -f 3910//3910 4080//4080 4082//4082 -f 3910//3910 4082//4082 3909//3909 -f 3909//3909 4082//4082 4084//4084 -f 3909//3909 4084//4084 3908//3908 -f 3908//3908 4084//4084 4086//4086 -f 3908//3908 4086//4086 3907//3907 -f 3907//3907 4086//4086 4088//4088 -f 3907//3907 4088//4088 3912//3912 -f 3912//3912 4088//4088 4090//4090 -f 3912//3912 4090//4090 3911//3911 -f 3911//3911 4090//4090 4092//4092 -f 3911//3911 4092//4092 3913//3913 -f 3913//3913 4092//4092 4094//4094 -f 3913//3913 4094//4094 3914//3914 -f 3914//3914 4094//4094 4096//4096 -f 3914//3914 4096//4096 3915//3915 -f 3915//3915 4096//4096 4098//4098 -f 3915//3915 4098//4098 3917//3917 -f 3917//3917 4098//4098 4100//4100 -f 3917//3917 4100//4100 3916//3916 -f 3916//3916 4100//4100 4102//4102 -f 3916//3916 4102//4102 3918//3918 -f 3918//3918 4102//4102 4104//4104 -f 3918//3918 4104//4104 3919//3919 -f 3919//3919 4104//4104 4106//4106 -f 3919//3919 4106//4106 3922//3922 -f 3922//3922 4106//4106 4108//4108 -f 3922//3922 4108//4108 3921//3921 -f 3921//3921 4108//4108 4110//4110 -f 3921//3921 4110//4110 3920//3920 -f 3920//3920 4110//4110 4112//4112 -f 3920//3920 4112//4112 4115//4115 -f 4115//4115 4112//4112 4114//4114 -f 4115//4115 4114//4114 3873//3873 -f 3873//3873 4114//4114 3739//3739 -f 3873//3873 3739//3739 3738//3738 -f 3738//3738 793//793 3873//3873 -f 3873//3873 793//793 3252//3252 -f 3873//3873 3252//3252 3251//3251 -f 4140//4140 4141//4141 4142//4142 -f 4143//4143 4144//4144 4145//4145 -f 4146//4146 4147//4147 4148//4148 -f 1552//1552 1558//1558 4149//4149 -f 4149//4149 1558//1558 4150//4150 -f 4151//4151 4152//4152 4153//4153 -f 4153//4153 4152//4152 4154//4154 -f 4153//4153 4154//4154 4155//4155 -f 4156//4156 4157//4157 4158//4158 -f 4158//4158 4157//4157 4151//4151 -f 4159//4159 4160//4160 4161//4161 -f 4161//4161 4160//4160 4162//4162 -f 4161//4161 4162//4162 4156//4156 -f 4163//4163 4164//4164 4165//4165 -f 4165//4165 4164//4164 4166//4166 -f 4165//4165 4166//4166 4159//4159 -f 4167//4167 4168//4168 4169//4169 -f 4169//4169 4168//4168 4170//4170 -f 4169//4169 4170//4170 4163//4163 -f 4147//4147 4171//4171 4148//4148 -f 4148//4148 4171//4171 4172//4172 -f 4148//4148 4172//4172 4167//4167 -f 4173//4173 4146//4146 4174//4174 -f 10//10 4175//4175 57//57 -f 57//57 4175//4175 4176//4176 -f 57//57 4176//4176 4174//4174 -f 4174//4174 4176//4176 4177//4177 -f 4174//4174 4177//4177 4173//4173 -f 4178//4178 102//102 101//101 -f 4179//4179 4180//4180 4181//4181 -f 4181//4181 4180//4180 4182//4182 -f 4183//4183 4184//4184 4185//4185 -f 4185//4185 4184//4184 4186//4186 -f 4185//4185 4186//4186 4187//4187 -f 4188//4188 4189//4189 4190//4190 -f 4190//4190 4189//4189 4191//4191 -f 4192//4192 4193//4193 4194//4194 -f 4194//4194 4193//4193 4195//4195 -f 4194//4194 4195//4195 4196//4196 -f 4197//4197 4198//4198 4199//4199 -f 4199//4199 4198//4198 4200//4200 -f 4140//4140 4142//4142 4201//4201 -f 4201//4201 1546//1546 4202//4202 -f 4202//4202 1546//1546 1544//1544 -f 4203//4203 4180//4180 99//99 -f 99//99 4180//4180 4179//4179 -f 99//99 4179//4179 101//101 -f 101//101 4179//4179 4204//4204 -f 101//101 4204//4204 4178//4178 -f 99//99 93//93 4203//4203 -f 4203//4203 93//93 95//95 -f 4203//4203 95//95 4205//4205 -f 4205//4205 95//95 96//96 -f 96//96 89//89 4205//4205 -f 4205//4205 89//89 87//87 -f 4205//4205 87//87 4206//4206 -f 4206//4206 87//87 85//85 -f 4206//4206 85//85 4207//4207 -f 85//85 83//83 4207//4207 -f 4207//4207 83//83 82//82 -f 4207//4207 82//82 4208//4208 -f 82//82 80//80 4208//4208 -f 4208//4208 80//80 78//78 -f 4208//4208 78//78 4209//4209 -f 4209//4209 78//78 76//76 -f 4209//4209 76//76 4210//4210 -f 76//76 74//74 4210//4210 -f 4210//4210 74//74 72//72 -f 4210//4210 72//72 4211//4211 -f 72//72 70//70 4211//4211 -f 4211//4211 70//70 68//68 -f 4211//4211 68//68 4212//4212 -f 4212//4212 68//68 66//66 -f 66//66 65//65 4212//4212 -f 4212//4212 65//65 63//63 -f 4212//4212 63//63 4213//4213 -f 4213//4213 63//63 61//61 -f 4213//4213 61//61 4174//4174 -f 4174//4174 61//61 59//59 -f 4174//4174 59//59 57//57 -f 4146//4146 4148//4148 4174//4174 -f 4174//4174 4148//4148 4214//4214 -f 4174//4174 4214//4214 4213//4213 -f 4213//4213 4214//4214 4215//4215 -f 4213//4213 4215//4215 4212//4212 -f 4212//4212 4215//4215 4216//4216 -f 4212//4212 4216//4216 4211//4211 -f 4211//4211 4216//4216 4217//4217 -f 4211//4211 4217//4217 4210//4210 -f 4210//4210 4217//4217 4218//4218 -f 4210//4210 4218//4218 4209//4209 -f 4209//4209 4218//4218 4219//4219 -f 4209//4209 4219//4219 4208//4208 -f 4208//4208 4219//4219 4220//4220 -f 4208//4208 4220//4220 4207//4207 -f 4207//4207 4220//4220 4221//4221 -f 4207//4207 4221//4221 4206//4206 -f 4206//4206 4221//4221 4222//4222 -f 4206//4206 4222//4222 4205//4205 -f 4205//4205 4222//4222 4223//4223 -f 4205//4205 4223//4223 4203//4203 -f 4203//4203 4223//4223 4185//4185 -f 4203//4203 4185//4185 4180//4180 -f 4180//4180 4185//4185 4187//4187 -f 4180//4180 4187//4187 4182//4182 -f 4167//4167 4169//4169 4148//4148 -f 4148//4148 4169//4169 4224//4224 -f 4148//4148 4224//4224 4214//4214 -f 4214//4214 4224//4224 4225//4225 -f 4214//4214 4225//4225 4215//4215 -f 4215//4215 4225//4225 4226//4226 -f 4215//4215 4226//4226 4216//4216 -f 4216//4216 4226//4226 4227//4227 -f 4216//4216 4227//4227 4217//4217 -f 4217//4217 4227//4227 4228//4228 -f 4217//4217 4228//4228 4218//4218 -f 4218//4218 4228//4228 4229//4229 -f 4218//4218 4229//4229 4219//4219 -f 4219//4219 4229//4229 4230//4230 -f 4219//4219 4230//4230 4220//4220 -f 4220//4220 4230//4230 4231//4231 -f 4220//4220 4231//4231 4221//4221 -f 4221//4221 4231//4231 4232//4232 -f 4221//4221 4232//4232 4222//4222 -f 4222//4222 4232//4232 4233//4233 -f 4222//4222 4233//4233 4223//4223 -f 4223//4223 4233//4233 4189//4189 -f 4223//4223 4189//4189 4185//4185 -f 4185//4185 4189//4189 4188//4188 -f 4185//4185 4188//4188 4183//4183 -f 4163//4163 4165//4165 4169//4169 -f 4169//4169 4165//4165 4234//4234 -f 4169//4169 4234//4234 4224//4224 -f 4224//4224 4234//4234 4235//4235 -f 4224//4224 4235//4235 4225//4225 -f 4225//4225 4235//4235 4236//4236 -f 4225//4225 4236//4236 4226//4226 -f 4226//4226 4236//4236 4237//4237 -f 4226//4226 4237//4237 4227//4227 -f 4227//4227 4237//4237 4238//4238 -f 4227//4227 4238//4238 4228//4228 -f 4228//4228 4238//4238 4239//4239 -f 4228//4228 4239//4239 4229//4229 -f 4229//4229 4239//4239 4240//4240 -f 4229//4229 4240//4240 4230//4230 -f 4230//4230 4240//4240 4241//4241 -f 4230//4230 4241//4241 4231//4231 -f 4231//4231 4241//4241 4242//4242 -f 4231//4231 4242//4242 4232//4232 -f 4232//4232 4242//4242 4243//4243 -f 4232//4232 4243//4243 4233//4233 -f 4233//4233 4243//4243 4145//4145 -f 4233//4233 4145//4145 4189//4189 -f 4189//4189 4145//4145 4144//4144 -f 4189//4189 4144//4144 4191//4191 -f 4159//4159 4161//4161 4165//4165 -f 4165//4165 4161//4161 4244//4244 -f 4165//4165 4244//4244 4234//4234 -f 4234//4234 4244//4244 4245//4245 -f 4234//4234 4245//4245 4235//4235 -f 4235//4235 4245//4245 4246//4246 -f 4235//4235 4246//4246 4236//4236 -f 4236//4236 4246//4246 4247//4247 -f 4236//4236 4247//4247 4237//4237 -f 4237//4237 4247//4247 4248//4248 -f 4237//4237 4248//4248 4238//4238 -f 4238//4238 4248//4248 4249//4249 -f 4238//4238 4249//4249 4239//4239 -f 4239//4239 4249//4249 4250//4250 -f 4239//4239 4250//4250 4240//4240 -f 4240//4240 4250//4250 4251//4251 -f 4240//4240 4251//4251 4241//4241 -f 4241//4241 4251//4251 4252//4252 -f 4241//4241 4252//4252 4242//4242 -f 4242//4242 4252//4252 4194//4194 -f 4242//4242 4194//4194 4243//4243 -f 4243//4243 4194//4194 4196//4196 -f 4243//4243 4196//4196 4145//4145 -f 4145//4145 4196//4196 4253//4253 -f 4145//4145 4253//4253 4143//4143 -f 4156//4156 4158//4158 4161//4161 -f 4161//4161 4158//4158 4254//4254 -f 4161//4161 4254//4254 4244//4244 -f 4244//4244 4254//4254 4255//4255 -f 4244//4244 4255//4255 4245//4245 -f 4245//4245 4255//4255 4256//4256 -f 4245//4245 4256//4256 4246//4246 -f 4246//4246 4256//4256 4257//4257 -f 4246//4246 4257//4257 4247//4247 -f 4247//4247 4257//4257 4258//4258 -f 4247//4247 4258//4258 4248//4248 -f 4248//4248 4258//4258 4259//4259 -f 4248//4248 4259//4259 4249//4249 -f 4249//4249 4259//4259 4260//4260 -f 4249//4249 4260//4260 4250//4250 -f 4250//4250 4260//4260 4261//4261 -f 4250//4250 4261//4261 4251//4251 -f 4251//4251 4261//4261 4262//4262 -f 4251//4251 4262//4262 4252//4252 -f 4252//4252 4262//4262 4198//4198 -f 4252//4252 4198//4198 4194//4194 -f 4194//4194 4198//4198 4197//4197 -f 4194//4194 4197//4197 4192//4192 -f 4151//4151 4153//4153 4158//4158 -f 4158//4158 4153//4153 4263//4263 -f 4158//4158 4263//4263 4254//4254 -f 4254//4254 4263//4263 4264//4264 -f 4254//4254 4264//4264 4255//4255 -f 4255//4255 4264//4264 4265//4265 -f 4255//4255 4265//4265 4256//4256 -f 4256//4256 4265//4265 4266//4266 -f 4256//4256 4266//4266 4257//4257 -f 4257//4257 4266//4266 4267//4267 -f 4257//4257 4267//4267 4258//4258 -f 4258//4258 4267//4267 4268//4268 -f 4258//4258 4268//4268 4259//4259 -f 4259//4259 4268//4268 4269//4269 -f 4259//4259 4269//4269 4260//4260 -f 4260//4260 4269//4269 4270//4270 -f 4260//4260 4270//4270 4261//4261 -f 4261//4261 4270//4270 4271//4271 -f 4261//4261 4271//4271 4262//4262 -f 4262//4262 4271//4271 4142//4142 -f 4262//4262 4142//4142 4198//4198 -f 4198//4198 4142//4142 4141//4141 -f 4198//4198 4141//4141 4200//4200 -f 4201//4201 4142//4142 1546//1546 -f 1546//1546 4142//4142 4271//4271 -f 1546//1546 4271//4271 1545//1545 -f 1545//1545 4271//4271 4270//4270 -f 1545//1545 4270//4270 1539//1539 -f 1539//1539 4270//4270 4269//4269 -f 1539//1539 4269//4269 1538//1538 -f 1538//1538 4269//4269 4268//4268 -f 1538//1538 4268//4268 1536//1536 -f 1536//1536 4268//4268 4267//4267 -f 1536//1536 4267//4267 1537//1537 -f 1537//1537 4267//4267 4266//4266 -f 1537//1537 4266//4266 1540//1540 -f 1540//1540 4266//4266 4265//4265 -f 1540//1540 4265//4265 1541//1541 -f 1541//1541 4265//4265 4264//4264 -f 1541//1541 4264//4264 1556//1556 -f 1556//1556 4264//4264 4263//4263 -f 1556//1556 4263//4263 1557//1557 -f 1557//1557 4263//4263 4153//4153 -f 1557//1557 4153//4153 1558//1558 -f 1558//1558 4153//4153 4155//4155 -f 1558//1558 4155//4155 4150//4150 -f 4272//4272 4273//4273 4274//4274 -f 4275//4275 1625//1625 1631//1631 -f 4276//4276 4277//4277 3889//3889 -f 3889//3889 4277//4277 4278//4278 -f 3889//3889 4278//4278 3890//3890 -f 3890//3890 4278//4278 4279//4279 -f 3890//3890 4279//4279 3892//3892 -f 3892//3892 4279//4279 4280//4280 -f 3892//3892 4280//4280 3893//3893 -f 3893//3893 4280//4280 4281//4281 -f 3893//3893 4281//4281 1631//1631 -f 1631//1631 4281//4281 4282//4282 -f 1631//1631 4282//4282 4275//4275 -f 3889//3889 3896//3896 4276//4276 -f 4276//4276 3896//3896 3887//3887 -f 4276//4276 3887//3887 4283//4283 -f 4283//4283 3887//3887 3886//3886 -f 4283//4283 3886//3886 4284//4284 -f 4285//4285 3883//3883 4286//4286 -f 4286//4286 3883//3883 4287//4287 -f 4284//4284 3886//3886 4285//4285 -f 4285//4285 3886//3886 3884//3884 -f 4285//4285 3884//3884 3883//3883 -f 4288//4288 4289//4289 3880//3880 -f 4287//4287 3883//3883 4289//4289 -f 4289//4289 3883//3883 3881//3881 -f 4289//4289 3881//3881 3880//3880 -f 4288//4288 3880//3880 4290//4290 -f 4290//4290 3880//3880 3898//3898 -f 4290//4290 3898//3898 4291//4291 -f 4291//4291 3898//3898 3878//3878 -f 4291//4291 3878//3878 4292//4292 -f 4293//4293 4294//4294 4292//4292 -f 4292//4292 4294//4294 4295//4295 -f 4292//4292 4295//4295 4291//4291 -f 4273//4273 4296//4296 4274//4274 -f 4274//4274 4296//4296 4297//4297 -f 4274//4274 4297//4297 4292//4292 -f 4292//4292 4297//4297 4298//4298 -f 4292//4292 4298//4298 4293//4293 -f 4272//4272 104//104 4299//4299 -f 4299//4299 104//104 102//102 -f 4272//4272 4274//4274 104//104 -f 104//104 4274//4274 3899//3899 -f 104//104 3899//3899 105//105 -f 3878//3878 3877//3877 4292//4292 -f 4292//4292 3877//3877 3875//3875 -f 4292//4292 3875//3875 4274//4274 -f 4274//4274 3875//3875 3874//3874 -f 4274//4274 3874//3874 3899//3899 -f 4300//4300 4301//4301 4302//4302 -f 4303//4303 4304//4304 4305//4305 -f 4306//4306 4307//4307 4308//4308 -f 1481//1481 1484//1484 4309//4309 -f 4309//4309 1484//1484 4310//4310 -f 4311//4311 4312//4312 4313//4313 -f 4313//4313 4312//4312 4314//4314 -f 4313//4313 4314//4314 4315//4315 -f 4316//4316 4317//4317 4318//4318 -f 4318//4318 4317//4317 4311//4311 -f 4319//4319 4320//4320 4321//4321 -f 4321//4321 4320//4320 4322//4322 -f 4321//4321 4322//4322 4316//4316 -f 4323//4323 4324//4324 4325//4325 -f 4325//4325 4324//4324 4326//4326 -f 4325//4325 4326//4326 4319//4319 -f 4327//4327 4328//4328 4329//4329 -f 4329//4329 4328//4328 4330//4330 -f 4329//4329 4330//4330 4323//4323 -f 4307//4307 4331//4331 4308//4308 -f 4308//4308 4331//4331 4332//4332 -f 4308//4308 4332//4332 4327//4327 -f 4333//4333 4334//4334 4335//4335 -f 4335//4335 4334//4334 4336//4336 -f 4335//4335 4336//4336 4306//4306 -f 390//390 388//388 4337//4337 -f 4338//4338 430//430 429//429 -f 4338//4338 429//429 4339//4339 -f 4339//4339 429//429 427//427 -f 4339//4339 427//427 4340//4340 -f 4341//4341 4342//4342 4343//4343 -f 4344//4344 4345//4345 4346//4346 -f 4346//4346 4345//4345 4347//4347 -f 4346//4346 4347//4347 4348//4348 -f 4349//4349 4350//4350 4351//4351 -f 4351//4351 4350//4350 4352//4352 -f 4353//4353 4354//4354 4355//4355 -f 4355//4355 4354//4354 4356//4356 -f 4355//4355 4356//4356 4357//4357 -f 4358//4358 4359//4359 4360//4360 -f 4360//4360 4359//4359 4361//4361 -f 4300//4300 4302//4302 4362//4362 -f 4362//4362 1472//1472 4363//4363 -f 4363//4363 1472//1472 1477//1477 -f 4343//4343 4340//4340 4341//4341 -f 4341//4341 4340//4340 427//427 -f 4341//4341 427//427 4364//4364 -f 427//427 425//425 4364//4364 -f 4364//4364 425//425 424//424 -f 4364//4364 424//424 4365//4365 -f 424//424 423//423 4365//4365 -f 4365//4365 423//423 421//421 -f 4365//4365 421//421 4366//4366 -f 4366//4366 421//421 419//419 -f 419//419 418//418 4366//4366 -f 4366//4366 418//418 416//416 -f 4366//4366 416//416 4367//4367 -f 4367//4367 416//416 414//414 -f 4367//4367 414//414 4368//4368 -f 414//414 412//412 4368//4368 -f 4368//4368 412//412 411//411 -f 4368//4368 411//411 4369//4369 -f 411//411 409//409 4369//4369 -f 4369//4369 409//409 407//407 -f 4369//4369 407//407 4370//4370 -f 4370//4370 407//407 405//405 -f 4370//4370 405//405 4371//4371 -f 405//405 403//403 4371//4371 -f 4371//4371 403//403 401//401 -f 4371//4371 401//401 4372//4372 -f 401//401 399//399 4372//4372 -f 4372//4372 399//399 397//397 -f 4372//4372 397//397 4373//4373 -f 4373//4373 397//397 395//395 -f 395//395 394//394 4373//4373 -f 4373//4373 394//394 392//392 -f 4373//4373 392//392 4335//4335 -f 4335//4335 392//392 390//390 -f 4335//4335 390//390 4333//4333 -f 4333//4333 390//390 4337//4337 -f 4306//4306 4308//4308 4335//4335 -f 4335//4335 4308//4308 4374//4374 -f 4335//4335 4374//4374 4373//4373 -f 4373//4373 4374//4374 4375//4375 -f 4373//4373 4375//4375 4372//4372 -f 4372//4372 4375//4375 4376//4376 -f 4372//4372 4376//4376 4371//4371 -f 4371//4371 4376//4376 4377//4377 -f 4371//4371 4377//4377 4370//4370 -f 4370//4370 4377//4377 4378//4378 -f 4370//4370 4378//4378 4369//4369 -f 4369//4369 4378//4378 4379//4379 -f 4369//4369 4379//4379 4368//4368 -f 4368//4368 4379//4379 4380//4380 -f 4368//4368 4380//4380 4367//4367 -f 4367//4367 4380//4380 4381//4381 -f 4367//4367 4381//4381 4366//4366 -f 4366//4366 4381//4381 4382//4382 -f 4366//4366 4382//4382 4365//4365 -f 4365//4365 4382//4382 4383//4383 -f 4365//4365 4383//4383 4364//4364 -f 4364//4364 4383//4383 4346//4346 -f 4364//4364 4346//4346 4341//4341 -f 4341//4341 4346//4346 4348//4348 -f 4341//4341 4348//4348 4342//4342 -f 4327//4327 4329//4329 4308//4308 -f 4308//4308 4329//4329 4384//4384 -f 4308//4308 4384//4384 4374//4374 -f 4374//4374 4384//4384 4385//4385 -f 4374//4374 4385//4385 4375//4375 -f 4375//4375 4385//4385 4386//4386 -f 4375//4375 4386//4386 4376//4376 -f 4376//4376 4386//4386 4387//4387 -f 4376//4376 4387//4387 4377//4377 -f 4377//4377 4387//4387 4388//4388 -f 4377//4377 4388//4388 4378//4378 -f 4378//4378 4388//4388 4389//4389 -f 4378//4378 4389//4389 4379//4379 -f 4379//4379 4389//4389 4390//4390 -f 4379//4379 4390//4390 4380//4380 -f 4380//4380 4390//4390 4391//4391 -f 4380//4380 4391//4391 4381//4381 -f 4381//4381 4391//4391 4392//4392 -f 4381//4381 4392//4392 4382//4382 -f 4382//4382 4392//4392 4393//4393 -f 4382//4382 4393//4393 4383//4383 -f 4383//4383 4393//4393 4350//4350 -f 4383//4383 4350//4350 4346//4346 -f 4346//4346 4350//4350 4349//4349 -f 4346//4346 4349//4349 4344//4344 -f 4323//4323 4325//4325 4329//4329 -f 4329//4329 4325//4325 4394//4394 -f 4329//4329 4394//4394 4384//4384 -f 4384//4384 4394//4394 4395//4395 -f 4384//4384 4395//4395 4385//4385 -f 4385//4385 4395//4395 4396//4396 -f 4385//4385 4396//4396 4386//4386 -f 4386//4386 4396//4396 4397//4397 -f 4386//4386 4397//4397 4387//4387 -f 4387//4387 4397//4397 4398//4398 -f 4387//4387 4398//4398 4388//4388 -f 4388//4388 4398//4398 4399//4399 -f 4388//4388 4399//4399 4389//4389 -f 4389//4389 4399//4399 4400//4400 -f 4389//4389 4400//4400 4390//4390 -f 4390//4390 4400//4400 4401//4401 -f 4390//4390 4401//4401 4391//4391 -f 4391//4391 4401//4401 4402//4402 -f 4391//4391 4402//4402 4392//4392 -f 4392//4392 4402//4402 4403//4403 -f 4392//4392 4403//4403 4393//4393 -f 4393//4393 4403//4403 4305//4305 -f 4393//4393 4305//4305 4350//4350 -f 4350//4350 4305//4305 4304//4304 -f 4350//4350 4304//4304 4352//4352 -f 4319//4319 4321//4321 4325//4325 -f 4325//4325 4321//4321 4404//4404 -f 4325//4325 4404//4404 4394//4394 -f 4394//4394 4404//4404 4405//4405 -f 4394//4394 4405//4405 4395//4395 -f 4395//4395 4405//4405 4406//4406 -f 4395//4395 4406//4406 4396//4396 -f 4396//4396 4406//4406 4407//4407 -f 4396//4396 4407//4407 4397//4397 -f 4397//4397 4407//4407 4408//4408 -f 4397//4397 4408//4408 4398//4398 -f 4398//4398 4408//4408 4409//4409 -f 4398//4398 4409//4409 4399//4399 -f 4399//4399 4409//4409 4410//4410 -f 4399//4399 4410//4410 4400//4400 -f 4400//4400 4410//4410 4411//4411 -f 4400//4400 4411//4411 4401//4401 -f 4401//4401 4411//4411 4412//4412 -f 4401//4401 4412//4412 4402//4402 -f 4402//4402 4412//4412 4355//4355 -f 4402//4402 4355//4355 4403//4403 -f 4403//4403 4355//4355 4357//4357 -f 4403//4403 4357//4357 4305//4305 -f 4305//4305 4357//4357 4413//4413 -f 4305//4305 4413//4413 4303//4303 -f 4316//4316 4318//4318 4321//4321 -f 4321//4321 4318//4318 4414//4414 -f 4321//4321 4414//4414 4404//4404 -f 4404//4404 4414//4414 4415//4415 -f 4404//4404 4415//4415 4405//4405 -f 4405//4405 4415//4415 4416//4416 -f 4405//4405 4416//4416 4406//4406 -f 4406//4406 4416//4416 4417//4417 -f 4406//4406 4417//4417 4407//4407 -f 4407//4407 4417//4417 4418//4418 -f 4407//4407 4418//4418 4408//4408 -f 4408//4408 4418//4418 4419//4419 -f 4408//4408 4419//4419 4409//4409 -f 4409//4409 4419//4419 4420//4420 -f 4409//4409 4420//4420 4410//4410 -f 4410//4410 4420//4420 4421//4421 -f 4410//4410 4421//4421 4411//4411 -f 4411//4411 4421//4421 4422//4422 -f 4411//4411 4422//4422 4412//4412 -f 4412//4412 4422//4422 4359//4359 -f 4412//4412 4359//4359 4355//4355 -f 4355//4355 4359//4359 4358//4358 -f 4355//4355 4358//4358 4353//4353 -f 4311//4311 4313//4313 4318//4318 -f 4318//4318 4313//4313 4423//4423 -f 4318//4318 4423//4423 4414//4414 -f 4414//4414 4423//4423 4424//4424 -f 4414//4414 4424//4424 4415//4415 -f 4415//4415 4424//4424 4425//4425 -f 4415//4415 4425//4425 4416//4416 -f 4416//4416 4425//4425 4426//4426 -f 4416//4416 4426//4426 4417//4417 -f 4417//4417 4426//4426 4427//4427 -f 4417//4417 4427//4427 4418//4418 -f 4418//4418 4427//4427 4428//4428 -f 4418//4418 4428//4428 4419//4419 -f 4419//4419 4428//4428 4429//4429 -f 4419//4419 4429//4429 4420//4420 -f 4420//4420 4429//4429 4430//4430 -f 4420//4420 4430//4430 4421//4421 -f 4421//4421 4430//4430 4431//4431 -f 4421//4421 4431//4431 4422//4422 -f 4422//4422 4431//4431 4302//4302 -f 4422//4422 4302//4302 4359//4359 -f 4359//4359 4302//4302 4301//4301 -f 4359//4359 4301//4301 4361//4361 -f 4362//4362 4302//4302 1472//1472 -f 1472//1472 4302//4302 4431//4431 -f 1472//1472 4431//4431 1473//1473 -f 1473//1473 4431//4431 4430//4430 -f 1473//1473 4430//4430 1474//1474 -f 1474//1474 4430//4430 4429//4429 -f 1474//1474 4429//4429 1468//1468 -f 1468//1468 4429//4429 4428//4428 -f 1468//1468 4428//4428 1467//1467 -f 1467//1467 4428//4428 4427//4427 -f 1467//1467 4427//4427 1466//1466 -f 1466//1466 4427//4427 4426//4426 -f 1466//1466 4426//4426 1469//1469 -f 1469//1469 4426//4426 4425//4425 -f 1469//1469 4425//4425 1470//1470 -f 1470//1470 4425//4425 4424//4424 -f 1470//1470 4424//4424 1471//1471 -f 1471//1471 4424//4424 4423//4423 -f 1471//1471 4423//4423 1483//1483 -f 1483//1483 4423//4423 4313//4313 -f 1483//1483 4313//4313 1484//1484 -f 1484//1484 4313//4313 4315//4315 -f 1484//1484 4315//4315 4310//4310 -f 4432//4432 4433//4433 4434//4434 -f 4435//4435 1457//1457 1455//1455 -f 4436//4436 4437//4437 4438//4438 -f 4436//4436 4438//4438 1455//1455 -f 1455//1455 4438//4438 4439//4439 -f 1455//1455 4439//4439 4435//4435 -f 4437//4437 4436//4436 4440//4440 -f 4440//4440 4436//4436 4441//4441 -f 4440//4440 4441//4441 4442//4442 -f 4442//4442 4441//4441 4443//4443 -f 4442//4442 4443//4443 4444//4444 -f 4445//4445 4446//4446 4447//4447 -f 4447//4447 4446//4446 4448//4448 -f 4444//4444 4443//4443 4445//4445 -f 4445//4445 4443//4443 4449//4449 -f 4445//4445 4449//4449 4446//4446 -f 4450//4450 4451//4451 4452//4452 -f 4452//4452 4451//4451 4453//4453 -f 4448//4448 4446//4446 4450//4450 -f 4450//4450 4446//4446 4454//4454 -f 4450//4450 4454//4454 4451//4451 -f 4455//4455 4456//4456 4457//4457 -f 4457//4457 4456//4456 4458//4458 -f 4453//4453 4451//4451 4455//4455 -f 4455//4455 4451//4451 4459//4459 -f 4455//4455 4459//4459 4456//4456 -f 4458//4458 4456//4456 4460//4460 -f 4460//4460 4456//4456 4461//4461 -f 4460//4460 4461//4461 4462//4462 -f 4463//4463 4464//4464 4462//4462 -f 4462//4462 4464//4464 4465//4465 -f 4462//4462 4465//4465 4460//4460 -f 4433//4433 4466//4466 4434//4434 -f 4434//4434 4466//4466 4467//4467 -f 4434//4434 4467//4467 4462//4462 -f 4462//4462 4467//4467 4468//4468 -f 4462//4462 4468//4468 4463//4463 -f 4432//4432 432//432 4469//4469 -f 4469//4469 432//432 430//430 -f 4432//4432 4434//4434 432//432 -f 432//432 4434//4434 4470//4470 -f 432//432 4470//4470 433//433 -f 4461//4461 4471//4471 4462//4462 -f 4462//4462 4471//4471 4472//4472 -f 4462//4462 4472//4472 4434//4434 -f 4434//4434 4472//4472 4473//4473 -f 4434//4434 4473//4473 4470//4470 -f 4474//4474 4475//4475 4476//4476 -f 4477//4477 4478//4478 4479//4479 -f 4480//4480 4481//4481 4482//4482 -f 388//388 386//386 4483//4483 -f 4483//4483 386//386 4484//4484 -f 4485//4485 4486//4486 4487//4487 -f 4487//4487 4486//4486 4488//4488 -f 4489//4489 4490//4490 4491//4491 -f 4491//4491 4490//4490 4492//4492 -f 4491//4491 4492//4492 4493//4493 -f 4494//4494 4495//4495 4496//4496 -f 4496//4496 4495//4495 4497//4497 -f 4498//4498 4499//4499 4500//4500 -f 4500//4500 4499//4499 4501//4501 -f 4500//4500 4501//4501 4502//4502 -f 4503//4503 4504//4504 4505//4505 -f 4505//4505 4504//4504 4506//4506 -f 4477//4477 4479//4479 4507//4507 -f 4507//4507 1496//1496 4508//4508 -f 4508//4508 1496//1496 1501//1501 -f 1507//1507 1505//1505 4509//4509 -f 4509//4509 1505//1505 4510//4510 -f 4511//4511 4512//4512 4513//4513 -f 4513//4513 4512//4512 4514//4514 -f 4513//4513 4514//4514 4515//4515 -f 4516//4516 4517//4517 4518//4518 -f 4518//4518 4517//4517 4511//4511 -f 4519//4519 4520//4520 4521//4521 -f 4521//4521 4520//4520 4522//4522 -f 4521//4521 4522//4522 4516//4516 -f 4523//4523 4524//4524 4525//4525 -f 4525//4525 4524//4524 4526//4526 -f 4525//4525 4526//4526 4519//4519 -f 4527//4527 4528//4528 4529//4529 -f 4529//4529 4528//4528 4530//4530 -f 4529//4529 4530//4530 4523//4523 -f 4475//4475 4531//4531 4476//4476 -f 4476//4476 4531//4531 4532//4532 -f 4476//4476 4532//4532 4527//4527 -f 4474//4474 4533//4533 4534//4534 -f 4534//4534 4533//4533 4535//4535 -f 348//348 337//337 4536//4536 -f 382//382 4537//4537 384//384 -f 384//384 4537//4537 4486//4486 -f 384//384 4486//4486 386//386 -f 386//386 4486//4486 4485//4485 -f 386//386 4485//4485 4484//4484 -f 382//382 380//380 4537//4537 -f 4537//4537 380//380 379//379 -f 4537//4537 379//379 4538//4538 -f 4538//4538 379//379 261//261 -f 4538//4538 261//261 4539//4539 -f 261//261 368//368 4539//4539 -f 4539//4539 368//368 370//370 -f 4539//4539 370//370 4540//4540 -f 370//370 372//372 4540//4540 -f 4540//4540 372//372 374//374 -f 4540//4540 374//374 4541//4541 -f 4541//4541 374//374 376//376 -f 4541//4541 376//376 4542//4542 -f 376//376 367//367 4542//4542 -f 4542//4542 367//367 366//366 -f 4542//4542 366//366 4543//4543 -f 4543//4543 366//366 362//362 -f 362//362 364//364 4543//4543 -f 4543//4543 364//364 357//357 -f 4543//4543 357//357 4544//4544 -f 4544//4544 357//357 359//359 -f 4544//4544 359//359 4545//4545 -f 4545//4545 359//359 352//352 -f 4545//4545 352//352 4546//4546 -f 4536//4536 4547//4547 348//348 -f 348//348 4547//4547 4535//4535 -f 348//348 4535//4535 349//349 -f 349//349 4535//4535 4533//4533 -f 349//349 4533//4533 345//345 -f 345//345 4533//4533 4546//4546 -f 345//345 4546//4546 354//354 -f 354//354 4546//4546 352//352 -f 4474//4474 4476//4476 4533//4533 -f 4533//4533 4476//4476 4548//4548 -f 4533//4533 4548//4548 4546//4546 -f 4546//4546 4548//4548 4549//4549 -f 4546//4546 4549//4549 4545//4545 -f 4545//4545 4549//4549 4550//4550 -f 4545//4545 4550//4550 4544//4544 -f 4544//4544 4550//4550 4551//4551 -f 4544//4544 4551//4551 4543//4543 -f 4543//4543 4551//4551 4552//4552 -f 4543//4543 4552//4552 4542//4542 -f 4542//4542 4552//4552 4553//4553 -f 4542//4542 4553//4553 4541//4541 -f 4541//4541 4553//4553 4554//4554 -f 4541//4541 4554//4554 4540//4540 -f 4540//4540 4554//4554 4555//4555 -f 4540//4540 4555//4555 4539//4539 -f 4539//4539 4555//4555 4556//4556 -f 4539//4539 4556//4556 4538//4538 -f 4538//4538 4556//4556 4557//4557 -f 4538//4538 4557//4557 4537//4537 -f 4537//4537 4557//4557 4491//4491 -f 4537//4537 4491//4491 4486//4486 -f 4486//4486 4491//4491 4493//4493 -f 4486//4486 4493//4493 4488//4488 -f 4527//4527 4529//4529 4476//4476 -f 4476//4476 4529//4529 4558//4558 -f 4476//4476 4558//4558 4548//4548 -f 4548//4548 4558//4558 4559//4559 -f 4548//4548 4559//4559 4549//4549 -f 4549//4549 4559//4559 4560//4560 -f 4549//4549 4560//4560 4550//4550 -f 4550//4550 4560//4560 4561//4561 -f 4550//4550 4561//4561 4551//4551 -f 4551//4551 4561//4561 4562//4562 -f 4551//4551 4562//4562 4552//4552 -f 4552//4552 4562//4562 4563//4563 -f 4552//4552 4563//4563 4553//4553 -f 4553//4553 4563//4563 4564//4564 -f 4553//4553 4564//4564 4554//4554 -f 4554//4554 4564//4564 4565//4565 -f 4554//4554 4565//4565 4555//4555 -f 4555//4555 4565//4565 4566//4566 -f 4555//4555 4566//4566 4556//4556 -f 4556//4556 4566//4566 4567//4567 -f 4556//4556 4567//4567 4557//4557 -f 4557//4557 4567//4567 4495//4495 -f 4557//4557 4495//4495 4491//4491 -f 4491//4491 4495//4495 4494//4494 -f 4491//4491 4494//4494 4489//4489 -f 4523//4523 4525//4525 4529//4529 -f 4529//4529 4525//4525 4568//4568 -f 4529//4529 4568//4568 4558//4558 -f 4558//4558 4568//4568 4569//4569 -f 4558//4558 4569//4569 4559//4559 -f 4559//4559 4569//4569 4570//4570 -f 4559//4559 4570//4570 4560//4560 -f 4560//4560 4570//4570 4571//4571 -f 4560//4560 4571//4571 4561//4561 -f 4561//4561 4571//4571 4572//4572 -f 4561//4561 4572//4572 4562//4562 -f 4562//4562 4572//4572 4573//4573 -f 4562//4562 4573//4573 4563//4563 -f 4563//4563 4573//4573 4574//4574 -f 4563//4563 4574//4574 4564//4564 -f 4564//4564 4574//4574 4575//4575 -f 4564//4564 4575//4575 4565//4565 -f 4565//4565 4575//4575 4576//4576 -f 4565//4565 4576//4576 4566//4566 -f 4566//4566 4576//4576 4577//4577 -f 4566//4566 4577//4577 4567//4567 -f 4567//4567 4577//4577 4482//4482 -f 4567//4567 4482//4482 4495//4495 -f 4495//4495 4482//4482 4481//4481 -f 4495//4495 4481//4481 4497//4497 -f 4519//4519 4521//4521 4525//4525 -f 4525//4525 4521//4521 4578//4578 -f 4525//4525 4578//4578 4568//4568 -f 4568//4568 4578//4578 4579//4579 -f 4568//4568 4579//4579 4569//4569 -f 4569//4569 4579//4579 4580//4580 -f 4569//4569 4580//4580 4570//4570 -f 4570//4570 4580//4580 4581//4581 -f 4570//4570 4581//4581 4571//4571 -f 4571//4571 4581//4581 4582//4582 -f 4571//4571 4582//4582 4572//4572 -f 4572//4572 4582//4582 4583//4583 -f 4572//4572 4583//4583 4573//4573 -f 4573//4573 4583//4583 4584//4584 -f 4573//4573 4584//4584 4574//4574 -f 4574//4574 4584//4584 4585//4585 -f 4574//4574 4585//4585 4575//4575 -f 4575//4575 4585//4585 4586//4586 -f 4575//4575 4586//4586 4576//4576 -f 4576//4576 4586//4586 4500//4500 -f 4576//4576 4500//4500 4577//4577 -f 4577//4577 4500//4500 4502//4502 -f 4577//4577 4502//4502 4482//4482 -f 4482//4482 4502//4502 4587//4587 -f 4482//4482 4587//4587 4480//4480 -f 4516//4516 4518//4518 4521//4521 -f 4521//4521 4518//4518 4588//4588 -f 4521//4521 4588//4588 4578//4578 -f 4578//4578 4588//4588 4589//4589 -f 4578//4578 4589//4589 4579//4579 -f 4579//4579 4589//4589 4590//4590 -f 4579//4579 4590//4590 4580//4580 -f 4580//4580 4590//4590 4591//4591 -f 4580//4580 4591//4591 4581//4581 -f 4581//4581 4591//4591 4592//4592 -f 4581//4581 4592//4592 4582//4582 -f 4582//4582 4592//4592 4593//4593 -f 4582//4582 4593//4593 4583//4583 -f 4583//4583 4593//4593 4594//4594 -f 4583//4583 4594//4594 4584//4584 -f 4584//4584 4594//4594 4595//4595 -f 4584//4584 4595//4595 4585//4585 -f 4585//4585 4595//4595 4596//4596 -f 4585//4585 4596//4596 4586//4586 -f 4586//4586 4596//4596 4504//4504 -f 4586//4586 4504//4504 4500//4500 -f 4500//4500 4504//4504 4503//4503 -f 4500//4500 4503//4503 4498//4498 -f 4511//4511 4513//4513 4518//4518 -f 4518//4518 4513//4513 4597//4597 -f 4518//4518 4597//4597 4588//4588 -f 4588//4588 4597//4597 4598//4598 -f 4588//4588 4598//4598 4589//4589 -f 4589//4589 4598//4598 4599//4599 -f 4589//4589 4599//4599 4590//4590 -f 4590//4590 4599//4599 4600//4600 -f 4590//4590 4600//4600 4591//4591 -f 4591//4591 4600//4600 4601//4601 -f 4591//4591 4601//4601 4592//4592 -f 4592//4592 4601//4601 4602//4602 -f 4592//4592 4602//4602 4593//4593 -f 4593//4593 4602//4602 4603//4603 -f 4593//4593 4603//4603 4594//4594 -f 4594//4594 4603//4603 4604//4604 -f 4594//4594 4604//4604 4595//4595 -f 4595//4595 4604//4604 4605//4605 -f 4595//4595 4605//4605 4596//4596 -f 4596//4596 4605//4605 4479//4479 -f 4596//4596 4479//4479 4504//4504 -f 4504//4504 4479//4479 4478//4478 -f 4504//4504 4478//4478 4506//4506 -f 4507//4507 4479//4479 1496//1496 -f 1496//1496 4479//4479 4605//4605 -f 1496//1496 4605//4605 1497//1497 -f 1497//1497 4605//4605 4604//4604 -f 1497//1497 4604//4604 1498//1498 -f 1498//1498 4604//4604 4603//4603 -f 1498//1498 4603//4603 1492//1492 -f 1492//1492 4603//4603 4602//4602 -f 1492//1492 4602//4602 1490//1490 -f 1490//1490 4602//4602 4601//4601 -f 1490//1490 4601//4601 1488//1488 -f 1488//1488 4601//4601 4600//4600 -f 1488//1488 4600//4600 1493//1493 -f 1493//1493 4600//4600 4599//4599 -f 1493//1493 4599//4599 1494//1494 -f 1494//1494 4599//4599 4598//4598 -f 1494//1494 4598//4598 1495//1495 -f 1495//1495 4598//4598 4597//4597 -f 1495//1495 4597//4597 1504//1504 -f 1504//1504 4597//4597 4513//4513 -f 1504//1504 4513//4513 1505//1505 -f 1505//1505 4513//4513 4515//4515 -f 1505//1505 4515//4515 4510//4510 -f 4473//4473 4472//4472 4606//4606 -f 4471//4471 4461//4461 4607//4607 -f 4451//4451 4454//4454 4608//4608 -f 4436//4436 1455//1455 1453//1453 -f 4441//4441 4436//4436 4609//4609 -f 4610//4610 4449//4449 4443//4443 -f 4449//4449 4610//4610 4446//4446 -f 4451//4451 4608//4608 4459//4459 -f 4456//4456 4459//4459 4611//4611 -f 4471//4471 4607//4607 4472//4472 -f 4473//4473 4606//4606 4470//4470 -f 433//433 4470//4470 4612//4612 -f 433//433 4612//4612 3347//3347 -f 3347//3347 4612//4612 4613//4613 -f 3347//3347 4613//4613 3340//3340 -f 3340//3340 4613//4613 4614//4614 -f 3340//3340 4614//4614 3339//3339 -f 4615//4615 3185//3185 4616//4616 -f 4616//4616 3185//3185 3184//3184 -f 4616//4616 3184//3184 4617//4617 -f 4617//4617 3184//3184 3182//3182 -f 4617//4617 3182//3182 4614//4614 -f 4614//4614 3182//3182 3181//3181 -f 4614//4614 3181//3181 3339//3339 -f 4618//4618 3187//3187 4615//4615 -f 4615//4615 3187//3187 3238//3238 -f 4615//4615 3238//3238 3185//3185 -f 4619//4619 3234//3234 4618//4618 -f 4618//4618 3234//3234 3188//3188 -f 4618//4618 3188//3188 3187//3187 -f 4620//4620 3229//3229 4621//4621 -f 4621//4621 3229//3229 3231//3231 -f 4621//4621 3231//3231 4622//4622 -f 4622//4622 3231//3231 3233//3233 -f 4622//4622 3233//3233 4623//4623 -f 4623//4623 3233//3233 3236//3236 -f 4623//4623 3236//3236 4619//4619 -f 4619//4619 3236//3236 3235//3235 -f 4619//4619 3235//3235 3234//3234 -f 4624//4624 3227//3227 4625//4625 -f 4625//4625 3227//3227 3225//3225 -f 4625//4625 3225//3225 4620//4620 -f 4620//4620 3225//3225 3224//3224 -f 4620//4620 3224//3224 3229//3229 -f 4626//4626 3222//3222 4627//4627 -f 4627//4627 3222//3222 3221//3221 -f 4627//4627 3221//3221 4628//4628 -f 4628//4628 3221//3221 3220//3220 -f 4628//4628 3220//3220 4624//4624 -f 4624//4624 3220//3220 3228//3228 -f 4624//4624 3228//3228 3227//3227 -f 4629//4629 3210//3210 4630//4630 -f 4630//4630 3210//3210 3216//3216 -f 4630//4630 3216//3216 4626//4626 -f 4626//4626 3216//3216 3223//3223 -f 4626//4626 3223//3223 3222//3222 -f 3214//3214 3213//3213 4629//4629 -f 4629//4629 3213//3213 3211//3211 -f 4629//4629 3211//3211 3210//3210 -f 4629//4629 4631//4631 3214//3214 -f 3214//3214 4631//4631 4632//4632 -f 3214//3214 4632//4632 3207//3207 -f 3207//3207 4632//4632 4633//4633 -f 3207//3207 4633//4633 3206//3206 -f 3206//3206 4633//4633 4634//4634 -f 3206//3206 4634//4634 3204//3204 -f 3204//3204 4634//4634 4635//4635 -f 4436//4436 1453//1453 4609//4609 -f 4609//4609 1453//1453 1452//1452 -f 4609//4609 1452//1452 4636//4636 -f 4636//4636 1452//1452 1448//1448 -f 4636//4636 1448//1448 4637//4637 -f 4637//4637 1448//1448 1447//1447 -f 4637//4637 1447//1447 4638//4638 -f 4638//4638 1447//1447 1446//1446 -f 4638//4638 1446//1446 4639//4639 -f 4639//4639 1446//1446 1440//1440 -f 4639//4639 1440//1440 4640//4640 -f 4640//4640 1440//1440 1439//1439 -f 4640//4640 1439//1439 4641//4641 -f 4641//4641 1439//1439 1438//1438 -f 4641//4641 1438//1438 4642//4642 -f 4642//4642 1438//1438 1437//1437 -f 4642//4642 1437//1437 4643//4643 -f 4643//4643 1437//1437 1436//1436 -f 4643//4643 1436//1436 4644//4644 -f 4644//4644 1436//1436 1435//1435 -f 4644//4644 1435//1435 4645//4645 -f 4645//4645 1435//1435 1427//1427 -f 4645//4645 1427//1427 4646//4646 -f 4646//4646 1427//1427 1429//1429 -f 4646//4646 1429//1429 4647//4647 -f 4647//4647 1429//1429 1431//1431 -f 4647//4647 1431//1431 4648//4648 -f 4648//4648 1431//1431 1434//1434 -f 4648//4648 1434//1434 4649//4649 -f 4649//4649 1434//1434 1433//1433 -f 4649//4649 1433//1433 4650//4650 -f 4650//4650 1433//1433 1432//1432 -f 4650//4650 1432//1432 4651//4651 -f 4651//4651 1432//1432 1445//1445 -f 4651//4651 1445//1445 4652//4652 -f 4652//4652 1445//1445 1444//1444 -f 4652//4652 1444//1444 4653//4653 -f 4653//4653 1444//1444 1442//1442 -f 4653//4653 1442//1442 4654//4654 -f 4654//4654 1442//1442 1441//1441 -f 4654//4654 1441//1441 4655//4655 -f 4655//4655 1441//1441 1443//1443 -f 4655//4655 1443//1443 4656//4656 -f 4656//4656 1443//1443 1451//1451 -f 4656//4656 1451//1451 4657//4657 -f 4657//4657 1451//1451 1450//1450 -f 4657//4657 1450//1450 4658//4658 -f 4658//4658 1450//1450 1449//1449 -f 4658//4658 1449//1449 4659//4659 -f 4446//4446 4610//4610 4660//4660 -f 4660//4660 4610//4610 4661//4661 -f 4660//4660 4661//4661 4662//4662 -f 4662//4662 4661//4661 4663//4663 -f 4662//4662 4663//4663 4664//4664 -f 4664//4664 4663//4663 4665//4665 -f 4664//4664 4665//4665 4666//4666 -f 4666//4666 4665//4665 4667//4667 -f 4666//4666 4667//4667 4668//4668 -f 4668//4668 4667//4667 4669//4669 -f 4668//4668 4669//4669 4670//4670 -f 4670//4670 4669//4669 4671//4671 -f 4670//4670 4671//4671 4672//4672 -f 4672//4672 4671//4671 4673//4673 -f 4672//4672 4673//4673 4674//4674 -f 4674//4674 4673//4673 4675//4675 -f 4674//4674 4675//4675 4676//4676 -f 4676//4676 4675//4675 4677//4677 -f 4676//4676 4677//4677 4678//4678 -f 4678//4678 4677//4677 4679//4679 -f 4678//4678 4679//4679 4680//4680 -f 4680//4680 4679//4679 4681//4681 -f 4680//4680 4681//4681 4682//4682 -f 4682//4682 4681//4681 4683//4683 -f 4682//4682 4683//4683 4684//4684 -f 4684//4684 4683//4683 4685//4685 -f 4684//4684 4685//4685 4686//4686 -f 4686//4686 4685//4685 4687//4687 -f 4686//4686 4687//4687 4688//4688 -f 4688//4688 4687//4687 4689//4689 -f 4688//4688 4689//4689 4690//4690 -f 4690//4690 4689//4689 4691//4691 -f 4690//4690 4691//4691 4692//4692 -f 4692//4692 4691//4691 4693//4693 -f 4692//4692 4693//4693 4694//4694 -f 4694//4694 4693//4693 4695//4695 -f 4694//4694 4695//4695 4696//4696 -f 4696//4696 4695//4695 4697//4697 -f 4696//4696 4697//4697 4698//4698 -f 4698//4698 4697//4697 4699//4699 -f 4698//4698 4699//4699 4700//4700 -f 4700//4700 4699//4699 4701//4701 -f 4700//4700 4701//4701 4702//4702 -f 4702//4702 4701//4701 4703//4703 -f 4702//4702 4703//4703 4704//4704 -f 4704//4704 4703//4703 4705//4705 -f 4704//4704 4705//4705 4706//4706 -f 4706//4706 4705//4705 4707//4707 -f 4706//4706 4707//4707 4708//4708 -f 4459//4459 4608//4608 4611//4611 -f 4611//4611 4608//4608 4709//4709 -f 4611//4611 4709//4709 4710//4710 -f 4710//4710 4709//4709 4711//4711 -f 4710//4710 4711//4711 4712//4712 -f 4712//4712 4711//4711 4713//4713 -f 4712//4712 4713//4713 4714//4714 -f 4714//4714 4713//4713 4715//4715 -f 4714//4714 4715//4715 4716//4716 -f 4716//4716 4715//4715 4717//4717 -f 4716//4716 4717//4717 4718//4718 -f 4718//4718 4717//4717 4719//4719 -f 4718//4718 4719//4719 4720//4720 -f 4720//4720 4719//4719 4721//4721 -f 4720//4720 4721//4721 4722//4722 -f 4722//4722 4721//4721 4723//4723 -f 4722//4722 4723//4723 4724//4724 -f 4724//4724 4723//4723 4725//4725 -f 4724//4724 4725//4725 4726//4726 -f 4726//4726 4725//4725 4727//4727 -f 4726//4726 4727//4727 4728//4728 -f 4728//4728 4727//4727 4729//4729 -f 4728//4728 4729//4729 4730//4730 -f 4730//4730 4729//4729 4731//4731 -f 4730//4730 4731//4731 4732//4732 -f 4732//4732 4731//4731 4733//4733 -f 4732//4732 4733//4733 4734//4734 -f 4734//4734 4733//4733 4735//4735 -f 4734//4734 4735//4735 4736//4736 -f 4736//4736 4735//4735 4737//4737 -f 4736//4736 4737//4737 4738//4738 -f 4738//4738 4737//4737 4739//4739 -f 4738//4738 4739//4739 4740//4740 -f 4740//4740 4739//4739 4741//4741 -f 4740//4740 4741//4741 4742//4742 -f 4742//4742 4741//4741 4743//4743 -f 4742//4742 4743//4743 4744//4744 -f 4744//4744 4743//4743 4745//4745 -f 4744//4744 4745//4745 4746//4746 -f 4746//4746 4745//4745 4747//4747 -f 4746//4746 4747//4747 4748//4748 -f 4748//4748 4747//4747 4749//4749 -f 4748//4748 4749//4749 4750//4750 -f 4750//4750 4749//4749 4751//4751 -f 4750//4750 4751//4751 4752//4752 -f 4752//4752 4751//4751 4753//4753 -f 4752//4752 4753//4753 4754//4754 -f 4754//4754 4753//4753 4755//4755 -f 4754//4754 4755//4755 4756//4756 -f 4472//4472 4607//4607 4606//4606 -f 4606//4606 4607//4607 4757//4757 -f 4606//4606 4757//4757 4758//4758 -f 4758//4758 4757//4757 4759//4759 -f 4758//4758 4759//4759 4760//4760 -f 4760//4760 4759//4759 4761//4761 -f 4760//4760 4761//4761 4762//4762 -f 4762//4762 4761//4761 4763//4763 -f 4762//4762 4763//4763 4764//4764 -f 4764//4764 4763//4763 4765//4765 -f 4764//4764 4765//4765 4766//4766 -f 4766//4766 4765//4765 4767//4767 -f 4766//4766 4767//4767 4768//4768 -f 4768//4768 4767//4767 4769//4769 -f 4768//4768 4769//4769 4770//4770 -f 4770//4770 4769//4769 4771//4771 -f 4770//4770 4771//4771 4772//4772 -f 4772//4772 4771//4771 4773//4773 -f 4772//4772 4773//4773 4774//4774 -f 4774//4774 4773//4773 4775//4775 -f 4774//4774 4775//4775 4776//4776 -f 4776//4776 4775//4775 4777//4777 -f 4776//4776 4777//4777 4778//4778 -f 4778//4778 4777//4777 4779//4779 -f 4778//4778 4779//4779 4780//4780 -f 4780//4780 4779//4779 4781//4781 -f 4780//4780 4781//4781 4782//4782 -f 4782//4782 4781//4781 4783//4783 -f 4782//4782 4783//4783 4784//4784 -f 4784//4784 4783//4783 4785//4785 -f 4784//4784 4785//4785 4786//4786 -f 4786//4786 4785//4785 4787//4787 -f 4786//4786 4787//4787 4788//4788 -f 4788//4788 4787//4787 4789//4789 -f 4788//4788 4789//4789 4790//4790 -f 4790//4790 4789//4789 4791//4791 -f 4790//4790 4791//4791 4792//4792 -f 4792//4792 4791//4791 4793//4793 -f 4792//4792 4793//4793 4794//4794 -f 4794//4794 4793//4793 4795//4795 -f 4794//4794 4795//4795 4796//4796 -f 4796//4796 4795//4795 4797//4797 -f 4796//4796 4797//4797 4798//4798 -f 4798//4798 4797//4797 4799//4799 -f 4798//4798 4799//4799 4800//4800 -f 4800//4800 4799//4799 4801//4801 -f 4800//4800 4801//4801 4802//4802 -f 4802//4802 4801//4801 4803//4803 -f 4802//4802 4803//4803 4804//4804 -f 3197//3197 3201//3201 4635//4635 -f 4635//4635 3201//3201 3200//3200 -f 4635//4635 3200//3200 3204//3204 -f 1449//1449 1463//1463 4659//4659 -f 4659//4659 1463//1463 4805//4805 -f 4659//4659 4805//4805 4806//4806 -f 4441//4441 4609//4609 4807//4807 -f 4807//4807 4609//4609 4636//4636 -f 4807//4807 4636//4636 4808//4808 -f 4808//4808 4636//4636 4637//4637 -f 4808//4808 4637//4637 4809//4809 -f 4809//4809 4637//4637 4638//4638 -f 4809//4809 4638//4638 4810//4810 -f 4810//4810 4638//4638 4639//4639 -f 4810//4810 4639//4639 4811//4811 -f 4811//4811 4639//4639 4640//4640 -f 4811//4811 4640//4640 4812//4812 -f 4812//4812 4640//4640 4641//4641 -f 4812//4812 4641//4641 4813//4813 -f 4813//4813 4641//4641 4642//4642 -f 4813//4813 4642//4642 4814//4814 -f 4814//4814 4642//4642 4643//4643 -f 4814//4814 4643//4643 4815//4815 -f 4815//4815 4643//4643 4644//4644 -f 4815//4815 4644//4644 4816//4816 -f 4816//4816 4644//4644 4645//4645 -f 4816//4816 4645//4645 4817//4817 -f 4817//4817 4645//4645 4646//4646 -f 4817//4817 4646//4646 4818//4818 -f 4818//4818 4646//4646 4647//4647 -f 4818//4818 4647//4647 4819//4819 -f 4819//4819 4647//4647 4648//4648 -f 4819//4819 4648//4648 4820//4820 -f 4820//4820 4648//4648 4649//4649 -f 4820//4820 4649//4649 4821//4821 -f 4821//4821 4649//4649 4650//4650 -f 4821//4821 4650//4650 4822//4822 -f 4822//4822 4650//4650 4651//4651 -f 4822//4822 4651//4651 4823//4823 -f 4823//4823 4651//4651 4652//4652 -f 4823//4823 4652//4652 4824//4824 -f 4824//4824 4652//4652 4653//4653 -f 4824//4824 4653//4653 4825//4825 -f 4825//4825 4653//4653 4654//4654 -f 4825//4825 4654//4654 4826//4826 -f 4826//4826 4654//4654 4655//4655 -f 4826//4826 4655//4655 4827//4827 -f 4827//4827 4655//4655 4656//4656 -f 4827//4827 4656//4656 4828//4828 -f 4828//4828 4656//4656 4657//4657 -f 4828//4828 4657//4657 4829//4829 -f 4829//4829 4657//4657 4658//4658 -f 4829//4829 4658//4658 4830//4830 -f 4830//4830 4658//4658 4659//4659 -f 4830//4830 4659//4659 4831//4831 -f 4831//4831 4659//4659 4806//4806 -f 4831//4831 4806//4806 4832//4832 -f 4832//4832 4707//4707 4831//4831 -f 4831//4831 4707//4707 4705//4705 -f 4831//4831 4705//4705 4830//4830 -f 4830//4830 4705//4705 4703//4703 -f 4830//4830 4703//4703 4829//4829 -f 4829//4829 4703//4703 4701//4701 -f 4829//4829 4701//4701 4828//4828 -f 4828//4828 4701//4701 4699//4699 -f 4828//4828 4699//4699 4827//4827 -f 4827//4827 4699//4699 4697//4697 -f 4827//4827 4697//4697 4826//4826 -f 4826//4826 4697//4697 4695//4695 -f 4826//4826 4695//4695 4825//4825 -f 4825//4825 4695//4695 4693//4693 -f 4825//4825 4693//4693 4824//4824 -f 4824//4824 4693//4693 4691//4691 -f 4824//4824 4691//4691 4823//4823 -f 4823//4823 4691//4691 4689//4689 -f 4823//4823 4689//4689 4822//4822 -f 4822//4822 4689//4689 4687//4687 -f 4822//4822 4687//4687 4821//4821 -f 4821//4821 4687//4687 4685//4685 -f 4821//4821 4685//4685 4820//4820 -f 4820//4820 4685//4685 4683//4683 -f 4820//4820 4683//4683 4819//4819 -f 4819//4819 4683//4683 4681//4681 -f 4819//4819 4681//4681 4818//4818 -f 4818//4818 4681//4681 4679//4679 -f 4818//4818 4679//4679 4817//4817 -f 4817//4817 4679//4679 4677//4677 -f 4817//4817 4677//4677 4816//4816 -f 4816//4816 4677//4677 4675//4675 -f 4816//4816 4675//4675 4815//4815 -f 4815//4815 4675//4675 4673//4673 -f 4815//4815 4673//4673 4814//4814 -f 4814//4814 4673//4673 4671//4671 -f 4814//4814 4671//4671 4813//4813 -f 4813//4813 4671//4671 4669//4669 -f 4813//4813 4669//4669 4812//4812 -f 4812//4812 4669//4669 4667//4667 -f 4812//4812 4667//4667 4811//4811 -f 4811//4811 4667//4667 4665//4665 -f 4811//4811 4665//4665 4810//4810 -f 4810//4810 4665//4665 4663//4663 -f 4810//4810 4663//4663 4809//4809 -f 4809//4809 4663//4663 4661//4661 -f 4809//4809 4661//4661 4808//4808 -f 4808//4808 4661//4661 4610//4610 -f 4808//4808 4610//4610 4807//4807 -f 4807//4807 4610//4610 4443//4443 -f 4807//4807 4443//4443 4441//4441 -f 4832//4832 4833//4833 4707//4707 -f 4707//4707 4833//4833 4834//4834 -f 4707//4707 4834//4834 4708//4708 -f 4708//4708 4834//4834 4835//4835 -f 4708//4708 4835//4835 4836//4836 -f 4836//4836 4755//4755 4708//4708 -f 4708//4708 4755//4755 4753//4753 -f 4708//4708 4753//4753 4706//4706 -f 4706//4706 4753//4753 4751//4751 -f 4706//4706 4751//4751 4704//4704 -f 4704//4704 4751//4751 4749//4749 -f 4704//4704 4749//4749 4702//4702 -f 4702//4702 4749//4749 4747//4747 -f 4702//4702 4747//4747 4700//4700 -f 4700//4700 4747//4747 4745//4745 -f 4700//4700 4745//4745 4698//4698 -f 4698//4698 4745//4745 4743//4743 -f 4698//4698 4743//4743 4696//4696 -f 4696//4696 4743//4743 4741//4741 -f 4696//4696 4741//4741 4694//4694 -f 4694//4694 4741//4741 4739//4739 -f 4694//4694 4739//4739 4692//4692 -f 4692//4692 4739//4739 4737//4737 -f 4692//4692 4737//4737 4690//4690 -f 4690//4690 4737//4737 4735//4735 -f 4690//4690 4735//4735 4688//4688 -f 4688//4688 4735//4735 4733//4733 -f 4688//4688 4733//4733 4686//4686 -f 4686//4686 4733//4733 4731//4731 -f 4686//4686 4731//4731 4684//4684 -f 4684//4684 4731//4731 4729//4729 -f 4684//4684 4729//4729 4682//4682 -f 4682//4682 4729//4729 4727//4727 -f 4682//4682 4727//4727 4680//4680 -f 4680//4680 4727//4727 4725//4725 -f 4680//4680 4725//4725 4678//4678 -f 4678//4678 4725//4725 4723//4723 -f 4678//4678 4723//4723 4676//4676 -f 4676//4676 4723//4723 4721//4721 -f 4676//4676 4721//4721 4674//4674 -f 4674//4674 4721//4721 4719//4719 -f 4674//4674 4719//4719 4672//4672 -f 4672//4672 4719//4719 4717//4717 -f 4672//4672 4717//4717 4670//4670 -f 4670//4670 4717//4717 4715//4715 -f 4670//4670 4715//4715 4668//4668 -f 4668//4668 4715//4715 4713//4713 -f 4668//4668 4713//4713 4666//4666 -f 4666//4666 4713//4713 4711//4711 -f 4666//4666 4711//4711 4664//4664 -f 4664//4664 4711//4711 4709//4709 -f 4664//4664 4709//4709 4662//4662 -f 4662//4662 4709//4709 4608//4608 -f 4662//4662 4608//4608 4660//4660 -f 4660//4660 4608//4608 4454//4454 -f 4660//4660 4454//4454 4446//4446 -f 4836//4836 4837//4837 4755//4755 -f 4755//4755 4837//4837 4838//4838 -f 4755//4755 4838//4838 4756//4756 -f 4756//4756 4838//4838 4839//4839 -f 4756//4756 4839//4839 4840//4840 -f 4456//4456 4611//4611 4841//4841 -f 4841//4841 4611//4611 4710//4710 -f 4841//4841 4710//4710 4842//4842 -f 4842//4842 4710//4710 4712//4712 -f 4842//4842 4712//4712 4843//4843 -f 4843//4843 4712//4712 4714//4714 -f 4843//4843 4714//4714 4844//4844 -f 4844//4844 4714//4714 4716//4716 -f 4844//4844 4716//4716 4845//4845 -f 4845//4845 4716//4716 4718//4718 -f 4845//4845 4718//4718 4846//4846 -f 4846//4846 4718//4718 4720//4720 -f 4846//4846 4720//4720 4847//4847 -f 4847//4847 4720//4720 4722//4722 -f 4847//4847 4722//4722 4848//4848 -f 4848//4848 4722//4722 4724//4724 -f 4848//4848 4724//4724 4849//4849 -f 4849//4849 4724//4724 4726//4726 -f 4849//4849 4726//4726 4850//4850 -f 4850//4850 4726//4726 4728//4728 -f 4850//4850 4728//4728 4851//4851 -f 4851//4851 4728//4728 4730//4730 -f 4851//4851 4730//4730 4852//4852 -f 4852//4852 4730//4730 4732//4732 -f 4852//4852 4732//4732 4853//4853 -f 4853//4853 4732//4732 4734//4734 -f 4853//4853 4734//4734 4854//4854 -f 4854//4854 4734//4734 4736//4736 -f 4854//4854 4736//4736 4855//4855 -f 4855//4855 4736//4736 4738//4738 -f 4855//4855 4738//4738 4856//4856 -f 4856//4856 4738//4738 4740//4740 -f 4856//4856 4740//4740 4857//4857 -f 4857//4857 4740//4740 4742//4742 -f 4857//4857 4742//4742 4858//4858 -f 4858//4858 4742//4742 4744//4744 -f 4858//4858 4744//4744 4859//4859 -f 4859//4859 4744//4744 4746//4746 -f 4859//4859 4746//4746 4860//4860 -f 4860//4860 4746//4746 4748//4748 -f 4860//4860 4748//4748 4861//4861 -f 4861//4861 4748//4748 4750//4750 -f 4861//4861 4750//4750 4862//4862 -f 4862//4862 4750//4750 4752//4752 -f 4862//4862 4752//4752 4863//4863 -f 4863//4863 4752//4752 4754//4754 -f 4863//4863 4754//4754 4864//4864 -f 4864//4864 4754//4754 4756//4756 -f 4864//4864 4756//4756 4865//4865 -f 4865//4865 4756//4756 4840//4840 -f 4865//4865 4840//4840 4866//4866 -f 4866//4866 4803//4803 4865//4865 -f 4865//4865 4803//4803 4801//4801 -f 4865//4865 4801//4801 4864//4864 -f 4864//4864 4801//4801 4799//4799 -f 4864//4864 4799//4799 4863//4863 -f 4863//4863 4799//4799 4797//4797 -f 4863//4863 4797//4797 4862//4862 -f 4862//4862 4797//4797 4795//4795 -f 4862//4862 4795//4795 4861//4861 -f 4861//4861 4795//4795 4793//4793 -f 4861//4861 4793//4793 4860//4860 -f 4860//4860 4793//4793 4791//4791 -f 4860//4860 4791//4791 4859//4859 -f 4859//4859 4791//4791 4789//4789 -f 4859//4859 4789//4789 4858//4858 -f 4858//4858 4789//4789 4787//4787 -f 4858//4858 4787//4787 4857//4857 -f 4857//4857 4787//4787 4785//4785 -f 4857//4857 4785//4785 4856//4856 -f 4856//4856 4785//4785 4783//4783 -f 4856//4856 4783//4783 4855//4855 -f 4855//4855 4783//4783 4781//4781 -f 4855//4855 4781//4781 4854//4854 -f 4854//4854 4781//4781 4779//4779 -f 4854//4854 4779//4779 4853//4853 -f 4853//4853 4779//4779 4777//4777 -f 4853//4853 4777//4777 4852//4852 -f 4852//4852 4777//4777 4775//4775 -f 4852//4852 4775//4775 4851//4851 -f 4851//4851 4775//4775 4773//4773 -f 4851//4851 4773//4773 4850//4850 -f 4850//4850 4773//4773 4771//4771 -f 4850//4850 4771//4771 4849//4849 -f 4849//4849 4771//4771 4769//4769 -f 4849//4849 4769//4769 4848//4848 -f 4848//4848 4769//4769 4767//4767 -f 4848//4848 4767//4767 4847//4847 -f 4847//4847 4767//4767 4765//4765 -f 4847//4847 4765//4765 4846//4846 -f 4846//4846 4765//4765 4763//4763 -f 4846//4846 4763//4763 4845//4845 -f 4845//4845 4763//4763 4761//4761 -f 4845//4845 4761//4761 4844//4844 -f 4844//4844 4761//4761 4759//4759 -f 4844//4844 4759//4759 4843//4843 -f 4843//4843 4759//4759 4757//4757 -f 4843//4843 4757//4757 4842//4842 -f 4842//4842 4757//4757 4607//4607 -f 4842//4842 4607//4607 4841//4841 -f 4841//4841 4607//4607 4461//4461 -f 4841//4841 4461//4461 4456//4456 -f 4866//4866 4867//4867 4803//4803 -f 4803//4803 4867//4867 4868//4868 -f 4803//4803 4868//4868 4804//4804 -f 4804//4804 4868//4868 4869//4869 -f 4804//4804 4869//4869 4870//4870 -f 4470//4470 4606//4606 4612//4612 -f 4612//4612 4606//4606 4758//4758 -f 4612//4612 4758//4758 4613//4613 -f 4613//4613 4758//4758 4760//4760 -f 4613//4613 4760//4760 4614//4614 -f 4614//4614 4760//4760 4762//4762 -f 4614//4614 4762//4762 4617//4617 -f 4617//4617 4762//4762 4764//4764 -f 4617//4617 4764//4764 4616//4616 -f 4616//4616 4764//4764 4766//4766 -f 4616//4616 4766//4766 4615//4615 -f 4615//4615 4766//4766 4768//4768 -f 4615//4615 4768//4768 4618//4618 -f 4618//4618 4768//4768 4770//4770 -f 4618//4618 4770//4770 4619//4619 -f 4619//4619 4770//4770 4772//4772 -f 4619//4619 4772//4772 4623//4623 -f 4623//4623 4772//4772 4774//4774 -f 4623//4623 4774//4774 4622//4622 -f 4622//4622 4774//4774 4776//4776 -f 4622//4622 4776//4776 4621//4621 -f 4621//4621 4776//4776 4778//4778 -f 4621//4621 4778//4778 4620//4620 -f 4620//4620 4778//4778 4780//4780 -f 4620//4620 4780//4780 4625//4625 -f 4625//4625 4780//4780 4782//4782 -f 4625//4625 4782//4782 4624//4624 -f 4624//4624 4782//4782 4784//4784 -f 4624//4624 4784//4784 4628//4628 -f 4628//4628 4784//4784 4786//4786 -f 4628//4628 4786//4786 4627//4627 -f 4627//4627 4786//4786 4788//4788 -f 4627//4627 4788//4788 4626//4626 -f 4626//4626 4788//4788 4790//4790 -f 4626//4626 4790//4790 4630//4630 -f 4630//4630 4790//4790 4792//4792 -f 4630//4630 4792//4792 4629//4629 -f 4629//4629 4792//4792 4794//4794 -f 4629//4629 4794//4794 4631//4631 -f 4631//4631 4794//4794 4796//4796 -f 4631//4631 4796//4796 4632//4632 -f 4632//4632 4796//4796 4798//4798 -f 4632//4632 4798//4798 4633//4633 -f 4633//4633 4798//4798 4800//4800 -f 4633//4633 4800//4800 4634//4634 -f 4634//4634 4800//4800 4802//4802 -f 4634//4634 4802//4802 4635//4635 -f 4635//4635 4802//4802 4804//4804 -f 4635//4635 4804//4804 4871//4871 -f 4871//4871 4804//4804 4870//4870 -f 4871//4871 4870//4870 4872//4872 -f 3197//3197 4635//4635 3198//3198 -f 3198//3198 4635//4635 4871//4871 -f 3198//3198 4871//4871 3199//3199 -f 3199//3199 4871//4871 4872//4872 -f 3199//3199 4872//4872 436//436 -f 4873//4873 4874//4874 4875//4875 -f 4876//4876 4877//4877 4878//4878 -f 1708//1708 1707//1707 4879//4879 -f 1723//1723 1726//1726 4880//4880 -f 1756//1756 1755//1755 4881//4881 -f 4881//4881 1755//1755 263//263 -f 1758//1758 4882//4882 1759//1759 -f 1759//1759 4882//4882 1754//1754 -f 1748//1748 1749//1749 4883//4883 -f 4883//4883 1749//1749 1751//1751 -f 4883//4883 1751//1751 4882//4882 -f 4882//4882 1751//1751 1752//1752 -f 4882//4882 1752//1752 1754//1754 -f 1740//1740 1742//1742 4884//4884 -f 1742//1742 1743//1743 4884//4884 -f 4884//4884 1743//1743 1745//1745 -f 4884//4884 1745//1745 4883//4883 -f 4883//4883 1745//1745 1746//1746 -f 4883//4883 1746//1746 1748//1748 -f 1726//1726 1728//1728 4885//4885 -f 4885//4885 1728//1728 1732//1732 -f 1732//1732 1731//1731 4885//4885 -f 4885//4885 1731//1731 1730//1730 -f 4885//4885 1730//1730 4886//4886 -f 4886//4886 1730//1730 1733//1733 -f 4886//4886 1733//1733 1735//1735 -f 1735//1735 1739//1739 4886//4886 -f 4886//4886 1739//1739 1738//1738 -f 4886//4886 1738//1738 4884//4884 -f 4884//4884 1738//1738 1737//1737 -f 4884//4884 1737//1737 1740//1740 -f 1721//1721 1725//1725 4880//4880 -f 4880//4880 1725//1725 1724//1724 -f 4880//4880 1724//1724 1723//1723 -f 1713//1713 1718//1718 4887//4887 -f 4887//4887 1718//1718 1717//1717 -f 1717//1717 1715//1715 4887//4887 -f 4887//4887 1715//1715 1714//1714 -f 4887//4887 1714//1714 4880//4880 -f 4880//4880 1714//1714 1719//1719 -f 4880//4880 1719//1719 1721//1721 -f 1707//1707 1705//1705 4888//4888 -f 4888//4888 1705//1705 1704//1704 -f 4888//4888 1704//1704 1709//1709 -f 1709//1709 1711//1711 4888//4888 -f 4888//4888 1711//1711 1713//1713 -f 293//293 302//302 1703//1703 -f 293//293 1703//1703 4879//4879 -f 4879//4879 1703//1703 1702//1702 -f 4879//4879 1702//1702 1708//1708 -f 4889//4889 4890//4890 340//340 -f 340//340 4890//4890 4891//4891 -f 340//340 4891//4891 337//337 -f 4889//4889 4892//4892 4893//4893 -f 4893//4893 4892//4892 4894//4894 -f 4895//4895 4896//4896 4897//4897 -f 4897//4897 4896//4896 4898//4898 -f 4897//4897 4898//4898 4899//4899 -f 4900//4900 4901//4901 4902//4902 -f 4902//4902 4901//4901 4903//4903 -f 4904//4904 4905//4905 4906//4906 -f 4906//4906 4905//4905 4907//4907 -f 4906//4906 4907//4907 4908//4908 -f 4909//4909 4910//4910 4911//4911 -f 4911//4911 4910//4910 4912//4912 -f 4873//4873 4875//4875 4913//4913 -f 4913//4913 1410//1410 4914//4914 -f 4914//4914 1410//1410 1415//1415 -f 1419//1419 1423//1423 4915//4915 -f 4915//4915 1423//1423 4916//4916 -f 4917//4917 4918//4918 4919//4919 -f 4919//4919 4918//4918 4920//4920 -f 4919//4919 4920//4920 4921//4921 -f 4922//4922 4923//4923 4924//4924 -f 4924//4924 4923//4923 4917//4917 -f 4925//4925 4926//4926 4927//4927 -f 4927//4927 4926//4926 4928//4928 -f 4927//4927 4928//4928 4922//4922 -f 4925//4925 4929//4929 4930//4930 -f 4930//4930 4929//4929 4931//4931 -f 4931//4931 4929//4929 4932//4932 -f 4932//4932 4929//4929 4933//4933 -f 4932//4932 4933//4933 4934//4934 -f 4935//4935 4936//4936 4937//4937 -f 4937//4937 4936//4936 4938//4938 -f 4937//4937 4938//4938 4933//4933 -f 4933//4933 4938//4938 4939//4939 -f 4933//4933 4939//4939 4934//4934 -f 4881//4881 4940//4940 4937//4937 -f 4937//4937 4940//4940 4941//4941 -f 4937//4937 4941//4941 4935//4935 -f 4942//4942 4943//4943 4881//4881 -f 4881//4881 4943//4943 4944//4944 -f 4881//4881 4944//4944 4940//4940 -f 263//263 262//262 4881//4881 -f 4881//4881 262//262 442//442 -f 4881//4881 442//442 4942//4942 -f 4942//4942 442//442 441//441 -f 4942//4942 441//441 4945//4945 -f 4945//4945 441//441 439//439 -f 4889//4889 340//340 4892//4892 -f 4892//4892 340//340 332//332 -f 4892//4892 332//332 4946//4946 -f 332//332 334//334 4946//4946 -f 4946//4946 334//334 323//323 -f 4946//4946 323//323 4947//4947 -f 323//323 325//325 4947//4947 -f 4947//4947 325//325 327//327 -f 4947//4947 327//327 4948//4948 -f 4948//4948 327//327 329//329 -f 4948//4948 329//329 4949//4949 -f 329//329 308//308 4949//4949 -f 4949//4949 308//308 310//310 -f 4949//4949 310//310 4950//4950 -f 4950//4950 310//310 312//312 -f 312//312 314//314 4950//4950 -f 4950//4950 314//314 316//316 -f 4950//4950 316//316 4951//4951 -f 4951//4951 316//316 318//318 -f 4951//4951 318//318 4952//4952 -f 318//318 320//320 4952//4952 -f 4952//4952 320//320 303//303 -f 4952//4952 303//303 4879//4879 -f 4879//4879 303//303 305//305 -f 4879//4879 305//305 293//293 -f 1707//1707 4888//4888 4879//4879 -f 4879//4879 4888//4888 4953//4953 -f 4879//4879 4953//4953 4952//4952 -f 4952//4952 4953//4953 4954//4954 -f 4952//4952 4954//4954 4951//4951 -f 4951//4951 4954//4954 4955//4955 -f 4951//4951 4955//4955 4950//4950 -f 4950//4950 4955//4955 4956//4956 -f 4950//4950 4956//4956 4949//4949 -f 4949//4949 4956//4956 4957//4957 -f 4949//4949 4957//4957 4948//4948 -f 4948//4948 4957//4957 4958//4958 -f 4948//4948 4958//4958 4947//4947 -f 4947//4947 4958//4958 4959//4959 -f 4947//4947 4959//4959 4946//4946 -f 4946//4946 4959//4959 4897//4897 -f 4946//4946 4897//4897 4892//4892 -f 4892//4892 4897//4897 4899//4899 -f 4892//4892 4899//4899 4894//4894 -f 1713//1713 4887//4887 4888//4888 -f 4888//4888 4887//4887 4960//4960 -f 4888//4888 4960//4960 4953//4953 -f 4953//4953 4960//4960 4961//4961 -f 4953//4953 4961//4961 4954//4954 -f 4954//4954 4961//4961 4962//4962 -f 4954//4954 4962//4962 4955//4955 -f 4955//4955 4962//4962 4963//4963 -f 4955//4955 4963//4963 4956//4956 -f 4956//4956 4963//4963 4964//4964 -f 4956//4956 4964//4964 4957//4957 -f 4957//4957 4964//4964 4965//4965 -f 4957//4957 4965//4965 4958//4958 -f 4958//4958 4965//4965 4966//4966 -f 4958//4958 4966//4966 4959//4959 -f 4959//4959 4966//4966 4901//4901 -f 4959//4959 4901//4901 4897//4897 -f 4897//4897 4901//4901 4900//4900 -f 4897//4897 4900//4900 4895//4895 -f 1726//1726 4885//4885 4880//4880 -f 4880//4880 4885//4885 4967//4967 -f 4880//4880 4967//4967 4887//4887 -f 4887//4887 4967//4967 4968//4968 -f 4887//4887 4968//4968 4960//4960 -f 4960//4960 4968//4968 4969//4969 -f 4960//4960 4969//4969 4961//4961 -f 4961//4961 4969//4969 4970//4970 -f 4961//4961 4970//4970 4962//4962 -f 4962//4962 4970//4970 4971//4971 -f 4962//4962 4971//4971 4963//4963 -f 4963//4963 4971//4971 4972//4972 -f 4963//4963 4972//4972 4964//4964 -f 4964//4964 4972//4972 4973//4973 -f 4964//4964 4973//4973 4965//4965 -f 4965//4965 4973//4973 4974//4974 -f 4965//4965 4974//4974 4966//4966 -f 4966//4966 4974//4974 4878//4878 -f 4966//4966 4878//4878 4901//4901 -f 4901//4901 4878//4878 4877//4877 -f 4901//4901 4877//4877 4903//4903 -f 1758//1758 1756//1756 4882//4882 -f 4882//4882 1756//1756 4881//4881 -f 4882//4882 4881//4881 4883//4883 -f 4883//4883 4881//4881 4937//4937 -f 4883//4883 4937//4937 4884//4884 -f 4884//4884 4937//4937 4933//4933 -f 4884//4884 4933//4933 4886//4886 -f 4886//4886 4933//4933 4929//4929 -f 4925//4925 4927//4927 4929//4929 -f 4929//4929 4927//4927 4975//4975 -f 4929//4929 4975//4975 4886//4886 -f 4886//4886 4975//4975 4976//4976 -f 4886//4886 4976//4976 4885//4885 -f 4885//4885 4976//4976 4977//4977 -f 4885//4885 4977//4977 4967//4967 -f 4967//4967 4977//4977 4978//4978 -f 4967//4967 4978//4978 4968//4968 -f 4968//4968 4978//4978 4979//4979 -f 4968//4968 4979//4979 4969//4969 -f 4969//4969 4979//4979 4980//4980 -f 4969//4969 4980//4980 4970//4970 -f 4970//4970 4980//4980 4981//4981 -f 4970//4970 4981//4981 4971//4971 -f 4971//4971 4981//4981 4982//4982 -f 4971//4971 4982//4982 4972//4972 -f 4972//4972 4982//4982 4983//4983 -f 4972//4972 4983//4983 4973//4973 -f 4973//4973 4983//4983 4906//4906 -f 4973//4973 4906//4906 4974//4974 -f 4974//4974 4906//4906 4908//4908 -f 4974//4974 4908//4908 4878//4878 -f 4878//4878 4908//4908 4984//4984 -f 4878//4878 4984//4984 4876//4876 -f 4922//4922 4924//4924 4927//4927 -f 4927//4927 4924//4924 4985//4985 -f 4927//4927 4985//4985 4975//4975 -f 4975//4975 4985//4985 4986//4986 -f 4975//4975 4986//4986 4976//4976 -f 4976//4976 4986//4986 4987//4987 -f 4976//4976 4987//4987 4977//4977 -f 4977//4977 4987//4987 4988//4988 -f 4977//4977 4988//4988 4978//4978 -f 4978//4978 4988//4988 4989//4989 -f 4978//4978 4989//4989 4979//4979 -f 4979//4979 4989//4989 4990//4990 -f 4979//4979 4990//4990 4980//4980 -f 4980//4980 4990//4990 4991//4991 -f 4980//4980 4991//4991 4981//4981 -f 4981//4981 4991//4991 4992//4992 -f 4981//4981 4992//4992 4982//4982 -f 4982//4982 4992//4992 4993//4993 -f 4982//4982 4993//4993 4983//4983 -f 4983//4983 4993//4993 4910//4910 -f 4983//4983 4910//4910 4906//4906 -f 4906//4906 4910//4910 4909//4909 -f 4906//4906 4909//4909 4904//4904 -f 4917//4917 4919//4919 4924//4924 -f 4924//4924 4919//4919 4994//4994 -f 4924//4924 4994//4994 4985//4985 -f 4985//4985 4994//4994 4995//4995 -f 4985//4985 4995//4995 4986//4986 -f 4986//4986 4995//4995 4996//4996 -f 4986//4986 4996//4996 4987//4987 -f 4987//4987 4996//4996 4997//4997 -f 4987//4987 4997//4997 4988//4988 -f 4988//4988 4997//4997 4998//4998 -f 4988//4988 4998//4998 4989//4989 -f 4989//4989 4998//4998 4999//4999 -f 4989//4989 4999//4999 4990//4990 -f 4990//4990 4999//4999 5000//5000 -f 4990//4990 5000//5000 4991//4991 -f 4991//4991 5000//5000 5001//5001 -f 4991//4991 5001//5001 4992//4992 -f 4992//4992 5001//5001 5002//5002 -f 4992//4992 5002//5002 4993//4993 -f 4993//4993 5002//5002 4875//4875 -f 4993//4993 4875//4875 4910//4910 -f 4910//4910 4875//4875 4874//4874 -f 4910//4910 4874//4874 4912//4912 -f 4913//4913 4875//4875 1410//1410 -f 1410//1410 4875//4875 5002//5002 -f 1410//1410 5002//5002 1411//1411 -f 1411//1411 5002//5002 5001//5001 -f 1411//1411 5001//5001 1412//1412 -f 1412//1412 5001//5001 5000//5000 -f 1412//1412 5000//5000 1405//1405 -f 1405//1405 5000//5000 4999//4999 -f 1405//1405 4999//4999 1406//1406 -f 1406//1406 4999//4999 4998//4998 -f 1406//1406 4998//4998 1407//1407 -f 1407//1407 4998//4998 4997//4997 -f 1407//1407 4997//4997 1408//1408 -f 1408//1408 4997//4997 4996//4996 -f 1408//1408 4996//4996 1409//1409 -f 1409//1409 4996//4996 4995//4995 -f 1409//1409 4995//4995 1421//1421 -f 1421//1421 4995//4995 4994//4994 -f 1421//1421 4994//4994 1422//1422 -f 1422//1422 4994//4994 4919//4919 -f 1422//1422 4919//4919 1423//1423 -f 1423//1423 4919//4919 4921//4921 -f 1423//1423 4921//4921 4916//4916 -f 4866//4866 4840//4840 5003//5003 -f 5004//5004 5005//5005 5006//5006 -f 439//439 437//437 5007//5007 -f 5007//5007 437//437 5008//5008 -f 5009//5009 5010//5010 5011//5011 -f 5011//5011 5010//5010 5012//5012 -f 5011//5011 5012//5012 5006//5006 -f 5006//5006 5012//5012 5013//5013 -f 5006//5006 5013//5013 5004//5004 -f 5011//5011 4868//4868 4867//4867 -f 4866//4866 5003//5003 4867//4867 -f 4867//4867 5003//5003 5014//5014 -f 4867//4867 5014//5014 5011//5011 -f 5011//5011 5014//5014 5015//5015 -f 5011//5011 5015//5015 5009//5009 -f 4838//4838 5016//5016 4839//4839 -f 4839//4839 5016//5016 5017//5017 -f 4839//4839 5017//5017 4840//4840 -f 4840//4840 5017//5017 5018//5018 -f 4840//4840 5018//5018 5003//5003 -f 4833//4833 5019//5019 4834//4834 -f 4834//4834 5019//5019 5020//5020 -f 4834//4834 5020//5020 4835//4835 -f 4835//4835 5020//5020 4836//4836 -f 5020//5020 5021//5021 4836//4836 -f 4836//4836 5021//5021 5022//5022 -f 4836//4836 5022//5022 4837//4837 -f 4837//4837 5022//5022 5023//5023 -f 4837//4837 5023//5023 4838//4838 -f 4838//4838 5023//5023 5024//5024 -f 4838//4838 5024//5024 5016//5016 -f 1460//1460 5025//5025 1463//1463 -f 1463//1463 5025//5025 5026//5026 -f 1463//1463 5026//5026 4805//4805 -f 4805//4805 5026//5026 5027//5027 -f 4805//4805 5027//5027 4806//4806 -f 4806//4806 5027//5027 5028//5028 -f 4806//4806 5028//5028 4832//4832 -f 4832//4832 5028//5028 5029//5029 -f 4832//4832 5029//5029 4833//4833 -f 4833//4833 5029//5029 5030//5030 -f 4833//4833 5030//5030 5019//5019 -f 436//436 5006//5006 437//437 -f 437//437 5006//5006 5005//5005 -f 437//437 5005//5005 5008//5008 -f 436//436 4872//4872 5006//5006 -f 5006//5006 4872//4872 4870//4870 -f 5006//5006 4870//4870 5011//5011 -f 5011//5011 4870//4870 4869//4869 -f 5011//5011 4869//4869 4868//4868 -f 5031//5031 2776//2776 2777//2777 -f 5032//5032 5033//5033 5034//5034 -f 5034//5034 5033//5033 1348//1348 -f 5035//5035 5036//5036 5037//5037 -f 5037//5037 5036//5036 5038//5038 -f 5037//5037 5038//5038 5032//5032 -f 5039//5039 5040//5040 5041//5041 -f 5041//5041 5040//5040 5035//5035 -f 5042//5042 5043//5043 5044//5044 -f 5044//5044 5043//5043 5039//5039 -f 5045//5045 5046//5046 5047//5047 -f 5047//5047 5046//5046 5042//5042 -f 5048//5048 5049//5049 5045//5045 -f 5049//5049 5048//5048 5050//5050 -f 5031//5031 2777//2777 5051//5051 -f 5051//5051 5052//5052 5053//5053 -f 5053//5053 5052//5052 5054//5054 -f 5055//5055 5056//5056 5057//5057 -f 5058//5058 5059//5059 5060//5060 -f 5061//5061 5062//5062 5063//5063 -f 1389//1389 1370//1370 5064//5064 -f 5051//5051 2777//2777 5052//5052 -f 5052//5052 2777//2777 2778//2778 -f 5052//5052 2778//2778 5065//5065 -f 2778//2778 2779//2779 5065//5065 -f 5065//5065 2779//2779 2780//2780 -f 5065//5065 2780//2780 5066//5066 -f 2780//2780 2781//2781 5066//5066 -f 5066//5066 2781//2781 2782//2782 -f 5066//5066 2782//2782 5067//5067 -f 5067//5067 2782//2782 2783//2783 -f 5067//5067 2783//2783 5068//5068 -f 2783//2783 2784//2784 5068//5068 -f 5068//5068 2784//2784 2785//2785 -f 5068//5068 2785//2785 5069//5069 -f 5069//5069 2785//2785 2786//2786 -f 2786//2786 2787//2787 5069//5069 -f 5069//5069 2787//2787 2788//2788 -f 5069//5069 2788//2788 5070//5070 -f 5070//5070 2788//2788 2789//2789 -f 5070//5070 2789//2789 5071//5071 -f 2789//2789 2791//2791 5071//5071 -f 5071//5071 2791//2791 2792//2792 -f 5071//5071 2792//2792 5072//5072 -f 2792//2792 2793//2793 5072//5072 -f 5072//5072 2793//2793 2794//2794 -f 5072//5072 2794//2794 5073//5073 -f 5073//5073 2794//2794 2795//2795 -f 5073//5073 2795//2795 5074//5074 -f 2795//2795 2796//2796 5074//5074 -f 5074//5074 2796//2796 2797//2797 -f 5074//5074 2797//2797 5048//5048 -f 2804//2804 5075//5075 2806//2806 -f 2806//2806 5075//5075 5050//5050 -f 2806//2806 5050//5050 2807//2807 -f 2807//2807 5050//5050 5048//5048 -f 2807//2807 5048//5048 2798//2798 -f 2798//2798 5048//5048 2797//2797 -f 5045//5045 5047//5047 5048//5048 -f 5048//5048 5047//5047 5076//5076 -f 5048//5048 5076//5076 5074//5074 -f 5074//5074 5076//5076 5077//5077 -f 5074//5074 5077//5077 5073//5073 -f 5073//5073 5077//5077 5078//5078 -f 5073//5073 5078//5078 5072//5072 -f 5072//5072 5078//5078 5079//5079 -f 5072//5072 5079//5079 5071//5071 -f 5071//5071 5079//5079 5080//5080 -f 5071//5071 5080//5080 5070//5070 -f 5070//5070 5080//5080 5081//5081 -f 5070//5070 5081//5081 5069//5069 -f 5069//5069 5081//5081 5082//5082 -f 5069//5069 5082//5082 5068//5068 -f 5068//5068 5082//5082 5083//5083 -f 5068//5068 5083//5083 5067//5067 -f 5067//5067 5083//5083 5084//5084 -f 5067//5067 5084//5084 5066//5066 -f 5066//5066 5084//5084 5085//5085 -f 5066//5066 5085//5085 5065//5065 -f 5065//5065 5085//5085 5086//5086 -f 5065//5065 5086//5086 5052//5052 -f 5052//5052 5086//5086 5087//5087 -f 5052//5052 5087//5087 5054//5054 -f 5042//5042 5044//5044 5047//5047 -f 5047//5047 5044//5044 5088//5088 -f 5047//5047 5088//5088 5076//5076 -f 5076//5076 5088//5088 5089//5089 -f 5076//5076 5089//5089 5077//5077 -f 5077//5077 5089//5089 5090//5090 -f 5077//5077 5090//5090 5078//5078 -f 5078//5078 5090//5090 5091//5091 -f 5078//5078 5091//5091 5079//5079 -f 5079//5079 5091//5091 5092//5092 -f 5079//5079 5092//5092 5080//5080 -f 5080//5080 5092//5092 5093//5093 -f 5080//5080 5093//5093 5081//5081 -f 5081//5081 5093//5093 5094//5094 -f 5081//5081 5094//5094 5082//5082 -f 5082//5082 5094//5094 5095//5095 -f 5082//5082 5095//5095 5083//5083 -f 5083//5083 5095//5095 5096//5096 -f 5083//5083 5096//5096 5084//5084 -f 5084//5084 5096//5096 5097//5097 -f 5084//5084 5097//5097 5085//5085 -f 5085//5085 5097//5097 5098//5098 -f 5085//5085 5098//5098 5086//5086 -f 5039//5039 5041//5041 5044//5044 -f 5044//5044 5041//5041 5099//5099 -f 5044//5044 5099//5099 5088//5088 -f 5088//5088 5099//5099 5100//5100 -f 5088//5088 5100//5100 5089//5089 -f 5089//5089 5100//5100 5101//5101 -f 5089//5089 5101//5101 5090//5090 -f 5090//5090 5101//5101 5102//5102 -f 5090//5090 5102//5102 5091//5091 -f 5091//5091 5102//5102 5103//5103 -f 5091//5091 5103//5103 5092//5092 -f 5092//5092 5103//5103 5104//5104 -f 5092//5092 5104//5104 5093//5093 -f 5093//5093 5104//5104 5105//5105 -f 5093//5093 5105//5105 5094//5094 -f 5094//5094 5105//5105 5106//5106 -f 5094//5094 5106//5106 5095//5095 -f 5095//5095 5106//5106 5107//5107 -f 5095//5095 5107//5107 5096//5096 -f 5096//5096 5107//5107 5108//5108 -f 5096//5096 5108//5108 5097//5097 -f 5097//5097 5108//5108 5055//5055 -f 5097//5097 5055//5055 5098//5098 -f 5098//5098 5055//5055 5057//5057 -f 5098//5098 5057//5057 5086//5086 -f 5086//5086 5057//5057 5109//5109 -f 5086//5086 5109//5109 5087//5087 -f 5035//5035 5110//5110 5041//5041 -f 5041//5041 5110//5110 5111//5111 -f 5041//5041 5111//5111 5099//5099 -f 5099//5099 5111//5111 5112//5112 -f 5099//5099 5112//5112 5100//5100 -f 5100//5100 5112//5112 5113//5113 -f 5100//5100 5113//5113 5101//5101 -f 5101//5101 5113//5113 5114//5114 -f 5101//5101 5114//5114 5102//5102 -f 5102//5102 5114//5114 5115//5115 -f 5102//5102 5115//5115 5103//5103 -f 5103//5103 5115//5115 5116//5116 -f 5103//5103 5116//5116 5104//5104 -f 5104//5104 5116//5116 5117//5117 -f 5104//5104 5117//5117 5105//5105 -f 5105//5105 5117//5117 5118//5118 -f 5105//5105 5118//5118 5106//5106 -f 5106//5106 5118//5118 5119//5119 -f 5106//5106 5119//5119 5107//5107 -f 5107//5107 5119//5119 5120//5120 -f 5107//5107 5120//5120 5108//5108 -f 5108//5108 5120//5120 5121//5121 -f 5108//5108 5121//5121 5055//5055 -f 5035//5035 5037//5037 5110//5110 -f 5110//5110 5037//5037 5122//5122 -f 5110//5110 5122//5122 5111//5111 -f 5111//5111 5122//5122 5123//5123 -f 5111//5111 5123//5123 5112//5112 -f 5112//5112 5123//5123 5124//5124 -f 5112//5112 5124//5124 5113//5113 -f 5113//5113 5124//5124 5125//5125 -f 5113//5113 5125//5125 5114//5114 -f 5114//5114 5125//5125 5126//5126 -f 5114//5114 5126//5126 5115//5115 -f 5115//5115 5126//5126 5127//5127 -f 5115//5115 5127//5127 5116//5116 -f 5116//5116 5127//5127 5128//5128 -f 5116//5116 5128//5128 5117//5117 -f 5117//5117 5128//5128 5129//5129 -f 5117//5117 5129//5129 5118//5118 -f 5118//5118 5129//5129 5130//5130 -f 5118//5118 5130//5130 5119//5119 -f 5119//5119 5130//5130 5131//5131 -f 5119//5119 5131//5131 5120//5120 -f 5120//5120 5131//5131 5058//5058 -f 5120//5120 5058//5058 5121//5121 -f 5121//5121 5058//5058 5060//5060 -f 5121//5121 5060//5060 5055//5055 -f 5055//5055 5060//5060 5132//5132 -f 5055//5055 5132//5132 5056//5056 -f 5032//5032 5034//5034 5037//5037 -f 5037//5037 5034//5034 5133//5133 -f 5037//5037 5133//5133 5122//5122 -f 5122//5122 5133//5133 5134//5134 -f 5122//5122 5134//5134 5123//5123 -f 5123//5123 5134//5134 5135//5135 -f 5123//5123 5135//5135 5124//5124 -f 5124//5124 5135//5135 5136//5136 -f 5124//5124 5136//5136 5125//5125 -f 5125//5125 5136//5136 5137//5137 -f 5125//5125 5137//5137 5126//5126 -f 5126//5126 5137//5137 5138//5138 -f 5126//5126 5138//5138 5127//5127 -f 5127//5127 5138//5138 5139//5139 -f 5127//5127 5139//5139 5128//5128 -f 5128//5128 5139//5139 5140//5140 -f 5128//5128 5140//5140 5129//5129 -f 5129//5129 5140//5140 5141//5141 -f 5129//5129 5141//5141 5130//5130 -f 5130//5130 5141//5141 5142//5142 -f 5130//5130 5142//5142 5131//5131 -f 5131//5131 5142//5142 5061//5061 -f 5131//5131 5061//5061 5058//5058 -f 5058//5058 5061//5061 5063//5063 -f 5058//5058 5063//5063 5059//5059 -f 1348//1348 1396//1396 5034//5034 -f 5034//5034 1396//1396 1395//1395 -f 5034//5034 1395//1395 5133//5133 -f 5133//5133 1395//1395 1385//1385 -f 5133//5133 1385//1385 5134//5134 -f 5134//5134 1385//1385 1384//1384 -f 5134//5134 1384//1384 5135//5135 -f 5135//5135 1384//1384 1383//1383 -f 5135//5135 1383//1383 5136//5136 -f 5136//5136 1383//1383 1378//1378 -f 5136//5136 1378//1378 5137//5137 -f 5137//5137 1378//1378 1380//1380 -f 5137//5137 1380//1380 5138//5138 -f 5138//5138 1380//1380 1382//1382 -f 5138//5138 1382//1382 5139//5139 -f 5139//5139 1382//1382 1388//1388 -f 5139//5139 1388//1388 5140//5140 -f 5140//5140 1388//1388 1387//1387 -f 5140//5140 1387//1387 5141//5141 -f 5141//5141 1387//1387 1386//1386 -f 5141//5141 1386//1386 5142//5142 -f 5142//5142 1386//1386 1389//1389 -f 5142//5142 1389//1389 5061//5061 -f 5061//5061 1389//1389 5064//5064 -f 5061//5061 5064//5064 5062//5062 -f 5143//5143 5144//5144 5145//5145 -f 5042//5042 5046//5046 5146//5146 -f 2804//2804 2802//2802 5075//5075 -f 5075//5075 2802//2802 5050//5050 -f 5146//5146 5046//5046 5147//5147 -f 5147//5147 5046//5046 5045//5045 -f 5147//5147 5045//5045 5049//5049 -f 5035//5035 5040//5040 5145//5145 -f 5145//5145 5040//5040 5039//5039 -f 5145//5145 5039//5039 5043//5043 -f 5032//5032 5038//5038 5148//5148 -f 5148//5148 5038//5038 5036//5036 -f 5148//5148 5036//5036 5149//5149 -f 1341//1341 1348//1348 5033//5033 -f 2801//2801 5147//5147 2802//2802 -f 2802//2802 5147//5147 5049//5049 -f 2802//2802 5049//5049 5050//5050 -f 2801//2801 5150//5150 5147//5147 -f 5147//5147 5150//5150 5151//5151 -f 5147//5147 5151//5151 5146//5146 -f 5146//5146 5151//5151 5152//5152 -f 5152//5152 5153//5153 5146//5146 -f 5146//5146 5153//5153 5154//5154 -f 5146//5146 5154//5154 5155//5155 -f 5155//5155 5154//5154 5156//5156 -f 5155//5155 5156//5156 5157//5157 -f 5042//5042 5146//5146 5043//5043 -f 5043//5043 5146//5146 5155//5155 -f 5043//5043 5155//5155 5145//5145 -f 5145//5145 5155//5155 5157//5157 -f 5145//5145 5157//5157 5143//5143 -f 5144//5144 5158//5158 5145//5145 -f 5145//5145 5158//5158 5149//5149 -f 5145//5145 5149//5149 5035//5035 -f 5035//5035 5149//5149 5036//5036 -f 5158//5158 5159//5159 5149//5149 -f 5149//5149 5159//5159 5160//5160 -f 5149//5149 5160//5160 5148//5148 -f 5148//5148 5160//5160 5161//5161 -f 5148//5148 5161//5161 5162//5162 -f 5162//5162 5161//5161 5163//5163 -f 5162//5162 5163//5163 5164//5164 -f 5032//5032 5148//5148 5033//5033 -f 5033//5033 5148//5148 5162//5162 -f 5033//5033 5162//5162 1341//1341 -f 1341//1341 5162//5162 5164//5164 -f 1341//1341 5164//5164 1339//1339 -f 5165//5165 5166//5166 5167//5167 -f 5168//5168 5169//5169 5170//5170 -f 5063//5063 5062//5062 5171//5171 -f 5064//5064 1370//1370 1368//1368 -f 5063//5063 5171//5171 5059//5059 -f 5132//5132 5060//5060 5172//5172 -f 5172//5172 5060//5060 5059//5059 -f 5173//5173 5056//5056 5132//5132 -f 5109//5109 5057//5057 5174//5174 -f 5174//5174 5057//5057 5056//5056 -f 5054//5054 5087//5087 5175//5175 -f 5175//5175 5087//5087 5109//5109 -f 5054//5054 5176//5176 5053//5053 -f 5053//5053 5176//5176 5051//5051 -f 2813//2813 2812//2812 5177//5177 -f 5177//5177 2812//2812 5178//5178 -f 5179//5179 5180//5180 5181//5181 -f 5181//5181 5180//5180 5182//5182 -f 5183//5183 5184//5184 5185//5185 -f 5185//5185 5184//5184 5186//5186 -f 5185//5185 5186//5186 5187//5187 -f 5188//5188 5189//5189 5190//5190 -f 5190//5190 5189//5189 5191//5191 -f 5192//5192 5193//5193 5194//5194 -f 5194//5194 5193//5193 5195//5195 -f 5194//5194 5195//5195 5196//5196 -f 5197//5197 5198//5198 5199//5199 -f 5199//5199 5198//5198 5200//5200 -f 5165//5165 5167//5167 5201//5201 -f 5201//5201 1359//1359 5202//5202 -f 5202//5202 1359//1359 1364//1364 -f 2810//2810 5203//5203 2811//2811 -f 2811//2811 5203//5203 5180//5180 -f 2811//2811 5180//5180 2812//2812 -f 2812//2812 5180//5180 5179//5179 -f 2812//2812 5179//5179 5178//5178 -f 2810//2810 2809//2809 5203//5203 -f 5203//5203 2809//2809 2808//2808 -f 5203//5203 2808//2808 5204//5204 -f 5204//5204 2808//2808 2769//2769 -f 5204//5204 2769//2769 5205//5205 -f 2769//2769 2770//2770 5205//5205 -f 5205//5205 2770//2770 2771//2771 -f 5205//5205 2771//2771 5206//5206 -f 2771//2771 2772//2772 5206//5206 -f 5206//5206 2772//2772 2773//2773 -f 5206//5206 2773//2773 5207//5207 -f 5207//5207 2773//2773 2774//2774 -f 5207//5207 2774//2774 5208//5208 -f 2774//2774 2768//2768 5208//5208 -f 5208//5208 2768//2768 2767//2767 -f 5208//5208 2767//2767 5209//5209 -f 5209//5209 2767//2767 2766//2766 -f 2766//2766 2765//2765 5209//5209 -f 5209//5209 2765//2765 2764//2764 -f 5209//5209 2764//2764 5210//5210 -f 5210//5210 2764//2764 2763//2763 -f 5210//5210 2763//2763 5211//5211 -f 5211//5211 2763//2763 2762//2762 -f 5211//5211 2762//2762 5212//5212 -f 2776//2776 5031//5031 2775//2775 -f 2775//2775 5031//5031 5051//5051 -f 2775//2775 5051//5051 2759//2759 -f 2759//2759 5051//5051 5176//5176 -f 2759//2759 5176//5176 2760//2760 -f 2760//2760 5176//5176 5212//5212 -f 2760//2760 5212//5212 2761//2761 -f 2761//2761 5212//5212 2762//2762 -f 5054//5054 5175//5175 5176//5176 -f 5176//5176 5175//5175 5213//5213 -f 5176//5176 5213//5213 5212//5212 -f 5212//5212 5213//5213 5214//5214 -f 5212//5212 5214//5214 5211//5211 -f 5211//5211 5214//5214 5215//5215 -f 5211//5211 5215//5215 5210//5210 -f 5210//5210 5215//5215 5216//5216 -f 5210//5210 5216//5216 5209//5209 -f 5209//5209 5216//5216 5217//5217 -f 5209//5209 5217//5217 5208//5208 -f 5208//5208 5217//5217 5218//5218 -f 5208//5208 5218//5218 5207//5207 -f 5207//5207 5218//5218 5219//5219 -f 5207//5207 5219//5219 5206//5206 -f 5206//5206 5219//5219 5220//5220 -f 5206//5206 5220//5220 5205//5205 -f 5205//5205 5220//5220 5221//5221 -f 5205//5205 5221//5221 5204//5204 -f 5204//5204 5221//5221 5222//5222 -f 5204//5204 5222//5222 5203//5203 -f 5203//5203 5222//5222 5185//5185 -f 5203//5203 5185//5185 5180//5180 -f 5180//5180 5185//5185 5187//5187 -f 5180//5180 5187//5187 5182//5182 -f 5109//5109 5174//5174 5175//5175 -f 5175//5175 5174//5174 5223//5223 -f 5175//5175 5223//5223 5213//5213 -f 5213//5213 5223//5223 5224//5224 -f 5213//5213 5224//5224 5214//5214 -f 5214//5214 5224//5224 5225//5225 -f 5214//5214 5225//5225 5215//5215 -f 5215//5215 5225//5225 5226//5226 -f 5215//5215 5226//5226 5216//5216 -f 5216//5216 5226//5226 5227//5227 -f 5216//5216 5227//5227 5217//5217 -f 5217//5217 5227//5227 5228//5228 -f 5217//5217 5228//5228 5218//5218 -f 5218//5218 5228//5228 5229//5229 -f 5218//5218 5229//5229 5219//5219 -f 5219//5219 5229//5229 5230//5230 -f 5219//5219 5230//5230 5220//5220 -f 5220//5220 5230//5230 5231//5231 -f 5220//5220 5231//5231 5221//5221 -f 5221//5221 5231//5231 5232//5232 -f 5221//5221 5232//5232 5222//5222 -f 5222//5222 5232//5232 5189//5189 -f 5222//5222 5189//5189 5185//5185 -f 5185//5185 5189//5189 5188//5188 -f 5185//5185 5188//5188 5183//5183 -f 5056//5056 5173//5173 5174//5174 -f 5174//5174 5173//5173 5233//5233 -f 5174//5174 5233//5233 5223//5223 -f 5223//5223 5233//5233 5234//5234 -f 5223//5223 5234//5234 5224//5224 -f 5224//5224 5234//5234 5235//5235 -f 5224//5224 5235//5235 5225//5225 -f 5225//5225 5235//5235 5236//5236 -f 5225//5225 5236//5236 5226//5226 -f 5226//5226 5236//5236 5237//5237 -f 5226//5226 5237//5237 5227//5227 -f 5227//5227 5237//5237 5238//5238 -f 5227//5227 5238//5238 5228//5228 -f 5228//5228 5238//5238 5239//5239 -f 5228//5228 5239//5239 5229//5229 -f 5229//5229 5239//5239 5240//5240 -f 5229//5229 5240//5240 5230//5230 -f 5230//5230 5240//5240 5241//5241 -f 5230//5230 5241//5241 5231//5231 -f 5231//5231 5241//5241 5242//5242 -f 5231//5231 5242//5242 5232//5232 -f 5232//5232 5242//5242 5170//5170 -f 5232//5232 5170//5170 5189//5189 -f 5189//5189 5170//5170 5169//5169 -f 5189//5189 5169//5169 5191//5191 -f 5132//5132 5172//5172 5173//5173 -f 5173//5173 5172//5172 5243//5243 -f 5173//5173 5243//5243 5233//5233 -f 5233//5233 5243//5243 5244//5244 -f 5233//5233 5244//5244 5234//5234 -f 5234//5234 5244//5244 5245//5245 -f 5234//5234 5245//5245 5235//5235 -f 5235//5235 5245//5245 5246//5246 -f 5235//5235 5246//5246 5236//5236 -f 5236//5236 5246//5246 5247//5247 -f 5236//5236 5247//5247 5237//5237 -f 5237//5237 5247//5247 5248//5248 -f 5237//5237 5248//5248 5238//5238 -f 5238//5238 5248//5248 5249//5249 -f 5238//5238 5249//5249 5239//5239 -f 5239//5239 5249//5249 5250//5250 -f 5239//5239 5250//5250 5240//5240 -f 5240//5240 5250//5250 5251//5251 -f 5240//5240 5251//5251 5241//5241 -f 5241//5241 5251//5251 5194//5194 -f 5241//5241 5194//5194 5242//5242 -f 5242//5242 5194//5194 5196//5196 -f 5242//5242 5196//5196 5170//5170 -f 5170//5170 5196//5196 5252//5252 -f 5170//5170 5252//5252 5168//5168 -f 5059//5059 5253//5253 5172//5172 -f 5172//5172 5253//5253 5254//5254 -f 5172//5172 5254//5254 5243//5243 -f 5243//5243 5254//5254 5255//5255 -f 5243//5243 5255//5255 5244//5244 -f 5244//5244 5255//5255 5256//5256 -f 5244//5244 5256//5256 5245//5245 -f 5245//5245 5256//5256 5257//5257 -f 5245//5245 5257//5257 5246//5246 -f 5246//5246 5257//5257 5258//5258 -f 5246//5246 5258//5258 5247//5247 -f 5247//5247 5258//5258 5259//5259 -f 5247//5247 5259//5259 5248//5248 -f 5248//5248 5259//5259 5260//5260 -f 5248//5248 5260//5260 5249//5249 -f 5249//5249 5260//5260 5261//5261 -f 5249//5249 5261//5261 5250//5250 -f 5250//5250 5261//5261 5262//5262 -f 5250//5250 5262//5262 5251//5251 -f 5251//5251 5262//5262 5198//5198 -f 5251//5251 5198//5198 5194//5194 -f 5194//5194 5198//5198 5197//5197 -f 5194//5194 5197//5197 5192//5192 -f 5059//5059 5171//5171 5253//5253 -f 5253//5253 5171//5171 5263//5263 -f 5253//5253 5263//5263 5254//5254 -f 5254//5254 5263//5263 5264//5264 -f 5254//5254 5264//5264 5255//5255 -f 5255//5255 5264//5264 5265//5265 -f 5255//5255 5265//5265 5256//5256 -f 5256//5256 5265//5265 5266//5266 -f 5256//5256 5266//5266 5257//5257 -f 5257//5257 5266//5266 5267//5267 -f 5257//5257 5267//5267 5258//5258 -f 5258//5258 5267//5267 5268//5268 -f 5258//5258 5268//5268 5259//5259 -f 5259//5259 5268//5268 5269//5269 -f 5259//5259 5269//5269 5260//5260 -f 5260//5260 5269//5269 5270//5270 -f 5260//5260 5270//5270 5261//5261 -f 5261//5261 5270//5270 5271//5271 -f 5261//5261 5271//5271 5262//5262 -f 5262//5262 5271//5271 5167//5167 -f 5262//5262 5167//5167 5198//5198 -f 5198//5198 5167//5167 5166//5166 -f 5198//5198 5166//5166 5200//5200 -f 5201//5201 5167//5167 1359//1359 -f 1359//1359 5167//5167 5271//5271 -f 1359//1359 5271//5271 1360//1360 -f 1360//1360 5271//5271 5270//5270 -f 1360//1360 5270//5270 1361//1361 -f 1361//1361 5270//5270 5269//5269 -f 1361//1361 5269//5269 1355//1355 -f 1355//1355 5269//5269 5268//5268 -f 1355//1355 5268//5268 1353//1353 -f 1353//1353 5268//5268 5267//5267 -f 1353//1353 5267//5267 1351//1351 -f 1351//1351 5267//5267 5266//5266 -f 1351//1351 5266//5266 1356//1356 -f 1356//1356 5266//5266 5265//5265 -f 1356//1356 5265//5265 1357//1357 -f 1357//1357 5265//5265 5264//5264 -f 1357//1357 5264//5264 1358//1358 -f 1358//1358 5264//5264 5263//5263 -f 1358//1358 5263//5263 1367//1367 -f 1367//1367 5263//5263 5171//5171 -f 1367//1367 5171//5171 1368//1368 -f 1368//1368 5171//5171 5062//5062 -f 1368//1368 5062//5062 5064//5064 -f 5272//5272 5273//5273 5274//5274 -f 5275//5275 5276//5276 5277//5277 -f 5278//5278 5279//5279 5280//5280 -f 5281//5281 5282//5282 5283//5283 -f 5284//5284 5285//5285 5286//5286 -f 5287//5287 5288//5288 5289//5289 -f 5290//5290 5291//5291 5292//5292 -f 5291//5291 1335//1335 1333//1333 -f 5290//5290 5292//5292 5288//5288 -f 5293//5293 5294//5294 5287//5287 -f 5294//5294 5293//5293 5285//5285 -f 5281//5281 5283//5283 5279//5279 -f 5295//5295 5296//5296 5278//5278 -f 5275//5275 5277//5277 5273//5273 -f 5272//5272 5274//5274 5297//5297 -f 2843//2843 5297//5297 5298//5298 -f 2843//2843 5298//5298 3158//3158 -f 3158//3158 5298//5298 5299//5299 -f 3158//3158 5299//5299 3151//3151 -f 3151//3151 5299//5299 5300//5300 -f 3151//3151 5300//5300 3150//3150 -f 5301//5301 2988//2988 5302//5302 -f 5302//5302 2988//2988 2987//2987 -f 5302//5302 2987//2987 5303//5303 -f 5303//5303 2987//2987 2985//2985 -f 5303//5303 2985//2985 5300//5300 -f 5300//5300 2985//2985 2984//2984 -f 5300//5300 2984//2984 3150//3150 -f 5304//5304 2990//2990 5301//5301 -f 5301//5301 2990//2990 3060//3060 -f 5301//5301 3060//3060 2988//2988 -f 5305//5305 3056//3056 5304//5304 -f 5304//5304 3056//3056 2991//2991 -f 5304//5304 2991//2991 2990//2990 -f 5306//5306 3051//3051 5307//5307 -f 5307//5307 3051//3051 3053//3053 -f 5307//5307 3053//3053 5308//5308 -f 5308//5308 3053//3053 3055//3055 -f 5308//5308 3055//3055 5309//5309 -f 5309//5309 3055//3055 3058//3058 -f 5309//5309 3058//3058 5305//5305 -f 5305//5305 3058//3058 3057//3057 -f 5305//5305 3057//3057 3056//3056 -f 5310//5310 3049//3049 5311//5311 -f 5311//5311 3049//3049 3047//3047 -f 5311//5311 3047//3047 5306//5306 -f 5306//5306 3047//3047 3046//3046 -f 5306//5306 3046//3046 3051//3051 -f 5312//5312 3044//3044 5313//5313 -f 5313//5313 3044//3044 3043//3043 -f 5313//5313 3043//3043 5314//5314 -f 5314//5314 3043//3043 3042//3042 -f 5314//5314 3042//3042 5310//5310 -f 5310//5310 3042//3042 3050//3050 -f 5310//5310 3050//3050 3049//3049 -f 5315//5315 3032//3032 5316//5316 -f 5316//5316 3032//3032 3038//3038 -f 5316//5316 3038//3038 5312//5312 -f 5312//5312 3038//3038 3045//3045 -f 5312//5312 3045//3045 3044//3044 -f 3036//3036 3035//3035 5315//5315 -f 5315//5315 3035//3035 3033//3033 -f 5315//5315 3033//3033 3032//3032 -f 5315//5315 5317//5317 3036//3036 -f 3036//3036 5317//5317 5318//5318 -f 3036//3036 5318//5318 3029//3029 -f 3029//3029 5318//5318 5319//5319 -f 3029//3029 5319//5319 3028//3028 -f 3028//3028 5319//5319 5320//5320 -f 3028//3028 5320//5320 3026//3026 -f 3026//3026 5320//5320 5321//5321 -f 5291//5291 1333//1333 5292//5292 -f 5292//5292 1333//1333 1332//1332 -f 5292//5292 1332//1332 5322//5322 -f 5322//5322 1332//1332 1328//1328 -f 5322//5322 1328//1328 5323//5323 -f 5323//5323 1328//1328 1327//1327 -f 5323//5323 1327//1327 5324//5324 -f 5324//5324 1327//1327 1326//1326 -f 5324//5324 1326//1326 5325//5325 -f 5325//5325 1326//1326 1320//1320 -f 5325//5325 1320//1320 5326//5326 -f 5326//5326 1320//1320 1319//1319 -f 5326//5326 1319//1319 5327//5327 -f 5327//5327 1319//1319 1318//1318 -f 5327//5327 1318//1318 5328//5328 -f 5328//5328 1318//1318 1317//1317 -f 5328//5328 1317//1317 5329//5329 -f 5329//5329 1317//1317 1316//1316 -f 5329//5329 1316//1316 5330//5330 -f 5330//5330 1316//1316 1315//1315 -f 5330//5330 1315//1315 5331//5331 -f 5331//5331 1315//1315 1307//1307 -f 5331//5331 1307//1307 5332//5332 -f 5332//5332 1307//1307 1309//1309 -f 5332//5332 1309//1309 5333//5333 -f 5333//5333 1309//1309 1311//1311 -f 5333//5333 1311//1311 5334//5334 -f 5334//5334 1311//1311 1314//1314 -f 5334//5334 1314//1314 5335//5335 -f 5335//5335 1314//1314 1313//1313 -f 5335//5335 1313//1313 5336//5336 -f 5336//5336 1313//1313 1312//1312 -f 5336//5336 1312//1312 5337//5337 -f 5337//5337 1312//1312 1325//1325 -f 5337//5337 1325//1325 5338//5338 -f 5338//5338 1325//1325 1324//1324 -f 5338//5338 1324//1324 5339//5339 -f 5339//5339 1324//1324 1322//1322 -f 5339//5339 1322//1322 5340//5340 -f 5340//5340 1322//1322 1321//1321 -f 5340//5340 1321//1321 5341//5341 -f 5341//5341 1321//1321 1323//1323 -f 5341//5341 1323//1323 5342//5342 -f 5342//5342 1323//1323 1331//1331 -f 5342//5342 1331//1331 5343//5343 -f 5343//5343 1331//1331 1330//1330 -f 5343//5343 1330//1330 5344//5344 -f 5344//5344 1330//1330 1329//1329 -f 5344//5344 1329//1329 5345//5345 -f 5288//5288 5292//5292 5289//5289 -f 5289//5289 5292//5292 5322//5322 -f 5289//5289 5322//5322 5346//5346 -f 5346//5346 5322//5322 5323//5323 -f 5346//5346 5323//5323 5347//5347 -f 5347//5347 5323//5323 5324//5324 -f 5347//5347 5324//5324 5348//5348 -f 5348//5348 5324//5324 5325//5325 -f 5348//5348 5325//5325 5349//5349 -f 5349//5349 5325//5325 5326//5326 -f 5349//5349 5326//5326 5350//5350 -f 5350//5350 5326//5326 5327//5327 -f 5350//5350 5327//5327 5351//5351 -f 5351//5351 5327//5327 5328//5328 -f 5351//5351 5328//5328 5352//5352 -f 5352//5352 5328//5328 5329//5329 -f 5352//5352 5329//5329 5353//5353 -f 5353//5353 5329//5329 5330//5330 -f 5353//5353 5330//5330 5354//5354 -f 5354//5354 5330//5330 5331//5331 -f 5354//5354 5331//5331 5355//5355 -f 5355//5355 5331//5331 5332//5332 -f 5355//5355 5332//5332 5356//5356 -f 5356//5356 5332//5332 5333//5333 -f 5356//5356 5333//5333 5357//5357 -f 5357//5357 5333//5333 5334//5334 -f 5357//5357 5334//5334 5358//5358 -f 5358//5358 5334//5334 5335//5335 -f 5358//5358 5335//5335 5359//5359 -f 5359//5359 5335//5335 5336//5336 -f 5359//5359 5336//5336 5360//5360 -f 5360//5360 5336//5336 5337//5337 -f 5360//5360 5337//5337 5361//5361 -f 5361//5361 5337//5337 5338//5338 -f 5361//5361 5338//5338 5362//5362 -f 5362//5362 5338//5338 5339//5339 -f 5362//5362 5339//5339 5363//5363 -f 5363//5363 5339//5339 5340//5340 -f 5363//5363 5340//5340 5364//5364 -f 5364//5364 5340//5340 5341//5341 -f 5364//5364 5341//5341 5365//5365 -f 5365//5365 5341//5341 5342//5342 -f 5365//5365 5342//5342 5366//5366 -f 5366//5366 5342//5342 5343//5343 -f 5366//5366 5343//5343 5367//5367 -f 5367//5367 5343//5343 5344//5344 -f 5367//5367 5344//5344 5368//5368 -f 5368//5368 5344//5344 5345//5345 -f 5368//5368 5345//5345 5369//5369 -f 5287//5287 5289//5289 5293//5293 -f 5293//5293 5289//5289 5346//5346 -f 5293//5293 5346//5346 5370//5370 -f 5370//5370 5346//5346 5347//5347 -f 5370//5370 5347//5347 5371//5371 -f 5371//5371 5347//5347 5348//5348 -f 5371//5371 5348//5348 5372//5372 -f 5372//5372 5348//5348 5349//5349 -f 5372//5372 5349//5349 5373//5373 -f 5373//5373 5349//5349 5350//5350 -f 5373//5373 5350//5350 5374//5374 -f 5374//5374 5350//5350 5351//5351 -f 5374//5374 5351//5351 5375//5375 -f 5375//5375 5351//5351 5352//5352 -f 5375//5375 5352//5352 5376//5376 -f 5376//5376 5352//5352 5353//5353 -f 5376//5376 5353//5353 5377//5377 -f 5377//5377 5353//5353 5354//5354 -f 5377//5377 5354//5354 5378//5378 -f 5378//5378 5354//5354 5355//5355 -f 5378//5378 5355//5355 5379//5379 -f 5379//5379 5355//5355 5356//5356 -f 5379//5379 5356//5356 5380//5380 -f 5380//5380 5356//5356 5357//5357 -f 5380//5380 5357//5357 5381//5381 -f 5381//5381 5357//5357 5358//5358 -f 5381//5381 5358//5358 5382//5382 -f 5382//5382 5358//5358 5359//5359 -f 5382//5382 5359//5359 5383//5383 -f 5383//5383 5359//5359 5360//5360 -f 5383//5383 5360//5360 5384//5384 -f 5384//5384 5360//5360 5361//5361 -f 5384//5384 5361//5361 5385//5385 -f 5385//5385 5361//5361 5362//5362 -f 5385//5385 5362//5362 5386//5386 -f 5386//5386 5362//5362 5363//5363 -f 5386//5386 5363//5363 5387//5387 -f 5387//5387 5363//5363 5364//5364 -f 5387//5387 5364//5364 5388//5388 -f 5388//5388 5364//5364 5365//5365 -f 5388//5388 5365//5365 5389//5389 -f 5389//5389 5365//5365 5366//5366 -f 5389//5389 5366//5366 5390//5390 -f 5390//5390 5366//5366 5367//5367 -f 5390//5390 5367//5367 5391//5391 -f 5391//5391 5367//5367 5368//5368 -f 5391//5391 5368//5368 5392//5392 -f 5392//5392 5368//5368 5369//5369 -f 5392//5392 5369//5369 5393//5393 -f 5285//5285 5293//5293 5286//5286 -f 5286//5286 5293//5293 5370//5370 -f 5286//5286 5370//5370 5394//5394 -f 5394//5394 5370//5370 5371//5371 -f 5394//5394 5371//5371 5395//5395 -f 5395//5395 5371//5371 5372//5372 -f 5395//5395 5372//5372 5396//5396 -f 5396//5396 5372//5372 5373//5373 -f 5396//5396 5373//5373 5397//5397 -f 5397//5397 5373//5373 5374//5374 -f 5397//5397 5374//5374 5398//5398 -f 5398//5398 5374//5374 5375//5375 -f 5398//5398 5375//5375 5399//5399 -f 5399//5399 5375//5375 5376//5376 -f 5399//5399 5376//5376 5400//5400 -f 5400//5400 5376//5376 5377//5377 -f 5400//5400 5377//5377 5401//5401 -f 5401//5401 5377//5377 5378//5378 -f 5401//5401 5378//5378 5402//5402 -f 5402//5402 5378//5378 5379//5379 -f 5402//5402 5379//5379 5403//5403 -f 5403//5403 5379//5379 5380//5380 -f 5403//5403 5380//5380 5404//5404 -f 5404//5404 5380//5380 5381//5381 -f 5404//5404 5381//5381 5405//5405 -f 5405//5405 5381//5381 5382//5382 -f 5405//5405 5382//5382 5406//5406 -f 5406//5406 5382//5382 5383//5383 -f 5406//5406 5383//5383 5407//5407 -f 5407//5407 5383//5383 5384//5384 -f 5407//5407 5384//5384 5408//5408 -f 5408//5408 5384//5384 5385//5385 -f 5408//5408 5385//5385 5409//5409 -f 5409//5409 5385//5385 5386//5386 -f 5409//5409 5386//5386 5410//5410 -f 5410//5410 5386//5386 5387//5387 -f 5410//5410 5387//5387 5411//5411 -f 5411//5411 5387//5387 5388//5388 -f 5411//5411 5388//5388 5412//5412 -f 5412//5412 5388//5388 5389//5389 -f 5412//5412 5389//5389 5413//5413 -f 5413//5413 5389//5389 5390//5390 -f 5413//5413 5390//5390 5414//5414 -f 5414//5414 5390//5390 5391//5391 -f 5414//5414 5391//5391 5415//5415 -f 5415//5415 5391//5391 5392//5392 -f 5415//5415 5392//5392 5416//5416 -f 5416//5416 5392//5392 5393//5393 -f 5416//5416 5393//5393 5417//5417 -f 5279//5279 5283//5283 5280//5280 -f 5280//5280 5283//5283 5418//5418 -f 5280//5280 5418//5418 5419//5419 -f 5419//5419 5418//5418 5420//5420 -f 5419//5419 5420//5420 5421//5421 -f 5421//5421 5420//5420 5422//5422 -f 5421//5421 5422//5422 5423//5423 -f 5423//5423 5422//5422 5424//5424 -f 5423//5423 5424//5424 5425//5425 -f 5425//5425 5424//5424 5426//5426 -f 5425//5425 5426//5426 5427//5427 -f 5427//5427 5426//5426 5428//5428 -f 5427//5427 5428//5428 5429//5429 -f 5429//5429 5428//5428 5430//5430 -f 5429//5429 5430//5430 5431//5431 -f 5431//5431 5430//5430 5432//5432 -f 5431//5431 5432//5432 5433//5433 -f 5433//5433 5432//5432 5434//5434 -f 5433//5433 5434//5434 5435//5435 -f 5435//5435 5434//5434 5436//5436 -f 5435//5435 5436//5436 5437//5437 -f 5437//5437 5436//5436 5438//5438 -f 5437//5437 5438//5438 5439//5439 -f 5439//5439 5438//5438 5440//5440 -f 5439//5439 5440//5440 5441//5441 -f 5441//5441 5440//5440 5442//5442 -f 5441//5441 5442//5442 5443//5443 -f 5443//5443 5442//5442 5444//5444 -f 5443//5443 5444//5444 5445//5445 -f 5445//5445 5444//5444 5446//5446 -f 5445//5445 5446//5446 5447//5447 -f 5447//5447 5446//5446 5448//5448 -f 5447//5447 5448//5448 5449//5449 -f 5449//5449 5448//5448 5450//5450 -f 5449//5449 5450//5450 5451//5451 -f 5451//5451 5450//5450 5452//5452 -f 5451//5451 5452//5452 5453//5453 -f 5453//5453 5452//5452 5454//5454 -f 5453//5453 5454//5454 5455//5455 -f 5455//5455 5454//5454 5456//5456 -f 5455//5455 5456//5456 5457//5457 -f 5457//5457 5456//5456 5458//5458 -f 5457//5457 5458//5458 5459//5459 -f 5459//5459 5458//5458 5460//5460 -f 5459//5459 5460//5460 5461//5461 -f 5461//5461 5460//5460 5462//5462 -f 5461//5461 5462//5462 5463//5463 -f 5463//5463 5462//5462 5464//5464 -f 5463//5463 5464//5464 5465//5465 -f 5273//5273 5277//5277 5274//5274 -f 5274//5274 5277//5277 5466//5466 -f 5274//5274 5466//5466 5467//5467 -f 5467//5467 5466//5466 5468//5468 -f 5467//5467 5468//5468 5469//5469 -f 5469//5469 5468//5468 5470//5470 -f 5469//5469 5470//5470 5471//5471 -f 5471//5471 5470//5470 5472//5472 -f 5471//5471 5472//5472 5473//5473 -f 5473//5473 5472//5472 5474//5474 -f 5473//5473 5474//5474 5475//5475 -f 5475//5475 5474//5474 5476//5476 -f 5475//5475 5476//5476 5477//5477 -f 5477//5477 5476//5476 5478//5478 -f 5477//5477 5478//5478 5479//5479 -f 5479//5479 5478//5478 5480//5480 -f 5479//5479 5480//5480 5481//5481 -f 5481//5481 5480//5480 5482//5482 -f 5481//5481 5482//5482 5483//5483 -f 5483//5483 5482//5482 5484//5484 -f 5483//5483 5484//5484 5485//5485 -f 5485//5485 5484//5484 5486//5486 -f 5485//5485 5486//5486 5487//5487 -f 5487//5487 5486//5486 5488//5488 -f 5487//5487 5488//5488 5489//5489 -f 5489//5489 5488//5488 5490//5490 -f 5489//5489 5490//5490 5491//5491 -f 5491//5491 5490//5490 5492//5492 -f 5491//5491 5492//5492 5493//5493 -f 5493//5493 5492//5492 5494//5494 -f 5493//5493 5494//5494 5495//5495 -f 5495//5495 5494//5494 5496//5496 -f 5495//5495 5496//5496 5497//5497 -f 5497//5497 5496//5496 5498//5498 -f 5497//5497 5498//5498 5499//5499 -f 5499//5499 5498//5498 5500//5500 -f 5499//5499 5500//5500 5501//5501 -f 5501//5501 5500//5500 5502//5502 -f 5501//5501 5502//5502 5503//5503 -f 5503//5503 5502//5502 5504//5504 -f 5503//5503 5504//5504 5505//5505 -f 5505//5505 5504//5504 5506//5506 -f 5505//5505 5506//5506 5507//5507 -f 5507//5507 5506//5506 5508//5508 -f 5507//5507 5508//5508 5509//5509 -f 5509//5509 5508//5508 5510//5510 -f 5509//5509 5510//5510 5511//5511 -f 5511//5511 5510//5510 5512//5512 -f 5511//5511 5512//5512 5513//5513 -f 3019//3019 3023//3023 5321//5321 -f 5321//5321 3023//3023 3022//3022 -f 5321//5321 3022//3022 3026//3026 -f 1329//1329 1339//1339 5345//5345 -f 5345//5345 1339//1339 5164//5164 -f 5345//5345 5164//5164 5369//5369 -f 5369//5369 5164//5164 5163//5163 -f 5369//5369 5163//5163 5393//5393 -f 5393//5393 5163//5163 5161//5161 -f 5393//5393 5161//5161 5417//5417 -f 5417//5417 5161//5161 5160//5160 -f 5417//5417 5160//5160 5159//5159 -f 5159//5159 5464//5464 5417//5417 -f 5417//5417 5464//5464 5462//5462 -f 5417//5417 5462//5462 5416//5416 -f 5416//5416 5462//5462 5460//5460 -f 5416//5416 5460//5460 5415//5415 -f 5415//5415 5460//5460 5458//5458 -f 5415//5415 5458//5458 5414//5414 -f 5414//5414 5458//5458 5456//5456 -f 5414//5414 5456//5456 5413//5413 -f 5413//5413 5456//5456 5454//5454 -f 5413//5413 5454//5454 5412//5412 -f 5412//5412 5454//5454 5452//5452 -f 5412//5412 5452//5452 5411//5411 -f 5411//5411 5452//5452 5450//5450 -f 5411//5411 5450//5450 5410//5410 -f 5410//5410 5450//5450 5448//5448 -f 5410//5410 5448//5448 5409//5409 -f 5409//5409 5448//5448 5446//5446 -f 5409//5409 5446//5446 5408//5408 -f 5408//5408 5446//5446 5444//5444 -f 5408//5408 5444//5444 5407//5407 -f 5407//5407 5444//5444 5442//5442 -f 5407//5407 5442//5442 5406//5406 -f 5406//5406 5442//5442 5440//5440 -f 5406//5406 5440//5440 5405//5405 -f 5405//5405 5440//5440 5438//5438 -f 5405//5405 5438//5438 5404//5404 -f 5404//5404 5438//5438 5436//5436 -f 5404//5404 5436//5436 5403//5403 -f 5403//5403 5436//5436 5434//5434 -f 5403//5403 5434//5434 5402//5402 -f 5402//5402 5434//5434 5432//5432 -f 5402//5402 5432//5432 5401//5401 -f 5401//5401 5432//5432 5430//5430 -f 5401//5401 5430//5430 5400//5400 -f 5400//5400 5430//5430 5428//5428 -f 5400//5400 5428//5428 5399//5399 -f 5399//5399 5428//5428 5426//5426 -f 5399//5399 5426//5426 5398//5398 -f 5398//5398 5426//5426 5424//5424 -f 5398//5398 5424//5424 5397//5397 -f 5397//5397 5424//5424 5422//5422 -f 5397//5397 5422//5422 5396//5396 -f 5396//5396 5422//5422 5420//5420 -f 5396//5396 5420//5420 5395//5395 -f 5395//5395 5420//5420 5418//5418 -f 5395//5395 5418//5418 5394//5394 -f 5394//5394 5418//5418 5283//5283 -f 5394//5394 5283//5283 5286//5286 -f 5286//5286 5283//5283 5282//5282 -f 5286//5286 5282//5282 5284//5284 -f 5159//5159 5158//5158 5464//5464 -f 5464//5464 5158//5158 5144//5144 -f 5464//5464 5144//5144 5465//5465 -f 5465//5465 5144//5144 5143//5143 -f 5465//5465 5143//5143 5157//5157 -f 5278//5278 5280//5280 5295//5295 -f 5295//5295 5280//5280 5419//5419 -f 5295//5295 5419//5419 5514//5514 -f 5514//5514 5419//5419 5421//5421 -f 5514//5514 5421//5421 5515//5515 -f 5515//5515 5421//5421 5423//5423 -f 5515//5515 5423//5423 5516//5516 -f 5516//5516 5423//5423 5425//5425 -f 5516//5516 5425//5425 5517//5517 -f 5517//5517 5425//5425 5427//5427 -f 5517//5517 5427//5427 5518//5518 -f 5518//5518 5427//5427 5429//5429 -f 5518//5518 5429//5429 5519//5519 -f 5519//5519 5429//5429 5431//5431 -f 5519//5519 5431//5431 5520//5520 -f 5520//5520 5431//5431 5433//5433 -f 5520//5520 5433//5433 5521//5521 -f 5521//5521 5433//5433 5435//5435 -f 5521//5521 5435//5435 5522//5522 -f 5522//5522 5435//5435 5437//5437 -f 5522//5522 5437//5437 5523//5523 -f 5523//5523 5437//5437 5439//5439 -f 5523//5523 5439//5439 5524//5524 -f 5524//5524 5439//5439 5441//5441 -f 5524//5524 5441//5441 5525//5525 -f 5525//5525 5441//5441 5443//5443 -f 5525//5525 5443//5443 5526//5526 -f 5526//5526 5443//5443 5445//5445 -f 5526//5526 5445//5445 5527//5527 -f 5527//5527 5445//5445 5447//5447 -f 5527//5527 5447//5447 5528//5528 -f 5528//5528 5447//5447 5449//5449 -f 5528//5528 5449//5449 5529//5529 -f 5529//5529 5449//5449 5451//5451 -f 5529//5529 5451//5451 5530//5530 -f 5530//5530 5451//5451 5453//5453 -f 5530//5530 5453//5453 5531//5531 -f 5531//5531 5453//5453 5455//5455 -f 5531//5531 5455//5455 5532//5532 -f 5532//5532 5455//5455 5457//5457 -f 5532//5532 5457//5457 5533//5533 -f 5533//5533 5457//5457 5459//5459 -f 5533//5533 5459//5459 5534//5534 -f 5534//5534 5459//5459 5461//5461 -f 5534//5534 5461//5461 5535//5535 -f 5535//5535 5461//5461 5463//5463 -f 5535//5535 5463//5463 5536//5536 -f 5536//5536 5463//5463 5465//5465 -f 5536//5536 5465//5465 5537//5537 -f 5537//5537 5465//5465 5157//5157 -f 5537//5537 5157//5157 5156//5156 -f 5156//5156 5512//5512 5537//5537 -f 5537//5537 5512//5512 5510//5510 -f 5537//5537 5510//5510 5536//5536 -f 5536//5536 5510//5510 5508//5508 -f 5536//5536 5508//5508 5535//5535 -f 5535//5535 5508//5508 5506//5506 -f 5535//5535 5506//5506 5534//5534 -f 5534//5534 5506//5506 5504//5504 -f 5534//5534 5504//5504 5533//5533 -f 5533//5533 5504//5504 5502//5502 -f 5533//5533 5502//5502 5532//5532 -f 5532//5532 5502//5502 5500//5500 -f 5532//5532 5500//5500 5531//5531 -f 5531//5531 5500//5500 5498//5498 -f 5531//5531 5498//5498 5530//5530 -f 5530//5530 5498//5498 5496//5496 -f 5530//5530 5496//5496 5529//5529 -f 5529//5529 5496//5496 5494//5494 -f 5529//5529 5494//5494 5528//5528 -f 5528//5528 5494//5494 5492//5492 -f 5528//5528 5492//5492 5527//5527 -f 5527//5527 5492//5492 5490//5490 -f 5527//5527 5490//5490 5526//5526 -f 5526//5526 5490//5490 5488//5488 -f 5526//5526 5488//5488 5525//5525 -f 5525//5525 5488//5488 5486//5486 -f 5525//5525 5486//5486 5524//5524 -f 5524//5524 5486//5486 5484//5484 -f 5524//5524 5484//5484 5523//5523 -f 5523//5523 5484//5484 5482//5482 -f 5523//5523 5482//5482 5522//5522 -f 5522//5522 5482//5482 5480//5480 -f 5522//5522 5480//5480 5521//5521 -f 5521//5521 5480//5480 5478//5478 -f 5521//5521 5478//5478 5520//5520 -f 5520//5520 5478//5478 5476//5476 -f 5520//5520 5476//5476 5519//5519 -f 5519//5519 5476//5476 5474//5474 -f 5519//5519 5474//5474 5518//5518 -f 5518//5518 5474//5474 5472//5472 -f 5518//5518 5472//5472 5517//5517 -f 5517//5517 5472//5472 5470//5470 -f 5517//5517 5470//5470 5516//5516 -f 5516//5516 5470//5470 5468//5468 -f 5516//5516 5468//5468 5515//5515 -f 5515//5515 5468//5468 5466//5466 -f 5515//5515 5466//5466 5514//5514 -f 5514//5514 5466//5466 5277//5277 -f 5514//5514 5277//5277 5295//5295 -f 5295//5295 5277//5277 5276//5276 -f 5295//5295 5276//5276 5296//5296 -f 5156//5156 5154//5154 5512//5512 -f 5512//5512 5154//5154 5153//5153 -f 5512//5512 5153//5153 5513//5513 -f 5513//5513 5153//5153 5152//5152 -f 5513//5513 5152//5152 5151//5151 -f 5297//5297 5274//5274 5298//5298 -f 5298//5298 5274//5274 5467//5467 -f 5298//5298 5467//5467 5299//5299 -f 5299//5299 5467//5467 5469//5469 -f 5299//5299 5469//5469 5300//5300 -f 5300//5300 5469//5469 5471//5471 -f 5300//5300 5471//5471 5303//5303 -f 5303//5303 5471//5471 5473//5473 -f 5303//5303 5473//5473 5302//5302 -f 5302//5302 5473//5473 5475//5475 -f 5302//5302 5475//5475 5301//5301 -f 5301//5301 5475//5475 5477//5477 -f 5301//5301 5477//5477 5304//5304 -f 5304//5304 5477//5477 5479//5479 -f 5304//5304 5479//5479 5305//5305 -f 5305//5305 5479//5479 5481//5481 -f 5305//5305 5481//5481 5309//5309 -f 5309//5309 5481//5481 5483//5483 -f 5309//5309 5483//5483 5308//5308 -f 5308//5308 5483//5483 5485//5485 -f 5308//5308 5485//5485 5307//5307 -f 5307//5307 5485//5485 5487//5487 -f 5307//5307 5487//5487 5306//5306 -f 5306//5306 5487//5487 5489//5489 -f 5306//5306 5489//5489 5311//5311 -f 5311//5311 5489//5489 5491//5491 -f 5311//5311 5491//5491 5310//5310 -f 5310//5310 5491//5491 5493//5493 -f 5310//5310 5493//5493 5314//5314 -f 5314//5314 5493//5493 5495//5495 -f 5314//5314 5495//5495 5313//5313 -f 5313//5313 5495//5495 5497//5497 -f 5313//5313 5497//5497 5312//5312 -f 5312//5312 5497//5497 5499//5499 -f 5312//5312 5499//5499 5316//5316 -f 5316//5316 5499//5499 5501//5501 -f 5316//5316 5501//5501 5315//5315 -f 5315//5315 5501//5501 5503//5503 -f 5315//5315 5503//5503 5317//5317 -f 5317//5317 5503//5503 5505//5505 -f 5317//5317 5505//5505 5318//5318 -f 5318//5318 5505//5505 5507//5507 -f 5318//5318 5507//5507 5319//5319 -f 5319//5319 5507//5507 5509//5509 -f 5319//5319 5509//5509 5320//5320 -f 5320//5320 5509//5509 5511//5511 -f 5320//5320 5511//5511 5321//5321 -f 5321//5321 5511//5511 5513//5513 -f 5321//5321 5513//5513 5538//5538 -f 5538//5538 5513//5513 5151//5151 -f 5538//5538 5151//5151 5150//5150 -f 3019//3019 5321//5321 3020//3020 -f 3020//3020 5321//5321 5538//5538 -f 3020//3020 5538//5538 3021//3021 -f 3021//3021 5538//5538 5150//5150 -f 3021//3021 5150//5150 2801//2801 -f 5539//5539 5540//5540 5541//5541 -f 5542//5542 5543//5543 5544//5544 -f 5545//5545 5546//5546 5547//5547 -f 1300//1300 1303//1303 5548//5548 -f 5548//5548 1303//1303 5549//5549 -f 5550//5550 5551//5551 5552//5552 -f 5552//5552 5551//5551 5553//5553 -f 5552//5552 5553//5553 5554//5554 -f 5555//5555 5556//5556 5557//5557 -f 5557//5557 5556//5556 5550//5550 -f 5558//5558 5559//5559 5560//5560 -f 5560//5560 5559//5559 5561//5561 -f 5560//5560 5561//5561 5555//5555 -f 5562//5562 5563//5563 5564//5564 -f 5564//5564 5563//5563 5565//5565 -f 5564//5564 5565//5565 5558//5558 -f 5566//5566 5567//5567 5568//5568 -f 5568//5568 5567//5567 5569//5569 -f 5568//5568 5569//5569 5562//5562 -f 5546//5546 5570//5570 5547//5547 -f 5547//5547 5570//5570 5571//5571 -f 5547//5547 5571//5571 5566//5566 -f 5572//5572 5573//5573 5574//5574 -f 5574//5574 5573//5573 5575//5575 -f 5574//5574 5575//5575 5545//5545 -f 2814//2814 2813//2813 5576//5576 -f 5577//5577 2840//2840 2839//2839 -f 5577//5577 2839//2839 5578//5578 -f 5578//5578 2839//2839 2837//2837 -f 5578//5578 2837//2837 5579//5579 -f 5580//5580 5581//5581 5582//5582 -f 5583//5583 5584//5584 5585//5585 -f 5585//5585 5584//5584 5586//5586 -f 5585//5585 5586//5586 5587//5587 -f 5588//5588 5589//5589 5590//5590 -f 5590//5590 5589//5589 5591//5591 -f 5592//5592 5593//5593 5594//5594 -f 5594//5594 5593//5593 5595//5595 -f 5594//5594 5595//5595 5596//5596 -f 5597//5597 5598//5598 5599//5599 -f 5599//5599 5598//5598 5600//5600 -f 5539//5539 5541//5541 5601//5601 -f 5601//5601 1291//1291 5602//5602 -f 5602//5602 1291//1291 1296//1296 -f 5582//5582 5579//5579 5580//5580 -f 5580//5580 5579//5579 2837//2837 -f 5580//5580 2837//2837 5603//5603 -f 2837//2837 2831//2831 5603//5603 -f 5603//5603 2831//2831 2832//2832 -f 5603//5603 2832//2832 5604//5604 -f 2832//2832 2833//2833 5604//5604 -f 5604//5604 2833//2833 2834//2834 -f 5604//5604 2834//2834 5605//5605 -f 5605//5605 2834//2834 2835//2835 -f 2835//2835 2829//2829 5605//5605 -f 5605//5605 2829//2829 2828//2828 -f 5605//5605 2828//2828 5606//5606 -f 5606//5606 2828//2828 2827//2827 -f 5606//5606 2827//2827 5607//5607 -f 2827//2827 2826//2826 5607//5607 -f 5607//5607 2826//2826 2825//2825 -f 5607//5607 2825//2825 5608//5608 -f 2825//2825 2824//2824 5608//5608 -f 5608//5608 2824//2824 2823//2823 -f 5608//5608 2823//2823 5609//5609 -f 5609//5609 2823//2823 2822//2822 -f 5609//5609 2822//2822 5610//5610 -f 2822//2822 2821//2821 5610//5610 -f 5610//5610 2821//2821 2820//2820 -f 5610//5610 2820//2820 5611//5611 -f 2820//2820 2819//2819 5611//5611 -f 5611//5611 2819//2819 2818//2818 -f 5611//5611 2818//2818 5612//5612 -f 5612//5612 2818//2818 2817//2817 -f 2817//2817 2816//2816 5612//5612 -f 5612//5612 2816//2816 2815//2815 -f 5612//5612 2815//2815 5574//5574 -f 5574//5574 2815//2815 2814//2814 -f 5574//5574 2814//2814 5572//5572 -f 5572//5572 2814//2814 5576//5576 -f 5545//5545 5547//5547 5574//5574 -f 5574//5574 5547//5547 5613//5613 -f 5574//5574 5613//5613 5612//5612 -f 5612//5612 5613//5613 5614//5614 -f 5612//5612 5614//5614 5611//5611 -f 5611//5611 5614//5614 5615//5615 -f 5611//5611 5615//5615 5610//5610 -f 5610//5610 5615//5615 5616//5616 -f 5610//5610 5616//5616 5609//5609 -f 5609//5609 5616//5616 5617//5617 -f 5609//5609 5617//5617 5608//5608 -f 5608//5608 5617//5617 5618//5618 -f 5608//5608 5618//5618 5607//5607 -f 5607//5607 5618//5618 5619//5619 -f 5607//5607 5619//5619 5606//5606 -f 5606//5606 5619//5619 5620//5620 -f 5606//5606 5620//5620 5605//5605 -f 5605//5605 5620//5620 5621//5621 -f 5605//5605 5621//5621 5604//5604 -f 5604//5604 5621//5621 5622//5622 -f 5604//5604 5622//5622 5603//5603 -f 5603//5603 5622//5622 5585//5585 -f 5603//5603 5585//5585 5580//5580 -f 5580//5580 5585//5585 5587//5587 -f 5580//5580 5587//5587 5581//5581 -f 5566//5566 5568//5568 5547//5547 -f 5547//5547 5568//5568 5623//5623 -f 5547//5547 5623//5623 5613//5613 -f 5613//5613 5623//5623 5624//5624 -f 5613//5613 5624//5624 5614//5614 -f 5614//5614 5624//5624 5625//5625 -f 5614//5614 5625//5625 5615//5615 -f 5615//5615 5625//5625 5626//5626 -f 5615//5615 5626//5626 5616//5616 -f 5616//5616 5626//5626 5627//5627 -f 5616//5616 5627//5627 5617//5617 -f 5617//5617 5627//5627 5628//5628 -f 5617//5617 5628//5628 5618//5618 -f 5618//5618 5628//5628 5629//5629 -f 5618//5618 5629//5629 5619//5619 -f 5619//5619 5629//5629 5630//5630 -f 5619//5619 5630//5630 5620//5620 -f 5620//5620 5630//5630 5631//5631 -f 5620//5620 5631//5631 5621//5621 -f 5621//5621 5631//5631 5632//5632 -f 5621//5621 5632//5632 5622//5622 -f 5622//5622 5632//5632 5589//5589 -f 5622//5622 5589//5589 5585//5585 -f 5585//5585 5589//5589 5588//5588 -f 5585//5585 5588//5588 5583//5583 -f 5562//5562 5564//5564 5568//5568 -f 5568//5568 5564//5564 5633//5633 -f 5568//5568 5633//5633 5623//5623 -f 5623//5623 5633//5633 5634//5634 -f 5623//5623 5634//5634 5624//5624 -f 5624//5624 5634//5634 5635//5635 -f 5624//5624 5635//5635 5625//5625 -f 5625//5625 5635//5635 5636//5636 -f 5625//5625 5636//5636 5626//5626 -f 5626//5626 5636//5636 5637//5637 -f 5626//5626 5637//5637 5627//5627 -f 5627//5627 5637//5637 5638//5638 -f 5627//5627 5638//5638 5628//5628 -f 5628//5628 5638//5638 5639//5639 -f 5628//5628 5639//5639 5629//5629 -f 5629//5629 5639//5639 5640//5640 -f 5629//5629 5640//5640 5630//5630 -f 5630//5630 5640//5640 5641//5641 -f 5630//5630 5641//5641 5631//5631 -f 5631//5631 5641//5641 5642//5642 -f 5631//5631 5642//5642 5632//5632 -f 5632//5632 5642//5642 5544//5544 -f 5632//5632 5544//5544 5589//5589 -f 5589//5589 5544//5544 5543//5543 -f 5589//5589 5543//5543 5591//5591 -f 5558//5558 5560//5560 5564//5564 -f 5564//5564 5560//5560 5643//5643 -f 5564//5564 5643//5643 5633//5633 -f 5633//5633 5643//5643 5644//5644 -f 5633//5633 5644//5644 5634//5634 -f 5634//5634 5644//5644 5645//5645 -f 5634//5634 5645//5645 5635//5635 -f 5635//5635 5645//5645 5646//5646 -f 5635//5635 5646//5646 5636//5636 -f 5636//5636 5646//5646 5647//5647 -f 5636//5636 5647//5647 5637//5637 -f 5637//5637 5647//5647 5648//5648 -f 5637//5637 5648//5648 5638//5638 -f 5638//5638 5648//5648 5649//5649 -f 5638//5638 5649//5649 5639//5639 -f 5639//5639 5649//5649 5650//5650 -f 5639//5639 5650//5650 5640//5640 -f 5640//5640 5650//5650 5651//5651 -f 5640//5640 5651//5651 5641//5641 -f 5641//5641 5651//5651 5594//5594 -f 5641//5641 5594//5594 5642//5642 -f 5642//5642 5594//5594 5596//5596 -f 5642//5642 5596//5596 5544//5544 -f 5544//5544 5596//5596 5652//5652 -f 5544//5544 5652//5652 5542//5542 -f 5555//5555 5557//5557 5560//5560 -f 5560//5560 5557//5557 5653//5653 -f 5560//5560 5653//5653 5643//5643 -f 5643//5643 5653//5653 5654//5654 -f 5643//5643 5654//5654 5644//5644 -f 5644//5644 5654//5654 5655//5655 -f 5644//5644 5655//5655 5645//5645 -f 5645//5645 5655//5655 5656//5656 -f 5645//5645 5656//5656 5646//5646 -f 5646//5646 5656//5656 5657//5657 -f 5646//5646 5657//5657 5647//5647 -f 5647//5647 5657//5657 5658//5658 -f 5647//5647 5658//5658 5648//5648 -f 5648//5648 5658//5658 5659//5659 -f 5648//5648 5659//5659 5649//5649 -f 5649//5649 5659//5659 5660//5660 -f 5649//5649 5660//5660 5650//5650 -f 5650//5650 5660//5660 5661//5661 -f 5650//5650 5661//5661 5651//5651 -f 5651//5651 5661//5661 5598//5598 -f 5651//5651 5598//5598 5594//5594 -f 5594//5594 5598//5598 5597//5597 -f 5594//5594 5597//5597 5592//5592 -f 5550//5550 5552//5552 5557//5557 -f 5557//5557 5552//5552 5662//5662 -f 5557//5557 5662//5662 5653//5653 -f 5653//5653 5662//5662 5663//5663 -f 5653//5653 5663//5663 5654//5654 -f 5654//5654 5663//5663 5664//5664 -f 5654//5654 5664//5664 5655//5655 -f 5655//5655 5664//5664 5665//5665 -f 5655//5655 5665//5665 5656//5656 -f 5656//5656 5665//5665 5666//5666 -f 5656//5656 5666//5666 5657//5657 -f 5657//5657 5666//5666 5667//5667 -f 5657//5657 5667//5667 5658//5658 -f 5658//5658 5667//5667 5668//5668 -f 5658//5658 5668//5668 5659//5659 -f 5659//5659 5668//5668 5669//5669 -f 5659//5659 5669//5669 5660//5660 -f 5660//5660 5669//5669 5670//5670 -f 5660//5660 5670//5670 5661//5661 -f 5661//5661 5670//5670 5541//5541 -f 5661//5661 5541//5541 5598//5598 -f 5598//5598 5541//5541 5540//5540 -f 5598//5598 5540//5540 5600//5600 -f 5601//5601 5541//5541 1291//1291 -f 1291//1291 5541//5541 5670//5670 -f 1291//1291 5670//5670 1292//1292 -f 1292//1292 5670//5670 5669//5669 -f 1292//1292 5669//5669 1293//1293 -f 1293//1293 5669//5669 5668//5668 -f 1293//1293 5668//5668 1287//1287 -f 1287//1287 5668//5668 5667//5667 -f 1287//1287 5667//5667 1286//1286 -f 1286//1286 5667//5667 5666//5666 -f 1286//1286 5666//5666 1285//1285 -f 1285//1285 5666//5666 5665//5665 -f 1285//1285 5665//5665 1288//1288 -f 1288//1288 5665//5665 5664//5664 -f 1288//1288 5664//5664 1289//1289 -f 1289//1289 5664//5664 5663//5663 -f 1289//1289 5663//5663 1290//1290 -f 1290//1290 5663//5663 5662//5662 -f 1290//1290 5662//5662 1302//1302 -f 1302//1302 5662//5662 5552//5552 -f 1302//1302 5552//5552 1303//1303 -f 1303//1303 5552//5552 5554//5554 -f 1303//1303 5554//5554 5549//5549 -f 5671//5671 5672//5672 5673//5673 -f 5674//5674 1337//1337 1335//1335 -f 5675//5675 5676//5676 5287//5287 -f 5287//5287 5676//5676 5677//5677 -f 5287//5287 5677//5677 5288//5288 -f 5288//5288 5677//5677 5678//5678 -f 5288//5288 5678//5678 5290//5290 -f 5290//5290 5678//5678 5679//5679 -f 5290//5290 5679//5679 5291//5291 -f 5291//5291 5679//5679 5680//5680 -f 5291//5291 5680//5680 1335//1335 -f 1335//1335 5680//5680 5681//5681 -f 1335//1335 5681//5681 5674//5674 -f 5287//5287 5294//5294 5675//5675 -f 5675//5675 5294//5294 5285//5285 -f 5675//5675 5285//5285 5682//5682 -f 5682//5682 5285//5285 5284//5284 -f 5682//5682 5284//5284 5683//5683 -f 5684//5684 5281//5281 5685//5685 -f 5685//5685 5281//5281 5686//5686 -f 5683//5683 5284//5284 5684//5684 -f 5684//5684 5284//5284 5282//5282 -f 5684//5684 5282//5282 5281//5281 -f 5687//5687 5688//5688 5278//5278 -f 5686//5686 5281//5281 5688//5688 -f 5688//5688 5281//5281 5279//5279 -f 5688//5688 5279//5279 5278//5278 -f 5687//5687 5278//5278 5689//5689 -f 5689//5689 5278//5278 5296//5296 -f 5689//5689 5296//5296 5690//5690 -f 5690//5690 5296//5296 5276//5276 -f 5690//5690 5276//5276 5691//5691 -f 5692//5692 5693//5693 5691//5691 -f 5691//5691 5693//5693 5694//5694 -f 5691//5691 5694//5694 5690//5690 -f 5672//5672 5695//5695 5673//5673 -f 5673//5673 5695//5695 5696//5696 -f 5673//5673 5696//5696 5691//5691 -f 5691//5691 5696//5696 5697//5697 -f 5691//5691 5697//5697 5692//5692 -f 5671//5671 2842//2842 5698//5698 -f 5698//5698 2842//2842 2840//2840 -f 5671//5671 5673//5673 2842//2842 -f 2842//2842 5673//5673 5297//5297 -f 2842//2842 5297//5297 2843//2843 -f 5276//5276 5275//5275 5691//5691 -f 5691//5691 5275//5275 5273//5273 -f 5691//5691 5273//5273 5673//5673 -f 5673//5673 5273//5273 5272//5272 -f 5673//5673 5272//5272 5297//5297 -f 5699//5699 5700//5700 5701//5701 -f 5702//5702 5703//5703 5704//5704 -f 5705//5705 5706//5706 5707//5707 -f 5708//5708 5709//5709 466//466 -f 466//466 5709//5709 5710//5710 -f 466//466 5710//5710 468//468 -f 5708//5708 5711//5711 5712//5712 -f 5712//5712 5711//5711 5713//5713 -f 5714//5714 5715//5715 5716//5716 -f 5716//5716 5715//5715 5717//5717 -f 5716//5716 5717//5717 5718//5718 -f 5719//5719 5720//5720 5721//5721 -f 5721//5721 5720//5720 5722//5722 -f 5723//5723 5724//5724 5725//5725 -f 5725//5725 5724//5724 5726//5726 -f 5725//5725 5726//5726 5727//5727 -f 5728//5728 5729//5729 5730//5730 -f 5730//5730 5729//5729 5731//5731 -f 5702//5702 5704//5704 5732//5732 -f 5732//5732 1246//1246 5733//5733 -f 5733//5733 1246//1246 1251//1251 -f 1257//1257 1255//1255 5734//5734 -f 5734//5734 1255//1255 5735//5735 -f 5736//5736 5737//5737 5738//5738 -f 5738//5738 5737//5737 5739//5739 -f 5738//5738 5739//5739 5740//5740 -f 5741//5741 5742//5742 5743//5743 -f 5743//5743 5742//5742 5736//5736 -f 5744//5744 5745//5745 5746//5746 -f 5746//5746 5745//5745 5747//5747 -f 5746//5746 5747//5747 5741//5741 -f 5748//5748 5749//5749 5750//5750 -f 5750//5750 5749//5749 5751//5751 -f 5750//5750 5751//5751 5744//5744 -f 5752//5752 5753//5753 5754//5754 -f 5754//5754 5753//5753 5755//5755 -f 5754//5754 5755//5755 5748//5748 -f 5700//5700 5756//5756 5701//5701 -f 5701//5701 5756//5756 5757//5757 -f 5701//5701 5757//5757 5752//5752 -f 5758//5758 5699//5699 5759//5759 -f 621//621 5760//5760 622//622 -f 622//622 5760//5760 5761//5761 -f 622//622 5761//5761 5759//5759 -f 5759//5759 5761//5761 5762//5762 -f 5759//5759 5762//5762 5758//5758 -f 5708//5708 466//466 5711//5711 -f 5711//5711 466//466 464//464 -f 5711//5711 464//464 5763//5763 -f 5763//5763 464//464 462//462 -f 5763//5763 462//462 5764//5764 -f 462//462 460//460 5764//5764 -f 5764//5764 460//460 458//458 -f 5764//5764 458//458 5765//5765 -f 458//458 456//456 5765//5765 -f 5765//5765 456//456 454//454 -f 5765//5765 454//454 5766//5766 -f 5766//5766 454//454 452//452 -f 452//452 450//450 5766//5766 -f 5766//5766 450//450 449//449 -f 5766//5766 449//449 5767//5767 -f 5767//5767 449//449 635//635 -f 5767//5767 635//635 5768//5768 -f 635//635 637//637 5768//5768 -f 5768//5768 637//637 638//638 -f 5768//5768 638//638 5769//5769 -f 638//638 641//641 5769//5769 -f 5769//5769 641//641 631//631 -f 5769//5769 631//631 5770//5770 -f 5770//5770 631//631 634//634 -f 5770//5770 634//634 5771//5771 -f 634//634 627//627 5771//5771 -f 5771//5771 627//627 630//630 -f 5771//5771 630//630 5772//5772 -f 630//630 623//623 5772//5772 -f 5772//5772 623//623 626//626 -f 5772//5772 626//626 5759//5759 -f 5759//5759 626//626 601//601 -f 5759//5759 601//601 622//622 -f 5699//5699 5701//5701 5759//5759 -f 5759//5759 5701//5701 5773//5773 -f 5759//5759 5773//5773 5772//5772 -f 5772//5772 5773//5773 5774//5774 -f 5772//5772 5774//5774 5771//5771 -f 5771//5771 5774//5774 5775//5775 -f 5771//5771 5775//5775 5770//5770 -f 5770//5770 5775//5775 5776//5776 -f 5770//5770 5776//5776 5769//5769 -f 5769//5769 5776//5776 5777//5777 -f 5769//5769 5777//5777 5768//5768 -f 5768//5768 5777//5777 5778//5778 -f 5768//5768 5778//5778 5767//5767 -f 5767//5767 5778//5778 5779//5779 -f 5767//5767 5779//5779 5766//5766 -f 5766//5766 5779//5779 5780//5780 -f 5766//5766 5780//5780 5765//5765 -f 5765//5765 5780//5780 5781//5781 -f 5765//5765 5781//5781 5764//5764 -f 5764//5764 5781//5781 5782//5782 -f 5764//5764 5782//5782 5763//5763 -f 5763//5763 5782//5782 5716//5716 -f 5763//5763 5716//5716 5711//5711 -f 5711//5711 5716//5716 5718//5718 -f 5711//5711 5718//5718 5713//5713 -f 5752//5752 5754//5754 5701//5701 -f 5701//5701 5754//5754 5783//5783 -f 5701//5701 5783//5783 5773//5773 -f 5773//5773 5783//5783 5784//5784 -f 5773//5773 5784//5784 5774//5774 -f 5774//5774 5784//5784 5785//5785 -f 5774//5774 5785//5785 5775//5775 -f 5775//5775 5785//5785 5786//5786 -f 5775//5775 5786//5786 5776//5776 -f 5776//5776 5786//5786 5787//5787 -f 5776//5776 5787//5787 5777//5777 -f 5777//5777 5787//5787 5788//5788 -f 5777//5777 5788//5788 5778//5778 -f 5778//5778 5788//5788 5789//5789 -f 5778//5778 5789//5789 5779//5779 -f 5779//5779 5789//5789 5790//5790 -f 5779//5779 5790//5790 5780//5780 -f 5780//5780 5790//5790 5791//5791 -f 5780//5780 5791//5791 5781//5781 -f 5781//5781 5791//5791 5792//5792 -f 5781//5781 5792//5792 5782//5782 -f 5782//5782 5792//5792 5720//5720 -f 5782//5782 5720//5720 5716//5716 -f 5716//5716 5720//5720 5719//5719 -f 5716//5716 5719//5719 5714//5714 -f 5748//5748 5750//5750 5754//5754 -f 5754//5754 5750//5750 5793//5793 -f 5754//5754 5793//5793 5783//5783 -f 5783//5783 5793//5793 5794//5794 -f 5783//5783 5794//5794 5784//5784 -f 5784//5784 5794//5794 5795//5795 -f 5784//5784 5795//5795 5785//5785 -f 5785//5785 5795//5795 5796//5796 -f 5785//5785 5796//5796 5786//5786 -f 5786//5786 5796//5796 5797//5797 -f 5786//5786 5797//5797 5787//5787 -f 5787//5787 5797//5797 5798//5798 -f 5787//5787 5798//5798 5788//5788 -f 5788//5788 5798//5798 5799//5799 -f 5788//5788 5799//5799 5789//5789 -f 5789//5789 5799//5799 5800//5800 -f 5789//5789 5800//5800 5790//5790 -f 5790//5790 5800//5800 5801//5801 -f 5790//5790 5801//5801 5791//5791 -f 5791//5791 5801//5801 5802//5802 -f 5791//5791 5802//5802 5792//5792 -f 5792//5792 5802//5802 5707//5707 -f 5792//5792 5707//5707 5720//5720 -f 5720//5720 5707//5707 5706//5706 -f 5720//5720 5706//5706 5722//5722 -f 5744//5744 5746//5746 5750//5750 -f 5750//5750 5746//5746 5803//5803 -f 5750//5750 5803//5803 5793//5793 -f 5793//5793 5803//5803 5804//5804 -f 5793//5793 5804//5804 5794//5794 -f 5794//5794 5804//5804 5805//5805 -f 5794//5794 5805//5805 5795//5795 -f 5795//5795 5805//5805 5806//5806 -f 5795//5795 5806//5806 5796//5796 -f 5796//5796 5806//5806 5807//5807 -f 5796//5796 5807//5807 5797//5797 -f 5797//5797 5807//5807 5808//5808 -f 5797//5797 5808//5808 5798//5798 -f 5798//5798 5808//5808 5809//5809 -f 5798//5798 5809//5809 5799//5799 -f 5799//5799 5809//5809 5810//5810 -f 5799//5799 5810//5810 5800//5800 -f 5800//5800 5810//5810 5811//5811 -f 5800//5800 5811//5811 5801//5801 -f 5801//5801 5811//5811 5725//5725 -f 5801//5801 5725//5725 5802//5802 -f 5802//5802 5725//5725 5727//5727 -f 5802//5802 5727//5727 5707//5707 -f 5707//5707 5727//5727 5812//5812 -f 5707//5707 5812//5812 5705//5705 -f 5741//5741 5743//5743 5746//5746 -f 5746//5746 5743//5743 5813//5813 -f 5746//5746 5813//5813 5803//5803 -f 5803//5803 5813//5813 5814//5814 -f 5803//5803 5814//5814 5804//5804 -f 5804//5804 5814//5814 5815//5815 -f 5804//5804 5815//5815 5805//5805 -f 5805//5805 5815//5815 5816//5816 -f 5805//5805 5816//5816 5806//5806 -f 5806//5806 5816//5816 5817//5817 -f 5806//5806 5817//5817 5807//5807 -f 5807//5807 5817//5817 5818//5818 -f 5807//5807 5818//5818 5808//5808 -f 5808//5808 5818//5818 5819//5819 -f 5808//5808 5819//5819 5809//5809 -f 5809//5809 5819//5819 5820//5820 -f 5809//5809 5820//5820 5810//5810 -f 5810//5810 5820//5820 5821//5821 -f 5810//5810 5821//5821 5811//5811 -f 5811//5811 5821//5821 5729//5729 -f 5811//5811 5729//5729 5725//5725 -f 5725//5725 5729//5729 5728//5728 -f 5725//5725 5728//5728 5723//5723 -f 5736//5736 5738//5738 5743//5743 -f 5743//5743 5738//5738 5822//5822 -f 5743//5743 5822//5822 5813//5813 -f 5813//5813 5822//5822 5823//5823 -f 5813//5813 5823//5823 5814//5814 -f 5814//5814 5823//5823 5824//5824 -f 5814//5814 5824//5824 5815//5815 -f 5815//5815 5824//5824 5825//5825 -f 5815//5815 5825//5825 5816//5816 -f 5816//5816 5825//5825 5826//5826 -f 5816//5816 5826//5826 5817//5817 -f 5817//5817 5826//5826 5827//5827 -f 5817//5817 5827//5827 5818//5818 -f 5818//5818 5827//5827 5828//5828 -f 5818//5818 5828//5828 5819//5819 -f 5819//5819 5828//5828 5829//5829 -f 5819//5819 5829//5829 5820//5820 -f 5820//5820 5829//5829 5830//5830 -f 5820//5820 5830//5830 5821//5821 -f 5821//5821 5830//5830 5704//5704 -f 5821//5821 5704//5704 5729//5729 -f 5729//5729 5704//5704 5703//5703 -f 5729//5729 5703//5703 5731//5731 -f 5732//5732 5704//5704 1246//1246 -f 1246//1246 5704//5704 5830//5830 -f 1246//1246 5830//5830 1247//1247 -f 1247//1247 5830//5830 5829//5829 -f 1247//1247 5829//5829 1248//1248 -f 1248//1248 5829//5829 5828//5828 -f 1248//1248 5828//5828 1242//1242 -f 1242//1242 5828//5828 5827//5827 -f 1242//1242 5827//5827 1240//1240 -f 1240//1240 5827//5827 5826//5826 -f 1240//1240 5826//5826 1238//1238 -f 1238//1238 5826//5826 5825//5825 -f 1238//1238 5825//5825 1243//1243 -f 1243//1243 5825//5825 5824//5824 -f 1243//1243 5824//5824 1244//1244 -f 1244//1244 5824//5824 5823//5823 -f 1244//1244 5823//5823 1245//1245 -f 1245//1245 5823//5823 5822//5822 -f 1245//1245 5822//5822 1254//1254 -f 1254//1254 5822//5822 5738//5738 -f 1254//1254 5738//5738 1255//1255 -f 1255//1255 5738//5738 5740//5740 -f 1255//1255 5740//5740 5735//5735 -f 542//542 544//544 5831//5831 -f 5832//5832 5833//5833 5834//5834 -f 5835//5835 5836//5836 5837//5837 -f 5838//5838 5839//5839 5840//5840 -f 5841//5841 539//539 540//540 -f 1842//1842 499//499 501//501 -f 1840//1840 5842//5842 1839//1839 -f 1839//1839 5842//5842 1837//1837 -f 5843//5843 1836//1836 1835//1835 -f 1835//1835 1834//1834 5843//5843 -f 5843//5843 1834//1834 1779//1779 -f 5843//5843 1779//1779 1778//1778 -f 1823//1823 1825//1825 5844//5844 -f 5844//5844 1825//1825 1832//1832 -f 5844//5844 1832//1832 1831//1831 -f 1831//1831 1830//1830 5844//5844 -f 5844//5844 1830//1830 1782//1782 -f 5844//5844 1782//1782 1781//1781 -f 1813//1813 1815//1815 5845//5845 -f 5845//5845 1815//1815 1817//1817 -f 1817//1817 1828//1828 5845//5845 -f 5845//5845 1828//1828 1827//1827 -f 5845//5845 1827//1827 5846//5846 -f 5846//5846 1827//1827 1826//1826 -f 5846//5846 1826//1826 1821//1821 -f 1820//1820 1819//1819 5845//5845 -f 5845//5845 1819//1819 1818//1818 -f 5845//5845 1818//1818 1813//1813 -f 1802//1802 1801//1801 5847//5847 -f 1801//1801 1809//1809 5847//5847 -f 5847//5847 1809//1809 1808//1808 -f 5847//5847 1808//1808 1807//1807 -f 1807//1807 1785//1785 5847//5847 -f 5847//5847 1785//1785 1784//1784 -f 5847//5847 1784//1784 5848//5848 -f 5848//5848 1784//1784 1812//1812 -f 5848//5848 1812//1812 5845//5845 -f 5845//5845 1812//1812 1811//1811 -f 5845//5845 1811//1811 1820//1820 -f 1798//1798 1805//1805 5849//5849 -f 5849//5849 1805//1805 1804//1804 -f 5849//5849 1804//1804 5847//5847 -f 5847//5847 1804//1804 1803//1803 -f 5847//5847 1803//1803 1802//1802 -f 545//545 546//546 1793//1793 -f 545//545 1793//1793 544//544 -f 1791//1791 1790//1790 5831//5831 -f 544//544 1793//1793 5831//5831 -f 5831//5831 1793//1793 1792//1792 -f 5831//5831 1792//1792 1791//1791 -f 1790//1790 1796//1796 5831//5831 -f 5831//5831 1796//1796 1795//1795 -f 5831//5831 1795//1795 5849//5849 -f 5849//5849 1795//1795 1799//1799 -f 5849//5849 1799//1799 1798//1798 -f 5840//5840 5839//5839 540//540 -f 540//540 5839//5839 5850//5850 -f 540//540 5850//5850 5841//5841 -f 5851//5851 5852//5852 5853//5853 -f 5853//5853 5852//5852 5854//5854 -f 5853//5853 5854//5854 5840//5840 -f 5840//5840 5854//5854 5855//5855 -f 5840//5840 5855//5855 5838//5838 -f 5856//5856 5857//5857 5858//5858 -f 5858//5858 5857//5857 5859//5859 -f 5858//5858 5859//5859 5860//5860 -f 5856//5856 5861//5861 5857//5857 -f 5857//5857 5861//5861 5862//5862 -f 5857//5857 5862//5862 5853//5853 -f 5853//5853 5862//5862 5863//5863 -f 5853//5853 5863//5863 5851//5851 -f 5864//5864 5865//5865 5866//5866 -f 5866//5866 5865//5865 5867//5867 -f 5866//5866 5867//5867 5868//5868 -f 5869//5869 5870//5870 5871//5871 -f 5871//5871 5870//5870 5872//5872 -f 5835//5835 5837//5837 5873//5873 -f 5873//5873 1198//1198 5874//5874 -f 5874//5874 1198//1198 1204//1204 -f 1209//1209 1212//1212 5875//5875 -f 5875//5875 1212//1212 5876//5876 -f 5877//5877 5878//5878 5879//5879 -f 5879//5879 5878//5878 5880//5880 -f 5879//5879 5880//5880 5881//5881 -f 5882//5882 5883//5883 5884//5884 -f 5884//5884 5883//5883 5877//5877 -f 5885//5885 5886//5886 5887//5887 -f 5887//5887 5886//5886 5888//5888 -f 5887//5887 5888//5888 5882//5882 -f 5889//5889 5890//5890 5891//5891 -f 5891//5891 5890//5890 5892//5892 -f 5891//5891 5892//5892 5885//5885 -f 5893//5893 5894//5894 5895//5895 -f 5895//5895 5894//5894 5896//5896 -f 5895//5895 5896//5896 5889//5889 -f 5833//5833 5897//5897 5834//5834 -f 5834//5834 5897//5897 5898//5898 -f 5834//5834 5898//5898 5893//5893 -f 5899//5899 5832//5832 5900//5900 -f 5899//5899 5900//5900 5901//5901 -f 5901//5901 5900//5900 471//471 -f 5901//5901 471//471 469//469 -f 468//468 5902//5902 469//469 -f 469//469 5902//5902 5903//5903 -f 469//469 5903//5903 5901//5901 -f 540//540 542//542 5840//5840 -f 5840//5840 542//542 5831//5831 -f 5840//5840 5831//5831 5853//5853 -f 5853//5853 5831//5831 5849//5849 -f 5853//5853 5849//5849 5857//5857 -f 5857//5857 5849//5849 5847//5847 -f 5857//5857 5847//5847 5859//5859 -f 5859//5859 5847//5847 5848//5848 -f 1840//1840 1842//1842 5842//5842 -f 5842//5842 1842//1842 501//501 -f 5842//5842 501//501 5904//5904 -f 501//501 498//498 5904//5904 -f 5904//5904 498//498 496//496 -f 5904//5904 496//496 5905//5905 -f 496//496 494//494 5905//5905 -f 5905//5905 494//494 492//492 -f 5905//5905 492//492 5906//5906 -f 5906//5906 492//492 490//490 -f 490//490 488//488 5906//5906 -f 5906//5906 488//488 487//487 -f 5906//5906 487//487 5907//5907 -f 5907//5907 487//487 485//485 -f 5907//5907 485//485 5908//5908 -f 485//485 483//483 5908//5908 -f 5908//5908 483//483 481//481 -f 5908//5908 481//481 5909//5909 -f 481//481 479//479 5909//5909 -f 5909//5909 479//479 477//477 -f 5909//5909 477//477 5910//5910 -f 5910//5910 477//477 475//475 -f 5910//5910 475//475 5900//5900 -f 5900//5900 475//475 473//473 -f 5900//5900 473//473 471//471 -f 5832//5832 5834//5834 5900//5900 -f 5900//5900 5834//5834 5911//5911 -f 5900//5900 5911//5911 5910//5910 -f 5910//5910 5911//5911 5912//5912 -f 5910//5910 5912//5912 5909//5909 -f 5909//5909 5912//5912 5913//5913 -f 5909//5909 5913//5913 5908//5908 -f 5908//5908 5913//5913 5914//5914 -f 5908//5908 5914//5914 5907//5907 -f 5907//5907 5914//5914 5915//5915 -f 5907//5907 5915//5915 5906//5906 -f 5906//5906 5915//5915 5916//5916 -f 5906//5906 5916//5916 5905//5905 -f 5905//5905 5916//5916 5917//5917 -f 5905//5905 5917//5917 5904//5904 -f 5904//5904 5917//5917 5843//5843 -f 5904//5904 5843//5843 5842//5842 -f 5842//5842 5843//5843 1778//1778 -f 5842//5842 1778//1778 1837//1837 -f 5893//5893 5895//5895 5834//5834 -f 5834//5834 5895//5895 5918//5918 -f 5834//5834 5918//5918 5911//5911 -f 5911//5911 5918//5918 5919//5919 -f 5911//5911 5919//5919 5912//5912 -f 5912//5912 5919//5919 5920//5920 -f 5912//5912 5920//5920 5913//5913 -f 5913//5913 5920//5920 5921//5921 -f 5913//5913 5921//5921 5914//5914 -f 5914//5914 5921//5921 5922//5922 -f 5914//5914 5922//5922 5915//5915 -f 5915//5915 5922//5922 5923//5923 -f 5915//5915 5923//5923 5916//5916 -f 5916//5916 5923//5923 5924//5924 -f 5916//5916 5924//5924 5917//5917 -f 5917//5917 5924//5924 5844//5844 -f 5917//5917 5844//5844 5843//5843 -f 5843//5843 5844//5844 1781//1781 -f 5843//5843 1781//1781 1836//1836 -f 5889//5889 5891//5891 5895//5895 -f 5895//5895 5891//5891 5925//5925 -f 5895//5895 5925//5925 5918//5918 -f 5918//5918 5925//5925 5926//5926 -f 5918//5918 5926//5926 5919//5919 -f 5919//5919 5926//5926 5927//5927 -f 5919//5919 5927//5927 5920//5920 -f 5920//5920 5927//5927 5928//5928 -f 5920//5920 5928//5928 5921//5921 -f 5921//5921 5928//5928 5929//5929 -f 5921//5921 5929//5929 5922//5922 -f 5922//5922 5929//5929 5930//5930 -f 5922//5922 5930//5930 5923//5923 -f 5923//5923 5930//5930 5931//5931 -f 5923//5923 5931//5931 5924//5924 -f 5924//5924 5931//5931 5846//5846 -f 5924//5924 5846//5846 5844//5844 -f 5844//5844 5846//5846 1821//1821 -f 5844//5844 1821//1821 1823//1823 -f 5885//5885 5887//5887 5891//5891 -f 5891//5891 5887//5887 5932//5932 -f 5891//5891 5932//5932 5925//5925 -f 5925//5925 5932//5932 5933//5933 -f 5925//5925 5933//5933 5926//5926 -f 5926//5926 5933//5933 5934//5934 -f 5926//5926 5934//5934 5927//5927 -f 5927//5927 5934//5934 5935//5935 -f 5927//5927 5935//5935 5928//5928 -f 5928//5928 5935//5935 5936//5936 -f 5928//5928 5936//5936 5929//5929 -f 5929//5929 5936//5936 5937//5937 -f 5929//5929 5937//5937 5930//5930 -f 5930//5930 5937//5937 5938//5938 -f 5930//5930 5938//5938 5931//5931 -f 5931//5931 5938//5938 5939//5939 -f 5931//5931 5939//5939 5846//5846 -f 5846//5846 5939//5939 5940//5940 -f 5846//5846 5940//5940 5845//5845 -f 5845//5845 5940//5940 5866//5866 -f 5845//5845 5866//5866 5848//5848 -f 5848//5848 5866//5866 5868//5868 -f 5848//5848 5868//5868 5859//5859 -f 5859//5859 5868//5868 5941//5941 -f 5859//5859 5941//5941 5860//5860 -f 5882//5882 5884//5884 5887//5887 -f 5887//5887 5884//5884 5942//5942 -f 5887//5887 5942//5942 5932//5932 -f 5932//5932 5942//5942 5943//5943 -f 5932//5932 5943//5943 5933//5933 -f 5933//5933 5943//5943 5944//5944 -f 5933//5933 5944//5944 5934//5934 -f 5934//5934 5944//5944 5945//5945 -f 5934//5934 5945//5945 5935//5935 -f 5935//5935 5945//5945 5946//5946 -f 5935//5935 5946//5946 5936//5936 -f 5936//5936 5946//5946 5947//5947 -f 5936//5936 5947//5947 5937//5937 -f 5937//5937 5947//5947 5948//5948 -f 5937//5937 5948//5948 5938//5938 -f 5938//5938 5948//5948 5949//5949 -f 5938//5938 5949//5949 5939//5939 -f 5939//5939 5949//5949 5950//5950 -f 5939//5939 5950//5950 5940//5940 -f 5940//5940 5950//5950 5870//5870 -f 5940//5940 5870//5870 5866//5866 -f 5866//5866 5870//5870 5869//5869 -f 5866//5866 5869//5869 5864//5864 -f 5877//5877 5879//5879 5884//5884 -f 5884//5884 5879//5879 5951//5951 -f 5884//5884 5951//5951 5942//5942 -f 5942//5942 5951//5951 5952//5952 -f 5942//5942 5952//5952 5943//5943 -f 5943//5943 5952//5952 5953//5953 -f 5943//5943 5953//5953 5944//5944 -f 5944//5944 5953//5953 5954//5954 -f 5944//5944 5954//5954 5945//5945 -f 5945//5945 5954//5954 5955//5955 -f 5945//5945 5955//5955 5946//5946 -f 5946//5946 5955//5955 5956//5956 -f 5946//5946 5956//5956 5947//5947 -f 5947//5947 5956//5956 5957//5957 -f 5947//5947 5957//5957 5948//5948 -f 5948//5948 5957//5957 5958//5958 -f 5948//5948 5958//5958 5949//5949 -f 5949//5949 5958//5958 5959//5959 -f 5949//5949 5959//5959 5950//5950 -f 5950//5950 5959//5959 5837//5837 -f 5950//5950 5837//5837 5870//5870 -f 5870//5870 5837//5837 5836//5836 -f 5870//5870 5836//5836 5872//5872 -f 5873//5873 5837//5837 1198//1198 -f 1198//1198 5837//5837 5959//5959 -f 1198//1198 5959//5959 1199//1199 -f 1199//1199 5959//5959 5958//5958 -f 1199//1199 5958//5958 1200//1200 -f 1200//1200 5958//5958 5957//5957 -f 1200//1200 5957//5957 1201//1201 -f 1201//1201 5957//5957 5956//5956 -f 1201//1201 5956//5956 1193//1193 -f 1193//1193 5956//5956 5955//5955 -f 1193//1193 5955//5955 1194//1194 -f 1194//1194 5955//5955 5954//5954 -f 1194//1194 5954//5954 1195//1195 -f 1195//1195 5954//5954 5953//5953 -f 1195//1195 5953//5953 1196//1196 -f 1196//1196 5953//5953 5952//5952 -f 1196//1196 5952//5952 1197//1197 -f 1197//1197 5952//5952 5951//5951 -f 1197//1197 5951//5951 1211//1211 -f 1211//1211 5951//5951 5879//5879 -f 1211//1211 5879//5879 1212//1212 -f 1212//1212 5879//5879 5881//5881 -f 1212//1212 5881//5881 5876//5876 -f 5960//5960 5961//5961 5962//5962 -f 5963//5963 5964//5964 5965//5965 -f 5966//5966 5967//5967 5968//5968 -f 5969//5969 5970//5970 619//619 -f 619//619 5970//5970 5971//5971 -f 619//619 5971//5971 621//621 -f 5969//5969 5972//5972 5973//5973 -f 5973//5973 5972//5972 5974//5974 -f 5975//5975 5976//5976 5977//5977 -f 5977//5977 5976//5976 5978//5978 -f 5977//5977 5978//5978 5979//5979 -f 5980//5980 5981//5981 5982//5982 -f 5982//5982 5981//5981 5983//5983 -f 5984//5984 5985//5985 5986//5986 -f 5986//5986 5985//5985 5987//5987 -f 5986//5986 5987//5987 5988//5988 -f 5989//5989 5990//5990 5991//5991 -f 5991//5991 5990//5990 5992//5992 -f 5963//5963 5965//5965 5993//5993 -f 5993//5993 1269//1269 5994//5994 -f 5994//5994 1269//1269 1274//1274 -f 1278//1278 1281//1281 5995//5995 -f 5995//5995 1281//1281 5996//5996 -f 5997//5997 5998//5998 5999//5999 -f 5999//5999 5998//5998 6000//6000 -f 5999//5999 6000//6000 6001//6001 -f 6002//6002 6003//6003 6004//6004 -f 6004//6004 6003//6003 5997//5997 -f 6005//6005 6006//6006 6007//6007 -f 6007//6007 6006//6006 6008//6008 -f 6007//6007 6008//6008 6002//6002 -f 6009//6009 6010//6010 6011//6011 -f 6011//6011 6010//6010 6012//6012 -f 6011//6011 6012//6012 6005//6005 -f 6013//6013 6014//6014 6015//6015 -f 6015//6015 6014//6014 6016//6016 -f 6015//6015 6016//6016 6009//6009 -f 5961//5961 6017//6017 5962//5962 -f 5962//5962 6017//6017 6018//6018 -f 5962//5962 6018//6018 6013//6013 -f 6019//6019 5960//5960 6020//6020 -f 571//571 6021//6021 573//573 -f 573//573 6021//6021 6022//6022 -f 573//573 6022//6022 6020//6020 -f 6020//6020 6022//6022 6023//6023 -f 6020//6020 6023//6023 6019//6019 -f 5969//5969 619//619 5972//5972 -f 5972//5972 619//619 617//617 -f 5972//5972 617//617 6024//6024 -f 617//617 615//615 6024//6024 -f 6024//6024 615//615 613//613 -f 6024//6024 613//613 6025//6025 -f 6025//6025 613//613 611//611 -f 611//611 609//609 6025//6025 -f 6025//6025 609//609 607//607 -f 6025//6025 607//607 6026//6026 -f 6026//6026 607//607 605//605 -f 6026//6026 605//605 6027//6027 -f 6027//6027 605//605 604//604 -f 6027//6027 604//604 6028//6028 -f 604//604 599//599 6028//6028 -f 6028//6028 599//599 597//597 -f 6028//6028 597//597 6029//6029 -f 6029//6029 597//597 595//595 -f 6029//6029 595//595 6030//6030 -f 595//595 593//593 6030//6030 -f 6030//6030 593//593 591//591 -f 6030//6030 591//591 6031//6031 -f 591//591 589//589 6031//6031 -f 6031//6031 589//589 587//587 -f 6031//6031 587//587 6032//6032 -f 6032//6032 587//587 585//585 -f 585//585 583//583 6032//6032 -f 6032//6032 583//583 582//582 -f 6032//6032 582//582 6033//6033 -f 6033//6033 582//582 445//445 -f 6033//6033 445//445 6020//6020 -f 6020//6020 445//445 446//446 -f 6020//6020 446//446 573//573 -f 5960//5960 5962//5962 6020//6020 -f 6020//6020 5962//5962 6034//6034 -f 6020//6020 6034//6034 6033//6033 -f 6033//6033 6034//6034 6035//6035 -f 6033//6033 6035//6035 6032//6032 -f 6032//6032 6035//6035 6036//6036 -f 6032//6032 6036//6036 6031//6031 -f 6031//6031 6036//6036 6037//6037 -f 6031//6031 6037//6037 6030//6030 -f 6030//6030 6037//6037 6038//6038 -f 6030//6030 6038//6038 6029//6029 -f 6029//6029 6038//6038 6039//6039 -f 6029//6029 6039//6039 6028//6028 -f 6028//6028 6039//6039 6040//6040 -f 6028//6028 6040//6040 6027//6027 -f 6027//6027 6040//6040 6041//6041 -f 6027//6027 6041//6041 6026//6026 -f 6026//6026 6041//6041 6042//6042 -f 6026//6026 6042//6042 6025//6025 -f 6025//6025 6042//6042 6043//6043 -f 6025//6025 6043//6043 6024//6024 -f 6024//6024 6043//6043 5977//5977 -f 6024//6024 5977//5977 5972//5972 -f 5972//5972 5977//5977 5979//5979 -f 5972//5972 5979//5979 5974//5974 -f 6013//6013 6015//6015 5962//5962 -f 5962//5962 6015//6015 6044//6044 -f 5962//5962 6044//6044 6034//6034 -f 6034//6034 6044//6044 6045//6045 -f 6034//6034 6045//6045 6035//6035 -f 6035//6035 6045//6045 6046//6046 -f 6035//6035 6046//6046 6036//6036 -f 6036//6036 6046//6046 6047//6047 -f 6036//6036 6047//6047 6037//6037 -f 6037//6037 6047//6047 6048//6048 -f 6037//6037 6048//6048 6038//6038 -f 6038//6038 6048//6048 6049//6049 -f 6038//6038 6049//6049 6039//6039 -f 6039//6039 6049//6049 6050//6050 -f 6039//6039 6050//6050 6040//6040 -f 6040//6040 6050//6050 6051//6051 -f 6040//6040 6051//6051 6041//6041 -f 6041//6041 6051//6051 6052//6052 -f 6041//6041 6052//6052 6042//6042 -f 6042//6042 6052//6052 6053//6053 -f 6042//6042 6053//6053 6043//6043 -f 6043//6043 6053//6053 5981//5981 -f 6043//6043 5981//5981 5977//5977 -f 5977//5977 5981//5981 5980//5980 -f 5977//5977 5980//5980 5975//5975 -f 6009//6009 6011//6011 6015//6015 -f 6015//6015 6011//6011 6054//6054 -f 6015//6015 6054//6054 6044//6044 -f 6044//6044 6054//6054 6055//6055 -f 6044//6044 6055//6055 6045//6045 -f 6045//6045 6055//6055 6056//6056 -f 6045//6045 6056//6056 6046//6046 -f 6046//6046 6056//6056 6057//6057 -f 6046//6046 6057//6057 6047//6047 -f 6047//6047 6057//6057 6058//6058 -f 6047//6047 6058//6058 6048//6048 -f 6048//6048 6058//6058 6059//6059 -f 6048//6048 6059//6059 6049//6049 -f 6049//6049 6059//6059 6060//6060 -f 6049//6049 6060//6060 6050//6050 -f 6050//6050 6060//6060 6061//6061 -f 6050//6050 6061//6061 6051//6051 -f 6051//6051 6061//6061 6062//6062 -f 6051//6051 6062//6062 6052//6052 -f 6052//6052 6062//6062 6063//6063 -f 6052//6052 6063//6063 6053//6053 -f 6053//6053 6063//6063 5968//5968 -f 6053//6053 5968//5968 5981//5981 -f 5981//5981 5968//5968 5967//5967 -f 5981//5981 5967//5967 5983//5983 -f 6005//6005 6007//6007 6011//6011 -f 6011//6011 6007//6007 6064//6064 -f 6011//6011 6064//6064 6054//6054 -f 6054//6054 6064//6064 6065//6065 -f 6054//6054 6065//6065 6055//6055 -f 6055//6055 6065//6065 6066//6066 -f 6055//6055 6066//6066 6056//6056 -f 6056//6056 6066//6066 6067//6067 -f 6056//6056 6067//6067 6057//6057 -f 6057//6057 6067//6067 6068//6068 -f 6057//6057 6068//6068 6058//6058 -f 6058//6058 6068//6068 6069//6069 -f 6058//6058 6069//6069 6059//6059 -f 6059//6059 6069//6069 6070//6070 -f 6059//6059 6070//6070 6060//6060 -f 6060//6060 6070//6070 6071//6071 -f 6060//6060 6071//6071 6061//6061 -f 6061//6061 6071//6071 6072//6072 -f 6061//6061 6072//6072 6062//6062 -f 6062//6062 6072//6072 5986//5986 -f 6062//6062 5986//5986 6063//6063 -f 6063//6063 5986//5986 5988//5988 -f 6063//6063 5988//5988 5968//5968 -f 5968//5968 5988//5988 6073//6073 -f 5968//5968 6073//6073 5966//5966 -f 6002//6002 6004//6004 6007//6007 -f 6007//6007 6004//6004 6074//6074 -f 6007//6007 6074//6074 6064//6064 -f 6064//6064 6074//6074 6075//6075 -f 6064//6064 6075//6075 6065//6065 -f 6065//6065 6075//6075 6076//6076 -f 6065//6065 6076//6076 6066//6066 -f 6066//6066 6076//6076 6077//6077 -f 6066//6066 6077//6077 6067//6067 -f 6067//6067 6077//6077 6078//6078 -f 6067//6067 6078//6078 6068//6068 -f 6068//6068 6078//6078 6079//6079 -f 6068//6068 6079//6079 6069//6069 -f 6069//6069 6079//6079 6080//6080 -f 6069//6069 6080//6080 6070//6070 -f 6070//6070 6080//6080 6081//6081 -f 6070//6070 6081//6081 6071//6071 -f 6071//6071 6081//6081 6082//6082 -f 6071//6071 6082//6082 6072//6072 -f 6072//6072 6082//6082 5990//5990 -f 6072//6072 5990//5990 5986//5986 -f 5986//5986 5990//5990 5989//5989 -f 5986//5986 5989//5989 5984//5984 -f 5997//5997 5999//5999 6004//6004 -f 6004//6004 5999//5999 6083//6083 -f 6004//6004 6083//6083 6074//6074 -f 6074//6074 6083//6083 6084//6084 -f 6074//6074 6084//6084 6075//6075 -f 6075//6075 6084//6084 6085//6085 -f 6075//6075 6085//6085 6076//6076 -f 6076//6076 6085//6085 6086//6086 -f 6076//6076 6086//6086 6077//6077 -f 6077//6077 6086//6086 6087//6087 -f 6077//6077 6087//6087 6078//6078 -f 6078//6078 6087//6087 6088//6088 -f 6078//6078 6088//6088 6079//6079 -f 6079//6079 6088//6088 6089//6089 -f 6079//6079 6089//6089 6080//6080 -f 6080//6080 6089//6089 6090//6090 -f 6080//6080 6090//6090 6081//6081 -f 6081//6081 6090//6090 6091//6091 -f 6081//6081 6091//6091 6082//6082 -f 6082//6082 6091//6091 5965//5965 -f 6082//6082 5965//5965 5990//5990 -f 5990//5990 5965//5965 5964//5964 -f 5990//5990 5964//5964 5992//5992 -f 5993//5993 5965//5965 1269//1269 -f 1269//1269 5965//5965 6091//6091 -f 1269//1269 6091//6091 1270//1270 -f 1270//1270 6091//6091 6090//6090 -f 1270//1270 6090//6090 1271//1271 -f 1271//1271 6090//6090 6089//6089 -f 1271//1271 6089//6089 1265//1265 -f 1265//1265 6089//6089 6088//6088 -f 1265//1265 6088//6088 1263//1263 -f 1263//1263 6088//6088 6087//6087 -f 1263//1263 6087//6087 1261//1261 -f 1261//1261 6087//6087 6086//6086 -f 1261//1261 6086//6086 1266//1266 -f 1266//1266 6086//6086 6085//6085 -f 1266//1266 6085//6085 1267//1267 -f 1267//1267 6085//6085 6084//6084 -f 1267//1267 6084//6084 1268//1268 -f 1268//1268 6084//6084 6083//6083 -f 1268//1268 6083//6083 1280//1280 -f 1280//1280 6083//6083 5999//5999 -f 1280//1280 5999//5999 1281//1281 -f 1281//1281 5999//5999 6001//6001 -f 1281//1281 6001//6001 5996//5996 -f 6092//6092 6093//6093 6094//6094 -f 6095//6095 6096//6096 6097//6097 -f 6098//6098 6099//6099 6100//6100 -f 1234//1234 1232//1232 6101//6101 -f 6101//6101 1232//1232 6102//6102 -f 6103//6103 6104//6104 6105//6105 -f 6105//6105 6104//6104 6106//6106 -f 6105//6105 6106//6106 6107//6107 -f 6108//6108 6109//6109 6110//6110 -f 6110//6110 6109//6109 6103//6103 -f 6111//6111 6112//6112 6113//6113 -f 6113//6113 6112//6112 6114//6114 -f 6113//6113 6114//6114 6108//6108 -f 6115//6115 6116//6116 6117//6117 -f 6117//6117 6116//6116 6118//6118 -f 6117//6117 6118//6118 6111//6111 -f 6119//6119 6120//6120 6121//6121 -f 6121//6121 6120//6120 6122//6122 -f 6121//6121 6122//6122 6115//6115 -f 6099//6099 6123//6123 6100//6100 -f 6100//6100 6123//6123 6124//6124 -f 6100//6100 6124//6124 6119//6119 -f 6098//6098 6125//6125 6126//6126 -f 6126//6126 6125//6125 6127//6127 -f 538//538 539//539 6128//6128 -f 571//571 567//567 6129//6129 -f 6129//6129 567//567 6130//6130 -f 6131//6131 6132//6132 6133//6133 -f 6133//6133 6132//6132 6134//6134 -f 6135//6135 6136//6136 6137//6137 -f 6137//6137 6136//6136 6138//6138 -f 6137//6137 6138//6138 6139//6139 -f 6140//6140 6141//6141 6142//6142 -f 6142//6142 6141//6141 6143//6143 -f 6144//6144 6145//6145 6146//6146 -f 6146//6146 6145//6145 6147//6147 -f 6146//6146 6147//6147 6148//6148 -f 6149//6149 6150//6150 6151//6151 -f 6151//6151 6150//6150 6152//6152 -f 6092//6092 6094//6094 6153//6153 -f 6153//6153 1223//1223 6154//6154 -f 6154//6154 1223//1223 1228//1228 -f 563//563 6155//6155 564//564 -f 564//564 6155//6155 6132//6132 -f 564//564 6132//6132 567//567 -f 567//567 6132//6132 6131//6131 -f 567//567 6131//6131 6130//6130 -f 563//563 562//562 6155//6155 -f 6155//6155 562//562 561//561 -f 6155//6155 561//561 6156//6156 -f 6156//6156 561//561 560//560 -f 6156//6156 560//560 6157//6157 -f 560//560 559//559 6157//6157 -f 6157//6157 559//559 558//558 -f 6157//6157 558//558 6158//6158 -f 558//558 557//557 6158//6158 -f 6158//6158 557//557 556//556 -f 6158//6158 556//556 6159//6159 -f 6159//6159 556//556 555//555 -f 6159//6159 555//555 6160//6160 -f 555//555 554//554 6160//6160 -f 6160//6160 554//554 553//553 -f 6160//6160 553//553 6161//6161 -f 6161//6161 553//553 552//552 -f 552//552 551//551 6161//6161 -f 6161//6161 551//551 550//550 -f 6161//6161 550//550 6162//6162 -f 6162//6162 550//550 549//549 -f 6162//6162 549//549 6163//6163 -f 6163//6163 549//549 548//548 -f 6163//6163 548//548 6164//6164 -f 6128//6128 6165//6165 538//538 -f 538//538 6165//6165 6127//6127 -f 538//538 6127//6127 537//537 -f 537//537 6127//6127 6125//6125 -f 537//537 6125//6125 447//447 -f 447//447 6125//6125 6164//6164 -f 447//447 6164//6164 547//547 -f 547//547 6164//6164 548//548 -f 6098//6098 6100//6100 6125//6125 -f 6125//6125 6100//6100 6166//6166 -f 6125//6125 6166//6166 6164//6164 -f 6164//6164 6166//6166 6167//6167 -f 6164//6164 6167//6167 6163//6163 -f 6163//6163 6167//6167 6168//6168 -f 6163//6163 6168//6168 6162//6162 -f 6162//6162 6168//6168 6169//6169 -f 6162//6162 6169//6169 6161//6161 -f 6161//6161 6169//6169 6170//6170 -f 6161//6161 6170//6170 6160//6160 -f 6160//6160 6170//6170 6171//6171 -f 6160//6160 6171//6171 6159//6159 -f 6159//6159 6171//6171 6172//6172 -f 6159//6159 6172//6172 6158//6158 -f 6158//6158 6172//6172 6173//6173 -f 6158//6158 6173//6173 6157//6157 -f 6157//6157 6173//6173 6174//6174 -f 6157//6157 6174//6174 6156//6156 -f 6156//6156 6174//6174 6175//6175 -f 6156//6156 6175//6175 6155//6155 -f 6155//6155 6175//6175 6137//6137 -f 6155//6155 6137//6137 6132//6132 -f 6132//6132 6137//6137 6139//6139 -f 6132//6132 6139//6139 6134//6134 -f 6119//6119 6121//6121 6100//6100 -f 6100//6100 6121//6121 6176//6176 -f 6100//6100 6176//6176 6166//6166 -f 6166//6166 6176//6176 6177//6177 -f 6166//6166 6177//6177 6167//6167 -f 6167//6167 6177//6177 6178//6178 -f 6167//6167 6178//6178 6168//6168 -f 6168//6168 6178//6178 6179//6179 -f 6168//6168 6179//6179 6169//6169 -f 6169//6169 6179//6179 6180//6180 -f 6169//6169 6180//6180 6170//6170 -f 6170//6170 6180//6180 6181//6181 -f 6170//6170 6181//6181 6171//6171 -f 6171//6171 6181//6181 6182//6182 -f 6171//6171 6182//6182 6172//6172 -f 6172//6172 6182//6182 6183//6183 -f 6172//6172 6183//6183 6173//6173 -f 6173//6173 6183//6183 6184//6184 -f 6173//6173 6184//6184 6174//6174 -f 6174//6174 6184//6184 6185//6185 -f 6174//6174 6185//6185 6175//6175 -f 6175//6175 6185//6185 6141//6141 -f 6175//6175 6141//6141 6137//6137 -f 6137//6137 6141//6141 6140//6140 -f 6137//6137 6140//6140 6135//6135 -f 6115//6115 6117//6117 6121//6121 -f 6121//6121 6117//6117 6186//6186 -f 6121//6121 6186//6186 6176//6176 -f 6176//6176 6186//6186 6187//6187 -f 6176//6176 6187//6187 6177//6177 -f 6177//6177 6187//6187 6188//6188 -f 6177//6177 6188//6188 6178//6178 -f 6178//6178 6188//6188 6189//6189 -f 6178//6178 6189//6189 6179//6179 -f 6179//6179 6189//6189 6190//6190 -f 6179//6179 6190//6190 6180//6180 -f 6180//6180 6190//6190 6191//6191 -f 6180//6180 6191//6191 6181//6181 -f 6181//6181 6191//6191 6192//6192 -f 6181//6181 6192//6192 6182//6182 -f 6182//6182 6192//6192 6193//6193 -f 6182//6182 6193//6193 6183//6183 -f 6183//6183 6193//6193 6194//6194 -f 6183//6183 6194//6194 6184//6184 -f 6184//6184 6194//6194 6195//6195 -f 6184//6184 6195//6195 6185//6185 -f 6185//6185 6195//6195 6097//6097 -f 6185//6185 6097//6097 6141//6141 -f 6141//6141 6097//6097 6096//6096 -f 6141//6141 6096//6096 6143//6143 -f 6111//6111 6113//6113 6117//6117 -f 6117//6117 6113//6113 6196//6196 -f 6117//6117 6196//6196 6186//6186 -f 6186//6186 6196//6196 6197//6197 -f 6186//6186 6197//6197 6187//6187 -f 6187//6187 6197//6197 6198//6198 -f 6187//6187 6198//6198 6188//6188 -f 6188//6188 6198//6198 6199//6199 -f 6188//6188 6199//6199 6189//6189 -f 6189//6189 6199//6199 6200//6200 -f 6189//6189 6200//6200 6190//6190 -f 6190//6190 6200//6200 6201//6201 -f 6190//6190 6201//6201 6191//6191 -f 6191//6191 6201//6201 6202//6202 -f 6191//6191 6202//6202 6192//6192 -f 6192//6192 6202//6202 6203//6203 -f 6192//6192 6203//6203 6193//6193 -f 6193//6193 6203//6203 6204//6204 -f 6193//6193 6204//6204 6194//6194 -f 6194//6194 6204//6204 6146//6146 -f 6194//6194 6146//6146 6195//6195 -f 6195//6195 6146//6146 6148//6148 -f 6195//6195 6148//6148 6097//6097 -f 6097//6097 6148//6148 6205//6205 -f 6097//6097 6205//6205 6095//6095 -f 6108//6108 6110//6110 6113//6113 -f 6113//6113 6110//6110 6206//6206 -f 6113//6113 6206//6206 6196//6196 -f 6196//6196 6206//6206 6207//6207 -f 6196//6196 6207//6207 6197//6197 -f 6197//6197 6207//6207 6208//6208 -f 6197//6197 6208//6208 6198//6198 -f 6198//6198 6208//6208 6209//6209 -f 6198//6198 6209//6209 6199//6199 -f 6199//6199 6209//6209 6210//6210 -f 6199//6199 6210//6210 6200//6200 -f 6200//6200 6210//6210 6211//6211 -f 6200//6200 6211//6211 6201//6201 -f 6201//6201 6211//6211 6212//6212 -f 6201//6201 6212//6212 6202//6202 -f 6202//6202 6212//6212 6213//6213 -f 6202//6202 6213//6213 6203//6203 -f 6203//6203 6213//6213 6214//6214 -f 6203//6203 6214//6214 6204//6204 -f 6204//6204 6214//6214 6150//6150 -f 6204//6204 6150//6150 6146//6146 -f 6146//6146 6150//6150 6149//6149 -f 6146//6146 6149//6149 6144//6144 -f 6103//6103 6105//6105 6110//6110 -f 6110//6110 6105//6105 6215//6215 -f 6110//6110 6215//6215 6206//6206 -f 6206//6206 6215//6215 6216//6216 -f 6206//6206 6216//6216 6207//6207 -f 6207//6207 6216//6216 6217//6217 -f 6207//6207 6217//6217 6208//6208 -f 6208//6208 6217//6217 6218//6218 -f 6208//6208 6218//6218 6209//6209 -f 6209//6209 6218//6218 6219//6219 -f 6209//6209 6219//6219 6210//6210 -f 6210//6210 6219//6219 6220//6220 -f 6210//6210 6220//6220 6211//6211 -f 6211//6211 6220//6220 6221//6221 -f 6211//6211 6221//6221 6212//6212 -f 6212//6212 6221//6221 6222//6222 -f 6212//6212 6222//6222 6213//6213 -f 6213//6213 6222//6222 6223//6223 -f 6213//6213 6223//6223 6214//6214 -f 6214//6214 6223//6223 6094//6094 -f 6214//6214 6094//6094 6150//6150 -f 6150//6150 6094//6094 6093//6093 -f 6150//6150 6093//6093 6152//6152 -f 6153//6153 6094//6094 1223//1223 -f 1223//1223 6094//6094 6223//6223 -f 1223//1223 6223//6223 1224//1224 -f 1224//1224 6223//6223 6222//6222 -f 1224//1224 6222//6222 1225//1225 -f 1225//1225 6222//6222 6221//6221 -f 1225//1225 6221//6221 1219//1219 -f 1219//1219 6221//6221 6220//6220 -f 1219//1219 6220//6220 1217//1217 -f 1217//1217 6220//6220 6219//6219 -f 1217//1217 6219//6219 1215//1215 -f 1215//1215 6219//6219 6218//6218 -f 1215//1215 6218//6218 1220//1220 -f 1220//1220 6218//6218 6217//6217 -f 1220//1220 6217//6217 1221//1221 -f 1221//1221 6217//6217 6216//6216 -f 1221//1221 6216//6216 1222//1222 -f 1222//1222 6216//6216 6215//6215 -f 1222//1222 6215//6215 1231//1231 -f 1231//1231 6215//6215 6105//6105 -f 1231//1231 6105//6105 1232//1232 -f 1232//1232 6105//6105 6107//6107 -f 1232//1232 6107//6107 6102//6102 -f 2732//2732 2731//2731 6224//6224 -f 2727//2727 2725//2725 6225//6225 -f 1338//1338 1337//1337 2733//2733 -f 2733//2733 1337//1337 6226//6226 -f 2733//2733 6226//6226 2715//2715 -f 2725//2725 2723//2723 6225//6225 -f 6225//6225 2723//2723 2721//2721 -f 6225//6225 2721//2721 6226//6226 -f 6226//6226 2721//2721 2720//2720 -f 6226//6226 2720//2720 2715//2715 -f 6224//6224 2731//2731 6225//6225 -f 6225//6225 2731//2731 2729//2729 -f 6225//6225 2729//2729 2727//2727 -f 2732//2732 6224//6224 2713//2713 -f 2713//2713 6224//6224 1296//1296 -f 2713//2713 1296//1296 1295//1295 -f 2840//2840 5577//5577 6227//6227 -f 2840//2840 6228//6228 6229//6229 -f 6229//6229 6228//6228 6230//6230 -f 5579//5579 5582//5582 6231//6231 -f 5697//5697 5696//5696 6232//6232 -f 5687//5687 6233//6233 6234//6234 -f 6226//6226 1337//1337 5674//5674 -f 6225//6225 6226//6226 6235//6235 -f 1296//1296 6236//6236 5602//5602 -f 5602//5602 6236//6236 6237//6237 -f 5602//5602 6237//6237 5601//5601 -f 5601//5601 6237//6237 6238//6238 -f 6226//6226 5674//5674 6235//6235 -f 6235//6235 5674//5674 5681//5681 -f 6235//6235 5681//5681 6239//6239 -f 6239//6239 5681//5681 5680//5680 -f 6239//6239 5680//5680 6240//6240 -f 6240//6240 5680//5680 5679//5679 -f 6240//6240 5679//5679 6241//6241 -f 6242//6242 5600//5600 6243//6243 -f 6243//6243 5600//5600 5540//5540 -f 6243//6243 5540//5540 6238//6238 -f 6238//6238 5540//5540 5539//5539 -f 6238//6238 5539//5539 5601//5601 -f 5679//5679 5678//5678 6241//6241 -f 6241//6241 5678//5678 5677//5677 -f 6241//6241 5677//5677 6244//6244 -f 6244//6244 5677//5677 5676//5676 -f 6244//6244 5676//5676 6245//6245 -f 6246//6246 5592//5592 6247//6247 -f 6247//6247 5592//5592 5597//5597 -f 6247//6247 5597//5597 6242//6242 -f 6242//6242 5597//5597 5599//5599 -f 6242//6242 5599//5599 5600//5600 -f 5676//5676 5675//5675 6245//6245 -f 6245//6245 5675//5675 5682//5682 -f 6245//6245 5682//5682 6248//6248 -f 6248//6248 5682//5682 5683//5683 -f 6248//6248 5683//5683 6249//6249 -f 5596//5596 5595//5595 6246//6246 -f 6246//6246 5595//5595 5593//5593 -f 6246//6246 5593//5593 5592//5592 -f 5596//5596 6246//6246 5652//5652 -f 5652//5652 6246//6246 6250//6250 -f 5652//5652 6250//6250 6251//6251 -f 5683//5683 5684//5684 6249//6249 -f 6249//6249 5684//5684 5685//5685 -f 6249//6249 5685//5685 6252//6252 -f 6252//6252 5685//5685 5686//5686 -f 6252//6252 5686//5686 6234//6234 -f 6234//6234 5686//5686 5688//5688 -f 6234//6234 5688//5688 5687//5687 -f 6253//6253 5591//5591 6254//6254 -f 6254//6254 5591//5591 5543//5543 -f 6254//6254 5543//5543 6251//6251 -f 6251//6251 5543//5543 5542//5542 -f 6251//6251 5542//5542 5652//5652 -f 5694//5694 6255//6255 5690//5690 -f 5690//5690 6255//6255 6233//6233 -f 5690//5690 6233//6233 5689//5689 -f 5689//5689 6233//6233 5687//5687 -f 6224//6224 6225//6225 6256//6256 -f 6256//6256 6225//6225 6235//6235 -f 6256//6256 6235//6235 6257//6257 -f 6257//6257 6235//6235 6239//6239 -f 6257//6257 6239//6239 6258//6258 -f 6258//6258 6239//6239 6240//6240 -f 6258//6258 6240//6240 6259//6259 -f 6259//6259 6240//6240 6241//6241 -f 6259//6259 6241//6241 6260//6260 -f 6260//6260 6241//6241 6244//6244 -f 6260//6260 6244//6244 6261//6261 -f 6261//6261 6244//6244 6245//6245 -f 6261//6261 6245//6245 6262//6262 -f 6262//6262 6245//6245 6248//6248 -f 6262//6262 6248//6248 6263//6263 -f 6263//6263 6248//6248 6249//6249 -f 6263//6263 6249//6249 6264//6264 -f 6264//6264 6249//6249 6252//6252 -f 6264//6264 6252//6252 6265//6265 -f 6265//6265 6252//6252 6234//6234 -f 6265//6265 6234//6234 6266//6266 -f 6266//6266 6234//6234 6233//6233 -f 6266//6266 6233//6233 6267//6267 -f 6267//6267 6233//6233 6255//6255 -f 6267//6267 6255//6255 6268//6268 -f 1296//1296 6224//6224 6236//6236 -f 6236//6236 6224//6224 6256//6256 -f 6236//6236 6256//6256 6237//6237 -f 6237//6237 6256//6256 6257//6257 -f 6237//6237 6257//6257 6238//6238 -f 6238//6238 6257//6257 6258//6258 -f 6238//6238 6258//6258 6243//6243 -f 6243//6243 6258//6258 6259//6259 -f 6243//6243 6259//6259 6242//6242 -f 6242//6242 6259//6259 6260//6260 -f 6242//6242 6260//6260 6247//6247 -f 6247//6247 6260//6260 6261//6261 -f 6247//6247 6261//6261 6246//6246 -f 6246//6246 6261//6261 6262//6262 -f 6246//6246 6262//6262 6250//6250 -f 6250//6250 6262//6262 6263//6263 -f 6250//6250 6263//6263 6251//6251 -f 6251//6251 6263//6263 6264//6264 -f 6251//6251 6264//6264 6254//6254 -f 6254//6254 6264//6264 6265//6265 -f 6254//6254 6265//6265 6253//6253 -f 6253//6253 6265//6265 6266//6266 -f 6253//6253 6266//6266 6269//6269 -f 6269//6269 6266//6266 6267//6267 -f 6269//6269 6267//6267 6270//6270 -f 6270//6270 6267//6267 6268//6268 -f 6270//6270 6268//6268 6271//6271 -f 5587//5587 5586//5586 6271//6271 -f 6271//6271 5586//5586 5584//5584 -f 6271//6271 5584//5584 6270//6270 -f 6270//6270 5584//5584 5583//5583 -f 6270//6270 5583//5583 6269//6269 -f 6269//6269 5583//5583 5588//5588 -f 6269//6269 5588//5588 6253//6253 -f 6253//6253 5588//5588 5590//5590 -f 6253//6253 5590//5590 5591//5591 -f 5581//5581 5587//5587 6272//6272 -f 6272//6272 5587//5587 6271//6271 -f 6272//6272 6271//6271 6273//6273 -f 6273//6273 6271//6271 6268//6268 -f 6273//6273 6268//6268 6274//6274 -f 6274//6274 6268//6268 6255//6255 -f 6274//6274 6255//6255 5693//5693 -f 5693//5693 6255//6255 5694//5694 -f 5582//5582 5581//5581 6231//6231 -f 6231//6231 5581//5581 6272//6272 -f 6231//6231 6272//6272 6275//6275 -f 6275//6275 6272//6272 6273//6273 -f 6275//6275 6273//6273 6276//6276 -f 6276//6276 6273//6273 6274//6274 -f 6276//6276 6274//6274 5692//5692 -f 5692//5692 6274//6274 5693//5693 -f 5578//5578 5579//5579 6277//6277 -f 6277//6277 5579//5579 6231//6231 -f 6277//6277 6231//6231 6278//6278 -f 6278//6278 6231//6231 6275//6275 -f 6278//6278 6275//6275 6232//6232 -f 6232//6232 6275//6275 6276//6276 -f 6232//6232 6276//6276 5697//5697 -f 5697//5697 6276//6276 5692//5692 -f 5672//5672 5671//5671 6230//6230 -f 6230//6230 5671//5671 5698//5698 -f 6230//6230 5698//5698 6229//6229 -f 6229//6229 5698//5698 2840//2840 -f 5695//5695 5672//5672 6279//6279 -f 6279//6279 5672//5672 6230//6230 -f 6279//6279 6230//6230 6280//6280 -f 6280//6280 6230//6230 6228//6228 -f 6280//6280 6228//6228 6227//6227 -f 6227//6227 6228//6228 2840//2840 -f 5577//5577 5578//5578 6227//6227 -f 6227//6227 5578//5578 6277//6277 -f 6227//6227 6277//6277 6280//6280 -f 6280//6280 6277//6277 6278//6278 -f 6280//6280 6278//6278 6279//6279 -f 6279//6279 6278//6278 6232//6232 -f 6279//6279 6232//6232 5695//5695 -f 5695//5695 6232//6232 5696//5696 -f 1298//1298 1300//1300 2641//2641 -f 2641//2641 1300//1300 6281//6281 -f 2641//2641 6281//6281 2642//2642 -f 2648//2648 2650//2650 6282//6282 -f 6282//6282 2650//2650 2652//2652 -f 6282//6282 2652//2652 6281//6281 -f 6281//6281 2652//2652 2654//2654 -f 6281//6281 2654//2654 2642//2642 -f 2660//2660 2657//2657 6283//6283 -f 6283//6283 2657//2657 2644//2644 -f 6283//6283 2644//2644 6282//6282 -f 6282//6282 2644//2644 2646//2646 -f 6282//6282 2646//2646 2648//2648 -f 2660//2660 6283//6283 2668//2668 -f 2668//2668 6283//6283 1364//1364 -f 2668//2668 1364//1364 1366//1366 -f 2813//2813 5177//5177 6284//6284 -f 2813//2813 6285//6285 6286//6286 -f 6286//6286 6285//6285 6287//6287 -f 5179//5179 5181//5181 6288//6288 -f 5546//5546 5545//5545 6289//6289 -f 6281//6281 1300//1300 5548//5548 -f 6282//6282 6281//6281 6290//6290 -f 1364//1364 6291//6291 5202//5202 -f 5202//5202 6291//6291 6292//6292 -f 5202//5202 6292//6292 5201//5201 -f 5201//5201 6292//6292 6293//6293 -f 6281//6281 5548//5548 6290//6290 -f 6290//6290 5548//5548 5549//5549 -f 6290//6290 5549//5549 6294//6294 -f 6294//6294 5549//5549 5554//5554 -f 6294//6294 5554//5554 6295//6295 -f 6295//6295 5554//5554 5553//5553 -f 6295//6295 5553//5553 6296//6296 -f 6297//6297 5200//5200 6298//6298 -f 6298//6298 5200//5200 5166//5166 -f 6298//6298 5166//5166 6293//6293 -f 6293//6293 5166//5166 5165//5165 -f 6293//6293 5165//5165 5201//5201 -f 5553//5553 5551//5551 6296//6296 -f 6296//6296 5551//5551 5550//5550 -f 6296//6296 5550//5550 6299//6299 -f 6299//6299 5550//5550 5556//5556 -f 6299//6299 5556//5556 6300//6300 -f 6301//6301 5192//5192 6302//6302 -f 6302//6302 5192//5192 5197//5197 -f 6302//6302 5197//5197 6297//6297 -f 6297//6297 5197//5197 5199//5199 -f 6297//6297 5199//5199 5200//5200 -f 5556//5556 5555//5555 6300//6300 -f 6300//6300 5555//5555 5561//5561 -f 6300//6300 5561//5561 6303//6303 -f 6303//6303 5561//5561 5559//5559 -f 6303//6303 5559//5559 6304//6304 -f 5196//5196 5195//5195 6301//6301 -f 6301//6301 5195//5195 5193//5193 -f 6301//6301 5193//5193 5192//5192 -f 5196//5196 6301//6301 5252//5252 -f 5252//5252 6301//6301 6305//6305 -f 5252//5252 6305//6305 6306//6306 -f 5559//5559 5558//5558 6304//6304 -f 6304//6304 5558//5558 5565//5565 -f 6304//6304 5565//5565 6307//6307 -f 6307//6307 5565//5565 5563//5563 -f 6307//6307 5563//5563 6308//6308 -f 6309//6309 5191//5191 6310//6310 -f 6310//6310 5191//5191 5169//5169 -f 6310//6310 5169//5169 6306//6306 -f 6306//6306 5169//5169 5168//5168 -f 6306//6306 5168//5168 5252//5252 -f 5566//5566 6311//6311 5567//5567 -f 5567//5567 6311//6311 6312//6312 -f 5567//5567 6312//6312 5569//5569 -f 5569//5569 6312//6312 6308//6308 -f 5569//5569 6308//6308 5562//5562 -f 5562//5562 6308//6308 5563//5563 -f 6283//6283 6282//6282 6313//6313 -f 6313//6313 6282//6282 6290//6290 -f 6313//6313 6290//6290 6314//6314 -f 6314//6314 6290//6290 6294//6294 -f 6314//6314 6294//6294 6315//6315 -f 6315//6315 6294//6294 6295//6295 -f 6315//6315 6295//6295 6316//6316 -f 6316//6316 6295//6295 6296//6296 -f 6316//6316 6296//6296 6317//6317 -f 6317//6317 6296//6296 6299//6299 -f 6317//6317 6299//6299 6318//6318 -f 6318//6318 6299//6299 6300//6300 -f 6318//6318 6300//6300 6319//6319 -f 6319//6319 6300//6300 6303//6303 -f 6319//6319 6303//6303 6320//6320 -f 6320//6320 6303//6303 6304//6304 -f 6320//6320 6304//6304 6321//6321 -f 6321//6321 6304//6304 6307//6307 -f 6321//6321 6307//6307 6322//6322 -f 6322//6322 6307//6307 6308//6308 -f 6322//6322 6308//6308 6323//6323 -f 6323//6323 6308//6308 6312//6312 -f 6323//6323 6312//6312 6324//6324 -f 6324//6324 6312//6312 6311//6311 -f 6324//6324 6311//6311 6325//6325 -f 1364//1364 6283//6283 6291//6291 -f 6291//6291 6283//6283 6313//6313 -f 6291//6291 6313//6313 6292//6292 -f 6292//6292 6313//6313 6314//6314 -f 6292//6292 6314//6314 6293//6293 -f 6293//6293 6314//6314 6315//6315 -f 6293//6293 6315//6315 6298//6298 -f 6298//6298 6315//6315 6316//6316 -f 6298//6298 6316//6316 6297//6297 -f 6297//6297 6316//6316 6317//6317 -f 6297//6297 6317//6317 6302//6302 -f 6302//6302 6317//6317 6318//6318 -f 6302//6302 6318//6318 6301//6301 -f 6301//6301 6318//6318 6319//6319 -f 6301//6301 6319//6319 6305//6305 -f 6305//6305 6319//6319 6320//6320 -f 6305//6305 6320//6320 6306//6306 -f 6306//6306 6320//6320 6321//6321 -f 6306//6306 6321//6321 6310//6310 -f 6310//6310 6321//6321 6322//6322 -f 6310//6310 6322//6322 6309//6309 -f 6309//6309 6322//6322 6323//6323 -f 6309//6309 6323//6323 6326//6326 -f 6326//6326 6323//6323 6324//6324 -f 6326//6326 6324//6324 6327//6327 -f 6327//6327 6324//6324 6325//6325 -f 6327//6327 6325//6325 6328//6328 -f 5187//5187 5186//5186 6328//6328 -f 6328//6328 5186//5186 5184//5184 -f 6328//6328 5184//5184 6327//6327 -f 6327//6327 5184//5184 5183//5183 -f 6327//6327 5183//5183 6326//6326 -f 6326//6326 5183//5183 5188//5188 -f 6326//6326 5188//5188 6309//6309 -f 6309//6309 5188//5188 5190//5190 -f 6309//6309 5190//5190 5191//5191 -f 5182//5182 5187//5187 6329//6329 -f 6329//6329 5187//5187 6328//6328 -f 6329//6329 6328//6328 6330//6330 -f 6330//6330 6328//6328 6325//6325 -f 6330//6330 6325//6325 6331//6331 -f 6331//6331 6325//6325 6311//6311 -f 6331//6331 6311//6311 5571//5571 -f 5571//5571 6311//6311 5566//5566 -f 5181//5181 5182//5182 6288//6288 -f 6288//6288 5182//5182 6329//6329 -f 6288//6288 6329//6329 6332//6332 -f 6332//6332 6329//6329 6330//6330 -f 6332//6332 6330//6330 6333//6333 -f 6333//6333 6330//6330 6331//6331 -f 6333//6333 6331//6331 5570//5570 -f 5570//5570 6331//6331 5571//5571 -f 5178//5178 5179//5179 6334//6334 -f 6334//6334 5179//5179 6288//6288 -f 6334//6334 6288//6288 6335//6335 -f 6335//6335 6288//6288 6332//6332 -f 6335//6335 6332//6332 6289//6289 -f 6289//6289 6332//6332 6333//6333 -f 6289//6289 6333//6333 5546//5546 -f 5546//5546 6333//6333 5570//5570 -f 5573//5573 5572//5572 6287//6287 -f 6287//6287 5572//5572 5576//5576 -f 6287//6287 5576//5576 6286//6286 -f 6286//6286 5576//5576 2813//2813 -f 5575//5575 5573//5573 6336//6336 -f 6336//6336 5573//5573 6287//6287 -f 6336//6336 6287//6287 6337//6337 -f 6337//6337 6287//6287 6285//6285 -f 6337//6337 6285//6285 6284//6284 -f 6284//6284 6285//6285 2813//2813 -f 5177//5177 5178//5178 6284//6284 -f 6284//6284 5178//5178 6334//6334 -f 6284//6284 6334//6334 6337//6337 -f 6337//6337 6334//6334 6335//6335 -f 6337//6337 6335//6335 6336//6336 -f 6336//6336 6335//6335 6289//6289 -f 6336//6336 6289//6289 5575//5575 -f 5575//5575 6289//6289 5545//5545 -f 2695//2695 2693//2693 6338//6338 -f 2691//2691 2698//2698 6339//6339 -f 1458//1458 1457//1457 2699//2699 -f 2699//2699 1457//1457 6340//6340 -f 2698//2698 2697//2697 6339//6339 -f 6339//6339 2697//2697 2696//2696 -f 6339//6339 2696//2696 6340//6340 -f 6340//6340 2696//2696 2701//2701 -f 6340//6340 2701//2701 2699//2699 -f 6338//6338 2693//2693 6339//6339 -f 6339//6339 2693//2693 2692//2692 -f 6339//6339 2692//2692 2691//2691 -f 2695//2695 6338//6338 2694//2694 -f 2694//2694 6338//6338 1477//1477 -f 2694//2694 1477//1477 1476//1476 -f 430//430 4338//4338 6341//6341 -f 430//430 6342//6342 6343//6343 -f 6343//6343 6342//6342 6344//6344 -f 4340//4340 4343//4343 6345//6345 -f 4468//4468 4467//4467 6346//6346 -f 4457//4457 6347//6347 6348//6348 -f 6340//6340 1457//1457 4435//4435 -f 6339//6339 6340//6340 6349//6349 -f 1477//1477 6350//6350 4363//4363 -f 4363//4363 6350//6350 6351//6351 -f 4363//4363 6351//6351 4362//4362 -f 4362//4362 6351//6351 6352//6352 -f 6340//6340 4435//4435 6349//6349 -f 6349//6349 4435//4435 4439//4439 -f 6349//6349 4439//4439 6353//6353 -f 6353//6353 4439//4439 4438//4438 -f 6353//6353 4438//4438 6354//6354 -f 6354//6354 4438//4438 4437//4437 -f 6354//6354 4437//4437 6355//6355 -f 6356//6356 4361//4361 6357//6357 -f 6357//6357 4361//4361 4301//4301 -f 6357//6357 4301//4301 6352//6352 -f 6352//6352 4301//4301 4300//4300 -f 6352//6352 4300//4300 4362//4362 -f 4437//4437 4440//4440 6355//6355 -f 6355//6355 4440//4440 4442//4442 -f 6355//6355 4442//4442 6358//6358 -f 6358//6358 4442//4442 4444//4444 -f 6358//6358 4444//4444 6359//6359 -f 6360//6360 4353//4353 6361//6361 -f 6361//6361 4353//4353 4358//4358 -f 6361//6361 4358//4358 6356//6356 -f 6356//6356 4358//4358 4360//4360 -f 6356//6356 4360//4360 4361//4361 -f 4444//4444 4445//4445 6359//6359 -f 6359//6359 4445//4445 4447//4447 -f 6359//6359 4447//4447 6362//6362 -f 6362//6362 4447//4447 4448//4448 -f 6362//6362 4448//4448 6363//6363 -f 4357//4357 4356//4356 6360//6360 -f 6360//6360 4356//4356 4354//4354 -f 6360//6360 4354//4354 4353//4353 -f 4357//4357 6360//6360 4413//4413 -f 4413//4413 6360//6360 6364//6364 -f 4413//4413 6364//6364 6365//6365 -f 4448//4448 4450//4450 6363//6363 -f 6363//6363 4450//4450 4452//4452 -f 6363//6363 4452//4452 6366//6366 -f 6366//6366 4452//4452 4453//4453 -f 6366//6366 4453//4453 6348//6348 -f 6348//6348 4453//4453 4455//4455 -f 6348//6348 4455//4455 4457//4457 -f 6367//6367 4352//4352 6368//6368 -f 6368//6368 4352//4352 4304//4304 -f 6368//6368 4304//4304 6365//6365 -f 6365//6365 4304//4304 4303//4303 -f 6365//6365 4303//4303 4413//4413 -f 4465//4465 6369//6369 4460//4460 -f 4460//4460 6369//6369 6347//6347 -f 4460//4460 6347//6347 4458//4458 -f 4458//4458 6347//6347 4457//4457 -f 6338//6338 6339//6339 6370//6370 -f 6370//6370 6339//6339 6349//6349 -f 6370//6370 6349//6349 6371//6371 -f 6371//6371 6349//6349 6353//6353 -f 6371//6371 6353//6353 6372//6372 -f 6372//6372 6353//6353 6354//6354 -f 6372//6372 6354//6354 6373//6373 -f 6373//6373 6354//6354 6355//6355 -f 6373//6373 6355//6355 6374//6374 -f 6374//6374 6355//6355 6358//6358 -f 6374//6374 6358//6358 6375//6375 -f 6375//6375 6358//6358 6359//6359 -f 6375//6375 6359//6359 6376//6376 -f 6376//6376 6359//6359 6362//6362 -f 6376//6376 6362//6362 6377//6377 -f 6377//6377 6362//6362 6363//6363 -f 6377//6377 6363//6363 6378//6378 -f 6378//6378 6363//6363 6366//6366 -f 6378//6378 6366//6366 6379//6379 -f 6379//6379 6366//6366 6348//6348 -f 6379//6379 6348//6348 6380//6380 -f 6380//6380 6348//6348 6347//6347 -f 6380//6380 6347//6347 6381//6381 -f 6381//6381 6347//6347 6369//6369 -f 6381//6381 6369//6369 6382//6382 -f 1477//1477 6338//6338 6350//6350 -f 6350//6350 6338//6338 6370//6370 -f 6350//6350 6370//6370 6351//6351 -f 6351//6351 6370//6370 6371//6371 -f 6351//6351 6371//6371 6352//6352 -f 6352//6352 6371//6371 6372//6372 -f 6352//6352 6372//6372 6357//6357 -f 6357//6357 6372//6372 6373//6373 -f 6357//6357 6373//6373 6356//6356 -f 6356//6356 6373//6373 6374//6374 -f 6356//6356 6374//6374 6361//6361 -f 6361//6361 6374//6374 6375//6375 -f 6361//6361 6375//6375 6360//6360 -f 6360//6360 6375//6375 6376//6376 -f 6360//6360 6376//6376 6364//6364 -f 6364//6364 6376//6376 6377//6377 -f 6364//6364 6377//6377 6365//6365 -f 6365//6365 6377//6377 6378//6378 -f 6365//6365 6378//6378 6368//6368 -f 6368//6368 6378//6378 6379//6379 -f 6368//6368 6379//6379 6367//6367 -f 6367//6367 6379//6379 6380//6380 -f 6367//6367 6380//6380 6383//6383 -f 6383//6383 6380//6380 6381//6381 -f 6383//6383 6381//6381 6384//6384 -f 6384//6384 6381//6381 6382//6382 -f 6384//6384 6382//6382 6385//6385 -f 4348//4348 4347//4347 6385//6385 -f 6385//6385 4347//4347 4345//4345 -f 6385//6385 4345//4345 6384//6384 -f 6384//6384 4345//4345 4344//4344 -f 6384//6384 4344//4344 6383//6383 -f 6383//6383 4344//4344 4349//4349 -f 6383//6383 4349//4349 6367//6367 -f 6367//6367 4349//4349 4351//4351 -f 6367//6367 4351//4351 4352//4352 -f 4342//4342 4348//4348 6386//6386 -f 6386//6386 4348//4348 6385//6385 -f 6386//6386 6385//6385 6387//6387 -f 6387//6387 6385//6385 6382//6382 -f 6387//6387 6382//6382 6388//6388 -f 6388//6388 6382//6382 6369//6369 -f 6388//6388 6369//6369 4464//4464 -f 4464//4464 6369//6369 4465//4465 -f 4343//4343 4342//4342 6345//6345 -f 6345//6345 4342//4342 6386//6386 -f 6345//6345 6386//6386 6389//6389 -f 6389//6389 6386//6386 6387//6387 -f 6389//6389 6387//6387 6390//6390 -f 6390//6390 6387//6387 6388//6388 -f 6390//6390 6388//6388 4463//4463 -f 4463//4463 6388//6388 4464//4464 -f 4339//4339 4340//4340 6391//6391 -f 6391//6391 4340//4340 6345//6345 -f 6391//6391 6345//6345 6392//6392 -f 6392//6392 6345//6345 6389//6389 -f 6392//6392 6389//6389 6346//6346 -f 6346//6346 6389//6389 6390//6390 -f 6346//6346 6390//6390 4468//4468 -f 4468//4468 6390//6390 4463//4463 -f 4433//4433 4432//4432 6344//6344 -f 6344//6344 4432//4432 4469//4469 -f 6344//6344 4469//4469 6343//6343 -f 6343//6343 4469//4469 430//430 -f 4466//4466 4433//4433 6393//6393 -f 6393//6393 4433//4433 6344//6344 -f 6393//6393 6344//6344 6394//6394 -f 6394//6394 6344//6344 6342//6342 -f 6394//6394 6342//6342 6341//6341 -f 6341//6341 6342//6342 430//430 -f 4338//4338 4339//4339 6341//6341 -f 6341//6341 4339//4339 6391//6391 -f 6341//6341 6391//6391 6394//6394 -f 6394//6394 6391//6391 6392//6392 -f 6394//6394 6392//6392 6393//6393 -f 6393//6393 6392//6392 6346//6346 -f 6393//6393 6346//6346 4466//4466 -f 4466//4466 6346//6346 4467//4467 -f 2687//2687 2686//2686 6395//6395 -f 1417//1417 1419//1419 2669//2669 -f 2669//2669 1419//1419 6396//6396 -f 2669//2669 6396//6396 2670//2670 -f 2686//2686 2673//2673 6395//6395 -f 6395//6395 2673//2673 2672//2672 -f 6395//6395 2672//2672 6396//6396 -f 6396//6396 2672//2672 2671//2671 -f 6396//6396 2671//2671 2670//2670 -f 2687//2687 6395//6395 2688//2688 -f 2688//2688 6395//6395 6397//6397 -f 2688//2688 6397//6397 2684//2684 -f 2684//2684 6397//6397 2685//2685 -f 2685//2685 6397//6397 1460//1460 -f 2685//2685 1460//1460 1459//1459 -f 439//439 5007//5007 6398//6398 -f 439//439 6399//6399 6400//6400 -f 6400//6400 6399//6399 6401//6401 -f 5005//5005 5004//5004 6402//6402 -f 4941//4941 4940//4940 6403//6403 -f 4939//4939 4938//4938 6404//6404 -f 5016//5016 5024//5024 6405//6405 -f 4931//4931 4932//4932 6406//6406 -f 5022//5022 5021//5021 6407//6407 -f 4926//4926 4925//4925 6408//6408 -f 5019//5019 5030//5030 6409//6409 -f 4923//4923 4922//4922 6410//6410 -f 5028//5028 5027//5027 6411//6411 -f 4920//4920 4918//4918 6412//6412 -f 6413//6413 6396//6396 4915//4915 -f 4915//4915 6396//6396 1419//1419 -f 5025//5025 1460//1460 6414//6414 -f 6414//6414 1460//1460 6397//6397 -f 5026//5026 5025//5025 6415//6415 -f 6415//6415 5025//5025 6414//6414 -f 6415//6415 6414//6414 6416//6416 -f 6416//6416 6414//6414 6397//6397 -f 6416//6416 6397//6397 6395//6395 -f 5027//5027 5026//5026 6411//6411 -f 6411//6411 5026//5026 6415//6415 -f 6411//6411 6415//6415 6417//6417 -f 6417//6417 6415//6415 6416//6416 -f 6417//6417 6416//6416 6413//6413 -f 6413//6413 6416//6416 6395//6395 -f 6413//6413 6395//6395 6396//6396 -f 5029//5029 5028//5028 6418//6418 -f 6418//6418 5028//5028 6411//6411 -f 6418//6418 6411//6411 6419//6419 -f 6419//6419 6411//6411 6417//6417 -f 6419//6419 6417//6417 6420//6420 -f 6420//6420 6417//6417 6413//6413 -f 6420//6420 6413//6413 4916//4916 -f 4916//4916 6413//6413 4915//4915 -f 5030//5030 5029//5029 6409//6409 -f 6409//6409 5029//5029 6418//6418 -f 6409//6409 6418//6418 6421//6421 -f 6421//6421 6418//6418 6419//6419 -f 6421//6421 6419//6419 6422//6422 -f 6422//6422 6419//6419 6420//6420 -f 6422//6422 6420//6420 4921//4921 -f 4921//4921 6420//6420 4916//4916 -f 5020//5020 5019//5019 6423//6423 -f 6423//6423 5019//5019 6409//6409 -f 6423//6423 6409//6409 6424//6424 -f 6424//6424 6409//6409 6421//6421 -f 6424//6424 6421//6421 6412//6412 -f 6412//6412 6421//6421 6422//6422 -f 6412//6412 6422//6422 4920//4920 -f 4920//4920 6422//6422 4921//4921 -f 5021//5021 5020//5020 6407//6407 -f 6407//6407 5020//5020 6423//6423 -f 6407//6407 6423//6423 6425//6425 -f 6425//6425 6423//6423 6424//6424 -f 6425//6425 6424//6424 6426//6426 -f 6426//6426 6424//6424 6412//6412 -f 6426//6426 6412//6412 4917//4917 -f 4917//4917 6412//6412 4918//4918 -f 5023//5023 5022//5022 6427//6427 -f 6427//6427 5022//5022 6407//6407 -f 6427//6427 6407//6407 6428//6428 -f 6428//6428 6407//6407 6425//6425 -f 6428//6428 6425//6425 6410//6410 -f 6410//6410 6425//6425 6426//6426 -f 6410//6410 6426//6426 4923//4923 -f 4923//4923 6426//6426 4917//4917 -f 5024//5024 5023//5023 6405//6405 -f 6405//6405 5023//5023 6427//6427 -f 6405//6405 6427//6427 6429//6429 -f 6429//6429 6427//6427 6428//6428 -f 6429//6429 6428//6428 6430//6430 -f 6430//6430 6428//6428 6410//6410 -f 6430//6430 6410//6410 4928//4928 -f 4928//4928 6410//6410 4922//4922 -f 5017//5017 5016//5016 6431//6431 -f 6431//6431 5016//5016 6405//6405 -f 6431//6431 6405//6405 6432//6432 -f 6432//6432 6405//6405 6429//6429 -f 6432//6432 6429//6429 6408//6408 -f 6408//6408 6429//6429 6430//6430 -f 6408//6408 6430//6430 4926//4926 -f 4926//4926 6430//6430 4928//4928 -f 4925//4925 4930//4930 6408//6408 -f 6408//6408 4930//4930 6433//6433 -f 6408//6408 6433//6433 6432//6432 -f 6432//6432 6433//6433 6434//6434 -f 6432//6432 6434//6434 6431//6431 -f 6431//6431 6434//6434 6435//6435 -f 6431//6431 6435//6435 5017//5017 -f 5015//5015 5014//5014 6435//6435 -f 5014//5014 5003//5003 6435//6435 -f 6435//6435 5003//5003 5018//5018 -f 6435//6435 5018//5018 5017//5017 -f 4932//4932 4934//4934 6406//6406 -f 6406//6406 4934//4934 6436//6436 -f 6406//6406 6436//6436 6437//6437 -f 6437//6437 6436//6436 6438//6438 -f 6437//6437 6438//6438 6439//6439 -f 6439//6439 6438//6438 6440//6440 -f 4934//4934 4939//4939 6436//6436 -f 6436//6436 4939//4939 6404//6404 -f 6436//6436 6404//6404 6438//6438 -f 6438//6438 6404//6404 6441//6441 -f 6438//6438 6441//6441 6440//6440 -f 6440//6440 6441//6441 6442//6442 -f 4930//4930 4931//4931 6433//6433 -f 6433//6433 4931//4931 6406//6406 -f 6433//6433 6406//6406 6434//6434 -f 6434//6434 6406//6406 6437//6437 -f 6434//6434 6437//6437 6435//6435 -f 6435//6435 6437//6437 6439//6439 -f 6435//6435 6439//6439 5015//5015 -f 5015//5015 6439//6439 6440//6440 -f 5015//5015 6440//6440 5009//5009 -f 5009//5009 6440//6440 6442//6442 -f 5009//5009 6442//6442 5010//5010 -f 5010//5010 6442//6442 5012//5012 -f 5013//5013 5012//5012 6443//6443 -f 6443//6443 5012//5012 6442//6442 -f 6443//6443 6442//6442 6444//6444 -f 6444//6444 6442//6442 6441//6441 -f 6444//6444 6441//6441 6445//6445 -f 6445//6445 6441//6441 6404//6404 -f 6445//6445 6404//6404 4936//4936 -f 4936//4936 6404//6404 4938//4938 -f 5004//5004 5013//5013 6402//6402 -f 6402//6402 5013//5013 6443//6443 -f 6402//6402 6443//6443 6446//6446 -f 6446//6446 6443//6443 6444//6444 -f 6446//6446 6444//6444 6447//6447 -f 6447//6447 6444//6444 6445//6445 -f 6447//6447 6445//6445 4935//4935 -f 4935//4935 6445//6445 4936//4936 -f 5008//5008 5005//5005 6448//6448 -f 6448//6448 5005//5005 6402//6402 -f 6448//6448 6402//6402 6449//6449 -f 6449//6449 6402//6402 6446//6446 -f 6449//6449 6446//6446 6403//6403 -f 6403//6403 6446//6446 6447//6447 -f 6403//6403 6447//6447 4941//4941 -f 4941//4941 6447//6447 4935//4935 -f 4943//4943 4942//4942 6401//6401 -f 6401//6401 4942//4942 4945//4945 -f 6401//6401 4945//4945 6400//6400 -f 6400//6400 4945//4945 439//439 -f 4944//4944 4943//4943 6450//6450 -f 6450//6450 4943//4943 6401//6401 -f 6450//6450 6401//6401 6451//6451 -f 6451//6451 6401//6401 6399//6399 -f 6451//6451 6399//6399 6398//6398 -f 6398//6398 6399//6399 439//439 -f 5007//5007 5008//5008 6398//6398 -f 6398//6398 5008//5008 6448//6448 -f 6398//6398 6448//6448 6451//6451 -f 6451//6451 6448//6448 6449//6449 -f 6451//6451 6449//6449 6450//6450 -f 6450//6450 6449//6449 6403//6403 -f 6450//6450 6403//6403 4944//4944 -f 4944//4944 6403//6403 4940//4940 -f 2598//2598 2607//2607 6452//6452 -f 2605//2605 2604//2604 6453//6453 -f 1509//1509 1507//1507 2609//2609 -f 2609//2609 1507//1507 6454//6454 -f 2604//2604 2603//2603 6453//6453 -f 6453//6453 2603//2603 2602//2602 -f 6453//6453 2602//2602 6454//6454 -f 6454//6454 2602//2602 2611//2611 -f 6454//6454 2611//2611 2609//2609 -f 6452//6452 2607//2607 6453//6453 -f 6453//6453 2607//2607 2606//2606 -f 6453//6453 2606//2606 2605//2605 -f 2598//2598 6452//6452 2608//2608 -f 2608//2608 6452//6452 1415//1415 -f 2608//2608 1415//1415 1414//1414 -f 337//337 4891//4891 6455//6455 -f 337//337 6456//6456 6457//6457 -f 6457//6457 6456//6456 6458//6458 -f 4889//4889 4893//4893 6459//6459 -f 4475//4475 4474//4474 6460//6460 -f 6454//6454 1507//1507 4509//4509 -f 6453//6453 6454//6454 6461//6461 -f 1415//1415 6462//6462 4914//4914 -f 4914//4914 6462//6462 6463//6463 -f 4914//4914 6463//6463 4913//4913 -f 4913//4913 6463//6463 6464//6464 -f 6454//6454 4509//4509 6461//6461 -f 6461//6461 4509//4509 4510//4510 -f 6461//6461 4510//4510 6465//6465 -f 6465//6465 4510//4510 4515//4515 -f 6465//6465 4515//4515 6466//6466 -f 6466//6466 4515//4515 4514//4514 -f 6466//6466 4514//4514 6467//6467 -f 6468//6468 4912//4912 6469//6469 -f 6469//6469 4912//4912 4874//4874 -f 6469//6469 4874//4874 6464//6464 -f 6464//6464 4874//4874 4873//4873 -f 6464//6464 4873//4873 4913//4913 -f 4514//4514 4512//4512 6467//6467 -f 6467//6467 4512//4512 4511//4511 -f 6467//6467 4511//4511 6470//6470 -f 6470//6470 4511//4511 4517//4517 -f 6470//6470 4517//4517 6471//6471 -f 6472//6472 4904//4904 6473//6473 -f 6473//6473 4904//4904 4909//4909 -f 6473//6473 4909//4909 6468//6468 -f 6468//6468 4909//4909 4911//4911 -f 6468//6468 4911//4911 4912//4912 -f 4517//4517 4516//4516 6471//6471 -f 6471//6471 4516//4516 4522//4522 -f 6471//6471 4522//4522 6474//6474 -f 6474//6474 4522//4522 4520//4520 -f 6474//6474 4520//4520 6475//6475 -f 4908//4908 4907//4907 6472//6472 -f 6472//6472 4907//4907 4905//4905 -f 6472//6472 4905//4905 4904//4904 -f 4908//4908 6472//6472 4984//4984 -f 4984//4984 6472//6472 6476//6476 -f 4984//4984 6476//6476 6477//6477 -f 4520//4520 4519//4519 6475//6475 -f 6475//6475 4519//4519 4526//4526 -f 6475//6475 4526//4526 6478//6478 -f 6478//6478 4526//4526 4524//4524 -f 6478//6478 4524//4524 6479//6479 -f 6480//6480 4903//4903 6481//6481 -f 6481//6481 4903//4903 4877//4877 -f 6481//6481 4877//4877 6477//6477 -f 6477//6477 4877//4877 4876//4876 -f 6477//6477 4876//4876 4984//4984 -f 4527//4527 6482//6482 4528//4528 -f 4528//4528 6482//6482 6483//6483 -f 4528//4528 6483//6483 4530//4530 -f 4530//4530 6483//6483 6479//6479 -f 4530//4530 6479//6479 4523//4523 -f 4523//4523 6479//6479 4524//4524 -f 6452//6452 6453//6453 6484//6484 -f 6484//6484 6453//6453 6461//6461 -f 6484//6484 6461//6461 6485//6485 -f 6485//6485 6461//6461 6465//6465 -f 6485//6485 6465//6465 6486//6486 -f 6486//6486 6465//6465 6466//6466 -f 6486//6486 6466//6466 6487//6487 -f 6487//6487 6466//6466 6467//6467 -f 6487//6487 6467//6467 6488//6488 -f 6488//6488 6467//6467 6470//6470 -f 6488//6488 6470//6470 6489//6489 -f 6489//6489 6470//6470 6471//6471 -f 6489//6489 6471//6471 6490//6490 -f 6490//6490 6471//6471 6474//6474 -f 6490//6490 6474//6474 6491//6491 -f 6491//6491 6474//6474 6475//6475 -f 6491//6491 6475//6475 6492//6492 -f 6492//6492 6475//6475 6478//6478 -f 6492//6492 6478//6478 6493//6493 -f 6493//6493 6478//6478 6479//6479 -f 6493//6493 6479//6479 6494//6494 -f 6494//6494 6479//6479 6483//6483 -f 6494//6494 6483//6483 6495//6495 -f 6495//6495 6483//6483 6482//6482 -f 6495//6495 6482//6482 6496//6496 -f 1415//1415 6452//6452 6462//6462 -f 6462//6462 6452//6452 6484//6484 -f 6462//6462 6484//6484 6463//6463 -f 6463//6463 6484//6484 6485//6485 -f 6463//6463 6485//6485 6464//6464 -f 6464//6464 6485//6485 6486//6486 -f 6464//6464 6486//6486 6469//6469 -f 6469//6469 6486//6486 6487//6487 -f 6469//6469 6487//6487 6468//6468 -f 6468//6468 6487//6487 6488//6488 -f 6468//6468 6488//6488 6473//6473 -f 6473//6473 6488//6488 6489//6489 -f 6473//6473 6489//6489 6472//6472 -f 6472//6472 6489//6489 6490//6490 -f 6472//6472 6490//6490 6476//6476 -f 6476//6476 6490//6490 6491//6491 -f 6476//6476 6491//6491 6477//6477 -f 6477//6477 6491//6491 6492//6492 -f 6477//6477 6492//6492 6481//6481 -f 6481//6481 6492//6492 6493//6493 -f 6481//6481 6493//6493 6480//6480 -f 6480//6480 6493//6493 6494//6494 -f 6480//6480 6494//6494 6497//6497 -f 6497//6497 6494//6494 6495//6495 -f 6497//6497 6495//6495 6498//6498 -f 6498//6498 6495//6495 6496//6496 -f 6498//6498 6496//6496 6499//6499 -f 4899//4899 4898//4898 6499//6499 -f 6499//6499 4898//4898 4896//4896 -f 6499//6499 4896//4896 6498//6498 -f 6498//6498 4896//4896 4895//4895 -f 6498//6498 4895//4895 6497//6497 -f 6497//6497 4895//4895 4900//4900 -f 6497//6497 4900//4900 6480//6480 -f 6480//6480 4900//4900 4902//4902 -f 6480//6480 4902//4902 4903//4903 -f 4894//4894 4899//4899 6500//6500 -f 6500//6500 4899//4899 6499//6499 -f 6500//6500 6499//6499 6501//6501 -f 6501//6501 6499//6499 6496//6496 -f 6501//6501 6496//6496 6502//6502 -f 6502//6502 6496//6496 6482//6482 -f 6502//6502 6482//6482 4532//4532 -f 4532//4532 6482//6482 4527//4527 -f 4893//4893 4894//4894 6459//6459 -f 6459//6459 4894//4894 6500//6500 -f 6459//6459 6500//6500 6503//6503 -f 6503//6503 6500//6500 6501//6501 -f 6503//6503 6501//6501 6504//6504 -f 6504//6504 6501//6501 6502//6502 -f 6504//6504 6502//6502 4531//4531 -f 4531//4531 6502//6502 4532//4532 -f 4890//4890 4889//4889 6505//6505 -f 6505//6505 4889//4889 6459//6459 -f 6505//6505 6459//6459 6506//6506 -f 6506//6506 6459//6459 6503//6503 -f 6506//6506 6503//6503 6460//6460 -f 6460//6460 6503//6503 6504//6504 -f 6460//6460 6504//6504 4475//4475 -f 4475//4475 6504//6504 4531//4531 -f 4535//4535 4547//4547 6458//6458 -f 6458//6458 4547//4547 4536//4536 -f 6458//6458 4536//4536 6457//6457 -f 6457//6457 4536//4536 337//337 -f 4534//4534 4535//4535 6507//6507 -f 6507//6507 4535//4535 6458//6458 -f 6507//6507 6458//6458 6508//6508 -f 6508//6508 6458//6458 6456//6456 -f 6508//6508 6456//6456 6455//6455 -f 6455//6455 6456//6456 337//337 -f 4891//4891 4890//4890 6455//6455 -f 6455//6455 4890//4890 6505//6505 -f 6455//6455 6505//6505 6508//6508 -f 6508//6508 6505//6505 6506//6506 -f 6508//6508 6506//6506 6507//6507 -f 6507//6507 6506//6506 6460//6460 -f 6507//6507 6460//6460 4534//4534 -f 4534//4534 6460//6460 4474//4474 -f 2580//2580 2579//2579 6509//6509 -f 1479//1479 1481//1481 2597//2597 -f 2597//2597 1481//1481 6510//6510 -f 2597//2597 6510//6510 2593//2593 -f 2579//2579 2596//2596 6509//6509 -f 6509//6509 2596//2596 2595//2595 -f 6509//6509 2595//2595 6510//6510 -f 6510//6510 2595//2595 2594//2594 -f 6510//6510 2594//2594 2593//2593 -f 2580//2580 6509//6509 2591//2591 -f 2591//2591 6509//6509 6511//6511 -f 2591//2591 6511//6511 2590//2590 -f 2590//2590 6511//6511 2592//2592 -f 2592//2592 6511//6511 1501//1501 -f 2592//2592 1501//1501 1503//1503 -f 388//388 4483//4483 6512//6512 -f 388//388 6513//6513 6514//6514 -f 6514//6514 6513//6513 6515//6515 -f 4485//4485 4487//4487 6516//6516 -f 4307//4307 4306//4306 6517//6517 -f 6510//6510 1481//1481 4309//4309 -f 6509//6509 6510//6510 6518//6518 -f 1501//1501 6519//6519 4508//4508 -f 4508//4508 6519//6519 6520//6520 -f 4508//4508 6520//6520 4507//4507 -f 4507//4507 6520//6520 6521//6521 -f 6510//6510 4309//4309 6518//6518 -f 6518//6518 4309//4309 4310//4310 -f 6518//6518 4310//4310 6522//6522 -f 6522//6522 4310//4310 4315//4315 -f 6522//6522 4315//4315 6523//6523 -f 6523//6523 4315//4315 4314//4314 -f 6523//6523 4314//4314 6524//6524 -f 6525//6525 4506//4506 6526//6526 -f 6526//6526 4506//4506 4478//4478 -f 6526//6526 4478//4478 6521//6521 -f 6521//6521 4478//4478 4477//4477 -f 6521//6521 4477//4477 4507//4507 -f 4314//4314 4312//4312 6524//6524 -f 6524//6524 4312//4312 4311//4311 -f 6524//6524 4311//4311 6527//6527 -f 6527//6527 4311//4311 4317//4317 -f 6527//6527 4317//4317 6528//6528 -f 6529//6529 4498//4498 6530//6530 -f 6530//6530 4498//4498 4503//4503 -f 6530//6530 4503//4503 6525//6525 -f 6525//6525 4503//4503 4505//4505 -f 6525//6525 4505//4505 4506//4506 -f 4317//4317 4316//4316 6528//6528 -f 6528//6528 4316//4316 4322//4322 -f 6528//6528 4322//4322 6531//6531 -f 6531//6531 4322//4322 4320//4320 -f 6531//6531 4320//4320 6532//6532 -f 4502//4502 4501//4501 6529//6529 -f 6529//6529 4501//4501 4499//4499 -f 6529//6529 4499//4499 4498//4498 -f 4502//4502 6529//6529 4587//4587 -f 4587//4587 6529//6529 6533//6533 -f 4587//4587 6533//6533 6534//6534 -f 4320//4320 4319//4319 6532//6532 -f 6532//6532 4319//4319 4326//4326 -f 6532//6532 4326//4326 6535//6535 -f 6535//6535 4326//4326 4324//4324 -f 6535//6535 4324//4324 6536//6536 -f 6537//6537 4497//4497 6538//6538 -f 6538//6538 4497//4497 4481//4481 -f 6538//6538 4481//4481 6534//6534 -f 6534//6534 4481//4481 4480//4480 -f 6534//6534 4480//4480 4587//4587 -f 4327//4327 6539//6539 4328//4328 -f 4328//4328 6539//6539 6540//6540 -f 4328//4328 6540//6540 4330//4330 -f 4330//4330 6540//6540 6536//6536 -f 4330//4330 6536//6536 4323//4323 -f 4323//4323 6536//6536 4324//4324 -f 6511//6511 6509//6509 6541//6541 -f 6541//6541 6509//6509 6518//6518 -f 6541//6541 6518//6518 6542//6542 -f 6542//6542 6518//6518 6522//6522 -f 6542//6542 6522//6522 6543//6543 -f 6543//6543 6522//6522 6523//6523 -f 6543//6543 6523//6523 6544//6544 -f 6544//6544 6523//6523 6524//6524 -f 6544//6544 6524//6524 6545//6545 -f 6545//6545 6524//6524 6527//6527 -f 6545//6545 6527//6527 6546//6546 -f 6546//6546 6527//6527 6528//6528 -f 6546//6546 6528//6528 6547//6547 -f 6547//6547 6528//6528 6531//6531 -f 6547//6547 6531//6531 6548//6548 -f 6548//6548 6531//6531 6532//6532 -f 6548//6548 6532//6532 6549//6549 -f 6549//6549 6532//6532 6535//6535 -f 6549//6549 6535//6535 6550//6550 -f 6550//6550 6535//6535 6536//6536 -f 6550//6550 6536//6536 6551//6551 -f 6551//6551 6536//6536 6540//6540 -f 6551//6551 6540//6540 6552//6552 -f 6552//6552 6540//6540 6539//6539 -f 6552//6552 6539//6539 6553//6553 -f 1501//1501 6511//6511 6519//6519 -f 6519//6519 6511//6511 6541//6541 -f 6519//6519 6541//6541 6520//6520 -f 6520//6520 6541//6541 6542//6542 -f 6520//6520 6542//6542 6521//6521 -f 6521//6521 6542//6542 6543//6543 -f 6521//6521 6543//6543 6526//6526 -f 6526//6526 6543//6543 6544//6544 -f 6526//6526 6544//6544 6525//6525 -f 6525//6525 6544//6544 6545//6545 -f 6525//6525 6545//6545 6530//6530 -f 6530//6530 6545//6545 6546//6546 -f 6530//6530 6546//6546 6529//6529 -f 6529//6529 6546//6546 6547//6547 -f 6529//6529 6547//6547 6533//6533 -f 6533//6533 6547//6547 6548//6548 -f 6533//6533 6548//6548 6534//6534 -f 6534//6534 6548//6548 6549//6549 -f 6534//6534 6549//6549 6538//6538 -f 6538//6538 6549//6549 6550//6550 -f 6538//6538 6550//6550 6537//6537 -f 6537//6537 6550//6550 6551//6551 -f 6537//6537 6551//6551 6554//6554 -f 6554//6554 6551//6551 6552//6552 -f 6554//6554 6552//6552 6555//6555 -f 6555//6555 6552//6552 6553//6553 -f 6555//6555 6553//6553 6556//6556 -f 4493//4493 4492//4492 6556//6556 -f 6556//6556 4492//4492 4490//4490 -f 6556//6556 4490//4490 6555//6555 -f 6555//6555 4490//4490 4489//4489 -f 6555//6555 4489//4489 6554//6554 -f 6554//6554 4489//4489 4494//4494 -f 6554//6554 4494//4494 6537//6537 -f 6537//6537 4494//4494 4496//4496 -f 6537//6537 4496//4496 4497//4497 -f 4488//4488 4493//4493 6557//6557 -f 6557//6557 4493//4493 6556//6556 -f 6557//6557 6556//6556 6558//6558 -f 6558//6558 6556//6556 6553//6553 -f 6558//6558 6553//6553 6559//6559 -f 6559//6559 6553//6553 6539//6539 -f 6559//6559 6539//6539 4332//4332 -f 4332//4332 6539//6539 4327//4327 -f 4487//4487 4488//4488 6516//6516 -f 6516//6516 4488//4488 6557//6557 -f 6516//6516 6557//6557 6560//6560 -f 6560//6560 6557//6557 6558//6558 -f 6560//6560 6558//6558 6561//6561 -f 6561//6561 6558//6558 6559//6559 -f 6561//6561 6559//6559 4331//4331 -f 4331//4331 6559//6559 4332//4332 -f 4484//4484 4485//4485 6562//6562 -f 6562//6562 4485//4485 6516//6516 -f 6562//6562 6516//6516 6563//6563 -f 6563//6563 6516//6516 6560//6560 -f 6563//6563 6560//6560 6517//6517 -f 6517//6517 6560//6560 6561//6561 -f 6517//6517 6561//6561 4307//4307 -f 4307//4307 6561//6561 4331//4331 -f 4334//4334 4333//4333 6515//6515 -f 6515//6515 4333//4333 4337//4337 -f 6515//6515 4337//4337 6514//6514 -f 6514//6514 4337//4337 388//388 -f 4336//4336 4334//4334 6564//6564 -f 6564//6564 4334//4334 6515//6515 -f 6564//6564 6515//6515 6565//6565 -f 6565//6565 6515//6515 6513//6513 -f 6565//6565 6513//6513 6512//6512 -f 6512//6512 6513//6513 388//388 -f 4483//4483 4484//4484 6512//6512 -f 6512//6512 4484//4484 6562//6562 -f 6512//6512 6562//6562 6565//6565 -f 6565//6565 6562//6562 6563//6563 -f 6565//6565 6563//6563 6564//6564 -f 6564//6564 6563//6563 6517//6517 -f 6564//6564 6517//6517 4336//4336 -f 4336//4336 6517//6517 4306//4306 -f 1276//1276 1278//1278 2711//2711 -f 2711//2711 1278//1278 6566//6566 -f 2711//2711 6566//6566 2712//2712 -f 2724//2724 2726//2726 6567//6567 -f 6567//6567 2726//2726 2728//2728 -f 6567//6567 2728//2728 6566//6566 -f 6566//6566 2728//2728 2730//2730 -f 6566//6566 2730//2730 2712//2712 -f 2718//2718 2717//2717 6568//6568 -f 6568//6568 2717//2717 2716//2716 -f 6568//6568 2716//2716 6567//6567 -f 6567//6567 2716//2716 2722//2722 -f 6567//6567 2722//2722 2724//2724 -f 2718//2718 6568//6568 2719//2719 -f 2719//2719 6568//6568 1228//1228 -f 2719//2719 1228//1228 1230//1230 -f 571//571 6129//6129 6569//6569 -f 571//571 6570//6570 6571//6571 -f 6571//6571 6570//6570 6572//6572 -f 6131//6131 6133//6133 6573//6573 -f 5961//5961 5960//5960 6574//6574 -f 6566//6566 1278//1278 5995//5995 -f 6567//6567 6566//6566 6575//6575 -f 1228//1228 6576//6576 6154//6154 -f 6154//6154 6576//6576 6577//6577 -f 6154//6154 6577//6577 6153//6153 -f 6153//6153 6577//6577 6578//6578 -f 6566//6566 5995//5995 6575//6575 -f 6575//6575 5995//5995 5996//5996 -f 6575//6575 5996//5996 6579//6579 -f 6579//6579 5996//5996 6001//6001 -f 6579//6579 6001//6001 6580//6580 -f 6580//6580 6001//6001 6000//6000 -f 6580//6580 6000//6000 6581//6581 -f 6582//6582 6152//6152 6583//6583 -f 6583//6583 6152//6152 6093//6093 -f 6583//6583 6093//6093 6578//6578 -f 6578//6578 6093//6093 6092//6092 -f 6578//6578 6092//6092 6153//6153 -f 6000//6000 5998//5998 6581//6581 -f 6581//6581 5998//5998 5997//5997 -f 6581//6581 5997//5997 6584//6584 -f 6584//6584 5997//5997 6003//6003 -f 6584//6584 6003//6003 6585//6585 -f 6586//6586 6144//6144 6587//6587 -f 6587//6587 6144//6144 6149//6149 -f 6587//6587 6149//6149 6582//6582 -f 6582//6582 6149//6149 6151//6151 -f 6582//6582 6151//6151 6152//6152 -f 6003//6003 6002//6002 6585//6585 -f 6585//6585 6002//6002 6008//6008 -f 6585//6585 6008//6008 6588//6588 -f 6588//6588 6008//6008 6006//6006 -f 6588//6588 6006//6006 6589//6589 -f 6148//6148 6147//6147 6586//6586 -f 6586//6586 6147//6147 6145//6145 -f 6586//6586 6145//6145 6144//6144 -f 6148//6148 6586//6586 6205//6205 -f 6205//6205 6586//6586 6590//6590 -f 6205//6205 6590//6590 6591//6591 -f 6006//6006 6005//6005 6589//6589 -f 6589//6589 6005//6005 6012//6012 -f 6589//6589 6012//6012 6592//6592 -f 6592//6592 6012//6012 6010//6010 -f 6592//6592 6010//6010 6593//6593 -f 6594//6594 6143//6143 6595//6595 -f 6595//6595 6143//6143 6096//6096 -f 6595//6595 6096//6096 6591//6591 -f 6591//6591 6096//6096 6095//6095 -f 6591//6591 6095//6095 6205//6205 -f 6013//6013 6596//6596 6014//6014 -f 6014//6014 6596//6596 6597//6597 -f 6014//6014 6597//6597 6016//6016 -f 6016//6016 6597//6597 6593//6593 -f 6016//6016 6593//6593 6009//6009 -f 6009//6009 6593//6593 6010//6010 -f 6568//6568 6567//6567 6598//6598 -f 6598//6598 6567//6567 6575//6575 -f 6598//6598 6575//6575 6599//6599 -f 6599//6599 6575//6575 6579//6579 -f 6599//6599 6579//6579 6600//6600 -f 6600//6600 6579//6579 6580//6580 -f 6600//6600 6580//6580 6601//6601 -f 6601//6601 6580//6580 6581//6581 -f 6601//6601 6581//6581 6602//6602 -f 6602//6602 6581//6581 6584//6584 -f 6602//6602 6584//6584 6603//6603 -f 6603//6603 6584//6584 6585//6585 -f 6603//6603 6585//6585 6604//6604 -f 6604//6604 6585//6585 6588//6588 -f 6604//6604 6588//6588 6605//6605 -f 6605//6605 6588//6588 6589//6589 -f 6605//6605 6589//6589 6606//6606 -f 6606//6606 6589//6589 6592//6592 -f 6606//6606 6592//6592 6607//6607 -f 6607//6607 6592//6592 6593//6593 -f 6607//6607 6593//6593 6608//6608 -f 6608//6608 6593//6593 6597//6597 -f 6608//6608 6597//6597 6609//6609 -f 6609//6609 6597//6597 6596//6596 -f 6609//6609 6596//6596 6610//6610 -f 1228//1228 6568//6568 6576//6576 -f 6576//6576 6568//6568 6598//6598 -f 6576//6576 6598//6598 6577//6577 -f 6577//6577 6598//6598 6599//6599 -f 6577//6577 6599//6599 6578//6578 -f 6578//6578 6599//6599 6600//6600 -f 6578//6578 6600//6600 6583//6583 -f 6583//6583 6600//6600 6601//6601 -f 6583//6583 6601//6601 6582//6582 -f 6582//6582 6601//6601 6602//6602 -f 6582//6582 6602//6602 6587//6587 -f 6587//6587 6602//6602 6603//6603 -f 6587//6587 6603//6603 6586//6586 -f 6586//6586 6603//6603 6604//6604 -f 6586//6586 6604//6604 6590//6590 -f 6590//6590 6604//6604 6605//6605 -f 6590//6590 6605//6605 6591//6591 -f 6591//6591 6605//6605 6606//6606 -f 6591//6591 6606//6606 6595//6595 -f 6595//6595 6606//6606 6607//6607 -f 6595//6595 6607//6607 6594//6594 -f 6594//6594 6607//6607 6608//6608 -f 6594//6594 6608//6608 6611//6611 -f 6611//6611 6608//6608 6609//6609 -f 6611//6611 6609//6609 6612//6612 -f 6612//6612 6609//6609 6610//6610 -f 6612//6612 6610//6610 6613//6613 -f 6139//6139 6138//6138 6613//6613 -f 6613//6613 6138//6138 6136//6136 -f 6613//6613 6136//6136 6612//6612 -f 6612//6612 6136//6136 6135//6135 -f 6612//6612 6135//6135 6611//6611 -f 6611//6611 6135//6135 6140//6140 -f 6611//6611 6140//6140 6594//6594 -f 6594//6594 6140//6140 6142//6142 -f 6594//6594 6142//6142 6143//6143 -f 6134//6134 6139//6139 6614//6614 -f 6614//6614 6139//6139 6613//6613 -f 6614//6614 6613//6613 6615//6615 -f 6615//6615 6613//6613 6610//6610 -f 6615//6615 6610//6610 6616//6616 -f 6616//6616 6610//6610 6596//6596 -f 6616//6616 6596//6596 6018//6018 -f 6018//6018 6596//6596 6013//6013 -f 6133//6133 6134//6134 6573//6573 -f 6573//6573 6134//6134 6614//6614 -f 6573//6573 6614//6614 6617//6617 -f 6617//6617 6614//6614 6615//6615 -f 6617//6617 6615//6615 6618//6618 -f 6618//6618 6615//6615 6616//6616 -f 6618//6618 6616//6616 6017//6017 -f 6017//6017 6616//6616 6018//6018 -f 6130//6130 6131//6131 6619//6619 -f 6619//6619 6131//6131 6573//6573 -f 6619//6619 6573//6573 6620//6620 -f 6620//6620 6573//6573 6617//6617 -f 6620//6620 6617//6617 6574//6574 -f 6574//6574 6617//6617 6618//6618 -f 6574//6574 6618//6618 5961//5961 -f 5961//5961 6618//6618 6017//6017 -f 6023//6023 6022//6022 6572//6572 -f 6572//6572 6022//6022 6021//6021 -f 6572//6572 6021//6021 6571//6571 -f 6571//6571 6021//6021 571//571 -f 6019//6019 6023//6023 6621//6621 -f 6621//6621 6023//6023 6572//6572 -f 6621//6621 6572//6572 6622//6622 -f 6622//6622 6572//6572 6570//6570 -f 6622//6622 6570//6570 6569//6569 -f 6569//6569 6570//6570 571//571 -f 6129//6129 6130//6130 6569//6569 -f 6569//6569 6130//6130 6619//6619 -f 6569//6569 6619//6619 6622//6622 -f 6622//6622 6619//6619 6620//6620 -f 6622//6622 6620//6620 6621//6621 -f 6621//6621 6620//6620 6574//6574 -f 6621//6621 6574//6574 6019//6019 -f 6019//6019 6574//6574 5960//5960 -f 2656//2656 2655//2655 6623//6623 -f 2651//2651 2649//2649 6624//6624 -f 1259//1259 1257//1257 2662//2662 -f 2662//2662 1257//1257 6625//6625 -f 2662//2662 6625//6625 2658//2658 -f 2649//2649 2647//2647 6624//6624 -f 6624//6624 2647//2647 2645//2645 -f 6624//6624 2645//2645 6625//6625 -f 6625//6625 2645//2645 2659//2659 -f 6625//6625 2659//2659 2658//2658 -f 6623//6623 2655//2655 6624//6624 -f 6624//6624 2655//2655 2653//2653 -f 6624//6624 2653//2653 2651//2651 -f 2656//2656 6623//6623 2643//2643 -f 2643//2643 6623//6623 1274//1274 -f 2643//2643 1274//1274 1273//1273 -f 621//621 5971//5971 6626//6626 -f 621//621 6627//6627 6628//6628 -f 6628//6628 6627//6627 6629//6629 -f 5969//5969 5973//5973 6630//6630 -f 5700//5700 5699//5699 6631//6631 -f 6625//6625 1257//1257 5734//5734 -f 6624//6624 6625//6625 6632//6632 -f 1274//1274 6633//6633 5994//5994 -f 5994//5994 6633//6633 6634//6634 -f 5994//5994 6634//6634 5993//5993 -f 5993//5993 6634//6634 6635//6635 -f 6625//6625 5734//5734 6632//6632 -f 6632//6632 5734//5734 5735//5735 -f 6632//6632 5735//5735 6636//6636 -f 6636//6636 5735//5735 5740//5740 -f 6636//6636 5740//5740 6637//6637 -f 6637//6637 5740//5740 5739//5739 -f 6637//6637 5739//5739 6638//6638 -f 6639//6639 5992//5992 6640//6640 -f 6640//6640 5992//5992 5964//5964 -f 6640//6640 5964//5964 6635//6635 -f 6635//6635 5964//5964 5963//5963 -f 6635//6635 5963//5963 5993//5993 -f 5739//5739 5737//5737 6638//6638 -f 6638//6638 5737//5737 5736//5736 -f 6638//6638 5736//5736 6641//6641 -f 6641//6641 5736//5736 5742//5742 -f 6641//6641 5742//5742 6642//6642 -f 6643//6643 5984//5984 6644//6644 -f 6644//6644 5984//5984 5989//5989 -f 6644//6644 5989//5989 6639//6639 -f 6639//6639 5989//5989 5991//5991 -f 6639//6639 5991//5991 5992//5992 -f 5742//5742 5741//5741 6642//6642 -f 6642//6642 5741//5741 5747//5747 -f 6642//6642 5747//5747 6645//6645 -f 6645//6645 5747//5747 5745//5745 -f 6645//6645 5745//5745 6646//6646 -f 5988//5988 5987//5987 6643//6643 -f 6643//6643 5987//5987 5985//5985 -f 6643//6643 5985//5985 5984//5984 -f 5988//5988 6643//6643 6073//6073 -f 6073//6073 6643//6643 6647//6647 -f 6073//6073 6647//6647 6648//6648 -f 5745//5745 5744//5744 6646//6646 -f 6646//6646 5744//5744 5751//5751 -f 6646//6646 5751//5751 6649//6649 -f 6649//6649 5751//5751 5749//5749 -f 6649//6649 5749//5749 6650//6650 -f 6651//6651 5983//5983 6652//6652 -f 6652//6652 5983//5983 5967//5967 -f 6652//6652 5967//5967 6648//6648 -f 6648//6648 5967//5967 5966//5966 -f 6648//6648 5966//5966 6073//6073 -f 5752//5752 6653//6653 5753//5753 -f 5753//5753 6653//6653 6654//6654 -f 5753//5753 6654//6654 5755//5755 -f 5755//5755 6654//6654 6650//6650 -f 5755//5755 6650//6650 5748//5748 -f 5748//5748 6650//6650 5749//5749 -f 6623//6623 6624//6624 6655//6655 -f 6655//6655 6624//6624 6632//6632 -f 6655//6655 6632//6632 6656//6656 -f 6656//6656 6632//6632 6636//6636 -f 6656//6656 6636//6636 6657//6657 -f 6657//6657 6636//6636 6637//6637 -f 6657//6657 6637//6637 6658//6658 -f 6658//6658 6637//6637 6638//6638 -f 6658//6658 6638//6638 6659//6659 -f 6659//6659 6638//6638 6641//6641 -f 6659//6659 6641//6641 6660//6660 -f 6660//6660 6641//6641 6642//6642 -f 6660//6660 6642//6642 6661//6661 -f 6661//6661 6642//6642 6645//6645 -f 6661//6661 6645//6645 6662//6662 -f 6662//6662 6645//6645 6646//6646 -f 6662//6662 6646//6646 6663//6663 -f 6663//6663 6646//6646 6649//6649 -f 6663//6663 6649//6649 6664//6664 -f 6664//6664 6649//6649 6650//6650 -f 6664//6664 6650//6650 6665//6665 -f 6665//6665 6650//6650 6654//6654 -f 6665//6665 6654//6654 6666//6666 -f 6666//6666 6654//6654 6653//6653 -f 6666//6666 6653//6653 6667//6667 -f 1274//1274 6623//6623 6633//6633 -f 6633//6633 6623//6623 6655//6655 -f 6633//6633 6655//6655 6634//6634 -f 6634//6634 6655//6655 6656//6656 -f 6634//6634 6656//6656 6635//6635 -f 6635//6635 6656//6656 6657//6657 -f 6635//6635 6657//6657 6640//6640 -f 6640//6640 6657//6657 6658//6658 -f 6640//6640 6658//6658 6639//6639 -f 6639//6639 6658//6658 6659//6659 -f 6639//6639 6659//6659 6644//6644 -f 6644//6644 6659//6659 6660//6660 -f 6644//6644 6660//6660 6643//6643 -f 6643//6643 6660//6660 6661//6661 -f 6643//6643 6661//6661 6647//6647 -f 6647//6647 6661//6661 6662//6662 -f 6647//6647 6662//6662 6648//6648 -f 6648//6648 6662//6662 6663//6663 -f 6648//6648 6663//6663 6652//6652 -f 6652//6652 6663//6663 6664//6664 -f 6652//6652 6664//6664 6651//6651 -f 6651//6651 6664//6664 6665//6665 -f 6651//6651 6665//6665 6668//6668 -f 6668//6668 6665//6665 6666//6666 -f 6668//6668 6666//6666 6669//6669 -f 6669//6669 6666//6666 6667//6667 -f 6669//6669 6667//6667 6670//6670 -f 5979//5979 5978//5978 6670//6670 -f 6670//6670 5978//5978 5976//5976 -f 6670//6670 5976//5976 6669//6669 -f 6669//6669 5976//5976 5975//5975 -f 6669//6669 5975//5975 6668//6668 -f 6668//6668 5975//5975 5980//5980 -f 6668//6668 5980//5980 6651//6651 -f 6651//6651 5980//5980 5982//5982 -f 6651//6651 5982//5982 5983//5983 -f 5974//5974 5979//5979 6671//6671 -f 6671//6671 5979//5979 6670//6670 -f 6671//6671 6670//6670 6672//6672 -f 6672//6672 6670//6670 6667//6667 -f 6672//6672 6667//6667 6673//6673 -f 6673//6673 6667//6667 6653//6653 -f 6673//6673 6653//6653 5757//5757 -f 5757//5757 6653//6653 5752//5752 -f 5973//5973 5974//5974 6630//6630 -f 6630//6630 5974//5974 6671//6671 -f 6630//6630 6671//6671 6674//6674 -f 6674//6674 6671//6671 6672//6672 -f 6674//6674 6672//6672 6675//6675 -f 6675//6675 6672//6672 6673//6673 -f 6675//6675 6673//6673 5756//5756 -f 5756//5756 6673//6673 5757//5757 -f 5970//5970 5969//5969 6676//6676 -f 6676//6676 5969//5969 6630//6630 -f 6676//6676 6630//6630 6677//6677 -f 6677//6677 6630//6630 6674//6674 -f 6677//6677 6674//6674 6631//6631 -f 6631//6631 6674//6674 6675//6675 -f 6631//6631 6675//6675 5700//5700 -f 5700//5700 6675//6675 5756//5756 -f 5762//5762 5761//5761 6629//6629 -f 6629//6629 5761//5761 5760//5760 -f 6629//6629 5760//5760 6628//6628 -f 6628//6628 5760//5760 621//621 -f 5758//5758 5762//5762 6678//6678 -f 6678//6678 5762//5762 6629//6629 -f 6678//6678 6629//6629 6679//6679 -f 6679//6679 6629//6629 6627//6627 -f 6679//6679 6627//6627 6626//6626 -f 6626//6626 6627//6627 621//621 -f 5971//5971 5970//5970 6626//6626 -f 6626//6626 5970//5970 6676//6676 -f 6626//6626 6676//6676 6679//6679 -f 6679//6679 6676//6676 6677//6677 -f 6679//6679 6677//6677 6678//6678 -f 6678//6678 6677//6677 6631//6631 -f 6678//6678 6631//6631 5758//5758 -f 5758//5758 6631//6631 5699//5699 -f 2636//2636 2635//2635 6680//6680 -f 1207//1207 1209//1209 2618//2618 -f 2618//2618 1209//1209 6681//6681 -f 2618//2618 6681//6681 2619//2619 -f 2635//2635 2622//2622 6680//6680 -f 6680//6680 2622//2622 2621//2621 -f 6680//6680 2621//2621 6681//6681 -f 6681//6681 2621//2621 2620//2620 -f 6681//6681 2620//2620 2619//2619 -f 2636//2636 6680//6680 2637//2637 -f 2637//2637 6680//6680 6682//6682 -f 2637//2637 6682//6682 2633//2633 -f 2633//2633 6682//6682 2634//2634 -f 2634//2634 6682//6682 1251//1251 -f 2634//2634 1251//1251 1253//1253 -f 468//468 5710//5710 6683//6683 -f 468//468 6684//6684 6685//6685 -f 6685//6685 6684//6684 6686//6686 -f 5708//5708 5712//5712 6687//6687 -f 5833//5833 5832//5832 6688//6688 -f 6681//6681 1209//1209 5875//5875 -f 6680//6680 6681//6681 6689//6689 -f 1251//1251 6690//6690 5733//5733 -f 5733//5733 6690//6690 6691//6691 -f 5733//5733 6691//6691 5732//5732 -f 5732//5732 6691//6691 6692//6692 -f 6681//6681 5875//5875 6689//6689 -f 6689//6689 5875//5875 5876//5876 -f 6689//6689 5876//5876 6693//6693 -f 6693//6693 5876//5876 5881//5881 -f 6693//6693 5881//5881 6694//6694 -f 6694//6694 5881//5881 5880//5880 -f 6694//6694 5880//5880 6695//6695 -f 6696//6696 5731//5731 6697//6697 -f 6697//6697 5731//5731 5703//5703 -f 6697//6697 5703//5703 6692//6692 -f 6692//6692 5703//5703 5702//5702 -f 6692//6692 5702//5702 5732//5732 -f 5880//5880 5878//5878 6695//6695 -f 6695//6695 5878//5878 5877//5877 -f 6695//6695 5877//5877 6698//6698 -f 6698//6698 5877//5877 5883//5883 -f 6698//6698 5883//5883 6699//6699 -f 6700//6700 5723//5723 6701//6701 -f 6701//6701 5723//5723 5728//5728 -f 6701//6701 5728//5728 6696//6696 -f 6696//6696 5728//5728 5730//5730 -f 6696//6696 5730//5730 5731//5731 -f 5883//5883 5882//5882 6699//6699 -f 6699//6699 5882//5882 5888//5888 -f 6699//6699 5888//5888 6702//6702 -f 6702//6702 5888//5888 5886//5886 -f 6702//6702 5886//5886 6703//6703 -f 5727//5727 5726//5726 6700//6700 -f 6700//6700 5726//5726 5724//5724 -f 6700//6700 5724//5724 5723//5723 -f 5727//5727 6700//6700 5812//5812 -f 5812//5812 6700//6700 6704//6704 -f 5812//5812 6704//6704 6705//6705 -f 5886//5886 5885//5885 6703//6703 -f 6703//6703 5885//5885 5892//5892 -f 6703//6703 5892//5892 6706//6706 -f 6706//6706 5892//5892 5890//5890 -f 6706//6706 5890//5890 6707//6707 -f 6708//6708 5722//5722 6709//6709 -f 6709//6709 5722//5722 5706//5706 -f 6709//6709 5706//5706 6705//6705 -f 6705//6705 5706//5706 5705//5705 -f 6705//6705 5705//5705 5812//5812 -f 5893//5893 6710//6710 5894//5894 -f 5894//5894 6710//6710 6711//6711 -f 5894//5894 6711//6711 5896//5896 -f 5896//5896 6711//6711 6707//6707 -f 5896//5896 6707//6707 5889//5889 -f 5889//5889 6707//6707 5890//5890 -f 6682//6682 6680//6680 6712//6712 -f 6712//6712 6680//6680 6689//6689 -f 6712//6712 6689//6689 6713//6713 -f 6713//6713 6689//6689 6693//6693 -f 6713//6713 6693//6693 6714//6714 -f 6714//6714 6693//6693 6694//6694 -f 6714//6714 6694//6694 6715//6715 -f 6715//6715 6694//6694 6695//6695 -f 6715//6715 6695//6695 6716//6716 -f 6716//6716 6695//6695 6698//6698 -f 6716//6716 6698//6698 6717//6717 -f 6717//6717 6698//6698 6699//6699 -f 6717//6717 6699//6699 6718//6718 -f 6718//6718 6699//6699 6702//6702 -f 6718//6718 6702//6702 6719//6719 -f 6719//6719 6702//6702 6703//6703 -f 6719//6719 6703//6703 6720//6720 -f 6720//6720 6703//6703 6706//6706 -f 6720//6720 6706//6706 6721//6721 -f 6721//6721 6706//6706 6707//6707 -f 6721//6721 6707//6707 6722//6722 -f 6722//6722 6707//6707 6711//6711 -f 6722//6722 6711//6711 6723//6723 -f 6723//6723 6711//6711 6710//6710 -f 6723//6723 6710//6710 6724//6724 -f 1251//1251 6682//6682 6690//6690 -f 6690//6690 6682//6682 6712//6712 -f 6690//6690 6712//6712 6691//6691 -f 6691//6691 6712//6712 6713//6713 -f 6691//6691 6713//6713 6692//6692 -f 6692//6692 6713//6713 6714//6714 -f 6692//6692 6714//6714 6697//6697 -f 6697//6697 6714//6714 6715//6715 -f 6697//6697 6715//6715 6696//6696 -f 6696//6696 6715//6715 6716//6716 -f 6696//6696 6716//6716 6701//6701 -f 6701//6701 6716//6716 6717//6717 -f 6701//6701 6717//6717 6700//6700 -f 6700//6700 6717//6717 6718//6718 -f 6700//6700 6718//6718 6704//6704 -f 6704//6704 6718//6718 6719//6719 -f 6704//6704 6719//6719 6705//6705 -f 6705//6705 6719//6719 6720//6720 -f 6705//6705 6720//6720 6709//6709 -f 6709//6709 6720//6720 6721//6721 -f 6709//6709 6721//6721 6708//6708 -f 6708//6708 6721//6721 6722//6722 -f 6708//6708 6722//6722 6725//6725 -f 6725//6725 6722//6722 6723//6723 -f 6725//6725 6723//6723 6726//6726 -f 6726//6726 6723//6723 6724//6724 -f 6726//6726 6724//6724 6727//6727 -f 5718//5718 5717//5717 6727//6727 -f 6727//6727 5717//5717 5715//5715 -f 6727//6727 5715//5715 6726//6726 -f 6726//6726 5715//5715 5714//5714 -f 6726//6726 5714//5714 6725//6725 -f 6725//6725 5714//5714 5719//5719 -f 6725//6725 5719//5719 6708//6708 -f 6708//6708 5719//5719 5721//5721 -f 6708//6708 5721//5721 5722//5722 -f 5713//5713 5718//5718 6728//6728 -f 6728//6728 5718//5718 6727//6727 -f 6728//6728 6727//6727 6729//6729 -f 6729//6729 6727//6727 6724//6724 -f 6729//6729 6724//6724 6730//6730 -f 6730//6730 6724//6724 6710//6710 -f 6730//6730 6710//6710 5898//5898 -f 5898//5898 6710//6710 5893//5893 -f 5712//5712 5713//5713 6687//6687 -f 6687//6687 5713//5713 6728//6728 -f 6687//6687 6728//6728 6731//6731 -f 6731//6731 6728//6728 6729//6729 -f 6731//6731 6729//6729 6732//6732 -f 6732//6732 6729//6729 6730//6730 -f 6732//6732 6730//6730 5897//5897 -f 5897//5897 6730//6730 5898//5898 -f 5709//5709 5708//5708 6733//6733 -f 6733//6733 5708//5708 6687//6687 -f 6733//6733 6687//6687 6734//6734 -f 6734//6734 6687//6687 6731//6731 -f 6734//6734 6731//6731 6688//6688 -f 6688//6688 6731//6731 6732//6732 -f 6688//6688 6732//6732 5833//5833 -f 5833//5833 6732//6732 5897//5897 -f 5901//5901 5903//5903 6686//6686 -f 6686//6686 5903//5903 5902//5902 -f 6686//6686 5902//5902 6685//6685 -f 6685//6685 5902//5902 468//468 -f 5899//5899 5901//5901 6735//6735 -f 6735//6735 5901//5901 6686//6686 -f 6735//6735 6686//6686 6736//6736 -f 6736//6736 6686//6686 6684//6684 -f 6736//6736 6684//6684 6683//6683 -f 6683//6683 6684//6684 468//468 -f 5710//5710 5709//5709 6683//6683 -f 6683//6683 5709//5709 6733//6733 -f 6683//6683 6733//6733 6736//6736 -f 6736//6736 6733//6733 6734//6734 -f 6736//6736 6734//6734 6735//6735 -f 6735//6735 6734//6734 6688//6688 -f 6735//6735 6688//6688 5899//5899 -f 5899//5899 6688//6688 5832//5832 -f 2748//2748 2747//2747 6737//6737 -f 2745//2745 2744//2744 6738//6738 -f 1236//1236 1234//1234 2750//2750 -f 2750//2750 1234//1234 6739//6739 -f 2744//2744 2743//2743 6738//6738 -f 6738//6738 2743//2743 2742//2742 -f 6738//6738 2742//2742 6739//6739 -f 6739//6739 2742//2742 2752//2752 -f 6739//6739 2752//2752 2750//2750 -f 6737//6737 2747//2747 6738//6738 -f 6738//6738 2747//2747 2746//2746 -f 6738//6738 2746//2746 2745//2745 -f 2748//2748 6737//6737 2749//2749 -f 2749//2749 6737//6737 1204//1204 -f 2749//2749 1204//1204 1206//1206 -f 539//539 5841//5841 6740//6740 -f 539//539 6741//6741 6742//6742 -f 6742//6742 6741//6741 6743//6743 -f 5839//5839 5838//5838 6744//6744 -f 6099//6099 6098//6098 6745//6745 -f 6739//6739 1234//1234 6101//6101 -f 6738//6738 6739//6739 6746//6746 -f 1204//1204 6747//6747 5874//5874 -f 5874//5874 6747//6747 6748//6748 -f 5874//5874 6748//6748 5873//5873 -f 5873//5873 6748//6748 6749//6749 -f 6739//6739 6101//6101 6746//6746 -f 6746//6746 6101//6101 6102//6102 -f 6746//6746 6102//6102 6750//6750 -f 6750//6750 6102//6102 6107//6107 -f 6750//6750 6107//6107 6751//6751 -f 6751//6751 6107//6107 6106//6106 -f 6751//6751 6106//6106 6752//6752 -f 6753//6753 5872//5872 6754//6754 -f 6754//6754 5872//5872 5836//5836 -f 6754//6754 5836//5836 6749//6749 -f 6749//6749 5836//5836 5835//5835 -f 6749//6749 5835//5835 5873//5873 -f 6106//6106 6104//6104 6752//6752 -f 6752//6752 6104//6104 6103//6103 -f 6752//6752 6103//6103 6755//6755 -f 6755//6755 6103//6103 6109//6109 -f 6755//6755 6109//6109 6756//6756 -f 6757//6757 5864//5864 6758//6758 -f 6758//6758 5864//5864 5869//5869 -f 6758//6758 5869//5869 6753//6753 -f 6753//6753 5869//5869 5871//5871 -f 6753//6753 5871//5871 5872//5872 -f 6109//6109 6108//6108 6756//6756 -f 6756//6756 6108//6108 6114//6114 -f 6756//6756 6114//6114 6759//6759 -f 6759//6759 6114//6114 6112//6112 -f 6759//6759 6112//6112 6760//6760 -f 5868//5868 5867//5867 6757//6757 -f 6757//6757 5867//5867 5865//5865 -f 6757//6757 5865//5865 5864//5864 -f 5868//5868 6757//6757 5941//5941 -f 5941//5941 6757//6757 6761//6761 -f 5941//5941 6761//6761 6762//6762 -f 6112//6112 6111//6111 6760//6760 -f 6760//6760 6111//6111 6118//6118 -f 6760//6760 6118//6118 6763//6763 -f 6763//6763 6118//6118 6116//6116 -f 6763//6763 6116//6116 6764//6764 -f 6765//6765 5856//5856 6766//6766 -f 6766//6766 5856//5856 5858//5858 -f 6766//6766 5858//5858 6762//6762 -f 6762//6762 5858//5858 5860//5860 -f 6762//6762 5860//5860 5941//5941 -f 6119//6119 6767//6767 6120//6120 -f 6120//6120 6767//6767 6768//6768 -f 6120//6120 6768//6768 6122//6122 -f 6122//6122 6768//6768 6764//6764 -f 6122//6122 6764//6764 6115//6115 -f 6115//6115 6764//6764 6116//6116 -f 6737//6737 6738//6738 6769//6769 -f 6769//6769 6738//6738 6746//6746 -f 6769//6769 6746//6746 6770//6770 -f 6770//6770 6746//6746 6750//6750 -f 6770//6770 6750//6750 6771//6771 -f 6771//6771 6750//6750 6751//6751 -f 6771//6771 6751//6751 6772//6772 -f 6772//6772 6751//6751 6752//6752 -f 6772//6772 6752//6752 6773//6773 -f 6773//6773 6752//6752 6755//6755 -f 6773//6773 6755//6755 6774//6774 -f 6774//6774 6755//6755 6756//6756 -f 6774//6774 6756//6756 6775//6775 -f 6775//6775 6756//6756 6759//6759 -f 6775//6775 6759//6759 6776//6776 -f 6776//6776 6759//6759 6760//6760 -f 6776//6776 6760//6760 6777//6777 -f 6777//6777 6760//6760 6763//6763 -f 6777//6777 6763//6763 6778//6778 -f 6778//6778 6763//6763 6764//6764 -f 6778//6778 6764//6764 6779//6779 -f 6779//6779 6764//6764 6768//6768 -f 6779//6779 6768//6768 6780//6780 -f 6780//6780 6768//6768 6767//6767 -f 6780//6780 6767//6767 6781//6781 -f 1204//1204 6737//6737 6747//6747 -f 6747//6747 6737//6737 6769//6769 -f 6747//6747 6769//6769 6748//6748 -f 6748//6748 6769//6769 6770//6770 -f 6748//6748 6770//6770 6749//6749 -f 6749//6749 6770//6770 6771//6771 -f 6749//6749 6771//6771 6754//6754 -f 6754//6754 6771//6771 6772//6772 -f 6754//6754 6772//6772 6753//6753 -f 6753//6753 6772//6772 6773//6773 -f 6753//6753 6773//6773 6758//6758 -f 6758//6758 6773//6773 6774//6774 -f 6758//6758 6774//6774 6757//6757 -f 6757//6757 6774//6774 6775//6775 -f 6757//6757 6775//6775 6761//6761 -f 6761//6761 6775//6775 6776//6776 -f 6761//6761 6776//6776 6762//6762 -f 6762//6762 6776//6776 6777//6777 -f 6762//6762 6777//6777 6766//6766 -f 6766//6766 6777//6777 6778//6778 -f 6766//6766 6778//6778 6765//6765 -f 6765//6765 6778//6778 6779//6779 -f 6765//6765 6779//6779 6782//6782 -f 6782//6782 6779//6779 6780//6780 -f 6782//6782 6780//6780 6783//6783 -f 6783//6783 6780//6780 6781//6781 -f 6783//6783 6781//6781 6784//6784 -f 5854//5854 5852//5852 6784//6784 -f 6784//6784 5852//5852 5851//5851 -f 6784//6784 5851//5851 6783//6783 -f 6783//6783 5851//5851 5863//5863 -f 6783//6783 5863//5863 6782//6782 -f 6782//6782 5863//5863 5862//5862 -f 6782//6782 5862//5862 6765//6765 -f 6765//6765 5862//5862 5861//5861 -f 6765//6765 5861//5861 5856//5856 -f 5855//5855 5854//5854 6785//6785 -f 6785//6785 5854//5854 6784//6784 -f 6785//6785 6784//6784 6786//6786 -f 6786//6786 6784//6784 6781//6781 -f 6786//6786 6781//6781 6787//6787 -f 6787//6787 6781//6781 6767//6767 -f 6787//6787 6767//6767 6124//6124 -f 6124//6124 6767//6767 6119//6119 -f 5838//5838 5855//5855 6744//6744 -f 6744//6744 5855//5855 6785//6785 -f 6744//6744 6785//6785 6788//6788 -f 6788//6788 6785//6785 6786//6786 -f 6788//6788 6786//6786 6789//6789 -f 6789//6789 6786//6786 6787//6787 -f 6789//6789 6787//6787 6123//6123 -f 6123//6123 6787//6787 6124//6124 -f 5850//5850 5839//5839 6790//6790 -f 6790//6790 5839//5839 6744//6744 -f 6790//6790 6744//6744 6791//6791 -f 6791//6791 6744//6744 6788//6788 -f 6791//6791 6788//6788 6745//6745 -f 6745//6745 6788//6788 6789//6789 -f 6745//6745 6789//6789 6099//6099 -f 6099//6099 6789//6789 6123//6123 -f 6127//6127 6165//6165 6743//6743 -f 6743//6743 6165//6165 6128//6128 -f 6743//6743 6128//6128 6742//6742 -f 6742//6742 6128//6128 539//539 -f 6126//6126 6127//6127 6792//6792 -f 6792//6792 6127//6127 6743//6743 -f 6792//6792 6743//6743 6793//6793 -f 6793//6793 6743//6743 6741//6741 -f 6793//6793 6741//6741 6740//6740 -f 6740//6740 6741//6741 539//539 -f 5841//5841 5850//5850 6740//6740 -f 6740//6740 5850//5850 6790//6790 -f 6740//6740 6790//6790 6793//6793 -f 6793//6793 6790//6790 6791//6791 -f 6793//6793 6791//6791 6792//6792 -f 6792//6792 6791//6791 6745//6745 -f 6792//6792 6745//6745 6126//6126 -f 6126//6126 6745//6745 6098//6098 -f 1526//1526 1528//1528 2734//2734 -f 2734//2734 1528//1528 6794//6794 -f 2734//2734 6794//6794 2735//2735 -f 2735//2735 6794//6794 2736//2736 -f 2736//2736 6794//6794 6795//6795 -f 2736//2736 6795//6795 2737//2737 -f 2737//2737 6795//6795 2738//2738 -f 2738//2738 6795//6795 6796//6796 -f 2738//2738 6796//6796 2708//2708 -f 2708//2708 6796//6796 2709//2709 -f 2709//2709 6796//6796 1593//1593 -f 2709//2709 1593//1593 1595//1595 -f 1//1 3674//3674 6797//6797 -f 1//1 6798//6798 6799//6799 -f 6799//6799 6798//6798 6800//6800 -f 3672//3672 3671//3671 6801//6801 -f 3742//3742 3741//3741 6802//6802 -f 3795//3795 3794//3794 6803//6803 -f 3683//3683 3691//3691 6804//6804 -f 3791//3791 3790//3790 6805//6805 -f 3689//3689 3688//3688 6806//6806 -f 3787//3787 3786//3786 6807//6807 -f 3686//3686 3697//3697 6808//6808 -f 3784//3784 3783//3783 6809//6809 -f 3695//3695 3694//3694 6810//6810 -f 3781//3781 3779//3779 6811//6811 -f 6812//6812 6794//6794 3776//3776 -f 3776//3776 6794//6794 1528//1528 -f 3692//3692 1593//1593 6813//6813 -f 6813//6813 1593//1593 6796//6796 -f 3693//3693 3692//3692 6814//6814 -f 6814//6814 3692//3692 6813//6813 -f 6814//6814 6813//6813 6815//6815 -f 6815//6815 6813//6813 6796//6796 -f 6815//6815 6796//6796 6795//6795 -f 3694//3694 3693//3693 6810//6810 -f 6810//6810 3693//3693 6814//6814 -f 6810//6810 6814//6814 6816//6816 -f 6816//6816 6814//6814 6815//6815 -f 6816//6816 6815//6815 6812//6812 -f 6812//6812 6815//6815 6795//6795 -f 6812//6812 6795//6795 6794//6794 -f 3696//3696 3695//3695 6817//6817 -f 6817//6817 3695//3695 6810//6810 -f 6817//6817 6810//6810 6818//6818 -f 6818//6818 6810//6810 6816//6816 -f 6818//6818 6816//6816 6819//6819 -f 6819//6819 6816//6816 6812//6812 -f 6819//6819 6812//6812 3777//3777 -f 3777//3777 6812//6812 3776//3776 -f 3697//3697 3696//3696 6808//6808 -f 6808//6808 3696//3696 6817//6817 -f 6808//6808 6817//6817 6820//6820 -f 6820//6820 6817//6817 6818//6818 -f 6820//6820 6818//6818 6821//6821 -f 6821//6821 6818//6818 6819//6819 -f 6821//6821 6819//6819 3782//3782 -f 3782//3782 6819//6819 3777//3777 -f 3687//3687 3686//3686 6822//6822 -f 6822//6822 3686//3686 6808//6808 -f 6822//6822 6808//6808 6823//6823 -f 6823//6823 6808//6808 6820//6820 -f 6823//6823 6820//6820 6811//6811 -f 6811//6811 6820//6820 6821//6821 -f 6811//6811 6821//6821 3781//3781 -f 3781//3781 6821//6821 3782//3782 -f 3688//3688 3687//3687 6806//6806 -f 6806//6806 3687//3687 6822//6822 -f 6806//6806 6822//6822 6824//6824 -f 6824//6824 6822//6822 6823//6823 -f 6824//6824 6823//6823 6825//6825 -f 6825//6825 6823//6823 6811//6811 -f 6825//6825 6811//6811 3778//3778 -f 3778//3778 6811//6811 3779//3779 -f 3690//3690 3689//3689 6826//6826 -f 6826//6826 3689//3689 6806//6806 -f 6826//6826 6806//6806 6827//6827 -f 6827//6827 6806//6806 6824//6824 -f 6827//6827 6824//6824 6809//6809 -f 6809//6809 6824//6824 6825//6825 -f 6809//6809 6825//6825 3784//3784 -f 3784//3784 6825//6825 3778//3778 -f 3691//3691 3690//3690 6804//6804 -f 6804//6804 3690//3690 6826//6826 -f 6804//6804 6826//6826 6828//6828 -f 6828//6828 6826//6826 6827//6827 -f 6828//6828 6827//6827 6829//6829 -f 6829//6829 6827//6827 6809//6809 -f 6829//6829 6809//6809 3789//3789 -f 3789//3789 6809//6809 3783//3783 -f 3684//3684 3683//3683 6830//6830 -f 6830//6830 3683//3683 6804//6804 -f 6830//6830 6804//6804 6831//6831 -f 6831//6831 6804//6804 6828//6828 -f 6831//6831 6828//6828 6807//6807 -f 6807//6807 6828//6828 6829//6829 -f 6807//6807 6829//6829 3787//3787 -f 3787//3787 6829//6829 3789//3789 -f 3786//3786 3793//3793 6807//6807 -f 6807//6807 3793//3793 6832//6832 -f 6807//6807 6832//6832 6831//6831 -f 6831//6831 6832//6832 6833//6833 -f 6831//6831 6833//6833 6830//6830 -f 6830//6830 6833//6833 6834//6834 -f 6830//6830 6834//6834 3684//3684 -f 3682//3682 3681//3681 6834//6834 -f 3681//3681 3670//3670 6834//6834 -f 6834//6834 3670//3670 3685//3685 -f 6834//6834 3685//3685 3684//3684 -f 3790//3790 3797//3797 6805//6805 -f 6805//6805 3797//3797 6835//6835 -f 6805//6805 6835//6835 6836//6836 -f 6836//6836 6835//6835 6837//6837 -f 6836//6836 6837//6837 6838//6838 -f 6838//6838 6837//6837 6839//6839 -f 3797//3797 3795//3795 6835//6835 -f 6835//6835 3795//3795 6803//6803 -f 6835//6835 6803//6803 6837//6837 -f 6837//6837 6803//6803 6840//6840 -f 6837//6837 6840//6840 6839//6839 -f 6839//6839 6840//6840 6841//6841 -f 3793//3793 3791//3791 6832//6832 -f 6832//6832 3791//3791 6805//6805 -f 6832//6832 6805//6805 6833//6833 -f 6833//6833 6805//6805 6836//6836 -f 6833//6833 6836//6836 6834//6834 -f 6834//6834 6836//6836 6838//6838 -f 6834//6834 6838//6838 3682//3682 -f 3682//3682 6838//6838 6839//6839 -f 3682//3682 6839//6839 3676//3676 -f 3676//3676 6839//6839 6841//6841 -f 3676//3676 6841//6841 3677//3677 -f 3677//3677 6841//6841 3679//3679 -f 3680//3680 3679//3679 6842//6842 -f 6842//6842 3679//3679 6841//6841 -f 6842//6842 6841//6841 6843//6843 -f 6843//6843 6841//6841 6840//6840 -f 6843//6843 6840//6840 6844//6844 -f 6844//6844 6840//6840 6803//6803 -f 6844//6844 6803//6803 3799//3799 -f 3799//3799 6803//6803 3794//3794 -f 3671//3671 3680//3680 6801//6801 -f 6801//6801 3680//3680 6842//6842 -f 6801//6801 6842//6842 6845//6845 -f 6845//6845 6842//6842 6843//6843 -f 6845//6845 6843//6843 6846//6846 -f 6846//6846 6843//6843 6844//6844 -f 6846//6846 6844//6844 3798//3798 -f 3798//3798 6844//6844 3799//3799 -f 3675//3675 3672//3672 6847//6847 -f 6847//6847 3672//3672 6801//6801 -f 6847//6847 6801//6801 6848//6848 -f 6848//6848 6801//6801 6845//6845 -f 6848//6848 6845//6845 6802//6802 -f 6802//6802 6845//6845 6846//6846 -f 6802//6802 6846//6846 3742//3742 -f 3742//3742 6846//6846 3798//3798 -f 3802//3802 3804//3804 6800//6800 -f 6800//6800 3804//3804 3803//3803 -f 6800//6800 3803//3803 6799//6799 -f 6799//6799 3803//3803 1//1 -f 3800//3800 3802//3802 6849//6849 -f 6849//6849 3802//3802 6800//6800 -f 6849//6849 6800//6800 6850//6850 -f 6850//6850 6800//6800 6798//6798 -f 6850//6850 6798//6798 6797//6797 -f 6797//6797 6798//6798 1//1 -f 3674//3674 3675//3675 6797//6797 -f 6797//6797 3675//3675 6847//6847 -f 6797//6797 6847//6847 6850//6850 -f 6850//6850 6847//6847 6848//6848 -f 6850//6850 6848//6848 6849//6849 -f 6849//6849 6848//6848 6802//6802 -f 6849//6849 6802//6802 3800//3800 -f 3800//3800 6802//6802 3741//3741 -f 1585//1585 1584//1584 2689//2689 -f 2689//2689 1584//1584 6851//6851 -f 2689//2689 6851//6851 2705//2705 -f 2705//2705 6851//6851 2706//2706 -f 2706//2706 6851//6851 6852//6852 -f 2706//2706 6852//6852 2707//2707 -f 2707//2707 6852//6852 2702//2702 -f 2702//2702 6852//6852 6853//6853 -f 2702//2702 6853//6853 2703//2703 -f 2703//2703 6853//6853 2704//2704 -f 2704//2704 6853//6853 1634//1634 -f 2704//2704 1634//1634 1636//1636 -f 789//789 3704//3704 6854//6854 -f 789//789 6855//6855 6856//6856 -f 6856//6856 6855//6855 6857//6857 -f 3702//3702 3701//3701 6858//6858 -f 3668//3668 3667//3667 6859//6859 -f 3661//3661 3665//3665 6860//6860 -f 3721//3721 3720//3720 6861//6861 -f 3657//3657 3659//3659 6862//6862 -f 3716//3716 3734//3734 6863//6863 -f 3654//3654 3655//3655 6864//6864 -f 3731//3731 3730//3730 6865//6865 -f 3647//3647 3646//3646 6866//6866 -f 3726//3726 3737//3737 6867//6867 -f 3650//3650 3649//3649 6868//6868 -f 6869//6869 6851//6851 3645//3645 -f 3645//3645 6851//6851 1584//1584 -f 3735//3735 1634//1634 6870//6870 -f 6870//6870 1634//1634 6853//6853 -f 3736//3736 3735//3735 6871//6871 -f 6871//6871 3735//3735 6870//6870 -f 6871//6871 6870//6870 6872//6872 -f 6872//6872 6870//6870 6853//6853 -f 6872//6872 6853//6853 6852//6852 -f 3737//3737 3736//3736 6867//6867 -f 6867//6867 3736//3736 6871//6871 -f 6867//6867 6871//6871 6873//6873 -f 6873//6873 6871//6871 6872//6872 -f 6873//6873 6872//6872 6869//6869 -f 6869//6869 6872//6872 6852//6852 -f 6869//6869 6852//6852 6851//6851 -f 3728//3728 3726//3726 6874//6874 -f 6874//6874 3726//3726 6867//6867 -f 6874//6874 6867//6867 6875//6875 -f 6875//6875 6867//6867 6873//6873 -f 6875//6875 6873//6873 6876//6876 -f 6876//6876 6873//6873 6869//6869 -f 6876//6876 6869//6869 3652//3652 -f 3652//3652 6869//6869 3645//3645 -f 3730//3730 3728//3728 6865//6865 -f 6865//6865 3728//3728 6874//6874 -f 6865//6865 6874//6874 6877//6877 -f 6877//6877 6874//6874 6875//6875 -f 6877//6877 6875//6875 6878//6878 -f 6878//6878 6875//6875 6876//6876 -f 6878//6878 6876//6876 3651//3651 -f 3651//3651 6876//6876 3652//3652 -f 3733//3733 3731//3731 6879//6879 -f 6879//6879 3731//3731 6865//6865 -f 6879//6879 6865//6865 6880//6880 -f 6880//6880 6865//6865 6877//6877 -f 6880//6880 6877//6877 6868//6868 -f 6868//6868 6877//6877 6878//6878 -f 6868//6868 6878//6878 3650//3650 -f 3650//3650 6878//6878 3651//3651 -f 3734//3734 3733//3733 6863//6863 -f 6863//6863 3733//3733 6879//6879 -f 6863//6863 6879//6879 6881//6881 -f 6881//6881 6879//6879 6880//6880 -f 6881//6881 6880//6880 6882//6882 -f 6882//6882 6880//6880 6868//6868 -f 6882//6882 6868//6868 3648//3648 -f 3648//3648 6868//6868 3649//3649 -f 3718//3718 3716//3716 6883//6883 -f 6883//6883 3716//3716 6863//6863 -f 6883//6883 6863//6863 6884//6884 -f 6884//6884 6863//6863 6881//6881 -f 6884//6884 6881//6881 6866//6866 -f 6866//6866 6881//6881 6882//6882 -f 6866//6866 6882//6882 3647//3647 -f 3647//3647 6882//6882 3648//3648 -f 3720//3720 3718//3718 6861//6861 -f 6861//6861 3718//3718 6883//6883 -f 6861//6861 6883//6883 6885//6885 -f 6885//6885 6883//6883 6884//6884 -f 6885//6885 6884//6884 6886//6886 -f 6886//6886 6884//6884 6866//6866 -f 6886//6886 6866//6866 3653//3653 -f 3653//3653 6866//6866 3646//3646 -f 3723//3723 3721//3721 6887//6887 -f 6887//6887 3721//3721 6861//6861 -f 6887//6887 6861//6861 6888//6888 -f 6888//6888 6861//6861 6885//6885 -f 6888//6888 6885//6885 6864//6864 -f 6864//6864 6885//6885 6886//6886 -f 6864//6864 6886//6886 3654//3654 -f 3654//3654 6886//6886 3653//3653 -f 3655//3655 3656//3656 6864//6864 -f 6864//6864 3656//3656 6889//6889 -f 6864//6864 6889//6889 6888//6888 -f 6888//6888 6889//6889 6890//6890 -f 6888//6888 6890//6890 6887//6887 -f 6887//6887 6890//6890 6891//6891 -f 6887//6887 6891//6891 3723//3723 -f 6892//6892 3658//3658 3660//3660 -f 3714//3714 3713//3713 6891//6891 -f 3713//3713 3700//3700 6891//6891 -f 6891//6891 3700//3700 3724//3724 -f 6891//6891 3724//3724 3723//3723 -f 3659//3659 3658//3658 6862//6862 -f 6862//6862 3658//3658 6892//6892 -f 6862//6862 6892//6892 6893//6893 -f 6893//6893 6892//6892 6894//6894 -f 6893//6893 6894//6894 6895//6895 -f 6895//6895 6894//6894 6896//6896 -f 3660//3660 3661//3661 6892//6892 -f 6892//6892 3661//3661 6860//6860 -f 6892//6892 6860//6860 6894//6894 -f 6894//6894 6860//6860 6897//6897 -f 6894//6894 6897//6897 6896//6896 -f 6896//6896 6897//6897 6898//6898 -f 3656//3656 3657//3657 6889//6889 -f 6889//6889 3657//3657 6862//6862 -f 6889//6889 6862//6862 6890//6890 -f 6890//6890 6862//6862 6893//6893 -f 6890//6890 6893//6893 6891//6891 -f 6891//6891 6893//6893 6895//6895 -f 6891//6891 6895//6895 3714//3714 -f 3714//3714 6895//6895 6896//6896 -f 3714//3714 6896//6896 3706//3706 -f 3706//3706 6896//6896 6898//6898 -f 3706//3706 6898//6898 3707//3707 -f 3707//3707 6898//6898 3709//3709 -f 3710//3710 3709//3709 6899//6899 -f 6899//6899 3709//3709 6898//6898 -f 6899//6899 6898//6898 6900//6900 -f 6900//6900 6898//6898 6897//6897 -f 6900//6900 6897//6897 6901//6901 -f 6901//6901 6897//6897 6860//6860 -f 6901//6901 6860//6860 3664//3664 -f 3664//3664 6860//6860 3665//3665 -f 3701//3701 3710//3710 6858//6858 -f 6858//6858 3710//3710 6899//6899 -f 6858//6858 6899//6899 6902//6902 -f 6902//6902 6899//6899 6900//6900 -f 6902//6902 6900//6900 6903//6903 -f 6903//6903 6900//6900 6901//6901 -f 6903//6903 6901//6901 3663//3663 -f 3663//3663 6901//6901 3664//3664 -f 3705//3705 3702//3702 6904//6904 -f 6904//6904 3702//3702 6858//6858 -f 6904//6904 6858//6858 6905//6905 -f 6905//6905 6858//6858 6902//6902 -f 6905//6905 6902//6902 6859//6859 -f 6859//6859 6902//6902 6903//6903 -f 6859//6859 6903//6903 3668//3668 -f 3668//3668 6903//6903 3663//3663 -f 3643//3643 3642//3642 6857//6857 -f 6857//6857 3642//3642 3669//3669 -f 6857//6857 3669//3669 6856//6856 -f 6856//6856 3669//3669 789//789 -f 3666//3666 3643//3643 6906//6906 -f 6906//6906 3643//3643 6857//6857 -f 6906//6906 6857//6857 6907//6907 -f 6907//6907 6857//6857 6855//6855 -f 6907//6907 6855//6855 6854//6854 -f 6854//6854 6855//6855 789//789 -f 3704//3704 3705//3705 6854//6854 -f 6854//6854 3705//3705 6904//6904 -f 6854//6854 6904//6904 6907//6907 -f 6907//6907 6904//6904 6905//6905 -f 6907//6907 6905//6905 6906//6906 -f 6906//6906 6905//6905 6859//6859 -f 6906//6906 6859//6859 3666//3666 -f 3666//3666 6859//6859 3667//3667 -f 1626//1626 1625//1625 2677//2677 -f 2677//2677 1625//1625 6908//6908 -f 2677//2677 6908//6908 2679//2679 -f 2679//2679 6908//6908 2680//2680 -f 2680//2680 6908//6908 6909//6909 -f 2680//2680 6909//6909 2681//2681 -f 2681//2681 6909//6909 2682//2682 -f 2682//2682 6909//6909 6910//6910 -f 2682//2682 6910//6910 2683//2683 -f 2683//2683 6910//6910 2674//2674 -f 2674//2674 6910//6910 1544//1544 -f 2674//2674 1544//1544 1543//1543 -f 102//102 4178//4178 6911//6911 -f 102//102 6912//6912 6913//6913 -f 6913//6913 6912//6912 6914//6914 -f 4179//4179 4181//4181 6915//6915 -f 4298//4298 4297//4297 6916//6916 -f 4288//4288 6917//6917 6918//6918 -f 6908//6908 1625//1625 4275//4275 -f 6909//6909 6908//6908 6919//6919 -f 1544//1544 6920//6920 4202//4202 -f 4202//4202 6920//6920 6921//6921 -f 4202//4202 6921//6921 4201//4201 -f 4201//4201 6921//6921 6922//6922 -f 6908//6908 4275//4275 6919//6919 -f 6919//6919 4275//4275 4282//4282 -f 6919//6919 4282//4282 6923//6923 -f 6923//6923 4282//4282 4281//4281 -f 6923//6923 4281//4281 6924//6924 -f 6924//6924 4281//4281 4280//4280 -f 6924//6924 4280//4280 6925//6925 -f 6926//6926 4200//4200 6927//6927 -f 6927//6927 4200//4200 4141//4141 -f 6927//6927 4141//4141 6922//6922 -f 6922//6922 4141//4141 4140//4140 -f 6922//6922 4140//4140 4201//4201 -f 4280//4280 4279//4279 6925//6925 -f 6925//6925 4279//4279 4278//4278 -f 6925//6925 4278//4278 6928//6928 -f 6928//6928 4278//4278 4277//4277 -f 6928//6928 4277//4277 6929//6929 -f 6930//6930 4192//4192 6931//6931 -f 6931//6931 4192//4192 4197//4197 -f 6931//6931 4197//4197 6926//6926 -f 6926//6926 4197//4197 4199//4199 -f 6926//6926 4199//4199 4200//4200 -f 4277//4277 4276//4276 6929//6929 -f 6929//6929 4276//4276 4283//4283 -f 6929//6929 4283//4283 6932//6932 -f 6932//6932 4283//4283 4284//4284 -f 6932//6932 4284//4284 6933//6933 -f 4196//4196 4195//4195 6930//6930 -f 6930//6930 4195//4195 4193//4193 -f 6930//6930 4193//4193 4192//4192 -f 4196//4196 6930//6930 4253//4253 -f 4253//4253 6930//6930 6934//6934 -f 4253//4253 6934//6934 6935//6935 -f 4284//4284 4285//4285 6933//6933 -f 6933//6933 4285//4285 4286//4286 -f 6933//6933 4286//4286 6936//6936 -f 6936//6936 4286//4286 4287//4287 -f 6936//6936 4287//4287 6918//6918 -f 6918//6918 4287//4287 4289//4289 -f 6918//6918 4289//4289 4288//4288 -f 6937//6937 4191//4191 6938//6938 -f 6938//6938 4191//4191 4144//4144 -f 6938//6938 4144//4144 6935//6935 -f 6935//6935 4144//4144 4143//4143 -f 6935//6935 4143//4143 4253//4253 -f 4295//4295 6939//6939 4291//4291 -f 4291//4291 6939//6939 6917//6917 -f 4291//4291 6917//6917 4290//4290 -f 4290//4290 6917//6917 4288//4288 -f 6910//6910 6909//6909 6940//6940 -f 6940//6940 6909//6909 6919//6919 -f 6940//6940 6919//6919 6941//6941 -f 6941//6941 6919//6919 6923//6923 -f 6941//6941 6923//6923 6942//6942 -f 6942//6942 6923//6923 6924//6924 -f 6942//6942 6924//6924 6943//6943 -f 6943//6943 6924//6924 6925//6925 -f 6943//6943 6925//6925 6944//6944 -f 6944//6944 6925//6925 6928//6928 -f 6944//6944 6928//6928 6945//6945 -f 6945//6945 6928//6928 6929//6929 -f 6945//6945 6929//6929 6946//6946 -f 6946//6946 6929//6929 6932//6932 -f 6946//6946 6932//6932 6947//6947 -f 6947//6947 6932//6932 6933//6933 -f 6947//6947 6933//6933 6948//6948 -f 6948//6948 6933//6933 6936//6936 -f 6948//6948 6936//6936 6949//6949 -f 6949//6949 6936//6936 6918//6918 -f 6949//6949 6918//6918 6950//6950 -f 6950//6950 6918//6918 6917//6917 -f 6950//6950 6917//6917 6951//6951 -f 6951//6951 6917//6917 6939//6939 -f 6951//6951 6939//6939 6952//6952 -f 1544//1544 6910//6910 6920//6920 -f 6920//6920 6910//6910 6940//6940 -f 6920//6920 6940//6940 6921//6921 -f 6921//6921 6940//6940 6941//6941 -f 6921//6921 6941//6941 6922//6922 -f 6922//6922 6941//6941 6942//6942 -f 6922//6922 6942//6942 6927//6927 -f 6927//6927 6942//6942 6943//6943 -f 6927//6927 6943//6943 6926//6926 -f 6926//6926 6943//6943 6944//6944 -f 6926//6926 6944//6944 6931//6931 -f 6931//6931 6944//6944 6945//6945 -f 6931//6931 6945//6945 6930//6930 -f 6930//6930 6945//6945 6946//6946 -f 6930//6930 6946//6946 6934//6934 -f 6934//6934 6946//6946 6947//6947 -f 6934//6934 6947//6947 6935//6935 -f 6935//6935 6947//6947 6948//6948 -f 6935//6935 6948//6948 6938//6938 -f 6938//6938 6948//6948 6949//6949 -f 6938//6938 6949//6949 6937//6937 -f 6937//6937 6949//6949 6950//6950 -f 6937//6937 6950//6950 6953//6953 -f 6953//6953 6950//6950 6951//6951 -f 6953//6953 6951//6951 6954//6954 -f 6954//6954 6951//6951 6952//6952 -f 6954//6954 6952//6952 6955//6955 -f 4187//4187 4186//4186 6955//6955 -f 6955//6955 4186//4186 4184//4184 -f 6955//6955 4184//4184 6954//6954 -f 6954//6954 4184//4184 4183//4183 -f 6954//6954 4183//4183 6953//6953 -f 6953//6953 4183//4183 4188//4188 -f 6953//6953 4188//4188 6937//6937 -f 6937//6937 4188//4188 4190//4190 -f 6937//6937 4190//4190 4191//4191 -f 4182//4182 4187//4187 6956//6956 -f 6956//6956 4187//4187 6955//6955 -f 6956//6956 6955//6955 6957//6957 -f 6957//6957 6955//6955 6952//6952 -f 6957//6957 6952//6952 6958//6958 -f 6958//6958 6952//6952 6939//6939 -f 6958//6958 6939//6939 4294//4294 -f 4294//4294 6939//6939 4295//4295 -f 4181//4181 4182//4182 6915//6915 -f 6915//6915 4182//4182 6956//6956 -f 6915//6915 6956//6956 6959//6959 -f 6959//6959 6956//6956 6957//6957 -f 6959//6959 6957//6957 6960//6960 -f 6960//6960 6957//6957 6958//6958 -f 6960//6960 6958//6958 4293//4293 -f 4293//4293 6958//6958 4294//4294 -f 4204//4204 4179//4179 6961//6961 -f 6961//6961 4179//4179 6915//6915 -f 6961//6961 6915//6915 6962//6962 -f 6962//6962 6915//6915 6959//6959 -f 6962//6962 6959//6959 6916//6916 -f 6916//6916 6959//6959 6960//6960 -f 6916//6916 6960//6960 4298//4298 -f 4298//4298 6960//6960 4293//4293 -f 4273//4273 4272//4272 6914//6914 -f 6914//6914 4272//4272 4299//4299 -f 6914//6914 4299//4299 6913//6913 -f 6913//6913 4299//4299 102//102 -f 4296//4296 4273//4273 6963//6963 -f 6963//6963 4273//4273 6914//6914 -f 6963//6963 6914//6914 6964//6964 -f 6964//6964 6914//6914 6912//6912 -f 6964//6964 6912//6912 6911//6911 -f 6911//6911 6912//6912 102//102 -f 4178//4178 4204//4204 6911//6911 -f 6911//6911 4204//4204 6961//6961 -f 6911//6911 6961//6961 6964//6964 -f 6964//6964 6961//6961 6962//6962 -f 6964//6964 6962//6962 6963//6963 -f 6963//6963 6962//6962 6916//6916 -f 6963//6963 6916//6916 4296//4296 -f 4296//4296 6916//6916 4297//4297 -f 1550//1550 1552//1552 2741//2741 -f 2741//2741 1552//1552 6965//6965 -f 2741//2741 6965//6965 2756//2756 -f 2756//2756 6965//6965 2757//2757 -f 2757//2757 6965//6965 6966//6966 -f 2757//2757 6966//6966 2758//2758 -f 2758//2758 6966//6966 2753//2753 -f 2753//2753 6966//6966 6967//6967 -f 2753//2753 6967//6967 2754//2754 -f 2754//2754 6967//6967 2755//2755 -f 2755//2755 6967//6967 1522//1522 -f 2755//2755 1522//1522 1521//1521 -f 10//10 3750//3750 6968//6968 -f 10//10 6969//6969 6970//6970 -f 6970//6970 6969//6969 6971//6971 -f 3754//3754 3752//3752 6972//6972 -f 4147//4147 4146//4146 6973//6973 -f 6965//6965 1552//1552 4149//4149 -f 6966//6966 6965//6965 6974//6974 -f 1522//1522 6975//6975 3775//3775 -f 3775//3775 6975//6975 6976//6976 -f 3775//3775 6976//6976 3774//3774 -f 3774//3774 6976//6976 6977//6977 -f 6965//6965 4149//4149 6974//6974 -f 6974//6974 4149//4149 4150//4150 -f 6974//6974 4150//4150 6978//6978 -f 6978//6978 4150//4150 4155//4155 -f 6978//6978 4155//4155 6979//6979 -f 6979//6979 4155//4155 4154//4154 -f 6979//6979 4154//4154 6980//6980 -f 6981//6981 3773//3773 6982//6982 -f 6982//6982 3773//3773 3745//3745 -f 6982//6982 3745//3745 6977//6977 -f 6977//6977 3745//3745 3744//3744 -f 6977//6977 3744//3744 3774//3774 -f 4154//4154 4152//4152 6980//6980 -f 6980//6980 4152//4152 4151//4151 -f 6980//6980 4151//4151 6983//6983 -f 6983//6983 4151//4151 4157//4157 -f 6983//6983 4157//4157 6984//6984 -f 6985//6985 3765//3765 6986//6986 -f 6986//6986 3765//3765 3770//3770 -f 6986//6986 3770//3770 6981//6981 -f 6981//6981 3770//3770 3772//3772 -f 6981//6981 3772//3772 3773//3773 -f 4157//4157 4156//4156 6984//6984 -f 6984//6984 4156//4156 4162//4162 -f 6984//6984 4162//4162 6987//6987 -f 6987//6987 4162//4162 4160//4160 -f 6987//6987 4160//4160 6988//6988 -f 3769//3769 3768//3768 6985//6985 -f 6985//6985 3768//3768 3766//3766 -f 6985//6985 3766//3766 3765//3765 -f 3769//3769 6985//6985 3854//3854 -f 3854//3854 6985//6985 6989//6989 -f 3854//3854 6989//6989 6990//6990 -f 4160//4160 4159//4159 6988//6988 -f 6988//6988 4159//4159 4166//4166 -f 6988//6988 4166//4166 6991//6991 -f 6991//6991 4166//4166 4164//4164 -f 6991//6991 4164//4164 6992//6992 -f 6993//6993 3764//3764 6994//6994 -f 6994//6994 3764//3764 3748//3748 -f 6994//6994 3748//3748 6990//6990 -f 6990//6990 3748//3748 3747//3747 -f 6990//6990 3747//3747 3854//3854 -f 4167//4167 6995//6995 4168//4168 -f 4168//4168 6995//6995 6996//6996 -f 4168//4168 6996//6996 4170//4170 -f 4170//4170 6996//6996 6992//6992 -f 4170//4170 6992//6992 4163//4163 -f 4163//4163 6992//6992 4164//4164 -f 6967//6967 6966//6966 6997//6997 -f 6997//6997 6966//6966 6974//6974 -f 6997//6997 6974//6974 6998//6998 -f 6998//6998 6974//6974 6978//6978 -f 6998//6998 6978//6978 6999//6999 -f 6999//6999 6978//6978 6979//6979 -f 6999//6999 6979//6979 7000//7000 -f 7000//7000 6979//6979 6980//6980 -f 7000//7000 6980//6980 7001//7001 -f 7001//7001 6980//6980 6983//6983 -f 7001//7001 6983//6983 7002//7002 -f 7002//7002 6983//6983 6984//6984 -f 7002//7002 6984//6984 7003//7003 -f 7003//7003 6984//6984 6987//6987 -f 7003//7003 6987//6987 7004//7004 -f 7004//7004 6987//6987 6988//6988 -f 7004//7004 6988//6988 7005//7005 -f 7005//7005 6988//6988 6991//6991 -f 7005//7005 6991//6991 7006//7006 -f 7006//7006 6991//6991 6992//6992 -f 7006//7006 6992//6992 7007//7007 -f 7007//7007 6992//6992 6996//6996 -f 7007//7007 6996//6996 7008//7008 -f 7008//7008 6996//6996 6995//6995 -f 7008//7008 6995//6995 7009//7009 -f 1522//1522 6967//6967 6975//6975 -f 6975//6975 6967//6967 6997//6997 -f 6975//6975 6997//6997 6976//6976 -f 6976//6976 6997//6997 6998//6998 -f 6976//6976 6998//6998 6977//6977 -f 6977//6977 6998//6998 6999//6999 -f 6977//6977 6999//6999 6982//6982 -f 6982//6982 6999//6999 7000//7000 -f 6982//6982 7000//7000 6981//6981 -f 6981//6981 7000//7000 7001//7001 -f 6981//6981 7001//7001 6986//6986 -f 6986//6986 7001//7001 7002//7002 -f 6986//6986 7002//7002 6985//6985 -f 6985//6985 7002//7002 7003//7003 -f 6985//6985 7003//7003 6989//6989 -f 6989//6989 7003//7003 7004//7004 -f 6989//6989 7004//7004 6990//6990 -f 6990//6990 7004//7004 7005//7005 -f 6990//6990 7005//7005 6994//6994 -f 6994//6994 7005//7005 7006//7006 -f 6994//6994 7006//7006 6993//6993 -f 6993//6993 7006//7006 7007//7007 -f 6993//6993 7007//7007 7010//7010 -f 7010//7010 7007//7007 7008//7008 -f 7010//7010 7008//7008 7011//7011 -f 7011//7011 7008//7008 7009//7009 -f 7011//7011 7009//7009 7012//7012 -f 3760//3760 3759//3759 7012//7012 -f 7012//7012 3759//3759 3757//3757 -f 7012//7012 3757//3757 7011//7011 -f 7011//7011 3757//3757 3756//3756 -f 7011//7011 3756//3756 7010//7010 -f 7010//7010 3756//3756 3761//3761 -f 7010//7010 3761//3761 6993//6993 -f 6993//6993 3761//3761 3763//3763 -f 6993//6993 3763//3763 3764//3764 -f 3751//3751 3760//3760 7013//7013 -f 7013//7013 3760//3760 7012//7012 -f 7013//7013 7012//7012 7014//7014 -f 7014//7014 7012//7012 7009//7009 -f 7014//7014 7009//7009 7015//7015 -f 7015//7015 7009//7009 6995//6995 -f 7015//7015 6995//6995 4172//4172 -f 4172//4172 6995//6995 4167//4167 -f 3752//3752 3751//3751 6972//6972 -f 6972//6972 3751//3751 7013//7013 -f 6972//6972 7013//7013 7016//7016 -f 7016//7016 7013//7013 7014//7014 -f 7016//7016 7014//7014 7017//7017 -f 7017//7017 7014//7014 7015//7015 -f 7017//7017 7015//7015 4171//4171 -f 4171//4171 7015//7015 4172//4172 -f 3755//3755 3754//3754 7018//7018 -f 7018//7018 3754//3754 6972//6972 -f 7018//7018 6972//6972 7019//7019 -f 7019//7019 6972//6972 7016//7016 -f 7019//7019 7016//7016 6973//6973 -f 6973//6973 7016//7016 7017//7017 -f 6973//6973 7017//7017 4147//4147 -f 4147//4147 7017//7017 4171//4171 -f 4177//4177 4176//4176 6971//6971 -f 6971//6971 4176//4176 4175//4175 -f 6971//6971 4175//4175 6970//6970 -f 6970//6970 4175//4175 10//10 -f 4173//4173 4177//4177 7020//7020 -f 7020//7020 4177//4177 6971//6971 -f 7020//7020 6971//6971 7021//7021 -f 7021//7021 6971//6971 6969//6969 -f 7021//7021 6969//6969 6968//6968 -f 6968//6968 6969//6969 10//10 -f 3750//3750 3755//3755 6968//6968 -f 6968//6968 3755//3755 7018//7018 -f 6968//6968 7018//7018 7021//7021 -f 7021//7021 7018//7018 7019//7019 -f 7021//7021 7019//7019 7020//7020 -f 7020//7020 7019//7019 6973//6973 -f 7020//7020 6973//6973 4173//4173 -f 4173//4173 6973//6973 4146//4146 -f 2535//2535 1659//1659 1658//1658 -f 2588//2588 2574//2574 2573//2573 -f 2535//2535 1658//1658 2538//2538 -f 2538//2538 1658//1658 2581//2581 -f 2538//2538 2581//2581 2539//2539 -f 2539//2539 2581//2581 2589//2589 -f 2539//2539 2589//2589 2569//2569 -f 2588//2588 2573//2573 2589//2589 -f 2589//2589 2573//2573 2571//2571 -f 2589//2589 2571//2571 2569//2569 -f 2568//2568 2570//2570 2585//2585 -f 2585//2585 2570//2570 2572//2572 -f 2585//2585 2572//2572 2586//2586 -f 2586//2586 2572//2572 2574//2574 -f 2586//2586 2574//2574 2587//2587 -f 2587//2587 2574//2574 2588//2588 -f 1689//1689 1688//1688 2537//2537 -f 1689//1689 2537//2537 2583//2583 -f 2583//2583 2537//2537 2536//2536 -f 2583//2583 2536//2536 2585//2585 -f 2585//2585 2536//2536 2540//2540 -f 2585//2585 2540//2540 2568//2568 -f 2533//2533 1645//1645 1644//1644 -f 2667//2667 2578//2578 2576//2576 -f 2533//2533 1644//1644 2534//2534 -f 2534//2534 1644//1644 2639//2639 -f 2534//2534 2639//2639 2556//2556 -f 2556//2556 2639//2639 2638//2638 -f 2556//2556 2638//2638 2554//2554 -f 2667//2667 2576//2576 2638//2638 -f 2638//2638 2576//2576 2575//2575 -f 2638//2638 2575//2575 2554//2554 -f 2553//2553 2552//2552 2664//2664 -f 2664//2664 2552//2552 2577//2577 -f 2664//2664 2577//2577 2665//2665 -f 2665//2665 2577//2577 2578//2578 -f 2665//2665 2578//2578 2666//2666 -f 2666//2666 2578//2578 2667//2667 -f 1661//1661 1660//1660 2558//2558 -f 1661//1661 2558//2558 2663//2663 -f 2663//2663 2558//2558 2557//2557 -f 2663//2663 2557//2557 2664//2664 -f 2664//2664 2557//2557 2555//2555 -f 2664//2664 2555//2555 2553//2553 -f 2529//2529 1674//1674 1678//1678 -f 2631//2631 2561//2561 2560//2560 -f 2529//2529 1678//1678 2530//2530 -f 2530//2530 1678//1678 2625//2625 -f 2530//2530 2625//2625 2550//2550 -f 2550//2550 2625//2625 2632//2632 -f 2550//2550 2632//2632 2551//2551 -f 2631//2631 2560//2560 2632//2632 -f 2632//2632 2560//2560 2548//2548 -f 2632//2632 2548//2548 2551//2551 -f 2547//2547 2546//2546 2628//2628 -f 2628//2628 2546//2546 2559//2559 -f 2628//2628 2559//2559 2629//2629 -f 2629//2629 2559//2559 2561//2561 -f 2629//2629 2561//2561 2630//2630 -f 2630//2630 2561//2561 2631//2631 -f 1647//1647 1646//1646 2531//2531 -f 1647//1647 2531//2531 2626//2626 -f 2626//2626 2531//2531 2532//2532 -f 2626//2626 2532//2532 2628//2628 -f 2628//2628 2532//2532 2549//2549 -f 2628//2628 2549//2549 2547//2547 -f 2527//2527 1687//1687 1686//1686 -f 2612//2612 2567//2567 2565//2565 -f 2527//2527 1686//1686 2528//2528 -f 2528//2528 1686//1686 2614//2614 -f 2528//2528 2614//2614 2543//2543 -f 2543//2543 2614//2614 2613//2613 -f 2543//2543 2613//2613 2562//2562 -f 2612//2612 2565//2565 2613//2613 -f 2613//2613 2565//2565 2563//2563 -f 2613//2613 2563//2563 2562//2562 -f 2541//2541 2564//2564 2615//2615 -f 2615//2615 2564//2564 2566//2566 -f 2615//2615 2566//2566 2616//2616 -f 2616//2616 2566//2566 2567//2567 -f 2616//2616 2567//2567 2617//2617 -f 2617//2617 2567//2567 2612//2612 -f 1672//1672 1671//1671 2545//2545 -f 1672//1672 2545//2545 2600//2600 -f 2600//2600 2545//2545 2544//2544 -f 2600//2600 2544//2544 2615//2615 -f 2615//2615 2544//2544 2542//2542 -f 2615//2615 2542//2542 2541//2541 -f 1975//1975 969//969 1977//1977 -f 1977//1977 969//969 968//968 -f 1977//1977 968//968 1979//1979 -f 1979//1979 968//968 1012//1012 -f 1979//1979 1012//1012 1981//1981 -f 1981//1981 1012//1012 1011//1011 -f 1981//1981 1011//1011 1983//1983 -f 1983//1983 1011//1011 1001//1001 -f 1983//1983 1001//1001 1985//1985 -f 1985//1985 1001//1001 1000//1000 -f 1985//1985 1000//1000 1987//1987 -f 1987//1987 1000//1000 999//999 -f 1987//1987 999//999 1989//1989 -f 1989//1989 999//999 998//998 -f 1989//1989 998//998 1991//1991 -f 1991//1991 998//998 997//997 -f 1991//1991 997//997 1993//1993 -f 1993//1993 997//997 1010//1010 -f 1993//1993 1010//1010 1995//1995 -f 1995//1995 1010//1010 1009//1009 -f 1995//1995 1009//1009 1997//1997 -f 1997//1997 1009//1009 1008//1008 -f 1997//1997 1008//1008 1999//1999 -f 1999//1999 1008//1008 996//996 -f 1999//1999 996//996 2001//2001 -f 2001//2001 996//996 995//995 -f 2001//2001 995//995 2003//2003 -f 2003//2003 995//995 994//994 -f 2003//2003 994//994 2005//2005 -f 2005//2005 994//994 981//981 -f 2005//2005 981//981 2007//2007 -f 2007//2007 981//981 980//980 -f 2007//2007 980//980 2009//2009 -f 2009//2009 980//980 979//979 -f 2009//2009 979//979 2011//2011 -f 2011//2011 979//979 977//977 -f 2011//2011 977//977 2013//2013 -f 2013//2013 977//977 978//978 -f 2013//2013 978//978 2015//2015 -f 2015//2015 978//978 1019//1019 -f 2015//2015 1019//1019 2017//2017 -f 2017//2017 1019//1019 1020//1020 -f 2017//2017 1020//1020 2019//2019 -f 2019//2019 1020//1020 992//992 -f 2019//2019 992//992 2021//2021 -f 2021//2021 992//992 991//991 -f 2021//2021 991//991 2023//2023 -f 2023//2023 991//991 1013//1013 -f 2023//2023 1013//1013 2025//2025 -f 2025//2025 1013//1013 1027//1027 -f 2025//2025 1027//1027 2027//2027 -f 2027//2027 1027//1027 1029//1029 -f 2027//2027 1029//1029 2029//2029 -f 2029//2029 1029//1029 1031//1031 -f 2029//2029 1031//1031 2031//2031 -f 2031//2031 1031//1031 1026//1026 -f 2031//2031 1026//1026 2033//2033 -f 2033//2033 1026//1026 1025//1025 -f 2033//2033 1025//1025 2035//2035 -f 2035//2035 1025//1025 1024//1024 -f 2035//2035 1024//1024 2037//2037 -f 2037//2037 1024//1024 1021//1021 -f 2037//2037 1021//1021 2039//2039 -f 2039//2039 1021//1021 975//975 -f 2039//2039 975//975 2041//2041 -f 2041//2041 975//975 973//973 -f 2041//2041 973//973 2043//2043 -f 2043//2043 973//973 972//972 -f 2043//2043 972//972 2045//2045 -f 2045//2045 972//972 971//971 -f 2045//2045 971//971 1973//1973 -f 1973//1973 971//971 970//970 -f 1973//1973 970//970 1975//1975 -f 1975//1975 970//970 969//969 -f 2197//2197 974//974 2199//2199 -f 2199//2199 974//974 976//976 -f 2199//2199 976//976 2201//2201 -f 2201//2201 976//976 1016//1016 -f 2201//2201 1016//1016 2203//2203 -f 2203//2203 1016//1016 1015//1015 -f 2203//2203 1015//1015 2205//2205 -f 2205//2205 1015//1015 1014//1014 -f 2205//2205 1014//1014 2207//2207 -f 2207//2207 1014//1014 1023//1023 -f 2207//2207 1023//1023 2209//2209 -f 2209//2209 1023//1023 1022//1022 -f 2209//2209 1022//1022 2211//2211 -f 2211//2211 1022//1022 1033//1033 -f 2211//2211 1033//1033 2213//2213 -f 2213//2213 1033//1033 1032//1032 -f 2213//2213 1032//1032 2215//2215 -f 2215//2215 1032//1032 1030//1030 -f 2215//2215 1030//1030 2217//2217 -f 2217//2217 1030//1030 1028//1028 -f 2217//2217 1028//1028 2219//2219 -f 2219//2219 1028//1028 993//993 -f 2219//2219 993//993 2221//2221 -f 2221//2221 993//993 1018//1018 -f 2221//2221 1018//1018 2223//2223 -f 2223//2223 1018//1018 1017//1017 -f 2223//2223 1017//1017 2225//2225 -f 2225//2225 1017//1017 1007//1007 -f 2225//2225 1007//1007 2227//2227 -f 2227//2227 1007//1007 1006//1006 -f 2227//2227 1006//1006 2229//2229 -f 2229//2229 1006//1006 1005//1005 -f 2229//2229 1005//1005 2231//2231 -f 2231//2231 1005//1005 1004//1004 -f 2231//2231 1004//1004 2233//2233 -f 2233//2233 1004//1004 1003//1003 -f 2233//2233 1003//1003 2235//2235 -f 2235//2235 1003//1003 1002//1002 -f 2235//2235 1002//1002 2237//2237 -f 2237//2237 1002//1002 967//967 -f 2237//2237 967//967 2239//2239 -f 2239//2239 967//967 966//966 -f 2239//2239 966//966 2241//2241 -f 2241//2241 966//966 965//965 -f 2241//2241 965//965 2243//2243 -f 2243//2243 965//965 963//963 -f 2243//2243 963//963 2245//2245 -f 2245//2245 963//963 962//962 -f 2245//2245 962//962 2247//2247 -f 2247//2247 962//962 990//990 -f 2247//2247 990//990 2249//2249 -f 2249//2249 990//990 989//989 -f 2249//2249 989//989 2251//2251 -f 2251//2251 989//989 988//988 -f 2251//2251 988//988 2253//2253 -f 2253//2253 988//988 987//987 -f 2253//2253 987//987 2255//2255 -f 2255//2255 987//987 986//986 -f 2255//2255 986//986 2257//2257 -f 2257//2257 986//986 985//985 -f 2257//2257 985//985 2259//2259 -f 2259//2259 985//985 984//984 -f 2259//2259 984//984 2261//2261 -f 2261//2261 984//984 983//983 -f 2261//2261 983//983 2263//2263 -f 2263//2263 983//983 982//982 -f 2263//2263 982//982 2265//2265 -f 2265//2265 982//982 959//959 -f 2265//2265 959//959 2267//2267 -f 2267//2267 959//959 960//960 -f 2267//2267 960//960 2195//2195 -f 2195//2195 960//960 961//961 -f 2195//2195 961//961 2197//2197 -f 2197//2197 961//961 974//974 -f 2086//2086 1036//1036 2088//2088 -f 2088//2088 1036//1036 1035//1035 -f 2088//2088 1035//1035 2090//2090 -f 2090//2090 1035//1035 1034//1034 -f 2090//2090 1034//1034 2092//2092 -f 2092//2092 1034//1034 1064//1064 -f 2092//2092 1064//1064 2094//2094 -f 2094//2094 1064//1064 1063//1063 -f 2094//2094 1063//1063 2096//2096 -f 2096//2096 1063//1063 1062//1062 -f 2096//2096 1062//1062 2098//2098 -f 2098//2098 1062//1062 1061//1061 -f 2098//2098 1061//1061 2100//2100 -f 2100//2100 1061//1061 1060//1060 -f 2100//2100 1060//1060 2102//2102 -f 2102//2102 1060//1060 1059//1059 -f 2102//2102 1059//1059 2104//2104 -f 2104//2104 1059//1059 1071//1071 -f 2104//2104 1071//1071 2106//2106 -f 2106//2106 1071//1071 1070//1070 -f 2106//2106 1070//1070 2108//2108 -f 2108//2108 1070//1070 1069//1069 -f 2108//2108 1069//1069 2110//2110 -f 2110//2110 1069//1069 1066//1066 -f 2110//2110 1066//1066 2112//2112 -f 2112//2112 1066//1066 1065//1065 -f 2112//2112 1065//1065 2114//2114 -f 2114//2114 1065//1065 1068//1068 -f 2114//2114 1068//1068 2116//2116 -f 2116//2116 1068//1068 1067//1067 -f 2116//2116 1067//1067 2118//2118 -f 2118//2118 1067//1067 1058//1058 -f 2118//2118 1058//1058 2120//2120 -f 2120//2120 1058//1058 1057//1057 -f 2120//2120 1057//1057 2122//2122 -f 2122//2122 1057//1057 1056//1056 -f 2122//2122 1056//1056 2124//2124 -f 2124//2124 1056//1056 1055//1055 -f 2124//2124 1055//1055 2126//2126 -f 2126//2126 1055//1055 1054//1054 -f 2126//2126 1054//1054 2128//2128 -f 2128//2128 1054//1054 1053//1053 -f 2128//2128 1053//1053 2130//2130 -f 2130//2130 1053//1053 1052//1052 -f 2130//2130 1052//1052 2132//2132 -f 2132//2132 1052//1052 1044//1044 -f 2132//2132 1044//1044 2134//2134 -f 2134//2134 1044//1044 1043//1043 -f 2134//2134 1043//1043 2136//2136 -f 2136//2136 1043//1043 1051//1051 -f 2136//2136 1051//1051 2138//2138 -f 2138//2138 1051//1051 1050//1050 -f 2138//2138 1050//1050 2140//2140 -f 2140//2140 1050//1050 1049//1049 -f 2140//2140 1049//1049 2142//2142 -f 2142//2142 1049//1049 1048//1048 -f 2142//2142 1048//1048 2144//2144 -f 2144//2144 1048//1048 1047//1047 -f 2144//2144 1047//1047 2146//2146 -f 2146//2146 1047//1047 1046//1046 -f 2146//2146 1046//1046 2148//2148 -f 2148//2148 1046//1046 1042//1042 -f 2148//2148 1042//1042 2150//2150 -f 2150//2150 1042//1042 1041//1041 -f 2150//2150 1041//1041 2152//2152 -f 2152//2152 1041//1041 1040//1040 -f 2152//2152 1040//1040 2154//2154 -f 2154//2154 1040//1040 1039//1039 -f 2154//2154 1039//1039 2156//2156 -f 2156//2156 1039//1039 1038//1038 -f 2156//2156 1038//1038 2084//2084 -f 2084//2084 1038//1038 1037//1037 -f 2084//2084 1037//1037 2086//2086 -f 2086//2086 1037//1037 1036//1036 -f 2308//2308 1086//1086 2310//2310 -f 2310//2310 1086//1086 1097//1097 -f 2310//2310 1097//1097 2312//2312 -f 2312//2312 1097//1097 1096//1096 -f 2312//2312 1096//1096 2314//2314 -f 2314//2314 1096//1096 1084//1084 -f 2314//2314 1084//1084 2316//2316 -f 2316//2316 1084//1084 1083//1083 -f 2316//2316 1083//1083 2318//2318 -f 2318//2318 1083//1083 1082//1082 -f 2318//2318 1082//1082 2320//2320 -f 2320//2320 1082//1082 1073//1073 -f 2320//2320 1073//1073 2322//2322 -f 2322//2322 1073//1073 1072//1072 -f 2322//2322 1072//1072 2324//2324 -f 2324//2324 1072//1072 1095//1095 -f 2324//2324 1095//1095 2326//2326 -f 2326//2326 1095//1095 1094//1094 -f 2326//2326 1094//1094 2328//2328 -f 2328//2328 1094//1094 1093//1093 -f 2328//2328 1093//1093 2330//2330 -f 2330//2330 1093//1093 1081//1081 -f 2330//2330 1081//1081 2332//2332 -f 2332//2332 1081//1081 1080//1080 -f 2332//2332 1080//1080 2334//2334 -f 2334//2334 1080//1080 1079//1079 -f 2334//2334 1079//1079 2336//2336 -f 2336//2336 1079//1079 1092//1092 -f 2336//2336 1092//1092 2338//2338 -f 2338//2338 1092//1092 1091//1091 -f 2338//2338 1091//1091 2340//2340 -f 2340//2340 1091//1091 1090//1090 -f 2340//2340 1090//1090 2342//2342 -f 2342//2342 1090//1090 1109//1109 -f 2342//2342 1109//1109 2344//2344 -f 2344//2344 1109//1109 1108//1108 -f 2344//2344 1108//1108 2346//2346 -f 2346//2346 1108//1108 1107//1107 -f 2346//2346 1107//1107 2348//2348 -f 2348//2348 1107//1107 1106//1106 -f 2348//2348 1106//1106 2350//2350 -f 2350//2350 1106//1106 1105//1105 -f 2350//2350 1105//1105 2352//2352 -f 2352//2352 1105//1105 1104//1104 -f 2352//2352 1104//1104 2354//2354 -f 2354//2354 1104//1104 1077//1077 -f 2354//2354 1077//1077 2356//2356 -f 2356//2356 1077//1077 1076//1076 -f 2356//2356 1076//1076 2358//2358 -f 2358//2358 1076//1076 1103//1103 -f 2358//2358 1103//1103 2360//2360 -f 2360//2360 1103//1103 1102//1102 -f 2360//2360 1102//1102 2362//2362 -f 2362//2362 1102//1102 1101//1101 -f 2362//2362 1101//1101 2364//2364 -f 2364//2364 1101//1101 1100//1100 -f 2364//2364 1100//1100 2366//2366 -f 2366//2366 1100//1100 1099//1099 -f 2366//2366 1099//1099 2368//2368 -f 2368//2368 1099//1099 1098//1098 -f 2368//2368 1098//1098 2370//2370 -f 2370//2370 1098//1098 1089//1089 -f 2370//2370 1089//1089 2372//2372 -f 2372//2372 1089//1089 1088//1088 -f 2372//2372 1088//1088 2374//2374 -f 2374//2374 1088//1088 1087//1087 -f 2374//2374 1087//1087 2376//2376 -f 2376//2376 1087//1087 1075//1075 -f 2376//2376 1075//1075 2378//2378 -f 2378//2378 1075//1075 1074//1074 -f 2378//2378 1074//1074 2306//2306 -f 2306//2306 1074//1074 1085//1085 -f 2306//2306 1085//1085 2308//2308 -f 2308//2308 1085//1085 1086//1086 -f 1864//1864 1120//1120 1866//1866 -f 1866//1866 1120//1120 1134//1134 -f 1866//1866 1134//1134 1868//1868 -f 1868//1868 1134//1134 1133//1133 -f 1868//1868 1133//1133 1870//1870 -f 1870//1870 1133//1133 1119//1119 -f 1870//1870 1119//1119 1872//1872 -f 1872//1872 1119//1119 1118//1118 -f 1872//1872 1118//1118 1874//1874 -f 1874//1874 1118//1118 1117//1117 -f 1874//1874 1117//1117 1876//1876 -f 1876//1876 1117//1117 1110//1110 -f 1876//1876 1110//1110 1878//1878 -f 1878//1878 1110//1110 1111//1111 -f 1878//1878 1111//1111 1880//1880 -f 1880//1880 1111//1111 1112//1112 -f 1880//1880 1112//1112 1882//1882 -f 1882//1882 1112//1112 1126//1126 -f 1882//1882 1126//1126 1884//1884 -f 1884//1884 1126//1126 1125//1125 -f 1884//1884 1125//1125 1886//1886 -f 1886//1886 1125//1125 1124//1124 -f 1886//1886 1124//1124 1888//1888 -f 1888//1888 1124//1124 1116//1116 -f 1888//1888 1116//1116 1890//1890 -f 1890//1890 1116//1116 1115//1115 -f 1890//1890 1115//1115 1892//1892 -f 1892//1892 1115//1115 1144//1144 -f 1892//1892 1144//1144 1894//1894 -f 1894//1894 1144//1144 1143//1143 -f 1894//1894 1143//1143 1896//1896 -f 1896//1896 1143//1143 1142//1142 -f 1896//1896 1142//1142 1898//1898 -f 1898//1898 1142//1142 1147//1147 -f 1898//1898 1147//1147 1900//1900 -f 1900//1900 1147//1147 1146//1146 -f 1900//1900 1146//1146 1902//1902 -f 1902//1902 1146//1146 1145//1145 -f 1902//1902 1145//1145 1904//1904 -f 1904//1904 1145//1145 1141//1141 -f 1904//1904 1141//1141 1906//1906 -f 1906//1906 1141//1141 1140//1140 -f 1906//1906 1140//1140 1908//1908 -f 1908//1908 1140//1140 1139//1139 -f 1908//1908 1139//1139 1910//1910 -f 1910//1910 1139//1139 1138//1138 -f 1910//1910 1138//1138 1912//1912 -f 1912//1912 1138//1138 1137//1137 -f 1912//1912 1137//1137 1914//1914 -f 1914//1914 1137//1137 1135//1135 -f 1914//1914 1135//1135 1916//1916 -f 1916//1916 1135//1135 1132//1132 -f 1916//1916 1132//1132 1918//1918 -f 1918//1918 1132//1132 1131//1131 -f 1918//1918 1131//1131 1920//1920 -f 1920//1920 1131//1131 1130//1130 -f 1920//1920 1130//1130 1922//1922 -f 1922//1922 1130//1130 1129//1129 -f 1922//1922 1129//1129 1924//1924 -f 1924//1924 1129//1129 1128//1128 -f 1924//1924 1128//1128 1926//1926 -f 1926//1926 1128//1128 1127//1127 -f 1926//1926 1127//1127 1928//1928 -f 1928//1928 1127//1127 1123//1123 -f 1928//1928 1123//1123 1930//1930 -f 1930//1930 1123//1123 1122//1122 -f 1930//1930 1122//1122 1932//1932 -f 1932//1932 1122//1122 1121//1121 -f 1932//1932 1121//1121 1934//1934 -f 1934//1934 1121//1121 1114//1114 -f 1934//1934 1114//1114 1862//1862 -f 1862//1862 1114//1114 1113//1113 -f 1862//1862 1113//1113 1864//1864 -f 1864//1864 1113//1113 1120//1120 -f 2419//2419 1191//1191 2421//2421 -f 2421//2421 1191//1191 1190//1190 -f 2421//2421 1190//1190 2423//2423 -f 2423//2423 1190//1190 1189//1189 -f 2423//2423 1189//1189 2425//2425 -f 2425//2425 1189//1189 1188//1188 -f 2425//2425 1188//1188 2427//2427 -f 2427//2427 1188//1188 1187//1187 -f 2427//2427 1187//1187 2429//2429 -f 2429//2429 1187//1187 1175//1175 -f 2429//2429 1175//1175 2431//2431 -f 2431//2431 1175//1175 1174//1174 -f 2431//2431 1174//1174 2433//2433 -f 2433//2433 1174//1174 1173//1173 -f 2433//2433 1173//1173 2435//2435 -f 2435//2435 1173//1173 1169//1169 -f 2435//2435 1169//1169 2437//2437 -f 2437//2437 1169//1169 1158//1158 -f 2437//2437 1158//1158 2439//2439 -f 2439//2439 1158//1158 1157//1157 -f 2439//2439 1157//1157 2441//2441 -f 2441//2441 1157//1157 1186//1186 -f 2441//2441 1186//1186 2443//2443 -f 2443//2443 1186//1186 1185//1185 -f 2443//2443 1185//1185 2445//2445 -f 2445//2445 1185//1185 1184//1184 -f 2445//2445 1184//1184 2447//2447 -f 2447//2447 1184//1184 1183//1183 -f 2447//2447 1183//1183 2449//2449 -f 2449//2449 1183//1183 1182//1182 -f 2449//2449 1182//1182 2451//2451 -f 2451//2451 1182//1182 1181//1181 -f 2451//2451 1181//1181 2453//2453 -f 2453//2453 1181//1181 1180//1180 -f 2453//2453 1180//1180 2455//2455 -f 2455//2455 1180//1180 1179//1179 -f 2455//2455 1179//1179 2457//2457 -f 2457//2457 1179//1179 1178//1178 -f 2457//2457 1178//1178 2459//2459 -f 2459//2459 1178//1178 1172//1172 -f 2459//2459 1172//1172 2461//2461 -f 2461//2461 1172//1172 1171//1171 -f 2461//2461 1171//1171 2463//2463 -f 2463//2463 1171//1171 1170//1170 -f 2463//2463 1170//1170 2465//2465 -f 2465//2465 1170//1170 1156//1156 -f 2465//2465 1156//1156 2467//2467 -f 2467//2467 1156//1156 1155//1155 -f 2467//2467 1155//1155 2469//2469 -f 2469//2469 1155//1155 1168//1168 -f 2469//2469 1168//1168 2471//2471 -f 2471//2471 1168//1168 1167//1167 -f 2471//2471 1167//1167 2473//2473 -f 2473//2473 1167//1167 1166//1166 -f 2473//2473 1166//1166 2475//2475 -f 2475//2475 1166//1166 1164//1164 -f 2475//2475 1164//1164 2477//2477 -f 2477//2477 1164//1164 1163//1163 -f 2477//2477 1163//1163 2479//2479 -f 2479//2479 1163//1163 1177//1177 -f 2479//2479 1177//1177 2481//2481 -f 2481//2481 1177//1177 1176//1176 -f 2481//2481 1176//1176 2483//2483 -f 2483//2483 1176//1176 1162//1162 -f 2483//2483 1162//1162 2485//2485 -f 2485//2485 1162//1162 1161//1161 -f 2485//2485 1161//1161 2487//2487 -f 2487//2487 1161//1161 1160//1160 -f 2487//2487 1160//1160 2489//2489 -f 2489//2489 1160//1160 1159//1159 -f 2489//2489 1159//1159 2417//2417 -f 2417//2417 1159//1159 1165//1165 -f 2417//2417 1165//1165 2419//2419 -f 2419//2419 1165//1165 1191//1191 -f 1699//1699 2055//2055 1700//1700 -f 1700//1700 2055//2055 2056//2056 -f 1700//1700 2056//2056 1701//1701 -f 1701//1701 2056//2056 2057//2057 -f 1701//1701 2057//2057 1706//1706 -f 1706//1706 2057//2057 2058//2058 -f 1706//1706 2058//2058 1710//1710 -f 1710//1710 2058//2058 2059//2059 -f 1710//1710 2059//2059 1712//1712 -f 1712//1712 2059//2059 2060//2060 -f 1712//1712 2060//2060 1716//1716 -f 1716//1716 2060//2060 2061//2061 -f 1716//1716 2061//2061 1720//1720 -f 1720//1720 2061//2061 2062//2062 -f 1720//1720 2062//2062 1722//1722 -f 1722//1722 2062//2062 2063//2063 -f 1722//1722 2063//2063 1727//1727 -f 1727//1727 2063//2063 2064//2064 -f 1727//1727 2064//2064 1729//1729 -f 1729//1729 2064//2064 2065//2065 -f 1729//1729 2065//2065 1734//1734 -f 1734//1734 2065//2065 2066//2066 -f 1734//1734 2066//2066 1736//1736 -f 1736//1736 2066//2066 2067//2067 -f 1736//1736 2067//2067 1741//1741 -f 1741//1741 2067//2067 2068//2068 -f 1741//1741 2068//2068 1744//1744 -f 1744//1744 2068//2068 2069//2069 -f 1744//1744 2069//2069 1747//1747 -f 1747//1747 2069//2069 2070//2070 -f 1747//1747 2070//2070 1750//1750 -f 1750//1750 2070//2070 2071//2071 -f 1750//1750 2071//2071 1753//1753 -f 1753//1753 2071//2071 2072//2072 -f 1753//1753 2072//2072 1757//1757 -f 1757//1757 2072//2072 2073//2073 -f 1757//1757 2073//2073 1760//1760 -f 1760//1760 2073//2073 2074//2074 -f 1760//1760 2074//2074 1761//1761 -f 1761//1761 2074//2074 2075//2075 -f 1761//1761 2075//2075 1762//1762 -f 1762//1762 2075//2075 2076//2076 -f 1762//1762 2076//2076 1763//1763 -f 1763//1763 2076//2076 2077//2077 -f 1763//1763 2077//2077 1764//1764 -f 1764//1764 2077//2077 2078//2078 -f 1764//1764 2078//2078 1765//1765 -f 1765//1765 2078//2078 2079//2079 -f 1765//1765 2079//2079 1766//1766 -f 1766//1766 2079//2079 2080//2080 -f 1766//1766 2080//2080 1767//1767 -f 1767//1767 2080//2080 2081//2081 -f 1767//1767 2081//2081 1768//1768 -f 1768//1768 2081//2081 2082//2082 -f 1768//1768 2082//2082 1769//1769 -f 1769//1769 2082//2082 2046//2046 -f 1769//1769 2046//2046 1770//1770 -f 1770//1770 2046//2046 2047//2047 -f 1770//1770 2047//2047 1771//1771 -f 1771//1771 2047//2047 2048//2048 -f 1771//1771 2048//2048 1772//1772 -f 1772//1772 2048//2048 2049//2049 -f 1772//1772 2049//2049 1773//1773 -f 1773//1773 2049//2049 2050//2050 -f 1773//1773 2050//2050 1774//1774 -f 1774//1774 2050//2050 2051//2051 -f 1774//1774 2051//2051 1775//1775 -f 1775//1775 2051//2051 2052//2052 -f 1775//1775 2052//2052 1776//1776 -f 1776//1776 2052//2052 2053//2053 -f 1776//1776 2053//2053 1777//1777 -f 1777//1777 2053//2053 2054//2054 -f 1777//1777 2054//2054 1699//1699 -f 1699//1699 2054//2054 2055//2055 -f 695//695 2272//2272 697//697 -f 697//697 2272//2272 2273//2273 -f 697//697 2273//2273 699//699 -f 699//699 2273//2273 2274//2274 -f 699//699 2274//2274 701//701 -f 701//701 2274//2274 2275//2275 -f 701//701 2275//2275 703//703 -f 703//703 2275//2275 2276//2276 -f 703//703 2276//2276 705//705 -f 705//705 2276//2276 2277//2277 -f 705//705 2277//2277 707//707 -f 707//707 2277//2277 2278//2278 -f 707//707 2278//2278 709//709 -f 709//709 2278//2278 2279//2279 -f 709//709 2279//2279 711//711 -f 711//711 2279//2279 2280//2280 -f 711//711 2280//2280 713//713 -f 713//713 2280//2280 2281//2281 -f 713//713 2281//2281 643//643 -f 643//643 2281//2281 2282//2282 -f 643//643 2282//2282 644//644 -f 644//644 2282//2282 2283//2283 -f 644//644 2283//2283 645//645 -f 645//645 2283//2283 2284//2284 -f 645//645 2284//2284 647//647 -f 647//647 2284//2284 2285//2285 -f 647//647 2285//2285 649//649 -f 649//649 2285//2285 2286//2286 -f 649//649 2286//2286 651//651 -f 651//651 2286//2286 2287//2287 -f 651//651 2287//2287 653//653 -f 653//653 2287//2287 2288//2288 -f 653//653 2288//2288 655//655 -f 655//655 2288//2288 2289//2289 -f 655//655 2289//2289 657//657 -f 657//657 2289//2289 2290//2290 -f 657//657 2290//2290 659//659 -f 659//659 2290//2290 2291//2291 -f 659//659 2291//2291 661//661 -f 661//661 2291//2291 2292//2292 -f 661//661 2292//2292 663//663 -f 663//663 2292//2292 2293//2293 -f 663//663 2293//2293 665//665 -f 665//665 2293//2293 2294//2294 -f 665//665 2294//2294 667//667 -f 667//667 2294//2294 2295//2295 -f 667//667 2295//2295 669//669 -f 669//669 2295//2295 2296//2296 -f 669//669 2296//2296 671//671 -f 671//671 2296//2296 2297//2297 -f 671//671 2297//2297 673//673 -f 673//673 2297//2297 2298//2298 -f 673//673 2298//2298 675//675 -f 675//675 2298//2298 2299//2299 -f 675//675 2299//2299 677//677 -f 677//677 2299//2299 2300//2300 -f 677//677 2300//2300 679//679 -f 679//679 2300//2300 2301//2301 -f 679//679 2301//2301 681//681 -f 681//681 2301//2301 2302//2302 -f 681//681 2302//2302 683//683 -f 683//683 2302//2302 2303//2303 -f 683//683 2303//2303 685//685 -f 685//685 2303//2303 2304//2304 -f 685//685 2304//2304 687//687 -f 687//687 2304//2304 2268//2268 -f 687//687 2268//2268 689//689 -f 689//689 2268//2268 2269//2269 -f 689//689 2269//2269 691//691 -f 691//691 2269//2269 2270//2270 -f 691//691 2270//2270 693//693 -f 693//693 2270//2270 2271//2271 -f 693//693 2271//2271 695//695 -f 695//695 2271//2271 2272//2272 -f 201//201 2175//2175 199//199 -f 199//199 2175//2175 2176//2176 -f 199//199 2176//2176 197//197 -f 197//197 2176//2176 2177//2177 -f 197//197 2177//2177 195//195 -f 195//195 2177//2177 2178//2178 -f 195//195 2178//2178 193//193 -f 193//193 2178//2178 2179//2179 -f 193//193 2179//2179 191//191 -f 191//191 2179//2179 2180//2180 -f 191//191 2180//2180 189//189 -f 189//189 2180//2180 2181//2181 -f 189//189 2181//2181 187//187 -f 187//187 2181//2181 2182//2182 -f 187//187 2182//2182 185//185 -f 185//185 2182//2182 2183//2183 -f 185//185 2183//2183 183//183 -f 183//183 2183//2183 2184//2184 -f 183//183 2184//2184 255//255 -f 255//255 2184//2184 2185//2185 -f 255//255 2185//2185 253//253 -f 253//253 2185//2185 2186//2186 -f 253//253 2186//2186 251//251 -f 251//251 2186//2186 2187//2187 -f 251//251 2187//2187 249//249 -f 249//249 2187//2187 2188//2188 -f 249//249 2188//2188 247//247 -f 247//247 2188//2188 2189//2189 -f 247//247 2189//2189 245//245 -f 245//245 2189//2189 2190//2190 -f 245//245 2190//2190 243//243 -f 243//243 2190//2190 2191//2191 -f 243//243 2191//2191 241//241 -f 241//241 2191//2191 2192//2192 -f 241//241 2192//2192 239//239 -f 239//239 2192//2192 2193//2193 -f 239//239 2193//2193 237//237 -f 237//237 2193//2193 2157//2157 -f 237//237 2157//2157 235//235 -f 235//235 2157//2157 2158//2158 -f 235//235 2158//2158 233//233 -f 233//233 2158//2158 2159//2159 -f 233//233 2159//2159 231//231 -f 231//231 2159//2159 2160//2160 -f 231//231 2160//2160 229//229 -f 229//229 2160//2160 2161//2161 -f 229//229 2161//2161 227//227 -f 227//227 2161//2161 2162//2162 -f 227//227 2162//2162 225//225 -f 225//225 2162//2162 2163//2163 -f 225//225 2163//2163 223//223 -f 223//223 2163//2163 2164//2164 -f 223//223 2164//2164 221//221 -f 221//221 2164//2164 2165//2165 -f 221//221 2165//2165 219//219 -f 219//219 2165//2165 2166//2166 -f 219//219 2166//2166 217//217 -f 217//217 2166//2166 2167//2167 -f 217//217 2167//2167 215//215 -f 215//215 2167//2167 2168//2168 -f 215//215 2168//2168 213//213 -f 213//213 2168//2168 2169//2169 -f 213//213 2169//2169 211//211 -f 211//211 2169//2169 2170//2170 -f 211//211 2170//2170 209//209 -f 209//209 2170//2170 2171//2171 -f 209//209 2171//2171 207//207 -f 207//207 2171//2171 2172//2172 -f 207//207 2172//2172 205//205 -f 205//205 2172//2172 2173//2173 -f 205//205 2173//2173 203//203 -f 203//203 2173//2173 2174//2174 -f 203//203 2174//2174 201//201 -f 201//201 2174//2174 2175//2175 -f 126//126 2411//2411 124//124 -f 124//124 2411//2411 2412//2412 -f 124//124 2412//2412 122//122 -f 122//122 2412//2412 2413//2413 -f 122//122 2413//2413 120//120 -f 120//120 2413//2413 2414//2414 -f 120//120 2414//2414 118//118 -f 118//118 2414//2414 2415//2415 -f 118//118 2415//2415 116//116 -f 116//116 2415//2415 2379//2379 -f 116//116 2379//2379 114//114 -f 114//114 2379//2379 2380//2380 -f 114//114 2380//2380 112//112 -f 112//112 2380//2380 2381//2381 -f 112//112 2381//2381 110//110 -f 110//110 2381//2381 2382//2382 -f 110//110 2382//2382 108//108 -f 108//108 2382//2382 2383//2383 -f 108//108 2383//2383 180//180 -f 180//180 2383//2383 2384//2384 -f 180//180 2384//2384 178//178 -f 178//178 2384//2384 2385//2385 -f 178//178 2385//2385 176//176 -f 176//176 2385//2385 2386//2386 -f 176//176 2386//2386 174//174 -f 174//174 2386//2386 2387//2387 -f 174//174 2387//2387 172//172 -f 172//172 2387//2387 2388//2388 -f 172//172 2388//2388 170//170 -f 170//170 2388//2388 2389//2389 -f 170//170 2389//2389 168//168 -f 168//168 2389//2389 2390//2390 -f 168//168 2390//2390 166//166 -f 166//166 2390//2390 2391//2391 -f 166//166 2391//2391 164//164 -f 164//164 2391//2391 2392//2392 -f 164//164 2392//2392 162//162 -f 162//162 2392//2392 2393//2393 -f 162//162 2393//2393 160//160 -f 160//160 2393//2393 2394//2394 -f 160//160 2394//2394 158//158 -f 158//158 2394//2394 2395//2395 -f 158//158 2395//2395 156//156 -f 156//156 2395//2395 2396//2396 -f 156//156 2396//2396 154//154 -f 154//154 2396//2396 2397//2397 -f 154//154 2397//2397 152//152 -f 152//152 2397//2397 2398//2398 -f 152//152 2398//2398 150//150 -f 150//150 2398//2398 2399//2399 -f 150//150 2399//2399 148//148 -f 148//148 2399//2399 2400//2400 -f 148//148 2400//2400 146//146 -f 146//146 2400//2400 2401//2401 -f 146//146 2401//2401 144//144 -f 144//144 2401//2401 2402//2402 -f 144//144 2402//2402 142//142 -f 142//142 2402//2402 2403//2403 -f 142//142 2403//2403 140//140 -f 140//140 2403//2403 2404//2404 -f 140//140 2404//2404 138//138 -f 138//138 2404//2404 2405//2405 -f 138//138 2405//2405 136//136 -f 136//136 2405//2405 2406//2406 -f 136//136 2406//2406 134//134 -f 134//134 2406//2406 2407//2407 -f 134//134 2407//2407 132//132 -f 132//132 2407//2407 2408//2408 -f 132//132 2408//2408 130//130 -f 130//130 2408//2408 2409//2409 -f 130//130 2409//2409 128//128 -f 128//128 2409//2409 2410//2410 -f 128//128 2410//2410 126//126 -f 126//126 2410//2410 2411//2411 -f 740//740 1944//1944 742//742 -f 742//742 1944//1944 1945//1945 -f 742//742 1945//1945 744//744 -f 744//744 1945//1945 1946//1946 -f 744//744 1946//1946 746//746 -f 746//746 1946//1946 1947//1947 -f 746//746 1947//1947 748//748 -f 748//748 1947//1947 1948//1948 -f 748//748 1948//1948 750//750 -f 750//750 1948//1948 1949//1949 -f 750//750 1949//1949 752//752 -f 752//752 1949//1949 1950//1950 -f 752//752 1950//1950 754//754 -f 754//754 1950//1950 1951//1951 -f 754//754 1951//1951 756//756 -f 756//756 1951//1951 1952//1952 -f 756//756 1952//1952 758//758 -f 758//758 1952//1952 1953//1953 -f 758//758 1953//1953 760//760 -f 760//760 1953//1953 1954//1954 -f 760//760 1954//1954 762//762 -f 762//762 1954//1954 1955//1955 -f 762//762 1955//1955 764//764 -f 764//764 1955//1955 1956//1956 -f 764//764 1956//1956 766//766 -f 766//766 1956//1956 1957//1957 -f 766//766 1957//1957 768//768 -f 768//768 1957//1957 1958//1958 -f 768//768 1958//1958 770//770 -f 770//770 1958//1958 1959//1959 -f 770//770 1959//1959 772//772 -f 772//772 1959//1959 1960//1960 -f 772//772 1960//1960 774//774 -f 774//774 1960//1960 1961//1961 -f 774//774 1961//1961 776//776 -f 776//776 1961//1961 1962//1962 -f 776//776 1962//1962 778//778 -f 778//778 1962//1962 1963//1963 -f 778//778 1963//1963 780//780 -f 780//780 1963//1963 1964//1964 -f 780//780 1964//1964 782//782 -f 782//782 1964//1964 1965//1965 -f 782//782 1965//1965 783//783 -f 783//783 1965//1965 1966//1966 -f 783//783 1966//1966 784//784 -f 784//784 1966//1966 1967//1967 -f 784//784 1967//1967 785//785 -f 785//785 1967//1967 1968//1968 -f 785//785 1968//1968 716//716 -f 716//716 1968//1968 1969//1969 -f 716//716 1969//1969 718//718 -f 718//718 1969//1969 1970//1970 -f 718//718 1970//1970 720//720 -f 720//720 1970//1970 1971//1971 -f 720//720 1971//1971 722//722 -f 722//722 1971//1971 1935//1935 -f 722//722 1935//1935 724//724 -f 724//724 1935//1935 1936//1936 -f 724//724 1936//1936 726//726 -f 726//726 1936//1936 1937//1937 -f 726//726 1937//1937 728//728 -f 728//728 1937//1937 1938//1938 -f 728//728 1938//1938 730//730 -f 730//730 1938//1938 1939//1939 -f 730//730 1939//1939 732//732 -f 732//732 1939//1939 1940//1940 -f 732//732 1940//1940 734//734 -f 734//734 1940//1940 1941//1941 -f 734//734 1941//1941 736//736 -f 736//736 1941//1941 1942//1942 -f 736//736 1942//1942 738//738 -f 738//738 1942//1942 1943//1943 -f 738//738 1943//1943 740//740 -f 740//740 1943//1943 1944//1944 -f 1844//1844 2499//2499 1846//1846 -f 1846//1846 2499//2499 2500//2500 -f 1846//1846 2500//2500 1847//1847 -f 1847//1847 2500//2500 2501//2501 -f 1847//1847 2501//2501 1849//1849 -f 1849//1849 2501//2501 2502//2502 -f 1849//1849 2502//2502 1848//1848 -f 1848//1848 2502//2502 2503//2503 -f 1848//1848 2503//2503 1859//1859 -f 1859//1859 2503//2503 2504//2504 -f 1859//1859 2504//2504 1858//1858 -f 1858//1858 2504//2504 2505//2505 -f 1858//1858 2505//2505 1857//1857 -f 1857//1857 2505//2505 2506//2506 -f 1857//1857 2506//2506 1856//1856 -f 1856//1856 2506//2506 2507//2507 -f 1856//1856 2507//2507 1855//1855 -f 1855//1855 2507//2507 2508//2508 -f 1855//1855 2508//2508 1854//1854 -f 1854//1854 2508//2508 2509//2509 -f 1854//1854 2509//2509 1853//1853 -f 1853//1853 2509//2509 2510//2510 -f 1853//1853 2510//2510 1852//1852 -f 1852//1852 2510//2510 2511//2511 -f 1852//1852 2511//2511 1851//1851 -f 1851//1851 2511//2511 2512//2512 -f 1851//1851 2512//2512 1850//1850 -f 1850//1850 2512//2512 2513//2513 -f 1850//1850 2513//2513 1860//1860 -f 1860//1860 2513//2513 2514//2514 -f 1860//1860 2514//2514 1787//1787 -f 1787//1787 2514//2514 2515//2515 -f 1787//1787 2515//2515 1788//1788 -f 1788//1788 2515//2515 2516//2516 -f 1788//1788 2516//2516 1789//1789 -f 1789//1789 2516//2516 2517//2517 -f 1789//1789 2517//2517 1794//1794 -f 1794//1794 2517//2517 2518//2518 -f 1794//1794 2518//2518 1797//1797 -f 1797//1797 2518//2518 2519//2519 -f 1797//1797 2519//2519 1800//1800 -f 1800//1800 2519//2519 2520//2520 -f 1800//1800 2520//2520 1806//1806 -f 1806//1806 2520//2520 2521//2521 -f 1806//1806 2521//2521 1786//1786 -f 1786//1786 2521//2521 2522//2522 -f 1786//1786 2522//2522 1810//1810 -f 1810//1810 2522//2522 2523//2523 -f 1810//1810 2523//2523 1814//1814 -f 1814//1814 2523//2523 2524//2524 -f 1814//1814 2524//2524 1816//1816 -f 1816//1816 2524//2524 2525//2525 -f 1816//1816 2525//2525 1822//1822 -f 1822//1822 2525//2525 2526//2526 -f 1822//1822 2526//2526 1824//1824 -f 1824//1824 2526//2526 2490//2490 -f 1824//1824 2490//2490 1829//1829 -f 1829//1829 2490//2490 2491//2491 -f 1829//1829 2491//2491 1783//1783 -f 1783//1783 2491//2491 2492//2492 -f 1783//1783 2492//2492 1833//1833 -f 1833//1833 2492//2492 2493//2493 -f 1833//1833 2493//2493 1780//1780 -f 1780//1780 2493//2493 2494//2494 -f 1780//1780 2494//2494 1838//1838 -f 1838//1838 2494//2494 2495//2495 -f 1838//1838 2495//2495 1841//1841 -f 1841//1841 2495//2495 2496//2496 -f 1841//1841 2496//2496 1843//1843 -f 1843//1843 2496//2496 2497//2497 -f 1843//1843 2497//2497 1845//1845 -f 1845//1845 2497//2497 2498//2498 -f 1845//1845 2498//2498 1844//1844 -f 1844//1844 2498//2498 2499//2499 -f 7022//7022 7023//7023 7024//7024 -f 7025//7025 7026//7026 7027//7027 -f 7027//7027 7026//7026 7028//7028 -f 7027//7027 7028//7028 7029//7029 -f 7030//7030 7031//7031 7032//7032 -f 7032//7032 7031//7031 7033//7033 -f 7032//7032 7033//7033 7034//7034 -f 7034//7034 7033//7033 7035//7035 -f 7034//7034 7035//7035 7025//7025 -f 7025//7025 7035//7035 7036//7036 -f 7025//7025 7036//7036 7026//7026 -f 7037//7037 7038//7038 7039//7039 -f 7039//7039 7038//7038 7040//7040 -f 7039//7039 7040//7040 7041//7041 -f 7041//7041 7040//7040 7042//7042 -f 7041//7041 7042//7042 7030//7030 -f 7030//7030 7042//7042 7043//7043 -f 7030//7030 7043//7043 7031//7031 -f 7044//7044 7045//7045 7046//7046 -f 7046//7046 7045//7045 7047//7047 -f 7046//7046 7047//7047 7048//7048 -f 7048//7048 7047//7047 7049//7049 -f 7048//7048 7049//7049 7050//7050 -f 7050//7050 7049//7049 7051//7051 -f 7050//7050 7051//7051 7052//7052 -f 7052//7052 7051//7051 7053//7053 -f 7052//7052 7053//7053 7054//7054 -f 7054//7054 7053//7053 7055//7055 -f 7054//7054 7055//7055 7056//7056 -f 7056//7056 7055//7055 7057//7057 -f 7056//7056 7057//7057 7058//7058 -f 7058//7058 7057//7057 7059//7059 -f 7058//7058 7059//7059 7060//7060 -f 7060//7060 7059//7059 7061//7061 -f 7060//7060 7061//7061 7062//7062 -f 7062//7062 7061//7061 7063//7063 -f 7062//7062 7063//7063 7064//7064 -f 7064//7064 7063//7063 7065//7065 -f 7064//7064 7065//7065 7066//7066 -f 7066//7066 7065//7065 7067//7067 -f 7066//7066 7067//7067 7068//7068 -f 7068//7068 7067//7067 7069//7069 -f 7068//7068 7069//7069 7070//7070 -f 7070//7070 7069//7069 7071//7071 -f 7070//7070 7071//7071 7072//7072 -f 7072//7072 7071//7071 7073//7073 -f 7072//7072 7073//7073 7074//7074 -f 7074//7074 7073//7073 7075//7075 -f 7074//7074 7075//7075 7076//7076 -f 7076//7076 7075//7075 7077//7077 -f 7076//7076 7077//7077 7078//7078 -f 7078//7078 7077//7077 7079//7079 -f 7078//7078 7079//7079 7080//7080 -f 7080//7080 7079//7079 7081//7081 -f 7080//7080 7081//7081 7037//7037 -f 7037//7037 7081//7081 7082//7082 -f 7037//7037 7082//7082 7038//7038 -f 7083//7083 7084//7084 7085//7085 -f 7085//7085 7084//7084 7086//7086 -f 7085//7085 7086//7086 7087//7087 -f 7087//7087 7086//7086 7088//7088 -f 7087//7087 7088//7088 7089//7089 -f 7089//7089 7088//7088 7090//7090 -f 7089//7089 7090//7090 7091//7091 -f 7091//7091 7090//7090 7092//7092 -f 7091//7091 7092//7092 7093//7093 -f 7093//7093 7092//7092 7094//7094 -f 7093//7093 7094//7094 7095//7095 -f 7095//7095 7094//7094 7096//7096 -f 7095//7095 7096//7096 7097//7097 -f 7097//7097 7096//7096 7098//7098 -f 7097//7097 7098//7098 7099//7099 -f 7099//7099 7098//7098 7100//7100 -f 7099//7099 7100//7100 7044//7044 -f 7044//7044 7100//7100 7101//7101 -f 7044//7044 7101//7101 7045//7045 -f 7102//7102 7103//7103 7104//7104 -f 7104//7104 7103//7103 7105//7105 -f 7104//7104 7105//7105 7083//7083 -f 7083//7083 7105//7105 7106//7106 -f 7083//7083 7106//7106 7084//7084 -f 7102//7102 7107//7107 7103//7103 -f 7103//7103 7107//7107 7108//7108 -f 7103//7103 7108//7108 7109//7109 -f 7109//7109 7108//7108 7110//7110 -f 7109//7109 7110//7110 7111//7111 -f 7111//7111 7110//7110 7112//7112 -f 7111//7111 7112//7112 7113//7113 -f 7113//7113 7112//7112 7114//7114 -f 7113//7113 7114//7114 7115//7115 -f 7115//7115 7114//7114 7116//7116 -f 7115//7115 7116//7116 7117//7117 -f 7117//7117 7116//7116 7118//7118 -f 7117//7117 7118//7118 7119//7119 -f 7119//7119 7118//7118 7120//7120 -f 7119//7119 7120//7120 7121//7121 -f 7121//7121 7120//7120 7122//7122 -f 7121//7121 7122//7122 7123//7123 -f 7123//7123 7122//7122 7124//7124 -f 7123//7123 7124//7124 7125//7125 -f 7125//7125 7124//7124 7126//7126 -f 7125//7125 7126//7126 7127//7127 -f 7127//7127 7126//7126 7128//7128 -f 7127//7127 7128//7128 7129//7129 -f 7129//7129 7128//7128 7130//7130 -f 7129//7129 7130//7130 7131//7131 -f 7131//7131 7130//7130 7132//7132 -f 7131//7131 7132//7132 7133//7133 -f 7133//7133 7132//7132 7134//7134 -f 7133//7133 7134//7134 7135//7135 -f 7135//7135 7134//7134 7136//7136 -f 7135//7135 7136//7136 7137//7137 -f 7137//7137 7136//7136 7138//7138 -f 7137//7137 7138//7138 7139//7139 -f 7139//7139 7138//7138 7140//7140 -f 7140//7140 7141//7141 7139//7139 -f 7139//7139 7141//7141 7142//7142 -f 7139//7139 7142//7142 7143//7143 -f 7143//7143 7142//7142 7144//7144 -f 7143//7143 7144//7144 7145//7145 -f 7145//7145 7144//7144 7146//7146 -f 7145//7145 7146//7146 7147//7147 -f 7147//7147 7146//7146 7148//7148 -f 7147//7147 7148//7148 7149//7149 -f 7149//7149 7148//7148 7150//7150 -f 7149//7149 7150//7150 7151//7151 -f 7151//7151 7150//7150 7152//7152 -f 7151//7151 7152//7152 7153//7153 -f 7153//7153 7152//7152 7154//7154 -f 7153//7153 7154//7154 7155//7155 -f 7155//7155 7154//7154 7156//7156 -f 7155//7155 7156//7156 7157//7157 -f 7157//7157 7156//7156 7158//7158 -f 7157//7157 7158//7158 7159//7159 -f 7159//7159 7158//7158 7160//7160 -f 7159//7159 7160//7160 7161//7161 -f 7161//7161 7160//7160 7162//7162 -f 7161//7161 7162//7162 7163//7163 -f 7163//7163 7162//7162 7164//7164 -f 7163//7163 7164//7164 7165//7165 -f 7165//7165 7164//7164 7166//7166 -f 7165//7165 7166//7166 7167//7167 -f 7167//7167 7166//7166 7168//7168 -f 7167//7167 7168//7168 7169//7169 -f 7169//7169 7168//7168 7170//7170 -f 7169//7169 7170//7170 7024//7024 -f 7024//7024 7170//7170 7171//7171 -f 7024//7024 7171//7171 7022//7022 -f 7023//7023 7022//7022 7172//7172 -f 7172//7172 7022//7022 7173//7173 -f 7172//7172 7173//7173 7029//7029 -f 7029//7029 7173//7173 7174//7174 -f 7029//7029 7174//7174 7027//7027 -f 7170//7170 905//905 7171//7171 -f 7171//7171 905//905 904//904 -f 7171//7171 904//904 7022//7022 -f 7022//7022 904//904 903//903 -f 7022//7022 903//903 7173//7173 -f 7173//7173 903//903 897//897 -f 7173//7173 897//897 7174//7174 -f 7174//7174 897//897 896//896 -f 7174//7174 896//896 7027//7027 -f 946//946 911//911 7168//7168 -f 7168//7168 911//911 910//910 -f 7168//7168 910//910 7170//7170 -f 7170//7170 910//910 909//909 -f 7170//7170 909//909 905//905 -f 7168//7168 7166//7166 946//946 -f 946//946 7166//7166 7164//7164 -f 946//946 7164//7164 947//947 -f 947//947 7164//7164 7162//7162 -f 947//947 7162//7162 949//949 -f 7162//7162 7160//7160 949//949 -f 949//949 7160//7160 7158//7158 -f 949//949 7158//7158 950//950 -f 950//950 7158//7158 7156//7156 -f 950//950 7156//7156 951//951 -f 951//951 7156//7156 952//952 -f 952//952 7156//7156 7154//7154 -f 952//952 7154//7154 953//953 -f 953//953 7154//7154 954//954 -f 954//954 7154//7154 7152//7152 -f 954//954 7152//7152 955//955 -f 955//955 7152//7152 7150//7150 -f 955//955 7150//7150 956//956 -f 956//956 7150//7150 7148//7148 -f 956//956 7148//7148 957//957 -f 957//957 7148//7148 7146//7146 -f 957//957 7146//7146 958//958 -f 958//958 7146//7146 7144//7144 -f 958//958 7144//7144 945//945 -f 945//945 7144//7144 7142//7142 -f 945//945 7142//7142 943//943 -f 943//943 7142//7142 7141//7141 -f 943//943 7141//7141 940//940 -f 7141//7141 7140//7140 940//940 -f 940//940 7140//7140 7138//7138 -f 940//940 7138//7138 941//941 -f 941//941 7138//7138 7136//7136 -f 941//941 7136//7136 942//942 -f 942//942 7136//7136 936//936 -f 936//936 7136//7136 7134//7134 -f 936//936 7134//7134 937//937 -f 937//937 7134//7134 7132//7132 -f 937//937 7132//7132 938//938 -f 938//938 7132//7132 7130//7130 -f 938//938 7130//7130 939//939 -f 939//939 7130//7130 7128//7128 -f 939//939 7128//7128 873//873 -f 873//873 7128//7128 7126//7126 -f 873//873 7126//7126 871//871 -f 871//871 7126//7126 865//865 -f 865//865 7126//7126 7124//7124 -f 865//865 7124//7124 864//864 -f 864//864 7124//7124 7122//7122 -f 864//864 7122//7122 863//863 -f 863//863 7122//7122 7120//7120 -f 863//863 7120//7120 866//866 -f 866//866 7120//7120 7118//7118 -f 866//866 7118//7118 867//867 -f 867//867 7118//7118 852//852 -f 852//852 7118//7118 7116//7116 -f 852//852 7116//7116 853//853 -f 7116//7116 7114//7114 853//853 -f 853//853 7114//7114 7112//7112 -f 853//853 7112//7112 855//855 -f 7112//7112 7110//7110 855//855 -f 855//855 7110//7110 7108//7108 -f 855//855 7108//7108 856//856 -f 856//856 7108//7108 7107//7107 -f 856//856 7107//7107 857//857 -f 857//857 7107//7107 7102//7102 -f 857//857 7102//7102 868//868 -f 868//868 7102//7102 7104//7104 -f 868//868 7104//7104 869//869 -f 869//869 7104//7104 7083//7083 -f 869//869 7083//7083 870//870 -f 870//870 7083//7083 7085//7085 -f 870//870 7085//7085 858//858 -f 858//858 7085//7085 7087//7087 -f 858//858 7087//7087 859//859 -f 859//859 7087//7087 861//861 -f 7087//7087 7089//7089 861//861 -f 861//861 7089//7089 7091//7091 -f 861//861 7091//7091 862//862 -f 862//862 7091//7091 7093//7093 -f 862//862 7093//7093 890//890 -f 890//890 7093//7093 7095//7095 -f 890//890 7095//7095 877//877 -f 877//877 7095//7095 874//874 -f 874//874 7095//7095 7097//7097 -f 874//874 7097//7097 882//882 -f 882//882 7097//7097 7099//7099 -f 882//882 7099//7099 929//929 -f 929//929 7099//7099 7044//7044 -f 929//929 7044//7044 930//930 -f 930//930 7044//7044 7046//7046 -f 930//930 7046//7046 934//934 -f 934//934 7046//7046 7048//7048 -f 934//934 7048//7048 935//935 -f 935//935 7048//7048 931//931 -f 931//931 7048//7048 7050//7050 -f 931//931 7050//7050 932//932 -f 932//932 7050//7050 7052//7052 -f 932//932 7052//7052 933//933 -f 933//933 7052//7052 7054//7054 -f 933//933 7054//7054 927//927 -f 7054//7054 7056//7056 927//927 -f 927//927 7056//7056 7058//7058 -f 927//927 7058//7058 928//928 -f 928//928 7058//7058 7060//7060 -f 928//928 7060//7060 923//923 -f 7060//7060 7062//7062 923//923 -f 923//923 7062//7062 7064//7064 -f 923//923 7064//7064 924//924 -f 924//924 7064//7064 7066//7066 -f 924//924 7066//7066 925//925 -f 925//925 7066//7066 7068//7068 -f 925//925 7068//7068 918//918 -f 918//918 7068//7068 915//915 -f 7068//7068 7070//7070 915//915 -f 915//915 7070//7070 7072//7072 -f 915//915 7072//7072 916//916 -f 916//916 7072//7072 7074//7074 -f 916//916 7074//7074 919//919 -f 7074//7074 7076//7076 919//919 -f 919//919 7076//7076 7078//7078 -f 919//919 7078//7078 920//920 -f 920//920 7078//7078 7080//7080 -f 920//920 7080//7080 921//921 -f 921//921 7080//7080 7037//7037 -f 921//921 7037//7037 899//899 -f 899//899 7037//7037 7039//7039 -f 899//899 7039//7039 900//900 -f 900//900 7039//7039 7041//7041 -f 7034//7034 907//907 7032//7032 -f 7032//7032 907//907 906//906 -f 7032//7032 906//906 7030//7030 -f 7030//7030 906//906 902//902 -f 7030//7030 902//902 7041//7041 -f 7041//7041 902//902 901//901 -f 7041//7041 901//901 900//900 -f 7025//7025 912//912 7034//7034 -f 7034//7034 912//912 908//908 -f 7034//7034 908//908 907//907 -f 896//896 898//898 7027//7027 -f 7027//7027 898//898 914//914 -f 7027//7027 914//914 7025//7025 -f 7025//7025 914//914 913//913 -f 7025//7025 913//913 912//912 -f 7024//7024 2868//2868 7169//7169 -f 7169//7169 2868//2868 2867//2867 -f 7169//7169 2867//2867 7167//7167 -f 7167//7167 2867//2867 2891//2891 -f 7167//7167 2891//2891 7165//7165 -f 7165//7165 2891//2891 2887//2887 -f 7165//7165 2887//2887 7163//7163 -f 7163//7163 2887//2887 2907//2907 -f 7163//7163 2907//2907 7161//7161 -f 7161//7161 2907//2907 2908//2908 -f 7161//7161 2908//2908 7159//7159 -f 7159//7159 2908//2908 2916//2916 -f 7159//7159 2916//2916 7157//7157 -f 2916//2916 2915//2915 7157//7157 -f 7157//7157 2915//2915 2914//2914 -f 7157//7157 2914//2914 7155//7155 -f 2929//2929 7153//7153 2909//2909 -f 2909//2909 7153//7153 7155//7155 -f 2909//2909 7155//7155 2910//2910 -f 2910//2910 7155//7155 2914//2914 -f 2847//2847 7147//7147 2928//2928 -f 2928//2928 7147//7147 7149//7149 -f 2928//2928 7149//7149 2929//2929 -f 2929//2929 7149//7149 7151//7151 -f 2929//2929 7151//7151 7153//7153 -f 7137//7137 7139//7139 2876//2876 -f 2876//2876 7139//7139 7143//7143 -f 2876//2876 7143//7143 2847//2847 -f 2847//2847 7143//7143 7145//7145 -f 2847//2847 7145//7145 7147//7147 -f 2876//2876 2894//2894 7137//7137 -f 7137//7137 2894//2894 2893//2893 -f 7137//7137 2893//2893 7135//7135 -f 7135//7135 2893//2893 2892//2892 -f 7135//7135 2892//2892 7133//7133 -f 7133//7133 2892//2892 2881//2881 -f 7133//7133 2881//2881 7131//7131 -f 7131//7131 2881//2881 2880//2880 -f 7131//7131 2880//2880 7129//7129 -f 7129//7129 2880//2880 7127//7127 -f 2880//2880 2879//2879 7127//7127 -f 7127//7127 2879//2879 2878//2878 -f 7127//7127 2878//2878 7125//7125 -f 7125//7125 2878//2878 2877//2877 -f 7125//7125 2877//2877 7123//7123 -f 7123//7123 2877//2877 2848//2848 -f 7123//7123 2848//2848 7121//7121 -f 7121//7121 2848//2848 2862//2862 -f 7121//7121 2862//2862 7119//7119 -f 7119//7119 2862//2862 7117//7117 -f 2862//2862 2861//2861 7117//7117 -f 7117//7117 2861//2861 2860//2860 -f 7117//7117 2860//2860 7115//7115 -f 7115//7115 2860//2860 2859//2859 -f 7115//7115 2859//2859 7113//7113 -f 7113//7113 2859//2859 2858//2858 -f 7113//7113 2858//2858 7111//7111 -f 7111//7111 2858//2858 2865//2865 -f 7111//7111 2865//2865 7109//7109 -f 7109//7109 2865//2865 2866//2866 -f 7109//7109 2866//2866 7103//7103 -f 7103//7103 2866//2866 2886//2886 -f 7103//7103 2886//2886 7105//7105 -f 7105//7105 2886//2886 2885//2885 -f 7105//7105 2885//2885 7106//7106 -f 7106//7106 2885//2885 2884//2884 -f 7106//7106 2884//2884 7084//7084 -f 7084//7084 2884//2884 2883//2883 -f 7084//7084 2883//2883 7086//7086 -f 7086//7086 2883//2883 2874//2874 -f 7086//7086 2874//2874 7088//7088 -f 7088//7088 2874//2874 2904//2904 -f 7088//7088 2904//2904 7090//7090 -f 7090//7090 2904//2904 7092//7092 -f 2904//2904 2903//2903 7092//7092 -f 7092//7092 2903//2903 2902//2902 -f 7092//7092 2902//2902 7094//7094 -f 7094//7094 2902//2902 2901//2901 -f 7094//7094 2901//2901 7096//7096 -f 7096//7096 2901//2901 2899//2899 -f 7061//7061 7059//7059 2922//2922 -f 2922//2922 7059//7059 7057//7057 -f 2922//2922 7057//7057 2940//2940 -f 2940//2940 7057//7057 7055//7055 -f 2940//2940 7055//7055 2941//2941 -f 2941//2941 7055//7055 7053//7053 -f 2941//2941 7053//7053 2942//2942 -f 2942//2942 7053//7053 7051//7051 -f 2942//2942 7051//7051 2895//2895 -f 2895//2895 7051//7051 7049//7049 -f 2895//2895 7049//7049 2896//2896 -f 2896//2896 7049//7049 7047//7047 -f 2896//2896 7047//7047 2936//2936 -f 2936//2936 7047//7047 7045//7045 -f 2936//2936 7045//7045 2937//2937 -f 2937//2937 7045//7045 7101//7101 -f 2937//2937 7101//7101 2938//2938 -f 2938//2938 7101//7101 7100//7100 -f 2938//2938 7100//7100 2899//2899 -f 2899//2899 7100//7100 7098//7098 -f 2899//2899 7098//7098 7096//7096 -f 2922//2922 2933//2933 7061//7061 -f 7061//7061 2933//2933 2935//2935 -f 7061//7061 2935//2935 7063//7063 -f 7063//7063 2935//2935 2962//2962 -f 7063//7063 2962//2962 7065//7065 -f 7065//7065 2962//2962 2961//2961 -f 7065//7065 2961//2961 7067//7067 -f 7067//7067 2961//2961 7069//7069 -f 2961//2961 2959//2959 7069//7069 -f 7069//7069 2959//2959 2958//2958 -f 7069//7069 2958//2958 7071//7071 -f 7071//7071 2958//2958 2954//2954 -f 7071//7071 2954//2954 7073//7073 -f 7073//7073 2954//2954 2956//2956 -f 7073//7073 2956//2956 7075//7075 -f 2956//2956 2957//2957 7075//7075 -f 7075//7075 2957//2957 2953//2953 -f 7075//7075 2953//2953 7077//7077 -f 7077//7077 2953//2953 2951//2951 -f 7077//7077 2951//2951 7079//7079 -f 7079//7079 2951//2951 2950//2950 -f 7079//7079 2950//2950 7081//7081 -f 7081//7081 2950//2950 2948//2948 -f 7081//7081 2948//2948 7082//7082 -f 7082//7082 2948//2948 2947//2947 -f 7082//7082 2947//2947 7038//7038 -f 7038//7038 2947//2947 2943//2943 -f 7038//7038 2943//2943 7040//7040 -f 7040//7040 2943//2943 2945//2945 -f 7040//7040 2945//2945 7042//7042 -f 7042//7042 2945//2945 2946//2946 -f 7042//7042 2946//2946 7043//7043 -f 7043//7043 2946//2946 2932//2932 -f 7043//7043 2932//2932 7031//7031 -f 7031//7031 2932//2932 7033//7033 -f 2932//2932 2931//2931 7033//7033 -f 7033//7033 2931//2931 2930//2930 -f 7033//7033 2930//2930 7035//7035 -f 7035//7035 2930//2930 2912//2912 -f 7035//7035 2912//2912 7036//7036 -f 7036//7036 2912//2912 2911//2911 -f 7036//7036 2911//2911 7026//7026 -f 7026//7026 2911//2911 2919//2919 -f 7026//7026 2919//2919 7028//7028 -f 7028//7028 2919//2919 2918//2918 -f 7028//7028 2918//2918 7029//7029 -f 7029//7029 2918//2918 2917//2917 -f 7029//7029 2917//2917 7172//7172 -f 7172//7172 2917//2917 2871//2871 -f 7172//7172 2871//2871 7023//7023 -f 7023//7023 2871//2871 2870//2870 -f 7023//7023 2870//2870 7024//7024 -f 7024//7024 2870//2870 2869//2869 -f 7024//7024 2869//2869 2868//2868 -# 14384 faces, 0 coords texture - -# End of File diff --git a/mep3_simulation/webots_data/worlds/assets/pcb.png b/mep3_simulation/webots_data/worlds/assets/pcb.png deleted file mode 100644 index 481b33250..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/pcb.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/samples/blue.png b/mep3_simulation/webots_data/worlds/assets/samples/blue.png deleted file mode 100644 index 4012965b0..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/samples/blue.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/samples/bottom.png b/mep3_simulation/webots_data/worlds/assets/samples/bottom.png deleted file mode 100644 index ea9be1e8a..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/samples/bottom.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/samples/empty.png b/mep3_simulation/webots_data/worlds/assets/samples/empty.png deleted file mode 100644 index 06c5c4f04..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/samples/empty.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/samples/green.png b/mep3_simulation/webots_data/worlds/assets/samples/green.png deleted file mode 100644 index d21cc01b6..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/samples/green.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/assets/samples/red.png b/mep3_simulation/webots_data/worlds/assets/samples/red.png deleted file mode 100644 index 6d3668346..000000000 Binary files a/mep3_simulation/webots_data/worlds/assets/samples/red.png and /dev/null differ diff --git a/mep3_simulation/webots_data/worlds/eurobot_2022.wbt b/mep3_simulation/webots_data/worlds/eurobot_2022.wbt deleted file mode 100644 index 81b0b2ff8..000000000 --- a/mep3_simulation/webots_data/worlds/eurobot_2022.wbt +++ /dev/null @@ -1,609 +0,0 @@ -#VRML_SIM R2022b utf8 - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/panels/protos/Panel.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackground.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/floors/protos/Floor.proto" -EXTERNPROTO "../protos/Statuette.proto" -EXTERNPROTO "../protos/OpponentBox.proto" -EXTERNPROTO "../protos/Replica.proto" -EXTERNPROTO "../protos/DispenserVertical.proto" -EXTERNPROTO "../protos/StatuetteSupport.proto" -EXTERNPROTO "../protos/DispenserOuter.proto" -EXTERNPROTO "../protos/RobotMemristor2.proto" -EXTERNPROTO "../protos/FixedBeaconSupport.proto" -EXTERNPROTO "../protos/GalleryPanel.proto" -EXTERNPROTO "../protos/Sample.proto" -EXTERNPROTO "../protos/ExcavationSquare.proto" - -WorldInfo { - basicTimeStep 20 - contactProperties [ - ContactProperties { - material1 "floor" - material2 "wheel" - coulombFriction [ - 100 - ] - } - ContactProperties { - coulombFriction [ - 0.1 - ] - } - ContactProperties { - material1 "resistance_measurement" - material2 "default" - bounce 1 - coulombFriction [ - 0.1 - ] - } - ] -} -Viewpoint { - orientation -0.33187941592824777 0.44070185635166165 0.8340491155149825 1.469596109455753 - position -1.5582221642880734 -7.095912395548499 6.972909520201469 -} -TexturedBackground { -} -TexturedBackgroundLight { -} -Floor { - name "table" - contactMaterial "floor" - size 3 2 - tileSize 4.096 2.048 - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ - "assets/table.png" - ] - repeatS FALSE - repeatT FALSE - } - roughness 1 - metalness 0 - } -} -Solid { - translation 0 1.233 0 - children [ - Transform { - translation 0 0 0.5 - children [ - Shape { - appearance DEF WALL_APPEARANCE PBRAppearance { - baseColor 0.631 0.612 0.537 - roughness 1 - metalness 0 - } - geometry Box { - size 0.2 0.022 1 - } - } - Transform { - translation 0 -0.11 -0.011 - children [ - Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.022 0.2 0.978 - } - } - ] - } - Group { - children [ - Transform { - translation -0.1 -0.0585 0.489 - children [ - Shape { - appearance DEF APPEARANCE_YELLOW PBRAppearance { - baseColor 0.972549 0.694118 0.0666667 - roughness 1 - metalness 0 - name "yellow" - } - geometry DEF CENTRAL_TRACKING_TOP_BOX_HALF Box { - size 0.2 0.095 0.022 - } - } - ] - } - Transform { - translation -0.0475 -0.111 0.489 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry DEF CENTRAL_TRACKING_BOX_SLIT Box { - size 0.095 0.01 0.022 - } - } - ] - } - Transform { - translation -0.1 -0.1635 0.489 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry USE CENTRAL_TRACKING_TOP_BOX_HALF - } - ] - } - ] - } - Group { - children [ - Transform { - translation 0.1 -0.0585 0.489 - children [ - Shape { - appearance DEF APPEARANCE_PURPLE PBRAppearance { - baseColor 0.360784 0.282353 0.541176 - roughness 1 - metalness 0 - name "purple" - } - geometry USE CENTRAL_TRACKING_TOP_BOX_HALF - } - ] - } - Transform { - translation 0.0475 -0.111 0.489 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry USE CENTRAL_TRACKING_BOX_SLIT - } - ] - } - Transform { - translation 0.1 -0.1635 0.489 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry USE CENTRAL_TRACKING_TOP_BOX_HALF - } - ] - } - ] - } - ] - } - ] - name "central_tracking_device_platform" - boundingObject Transform { - translation 0 -0.111 0.989 - children [ - Box { - size 0.4 0.2 0.022 - } - ] - } - locked TRUE -} -Solid { - translation 0 1.011 0.035 - rotation 1 0 0 1.5708 - children [ - DEF WALL_W Shape { - appearance DEF WALL_APPEARANCE PBRAppearance { - baseColor 0.631 0.612 0.537 - roughness 1 - metalness 0 - } - geometry Box { - size 3 0.07 0.022 - } - isPickable FALSE - } - ] - name "wall_top" - boundingObject USE WALL_W - locked TRUE -} -Solid { - translation 0 -1.011 0.035 - rotation 1 0 0 1.5708 - children [ - USE WALL_W - ] - name "wall_bottom" - boundingObject USE WALL_W - locked TRUE -} -Solid { - translation -1.511 0 0.035 - rotation 1 0 0 1.5708 - children [ - DEF WALL_H Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.022 0.07 2.044 - } - isPickable FALSE - } - Transform { - translation 0 0.0351 -0.3 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry DEF WALL_H_START Box { - size 0.022 1e-06 0.6 - } - castShadows FALSE - } - ] - } - ] - name "wall_left" - boundingObject USE WALL_H - locked TRUE -} -Solid { - translation 1.511 0 0.035 - rotation 1 0 0 1.5708 - children [ - USE WALL_H - Transform { - translation 0 0.0351 -0.3 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry USE WALL_H_START - castShadows FALSE - } - ] - } - ] - name "wall_right" - boundingObject USE WALL_H - locked TRUE -} -Solid { - translation 0 0.85 0.011 - children [ - DEF middle_divider Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.022 0.3 0.022 - } - } - ] - boundingObject USE middle_divider - locked TRUE -} -StatuetteSupport { -} -StatuetteSupport { - teamColor "purple" -} -DispenserOuter { -} -DispenserOuter { - teamColor "purple" -} -Sample { - name "sample_purple_excavation_site_red" - translation 0.442219 -0.454349 0.0075 - rotation 0 0 1 -0.785395307179586 - frontTexture "red" -} -Sample { - name "sample_purple_excavation_site_green" - translation 0.531922 -0.303676 0.0075 - rotation 0 0 1 1.309 - frontTexture "green" -} -Sample { - name "sample_purple_excavation_site_blue" - translation 0.61144 -0.45196 0.0075 - rotation 0 0 1 -2.6179953071795863 - frontTexture "blue" -} -Sample { - name "sample_yellow_excavation_site_red" - translation -0.446015 -0.290911 0.0075 - rotation 0 0 1 -0.261795307179586 - frontTexture "red" -} -Sample { - name "sample_yellow_excavation_site_green" - translation -0.608832 -0.343505 0.0075 - rotation 0 0 1 -1.3089953071795861 - frontTexture "green" -} -Sample { - name "sample_yellow_excavation_site_blue" - translation -0.498243 -0.466137 0.0075 - rotation 0 0 1 -2.094395307179586 - frontTexture "blue" -} -Sample { - name "sample_purple_playing_area_red" - translation 0.6 0.2 0.00750369 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "red" -} -Sample { - name "sample_purple_playing_area_green" - translation 0.67 0.325 0.00750385 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "green" -} -Sample { - name "sample_purple_playing_area_blue" - translation 0.6 0.45 0.00750346 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "blue" -} -Sample { - name "sample_yellow_playing_area_red" - translation -0.6 0.2 0.00749988 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "red" -} -Sample { - name "sample_yellow_playing_area_green" - translation -0.67 0.325 0.00749957 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "green" -} -Sample { - name "sample_yellow_playing_area_blue" - translation -0.6 0.45 0.00749969 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "blue" -} -DispenserVertical { - name "vertical_dispenser_left" - translation -0.15 1 0 - teamColor USE WALL_APPEARANCE -} -DispenserVertical { - name "vertical_dispenser_right" - translation 0.15 1 0 - teamColor USE WALL_APPEARANCE -} -DispenserVertical { - name "vertical_dispenser_yellow" - translation -1.5 -0.25 0 - rotation 0 0 1 1.5708 - teamColor USE APPEARANCE_YELLOW -} -DispenserVertical { - name "vertical_dispenser_purple" - translation 1.5 -0.25 0 - rotation 0 0 1 -1.5708 - teamColor USE APPEARANCE_PURPLE -} -Sample { - name "sample_green_PURPLE_horizontal_dispenser" - translation 1.56495 0.7 0.0775 - rotation 0.965925849201117 0.2588189595935754 1.2410098062554258e-09 3.14159 - frontTexture "green" -} -Sample { - name "sample_red_PURPLE_horizontal_dispenser" - translation 1.1884 -0.8794 0.0775 - rotation 0.3826841051424448 -0.9238792538357933 1.773180487181278e-06 3.14159 - frontTexture "red" -} -Sample { - name "sample_blue_PURPLE_horizontal_dispenser" - translation 1.3794 -0.6884 0.0775 - rotation -0.9238792538356376 -0.38268410514238027 1.865750512614575e-06 3.14159 - frontTexture "blue" -} -Sample { - name "sample_green_YELLOW_horizontal_dispenser" - translation -1.56495 0.7 0.0775 - rotation -0.25881895959340473 -0.96592584920048 1.1484198207096768e-06 3.14159 - frontTexture "green" -} -Sample { - name "sample_red_YELLOW_horizontal_dispenser" - translation -1.1884 -0.8794 0.0775 - rotation -0.9238797538367262 0.3826828980360002 1.1655496894449454e-06 -3.1415853071795863 - frontTexture "red" -} -Sample { - name "sample_blue_YELLOW_horizontal_dispenser" - translation -1.3794 -0.6884 0.0775 - rotation -0.38268289803593086 -0.9238797538365588 1.3117796504824447e-06 3.14159 - frontTexture "blue" -} -Sample { - name "sample_red_YELLOW_vertical_dispenser" - translation -1.48816 -0.25 0.0621705 - rotation -0.25532206437512617 -0.9528732402508189 0.1638390413092342 2.04399 - frontTexture "red" -} -Sample { - name "sample_green_YELLOW_vertical_dispenser" - translation -1.47166 -0.25 0.0621705 - rotation -0.25532206437512617 -0.9528732402508189 0.1638390413092342 2.04399 - frontTexture "green" -} -Sample { - name "sample_blue_YELLOW_vertical_dispenser" - translation -1.45516 -0.25 0.0621705 - rotation -0.25532206437512617 -0.9528732402508189 0.1638390413092342 2.04399 - frontTexture "blue" -} -Sample { - name "sample_red_PURPLE_vertical_dispenser" - translation 1.48816 -0.25 0.0621705 - rotation 0.8210037674901239 -0.21998793769898486 0.5268378507984881 -2.861115307179586 - frontTexture "red" -} -Sample { - name "sample_green_PURPLE_vertical_dispenser" - translation 1.47166 -0.25 0.0621705 - rotation 0.8210037674901239 -0.21998793769898486 0.5268378507984881 -2.861115307179586 - frontTexture "green" -} -Sample { - name "sample_blue_PURPLE_vertical_dispenser" - translation 1.45516 -0.25 0.0621705 - rotation 0.8210037674901239 -0.21998793769898486 0.5268378507984881 -2.861115307179586 - frontTexture "blue" -} -Sample { - name "sample_red_RIGHT_vertical_dispenser" - translation 0.15 0.988161 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "red" -} -Sample { - name "sample_green_RIGHT_vertical_dispenser" - translation 0.15 0.97166 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "green" -} -Sample { - name "sample_blue_RIGHT_vertical_dispenser" - translation 0.15 0.955155 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "blue" -} -Sample { - name "sample_red_LEFT_vertical_dispenser" - translation -0.15 0.988161 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "red" -} -Sample { - name "sample_green_LEFT_vertical_dispenser" - translation -0.15 0.97166 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "green" -} -Sample { - name "sample_blue_LEFT_vertical_dispenser" - translation -0.15 0.955155 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "blue" -} -ExcavationSquare { - name "excSq0" - translation -0.8325 -1.022 0 -} -ExcavationSquare { - name "excSq1" - translation -0.6475 -1.022 0 -} -ExcavationSquare { - name "excSq2" - translation -0.4625 -1.022 0 - frontTexture "red" -} -ExcavationSquare { - name "excSq3" - translation -0.2775 -1.022 0 - frontTexture "purple1" -} -ExcavationSquare { - name "excSq4" - translation -0.0925 -1.022 0 -} -ExcavationSquare { - name "excSq5" - translation 0.0925 -1.022 0 -} -ExcavationSquare { - name "excSq6" - translation 0.2775 -1.022 0 - frontTexture "purple1" -} -ExcavationSquare { - name "excSq7" - translation 0.4625 -1.022 0 - frontTexture "red" -} -ExcavationSquare { - name "excSq8" - translation 0.6475 -1.022 0 - frontTexture "purple1" -} -ExcavationSquare { - name "excSq9" - translation 0.8325 -1.022 0 - frontTexture "purple1" -} -GalleryPanel { - teamColor "purple" -} -GalleryPanel { -} -FixedBeaconSupport { - name "FBS_top_left" - translation -1.583 0.95 0 -} -FixedBeaconSupport { - name "FBS_top_right" - translation 1.583 0.95 0 - color "yellow" - position "right" -} -FixedBeaconSupport { - name "FBS_mid_left" - translation -1.583 0 0 - color "yellow" -} -FixedBeaconSupport { - name "FBS_mid_right" - translation 1.583 0 0 - position "right" -} -FixedBeaconSupport { - name "FBS_bot_left" - translation -1.583 -0.95 0 -} -FixedBeaconSupport { - name "FBS_bot_right" - translation 1.583 -0.95 0 - color "yellow" - position "right" -} -ExhibitionHall { - teamColor "purple" -} -ExhibitionHall { -} -DEF ROBOT_OPPONENT_BIG OpponentBox { - name "opponent_box_big" - translation -1.26 0.46 0 - rotation 0 0 1 0 -} -DEF ROBOT_OPPONENT_SMALL OpponentBox { - name "opponent_box_small" - translation -1.26 0.128 0 - rotation 0 0 1 0 - arucoNumber 2 -} -DEF ROBOT_BIG RobotMemristor2 { - name "robot_big" - translation 1.2491 0.1 0 - rotation 0 0 1 -1.5708 - controller "" - supervisor TRUE - arucoNumber 6 -} -DEF ROBOT_SMALL RobotMemristor2 { - name "robot_small" - translation 1.1991 0.44 0 - rotation 0 0 1 3.14159 - controller "" - supervisor TRUE - arucoNumber 6 -} -DEF JUDGE Robot { - controller "judge" - supervisor TRUE -} -DEF STATUETTE Statuette { -} -DEF REPLICA Replica { -} diff --git a/mep3_simulation/webots_data/worlds/eurobot_2023.wbt b/mep3_simulation/webots_data/worlds/eurobot_2023.wbt index 29a229c8a..b1e6e6be2 100644 --- a/mep3_simulation/webots_data/worlds/eurobot_2023.wbt +++ b/mep3_simulation/webots_data/worlds/eurobot_2023.wbt @@ -4,6 +4,7 @@ EXTERNPROTO "../protos/Cake.proto" EXTERNPROTO "../protos/Cherry.proto" EXTERNPROTO "../protos/OpponentBox.proto" EXTERNPROTO "../protos/StaticObjects.proto" +EXTERNPROTO "../protos/GenericRobot.proto" EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackground.proto" EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" @@ -25,8 +26,8 @@ WorldInfo { ] } Viewpoint { - orientation 0 1 0 1.57 - position 0 0 5 + orientation 0.1784876953961999 0.07774536495607919 -0.9808658424167902 2.3340532829260487 + position 1.6611698020954249 1.468483579255041 0.8481203223258266 } TexturedBackground { } @@ -413,3 +414,10 @@ Cherry { name "cherry_right_9" translation 0.985 -0.135 0.0351525 } +GenericRobot { + name "robot_small" +} +GenericRobot { + translation 0 0.3 0 + name "robot_big" +} diff --git a/mep3_simulation/webots_data/worlds/test_controller.wbt b/mep3_simulation/webots_data/worlds/test_controller.wbt deleted file mode 100644 index a7401e541..000000000 --- a/mep3_simulation/webots_data/worlds/test_controller.wbt +++ /dev/null @@ -1,663 +0,0 @@ -#VRML_SIM R2022b utf8 - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackground.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/floors/protos/Floor.proto" -EXTERNPROTO "../protos/OpponentBox.proto" -EXTERNPROTO "../protos/DispenserVertical.proto" -EXTERNPROTO "../protos/Sample.proto" -EXTERNPROTO "../protos/ExcavationSquare.proto" - -WorldInfo { - basicTimeStep 10 -} -Viewpoint { - orientation -0.5773502691896258 0.5773502691896258 0.5773502691896258 2.0944 - position -2.744319359575267e-16 5.488638719150534e-16 9.887452516135049 -} -TexturedBackground { -} -TexturedBackgroundLight { -} -Floor { - name "table" - size 3 2 - tileSize 4.096 2.048 - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ - "assets/table.png" - ] - repeatS FALSE - repeatT FALSE - } - roughness 1 - metalness 0 - } -} -Solid { - children [ - DEF purple_statuette_support_shape Group { - children [ - Shape { - appearance DEF APPEARANCE_PURPLE PBRAppearance { - baseColor 0.360784 0.282353 0.541176 - roughness 1 - metalness 0 - name "purple" - } - geometry IndexedFaceSet { - coord Coordinate { - point [ - 1.5 -0.49 0.07 - 1.5 -0.49 0.048 - 1.5 -0.69082 0.07 - 1.5 -0.69082 0.048 - 0.99 -1 0.07 - 0.99 -1 0.048 - 1.19082 -1 0.07 - 1.19082 -1 0.048 - ] - } - normal Normal { - vector [ - 0 0 1 - 0 0 1 - 0 0 -1 - 0 0 -1 - 1 0 0 - 1 0 0 - -0.70711 0.70711 0 - -0.70711 0.70711 0 - 0 -1 0 - 0 -1 0 - 0.70711 -0.70711 0 - 0.70711 -0.70711 0 - ] - } - normalPerVertex FALSE - coordIndex [ - 0, 4, 2, -1, 2, 4, 6, -1, 1, 3, 5, -1, 3, 7, 5, -1, 0, 2, 1, -1, 1, 2, 3, -1, 0, 1, 4, -1, 1, 5, 4, -1, 4, 5, 6, -1, 5, 7, 6, -1, 2, 6, 3, -1, 3, 6, 7, -1 - ] - } - isPickable FALSE - } - Transform { - translation 1.28743 -0.78743 0.081 - rotation 0 0 1 0.7853996938995746 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry Box { - size 0.12 0.12 0.022 - } - } - ] - } - Transform { - translation 1.33763 -0.83763 0.081 - rotation 0 0 1 0.7853996938995746 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry Box { - size 0.481249 0.022 0.022 - } - } - ] - } - ] - } - ] - name "purple statuette support" - boundingObject USE purple_statuette_support_shape - locked TRUE -} -Solid { - children [ - DEF yellow_statuette_support_shape Group { - children [ - Shape { - appearance DEF APPEARANCE_YELLOW PBRAppearance { - baseColor 0.972549 0.694118 0.0666667 - roughness 1 - metalness 0 - name "yellow" - } - geometry IndexedFaceSet { - coord Coordinate { - point [ - -1.5 -0.49 0.07 - -1.5 -0.49 0.048 - -1.5 -0.69082 0.07 - -1.5 -0.69082 0.048 - -0.99 -1 0.07 - -0.99 -1 0.048 - -1.19082 -1 0.07 - -1.19082 -1 0.048 - ] - } - normal Normal { - vector [ - 0 0 1 - 0 0 1 - 0 0 -1 - 0 0 -1 - 1 0 0 - 1 0 0 - -0.70711 0.70711 0 - -0.70711 0.70711 0 - 0 -1 0 - 0 -1 0 - 0.70711 -0.70711 0 - 0.70711 -0.70711 0 - ] - } - normalPerVertex FALSE - coordIndex [ - 0, 2, 4, -1, 2, 6, 4, -1, 1, 5, 3, -1, 3, 5, 7, -1, 0, 1, 2, -1, 1, 3, 2, -1, 0, 4, 1, -1, 1, 4, 5, -1, 4, 6, 5, -1, 5, 6, 7, -1, 2, 3, 6, -1, 3, 7, 6, -1 - ] - } - isPickable FALSE - } - Transform { - translation -1.28743 -0.78743 0.081 - rotation 0 0 1 0.7853996938995746 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry Box { - size 0.12 0.12 0.022 - } - } - ] - } - Transform { - translation -1.33763 -0.83763 0.081 - rotation 0 0 1 -0.7854 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry Box { - size 0.481249 0.022 0.022 - } - } - ] - } - ] - } - ] - name "yellow statuette support" - boundingObject USE yellow_statuette_support_shape - locked TRUE -} -Solid { - translation 0 1.011 0.035 - rotation 1 0 0 1.5708 - children [ - DEF WALL_W Shape { - appearance DEF WALL_APPEARANCE PBRAppearance { - baseColor 0.631 0.612 0.537 - roughness 1 - metalness 0 - } - geometry Box { - size 3 0.07 0.022 - } - isPickable FALSE - } - ] - name "wall_top" - boundingObject USE WALL_W - locked TRUE -} -Solid { - translation 0 -1.011 0.035 - rotation 1 0 0 1.5708 - children [ - USE WALL_W - ] - name "wall_bottom" - boundingObject USE WALL_W - locked TRUE -} -Solid { - translation -1.511 0 0.035 - rotation 1 0 0 1.5708 - children [ - DEF WALL_H Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.022 0.07 2.044 - } - isPickable FALSE - } - ] - name "wall_left" - boundingObject USE WALL_H - locked TRUE -} -Solid { - translation 1.511 0 0.035 - rotation 1 0 0 1.5708 - children [ - USE WALL_H - ] - name "wall_right" - boundingObject USE WALL_H - locked TRUE -} -Sample { - name "sample_purple_excavation_site_red" - translation 0.442219 -0.454349 0.0075 - rotation 0 0 1 -0.785395307179586 - frontTexture "red" -} -Sample { - name "sample_purple_excavation_site_green" - translation 0.531922 -0.303676 0.0075 - rotation 0 0 1 1.309 - frontTexture "green" -} -Sample { - name "sample_purple_excavation_site_blue" - translation 0.61144 -0.45196 0.0075 - rotation 0 0 1 -2.6179953071795863 - frontTexture "blue" -} -Sample { - name "sample_yellow_excavation_site_red" - translation -0.446015 -0.290911 0.0075 - rotation 0 0 1 -0.261795307179586 - frontTexture "red" -} -Sample { - name "sample_yellow_excavation_site_green" - translation -0.608832 -0.343505 0.0075 - rotation 0 0 1 -1.3089953071795861 - frontTexture "green" -} -Sample { - name "sample_yellow_excavation_site_blue" - translation -0.498243 -0.466137 0.0075 - rotation 0 0 1 -2.094395307179586 - frontTexture "blue" -} -Sample { - name "sample_purple_playing_area_red" - translation 0.6 0.2 0.00750369 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "red" -} -Sample { - name "sample_purple_playing_area_green" - translation 0.67 0.325 0.00750385 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "green" -} -Sample { - name "sample_purple_playing_area_blue" - translation 0.6 0.45 0.00750346 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "blue" -} -Sample { - name "sample_yellow_playing_area_red" - translation -0.6 0.2 0.00749988 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "red" -} -Sample { - name "sample_yellow_playing_area_green" - translation -0.67 0.325 0.00749957 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "green" -} -Sample { - name "sample_yellow_playing_area_blue" - translation -0.6 0.45 0.00749969 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "blue" -} -Solid { - translation 0 1.233 0 - children [ - Transform { - translation 0 0 0.5 - children [ - Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.2 0.022 1 - } - } - Transform { - translation 0 -0.11 -0.011 - children [ - Shape { - appearance USE WALL_APPEARANCE - geometry Box { - size 0.022 0.2 0.978 - } - } - ] - } - Group { - children [ - Transform { - translation -0.1 -0.0585 0.489 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry DEF CENTRAL_TRACKING_TOP_BOX_HALF Box { - size 0.2 0.095 0.022 - } - } - ] - } - Transform { - translation -0.0475 -0.111 0.489 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry DEF CENTRAL_TRACKING_BOX_SLIT Box { - size 0.095 0.01 0.022 - } - } - ] - } - Transform { - translation -0.1 -0.1635 0.489 - children [ - Shape { - appearance USE APPEARANCE_YELLOW - geometry USE CENTRAL_TRACKING_TOP_BOX_HALF - } - ] - } - ] - } - Group { - children [ - Transform { - translation 0.1 -0.0585 0.489 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry USE CENTRAL_TRACKING_TOP_BOX_HALF - } - ] - } - Transform { - translation 0.0475 -0.111 0.489 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry USE CENTRAL_TRACKING_BOX_SLIT - } - ] - } - Transform { - translation 0.1 -0.1635 0.489 - children [ - Shape { - appearance USE APPEARANCE_PURPLE - geometry USE CENTRAL_TRACKING_TOP_BOX_HALF - } - ] - } - ] - } - ] - } - ] - name "central_tracking_device_platform" - boundingObject Transform { - translation 0 -0.111 0.989 - children [ - Box { - size 0.4 0.2 0.022 - } - ] - } - locked TRUE -} -DispenserVertical { - name "vertical_dispenser_left" - translation -0.15 1 0 - teamColor USE WALL_APPEARANCE -} -DispenserVertical { - name "vertical_dispenser_right" - translation 0.15 1 0 - teamColor USE WALL_APPEARANCE -} -DispenserVertical { - name "vertical_dispenser_yellow" - translation -1.5 -0.25 0 - rotation 0 0 1 1.5708 - teamColor USE APPEARANCE_YELLOW -} -DispenserVertical { - name "vertical_dispenser_purple" - translation 1.5 -0.25 0 - rotation 0 0 1 -1.5708 - teamColor USE APPEARANCE_PURPLE -} -Solid { - translation -1.522 0.7 0 - children [ - DEF dispenser_outer Transform { - translation -0.1075 -0.075 0.048 - scale 0.001 0.001 0.001 - children [ - Shape { - appearance USE WALL_APPEARANCE - geometry IndexedFaceSet { - coord DEF o6 Coordinate { - point [ - 1e-15 37.5 22, 1e-15 112.5 22, 1e-15 37.5 0, 1e-15 112.5 0, 1e-15 37.5 22, 1e-15 112.5 22, 64.949997 -2e-15 22, 107.9 0 22, 107.9 150 22, 64.949997 150 22, 64.949997 150 0, 64.949997 150 22, 1e-15 112.5 22, 1e-15 112.5 0, 1e-15 37.5 0, 1e-15 112.5 0, 64.949997 -2e-15 0, 107.9 0 0, 107.9 150 0, 64.949997 150 0, 64.949997 -2e-15 0, 64.949997 -2e-15 22, 1e-15 37.5 22, 1e-15 37.5 0, 64.949997 150 0, 107.9 150 0, 64.949997 150 22, 107.9 150 22, 107.9 0 0, 107.9 0 22, 107.9 150 0, 107.9 150 22, 64.949997 -2e-15 0, 107.9 0 0, 64.949997 -2e-15 22, 107.9 0 22, 1e-15 37.5 22, 1e-15 112.5 22, 1e-15 112.5 0, 1e-15 37.5 0, 64.949997 150 22, 107.9 150 22, 107.9 0 22, 64.949997 -2e-15 22, 64.949997 150 0, 107.9 150 0, 107.9 0 0, 64.949997 -2e-15 0 - ] - } - coordIndex [ - 2, 0, 3, -1, 3, 0, 1, -1, 9, 5, 4, -1, 9, 4, 6, -1, 9, 6, 7, -1, 8, 9, 7, -1, 10, 12, 11, -1, 10, 13, 12, -1, 15, 19, 14, -1, 14, 19, 16, -1, 16, 19, 17, -1, 19, 18, 17, -1, 23, 20, 21, -1, 23, 21, 22, -1, 27, 25, 24, -1, 27, 24, 26, -1, 28, 30, 31, -1, 29, 28, 31, -1, 33, 35, 32, -1, 32, 35, 34, -1 - ] - } - } - ] - } - ] - name "dispenser_yellow_outer" - boundingObject Transform { - translation -0.053952 0 0.059 - children [ - Box { - size 0.107902 0.15 0.022 - } - ] - } - locked TRUE -} -Solid { - translation 1.522 0.7 0 - rotation 0 0 1 3.141592653589793 - children [ - USE dispenser_outer - ] - name "dispenser_purple_outer" - boundingObject Transform { - translation -0.053952 0 0.059 - children [ - Box { - size 0.107902 0.15 0.022 - } - ] - } - locked TRUE -} -Sample { - name "sample_green_PURPLE_horizontal_dispenser" - translation 1.56495 0.7 0.0775 - rotation 0.965925849201117 0.2588189595935754 1.2410098062554258e-09 3.14159 - frontTexture "green" -} -Sample { - name "sample_red_PURPLE_horizontal_dispenser" - translation 1.1884 -0.8794 0.0775 - rotation 0.3826841051424448 -0.9238792538357933 1.773180487181278e-06 3.14159 - frontTexture "red" -} -Sample { - name "sample_blue_PURPLE_horizontal_dispenser" - translation 1.3794 -0.6884 0.0775 - rotation -0.9238792538356376 -0.38268410514238027 1.865750512614575e-06 3.14159 - frontTexture "blue" -} -Sample { - name "sample_green_YELLOW_horizontal_dispenser" - translation -1.56495 0.7 0.0775 - rotation -0.25881895959340473 -0.96592584920048 1.1484198207096768e-06 3.14159 - frontTexture "green" -} -Sample { - name "sample_red_YELLOW_horizontal_dispenser" - translation -1.1884 -0.8794 0.0775 - rotation -0.9238797538367262 0.3826828980360002 1.1655496894449454e-06 -3.1415853071795863 - frontTexture "red" -} -Sample { - name "sample_blue_YELLOW_horizontal_dispenser" - translation -1.3794 -0.6884 0.0775 - rotation -0.38268289803593086 -0.9238797538365588 1.3117796504824447e-06 3.14159 - frontTexture "blue" -} -Sample { - name "sample_red_YELLOW_vertical_dispenser" - translation -1.48816 -0.25 0.0621705 - rotation -0.25532206437512617 -0.9528732402508189 0.1638390413092342 2.04399 - frontTexture "red" -} -Sample { - name "sample_green_YELLOW_vertical_dispenser" - translation -1.47166 -0.25 0.0621705 - rotation -0.25532206437512617 -0.9528732402508189 0.1638390413092342 2.04399 - frontTexture "green" -} -Sample { - name "sample_blue_YELLOW_vertical_dispenser" - translation -1.45516 -0.25 0.0621705 - rotation -0.25532206437512617 -0.9528732402508189 0.1638390413092342 2.04399 - frontTexture "blue" -} -Sample { - name "sample_red_PURPLE_vertical_dispenser" - translation 1.48816 -0.25 0.0621705 - rotation 0.8210037674901239 -0.21998793769898486 0.5268378507984881 -2.861115307179586 - frontTexture "red" -} -Sample { - name "sample_green_PURPLE_vertical_dispenser" - translation 1.47166 -0.25 0.0621705 - rotation 0.8210037674901239 -0.21998793769898486 0.5268378507984881 -2.861115307179586 - frontTexture "green" -} -Sample { - name "sample_blue_PURPLE_vertical_dispenser" - translation 1.45516 -0.25 0.0621705 - rotation 0.8210037674901239 -0.21998793769898486 0.5268378507984881 -2.861115307179586 - frontTexture "blue" -} -Sample { - name "sample_red_RIGHT_vertical_dispenser" - translation 0.15 0.988161 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "red" -} -Sample { - name "sample_green_RIGHT_vertical_dispenser" - translation 0.15 0.97166 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "green" -} -Sample { - name "sample_blue_RIGHT_vertical_dispenser" - translation 0.15 0.955155 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "blue" -} -Sample { - name "sample_red_LEFT_vertical_dispenser" - translation -0.15 0.988161 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "red" -} -Sample { - name "sample_green_LEFT_vertical_dispenser" - translation -0.15 0.97166 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "green" -} -Sample { - name "sample_blue_LEFT_vertical_dispenser" - translation -0.15 0.955155 0.0621705 - rotation 0.8246198587813874 0.4760949184673239 0.30550894768068065 -2.1681953071795865 - frontTexture "blue" -} -RobotMemristor { - controller "" -} -ExcavationSquare { - name "excSq0" - translation -0.8325 -1.022 0 -} -ExcavationSquare { - name "excSq1" - translation -0.6475 -1.022 0 -} -ExcavationSquare { - name "excSq2" - translation -0.4625 -1.022 0 - frontTexture "red" -} -ExcavationSquare { - name "excSq3" - translation -0.2775 -1.022 0 - frontTexture "purple1" -} -ExcavationSquare { - name "excSq4" - translation -0.0925 -1.022 0 -} -ExcavationSquare { - name "excSq5" - translation 0.0925 -1.022 0 -} -ExcavationSquare { - name "excSq6" - translation 0.2775 -1.022 0 - frontTexture "purple1" -} -ExcavationSquare { - name "excSq7" - translation 0.4625 -1.022 0 - frontTexture "red" -} -ExcavationSquare { - name "excSq8" - translation 0.6475 -1.022 0 - frontTexture "purple1" -} -ExcavationSquare { - name "excSq9" - translation 0.8325 -1.022 0 - frontTexture "purple1" -} -OpponentBox { - translation 0.87 0.1 0 - rotation 0 0 1 -1.047195307179586 -} -OpponentBox { - name "opponent_box(1)" - translation -0.44 0.29 0 - rotation 0 0 1 0.523599 -} diff --git a/mep3_simulation/webots_data/worlds/test_robot.wbt b/mep3_simulation/webots_data/worlds/test_robot.wbt deleted file mode 100644 index eaaa176c1..000000000 --- a/mep3_simulation/webots_data/worlds/test_robot.wbt +++ /dev/null @@ -1,56 +0,0 @@ -#VRML_SIM R2022b utf8 - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackground.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/floors/protos/Floor.proto" -EXTERNPROTO "../protos/RobotMemristor2.proto" -EXTERNPROTO "../protos/Sample.proto" - -WorldInfo { - basicTimeStep 10 - contactProperties [ - ContactProperties { - material1 "floor" - material2 "omni_wheel" - coulombFriction [ - 0 - ] - } - ] -} -Viewpoint { - orientation -0.3937050156912503 -0.11140936440085694 0.9124605822408712 3.4760028290807505 - position 0.7956641609680842 0.2905934507793585 0.9776416058836312 -} -TexturedBackground { -} -TexturedBackgroundLight { -} -Floor { - name "table" - contactMaterial "floor" - size 3 2 - tileSize 4.096 2.048 - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ - "assets/table.png" - ] - repeatS FALSE - repeatT FALSE - } - roughness 1 - metalness 0 - } -} -Sample { - name "sample_purple_playing_area_red" - translation 0.2 0.09 0.0075023 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "red" -} -RobotMemristor2 { - translation 0 0 0 - rotation 0 0 1 0 - controller "test_robot" -} diff --git a/mep3_simulation/webots_data/worlds/test_robot_arm_memristor.wbt b/mep3_simulation/webots_data/worlds/test_robot_arm_memristor.wbt deleted file mode 100644 index b014a348b..000000000 --- a/mep3_simulation/webots_data/worlds/test_robot_arm_memristor.wbt +++ /dev/null @@ -1,50 +0,0 @@ -#VRML_SIM R2022b utf8 - -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackground.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" -EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2022b/projects/objects/floors/protos/Floor.proto" -EXTERNPROTO "../protos/Sample.proto" - -WorldInfo { - basicTimeStep 10 -} -Viewpoint { - orientation -0.25762270140123883 0.5920981261512926 0.7635773390632123 1.0358757455753214 - position -0.8344738187863388 -1.0772376137528865 1.0830410984015233 -} -TexturedBackground { -} -TexturedBackgroundLight { -} -Floor { - name "table" - size 3 2 - tileSize 4.096 2.048 - appearance PBRAppearance { - baseColorMap ImageTexture { - url [ - "assets/table.png" - ] - repeatS FALSE - repeatT FALSE - } - roughness 1 - metalness 0 - } -} -Sample { - name "sample_purple_playing_area_red" - translation 0.1 -4.40149e-13 0.00750212 - rotation 0.7071067811862364 0.7071067811862364 9.381857096790023e-07 3.14159 - frontTexture "red" -} -Robot { - translation 0 0 0.01 - rotation 0 0 1 1.5708 - children [ - RobotArmMemristor { - name "test_arm" - } - ] - controller "test_robot_arm_memristor" -} diff --git a/tools/dynamixel.py b/tools/dynamixel.py deleted file mode 100644 index 286c97002..000000000 --- a/tools/dynamixel.py +++ /dev/null @@ -1,226 +0,0 @@ -#!/usr/bin/env python3 - -from threading import Lock -import can -import struct -import curses - -SERVOS = [ - {'id': 1, 'name': 'arm_left_motor_base', 'model': 'ax12'}, - {'id': 2, 'name': 'arm_left_motor_mid', 'model': 'mx28'}, - {'id': 3, 'name': 'arm_left_motor_gripper', 'model': 'ax12'}, - {'id': 4, 'name': 'arm_right_motor_base', 'model': 'ax12'}, - {'id': 5, 'name': 'arm_right_motor_mid', 'model': 'mx28'}, - {'id': 6, 'name': 'arm_right_motor_gripper', 'model': 'ax12'}, - {'id': 9, 'name': 'hand_right_G', 'model': 'ax12'}, - {'id': 10,'name': 'hand_right_Dz', 'model': 'ax12'}, - {'id': 7, 'name': 'hand_mid_L', 'model': 'ax12'}, - {'id': 69,'name': 'hand_mid_S', 'model': 'ax12'}, -] - -SERVO_CAN_ID = 0x00006C00 -POLL_PERIOD = 0.2 - -servo_commands = { - 'ModelNumber': [0, 'R', 'h'], - - 'SetId': [3, 'RW', 'B'], - 'SetBaud': [4, 'RW', 'B'], - 'ReturnDelayTime': [5, 'RW', 'B'], - 'CWAngleLimit': [6, 'RW', 'h'], - 'CCWAngleLimit': [8, 'RW', 'h'], - 'HLimitTemp': [11, 'RW', 'B'], - 'MinVoltage': [12, 'RW', 'B'], - 'MaxVoltage': [13, 'RW', 'B'], - 'MaxTorque': [14, 'RW', 'h'], - 'Status': [16, 'RW', 'B'], - 'AlarmLED': [17, 'RW', 'B'], - 'AlarmShutdown': [18, 'RW', 'B'], - 'TorqueEnable': [24, 'RW', 'B'], - 'LED': [25, 'RW', 'B'], - 'CWComplianceMargin': [26, 'RW', 'B'], - 'CCWComplianceMargin': [27, 'RW', 'B'], - 'CWComplianceScope': [28, 'RW', 'B'], - 'CCWComplianceScope': [29, 'RW', 'B'], - 'GoalPosition': [30, 'RW', 'h'], - 'MovingSpeed': [32, 'RW', 'h'], - 'TorqueLimit': [34, 'RW', 'B'], - 'PresentPosition': [36, 'R', 'h'], - 'PresentSpeed': [38, 'R', 'h'], - 'PresentLoad': [40, 'R', 'h'], - 'PresentVoltage': [42, 'R', 'B'], - 'PresentTemp': [43, 'R', 'B'], - 'Punch': [48, 'RW', 'h'], -} - - -def scale(val, src, dst): - return ((val - src[0]) / (src[1] - src[0])) * (dst[1] - dst[0]) + dst[0] - - -class DynamixelServo: - def __init__(self, servo_id, name, model): - self.id = servo_id - self.name = name - self.model = model - - # Values we need to keep track of while Node is active - self.present_position = None - self.present_velocity = None - - def get_command_data(self, command, val): - # doing only GoalPosition action for now and only AX12 - - cmd = servo_commands[command] - - val = int(val) if val else None - servo_len = 4 - servo_func = cmd[0] - servo_rw = cmd[1] - pfmt = servo_fmt = cmd[2] - - if (val is None) and ('R' not in servo_rw): - print('function ' + command + ' is not readable') - return - - if (val is not None) and ('W' not in servo_rw): - print('function ' + command + ' is not writable') - return - - if val is None: - servo_rw = 2 - servo_fmt = 'B' - servo_len = 4 - else: - servo_rw = 3 - if servo_fmt == 'h': - servo_len += 1 - - fmt = '4B' + servo_fmt - data = [self.id, servo_len, servo_rw, servo_func] - - if val is not None: - data += [val] - else: - data += [2] if pfmt == 'h' else [1] - - binary_data = struct.pack(fmt, *data) - - return binary_data - - def increment_per_degree(self, degree): - increment = 0 - - if self.model == "ax12": - increment = scale(degree, [0, 300], [0, 1023]) - else: - increment = scale(degree, [0, 360], [0, 4095]) - - return increment - - def degree_to_increment(self, degree): - increment = 0 - - if self.model == "ax12": - increment = scale(degree, [-150, 150], [0, 1023]) - else: - increment = scale(degree, [-180, 180], [0, 4095]) - - return increment - - def increment_to_degree(self, increment): - degree = 0 - - if self.model == "ax12": - degree = scale(increment, [0, 1023], [-150, 150]) - else: - degree = scale(increment, [0, 4095], [-180, 180]) - - return degree - - -class DynamixelDriver: - def __init__(self, can_mutex, can_bus): - self.servo_list = [] - self.can_mutex = can_mutex - self.bus = can_bus - for servo_config in SERVOS: - new_servo = DynamixelServo( - servo_id=servo_config['id'], name=servo_config['name'], model=servo_config['model'] - ) - self.servo_list.append(new_servo) - #self.process_single_command(bin_data=new_servo.get_command_data('TorqueEnable', 0)) - self.stdscr = curses.initscr() - curses.noecho() - curses.cbreak() - - def process_single_command(self, bin_data): - - self.can_mutex.acquire() - - msg = can.Message(arbitration_id=SERVO_CAN_ID, - data=bin_data, - is_extended_id=True) - - try: - self.bus.send(msg) - except can.CanError: - print("CAN ERROR: Cannot send message over CAN bus. Check if can0 is active.") - - message = self.bus.recv(0.1) # Wait until a message is received or 0.1s - - self.can_mutex.release() - - if message: - ret_val = message - else: - print("Timeout error for servo response. Check servo connections.") - ret_val = False - - return ret_val - - def read(self): - self.stdscr.clear() - for i, servo in enumerate(self.servo_list): - success = self.get_present_position(servo) - position = None - if success: - position = servo.increment_to_degree(servo.present_position) - - servo_name = servo.name.ljust(40) - self.stdscr.addstr(i, 0, f'{servo_name} {position}') - self.stdscr.refresh() - - def get_present_position(self, servo): - ret_val = 1 - status = self.process_single_command( - bin_data=servo.get_command_data('PresentPosition', None)) - - if not status: - ret_val = 0 - else: - if len(status.data) == 5: - servo.present_position = float(struct.unpack( - servo_commands['PresentPosition'][2], status.data[3:])[0]) - else: - print("Wrong response") - ret_val = 0 - return ret_val - - def __del__(self): - curses.echo() - curses.nocbreak() - curses.endwin() - - -def main(args=None): - can_mutex = Lock() - bus = can.ThreadSafeBus(bustype='socketcan', channel='can0', bitrate=500000) - bus.set_filters(filters=[{"can_id": SERVO_CAN_ID, "can_mask": 0x1FFFFFFF, "extended": True}]) - driver = DynamixelDriver(can_mutex, bus) - - while True: - driver.read() - -if __name__ == '__main__': - main() diff --git a/tools/position_reader.py b/tools/position_reader.py deleted file mode 100644 index b225ed114..000000000 --- a/tools/position_reader.py +++ /dev/null @@ -1,46 +0,0 @@ -import math -import rclpy -from rclpy.node import Node -from tf2_ros.buffer import Buffer -from tf2_ros.transform_listener import TransformListener - - -class DisplayTransforms(Node): - def __init__(self, parent_frame, child_frame): - super().__init__('image_subscriber') - - self.__tf_buffer = Buffer() - self.__tf_listener = TransformListener(self.__tf_buffer, self) - while True: - transform = None - try: - transform = self.__tf_buffer.lookup_transform( - child_frame, parent_frame, rclpy.time.Time()) - except Exception: # noqa: E501 - # logging.exception("StaticTfListener"): - pass - - if transform is not None: - x = transform.transform.translation.x - y = transform.transform.translation.y - q = transform.transform.rotation - # Convert quaternion to yaw - yaw = math.atan2(2 * (q.w * q.z + q.x * q.y), 1 - 2 * (q.y * q.y + q.z * q.z)) - print(x, y, math.degrees(yaw)) - - - rclpy.spin_once(self, timeout_sec=0.1) - - -# python3 position.py --ros-args -r /tf:=/big/tf -r /tf_static:=/big/tf_static -def main(args=None): - rclpy.init(args=args) - - display_transforms = DisplayTransforms('base_link', 'map') - rclpy.spin(display_transforms) - display_transforms.destroy_node() - rclpy.shutdown() - - -if __name__ == '__main__': - main()